From 2d90bd5a52cdd58b635e95ec5d5ef3d59a239caf Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 25 Jan 2019 02:01:51 +0900 Subject: [PATCH 001/940] add n_joint_arm_3d & implement forward kinematics --- ArmNavigation/n_joint_arm_3d/NLinkArm.py | 94 +++++++++++++++++++ .../n_joint_arm_3d/random_joint_angles.py | 20 ++++ 2 files changed, 114 insertions(+) create mode 100644 ArmNavigation/n_joint_arm_3d/NLinkArm.py create mode 100644 ArmNavigation/n_joint_arm_3d/random_joint_angles.py diff --git a/ArmNavigation/n_joint_arm_3d/NLinkArm.py b/ArmNavigation/n_joint_arm_3d/NLinkArm.py new file mode 100644 index 0000000000..d50f9d5c1b --- /dev/null +++ b/ArmNavigation/n_joint_arm_3d/NLinkArm.py @@ -0,0 +1,94 @@ +import numpy as np +import math +from mpl_toolkits.mplot3d import Axes3D +import matplotlib.pyplot as plt + +class Link: + def __init__(self, dh_params): + self.dh_params_ = dh_params + + def calc_transformation_matrix(self): + theta = self.dh_params_[0] + alpha = self.dh_params_[1] + a = self.dh_params_[2] + d = self.dh_params_[3] + + trans = np.array( + [[math.cos(theta), -math.sin(theta), 0, a], + [math.cos(alpha) * math.sin(theta), math.cos(alpha) * math.cos(theta), -math.sin(alpha), -d * math.sin(alpha)], + [math.sin(alpha) * math.sin(theta), math.sin(alpha) * math.cos(theta), math.cos(alpha), d * math.cos(alpha)], + [0, 0, 0, 1]]) + + return trans + +class NLinkArm: + def __init__(self, dh_params_list): + self.link_list = [] + for i in range(len(dh_params_list)): + self.link_list.append(Link(dh_params_list[i])) + + self.fig = plt.figure() + self.ax = Axes3D(self.fig) + + def calc_transformation_matrix(self): + trans = np.array([[1, 0, 0, 0], + [0, 1, 0, 0], + [0, 0, 1, 0], + [0, 0, 0, 1]]) + for i in range(len(self.link_list)): + trans = np.dot(trans, self.link_list[i].calc_transformation_matrix()) + + return trans + + def forward_kinematics(self): + trans = self.calc_transformation_matrix() + + x = trans[0, 3] + y = trans[1, 3] + z = trans[2, 3] + alpha = math.atan2(trans[1, 2], trans[1, 3]) + beta = math.atan2(trans[0, 2] * math.cos(alpha) + trans[1, 2] * math.sin(alpha), trans[2, 2]) + gamma = math.atan2(-trans[0, 0] * math.sin(alpha) + trans[1, 0] * math.cos(alpha), -trans[0, 1] * math.sin(alpha) + trans[1, 1] * math.cos(alpha)) + + return [x, y, z, alpha, beta, gamma] + + def set_joint_angles(self, joint_angle_list): + for i in range(len(self.link_list)): + self.link_list[i].dh_params_[0] = joint_angle_list[i] + + def plot(self): + x_list = [] + y_list = [] + z_list = [] + + trans = np.identity(4) + + x_list.append(trans[0, 3]) + y_list.append(trans[1, 3]) + z_list.append(trans[2, 3]) + for i in range(len(self.link_list)): + trans = np.dot(trans, self.link_list[i].calc_transformation_matrix()) + x_list.append(trans[0, 3]) + y_list.append(trans[1, 3]) + z_list.append(trans[2, 3]) + + self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4, mew=0.5) + self.ax.plot([0], [0], [0], "o") + + self.ax.set_xlim(-1, 1) + self.ax.set_ylim(-1, 1) + self.ax.set_zlim(-1, 1) + plt.show() + +if __name__ == "__main__": + n_link_arm = NLinkArm([[0., -math.pi/2, .1, 0.], + [math.pi/2, math.pi/2, 0., 0.], + [0., -math.pi/2, 0., .4], + [0., math.pi/2, 0., 0.], + [0., -math.pi/2, 0., .321], + [0., math.pi/2, 0., 0.], + [0., 0., 0., 0.]]) + + print(n_link_arm.forward_kinematics()) + n_link_arm.set_joint_angles([1, 1, 1, 1, 1, 1, 1]) + n_link_arm.plot() diff --git a/ArmNavigation/n_joint_arm_3d/random_joint_angles.py b/ArmNavigation/n_joint_arm_3d/random_joint_angles.py new file mode 100644 index 0000000000..54be155ef1 --- /dev/null +++ b/ArmNavigation/n_joint_arm_3d/random_joint_angles.py @@ -0,0 +1,20 @@ +import math +from NLinkArm import NLinkArm +import random +import time + +def random_val(min_val, max_val): + return min_val + random.random() * (max_val - min_val) + +for i in range(10): + n_link_arm = NLinkArm([[0., -math.pi/2, .1, 0.], + [math.pi/2, math.pi/2, 0., 0.], + [0., -math.pi/2, 0., .4], + [0., math.pi/2, 0., 0.], + [0., -math.pi/2, 0., .321], + [0., math.pi/2, 0., 0.], + [0., 0., 0., 0.]]) + + n_link_arm.set_joint_angles([random_val(-1, 1) for j in range(len(n_link_arm.link_list))]) + n_link_arm.plot() + From c49f982923cb415e80291ae7d743fd42532713d8 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Fri, 25 Jan 2019 21:39:32 +0900 Subject: [PATCH 002/940] implement inverse kinematics --- ArmNavigation/n_joint_arm_3d/NLinkArm.py | 65 ++++++++++++++++--- ...angles.py => random_forward_kinematics.py} | 0 .../random_inverse_kinematics.py | 17 +++++ 3 files changed, 72 insertions(+), 10 deletions(-) rename ArmNavigation/n_joint_arm_3d/{random_joint_angles.py => random_forward_kinematics.py} (100%) create mode 100644 ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py diff --git a/ArmNavigation/n_joint_arm_3d/NLinkArm.py b/ArmNavigation/n_joint_arm_3d/NLinkArm.py index d50f9d5c1b..f6b9c28788 100644 --- a/ArmNavigation/n_joint_arm_3d/NLinkArm.py +++ b/ArmNavigation/n_joint_arm_3d/NLinkArm.py @@ -7,7 +7,7 @@ class Link: def __init__(self, dh_params): self.dh_params_ = dh_params - def calc_transformation_matrix(self): + def transformation_matrix(self): theta = self.dh_params_[0] alpha = self.dh_params_[1] a = self.dh_params_[2] @@ -21,6 +21,14 @@ def calc_transformation_matrix(self): return trans + def basic_jacobian(self, trans_prev, ee_pose): + pos_prev = np.array([trans_prev[0, 3], trans_prev[1, 3], trans_prev[2, 3]]) + z_axis_prev = np.array([trans_prev[0, 2], trans_prev[1, 2], trans_prev[2, 2]]) + + basic_jacobian = np.hstack((np.cross(z_axis_prev, ee_pose - pos_prev), z_axis_prev)) + return basic_jacobian + + class NLinkArm: def __init__(self, dh_params_list): self.link_list = [] @@ -30,18 +38,14 @@ def __init__(self, dh_params_list): self.fig = plt.figure() self.ax = Axes3D(self.fig) - def calc_transformation_matrix(self): - trans = np.array([[1, 0, 0, 0], - [0, 1, 0, 0], - [0, 0, 1, 0], - [0, 0, 0, 1]]) + def transformation_matrix(self): + trans = np.identity(4) for i in range(len(self.link_list)): - trans = np.dot(trans, self.link_list[i].calc_transformation_matrix()) - + trans = np.dot(trans, self.link_list[i].transformation_matrix()) return trans def forward_kinematics(self): - trans = self.calc_transformation_matrix() + trans = self.transformation_matrix() x = trans[0, 3] y = trans[1, 3] @@ -52,9 +56,50 @@ def forward_kinematics(self): return [x, y, z, alpha, beta, gamma] + def basic_jacobian(self, ref_ee_pose): + basic_jacobian_mat = [] + + trans = np.identity(4) + for i in range(len(self.link_list)): + trans = np.dot(trans, self.link_list[i].transformation_matrix()) + basic_jacobian_mat.append(self.link_list[i].basic_jacobian(trans, ref_ee_pose[0:3])) + + #print(np.array(basic_jacobian_mat).T) + return np.array(basic_jacobian_mat).T + + def inverse_kinematics(self, ref_ee_pose): + ee_pose = self.forward_kinematics() + diff_pose = ee_pose - np.array(ref_ee_pose) + + for cnt in range(1000): + basic_jacobian_mat = self.basic_jacobian(ref_ee_pose) + alpha, beta, gamma = self.calc_euler_angle() + + K_zyz = np.array([[0, -math.sin(alpha), math.cos(alpha) * math.sin(beta)], + [0, math.cos(alpha), math.sin(alpha) * math.sin(beta)], + [1, 0, math.cos(beta)]]) + K_alpha = np.identity(6) + K_alpha[3:, 3:] = K_zyz + + theta_dot = np.dot(np.dot(np.linalg.pinv(basic_jacobian_mat), K_alpha), np.array(diff_pose)) + self.update_joint_angles(theta_dot) + + def calc_euler_angle(self): + trans = self.transformation_matrix() + + alpha = math.atan2(trans[1][2], trans[0][2]) + beta = math.atan2(trans[0][2] * math.cos(alpha) + trans[1][2] * math.sin(alpha), trans[2][2]) + gamma = math.atan2(-trans[0][0] * math.sin(alpha) + trans[1][0] * math.cos(alpha), -trans[0][1] * math.sin(alpha) + trans[1][1] * math.cos(alpha)) + + return alpha, beta, gamma + def set_joint_angles(self, joint_angle_list): for i in range(len(self.link_list)): self.link_list[i].dh_params_[0] = joint_angle_list[i] + + def update_joint_angles(self, diff_joint_angle_list): + for i in range(len(self.link_list)): + self.link_list[i].dh_params_[0] += diff_joint_angle_list[i] def plot(self): x_list = [] @@ -67,7 +112,7 @@ def plot(self): y_list.append(trans[1, 3]) z_list.append(trans[2, 3]) for i in range(len(self.link_list)): - trans = np.dot(trans, self.link_list[i].calc_transformation_matrix()) + trans = np.dot(trans, self.link_list[i].transformation_matrix()) x_list.append(trans[0, 3]) y_list.append(trans[1, 3]) z_list.append(trans[2, 3]) diff --git a/ArmNavigation/n_joint_arm_3d/random_joint_angles.py b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py similarity index 100% rename from ArmNavigation/n_joint_arm_3d/random_joint_angles.py rename to ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py diff --git a/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py new file mode 100644 index 0000000000..a728647547 --- /dev/null +++ b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py @@ -0,0 +1,17 @@ +import math +from NLinkArm import NLinkArm +import random +import time + + +n_link_arm = NLinkArm([[0., -math.pi/2, .1, 0.], + [math.pi/2, math.pi/2, 0., 0.], + [0., -math.pi/2, 0., .4], + [0., math.pi/2, 0., 0.], + [0., -math.pi/2, 0., .321], + [0., math.pi/2, 0., 0.], + [0., 0., 0., 0.]]) + +#n_link_arm.inverse_kinematics([-0.621, 0., 0., 0., 0., math.pi / 2]) +n_link_arm.inverse_kinematics([-0.5, 0., 0.1, 0., 0., math.pi / 2]) +n_link_arm.plot() From 3504833748d7e5ebb0d9b8ca82b4ab854bd25572 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 26 Jan 2019 02:23:53 +0900 Subject: [PATCH 003/940] fix bug of NLinkArm.py and modify random exapmle scripts --- ArmNavigation/n_joint_arm_3d/NLinkArm.py | 106 +++++++++++++++--- .../random_forward_kinematics.py | 16 ++- .../random_inverse_kinematics.py | 32 ++++-- 3 files changed, 121 insertions(+), 33 deletions(-) diff --git a/ArmNavigation/n_joint_arm_3d/NLinkArm.py b/ArmNavigation/n_joint_arm_3d/NLinkArm.py index f6b9c28788..e1d7369731 100644 --- a/ArmNavigation/n_joint_arm_3d/NLinkArm.py +++ b/ArmNavigation/n_joint_arm_3d/NLinkArm.py @@ -13,11 +13,21 @@ def transformation_matrix(self): a = self.dh_params_[2] d = self.dh_params_[3] + ''' trans = np.array( [[math.cos(theta), -math.sin(theta), 0, a], [math.cos(alpha) * math.sin(theta), math.cos(alpha) * math.cos(theta), -math.sin(alpha), -d * math.sin(alpha)], [math.sin(alpha) * math.sin(theta), math.sin(alpha) * math.cos(theta), math.cos(alpha), d * math.cos(alpha)], [0, 0, 0, 1]]) + ''' + st = math.sin(theta) + ct = math.cos(theta) + sa = math.sin(alpha) + ca = math.cos(alpha) + trans = np.array([[ct, -st * ca, st * sa, a * ct], + [st, ct * ca, -ct * sa, a * st], + [0, sa, ca, d], + [0, 0, 0, 1]]) return trans @@ -35,44 +45,66 @@ def __init__(self, dh_params_list): for i in range(len(dh_params_list)): self.link_list.append(Link(dh_params_list[i])) - self.fig = plt.figure() - self.ax = Axes3D(self.fig) - def transformation_matrix(self): trans = np.identity(4) for i in range(len(self.link_list)): trans = np.dot(trans, self.link_list[i].transformation_matrix()) return trans - def forward_kinematics(self): + def forward_kinematics(self, plot=False): trans = self.transformation_matrix() x = trans[0, 3] y = trans[1, 3] z = trans[2, 3] - alpha = math.atan2(trans[1, 2], trans[1, 3]) - beta = math.atan2(trans[0, 2] * math.cos(alpha) + trans[1, 2] * math.sin(alpha), trans[2, 2]) - gamma = math.atan2(-trans[0, 0] * math.sin(alpha) + trans[1, 0] * math.cos(alpha), -trans[0, 1] * math.sin(alpha) + trans[1, 1] * math.cos(alpha)) + alpha, beta, gamma = self.calc_euler_angle() + + if plot: + self.fig = plt.figure() + self.ax = Axes3D(self.fig) + + x_list = [] + y_list = [] + z_list = [] + + trans = np.identity(4) + + x_list.append(trans[0, 3]) + y_list.append(trans[1, 3]) + z_list.append(trans[2, 3]) + for i in range(len(self.link_list)): + trans = np.dot(trans, self.link_list[i].transformation_matrix()) + x_list.append(trans[0, 3]) + y_list.append(trans[1, 3]) + z_list.append(trans[2, 3]) + + self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4, mew=0.5) + self.ax.plot([0], [0], [0], "o") + + self.ax.set_xlim(-1, 1) + self.ax.set_ylim(-1, 1) + self.ax.set_zlim(-1, 1) + + plt.show() return [x, y, z, alpha, beta, gamma] - def basic_jacobian(self, ref_ee_pose): + def basic_jacobian(self, ee_pose): basic_jacobian_mat = [] trans = np.identity(4) for i in range(len(self.link_list)): + basic_jacobian_mat.append(self.link_list[i].basic_jacobian(trans, ee_pose[0:3])) trans = np.dot(trans, self.link_list[i].transformation_matrix()) - basic_jacobian_mat.append(self.link_list[i].basic_jacobian(trans, ref_ee_pose[0:3])) - #print(np.array(basic_jacobian_mat).T) return np.array(basic_jacobian_mat).T - def inverse_kinematics(self, ref_ee_pose): - ee_pose = self.forward_kinematics() - diff_pose = ee_pose - np.array(ref_ee_pose) + def inverse_kinematics(self, ref_ee_pose, plot=False): + for cnt in range(500): + ee_pose = self.forward_kinematics() + diff_pose = np.array(ref_ee_pose) - ee_pose - for cnt in range(1000): - basic_jacobian_mat = self.basic_jacobian(ref_ee_pose) + basic_jacobian_mat = self.basic_jacobian(ee_pose) alpha, beta, gamma = self.calc_euler_angle() K_zyz = np.array([[0, -math.sin(alpha), math.cos(alpha) * math.sin(beta)], @@ -82,12 +114,45 @@ def inverse_kinematics(self, ref_ee_pose): K_alpha[3:, 3:] = K_zyz theta_dot = np.dot(np.dot(np.linalg.pinv(basic_jacobian_mat), K_alpha), np.array(diff_pose)) - self.update_joint_angles(theta_dot) - + self.update_joint_angles(theta_dot / 100.) + + if plot: + self.fig = plt.figure() + self.ax = Axes3D(self.fig) + + x_list = [] + y_list = [] + z_list = [] + + trans = np.identity(4) + + x_list.append(trans[0, 3]) + y_list.append(trans[1, 3]) + z_list.append(trans[2, 3]) + for i in range(len(self.link_list)): + trans = np.dot(trans, self.link_list[i].transformation_matrix()) + x_list.append(trans[0, 3]) + y_list.append(trans[1, 3]) + z_list.append(trans[2, 3]) + + self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4, mew=0.5) + self.ax.plot([0], [0], [0], "o") + + self.ax.set_xlim(-1, 1) + self.ax.set_ylim(-1, 1) + self.ax.set_zlim(-1, 1) + + self.ax.plot([ref_ee_pose[0]], [ref_ee_pose[1]], [ref_ee_pose[2]], "o") + plt.show() + def calc_euler_angle(self): trans = self.transformation_matrix() alpha = math.atan2(trans[1][2], trans[0][2]) + if -math.pi / 2 <= alpha and alpha <= math.pi / 2: + alpha = math.atan2(trans[1][2], trans[0][2]) + math.pi + if -math.pi / 2 <= alpha and alpha <= math.pi / 2: + alpha = math.atan2(trans[1][2], trans[0][2]) - math.pi beta = math.atan2(trans[0][2] * math.cos(alpha) + trans[1][2] * math.sin(alpha), trans[2][2]) gamma = math.atan2(-trans[0][0] * math.sin(alpha) + trans[1][0] * math.cos(alpha), -trans[0][1] * math.sin(alpha) + trans[1][1] * math.cos(alpha)) @@ -102,6 +167,9 @@ def update_joint_angles(self, diff_joint_angle_list): self.link_list[i].dh_params_[0] += diff_joint_angle_list[i] def plot(self): + self.fig = plt.figure() + self.ax = Axes3D(self.fig) + x_list = [] y_list = [] z_list = [] @@ -119,6 +187,10 @@ def plot(self): self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4, mew=0.5) self.ax.plot([0], [0], [0], "o") + + self.ax.set_xlabel("x") + self.ax.set_ylabel("y") + self.ax.set_zlabel("z") self.ax.set_xlim(-1, 1) self.ax.set_ylim(-1, 1) diff --git a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py index 54be155ef1..df037fb5ea 100644 --- a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py +++ b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py @@ -1,12 +1,15 @@ import math from NLinkArm import NLinkArm import random -import time def random_val(min_val, max_val): return min_val + random.random() * (max_val - min_val) -for i in range(10): + +if __name__ == "__main__": + print("Start solving Forward Kinematics 10 times") + + # init NLinkArm with Denavit-Hartenberg parameters of PR2 n_link_arm = NLinkArm([[0., -math.pi/2, .1, 0.], [math.pi/2, math.pi/2, 0., 0.], [0., -math.pi/2, 0., .4], @@ -14,7 +17,10 @@ def random_val(min_val, max_val): [0., -math.pi/2, 0., .321], [0., math.pi/2, 0., 0.], [0., 0., 0., 0.]]) - - n_link_arm.set_joint_angles([random_val(-1, 1) for j in range(len(n_link_arm.link_list))]) - n_link_arm.plot() + + for i in range(10): + n_link_arm.set_joint_angles([random_val(-1, 1) for j in range(len(n_link_arm.link_list))]) + + ee_pose = n_link_arm.forward_kinematics(plot=True) + print(ee_pose) diff --git a/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py index a728647547..dd51381678 100644 --- a/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py +++ b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py @@ -1,17 +1,27 @@ import math from NLinkArm import NLinkArm import random -import time -n_link_arm = NLinkArm([[0., -math.pi/2, .1, 0.], - [math.pi/2, math.pi/2, 0., 0.], - [0., -math.pi/2, 0., .4], - [0., math.pi/2, 0., 0.], - [0., -math.pi/2, 0., .321], - [0., math.pi/2, 0., 0.], - [0., 0., 0., 0.]]) +def random_val(min_val, max_val): + return min_val + random.random() * (max_val - min_val) -#n_link_arm.inverse_kinematics([-0.621, 0., 0., 0., 0., math.pi / 2]) -n_link_arm.inverse_kinematics([-0.5, 0., 0.1, 0., 0., math.pi / 2]) -n_link_arm.plot() +if __name__ == "__main__": + print("Start solving Inverse Kinematics 10 times") + + # init NLinkArm with Denavit-Hartenberg parameters of PR2 + n_link_arm = NLinkArm([[0., -math.pi/2, .1, 0.], + [math.pi/2, math.pi/2, 0., 0.], + [0., -math.pi/2, 0., .4], + [0., math.pi/2, 0., 0.], + [0., -math.pi/2, 0., .321], + [0., math.pi/2, 0., 0.], + [0., 0., 0., 0.]]) + + for i in range(10): + n_link_arm.inverse_kinematics([random_val(-0.5, 0.5), + random_val(-0.5, 0.5), + random_val(-0.5, 0.5), + random_val(-0.5, 0.5), + random_val(-0.5, 0.5), + random_val(-0.5, 0.5)], plot=True) From b543623cada7f6f425df6463b44027fdc4ec211d Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 26 Jan 2019 02:32:49 +0900 Subject: [PATCH 004/940] minor change --- ArmNavigation/n_joint_arm_3d/NLinkArm.py | 20 -------------------- 1 file changed, 20 deletions(-) diff --git a/ArmNavigation/n_joint_arm_3d/NLinkArm.py b/ArmNavigation/n_joint_arm_3d/NLinkArm.py index e1d7369731..19b1a32a5b 100644 --- a/ArmNavigation/n_joint_arm_3d/NLinkArm.py +++ b/ArmNavigation/n_joint_arm_3d/NLinkArm.py @@ -13,13 +13,6 @@ def transformation_matrix(self): a = self.dh_params_[2] d = self.dh_params_[3] - ''' - trans = np.array( - [[math.cos(theta), -math.sin(theta), 0, a], - [math.cos(alpha) * math.sin(theta), math.cos(alpha) * math.cos(theta), -math.sin(alpha), -d * math.sin(alpha)], - [math.sin(alpha) * math.sin(theta), math.sin(alpha) * math.cos(theta), math.cos(alpha), d * math.cos(alpha)], - [0, 0, 0, 1]]) - ''' st = math.sin(theta) ct = math.cos(theta) sa = math.sin(alpha) @@ -196,16 +189,3 @@ def plot(self): self.ax.set_ylim(-1, 1) self.ax.set_zlim(-1, 1) plt.show() - -if __name__ == "__main__": - n_link_arm = NLinkArm([[0., -math.pi/2, .1, 0.], - [math.pi/2, math.pi/2, 0., 0.], - [0., -math.pi/2, 0., .4], - [0., math.pi/2, 0., 0.], - [0., -math.pi/2, 0., .321], - [0., math.pi/2, 0., 0.], - [0., 0., 0., 0.]]) - - print(n_link_arm.forward_kinematics()) - n_link_arm.set_joint_angles([1, 1, 1, 1, 1, 1, 1]) - n_link_arm.plot() From 33e7b67db0130f6ec5277fdf7e630738d13fb2dd Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 26 Jan 2019 03:06:27 +0900 Subject: [PATCH 005/940] minor changes --- ArmNavigation/n_joint_arm_3d/NLinkArm.py | 21 ++++++++++--------- .../random_forward_kinematics.py | 1 - 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/ArmNavigation/n_joint_arm_3d/NLinkArm.py b/ArmNavigation/n_joint_arm_3d/NLinkArm.py index 19b1a32a5b..d0e32a05da 100644 --- a/ArmNavigation/n_joint_arm_3d/NLinkArm.py +++ b/ArmNavigation/n_joint_arm_3d/NLinkArm.py @@ -24,11 +24,11 @@ def transformation_matrix(self): return trans - def basic_jacobian(self, trans_prev, ee_pose): + def basic_jacobian(self, trans_prev, ee_pos): pos_prev = np.array([trans_prev[0, 3], trans_prev[1, 3], trans_prev[2, 3]]) z_axis_prev = np.array([trans_prev[0, 2], trans_prev[1, 2], trans_prev[2, 2]]) - basic_jacobian = np.hstack((np.cross(z_axis_prev, ee_pose - pos_prev), z_axis_prev)) + basic_jacobian = np.hstack((np.cross(z_axis_prev, ee_pos - pos_prev), z_axis_prev)) return basic_jacobian @@ -50,7 +50,7 @@ def forward_kinematics(self, plot=False): x = trans[0, 3] y = trans[1, 3] z = trans[2, 3] - alpha, beta, gamma = self.calc_euler_angle() + alpha, beta, gamma = self.euler_angle() if plot: self.fig = plt.figure() @@ -82,12 +82,13 @@ def forward_kinematics(self, plot=False): return [x, y, z, alpha, beta, gamma] - def basic_jacobian(self, ee_pose): + def basic_jacobian(self): + ee_pos = self.forward_kinematics()[0:3] basic_jacobian_mat = [] trans = np.identity(4) for i in range(len(self.link_list)): - basic_jacobian_mat.append(self.link_list[i].basic_jacobian(trans, ee_pose[0:3])) + basic_jacobian_mat.append(self.link_list[i].basic_jacobian(trans, ee_pos)) trans = np.dot(trans, self.link_list[i].transformation_matrix()) return np.array(basic_jacobian_mat).T @@ -97,8 +98,8 @@ def inverse_kinematics(self, ref_ee_pose, plot=False): ee_pose = self.forward_kinematics() diff_pose = np.array(ref_ee_pose) - ee_pose - basic_jacobian_mat = self.basic_jacobian(ee_pose) - alpha, beta, gamma = self.calc_euler_angle() + basic_jacobian_mat = self.basic_jacobian() + alpha, beta, gamma = self.euler_angle() K_zyz = np.array([[0, -math.sin(alpha), math.cos(alpha) * math.sin(beta)], [0, math.cos(alpha), math.sin(alpha) * math.sin(beta)], @@ -138,13 +139,13 @@ def inverse_kinematics(self, ref_ee_pose, plot=False): self.ax.plot([ref_ee_pose[0]], [ref_ee_pose[1]], [ref_ee_pose[2]], "o") plt.show() - def calc_euler_angle(self): + def euler_angle(self): trans = self.transformation_matrix() alpha = math.atan2(trans[1][2], trans[0][2]) - if -math.pi / 2 <= alpha and alpha <= math.pi / 2: + if not (-math.pi / 2 <= alpha and alpha <= math.pi / 2): alpha = math.atan2(trans[1][2], trans[0][2]) + math.pi - if -math.pi / 2 <= alpha and alpha <= math.pi / 2: + if not (-math.pi / 2 <= alpha and alpha <= math.pi / 2): alpha = math.atan2(trans[1][2], trans[0][2]) - math.pi beta = math.atan2(trans[0][2] * math.cos(alpha) + trans[1][2] * math.sin(alpha), trans[2][2]) gamma = math.atan2(-trans[0][0] * math.sin(alpha) + trans[1][0] * math.cos(alpha), -trans[0][1] * math.sin(alpha) + trans[1][1] * math.cos(alpha)) diff --git a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py index df037fb5ea..e94795213c 100644 --- a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py +++ b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py @@ -22,5 +22,4 @@ def random_val(min_val, max_val): n_link_arm.set_joint_angles([random_val(-1, 1) for j in range(len(n_link_arm.link_list))]) ee_pose = n_link_arm.forward_kinematics(plot=True) - print(ee_pose) From 47b497019a0bcedc2cd257ea8bd48942f2b616d5 Mon Sep 17 00:00:00 2001 From: Takayuki Murooka Date: Sat, 26 Jan 2019 15:28:59 +0900 Subject: [PATCH 006/940] add header comment in each scripts --- ArmNavigation/n_joint_arm_3d/NLinkArm.py | 4 ++++ ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py | 7 ++++++- ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py | 5 +++++ 3 files changed, 15 insertions(+), 1 deletion(-) diff --git a/ArmNavigation/n_joint_arm_3d/NLinkArm.py b/ArmNavigation/n_joint_arm_3d/NLinkArm.py index d0e32a05da..da562d9f17 100644 --- a/ArmNavigation/n_joint_arm_3d/NLinkArm.py +++ b/ArmNavigation/n_joint_arm_3d/NLinkArm.py @@ -1,3 +1,7 @@ +""" +Class of n-link arm in 3D +Author: Takayuki Murooka (takayuki5168) +""" import numpy as np import math from mpl_toolkits.mplot3d import Axes3D diff --git a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py index e94795213c..87907f803b 100644 --- a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py +++ b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py @@ -1,3 +1,7 @@ +""" +Forward Kinematics for an n-link arm in 3D +Author: Takayuki Murooka (takayuki5168) +""" import math from NLinkArm import NLinkArm import random @@ -17,7 +21,8 @@ def random_val(min_val, max_val): [0., -math.pi/2, 0., .321], [0., math.pi/2, 0., 0.], [0., 0., 0., 0.]]) - + + # execute FK 10 times for i in range(10): n_link_arm.set_joint_angles([random_val(-1, 1) for j in range(len(n_link_arm.link_list))]) diff --git a/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py index dd51381678..44be22709f 100644 --- a/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py +++ b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py @@ -1,3 +1,7 @@ +""" +Inverse Kinematics for an n-link arm in 3D +Author: Takayuki Murooka (takayuki5168) +""" import math from NLinkArm import NLinkArm import random @@ -18,6 +22,7 @@ def random_val(min_val, max_val): [0., math.pi/2, 0., 0.], [0., 0., 0., 0.]]) + # execute IK 10 times for i in range(10): n_link_arm.inverse_kinematics([random_val(-0.5, 0.5), random_val(-0.5, 0.5), From 9b8f2bd88a3d516d8deb473693661c1aea59fe68 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 18 Jul 2019 20:57:42 +0900 Subject: [PATCH 007/940] fix typo --- README.md | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 551490461b..967c4aca69 100644 --- a/README.md +++ b/README.md @@ -12,7 +12,6 @@ Python codes for robotics algorithm. - # Table of Contents * [What is this?](#what-is-this) * [Requirements](#requirements) @@ -45,7 +44,7 @@ Python codes for robotics algorithm. * [Probabilistic Road-Map (PRM) planning](#probabilistic-road-map-prm-planning) * [Rapidly-Exploring Random Trees (RRT)](#rapidly-exploring-random-trees-rrt) * [RRT*](#rrt) - * [RRT* with reeds-sheep path](#rrt-with-reeds-sheep-path) + * [RRT* with reeds-shepp path](#rrt-with-reeds-shepp-path) * [LQR-RRT*](#lqr-rrt) * [Quintic polynomials planning](#quintic-polynomials-planning) * [Reeds Shepp planning](#reeds-shepp-planning) @@ -69,6 +68,7 @@ Python codes for robotics algorithm. * [License](#license) * [Use-case](#use-case) * [Contribution](#contribution) + * [Citing](#citing) * [Support](#support) * [Authors](#authors) @@ -360,11 +360,11 @@ Ref: - [Sampling-based Algorithms for Optimal Motion Planning](http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.419.5503&rep=rep1&type=pdf) -### RRT\* with reeds-sheep path +### RRT\* with reeds-shepp path ![Robotics/animation.gif at master · AtsushiSakai/PythonRobotics](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarReedsShepp/animation.gif)) -Path planning for a car robot with RRT\* and reeds sheep path planner. +Path planning for a car robot with RRT\* and reeds shepp path planner. ### LQR-RRT\* @@ -622,3 +622,4 @@ This is a list: [Users comments](https://github.com/AtsushiSakai/PythonRobotics/ + From 8ff5df74637e40e6496c8ea3b74129cf73cd6d36 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 19 Jul 2019 20:35:55 +0900 Subject: [PATCH 008/940] start implementing. --- PathPlanning/RRT/rrt.py | 43 +++++++++++++++++++++++------------------ 1 file changed, 24 insertions(+), 19 deletions(-) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index f257ef4d2a..0d44703be2 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -47,7 +47,7 @@ def __init__(self, start, goal, obstacle_list, self.expand_dis = expand_dis self.goal_sample_rate = goal_sample_rate self.max_iter = max_iter - self.obstacleList = obstacle_list + self.obstacle_list = obstacle_list self.node_list = [] def planning(self, animation=True): @@ -59,14 +59,14 @@ def planning(self, animation=True): self.node_list = [self.start] for i in range(self.max_iter): - rnd = self.get_random_point() - nearest_ind = self.get_nearest_list_index(self.node_list, rnd) + rnd_node = self.get_random_node() + nearest_ind = self.get_nearest_list_index(self.node_list, rnd_node) nearest_node = self.node_list[nearest_ind] - new_node = self.steer(rnd, nearest_node) + new_node = self.steer(nearest_node, rnd_node) new_node.parent = nearest_node - if not self.check_collision(new_node, self.obstacleList): + if not self.check_collision(new_node, self.obstacle_list): continue self.node_list.append(new_node) @@ -78,16 +78,21 @@ def planning(self, animation=True): return self.generate_final_course(len(self.node_list) - 1) if animation and i % 5: - self.draw_graph(rnd) + self.draw_graph(rnd_node) return None # cannot find path - def steer(self, rnd, nearest_node): - new_node = self.Node(rnd[0], rnd[1]) - d, theta = self.calc_distance_and_angle(nearest_node, new_node) + def steer(self, from_node, to_node): + d, theta = self.calc_distance_and_angle(from_node, to_node) if d > self.expand_dis: - new_node.x = nearest_node.x + self.expand_dis * math.cos(theta) - new_node.y = nearest_node.y + self.expand_dis * math.sin(theta) + x = from_node.x + self.expand_dis * math.cos(theta) + y = from_node.y + self.expand_dis * math.sin(theta) + else: + x = to_node.x + y = to_node.y + + new_node = self.Node(x, y) + new_node.parent = from_node return new_node @@ -106,25 +111,25 @@ def calc_dist_to_goal(self, x, y): dy = y - self.end.y return math.sqrt(dx ** 2 + dy ** 2) - def get_random_point(self): + def get_random_node(self): if random.randint(0, 100) > self.goal_sample_rate: - rnd = [random.uniform(self.min_rand, self.max_rand), - random.uniform(self.min_rand, self.max_rand)] + rnd = self.Node(random.uniform(self.min_rand, self.max_rand), + random.uniform(self.min_rand, self.max_rand)) else: # goal point sampling - rnd = [self.end.x, self.end.y] + rnd = self.Node(self.end.x, self.end.y) return rnd def draw_graph(self, rnd=None): plt.clf() if rnd is not None: - plt.plot(rnd[0], rnd[1], "^k") + plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: if node.parent: plt.plot([node.x, node.parent.x], [node.y, node.parent.y], "-g") - for (ox, oy, size) in self.obstacleList: + for (ox, oy, size) in self.obstacle_list: plt.plot(ox, oy, "ok", ms=30 * size) plt.plot(self.start.x, self.start.y, "xr") @@ -134,8 +139,8 @@ def draw_graph(self, rnd=None): plt.pause(0.01) @staticmethod - def get_nearest_list_index(node_list, rnd): - dlist = [(node.x - rnd[0]) ** 2 + (node.y - rnd[1]) + def get_nearest_list_index(node_list, rnd_node): + dlist = [(node.x - rnd_node.x) ** 2 + (node.y - rnd_node.y) ** 2 for node in node_list] minind = dlist.index(min(dlist)) From d7c570bf97c2cbc097494295322276c8877c4516 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 19 Jul 2019 20:39:41 +0900 Subject: [PATCH 009/940] remove duplicate script --- .../RRTStarDubins/dubins_path_planning.py | 303 ------------------ 1 file changed, 303 deletions(-) delete mode 100644 PathPlanning/RRTStarDubins/dubins_path_planning.py diff --git a/PathPlanning/RRTStarDubins/dubins_path_planning.py b/PathPlanning/RRTStarDubins/dubins_path_planning.py deleted file mode 100644 index b29465209b..0000000000 --- a/PathPlanning/RRTStarDubins/dubins_path_planning.py +++ /dev/null @@ -1,303 +0,0 @@ -""" - -Dubins path planner sample code - -author Atsushi Sakai (@Atsushi_twi) - -""" -import math -import matplotlib.pyplot as plt -import numpy as np - - -def mod2pi(theta): - return theta - 2.0 * math.pi * math.floor(theta / 2.0 / math.pi) - - -def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi - - -def LSL(alpha, beta, d): - sa = math.sin(alpha) - sb = math.sin(beta) - ca = math.cos(alpha) - cb = math.cos(beta) - c_ab = math.cos(alpha - beta) - - tmp0 = d + sa - sb - - mode = ["L", "S", "L"] - p_squared = 2 + (d * d) - (2 * c_ab) + (2 * d * (sa - sb)) - if p_squared < 0: - return None, None, None, mode - tmp1 = math.atan2((cb - ca), tmp0) - t = mod2pi(-alpha + tmp1) - p = math.sqrt(p_squared) - q = mod2pi(beta - tmp1) - # print(np.rad2deg(t), p, np.rad2deg(q)) - - return t, p, q, mode - - -def RSR(alpha, beta, d): - sa = math.sin(alpha) - sb = math.sin(beta) - ca = math.cos(alpha) - cb = math.cos(beta) - c_ab = math.cos(alpha - beta) - - tmp0 = d - sa + sb - mode = ["R", "S", "R"] - p_squared = 2 + (d * d) - (2 * c_ab) + (2 * d * (sb - sa)) - if p_squared < 0: - return None, None, None, mode - tmp1 = math.atan2((ca - cb), tmp0) - t = mod2pi(alpha - tmp1) - p = math.sqrt(p_squared) - q = mod2pi(-beta + tmp1) - - return t, p, q, mode - - -def LSR(alpha, beta, d): - sa = math.sin(alpha) - sb = math.sin(beta) - ca = math.cos(alpha) - cb = math.cos(beta) - c_ab = math.cos(alpha - beta) - - p_squared = -2 + (d * d) + (2 * c_ab) + (2 * d * (sa + sb)) - mode = ["L", "S", "R"] - if p_squared < 0: - return None, None, None, mode - p = math.sqrt(p_squared) - tmp2 = math.atan2((-ca - cb), (d + sa + sb)) - math.atan2(-2.0, p) - t = mod2pi(-alpha + tmp2) - q = mod2pi(-mod2pi(beta) + tmp2) - - return t, p, q, mode - - -def RSL(alpha, beta, d): - sa = math.sin(alpha) - sb = math.sin(beta) - ca = math.cos(alpha) - cb = math.cos(beta) - c_ab = math.cos(alpha - beta) - - p_squared = (d * d) - 2 + (2 * c_ab) - (2 * d * (sa + sb)) - mode = ["R", "S", "L"] - if p_squared < 0: - return None, None, None, mode - p = math.sqrt(p_squared) - tmp2 = math.atan2((ca + cb), (d - sa - sb)) - math.atan2(2.0, p) - t = mod2pi(alpha - tmp2) - q = mod2pi(beta - tmp2) - - return t, p, q, mode - - -def RLR(alpha, beta, d): - sa = math.sin(alpha) - sb = math.sin(beta) - ca = math.cos(alpha) - cb = math.cos(beta) - c_ab = math.cos(alpha - beta) - - mode = ["R", "L", "R"] - tmp_rlr = (6.0 - d * d + 2.0 * c_ab + 2.0 * d * (sa - sb)) / 8.0 - if abs(tmp_rlr) > 1.0: - return None, None, None, mode - - p = mod2pi(2 * math.pi - math.acos(tmp_rlr)) - t = mod2pi(alpha - math.atan2(ca - cb, d - sa + sb) + mod2pi(p / 2.0)) - q = mod2pi(alpha - beta - t + mod2pi(p)) - return t, p, q, mode - - -def LRL(alpha, beta, d): - sa = math.sin(alpha) - sb = math.sin(beta) - ca = math.cos(alpha) - cb = math.cos(beta) - c_ab = math.cos(alpha - beta) - - mode = ["L", "R", "L"] - tmp_lrl = (6. - d * d + 2 * c_ab + 2 * d * (- sa + sb)) / 8. - if abs(tmp_lrl) > 1: - return None, None, None, mode - p = mod2pi(2 * math.pi - math.acos(tmp_lrl)) - t = mod2pi(-alpha - math.atan2(ca - cb, d + sa - sb) + p / 2.) - q = mod2pi(mod2pi(beta) - alpha - t + mod2pi(p)) - - return t, p, q, mode - - -def dubins_path_planning_from_origin(ex, ey, eyaw, c): - # nomalize - dx = ex - dy = ey - D = math.sqrt(dx ** 2.0 + dy ** 2.0) - d = D / c - # print(dx, dy, D, d) - - theta = mod2pi(math.atan2(dy, dx)) - alpha = mod2pi(- theta) - beta = mod2pi(eyaw - theta) - # print(theta, alpha, beta, d) - - planners = [LSL, RSR, LSR, RSL, RLR, LRL] - - bcost = float("inf") - bt, bp, bq, bmode = None, None, None, None - - for planner in planners: - t, p, q, mode = planner(alpha, beta, d) - if t is None: - # print("".join(mode) + " cannot generate path") - continue - - cost = (abs(t) + abs(p) + abs(q)) - if bcost > cost: - bt, bp, bq, bmode = t, p, q, mode - bcost = cost - - # print(bmode) - px, py, pyaw = generate_course([bt, bp, bq], bmode, c) - - return px, py, pyaw, bmode, bcost - - -def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c): - """ - Dubins path plannner - - input: - sx x position of start point [m] - sy y position of start point [m] - syaw yaw angle of start point [rad] - ex x position of end point [m] - ey y position of end point [m] - eyaw yaw angle of end point [rad] - c curvature [1/m] - - output: - px - py - pyaw - mode - - """ - - ex = ex - sx - ey = ey - sy - - lex = math.cos(syaw) * ex + math.sin(syaw) * ey - ley = - math.sin(syaw) * ex + math.cos(syaw) * ey - leyaw = eyaw - syaw - - lpx, lpy, lpyaw, mode, clen = dubins_path_planning_from_origin( - lex, ley, leyaw, c) - - px = [math.cos(-syaw) * x + math.sin(-syaw) - * y + sx for x, y in zip(lpx, lpy)] - py = [- math.sin(-syaw) * x + math.cos(-syaw) - * y + sy for x, y in zip(lpx, lpy)] - pyaw = [pi_2_pi(iyaw + syaw) for iyaw in lpyaw] - # print(syaw) - # pyaw = lpyaw - - # plt.plot(pyaw, "-r") - # plt.plot(lpyaw, "-b") - # plt.plot(eyaw, "*r") - # plt.plot(syaw, "*b") - # plt.show() - - return px, py, pyaw, mode, clen - - -def generate_course(length, mode, c): - - px = [0.0] - py = [0.0] - pyaw = [0.0] - - for m, l in zip(mode, length): - pd = 0.0 - if m == "S": - d = 1.0 / c - else: # turning couse - d = np.deg2rad(3.0) - - while pd < abs(l - d): - # print(pd, l) - px.append(px[-1] + d * c * math.cos(pyaw[-1])) - py.append(py[-1] + d * c * math.sin(pyaw[-1])) - - if m == "L": # left turn - pyaw.append(pyaw[-1] + d) - elif m == "S": # Straight - pyaw.append(pyaw[-1]) - elif m == "R": # right turn - pyaw.append(pyaw[-1] - d) - pd += d - - d = l - pd - px.append(px[-1] + d * c * math.cos(pyaw[-1])) - py.append(py[-1] + d * c * math.sin(pyaw[-1])) - - if m == "L": # left turn - pyaw.append(pyaw[-1] + d) - elif m == "S": # Straight - pyaw.append(pyaw[-1]) - elif m == "R": # right turn - pyaw.append(pyaw[-1] - d) - pd += d - - return px, py, pyaw - - -def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): # pragma: no cover - """ - Plot arrow - """ - - if not isinstance(x, float): - for (ix, iy, iyaw) in zip(x, y, yaw): - plot_arrow(ix, iy, iyaw) - else: - plt.arrow(x, y, length * math.cos(yaw), length * math.sin(yaw), - fc=fc, ec=ec, head_width=width, head_length=width) - plt.plot(x, y) - - -if __name__ == '__main__': - print("Dubins path planner sample start!!") - - start_x = 1.0 # [m] - start_y = 1.0 # [m] - start_yaw = np.deg2rad(45.0) # [rad] - - end_x = -3.0 # [m] - end_y = -3.0 # [m] - end_yaw = np.deg2rad(-45.0) # [rad] - - curvature = 1.0 - - px, py, pyaw, mode, clen = dubins_path_planning(start_x, start_y, start_yaw, - end_x, end_y, end_yaw, curvature) - - plt.plot(px, py, label="final course " + "".join(mode)) - - # plotting - plot_arrow(start_x, start_y, start_yaw) - plot_arrow(end_x, end_y, end_yaw) - - # for (ix, iy, iyaw) in zip(px, py, pyaw): - # plot_arrow(ix, iy, iyaw, fc="b") - - plt.legend() - plt.grid(True) - plt.axis("equal") - plt.show() From 2bf23adb27727e17a68ce2718e849ec2ffc826ba Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 20 Jul 2019 12:01:03 +0900 Subject: [PATCH 010/940] code clean up again --- PathPlanning/RRT/rrt.py | 47 +++++++++------ PathPlanning/RRTStar/rrt_star.py | 99 ++++++++++++++++++-------------- tests/test_rrt_star.py | 2 +- 3 files changed, 87 insertions(+), 61 deletions(-) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 0d44703be2..225bfa5dca 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -27,17 +27,19 @@ class Node(): def __init__(self, x, y): self.x = x self.y = y + self.path_x = [] + self.path_y = [] self.parent = None - def __init__(self, start, goal, obstacle_list, - rand_area, expand_dis=1.0, goal_sample_rate=5, max_iter=500): + def __init__(self, start, goal, obstacle_list, rand_area, + expand_dis=3.0, path_resolution=1.0, goal_sample_rate=5, max_iter=500): """ Setting Parameter start:Start Position [x,y] goal:Goal Position [x,y] obstacleList:obstacle Positions [[x,y,size],...] - randArea:Ramdom Samping Area [min,max] + randArea:Random Sampling Area [min,max] """ self.start = self.Node(start[0], start[1]) @@ -45,6 +47,7 @@ def __init__(self, start, goal, obstacle_list, self.min_rand = rand_area[0] self.max_rand = rand_area[1] self.expand_dis = expand_dis + self.path_resolution = path_resolution self.goal_sample_rate = goal_sample_rate self.max_iter = max_iter self.obstacle_list = obstacle_list @@ -63,7 +66,7 @@ def planning(self, animation=True): nearest_ind = self.get_nearest_list_index(self.node_list, rnd_node) nearest_node = self.node_list[nearest_ind] - new_node = self.steer(nearest_node, rnd_node) + new_node = self.steer(nearest_node, rnd_node, self.expand_dis) new_node.parent = nearest_node if not self.check_collision(new_node, self.obstacle_list): @@ -82,16 +85,25 @@ def planning(self, animation=True): return None # cannot find path - def steer(self, from_node, to_node): - d, theta = self.calc_distance_and_angle(from_node, to_node) - if d > self.expand_dis: - x = from_node.x + self.expand_dis * math.cos(theta) - y = from_node.y + self.expand_dis * math.sin(theta) - else: - x = to_node.x - y = to_node.y + def steer(self, from_node, to_node, extend_length=float("inf")): + + new_node = self.Node(from_node.x, from_node.y) + d, theta = self.calc_distance_and_angle(new_node, to_node) + + new_node.path_x = [new_node.x] + new_node.path_y = [new_node.y] + + if extend_length > d: + extend_length = d + + n_expand = math.floor(extend_length / self.path_resolution) + + for _ in range(n_expand): + new_node.x += self.path_resolution * math.cos(theta) + new_node.y += self.path_resolution * math.sin(theta) + new_node.path_x.append(new_node.x) + new_node.path_y.append(new_node.y) - new_node = self.Node(x, y) new_node.parent = from_node return new_node @@ -149,10 +161,11 @@ def get_nearest_list_index(node_list, rnd_node): @staticmethod def check_collision(node, obstacleList): for (ox, oy, size) in obstacleList: - dx = ox - node.x - dy = oy - node.y - d = dx * dx + dy * dy - if d <= size ** 2: + dx_list = [ox - x for x in node.path_x] + dy_list = [oy - y for y in node.path_y] + d_list = [dx * dx + dy * dy for (dx, dy) in zip(dx_list, dy_list)] + + if min(d_list) <= size ** 2: return False # collision return True # safe diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index da24d2c86b..446033d77f 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -6,7 +6,6 @@ """ -import copy import math import os import sys @@ -29,21 +28,20 @@ class RRTStar(RRT): Class for RRT Star planning """ - class Node: + class Node(RRT.Node): def __init__(self, x, y): - self.x = x - self.y = y + super().__init__(x, y) self.cost = 0.0 - self.parent = None def __init__(self, start, goal, obstacle_list, rand_area, - expand_dis=0.5, + expand_dis=3.0, + path_resolution=1.0, goal_sample_rate=20, - max_iter=500, + max_iter=300, connect_circle_dist=50.0 ): super().__init__(start, goal, obstacle_list, - rand_area, expand_dis, goal_sample_rate, max_iter) + rand_area, expand_dis, path_resolution, goal_sample_rate, max_iter) """ Setting Parameter @@ -65,11 +63,12 @@ def planning(self, animation=True, search_until_maxiter=True): self.node_list = [self.start] for i in range(self.max_iter): - rnd = self.get_random_point() + print(i, len(self.node_list)) + rnd = self.get_random_node() nearest_ind = self.get_nearest_list_index(self.node_list, rnd) - new_node = self.steer(rnd, self.node_list[nearest_ind]) + new_node = self.steer(self.node_list[nearest_ind], rnd, self.expand_dis) - if self.check_collision(new_node, self.obstacleList): + if self.check_collision(new_node, self.obstacle_list): near_inds = self.find_near_nodes(new_node) new_node = self.choose_parent(new_node, near_inds) if new_node: @@ -79,7 +78,7 @@ def planning(self, animation=True, search_until_maxiter=True): if animation and i % 5 == 0: self.draw_graph(rnd) - if not search_until_maxiter and new_node: # check reaching the goal + if (not search_until_maxiter) and new_node: # check reaching the goal d, _ = self.calc_distance_and_angle(new_node, self.end) if d <= self.expand_dis: return self.generate_final_course(len(self.node_list) - 1) @@ -92,6 +91,25 @@ def planning(self, animation=True, search_until_maxiter=True): return None + def connect_nodes(self, from_node, to_node): + new_node = self.Node(from_node.x, from_node.y) + d, theta = self.calc_distance_and_angle(new_node, to_node) + + new_node.path_x = [new_node.x] + new_node.path_y = [new_node.y] + + n_expand = math.floor(d / self.path_resolution) + + for _ in range(n_expand): + new_node.x += self.path_resolution * math.cos(theta) + new_node.y += self.path_resolution * math.sin(theta) + new_node.path_x.append(new_node.x) + new_node.path_y.append(new_node.y) + + new_node.parent = from_node + + return new_node + def choose_parent(self, new_node, near_inds): if not near_inds: return None @@ -99,9 +117,10 @@ def choose_parent(self, new_node, near_inds): # search nearest cost in near_inds costs = [] for i in near_inds: - d, theta = self.calc_distance_and_angle(self.node_list[i], new_node) - if self.check_collision_extend(self.node_list[i], theta, d): - costs.append(self.node_list[i].cost + d) + near_node = self.node_list[i] + t_node = self.steer(near_node, new_node) + if self.check_collision(t_node, self.obstacle_list): + costs.append(self.calc_new_cost(near_node, new_node)) else: costs.append(float("inf")) # the cost of collision node min_cost = min(costs) @@ -110,9 +129,10 @@ def choose_parent(self, new_node, near_inds): print("There is no good path.(min_cost is inf)") return None - new_node.cost = min_cost min_ind = near_inds[costs.index(min_cost)] new_node.parent = self.node_list[min_ind] + new_node = self.steer(new_node.parent, new_node) + new_node.cost = min_cost return new_node @@ -141,34 +161,27 @@ def find_near_nodes(self, new_node): def rewire(self, new_node, near_inds): for i in near_inds: near_node = self.node_list[i] - d, theta = self.calc_distance_and_angle(near_node, new_node) - new_cost = new_node.cost + d + edge_node = self.steer(new_node, near_node) + edge_node.cost = self.calc_new_cost(near_node, new_node) + + no_collision = self.check_collision(edge_node, self.obstacle_list) + improved_cost = near_node.cost > edge_node.cost + + if no_collision and improved_cost: + near_node.parent = new_node + near_node.cost = edge_node.cost + self.propagate_cost_to_leaves(new_node) - if near_node.cost > new_cost: - if self.check_collision_extend(near_node, theta, d): - near_node.parent = new_node - near_node.cost = new_cost - self.propagate_cost_to_leaves(new_node) + def calc_new_cost(self, from_node, to_node): + d, _ = self.calc_distance_and_angle(from_node, to_node) + return from_node.cost + d def propagate_cost_to_leaves(self, parent_node): for node in self.node_list: if node.parent == parent_node: - d, _ = self.calc_distance_and_angle(parent_node, node) - node.cost = parent_node.cost + d + node.cost = self.calc_new_cost(parent_node, node) self.propagate_cost_to_leaves(node) - def check_collision_extend(self, near_node, theta, d): - - tmp_node = copy.deepcopy(near_node) - - for i in range(int(d / self.expand_dis)): - tmp_node.x += self.expand_dis * math.cos(theta) - tmp_node.y += self.expand_dis * math.sin(theta) - if not self.check_collision(tmp_node, self.obstacleList): - return False - - return True - def main(): print("Start " + __file__) @@ -184,11 +197,11 @@ def main(): ] # [x,y,size(radius)] # Set Initial parameters - rrt = RRTStar(start=[0, 0], - goal=[10, 10], - rand_area=[-2, 15], - obstacle_list=obstacle_list) - path = rrt.planning(animation=show_animation, search_until_maxiter=False) + rrt_star = RRTStar(start=[0, 0], + goal=[10, 10], + rand_area=[-2, 15], + obstacle_list=obstacle_list) + path = rrt_star.planning(animation=show_animation) if path is None: print("Cannot find path") @@ -197,7 +210,7 @@ def main(): # Draw final path if show_animation: - rrt.draw_graph() + rrt_star.draw_graph() plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') plt.grid(True) plt.pause(0.01) # Need for Mac diff --git a/tests/test_rrt_star.py b/tests/test_rrt_star.py index c5f8f870e0..514ed34829 100644 --- a/tests/test_rrt_star.py +++ b/tests/test_rrt_star.py @@ -7,7 +7,7 @@ try: import rrt_star as m -except: +except ImportError: raise From c66fccc71c681387ff61b59554694b25399ca790 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 24 Jul 2019 19:42:54 +0900 Subject: [PATCH 011/940] Update users_comments.md --- users_comments.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/users_comments.md b/users_comments.md index b7e88c92bb..bf3c8455de 100644 --- a/users_comments.md +++ b/users_comments.md @@ -304,6 +304,9 @@ URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8516589&isnumber=85 3. Welburn, E, Hakim Khalili, H, Gupta, A, Watson, S & Carrasco, J 2019, A Navigational System for Quadcopter Remote Inspection of Offshore Substations. in The Fifteenth International Conference on Autonomic and Autonomous Systems 2019. URL:https://www.research.manchester.ac.uk/portal/files/107169964/ICAS19_A_Navigational_System_for_Quadcopter_Remote_Inspection_of_Offshore_Substations.pdf +4. E. Horváth, C. Hajdu, C. Radu and Á. Ballagi, "Range Sensor-based Occupancy Grid Mapping with Signatures," 2019 20th International Carpathian Control Conference (ICCC), Krakow-Wieliczka, Poland, 2019, pp. 1-5. +URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8765684&isnumber=8765679 + # Others From 446391e9e21df9a710b434c0617881cd962f05fb Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 26 Jul 2019 19:42:34 +0900 Subject: [PATCH 012/940] Update users_comments.md --- users_comments.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/users_comments.md b/users_comments.md index bf3c8455de..9bbf87be67 100644 --- a/users_comments.md +++ b/users_comments.md @@ -293,6 +293,12 @@ Thanks for your robotics repo! --- +You made such a nice work. Congratulations :) + +--ATroya + +--- + # Citations 1. B. Blaga, M. Deac, R. W. Y. Al-doori, M. Negru and R. Dǎnescu, "Miniature Autonomous Vehicle Development on Raspberry Pi," 2018 IEEE 14th International Conference on Intelligent Computer Communication and Processing (ICCP), Cluj-Napoca, Romania, 2018, pp. 229-236. From 4102b6ed150930c463ecb743bc7994b72ad45636 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 27 Jul 2019 07:32:17 +0900 Subject: [PATCH 013/940] Update README.md --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index 967c4aca69..e8bf0d297d 100644 --- a/README.md +++ b/README.md @@ -491,6 +491,8 @@ Ref: - [notebook](https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/model_predictive_speed_and_steer_control/Model_predictive_speed_and_steering_control.ipynb) +- [Real\-time Model Predictive Control \(MPC\), ACADO, Python \| Work\-is\-Playing](http://grauonline.de/wordpress/?page_id=3244) + ## Nonlinear Model predictive control with C-GMRES A motion planning and path tracking simulation with NMPC of C-GMRES From cc9bb11345975bae4a1b3946953ad746b43ca94d Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 27 Jul 2019 07:32:54 +0900 Subject: [PATCH 014/940] Update users_comments.md --- users_comments.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/users_comments.md b/users_comments.md index 9bbf87be67..087acd3a7c 100644 --- a/users_comments.md +++ b/users_comments.md @@ -320,3 +320,5 @@ URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8765684&isnumber=87 - 36 Amazing Python Open Source Projects (v.2019) – Mybridge for Professionals https://medium.mybridge.co/36-amazing-python-open-source-projects-v-2019-2fe058d79450 +- Real-time Model Predictive Control (MPC), ACADO, Python | Work-is-Playing http://grauonline.de/wordpress/?page_id=3244 + From d9508f6e725d1735bb80a9acebecd4e8ca2667ad Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 27 Jul 2019 15:08:25 +0900 Subject: [PATCH 015/940] fix rrt_star_dubins --- .../DubinsPath/dubins_path_planning.py | 17 +++++---- PathPlanning/RRT/rrt.py | 13 +++++-- PathPlanning/RRTStar/rrt_star.py | 38 +++++-------------- 3 files changed, 28 insertions(+), 40 deletions(-) diff --git a/PathPlanning/DubinsPath/dubins_path_planning.py b/PathPlanning/DubinsPath/dubins_path_planning.py index dc7485ad9a..706b5a49af 100644 --- a/PathPlanning/DubinsPath/dubins_path_planning.py +++ b/PathPlanning/DubinsPath/dubins_path_planning.py @@ -6,8 +6,9 @@ """ import math -import numpy as np + import matplotlib.pyplot as plt +import numpy as np show_animation = True @@ -136,8 +137,8 @@ def LRL(alpha, beta, d): return t, p, q, mode -def dubins_path_planning_from_origin(ex, ey, eyaw, c): - # nomalize +def dubins_path_planning_from_origin(ex, ey, eyaw, c, D_ANGLE): + # normalize dx = ex dy = ey D = math.sqrt(dx ** 2.0 + dy ** 2.0) @@ -165,12 +166,12 @@ def dubins_path_planning_from_origin(ex, ey, eyaw, c): bcost = cost # print(bmode) - px, py, pyaw = generate_course([bt, bp, bq], bmode, c) + px, py, pyaw = generate_course([bt, bp, bq], bmode, c, D_ANGLE) return px, py, pyaw, bmode, bcost -def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c): +def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c, D_ANGLE=np.deg2rad(10.0)): """ Dubins path plannner @@ -199,7 +200,7 @@ def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c): leyaw = eyaw - syaw lpx, lpy, lpyaw, mode, clen = dubins_path_planning_from_origin( - lex, ley, leyaw, c) + lex, ley, leyaw, c, D_ANGLE) px = [math.cos(-syaw) * x + math.sin(-syaw) * y + sx for x, y in zip(lpx, lpy)] @@ -210,7 +211,7 @@ def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c): return px, py, pyaw, mode, clen -def generate_course(length, mode, c): +def generate_course(length, mode, c, D_ANGLE): px = [0.0] py = [0.0] @@ -221,7 +222,7 @@ def generate_course(length, mode, c): if m == "S": d = 1.0 * c else: # turning couse - d = np.deg2rad(3.0) + d = D_ANGLE while pd < abs(l - d): # print(pd, l) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 225bfa5dca..768fe41d1e 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -19,7 +19,7 @@ class RRT: Class for RRT planning """ - class Node(): + class Node: """ RRT Node """ @@ -104,6 +104,13 @@ def steer(self, from_node, to_node, extend_length=float("inf")): new_node.path_x.append(new_node.x) new_node.path_y.append(new_node.y) + d, _ = self.calc_distance_and_angle(new_node, to_node) + if d <= self.path_resolution: + new_node.x = to_node.x + new_node.y = to_node.y + new_node.path_x[-1] = to_node.x + new_node.path_y[-1] = to_node.y + new_node.parent = from_node return new_node @@ -137,9 +144,7 @@ def draw_graph(self, rnd=None): plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: if node.parent: - plt.plot([node.x, node.parent.x], - [node.y, node.parent.y], - "-g") + plt.plot(node.path_x, node.path_y, "-g") for (ox, oy, size) in self.obstacle_list: plt.plot(ox, oy, "ok", ms=30 * size) diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index 446033d77f..19e6812686 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -53,7 +53,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, """ self.connect_circle_dist = connect_circle_dist - def planning(self, animation=True, search_until_maxiter=True): + def planning(self, animation=True, search_until_max_iter=True): """ rrt star path planning @@ -63,7 +63,7 @@ def planning(self, animation=True, search_until_maxiter=True): self.node_list = [self.start] for i in range(self.max_iter): - print(i, len(self.node_list)) + print("Iter:", i, ", number of nodes:", len(self.node_list)) rnd = self.get_random_node() nearest_ind = self.get_nearest_list_index(self.node_list, rnd) new_node = self.steer(self.node_list[nearest_ind], rnd, self.expand_dis) @@ -78,10 +78,10 @@ def planning(self, animation=True, search_until_maxiter=True): if animation and i % 5 == 0: self.draw_graph(rnd) - if (not search_until_maxiter) and new_node: # check reaching the goal - d, _ = self.calc_distance_and_angle(new_node, self.end) - if d <= self.expand_dis: - return self.generate_final_course(len(self.node_list) - 1) + if (not search_until_max_iter) and new_node: # check reaching the goal + last_index = self.search_best_goal_node() + if last_index: + return self.generate_final_course(last_index) print("reached max iteration") @@ -91,25 +91,6 @@ def planning(self, animation=True, search_until_maxiter=True): return None - def connect_nodes(self, from_node, to_node): - new_node = self.Node(from_node.x, from_node.y) - d, theta = self.calc_distance_and_angle(new_node, to_node) - - new_node.path_x = [new_node.x] - new_node.path_y = [new_node.y] - - n_expand = math.floor(d / self.path_resolution) - - for _ in range(n_expand): - new_node.x += self.path_resolution * math.cos(theta) - new_node.y += self.path_resolution * math.sin(theta) - new_node.path_x.append(new_node.x) - new_node.path_y.append(new_node.y) - - new_node.parent = from_node - - return new_node - def choose_parent(self, new_node, near_inds): if not near_inds: return None @@ -130,8 +111,8 @@ def choose_parent(self, new_node, near_inds): return None min_ind = near_inds[costs.index(min_cost)] + new_node = self.steer(self.node_list[min_ind], new_node) new_node.parent = self.node_list[min_ind] - new_node = self.steer(new_node.parent, new_node) new_node.cost = min_cost return new_node @@ -162,14 +143,14 @@ def rewire(self, new_node, near_inds): for i in near_inds: near_node = self.node_list[i] edge_node = self.steer(new_node, near_node) - edge_node.cost = self.calc_new_cost(near_node, new_node) + edge_node.cost = self.calc_new_cost(new_node, near_node) no_collision = self.check_collision(edge_node, self.obstacle_list) improved_cost = near_node.cost > edge_node.cost if no_collision and improved_cost: + near_node = edge_node near_node.parent = new_node - near_node.cost = edge_node.cost self.propagate_cost_to_leaves(new_node) def calc_new_cost(self, from_node, to_node): @@ -177,6 +158,7 @@ def calc_new_cost(self, from_node, to_node): return from_node.cost + d def propagate_cost_to_leaves(self, parent_node): + for node in self.node_list: if node.parent == parent_node: node.cost = self.calc_new_cost(parent_node, node) From 67540275a6ca5abad9ff8466ce76e65c422d1724 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 27 Jul 2019 15:25:50 +0900 Subject: [PATCH 016/940] fix RRTDubins --- PathPlanning/RRT/rrt.py | 10 +- PathPlanning/RRTDubins/rrt_dubins.py | 277 +++++++------- PathPlanning/RRTStarDubins/rrt_star_dubins.py | 347 ++++++++---------- 3 files changed, 288 insertions(+), 346 deletions(-) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 768fe41d1e..541c2a9636 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -67,15 +67,13 @@ def planning(self, animation=True): nearest_node = self.node_list[nearest_ind] new_node = self.steer(nearest_node, rnd_node, self.expand_dis) - new_node.parent = nearest_node - if not self.check_collision(new_node, self.obstacle_list): - continue + if self.check_collision(new_node, self.obstacle_list): + self.node_list.append(new_node) - self.node_list.append(new_node) - print("nNodelist:", len(self.node_list)) + if animation and i % 5 == 0: + self.draw_graph(rnd_node) - # check goal if self.calc_dist_to_goal(new_node.x, new_node.y) <= self.expand_dis: print("Goal!!") return self.generate_final_course(len(self.node_list) - 1) diff --git a/PathPlanning/RRTDubins/rrt_dubins.py b/PathPlanning/RRTDubins/rrt_dubins.py index 54752ef81e..e87e3aa0a6 100644 --- a/PathPlanning/RRTDubins/rrt_dubins.py +++ b/PathPlanning/RRTDubins/rrt_dubins.py @@ -1,204 +1,207 @@ """ -Path Planning Sample Code with RRT for car like robot. +Path planning Sample Code with RRT for car like robot. author: AtsushiSakai(@Atsushi_twi) """ -import matplotlib.pyplot as plt -import numpy as np import copy import math +import os import random import sys -import os + +import matplotlib.pyplot as plt +import numpy as np + sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../DubinsPath/") +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../RRT/") try: + from rrt import RRT import dubins_path_planning -except: +except ImportError: raise show_animation = True -class RRT(): +class RRTDubins(RRT): """ - Class for RRT Planning + Class for RRT planning with Dubins path """ - def __init__(self, start, goal, obstacleList, randArea, - goalSampleRate=10, maxIter=1000): + class Node(RRT.Node): + """ + RRT Node + """ + + def __init__(self, x, y, yaw): + super().__init__(x, y) + self.cost = 0 + self.yaw = yaw + self.path_yaw = [] + + def __init__(self, start, goal, obstacle_list, rand_area, + goal_sample_rate=10, + max_iter=200, + ): """ Setting Parameter start:Start Position [x,y] goal:Goal Position [x,y] obstacleList:obstacle Positions [[x,y,size],...] - randArea:Ramdom Samping Area [min,max] + randArea:Random Sampling Area [min,max] """ - self.start = Node(start[0], start[1], start[2]) - self.end = Node(goal[0], goal[1], goal[2]) - self.minrand = randArea[0] - self.maxrand = randArea[1] - self.goalSampleRate = goalSampleRate - self.maxIter = maxIter - self.obstacleList = obstacleList - - def Planning(self, animation=False): + self.start = self.Node(start[0], start[1], start[2]) + self.end = self.Node(goal[0], goal[1], goal[2]) + self.min_rand = rand_area[0] + self.max_rand = rand_area[1] + self.goal_sample_rate = goal_sample_rate + self.max_iter = max_iter + self.obstacle_list = obstacle_list + + self.curvature = 1.0 # for dubins path + self.goal_yaw_th = np.deg2rad(1.0) + self.goal_xy_th = 0.5 + + def planning(self, animation=True, search_until_max_iter=True): """ - Pathplanning + execute planning animation: flag for animation on or off """ - self.nodeList = [self.start] - for i in range(self.maxIter): - rnd = self.get_random_point() - nind = self.GetNearestListIndex(self.nodeList, rnd) - - newNode = self.steer(rnd, nind) + self.node_list = [self.start] + for i in range(self.max_iter): + print("Iter:", i, ", number of nodes:", len(self.node_list)) + rnd = self.get_random_node() + nearest_ind = self.get_nearest_list_index(self.node_list, rnd) + new_node = self.steer(self.node_list[nearest_ind], rnd) - if self.__CollisionCheck(newNode, self.obstacleList): - self.nodeList.append(newNode) + if self.check_collision(new_node, self.obstacle_list): + self.node_list.append(new_node) if animation and i % 5 == 0: - self.DrawGraph(rnd=rnd) + self.plot_start_goal_arrow() + self.draw_graph(rnd) - # generate coruse - lastIndex = self.get_best_last_index() - # print(lastIndex) + if (not search_until_max_iter) and new_node: # check reaching the goal + last_index = self.search_best_goal_node() + if last_index: + return self.generate_final_course(last_index) - if lastIndex is None: - return None + print("reached max iteration") - path = self.gen_final_course(lastIndex) - return path + last_index = self.search_best_goal_node() + if last_index: + return self.generate_final_course(last_index) + else: + print("Cannot find path") - def pi_2_pi(self, angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + return None + + def draw_graph(self, rnd=None): + plt.clf() + if rnd is not None: + plt.plot(rnd.x, rnd.y, "^k") + for node in self.node_list: + if node.parent: + plt.plot(node.path_x, node.path_y, "-g") + + for (ox, oy, size) in self.obstacle_list: + plt.plot(ox, oy, "ok", ms=30 * size) + + plt.plot(self.start.x, self.start.y, "xr") + plt.plot(self.end.x, self.end.y, "xr") + plt.axis([-2, 15, -2, 15]) + plt.grid(True) + self.plot_start_goal_arrow() + plt.pause(0.01) + + def plot_start_goal_arrow(self): + dubins_path_planning.plot_arrow( + self.start.x, self.start.y, self.start.yaw) + dubins_path_planning.plot_arrow( + self.end.x, self.end.y, self.end.yaw) - def steer(self, rnd, nind): - # print(rnd) - curvature = 1.0 + def steer(self, from_node, to_node): - nearestNode = self.nodeList[nind] + px, py, pyaw, mode, course_length = dubins_path_planning.dubins_path_planning( + from_node.x, from_node.y, from_node.yaw, + to_node.x, to_node.y, to_node.yaw, self.curvature) - px, py, pyaw, mode, clen = dubins_path_planning.dubins_path_planning( - nearestNode.x, nearestNode.y, nearestNode.yaw, rnd[0], rnd[1], rnd[2], curvature) + new_node = copy.deepcopy(from_node) + new_node.x = px[-1] + new_node.y = py[-1] + new_node.yaw = pyaw[-1] - newNode = copy.deepcopy(nearestNode) - newNode.x = px[-1] - newNode.y = py[-1] - newNode.yaw = pyaw[-1] + new_node.path_x = px + new_node.path_y = py + new_node.path_yaw = pyaw + new_node.cost += course_length + new_node.parent = from_node - newNode.path_x = px - newNode.path_y = py - newNode.path_yaw = pyaw - newNode.cost += clen - newNode.parent = nind + return new_node - return newNode + def calc_new_cost(self, from_node, to_node): - def get_random_point(self): + _, _, _, _, course_length = dubins_path_planning.dubins_path_planning( + from_node.x, from_node.y, from_node.yaw, + to_node.x, to_node.y, to_node.yaw, self.curvature) - if random.randint(0, 100) > self.goalSampleRate: - rnd = [random.uniform(self.minrand, self.maxrand), - random.uniform(self.minrand, self.maxrand), - random.uniform(-math.pi, math.pi) - ] + return from_node.cost + course_length + + def get_random_node(self): + + if random.randint(0, 100) > self.goal_sample_rate: + rnd = self.Node(random.uniform(self.min_rand, self.max_rand), + random.uniform(self.min_rand, self.max_rand), + random.uniform(-math.pi, math.pi) + ) else: # goal point sampling - rnd = [self.end.x, self.end.y, self.end.yaw] + rnd = self.Node(self.end.x, self.end.y, self.end.yaw) return rnd - def get_best_last_index(self): - # print("get_best_last_index") + def search_best_goal_node(self): + + goal_indexes = [] + for (i, node) in enumerate(self.node_list): + if self.calc_dist_to_goal(node.x, node.y) <= self.goal_xy_th: + goal_indexes.append(i) + + # angle check + final_goal_indexes = [] + for i in goal_indexes: + if abs(self.node_list[i].yaw - self.end.yaw) <= self.goal_yaw_th: + final_goal_indexes.append(i) - disglist = [self.calc_dist_to_goal( - node.x, node.y) for node in self.nodeList] - goalinds = [disglist.index(i) for i in disglist if i <= 0.1] - # print(goalinds) + if not final_goal_indexes: + return None - mincost = min([self.nodeList[i].cost for i in goalinds]) - for i in goalinds: - if self.nodeList[i].cost == mincost: + min_cost = min([self.node_list[i].cost for i in final_goal_indexes]) + for i in final_goal_indexes: + if self.node_list[i].cost == min_cost: return i return None - def gen_final_course(self, goalind): + def generate_final_course(self, goal_index): + print("final") path = [[self.end.x, self.end.y]] - while self.nodeList[goalind].parent is not None: - node = self.nodeList[goalind] + node = self.node_list[goal_index] + while node.parent: for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)): path.append([ix, iy]) - # path.append([node.x, node.y]) - goalind = node.parent + node = node.parent path.append([self.start.x, self.start.y]) return path - def calc_dist_to_goal(self, x, y): - return np.linalg.norm([x - self.end.x, y - self.end.y]) - - def DrawGraph(self, rnd=None): # pragma: no cover - plt.clf() - if rnd is not None: - plt.plot(rnd[0], rnd[1], "^k") - for node in self.nodeList: - if node.parent is not None: - plt.plot(node.path_x, node.path_y, "-g") - - for (ox, oy, size) in self.obstacleList: - plt.plot(ox, oy, "ok", ms=30 * size) - - dubins_path_planning.plot_arrow( - self.start.x, self.start.y, self.start.yaw) - dubins_path_planning.plot_arrow( - self.end.x, self.end.y, self.end.yaw) - - plt.axis([-2, 15, -2, 15]) - plt.grid(True) - plt.pause(0.01) - - def GetNearestListIndex(self, nodeList, rnd): - dlist = [(node.x - rnd[0]) ** 2 - + (node.y - rnd[1]) ** 2 - + (node.yaw - rnd[2] ** 2) for node in nodeList] - minind = dlist.index(min(dlist)) - - return minind - - def __CollisionCheck(self, node, obstacleList): - - for (ox, oy, size) in obstacleList: - for (ix, iy) in zip(node.path_x, node.path_y): - dx = ox - ix - dy = oy - iy - d = dx * dx + dy * dy - if d <= size ** 2: - return False # collision - - return True # safe - - -class Node(): - """ - RRT Node - """ - - def __init__(self, x, y, yaw): - self.x = x - self.y = y - self.yaw = yaw - self.path_x = [] - self.path_y = [] - self.path_yaw = [] - self.cost = 0.0 - self.parent = None - def main(): print("Start " + __file__) @@ -216,12 +219,12 @@ def main(): start = [0.0, 0.0, np.deg2rad(0.0)] goal = [10.0, 10.0, np.deg2rad(0.0)] - rrt = RRT(start, goal, randArea=[-2.0, 15.0], obstacleList=obstacleList) - path = rrt.Planning(animation=show_animation) + rrt_dubins = RRTDubins(start, goal, obstacleList, [-2.0, 15.0]) + path = rrt_dubins.planning(animation=show_animation) # Draw final path if show_animation: # pragma: no cover - rrt.DrawGraph() + rrt_dubins.draw_graph() plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') plt.grid(True) plt.pause(0.001) diff --git a/PathPlanning/RRTStarDubins/rrt_star_dubins.py b/PathPlanning/RRTStarDubins/rrt_star_dubins.py index 0494bbabef..b98c7dca1c 100644 --- a/PathPlanning/RRTStarDubins/rrt_star_dubins.py +++ b/PathPlanning/RRTStarDubins/rrt_star_dubins.py @@ -1,271 +1,212 @@ """ -Path Planning Sample Code with RRT and Dubins path +Path planning Sample Code with RRT and Dubins path author: AtsushiSakai(@Atsushi_twi) """ -import random -import math import copy -import numpy as np -import dubins_path_planning +import math +import os +import random +import sys + import matplotlib.pyplot as plt +import numpy as np + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../DubinsPath/") +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../RRTStar/") + +try: + import dubins_path_planning + from rrt_star import RRTStar +except ImportError: + raise show_animation = True -class RRT(): +class RRTStarDubins(RRTStar): """ - Class for RRT Planning + Class for RRT star planning with Dubins path """ - def __init__(self, start, goal, obstacleList, randArea, - goalSampleRate=10, maxIter=100): + class Node(RRTStar.Node): + """ + RRT Node + """ + + def __init__(self, x, y, yaw): + super().__init__(x, y) + self.yaw = yaw + self.path_yaw = [] + + def __init__(self, start, goal, obstacle_list, rand_area, + goal_sample_rate=10, + max_iter=200, + connect_circle_dist=50.0 + ): """ Setting Parameter start:Start Position [x,y] goal:Goal Position [x,y] obstacleList:obstacle Positions [[x,y,size],...] - randArea:Ramdom Samping Area [min,max] + randArea:Random Sampling Area [min,max] """ - self.start = Node(start[0], start[1], start[2]) - self.end = Node(goal[0], goal[1], goal[2]) - self.minrand = randArea[0] - self.maxrand = randArea[1] - self.goalSampleRate = goalSampleRate - self.maxIter = maxIter - self.obstacleList = obstacleList - - def Planning(self, animation=True): + self.start = self.Node(start[0], start[1], start[2]) + self.end = self.Node(goal[0], goal[1], goal[2]) + self.min_rand = rand_area[0] + self.max_rand = rand_area[1] + self.goal_sample_rate = goal_sample_rate + self.max_iter = max_iter + self.obstacle_list = obstacle_list + self.connect_circle_dist = connect_circle_dist + + self.curvature = 1.0 # for dubins path + self.goal_yaw_th = np.deg2rad(1.0) + self.goal_xy_th = 0.5 + + def planning(self, animation=True, search_until_max_iter=True): """ - Pathplanning + RRT Star planning animation: flag for animation on or off """ - self.nodeList = [self.start] - for i in range(self.maxIter): - rnd = self.get_random_point() - nind = self.GetNearestListIndex(self.nodeList, rnd) + self.node_list = [self.start] + for i in range(self.max_iter): + print("Iter:", i, ", number of nodes:", len(self.node_list)) + rnd = self.get_random_node() + nearest_ind = self.get_nearest_list_index(self.node_list, rnd) + new_node = self.steer(self.node_list[nearest_ind], rnd) - newNode = self.steer(rnd, nind) - # print(newNode.cost) - - if self.CollisionCheck(newNode, self.obstacleList): - nearinds = self.find_near_nodes(newNode) - newNode = self.choose_parent(newNode, nearinds) - self.nodeList.append(newNode) - self.rewire(newNode, nearinds) + if self.check_collision(new_node, self.obstacle_list): + near_indexes = self.find_near_nodes(new_node) + new_node = self.choose_parent(new_node, near_indexes) + if new_node: + self.node_list.append(new_node) + self.rewire(new_node, near_indexes) if animation and i % 5 == 0: - self.DrawGraph(rnd=rnd) + self.plot_start_goal_arrow() + self.draw_graph(rnd) - # generate coruse - lastIndex = self.get_best_last_index() - # print(lastIndex) + if (not search_until_max_iter) and new_node: # check reaching the goal + last_index = self.search_best_goal_node() + if last_index: + return self.generate_final_course(last_index) - if lastIndex is None: - return None + print("reached max iteration") - path = self.gen_final_course(lastIndex) - return path + last_index = self.search_best_goal_node() + if last_index: + return self.generate_final_course(last_index) + else: + print("Cannot find path") - def choose_parent(self, newNode, nearinds): - if not nearinds: - return newNode + return None - dlist = [] - for i in nearinds: - tNode = self.steer(newNode, i) - if self.CollisionCheck(tNode, self.obstacleList): - dlist.append(tNode.cost) - else: - dlist.append(float("inf")) + def draw_graph(self, rnd=None): + plt.clf() + if rnd is not None: + plt.plot(rnd.x, rnd.y, "^k") + for node in self.node_list: + if node.parent: + plt.plot(node.path_x, node.path_y, "-g") - mincost = min(dlist) - minind = nearinds[dlist.index(mincost)] + for (ox, oy, size) in self.obstacle_list: + plt.plot(ox, oy, "ok", ms=30 * size) - if mincost == float("inf"): - print("mincost is inf") - return newNode + plt.plot(self.start.x, self.start.y, "xr") + plt.plot(self.end.x, self.end.y, "xr") + plt.axis([-2, 15, -2, 15]) + plt.grid(True) + self.plot_start_goal_arrow() + plt.pause(0.01) - newNode = self.steer(newNode, minind) + def plot_start_goal_arrow(self): + dubins_path_planning.plot_arrow( + self.start.x, self.start.y, self.start.yaw) + dubins_path_planning.plot_arrow( + self.end.x, self.end.y, self.end.yaw) - return newNode + def steer(self, from_node, to_node): - def pi_2_pi(self, angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + px, py, pyaw, mode, course_length = dubins_path_planning.dubins_path_planning( + from_node.x, from_node.y, from_node.yaw, + to_node.x, to_node.y, to_node.yaw, self.curvature) - def steer(self, rnd, nind): - # print(rnd) - curvature = 1.0 + new_node = copy.deepcopy(from_node) + new_node.x = px[-1] + new_node.y = py[-1] + new_node.yaw = pyaw[-1] - nearestNode = self.nodeList[nind] + new_node.path_x = px + new_node.path_y = py + new_node.path_yaw = pyaw + new_node.cost += course_length + new_node.parent = from_node - px, py, pyaw, mode, clen = dubins_path_planning.dubins_path_planning( - nearestNode.x, nearestNode.y, nearestNode.yaw, rnd.x, rnd.y, rnd.yaw, curvature) + return new_node - newNode = copy.deepcopy(nearestNode) - newNode.x = px[-1] - newNode.y = py[-1] - newNode.yaw = pyaw[-1] + def calc_new_cost(self, from_node, to_node): - newNode.path_x = px - newNode.path_y = py - newNode.path_yaw = pyaw - newNode.cost += clen - newNode.parent = nind + _, _, _, _, course_length = dubins_path_planning.dubins_path_planning( + from_node.x, from_node.y, from_node.yaw, + to_node.x, to_node.y, to_node.yaw, self.curvature) - return newNode + return from_node.cost + course_length - def get_random_point(self): + def get_random_node(self): - if random.randint(0, 100) > self.goalSampleRate: - rnd = [random.uniform(self.minrand, self.maxrand), - random.uniform(self.minrand, self.maxrand), - random.uniform(-math.pi, math.pi) - ] + if random.randint(0, 100) > self.goal_sample_rate: + rnd = self.Node(random.uniform(self.min_rand, self.max_rand), + random.uniform(self.min_rand, self.max_rand), + random.uniform(-math.pi, math.pi) + ) else: # goal point sampling - rnd = [self.end.x, self.end.y, self.end.yaw] - - node = Node(rnd[0], rnd[1], rnd[2]) + rnd = self.Node(self.end.x, self.end.y, self.end.yaw) - return node + return rnd - def get_best_last_index(self): - # print("get_best_last_index") + def search_best_goal_node(self): - YAWTH = np.deg2rad(1.0) - XYTH = 0.5 - - goalinds = [] - for (i, node) in enumerate(self.nodeList): - if self.calc_dist_to_goal(node.x, node.y) <= XYTH: - goalinds.append(i) + goal_indexes = [] + for (i, node) in enumerate(self.node_list): + if self.calc_dist_to_goal(node.x, node.y) <= self.goal_xy_th: + goal_indexes.append(i) # angle check - fgoalinds = [] - for i in goalinds: - if abs(self.nodeList[i].yaw - self.end.yaw) <= YAWTH: - fgoalinds.append(i) + final_goal_indexes = [] + for i in goal_indexes: + if abs(self.node_list[i].yaw - self.end.yaw) <= self.goal_yaw_th: + final_goal_indexes.append(i) - if not fgoalinds: + if not final_goal_indexes: return None - mincost = min([self.nodeList[i].cost for i in fgoalinds]) - for i in fgoalinds: - if self.nodeList[i].cost == mincost: + min_cost = min([self.node_list[i].cost for i in final_goal_indexes]) + for i in final_goal_indexes: + if self.node_list[i].cost == min_cost: return i return None - def gen_final_course(self, goalind): + def generate_final_course(self, goal_index): + print("final") path = [[self.end.x, self.end.y]] - while self.nodeList[goalind].parent is not None: - node = self.nodeList[goalind] + node = self.node_list[goal_index] + while node.parent: for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)): path.append([ix, iy]) - # path.append([node.x, node.y]) - goalind = node.parent + node = node.parent path.append([self.start.x, self.start.y]) return path - def calc_dist_to_goal(self, x, y): - return np.linalg.norm([x - self.end.x, y - self.end.y]) - - def find_near_nodes(self, newNode): - nnode = len(self.nodeList) - r = 50.0 * math.sqrt((math.log(nnode) / nnode)) - # r = self.expandDis * 5.0 - dlist = [(node.x - newNode.x) ** 2 + - (node.y - newNode.y) ** 2 + - (node.yaw - newNode.yaw) ** 2 - for node in self.nodeList] - nearinds = [dlist.index(i) for i in dlist if i <= r ** 2] - return nearinds - - def rewire(self, newNode, nearinds): - - nnode = len(self.nodeList) - - for i in nearinds: - nearNode = self.nodeList[i] - tNode = self.steer(nearNode, nnode - 1) - - obstacleOK = self.CollisionCheck(tNode, self.obstacleList) - imporveCost = nearNode.cost > tNode.cost - - if obstacleOK and imporveCost: - # print("rewire") - self.nodeList[i] = tNode - - def DrawGraph(self, rnd=None): # pragma: no cover - """ - Draw Graph - """ - plt.clf() - if rnd is not None: - plt.plot(rnd.x, rnd.y, "^k") - for node in self.nodeList: - if node.parent is not None: - plt.plot(node.path_x, node.path_y, "-g") - # plt.plot([node.x, self.nodeList[node.parent].x], [ - # node.y, self.nodeList[node.parent].y], "-g") - - for (ox, oy, size) in self.obstacleList: - plt.plot(ox, oy, "ok", ms=30 * size) - - dubins_path_planning.plot_arrow( - self.start.x, self.start.y, self.start.yaw) - dubins_path_planning.plot_arrow( - self.end.x, self.end.y, self.end.yaw) - - plt.axis([-2, 15, -2, 15]) - plt.grid(True) - plt.pause(0.01) - - # plt.show() - # input() - - def GetNearestListIndex(self, nodeList, rnd): - dlist = [(node.x - rnd.x) ** 2 + - (node.y - rnd.y) ** 2 + - (node.yaw - rnd.yaw) ** 2 for node in nodeList] - minind = dlist.index(min(dlist)) - - return minind - - def CollisionCheck(self, node, obstacleList): - - for (ox, oy, size) in obstacleList: - for (ix, iy) in zip(node.path_x, node.path_y): - dx = ox - ix - dy = oy - iy - d = dx * dx + dy * dy - if d <= size ** 2: - return False # collision - - return True # safe - - -class Node(): - """ - RRT Node - """ - - def __init__(self, x, y, yaw): - self.x = x - self.y = y - self.yaw = yaw - self.path_x = [] - self.path_y = [] - self.path_yaw = [] - self.cost = 0.0 - self.parent = None - def main(): print("Start rrt star with dubins planning") @@ -284,12 +225,12 @@ def main(): start = [0.0, 0.0, np.deg2rad(0.0)] goal = [10.0, 10.0, np.deg2rad(0.0)] - rrt = RRT(start, goal, randArea=[-2.0, 15.0], obstacleList=obstacleList) - path = rrt.Planning(animation=show_animation) + rrtstar_dubins = RRTStarDubins(start, goal, rand_area=[-2.0, 15.0], obstacle_list=obstacleList) + path = rrtstar_dubins.planning(animation=show_animation) # Draw final path if show_animation: # pragma: no cover - rrt.DrawGraph() + rrtstar_dubins.draw_graph() plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') plt.grid(True) plt.pause(0.001) From 0937486803ba629c9bc8db99455ef930ea00a612 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 27 Jul 2019 15:56:16 +0900 Subject: [PATCH 017/940] fix rrt star reeds shepp rewire and test --- PathPlanning/RRTDubins/rrt_dubins.py | 2 +- PathPlanning/RRTStar/rrt_star.py | 4 +- .../RRTStarReedsShepp/rrt_star_reeds_shepp.py | 362 +++++++----------- .../reeds_shepp_path_planning.py | 6 +- tests/test_dubins_path_planning.py | 8 +- 5 files changed, 158 insertions(+), 224 deletions(-) diff --git a/PathPlanning/RRTDubins/rrt_dubins.py b/PathPlanning/RRTDubins/rrt_dubins.py index e87e3aa0a6..78ce9611b3 100644 --- a/PathPlanning/RRTDubins/rrt_dubins.py +++ b/PathPlanning/RRTDubins/rrt_dubins.py @@ -1,5 +1,5 @@ """ -Path planning Sample Code with RRT for car like robot. +Path planning Sample Code with RRT with Dubins path author: AtsushiSakai(@Atsushi_twi) diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index 19e6812686..c92f435080 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -100,7 +100,7 @@ def choose_parent(self, new_node, near_inds): for i in near_inds: near_node = self.node_list[i] t_node = self.steer(near_node, new_node) - if self.check_collision(t_node, self.obstacle_list): + if t_node and self.check_collision(t_node, self.obstacle_list): costs.append(self.calc_new_cost(near_node, new_node)) else: costs.append(float("inf")) # the cost of collision node @@ -143,6 +143,8 @@ def rewire(self, new_node, near_inds): for i in near_inds: near_node = self.node_list[i] edge_node = self.steer(new_node, near_node) + if not edge_node: + continue edge_node.cost = self.calc_new_cost(new_node, near_node) no_collision = self.check_collision(edge_node, self.obstacle_list) diff --git a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py index aa03418f59..9082117286 100644 --- a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py +++ b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py @@ -1,289 +1,219 @@ """ -Path Planning Sample Code with RRT for car like robot. +Path planning Sample Code with RRT with Reeds-Shepp path author: AtsushiSakai(@Atsushi_twi) """ -import matplotlib.pyplot as plt -import numpy as np import copy import math +import os import random import sys -import os + +import matplotlib.pyplot as plt +import numpy as np + sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../ReedsSheppPath/") +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../RRTStar/") try: import reeds_shepp_path_planning -except: + from rrt_star import RRTStar +except ImportError: raise show_animation = True -STEP_SIZE = 0.1 -curvature = 1.0 -class RRT(): +class RRTStarReedsShepp(RRTStar): """ - Class for RRT Planning + Class for RRT star planning with Reeds Shepp path """ - def __init__(self, start, goal, obstacleList, randArea, - goalSampleRate=10, maxIter=400): + class Node(RRTStar.Node): + """ + RRT Node + """ + + def __init__(self, x, y, yaw): + super().__init__(x, y) + self.yaw = yaw + self.path_yaw = [] + + def __init__(self, start, goal, obstacle_list, rand_area, + goal_sample_rate=10, + max_iter=200, + connect_circle_dist=50.0 + ): """ Setting Parameter start:Start Position [x,y] goal:Goal Position [x,y] obstacleList:obstacle Positions [[x,y,size],...] - randArea:Ramdom Samping Area [min,max] + randArea:Random Sampling Area [min,max] """ - self.start = Node(start[0], start[1], start[2]) - self.end = Node(goal[0], goal[1], goal[2]) - self.minrand = randArea[0] - self.maxrand = randArea[1] - self.goalSampleRate = goalSampleRate - self.maxIter = maxIter - self.obstacleList = obstacleList - - def Planning(self, animation=True): + self.start = self.Node(start[0], start[1], start[2]) + self.end = self.Node(goal[0], goal[1], goal[2]) + self.min_rand = rand_area[0] + self.max_rand = rand_area[1] + self.goal_sample_rate = goal_sample_rate + self.max_iter = max_iter + self.obstacle_list = obstacle_list + self.connect_circle_dist = connect_circle_dist + + self.curvature = 1.0 + self.goal_yaw_th = np.deg2rad(1.0) + self.goal_xy_th = 0.5 + + def planning(self, animation=True, search_until_max_iter=True): """ - Pathplanning + RRT Star planning animation: flag for animation on or off """ - self.nodeList = [self.start] - for i in range(self.maxIter): - rnd = self.get_random_point() - nind = self.GetNearestListIndex(self.nodeList, rnd) - - newNode = self.steer(rnd, nind) - if newNode is None: - continue + self.node_list = [self.start] + for i in range(self.max_iter): + print("Iter:", i, ", number of nodes:", len(self.node_list)) + rnd = self.get_random_node() + nearest_ind = self.get_nearest_list_index(self.node_list, rnd) + new_node = self.steer(self.node_list[nearest_ind], rnd) - if self.CollisionCheck(newNode, self.obstacleList): - nearinds = self.find_near_nodes(newNode) - newNode = self.choose_parent(newNode, nearinds) - if newNode is None: - continue - self.nodeList.append(newNode) - self.rewire(newNode, nearinds) + if self.check_collision(new_node, self.obstacle_list): + near_indexes = self.find_near_nodes(new_node) + new_node = self.choose_parent(new_node, near_indexes) + if new_node: + self.node_list.append(new_node) + self.rewire(new_node, near_indexes) if animation and i % 5 == 0: - self.DrawGraph(rnd=rnd) - - # generate coruse - lastIndex = self.get_best_last_index() - if lastIndex is None: - return None - path = self.gen_final_course(lastIndex) - return path - - def choose_parent(self, newNode, nearinds): - if not nearinds: - return newNode + self.plot_start_goal_arrow() + self.draw_graph(rnd) - dlist = [] - for i in nearinds: - tNode = self.steer(newNode, i) - if tNode is None: - continue + if (not search_until_max_iter) and new_node: # check reaching the goal + last_index = self.search_best_goal_node() + if last_index: + return self.generate_final_course(last_index) - if self.CollisionCheck(tNode, self.obstacleList): - dlist.append(tNode.cost) - else: - dlist.append(float("inf")) + print("reached max iteration") - mincost = min(dlist) - minind = nearinds[dlist.index(mincost)] + last_index = self.search_best_goal_node() + if last_index: + return self.generate_final_course(last_index) + else: + print("Cannot find path") - if mincost == float("inf"): - print("mincost is inf") - return newNode + return None - newNode = self.steer(newNode, minind) + def draw_graph(self, rnd=None): + plt.clf() + if rnd is not None: + plt.plot(rnd.x, rnd.y, "^k") + for node in self.node_list: + if node.parent: + plt.plot(node.path_x, node.path_y, "-g") - return newNode + for (ox, oy, size) in self.obstacle_list: + plt.plot(ox, oy, "ok", ms=30 * size) - def pi_2_pi(self, angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + plt.plot(self.start.x, self.start.y, "xr") + plt.plot(self.end.x, self.end.y, "xr") + plt.axis([-2, 15, -2, 15]) + plt.grid(True) + self.plot_start_goal_arrow() + plt.pause(0.01) - def steer(self, rnd, nind): + def plot_start_goal_arrow(self): + reeds_shepp_path_planning.plot_arrow( + self.start.x, self.start.y, self.start.yaw) + reeds_shepp_path_planning.plot_arrow( + self.end.x, self.end.y, self.end.yaw) - nearestNode = self.nodeList[nind] + def steer(self, from_node, to_node): - px, py, pyaw, mode, clen = reeds_shepp_path_planning.reeds_shepp_path_planning( - nearestNode.x, nearestNode.y, nearestNode.yaw, rnd.x, rnd.y, rnd.yaw, curvature, STEP_SIZE) + px, py, pyaw, mode, course_lengths = reeds_shepp_path_planning.reeds_shepp_path_planning( + from_node.x, from_node.y, from_node.yaw, + to_node.x, to_node.y, to_node.yaw, self.curvature) - if px is None: + if not px: return None - newNode = copy.deepcopy(nearestNode) - newNode.x = px[-1] - newNode.y = py[-1] - newNode.yaw = pyaw[-1] + new_node = copy.deepcopy(from_node) + new_node.x = px[-1] + new_node.y = py[-1] + new_node.yaw = pyaw[-1] - newNode.path_x = px - newNode.path_y = py - newNode.path_yaw = pyaw - newNode.cost += sum([abs(c) for c in clen]) - newNode.parent = nind + new_node.path_x = px + new_node.path_y = py + new_node.path_yaw = pyaw + new_node.cost += sum(course_lengths) + new_node.parent = from_node - return newNode + return new_node - def get_random_point(self): + def calc_new_cost(self, from_node, to_node): - if random.randint(0, 100) > self.goalSampleRate: - rnd = [random.uniform(self.minrand, self.maxrand), - random.uniform(self.minrand, self.maxrand), - random.uniform(-math.pi, math.pi) - ] - else: # goal point sampling - rnd = [self.end.x, self.end.y, self.end.yaw] + _, _, _, _, course_lengths = reeds_shepp_path_planning.reeds_shepp_path_planning( + from_node.x, from_node.y, from_node.yaw, + to_node.x, to_node.y, to_node.yaw, self.curvature) + if not course_lengths: + return float("inf") + + return from_node.cost + sum(course_lengths) - node = Node(rnd[0], rnd[1], rnd[2]) + def get_random_node(self): - return node + if random.randint(0, 100) > self.goal_sample_rate: + rnd = self.Node(random.uniform(self.min_rand, self.max_rand), + random.uniform(self.min_rand, self.max_rand), + random.uniform(-math.pi, math.pi) + ) + else: # goal point sampling + rnd = self.Node(self.end.x, self.end.y, self.end.yaw) - def get_best_last_index(self): - # print("get_best_last_index") + return rnd - YAWTH = np.deg2rad(3.0) - XYTH = 0.5 + def search_best_goal_node(self): - goalinds = [] - for (i, node) in enumerate(self.nodeList): - if self.calc_dist_to_goal(node.x, node.y) <= XYTH: - goalinds.append(i) - # print("OK XY TH num is") - # print(len(goalinds)) + goal_indexes = [] + for (i, node) in enumerate(self.node_list): + if self.calc_dist_to_goal(node.x, node.y) <= self.goal_xy_th: + goal_indexes.append(i) # angle check - fgoalinds = [] - for i in goalinds: - if abs(self.nodeList[i].yaw - self.end.yaw) <= YAWTH: - fgoalinds.append(i) - # print("OK YAW TH num is") - # print(len(fgoalinds)) - - if not fgoalinds: + final_goal_indexes = [] + for i in goal_indexes: + if abs(self.node_list[i].yaw - self.end.yaw) <= self.goal_yaw_th: + final_goal_indexes.append(i) + + if not final_goal_indexes: return None - mincost = min([self.nodeList[i].cost for i in fgoalinds]) - for i in fgoalinds: - if self.nodeList[i].cost == mincost: + min_cost = min([self.node_list[i].cost for i in final_goal_indexes]) + for i in final_goal_indexes: + if self.node_list[i].cost == min_cost: return i return None - def gen_final_course(self, goalind): + def generate_final_course(self, goal_index): + print("final") path = [[self.end.x, self.end.y]] - while self.nodeList[goalind].parent is not None: - node = self.nodeList[goalind] + node = self.node_list[goal_index] + while node.parent: for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)): path.append([ix, iy]) - goalind = node.parent + node = node.parent path.append([self.start.x, self.start.y]) return path - def calc_dist_to_goal(self, x, y): - return np.linalg.norm([x - self.end.x, y - self.end.y]) - - def find_near_nodes(self, newNode): - nnode = len(self.nodeList) - r = 50.0 * math.sqrt((math.log(nnode) / nnode)) - # r = self.expandDis * 5.0 - dlist = [(node.x - newNode.x) ** 2 + - (node.y - newNode.y) ** 2 + - (node.yaw - newNode.yaw) ** 2 - for node in self.nodeList] - nearinds = [dlist.index(i) for i in dlist if i <= r ** 2] - return nearinds - - def rewire(self, newNode, nearinds): - - nnode = len(self.nodeList) - - for i in nearinds: - nearNode = self.nodeList[i] - tNode = self.steer(nearNode, nnode - 1) - if tNode is None: - continue - - obstacleOK = self.CollisionCheck(tNode, self.obstacleList) - imporveCost = nearNode.cost > tNode.cost - - if obstacleOK and imporveCost: - # print("rewire") - self.nodeList[i] = tNode - - def DrawGraph(self, rnd=None): # pragma: no cover - plt.clf() - if rnd is not None: - plt.plot(rnd.x, rnd.y, "^k") - for node in self.nodeList: - if node.parent is not None: - plt.plot(node.path_x, node.path_y, "-g") - # plt.plot([node.x, self.nodeList[node.parent].x], [ - # node.y, self.nodeList[node.parent].y], "-g") - - for (ox, oy, size) in self.obstacleList: - plt.plot(ox, oy, "ok", ms=30 * size) - - reeds_shepp_path_planning.plot_arrow( - self.start.x, self.start.y, self.start.yaw) - reeds_shepp_path_planning.plot_arrow( - self.end.x, self.end.y, self.end.yaw) - - plt.axis([-2, 15, -2, 15]) - plt.grid(True) - plt.pause(0.01) - - # plt.show() - # input() - - def GetNearestListIndex(self, nodeList, rnd): - dlist = [(node.x - rnd.x) ** 2 + - (node.y - rnd.y) ** 2 + - (node.yaw - rnd.yaw) ** 2 for node in nodeList] - minind = dlist.index(min(dlist)) - - return minind - - def CollisionCheck(self, node, obstacleList): - - for (ox, oy, size) in obstacleList: - for (ix, iy) in zip(node.path_x, node.path_y): - dx = ox - ix - dy = oy - iy - d = dx * dx + dy * dy - if d <= size ** 2: - return False # collision - - return True # safe - - -class Node(): - """ - RRT Node - """ - - def __init__(self, x, y, yaw): - self.x = x - self.y = y - self.yaw = yaw - self.path_x = [] - self.path_y = [] - self.path_yaw = [] - self.cost = 0.0 - self.parent = None - -def main(maxIter=200): +def main(): print("Start " + __file__) # ====Search Path with RRT==== @@ -303,14 +233,14 @@ def main(maxIter=200): start = [0.0, 0.0, np.deg2rad(0.0)] goal = [6.0, 7.0, np.deg2rad(90.0)] - rrt = RRT(start, goal, randArea=[-2.0, 15.0], - obstacleList=obstacleList, - maxIter=maxIter) - path = rrt.Planning(animation=show_animation) + rrt_star_reeds_shepp = RRTStarReedsShepp(start, goal, + obstacleList, + [-2.0, 15.0]) + path = rrt_star_reeds_shepp.planning(animation=show_animation) # Draw final path - if show_animation: # pragma: no cover - rrt.DrawGraph() + if path and show_animation: # pragma: no cover + rrt_star_reeds_shepp.draw_graph() plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') plt.grid(True) plt.pause(0.001) diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py index da1b4f3494..54b5adbe6d 100644 --- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py +++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py @@ -5,10 +5,10 @@ author Atsushi Sakai(@Atsushi_twi) """ -import numpy as np import math -import matplotlib.pyplot as plt +import matplotlib.pyplot as plt +import numpy as np show_animation = True @@ -353,7 +353,7 @@ def calc_paths(sx, sy, syaw, gx, gy, gyaw, maxc, step_size): def reeds_shepp_path_planning(sx, sy, syaw, - gx, gy, gyaw, maxc, step_size): + gx, gy, gyaw, maxc, step_size=0.2): paths = calc_paths(sx, sy, syaw, gx, gy, gyaw, maxc, step_size) diff --git a/tests/test_dubins_path_planning.py b/tests/test_dubins_path_planning.py index d2ddb8cac1..ad140b6c3a 100644 --- a/tests/test_dubins_path_planning.py +++ b/tests/test_dubins_path_planning.py @@ -1,7 +1,9 @@ from unittest import TestCase -from PathPlanning.DubinsPath import dubins_path_planning + import numpy as np +from PathPlanning.DubinsPath import dubins_path_planning + class Test(TestCase): @@ -19,8 +21,8 @@ def test1(self): px, py, pyaw, mode, clen = dubins_path_planning.dubins_path_planning( start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature) - assert(abs(px[-1] - end_x) <= 0.1) - assert(abs(py[-1] - end_y) <= 0.1) + assert (abs(px[-1] - end_x) <= 0.5) + assert (abs(py[-1] - end_y) <= 0.5) assert(abs(pyaw[-1] - end_yaw) <= 0.1) def test2(self): From 8061e733375a389bb49802ad7f9c172e88aa42c8 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 27 Jul 2019 16:32:40 +0900 Subject: [PATCH 018/940] fix LQR rrt star --- PathPlanning/LQRPlanner/LQRplanner.py | 11 +- PathPlanning/LQRRRTStar/lqr_rrt_star.py | 337 +++++++----------- .../RRTStarReedsShepp/rrt_star_reeds_shepp.py | 4 +- tests/test_rrt_star_reeds_shepp.py | 6 +- 4 files changed, 138 insertions(+), 220 deletions(-) diff --git a/PathPlanning/LQRPlanner/LQRplanner.py b/PathPlanning/LQRPlanner/LQRplanner.py index fef1020e5b..e726609298 100644 --- a/PathPlanning/LQRPlanner/LQRplanner.py +++ b/PathPlanning/LQRPlanner/LQRplanner.py @@ -6,19 +6,20 @@ """ +import math +import random + import matplotlib.pyplot as plt import numpy as np import scipy.linalg as la -import math -import random -show_animation = True +SHOW_ANIMATION = True MAX_TIME = 100.0 # Maximum simulation time DT = 0.1 # Time tick -def LQRplanning(sx, sy, gx, gy): +def LQRplanning(sx, sy, gx, gy, show_animation=SHOW_ANIMATION): rx, ry = [sx], [sy] @@ -129,7 +130,7 @@ def main(): rx, ry = LQRplanning(sx, sy, gx, gy) - if show_animation: # pragma: no cover + if SHOW_ANIMATION: # pragma: no cover plt.plot(sx, sy, "or") plt.plot(gx, gy, "ob") plt.plot(rx, ry, "-r") diff --git a/PathPlanning/LQRRRTStar/lqr_rrt_star.py b/PathPlanning/LQRRRTStar/lqr_rrt_star.py index 0fb25fe421..4c8d33aa26 100644 --- a/PathPlanning/LQRRRTStar/lqr_rrt_star.py +++ b/PathPlanning/LQRRRTStar/lqr_rrt_star.py @@ -5,283 +5,200 @@ author: AtsushiSakai(@Atsushi_twi) """ - -import matplotlib.pyplot as plt -import numpy as np import copy import math +import os import random import sys -import os + +import matplotlib.pyplot as plt +import numpy as np + sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../LQRPlanner/") +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../RRTStar/") try: import LQRplanner -except: + from rrt_star import RRTStar +except ImportError: raise - show_animation = True -LQRplanner.show_animation = False -STEP_SIZE = 0.05 # step size of local path -XYTH = 0.5 # [m] acceptance xy distance in final paths - - -class RRT(): +class LQRRRTStar(RRTStar): """ - Class for RRT Planning + Class for RRT star planning with LQR planning """ - def __init__(self, start, goal, obstacleList, randArea, - goalSampleRate=10, maxIter=200): + def __init__(self, start, goal, obstacle_list, rand_area, + goal_sample_rate=10, + max_iter=200, + connect_circle_dist=50.0, + step_size=0.2 + ): """ Setting Parameter start:Start Position [x,y] goal:Goal Position [x,y] obstacleList:obstacle Positions [[x,y,size],...] - randArea:Ramdom Samping Area [min,max] + randArea:Random Sampling Area [min,max] """ - self.start = Node(start[0], start[1]) - self.end = Node(goal[0], goal[1]) - self.minrand = randArea[0] - self.maxrand = randArea[1] - self.goalSampleRate = goalSampleRate - self.maxIter = maxIter - self.obstacleList = obstacleList - - def planning(self, animation=True): + self.start = self.Node(start[0], start[1]) + self.end = self.Node(goal[0], goal[1]) + self.min_rand = rand_area[0] + self.max_rand = rand_area[1] + self.goal_sample_rate = goal_sample_rate + self.max_iter = max_iter + self.obstacle_list = obstacle_list + self.connect_circle_dist = connect_circle_dist + + self.curvature = 1.0 + self.goal_xy_th = 0.5 + self.step_size = step_size + + def planning(self, animation=True, search_until_max_iter=True): """ - Pathplanning + RRT Star planning animation: flag for animation on or off """ - self.nodeList = [self.start] - for i in range(self.maxIter): - rnd = self.get_random_point() - nind = self.get_nearest_index(self.nodeList, rnd) - - newNode = self.steer(rnd, nind) - if newNode is None: - continue + self.node_list = [self.start] + for i in range(self.max_iter): + print("Iter:", i, ", number of nodes:", len(self.node_list)) + rnd = self.get_random_node() + nearest_ind = self.get_nearest_list_index(self.node_list, rnd) + new_node = self.steer(self.node_list[nearest_ind], rnd) - if self.check_collision(newNode, self.obstacleList): - nearinds = self.find_near_nodes(newNode) - newNode = self.choose_parent(newNode, nearinds) - if newNode is None: - continue - self.nodeList.append(newNode) - self.rewire(newNode, nearinds) + if self.check_collision(new_node, self.obstacle_list): + near_indexes = self.find_near_nodes(new_node) + new_node = self.choose_parent(new_node, near_indexes) + if new_node: + self.node_list.append(new_node) + self.rewire(new_node, near_indexes) if animation and i % 5 == 0: - self.draw_graph(rnd=rnd) + self.draw_graph(rnd) - # generate coruse - lastIndex = self.get_best_last_index() - if lastIndex is None: - return None - path = self.gen_final_course(lastIndex) - return path - - def choose_parent(self, newNode, nearinds): - if not nearinds: - return newNode - - dlist = [] - for i in nearinds: - tNode = self.steer(newNode, i) - if tNode is None: - continue - - if self.check_collision(tNode, self.obstacleList): - dlist.append(tNode.cost) - else: - dlist.append(float("inf")) - - mincost = min(dlist) - minind = nearinds[dlist.index(mincost)] + if (not search_until_max_iter) and new_node: # check reaching the goal + last_index = self.search_best_goal_node() + if last_index: + return self.generate_final_course(last_index) - if mincost == float("inf"): - print("mincost is inf") - return newNode + print("reached max iteration") - newNode = self.steer(newNode, minind) + last_index = self.search_best_goal_node() + if last_index: + return self.generate_final_course(last_index) + else: + print("Cannot find path") - return newNode - - def pi_2_pi(self, angle): - return (angle + math.pi) % (2 * math.pi) - math.pi - - def sample_path(self, wx, wy, step): + return None - px, py, clen = [], [], [] + def draw_graph(self, rnd=None): + plt.clf() + if rnd is not None: + plt.plot(rnd.x, rnd.y, "^k") + for node in self.node_list: + if node.parent: + plt.plot(node.path_x, node.path_y, "-g") - for i in range(len(wx) - 1): + for (ox, oy, size) in self.obstacle_list: + plt.plot(ox, oy, "ok", ms=30 * size) - for t in np.arange(0.0, 1.0, step): - px.append(t * wx[i + 1] + (1.0 - t) * wx[i]) - py.append(t * wy[i + 1] + (1.0 - t) * wy[i]) + plt.plot(self.start.x, self.start.y, "xr") + plt.plot(self.end.x, self.end.y, "xr") + plt.axis([-2, 15, -2, 15]) + plt.grid(True) + plt.pause(0.01) - dx = np.diff(px) - dy = np.diff(py) + def search_best_goal_node(self): + dist_to_goal_list = [self.calc_dist_to_goal(n.x, n.y) for n in self.node_list] + goal_inds = [dist_to_goal_list.index(i) for i in dist_to_goal_list if i <= self.goal_xy_th] - clen = [math.sqrt(idx**2 + idy**2) for (idx, idy) in zip(dx, dy)] + if not goal_inds: + return None - return px, py, clen + min_cost = min([self.node_list[i].cost for i in goal_inds]) + for i in goal_inds: + if self.node_list[i].cost == min_cost: + return i - def steer(self, rnd, nind): + return None - nearestNode = self.nodeList[nind] + def calc_new_cost(self, from_node, to_node): wx, wy = LQRplanner.LQRplanning( - nearestNode.x, nearestNode.y, rnd.x, rnd.y) - - px, py, clen = self.sample_path(wx, wy, STEP_SIZE) - - if px is None: - return None + from_node.x, from_node.y, to_node.x, to_node.y, show_animation=False) - newNode = copy.deepcopy(nearestNode) - newNode.x = px[-1] - newNode.y = py[-1] + px, py, course_lengths = self.sample_path(wx, wy, self.step_size) - newNode.path_x = px - newNode.path_y = py - newNode.cost += sum([abs(c) for c in clen]) - newNode.parent = nind + if not course_lengths: + return float("inf") - return newNode + return from_node.cost + sum(course_lengths) - def get_random_point(self): + def get_random_node(self): - if random.randint(0, 100) > self.goalSampleRate: - rnd = [random.uniform(self.minrand, self.maxrand), - random.uniform(self.minrand, self.maxrand), - random.uniform(-math.pi, math.pi) - ] + if random.randint(0, 100) > self.goal_sample_rate: + rnd = self.Node(random.uniform(self.min_rand, self.max_rand), + random.uniform(self.min_rand, self.max_rand) + ) else: # goal point sampling - rnd = [self.end.x, self.end.y] - - node = Node(rnd[0], rnd[1]) - - return node - - def get_best_last_index(self): - # print("get_best_last_index") + rnd = self.Node(self.end.x, self.end.y) - goalinds = [] - for (i, node) in enumerate(self.nodeList): - if self.calc_dist_to_goal(node.x, node.y) <= XYTH: - goalinds.append(i) - - if not goalinds: - return None - - mincost = min([self.nodeList[i].cost for i in goalinds]) - for i in goalinds: - if self.nodeList[i].cost == mincost: - return i - - return None + return rnd - def gen_final_course(self, goalind): + def generate_final_course(self, goal_index): + print("final") path = [[self.end.x, self.end.y]] - while self.nodeList[goalind].parent is not None: - node = self.nodeList[goalind] + node = self.node_list[goal_index] + while node.parent: for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)): path.append([ix, iy]) - goalind = node.parent + node = node.parent path.append([self.start.x, self.start.y]) return path - def calc_dist_to_goal(self, x, y): - return np.linalg.norm([x - self.end.x, y - self.end.y]) - - def find_near_nodes(self, newNode): - nnode = len(self.nodeList) - r = 50.0 * math.sqrt((math.log(nnode) / nnode)) - dlist = [(node.x - newNode.x) ** 2 - + (node.y - newNode.y) ** 2 - for node in self.nodeList] - nearinds = [dlist.index(i) for i in dlist if i <= r ** 2] - return nearinds - - def rewire(self, newNode, nearinds): - - nnode = len(self.nodeList) - - for i in nearinds: - nearNode = self.nodeList[i] - tNode = self.steer(nearNode, nnode - 1) - if tNode is None: - continue - - obstacleOK = self.check_collision(tNode, self.obstacleList) - imporveCost = nearNode.cost > tNode.cost - - if obstacleOK and imporveCost: - # print("rewire") - self.nodeList[i] = tNode - - def draw_graph(self, rnd=None): - plt.clf() - if rnd is not None: - plt.plot(rnd.x, rnd.y, "^k") - - for node in self.nodeList: - if node.parent is not None: - plt.plot(node.path_x, node.path_y, "-g") + def sample_path(self, wx, wy, step): - for (ox, oy, size) in self.obstacleList: - plt.plot(ox, oy, "ok", ms=30 * size) + px, py, clen = [], [], [] - plt.plot(self.start.x, self.start.y, "or") - plt.plot(self.end.x, self.end.y, "or") + for i in range(len(wx) - 1): - plt.axis([-2, 15, -2, 15]) - plt.grid(True) - plt.pause(0.01) + for t in np.arange(0.0, 1.0, step): + px.append(t * wx[i + 1] + (1.0 - t) * wx[i]) + py.append(t * wy[i + 1] + (1.0 - t) * wy[i]) - def get_nearest_index(self, nodeList, rnd): - dlist = [(node.x - rnd.x) ** 2 - + (node.y - rnd.y) ** 2 - for node in nodeList] - minind = dlist.index(min(dlist)) + dx = np.diff(px) + dy = np.diff(py) - return minind + clen = [math.sqrt(idx ** 2 + idy ** 2) for (idx, idy) in zip(dx, dy)] - def check_collision(self, node, obstacleList): + return px, py, clen - px = np.array(node.path_x) - py = np.array(node.path_y) + def steer(self, from_node, to_node): - for (ox, oy, size) in obstacleList: - dx = ox - px - dy = oy - py - d = dx ** 2 + dy ** 2 - dmin = min(d) - if dmin <= size ** 2: - return False # collision + wx, wy = LQRplanner.LQRplanning( + from_node.x, from_node.y, to_node.x, to_node.y, show_animation=False) - return True # safe + px, py, course_lens = self.sample_path(wx, wy, self.step_size) + if px is None: + return None -class Node(): - """ - RRT Node - """ + newNode = copy.deepcopy(from_node) + newNode.x = px[-1] + newNode.y = py[-1] + newNode.path_x = px + newNode.path_y = py + newNode.cost += sum([abs(c) for c in course_lens]) + newNode.parent = from_node - def __init__(self, x, y): - self.x = x - self.y = y - self.path_x = [] - self.path_y = [] - self.cost = 0.0 - self.parent = None + return newNode def main(maxIter=200): @@ -301,14 +218,14 @@ def main(maxIter=200): start = [0.0, 0.0] goal = [6.0, 7.0] - rrt = RRT(start, goal, randArea=[-2.0, 15.0], - obstacleList=obstacleList, - maxIter=maxIter) - path = rrt.planning(animation=show_animation) + lqr_rrt_star = LQRRRTStar(start, goal, + obstacleList, + [-2.0, 15.0]) + path = lqr_rrt_star.planning(animation=show_animation) # Draw final path if show_animation: # pragma: no cover - rrt.draw_graph() + lqr_rrt_star.draw_graph() plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') plt.grid(True) plt.pause(0.001) diff --git a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py index 9082117286..ea31337cbc 100644 --- a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py +++ b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py @@ -213,7 +213,7 @@ def generate_final_course(self, goal_index): return path -def main(): +def main(max_iter=200): print("Start " + __file__) # ====Search Path with RRT==== @@ -235,7 +235,7 @@ def main(): rrt_star_reeds_shepp = RRTStarReedsShepp(start, goal, obstacleList, - [-2.0, 15.0]) + [-2.0, 15.0], max_iter=max_iter) path = rrt_star_reeds_shepp.planning(animation=show_animation) # Draw final path diff --git a/tests/test_rrt_star_reeds_shepp.py b/tests/test_rrt_star_reeds_shepp.py index 4a1fa132fe..f7eeae3e6b 100644 --- a/tests/test_rrt_star_reeds_shepp.py +++ b/tests/test_rrt_star_reeds_shepp.py @@ -1,7 +1,7 @@ +import os +import sys from unittest import TestCase -import sys -import os sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../PathPlanning/RRTStarReedsShepp/") sys.path.append(os.path.dirname(os.path.abspath(__file__)) @@ -20,7 +20,7 @@ class Test(TestCase): def test1(self): m.show_animation = False - m.main(maxIter=5) + m.main(max_iter=5) if __name__ == '__main__': # pragma: no cover From 86b80d55c33d1c5b33880e67d71141393b78e681 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 28 Jul 2019 15:04:15 +0900 Subject: [PATCH 019/940] clean up lqr planner --- PathPlanning/LQRPlanner/LQRplanner.py | 141 ++++++++++++------------ PathPlanning/LQRRRTStar/lqr_rrt_star.py | 8 +- 2 files changed, 76 insertions(+), 73 deletions(-) diff --git a/PathPlanning/LQRPlanner/LQRplanner.py b/PathPlanning/LQRPlanner/LQRplanner.py index e726609298..e2000a957c 100644 --- a/PathPlanning/LQRPlanner/LQRplanner.py +++ b/PathPlanning/LQRPlanner/LQRplanner.py @@ -15,105 +15,104 @@ SHOW_ANIMATION = True -MAX_TIME = 100.0 # Maximum simulation time -DT = 0.1 # Time tick +class LQRPlanner: -def LQRplanning(sx, sy, gx, gy, show_animation=SHOW_ANIMATION): + def __init__(self): + self.MAX_TIME = 100.0 # Maximum simulation time + self.DT = 0.1 # Time tick + self.GOAL_DIST = 0.1 + self.MAX_ITER = 150 + self.EPS = 0.01 - rx, ry = [sx], [sy] + def lqr_planning(self, sx, sy, gx, gy, show_animation=SHOW_ANIMATION): - x = np.array([sx - gx, sy - gy]).reshape(2, 1) # State vector + rx, ry = [sx], [sy] - # Linear system model - A, B = get_system_model() + x = np.array([sx - gx, sy - gy]).reshape(2, 1) # State vector - found_path = False + # Linear system model + A, B = self.get_system_model() - time = 0.0 - while time <= MAX_TIME: - time += DT + found_path = False - u = LQR_control(A, B, x) + time = 0.0 + while time <= self.MAX_TIME: + time += self.DT - x = A @ x + B @ u + u = self.lqr_control(A, B, x) - rx.append(x[0, 0] + gx) - ry.append(x[1, 0] + gy) + x = A @ x + B @ u - d = math.sqrt((gx - rx[-1])**2 + (gy - ry[-1])**2) - if d <= 0.1: - # print("Goal!!") - found_path = True - break + rx.append(x[0, 0] + gx) + ry.append(x[1, 0] + gy) - # animation - if show_animation: # pragma: no cover - plt.plot(sx, sy, "or") - plt.plot(gx, gy, "ob") - plt.plot(rx, ry, "-r") - plt.axis("equal") - plt.pause(1.0) + d = math.sqrt((gx - rx[-1]) ** 2 + (gy - ry[-1]) ** 2) + if d <= self.GOAL_DIST: + found_path = True + break - if not found_path: - print("Cannot found path") - return [], [] + # animation + if show_animation: # pragma: no cover + plt.plot(sx, sy, "or") + plt.plot(gx, gy, "ob") + plt.plot(rx, ry, "-r") + plt.axis("equal") + plt.pause(1.0) - return rx, ry + if not found_path: + print("Cannot found path") + return [], [] + return rx, ry -def solve_DARE(A, B, Q, R): - """ - solve a discrete time_Algebraic Riccati equation (DARE) - """ - X = Q - maxiter = 150 - eps = 0.01 + def solve_dare(self, A, B, Q, R): + """ + solve a discrete time_Algebraic Riccati equation (DARE) + """ + X, Xn = Q, Q - for i in range(maxiter): - Xn = A.T * X * A - A.T * X * B * \ - la.inv(R + B.T * X * B) * B.T * X * A + Q - if (abs(Xn - X)).max() < eps: - break - X = Xn + for i in range(self.MAX_ITER): + Xn = A.T * X * A - A.T * X * B * \ + la.inv(R + B.T * X * B) * B.T * X * A + Q + if (abs(Xn - X)).max() < self.EPS: + break + X = Xn - return Xn + return Xn + def dlqr(self, A, B, Q, R): + """Solve the discrete time lqr controller. + x[k+1] = A x[k] + B u[k] + cost = sum x[k].T*Q*x[k] + u[k].T*R*u[k] + # ref Bertsekas, p.151 + """ -def dlqr(A, B, Q, R): - """Solve the discrete time lqr controller. - x[k+1] = A x[k] + B u[k] - cost = sum x[k].T*Q*x[k] + u[k].T*R*u[k] - # ref Bertsekas, p.151 - """ + # first, try to solve the ricatti equation + X = self.solve_dare(A, B, Q, R) - # first, try to solve the ricatti equation - X = solve_DARE(A, B, Q, R) + # compute the LQR gain + K = la.inv(B.T @ X @ B + R) @ (B.T @ X @ A) - # compute the LQR gain - K = la.inv(B.T @ X @ B + R) @ (B.T @ X @ A) + eigValues = la.eigvals(A - B @ K) - eigVals, eigVecs = la.eig(A - B @ K) + return K, X, eigValues - return K, X, eigVals + def get_system_model(self): + A = np.array([[self.DT, 1.0], + [0.0, self.DT]]) + B = np.array([0.0, 1.0]).reshape(2, 1) -def get_system_model(): + return A, B - A = np.array([[DT, 1.0], - [0.0, DT]]) - B = np.array([0.0, 1.0]).reshape(2, 1) + def lqr_control(self, A, B, x): - return A, B + Kopt, X, ev = self.dlqr(A, B, np.eye(2), np.eye(1)) + u = -Kopt @ x -def LQR_control(A, B, x): - - Kopt, X, ev = dlqr(A, B, np.eye(2), np.eye(1)) - - u = -Kopt @ x - - return u + return u def main(): @@ -122,13 +121,15 @@ def main(): ntest = 10 # number of goal area = 100.0 # sampling area + lqr_planner = LQRPlanner() + for i in range(ntest): sx = 6.0 sy = 6.0 gx = random.uniform(-area, area) gy = random.uniform(-area, area) - rx, ry = LQRplanning(sx, sy, gx, gy) + rx, ry = lqr_planner.lqr_planning(sx, sy, gx, gy) if SHOW_ANIMATION: # pragma: no cover plt.plot(sx, sy, "or") diff --git a/PathPlanning/LQRRRTStar/lqr_rrt_star.py b/PathPlanning/LQRRRTStar/lqr_rrt_star.py index 4c8d33aa26..c6cd760eda 100644 --- a/PathPlanning/LQRRRTStar/lqr_rrt_star.py +++ b/PathPlanning/LQRRRTStar/lqr_rrt_star.py @@ -18,7 +18,7 @@ sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../RRTStar/") try: - import LQRplanner + from LQRplanner import LQRPlanner from rrt_star import RRTStar except ImportError: raise @@ -59,6 +59,8 @@ def __init__(self, start, goal, obstacle_list, rand_area, self.goal_xy_th = 0.5 self.step_size = step_size + self.lqr_planner = LQRPlanner() + def planning(self, animation=True, search_until_max_iter=True): """ RRT Star planning @@ -131,7 +133,7 @@ def search_best_goal_node(self): def calc_new_cost(self, from_node, to_node): - wx, wy = LQRplanner.LQRplanning( + wx, wy = self.lqr_planner.lqr_planning( from_node.x, from_node.y, to_node.x, to_node.y, show_animation=False) px, py, course_lengths = self.sample_path(wx, wy, self.step_size) @@ -182,7 +184,7 @@ def sample_path(self, wx, wy, step): def steer(self, from_node, to_node): - wx, wy = LQRplanner.LQRplanning( + wx, wy = self.lqr_planner.lqr_planning( from_node.x, from_node.y, to_node.x, to_node.y, show_animation=False) px, py, course_lens = self.sample_path(wx, wy, self.step_size) From 5c15bc0357542ca8297fddba0dc9196c4eccdcae Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 28 Jul 2019 15:12:26 +0900 Subject: [PATCH 020/940] clean up quintic_polynomial_planner --- .../quintic_polynomials_planner.py | 25 +++++++++++-------- 1 file changed, 14 insertions(+), 11 deletions(-) diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py index e2411d2bcb..ecef7d454c 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py @@ -1,19 +1,20 @@ """ -Quinitc Polynomials Planner +Quintic Polynomials Planner author: Atsushi Sakai (@Atsushi_twi) Ref: -- [Local Path Planning And Motion Control For Agv In Positioning](http://ieeexplore.ieee.org/document/637936/) +- [Local Path planning And Motion Control For Agv In Positioning](http://ieeexplore.ieee.org/document/637936/) """ -import numpy as np -import matplotlib.pyplot as plt import math +import matplotlib.pyplot as plt +import numpy as np + # parameter MAX_T = 100.0 # maximum time to the goal [s] MIN_T = 5.0 # minimum time to the goal[s] @@ -21,7 +22,7 @@ show_animation = True -class quinic_polynomial: +class QuinticPolynomial: def __init__(self, xs, vxs, axs, xe, vxe, axe, T): @@ -72,9 +73,9 @@ def calc_third_derivative(self, t): return xt -def quinic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_accel, max_jerk, dt): +def quintic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_accel, max_jerk, dt): """ - quinic polynomial planner + quintic polynomial planner input sx: start x position [m] @@ -109,9 +110,11 @@ def quinic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_a axg = ga * math.cos(gyaw) ayg = ga * math.sin(gyaw) + time, rx, ry, ryaw, rv, ra, rj = [], [], [], [], [], [], [] + for T in np.arange(MIN_T, MAX_T, MIN_T): - xqp = quinic_polynomial(sx, vxs, axs, gx, vxg, axg, T) - yqp = quinic_polynomial(sy, vys, ays, gy, vyg, ayg, T) + xqp = QuinticPolynomial(sx, vxs, axs, gx, vxg, axg, T) + yqp = QuinticPolynomial(sy, vys, ays, gy, vyg, ayg, T) time, rx, ry, ryaw, rv, ra, rj = [], [], [], [], [], [], [] @@ -146,7 +149,7 @@ def quinic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_a break if show_animation: # pragma: no cover - for i, _ in enumerate(rx): + for i, _ in enumerate(time): plt.cla() plt.grid(True) plt.axis("equal") @@ -194,7 +197,7 @@ def main(): max_jerk = 0.5 # max jerk [m/sss] dt = 0.1 # time tick [s] - time, x, y, yaw, v, a, j = quinic_polynomials_planner( + time, x, y, yaw, v, a, j = quintic_polynomials_planner( sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_accel, max_jerk, dt) if show_animation: # pragma: no cover From 0747db006f0b69803fb1ded2a1a0881e3871a8ca Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 28 Jul 2019 15:16:00 +0900 Subject: [PATCH 021/940] clean up model_predictive_trajectory gene --- .../model_predictive_trajectory_generator.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/model_predictive_trajectory_generator.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/model_predictive_trajectory_generator.py index ad3bb11f2a..3ba1dd9fc2 100644 --- a/PathPlanning/ModelPredictiveTrajectoryGenerator/model_predictive_trajectory_generator.py +++ b/PathPlanning/ModelPredictiveTrajectoryGenerator/model_predictive_trajectory_generator.py @@ -6,9 +6,11 @@ """ -import numpy as np -import matplotlib.pyplot as plt import math + +import matplotlib.pyplot as plt +import numpy as np + import motion_model # optimization parameter @@ -37,7 +39,7 @@ def calc_diff(target, x, y, yaw): return d -def calc_J(target, p, h, k0): +def calc_j(target, p, h, k0): xp, yp, yawp = motion_model.generate_last_state( p[0, 0] + h[0], p[1, 0], p[2, 0], k0) dp = calc_diff(target, [xp], [yp], [yawp]) @@ -68,7 +70,6 @@ def calc_J(target, p, h, k0): def selection_learning_param(dp, p, k0, target): - mincost = float("inf") mina = 1.0 maxa = 2.0 @@ -110,7 +111,7 @@ def optimize_trajectory(target, k0, p): print("path is ok cost is:" + str(cost)) break - J = calc_J(target, p, h, k0) + J = calc_j(target, p, h, k0) try: dp = - np.linalg.inv(J) @ dc except np.linalg.linalg.LinAlgError: From 76977ac2564f1bae8d6dddae2c6fe454fddf232a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 28 Jul 2019 19:50:02 +0900 Subject: [PATCH 022/940] cleanup closed loop RRT star. --- .../closed_loop_rrt_star_car.py | 325 +++--------------- PathPlanning/LQRRRTStar/lqr_rrt_star.py | 2 +- PathPlanning/RRT/rrt.py | 4 +- PathPlanning/RRTDubins/rrt_dubins.py | 2 +- PathPlanning/RRTStar/rrt_star.py | 2 +- PathPlanning/RRTStarDubins/rrt_star_dubins.py | 2 +- .../RRTStarReedsShepp/rrt_star_reeds_shepp.py | 50 +-- 7 files changed, 87 insertions(+), 300 deletions(-) diff --git a/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py b/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py index 2aa0ba61de..a07dc48af0 100644 --- a/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py +++ b/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py @@ -1,14 +1,13 @@ """ + Path planning Sample Code with Closed loop RRT for car like robot. author: AtsushiSakai(@Atsushi_twi) """ -import copy import math import os -import random import sys import matplotlib.pyplot as plt @@ -18,92 +17,49 @@ sys.path.append(os.path.dirname( os.path.abspath(__file__)) + "/../ReedsSheppPath/") +sys.path.append(os.path.dirname( + os.path.abspath(__file__)) + "/../RRTStarReedsShepp/") try: import reeds_shepp_path_planning import unicycle_model -except: + from rrt_star_reeds_shepp import RRTStarReedsShepp +except ImportError: raise show_animation = True -target_speed = 10.0 / 3.6 -STEP_SIZE = 0.1 - - -class RRT(): +class ClosedLoopRRTStar(RRTStarReedsShepp): """ - Class for RRT planning + Class for Closed loop RRT star planning """ - def __init__(self, start, goal, obstacleList, randArea, - maxIter=50): + def __init__(self, start, goal, obstacle_list, rand_area, + max_iter=200, + connect_circle_dist=50.0 + ): + super().__init__(start, goal, obstacle_list, rand_area, + max_iter=max_iter, + connect_circle_dist=connect_circle_dist, + ) + + self.target_speed = 10.0 / 3.6 + self.yaw_th = np.deg2rad(3.0) + self.xy_th = 0.5 + self.invalid_travel_ratio = 5.0 + + def planning(self, animation=True): """ - Setting Parameter - - start:Start Position [x,y] - goal:Goal Position [x,y] - obstacleList:obstacle Positions [[x,y,size],...] - randArea:Ramdom Samping Area [min,max] - - """ - self.start = Node(start[0], start[1], start[2]) - self.end = Node(goal[0], goal[1], goal[2]) - self.minrand = randArea[0] - self.maxrand = randArea[1] - self.obstacleList = obstacleList - self.maxIter = maxIter - - def try_goal_path(self): - - goal = Node(self.end.x, self.end.y, self.end.yaw) - - newNode = self.steer(goal, len(self.nodeList) - 1) - if newNode is None: - return - - if self.CollisionCheck(newNode, self.obstacleList): - # print("goal path is OK") - self.nodeList.append(newNode) - - def Planning(self, animation=True): - """ - Pathplanning + do planning animation: flag for animation on or off """ - - self.nodeList = [self.start] - - self.try_goal_path() - - for i in range(self.maxIter): - print("loop:", i) - rnd = self.get_random_point() - nind = self.GetNearestListIndex(self.nodeList, rnd) - - newNode = self.steer(rnd, nind) - # print(newNode.cost) - if newNode is None: - continue - - if self.CollisionCheck(newNode, self.obstacleList): - nearinds = self.find_near_nodes(newNode) - newNode = self.choose_parent(newNode, nearinds) - if newNode is None: - continue - - self.nodeList.append(newNode) - self.rewire(newNode, nearinds) - - self.try_goal_path() - - if animation and i % 5 == 0: - self.DrawGraph(rnd=rnd) + # planning with RRTStarReedsShepp + super().planning(animation=animation) # generate coruse - path_indexs = self.get_best_last_indexs() + path_indexs = self.get_goal_indexes() flag, x, y, yaw, v, t, a, d = self.search_best_feasible_path( path_indexs) @@ -120,10 +76,9 @@ def search_best_feasible_path(self, path_indexs): # pure pursuit tracking for ind in path_indexs: - path = self.gen_final_course(ind) + path = self.generate_final_course(ind) - flag, x, y, yaw, v, t, a, d = self.check_tracking_path_is_feasible( - path) + flag, x, y, yaw, v, t, a, d = self.check_tracking_path_is_feasible(path) if flag and best_time >= t[-1]: print("feasible path is found") @@ -142,121 +97,46 @@ def search_best_feasible_path(self, path_indexs): return False, None, None, None, None, None, None, None def check_tracking_path_is_feasible(self, path): - # print("check_tracking_path_is_feasible") - cx = np.array(path[:, 0]) - cy = np.array(path[:, 1]) - cyaw = np.array(path[:, 2]) + cx = np.array([state[0] for state in path])[::-1] + cy = np.array([state[1] for state in path])[::-1] + cyaw = np.array([state[2] for state in path])[::-1] goal = [cx[-1], cy[-1], cyaw[-1]] cx, cy, cyaw = pure_pursuit.extend_path(cx, cy, cyaw) speed_profile = pure_pursuit.calc_speed_profile( - cx, cy, cyaw, target_speed) + cx, cy, cyaw, self.target_speed) t, x, y, yaw, v, a, d, find_goal = pure_pursuit.closed_loop_prediction( cx, cy, cyaw, speed_profile, goal) - yaw = [self.pi_2_pi(iyaw) for iyaw in yaw] + yaw = [reeds_shepp_path_planning.pi_2_pi(iyaw) for iyaw in yaw] if not find_goal: print("cannot reach goal") - if abs(yaw[-1] - goal[2]) >= math.pi / 4.0: + if abs(yaw[-1] - goal[2]) >= self.yaw_th * 10.0: print("final angle is bad") find_goal = False travel = sum([abs(iv) * unicycle_model.dt for iv in v]) - # print(travel) origin_travel = sum([math.sqrt(dx ** 2 + dy ** 2) for (dx, dy) in zip(np.diff(cx), np.diff(cy))]) - # print(origin_travel) - if (travel / origin_travel) >= 5.0: + if (travel / origin_travel) >= self.invalid_travel_ratio: print("path is too long") find_goal = False - if not self.CollisionCheckWithXY(x, y, self.obstacleList): + if not self.collision_check_with_xy(x, y, self.obstacle_list): print("This path is collision") find_goal = False return find_goal, x, y, yaw, v, t, a, d - def choose_parent(self, newNode, nearinds): - if not nearinds: - return newNode - - dlist = [] - for i in nearinds: - tNode = self.steer(newNode, i) - if tNode is None: - continue - - if self.CollisionCheck(tNode, self.obstacleList): - dlist.append(tNode.cost) - else: - dlist.append(float("inf")) - - mincost = min(dlist) - minind = nearinds[dlist.index(mincost)] - - if mincost == float("inf"): - print("mincost is inf") - return newNode - - newNode = self.steer(newNode, minind) - if newNode is None: - return None - - return newNode - - def pi_2_pi(self, angle): - return (angle + math.pi) % (2 * math.pi) - math.pi - - def steer(self, rnd, nind): - # print(rnd) - - nearestNode = self.nodeList[nind] - - px, py, pyaw, mode, clen = reeds_shepp_path_planning.reeds_shepp_path_planning( - nearestNode.x, nearestNode.y, nearestNode.yaw, - rnd.x, rnd.y, rnd.yaw, unicycle_model.curvature_max, STEP_SIZE) - - if px is None: - return None - - newNode = copy.deepcopy(nearestNode) - newNode.x = px[-1] - newNode.y = py[-1] - newNode.yaw = pyaw[-1] - - newNode.path_x = px - newNode.path_y = py - newNode.path_yaw = pyaw - newNode.cost += sum([abs(c) for c in clen]) - newNode.parent = nind - - return newNode - - def get_random_point(self): - - rnd = [random.uniform(self.minrand, self.maxrand), - random.uniform(self.minrand, self.maxrand), - random.uniform(-math.pi, math.pi) - ] - - node = Node(rnd[0], rnd[1], rnd[2]) - - return node - - def get_best_last_indexs(self): - # print("search_finish_node") - - YAWTH = np.deg2rad(1.0) - XYTH = 0.5 - + def get_goal_indexes(self): goalinds = [] - for (i, node) in enumerate(self.nodeList): - if self.calc_dist_to_goal(node.x, node.y) <= XYTH: + for (i, node) in enumerate(self.node_list): + if self.calc_dist_to_goal(node.x, node.y) <= self.xy_th: goalinds.append(i) print("OK XY TH num is") print(len(goalinds)) @@ -264,106 +144,17 @@ def get_best_last_indexs(self): # angle check fgoalinds = [] for i in goalinds: - if abs(self.nodeList[i].yaw - self.end.yaw) <= YAWTH: + if abs(self.node_list[i].yaw - self.end.yaw) <= self.yaw_th: fgoalinds.append(i) print("OK YAW TH num is") print(len(fgoalinds)) return fgoalinds - def gen_final_course(self, goalind): - path = [[self.end.x, self.end.y, self.end.yaw]] - while self.nodeList[goalind].parent is not None: - node = self.nodeList[goalind] - path_x = reversed(node.path_x) - path_y = reversed(node.path_y) - path_yaw = reversed(node.path_yaw) - for (ix, iy, iyaw) in zip(path_x, path_y, path_yaw): - path.append([ix, iy, iyaw]) - # path.append([node.x, node.y]) - goalind = node.parent - path.append([self.start.x, self.start.y, self.start.yaw]) - - path = np.array(path[::-1]) - return path - - def calc_dist_to_goal(self, x, y): - return np.linalg.norm([x - self.end.x, y - self.end.y]) - - def find_near_nodes(self, newNode): - nnode = len(self.nodeList) - r = 50.0 * math.sqrt((math.log(nnode) / nnode)) - # r = self.expandDis * 5.0 - dlist = [(node.x - newNode.x) ** 2 - + (node.y - newNode.y) ** 2 - + (node.yaw - newNode.yaw) ** 2 - for node in self.nodeList] - nearinds = [dlist.index(i) for i in dlist if i <= r ** 2] - return nearinds - - def rewire(self, newNode, nearinds): - - nnode = len(self.nodeList) - - for i in nearinds: - nearNode = self.nodeList[i] - tNode = self.steer(nearNode, nnode - 1) - - if tNode is None: - continue - - obstacleOK = self.CollisionCheck(tNode, self.obstacleList) - imporveCost = nearNode.cost > tNode.cost - - if obstacleOK and imporveCost: - # print("rewire") - self.nodeList[i] = tNode - - def DrawGraph(self, rnd=None): # pragma: no cover - """ - Draw Graph - """ - if rnd is not None: - plt.plot(rnd.x, rnd.y, "^k") - for node in self.nodeList: - if node.parent is not None: - plt.plot(node.path_x, node.path_y, "-g") - - for (ox, oy, size) in self.obstacleList: - plt.plot(ox, oy, "ok", ms=30 * size) - - reeds_shepp_path_planning.plot_arrow( - self.start.x, self.start.y, self.start.yaw) - reeds_shepp_path_planning.plot_arrow( - self.end.x, self.end.y, self.end.yaw) - - plt.axis([-2, 15, -2, 15]) - plt.grid(True) - plt.pause(0.01) - - def GetNearestListIndex(self, nodeList, rnd): - dlist = [(node.x - rnd.x) ** 2 - + (node.y - rnd.y) ** 2 - + (node.yaw - rnd.yaw) ** 2 for node in nodeList] - minind = dlist.index(min(dlist)) + @staticmethod + def collision_check_with_xy(x, y, obstacle_list): - return minind - - def CollisionCheck(self, node, obstacleList): - - for (ox, oy, size) in obstacleList: - for (ix, iy) in zip(node.path_x, node.path_y): - dx = ox - ix - dy = oy - iy - d = dx * dx + dy * dy - if d <= size ** 2: - return False # collision - - return True # safe - - def CollisionCheckWithXY(self, x, y, obstacleList): - - for (ox, oy, size) in obstacleList: + for (ox, oy, size) in obstacle_list: for (ix, iy) in zip(x, y): dx = ox - ix dy = oy - iy @@ -374,26 +165,10 @@ def CollisionCheckWithXY(self, x, y, obstacleList): return True # safe -class Node(): - """ - RRT Node - """ - - def __init__(self, x, y, yaw): - self.x = x - self.y = y - self.yaw = yaw - self.path_x = [] - self.path_y = [] - self.path_yaw = [] - self.cost = 0.0 - self.parent = None - - -def main(gx=6.0, gy=7.0, gyaw=np.deg2rad(90.0), maxIter=200): +def main(gx=6.0, gy=7.0, gyaw=np.deg2rad(90.0), max_iter=100): print("Start" + __file__) # ====Search Path with RRT==== - obstacleList = [ + obstacle_list = [ (5, 5, 1), (4, 6, 1), (4, 8, 1), @@ -409,16 +184,18 @@ def main(gx=6.0, gy=7.0, gyaw=np.deg2rad(90.0), maxIter=200): start = [0.0, 0.0, np.deg2rad(0.0)] goal = [gx, gy, gyaw] - rrt = RRT(start, goal, randArea=[-2.0, 20.0], - obstacleList=obstacleList, maxIter=maxIter) - flag, x, y, yaw, v, t, a, d = rrt.Planning(animation=show_animation) + closed_loop_rrt_star = ClosedLoopRRTStar(start, goal, + obstacle_list, + [-2.0, 20.0], + max_iter=max_iter) + flag, x, y, yaw, v, t, a, d = closed_loop_rrt_star.planning(animation=show_animation) if not flag: print("cannot find feasible path") # Draw final path if show_animation: - rrt.DrawGraph() + closed_loop_rrt_star.draw_graph() plt.plot(x, y, '-r') plt.grid(True) plt.pause(0.001) diff --git a/PathPlanning/LQRRRTStar/lqr_rrt_star.py b/PathPlanning/LQRRRTStar/lqr_rrt_star.py index c6cd760eda..2e276b9f9b 100644 --- a/PathPlanning/LQRRRTStar/lqr_rrt_star.py +++ b/PathPlanning/LQRRRTStar/lqr_rrt_star.py @@ -72,7 +72,7 @@ def planning(self, animation=True, search_until_max_iter=True): for i in range(self.max_iter): print("Iter:", i, ", number of nodes:", len(self.node_list)) rnd = self.get_random_node() - nearest_ind = self.get_nearest_list_index(self.node_list, rnd) + nearest_ind = self.get_nearest_node_index(self.node_list, rnd) new_node = self.steer(self.node_list[nearest_ind], rnd) if self.check_collision(new_node, self.obstacle_list): diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 541c2a9636..887cb1545f 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -63,7 +63,7 @@ def planning(self, animation=True): self.node_list = [self.start] for i in range(self.max_iter): rnd_node = self.get_random_node() - nearest_ind = self.get_nearest_list_index(self.node_list, rnd_node) + nearest_ind = self.get_nearest_node_index(self.node_list, rnd_node) nearest_node = self.node_list[nearest_ind] new_node = self.steer(nearest_node, rnd_node, self.expand_dis) @@ -154,7 +154,7 @@ def draw_graph(self, rnd=None): plt.pause(0.01) @staticmethod - def get_nearest_list_index(node_list, rnd_node): + def get_nearest_node_index(node_list, rnd_node): dlist = [(node.x - rnd_node.x) ** 2 + (node.y - rnd_node.y) ** 2 for node in node_list] minind = dlist.index(min(dlist)) diff --git a/PathPlanning/RRTDubins/rrt_dubins.py b/PathPlanning/RRTDubins/rrt_dubins.py index 78ce9611b3..ed2b27ca0b 100644 --- a/PathPlanning/RRTDubins/rrt_dubins.py +++ b/PathPlanning/RRTDubins/rrt_dubins.py @@ -80,7 +80,7 @@ def planning(self, animation=True, search_until_max_iter=True): for i in range(self.max_iter): print("Iter:", i, ", number of nodes:", len(self.node_list)) rnd = self.get_random_node() - nearest_ind = self.get_nearest_list_index(self.node_list, rnd) + nearest_ind = self.get_nearest_node_index(self.node_list, rnd) new_node = self.steer(self.node_list[nearest_ind], rnd) if self.check_collision(new_node, self.obstacle_list): diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index c92f435080..eb37964d5c 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -65,7 +65,7 @@ def planning(self, animation=True, search_until_max_iter=True): for i in range(self.max_iter): print("Iter:", i, ", number of nodes:", len(self.node_list)) rnd = self.get_random_node() - nearest_ind = self.get_nearest_list_index(self.node_list, rnd) + nearest_ind = self.get_nearest_node_index(self.node_list, rnd) new_node = self.steer(self.node_list[nearest_ind], rnd, self.expand_dis) if self.check_collision(new_node, self.obstacle_list): diff --git a/PathPlanning/RRTStarDubins/rrt_star_dubins.py b/PathPlanning/RRTStarDubins/rrt_star_dubins.py index b98c7dca1c..4d7312933d 100644 --- a/PathPlanning/RRTStarDubins/rrt_star_dubins.py +++ b/PathPlanning/RRTStarDubins/rrt_star_dubins.py @@ -81,7 +81,7 @@ def planning(self, animation=True, search_until_max_iter=True): for i in range(self.max_iter): print("Iter:", i, ", number of nodes:", len(self.node_list)) rnd = self.get_random_node() - nearest_ind = self.get_nearest_list_index(self.node_list, rnd) + nearest_ind = self.get_nearest_node_index(self.node_list, rnd) new_node = self.steer(self.node_list[nearest_ind], rnd) if self.check_collision(new_node, self.obstacle_list): diff --git a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py index ea31337cbc..5d78f98f31 100644 --- a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py +++ b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py @@ -44,7 +44,6 @@ def __init__(self, x, y, yaw): self.path_yaw = [] def __init__(self, start, goal, obstacle_list, rand_area, - goal_sample_rate=10, max_iter=200, connect_circle_dist=50.0 ): @@ -61,7 +60,6 @@ def __init__(self, start, goal, obstacle_list, rand_area, self.end = self.Node(goal[0], goal[1], goal[2]) self.min_rand = rand_area[0] self.max_rand = rand_area[1] - self.goal_sample_rate = goal_sample_rate self.max_iter = max_iter self.obstacle_list = obstacle_list self.connect_circle_dist = connect_circle_dist @@ -72,7 +70,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, def planning(self, animation=True, search_until_max_iter=True): """ - RRT Star planning + planning animation: flag for animation on or off """ @@ -81,7 +79,7 @@ def planning(self, animation=True, search_until_max_iter=True): for i in range(self.max_iter): print("Iter:", i, ", number of nodes:", len(self.node_list)) rnd = self.get_random_node() - nearest_ind = self.get_nearest_list_index(self.node_list, rnd) + nearest_ind = self.get_nearest_node_index(self.node_list, rnd) new_node = self.steer(self.node_list[nearest_ind], rnd) if self.check_collision(new_node, self.obstacle_list): @@ -90,6 +88,7 @@ def planning(self, animation=True, search_until_max_iter=True): if new_node: self.node_list.append(new_node) self.rewire(new_node, near_indexes) + self.try_goal_path(new_node) if animation and i % 5 == 0: self.plot_start_goal_arrow() @@ -110,6 +109,17 @@ def planning(self, animation=True, search_until_max_iter=True): return None + def try_goal_path(self, node): + + goal = self.Node(self.end.x, self.end.y, self.end.yaw) + + new_node = self.steer(node, goal) + if new_node is None: + return + + if self.check_collision(new_node, self.obstacle_list): + self.node_list.append(new_node) + def draw_graph(self, rnd=None): plt.clf() if rnd is not None: @@ -151,7 +161,7 @@ def steer(self, from_node, to_node): new_node.path_x = px new_node.path_y = py new_node.path_yaw = pyaw - new_node.cost += sum(course_lengths) + new_node.cost += sum([abs(l) for l in course_lengths]) new_node.parent = from_node return new_node @@ -164,17 +174,14 @@ def calc_new_cost(self, from_node, to_node): if not course_lengths: return float("inf") - return from_node.cost + sum(course_lengths) + return from_node.cost + sum([abs(l) for l in course_lengths]) def get_random_node(self): - if random.randint(0, 100) > self.goal_sample_rate: - rnd = self.Node(random.uniform(self.min_rand, self.max_rand), - random.uniform(self.min_rand, self.max_rand), - random.uniform(-math.pi, math.pi) - ) - else: # goal point sampling - rnd = self.Node(self.end.x, self.end.y, self.end.yaw) + rnd = self.Node(random.uniform(self.min_rand, self.max_rand), + random.uniform(self.min_rand, self.max_rand), + random.uniform(-math.pi, math.pi) + ) return rnd @@ -184,6 +191,7 @@ def search_best_goal_node(self): for (i, node) in enumerate(self.node_list): if self.calc_dist_to_goal(node.x, node.y) <= self.goal_xy_th: goal_indexes.append(i) + print("goal_indexes:", len(goal_indexes)) # angle check final_goal_indexes = [] @@ -191,10 +199,13 @@ def search_best_goal_node(self): if abs(self.node_list[i].yaw - self.end.yaw) <= self.goal_yaw_th: final_goal_indexes.append(i) + print("final_goal_indexes:", len(final_goal_indexes)) + if not final_goal_indexes: return None min_cost = min([self.node_list[i].cost for i in final_goal_indexes]) + print("min_cost:", min_cost) for i in final_goal_indexes: if self.node_list[i].cost == min_cost: return i @@ -202,18 +213,17 @@ def search_best_goal_node(self): return None def generate_final_course(self, goal_index): - print("final") - path = [[self.end.x, self.end.y]] + path = [[self.end.x, self.end.y, self.end.yaw]] node = self.node_list[goal_index] while node.parent: - for (ix, iy) in zip(reversed(node.path_x), reversed(node.path_y)): - path.append([ix, iy]) + for (ix, iy, iyaw) in zip(reversed(node.path_x), reversed(node.path_y), reversed(node.path_yaw)): + path.append([ix, iy, iyaw]) node = node.parent - path.append([self.start.x, self.start.y]) + path.append([self.start.x, self.start.y, self.start.yaw]) return path -def main(max_iter=200): +def main(max_iter=100): print("Start " + __file__) # ====Search Path with RRT==== @@ -241,7 +251,7 @@ def main(max_iter=200): # Draw final path if path and show_animation: # pragma: no cover rrt_star_reeds_shepp.draw_graph() - plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') + plt.plot([x for (x, y, yaw) in path], [y for (x, y, yaw) in path], '-r') plt.grid(True) plt.pause(0.001) plt.show() From 3e017c9170ded3625df5d57ff4a062a658130045 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 28 Jul 2019 20:04:12 +0900 Subject: [PATCH 023/940] fix closed RRT star test --- tests/test_closed_loop_rrt_star_car.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/tests/test_closed_loop_rrt_star_car.py b/tests/test_closed_loop_rrt_star_car.py index f82d3f2561..18513ce665 100644 --- a/tests/test_closed_loop_rrt_star_car.py +++ b/tests/test_closed_loop_rrt_star_car.py @@ -1,6 +1,7 @@ -from unittest import TestCase -import sys import os +import sys +from unittest import TestCase + sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../") sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../PathPlanning/ClosedLoopRRTStar/") @@ -17,7 +18,7 @@ class Test(TestCase): def test1(self): m.show_animation = False - m.main(gx=1.0, gy=0.0, gyaw=0.0, maxIter=5) + m.main(gx=1.0, gy=0.0, gyaw=0.0, max_iter=5) if __name__ == '__main__': # pragma: no cover From 9a9ea3b3d7cc2f5e4cb10b384610964044f17583 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 28 Jul 2019 20:57:35 +0900 Subject: [PATCH 024/940] Update users_comments.md --- users_comments.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/users_comments.md b/users_comments.md index 087acd3a7c..61ffd07d3c 100644 --- a/users_comments.md +++ b/users_comments.md @@ -299,6 +299,12 @@ You made such a nice work. Congratulations :) --- +thank you for python path finding repo + +--fengzongbao + +--- + # Citations 1. B. Blaga, M. Deac, R. W. Y. Al-doori, M. Negru and R. Dǎnescu, "Miniature Autonomous Vehicle Development on Raspberry Pi," 2018 IEEE 14th International Conference on Intelligent Computer Communication and Processing (ICCP), Cluj-Napoca, Romania, 2018, pp. 229-236. From 2b907725b89f50df02e72dea26899fd4a00bda20 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 29 Jul 2019 20:17:55 +0900 Subject: [PATCH 025/940] Update users_comments.md --- users_comments.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/users_comments.md b/users_comments.md index 61ffd07d3c..a68cbddbc1 100644 --- a/users_comments.md +++ b/users_comments.md @@ -305,6 +305,12 @@ thank you for python path finding repo --- +Dear AtsushiSakai,

Thank you so much for making the concept of robotics approachable for the general mass. Keep up the good work :) + +--Harsh Munshi + +--- + # Citations 1. B. Blaga, M. Deac, R. W. Y. Al-doori, M. Negru and R. Dǎnescu, "Miniature Autonomous Vehicle Development on Raspberry Pi," 2018 IEEE 14th International Conference on Intelligent Computer Communication and Processing (ICCP), Cluj-Napoca, Romania, 2018, pp. 229-236. From 2d9dcc1d99204700d774026dc5a472a119a71d0b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 29 Jul 2019 20:54:59 +0900 Subject: [PATCH 026/940] Update users_comments.md --- users_comments.md | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/users_comments.md b/users_comments.md index a68cbddbc1..72ac0e9c87 100644 --- a/users_comments.md +++ b/users_comments.md @@ -1,3 +1,19 @@ +# User's demos + +## WHILL MODEL CR with move to a pose control + +This is an electric wheelchair control demo by [Katsushun89](https://github.com/Katsushun89). + +[WHILL Model CR](https://whill.jp/model-cr) is the control target, [M5Stack](https://m5stack.com/) is used for the controller, and [toio](https://toio.io/) is used for the control input device. + +[move-to-a-pose-control](https://pythonrobotics.readthedocs.io/en/latest/modules/path_tracking.html#move-to-a-pose-control) is used for its control algorithm ([code link](https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/move_to_pose/move_to_pose.py)). + +![1](https://github.com/AtsushiSakai/PythonRoboticsGifs/blob/master/Users/WHILL_Model_CR_with_move_to_a_pose/WHLL_Model_CR_with_move_to_a_pose.gif) + +Ref: + +- [toioと同じように動くWHILL Model CR (in Japanese)](https://qiita.com/KatsuShun89/items/68fde7544ecfe36096d2) + # Educational users From 763d1e3efdd72d9a0f1fb91a80af2e37655c182b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 31 Jul 2019 17:41:59 +0900 Subject: [PATCH 027/940] Update users_comments.md --- users_comments.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/users_comments.md b/users_comments.md index 72ac0e9c87..49d4a3f7a3 100644 --- a/users_comments.md +++ b/users_comments.md @@ -327,6 +327,12 @@ Dear AtsushiSakai,

Thank you so much for making the concept of robotics --- +Benefit a lot for your GitHub repository of PythonRobotics. Thanks so much. + +--Haoran + +--- + # Citations 1. B. Blaga, M. Deac, R. W. Y. Al-doori, M. Negru and R. Dǎnescu, "Miniature Autonomous Vehicle Development on Raspberry Pi," 2018 IEEE 14th International Conference on Intelligent Computer Communication and Processing (ICCP), Cluj-Napoca, Romania, 2018, pp. 229-236. From 43c748a205ef7147102569d2971d1fa50ae10a56 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 1 Aug 2019 20:18:11 +0900 Subject: [PATCH 028/940] Update users_comments.md --- users_comments.md | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/users_comments.md b/users_comments.md index 49d4a3f7a3..1b6f192594 100644 --- a/users_comments.md +++ b/users_comments.md @@ -333,6 +333,19 @@ Benefit a lot for your GitHub repository of PythonRobotics. Thanks so much. --- +Thanks! + +--Reinzor + +--- + +Thanks for writing these algorithms. They are very helpful for learning robotics. + +--Arihant Lunawat + +--- + + # Citations 1. B. Blaga, M. Deac, R. W. Y. Al-doori, M. Negru and R. Dǎnescu, "Miniature Autonomous Vehicle Development on Raspberry Pi," 2018 IEEE 14th International Conference on Intelligent Computer Communication and Processing (ICCP), Cluj-Napoca, Romania, 2018, pp. 229-236. From c9a2beab73d75ac9687765e73a8666f51ccf3429 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 2 Aug 2019 09:29:43 +0900 Subject: [PATCH 029/940] Update users_comments.md --- users_comments.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/users_comments.md b/users_comments.md index 1b6f192594..294f3b3b13 100644 --- a/users_comments.md +++ b/users_comments.md @@ -360,6 +360,8 @@ URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8516589&isnumber=85 4. E. Horváth, C. Hajdu, C. Radu and Á. Ballagi, "Range Sensor-based Occupancy Grid Mapping with Signatures," 2019 20th International Carpathian Control Conference (ICCC), Krakow-Wieliczka, Poland, 2019, pp. 1-5. URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8765684&isnumber=8765679 +5. Josie Hughes, Masaru Shimizu, and Arnoud Visser, "A Review of Robot Rescue Simulation Platforms for Robotics Education" +URL: https://2019.robocup.org/downloads/program/HughesEtAl2019.pdf # Others From 38373ac7de43573dad62cb4fbb3d206e62dc3b15 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 3 Aug 2019 13:45:20 +0900 Subject: [PATCH 030/940] fix batch_informed_rrtstar.py --- .../batch_informed_rrtstar.py | 250 +++++++++--------- 1 file changed, 127 insertions(+), 123 deletions(-) diff --git a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py index 366ec5acc2..37ac75ada9 100644 --- a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py +++ b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py @@ -14,10 +14,11 @@ Reference: https://arxiv.org/abs/1405.5848 """ -import random -import numpy as np import math +import random + import matplotlib.pyplot as plt +import numpy as np show_animation = True @@ -26,8 +27,14 @@ class RTree(object): # Class to represent the explicit tree created # while sampling through the state space - def __init__(self, start=[0, 0], lowerLimit=[0, 0], upperLimit=[10, 10], resolution=1): + def __init__(self, start=None, lowerLimit=None, upperLimit=None, resolution=1.0): + if upperLimit is None: + upperLimit = [10, 10] + if lowerLimit is None: + lowerLimit = [0, 0] + if start is None: + start = [0, 0] self.vertices = dict() self.edges = [] self.start = start @@ -42,20 +49,21 @@ def __init__(self, start=[0, 0], lowerLimit=[0, 0], upperLimit=[10, 10], resolut self.num_cells[idx] = np.ceil( (upperLimit[idx] - lowerLimit[idx]) / resolution) - vertex_id = self.realWorldToNodeId(start) + vertex_id = self.real_world_to_node_id(start) self.vertices[vertex_id] = [] - def getRootId(self): + @staticmethod + def get_root_id(): # return the id of the root of the tree return 0 - def addVertex(self, vertex): + def add_vertex(self, vertex): # add a vertex to the tree - vertex_id = self.realWorldToNodeId(vertex) + vertex_id = self.real_world_to_node_id(vertex) self.vertices[vertex_id] = [] return vertex_id - def addEdge(self, v, x): + def add_edge(self, v, x): # create an edge between v and x vertices if (v, x) not in self.edges: self.edges.append((v, x)) @@ -63,7 +71,7 @@ def addEdge(self, v, x): self.vertices[v].append(x) self.vertices[x].append(v) - def realCoordsToGridCoord(self, real_coord): + def real_coords_to_grid_coord(self, real_coord): # convert real world coordinates to grid space # depends on the resolution of the grid # the output is the same as real world coords if the resolution @@ -71,10 +79,10 @@ def realCoordsToGridCoord(self, real_coord): coord = [0] * self.dimension for i in range(len(coord)): start = self.lowerLimit[i] # start of the grid space - coord[i] = np.around((real_coord[i] - start) / self.resolution) + coord[i] = int(np.around((real_coord[i] - start) / self.resolution)) return coord - def gridCoordinateToNodeId(self, coord): + def grid_coordinate_to_node_id(self, coord): # This function maps a grid coordinate to a unique # node id nodeId = 0 @@ -85,12 +93,12 @@ def gridCoordinateToNodeId(self, coord): nodeId = nodeId + coord[i] * product return nodeId - def realWorldToNodeId(self, real_coord): + def real_world_to_node_id(self, real_coord): # first convert the given coordinates to grid space and then # convert the grid space coordinates to a unique node id - return self.gridCoordinateToNodeId(self.realCoordsToGridCoord(real_coord)) + return self.grid_coordinate_to_node_id(self.real_coords_to_grid_coord(real_coord)) - def gridCoordToRealWorldCoord(self, coord): + def grid_coord_to_real_world_coord(self, coord): # This function smaps a grid coordinate in discrete space # to a configuration in the full configuration space config = [0] * self.dimension @@ -102,7 +110,7 @@ def gridCoordToRealWorldCoord(self, coord): config[i] = start + grid_step return config - def nodeIdToGridCoord(self, node_id): + def node_id_to_grid_coord(self, node_id): # This function maps a node id to the associated # grid coordinate coord = [0] * len(self.lowerLimit) @@ -115,12 +123,10 @@ def nodeIdToGridCoord(self, node_id): node_id = node_id - (coord[i] * prod) return coord - def nodeIdToRealWorldCoord(self, nid): - # This function maps a node in discrete space to a configuraiton + def node_id_to_real_world_coord(self, nid): + # This function maps a node in discrete space to a configuration # in the full configuration space - return self.gridCoordToRealWorldCoord(self.nodeIdToGridCoord(nid)) - -# Uses Batch Informed Trees to find a path from start to goal + return self.grid_coord_to_real_world_coord(self.node_id_to_grid_coord(nid)) class BITStar(object): @@ -135,6 +141,8 @@ def __init__(self, start, goal, self.maxrand = randArea[1] self.maxIter = maxIter self.obstacleList = obstacleList + self.startId = None + self.goalId = None self.vertex_queue = [] self.edge_queue = [] @@ -154,8 +162,8 @@ def __init__(self, start, goal, upperLimit=upperLimit, resolution=0.01) def setup_planning(self): - self.startId = self.tree.realWorldToNodeId(self.start) - self.goalId = self.tree.realWorldToNodeId(self.goal) + self.startId = self.tree.real_world_to_node_id(self.start) + self.goalId = self.tree.real_world_to_node_id(self.goal) # add goal to the samples self.samples[self.goalId] = self.goal @@ -163,9 +171,9 @@ def setup_planning(self): self.f_scores[self.goalId] = 0 # add the start id to the tree - self.tree.addVertex(self.start) + self.tree.add_vertex(self.start) self.g_scores[self.startId] = 0 - self.f_scores[self.startId] = self.computeHeuristicCost( + self.f_scores[self.startId] = self.compute_heuristic_cost( self.startId, self.goalId) # max length we expect to find in our 'informed' sample space, starts as infinite @@ -182,11 +190,11 @@ def setup_planning(self): # first column of idenity matrix transposed id1_t = np.array([1.0, 0.0, 0.0]).reshape(1, 3) M = np.dot(a1, id1_t) - U, S, Vh = np.linalg.svd(M, 1, 1) + U, S, Vh = np.linalg.svd(M, True, True) C = np.dot(np.dot(U, np.diag( [1.0, 1.0, np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])), Vh) - self.samples.update(self.informedSample( + self.samples.update(self.informed_sample( 200, cBest, cMin, xCenter, C)) return etheta, cMin, xCenter, C, cBest @@ -207,7 +215,7 @@ def setup_sample(self, iterations, foundGoal, cMin, xCenter, C, cBest): else: m = 100 cBest = self.g_scores[self.goalId] - self.samples.update(self.informedSample( + self.samples.update(self.informed_sample( m, cBest, cMin, xCenter, C)) # make the old vertices the new vertices @@ -225,26 +233,25 @@ def plan(self, animation=True): foundGoal = False # run until done - while (iterations < self.maxIter): + while iterations < self.maxIter: cBest = self.setup_sample(iterations, foundGoal, cMin, xCenter, C, cBest) # expand the best vertices until an edge is better than the vertex # this is done because the vertex cost represents the lower bound # on the edge cost - while(self.bestVertexQueueValue() <= self.bestEdgeQueueValue()): - self.expandVertex(self.bestInVertexQueue()) + while self.best_vertex_queue_value() <= self.best_edge_queue_value(): + self.expand_vertex(self.best_in_vertex_queue()) # add the best edge to the tree - bestEdge = self.bestInEdgeQueue() + bestEdge = self.best_in_edge_queue() self.edge_queue.remove(bestEdge) # Check if this can improve the current solution - estimatedCostOfVertex = self.g_scores[bestEdge[0]] + self.computeDistanceCost( - bestEdge[0], bestEdge[1]) + self.computeHeuristicCost(bestEdge[1], self.goalId) - estimatedCostOfEdge = self.computeDistanceCost(self.startId, bestEdge[0]) + self.computeHeuristicCost( - bestEdge[0], bestEdge[1]) + self.computeHeuristicCost(bestEdge[1], self.goalId) - actualCostOfEdge = self.g_scores[bestEdge[0]] + \ - self.computeDistanceCost(bestEdge[0], bestEdge[1]) + estimatedCostOfVertex = self.g_scores[bestEdge[0]] + self.compute_distance_cost( + bestEdge[0], bestEdge[1]) + self.compute_heuristic_cost(bestEdge[1], self.goalId) + estimatedCostOfEdge = self.compute_distance_cost(self.startId, bestEdge[0]) + self.compute_heuristic_cost( + bestEdge[0], bestEdge[1]) + self.compute_heuristic_cost(bestEdge[1], self.goalId) + actualCostOfEdge = self.g_scores[bestEdge[0]] + self.compute_distance_cost(bestEdge[0], bestEdge[1]) f1 = estimatedCostOfVertex < self.g_scores[self.goalId] f2 = estimatedCostOfEdge < self.g_scores[self.goalId] @@ -252,46 +259,44 @@ def plan(self, animation=True): if f1 and f2 and f3: # connect this edge - firstCoord = self.tree.nodeIdToRealWorldCoord( + firstCoord = self.tree.node_id_to_real_world_coord( bestEdge[0]) - secondCoord = self.tree.nodeIdToRealWorldCoord( + secondCoord = self.tree.node_id_to_real_world_coord( bestEdge[1]) path = self.connect(firstCoord, secondCoord) - lastEdge = self.tree.realWorldToNodeId(secondCoord) + lastEdge = self.tree.real_world_to_node_id(secondCoord) if path is None or len(path) == 0: continue nextCoord = path[len(path) - 1, :] - nextCoordPathId = self.tree.realWorldToNodeId( + nextCoordPathId = self.tree.real_world_to_node_id( nextCoord) bestEdge = (bestEdge[0], nextCoordPathId) - if(bestEdge[1] in self.tree.vertices.keys()): + if bestEdge[1] in self.tree.vertices.keys(): continue else: try: del self.samples[bestEdge[1]] - except(KeyError): + except KeyError: pass - eid = self.tree.addVertex(nextCoord) + eid = self.tree.add_vertex(nextCoord) self.vertex_queue.append(eid) if eid == self.goalId or bestEdge[0] == self.goalId or bestEdge[1] == self.goalId: print("Goal found") foundGoal = True - self.tree.addEdge(bestEdge[0], bestEdge[1]) + self.tree.add_edge(bestEdge[0], bestEdge[1]) - g_score = self.computeDistanceCost( + g_score = self.compute_distance_cost( bestEdge[0], bestEdge[1]) - self.g_scores[bestEdge[1]] = g_score + \ - self.g_scores[bestEdge[0]] - self.f_scores[bestEdge[1]] = g_score + \ - self.computeHeuristicCost(bestEdge[1], self.goalId) - self.updateGraph() + self.g_scores[bestEdge[1]] = g_score + self.g_scores[bestEdge[0]] + self.f_scores[bestEdge[1]] = g_score + self.compute_heuristic_cost(bestEdge[1], self.goalId) + self.update_graph() # visualize new edge if animation: - self.drawGraph(xCenter=xCenter, cBest=cBest, - cMin=cMin, etheta=etheta, samples=self.samples.values(), - start=firstCoord, end=secondCoord, tree=self.tree.edges) + self.draw_graph(xCenter=xCenter, cBest=cBest, + cMin=cMin, etheta=etheta, samples=self.samples.values(), + start=firstCoord, end=secondCoord) self.remove_queue(lastEdge, bestEdge) @@ -306,14 +311,13 @@ def plan(self, animation=True): return self.find_final_path() def find_final_path(self): - plan = [] - plan.append(self.goal) + plan = [self.goal] currId = self.goalId - while (currId != self.startId): - plan.append(self.tree.nodeIdToRealWorldCoord(currId)) + while currId != self.startId: + plan.append(self.tree.node_id_to_real_world_coord(currId)) try: currId = self.nodes[currId] - except(KeyError): + except KeyError: print("cannot find Path") return [] @@ -324,29 +328,30 @@ def find_final_path(self): def remove_queue(self, lastEdge, bestEdge): for edge in self.edge_queue: - if(edge[1] == bestEdge[1]): - if self.g_scores[edge[1]] + self.computeDistanceCost(edge[1], bestEdge[1]) >= self.g_scores[self.goalId]: - if(lastEdge, bestEdge[1]) in self.edge_queue: + if edge[1] == bestEdge[1]: + dist_cost = self.compute_distance_cost(edge[1], bestEdge[1]) + if self.g_scores[edge[1]] + dist_cost >= self.g_scores[self.goalId]: + if (lastEdge, bestEdge[1]) in self.edge_queue: self.edge_queue.remove( (lastEdge, bestEdge[1])) def connect(self, start, end): # A function which attempts to extend from a start coordinates # to goal coordinates - steps = int(self.computeDistanceCost(self.tree.realWorldToNodeId( - start), self.tree.realWorldToNodeId(end)) * 10) + steps = int(self.compute_distance_cost(self.tree.real_world_to_node_id( + start), self.tree.real_world_to_node_id(end)) * 10) x = np.linspace(start[0], end[0], num=steps) y = np.linspace(start[1], end[1], num=steps) for i in range(len(x)): - if(self._collisionCheck(x[i], y[i])): - if(i == 0): + if self._collision_check(x[i], y[i]): + if i == 0: return None # if collision, send path until collision return np.vstack((x[0:i], y[0:i])).transpose() return np.vstack((x, y)).transpose() - def _collisionCheck(self, x, y): + def _collision_check(self, x, y): for (ox, oy, size) in self.obstacleList: dx = ox - x dy = oy - y @@ -355,45 +360,44 @@ def _collisionCheck(self, x, y): return True # collision return False - # def prune(self, c): - - def computeHeuristicCost(self, start_id, goal_id): + def compute_heuristic_cost(self, start_id, goal_id): # Using Manhattan distance as heuristic - start = np.array(self.tree.nodeIdToRealWorldCoord(start_id)) - goal = np.array(self.tree.nodeIdToRealWorldCoord(goal_id)) + start = np.array(self.tree.node_id_to_real_world_coord(start_id)) + goal = np.array(self.tree.node_id_to_real_world_coord(goal_id)) return np.linalg.norm(start - goal, 2) - def computeDistanceCost(self, vid, xid): + def compute_distance_cost(self, vid, xid): # L2 norm distance - start = np.array(self.tree.nodeIdToRealWorldCoord(vid)) - stop = np.array(self.tree.nodeIdToRealWorldCoord(xid)) + start = np.array(self.tree.node_id_to_real_world_coord(vid)) + stop = np.array(self.tree.node_id_to_real_world_coord(xid)) return np.linalg.norm(stop - start, 2) # Sample free space confined in the radius of ball R - def informedSample(self, m, cMax, cMin, xCenter, C): + def informed_sample(self, m, cMax, cMin, xCenter, C): samples = dict() print("g_Score goal id: ", self.g_scores[self.goalId]) for i in range(m + 1): if cMax < float('inf'): r = [cMax / 2.0, - math.sqrt(cMax**2 - cMin**2) / 2.0, - math.sqrt(cMax**2 - cMin**2) / 2.0] + math.sqrt(cMax ** 2 - cMin ** 2) / 2.0, + math.sqrt(cMax ** 2 - cMin ** 2) / 2.0] L = np.diag(r) - xBall = self.sampleUnitBall() + xBall = self.sample_unit_ball() rnd = np.dot(np.dot(C, L), xBall) + xCenter rnd = [rnd[(0, 0)], rnd[(1, 0)]] - random_id = self.tree.realWorldToNodeId(rnd) + random_id = self.tree.real_world_to_node_id(rnd) samples[random_id] = rnd else: - rnd = self.sampleFreeSpace() - random_id = self.tree.realWorldToNodeId(rnd) + rnd = self.sample_free_space() + random_id = self.tree.real_world_to_node_id(rnd) samples[random_id] = rnd return samples # Sample point in a unit ball - def sampleUnitBall(self): + @staticmethod + def sample_unit_ball(): a = random.random() b = random.random() @@ -404,63 +408,64 @@ def sampleUnitBall(self): b * math.sin(2 * math.pi * a / b)) return np.array([[sample[0]], [sample[1]], [0]]) - def sampleFreeSpace(self): + def sample_free_space(self): rnd = [random.uniform(self.minrand, self.maxrand), random.uniform(self.minrand, self.maxrand)] return rnd - def bestVertexQueueValue(self): - if(len(self.vertex_queue) == 0): + def best_vertex_queue_value(self): + if len(self.vertex_queue) == 0: return float('inf') values = [self.g_scores[v] - + self.computeHeuristicCost(v, self.goalId) for v in self.vertex_queue] + + self.compute_heuristic_cost(v, self.goalId) for v in self.vertex_queue] values.sort() return values[0] - def bestEdgeQueueValue(self): - if(len(self.edge_queue) == 0): + def best_edge_queue_value(self): + if len(self.edge_queue) == 0: return float('inf') # return the best value in the queue by score g_tau[v] + c(v,x) + h(x) - values = [self.g_scores[e[0]] + self.computeDistanceCost(e[0], e[1]) - + self.computeHeuristicCost(e[1], self.goalId) for e in self.edge_queue] + values = [self.g_scores[e[0]] + self.compute_distance_cost(e[0], e[1]) + + self.compute_heuristic_cost(e[1], self.goalId) for e in self.edge_queue] values.sort(reverse=True) return values[0] - def bestInVertexQueue(self): + def best_in_vertex_queue(self): # return the best value in the vertex queue - v_plus_vals = [(v, self.g_scores[v] + self.computeHeuristicCost(v, self.goalId)) + v_plus_vals = [(v, self.g_scores[v] + self.compute_heuristic_cost(v, self.goalId)) for v in self.vertex_queue] v_plus_vals = sorted(v_plus_vals, key=lambda x: x[1]) # print(v_plus_vals) return v_plus_vals[0][0] - def bestInEdgeQueue(self): - e_and_values = [(e[0], e[1], self.g_scores[e[0]] + self.computeDistanceCost( - e[0], e[1]) + self.computeHeuristicCost(e[1], self.goalId)) for e in self.edge_queue] + def best_in_edge_queue(self): + e_and_values = [(e[0], e[1], self.g_scores[e[0]] + self.compute_distance_cost( + e[0], e[1]) + self.compute_heuristic_cost(e[1], self.goalId)) for e in self.edge_queue] e_and_values = sorted(e_and_values, key=lambda x: x[2]) - return (e_and_values[0][0], e_and_values[0][1]) + return e_and_values[0][0], e_and_values[0][1] - def expandVertex(self, vid): + def expand_vertex(self, vid): self.vertex_queue.remove(vid) # get the coordinates for given vid - currCoord = np.array(self.tree.nodeIdToRealWorldCoord(vid)) + currCoord = np.array(self.tree.node_id_to_real_world_coord(vid)) # get the nearest value in vertex for every one in samples where difference is # less than the radius neigbors = [] for sid, scoord in self.samples.items(): scoord = np.array(scoord) - if(np.linalg.norm(scoord - currCoord, 2) <= self.r and sid != vid): + if np.linalg.norm(scoord - currCoord, 2) <= self.r and sid != vid: neigbors.append((sid, scoord)) # add an edge to the edge queue is the path might improve the solution for neighbor in neigbors: sid = neighbor[0] - estimated_f_score = self.computeDistanceCost( - self.startId, vid) + self.computeHeuristicCost(sid, self.goalId) + self.computeDistanceCost(vid, sid) + h_cost = self.compute_heuristic_cost(sid, self.goalId) + estimated_f_score = self.compute_distance_cost( + self.startId, vid) + h_cost + self.compute_distance_cost(vid, sid) if estimated_f_score < self.g_scores[self.goalId]: self.edge_queue.append((vid, sid)) @@ -469,22 +474,22 @@ def expandVertex(self, vid): def add_vertex_to_edge_queue(self, vid, currCoord): if vid not in self.old_vertices: - neigbors = [] + neighbors = [] for v, edges in self.tree.vertices.items(): if v != vid and (v, vid) not in self.edge_queue and (vid, v) not in self.edge_queue: - vcoord = self.tree.nodeIdToRealWorldCoord(v) - if(np.linalg.norm(vcoord - currCoord, 2) <= self.r): - neigbors.append((vid, vcoord)) + v_coord = self.tree.node_id_to_real_world_coord(v) + if np.linalg.norm(currCoord - v_coord, 2) <= self.r: + neighbors.append((vid, v_coord)) - for neighbor in neigbors: + for neighbor in neighbors: sid = neighbor[0] - estimated_f_score = self.computeDistanceCost(self.startId, vid) + \ - self.computeDistanceCost( - vid, sid) + self.computeHeuristicCost(sid, self.goalId) - if estimated_f_score < self.g_scores[self.goalId] and (self.g_scores[vid] + self.computeDistanceCost(vid, sid)) < self.g_scores[sid]: + estimated_f_score = self.compute_distance_cost(self.startId, vid) + self.compute_distance_cost( + vid, sid) + self.compute_heuristic_cost(sid, self.goalId) + if estimated_f_score < self.g_scores[self.goalId] and ( + self.g_scores[vid] + self.compute_distance_cost(vid, sid)) < self.g_scores[sid]: self.edge_queue.append((vid, sid)) - def updateGraph(self): + def update_graph(self): closedSet = [] openSet = [] currId = self.startId @@ -498,22 +503,21 @@ def updateGraph(self): openSet.remove(currId) # Check if we're at the goal - if(currId == self.goalId): - self.nodes[self.goalId] + if currId == self.goalId: break - if(currId not in closedSet): + if currId not in closedSet: closedSet.append(currId) # find a non visited successor to the current node successors = self.tree.vertices[currId] for succesor in successors: - if(succesor in closedSet): + if succesor in closedSet: continue else: # claculate tentative g score g_score = self.g_scores[currId] + \ - self.computeDistanceCost(currId, succesor) + self.compute_distance_cost(currId, succesor) if succesor not in openSet: # add the successor to open set openSet.append(succesor) @@ -522,14 +526,13 @@ def updateGraph(self): # update g and f scores self.g_scores[succesor] = g_score - self.f_scores[succesor] = g_score + \ - self.computeHeuristicCost(succesor, self.goalId) + self.f_scores[succesor] = g_score + self.compute_heuristic_cost(succesor, self.goalId) # store the parent and child self.nodes[succesor] = currId - def drawGraph(self, xCenter=None, cBest=None, cMin=None, etheta=None, - samples=None, start=None, end=None, tree=None): + def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, + samples=None, start=None, end=None): plt.clf() for rnd in samples: if rnd is not None: @@ -549,9 +552,10 @@ def drawGraph(self, xCenter=None, cBest=None, cMin=None, etheta=None, plt.grid(True) plt.pause(0.01) - def plot_ellipse(self, xCenter, cBest, cMin, etheta): # pragma: no cover + @staticmethod + def plot_ellipse(xCenter, cBest, cMin, etheta): # pragma: no cover - a = math.sqrt(cBest**2 - cMin**2) / 2.0 + a = math.sqrt(cBest ** 2 - cMin ** 2) / 2.0 b = cBest / 2.0 angle = math.pi / 2.0 - etheta cx = xCenter[0] From 097a289a88fe38dd6e27df8de956d75a17bba947 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 3 Aug 2019 14:04:10 +0900 Subject: [PATCH 031/940] code clean up for informed rrt star --- .../InformedRRTStar/informed_rrt_star.py | 181 +++++++++--------- 1 file changed, 94 insertions(+), 87 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 2a999fd0c5..4a32801da5 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -4,22 +4,22 @@ author: Karan Chawla Atsushi Sakai(@Atsushi_twi) -Reference: Informed RRT*: Optimal Sampling-based Path Planning Focused via +Reference: Informed RRT*: Optimal Sampling-based Path planning Focused via Direct Sampling of an Admissible Ellipsoidal Heuristichttps://arxiv.org/pdf/1404.2334.pdf """ - -import random -import numpy as np -import math import copy +import math +import random + import matplotlib.pyplot as plt +import numpy as np show_animation = True -class InformedRRTStar(): +class InformedRRTStar: def __init__(self, start, goal, obstacleList, randArea, @@ -27,16 +27,17 @@ def __init__(self, start, goal, self.start = Node(start[0], start[1]) self.goal = Node(goal[0], goal[1]) - self.minrand = randArea[0] - self.maxrand = randArea[1] - self.expandDis = expandDis - self.goalSampleRate = goalSampleRate - self.maxIter = maxIter - self.obstacleList = obstacleList + self.min_rand = randArea[0] + self.max_rand = randArea[1] + self.expand_dis = expandDis + self.goal_sample_rate = goalSampleRate + self.max_iter = maxIter + self.obstacle_list = obstacleList + self.node_list = None - def InformedRRTStarSearch(self, animation=True): + def informed_rrt_star_search(self, animation=True): - self.nodeList = [self.start] + self.node_list = [self.start] # max length we expect to find in our 'informed' sample space, starts as infinite cBest = float('inf') pathLen = float('inf') @@ -55,62 +56,62 @@ def InformedRRTStarSearch(self, animation=True): # first column of idenity matrix transposed id1_t = np.array([1.0, 0.0, 0.0]).reshape(1, 3) M = a1 @ id1_t - U, S, Vh = np.linalg.svd(M, 1, 1) + U, S, Vh = np.linalg.svd(M, True, True) C = np.dot(np.dot(U, np.diag( [1.0, 1.0, np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])), Vh) - for i in range(self.maxIter): + for i in range(self.max_iter): # Sample space is defined by cBest # cMin is the minimum distance between the start point and the goal # xCenter is the midpoint between the start and the goal # cBest changes when a new path is found rnd = self.informed_sample(cBest, cMin, xCenter, C) - nind = self.getNearestListIndex(self.nodeList, rnd) - nearestNode = self.nodeList[nind] + nind = self.get_nearest_list_index(self.node_list, rnd) + nearestNode = self.node_list[nind] # steer theta = math.atan2(rnd[1] - nearestNode.y, rnd[0] - nearestNode.x) - newNode = self.getNewNode(theta, nind, nearestNode) - d = self.lineCost(nearestNode, newNode) + newNode = self.get_new_node(theta, nind, nearestNode) + d = self.line_cost(nearestNode, newNode) - isCollision = self.__CollisionCheck(newNode, self.obstacleList) + isCollision = self.collision_check(newNode, self.obstacle_list) isCollisionEx = self.check_collision_extend(nearestNode, theta, d) if isCollision and isCollisionEx: - nearInds = self.findNearNodes(newNode) - newNode = self.chooseParent(newNode, nearInds) + nearInds = self.find_near_nodes(newNode) + newNode = self.choose_parent(newNode, nearInds) - self.nodeList.append(newNode) + self.node_list.append(newNode) self.rewire(newNode, nearInds) - if self.isNearGoal(newNode): + if self.is_near_goal(newNode): solutionSet.add(newNode) - lastIndex = len(self.nodeList) - 1 - tempPath = self.getFinalCourse(lastIndex) - tempPathLen = self.getPathLen(tempPath) + lastIndex = len(self.node_list) - 1 + tempPath = self.get_final_course(lastIndex) + tempPathLen = self.get_path_len(tempPath) if tempPathLen < pathLen: path = tempPath cBest = tempPathLen if animation: - self.drawGraph(xCenter=xCenter, - cBest=cBest, cMin=cMin, - etheta=etheta, rnd=rnd) + self.draw_graph(xCenter=xCenter, + cBest=cBest, cMin=cMin, + etheta=etheta, rnd=rnd) return path - def chooseParent(self, newNode, nearInds): + def choose_parent(self, newNode, nearInds): if len(nearInds) == 0: return newNode dList = [] for i in nearInds: - dx = newNode.x - self.nodeList[i].x - dy = newNode.y - self.nodeList[i].y + dx = newNode.x - self.node_list[i].x + dy = newNode.y - self.node_list[i].y d = math.sqrt(dx ** 2 + dy ** 2) theta = math.atan2(dy, dx) - if self.check_collision_extend(self.nodeList[i], theta, d): - dList.append(self.nodeList[i].cost + d) + if self.check_collision_extend(self.node_list[i], theta, d): + dList.append(self.node_list[i].cost + d) else: dList.append(float('inf')) @@ -126,29 +127,30 @@ def chooseParent(self, newNode, nearInds): return newNode - def findNearNodes(self, newNode): - nnode = len(self.nodeList) + def find_near_nodes(self, newNode): + nnode = len(self.node_list) r = 50.0 * math.sqrt((math.log(nnode) / nnode)) dlist = [(node.x - newNode.x) ** 2 - + (node.y - newNode.y) ** 2 for node in self.nodeList] + + (node.y - newNode.y) ** 2 for node in self.node_list] nearinds = [dlist.index(i) for i in dlist if i <= r ** 2] return nearinds def informed_sample(self, cMax, cMin, xCenter, C): if cMax < float('inf'): r = [cMax / 2.0, - math.sqrt(cMax**2 - cMin**2) / 2.0, - math.sqrt(cMax**2 - cMin**2) / 2.0] + math.sqrt(cMax ** 2 - cMin ** 2) / 2.0, + math.sqrt(cMax ** 2 - cMin ** 2) / 2.0] L = np.diag(r) - xBall = self.sampleUnitBall() + xBall = self.sample_unit_ball() rnd = np.dot(np.dot(C, L), xBall) + xCenter rnd = [rnd[(0, 0)], rnd[(1, 0)]] else: - rnd = self.sampleFreeSpace() + rnd = self.sample_free_space() return rnd - def sampleUnitBall(self): + @staticmethod + def sample_unit_ball(): a = random.random() b = random.random() @@ -159,16 +161,17 @@ def sampleUnitBall(self): b * math.sin(2 * math.pi * a / b)) return np.array([[sample[0]], [sample[1]], [0]]) - def sampleFreeSpace(self): - if random.randint(0, 100) > self.goalSampleRate: - rnd = [random.uniform(self.minrand, self.maxrand), - random.uniform(self.minrand, self.maxrand)] + def sample_free_space(self): + if random.randint(0, 100) > self.goal_sample_rate: + rnd = [random.uniform(self.min_rand, self.max_rand), + random.uniform(self.min_rand, self.max_rand)] else: rnd = [self.goal.x, self.goal.y] return rnd - def getPathLen(self, path): + @staticmethod + def get_path_len(path): pathLen = 0 for i in range(1, len(path)): node1_x = path[i][0] @@ -176,52 +179,55 @@ def getPathLen(self, path): node2_x = path[i - 1][0] node2_y = path[i - 1][1] pathLen += math.sqrt((node1_x - node2_x) - ** 2 + (node1_y - node2_y)**2) + ** 2 + (node1_y - node2_y) ** 2) return pathLen - def lineCost(self, node1, node2): - return math.sqrt((node1.x - node2.x)**2 + (node1.y - node2.y)**2) + @staticmethod + def line_cost(node1, node2): + return math.sqrt((node1.x - node2.x) ** 2 + (node1.y - node2.y) ** 2) - def getNearestListIndex(self, nodes, rnd): - dList = [(node.x - rnd[0])**2 - + (node.y - rnd[1])**2 for node in nodes] + @staticmethod + def get_nearest_list_index(nodes, rnd): + dList = [(node.x - rnd[0]) ** 2 + + (node.y - rnd[1]) ** 2 for node in nodes] minIndex = dList.index(min(dList)) return minIndex - def __CollisionCheck(self, newNode, obstacleList): + @staticmethod + def collision_check(newNode, obstacleList): for (ox, oy, size) in obstacleList: dx = ox - newNode.x dy = oy - newNode.y d = dx * dx + dy * dy - if d <= 1.1 * size**2: + if d <= 1.1 * size ** 2: return False # collision return True # safe - def getNewNode(self, theta, nind, nearestNode): + def get_new_node(self, theta, nind, nearestNode): newNode = copy.deepcopy(nearestNode) - newNode.x += self.expandDis * math.cos(theta) - newNode.y += self.expandDis * math.sin(theta) + newNode.x += self.expand_dis * math.cos(theta) + newNode.y += self.expand_dis * math.sin(theta) - newNode.cost += self.expandDis + newNode.cost += self.expand_dis newNode.parent = nind return newNode - def isNearGoal(self, node): - d = self.lineCost(node, self.goal) - if d < self.expandDis: + def is_near_goal(self, node): + d = self.line_cost(node, self.goal) + if d < self.expand_dis: return True return False def rewire(self, newNode, nearInds): - nnode = len(self.nodeList) + n_node = len(self.node_list) for i in nearInds: - nearNode = self.nodeList[i] + nearNode = self.node_list[i] - d = math.sqrt((nearNode.x - newNode.x)**2 - + (nearNode.y - newNode.y)**2) + d = math.sqrt((nearNode.x - newNode.x) ** 2 + + (nearNode.y - newNode.y) ** 2) scost = newNode.cost + d @@ -229,30 +235,30 @@ def rewire(self, newNode, nearInds): theta = math.atan2(newNode.y - nearNode.y, newNode.x - nearNode.x) if self.check_collision_extend(nearNode, theta, d): - nearNode.parent = nnode - 1 + nearNode.parent = n_node - 1 nearNode.cost = scost def check_collision_extend(self, nearNode, theta, d): tmpNode = copy.deepcopy(nearNode) - for i in range(int(d / self.expandDis)): - tmpNode.x += self.expandDis * math.cos(theta) - tmpNode.y += self.expandDis * math.sin(theta) - if not self.__CollisionCheck(tmpNode, self.obstacleList): + for i in range(int(d / self.expand_dis)): + tmpNode.x += self.expand_dis * math.cos(theta) + tmpNode.y += self.expand_dis * math.sin(theta) + if not self.collision_check(tmpNode, self.obstacle_list): return False return True - def getFinalCourse(self, lastIndex): + def get_final_course(self, lastIndex): path = [[self.goal.x, self.goal.y]] - while self.nodeList[lastIndex].parent is not None: - node = self.nodeList[lastIndex] + while self.node_list[lastIndex].parent is not None: + node = self.node_list[lastIndex] path.append([node.x, node.y]) lastIndex = node.parent path.append([self.start.x, self.start.y]) return path - def drawGraph(self, xCenter=None, cBest=None, cMin=None, etheta=None, rnd=None): + def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, rnd=None): plt.clf() if rnd is not None: @@ -260,13 +266,13 @@ def drawGraph(self, xCenter=None, cBest=None, cMin=None, etheta=None, rnd=None): if cBest != float('inf'): self.plot_ellipse(xCenter, cBest, cMin, etheta) - for node in self.nodeList: + for node in self.node_list: if node.parent is not None: if node.x or node.y is not None: - plt.plot([node.x, self.nodeList[node.parent].x], [ - node.y, self.nodeList[node.parent].y], "-g") + plt.plot([node.x, self.node_list[node.parent].x], [ + node.y, self.node_list[node.parent].y], "-g") - for (ox, oy, size) in self.obstacleList: + for (ox, oy, size) in self.obstacle_list: plt.plot(ox, oy, "ok", ms=30 * size) plt.plot(self.start.x, self.start.y, "xr") @@ -275,9 +281,10 @@ def drawGraph(self, xCenter=None, cBest=None, cMin=None, etheta=None, rnd=None): plt.grid(True) plt.pause(0.01) - def plot_ellipse(self, xCenter, cBest, cMin, etheta): # pragma: no cover + @staticmethod + def plot_ellipse(xCenter, cBest, cMin, etheta): # pragma: no cover - a = math.sqrt(cBest**2 - cMin**2) / 2.0 + a = math.sqrt(cBest ** 2 - cMin ** 2) / 2.0 b = cBest / 2.0 angle = math.pi / 2.0 - etheta cx = xCenter[0] @@ -295,7 +302,7 @@ def plot_ellipse(self, xCenter, cBest, cMin, etheta): # pragma: no cover plt.plot(px, py, "--c") -class Node(): +class Node: def __init__(self, x, y): self.x = x @@ -320,12 +327,12 @@ def main(): # Set params rrt = InformedRRTStar(start=[0, 0], goal=[5, 10], randArea=[-2, 15], obstacleList=obstacleList) - path = rrt.InformedRRTStarSearch(animation=show_animation) + path = rrt.informed_rrt_star_search(animation=show_animation) print("Done!!") # Plot path if show_animation: - rrt.drawGraph() + rrt.draw_graph() plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') plt.grid(True) plt.pause(0.01) @@ -333,4 +340,4 @@ def main(): if __name__ == '__main__': - main() \ No newline at end of file + main() From 98584912e9810add1c055e39db5a7ed1f7aea115 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 3 Aug 2019 14:17:03 +0900 Subject: [PATCH 032/940] add a test case for grid map lib --- ..._grid_based_sweep_coverage_path_planner.py | 2 +- tests/test_grid_map_lib.py | 38 +++++++++++++++++++ 2 files changed, 39 insertions(+), 1 deletion(-) create mode 100644 tests/test_grid_map_lib.py diff --git a/tests/test_grid_based_sweep_coverage_path_planner.py b/tests/test_grid_based_sweep_coverage_path_planner.py index 3caaac8952..3933356726 100644 --- a/tests/test_grid_based_sweep_coverage_path_planner.py +++ b/tests/test_grid_based_sweep_coverage_path_planner.py @@ -6,7 +6,7 @@ sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../Mapping/grid_map_lib") try: import grid_based_sweep_coverage_path_planner -except: +except ImportError: raise class TestPlanning(TestCase): diff --git a/tests/test_grid_map_lib.py b/tests/test_grid_map_lib.py new file mode 100644 index 0000000000..63b3cc86b7 --- /dev/null +++ b/tests/test_grid_map_lib.py @@ -0,0 +1,38 @@ +import os +import sys +import unittest + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../Mapping/grid_map_lib") +try: + from grid_map_lib import GridMap +except ImportError: + raise + + +class MyTestCase(unittest.TestCase): + + def test_position_set(self): + grid_map = GridMap(100, 120, 0.5, 10.0, -0.5) + + grid_map.set_value_from_xy_pos(10.1, -1.1, 1.0) + grid_map.set_value_from_xy_pos(10.1, -0.1, 1.0) + grid_map.set_value_from_xy_pos(10.1, 1.1, 1.0) + grid_map.set_value_from_xy_pos(11.1, 0.1, 1.0) + grid_map.set_value_from_xy_pos(10.1, 0.1, 1.0) + grid_map.set_value_from_xy_pos(9.1, 0.1, 1.0) + + self.assertEqual(True, True) + + def test_polygon_set(self): + ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0] + oy = [0.0, -20.0, 0.0, 30.0, 60.0, 80.0] + + grid_map = GridMap(600, 290, 0.7, 60.0, 30.5) + + grid_map.set_value_from_polygon(ox, oy, 1.0, inside=False) + + self.assertEqual(True, True) + + +if __name__ == '__main__': + unittest.main() From 625b00b5b88e470029b4fa5676b6a2e5c0999eec Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 3 Aug 2019 14:22:48 +0900 Subject: [PATCH 033/940] add no cover annotations --- .../grid_based_sweep_coverage_path_planner.py | 4 ++-- PathPlanning/RRTDubins/rrt_dubins.py | 5 ++--- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py index 3d068559f8..5d691ffde3 100644 --- a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py +++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py @@ -259,7 +259,7 @@ def planning(ox, oy, reso, return rx, ry -def planning_animation(ox, oy, reso): +def planning_animation(ox, oy, reso) # pragma: no cover: px, py = planning(ox, oy, reso) # animation @@ -281,7 +281,7 @@ def planning_animation(ox, oy, reso): plt.pause(0.1) -def main(): +def main() # pragma: no cover: print("start!!") ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0, 0.0] diff --git a/PathPlanning/RRTDubins/rrt_dubins.py b/PathPlanning/RRTDubins/rrt_dubins.py index ed2b27ca0b..339acd2c3a 100644 --- a/PathPlanning/RRTDubins/rrt_dubins.py +++ b/PathPlanning/RRTDubins/rrt_dubins.py @@ -24,7 +24,6 @@ except ImportError: raise - show_animation = True @@ -105,7 +104,7 @@ def planning(self, animation=True, search_until_max_iter=True): return None - def draw_graph(self, rnd=None): + def draw_graph(self, rnd=None): # pragma: no cover plt.clf() if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") @@ -123,7 +122,7 @@ def draw_graph(self, rnd=None): self.plot_start_goal_arrow() plt.pause(0.01) - def plot_start_goal_arrow(self): + def plot_start_goal_arrow(self): # pragma: no cover dubins_path_planning.plot_arrow( self.start.x, self.start.y, self.start.yaw) dubins_path_planning.plot_arrow( From 76074568ced5118a8929cbe856492e156760d894 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 3 Aug 2019 14:33:58 +0900 Subject: [PATCH 034/940] fix test --- .../grid_based_sweep_coverage_path_planner.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py index 5d691ffde3..f22b058fa8 100644 --- a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py +++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py @@ -259,7 +259,7 @@ def planning(ox, oy, reso, return rx, ry -def planning_animation(ox, oy, reso) # pragma: no cover: +def planning_animation(ox, oy, reso): # pragma: no cover px, py = planning(ox, oy, reso) # animation @@ -281,7 +281,7 @@ def planning_animation(ox, oy, reso) # pragma: no cover: plt.pause(0.1) -def main() # pragma: no cover: +def main(): # pragma: no cover print("start!!") ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0, 0.0] From b94e13500fd9ca790fb4b488eba2428fe97b879c Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 3 Aug 2019 16:43:24 +0900 Subject: [PATCH 035/940] code clean up2 --- .../histogram_filter/histogram_filter.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index 1e43fee850..a70658e61c 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -11,12 +11,13 @@ """ +import copy import math -import numpy as np + import matplotlib.pyplot as plt -import copy -from scipy.stats import norm +import numpy as np from scipy.ndimage import gaussian_filter +from scipy.stats import norm # Parameters EXTEND_AREA = 10.0 # [m] grid map extention length @@ -41,7 +42,7 @@ show_animation = True -class grid_map(): +class GridMap: def __init__(self): self.data = None @@ -117,7 +118,7 @@ def motion_model(x, u): def draw_heatmap(data, mx, my): maxp = max([max(igmap) for igmap in data]) - plt.pcolor(mx, my, data, vmax=maxp, cmap=plt.cm.Blues) + plt.pcolor(mx, my, data, vmax=maxp, cmap=plt.cm.get_cmap("Blues")) plt.axis("equal") @@ -157,8 +158,7 @@ def normalize_probability(gmap): def init_gmap(xyreso, minx, miny, maxx, maxy): - - gmap = grid_map() + gmap = GridMap() gmap.xyreso = xyreso gmap.minx = minx @@ -168,7 +168,7 @@ def init_gmap(xyreso, minx, miny, maxx, maxy): gmap.xw = int(round((gmap.maxx - gmap.minx) / gmap.xyreso)) gmap.yw = int(round((gmap.maxy - gmap.miny) / gmap.xyreso)) - gmap.data = [[1.0 for i in range(gmap.yw)] for i in range(gmap.xw)] + gmap.data = [[1.0 for _ in range(gmap.yw)] for _ in range(gmap.xw)] gmap = normalize_probability(gmap) return gmap @@ -183,7 +183,7 @@ def map_shift(gmap, xshift, yshift): nix = ix + xshift niy = iy + yshift - if nix >= 0 and nix < gmap.xw and niy >= 0 and niy < gmap.yw: + if 0 <= nix < gmap.xw and 0 <= niy < gmap.yw: gmap.data[ix + xshift][iy + yshift] = tgmap[ix][iy] return gmap From ac547941aad6ecd340d99cbf76028f536b107179 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 3 Aug 2019 16:43:24 +0900 Subject: [PATCH 036/940] code clean up --- .../histogram_filter/histogram_filter.py | 26 +++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index 1e43fee850..f7696e6ba9 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -11,12 +11,13 @@ """ +import copy import math -import numpy as np + import matplotlib.pyplot as plt -import copy -from scipy.stats import norm +import numpy as np from scipy.ndimage import gaussian_filter +from scipy.stats import norm # Parameters EXTEND_AREA = 10.0 # [m] grid map extention length @@ -41,11 +42,11 @@ show_animation = True -class grid_map(): +class GridMap: def __init__(self): self.data = None - self.xyreso = None + self.xy_reso = None self.minx = None self.miny = None self.maxx = None @@ -117,7 +118,7 @@ def motion_model(x, u): def draw_heatmap(data, mx, my): maxp = max([max(igmap) for igmap in data]) - plt.pcolor(mx, my, data, vmax=maxp, cmap=plt.cm.Blues) + plt.pcolor(mx, my, data, vmax=maxp, cmap=plt.cm.get_cmap("Blues")) plt.axis("equal") @@ -157,18 +158,17 @@ def normalize_probability(gmap): def init_gmap(xyreso, minx, miny, maxx, maxy): + gmap = GridMap() - gmap = grid_map() - - gmap.xyreso = xyreso + gmap.xy_reso = xyreso gmap.minx = minx gmap.miny = miny gmap.maxx = maxx gmap.maxy = maxy - gmap.xw = int(round((gmap.maxx - gmap.minx) / gmap.xyreso)) - gmap.yw = int(round((gmap.maxy - gmap.miny) / gmap.xyreso)) + gmap.xw = int(round((gmap.maxx - gmap.minx) / gmap.xy_reso)) + gmap.yw = int(round((gmap.maxy - gmap.miny) / gmap.xy_reso)) - gmap.data = [[1.0 for i in range(gmap.yw)] for i in range(gmap.xw)] + gmap.data = [[1.0 for _ in range(gmap.yw)] for _ in range(gmap.xw)] gmap = normalize_probability(gmap) return gmap @@ -183,7 +183,7 @@ def map_shift(gmap, xshift, yshift): nix = ix + xshift niy = iy + yshift - if nix >= 0 and nix < gmap.xw and niy >= 0 and niy < gmap.yw: + if 0 <= nix < gmap.xw and 0 <= niy < gmap.yw: gmap.data[ix + xshift][iy + yshift] = tgmap[ix][iy] return gmap From da2b1ac6c7b4521ec44dd3408e3b9e8971dcdfcf Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 3 Aug 2019 20:35:44 +0900 Subject: [PATCH 037/940] code cleanup --- .../histogram_filter/histogram_filter.py | 109 +++++++++--------- 1 file changed, 53 insertions(+), 56 deletions(-) diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index 5342d02b4f..9c1cb3e524 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -11,12 +11,13 @@ """ +import copy import math -import numpy as np + import matplotlib.pyplot as plt -import copy -from scipy.stats import norm +import numpy as np from scipy.ndimage import gaussian_filter +from scipy.stats import norm # Parameters EXTEND_AREA = 10.0 # [m] grid map extended length @@ -41,11 +42,11 @@ show_animation = True -class grid_map(): +class GridMap(): def __init__(self): self.data = None - self.xyreso = None + self.xy_reso = None self.minx = None self.miny = None self.maxx = None @@ -56,20 +57,19 @@ def __init__(self): self.dy = 0.0 # movement distance -def histogram_filter_localization(gmap, u, z, yaw): +def histogram_filter_localization(grid_map, u, z, yaw): + grid_map = motion_update(grid_map, u, yaw) - gmap = motion_update(gmap, u, yaw) + grid_map = observation_update(grid_map, z, RANGE_STD) - gmap = observation_update(gmap, z, RANGE_STD) - - return gmap + return grid_map def calc_gaussian_observation_pdf(gmap, z, iz, ix, iy, std): # predicted range - x = ix * gmap.xyreso + gmap.minx - y = iy * gmap.xyreso + gmap.miny + x = ix * gmap.xy_reso + gmap.minx + y = iy * gmap.xy_reso + gmap.miny d = math.sqrt((x - z[iz, 1])**2 + (y - z[iz, 2])**2) # likelihood @@ -93,8 +93,8 @@ def observation_update(gmap, z, std): def calc_input(): v = 1.0 # [m/s] - yawrate = 0.1 # [rad/s] - u = np.array([v, yawrate]).reshape(2, 1) + yaw_rate = 0.1 # [rad/s] + u = np.array([v, yaw_rate]).reshape(2, 1) return u @@ -115,7 +115,7 @@ def motion_model(x, u): return x -def draw_heatmap(data, mx, my): +def draw_heat_map(data, mx, my): maxp = max([max(igmap) for igmap in data]) plt.pcolor(mx, my, data, vmax=maxp, cmap=plt.cm.get_cmap("Blues")) plt.axis("equal") @@ -156,60 +156,57 @@ def normalize_probability(gmap): return gmap -def init_gmap(xyreso, minx, miny, maxx, maxy): +def init_gmap(xy_reso, minx, miny, maxx, maxy): + grid_map = GridMap() - gmap = grid_map() + grid_map.xy_reso = xy_reso + grid_map.minx = minx + grid_map.miny = miny + grid_map.maxx = maxx + grid_map.maxy = maxy + grid_map.xw = int(round((grid_map.maxx - grid_map.minx) / grid_map.xy_reso)) + grid_map.yw = int(round((grid_map.maxy - grid_map.miny) / grid_map.xy_reso)) - gmap.xy_reso = xyreso - gmap.minx = minx - gmap.miny = miny - gmap.maxx = maxx - gmap.maxy = maxy - gmap.xw = int(round((gmap.maxx - gmap.minx) / gmap.xy_reso)) - gmap.yw = int(round((gmap.maxy - gmap.miny) / gmap.xy_reso)) + grid_map.data = [[1.0 for _ in range(grid_map.yw)] for _ in range(grid_map.xw)] + grid_map = normalize_probability(grid_map) - gmap.data = [[1.0 for _ in range(gmap.yw)] for _ in range(gmap.xw)] - gmap = normalize_probability(gmap) + return grid_map - return gmap +def map_shift(grid_map, x_shift, y_shift): + tgmap = copy.deepcopy(grid_map.data) -def map_shift(gmap, xshift, yshift): + for ix in range(grid_map.xw): + for iy in range(grid_map.yw): + nix = ix + x_shift + niy = iy + y_shift - tgmap = copy.deepcopy(gmap.data) + if 0 <= nix < grid_map.xw and 0 <= niy < grid_map.yw: + grid_map.data[ix + x_shift][iy + y_shift] = tgmap[ix][iy] - for ix in range(gmap.xw): - for iy in range(gmap.yw): - nix = ix + xshift - niy = iy + yshift + return grid_map - if 0 <= nix < gmap.xw and 0 <= niy < gmap.yw: - gmap.data[ix + xshift][iy + yshift] = tgmap[ix][iy] - return gmap +def motion_update(grid_map, u, yaw): + grid_map.dx += DT * math.cos(yaw) * u[0] + grid_map.dy += DT * math.sin(yaw) * u[0] + x_shift = grid_map.dx // grid_map.xy_reso + y_shift = grid_map.dy // grid_map.xy_reso -def motion_update(gmap, u, yaw): + if abs(x_shift) >= 1.0 or abs(y_shift) >= 1.0: # map should be shifted + grid_map = map_shift(grid_map, int(x_shift), int(y_shift)) + grid_map.dx -= x_shift * grid_map.xy_reso + grid_map.dy -= y_shift * grid_map.xy_reso - gmap.dx += DT * math.cos(yaw) * u[0] - gmap.dy += DT * math.sin(yaw) * u[0] + grid_map.data = gaussian_filter(grid_map.data, sigma=MOTION_STD) - xshift = gmap.dx // gmap.xyreso - yshift = gmap.dy // gmap.xyreso - - if abs(xshift) >= 1.0 or abs(yshift) >= 1.0: # map should be shifted - gmap = map_shift(gmap, int(xshift), int(yshift)) - gmap.dx -= xshift * gmap.xyreso - gmap.dy -= yshift * gmap.xyreso - - gmap.data = gaussian_filter(gmap.data, sigma=MOTION_STD) - - return gmap + return grid_map def calc_grid_index(gmap): - mx, my = np.mgrid[slice(gmap.minx - gmap.xyreso / 2.0, gmap.maxx + gmap.xyreso / 2.0, gmap.xyreso), - slice(gmap.miny - gmap.xyreso / 2.0, gmap.maxy + gmap.xyreso / 2.0, gmap.xyreso)] + mx, my = np.mgrid[slice(gmap.minx - gmap.xy_reso / 2.0, gmap.maxx + gmap.xy_reso / 2.0, gmap.xy_reso), + slice(gmap.miny - gmap.xy_reso / 2.0, gmap.maxy + gmap.xy_reso / 2.0, gmap.xy_reso)] return mx, my @@ -226,8 +223,8 @@ def main(): time = 0.0 xTrue = np.zeros((4, 1)) - gmap = init_gmap(XY_RESO, MINX, MINY, MAXX, MAXY) - mx, my = calc_grid_index(gmap) # for grid map visualization + grid_map = init_gmap(XY_RESO, MINX, MINY, MAXX, MAXY) + mx, my = calc_grid_index(grid_map) # for grid map visualization while SIM_TIME >= time: time += DT @@ -238,11 +235,11 @@ def main(): yaw = xTrue[2, 0] # Orientation is known xTrue, z, ud = observation(xTrue, u, RFID) - gmap = histogram_filter_localization(gmap, u, z, yaw) + grid_map = histogram_filter_localization(grid_map, u, z, yaw) if show_animation: plt.cla() - draw_heatmap(gmap.data, mx, my) + draw_heat_map(grid_map.data, mx, my) plt.plot(xTrue[0, :], xTrue[1, :], "xr") plt.plot(RFID[:, 0], RFID[:, 1], ".k") for i in range(z.shape[0]): From 44ac74b08f94ab59ff772dcbafbd8213927c994e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 5 Aug 2019 20:11:06 +0900 Subject: [PATCH 038/940] Update users_comments.md --- users_comments.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/users_comments.md b/users_comments.md index 294f3b3b13..d0bd285842 100644 --- a/users_comments.md +++ b/users_comments.md @@ -345,6 +345,12 @@ Thanks for writing these algorithms. They are very helpful for learning robotics --- +Dear AtsushiSakai,
Thank you for providing us this great repository for playing and look around:)! + +--Hsin-Wen + + + # Citations From e27f0cd70b503dd95e0437f32204b4c5774012d1 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 9 Aug 2019 22:37:09 +0900 Subject: [PATCH 039/940] Update users_comments.md --- users_comments.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/users_comments.md b/users_comments.md index d0bd285842..e015c19d1f 100644 --- a/users_comments.md +++ b/users_comments.md @@ -349,7 +349,11 @@ Dear AtsushiSakai,
Thank you for providing us this great repository for play --Hsin-Wen +--- + +Thanks for PythonRobotics! +--Nick V # Citations From b762fd036e35f25a178de4add06706357fe1bed6 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 15 Aug 2019 09:00:42 +0900 Subject: [PATCH 040/940] Update users_comments.md --- users_comments.md | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/users_comments.md b/users_comments.md index e015c19d1f..8e66ae9f11 100644 --- a/users_comments.md +++ b/users_comments.md @@ -355,6 +355,14 @@ Thanks for PythonRobotics! --Nick V +--- + +Dear AtsushiSakai, thank you so much for this material, it's so useful to me, i'm really glad with it =D + +--Juanda + +--- + # Citations From a48bacd6cf6c55b304ebe7ea3c4632ed28cec819 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 22 Aug 2019 21:32:02 +0900 Subject: [PATCH 041/940] Update state_lattice_planner.py --- PathPlanning/StateLatticePlanner/state_lattice_planner.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/PathPlanning/StateLatticePlanner/state_lattice_planner.py b/PathPlanning/StateLatticePlanner/state_lattice_planner.py index 424609064d..c2819eb250 100644 --- a/PathPlanning/StateLatticePlanner/state_lattice_planner.py +++ b/PathPlanning/StateLatticePlanner/state_lattice_planner.py @@ -4,6 +4,12 @@ author: Atsushi Sakai (@Atsushi_twi) +- lookuptable.csv is generated with this script: https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable_generator.py + +Ref: + +- State Space Sampling of Feasible Motions for High-Performance Mobile Robot Navigation in Complex Environments http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.187.8210&rep=rep1&type=pdf + """ import sys import os From 7864296494d936b35e80e6cef946fed2bcff066d Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 22 Aug 2019 21:53:35 +0900 Subject: [PATCH 042/940] Update users_comments.md --- users_comments.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/users_comments.md b/users_comments.md index 8e66ae9f11..772b5774ec 100644 --- a/users_comments.md +++ b/users_comments.md @@ -363,6 +363,12 @@ Dear AtsushiSakai, thank you so much for this material, it's so useful to me, i' --- +Dear Atsushi Thanks for compiling such a vast resource for robotics motion planning. + +--Kartik Prakash + +--- + # Citations From 4e76b94eabb2519e05a9c82ffd701699fc4f454b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 26 Aug 2019 20:41:17 +0900 Subject: [PATCH 043/940] Update users_comments.md --- users_comments.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/users_comments.md b/users_comments.md index 772b5774ec..c0165bd2d7 100644 --- a/users_comments.md +++ b/users_comments.md @@ -369,6 +369,12 @@ Dear Atsushi Thanks for compiling such a vast resource for robotics motion plann --- +Thanks for your job!
I have learned a lot from it! + +--ZhongyiShen + +--- + # Citations From 21bd3b3ebc74c4a0313f3d35fdbe31da14a578f0 Mon Sep 17 00:00:00 2001 From: Ryohei Sasaki Date: Sat, 7 Sep 2019 12:34:53 +0900 Subject: [PATCH 044/940] Add PoseOptimizationSLAM3D --- SLAM/PoseOptimizationSLAM3D/README.md | 21 + .../PoseOptimizationSLAM3D/data_downloader.py | 22 + .../pose_optimization_slam_3d.py | 535 ++++++++++++++++++ 3 files changed, 578 insertions(+) create mode 100644 SLAM/PoseOptimizationSLAM3D/README.md create mode 100644 SLAM/PoseOptimizationSLAM3D/data_downloader.py create mode 100644 SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py diff --git a/SLAM/PoseOptimizationSLAM3D/README.md b/SLAM/PoseOptimizationSLAM3D/README.md new file mode 100644 index 0000000000..ac95c7e206 --- /dev/null +++ b/SLAM/PoseOptimizationSLAM3D/README.md @@ -0,0 +1,21 @@ +# PoseOptimizationSLAM3D +3D (x, y, z, qw, qx, qy, qz) pose optimization SLAM + +## How to use +1. Download data + +~~~ +python data_downloader.py +~~~ + +2. run SLAM + +~~~ +python pose_optimization_slam_3d.py +~~~ + +## Reference +[A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) +[GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) +[GitHub \- AtsushiSakai/PythonRobotics +/SLAM/PoseOptimizationSLAM](https://github.com/AtsushiSakai/PythonRobotics/tree/master/SLAM/PoseOptimizationSLAM) diff --git a/SLAM/PoseOptimizationSLAM3D/data_downloader.py b/SLAM/PoseOptimizationSLAM3D/data_downloader.py new file mode 100644 index 0000000000..31bd3bb3a5 --- /dev/null +++ b/SLAM/PoseOptimizationSLAM3D/data_downloader.py @@ -0,0 +1,22 @@ +""" + +Data down loader for pose optimization + +author: Atsushi Sakai + +""" + + +import subprocess +def main(): + print("start!!") + + cmd = "wget https://www.dropbox.com/s/zu23p8d522qccor/parking-garage.g2o?dl=0 -O parking-garage.g2o -nc" + subprocess.call(cmd, shell=True) + + print("done!!") + + +if __name__ == '__main__': + main() + diff --git a/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py b/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py new file mode 100644 index 0000000000..e5cf6ac62d --- /dev/null +++ b/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py @@ -0,0 +1,535 @@ +""" +3D (x, y, z, qw, qx, qy, qz) pose optimization SLAM +author: Ryohei Sasaki(@rsasaki0109) +Ref: +- [A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) +- [GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) +- [GitHub \- AtsushiSakai/PythonRobotics +/SLAM/PoseOptimizationSLAM](https://github.com/AtsushiSakai/PythonRobotics/blob/master/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py) +""" + +import sys +import time +import numpy as np +from scipy import sparse +from scipy.sparse import linalg +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D + +est_traj_fig = plt.figure() +ax = est_traj_fig.add_subplot(111, projection='3d') + +def skew_symmetric(v): + + return np.array( + [[0, -v[2], v[1]], + [v[2], 0, -v[0]], + [-v[1], v[0], 0]] + ) + +def robust_coeff(squared_error, delta): + + if (squared_error < 0): + return 0 + sqre = np.sqrt(squared_error) + if (sqre < delta): + return 1 # no effect + return delta / sqre # linear + + +class Optimizer3D: + + def __init__(self): + self.verbose = False + self.animation = False + self.p_lambda = 1e-7 + self.init_w = 1e10 + self.stop_thre = 1e-3 + self.robust_delta = 1 + self.dim = 6 # state dimension + + def optimize_path(self, nodes, consts, max_iter, min_iter): + + graph_nodes = nodes[:] + prev_cost = sys.float_info.max + + est_traj_fig = plt.figure() + ax = est_traj_fig.add_subplot(111, projection='3d') + + for i in range(max_iter): + start = time.time() + cost, graph_nodes = self.optimize_path_one_step( + graph_nodes, consts) + elapsed = time.time() - start + if self.verbose: + print("step ", i, " cost: ", cost, " time:", elapsed, "s") + + # check convergence + if (i > min_iter) and (prev_cost - cost < self.stop_thre): + if self.verbose: + print("converged:", prev_cost + - cost, " < ", self.stop_thre) + break + prev_cost = cost + + if self.animation: + plt.cla() + plot_nodes(nodes, ax, color="-b") + plot_nodes(graph_nodes, ax) + plt.pause(1.0) + + return graph_nodes + + def optimize_path_one_step(self, graph_nodes, constraints): + + indlist = [i for i in range(self.dim)] + numnodes = len(graph_nodes) + bf = np.zeros(numnodes * self.dim) + tripletList = TripletList() + + for con in constraints: + ida = con.id1 + idb = con.id2 + assert 0 <= ida and ida < numnodes, "ida is invalid" + assert 0 <= idb and idb < numnodes, "idb is invalid" + pa = graph_nodes[ida] + pb = graph_nodes[idb] + r, Ja, Jb = self.calc_error( + pa, pb, con.t) + + info_mat = con.info_mat * robust_coeff(r.reshape(self.dim,1).T @ con.info_mat @ r.reshape(self.dim,1), self.robust_delta) + + trJaInfo = Ja.transpose() @ info_mat + trJaInfoJa = trJaInfo @ Ja + trJbInfo = Jb.transpose() @ info_mat + trJbInfoJb = trJbInfo @ Jb + trJaInfoJb = trJaInfo @ Jb + + for k in indlist: + for m in indlist: + tripletList.push_back( + ida * self.dim + k, ida * self.dim + m, trJaInfoJa[k, m]) + tripletList.push_back( + idb * self.dim + k, idb * self.dim + m, trJbInfoJb[k, m]) + tripletList.push_back( + ida * self.dim + k, idb * self.dim + m, trJaInfoJb[k, m]) + tripletList.push_back( + idb * self.dim + k, ida * self.dim + m, trJaInfoJb[m, k]) + + bf[ida * self.dim: (ida + 1) * self.dim ] += trJaInfo @ r + bf[idb * self.dim: (idb + 1) * self.dim ] += trJbInfo @ r + + for k in indlist: + tripletList.push_back(k, k, self.init_w) + + for i in range(self.dim * numnodes): + tripletList.push_back(i, i, self.p_lambda) + + mat = sparse.coo_matrix((tripletList.data, (tripletList.row, tripletList.col)), + shape=(numnodes * self.dim, numnodes * self.dim)) + + x = linalg.spsolve(mat.tocsr(), -bf) + + out_nodes = [] + + for i in range(len(graph_nodes)): + + u_i = i * self.dim + + q_before = Quaternion(graph_nodes[i].qw, graph_nodes[i].qx, graph_nodes[i].qy, graph_nodes[i].qz) + rv_before = RotVec(quaternion = q_before) + rv_after = RotVec(ax = rv_before.ax + x[u_i + 3], ay = rv_before.ay + x[u_i + 4], az = rv_before.az + x[u_i + 5]) + q_after = rv_after.toQuaternion() + + pos = Pose3D( + graph_nodes[i].x + x[u_i], + graph_nodes[i].y + x[u_i + 1], + graph_nodes[i].z + x[u_i + 2], + q_after.qw, + q_after.qx, + q_after.qy, + q_after.qz + ) + out_nodes.append(pos) + + cost = self.calc_global_cost(out_nodes, constraints) + + return cost, out_nodes + + def calc_global_cost(self, nodes, constraints): + + cost = 0.0 + for c in constraints: + diff = self.error_func(nodes[c.id1], nodes[c.id2], c.t) + info_mat = c.info_mat * robust_coeff(diff.reshape(self.dim,1).T @ c.info_mat @ diff.reshape(self.dim,1), self.robust_delta) + cost += diff.transpose() @ info_mat @ diff + + return cost + + def error_func(self, pa, pb, t): + + ba = pb.ominus(pa) + q = t.rv().toQuaternion().conjugate().quat_mult(ba.rv().toQuaternion(), out = 'Quaternion') + drv = RotVec(quaternion = q) + error = np.array([ba.x - t.x, + ba.y - t.y, + ba.z - t.z, + drv.ax[0], + drv.ay[0], + drv.az[0]]) + return error + + def dQuat_dRV(self, rv): + + u1 = rv.ax; u2 = rv.ay; u3 = rv.az + v = np.sqrt(u1**2 + u2**2 + u3**2) + if v < 1e-6: + dqu = 0.25 * np.array( + [[ -u1, -u2, -u3], + [ 2.0, 0.0, 0.0], + [ 0.0, 2.0, 0.0], + [ 0.0, 0.0, 2.0]] + ) + return dqu + + vd = v*2 + v2 = v**2 + v3 = v**3 + + S = np.sin(v/2.0); C = np.cos(v/2.0) + dqu = np.array( + [[ -u1 * S/vd , -u2*S/vd , -u3*S/vd], + [ S/v + u1*u1*C/(2*v2) - u1*u1*S/v3, u1*u2*(C/(2*v2)-S/v3) , u1*u3*(C/(2*v2)-S/v3)], + [ u1*u2*(C/(2*v2)-S/v3) , S/v+u2*u2*C/(2*v2)-u2*u2*S/v3, u2*u3*(C/(2*v2)-S/v3)], + [ u1*u3*(C/(2*v2)-S/v3) , u2*u3*(C/(2*v2)-S/v3) , S/v+u3*u3*C/(2*v2)-u3*u3*S/v3]] + ) + + return dqu + + def dR_dRV(self, rv): + + q = rv.toQuaternion() + qw = q.qw;qx = q.qx; qy = q.qy;qz = q.qz + dRdqw = 2 * np.array( + [[ qw, -qz, qy], + [ qz, qw, -qx], + [-qy, qx, qw]] + ) + dRdqx = 2 * np.array( + [[ qx, qy, qz], + [ qy, -qx, -qw], + [ qz, qw, -qx]] + ) + dRdqy = 2 * np.array( + [[-qy, qx, qw], + [ qx, qy, qz], + [-qw, qz, -qy]] + ) + dRdqz = 2 * np.array( + [[-qz, -qw, qx], + [ qw, -qz, -qy], + [ qz, qy, qz]] + ) + dqdu = self.dQuat_dRV(rv) + dux = dRdqw * dqdu[0,0] + dRdqx * dqdu[1, 0] + dRdqy * dqdu[2, 0] + dRdqz * dqdu[3, 0] + duy = dRdqw * dqdu[0,1] + dRdqx * dqdu[1, 1] + dRdqy * dqdu[2, 1] + dRdqz * dqdu[3, 1] + duz = dRdqw * dqdu[0,2] + dRdqx * dqdu[1, 2] + dRdqy * dqdu[2, 2] + dRdqz * dqdu[3, 2] + return dux, duy, duz + + def dRV_dQuat(self, q): + + if 1 - q.qw**2 < 1e-7: + ret = np.array( + [[ 0.0, 2.0, 0.0, 0.0], + [ 0.0, 0.0, 2.0, 0.0], + [ 0.0, 0.0, 0.0, 2.0]] + ) + return ret + c = 1/(1 - q.qw**2) + d = np.arccos(q.qw)/(np.sqrt(1-q.qw**2)) + ret = 2.0 * np.array( + [[ c*q.qx*(d*q.qw-1), d, 0.0, 0.0], + [ c*q.qy*(d*q.qw-1), 0.0, d, 0.0], + [ c*q.qz*(d*q.qw-1), 0.0, 0.0, d]] + ) + return ret + + def QMat(self, q): + + qw = q.qw; qx = q.qx; qy = q.qy; qz = q.qz + Q = np.array( + [[ qw, -qx, -qy, -qz], + [ qx, qw, -qz, qy], + [ qy, qz, qw, -qx], + [ qz, -qy, qx, qw]] + ) + return Q + + def QMatBar(self, q): + + qw = q.qw; qx = q.qx; qy = q.qy; qz = q.qz + Q = np.array( + [[ qw, -qx, -qy, -qz], + [ qx, qw, qz, -qy], + [ qy, -qz, qw, qx], + [ qz, qy, -qx, qw]] + ) + return Q + + def calc_error(self, pa, pb, t): + + e0 = self.error_func(pa, pb, t) + Ja = np.identity(6); Jb = np.identity(6) + + rva_inv = pa.rv().inverted() + rotPaInv = rva_inv.toRotationMatrix() + + Ja[:3,:3] = -rotPaInv + Jb[:3,:3] = rotPaInv + + dRux, dRuy, dRuz = self.dR_dRV(rva_inv) + + cvec = np.array([[pb.x - pa.x],[pb.y - pa.y],[pb.z - pa.z]]) + + Ja[0:3,3:4] = -dRux @ cvec + Ja[0:3,4:5] = -dRuy @ cvec + Ja[0:3,5:6] = -dRuz @ cvec + + # rotation part: qdiff = qc-1 * qa-1 * qb + qainv = rva_inv.toQuaternion() + qcinv = t.rv().inverted().toQuaternion() + qb = pb.rv().toQuaternion() + qinvca = qcinv.quat_mult(qainv, out = 'Quaternion') + qdiff = qinvca.quat_mult(qb, out = 'Quaternion') + + Ja[3:6,3:6] = -self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMatBar(qb) @ self.dQuat_dRV(rva_inv) + Jb[3:6,3:6] = self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMat(qainv) @ self.dQuat_dRV(pb.rv()) + + return e0, Ja, Jb + +class Quaternion: + + def __init__(self, qw, qx, qy, qz): + self.qw = qw; self.qx = qx; self.qy = qy; self.qz = qz + + def conjugate(self): + return Quaternion(self.qw, -self.qx, -self.qy, -self.qz) + + def to_numpy(self): + return np.array([self.qw, self.qx, self.qy, self.qz]).reshape(4,1) + + def quat_mult(self, q, out='np'): + v = np.array([self.qx, self.qy, self.qz]).reshape(3, 1) + sum_term = np.zeros([4,4]) + sum_term[0,1:] = -v[:,0] + sum_term[1:, 0] = v[:,0] + sum_term[1:, 1:] = skew_symmetric(v) + sigma = self.qw * np.eye(4) + sum_term + q_new = sigma @ q.to_numpy() + if out == 'np': + return q_new + elif out == 'Quaternion': + q_obj = Quaternion(*q_new) + return q_obj + + +class RotVec: + + def __init__(self, ax=0., ay=0., az=0., quaternion=None): + if quaternion is None: + self.ax = ax; self.ay = ay; self.az = az + else: + x = quaternion.qx; y = quaternion.qy; z = quaternion.qz + norm_im = np.sqrt(x**2 + y**2 + z**2) + if (norm_im < 1e-7): + self.ax = 2*x; self.ay = 2*y; self.az = 2*z + else: + th = 2 * np.arctan2(norm_im, quaternion.qw) + th = self.pi2pi(th) + self.ax = x / norm_im * th + self.ay = y / norm_im * th + self.az = z / norm_im * th + + def inverted(self): + + return RotVec(-self.ax, -self.ay, -self.az) + + def toRotationMatrix(self): + + q = self.toQuaternion() + q_vec = np.array([q.qx, q.qy, q.qz]).reshape(3,1) + qw = q.qw + mat = (qw**2 - q_vec.T @ q_vec) * np.eye(3) + \ + 2 * q_vec @ q_vec.T - 2 * qw * skew_symmetric(q_vec.reshape(-1,)) + return mat.T + + def toQuaternion(self): + + v = np.sqrt(self.ax**2 + self.ay**2 + self.az**2) + if (v < 1e-6): + return Quaternion(1, 0, 0, 0) + else: + return Quaternion(np.cos(v/2), np.sin(v/2)*self.ax/v, + np.sin(v/2)*self.ay/v, np.sin(v/2)*self.az/v) + + def pi2pi(self, rad): + + val = np.fmod(rad, 2.0 * np.pi) + if val > np.pi: + val -= 2.0 * np.pi + elif val < -np.pi: + val += 2.0 * np.pi + + return val + + +class TripletList: + + def __init__(self): + self.row = [] + self.col = [] + self.data = [] + + def push_back(self, irow, icol, idata): + self.row.append(irow) + self.col.append(icol) + self.data.append(idata) + +class Pose3D: + + def __init__(self, x, y, z, qw, qx, qy, qz): + self.x = x; self.y = y; self.z = z + self.qw = qw; self.qx = qx; self.qy = qy; self.qz = qz + + def pos(self): + v = np.array([self.x, self.y, self.z]).reshape(3,1) + return v + + def rv(self): + q = Quaternion(self.qw, self.qx, self.qy, self.qz) + return RotVec(quaternion = q) + + def ominus(self, base): + t = base.rv().toRotationMatrix().T @ (self.pos() - base.pos()) + q = base.rv().toQuaternion().conjugate().quat_mult(self.rv().toQuaternion(), out = 'Quaternion') + return Pose3D(t[0][0], t[1][0], t[2][0], q.qw, q.qx, q.qy, q.qz) + + +class Constrant3D: + + def __init__(self, id1, id2, t, info_mat): + self.id1 = id1 + self.id2 = id2 + self.t = t + self.info_mat = info_mat + +def plot_nodes(nodes, ax, color ="-r", label = ""): + + x, y, z = [], [], [] + for n in nodes: + x.append(n.x); y.append(n.y); z.append(n.z) + ax.plot(x, y, z, color, label=label) + +def load_data(fname): + + nodes, consts = [], [] + + for line in open(fname): + sline = line.split() + tag = sline[0] + + if tag == "VERTEX_SE3:QUAT": + #data_id = int(sline[1]) # unused + x = float(sline[2]) + y = float(sline[3]) + z = float(sline[4]) + qx = float(sline[5]) + qy = float(sline[6]) + qz = float(sline[7]) + qw = float(sline[8]) + + nodes.append(Pose3D(x, y, z, qw, qx, qy, qz)) + elif tag == "EDGE_SE3:QUAT": + id1 = int(sline[1]) + id2 = int(sline[2]) + x = float(sline[3]) + y = float(sline[4]) + z = float(sline[5]) + qx = float(sline[6]) + qy = float(sline[7]) + qz = float(sline[8]) + qw = float(sline[9]) + c1 = float(sline[10]) + c2 = float(sline[11]) + c3 = float(sline[12]) + c4 = float(sline[13]) + c5 = float(sline[14]) + c6 = float(sline[15]) + c7 = float(sline[16]) + c8 = float(sline[17]) + c9 = float(sline[18]) + c10 = float(sline[19]) + c11 = float(sline[20]) + c12 = float(sline[21]) + c13 = float(sline[22]) + c14 = float(sline[23]) + c15 = float(sline[24]) + c16 = float(sline[25]) + c17 = float(sline[26]) + c18 = float(sline[27]) + c19 = float(sline[28]) + c20 = float(sline[29]) + c21 = float(sline[30]) + t = Pose3D(x, y, z, qw, qx, qy, qz) + info_mat = np.array([[c1, c2, c3, c4, c5, c6], + [c2, c7, c8, c9, c10, c11], + [c3, c8, c12, c13, c14, c15], + [c4, c9, c13, c16, c17, c18], + [c5, c10, c14, c17, c19, c20], + [c6, c11, c15, c18, c20, c21] + ]) + consts.append(Constrant3D(id1, id2, t, info_mat)) + + print("n_nodes:", len(nodes)) + print("n_consts:", len(consts)) + + return nodes, consts + + + +def main(): + + print("start!!") + + fnames = ["parking-garage.g2o"] + + max_iter = 20 + min_iter = 3 + + # parameter setting + optimizer = Optimizer3D() + optimizer.p_lambda = 1e-6 + optimizer.verbose = True + optimizer.animation = True + + for f in fnames: + print(f) + + nodes, consts = load_data(f) + + start = time.time() + final_nodes = optimizer.optimize_path(nodes, consts, max_iter, min_iter) + print("elapsed_time", time.time() - start, "sec") + + # plot + plt.cla() + est_traj_fig = plt.figure() + ax = est_traj_fig.add_subplot(111, projection='3d') + plot_nodes(nodes, ax, color="-b", label="before") + plot_nodes(final_nodes, ax, label="after") + plt.show() + + print("done!!") + +if __name__ == '__main__': + main() From 4beee9bb401be7e72ff733b52cf7a9a871654fa8 Mon Sep 17 00:00:00 2001 From: Ryohei Sasaki Date: Sat, 7 Sep 2019 13:01:47 +0900 Subject: [PATCH 045/940] Fix Trailing newlines --- SLAM/PoseOptimizationSLAM3D/data_downloader.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/SLAM/PoseOptimizationSLAM3D/data_downloader.py b/SLAM/PoseOptimizationSLAM3D/data_downloader.py index 31bd3bb3a5..8dea252640 100644 --- a/SLAM/PoseOptimizationSLAM3D/data_downloader.py +++ b/SLAM/PoseOptimizationSLAM3D/data_downloader.py @@ -18,5 +18,4 @@ def main(): if __name__ == '__main__': - main() - + main() \ No newline at end of file From cc70f5c2667c4c775b96a4d1143ef0e0f2cb0f8b Mon Sep 17 00:00:00 2001 From: Ryohei Sasaki Date: Sat, 7 Sep 2019 14:32:38 +0900 Subject: [PATCH 046/940] Fix function dRV_dQuat of class Optimizer3D --- pose_optimization_slam_3d.py | 541 +++++++++++++++++++++++++++++++++++ 1 file changed, 541 insertions(+) create mode 100644 pose_optimization_slam_3d.py diff --git a/pose_optimization_slam_3d.py b/pose_optimization_slam_3d.py new file mode 100644 index 0000000000..105201f8a2 --- /dev/null +++ b/pose_optimization_slam_3d.py @@ -0,0 +1,541 @@ +""" +3D (x, y, z, qw, qx, qy, qz) pose optimization SLAM +author: Ryohei Sasaki(@rsasaki0109) +Ref: +- [A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) +- [GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) +- [GitHub \- AtsushiSakai/PythonRobotics +/SLAM/PoseOptimizationSLAM](https://github.com/AtsushiSakai/PythonRobotics/blob/master/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py) +""" + +import sys +import time +import numpy as np +from scipy import sparse +from scipy.sparse import linalg +import matplotlib.pyplot as plt +from mpl_toolkits.mplot3d import Axes3D + +est_traj_fig = plt.figure() +ax = est_traj_fig.add_subplot(111, projection='3d') + +def skew_symmetric(v): + + return np.array( + [[0, -v[2], v[1]], + [v[2], 0, -v[0]], + [-v[1], v[0], 0]] + ) + +def robust_coeff(squared_error, delta): + + if (squared_error < 0): + return 0 + sqre = np.sqrt(squared_error) + if (sqre < delta): + return 1 # no effect + return delta / sqre # linear + + +class Optimizer3D: + + def __init__(self): + self.verbose = False + self.animation = False + self.p_lambda = 1e-7 + self.init_w = 1e10 + self.stop_thre = 1e-3 + self.robust_delta = 1 + self.dim = 6 # state dimension + + def optimize_path(self, nodes, consts, max_iter, min_iter): + + graph_nodes = nodes[:] + prev_cost = sys.float_info.max + + est_traj_fig = plt.figure() + ax = est_traj_fig.add_subplot(111, projection='3d') + + for i in range(max_iter): + start = time.time() + cost, graph_nodes = self.optimize_path_one_step( + graph_nodes, consts) + elapsed = time.time() - start + if self.verbose: + print("step ", i, " cost: ", cost, " time:", elapsed, "s") + + # check convergence + if (i > min_iter) and (prev_cost - cost < self.stop_thre): + if self.verbose: + print("converged:", prev_cost + - cost, " < ", self.stop_thre) + break + prev_cost = cost + + if self.animation: + plt.cla() + plot_nodes(nodes, ax, color="-b") + plot_nodes(graph_nodes, ax) + plt.pause(1.0) + + return graph_nodes + + def optimize_path_one_step(self, graph_nodes, constraints): + + indlist = [i for i in range(self.dim)] + numnodes = len(graph_nodes) + bf = np.zeros(numnodes * self.dim) + tripletList = TripletList() + + for con in constraints: + ida = con.id1 + idb = con.id2 + assert 0 <= ida and ida < numnodes, "ida is invalid" + assert 0 <= idb and idb < numnodes, "idb is invalid" + pa = graph_nodes[ida] + pb = graph_nodes[idb] + r, Ja, Jb = self.calc_error( + pa, pb, con.t) + + info_mat = con.info_mat * robust_coeff(r.reshape(self.dim,1).T @ con.info_mat @ r.reshape(self.dim,1), self.robust_delta) + + trJaInfo = Ja.transpose() @ info_mat + trJaInfoJa = trJaInfo @ Ja + trJbInfo = Jb.transpose() @ info_mat + trJbInfoJb = trJbInfo @ Jb + trJaInfoJb = trJaInfo @ Jb + + for k in indlist: + for m in indlist: + tripletList.push_back( + ida * self.dim + k, ida * self.dim + m, trJaInfoJa[k, m]) + tripletList.push_back( + idb * self.dim + k, idb * self.dim + m, trJbInfoJb[k, m]) + tripletList.push_back( + ida * self.dim + k, idb * self.dim + m, trJaInfoJb[k, m]) + tripletList.push_back( + idb * self.dim + k, ida * self.dim + m, trJaInfoJb[m, k]) + + bf[ida * self.dim: (ida + 1) * self.dim ] += trJaInfo @ r + bf[idb * self.dim: (idb + 1) * self.dim ] += trJbInfo @ r + + for k in indlist: + tripletList.push_back(k, k, self.init_w) + + for i in range(self.dim * numnodes): + tripletList.push_back(i, i, self.p_lambda) + + mat = sparse.coo_matrix((tripletList.data, (tripletList.row, tripletList.col)), + shape=(numnodes * self.dim, numnodes * self.dim)) + + x = linalg.spsolve(mat.tocsr(), -bf) + + out_nodes = [] + + for i in range(len(graph_nodes)): + + u_i = i * self.dim + + q_before = Quaternion(graph_nodes[i].qw, graph_nodes[i].qx, graph_nodes[i].qy, graph_nodes[i].qz) + rv_before = RotVec(quaternion = q_before) + rv_after = RotVec(ax = rv_before.ax + x[u_i + 3], ay = rv_before.ay + x[u_i + 4], az = rv_before.az + x[u_i + 5]) + q_after = rv_after.toQuaternion() + + pos = Pose3D( + graph_nodes[i].x + x[u_i], + graph_nodes[i].y + x[u_i + 1], + graph_nodes[i].z + x[u_i + 2], + q_after.qw, + q_after.qx, + q_after.qy, + q_after.qz + ) + out_nodes.append(pos) + + cost = self.calc_global_cost(out_nodes, constraints) + + return cost, out_nodes + + def calc_global_cost(self, nodes, constraints): + + cost = 0.0 + for c in constraints: + diff = self.error_func(nodes[c.id1], nodes[c.id2], c.t) + info_mat = c.info_mat * robust_coeff(diff.reshape(self.dim,1).T @ c.info_mat @ diff.reshape(self.dim,1), self.robust_delta) + cost += diff.transpose() @ info_mat @ diff + + return cost + + def error_func(self, pa, pb, t): + + ba = pb.ominus(pa) + q = t.rv().toQuaternion().conjugate().quat_mult(ba.rv().toQuaternion(), out = 'Quaternion') + drv = RotVec(quaternion = q) + error = np.array([ba.x - t.x, + ba.y - t.y, + ba.z - t.z, + drv.ax[0], + drv.ay[0], + drv.az[0]]) + return error + + def dQuat_dRV(self, rv): + + u1 = rv.ax; u2 = rv.ay; u3 = rv.az + v = np.sqrt(u1**2 + u2**2 + u3**2) + if v < 1e-6: + dqu = 0.25 * np.array( + [[ -u1, -u2, -u3], + [ 2.0, 0.0, 0.0], + [ 0.0, 2.0, 0.0], + [ 0.0, 0.0, 2.0]] + ) + return dqu + + vd = v*2 + v2 = v**2 + v3 = v**3 + + S = np.sin(v/2.0); C = np.cos(v/2.0) + dqu = np.array( + [[ -u1 * S/vd , -u2*S/vd , -u3*S/vd], + [ S/v + u1*u1*C/(2*v2) - u1*u1*S/v3, u1*u2*(C/(2*v2)-S/v3) , u1*u3*(C/(2*v2)-S/v3)], + [ u1*u2*(C/(2*v2)-S/v3) , S/v+u2*u2*C/(2*v2)-u2*u2*S/v3, u2*u3*(C/(2*v2)-S/v3)], + [ u1*u3*(C/(2*v2)-S/v3) , u2*u3*(C/(2*v2)-S/v3) , S/v+u3*u3*C/(2*v2)-u3*u3*S/v3]] + ) + + return dqu + + def dR_dRV(self, rv): + + q = rv.toQuaternion() + qw = q.qw;qx = q.qx; qy = q.qy;qz = q.qz + dRdqw = 2 * np.array( + [[ qw, -qz, qy], + [ qz, qw, -qx], + [-qy, qx, qw]] + ) + dRdqx = 2 * np.array( + [[ qx, qy, qz], + [ qy, -qx, -qw], + [ qz, qw, -qx]] + ) + dRdqy = 2 * np.array( + [[-qy, qx, qw], + [ qx, qy, qz], + [-qw, qz, -qy]] + ) + dRdqz = 2 * np.array( + [[-qz, -qw, qx], + [ qw, -qz, -qy], + [ qz, qy, qz]] + ) + dqdu = self.dQuat_dRV(rv) + dux = dRdqw * dqdu[0,0] + dRdqx * dqdu[1, 0] + dRdqy * dqdu[2, 0] + dRdqz * dqdu[3, 0] + duy = dRdqw * dqdu[0,1] + dRdqx * dqdu[1, 1] + dRdqy * dqdu[2, 1] + dRdqz * dqdu[3, 1] + duz = dRdqw * dqdu[0,2] + dRdqx * dqdu[1, 2] + dRdqy * dqdu[2, 2] + dRdqz * dqdu[3, 2] + return dux, duy, duz + + def dRV_dQuat(self, q): + + qw = q.qw[0] + qx = q.qx[0] + qy = q.qy[0] + qz = q.qz[0] + + if 1 - qw**2 < 1e-7: + ret = np.array( + [[ 0.0, 2.0, 0.0, 0.0], + [ 0.0, 0.0, 2.0, 0.0], + [ 0.0, 0.0, 0.0, 2.0]] + ) + return ret + + c = 1/(1 - qw**2) + d = np.arccos(qw)/(np.sqrt(1-qw**2)) + ret = 2.0 * np.array( + [[ c*qx*(d*qw-1), d, 0.0, 0.0], + [ c*qy*(d*qw-1), 0.0, d, 0.0], + [ c*qz*(d*qw-1), 0.0, 0.0, d]] + ) + return ret + + def QMat(self, q): + + qw = q.qw; qx = q.qx; qy = q.qy; qz = q.qz + Q = np.array( + [[ qw, -qx, -qy, -qz], + [ qx, qw, -qz, qy], + [ qy, qz, qw, -qx], + [ qz, -qy, qx, qw]] + ) + return Q + + def QMatBar(self, q): + + qw = q.qw; qx = q.qx; qy = q.qy; qz = q.qz + Q = np.array( + [[ qw, -qx, -qy, -qz], + [ qx, qw, qz, -qy], + [ qy, -qz, qw, qx], + [ qz, qy, -qx, qw]] + ) + return Q + + def calc_error(self, pa, pb, t): + + e0 = self.error_func(pa, pb, t) + Ja = np.identity(6); Jb = np.identity(6) + + rva_inv = pa.rv().inverted() + rotPaInv = rva_inv.toRotationMatrix() + + Ja[:3,:3] = -rotPaInv + Jb[:3,:3] = rotPaInv + + dRux, dRuy, dRuz = self.dR_dRV(rva_inv) + + cvec = np.array([[pb.x - pa.x],[pb.y - pa.y],[pb.z - pa.z]]) + + Ja[0:3,3:4] = -dRux @ cvec + Ja[0:3,4:5] = -dRuy @ cvec + Ja[0:3,5:6] = -dRuz @ cvec + + # rotation part: qdiff = qc-1 * qa-1 * qb + qainv = rva_inv.toQuaternion() + qcinv = t.rv().inverted().toQuaternion() + qb = pb.rv().toQuaternion() + qinvca = qcinv.quat_mult(qainv, out = 'Quaternion') + qdiff = qinvca.quat_mult(qb, out = 'Quaternion') + + Ja[3:6,3:6] = -self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMatBar(qb) @ self.dQuat_dRV(rva_inv) + Jb[3:6,3:6] = self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMat(qainv) @ self.dQuat_dRV(pb.rv()) + + return e0, Ja, Jb + +class Quaternion: + + def __init__(self, qw, qx, qy, qz): + self.qw = qw; self.qx = qx; self.qy = qy; self.qz = qz + + def conjugate(self): + return Quaternion(self.qw, -self.qx, -self.qy, -self.qz) + + def to_numpy(self): + return np.array([self.qw, self.qx, self.qy, self.qz]).reshape(4,1) + + def quat_mult(self, q, out='np'): + v = np.array([self.qx, self.qy, self.qz]).reshape(3, 1) + sum_term = np.zeros([4,4]) + sum_term[0,1:] = -v[:,0] + sum_term[1:, 0] = v[:,0] + sum_term[1:, 1:] = skew_symmetric(v) + sigma = self.qw * np.eye(4) + sum_term + q_new = sigma @ q.to_numpy() + if out == 'np': + return q_new + elif out == 'Quaternion': + q_obj = Quaternion(*q_new) + return q_obj + + +class RotVec: + + def __init__(self, ax=0., ay=0., az=0., quaternion=None): + if quaternion is None: + self.ax = ax; self.ay = ay; self.az = az + else: + x = quaternion.qx; y = quaternion.qy; z = quaternion.qz + norm_im = np.sqrt(x**2 + y**2 + z**2) + if (norm_im < 1e-7): + self.ax = 2*x; self.ay = 2*y; self.az = 2*z + else: + th = 2 * np.arctan2(norm_im, quaternion.qw) + th = self.pi2pi(th) + self.ax = x / norm_im * th + self.ay = y / norm_im * th + self.az = z / norm_im * th + + def inverted(self): + + return RotVec(-self.ax, -self.ay, -self.az) + + def toRotationMatrix(self): + + q = self.toQuaternion() + q_vec = np.array([q.qx, q.qy, q.qz]).reshape(3,1) + qw = q.qw + mat = (qw**2 - q_vec.T @ q_vec) * np.eye(3) + \ + 2 * q_vec @ q_vec.T - 2 * qw * skew_symmetric(q_vec.reshape(-1,)) + return mat.T + + def toQuaternion(self): + + v = np.sqrt(self.ax**2 + self.ay**2 + self.az**2) + if (v < 1e-6): + return Quaternion(1, 0, 0, 0) + else: + return Quaternion(np.cos(v/2), np.sin(v/2)*self.ax/v, + np.sin(v/2)*self.ay/v, np.sin(v/2)*self.az/v) + + def pi2pi(self, rad): + + val = np.fmod(rad, 2.0 * np.pi) + if val > np.pi: + val -= 2.0 * np.pi + elif val < -np.pi: + val += 2.0 * np.pi + + return val + + +class TripletList: + + def __init__(self): + self.row = [] + self.col = [] + self.data = [] + + def push_back(self, irow, icol, idata): + self.row.append(irow) + self.col.append(icol) + self.data.append(idata) + +class Pose3D: + + def __init__(self, x, y, z, qw, qx, qy, qz): + self.x = x; self.y = y; self.z = z + self.qw = qw; self.qx = qx; self.qy = qy; self.qz = qz + + def pos(self): + v = np.array([self.x, self.y, self.z]).reshape(3,1) + return v + + def rv(self): + q = Quaternion(self.qw, self.qx, self.qy, self.qz) + return RotVec(quaternion = q) + + def ominus(self, base): + t = base.rv().toRotationMatrix().T @ (self.pos() - base.pos()) + q = base.rv().toQuaternion().conjugate().quat_mult(self.rv().toQuaternion(), out = 'Quaternion') + return Pose3D(t[0][0], t[1][0], t[2][0], q.qw, q.qx, q.qy, q.qz) + + +class Constrant3D: + + def __init__(self, id1, id2, t, info_mat): + self.id1 = id1 + self.id2 = id2 + self.t = t + self.info_mat = info_mat + +def plot_nodes(nodes, ax, color ="-r", label = ""): + + x, y, z = [], [], [] + for n in nodes: + x.append(n.x); y.append(n.y); z.append(n.z) + ax.plot(x, y, z, color, label=label) + +def load_data(fname): + + nodes, consts = [], [] + + for line in open(fname): + sline = line.split() + tag = sline[0] + + if tag == "VERTEX_SE3:QUAT": + #data_id = int(sline[1]) # unused + x = float(sline[2]) + y = float(sline[3]) + z = float(sline[4]) + qx = float(sline[5]) + qy = float(sline[6]) + qz = float(sline[7]) + qw = float(sline[8]) + + nodes.append(Pose3D(x, y, z, qw, qx, qy, qz)) + elif tag == "EDGE_SE3:QUAT": + id1 = int(sline[1]) + id2 = int(sline[2]) + x = float(sline[3]) + y = float(sline[4]) + z = float(sline[5]) + qx = float(sline[6]) + qy = float(sline[7]) + qz = float(sline[8]) + qw = float(sline[9]) + c1 = float(sline[10]) + c2 = float(sline[11]) + c3 = float(sline[12]) + c4 = float(sline[13]) + c5 = float(sline[14]) + c6 = float(sline[15]) + c7 = float(sline[16]) + c8 = float(sline[17]) + c9 = float(sline[18]) + c10 = float(sline[19]) + c11 = float(sline[20]) + c12 = float(sline[21]) + c13 = float(sline[22]) + c14 = float(sline[23]) + c15 = float(sline[24]) + c16 = float(sline[25]) + c17 = float(sline[26]) + c18 = float(sline[27]) + c19 = float(sline[28]) + c20 = float(sline[29]) + c21 = float(sline[30]) + t = Pose3D(x, y, z, qw, qx, qy, qz) + info_mat = np.array([[c1, c2, c3, c4, c5, c6], + [c2, c7, c8, c9, c10, c11], + [c3, c8, c12, c13, c14, c15], + [c4, c9, c13, c16, c17, c18], + [c5, c10, c14, c17, c19, c20], + [c6, c11, c15, c18, c20, c21] + ]) + consts.append(Constrant3D(id1, id2, t, info_mat)) + + print("n_nodes:", len(nodes)) + print("n_consts:", len(consts)) + + return nodes, consts + + + +def main(): + + print("start!!") + + fnames = ["parking-garage.g2o"] + + max_iter = 20 + min_iter = 3 + + # parameter setting + optimizer = Optimizer3D() + optimizer.p_lambda = 1e-6 + optimizer.verbose = True + optimizer.animation = True + + for f in fnames: + print(f) + + nodes, consts = load_data(f) + + start = time.time() + final_nodes = optimizer.optimize_path(nodes, consts, max_iter, min_iter) + print("elapsed_time", time.time() - start, "sec") + + # plot + plt.cla() + est_traj_fig = plt.figure() + ax = est_traj_fig.add_subplot(111, projection='3d') + plot_nodes(nodes, ax, color="-b", label="before") + plot_nodes(final_nodes, ax, label="after") + plt.show() + + print("done!!") + +if __name__ == '__main__': + main() From cb8af3c2e4db403ce524df2df8ade7dad28039a6 Mon Sep 17 00:00:00 2001 From: Ryohei Sasaki Date: Sat, 7 Sep 2019 14:34:09 +0900 Subject: [PATCH 047/940] Delete pose_optimization_slam_3d.py --- pose_optimization_slam_3d.py | 541 ----------------------------------- 1 file changed, 541 deletions(-) delete mode 100644 pose_optimization_slam_3d.py diff --git a/pose_optimization_slam_3d.py b/pose_optimization_slam_3d.py deleted file mode 100644 index 105201f8a2..0000000000 --- a/pose_optimization_slam_3d.py +++ /dev/null @@ -1,541 +0,0 @@ -""" -3D (x, y, z, qw, qx, qy, qz) pose optimization SLAM -author: Ryohei Sasaki(@rsasaki0109) -Ref: -- [A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) -- [GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) -- [GitHub \- AtsushiSakai/PythonRobotics -/SLAM/PoseOptimizationSLAM](https://github.com/AtsushiSakai/PythonRobotics/blob/master/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py) -""" - -import sys -import time -import numpy as np -from scipy import sparse -from scipy.sparse import linalg -import matplotlib.pyplot as plt -from mpl_toolkits.mplot3d import Axes3D - -est_traj_fig = plt.figure() -ax = est_traj_fig.add_subplot(111, projection='3d') - -def skew_symmetric(v): - - return np.array( - [[0, -v[2], v[1]], - [v[2], 0, -v[0]], - [-v[1], v[0], 0]] - ) - -def robust_coeff(squared_error, delta): - - if (squared_error < 0): - return 0 - sqre = np.sqrt(squared_error) - if (sqre < delta): - return 1 # no effect - return delta / sqre # linear - - -class Optimizer3D: - - def __init__(self): - self.verbose = False - self.animation = False - self.p_lambda = 1e-7 - self.init_w = 1e10 - self.stop_thre = 1e-3 - self.robust_delta = 1 - self.dim = 6 # state dimension - - def optimize_path(self, nodes, consts, max_iter, min_iter): - - graph_nodes = nodes[:] - prev_cost = sys.float_info.max - - est_traj_fig = plt.figure() - ax = est_traj_fig.add_subplot(111, projection='3d') - - for i in range(max_iter): - start = time.time() - cost, graph_nodes = self.optimize_path_one_step( - graph_nodes, consts) - elapsed = time.time() - start - if self.verbose: - print("step ", i, " cost: ", cost, " time:", elapsed, "s") - - # check convergence - if (i > min_iter) and (prev_cost - cost < self.stop_thre): - if self.verbose: - print("converged:", prev_cost - - cost, " < ", self.stop_thre) - break - prev_cost = cost - - if self.animation: - plt.cla() - plot_nodes(nodes, ax, color="-b") - plot_nodes(graph_nodes, ax) - plt.pause(1.0) - - return graph_nodes - - def optimize_path_one_step(self, graph_nodes, constraints): - - indlist = [i for i in range(self.dim)] - numnodes = len(graph_nodes) - bf = np.zeros(numnodes * self.dim) - tripletList = TripletList() - - for con in constraints: - ida = con.id1 - idb = con.id2 - assert 0 <= ida and ida < numnodes, "ida is invalid" - assert 0 <= idb and idb < numnodes, "idb is invalid" - pa = graph_nodes[ida] - pb = graph_nodes[idb] - r, Ja, Jb = self.calc_error( - pa, pb, con.t) - - info_mat = con.info_mat * robust_coeff(r.reshape(self.dim,1).T @ con.info_mat @ r.reshape(self.dim,1), self.robust_delta) - - trJaInfo = Ja.transpose() @ info_mat - trJaInfoJa = trJaInfo @ Ja - trJbInfo = Jb.transpose() @ info_mat - trJbInfoJb = trJbInfo @ Jb - trJaInfoJb = trJaInfo @ Jb - - for k in indlist: - for m in indlist: - tripletList.push_back( - ida * self.dim + k, ida * self.dim + m, trJaInfoJa[k, m]) - tripletList.push_back( - idb * self.dim + k, idb * self.dim + m, trJbInfoJb[k, m]) - tripletList.push_back( - ida * self.dim + k, idb * self.dim + m, trJaInfoJb[k, m]) - tripletList.push_back( - idb * self.dim + k, ida * self.dim + m, trJaInfoJb[m, k]) - - bf[ida * self.dim: (ida + 1) * self.dim ] += trJaInfo @ r - bf[idb * self.dim: (idb + 1) * self.dim ] += trJbInfo @ r - - for k in indlist: - tripletList.push_back(k, k, self.init_w) - - for i in range(self.dim * numnodes): - tripletList.push_back(i, i, self.p_lambda) - - mat = sparse.coo_matrix((tripletList.data, (tripletList.row, tripletList.col)), - shape=(numnodes * self.dim, numnodes * self.dim)) - - x = linalg.spsolve(mat.tocsr(), -bf) - - out_nodes = [] - - for i in range(len(graph_nodes)): - - u_i = i * self.dim - - q_before = Quaternion(graph_nodes[i].qw, graph_nodes[i].qx, graph_nodes[i].qy, graph_nodes[i].qz) - rv_before = RotVec(quaternion = q_before) - rv_after = RotVec(ax = rv_before.ax + x[u_i + 3], ay = rv_before.ay + x[u_i + 4], az = rv_before.az + x[u_i + 5]) - q_after = rv_after.toQuaternion() - - pos = Pose3D( - graph_nodes[i].x + x[u_i], - graph_nodes[i].y + x[u_i + 1], - graph_nodes[i].z + x[u_i + 2], - q_after.qw, - q_after.qx, - q_after.qy, - q_after.qz - ) - out_nodes.append(pos) - - cost = self.calc_global_cost(out_nodes, constraints) - - return cost, out_nodes - - def calc_global_cost(self, nodes, constraints): - - cost = 0.0 - for c in constraints: - diff = self.error_func(nodes[c.id1], nodes[c.id2], c.t) - info_mat = c.info_mat * robust_coeff(diff.reshape(self.dim,1).T @ c.info_mat @ diff.reshape(self.dim,1), self.robust_delta) - cost += diff.transpose() @ info_mat @ diff - - return cost - - def error_func(self, pa, pb, t): - - ba = pb.ominus(pa) - q = t.rv().toQuaternion().conjugate().quat_mult(ba.rv().toQuaternion(), out = 'Quaternion') - drv = RotVec(quaternion = q) - error = np.array([ba.x - t.x, - ba.y - t.y, - ba.z - t.z, - drv.ax[0], - drv.ay[0], - drv.az[0]]) - return error - - def dQuat_dRV(self, rv): - - u1 = rv.ax; u2 = rv.ay; u3 = rv.az - v = np.sqrt(u1**2 + u2**2 + u3**2) - if v < 1e-6: - dqu = 0.25 * np.array( - [[ -u1, -u2, -u3], - [ 2.0, 0.0, 0.0], - [ 0.0, 2.0, 0.0], - [ 0.0, 0.0, 2.0]] - ) - return dqu - - vd = v*2 - v2 = v**2 - v3 = v**3 - - S = np.sin(v/2.0); C = np.cos(v/2.0) - dqu = np.array( - [[ -u1 * S/vd , -u2*S/vd , -u3*S/vd], - [ S/v + u1*u1*C/(2*v2) - u1*u1*S/v3, u1*u2*(C/(2*v2)-S/v3) , u1*u3*(C/(2*v2)-S/v3)], - [ u1*u2*(C/(2*v2)-S/v3) , S/v+u2*u2*C/(2*v2)-u2*u2*S/v3, u2*u3*(C/(2*v2)-S/v3)], - [ u1*u3*(C/(2*v2)-S/v3) , u2*u3*(C/(2*v2)-S/v3) , S/v+u3*u3*C/(2*v2)-u3*u3*S/v3]] - ) - - return dqu - - def dR_dRV(self, rv): - - q = rv.toQuaternion() - qw = q.qw;qx = q.qx; qy = q.qy;qz = q.qz - dRdqw = 2 * np.array( - [[ qw, -qz, qy], - [ qz, qw, -qx], - [-qy, qx, qw]] - ) - dRdqx = 2 * np.array( - [[ qx, qy, qz], - [ qy, -qx, -qw], - [ qz, qw, -qx]] - ) - dRdqy = 2 * np.array( - [[-qy, qx, qw], - [ qx, qy, qz], - [-qw, qz, -qy]] - ) - dRdqz = 2 * np.array( - [[-qz, -qw, qx], - [ qw, -qz, -qy], - [ qz, qy, qz]] - ) - dqdu = self.dQuat_dRV(rv) - dux = dRdqw * dqdu[0,0] + dRdqx * dqdu[1, 0] + dRdqy * dqdu[2, 0] + dRdqz * dqdu[3, 0] - duy = dRdqw * dqdu[0,1] + dRdqx * dqdu[1, 1] + dRdqy * dqdu[2, 1] + dRdqz * dqdu[3, 1] - duz = dRdqw * dqdu[0,2] + dRdqx * dqdu[1, 2] + dRdqy * dqdu[2, 2] + dRdqz * dqdu[3, 2] - return dux, duy, duz - - def dRV_dQuat(self, q): - - qw = q.qw[0] - qx = q.qx[0] - qy = q.qy[0] - qz = q.qz[0] - - if 1 - qw**2 < 1e-7: - ret = np.array( - [[ 0.0, 2.0, 0.0, 0.0], - [ 0.0, 0.0, 2.0, 0.0], - [ 0.0, 0.0, 0.0, 2.0]] - ) - return ret - - c = 1/(1 - qw**2) - d = np.arccos(qw)/(np.sqrt(1-qw**2)) - ret = 2.0 * np.array( - [[ c*qx*(d*qw-1), d, 0.0, 0.0], - [ c*qy*(d*qw-1), 0.0, d, 0.0], - [ c*qz*(d*qw-1), 0.0, 0.0, d]] - ) - return ret - - def QMat(self, q): - - qw = q.qw; qx = q.qx; qy = q.qy; qz = q.qz - Q = np.array( - [[ qw, -qx, -qy, -qz], - [ qx, qw, -qz, qy], - [ qy, qz, qw, -qx], - [ qz, -qy, qx, qw]] - ) - return Q - - def QMatBar(self, q): - - qw = q.qw; qx = q.qx; qy = q.qy; qz = q.qz - Q = np.array( - [[ qw, -qx, -qy, -qz], - [ qx, qw, qz, -qy], - [ qy, -qz, qw, qx], - [ qz, qy, -qx, qw]] - ) - return Q - - def calc_error(self, pa, pb, t): - - e0 = self.error_func(pa, pb, t) - Ja = np.identity(6); Jb = np.identity(6) - - rva_inv = pa.rv().inverted() - rotPaInv = rva_inv.toRotationMatrix() - - Ja[:3,:3] = -rotPaInv - Jb[:3,:3] = rotPaInv - - dRux, dRuy, dRuz = self.dR_dRV(rva_inv) - - cvec = np.array([[pb.x - pa.x],[pb.y - pa.y],[pb.z - pa.z]]) - - Ja[0:3,3:4] = -dRux @ cvec - Ja[0:3,4:5] = -dRuy @ cvec - Ja[0:3,5:6] = -dRuz @ cvec - - # rotation part: qdiff = qc-1 * qa-1 * qb - qainv = rva_inv.toQuaternion() - qcinv = t.rv().inverted().toQuaternion() - qb = pb.rv().toQuaternion() - qinvca = qcinv.quat_mult(qainv, out = 'Quaternion') - qdiff = qinvca.quat_mult(qb, out = 'Quaternion') - - Ja[3:6,3:6] = -self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMatBar(qb) @ self.dQuat_dRV(rva_inv) - Jb[3:6,3:6] = self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMat(qainv) @ self.dQuat_dRV(pb.rv()) - - return e0, Ja, Jb - -class Quaternion: - - def __init__(self, qw, qx, qy, qz): - self.qw = qw; self.qx = qx; self.qy = qy; self.qz = qz - - def conjugate(self): - return Quaternion(self.qw, -self.qx, -self.qy, -self.qz) - - def to_numpy(self): - return np.array([self.qw, self.qx, self.qy, self.qz]).reshape(4,1) - - def quat_mult(self, q, out='np'): - v = np.array([self.qx, self.qy, self.qz]).reshape(3, 1) - sum_term = np.zeros([4,4]) - sum_term[0,1:] = -v[:,0] - sum_term[1:, 0] = v[:,0] - sum_term[1:, 1:] = skew_symmetric(v) - sigma = self.qw * np.eye(4) + sum_term - q_new = sigma @ q.to_numpy() - if out == 'np': - return q_new - elif out == 'Quaternion': - q_obj = Quaternion(*q_new) - return q_obj - - -class RotVec: - - def __init__(self, ax=0., ay=0., az=0., quaternion=None): - if quaternion is None: - self.ax = ax; self.ay = ay; self.az = az - else: - x = quaternion.qx; y = quaternion.qy; z = quaternion.qz - norm_im = np.sqrt(x**2 + y**2 + z**2) - if (norm_im < 1e-7): - self.ax = 2*x; self.ay = 2*y; self.az = 2*z - else: - th = 2 * np.arctan2(norm_im, quaternion.qw) - th = self.pi2pi(th) - self.ax = x / norm_im * th - self.ay = y / norm_im * th - self.az = z / norm_im * th - - def inverted(self): - - return RotVec(-self.ax, -self.ay, -self.az) - - def toRotationMatrix(self): - - q = self.toQuaternion() - q_vec = np.array([q.qx, q.qy, q.qz]).reshape(3,1) - qw = q.qw - mat = (qw**2 - q_vec.T @ q_vec) * np.eye(3) + \ - 2 * q_vec @ q_vec.T - 2 * qw * skew_symmetric(q_vec.reshape(-1,)) - return mat.T - - def toQuaternion(self): - - v = np.sqrt(self.ax**2 + self.ay**2 + self.az**2) - if (v < 1e-6): - return Quaternion(1, 0, 0, 0) - else: - return Quaternion(np.cos(v/2), np.sin(v/2)*self.ax/v, - np.sin(v/2)*self.ay/v, np.sin(v/2)*self.az/v) - - def pi2pi(self, rad): - - val = np.fmod(rad, 2.0 * np.pi) - if val > np.pi: - val -= 2.0 * np.pi - elif val < -np.pi: - val += 2.0 * np.pi - - return val - - -class TripletList: - - def __init__(self): - self.row = [] - self.col = [] - self.data = [] - - def push_back(self, irow, icol, idata): - self.row.append(irow) - self.col.append(icol) - self.data.append(idata) - -class Pose3D: - - def __init__(self, x, y, z, qw, qx, qy, qz): - self.x = x; self.y = y; self.z = z - self.qw = qw; self.qx = qx; self.qy = qy; self.qz = qz - - def pos(self): - v = np.array([self.x, self.y, self.z]).reshape(3,1) - return v - - def rv(self): - q = Quaternion(self.qw, self.qx, self.qy, self.qz) - return RotVec(quaternion = q) - - def ominus(self, base): - t = base.rv().toRotationMatrix().T @ (self.pos() - base.pos()) - q = base.rv().toQuaternion().conjugate().quat_mult(self.rv().toQuaternion(), out = 'Quaternion') - return Pose3D(t[0][0], t[1][0], t[2][0], q.qw, q.qx, q.qy, q.qz) - - -class Constrant3D: - - def __init__(self, id1, id2, t, info_mat): - self.id1 = id1 - self.id2 = id2 - self.t = t - self.info_mat = info_mat - -def plot_nodes(nodes, ax, color ="-r", label = ""): - - x, y, z = [], [], [] - for n in nodes: - x.append(n.x); y.append(n.y); z.append(n.z) - ax.plot(x, y, z, color, label=label) - -def load_data(fname): - - nodes, consts = [], [] - - for line in open(fname): - sline = line.split() - tag = sline[0] - - if tag == "VERTEX_SE3:QUAT": - #data_id = int(sline[1]) # unused - x = float(sline[2]) - y = float(sline[3]) - z = float(sline[4]) - qx = float(sline[5]) - qy = float(sline[6]) - qz = float(sline[7]) - qw = float(sline[8]) - - nodes.append(Pose3D(x, y, z, qw, qx, qy, qz)) - elif tag == "EDGE_SE3:QUAT": - id1 = int(sline[1]) - id2 = int(sline[2]) - x = float(sline[3]) - y = float(sline[4]) - z = float(sline[5]) - qx = float(sline[6]) - qy = float(sline[7]) - qz = float(sline[8]) - qw = float(sline[9]) - c1 = float(sline[10]) - c2 = float(sline[11]) - c3 = float(sline[12]) - c4 = float(sline[13]) - c5 = float(sline[14]) - c6 = float(sline[15]) - c7 = float(sline[16]) - c8 = float(sline[17]) - c9 = float(sline[18]) - c10 = float(sline[19]) - c11 = float(sline[20]) - c12 = float(sline[21]) - c13 = float(sline[22]) - c14 = float(sline[23]) - c15 = float(sline[24]) - c16 = float(sline[25]) - c17 = float(sline[26]) - c18 = float(sline[27]) - c19 = float(sline[28]) - c20 = float(sline[29]) - c21 = float(sline[30]) - t = Pose3D(x, y, z, qw, qx, qy, qz) - info_mat = np.array([[c1, c2, c3, c4, c5, c6], - [c2, c7, c8, c9, c10, c11], - [c3, c8, c12, c13, c14, c15], - [c4, c9, c13, c16, c17, c18], - [c5, c10, c14, c17, c19, c20], - [c6, c11, c15, c18, c20, c21] - ]) - consts.append(Constrant3D(id1, id2, t, info_mat)) - - print("n_nodes:", len(nodes)) - print("n_consts:", len(consts)) - - return nodes, consts - - - -def main(): - - print("start!!") - - fnames = ["parking-garage.g2o"] - - max_iter = 20 - min_iter = 3 - - # parameter setting - optimizer = Optimizer3D() - optimizer.p_lambda = 1e-6 - optimizer.verbose = True - optimizer.animation = True - - for f in fnames: - print(f) - - nodes, consts = load_data(f) - - start = time.time() - final_nodes = optimizer.optimize_path(nodes, consts, max_iter, min_iter) - print("elapsed_time", time.time() - start, "sec") - - # plot - plt.cla() - est_traj_fig = plt.figure() - ax = est_traj_fig.add_subplot(111, projection='3d') - plot_nodes(nodes, ax, color="-b", label="before") - plot_nodes(final_nodes, ax, label="after") - plt.show() - - print("done!!") - -if __name__ == '__main__': - main() From 01a5bcb419cbe3db2377e4b348e24dc76a79e200 Mon Sep 17 00:00:00 2001 From: Ryohei Sasaki Date: Sat, 7 Sep 2019 14:35:09 +0900 Subject: [PATCH 048/940] Fix function dRV_dQuat of class Optimizer3D --- .../pose_optimization_slam_3d.py | 20 ++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py b/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py index e5cf6ac62d..105201f8a2 100644 --- a/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py +++ b/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py @@ -235,22 +235,28 @@ def dR_dRV(self, rv): duy = dRdqw * dqdu[0,1] + dRdqx * dqdu[1, 1] + dRdqy * dqdu[2, 1] + dRdqz * dqdu[3, 1] duz = dRdqw * dqdu[0,2] + dRdqx * dqdu[1, 2] + dRdqy * dqdu[2, 2] + dRdqz * dqdu[3, 2] return dux, duy, duz - + def dRV_dQuat(self, q): + + qw = q.qw[0] + qx = q.qx[0] + qy = q.qy[0] + qz = q.qz[0] - if 1 - q.qw**2 < 1e-7: + if 1 - qw**2 < 1e-7: ret = np.array( [[ 0.0, 2.0, 0.0, 0.0], [ 0.0, 0.0, 2.0, 0.0], [ 0.0, 0.0, 0.0, 2.0]] ) return ret - c = 1/(1 - q.qw**2) - d = np.arccos(q.qw)/(np.sqrt(1-q.qw**2)) + + c = 1/(1 - qw**2) + d = np.arccos(qw)/(np.sqrt(1-qw**2)) ret = 2.0 * np.array( - [[ c*q.qx*(d*q.qw-1), d, 0.0, 0.0], - [ c*q.qy*(d*q.qw-1), 0.0, d, 0.0], - [ c*q.qz*(d*q.qw-1), 0.0, 0.0, d]] + [[ c*qx*(d*qw-1), d, 0.0, 0.0], + [ c*qy*(d*qw-1), 0.0, d, 0.0], + [ c*qz*(d*qw-1), 0.0, 0.0, d]] ) return ret From d147df5ba77b7898f1aa8b6f68a3ae2abe0c8dbe Mon Sep 17 00:00:00 2001 From: Ryohei Sasaki Date: Sat, 7 Sep 2019 15:02:36 +0900 Subject: [PATCH 049/940] Make 3D graph correctly scaled --- .../pose_optimization_slam_3d.py | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py b/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py index 105201f8a2..c9b72e88a8 100644 --- a/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py +++ b/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py @@ -434,6 +434,16 @@ def plot_nodes(nodes, ax, color ="-r", label = ""): x, y, z = [], [], [] for n in nodes: x.append(n.x); y.append(n.y); z.append(n.z) + x = np.array(x) + y = np.array(y) + z = np.array(z) + max_range = np.array([x.max()-x.min(), y.max()-y.min(), z.max()-z.min()]).max() / 2.0 + mid_x = (x.max()+x.min()) * 0.5 + mid_y = (y.max()+y.min()) * 0.5 + mid_z = (z.max()+z.min()) * 0.5 + ax.set_xlim(mid_x - max_range, mid_x + max_range) + ax.set_ylim(mid_y - max_range, mid_y + max_range) + ax.set_zlim(mid_z - max_range, mid_z + max_range) ax.plot(x, y, z, color, label=label) def load_data(fname): From 7c1a1ddd66eca65c6e1b7eb3ddec555cd7c02066 Mon Sep 17 00:00:00 2001 From: Zhao Zihe <2809075376@qq.com> Date: Sat, 7 Sep 2019 16:28:06 +0800 Subject: [PATCH 050/940] Update motion_model.py fix the problem of the unsafe type in the `scipy.interpolate` --- .../ModelPredictiveTrajectoryGenerator/motion_model.py | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py index bb66d1fb54..f6c78d3bc1 100644 --- a/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py +++ b/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py @@ -36,6 +36,11 @@ def generate_trajectory(s, km, kf, k0): n = s / ds time = s / v # [s] + + if isinstance(time, type(np.array([]))): time = time[0] + if isinstance(km, type(np.array([]))): km = km[0] + if isinstance(kf, type(np.array([]))): kf = kf[0] + tk = np.array([0.0, time / 2.0, time]) kk = np.array([k0, km, kf]) t = np.arange(0.0, time, time / n) @@ -62,6 +67,11 @@ def generate_last_state(s, km, kf, k0): n = s / ds time = s / v # [s] + + if isinstance(time, type(np.array([]))): time = time[0] + if isinstance(km, type(np.array([]))): km = km[0] + if isinstance(kf, type(np.array([]))): kf = kf[0] + tk = np.array([0.0, time / 2.0, time]) kk = np.array([k0, km, kf]) t = np.arange(0.0, time, time / n) From ec2a275f6e546dd229f7c97a1baeb37f3cb07f6f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 7 Sep 2019 22:58:05 +0900 Subject: [PATCH 051/940] release PoseOptimizationSLAM3D --- .../histogram_filter/histogram_filter.py | 26 +- README.md | 15 +- SLAM/PoseOptimizationSLAM3D/README.md | 10 +- .../PoseOptimizationSLAM3D/data_downloader.py | 9 +- .../pose_optimization_slam_3d.py | 390 ++++++++++-------- 5 files changed, 245 insertions(+), 205 deletions(-) diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index 9c1cb3e524..bdfbb13fa7 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -38,7 +38,6 @@ NOISE_RANGE = 2.0 # [m] 1σ range noise parameter NOISE_SPEED = 0.5 # [m/s] 1σ speed noise parameter - show_animation = True @@ -66,11 +65,10 @@ def histogram_filter_localization(grid_map, u, z, yaw): def calc_gaussian_observation_pdf(gmap, z, iz, ix, iy, std): - # predicted range x = ix * gmap.xy_reso + gmap.minx y = iy * gmap.xy_reso + gmap.miny - d = math.sqrt((x - z[iz, 1])**2 + (y - z[iz, 2])**2) + d = math.sqrt((x - z[iz, 1]) ** 2 + (y - z[iz, 2]) ** 2) # likelihood pdf = (1.0 - norm.cdf(abs(d - z[iz, 0]), 0.0, std)) @@ -79,7 +77,6 @@ def calc_gaussian_observation_pdf(gmap, z, iz, ix, iy, std): def observation_update(gmap, z, std): - for iz in range(z.shape[0]): for ix in range(gmap.xw): for iy in range(gmap.yw): @@ -99,7 +96,6 @@ def calc_input(): def motion_model(x, u): - F = np.array([[1.0, 0, 0, 0], [0, 1.0, 0, 0], [0, 0, 1.0, 0], @@ -122,7 +118,6 @@ def draw_heat_map(data, mx, my): def observation(xTrue, u, RFID): - xTrue = motion_model(xTrue, u) z = np.zeros((0, 3)) @@ -131,7 +126,7 @@ def observation(xTrue, u, RFID): dx = xTrue[0, 0] - RFID[i, 0] dy = xTrue[1, 0] - RFID[i, 1] - d = math.sqrt(dx**2 + dy**2) + d = math.sqrt(dx ** 2 + dy ** 2) if d <= MAX_RANGE: # add noise to range observation dn = d + np.random.randn() * NOISE_RANGE @@ -146,7 +141,6 @@ def observation(xTrue, u, RFID): def normalize_probability(gmap): - sump = sum([sum(igmap) for igmap in gmap.data]) for ix in range(gmap.xw): @@ -214,11 +208,11 @@ def calc_grid_index(gmap): def main(): print(__file__ + " start!!") - # RFID positions [x, y] - RFID = np.array([[10.0, 0.0], - [10.0, 10.0], - [0.0, 15.0], - [-5.0, 20.0]]) + # RF_ID positions [x, y] + RF_ID = np.array([[10.0, 0.0], + [10.0, 10.0], + [0.0, 15.0], + [-5.0, 20.0]]) time = 0.0 @@ -233,7 +227,7 @@ def main(): u = calc_input() yaw = xTrue[2, 0] # Orientation is known - xTrue, z, ud = observation(xTrue, u, RFID) + xTrue, z, ud = observation(xTrue, u, RF_ID) grid_map = histogram_filter_localization(grid_map, u, z, yaw) @@ -241,10 +235,10 @@ def main(): plt.cla() draw_heat_map(grid_map.data, mx, my) plt.plot(xTrue[0, :], xTrue[1, :], "xr") - plt.plot(RFID[:, 0], RFID[:, 1], ".k") + plt.plot(RF_ID[:, 0], RF_ID[:, 1], ".k") for i in range(z.shape[0]): plt.plot([xTrue[0, :], z[i, 1]], [ - xTrue[1, :], z[i, 2]], "-k") + xTrue[1, :], z[i, 2]], "-k") plt.title("Time[s]:" + str(time)[0: 4]) plt.pause(0.1) diff --git a/README.md b/README.md index e8bf0d297d..d2614f0f9c 100644 --- a/README.md +++ b/README.md @@ -609,19 +609,6 @@ This is a list: [Users comments](https://github.com/AtsushiSakai/PythonRobotics/ - [Alexis Paques](https://github.com/AlexisTM) - - - - - - - - - - - - - - +- [Ryohei Sasaki](https://github.com/rsasaki0109) diff --git a/SLAM/PoseOptimizationSLAM3D/README.md b/SLAM/PoseOptimizationSLAM3D/README.md index ac95c7e206..396a629735 100644 --- a/SLAM/PoseOptimizationSLAM3D/README.md +++ b/SLAM/PoseOptimizationSLAM3D/README.md @@ -15,7 +15,11 @@ python pose_optimization_slam_3d.py ~~~ ## Reference -[A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) -[GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) -[GitHub \- AtsushiSakai/PythonRobotics +- [A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) + +- [GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) + +- [GitHub \- AtsushiSakai/PythonRobotics /SLAM/PoseOptimizationSLAM](https://github.com/AtsushiSakai/PythonRobotics/tree/master/SLAM/PoseOptimizationSLAM) + +- [リー代数による3次元ポーズ調整\(Pose Adjustment\)\[PythonRobotics\]\[SLAM\] \- Qiita](https://qiita.com/saitosasaki/items/a0540cba994f08bf5e16#comment-3e6588e6b096cc2567d8) diff --git a/SLAM/PoseOptimizationSLAM3D/data_downloader.py b/SLAM/PoseOptimizationSLAM3D/data_downloader.py index 8dea252640..a0c04fd1ab 100644 --- a/SLAM/PoseOptimizationSLAM3D/data_downloader.py +++ b/SLAM/PoseOptimizationSLAM3D/data_downloader.py @@ -6,16 +6,21 @@ """ - import subprocess + + def main(): print("start!!") cmd = "wget https://www.dropbox.com/s/zu23p8d522qccor/parking-garage.g2o?dl=0 -O parking-garage.g2o -nc" subprocess.call(cmd, shell=True) + cmd = "wget http://www.furo.org/irie/datasets/torus3d_guess.g2o -nc" + subprocess.call(cmd, shell=True) + cmd = "wget http://www.furo.org/irie/datasets/sphere2200_guess.g2o -nc" + subprocess.call(cmd, shell=True) print("done!!") if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py b/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py index c9b72e88a8..0f39b22f3c 100644 --- a/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py +++ b/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py @@ -1,40 +1,45 @@ """ 3D (x, y, z, qw, qx, qy, qz) pose optimization SLAM + author: Ryohei Sasaki(@rsasaki0109) + Ref: + - [A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) + - [GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) + - [GitHub \- AtsushiSakai/PythonRobotics /SLAM/PoseOptimizationSLAM](https://github.com/AtsushiSakai/PythonRobotics/blob/master/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py) + + """ +import os import sys import time + +import matplotlib.pyplot as plt import numpy as np from scipy import sparse from scipy.sparse import linalg -import matplotlib.pyplot as plt -from mpl_toolkits.mplot3d import Axes3D -est_traj_fig = plt.figure() -ax = est_traj_fig.add_subplot(111, projection='3d') def skew_symmetric(v): - return np.array( [[0, -v[2], v[1]], [v[2], 0, -v[0]], [-v[1], v[0], 0]] ) -def robust_coeff(squared_error, delta): - if (squared_error < 0): +def robust_coeff(squared_error, delta): + if squared_error < 0: return 0 sqre = np.sqrt(squared_error) - if (sqre < delta): - return 1 # no effect - return delta / sqre # linear + if sqre < delta: + return 1 # no effect + return delta / sqre # linear class Optimizer3D: @@ -90,14 +95,15 @@ def optimize_path_one_step(self, graph_nodes, constraints): for con in constraints: ida = con.id1 idb = con.id2 - assert 0 <= ida and ida < numnodes, "ida is invalid" - assert 0 <= idb and idb < numnodes, "idb is invalid" + assert 0 <= ida < numnodes, "ida is invalid" + assert 0 <= idb < numnodes, "idb is invalid" pa = graph_nodes[ida] pb = graph_nodes[idb] r, Ja, Jb = self.calc_error( pa, pb, con.t) - - info_mat = con.info_mat * robust_coeff(r.reshape(self.dim,1).T @ con.info_mat @ r.reshape(self.dim,1), self.robust_delta) + + info_mat = con.info_mat * robust_coeff(r.reshape(self.dim, 1).T @ con.info_mat @ r.reshape(self.dim, 1), + self.robust_delta) trJaInfo = Ja.transpose() @ info_mat trJaInfoJa = trJaInfo @ Ja @@ -115,10 +121,10 @@ def optimize_path_one_step(self, graph_nodes, constraints): ida * self.dim + k, idb * self.dim + m, trJaInfoJb[k, m]) tripletList.push_back( idb * self.dim + k, ida * self.dim + m, trJaInfoJb[m, k]) - - bf[ida * self.dim: (ida + 1) * self.dim ] += trJaInfo @ r - bf[idb * self.dim: (idb + 1) * self.dim ] += trJbInfo @ r - + + bf[ida * self.dim: (ida + 1) * self.dim] += trJaInfo @ r + bf[idb * self.dim: (idb + 1) * self.dim] += trJbInfo @ r + for k in indlist: tripletList.push_back(k, k, self.init_w) @@ -133,18 +139,17 @@ def optimize_path_one_step(self, graph_nodes, constraints): out_nodes = [] for i in range(len(graph_nodes)): - u_i = i * self.dim - + q_before = Quaternion(graph_nodes[i].qw, graph_nodes[i].qx, graph_nodes[i].qy, graph_nodes[i].qz) - rv_before = RotVec(quaternion = q_before) - rv_after = RotVec(ax = rv_before.ax + x[u_i + 3], ay = rv_before.ay + x[u_i + 4], az = rv_before.az + x[u_i + 5]) - q_after = rv_after.toQuaternion() + rv_before = RotVec(quaternion=q_before) + rv_after = RotVec(ax=rv_before.ax + x[u_i + 3], ay=rv_before.ay + x[u_i + 4], az=rv_before.az + x[u_i + 5]) + q_after = rv_after.to_quaternion() pos = Pose3D( - graph_nodes[i].x + x[u_i], - graph_nodes[i].y + x[u_i + 1], - graph_nodes[i].z + x[u_i + 2], + graph_nodes[i].x + x[u_i], + graph_nodes[i].y + x[u_i + 1], + graph_nodes[i].z + x[u_i + 2], q_after.qw, q_after.qx, q_after.qy, @@ -161,16 +166,18 @@ def calc_global_cost(self, nodes, constraints): cost = 0.0 for c in constraints: diff = self.error_func(nodes[c.id1], nodes[c.id2], c.t) - info_mat = c.info_mat * robust_coeff(diff.reshape(self.dim,1).T @ c.info_mat @ diff.reshape(self.dim,1), self.robust_delta) + info_mat = c.info_mat * robust_coeff(diff.reshape(self.dim, 1).T @ c.info_mat @ diff.reshape(self.dim, 1), + self.robust_delta) cost += diff.transpose() @ info_mat @ diff return cost - def error_func(self, pa, pb, t): + @staticmethod + def error_func(pa, pb, t): ba = pb.ominus(pa) - q = t.rv().toQuaternion().conjugate().quat_mult(ba.rv().toQuaternion(), out = 'Quaternion') - drv = RotVec(quaternion = q) + q = t.rv().to_quaternion().conjugate().quat_mult(ba.rv().to_quaternion(), out='Quaternion') + drv = RotVec(quaternion=q) error = np.array([ba.x - t.x, ba.y - t.y, ba.z - t.z, @@ -179,156 +186,177 @@ def error_func(self, pa, pb, t): drv.az[0]]) return error - def dQuat_dRV(self, rv): - - u1 = rv.ax; u2 = rv.ay; u3 = rv.az - v = np.sqrt(u1**2 + u2**2 + u3**2) + @staticmethod + def dQuat_dRV(rv): + u1 = rv.ax + u2 = rv.ay + u3 = rv.az + v = np.sqrt(u1 ** 2 + u2 ** 2 + u3 ** 2) if v < 1e-6: dqu = 0.25 * np.array( - [[ -u1, -u2, -u3], - [ 2.0, 0.0, 0.0], - [ 0.0, 2.0, 0.0], - [ 0.0, 0.0, 2.0]] + [[-u1, -u2, -u3], + [2.0, 0.0, 0.0], + [0.0, 2.0, 0.0], + [0.0, 0.0, 2.0]] ) return dqu - vd = v*2 - v2 = v**2 - v3 = v**3 + vd = v * 2 + v2 = v ** 2 + v3 = v ** 3 - S = np.sin(v/2.0); C = np.cos(v/2.0) + S = np.sin(v / 2.0) + C = np.cos(v / 2.0) dqu = np.array( - [[ -u1 * S/vd , -u2*S/vd , -u3*S/vd], - [ S/v + u1*u1*C/(2*v2) - u1*u1*S/v3, u1*u2*(C/(2*v2)-S/v3) , u1*u3*(C/(2*v2)-S/v3)], - [ u1*u2*(C/(2*v2)-S/v3) , S/v+u2*u2*C/(2*v2)-u2*u2*S/v3, u2*u3*(C/(2*v2)-S/v3)], - [ u1*u3*(C/(2*v2)-S/v3) , u2*u3*(C/(2*v2)-S/v3) , S/v+u3*u3*C/(2*v2)-u3*u3*S/v3]] - ) + [[-u1 * S / vd, -u2 * S / vd, -u3 * S / vd], + [S / v + u1 * u1 * C / (2 * v2) - u1 * u1 * S / v3, u1 * u2 * (C / (2 * v2) - S / v3), + u1 * u3 * (C / (2 * v2) - S / v3)], + [u1 * u2 * (C / (2 * v2) - S / v3), S / v + u2 * u2 * C / (2 * v2) - u2 * u2 * S / v3, + u2 * u3 * (C / (2 * v2) - S / v3)], + [u1 * u3 * (C / (2 * v2) - S / v3), u2 * u3 * (C / (2 * v2) - S / v3), + S / v + u3 * u3 * C / (2 * v2) - u3 * u3 * S / v3]] + ) return dqu def dR_dRV(self, rv): - q = rv.toQuaternion() - qw = q.qw;qx = q.qx; qy = q.qy;qz = q.qz + q = rv.to_quaternion() + qw = q.qw + qx = q.qx + qy = q.qy + qz = q.qz dRdqw = 2 * np.array( - [[ qw, -qz, qy], - [ qz, qw, -qx], - [-qy, qx, qw]] + [[qw, -qz, qy], + [qz, qw, -qx], + [-qy, qx, qw]] ) dRdqx = 2 * np.array( - [[ qx, qy, qz], - [ qy, -qx, -qw], - [ qz, qw, -qx]] + [[qx, qy, qz], + [qy, -qx, -qw], + [qz, qw, -qx]] ) dRdqy = 2 * np.array( - [[-qy, qx, qw], - [ qx, qy, qz], - [-qw, qz, -qy]] + [[-qy, qx, qw], + [qx, qy, qz], + [-qw, qz, -qy]] ) dRdqz = 2 * np.array( - [[-qz, -qw, qx], - [ qw, -qz, -qy], - [ qz, qy, qz]] + [[-qz, -qw, qx], + [qw, -qz, -qy], + [qz, qy, qz]] ) dqdu = self.dQuat_dRV(rv) - dux = dRdqw * dqdu[0,0] + dRdqx * dqdu[1, 0] + dRdqy * dqdu[2, 0] + dRdqz * dqdu[3, 0] - duy = dRdqw * dqdu[0,1] + dRdqx * dqdu[1, 1] + dRdqy * dqdu[2, 1] + dRdqz * dqdu[3, 1] - duz = dRdqw * dqdu[0,2] + dRdqx * dqdu[1, 2] + dRdqy * dqdu[2, 2] + dRdqz * dqdu[3, 2] + dux = dRdqw * dqdu[0, 0] + dRdqx * dqdu[1, 0] + dRdqy * dqdu[2, 0] + dRdqz * dqdu[3, 0] + duy = dRdqw * dqdu[0, 1] + dRdqx * dqdu[1, 1] + dRdqy * dqdu[2, 1] + dRdqz * dqdu[3, 1] + duz = dRdqw * dqdu[0, 2] + dRdqx * dqdu[1, 2] + dRdqy * dqdu[2, 2] + dRdqz * dqdu[3, 2] return dux, duy, duz - - def dRV_dQuat(self, q): - + + @staticmethod + def dRV_dQuat(q): + qw = q.qw[0] qx = q.qx[0] qy = q.qy[0] qz = q.qz[0] - if 1 - qw**2 < 1e-7: + if 1 - qw ** 2 < 1e-7: ret = np.array( - [[ 0.0, 2.0, 0.0, 0.0], - [ 0.0, 0.0, 2.0, 0.0], - [ 0.0, 0.0, 0.0, 2.0]] + [[0.0, 2.0, 0.0, 0.0], + [0.0, 0.0, 2.0, 0.0], + [0.0, 0.0, 0.0, 2.0]] ) return ret - - c = 1/(1 - qw**2) - d = np.arccos(qw)/(np.sqrt(1-qw**2)) + + c = 1 / (1 - qw ** 2) + d = np.arccos(qw) / (np.sqrt(1 - qw ** 2)) ret = 2.0 * np.array( - [[ c*qx*(d*qw-1), d, 0.0, 0.0], - [ c*qy*(d*qw-1), 0.0, d, 0.0], - [ c*qz*(d*qw-1), 0.0, 0.0, d]] - ) + [[c * qx * (d * qw - 1), d, 0.0, 0.0], + [c * qy * (d * qw - 1), 0.0, d, 0.0], + [c * qz * (d * qw - 1), 0.0, 0.0, d]] + ) return ret def QMat(self, q): - qw = q.qw; qx = q.qx; qy = q.qy; qz = q.qz + qw = q.qw + qx = q.qx + qy = q.qy + qz = q.qz Q = np.array( - [[ qw, -qx, -qy, -qz], - [ qx, qw, -qz, qy], - [ qy, qz, qw, -qx], - [ qz, -qy, qx, qw]] - ) + [[qw, -qx, -qy, -qz], + [qx, qw, -qz, qy], + [qy, qz, qw, -qx], + [qz, -qy, qx, qw]] + ) return Q def QMatBar(self, q): - qw = q.qw; qx = q.qx; qy = q.qy; qz = q.qz + qw = q.qw + qx = q.qx + qy = q.qy + qz = q.qz Q = np.array( - [[ qw, -qx, -qy, -qz], - [ qx, qw, qz, -qy], - [ qy, -qz, qw, qx], - [ qz, qy, -qx, qw]] - ) + [[qw, -qx, -qy, -qz], + [qx, qw, qz, -qy], + [qy, -qz, qw, qx], + [qz, qy, -qx, qw]] + ) return Q def calc_error(self, pa, pb, t): e0 = self.error_func(pa, pb, t) - Ja = np.identity(6); Jb = np.identity(6) + Ja = np.identity(6) + Jb = np.identity(6) rva_inv = pa.rv().inverted() - rotPaInv = rva_inv.toRotationMatrix() + rotPaInv = rva_inv.to_rotation_matrix() - Ja[:3,:3] = -rotPaInv - Jb[:3,:3] = rotPaInv + Ja[:3, :3] = -rotPaInv + Jb[:3, :3] = rotPaInv dRux, dRuy, dRuz = self.dR_dRV(rva_inv) - cvec = np.array([[pb.x - pa.x],[pb.y - pa.y],[pb.z - pa.z]]) + cvec = np.array([[pb.x - pa.x], [pb.y - pa.y], [pb.z - pa.z]]) - Ja[0:3,3:4] = -dRux @ cvec - Ja[0:3,4:5] = -dRuy @ cvec - Ja[0:3,5:6] = -dRuz @ cvec + Ja[0:3, 3:4] = -dRux @ cvec + Ja[0:3, 4:5] = -dRuy @ cvec + Ja[0:3, 5:6] = -dRuz @ cvec # rotation part: qdiff = qc-1 * qa-1 * qb - qainv = rva_inv.toQuaternion() - qcinv = t.rv().inverted().toQuaternion() - qb = pb.rv().toQuaternion() - qinvca = qcinv.quat_mult(qainv, out = 'Quaternion') - qdiff = qinvca.quat_mult(qb, out = 'Quaternion') + qainv = rva_inv.to_quaternion() + qcinv = t.rv().inverted().to_quaternion() + qb = pb.rv().to_quaternion() + qinvca = qcinv.quat_mult(qainv, out='Quaternion') + qdiff = qinvca.quat_mult(qb, out='Quaternion') - Ja[3:6,3:6] = -self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMatBar(qb) @ self.dQuat_dRV(rva_inv) - Jb[3:6,3:6] = self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMat(qainv) @ self.dQuat_dRV(pb.rv()) + Ja[3:6, 3:6] = -self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMatBar(qb) @ self.dQuat_dRV(rva_inv) + Jb[3:6, 3:6] = self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMat(qainv) @ self.dQuat_dRV(pb.rv()) return e0, Ja, Jb + class Quaternion: def __init__(self, qw, qx, qy, qz): - self.qw = qw; self.qx = qx; self.qy = qy; self.qz = qz - + self.qw = qw + self.qx = qx + self.qy = qy + self.qz = qz + def conjugate(self): return Quaternion(self.qw, -self.qx, -self.qy, -self.qz) - + def to_numpy(self): - return np.array([self.qw, self.qx, self.qy, self.qz]).reshape(4,1) + return np.array([self.qw, self.qx, self.qy, self.qz]).reshape(4, 1) def quat_mult(self, q, out='np'): v = np.array([self.qx, self.qy, self.qz]).reshape(3, 1) - sum_term = np.zeros([4,4]) - sum_term[0,1:] = -v[:,0] - sum_term[1:, 0] = v[:,0] + sum_term = np.zeros([4, 4]) + sum_term[0, 1:] = -v[:, 0] + sum_term[1:, 0] = v[:, 0] sum_term[1:, 1:] = skew_symmetric(v) sigma = self.qw * np.eye(4) + sum_term q_new = sigma @ q.to_numpy() @@ -337,18 +365,24 @@ def quat_mult(self, q, out='np'): elif out == 'Quaternion': q_obj = Quaternion(*q_new) return q_obj - + class RotVec: def __init__(self, ax=0., ay=0., az=0., quaternion=None): if quaternion is None: - self.ax = ax; self.ay = ay; self.az = az + self.ax = ax + self.ay = ay + self.az = az else: - x = quaternion.qx; y = quaternion.qy; z = quaternion.qz - norm_im = np.sqrt(x**2 + y**2 + z**2) - if (norm_im < 1e-7): - self.ax = 2*x; self.ay = 2*y; self.az = 2*z + x = quaternion.qx + y = quaternion.qy + z = quaternion.qz + norm_im = np.sqrt(x ** 2 + y ** 2 + z ** 2) + if norm_im < 1e-7: + self.ax = 2 * x + self.ay = 2 * y + self.az = 2 * z else: th = 2 * np.arctan2(norm_im, quaternion.qw) th = self.pi2pi(th) @@ -360,25 +394,26 @@ def inverted(self): return RotVec(-self.ax, -self.ay, -self.az) - def toRotationMatrix(self): + def to_rotation_matrix(self): - q = self.toQuaternion() - q_vec = np.array([q.qx, q.qy, q.qz]).reshape(3,1) + q = self.to_quaternion() + q_vec = np.array([q.qx, q.qy, q.qz]).reshape(3, 1) qw = q.qw - mat = (qw**2 - q_vec.T @ q_vec) * np.eye(3) + \ - 2 * q_vec @ q_vec.T - 2 * qw * skew_symmetric(q_vec.reshape(-1,)) + mat = (qw ** 2 - q_vec.T @ q_vec) * np.eye(3) \ + + 2 * q_vec @ q_vec.T - 2 * qw * skew_symmetric(q_vec.reshape(-1, )) return mat.T - - def toQuaternion(self): - v = np.sqrt(self.ax**2 + self.ay**2 + self.az**2) + def to_quaternion(self): + + v = np.sqrt(self.ax ** 2 + self.ay ** 2 + self.az ** 2) if (v < 1e-6): return Quaternion(1, 0, 0, 0) else: - return Quaternion(np.cos(v/2), np.sin(v/2)*self.ax/v, - np.sin(v/2)*self.ay/v, np.sin(v/2)*self.az/v) + return Quaternion(np.cos(v / 2), np.sin(v / 2) * self.ax / v, + np.sin(v / 2) * self.ay / v, np.sin(v / 2) * self.az / v) - def pi2pi(self, rad): + @staticmethod + def pi2pi(rad): val = np.fmod(rad, 2.0 * np.pi) if val > np.pi: @@ -387,7 +422,7 @@ def pi2pi(self, rad): val += 2.0 * np.pi return val - + class TripletList: @@ -401,27 +436,33 @@ def push_back(self, irow, icol, idata): self.col.append(icol) self.data.append(idata) + class Pose3D: def __init__(self, x, y, z, qw, qx, qy, qz): - self.x = x; self.y = y; self.z = z - self.qw = qw; self.qx = qx; self.qy = qy; self.qz = qz - + self.x = x + self.y = y + self.z = z + self.qw = qw + self.qx = qx + self.qy = qy + self.qz = qz + def pos(self): - v = np.array([self.x, self.y, self.z]).reshape(3,1) + v = np.array([self.x, self.y, self.z]).reshape(3, 1) return v - + def rv(self): q = Quaternion(self.qw, self.qx, self.qy, self.qz) - return RotVec(quaternion = q) + return RotVec(quaternion=q) def ominus(self, base): - t = base.rv().toRotationMatrix().T @ (self.pos() - base.pos()) - q = base.rv().toQuaternion().conjugate().quat_mult(self.rv().toQuaternion(), out = 'Quaternion') + t = base.rv().to_rotation_matrix().T @ (self.pos() - base.pos()) + q = base.rv().to_quaternion().conjugate().quat_mult(self.rv().to_quaternion(), out='Quaternion') return Pose3D(t[0][0], t[1][0], t[2][0], q.qw, q.qx, q.qy, q.qz) -class Constrant3D: +class Constraint3D: def __init__(self, id1, id2, t, info_mat): self.id1 = id1 @@ -429,25 +470,28 @@ def __init__(self, id1, id2, t, info_mat): self.t = t self.info_mat = info_mat -def plot_nodes(nodes, ax, color ="-r", label = ""): +def plot_nodes(nodes, ax, color="-r", label=""): x, y, z = [], [], [] for n in nodes: - x.append(n.x); y.append(n.y); z.append(n.z) + x.append(n.x) + y.append(n.y) + z.append(n.z) x = np.array(x) y = np.array(y) z = np.array(z) - max_range = np.array([x.max()-x.min(), y.max()-y.min(), z.max()-z.min()]).max() / 2.0 - mid_x = (x.max()+x.min()) * 0.5 - mid_y = (y.max()+y.min()) * 0.5 - mid_z = (z.max()+z.min()) * 0.5 + max_range = np.array([x.max() - x.min(), y.max() - y.min(), z.max() - z.min()]).max() / 2.0 + mid_x = (x.max() + x.min()) * 0.5 + mid_y = (y.max() + y.min()) * 0.5 + mid_z = (z.max() + z.min()) * 0.5 ax.set_xlim(mid_x - max_range, mid_x + max_range) ax.set_ylim(mid_y - max_range, mid_y + max_range) - ax.set_zlim(mid_z - max_range, mid_z + max_range) + ax.set_zlim(mid_z - max_range, mid_z + max_range) ax.plot(x, y, z, color, label=label) + # ax.plot(x, y, color, label=label) -def load_data(fname): +def load_data(fname): nodes, consts = [], [] for line in open(fname): @@ -455,7 +499,7 @@ def load_data(fname): tag = sline[0] if tag == "VERTEX_SE3:QUAT": - #data_id = int(sline[1]) # unused + # data_id = int(sline[1]) # unused x = float(sline[2]) y = float(sline[3]) z = float(sline[4]) @@ -463,7 +507,7 @@ def load_data(fname): qy = float(sline[6]) qz = float(sline[7]) qw = float(sline[8]) - + nodes.append(Pose3D(x, y, z, qw, qx, qy, qz)) elif tag == "EDGE_SE3:QUAT": id1 = int(sline[1]) @@ -475,15 +519,15 @@ def load_data(fname): qy = float(sline[7]) qz = float(sline[8]) qw = float(sline[9]) - c1 = float(sline[10]) - c2 = float(sline[11]) - c3 = float(sline[12]) - c4 = float(sline[13]) - c5 = float(sline[14]) - c6 = float(sline[15]) - c7 = float(sline[16]) - c8 = float(sline[17]) - c9 = float(sline[18]) + c1 = float(sline[10]) + c2 = float(sline[11]) + c3 = float(sline[12]) + c4 = float(sline[13]) + c5 = float(sline[14]) + c6 = float(sline[15]) + c7 = float(sline[16]) + c8 = float(sline[17]) + c9 = float(sline[18]) c10 = float(sline[19]) c11 = float(sline[20]) c12 = float(sline[21]) @@ -497,14 +541,14 @@ def load_data(fname): c20 = float(sline[29]) c21 = float(sline[30]) t = Pose3D(x, y, z, qw, qx, qy, qz) - info_mat = np.array([[c1, c2, c3, c4, c5, c6], - [c2, c7, c8, c9, c10, c11], - [c3, c8, c12, c13, c14, c15], - [c4, c9, c13, c16, c17, c18], + info_mat = np.array([[c1, c2, c3, c4, c5, c6], + [c2, c7, c8, c9, c10, c11], + [c3, c8, c12, c13, c14, c15], + [c4, c9, c13, c16, c17, c18], [c5, c10, c14, c17, c19, c20], [c6, c11, c15, c18, c20, c21] ]) - consts.append(Constrant3D(id1, id2, t, info_mat)) + consts.append(Constraint3D(id1, id2, t, info_mat)) print("n_nodes:", len(nodes)) print("n_consts:", len(consts)) @@ -512,22 +556,26 @@ def load_data(fname): return nodes, consts - def main(): - print("start!!") - fnames = ["parking-garage.g2o"] + dir = os.path.dirname(os.path.abspath(__file__)) - max_iter = 20 + fnames = [ + dir + "/sphere2200_guess.g2o", + dir + "/torus3d_guess.g2o", + dir + "/parking-garage.g2o", + ] + + max_iter = 10 min_iter = 3 # parameter setting optimizer = Optimizer3D() optimizer.p_lambda = 1e-6 optimizer.verbose = True - optimizer.animation = True - + optimizer.animation = False + for f in fnames: print(f) @@ -538,14 +586,16 @@ def main(): print("elapsed_time", time.time() - start, "sec") # plot - plt.cla() + plt.close("all") est_traj_fig = plt.figure() ax = est_traj_fig.add_subplot(111, projection='3d') plot_nodes(nodes, ax, color="-b", label="before") plot_nodes(final_nodes, ax, label="after") + plt.legend() plt.show() print("done!!") + if __name__ == '__main__': main() From 52d836cff8103cda64100f3df3f1156e6217fa5f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Sep 2019 09:55:22 +0900 Subject: [PATCH 052/940] add PoseOptimizationSLAM3D gif and change dir name --- README.md | 15 ++++++++++++--- .../README.md | 0 .../data_downloader.py | 0 .../pose_optimization_slam_2d.py} | 0 4 files changed, 12 insertions(+), 3 deletions(-) rename SLAM/{PoseOptimizationSLAM => PoseOptimizationSLAM2D}/README.md (100%) rename SLAM/{PoseOptimizationSLAM => PoseOptimizationSLAM2D}/data_downloader.py (100%) rename SLAM/{PoseOptimizationSLAM/pose_optimization_slam.py => PoseOptimizationSLAM2D/pose_optimization_slam_2d.py} (100%) diff --git a/README.md b/README.md index d2614f0f9c..93ede20a7e 100644 --- a/README.md +++ b/README.md @@ -249,11 +249,20 @@ Ref: - [SLAM simulations by Tim Bailey](http://www-personal.acfr.usyd.edu.au/tbailey/software/slam_simulations.htm) -## Pose Optimization SLAM +## Pose Optimization SLAM 2D + +This is a graph based 2D pose optimization SLAM example. + +![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/PoseOptimizationSLAM2D/animation.gif) + + +## Pose Optimization SLAM 3D + +This is a graph based 3D pose optimization SLAM example. + +![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/PoseOptimizationSLAM3D/animation.gif) -This is a graph based pose optimization SLAM example. -![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/PoseOptimizationSLAM/animation.gif) # Path Planning diff --git a/SLAM/PoseOptimizationSLAM/README.md b/SLAM/PoseOptimizationSLAM2D/README.md similarity index 100% rename from SLAM/PoseOptimizationSLAM/README.md rename to SLAM/PoseOptimizationSLAM2D/README.md diff --git a/SLAM/PoseOptimizationSLAM/data_downloader.py b/SLAM/PoseOptimizationSLAM2D/data_downloader.py similarity index 100% rename from SLAM/PoseOptimizationSLAM/data_downloader.py rename to SLAM/PoseOptimizationSLAM2D/data_downloader.py diff --git a/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py b/SLAM/PoseOptimizationSLAM2D/pose_optimization_slam_2d.py similarity index 100% rename from SLAM/PoseOptimizationSLAM/pose_optimization_slam.py rename to SLAM/PoseOptimizationSLAM2D/pose_optimization_slam_2d.py From 4246172d261fa865cd5f07fea5dc01702dae91c0 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Sep 2019 09:57:33 +0900 Subject: [PATCH 053/940] update TOC --- README.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 93ede20a7e..8e39d6982c 100644 --- a/README.md +++ b/README.md @@ -12,6 +12,7 @@ Python codes for robotics algorithm. + # Table of Contents * [What is this?](#what-is-this) * [Requirements](#requirements) @@ -30,7 +31,8 @@ Python codes for robotics algorithm. * [SLAM](#slam) * [Iterative Closest Point (ICP) Matching](#iterative-closest-point-icp-matching) * [FastSLAM 1.0](#fastslam-10) - * [Pose Optimization SLAM](#pose-optimization-slam) + * [Pose Optimization SLAM 2D](#pose-optimization-slam-2d) + * [Pose Optimization SLAM 3D](#pose-optimization-slam-3d) * [Path Planning](#path-planning) * [Dynamic Window Approach](#dynamic-window-approach) * [Grid based search](#grid-based-search) @@ -621,3 +623,4 @@ This is a list: [Users comments](https://github.com/AtsushiSakai/PythonRobotics/ - [Ryohei Sasaki](https://github.com/rsasaki0109) + From 4264bde171840c1544da1f50eb71f7a346b89b5d Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Sep 2019 16:10:58 +0900 Subject: [PATCH 054/940] once remove the scripts for solving refactoring --- .../pose_optimization_slam_2d.py | 290 --------- .../pose_optimization_slam_3d.py | 601 ------------------ 2 files changed, 891 deletions(-) delete mode 100644 SLAM/PoseOptimizationSLAM2D/pose_optimization_slam_2d.py delete mode 100644 SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py diff --git a/SLAM/PoseOptimizationSLAM2D/pose_optimization_slam_2d.py b/SLAM/PoseOptimizationSLAM2D/pose_optimization_slam_2d.py deleted file mode 100644 index 764b0f5e73..0000000000 --- a/SLAM/PoseOptimizationSLAM2D/pose_optimization_slam_2d.py +++ /dev/null @@ -1,290 +0,0 @@ -""" - -2D (x, y, yaw) pose optimization SLAM - -author: Atsushi Sakai - -Ref: -- [A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) - -- [GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) - -""" - -import sys -import time -import math -import numpy as np -import matplotlib.pyplot as plt -from scipy import sparse -from scipy.sparse import linalg - - -class Optimizer2D: - - def __init__(self): - self.verbose = False - self.animation = False - self.p_lambda = 0.0 - self.init_w = 1e10 - self.stop_thre = 1e-3 - self.dim = 3 # state dimension - - def optimize_path(self, nodes, consts, max_iter, min_iter): - - graph_nodes = nodes[:] - prev_cost = sys.float_info.max - - for i in range(max_iter): - start = time.time() - cost, graph_nodes = self.optimize_path_one_step( - graph_nodes, consts) - elapsed = time.time() - start - if self.verbose: - print("step ", i, " cost: ", cost, " time:", elapsed, "s") - - # check convergence - if (i > min_iter) and (prev_cost - cost < self.stop_thre): - if self.verbose: - print("converged:", prev_cost - - cost, " < ", self.stop_thre) - break - prev_cost = cost - - if self.animation: - plt.cla() - plot_nodes(nodes, color="-b") - plot_nodes(graph_nodes) - plt.axis("equal") - plt.pause(1.0) - - return graph_nodes - - def optimize_path_one_step(self, graph_nodes, constraints): - - indlist = [i for i in range(self.dim)] - numnodes = len(graph_nodes) - bf = np.zeros(numnodes * self.dim) - tripletList = TripletList() - - for con in constraints: - ida = con.id1 - idb = con.id2 - assert 0 <= ida and ida < numnodes, "ida is invalid" - assert 0 <= idb and idb < numnodes, "idb is invalid" - r, Ja, Jb = self.calc_error( - graph_nodes[ida], graph_nodes[idb], con.t) - - trJaInfo = Ja.transpose() @ con.info_mat - trJaInfoJa = trJaInfo @ Ja - trJbInfo = Jb.transpose() @ con.info_mat - trJbInfoJb = trJbInfo @ Jb - trJaInfoJb = trJaInfo @ Jb - - for k in indlist: - for m in indlist: - tripletList.push_back( - ida * self.dim + k, ida * self.dim + m, trJaInfoJa[k, m]) - tripletList.push_back( - idb * self.dim + k, idb * self.dim + m, trJbInfoJb[k, m]) - tripletList.push_back( - ida * self.dim + k, idb * self.dim + m, trJaInfoJb[k, m]) - tripletList.push_back( - idb * self.dim + k, ida * self.dim + m, trJaInfoJb[m, k]) - - bf[ida * self.dim: ida * self.dim + 3] += trJaInfo @ r - bf[idb * self.dim: idb * self.dim + 3] += trJbInfo @ r - - for k in indlist: - tripletList.push_back(k, k, self.init_w) - - for i in range(self.dim * numnodes): - tripletList.push_back(i, i, self.p_lambda) - - mat = sparse.coo_matrix((tripletList.data, (tripletList.row, tripletList.col)), - shape=(numnodes * self.dim, numnodes * self.dim)) - - x = linalg.spsolve(mat.tocsr(), -bf) - - out_nodes = [] - for i in range(len(graph_nodes)): - u_i = i * self.dim - pos = Pose2D( - graph_nodes[i].x + x[u_i], - graph_nodes[i].y + x[u_i + 1], - graph_nodes[i].theta + x[u_i + 2] - ) - out_nodes.append(pos) - - cost = self.calc_global_cost(out_nodes, constraints) - - return cost, out_nodes - - def calc_global_cost(self, nodes, constraints): - cost = 0.0 - for c in constraints: - diff = self.error_func(nodes[c.id1], nodes[c.id2], c.t) - cost += diff.transpose() @ c.info_mat @ diff - - return cost - - def error_func(self, pa, pb, t): - ba = self.calc_constraint_pose(pb, pa) - error = np.array([ba.x - t.x, - ba.y - t.y, - self.pi2pi(ba.theta - t.theta)]) - return error - - def calc_constraint_pose(self, l, r): - diff = np.array([l.x - r.x, l.y - r.y, l.theta - r.theta]) - v = self.rot_mat_2d(-r.theta) @ diff - v[2] = self.pi2pi(l.theta - r.theta) - return Pose2D(v[0], v[1], v[2]) - - def rot_mat_2d(self, theta): - return np.array([[math.cos(theta), -math.sin(theta), 0.0], - [math.sin(theta), math.cos(theta), 0.0], - [0.0, 0.0, 1.0] - ]) - - def calc_error(self, pa, pb, t): - e0 = self.error_func(pa, pb, t) - dx = pb.x - pa.x - dy = pb.y - pa.y - dxdt = -math.sin(pa.theta) * dx + math.cos(pa.theta) * dy - dydt = -math.cos(pa.theta) * dx - math.sin(pa.theta) * dy - Ja = np.array([[-math.cos(pa.theta), -math.sin(pa.theta), dxdt], - [math.sin(pa.theta), -math.cos(pa.theta), dydt], - [0.0, 0.0, -1.0] - ]) - Jb = np.array([[math.cos(pa.theta), math.sin(pa.theta), 0.0], - [-math.sin(pa.theta), math.cos(pa.theta), 0.0], - [0.0, 0.0, 1.0] - ]) - return e0, Ja, Jb - - def pi2pi(self, rad): - - val = math.fmod(rad, 2.0 * math.pi) - if val > math.pi: - val -= 2.0 * math.pi - elif val < -math.pi: - val += 2.0 * math.pi - - return val - - -class TripletList: - - def __init__(self): - self.row = [] - self.col = [] - self.data = [] - - def push_back(self, irow, icol, idata): - self.row.append(irow) - self.col.append(icol) - self.data.append(idata) - - -class Pose2D: - - def __init__(self, x, y, theta): - self.x = x - self.y = y - self.theta = theta - - -class Constrant2D: - - def __init__(self, id1, id2, t, info_mat): - self.id1 = id1 - self.id2 = id2 - self.t = t - self.info_mat = info_mat - - -def plot_nodes(nodes, color ="-r", label = ""): - x, y = [], [] - for n in nodes: - x.append(n.x) - y.append(n.y) - plt.plot(x, y, color, label=label) - - -def load_data(fname): - nodes, consts = [], [] - - for line in open(fname): - sline = line.split() - tag = sline[0] - - if tag == "VERTEX_SE2": - data_id = int(sline[1]) - x = float(sline[2]) - y = float(sline[3]) - theta = float(sline[4]) - nodes.append(Pose2D(x, y, theta)) - elif tag == "EDGE_SE2": - id1 = int(sline[1]) - id2 = int(sline[2]) - x = float(sline[3]) - y = float(sline[4]) - th = float(sline[5]) - c1 = float(sline[6]) - c2 = float(sline[7]) - c3 = float(sline[8]) - c4 = float(sline[9]) - c5 = float(sline[10]) - c6 = float(sline[11]) - t = Pose2D(x, y, th) - info_mat = np.array([[c1, c2, c3], - [c2, c4, c5], - [c3, c5, c6] - ]) - consts.append(Constrant2D(id1, id2, t, info_mat)) - - print("n_nodes:", len(nodes)) - print("n_consts:", len(consts)) - - return nodes, consts - - -def main(): - print("start!!") - - fnames = ["intel.g2o", - "manhattan3500.g2o", - "mit_killian.g2o" - ] - - max_iter = 20 - min_iter = 3 - - # parameter setting - optimizer = Optimizer2D() - optimizer.p_lambda = 1e-6 - optimizer.verbose = True - optimizer.animation = True - - for f in fnames: - nodes, consts = load_data(f) - - start = time.time() - final_nodes = optimizer.optimize_path(nodes, consts, max_iter, min_iter) - print("elapsed_time", time.time() - start, "sec") - - # plotting - plt.cla() - plot_nodes(nodes, color="-b", label="before") - plot_nodes(final_nodes, label="after") - plt.axis("equal") - plt.grid(True) - plt.legend() - plt.pause(3.0) - - print("done!!") - - -if __name__ == '__main__': - main() diff --git a/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py b/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py deleted file mode 100644 index 0f39b22f3c..0000000000 --- a/SLAM/PoseOptimizationSLAM3D/pose_optimization_slam_3d.py +++ /dev/null @@ -1,601 +0,0 @@ -""" -3D (x, y, z, qw, qx, qy, qz) pose optimization SLAM - -author: Ryohei Sasaki(@rsasaki0109) - -Ref: - -- [A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) - -- [GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) - -- [GitHub \- AtsushiSakai/PythonRobotics -/SLAM/PoseOptimizationSLAM](https://github.com/AtsushiSakai/PythonRobotics/blob/master/SLAM/PoseOptimizationSLAM/pose_optimization_slam.py) - - -""" - -import os -import sys -import time - -import matplotlib.pyplot as plt -import numpy as np -from scipy import sparse -from scipy.sparse import linalg - - -def skew_symmetric(v): - return np.array( - [[0, -v[2], v[1]], - [v[2], 0, -v[0]], - [-v[1], v[0], 0]] - ) - - -def robust_coeff(squared_error, delta): - if squared_error < 0: - return 0 - sqre = np.sqrt(squared_error) - if sqre < delta: - return 1 # no effect - return delta / sqre # linear - - -class Optimizer3D: - - def __init__(self): - self.verbose = False - self.animation = False - self.p_lambda = 1e-7 - self.init_w = 1e10 - self.stop_thre = 1e-3 - self.robust_delta = 1 - self.dim = 6 # state dimension - - def optimize_path(self, nodes, consts, max_iter, min_iter): - - graph_nodes = nodes[:] - prev_cost = sys.float_info.max - - est_traj_fig = plt.figure() - ax = est_traj_fig.add_subplot(111, projection='3d') - - for i in range(max_iter): - start = time.time() - cost, graph_nodes = self.optimize_path_one_step( - graph_nodes, consts) - elapsed = time.time() - start - if self.verbose: - print("step ", i, " cost: ", cost, " time:", elapsed, "s") - - # check convergence - if (i > min_iter) and (prev_cost - cost < self.stop_thre): - if self.verbose: - print("converged:", prev_cost - - cost, " < ", self.stop_thre) - break - prev_cost = cost - - if self.animation: - plt.cla() - plot_nodes(nodes, ax, color="-b") - plot_nodes(graph_nodes, ax) - plt.pause(1.0) - - return graph_nodes - - def optimize_path_one_step(self, graph_nodes, constraints): - - indlist = [i for i in range(self.dim)] - numnodes = len(graph_nodes) - bf = np.zeros(numnodes * self.dim) - tripletList = TripletList() - - for con in constraints: - ida = con.id1 - idb = con.id2 - assert 0 <= ida < numnodes, "ida is invalid" - assert 0 <= idb < numnodes, "idb is invalid" - pa = graph_nodes[ida] - pb = graph_nodes[idb] - r, Ja, Jb = self.calc_error( - pa, pb, con.t) - - info_mat = con.info_mat * robust_coeff(r.reshape(self.dim, 1).T @ con.info_mat @ r.reshape(self.dim, 1), - self.robust_delta) - - trJaInfo = Ja.transpose() @ info_mat - trJaInfoJa = trJaInfo @ Ja - trJbInfo = Jb.transpose() @ info_mat - trJbInfoJb = trJbInfo @ Jb - trJaInfoJb = trJaInfo @ Jb - - for k in indlist: - for m in indlist: - tripletList.push_back( - ida * self.dim + k, ida * self.dim + m, trJaInfoJa[k, m]) - tripletList.push_back( - idb * self.dim + k, idb * self.dim + m, trJbInfoJb[k, m]) - tripletList.push_back( - ida * self.dim + k, idb * self.dim + m, trJaInfoJb[k, m]) - tripletList.push_back( - idb * self.dim + k, ida * self.dim + m, trJaInfoJb[m, k]) - - bf[ida * self.dim: (ida + 1) * self.dim] += trJaInfo @ r - bf[idb * self.dim: (idb + 1) * self.dim] += trJbInfo @ r - - for k in indlist: - tripletList.push_back(k, k, self.init_w) - - for i in range(self.dim * numnodes): - tripletList.push_back(i, i, self.p_lambda) - - mat = sparse.coo_matrix((tripletList.data, (tripletList.row, tripletList.col)), - shape=(numnodes * self.dim, numnodes * self.dim)) - - x = linalg.spsolve(mat.tocsr(), -bf) - - out_nodes = [] - - for i in range(len(graph_nodes)): - u_i = i * self.dim - - q_before = Quaternion(graph_nodes[i].qw, graph_nodes[i].qx, graph_nodes[i].qy, graph_nodes[i].qz) - rv_before = RotVec(quaternion=q_before) - rv_after = RotVec(ax=rv_before.ax + x[u_i + 3], ay=rv_before.ay + x[u_i + 4], az=rv_before.az + x[u_i + 5]) - q_after = rv_after.to_quaternion() - - pos = Pose3D( - graph_nodes[i].x + x[u_i], - graph_nodes[i].y + x[u_i + 1], - graph_nodes[i].z + x[u_i + 2], - q_after.qw, - q_after.qx, - q_after.qy, - q_after.qz - ) - out_nodes.append(pos) - - cost = self.calc_global_cost(out_nodes, constraints) - - return cost, out_nodes - - def calc_global_cost(self, nodes, constraints): - - cost = 0.0 - for c in constraints: - diff = self.error_func(nodes[c.id1], nodes[c.id2], c.t) - info_mat = c.info_mat * robust_coeff(diff.reshape(self.dim, 1).T @ c.info_mat @ diff.reshape(self.dim, 1), - self.robust_delta) - cost += diff.transpose() @ info_mat @ diff - - return cost - - @staticmethod - def error_func(pa, pb, t): - - ba = pb.ominus(pa) - q = t.rv().to_quaternion().conjugate().quat_mult(ba.rv().to_quaternion(), out='Quaternion') - drv = RotVec(quaternion=q) - error = np.array([ba.x - t.x, - ba.y - t.y, - ba.z - t.z, - drv.ax[0], - drv.ay[0], - drv.az[0]]) - return error - - @staticmethod - def dQuat_dRV(rv): - u1 = rv.ax - u2 = rv.ay - u3 = rv.az - v = np.sqrt(u1 ** 2 + u2 ** 2 + u3 ** 2) - if v < 1e-6: - dqu = 0.25 * np.array( - [[-u1, -u2, -u3], - [2.0, 0.0, 0.0], - [0.0, 2.0, 0.0], - [0.0, 0.0, 2.0]] - ) - return dqu - - vd = v * 2 - v2 = v ** 2 - v3 = v ** 3 - - S = np.sin(v / 2.0) - C = np.cos(v / 2.0) - dqu = np.array( - [[-u1 * S / vd, -u2 * S / vd, -u3 * S / vd], - [S / v + u1 * u1 * C / (2 * v2) - u1 * u1 * S / v3, u1 * u2 * (C / (2 * v2) - S / v3), - u1 * u3 * (C / (2 * v2) - S / v3)], - [u1 * u2 * (C / (2 * v2) - S / v3), S / v + u2 * u2 * C / (2 * v2) - u2 * u2 * S / v3, - u2 * u3 * (C / (2 * v2) - S / v3)], - [u1 * u3 * (C / (2 * v2) - S / v3), u2 * u3 * (C / (2 * v2) - S / v3), - S / v + u3 * u3 * C / (2 * v2) - u3 * u3 * S / v3]] - ) - - return dqu - - def dR_dRV(self, rv): - - q = rv.to_quaternion() - qw = q.qw - qx = q.qx - qy = q.qy - qz = q.qz - dRdqw = 2 * np.array( - [[qw, -qz, qy], - [qz, qw, -qx], - [-qy, qx, qw]] - ) - dRdqx = 2 * np.array( - [[qx, qy, qz], - [qy, -qx, -qw], - [qz, qw, -qx]] - ) - dRdqy = 2 * np.array( - [[-qy, qx, qw], - [qx, qy, qz], - [-qw, qz, -qy]] - ) - dRdqz = 2 * np.array( - [[-qz, -qw, qx], - [qw, -qz, -qy], - [qz, qy, qz]] - ) - dqdu = self.dQuat_dRV(rv) - dux = dRdqw * dqdu[0, 0] + dRdqx * dqdu[1, 0] + dRdqy * dqdu[2, 0] + dRdqz * dqdu[3, 0] - duy = dRdqw * dqdu[0, 1] + dRdqx * dqdu[1, 1] + dRdqy * dqdu[2, 1] + dRdqz * dqdu[3, 1] - duz = dRdqw * dqdu[0, 2] + dRdqx * dqdu[1, 2] + dRdqy * dqdu[2, 2] + dRdqz * dqdu[3, 2] - return dux, duy, duz - - @staticmethod - def dRV_dQuat(q): - - qw = q.qw[0] - qx = q.qx[0] - qy = q.qy[0] - qz = q.qz[0] - - if 1 - qw ** 2 < 1e-7: - ret = np.array( - [[0.0, 2.0, 0.0, 0.0], - [0.0, 0.0, 2.0, 0.0], - [0.0, 0.0, 0.0, 2.0]] - ) - return ret - - c = 1 / (1 - qw ** 2) - d = np.arccos(qw) / (np.sqrt(1 - qw ** 2)) - ret = 2.0 * np.array( - [[c * qx * (d * qw - 1), d, 0.0, 0.0], - [c * qy * (d * qw - 1), 0.0, d, 0.0], - [c * qz * (d * qw - 1), 0.0, 0.0, d]] - ) - return ret - - def QMat(self, q): - - qw = q.qw - qx = q.qx - qy = q.qy - qz = q.qz - Q = np.array( - [[qw, -qx, -qy, -qz], - [qx, qw, -qz, qy], - [qy, qz, qw, -qx], - [qz, -qy, qx, qw]] - ) - return Q - - def QMatBar(self, q): - - qw = q.qw - qx = q.qx - qy = q.qy - qz = q.qz - Q = np.array( - [[qw, -qx, -qy, -qz], - [qx, qw, qz, -qy], - [qy, -qz, qw, qx], - [qz, qy, -qx, qw]] - ) - return Q - - def calc_error(self, pa, pb, t): - - e0 = self.error_func(pa, pb, t) - Ja = np.identity(6) - Jb = np.identity(6) - - rva_inv = pa.rv().inverted() - rotPaInv = rva_inv.to_rotation_matrix() - - Ja[:3, :3] = -rotPaInv - Jb[:3, :3] = rotPaInv - - dRux, dRuy, dRuz = self.dR_dRV(rva_inv) - - cvec = np.array([[pb.x - pa.x], [pb.y - pa.y], [pb.z - pa.z]]) - - Ja[0:3, 3:4] = -dRux @ cvec - Ja[0:3, 4:5] = -dRuy @ cvec - Ja[0:3, 5:6] = -dRuz @ cvec - - # rotation part: qdiff = qc-1 * qa-1 * qb - qainv = rva_inv.to_quaternion() - qcinv = t.rv().inverted().to_quaternion() - qb = pb.rv().to_quaternion() - qinvca = qcinv.quat_mult(qainv, out='Quaternion') - qdiff = qinvca.quat_mult(qb, out='Quaternion') - - Ja[3:6, 3:6] = -self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMatBar(qb) @ self.dQuat_dRV(rva_inv) - Jb[3:6, 3:6] = self.dRV_dQuat(qdiff) @ self.QMat(qcinv) @ self.QMat(qainv) @ self.dQuat_dRV(pb.rv()) - - return e0, Ja, Jb - - -class Quaternion: - - def __init__(self, qw, qx, qy, qz): - self.qw = qw - self.qx = qx - self.qy = qy - self.qz = qz - - def conjugate(self): - return Quaternion(self.qw, -self.qx, -self.qy, -self.qz) - - def to_numpy(self): - return np.array([self.qw, self.qx, self.qy, self.qz]).reshape(4, 1) - - def quat_mult(self, q, out='np'): - v = np.array([self.qx, self.qy, self.qz]).reshape(3, 1) - sum_term = np.zeros([4, 4]) - sum_term[0, 1:] = -v[:, 0] - sum_term[1:, 0] = v[:, 0] - sum_term[1:, 1:] = skew_symmetric(v) - sigma = self.qw * np.eye(4) + sum_term - q_new = sigma @ q.to_numpy() - if out == 'np': - return q_new - elif out == 'Quaternion': - q_obj = Quaternion(*q_new) - return q_obj - - -class RotVec: - - def __init__(self, ax=0., ay=0., az=0., quaternion=None): - if quaternion is None: - self.ax = ax - self.ay = ay - self.az = az - else: - x = quaternion.qx - y = quaternion.qy - z = quaternion.qz - norm_im = np.sqrt(x ** 2 + y ** 2 + z ** 2) - if norm_im < 1e-7: - self.ax = 2 * x - self.ay = 2 * y - self.az = 2 * z - else: - th = 2 * np.arctan2(norm_im, quaternion.qw) - th = self.pi2pi(th) - self.ax = x / norm_im * th - self.ay = y / norm_im * th - self.az = z / norm_im * th - - def inverted(self): - - return RotVec(-self.ax, -self.ay, -self.az) - - def to_rotation_matrix(self): - - q = self.to_quaternion() - q_vec = np.array([q.qx, q.qy, q.qz]).reshape(3, 1) - qw = q.qw - mat = (qw ** 2 - q_vec.T @ q_vec) * np.eye(3) \ - + 2 * q_vec @ q_vec.T - 2 * qw * skew_symmetric(q_vec.reshape(-1, )) - return mat.T - - def to_quaternion(self): - - v = np.sqrt(self.ax ** 2 + self.ay ** 2 + self.az ** 2) - if (v < 1e-6): - return Quaternion(1, 0, 0, 0) - else: - return Quaternion(np.cos(v / 2), np.sin(v / 2) * self.ax / v, - np.sin(v / 2) * self.ay / v, np.sin(v / 2) * self.az / v) - - @staticmethod - def pi2pi(rad): - - val = np.fmod(rad, 2.0 * np.pi) - if val > np.pi: - val -= 2.0 * np.pi - elif val < -np.pi: - val += 2.0 * np.pi - - return val - - -class TripletList: - - def __init__(self): - self.row = [] - self.col = [] - self.data = [] - - def push_back(self, irow, icol, idata): - self.row.append(irow) - self.col.append(icol) - self.data.append(idata) - - -class Pose3D: - - def __init__(self, x, y, z, qw, qx, qy, qz): - self.x = x - self.y = y - self.z = z - self.qw = qw - self.qx = qx - self.qy = qy - self.qz = qz - - def pos(self): - v = np.array([self.x, self.y, self.z]).reshape(3, 1) - return v - - def rv(self): - q = Quaternion(self.qw, self.qx, self.qy, self.qz) - return RotVec(quaternion=q) - - def ominus(self, base): - t = base.rv().to_rotation_matrix().T @ (self.pos() - base.pos()) - q = base.rv().to_quaternion().conjugate().quat_mult(self.rv().to_quaternion(), out='Quaternion') - return Pose3D(t[0][0], t[1][0], t[2][0], q.qw, q.qx, q.qy, q.qz) - - -class Constraint3D: - - def __init__(self, id1, id2, t, info_mat): - self.id1 = id1 - self.id2 = id2 - self.t = t - self.info_mat = info_mat - - -def plot_nodes(nodes, ax, color="-r", label=""): - x, y, z = [], [], [] - for n in nodes: - x.append(n.x) - y.append(n.y) - z.append(n.z) - x = np.array(x) - y = np.array(y) - z = np.array(z) - max_range = np.array([x.max() - x.min(), y.max() - y.min(), z.max() - z.min()]).max() / 2.0 - mid_x = (x.max() + x.min()) * 0.5 - mid_y = (y.max() + y.min()) * 0.5 - mid_z = (z.max() + z.min()) * 0.5 - ax.set_xlim(mid_x - max_range, mid_x + max_range) - ax.set_ylim(mid_y - max_range, mid_y + max_range) - ax.set_zlim(mid_z - max_range, mid_z + max_range) - ax.plot(x, y, z, color, label=label) - # ax.plot(x, y, color, label=label) - - -def load_data(fname): - nodes, consts = [], [] - - for line in open(fname): - sline = line.split() - tag = sline[0] - - if tag == "VERTEX_SE3:QUAT": - # data_id = int(sline[1]) # unused - x = float(sline[2]) - y = float(sline[3]) - z = float(sline[4]) - qx = float(sline[5]) - qy = float(sline[6]) - qz = float(sline[7]) - qw = float(sline[8]) - - nodes.append(Pose3D(x, y, z, qw, qx, qy, qz)) - elif tag == "EDGE_SE3:QUAT": - id1 = int(sline[1]) - id2 = int(sline[2]) - x = float(sline[3]) - y = float(sline[4]) - z = float(sline[5]) - qx = float(sline[6]) - qy = float(sline[7]) - qz = float(sline[8]) - qw = float(sline[9]) - c1 = float(sline[10]) - c2 = float(sline[11]) - c3 = float(sline[12]) - c4 = float(sline[13]) - c5 = float(sline[14]) - c6 = float(sline[15]) - c7 = float(sline[16]) - c8 = float(sline[17]) - c9 = float(sline[18]) - c10 = float(sline[19]) - c11 = float(sline[20]) - c12 = float(sline[21]) - c13 = float(sline[22]) - c14 = float(sline[23]) - c15 = float(sline[24]) - c16 = float(sline[25]) - c17 = float(sline[26]) - c18 = float(sline[27]) - c19 = float(sline[28]) - c20 = float(sline[29]) - c21 = float(sline[30]) - t = Pose3D(x, y, z, qw, qx, qy, qz) - info_mat = np.array([[c1, c2, c3, c4, c5, c6], - [c2, c7, c8, c9, c10, c11], - [c3, c8, c12, c13, c14, c15], - [c4, c9, c13, c16, c17, c18], - [c5, c10, c14, c17, c19, c20], - [c6, c11, c15, c18, c20, c21] - ]) - consts.append(Constraint3D(id1, id2, t, info_mat)) - - print("n_nodes:", len(nodes)) - print("n_consts:", len(consts)) - - return nodes, consts - - -def main(): - print("start!!") - - dir = os.path.dirname(os.path.abspath(__file__)) - - fnames = [ - dir + "/sphere2200_guess.g2o", - dir + "/torus3d_guess.g2o", - dir + "/parking-garage.g2o", - ] - - max_iter = 10 - min_iter = 3 - - # parameter setting - optimizer = Optimizer3D() - optimizer.p_lambda = 1e-6 - optimizer.verbose = True - optimizer.animation = False - - for f in fnames: - print(f) - - nodes, consts = load_data(f) - - start = time.time() - final_nodes = optimizer.optimize_path(nodes, consts, max_iter, min_iter) - print("elapsed_time", time.time() - start, "sec") - - # plot - plt.close("all") - est_traj_fig = plt.figure() - ax = est_traj_fig.add_subplot(111, projection='3d') - plot_nodes(nodes, ax, color="-b", label="before") - plot_nodes(final_nodes, ax, label="after") - plt.legend() - plt.show() - - print("done!!") - - -if __name__ == '__main__': - main() From ae32cb332a91ac706c46e3a1e977f80d948b3e60 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 12 Sep 2019 20:26:48 +0900 Subject: [PATCH 055/940] fix early termination bug. fix #223 --- PathPlanning/RRT/rrt.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 887cb1545f..13ca367637 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -74,7 +74,7 @@ def planning(self, animation=True): if animation and i % 5 == 0: self.draw_graph(rnd_node) - if self.calc_dist_to_goal(new_node.x, new_node.y) <= self.expand_dis: + if self.calc_dist_to_goal(self.node_list[-1].x, self.node_list[-1].y) <= self.expand_dis: print("Goal!!") return self.generate_final_course(len(self.node_list) - 1) From 8eef2fd7bbda218d2c381c4a29a17c1f6f710591 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 12 Sep 2019 21:24:20 +0900 Subject: [PATCH 056/940] Update users_comments.md --- users_comments.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/users_comments.md b/users_comments.md index c0165bd2d7..87170eb0c8 100644 --- a/users_comments.md +++ b/users_comments.md @@ -375,6 +375,11 @@ Thanks for your job!
I have learned a lot from it! --- +Dear Atsushi Sakai,
Thank you so much for creating PythonRobotics and documenting it so well. I am a senior in high school trying to learn and better myself in these concepts. + +--Rohan Mathur + + # Citations From 7bafe3d7a572aea4fa49cd0a4ffe667c288921da Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 22 Sep 2019 22:12:57 +0900 Subject: [PATCH 057/940] Update users_comments.md --- users_comments.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/users_comments.md b/users_comments.md index 87170eb0c8..b1a0b66f8e 100644 --- a/users_comments.md +++ b/users_comments.md @@ -398,6 +398,9 @@ URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8765684&isnumber=87 5. Josie Hughes, Masaru Shimizu, and Arnoud Visser, "A Review of Robot Rescue Simulation Platforms for Robotics Education" URL: https://2019.robocup.org/downloads/program/HughesEtAl2019.pdf +6. Hughes, Josie, Masaru Shimizu, and Arnoud Visser. "A review of robot rescue simulation platforms for robotics education." (2019). +URL: https://www.semanticscholar.org/paper/A-Review-of-Robot-Rescue-Simulation-Platforms-for-Hughes-Shimizu/318a4bcb97a44661422ae1430d950efc408097da + # Others - Autonomous Vehicle Readings https://richardkelley.io/readings From a485b0137744a1295292a1caa7abad04da5472e0 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 22 Sep 2019 22:31:17 +0900 Subject: [PATCH 058/940] Update getting_started.rst --- docs/getting_started.rst | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) diff --git a/docs/getting_started.rst b/docs/getting_started.rst index 2f60557f38..93ab70503a 100644 --- a/docs/getting_started.rst +++ b/docs/getting_started.rst @@ -3,6 +3,25 @@ Getting Started =============== +What is this? +------------- + +This is an Open Source Software (OSS) project: PythonRobotics, which is a Python code collection of robotics algorithms. + +The focus of the project is on autonomous navigation, and the goal is for beginners in robotics to understand the basic ideas behind each algorithm. + +In this project, the algorithms which are practical and widely used in both academia and industry are selected. + +Each sample code is written in Python3 and only depends on some standard modules for readability and ease of use. + +It includes intuitive animations to understand the behavior of the simulation. + + +See this paper for more details: + +- PythonRobotics: a Python code collection of robotics algorithms: https://arxiv.org/abs/1808.10703 + + Requirements ------------- From eefa6bf20a2a6d979ed3877b4c6d27bd29a31ef9 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 1 Oct 2019 20:10:42 +0900 Subject: [PATCH 059/940] try to check collision check bug --- PathPlanning/RRT/rrt.py | 24 ++++++++++++++++-------- 1 file changed, 16 insertions(+), 8 deletions(-) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 13ca367637..5f7bab54fc 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -10,6 +10,7 @@ import random import matplotlib.pyplot as plt +import numpy as np show_animation = True @@ -104,10 +105,8 @@ def steer(self, from_node, to_node, extend_length=float("inf")): d, _ = self.calc_distance_and_angle(new_node, to_node) if d <= self.path_resolution: - new_node.x = to_node.x - new_node.y = to_node.y - new_node.path_x[-1] = to_node.x - new_node.path_y[-1] = to_node.y + new_node.path_x.append(to_node.x) + new_node.path_y.append(to_node.y) new_node.parent = from_node @@ -142,17 +141,26 @@ def draw_graph(self, rnd=None): plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: if node.parent: - plt.plot(node.path_x, node.path_y, "-g") + plt.plot(node.path_x, node.path_y, "-xg") for (ox, oy, size) in self.obstacle_list: - plt.plot(ox, oy, "ok", ms=30 * size) + self.plot_circle(ox, oy, size) plt.plot(self.start.x, self.start.y, "xr") plt.plot(self.end.x, self.end.y, "xr") + plt.axis("equal") plt.axis([-2, 15, -2, 15]) plt.grid(True) plt.pause(0.01) + @staticmethod + def plot_circle(x, y, size, color="-b"): # pragma: no cover + deg = list(range(0, 360, 5)) + deg.append(0) + xl = [x + size * math.cos(np.deg2rad(d)) for d in deg] + yl = [y + size * math.sin(np.deg2rad(d)) for d in deg] + plt.plot(xl, yl, color) + @staticmethod def get_nearest_node_index(node_list, rnd_node): dlist = [(node.x - rnd_node.x) ** 2 + (node.y - rnd_node.y) @@ -182,7 +190,7 @@ def calc_distance_and_angle(from_node, to_node): return d, theta -def main(gx=5.0, gy=10.0): +def main(gx=6.0, gy=10.0): print("start " + __file__) # ====Search Path with RRT==== @@ -193,7 +201,7 @@ def main(gx=5.0, gy=10.0): (3, 10, 2), (7, 5, 2), (9, 5, 2) - ] # [x,y,size] + ] # [x, y, radius] # Set Initial parameters rrt = RRT(start=[0, 0], goal=[gx, gy], From 97d6dbdd6cc91c7809d8607646e7af830068a9b1 Mon Sep 17 00:00:00 2001 From: Pavel Date: Tue, 1 Oct 2019 23:02:50 +0300 Subject: [PATCH 060/940] cvxpy link fixed --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 8e39d6982c..6577cf70b8 100644 --- a/README.md +++ b/README.md @@ -103,7 +103,7 @@ See this paper for more details: - pandas -- [cvxpy](http://www.cvxpy.org/en/latest/) +- [cvxpy](https://www.cvxpy.org/index.html) # Documentation From 3cef87ea3fa28df6b1bab1bca9915aa427858453 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 2 Oct 2019 20:19:33 +0900 Subject: [PATCH 061/940] fixed rrt.py --- PathPlanning/RRT/rrt.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 5f7bab54fc..3bcc622100 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -33,7 +33,7 @@ def __init__(self, x, y): self.parent = None def __init__(self, start, goal, obstacle_list, rand_area, - expand_dis=3.0, path_resolution=1.0, goal_sample_rate=5, max_iter=500): + expand_dis=3.0, path_resolution=0.5, goal_sample_rate=5, max_iter=500): """ Setting Parameter @@ -76,8 +76,9 @@ def planning(self, animation=True): self.draw_graph(rnd_node) if self.calc_dist_to_goal(self.node_list[-1].x, self.node_list[-1].y) <= self.expand_dis: - print("Goal!!") - return self.generate_final_course(len(self.node_list) - 1) + final_node = self.steer(self.node_list[-1], self.end, self.expand_dis) + if self.check_collision(final_node, self.obstacle_list): + return self.generate_final_course(len(self.node_list) - 1) if animation and i % 5: self.draw_graph(rnd_node) @@ -141,7 +142,7 @@ def draw_graph(self, rnd=None): plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: if node.parent: - plt.plot(node.path_x, node.path_y, "-xg") + plt.plot(node.path_x, node.path_y, "-g") for (ox, oy, size) in self.obstacle_list: self.plot_circle(ox, oy, size) @@ -200,7 +201,8 @@ def main(gx=6.0, gy=10.0): (3, 8, 2), (3, 10, 2), (7, 5, 2), - (9, 5, 2) + (9, 5, 2), + (8, 10, 1) ] # [x, y, radius] # Set Initial parameters rrt = RRT(start=[0, 0], From a5c7096c7befd4c1af423b529d62dd440f105243 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 2 Oct 2019 20:28:59 +0900 Subject: [PATCH 062/940] fixed rrt_with_pathsmoothing.py --- PathPlanning/RRT/rrt_with_pathsmoothing.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/PathPlanning/RRT/rrt_with_pathsmoothing.py b/PathPlanning/RRT/rrt_with_pathsmoothing.py index 24b6bfeb6e..9826dba072 100644 --- a/PathPlanning/RRT/rrt_with_pathsmoothing.py +++ b/PathPlanning/RRT/rrt_with_pathsmoothing.py @@ -76,8 +76,6 @@ def line_collision_check(first, second, obstacleList): if d <= size: return False - # print("OK") - return True # OK @@ -127,7 +125,7 @@ def main(): (7, 5, 2), (9, 5, 2) ] # [x,y,size] - rrt = RRT(start=[0, 0], goal=[5, 10], + rrt = RRT(start=[0, 0], goal=[6, 10], rand_area=[-2, 15], obstacle_list=obstacleList) path = rrt.planning(animation=show_animation) @@ -141,7 +139,7 @@ def main(): plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') plt.plot([x for (x, y) in smoothedPath], [ - y for (x, y) in smoothedPath], '-b') + y for (x, y) in smoothedPath], '-c') plt.grid(True) plt.pause(0.01) # Need for Mac From 295645f4169c4b7031f8cf0cadf3a643d242c50a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 2 Oct 2019 20:51:22 +0900 Subject: [PATCH 063/940] fixed rrt star.py --- PathPlanning/RRTStar/rrt_star.py | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index eb37964d5c..1c6d682800 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -52,6 +52,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, """ self.connect_circle_dist = connect_circle_dist + self.goal_node = self.Node(goal[0], goal[1]) def planning(self, animation=True, search_until_max_iter=True): """ @@ -121,7 +122,14 @@ def search_best_goal_node(self): dist_to_goal_list = [self.calc_dist_to_goal(n.x, n.y) for n in self.node_list] goal_inds = [dist_to_goal_list.index(i) for i in dist_to_goal_list if i <= self.expand_dis] - if not goal_inds: + # safe_goal_inds = goal_inds + safe_goal_inds = [] + for goal_ind in goal_inds: + t_node = self.steer(self.node_list[goal_ind], self.goal_node) + if self.check_collision(t_node, self.obstacle_list): + safe_goal_inds.append(goal_ind) + + if not safe_goal_inds: return None min_cost = min([self.node_list[i].cost for i in goal_inds]) @@ -177,12 +185,13 @@ def main(): (3, 8, 2), (3, 10, 2), (7, 5, 2), - (9, 5, 2) + (9, 5, 2), + (8, 10, 1), ] # [x,y,size(radius)] # Set Initial parameters rrt_star = RRTStar(start=[0, 0], - goal=[10, 10], + goal=[6, 10], rand_area=[-2, 15], obstacle_list=obstacle_list) path = rrt_star.planning(animation=show_animation) From 67141071c9e1b351ac6c3819c0d53b58d9582103 Mon Sep 17 00:00:00 2001 From: Naveen Date: Wed, 2 Oct 2019 17:48:51 -0700 Subject: [PATCH 064/940] convert 1D array to scalar for np.matmul operation thrust variable is currently a 1D numpy array so the matmul function throws an error when executed, converting thrust to a scalar before the matmul operation solves the issue. --- .../drone_3d_trajectory_following.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py b/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py index 438494a410..e00b3fff48 100644 --- a/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py +++ b/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py @@ -99,7 +99,7 @@ def quad_sim(x_c, y_c, z_c): R = rotation_matrix(roll, pitch, yaw) acc = (np.matmul(R, np.array( - [0, 0, thrust]).T) - np.array([0, 0, m * g]).T) / m + [0, 0, thrust.item()]).T) - np.array([0, 0, m * g]).T) / m x_acc = acc[0] y_acc = acc[1] z_acc = acc[2] @@ -209,4 +209,4 @@ def main(): if __name__ == "__main__": - main() \ No newline at end of file + main() From d2da3abe25f56bf19f89d54d48c4f902f5922718 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 5 Oct 2019 18:00:18 +0900 Subject: [PATCH 065/940] fix safe index reference --- PathPlanning/RRTStar/rrt_star.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index 1c6d682800..09a421937a 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -59,7 +59,7 @@ def planning(self, animation=True, search_until_max_iter=True): rrt star path planning animation: flag for animation on or off - search_until_maxiter: search until max iteration for path improving or not + search_until_max_iter: search until max iteration for path improving or not """ self.node_list = [self.start] @@ -122,7 +122,6 @@ def search_best_goal_node(self): dist_to_goal_list = [self.calc_dist_to_goal(n.x, n.y) for n in self.node_list] goal_inds = [dist_to_goal_list.index(i) for i in dist_to_goal_list if i <= self.expand_dis] - # safe_goal_inds = goal_inds safe_goal_inds = [] for goal_ind in goal_inds: t_node = self.steer(self.node_list[goal_ind], self.goal_node) @@ -132,8 +131,8 @@ def search_best_goal_node(self): if not safe_goal_inds: return None - min_cost = min([self.node_list[i].cost for i in goal_inds]) - for i in goal_inds: + min_cost = min([self.node_list[i].cost for i in safe_goal_inds]) + for i in safe_goal_inds: if self.node_list[i].cost == min_cost: return i @@ -187,6 +186,7 @@ def main(): (7, 5, 2), (9, 5, 2), (8, 10, 1), + (6, 12, 1), ] # [x,y,size(radius)] # Set Initial parameters From 45f90ca37f30e6b201ed5b9cb7b18a5f5fd6a3eb Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 6 Oct 2019 08:57:53 +0900 Subject: [PATCH 066/940] try to upgrade 3.7 --- .travis.yml | 4 ++-- README.md | 8 ++++---- appveyor.yml | 4 +--- 3 files changed, 7 insertions(+), 9 deletions(-) diff --git a/.travis.yml b/.travis.yml index eff3df24fa..042c69ee42 100644 --- a/.travis.yml +++ b/.travis.yml @@ -5,7 +5,7 @@ matrix: - os: linux python: - - 3.6 + - 3.7 before_install: - sudo apt-get update @@ -18,7 +18,7 @@ before_install: - conda update -q conda # Useful for debugging any issues with conda - conda info -a - - conda install python==3.6.8 +# - conda install python==3.6.8 install: - conda install numpy==1.15 diff --git a/README.md b/README.md index 6577cf70b8..1c455e928b 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ - +header pic # PythonRobotics [![Build Status](https://travis-ci.org/AtsushiSakai/PythonRobotics.svg?branch=master)](https://travis-ci.org/AtsushiSakai/PythonRobotics) @@ -93,7 +93,7 @@ See this paper for more details: # Requirements -- Python 3.6.x (2.7 is not supported) +- Python 3.7.x (2.7 is not supported) - numpy @@ -137,7 +137,7 @@ All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation ## Extended Kalman Filter localization - +EKF pic Documentation: [Notebook](https://github.com/AtsushiSakai/PythonRobotics/blob/master/Localization/extended_kalman_filter/extended_kalman_filter_localization.ipynb) @@ -496,7 +496,7 @@ Ref: Path tracking simulation with iterative linear model predictive speed and steering control. - +MPC pic Ref: diff --git a/appveyor.yml b/appveyor.yml index 61f8a0b364..33d4d02970 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -6,9 +6,7 @@ environment: CMD_IN_ENV: "cmd /E:ON /V:ON /C .\\appveyor\\run_with_env.cmd" matrix: - - MINICONDA: C:\Miniconda36-x64 - - + - MINICONDA: C:\Miniconda37-x64 init: - "ECHO %MINICONDA% %PYTHON_VERSION% %PYTHON_ARCH%" From 0e689bf0e88b51d79928e068afa272a95e693ba3 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 6 Oct 2019 09:12:29 +0900 Subject: [PATCH 067/940] removed pycharm markdown setting --- README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 1c455e928b..d97d92adb3 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,6 @@ -header pic +
+header pic +
# PythonRobotics [![Build Status](https://travis-ci.org/AtsushiSakai/PythonRobotics.svg?branch=master)](https://travis-ci.org/AtsushiSakai/PythonRobotics) From 16891e60d104824fadd908fdb41eb5eea4389d71 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 6 Oct 2019 09:18:35 +0900 Subject: [PATCH 068/940] revert it --- README.md | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/README.md b/README.md index d97d92adb3..1c455e928b 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,4 @@ -
-header pic -
+header pic # PythonRobotics [![Build Status](https://travis-ci.org/AtsushiSakai/PythonRobotics.svg?branch=master)](https://travis-ci.org/AtsushiSakai/PythonRobotics) From b942c430e6df8d854fe00f9a264efaca94cc90c9 Mon Sep 17 00:00:00 2001 From: sszwfy <476020374@qq.com> Date: Sun, 6 Oct 2019 14:32:22 +0800 Subject: [PATCH 069/940] fix error for goal cost angle --- PathPlanning/DynamicWindowApproach/dynamic_window_approach.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index fa1dcc62c4..a7d74332a8 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -167,7 +167,8 @@ def calc_to_goal_cost(traj, goal, config): dx = goal[0] - traj[-1, 0] dy = goal[1] - traj[-1, 1] error_angle = math.atan2(dy, dx) - cost = abs(error_angle - traj[-1, 2]) + cost_angle = error_angle - traj[-1, 2] + cost = abs(math.atan2(math.sin(cost_angle), math.cos(cost_angle))) return cost From 0c5bb95761c48bfe976395b350cce317e76ff838 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 9 Oct 2019 19:42:51 +0900 Subject: [PATCH 070/940] Update users_comments.md --- users_comments.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/users_comments.md b/users_comments.md index b1a0b66f8e..2cfd7a4a9b 100644 --- a/users_comments.md +++ b/users_comments.md @@ -401,6 +401,9 @@ URL: https://2019.robocup.org/downloads/program/HughesEtAl2019.pdf 6. Hughes, Josie, Masaru Shimizu, and Arnoud Visser. "A review of robot rescue simulation platforms for robotics education." (2019). URL: https://www.semanticscholar.org/paper/A-Review-of-Robot-Rescue-Simulation-Platforms-for-Hughes-Shimizu/318a4bcb97a44661422ae1430d950efc408097da +7. Ghosh, Ritwika, et al. "CyPhyHouse: A Programming, Simulation, and Deployment Toolchain for Heterogeneous Distributed Coordination." arXiv preprint arXiv:1910.01557 (2019). +URL: https://arxiv.org/abs/1910.01557 + # Others - Autonomous Vehicle Readings https://richardkelley.io/readings From 415bf654f1992cf108eb761eb474b55892cef47d Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 11 Oct 2019 20:13:27 +0900 Subject: [PATCH 071/940] Fix #229 --- .../particle_filter/particle_filter.py | 24 +++++++++---------- 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 8e93893e48..a3dd6bcdb5 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -6,17 +6,18 @@ """ -import numpy as np import math + import matplotlib.pyplot as plt +import numpy as np # Estimation parameter of PF -Q = np.diag([0.1])**2 # range error -R = np.diag([1.0, np.deg2rad(40.0)])**2 # input error +Q = np.diag([0.1]) ** 2 # range error +R = np.diag([1.0, np.deg2rad(40.0)]) ** 2 # input error # Simulation parameter -Qsim = np.diag([0.2])**2 -Rsim = np.diag([1.0, np.deg2rad(30.0)])**2 +Qsim = np.diag([0.2]) ** 2 +Rsim = np.diag([1.0, np.deg2rad(30.0)]) ** 2 DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] @@ -37,7 +38,6 @@ def calc_input(): def observation(xTrue, xd, u, RFID): - xTrue = motion_model(xTrue, u) # add noise to gps x-y @@ -47,7 +47,7 @@ def observation(xTrue, xd, u, RFID): dx = xTrue[0, 0] - RFID[i, 0] dy = xTrue[1, 0] - RFID[i, 1] - d = math.sqrt(dx**2 + dy**2) + d = math.sqrt(dx ** 2 + dy ** 2) if d <= MAX_RANGE: dn = d + np.random.randn() * Qsim[0, 0] # add noise zi = np.array([[dn, RFID[i, 0], RFID[i, 1]]]) @@ -64,7 +64,6 @@ def observation(xTrue, xd, u, RFID): def motion_model(x, u): - F = np.array([[1.0, 0, 0, 0], [0, 1.0, 0, 0], [0, 0, 1.0, 0], @@ -97,7 +96,7 @@ def calc_covariance(xEst, px, pw): return cov -def pf_localization(px, pw, xEst, PEst, z, u): +def pf_localization(px, pw, z, u): """ Localization with Particle filter """ @@ -105,6 +104,7 @@ def pf_localization(px, pw, xEst, PEst, z, u): for ip in range(NP): x = np.array([px[:, ip]]).T w = pw[0, ip] + # Predict with random input sampling ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0] ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] @@ -115,8 +115,8 @@ def pf_localization(px, pw, xEst, PEst, z, u): for i in range(len(z[:, 0])): dx = x[0, 0] - z[i, 1] dy = x[1, 0] - z[i, 2] - prez = math.sqrt(dx**2 + dy**2) - dz = prez - z[i, 0] + pre_z = math.sqrt(dx ** 2 + dy ** 2) + dz = pre_z - z[i, 0] w = w * gauss_likelihood(dz, math.sqrt(Q[0, 0])) px[:, ip] = x[:, 0] @@ -223,7 +223,7 @@ def main(): xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID) - xEst, PEst, px, pw = pf_localization(px, pw, xEst, PEst, z, ud) + xEst, PEst, px, pw = pf_localization(px, pw, z, ud) # store data history hxEst = np.hstack((hxEst, xEst)) From 85bf664a9166d9cb7f9463a801931ceb3af5dec9 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 11 Oct 2019 20:49:07 +0900 Subject: [PATCH 072/940] fix PF problems --- .../particle_filter/particle_filter.py | 94 +++++++++---------- 1 file changed, 47 insertions(+), 47 deletions(-) diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index a3dd6bcdb5..6643116f5a 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -12,12 +12,12 @@ import numpy as np # Estimation parameter of PF -Q = np.diag([0.1]) ** 2 # range error -R = np.diag([1.0, np.deg2rad(40.0)]) ** 2 # input error +Q = np.diag([0.2]) ** 2 # range error +R = np.diag([2.0, np.deg2rad(40.0)]) ** 2 # input error # Simulation parameter -Qsim = np.diag([0.2]) ** 2 -Rsim = np.diag([1.0, np.deg2rad(30.0)]) ** 2 +Q_sim = np.diag([0.2]) ** 2 +R_sim = np.diag([1.0, np.deg2rad(30.0)]) ** 2 DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] @@ -32,30 +32,30 @@ def calc_input(): v = 1.0 # [m/s] - yawrate = 0.1 # [rad/s] - u = np.array([[v, yawrate]]).T + yaw_rate = 0.1 # [rad/s] + u = np.array([[v, yaw_rate]]).T return u -def observation(xTrue, xd, u, RFID): +def observation(xTrue, xd, u, RF_ID): xTrue = motion_model(xTrue, u) # add noise to gps x-y z = np.zeros((0, 3)) - for i in range(len(RFID[:, 0])): + for i in range(len(RF_ID[:, 0])): - dx = xTrue[0, 0] - RFID[i, 0] - dy = xTrue[1, 0] - RFID[i, 1] + dx = xTrue[0, 0] - RF_ID[i, 0] + dy = xTrue[1, 0] - RF_ID[i, 1] d = math.sqrt(dx ** 2 + dy ** 2) if d <= MAX_RANGE: - dn = d + np.random.randn() * Qsim[0, 0] # add noise - zi = np.array([[dn, RFID[i, 0], RFID[i, 1]]]) + dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise + zi = np.array([[dn, RF_ID[i, 0], RF_ID[i, 1]]]) z = np.vstack((z, zi)) # add noise to input - ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0] - ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5 + ud2 = u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5 ud = np.array([[ud1, ud2]]).T xd = motion_model(xd, ud) @@ -92,6 +92,7 @@ def calc_covariance(xEst, px, pw): for i in range(px.shape[1]): dx = (px[:, i] - xEst)[0:3] cov += pw[0, i] * dx.dot(dx.T) + cov /= NP return cov @@ -106,8 +107,8 @@ def pf_localization(px, pw, z, u): w = pw[0, ip] # Predict with random input sampling - ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0] - ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + ud1 = u[0, 0] + np.random.randn() * R[0, 0] ** 0.5 + ud2 = u[1, 0] + np.random.randn() * R[1, 1] ** 0.5 ud = np.array([[ud1, ud2]]).T x = motion_model(x, ud) @@ -127,30 +128,30 @@ def pf_localization(px, pw, z, u): xEst = px.dot(pw.T) PEst = calc_covariance(xEst, px, pw) - px, pw = resampling(px, pw) + px, pw = re_sampling(px, pw) return xEst, PEst, px, pw -def resampling(px, pw): +def re_sampling(px, pw): """ low variance re-sampling """ - Neff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number - if Neff < NTh: - wcum = np.cumsum(pw) + N_eff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number + if N_eff < NTh: + w_cum = np.cumsum(pw) base = np.cumsum(pw * 0.0 + 1 / NP) - 1 / NP - resampleid = base + np.random.rand(base.shape[0]) / NP + re_sample_id = base + np.random.rand(base.shape[0]) / NP - inds = [] + indexes = [] ind = 0 for ip in range(NP): - while resampleid[ip] > wcum[ind]: + while re_sample_id[ip] > w_cum[ind]: ind += 1 - inds.append(ind) + indexes.append(ind) - px = px[:, inds] + px = px[:, indexes] pw = np.zeros((1, NP)) + 1.0 / NP # init weight return px, pw @@ -158,35 +159,35 @@ def resampling(px, pw): def plot_covariance_ellipse(xEst, PEst): # pragma: no cover Pxy = PEst[0:2, 0:2] - eigval, eigvec = np.linalg.eig(Pxy) + eig_val, eig_vec = np.linalg.eig(Pxy) - if eigval[0] >= eigval[1]: - bigind = 0 - smallind = 1 + if eig_val[0] >= eig_val[1]: + big_ind = 0 + small_ind = 1 else: - bigind = 1 - smallind = 0 + big_ind = 1 + small_ind = 0 t = np.arange(0, 2 * math.pi + 0.1, 0.1) - # eigval[bigind] or eiqval[smallind] were occassionally negative numbers extremely + # eig_val[big_ind] or eiq_val[small_ind] were occasionally negative numbers extremely # close to 0 (~10^-20), catch these cases and set the respective variable to 0 try: - a = math.sqrt(eigval[bigind]) + a = math.sqrt(eig_val[big_ind]) except ValueError: a = 0 try: - b = math.sqrt(eigval[smallind]) + b = math.sqrt(eig_val[small_ind]) except ValueError: b = 0 x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] - angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0]) - R = np.array([[math.cos(angle), math.sin(angle)], - [-math.sin(angle), math.cos(angle)]]) - fx = R.dot(np.array([[x, y]])) + angle = math.atan2(eig_vec[big_ind, 1], eig_vec[big_ind, 0]) + Rot = np.array([[math.cos(angle), -math.sin(angle)], + [math.sin(angle), math.cos(angle)]]) + fx = Rot.dot(np.array([[x, y]])) px = np.array(fx[0, :] + xEst[0, 0]).flatten() py = np.array(fx[1, :] + xEst[1, 0]).flatten() plt.plot(px, py, "--r") @@ -197,16 +198,15 @@ def main(): time = 0.0 - # RFID positions [x, y] - RFID = np.array([[10.0, 0.0], - [10.0, 10.0], - [0.0, 15.0], - [-5.0, 20.0]]) + # RF_ID positions [x, y] + RFi_ID = np.array([[10.0, 0.0], + [10.0, 10.0], + [0.0, 15.0], + [-5.0, 20.0]]) # State Vector [x y yaw v]' xEst = np.zeros((4, 1)) xTrue = np.zeros((4, 1)) - PEst = np.eye(4) px = np.zeros((4, NP)) # Particle store pw = np.zeros((1, NP)) + 1.0 / NP # Particle weight @@ -221,7 +221,7 @@ def main(): time += DT u = calc_input() - xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID) + xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFi_ID) xEst, PEst, px, pw = pf_localization(px, pw, z, ud) @@ -235,7 +235,7 @@ def main(): for i in range(len(z[:, 0])): plt.plot([xTrue[0, 0], z[i, 1]], [xTrue[1, 0], z[i, 2]], "-k") - plt.plot(RFID[:, 0], RFID[:, 1], "*k") + plt.plot(RFi_ID[:, 0], RFi_ID[:, 1], "*k") plt.plot(px[0, :], px[1, :], ".r") plt.plot(np.array(hxTrue[0, :]).flatten(), np.array(hxTrue[1, :]).flatten(), "-b") From 46e0506cf57a96d67203a6f50e3dc7ab60f8c5f3 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 12 Oct 2019 14:01:54 +0900 Subject: [PATCH 073/940] Start fixing randn --- .../extended_kalman_filter.py | 34 +++++++++---------- 1 file changed, 16 insertions(+), 18 deletions(-) diff --git a/Localization/extended_kalman_filter/extended_kalman_filter.py b/Localization/extended_kalman_filter/extended_kalman_filter.py index 3f0589b8c6..7150b497f9 100644 --- a/Localization/extended_kalman_filter/extended_kalman_filter.py +++ b/Localization/extended_kalman_filter/extended_kalman_filter.py @@ -7,21 +7,22 @@ """ import math -import numpy as np + import matplotlib.pyplot as plt +import numpy as np # Covariance for EKF simulation Q = np.diag([ - 0.1, # variance of location on x-axis - 0.1, # variance of location on y-axis - np.deg2rad(1.0), # variance of yaw angle - 1.0 # variance of velocity - ])**2 # predict state covariance -R = np.diag([1.0, 1.0])**2 # Observation x,y position covariance + 0.1, # variance of location on x-axis + 0.1, # variance of location on y-axis + np.deg2rad(1.0), # variance of yaw angle + 1.0 # variance of velocity +]) ** 2 # predict state covariance +R = np.diag([1.0, 1.0]) ** 2 # Observation x,y position covariance # Simulation parameter -INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)])**2 -GPS_NOISE = np.diag([0.5, 0.5])**2 +INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)]) ** 2 +GPS_NOISE = np.diag([0.5, 0.5]) ** 2 DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] @@ -37,7 +38,6 @@ def calc_input(): def observation(xTrue, xd, u): - xTrue = motion_model(xTrue, u) # add noise to gps x-y @@ -52,7 +52,6 @@ def observation(xTrue, xd, u): def motion_model(x, u): - F = np.array([[1.0, 0, 0, 0], [0, 1.0, 0, 0], [0, 0, 1.0, 0], @@ -116,20 +115,19 @@ def jacobH(x): def ekf_estimation(xEst, PEst, z, u): - # Predict xPred = motion_model(xEst, u) jF = jacobF(xPred, u) - PPred = jF@PEst@jF.T + Q + PPred = jF @ PEst @ jF.T + Q # Update jH = jacobH(xPred) zPred = observation_model(xPred) y = z - zPred - S = jH@PPred@jH.T + R - K = PPred@jH.T@np.linalg.inv(S) - xEst = xPred + K@y - PEst = (np.eye(len(xEst)) - K@jH)@PPred + S = jH @ PPred @ jH.T + R + K = PPred @ jH.T @ np.linalg.inv(S) + xEst = xPred + K @ y + PEst = (np.eye(len(xEst)) - K @ jH) @ PPred return xEst, PEst @@ -153,7 +151,7 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0]) R = np.array([[math.cos(angle), math.sin(angle)], [-math.sin(angle), math.cos(angle)]]) - fx = R@(np.array([x, y])) + fx = R @ (np.array([x, y])) px = np.array(fx[0, :] + xEst[0, 0]).flatten() py = np.array(fx[1, :] + xEst[1, 0]).flatten() plt.plot(px, py, "--r") From 8fb4b8a5644904efc4dbbdefa1c6cd62c4cfe2da Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Sat, 12 Oct 2019 14:35:00 +0300 Subject: [PATCH 074/940] optimize obstacle cost calculation The obstacle calculation was too slow to work with more obstacles, it is vectorized to speed up the calculation. --- .../dynamic_window_approach.py | 38 ++++++++----------- 1 file changed, 15 insertions(+), 23 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index fa1dcc62c4..1896107220 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -47,8 +47,6 @@ def __init__(self): self.obstacle_cost_gain = 1.0 self.robot_radius = 1.0 # [m] for collision check - - def motion(x, u, dt): """ motion model @@ -138,24 +136,14 @@ def calc_obstacle_cost(traj, ob, config): """ calc obstacle cost inf: collision """ - - skip_n = 2 # for speed up - minr = float("inf") - - for ii in range(0, len(traj[:, 1]), skip_n): - for i in range(len(ob[:, 0])): - ox = ob[i, 0] - oy = ob[i, 1] - dx = traj[ii, 0] - ox - dy = traj[ii, 1] - oy - - r = math.sqrt(dx**2 + dy**2) - if r <= config.robot_radius: - return float("Inf") # collision - - if minr >= r: - minr = r - + ox = ob[:, 0] + oy = ob[:, 1] + dx = traj[:, 0] - ox[:, None] + dy = traj[:, 1] - oy[:, None] + r = np.sqrt(np.square(dx) + np.square(dy)) + if (r <= config.robot_radius).any(): + return float("Inf") + minr = np.min(r) return 1.0 / minr # OK @@ -178,7 +166,7 @@ def plot_arrow(x, y, yaw, length=0.5, width=0.1): # pragma: no cover plt.plot(x, y) -def main(gx=10, gy=10): +def main(gx=10.0, gy=10.0): print(__file__ + " start!!") # initial state [x(m), y(m), yaw(rad), v(m/s), omega(rad/s)] x = np.array([0.0, 0.0, math.pi / 8.0, 0.0, 0.0]) @@ -194,7 +182,12 @@ def main(gx=10, gy=10): [5.0, 9.0], [8.0, 9.0], [7.0, 9.0], - [12.0, 12.0] + [8.0, 10.0], + [9.0, 11.0], + [12.0, 13.0], + [12.0, 12.0], + [15.0, 15.0], + [13.0, 13.0] ]) # input [forward speed, yawrate] @@ -204,7 +197,6 @@ def main(gx=10, gy=10): while True: u, ptraj = dwa_control(x, u, config, goal, ob) - x = motion(x, u, config.dt) # simulate robot traj = np.vstack((traj, x)) # store state history From bf3b4680ecd56c5478e247e4cfebc4539680e1dc Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 12 Oct 2019 20:48:04 +0900 Subject: [PATCH 075/940] fix randn usage and code clean up --- .../ensemble_kalman_filter.py | 95 +++++++++---------- .../extended_kalman_filter.py | 14 +-- .../unscented_kalman_filter.py | 30 +++--- SLAM/EKFSLAM/ekf_slam.py | 61 ++++++------ SLAM/FastSLAM1/fast_slam1.py | 60 +++++------- SLAM/FastSLAM2/fast_slam2.py | 80 +++++++--------- 6 files changed, 152 insertions(+), 188 deletions(-) diff --git a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py index 5ca7713b7d..293509157b 100644 --- a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py +++ b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py @@ -1,4 +1,3 @@ - """ Ensemble Kalman Filter(EnKF) localization sample @@ -10,13 +9,14 @@ """ -import numpy as np import math + import matplotlib.pyplot as plt +import numpy as np # Simulation parameter -Qsim = np.diag([0.2, np.deg2rad(1.0)])**2 -Rsim = np.diag([1.0, np.deg2rad(30.0)])**2 +Q_sim = np.diag([0.2, np.deg2rad(1.0)]) ** 2 +R_sim = np.diag([1.0, np.deg2rad(30.0)]) ** 2 DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] @@ -30,13 +30,12 @@ def calc_input(): v = 1.0 # [m/s] - yawrate = 0.1 # [rad/s] - u = np.array([[v, yawrate]]).T + yaw_rate = 0.1 # [rad/s] + u = np.array([[v, yaw_rate]]).T return u def observation(xTrue, xd, u, RFID): - xTrue = motion_model(xTrue, u) z = np.zeros((0, 4)) @@ -45,18 +44,18 @@ def observation(xTrue, xd, u, RFID): dx = RFID[i, 0] - xTrue[0, 0] dy = RFID[i, 1] - xTrue[1, 0] - d = math.sqrt(dx**2 + dy**2) + d = math.sqrt(dx ** 2 + dy ** 2) angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: - dn = d + np.random.randn() * Qsim[0, 0] # add noise - anglen = angle + np.random.randn() * Qsim[1, 1] # add noise + dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise + anglen = angle + np.random.randn() * Q_sim[1, 1] ** 0.5 # add noise zi = np.array([dn, anglen, RFID[i, 0], RFID[i, 1]]) z = np.vstack((z, zi)) # add noise to input ud = np.array([[ - u[0, 0] + np.random.randn() * Rsim[0, 0], - u[1, 0] + np.random.randn() * Rsim[1, 1]]]).T + u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5, + u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5]]).T xd = motion_model(xd, ud) return xTrue, z, xd, ud @@ -77,15 +76,13 @@ def motion_model(x, u): return x -def calc_LM_Pos(x, landmarks): - landmarks_pos = np.zeros((2*landmarks.shape[0], 1)) +def observe_landmark_position(x, landmarks): + landmarks_pos = np.zeros((2 * landmarks.shape[0], 1)) for (i, lm) in enumerate(landmarks): - landmarks_pos[2*i] = x[0, 0] + lm[0] * \ - math.cos(x[2, 0] + lm[1]) + np.random.randn() * \ - Qsim[0, 0]/np.sqrt(2) - landmarks_pos[2*i+1] = x[1, 0] + lm[0] * \ - math.sin(x[2, 0] + lm[1]) + np.random.randn() * \ - Qsim[0, 0]/np.sqrt(2) + landmarks_pos[2 * i] = x[0, 0] + lm[0] * math.cos(x[2, 0] + lm[1]) + np.random.randn() * Q_sim[ + 0, 0] ** 0.5 / np.sqrt(2) + landmarks_pos[2 * i + 1] = x[1, 0] + lm[0] * math.sin(x[2, 0] + lm[1]) + np.random.randn() * Q_sim[ + 0, 0] ** 0.5 / np.sqrt(2) return landmarks_pos @@ -95,25 +92,26 @@ def calc_covariance(xEst, px): for i in range(px.shape[1]): dx = (px[:, i] - xEst)[0:3] cov += dx.dot(dx.T) + cov /= NP return cov -def enkf_localization(px, xEst, PEst, z, u): +def enkf_localization(px, z, u): """ Localization with Ensemble Kalman filter """ - pz = np.zeros((z.shape[0]*2, NP)) # Particle store of z + pz = np.zeros((z.shape[0] * 2, NP)) # Particle store of z for ip in range(NP): x = np.array([px[:, ip]]).T # Predict with random input sampling - ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0] - ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5 + ud2 = u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5 ud = np.array([[ud1, ud2]]).T x = motion_model(x, ud) px[:, ip] = x[:, 0] - z_pos = calc_LM_Pos(x, z) + z_pos = observe_landmark_position(x, z) pz[:, ip] = z_pos[:, 0] x_ave = np.mean(px, axis=1) @@ -122,12 +120,12 @@ def enkf_localization(px, xEst, PEst, z, u): z_ave = np.mean(pz, axis=1) z_dif = pz - np.tile(z_ave, (NP, 1)).T - U = 1/(NP-1) * x_dif @ z_dif.T - V = 1/(NP-1) * z_dif @ z_dif.T + U = 1 / (NP - 1) * x_dif @ z_dif.T + V = 1 / (NP - 1) * z_dif @ z_dif.T K = U @ np.linalg.inv(V) # Kalman Gain - z_lm_pos = z[:, [2, 3]].reshape(-1,) + z_lm_pos = z[:, [2, 3]].reshape(-1, ) px_hat = px + K @ (np.tile(z_lm_pos, (NP, 1)).T - pz) @@ -139,32 +137,32 @@ def enkf_localization(px, xEst, PEst, z, u): def plot_covariance_ellipse(xEst, PEst): # pragma: no cover Pxy = PEst[0:2, 0:2] - eigval, eigvec = np.linalg.eig(Pxy) + eig_val, eig_vec = np.linalg.eig(Pxy) - if eigval[0] >= eigval[1]: - bigind = 0 - smallind = 1 + if eig_val[0] >= eig_val[1]: + big_ind = 0 + small_ind = 1 else: - bigind = 1 - smallind = 0 + big_ind = 1 + small_ind = 0 t = np.arange(0, 2 * math.pi + 0.1, 0.1) - # eigval[bigind] or eiqval[smallind] were occassionally negative numbers extremely + # eig_val[big_ind] or eiq_val[small_ind] were occasionally negative numbers extremely # close to 0 (~10^-20), catch these cases and set the respective variable to 0 try: - a = math.sqrt(eigval[bigind]) + a = math.sqrt(eig_val[big_ind]) except ValueError: a = 0 try: - b = math.sqrt(eigval[smallind]) + b = math.sqrt(eig_val[small_ind]) except ValueError: b = 0 x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] - angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0]) + angle = math.atan2(eig_vec[big_ind, 1], eig_vec[big_ind, 0]) R = np.array([[math.cos(angle), math.sin(angle)], [-math.sin(angle), math.cos(angle)]]) fx = R.dot(np.array([[x, y]])) @@ -182,17 +180,15 @@ def main(): time = 0.0 - # RFID positions [x, y] - RFID = np.array([[10.0, 0.0], - [10.0, 10.0], - [0.0, 15.0], - [-5.0, 20.0]]) + # RF_ID positions [x, y] + RF_ID = np.array([[10.0, 0.0], + [10.0, 10.0], + [0.0, 15.0], + [-5.0, 20.0]]) # State Vector [x y yaw v]' xEst = np.zeros((4, 1)) xTrue = np.zeros((4, 1)) - PEst = np.eye(4) - px = np.zeros((4, NP)) # Particle store of x xDR = np.zeros((4, 1)) # Dead reckoning @@ -206,9 +202,9 @@ def main(): time += DT u = calc_input() - xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID) + xTrue, z, xDR, ud = observation(xTrue, xDR, u, RF_ID) - xEst, PEst, px = enkf_localization(px, xEst, PEst, z, ud) + xEst, PEst, px = enkf_localization(px, z, ud) # store data history hxEst = np.hstack((hxEst, xEst)) @@ -220,7 +216,7 @@ def main(): for i in range(len(z[:, 0])): plt.plot([xTrue[0, 0], z[i, 2]], [xTrue[1, 0], z[i, 3]], "-k") - plt.plot(RFID[:, 0], RFID[:, 1], "*k") + plt.plot(RF_ID[:, 0], RF_ID[:, 1], "*k") plt.plot(px[0, :], px[1, :], ".r") plt.plot(np.array(hxTrue[0, :]).flatten(), np.array(hxTrue[1, :]).flatten(), "-b") @@ -228,7 +224,7 @@ def main(): np.array(hxDR[1, :]).flatten(), "-k") plt.plot(np.array(hxEst[0, :]).flatten(), np.array(hxEst[1, :]).flatten(), "-r") - #plot_covariance_ellipse(xEst, PEst) + # plot_covariance_ellipse(xEst, PEst) plt.axis("equal") plt.grid(True) plt.pause(0.001) @@ -236,4 +232,3 @@ def main(): if __name__ == '__main__': main() - diff --git a/Localization/extended_kalman_filter/extended_kalman_filter.py b/Localization/extended_kalman_filter/extended_kalman_filter.py index 7150b497f9..d2d7178ae6 100644 --- a/Localization/extended_kalman_filter/extended_kalman_filter.py +++ b/Localization/extended_kalman_filter/extended_kalman_filter.py @@ -78,7 +78,7 @@ def observation_model(x): return z -def jacobF(x, u): +def jacob_f(x, u): """ Jacobian of Motion Model @@ -104,7 +104,7 @@ def jacobF(x, u): return jF -def jacobH(x): +def jacob_h(): # Jacobian of Observation Model jH = np.array([ [1, 0, 0, 0], @@ -117,11 +117,11 @@ def jacobH(x): def ekf_estimation(xEst, PEst, z, u): # Predict xPred = motion_model(xEst, u) - jF = jacobF(xPred, u) + jF = jacob_f(xPred, u) PPred = jF @ PEst @ jF.T + Q # Update - jH = jacobH(xPred) + jH = jacob_h() zPred = observation_model(xPred) y = z - zPred S = jH @ PPred @ jH.T + R @@ -149,9 +149,9 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0]) - R = np.array([[math.cos(angle), math.sin(angle)], - [-math.sin(angle), math.cos(angle)]]) - fx = R @ (np.array([x, y])) + rot = np.array([[math.cos(angle), math.sin(angle)], + [-math.sin(angle), math.cos(angle)]]) + fx = rot @ (np.array([x, y])) px = np.array(fx[0, :] + xEst[0, 0]).flatten() py = np.array(fx[1, :] + xEst[1, 0]).flatten() plt.plot(px, py, "--r") diff --git a/Localization/unscented_kalman_filter/unscented_kalman_filter.py b/Localization/unscented_kalman_filter/unscented_kalman_filter.py index 78b44754ee..45d5b78132 100644 --- a/Localization/unscented_kalman_filter/unscented_kalman_filter.py +++ b/Localization/unscented_kalman_filter/unscented_kalman_filter.py @@ -6,23 +6,24 @@ """ -import numpy as np -import scipy.linalg import math + import matplotlib.pyplot as plt +import numpy as np +import scipy.linalg # Covariance for UKF simulation Q = np.diag([ - 0.1, # variance of location on x-axis - 0.1, # variance of location on y-axis - np.deg2rad(1.0), # variance of yaw angle - 1.0 # variance of velocity - ])**2 # predict state covariance -R = np.diag([1.0, 1.0])**2 # Observation x,y position covariance + 0.1, # variance of location on x-axis + 0.1, # variance of location on y-axis + np.deg2rad(1.0), # variance of yaw angle + 1.0 # variance of velocity +]) ** 2 # predict state covariance +R = np.diag([1.0, 1.0]) ** 2 # Observation x,y position covariance # Simulation parameter -INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)])**2 -GPS_NOISE = np.diag([0.5, 0.5])**2 +INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)]) ** 2 +GPS_NOISE = np.diag([0.5, 0.5]) ** 2 DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] @@ -43,7 +44,6 @@ def calc_input(): def observation(xTrue, xd, u): - xTrue = motion_model(xTrue, u) # add noise to gps x-y @@ -58,7 +58,6 @@ def observation(xTrue, xd, u): def motion_model(x, u): - F = np.array([[1.0, 0, 0, 0], [0, 1.0, 0, 0], [0, 0, 1.0, 0], @@ -144,7 +143,6 @@ def calc_pxz(sigma, x, z_sigma, zb, wc): def ukf_estimation(xEst, PEst, z, u, wm, wc, gamma): - # Predict sigma = generate_sigma_points(xEst, PEst, gamma) sigma = predict_sigma_motion(sigma, u) @@ -183,9 +181,9 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0]) - R = np.array([[math.cos(angle), math.sin(angle)], - [-math.sin(angle), math.cos(angle)]]) - fx = R @ np.array([x, y]) + rot = np.array([[math.cos(angle), math.sin(angle)], + [-math.sin(angle), math.cos(angle)]]) + fx = rot @ np.array([x, y]) px = np.array(fx[0, :] + xEst[0, 0]).flatten() py = np.array(fx[1, :] + xEst[1, 0]).flatten() plt.plot(px, py, "--r") diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index de1b94ec8f..ae39c9e0ea 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -4,16 +4,16 @@ """ import math -import numpy as np -import matplotlib.pyplot as plt +import matplotlib.pyplot as plt +import numpy as np # EKF state covariance -Cx = np.diag([0.5, 0.5, np.deg2rad(30.0)])**2 +Cx = np.diag([0.5, 0.5, np.deg2rad(30.0)]) ** 2 # Simulation parameter -Qsim = np.diag([0.2, np.deg2rad(1.0)])**2 -Rsim = np.diag([1.0, np.deg2rad(10.0)])**2 +Q_sim = np.diag([0.2, np.deg2rad(1.0)]) ** 2 +R_sim = np.diag([1.0, np.deg2rad(10.0)]) ** 2 DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] @@ -26,7 +26,6 @@ def ekf_slam(xEst, PEst, u, z): - # Predict S = STATE_SIZE xEst[0:S] = motion_model(xEst[0:S], u) @@ -36,18 +35,18 @@ def ekf_slam(xEst, PEst, u, z): # Update for iz in range(len(z[:, 0])): # for each observation - minid = search_correspond_LM_ID(xEst, PEst, z[iz, 0:2]) + minid = search_correspond_landmark_id(xEst, PEst, z[iz, 0:2]) - nLM = calc_n_LM(xEst) + nLM = calc_n_lm(xEst) if minid == nLM: print("New LM") # Extend state and covariance matrix - xAug = np.vstack((xEst, calc_LM_Pos(xEst, z[iz, :]))) + xAug = np.vstack((xEst, calc_landmark_position(xEst, z[iz, :]))) PAug = np.vstack((np.hstack((PEst, np.zeros((len(xEst), LM_SIZE)))), np.hstack((np.zeros((LM_SIZE, len(xEst))), initP)))) xEst = xAug PEst = PAug - lm = get_LM_Pos_from_state(xEst, minid) + lm = get_landmark_position_from_state(xEst, minid) y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], minid) K = (PEst @ H.T) @ np.linalg.inv(S) @@ -67,7 +66,6 @@ def calc_input(): def observation(xTrue, xd, u, RFID): - xTrue = motion_model(xTrue, u) # add noise to gps x-y @@ -77,25 +75,24 @@ def observation(xTrue, xd, u, RFID): dx = RFID[i, 0] - xTrue[0, 0] dy = RFID[i, 1] - xTrue[1, 0] - d = math.sqrt(dx**2 + dy**2) + d = math.sqrt(dx ** 2 + dy ** 2) angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: - dn = d + np.random.randn() * Qsim[0, 0] # add noise - anglen = angle + np.random.randn() * Qsim[1, 1] # add noise + dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise + anglen = angle + np.random.randn() * Q_sim[1, 1] ** 0.5 # add noise zi = np.array([dn, anglen, i]) z = np.vstack((z, zi)) # add noise to input ud = np.array([[ - u[0, 0] + np.random.randn() * Rsim[0, 0], - u[1, 0] + np.random.randn() * Rsim[1, 1]]]).T + u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5, + u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5]]).T xd = motion_model(xd, ud) return xTrue, z, xd, ud def motion_model(x, u): - F = np.array([[1.0, 0, 0], [0, 1.0, 0], [0, 0, 1.0]]) @@ -108,15 +105,14 @@ def motion_model(x, u): return x -def calc_n_LM(x): +def calc_n_lm(x): n = int((len(x) - STATE_SIZE) / LM_SIZE) return n def jacob_motion(x, u): - Fx = np.hstack((np.eye(STATE_SIZE), np.zeros( - (STATE_SIZE, LM_SIZE * calc_n_LM(x))))) + (STATE_SIZE, LM_SIZE * calc_n_lm(x))))) jF = np.array([[0.0, 0.0, -DT * u[0] * math.sin(x[2, 0])], [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])], @@ -127,35 +123,34 @@ def jacob_motion(x, u): return G, Fx, -def calc_LM_Pos(x, z): +def calc_landmark_position(x, z): zp = np.zeros((2, 1)) zp[0, 0] = x[0, 0] + z[0] * math.cos(x[2, 0] + z[1]) zp[1, 0] = x[1, 0] + z[0] * math.sin(x[2, 0] + z[1]) - #zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1]) - #zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1]) + # zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1]) + # zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1]) return zp -def get_LM_Pos_from_state(x, ind): - +def get_landmark_position_from_state(x, ind): lm = x[STATE_SIZE + LM_SIZE * ind: STATE_SIZE + LM_SIZE * (ind + 1), :] return lm -def search_correspond_LM_ID(xAug, PAug, zi): +def search_correspond_landmark_id(xAug, PAug, zi): """ Landmark association with Mahalanobis distance """ - nLM = calc_n_LM(xAug) + nLM = calc_n_lm(xAug) mdist = [] for i in range(nLM): - lm = get_LM_Pos_from_state(xAug, i) + lm = get_landmark_position_from_state(xAug, i) y, S, H = calc_innovation(lm, xAug, PAug, zi, i) mdist.append(y.T @ np.linalg.inv(S) @ y) @@ -173,19 +168,19 @@ def calc_innovation(lm, xEst, PEst, z, LMid): zp = np.array([[math.sqrt(q), pi_2_pi(zangle)]]) y = (z - zp).T y[1] = pi_2_pi(y[1]) - H = jacobH(q, delta, xEst, LMid + 1) + H = jacob_h(q, delta, xEst, LMid + 1) S = H @ PEst @ H.T + Cx[0:2, 0:2] return y, S, H -def jacobH(q, delta, x, i): +def jacob_h(q, delta, x, i): sq = math.sqrt(q) G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]], [delta[1, 0], - delta[0, 0], - 1.0, - delta[1, 0], delta[0, 0]]]) G = G / q - nLM = calc_n_LM(x) + nLM = calc_n_lm(x) F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM)))) F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))), np.eye(2), np.zeros((2, 2 * nLM - 2 * i)))) @@ -246,7 +241,7 @@ def main(): plt.plot(xEst[0], xEst[1], ".r") # plot landmark - for i in range(calc_n_LM(xEst)): + for i in range(calc_n_lm(xEst)): plt.plot(xEst[STATE_SIZE + i * 2], xEst[STATE_SIZE + i * 2 + 1], "xg") @@ -262,4 +257,4 @@ def main(): if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/SLAM/FastSLAM1/fast_slam1.py b/SLAM/FastSLAM1/fast_slam1.py index 757e9f95ad..c16407e89f 100644 --- a/SLAM/FastSLAM1/fast_slam1.py +++ b/SLAM/FastSLAM1/fast_slam1.py @@ -6,18 +6,18 @@ """ -import numpy as np import math -import matplotlib.pyplot as plt +import matplotlib.pyplot as plt +import numpy as np # Fast SLAM covariance -Q = np.diag([3.0, np.deg2rad(10.0)])**2 -R = np.diag([1.0, np.deg2rad(20.0)])**2 +Q = np.diag([3.0, np.deg2rad(10.0)]) ** 2 +R = np.diag([1.0, np.deg2rad(20.0)]) ** 2 # Simulation parameter -Qsim = np.diag([0.3, np.deg2rad(2.0)])**2 -Rsim = np.diag([0.5, np.deg2rad(10.0)])**2 +Qsim = np.diag([0.3, np.deg2rad(2.0)]) ** 2 +Rsim = np.diag([0.5, np.deg2rad(10.0)]) ** 2 OFFSET_YAWRATE_NOISE = 0.01 DT = 0.1 # time tick [s] @@ -46,7 +46,6 @@ def __init__(self, N_LM): def fast_slam1(particles, u, z): - particles = predict_particles(particles, u) particles = update_with_observation(particles, z) @@ -57,7 +56,6 @@ def fast_slam1(particles, u, z): def normalize_weight(particles): - sumw = sum([p.w for p in particles]) try: @@ -73,7 +71,6 @@ def normalize_weight(particles): def calc_final_state(particles): - xEst = np.zeros((STATE_SIZE, 1)) particles = normalize_weight(particles) @@ -90,13 +87,12 @@ def calc_final_state(particles): def predict_particles(particles, u): - for i in range(N_PARTICLE): px = np.zeros((STATE_SIZE, 1)) px[0, 0] = particles[i].x px[1, 0] = particles[i].y px[2, 0] = particles[i].yaw - ud = u + (np.random.randn(1, 2) @ R).T # add noise + ud = u + (np.random.randn(1, 2) @ R ** 0.5).T # add noise px = motion_model(px, ud) particles[i].x = px[0, 0] particles[i].y = px[1, 0] @@ -105,8 +101,7 @@ def predict_particles(particles, u): return particles -def add_new_lm(particle, z, Q): - +def add_new_lm(particle, z, Q_cov): r = z[0] b = z[1] lm_id = int(z[2]) @@ -121,15 +116,15 @@ def add_new_lm(particle, z, Q): Gz = np.array([[c, -r * s], [s, r * c]]) - particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q @ Gz.T + particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q_cov @ Gz.T return particle -def compute_jacobians(particle, xf, Pf, Q): +def compute_jacobians(particle, xf, Pf, Q_cov): dx = xf[0, 0] - particle.x dy = xf[1, 0] - particle.y - d2 = dx**2 + dy**2 + d2 = dx ** 2 + dy ** 2 d = math.sqrt(d2) zp = np.array( @@ -141,14 +136,14 @@ def compute_jacobians(particle, xf, Pf, Q): Hf = np.array([[dx / d, dy / d], [-dy / d2, dx / d2]]) - Sf = Hf @ Pf @ Hf.T + Q + Sf = Hf @ Pf @ Hf.T + Q_cov return zp, Hv, Hf, Sf -def update_KF_with_cholesky(xf, Pf, v, Q, Hf): +def update_kf_with_cholesky(xf, Pf, v, Q_cov, Hf): PHt = Pf @ Hf.T - S = Hf @ PHt + Q + S = Hf @ PHt + Q_cov S = (S + S.T) * 0.5 SChol = np.linalg.cholesky(S).T @@ -162,8 +157,7 @@ def update_KF_with_cholesky(xf, Pf, v, Q, Hf): return x, P -def update_landmark(particle, z, Q): - +def update_landmark(particle, z, Q_cov): lm_id = int(z[2]) xf = np.array(particle.lm[lm_id, :]).reshape(2, 1) Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2, :]) @@ -173,7 +167,7 @@ def update_landmark(particle, z, Q): dz = z[0:2].reshape(2, 1) - zp dz[1, 0] = pi_2_pi(dz[1, 0]) - xf, Pf = update_KF_with_cholesky(xf, Pf, dz, Q, Hf) + xf, Pf = update_kf_with_cholesky(xf, Pf, dz, Q_cov, Hf) particle.lm[lm_id, :] = xf.T particle.lmP[2 * lm_id:2 * lm_id + 2, :] = Pf @@ -181,11 +175,11 @@ def update_landmark(particle, z, Q): return particle -def compute_weight(particle, z, Q): +def compute_weight(particle, z, Q_cov): lm_id = int(z[2]) xf = np.array(particle.lm[lm_id, :]).reshape(2, 1) Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2]) - zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q) + zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q_cov) dx = z[0:2].reshape(2, 1) - zp dx[1, 0] = pi_2_pi(dx[1, 0]) @@ -205,7 +199,6 @@ def compute_weight(particle, z, Q): def update_with_observation(particles, z): - for iz in range(len(z[0, :])): lmid = int(z[2, iz]) @@ -247,7 +240,7 @@ def resampling(particles): inds = [] ind = 0 for ip in range(N_PARTICLE): - while ((ind < wcum.shape[0] - 1) and (resampleid[ip] > wcum[ind])): + while (ind < wcum.shape[0] - 1) and (resampleid[ip] > wcum[ind]): ind += 1 inds.append(ind) @@ -264,7 +257,6 @@ def resampling(particles): def calc_input(time): - if time <= 3.0: # wait at first v = 0.0 yawrate = 0.0 @@ -278,7 +270,6 @@ def calc_input(time): def observation(xTrue, xd, u, RFID): - # calc true state xTrue = motion_model(xTrue, u) @@ -288,17 +279,17 @@ def observation(xTrue, xd, u, RFID): dx = RFID[i, 0] - xTrue[0, 0] dy = RFID[i, 1] - xTrue[1, 0] - d = math.sqrt(dx**2 + dy**2) + d = math.sqrt(dx ** 2 + dy ** 2) angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: - dn = d + np.random.randn() * Qsim[0, 0] # add noise - anglen = angle + np.random.randn() * Qsim[1, 1] # add noise + dn = d + np.random.randn() * Qsim[0, 0] ** 0.5 # add noise + anglen = angle + np.random.randn() * Qsim[1, 1] ** 0.5 # add noise zi = np.array([dn, pi_2_pi(anglen), i]).reshape(3, 1) z = np.hstack((z, zi)) # add noise to input - ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0] - ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + OFFSET_YAWRATE_NOISE + ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0] ** 0.5 + ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] ** 0.5 + OFFSET_YAWRATE_NOISE ud = np.array([ud1, ud2]).reshape(2, 1) xd = motion_model(xd, ud) @@ -307,7 +298,6 @@ def observation(xTrue, xd, u, RFID): def motion_model(x, u): - F = np.array([[1.0, 0, 0], [0, 1.0, 0], [0, 0, 1.0]]) @@ -354,7 +344,7 @@ def main(): hxTrue = xTrue hxDR = xTrue - particles = [Particle(N_LM) for i in range(N_PARTICLE)] + particles = [Particle(N_LM) for _ in range(N_PARTICLE)] while SIM_TIME >= time: time += DT diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py index 3d73a58e30..73624dbf1f 100644 --- a/SLAM/FastSLAM2/fast_slam2.py +++ b/SLAM/FastSLAM2/fast_slam2.py @@ -6,19 +6,19 @@ """ -import numpy as np import math -import matplotlib.pyplot as plt +import matplotlib.pyplot as plt +import numpy as np # Fast SLAM covariance -Q = np.diag([3.0, np.deg2rad(10.0)])**2 -R = np.diag([1.0, np.deg2rad(20.0)])**2 +Q = np.diag([3.0, np.deg2rad(10.0)]) ** 2 +R = np.diag([1.0, np.deg2rad(20.0)]) ** 2 # Simulation parameter -Qsim = np.diag([0.3, np.deg2rad(2.0)])**2 -Rsim = np.diag([0.5, np.deg2rad(10.0)])**2 -OFFSET_YAWRATE_NOISE = 0.01 +Q_sim = np.diag([0.3, np.deg2rad(2.0)]) ** 2 +R_sim = np.diag([0.5, np.deg2rad(10.0)]) ** 2 +OFFSET_YAW_RATE_NOISE = 0.01 DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] @@ -47,7 +47,6 @@ def __init__(self, N_LM): def fast_slam2(particles, u, z): - particles = predict_particles(particles, u) particles = update_with_observation(particles, z) @@ -58,12 +57,11 @@ def fast_slam2(particles, u, z): def normalize_weight(particles): - - sumw = sum([p.w for p in particles]) + sum_w = sum([p.w for p in particles]) try: for i in range(N_PARTICLE): - particles[i].w /= sumw + particles[i].w /= sum_w except ZeroDivisionError: for i in range(N_PARTICLE): particles[i].w = 1.0 / N_PARTICLE @@ -74,7 +72,6 @@ def normalize_weight(particles): def calc_final_state(particles): - xEst = np.zeros((STATE_SIZE, 1)) particles = normalize_weight(particles) @@ -85,19 +82,17 @@ def calc_final_state(particles): xEst[2, 0] += particles[i].w * particles[i].yaw xEst[2, 0] = pi_2_pi(xEst[2, 0]) - # print(xEst) return xEst def predict_particles(particles, u): - for i in range(N_PARTICLE): px = np.zeros((STATE_SIZE, 1)) px[0, 0] = particles[i].x px[1, 0] = particles[i].y px[2, 0] = particles[i].yaw - ud = u + (np.random.randn(1, 2) @ R).T # add noise + ud = u + (np.random.randn(1, 2) @ R ** 0.5).T # add noise px = motion_model(px, ud) particles[i].x = px[0, 0] particles[i].y = px[1, 0] @@ -106,8 +101,7 @@ def predict_particles(particles, u): return particles -def add_new_lm(particle, z, Q): - +def add_new_lm(particle, z, Q_cov): r = z[0] b = z[1] lm_id = int(z[2]) @@ -122,15 +116,15 @@ def add_new_lm(particle, z, Q): Gz = np.array([[c, -r * s], [s, r * c]]) - particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q @ Gz.T + particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q_cov @ Gz.T return particle -def compute_jacobians(particle, xf, Pf, Q): +def compute_jacobians(particle, xf, Pf, Q_cov): dx = xf[0, 0] - particle.x dy = xf[1, 0] - particle.y - d2 = dx**2 + dy**2 + d2 = dx ** 2 + dy ** 2 d = math.sqrt(d2) zp = np.array( @@ -142,14 +136,14 @@ def compute_jacobians(particle, xf, Pf, Q): Hf = np.array([[dx / d, dy / d], [-dy / d2, dx / d2]]) - Sf = Hf @ Pf @ Hf.T + Q + Sf = Hf @ Pf @ Hf.T + Q_cov return zp, Hv, Hf, Sf -def update_KF_with_cholesky(xf, Pf, v, Q, Hf): +def update_kf_with_cholesky(xf, Pf, v, Q_cov, Hf): PHt = Pf @ Hf.T - S = Hf @ PHt + Q + S = Hf @ PHt + Q_cov S = (S + S.T) * 0.5 SChol = np.linalg.cholesky(S).T @@ -163,18 +157,17 @@ def update_KF_with_cholesky(xf, Pf, v, Q, Hf): return x, P -def update_landmark(particle, z, Q): - +def update_landmark(particle, z, Q_cov): lm_id = int(z[2]) xf = np.array(particle.lm[lm_id, :]).reshape(2, 1) Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2]) - zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q) + zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q_cov) dz = z[0:2].reshape(2, 1) - zp dz[1, 0] = pi_2_pi(dz[1, 0]) - xf, Pf = update_KF_with_cholesky(xf, Pf, dz, Q, Hf) + xf, Pf = update_kf_with_cholesky(xf, Pf, dz, Q, Hf) particle.lm[lm_id, :] = xf.T particle.lmP[2 * lm_id:2 * lm_id + 2, :] = Pf @@ -182,12 +175,11 @@ def update_landmark(particle, z, Q): return particle -def compute_weight(particle, z, Q): - +def compute_weight(particle, z, Q_cov): lm_id = int(z[2]) xf = np.array(particle.lm[lm_id, :]).reshape(2, 1) Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2]) - zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q) + zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q_cov) dz = z[0:2].reshape(2, 1) - zp dz[1, 0] = pi_2_pi(dz[1, 0]) @@ -205,15 +197,14 @@ def compute_weight(particle, z, Q): return w -def proposal_sampling(particle, z, Q): - +def proposal_sampling(particle, z, Q_cov): lm_id = int(z[2]) xf = particle.lm[lm_id, :].reshape(2, 1) Pf = particle.lmP[2 * lm_id:2 * lm_id + 2] # State x = np.array([particle.x, particle.y, particle.yaw]).reshape(3, 1) P = particle.P - zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q) + zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q_cov) Sfi = np.linalg.inv(Sf) dz = z[0:2].reshape(2, 1) - zp @@ -232,7 +223,6 @@ def proposal_sampling(particle, z, Q): def update_with_observation(particles, z): - for iz in range(len(z[0, :])): lmid = int(z[2, iz]) @@ -265,17 +255,16 @@ def resampling(particles): pw = np.array(pw) Neff = 1.0 / (pw @ pw.T) # Effective particle number - # print(Neff) if Neff < NTH: # resampling wcum = np.cumsum(pw) base = np.cumsum(pw * 0.0 + 1 / N_PARTICLE) - 1 / N_PARTICLE - resampleid = base + np.random.rand(base.shape[0]) / N_PARTICLE + resamplei_id = base + np.random.rand(base.shape[0]) / N_PARTICLE inds = [] ind = 0 for ip in range(N_PARTICLE): - while ((ind < wcum.shape[0] - 1) and (resampleid[ip] > wcum[ind])): + while (ind < wcum.shape[0] - 1) and (resamplei_id[ip] > wcum[ind]): ind += 1 inds.append(ind) @@ -292,7 +281,6 @@ def resampling(particles): def calc_input(time): - if time <= 3.0: # wait at first v = 0.0 yawrate = 0.0 @@ -306,7 +294,6 @@ def calc_input(time): def observation(xTrue, xd, u, RFID): - # calc true state xTrue = motion_model(xTrue, u) @@ -317,17 +304,17 @@ def observation(xTrue, xd, u, RFID): dx = RFID[i, 0] - xTrue[0, 0] dy = RFID[i, 1] - xTrue[1, 0] - d = math.sqrt(dx**2 + dy**2) + d = math.sqrt(dx ** 2 + dy ** 2) angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: - dn = d + np.random.randn() * Qsim[0, 0] # add noise - anglen = angle + np.random.randn() * Qsim[1, 1] # add noise + dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise + anglen = angle + np.random.randn() * Q_sim[1, 1] ** 0.5 # add noise zi = np.array([dn, pi_2_pi(anglen), i]).reshape(3, 1) z = np.hstack((z, zi)) # add noise to input - ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0] - ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + OFFSET_YAWRATE_NOISE + ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5 + ud2 = u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5 + OFFSET_YAW_RATE_NOISE ud = np.array([ud1, ud2]).reshape(2, 1) xd = motion_model(xd, ud) @@ -336,7 +323,6 @@ def observation(xTrue, xd, u, RFID): def motion_model(x, u): - F = np.array([[1.0, 0, 0], [0, 1.0, 0], [0, 0, 1.0]]) @@ -383,7 +369,7 @@ def main(): hxTrue = xTrue hxDR = xTrue - particles = [Particle(N_LM) for i in range(N_PARTICLE)] + particles = [Particle(N_LM) for _ in range(N_PARTICLE)] while SIM_TIME >= time: time += DT @@ -409,7 +395,7 @@ def main(): for iz in range(len(z[:, 0])): lmid = int(z[2, iz]) plt.plot([xEst[0], RFID[lmid, 0]], [ - xEst[1], RFID[lmid, 1]], "-k") + xEst[1], RFID[lmid, 1]], "-k") for i in range(N_PARTICLE): plt.plot(particles[i].x, particles[i].y, ".r") From 23c73567d6f20f539e860d03d0ce2e7bbe74cad5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Sat, 12 Oct 2019 15:08:20 +0300 Subject: [PATCH 076/940] Optimize the obstacle cost calculation. The calculation was too slow to work with more obstacles. The calculation function is vectorized to increase the speed. --- .../dynamic_window_approach.py | 24 +++++++------------ 1 file changed, 8 insertions(+), 16 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index a7d74332a8..7b5eba1743 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -139,22 +139,14 @@ def calc_obstacle_cost(traj, ob, config): calc obstacle cost inf: collision """ - skip_n = 2 # for speed up - minr = float("inf") - - for ii in range(0, len(traj[:, 1]), skip_n): - for i in range(len(ob[:, 0])): - ox = ob[i, 0] - oy = ob[i, 1] - dx = traj[ii, 0] - ox - dy = traj[ii, 1] - oy - - r = math.sqrt(dx**2 + dy**2) - if r <= config.robot_radius: - return float("Inf") # collision - - if minr >= r: - minr = r + ox = ob[:, 0] + oy = ob[:, 1] + dx = traj[:, 0] - ox[:, None] + dy = traj[:, 1] - oy[:, None] + r = np.sqrt(np.square(dx) + np.square(dy)) + if (r <= config.robot_radius).any(): + return float("Inf") + minr = np.min(r) return 1.0 / minr # OK From 87a5517c3a6f929c785c6b8a4c4926815e5d55ba Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 15 Oct 2019 21:56:17 +0900 Subject: [PATCH 077/940] code clean up for DWA sample. --- .../dynamic_window_approach.py | 66 +++++++++---------- 1 file changed, 33 insertions(+), 33 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index f418372c46..fe906e0303 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -7,26 +7,26 @@ """ import math -import numpy as np -import matplotlib.pyplot as plt +import matplotlib.pyplot as plt +import numpy as np show_animation = True -def dwa_control(x, u, config, goal, ob): +def dwa_control(x, config, goal, ob): """ Dynamic Window Approach control """ dw = calc_dynamic_window(x, config) - u, traj = calc_final_input(x, u, dw, config, goal, ob) + u, trajectory = calc_final_input(x, dw, config, goal, ob) - return u, traj + return u, trajectory -class Config(): +class Config: """ simulation parameter class """ @@ -47,6 +47,7 @@ def __init__(self): self.obstacle_cost_gain = 1.0 self.robot_radius = 1.0 # [m] for collision check + def motion(x, u, dt): """ motion model @@ -99,27 +100,26 @@ def predict_trajectory(x_init, v, y, config): return traj -def calc_final_input(x, u, dw, config, goal, ob): +def calc_final_input(x, dw, config, goal, ob): """ - calculation final input with dinamic window + calculation final input with dynamic window """ x_init = x[:] min_cost = float("inf") best_u = [0.0, 0.0] - best_traj = np.array([x]) + best_trajectory = np.array([x]) - # evalucate all trajectory with sampled input in dynamic window + # evaluate all trajectory with sampled input in dynamic window for v in np.arange(dw[0], dw[1], config.v_reso): for y in np.arange(dw[2], dw[3], config.yawrate_reso): - traj = predict_trajectory(x_init, v, y, config) + trajectory = predict_trajectory(x_init, v, y, config) # calc cost - to_goal_cost = config.to_goal_cost_gain * calc_to_goal_cost(traj, goal, config) - speed_cost = config.speed_cost_gain * \ - (config.max_speed - traj[-1, 3]) - ob_cost = config.obstacle_cost_gain*calc_obstacle_cost(traj, ob, config) + to_goal_cost = config.to_goal_cost_gain * calc_to_goal_cost(trajectory, goal) + speed_cost = config.speed_cost_gain * (config.max_speed - trajectory[-1, 3]) + ob_cost = config.obstacle_cost_gain * calc_obstacle_cost(trajectory, ob, config) final_cost = to_goal_cost + speed_cost + ob_cost @@ -127,35 +127,35 @@ def calc_final_input(x, u, dw, config, goal, ob): if min_cost >= final_cost: min_cost = final_cost best_u = [v, y] - best_traj = traj + best_trajectory = trajectory - return best_u, best_traj + return best_u, best_trajectory -def calc_obstacle_cost(traj, ob, config): +def calc_obstacle_cost(trajectory, ob, config): """ calc obstacle cost inf: collision """ ox = ob[:, 0] oy = ob[:, 1] - dx = traj[:, 0] - ox[:, None] - dy = traj[:, 1] - oy[:, None] + dx = trajectory[:, 0] - ox[:, None] + dy = trajectory[:, 1] - oy[:, None] r = np.sqrt(np.square(dx) + np.square(dy)) if (r <= config.robot_radius).any(): return float("Inf") - minr = np.min(r) - return 1.0 / minr # OK + min_r = np.min(r) + return 1.0 / min_r # OK -def calc_to_goal_cost(traj, goal, config): +def calc_to_goal_cost(trajectory, goal): """ calc to goal cost with angle difference """ - dx = goal[0] - traj[-1, 0] - dy = goal[1] - traj[-1, 1] + dx = goal[0] - trajectory[-1, 0] + dy = goal[1] - trajectory[-1, 1] error_angle = math.atan2(dy, dx) - cost_angle = error_angle - traj[-1, 2] + cost_angle = error_angle - trajectory[-1, 2] cost = abs(math.atan2(math.sin(cost_angle), math.cos(cost_angle))) return cost @@ -194,16 +194,16 @@ def main(gx=10.0, gy=10.0): # input [forward speed, yawrate] u = np.array([0.0, 0.0]) config = Config() - traj = np.array(x) + trajectory = np.array(x) while True: - u, ptraj = dwa_control(x, u, config, goal, ob) - x = motion(x, u, config.dt) # simulate robot - traj = np.vstack((traj, x)) # store state history + u, predicted_trajectory = dwa_control(x, config, goal, ob) + x = motion(x, u, config.dt) # simulate robot + trajectory = np.vstack((trajectory, x)) # store state history if show_animation: plt.cla() - plt.plot(ptraj[:, 0], ptraj[:, 1], "-g") + plt.plot(predicted_trajectory[:, 0], predicted_trajectory[:, 1], "-g") plt.plot(x[0], x[1], "xr") plt.plot(goal[0], goal[1], "xb") plt.plot(ob[:, 0], ob[:, 1], "ok") @@ -213,14 +213,14 @@ def main(gx=10.0, gy=10.0): plt.pause(0.0001) # check reaching goal - dist_to_goal = math.sqrt((x[0] - goal[0])**2 + (x[1] - goal[1])**2) + dist_to_goal = math.sqrt((x[0] - goal[0]) ** 2 + (x[1] - goal[1]) ** 2) if dist_to_goal <= config.robot_radius: print("Goal!!") break print("Done") if show_animation: - plt.plot(traj[:, 0], traj[:, 1], "-r") + plt.plot(trajectory[:, 0], trajectory[:, 1], "-r") plt.pause(0.0001) plt.show() From 4cedb7aad4d2b4f6431536a8c749f1980cc8f84e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Tue, 15 Oct 2019 21:55:56 +0300 Subject: [PATCH 078/940] Add rectangle robot type and collision check Add collision check for rectangle robots Add new function to draw robot depending on the type --- .../dynamic_window_approach.py | 56 ++++++++++++++++++- 1 file changed, 53 insertions(+), 3 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 7b0882ab0c..1fad0e91cf 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -45,8 +45,16 @@ def __init__(self): self.to_goal_cost_gain = 0.15 self.speed_cost_gain = 1.0 self.obstacle_cost_gain = 1.0 + self.robot_type = 'circle' # circle or rectangle + + # if robot_type == circle + # Also used to check if goal is reached in both types self.robot_radius = 1.0 # [m] for collision check + # if robot_type == rectangle + self.robot_width = 0.5 # [m] for collision check + self.robot_length = 1.2 # [m] for collision check + def motion(x, u, dt): """ @@ -141,8 +149,25 @@ def calc_obstacle_cost(trajectory, ob, config): dx = trajectory[:, 0] - ox[:, None] dy = trajectory[:, 1] - oy[:, None] r = np.sqrt(np.square(dx) + np.square(dy)) - if (r <= config.robot_radius).any(): - return float("Inf") + + if config.robot_type == 'rectangle': + yaw = trajectory[:, 2] + rot = np.array([[np.cos(yaw), -np.sin(yaw)], [np.sin(yaw), np.cos(yaw)]]) + local_ob = ob[:, None] - trajectory[:, 0:2] + local_ob = local_ob.reshape(-1, local_ob.shape[-1]) + local_ob = np.array([local_ob @ -x for x in rot.T]) + local_ob = local_ob.reshape(-1, local_ob.shape[-1]) + upper_check = local_ob[:, 0] <= config.robot_length/2 + right_check = local_ob[:, 1] <= config.robot_width/2 + bottom_check = local_ob[:, 0] >= -config.robot_length/2 + left_check = local_ob[:, 1] >= -config.robot_width/2 + if (np.logical_and(np.logical_and(upper_check, right_check), + np.logical_and(bottom_check, left_check))).any(): + return float("Inf") + elif config.robot_type == 'circle': + if (r <= config.robot_radius).any(): + return float("Inf") + min_r = np.min(r) return 1.0 / min_r # OK @@ -166,7 +191,30 @@ def plot_arrow(x, y, yaw, length=0.5, width=0.1): # pragma: no cover plt.plot(x, y) -def main(gx=10.0, gy=10.0): +def plot_robot(x, y, yaw, config): # pragma: no cover + if config.robot_type == 'rectangle': + outline = np.array([[-config.robot_length/2, config.robot_length/2, + (config.robot_length/2), -config.robot_length/2, + -config.robot_length/2], + [config.robot_width / 2, config.robot_width / 2, + - config.robot_width / 2, -config.robot_width / 2, + config.robot_width / 2]]) + Rot1 = np.array([[math.cos(yaw), math.sin(yaw)], + [-math.sin(yaw), math.cos(yaw)]]) + outline = (outline.T.dot(Rot1)).T + outline[0, :] += x + outline[1, :] += y + plt.plot(np.array(outline[0, :]).flatten(), + np.array(outline[1, :]).flatten(), "-k") + elif config.robot_type == 'circle': + circle = plt.Circle((x, y), config.robot_radius, color="b") + plt.gcf().gca().add_artist(circle) + out_x, out_y = (np.array([x, y]) + + np.array([np.cos(yaw), np.sin(yaw)]) * config.robot_radius) + plt.plot([x, out_x], [y, out_y], "-k") + + +def main(gx=10.0, gy=10.0, robot_type='circle'): print(__file__ + " start!!") # initial state [x(m), y(m), yaw(rad), v(m/s), omega(rad/s)] x = np.array([0.0, 0.0, math.pi / 8.0, 0.0, 0.0]) @@ -193,6 +241,7 @@ def main(gx=10.0, gy=10.0): # input [forward speed, yawrate] u = np.array([0.0, 0.0]) config = Config() + config.robot_type = robot_type trajectory = np.array(x) while True: @@ -206,6 +255,7 @@ def main(gx=10.0, gy=10.0): plt.plot(x[0], x[1], "xr") plt.plot(goal[0], goal[1], "xb") plt.plot(ob[:, 0], ob[:, 1], "ok") + plot_robot(x[0], x[1], x[2], config) plot_arrow(x[0], x[1], x[2]) plt.axis("equal") plt.grid(True) From d98604158c56f67d47ad2f9481e6498ee469b415 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Tue, 15 Oct 2019 22:03:28 +0300 Subject: [PATCH 079/940] add test for the rectangle robot type --- tests/test_dynamic_window_approach.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/tests/test_dynamic_window_approach.py b/tests/test_dynamic_window_approach.py index ab2e0a27ac..de371f4a2b 100644 --- a/tests/test_dynamic_window_approach.py +++ b/tests/test_dynamic_window_approach.py @@ -17,7 +17,12 @@ def test1(self): m.show_animation = False m.main(gx=1.0, gy=1.0) + def test2(self): + m.show_animation = False + m.main(gx=1.0, gy=1.0, robot_type='rectangle') + if __name__ == '__main__': # pragma: no cover test = Test() test.test1() + test.test2() From bcdf088684b1b47ef9867c39263f624f677fe869 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Wed, 16 Oct 2019 19:19:11 +0300 Subject: [PATCH 080/940] Change robot_type comparison to enum class named RobotType - Instead of using string based comparison for robot_type, use Enum class. - Append authors --- .../dynamic_window_approach.py | 22 +++++++++++-------- 1 file changed, 13 insertions(+), 9 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 1fad0e91cf..0313b0f1ef 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -2,10 +2,11 @@ Mobile robot motion planning sample with Dynamic Window Approach -author: Atsushi Sakai (@Atsushi_twi) +author: Atsushi Sakai (@Atsushi_twi), Goktug Karakasli """ +from enum import Enum import math import matplotlib.pyplot as plt @@ -25,6 +26,9 @@ def dwa_control(x, config, goal, ob): return u, trajectory +class RobotType(Enum): + circle = 0 + rectangle = 1 class Config: """ @@ -45,13 +49,13 @@ def __init__(self): self.to_goal_cost_gain = 0.15 self.speed_cost_gain = 1.0 self.obstacle_cost_gain = 1.0 - self.robot_type = 'circle' # circle or rectangle + self.robot_type = RobotType.circle - # if robot_type == circle + # if robot_type == RobotType.circle # Also used to check if goal is reached in both types self.robot_radius = 1.0 # [m] for collision check - # if robot_type == rectangle + # if robot_type == RobotType.rectangle self.robot_width = 0.5 # [m] for collision check self.robot_length = 1.2 # [m] for collision check @@ -150,7 +154,7 @@ def calc_obstacle_cost(trajectory, ob, config): dy = trajectory[:, 1] - oy[:, None] r = np.sqrt(np.square(dx) + np.square(dy)) - if config.robot_type == 'rectangle': + if config.robot_type == RobotType.rectangle: yaw = trajectory[:, 2] rot = np.array([[np.cos(yaw), -np.sin(yaw)], [np.sin(yaw), np.cos(yaw)]]) local_ob = ob[:, None] - trajectory[:, 0:2] @@ -164,7 +168,7 @@ def calc_obstacle_cost(trajectory, ob, config): if (np.logical_and(np.logical_and(upper_check, right_check), np.logical_and(bottom_check, left_check))).any(): return float("Inf") - elif config.robot_type == 'circle': + elif config.robot_type == RobotType.circle: if (r <= config.robot_radius).any(): return float("Inf") @@ -192,7 +196,7 @@ def plot_arrow(x, y, yaw, length=0.5, width=0.1): # pragma: no cover def plot_robot(x, y, yaw, config): # pragma: no cover - if config.robot_type == 'rectangle': + if config.robot_type == RobotType.rectangle: outline = np.array([[-config.robot_length/2, config.robot_length/2, (config.robot_length/2), -config.robot_length/2, -config.robot_length/2], @@ -206,7 +210,7 @@ def plot_robot(x, y, yaw, config): # pragma: no cover outline[1, :] += y plt.plot(np.array(outline[0, :]).flatten(), np.array(outline[1, :]).flatten(), "-k") - elif config.robot_type == 'circle': + elif config.robot_type == RobotType.circle: circle = plt.Circle((x, y), config.robot_radius, color="b") plt.gcf().gca().add_artist(circle) out_x, out_y = (np.array([x, y]) + @@ -214,7 +218,7 @@ def plot_robot(x, y, yaw, config): # pragma: no cover plt.plot([x, out_x], [y, out_y], "-k") -def main(gx=10.0, gy=10.0, robot_type='circle'): +def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): print(__file__ + " start!!") # initial state [x(m), y(m), yaw(rad), v(m/s), omega(rad/s)] x = np.array([0.0, 0.0, math.pi / 8.0, 0.0, 0.0]) From 457b4086ef4e900f53a104a6baf36246ef57889e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Wed, 16 Oct 2019 19:24:37 +0300 Subject: [PATCH 081/940] Change string to RobotType enum --- tests/test_dynamic_window_approach.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/test_dynamic_window_approach.py b/tests/test_dynamic_window_approach.py index de371f4a2b..890f000475 100644 --- a/tests/test_dynamic_window_approach.py +++ b/tests/test_dynamic_window_approach.py @@ -19,7 +19,7 @@ def test1(self): def test2(self): m.show_animation = False - m.main(gx=1.0, gy=1.0, robot_type='rectangle') + m.main(gx=1.0, gy=1.0, robot_type=m.RobotType.rectangle) if __name__ == '__main__': # pragma: no cover From 0ec56812be8e6811cc0a3b2486528b1fb2c64685 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Wed, 16 Oct 2019 20:17:46 +0300 Subject: [PATCH 082/940] Add type checking for robot_type --- .../DynamicWindowApproach/dynamic_window_approach.py | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 0313b0f1ef..267ca1676d 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -59,6 +59,15 @@ def __init__(self): self.robot_width = 0.5 # [m] for collision check self.robot_length = 1.2 # [m] for collision check + @property + def robot_type(self): + return self._robot_type + + @robot_type.setter + def robot_type(self, value): + if not isinstance(value, RobotType): + raise TypeError("robot_type must be an instance of RobotType") + self._robot_type = value def motion(x, u, dt): """ From adb4e99ceb5628f103c486b9eb84ef35d1c4b3d0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Wed, 16 Oct 2019 21:03:18 +0300 Subject: [PATCH 083/940] Fix transpose error of the rotation matrix --- PathPlanning/DynamicWindowApproach/dynamic_window_approach.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 267ca1676d..9216892aee 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -166,9 +166,10 @@ def calc_obstacle_cost(trajectory, ob, config): if config.robot_type == RobotType.rectangle: yaw = trajectory[:, 2] rot = np.array([[np.cos(yaw), -np.sin(yaw)], [np.sin(yaw), np.cos(yaw)]]) + rot = np.transpose(rot, [2, 0, 1]) local_ob = ob[:, None] - trajectory[:, 0:2] local_ob = local_ob.reshape(-1, local_ob.shape[-1]) - local_ob = np.array([local_ob @ -x for x in rot.T]) + local_ob = np.array([local_ob @ -x for x in rot]) local_ob = local_ob.reshape(-1, local_ob.shape[-1]) upper_check = local_ob[:, 0] <= config.robot_length/2 right_check = local_ob[:, 1] <= config.robot_width/2 From c1ba9bab0a48100aa3f81286a2015c5112bb1f9f Mon Sep 17 00:00:00 2001 From: Francisco Moretti Date: Thu, 17 Oct 2019 09:09:54 -0300 Subject: [PATCH 084/940] fix check segment intersection with obstacle The previous method only worked because the step that checked collision from a point of the line to obstacles was the same as the minimum obstacle radius. If the obstacle radius is very small a great amount of steps would be required. Thus It's better to check the distance from the segment to the obstacles directly and compare with obstacle radius Now there is no need to have two check functions. --- .../InformedRRTStar/informed_rrt_star.py | 54 ++++++++++--------- 1 file changed, 29 insertions(+), 25 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 4a32801da5..b9769bea53 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -74,10 +74,9 @@ def informed_rrt_star_search(self, animation=True): newNode = self.get_new_node(theta, nind, nearestNode) d = self.line_cost(nearestNode, newNode) - isCollision = self.collision_check(newNode, self.obstacle_list) - isCollisionEx = self.check_collision_extend(nearestNode, theta, d) + isCollision = self.check_collision(nearestNode, theta, d) - if isCollision and isCollisionEx: + if isCollision: nearInds = self.find_near_nodes(newNode) newNode = self.choose_parent(newNode, nearInds) @@ -110,7 +109,7 @@ def choose_parent(self, newNode, nearInds): dy = newNode.y - self.node_list[i].y d = math.sqrt(dx ** 2 + dy ** 2) theta = math.atan2(dy, dx) - if self.check_collision_extend(self.node_list[i], theta, d): + if self.check_collision(self.node_list[i], theta, d): dList.append(self.node_list[i].cost + d) else: dList.append(float('inf')) @@ -194,17 +193,6 @@ def get_nearest_list_index(nodes, rnd): minIndex = dList.index(min(dList)) return minIndex - @staticmethod - def collision_check(newNode, obstacleList): - for (ox, oy, size) in obstacleList: - dx = ox - newNode.x - dy = oy - newNode.y - d = dx * dx + dy * dy - if d <= 1.1 * size ** 2: - return False # collision - - return True # safe - def get_new_node(self, theta, nind, nearestNode): newNode = copy.deepcopy(nearestNode) @@ -234,19 +222,35 @@ def rewire(self, newNode, nearInds): if nearNode.cost > scost: theta = math.atan2(newNode.y - nearNode.y, newNode.x - nearNode.x) - if self.check_collision_extend(nearNode, theta, d): + if self.check_collision(nearNode, theta, d): nearNode.parent = n_node - 1 nearNode.cost = scost - - def check_collision_extend(self, nearNode, theta, d): + + @staticmethod + def distance_squared_point_to_segment(v, w, p): + # Return minimum distance between line segment vw and point p + if (np.array_equal(v, w)): + return (p-v).dot(p-v) # v == w case + l2 = (w-v).dot(w-v) # i.e. |w-v|^2 - avoid a sqrt + # Consider the line extending the segment, parameterized as v + t (w - v). + # We find projection of point p onto the line. + # It falls where t = [(p-v) . (w-v)] / |w-v|^2 + # We clamp t from [0,1] to handle points outside the segment vw. + t = max(0, min(1, (p - v).dot(w - v) / l2)) + projection = v + t * (w - v) # Projection falls on the segment + return (p-projection).dot(p-projection) + + def check_collision(self, nearNode, theta, d): tmpNode = copy.deepcopy(nearNode) - - for i in range(int(d / self.expand_dis)): - tmpNode.x += self.expand_dis * math.cos(theta) - tmpNode.y += self.expand_dis * math.sin(theta) - if not self.collision_check(tmpNode, self.obstacle_list): - return False - + endx = tmpNode.x + math.cos(theta)*d + endy = tmpNode.y + math.sin(theta)*d + for (ox, oy, size) in self.obstacle_list: + dd = self.distance_squared_point_to_segment( + np.array([tmpNode.x, tmpNode.y]), + np.array([endx, endy]), + np.array([ox, oy])) + if dd <= 1.1 * size**2: + return False # collision return True def get_final_course(self, lastIndex): From 35ea4b955cb776718e89440becb5aac8443e962d Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 17 Oct 2019 21:53:39 +0900 Subject: [PATCH 085/940] code clean up for DWA --- .../dynamic_window_approach.py | 33 ++++++++++--------- 1 file changed, 18 insertions(+), 15 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 9216892aee..c2a8674ae3 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -6,8 +6,8 @@ """ -from enum import Enum import math +from enum import Enum import matplotlib.pyplot as plt import numpy as np @@ -17,7 +17,7 @@ def dwa_control(x, config, goal, ob): """ - Dynamic Window Approach control + Dynamic Window Approach control """ dw = calc_dynamic_window(x, config) @@ -26,10 +26,12 @@ def dwa_control(x, config, goal, ob): return u, trajectory + class RobotType(Enum): circle = 0 rectangle = 1 + class Config: """ simulation parameter class @@ -56,8 +58,8 @@ def __init__(self): self.robot_radius = 1.0 # [m] for collision check # if robot_type == RobotType.rectangle - self.robot_width = 0.5 # [m] for collision check - self.robot_length = 1.2 # [m] for collision check + self.robot_width = 0.5 # [m] for collision check + self.robot_length = 1.2 # [m] for collision check @property def robot_type(self): @@ -69,6 +71,7 @@ def robot_type(self, value): raise TypeError("robot_type must be an instance of RobotType") self._robot_type = value + def motion(x, u, dt): """ motion model @@ -98,7 +101,7 @@ def calc_dynamic_window(x, config): x[4] - config.max_dyawrate * config.dt, x[4] + config.max_dyawrate * config.dt] - # [vmin,vmax, yawrate min, yawrate max] + # [vmin,vmax, yaw_rate min, yaw_rate max] dw = [max(Vs[0], Vd[0]), min(Vs[1], Vd[1]), max(Vs[2], Vd[2]), min(Vs[3], Vd[3])] @@ -171,10 +174,10 @@ def calc_obstacle_cost(trajectory, ob, config): local_ob = local_ob.reshape(-1, local_ob.shape[-1]) local_ob = np.array([local_ob @ -x for x in rot]) local_ob = local_ob.reshape(-1, local_ob.shape[-1]) - upper_check = local_ob[:, 0] <= config.robot_length/2 - right_check = local_ob[:, 1] <= config.robot_width/2 - bottom_check = local_ob[:, 0] >= -config.robot_length/2 - left_check = local_ob[:, 1] >= -config.robot_width/2 + upper_check = local_ob[:, 0] <= config.robot_length / 2 + right_check = local_ob[:, 1] <= config.robot_width / 2 + bottom_check = local_ob[:, 0] >= -config.robot_length / 2 + left_check = local_ob[:, 1] >= -config.robot_width / 2 if (np.logical_and(np.logical_and(upper_check, right_check), np.logical_and(bottom_check, left_check))).any(): return float("Inf") @@ -185,6 +188,7 @@ def calc_obstacle_cost(trajectory, ob, config): min_r = np.min(r) return 1.0 / min_r # OK + def calc_to_goal_cost(trajectory, goal): """ calc to goal cost with angle difference @@ -207,9 +211,9 @@ def plot_arrow(x, y, yaw, length=0.5, width=0.1): # pragma: no cover def plot_robot(x, y, yaw, config): # pragma: no cover if config.robot_type == RobotType.rectangle: - outline = np.array([[-config.robot_length/2, config.robot_length/2, - (config.robot_length/2), -config.robot_length/2, - -config.robot_length/2], + outline = np.array([[-config.robot_length / 2, config.robot_length / 2, + (config.robot_length / 2), -config.robot_length / 2, + -config.robot_length / 2], [config.robot_width / 2, config.robot_width / 2, - config.robot_width / 2, -config.robot_width / 2, config.robot_width / 2]]) @@ -252,8 +256,7 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): [13.0, 13.0] ]) - # input [forward speed, yawrate] - u = np.array([0.0, 0.0]) + # input [forward speed, yaw_rate] config = Config() config.robot_type = robot_type trajectory = np.array(x) @@ -290,4 +293,4 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): if __name__ == '__main__': - main() + main(robot_type=RobotType.rectangle) From 71c124bdd3e15118004c06ed06f62cd7341c963c Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 17 Oct 2019 22:00:10 +0900 Subject: [PATCH 086/940] Update issue templates --- .github/ISSUE_TEMPLATE/bug_report.md | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) create mode 100644 .github/ISSUE_TEMPLATE/bug_report.md diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md new file mode 100644 index 0000000000..a643b49571 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -0,0 +1,21 @@ +--- +name: Bug report +about: Create a report to help us improve +title: '' +labels: '' +assignees: '' + +--- + +**Describe the bug** +A clear and concise description of what the bug is. + +**Expected behavior** +A clear and concise description of what you expected to happen. + +**Screenshots** +If applicable, add screenshots to help explain your problem. + +**Desktop (please complete the following information):** + - Python version (This repo only supports Python 3.7.x or higher). + - Each library version From afbcdfc0bdcd8a15b6b0503ae9027eb153d02afc Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 20 Oct 2019 11:27:37 +0900 Subject: [PATCH 087/940] update tests --- tests/test_dynamic_window_approach.py | 19 +++++++++---------- 1 file changed, 9 insertions(+), 10 deletions(-) diff --git a/tests/test_dynamic_window_approach.py b/tests/test_dynamic_window_approach.py index 890f000475..197dda2158 100644 --- a/tests/test_dynamic_window_approach.py +++ b/tests/test_dynamic_window_approach.py @@ -1,28 +1,27 @@ +import os +import sys from unittest import TestCase -import sys -import os sys.path.append(os.path.dirname(__file__) + "/../") try: from PathPlanning.DynamicWindowApproach import dynamic_window_approach as m -except: +except ImportError: raise print(__file__) -class Test(TestCase): - - def test1(self): +class TestDynamicWindowApproach(TestCase): + def test_main1(self): m.show_animation = False m.main(gx=1.0, gy=1.0) - def test2(self): + def test_main2(self): m.show_animation = False m.main(gx=1.0, gy=1.0, robot_type=m.RobotType.rectangle) if __name__ == '__main__': # pragma: no cover - test = Test() - test.test1() - test.test2() + test = TestDynamicWindowApproach() + test.test_main1() + test.test_main2() From 245838250bc1c2e23ee826026157aeb70d3116a5 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 20 Oct 2019 15:00:57 +0900 Subject: [PATCH 088/940] fix unittests. --- PathPlanning/LQRPlanner/LQRplanner.py | 4 ++-- tests/test_drone_3d_trajectory_following.py | 8 +++++--- tests/test_grid_based_sweep_coverage_path_planner.py | 3 +++ tests/test_n_joint_arm_to_point_control.py | 8 +++++--- 4 files changed, 15 insertions(+), 8 deletions(-) diff --git a/PathPlanning/LQRPlanner/LQRplanner.py b/PathPlanning/LQRPlanner/LQRplanner.py index e2000a957c..5a0b453f78 100644 --- a/PathPlanning/LQRPlanner/LQRplanner.py +++ b/PathPlanning/LQRPlanner/LQRplanner.py @@ -25,7 +25,7 @@ def __init__(self): self.MAX_ITER = 150 self.EPS = 0.01 - def lqr_planning(self, sx, sy, gx, gy, show_animation=SHOW_ANIMATION): + def lqr_planning(self, sx, sy, gx, gy, show_animation=True): rx, ry = [sx], [sy] @@ -129,7 +129,7 @@ def main(): gx = random.uniform(-area, area) gy = random.uniform(-area, area) - rx, ry = lqr_planner.lqr_planning(sx, sy, gx, gy) + rx, ry = lqr_planner.lqr_planning(sx, sy, gx, gy, show_animation=SHOW_ANIMATION) if SHOW_ANIMATION: # pragma: no cover plt.plot(sx, sy, "or") diff --git a/tests/test_drone_3d_trajectory_following.py b/tests/test_drone_3d_trajectory_following.py index 194a329946..dfadcdaee4 100644 --- a/tests/test_drone_3d_trajectory_following.py +++ b/tests/test_drone_3d_trajectory_following.py @@ -1,9 +1,11 @@ +import os +import sys from unittest import TestCase -import sys -sys.path.append("./AerialNavigation/drone_3d_trajectory_following/") +sys.path.append(os.path.dirname(__file__) + "/../AerialNavigation/drone_3d_trajectory_following/") + +import drone_3d_trajectory_following as m -from AerialNavigation.drone_3d_trajectory_following import drone_3d_trajectory_following as m print(__file__) diff --git a/tests/test_grid_based_sweep_coverage_path_planner.py b/tests/test_grid_based_sweep_coverage_path_planner.py index 3933356726..fa2d0a7a64 100644 --- a/tests/test_grid_based_sweep_coverage_path_planner.py +++ b/tests/test_grid_based_sweep_coverage_path_planner.py @@ -9,6 +9,9 @@ except ImportError: raise +grid_based_sweep_coverage_path_planner.do_animation = False + + class TestPlanning(TestCase): def test_planning1(self): diff --git a/tests/test_n_joint_arm_to_point_control.py b/tests/test_n_joint_arm_to_point_control.py index e39883559a..a935216475 100644 --- a/tests/test_n_joint_arm_to_point_control.py +++ b/tests/test_n_joint_arm_to_point_control.py @@ -1,9 +1,11 @@ +import os +import sys from unittest import TestCase -import sys -sys.path.append("./ArmNavigation/n_joint_arm_to_point_control/") +sys.path.append(os.path.dirname(__file__) + "/../ArmNavigation/n_joint_arm_to_point_control/") + +import n_joint_arm_to_point_control as m -from ArmNavigation.n_joint_arm_to_point_control import n_joint_arm_to_point_control as m print(__file__) From 692b7bd68411117204636f3534b4ea1eb661d872 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Wed, 23 Oct 2019 10:14:14 +0300 Subject: [PATCH 089/940] Fix wrong rotation direction - The obstacle rotation for the rectangle obstacle calculation is wrong. It should be positive instead of negative. --- PathPlanning/DynamicWindowApproach/dynamic_window_approach.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index c2a8674ae3..ebf254e110 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -172,7 +172,7 @@ def calc_obstacle_cost(trajectory, ob, config): rot = np.transpose(rot, [2, 0, 1]) local_ob = ob[:, None] - trajectory[:, 0:2] local_ob = local_ob.reshape(-1, local_ob.shape[-1]) - local_ob = np.array([local_ob @ -x for x in rot]) + local_ob = np.array([local_ob @ x for x in rot]) local_ob = local_ob.reshape(-1, local_ob.shape[-1]) upper_check = local_ob[:, 0] <= config.robot_length / 2 right_check = local_ob[:, 1] <= config.robot_width / 2 From 9f4102378a75b99ec3e8c2f9c465015a5ed2d093 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Wed, 23 Oct 2019 21:46:33 +0300 Subject: [PATCH 090/940] change resampling calculation to match with the book --- Localization/particle_filter/particle_filter.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 6643116f5a..8859b51428 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -141,9 +141,8 @@ def re_sampling(px, pw): N_eff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number if N_eff < NTh: w_cum = np.cumsum(pw) - base = np.cumsum(pw * 0.0 + 1 / NP) - 1 / NP - re_sample_id = base + np.random.rand(base.shape[0]) / NP - + base = np.arange(0.0, 1.0, 1/NP) + re_sample_id = base + np.random.uniform(0, 1/NP) indexes = [] ind = 0 for ip in range(NP): From 7a1784ad4798b4febd82a9a276fdae79a116a57b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Thu, 24 Oct 2019 19:43:22 +0300 Subject: [PATCH 091/940] condition check is moved condition check is moved from the inside of the resampling function to the outside of the function, this way the purpose of the function is much clear. Instead "resampling" every iteration, resample if the condition holds. --- .../particle_filter/particle_filter.py | 31 +++++++++---------- 1 file changed, 15 insertions(+), 16 deletions(-) diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 8859b51428..0ebb5fc3d1 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -128,8 +128,9 @@ def pf_localization(px, pw, z, u): xEst = px.dot(pw.T) PEst = calc_covariance(xEst, px, pw) - px, pw = re_sampling(px, pw) - + N_eff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number + if N_eff < NTh: + px, pw = re_sampling(px, pw) return xEst, PEst, px, pw @@ -138,20 +139,18 @@ def re_sampling(px, pw): low variance re-sampling """ - N_eff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number - if N_eff < NTh: - w_cum = np.cumsum(pw) - base = np.arange(0.0, 1.0, 1/NP) - re_sample_id = base + np.random.uniform(0, 1/NP) - indexes = [] - ind = 0 - for ip in range(NP): - while re_sample_id[ip] > w_cum[ind]: - ind += 1 - indexes.append(ind) - - px = px[:, indexes] - pw = np.zeros((1, NP)) + 1.0 / NP # init weight + w_cum = np.cumsum(pw) + base = np.arange(0.0, 1.0, 1/NP) + re_sample_id = base + np.random.uniform(0, 1/NP) + indexes = [] + ind = 0 + for ip in range(NP): + while re_sample_id[ip] > w_cum[ind]: + ind += 1 + indexes.append(ind) + + px = px[:, indexes] + pw = np.zeros((1, NP)) + 1.0 / NP # init weight return px, pw From bf0652970abe99f42e9e175c55da0d8e5e38f540 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Fri, 25 Oct 2019 15:30:16 +0300 Subject: [PATCH 092/940] optimize nearest_neighbor_assosiation --- .../iterative_closest_point.py | 22 ++++++------------- 1 file changed, 7 insertions(+), 15 deletions(-) diff --git a/SLAM/iterative_closest_point/iterative_closest_point.py b/SLAM/iterative_closest_point/iterative_closest_point.py index 73651d8ec5..924619fdf1 100644 --- a/SLAM/iterative_closest_point/iterative_closest_point.py +++ b/SLAM/iterative_closest_point/iterative_closest_point.py @@ -39,7 +39,7 @@ def ICP_matching(ppoints, cpoints): plt.plot(cpoints[0, :], cpoints[1, :], ".b") plt.plot(0.0, 0.0, "xr") plt.axis("equal") - plt.pause(1.0) + plt.pause(0.1) inds, error = nearest_neighbor_assosiation(ppoints, cpoints) Rt, Tt = SVD_motion_estimation(ppoints[:, inds], cpoints) @@ -93,18 +93,10 @@ def nearest_neighbor_assosiation(ppoints, cpoints): error = sum(d) # calc index with nearest neighbor assosiation - inds = [] - for i in range(cpoints.shape[1]): - minid = -1 - mind = float("inf") - for ii in range(ppoints.shape[1]): - d = np.linalg.norm(ppoints[:, ii] - cpoints[:, i]) - - if mind >= d: - mind = d - minid = ii - - inds.append(minid) + d = np.linalg.norm( + np.repeat(cpoints, ppoints.shape[1], axis=1) - np.tile(ppoints, (1, + cpoints.shape[1])), axis=0) + inds = np.argmin(d.reshape(cpoints.shape[1], ppoints.shape[1]), axis=1) return inds, error @@ -130,7 +122,7 @@ def main(): print(__file__ + " start!!") # simulation parameters - nPoint = 10 + nPoint = 1000 fieldLength = 50.0 motion = [0.5, 2.0, np.deg2rad(-10.0)] # movement [x[m],y[m],yaw[deg]] @@ -156,4 +148,4 @@ def main(): if __name__ == '__main__': - main() \ No newline at end of file + main() From b2d65f277ec9d7a122baaec7d2bf4a4b77c5d6a8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Sat, 26 Oct 2019 09:11:23 +0300 Subject: [PATCH 093/940] change resampling function to match with the book - changed resampling function so that it chooses random number once for the starting point. - condition check is moved from the inside of the resampling function to the outside of the function, this way the purpose of the function is much clear. Instead "resampling" every iteration, resample if the condition holds. --- .../particle_filter/particle_filter.py | 32 +++++++++---------- 1 file changed, 15 insertions(+), 17 deletions(-) diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 6643116f5a..0ebb5fc3d1 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -128,8 +128,9 @@ def pf_localization(px, pw, z, u): xEst = px.dot(pw.T) PEst = calc_covariance(xEst, px, pw) - px, pw = re_sampling(px, pw) - + N_eff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number + if N_eff < NTh: + px, pw = re_sampling(px, pw) return xEst, PEst, px, pw @@ -138,21 +139,18 @@ def re_sampling(px, pw): low variance re-sampling """ - N_eff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number - if N_eff < NTh: - w_cum = np.cumsum(pw) - base = np.cumsum(pw * 0.0 + 1 / NP) - 1 / NP - re_sample_id = base + np.random.rand(base.shape[0]) / NP - - indexes = [] - ind = 0 - for ip in range(NP): - while re_sample_id[ip] > w_cum[ind]: - ind += 1 - indexes.append(ind) - - px = px[:, indexes] - pw = np.zeros((1, NP)) + 1.0 / NP # init weight + w_cum = np.cumsum(pw) + base = np.arange(0.0, 1.0, 1/NP) + re_sample_id = base + np.random.uniform(0, 1/NP) + indexes = [] + ind = 0 + for ip in range(NP): + while re_sample_id[ip] > w_cum[ind]: + ind += 1 + indexes.append(ind) + + px = px[:, indexes] + pw = np.zeros((1, NP)) + 1.0 / NP # init weight return px, pw From 69772b4ad66cc27f7195659fff14e6c8006203b4 Mon Sep 17 00:00:00 2001 From: Mengge Jin Date: Sun, 27 Oct 2019 16:08:28 +0800 Subject: [PATCH 094/940] Remove PathLen in informed RRT* and instead with cBest --- PathPlanning/InformedRRTStar/informed_rrt_star.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 4a32801da5..6047660fb4 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -40,7 +40,6 @@ def informed_rrt_star_search(self, animation=True): self.node_list = [self.start] # max length we expect to find in our 'informed' sample space, starts as infinite cBest = float('inf') - pathLen = float('inf') solutionSet = set() path = None @@ -89,7 +88,7 @@ def informed_rrt_star_search(self, animation=True): lastIndex = len(self.node_list) - 1 tempPath = self.get_final_course(lastIndex) tempPathLen = self.get_path_len(tempPath) - if tempPathLen < pathLen: + if tempPathLen < cBest: path = tempPath cBest = tempPathLen From 342e671b34f7cced14388b3b33fc4c4dd7dd119f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Fri, 25 Oct 2019 15:30:16 +0300 Subject: [PATCH 095/940] optimize nearest_neighbor_assosiation - vectorize distance calculation - append authors --- .../iterative_closest_point.py | 24 +++++++------------ 1 file changed, 8 insertions(+), 16 deletions(-) diff --git a/SLAM/iterative_closest_point/iterative_closest_point.py b/SLAM/iterative_closest_point/iterative_closest_point.py index 73651d8ec5..ec81bb1233 100644 --- a/SLAM/iterative_closest_point/iterative_closest_point.py +++ b/SLAM/iterative_closest_point/iterative_closest_point.py @@ -1,6 +1,6 @@ """ Iterative Closest Point (ICP) SLAM example -author: Atsushi Sakai (@Atsushi_twi) +author: Atsushi Sakai (@Atsushi_twi), Göktuğ Karakaşlı """ import math @@ -39,7 +39,7 @@ def ICP_matching(ppoints, cpoints): plt.plot(cpoints[0, :], cpoints[1, :], ".b") plt.plot(0.0, 0.0, "xr") plt.axis("equal") - plt.pause(1.0) + plt.pause(0.1) inds, error = nearest_neighbor_assosiation(ppoints, cpoints) Rt, Tt = SVD_motion_estimation(ppoints[:, inds], cpoints) @@ -93,18 +93,10 @@ def nearest_neighbor_assosiation(ppoints, cpoints): error = sum(d) # calc index with nearest neighbor assosiation - inds = [] - for i in range(cpoints.shape[1]): - minid = -1 - mind = float("inf") - for ii in range(ppoints.shape[1]): - d = np.linalg.norm(ppoints[:, ii] - cpoints[:, i]) - - if mind >= d: - mind = d - minid = ii - - inds.append(minid) + d = np.linalg.norm( + np.repeat(cpoints, ppoints.shape[1], axis=1) - np.tile(ppoints, (1, + cpoints.shape[1])), axis=0) + inds = np.argmin(d.reshape(cpoints.shape[1], ppoints.shape[1]), axis=1) return inds, error @@ -130,7 +122,7 @@ def main(): print(__file__ + " start!!") # simulation parameters - nPoint = 10 + nPoint = 1000 fieldLength = 50.0 motion = [0.5, 2.0, np.deg2rad(-10.0)] # movement [x[m],y[m],yaw[deg]] @@ -156,4 +148,4 @@ def main(): if __name__ == '__main__': - main() \ No newline at end of file + main() From 97570de50c222c3362dfda765fd951f37cfb900f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Wed, 23 Oct 2019 10:14:14 +0300 Subject: [PATCH 096/940] Fix wrong rotation direction - The obstacle rotation for the rectangle obstacle calculation is wrong. It should be positive instead of negative. --- PathPlanning/DynamicWindowApproach/dynamic_window_approach.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index c2a8674ae3..c8a4434958 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -2,7 +2,7 @@ Mobile robot motion planning sample with Dynamic Window Approach -author: Atsushi Sakai (@Atsushi_twi), Goktug Karakasli +author: Atsushi Sakai (@Atsushi_twi), Göktuğ Karakaşlı """ @@ -172,7 +172,7 @@ def calc_obstacle_cost(trajectory, ob, config): rot = np.transpose(rot, [2, 0, 1]) local_ob = ob[:, None] - trajectory[:, 0:2] local_ob = local_ob.reshape(-1, local_ob.shape[-1]) - local_ob = np.array([local_ob @ -x for x in rot]) + local_ob = np.array([local_ob @ x for x in rot]) local_ob = local_ob.reshape(-1, local_ob.shape[-1]) upper_check = local_ob[:, 0] <= config.robot_length / 2 right_check = local_ob[:, 1] <= config.robot_width / 2 From 49ce57d6f8de1265eb1e578dd0f069c6b7a56ca6 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 27 Oct 2019 17:59:08 +0900 Subject: [PATCH 097/940] Code cleanup. --- .../iterative_closest_point.py | 57 +++++++++---------- tests/test_LQR_planner.py | 4 +- 2 files changed, 30 insertions(+), 31 deletions(-) diff --git a/SLAM/iterative_closest_point/iterative_closest_point.py b/SLAM/iterative_closest_point/iterative_closest_point.py index ec81bb1233..3512ef976b 100644 --- a/SLAM/iterative_closest_point/iterative_closest_point.py +++ b/SLAM/iterative_closest_point/iterative_closest_point.py @@ -4,22 +4,23 @@ """ import math -import numpy as np + import matplotlib.pyplot as plt +import numpy as np # ICP parameters EPS = 0.0001 -MAXITER = 100 +MAX_ITER = 100 show_animation = True -def ICP_matching(ppoints, cpoints): +def icp_matching(previous_points, current_points): """ Iterative Closest Point matching - input - ppoints: 2D points in the previous frame - cpoints: 2D points in the current frame + previous_points: 2D points in the previous frame + current_points: 2D points in the current frame - output R: Rotation matrix T: Translation vector @@ -35,17 +36,17 @@ def ICP_matching(ppoints, cpoints): if show_animation: # pragma: no cover plt.cla() - plt.plot(ppoints[0, :], ppoints[1, :], ".r") - plt.plot(cpoints[0, :], cpoints[1, :], ".b") + plt.plot(previous_points[0, :], previous_points[1, :], ".r") + plt.plot(current_points[0, :], current_points[1, :], ".b") plt.plot(0.0, 0.0, "xr") plt.axis("equal") plt.pause(0.1) - inds, error = nearest_neighbor_assosiation(ppoints, cpoints) - Rt, Tt = SVD_motion_estimation(ppoints[:, inds], cpoints) + indexes, error = nearest_neighbor_association(previous_points, current_points) + Rt, Tt = svd_motion_estimation(previous_points[:, indexes], current_points) # update current points - cpoints = (Rt @ cpoints) + Tt[:, np.newaxis] + current_points = (Rt @ current_points) + Tt[:, np.newaxis] H = update_homogeneous_matrix(H, Rt, Tt) @@ -56,7 +57,7 @@ def ICP_matching(ppoints, cpoints): if dError <= EPS: print("Converge", error, dError, count) break - elif MAXITER <= count: + elif MAX_ITER <= count: print("Not Converge...", error, dError, count) break @@ -85,31 +86,29 @@ def update_homogeneous_matrix(Hin, R, T): return Hin @ H -def nearest_neighbor_assosiation(ppoints, cpoints): +def nearest_neighbor_association(previous_points, current_points): # calc the sum of residual errors - dcpoints = ppoints - cpoints - d = np.linalg.norm(dcpoints, axis=0) + delta_points = previous_points - current_points + d = np.linalg.norm(delta_points, axis=0) error = sum(d) # calc index with nearest neighbor assosiation - d = np.linalg.norm( - np.repeat(cpoints, ppoints.shape[1], axis=1) - np.tile(ppoints, (1, - cpoints.shape[1])), axis=0) - inds = np.argmin(d.reshape(cpoints.shape[1], ppoints.shape[1]), axis=1) - - return inds, error + d = np.linalg.norm(np.repeat(current_points, previous_points.shape[1], axis=1) + - np.tile(previous_points, (1, current_points.shape[1])), axis=0) + indexes = np.argmin(d.reshape(current_points.shape[1], previous_points.shape[1]), axis=1) + return indexes, error -def SVD_motion_estimation(ppoints, cpoints): - pm = np.mean(ppoints, axis=1) - cm = np.mean(cpoints, axis=1) +def svd_motion_estimation(previous_points, current_points): + pm = np.mean(previous_points, axis=1) + cm = np.mean(current_points, axis=1) - pshift = ppoints - pm[:, np.newaxis] - cshift = cpoints - cm[:, np.newaxis] + p_shift = previous_points - pm[:, np.newaxis] + c_shift = current_points - cm[:, np.newaxis] - W = cshift @ pshift.T + W = c_shift @ p_shift.T u, s, vh = np.linalg.svd(W) R = (u @ vh).T @@ -133,16 +132,16 @@ def main(): # previous points px = (np.random.rand(nPoint) - 0.5) * fieldLength py = (np.random.rand(nPoint) - 0.5) * fieldLength - ppoints = np.vstack((px, py)) + previous_points = np.vstack((px, py)) # current points cx = [math.cos(motion[2]) * x - math.sin(motion[2]) * y + motion[0] for (x, y) in zip(px, py)] cy = [math.sin(motion[2]) * x + math.cos(motion[2]) * y + motion[1] for (x, y) in zip(px, py)] - cpoints = np.vstack((cx, cy)) + current_points = np.vstack((cx, cy)) - R, T = ICP_matching(ppoints, cpoints) + R, T = icp_matching(previous_points, current_points) print("R:", R) print("T:", T) diff --git a/tests/test_LQR_planner.py b/tests/test_LQR_planner.py index 5ece27f80b..2bcf828c38 100644 --- a/tests/test_LQR_planner.py +++ b/tests/test_LQR_planner.py @@ -1,6 +1,6 @@ +import sys from unittest import TestCase -import sys sys.path.append("./PathPlanning/LQRPlanner") from PathPlanning.LQRPlanner import LQRplanner as m @@ -11,5 +11,5 @@ class Test(TestCase): def test1(self): - m.show_animation = False + m.SHOW_ANIMATION = False m.main() From 3f14311cc54cb071b530a03b7a0245a61987c300 Mon Sep 17 00:00:00 2001 From: Francisco Moretti Date: Sun, 3 Nov 2019 12:07:56 -0300 Subject: [PATCH 098/940] correct variable name --- PathPlanning/InformedRRTStar/informed_rrt_star.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index b9769bea53..98a239ab6e 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -74,9 +74,9 @@ def informed_rrt_star_search(self, animation=True): newNode = self.get_new_node(theta, nind, nearestNode) d = self.line_cost(nearestNode, newNode) - isCollision = self.check_collision(nearestNode, theta, d) + noCollision = self.check_collision(nearestNode, theta, d) - if isCollision: + if noCollision: nearInds = self.find_near_nodes(newNode) newNode = self.choose_parent(newNode, nearInds) From 178dca3e343749b9e3ec3d1fda7a89f464532cda Mon Sep 17 00:00:00 2001 From: Francisco Moretti Date: Sun, 3 Nov 2019 12:12:53 -0300 Subject: [PATCH 099/940] add collision check to node near to goal --- .../InformedRRTStar/informed_rrt_star.py | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 98a239ab6e..a8352bc03f 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -84,6 +84,7 @@ def informed_rrt_star_search(self, animation=True): self.rewire(newNode, nearInds) if self.is_near_goal(newNode): + if self.check_segment_collision(newNode.x, newNode.y, self.goal.x , self.goal.y): solutionSet.add(newNode) lastIndex = len(self.node_list) - 1 tempPath = self.get_final_course(lastIndex) @@ -240,19 +241,23 @@ def distance_squared_point_to_segment(v, w, p): projection = v + t * (w - v) # Projection falls on the segment return (p-projection).dot(p-projection) - def check_collision(self, nearNode, theta, d): - tmpNode = copy.deepcopy(nearNode) - endx = tmpNode.x + math.cos(theta)*d - endy = tmpNode.y + math.sin(theta)*d + def check_segment_collision(self, x1, y1, x2, y2): for (ox, oy, size) in self.obstacle_list: dd = self.distance_squared_point_to_segment( - np.array([tmpNode.x, tmpNode.y]), - np.array([endx, endy]), + np.array([x1, y1]), + np.array([x2, y2]), np.array([ox, oy])) - if dd <= 1.1 * size**2: + if dd <= size**2: return False # collision return True + + def check_collision(self, nearNode, theta, d): + tmpNode = copy.deepcopy(nearNode) + endx = tmpNode.x + math.cos(theta)*d + endy = tmpNode.y + math.sin(theta)*d + return self.check_segment_collision(tmpNode.x, tmpNode.y, endx, endy) + def get_final_course(self, lastIndex): path = [[self.goal.x, self.goal.y]] while self.node_list[lastIndex].parent is not None: From 3e5cad819247edd892ae7f8f0192170e8a4c31bd Mon Sep 17 00:00:00 2001 From: Francisco Moretti Date: Sun, 3 Nov 2019 12:23:48 -0300 Subject: [PATCH 100/940] fix indentation --- PathPlanning/InformedRRTStar/informed_rrt_star.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index a8352bc03f..62a9406405 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -85,13 +85,13 @@ def informed_rrt_star_search(self, animation=True): if self.is_near_goal(newNode): if self.check_segment_collision(newNode.x, newNode.y, self.goal.x , self.goal.y): - solutionSet.add(newNode) - lastIndex = len(self.node_list) - 1 - tempPath = self.get_final_course(lastIndex) - tempPathLen = self.get_path_len(tempPath) - if tempPathLen < pathLen: - path = tempPath - cBest = tempPathLen + solutionSet.add(newNode) + lastIndex = len(self.node_list) - 1 + tempPath = self.get_final_course(lastIndex) + tempPathLen = self.get_path_len(tempPath) + if tempPathLen < pathLen: + path = tempPath + cBest = tempPathLen if animation: self.draw_graph(xCenter=xCenter, From 8b31c2bdf0cd1672f2282509e279540f76c2ef3a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 10:25:24 +0900 Subject: [PATCH 101/940] Create greetings.yml --- .github/workflows/greetings.yml | 13 +++++++++++++ 1 file changed, 13 insertions(+) create mode 100644 .github/workflows/greetings.yml diff --git a/.github/workflows/greetings.yml b/.github/workflows/greetings.yml new file mode 100644 index 0000000000..3da4a69458 --- /dev/null +++ b/.github/workflows/greetings.yml @@ -0,0 +1,13 @@ +name: Greetings + +on: [pull_request, issues] + +jobs: + greeting: + runs-on: ubuntu-latest + steps: + - uses: actions/first-interaction@v1 + with: + repo-token: ${{ secrets.GITHUB_TOKEN }} + issue-message: 'Message that will be displayed on users'' This is first issue for you on this project' + pr-message: 'Message that will be displayed on users'' This is first pr for you on this project' From 25ea5eb6c5a896350e6cd2c3ab2377ea2e9c1daa Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 10:34:19 +0900 Subject: [PATCH 102/940] Create pythonpackage.yml --- .github/workflows/pythonpackage.yml | 33 +++++++++++++++++++++++++++++ 1 file changed, 33 insertions(+) create mode 100644 .github/workflows/pythonpackage.yml diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml new file mode 100644 index 0000000000..901eb4c696 --- /dev/null +++ b/.github/workflows/pythonpackage.yml @@ -0,0 +1,33 @@ +name: Python package + +on: [push] + +jobs: + build: + + runs-on: ubuntu-latest + strategy: + max-parallel: 4 + matrix: + python-version: [3.5, 3.6, 3.7] + + steps: + - uses: actions/checkout@v1 + - name: Set up Python ${{ matrix.python-version }} + uses: actions/setup-python@v1 + with: + python-version: ${{ matrix.python-version }} + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install -r requirements.txt + - name: Lint with flake8 + run: | + pip install flake8 + # stop the build if there are Python syntax errors or undefined names + flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics + # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide + flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics + - name: Test with pytest + run: | + runtests.sh From 8877bc1a42d7853d949f00794385a16b488b3292 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 10:41:28 +0900 Subject: [PATCH 103/940] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 901eb4c696..c49c61de54 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -28,6 +28,6 @@ jobs: flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - - name: Test with pytest - run: | - runtests.sh + - name: Test + run: runtests.sh + shell: bash From 4d9ff51f27a11dbf615b5755781a3e1e961bb5a8 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 12:00:00 +0900 Subject: [PATCH 104/940] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index c49c61de54..b9f0adb822 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -28,6 +28,9 @@ jobs: flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics + - name: Test1 + run: ls + shell: bash - name: Test run: runtests.sh shell: bash From ecdff00fa2ee0d870b0c4b01fd2c92c52389ce21 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 13:15:57 +0900 Subject: [PATCH 105/940] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index b9f0adb822..4d6e3d3b03 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -28,9 +28,5 @@ jobs: flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - - name: Test1 - run: ls - shell: bash - name: Test - run: runtests.sh - shell: bash + run: bash runtests.sh From 27b6e19ea6f9d4b4e08b23b5db305e79a624e6bf Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 13:21:14 +0900 Subject: [PATCH 106/940] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 4d6e3d3b03..fbac68ac3b 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -28,5 +28,7 @@ jobs: flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics + - name: install coverage + run: pip insall coverage - name: Test run: bash runtests.sh From 157664857b9eb12181e1405c28b18928d7120a59 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 13:23:30 +0900 Subject: [PATCH 107/940] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index fbac68ac3b..fc70845789 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -29,6 +29,6 @@ jobs: # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - name: install coverage - run: pip insall coverage + run: pip install coverage - name: Test run: bash runtests.sh From 3333b34ce215b0287073fd250aa0c2813ed36e48 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 13:33:50 +0900 Subject: [PATCH 108/940] Update pythonpackage.yml --- .github/workflows/pythonpackage.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index fc70845789..a3203ff1ac 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -9,7 +9,7 @@ jobs: strategy: max-parallel: 4 matrix: - python-version: [3.5, 3.6, 3.7] + python-version: [3.6, 3.7] steps: - uses: actions/checkout@v1 From 0067577cbe500054bafc5ce6dd00a3effc68f88e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 17 Nov 2019 14:33:24 +0900 Subject: [PATCH 109/940] remove PoseOptimizationSLAM --- README.md | 17 ----------- SLAM/PoseOptimizationSLAM2D/README.md | 9 ------ .../PoseOptimizationSLAM2D/data_downloader.py | 28 ------------------- SLAM/PoseOptimizationSLAM3D/README.md | 25 ----------------- .../PoseOptimizationSLAM3D/data_downloader.py | 26 ----------------- 5 files changed, 105 deletions(-) delete mode 100644 SLAM/PoseOptimizationSLAM2D/README.md delete mode 100644 SLAM/PoseOptimizationSLAM2D/data_downloader.py delete mode 100644 SLAM/PoseOptimizationSLAM3D/README.md delete mode 100644 SLAM/PoseOptimizationSLAM3D/data_downloader.py diff --git a/README.md b/README.md index 1c455e928b..e740049b90 100644 --- a/README.md +++ b/README.md @@ -31,8 +31,6 @@ Python codes for robotics algorithm. * [SLAM](#slam) * [Iterative Closest Point (ICP) Matching](#iterative-closest-point-icp-matching) * [FastSLAM 1.0](#fastslam-10) - * [Pose Optimization SLAM 2D](#pose-optimization-slam-2d) - * [Pose Optimization SLAM 3D](#pose-optimization-slam-3d) * [Path Planning](#path-planning) * [Dynamic Window Approach](#dynamic-window-approach) * [Grid based search](#grid-based-search) @@ -251,21 +249,6 @@ Ref: - [SLAM simulations by Tim Bailey](http://www-personal.acfr.usyd.edu.au/tbailey/software/slam_simulations.htm) -## Pose Optimization SLAM 2D - -This is a graph based 2D pose optimization SLAM example. - -![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/PoseOptimizationSLAM2D/animation.gif) - - -## Pose Optimization SLAM 3D - -This is a graph based 3D pose optimization SLAM example. - -![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/PoseOptimizationSLAM3D/animation.gif) - - - # Path Planning ## Dynamic Window Approach diff --git a/SLAM/PoseOptimizationSLAM2D/README.md b/SLAM/PoseOptimizationSLAM2D/README.md deleted file mode 100644 index 612fa5186d..0000000000 --- a/SLAM/PoseOptimizationSLAM2D/README.md +++ /dev/null @@ -1,9 +0,0 @@ -# How to use - -1. Download data - ->$ python data_downloader.py - -2. run SLAM - ->$ python pose_optimization_slam.py diff --git a/SLAM/PoseOptimizationSLAM2D/data_downloader.py b/SLAM/PoseOptimizationSLAM2D/data_downloader.py deleted file mode 100644 index d1b8a2c23b..0000000000 --- a/SLAM/PoseOptimizationSLAM2D/data_downloader.py +++ /dev/null @@ -1,28 +0,0 @@ -""" - -Data down loader for pose optimization - -author: Atsushi Sakai - -""" - - -import subprocess -def main(): - print("start!!") - - cmd = "wget https://www.dropbox.com/s/vcz8cag7bo0zlaj/input_INTEL_g2o.g2o?dl=0 -O intel.g2o -nc" - subprocess.call(cmd, shell=True) - - cmd = "wget https://www.dropbox.com/s/d8fcn1jg1mebx8f/input_MITb_g2o.g2o?dl=0 -O mit_killian.g2o -nc" - - subprocess.call(cmd, shell=True) - cmd = "wget https://www.dropbox.com/s/gmdzo74b3tzvbrw/input_M3500_g2o.g2o?dl=0 -O manhattan3500.g2o -nc" - subprocess.call(cmd, shell=True) - - print("done!!") - - -if __name__ == '__main__': - main() - diff --git a/SLAM/PoseOptimizationSLAM3D/README.md b/SLAM/PoseOptimizationSLAM3D/README.md deleted file mode 100644 index 396a629735..0000000000 --- a/SLAM/PoseOptimizationSLAM3D/README.md +++ /dev/null @@ -1,25 +0,0 @@ -# PoseOptimizationSLAM3D -3D (x, y, z, qw, qx, qy, qz) pose optimization SLAM - -## How to use -1. Download data - -~~~ -python data_downloader.py -~~~ - -2. run SLAM - -~~~ -python pose_optimization_slam_3d.py -~~~ - -## Reference -- [A Compact and Portable Implementation of Graph\-based SLAM](https://www.researchgate.net/publication/321287640_A_Compact_and_Portable_Implementation_of_Graph-based_SLAM) - -- [GitHub \- furo\-org/p2o: Single header 2D/3D graph\-based SLAM library](https://github.com/furo-org/p2o) - -- [GitHub \- AtsushiSakai/PythonRobotics -/SLAM/PoseOptimizationSLAM](https://github.com/AtsushiSakai/PythonRobotics/tree/master/SLAM/PoseOptimizationSLAM) - -- [リー代数による3次元ポーズ調整\(Pose Adjustment\)\[PythonRobotics\]\[SLAM\] \- Qiita](https://qiita.com/saitosasaki/items/a0540cba994f08bf5e16#comment-3e6588e6b096cc2567d8) diff --git a/SLAM/PoseOptimizationSLAM3D/data_downloader.py b/SLAM/PoseOptimizationSLAM3D/data_downloader.py deleted file mode 100644 index a0c04fd1ab..0000000000 --- a/SLAM/PoseOptimizationSLAM3D/data_downloader.py +++ /dev/null @@ -1,26 +0,0 @@ -""" - -Data down loader for pose optimization - -author: Atsushi Sakai - -""" - -import subprocess - - -def main(): - print("start!!") - - cmd = "wget https://www.dropbox.com/s/zu23p8d522qccor/parking-garage.g2o?dl=0 -O parking-garage.g2o -nc" - subprocess.call(cmd, shell=True) - cmd = "wget http://www.furo.org/irie/datasets/torus3d_guess.g2o -nc" - subprocess.call(cmd, shell=True) - cmd = "wget http://www.furo.org/irie/datasets/sphere2200_guess.g2o -nc" - subprocess.call(cmd, shell=True) - - print("done!!") - - -if __name__ == '__main__': - main() From 54991efb8f335faf42fa665dce9dfecdc2833810 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 25 Nov 2019 21:54:32 +0900 Subject: [PATCH 110/940] Update FUNDING.yml --- .github/FUNDING.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/FUNDING.yml b/.github/FUNDING.yml index 80f4984c3f..24f0926299 100644 --- a/.github/FUNDING.yml +++ b/.github/FUNDING.yml @@ -1,3 +1,4 @@ # These are supported funding model platforms +github: AtsushiSakai patreon: myenigma custom: https://www.paypal.me/myenigmapay/ From 2fe00f8824842452345cbe180b4303e240c18a6c Mon Sep 17 00:00:00 2001 From: Michael Dobler Date: Thu, 28 Nov 2019 23:35:55 +0100 Subject: [PATCH 111/940] Fix jacobian of observation --- SLAM/EKFSLAM/ekf_slam.ipynb | 2 +- SLAM/EKFSLAM/ekf_slam.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/SLAM/EKFSLAM/ekf_slam.ipynb b/SLAM/EKFSLAM/ekf_slam.ipynb index 6509373d2b..f800939576 100644 --- a/SLAM/EKFSLAM/ekf_slam.ipynb +++ b/SLAM/EKFSLAM/ekf_slam.ipynb @@ -479,7 +479,7 @@ " \"\"\"\n", " sq = math.sqrt(q)\n", " G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]],\n", - " [delta[1, 0], - delta[0, 0], - 1.0, - delta[1, 0], delta[0, 0]]])\n", + " [delta[1, 0], - delta[0, 0], - q, - delta[1, 0], delta[0, 0]]])\n", "\n", " G = G / q\n", " nLM = calc_n_LM(x)\n", diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index ae39c9e0ea..84cf4d9701 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -177,7 +177,7 @@ def calc_innovation(lm, xEst, PEst, z, LMid): def jacob_h(q, delta, x, i): sq = math.sqrt(q) G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]], - [delta[1, 0], - delta[0, 0], - 1.0, - delta[1, 0], delta[0, 0]]]) + [delta[1, 0], - delta[0, 0], - q, - delta[1, 0], delta[0, 0]]]) G = G / q nLM = calc_n_lm(x) From 0b07425d2e8d97f61fb456d0969e1a64eeee33ba Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 30 Nov 2019 20:05:52 +0900 Subject: [PATCH 112/940] Code clen up --- SLAM/EKFSLAM/ekf_slam.py | 33 ++++++++++++++++----------------- 1 file changed, 16 insertions(+), 17 deletions(-) diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index 84cf4d9701..27e5035459 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -1,5 +1,6 @@ """ Extended Kalman Filter SLAM example + author: Atsushi Sakai (@Atsushi_twi) """ @@ -35,10 +36,10 @@ def ekf_slam(xEst, PEst, u, z): # Update for iz in range(len(z[:, 0])): # for each observation - minid = search_correspond_landmark_id(xEst, PEst, z[iz, 0:2]) + min_id = search_correspond_landmark_id(xEst, PEst, z[iz, 0:2]) nLM = calc_n_lm(xEst) - if minid == nLM: + if min_id == nLM: print("New LM") # Extend state and covariance matrix xAug = np.vstack((xEst, calc_landmark_position(xEst, z[iz, :]))) @@ -46,8 +47,8 @@ def ekf_slam(xEst, PEst, u, z): np.hstack((np.zeros((LM_SIZE, len(xEst))), initP)))) xEst = xAug PEst = PAug - lm = get_landmark_position_from_state(xEst, minid) - y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], minid) + lm = get_landmark_position_from_state(xEst, min_id) + y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], min_id) K = (PEst @ H.T) @ np.linalg.inv(S) xEst = xEst + (K @ y) @@ -60,8 +61,8 @@ def ekf_slam(xEst, PEst, u, z): def calc_input(): v = 1.0 # [m/s] - yawrate = 0.1 # [rad/s] - u = np.array([[v, yawrate]]).T + yaw_rate = 0.1 # [rad/s] + u = np.array([[v, yaw_rate]]).T return u @@ -79,8 +80,8 @@ def observation(xTrue, xd, u, RFID): angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise - anglen = angle + np.random.randn() * Q_sim[1, 1] ** 0.5 # add noise - zi = np.array([dn, anglen, i]) + angle_n = angle + np.random.randn() * Q_sim[1, 1] ** 0.5 # add noise + zi = np.array([dn, angle_n, i]) z = np.vstack((z, zi)) # add noise to input @@ -128,8 +129,6 @@ def calc_landmark_position(x, z): zp[0, 0] = x[0, 0] + z[0] * math.cos(x[2, 0] + z[1]) zp[1, 0] = x[1, 0] + z[0] * math.sin(x[2, 0] + z[1]) - # zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1]) - # zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1]) return zp @@ -147,25 +146,25 @@ def search_correspond_landmark_id(xAug, PAug, zi): nLM = calc_n_lm(xAug) - mdist = [] + min_dist = [] for i in range(nLM): lm = get_landmark_position_from_state(xAug, i) y, S, H = calc_innovation(lm, xAug, PAug, zi, i) - mdist.append(y.T @ np.linalg.inv(S) @ y) + min_dist.append(y.T @ np.linalg.inv(S) @ y) - mdist.append(M_DIST_TH) # new landmark + min_dist.append(M_DIST_TH) # new landmark - minid = mdist.index(min(mdist)) + min_id = min_dist.index(min(min_dist)) - return minid + return min_id def calc_innovation(lm, xEst, PEst, z, LMid): delta = lm - xEst[0:2] q = (delta.T @ delta)[0, 0] - zangle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0] - zp = np.array([[math.sqrt(q), pi_2_pi(zangle)]]) + z_angle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0] + zp = np.array([[math.sqrt(q), pi_2_pi(z_angle)]]) y = (z - zp).T y[1] = pi_2_pi(y[1]) H = jacob_h(q, delta, xEst, LMid + 1) From f26a91d5342c974b78e3cc3c820518c3400a08f7 Mon Sep 17 00:00:00 2001 From: harderthan Date: Tue, 3 Dec 2019 12:46:58 +0900 Subject: [PATCH 113/940] Update Kalmanfilter_basics.rst Edited the misspelling --- docs/modules/Kalmanfilter_basics.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/modules/Kalmanfilter_basics.rst b/docs/modules/Kalmanfilter_basics.rst index ce84fe0db4..7325dafdea 100644 --- a/docs/modules/Kalmanfilter_basics.rst +++ b/docs/modules/Kalmanfilter_basics.rst @@ -180,7 +180,7 @@ Central Limit Theorem ^^^^^^^^^^^^^^^^^^^^^ According to this theorem, the average of n samples of random and -independant variables tends to follow a normal distribution as we +independent variables tends to follow a normal distribution as we increase the sample size.(Generally, for n>=30) .. code-block:: ipython3 From 338b7945b6e12511dc1ae19166c1f32c3e9d313e Mon Sep 17 00:00:00 2001 From: harderthan Date: Tue, 3 Dec 2019 12:49:52 +0900 Subject: [PATCH 114/940] Update Kalmanfilter_basics Edited misspelling --- Localization/Kalmanfilter_basics.ipynb | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Localization/Kalmanfilter_basics.ipynb b/Localization/Kalmanfilter_basics.ipynb index 374287911b..b4913f9e7a 100644 --- a/Localization/Kalmanfilter_basics.ipynb +++ b/Localization/Kalmanfilter_basics.ipynb @@ -228,7 +228,7 @@ "\n", "#### Central Limit Theorem\n", "\n", - "According to this theorem, the average of n samples of random and independant variables tends to follow a normal distribution as we increase the sample size.(Generally, for n>=30)" + "According to this theorem, the average of n samples of random and independent variables tends to follow a normal distribution as we increase the sample size.(Generally, for n>=30)" ] }, { From 99c784948d9cfc8145ae208d5301c6bd1144f401 Mon Sep 17 00:00:00 2001 From: Michael Dobler Date: Fri, 6 Dec 2019 11:35:29 +0100 Subject: [PATCH 115/940] Use matrix multiplication instead of elementwise --- SLAM/EKFSLAM/ekf_slam.ipynb | 4 ++-- SLAM/EKFSLAM/ekf_slam.py | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/SLAM/EKFSLAM/ekf_slam.ipynb b/SLAM/EKFSLAM/ekf_slam.ipynb index f800939576..ccf5e5bbd6 100644 --- a/SLAM/EKFSLAM/ekf_slam.ipynb +++ b/SLAM/EKFSLAM/ekf_slam.ipynb @@ -309,7 +309,7 @@ " G, Fx = jacob_motion(xEst[0:S], u)\n", " # Fx is an an identity matrix of size (STATE_SIZE)\n", " # sigma = G*sigma*G.T + Noise\n", - " PEst[0:S, 0:S] = G.T * PEst[0:S, 0:S] * G + Fx.T * Cx * Fx\n", + " PEst[0:S, 0:S] = G.T @ PEst[0:S, 0:S] @ G + Fx.T @ Cx @ Fx\n", " return xEst, PEst, G, Fx" ] }, @@ -584,7 +584,7 @@ " [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])],\n", " [0.0, 0.0, 0.0]])\n", "\n", - " G = np.eye(STATE_SIZE) + Fx.T * jF * Fx\n", + " G = np.eye(STATE_SIZE) + Fx.T @ jF @ Fx\n", " if calc_n_LM(x) > 0:\n", " print(Fx.shape)\n", " return G, Fx,\n", diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index 27e5035459..22ccd8d659 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -31,7 +31,7 @@ def ekf_slam(xEst, PEst, u, z): S = STATE_SIZE xEst[0:S] = motion_model(xEst[0:S], u) G, Fx = jacob_motion(xEst[0:S], u) - PEst[0:S, 0:S] = G.T * PEst[0:S, 0:S] * G + Fx.T * Cx * Fx + PEst[0:S, 0:S] = G.T @ PEst[0:S, 0:S] @ G + Fx.T @ Cx @ Fx initP = np.eye(2) # Update @@ -119,7 +119,7 @@ def jacob_motion(x, u): [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])], [0.0, 0.0, 0.0]]) - G = np.eye(STATE_SIZE) + Fx.T * jF * Fx + G = np.eye(STATE_SIZE) + Fx.T @ jF @ Fx return G, Fx, From dacff1c97c21b915199493492e303a6e11031faa Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 7 Dec 2019 20:23:36 +0900 Subject: [PATCH 116/940] Fixed kmeans clustering bug #251 --- .../kmeans_clustering/kmeans_clustering.py | 174 +++++++----------- 1 file changed, 71 insertions(+), 103 deletions(-) diff --git a/Mapping/kmeans_clustering/kmeans_clustering.py b/Mapping/kmeans_clustering/kmeans_clustering.py index 8edfa11e3a..bdaa45455e 100644 --- a/Mapping/kmeans_clustering/kmeans_clustering.py +++ b/Mapping/kmeans_clustering/kmeans_clustering.py @@ -6,97 +6,87 @@ """ -import numpy as np import math import matplotlib.pyplot as plt import random +# k means parameters +MAX_LOOP = 10 +DCOST_TH = 0.1 show_animation = True -class Clusters: - - def __init__(self, x, y, nlabel): - self.x = x - self.y = y - self.ndata = len(self.x) - self.nlabel = nlabel - self.labels = [random.randint(0, nlabel - 1) - for _ in range(self.ndata)] - self.cx = [0.0 for _ in range(nlabel)] - self.cy = [0.0 for _ in range(nlabel)] - - def kmeans_clustering(rx, ry, nc): - clusters = Clusters(rx, ry, nc) - clusters = calc_centroid(clusters) + clusters.calc_centroid() - MAX_LOOP = 10 - DCOST_TH = 0.1 - pcost = 100.0 + pre_cost = float("inf") for loop in range(MAX_LOOP): - # print("Loop:", loop) - clusters, cost = update_clusters(clusters) - clusters = calc_centroid(clusters) + print("loop:", loop) + cost = clusters.update_clusters() + clusters.calc_centroid() - dcost = abs(cost - pcost) - if dcost < DCOST_TH: + d_cost = abs(cost - pre_cost) + if d_cost < DCOST_TH: break - pcost = cost + pre_cost = cost return clusters -def calc_centroid(clusters): - - for ic in range(clusters.nlabel): - x, y = calc_labeled_points(ic, clusters) - ndata = len(x) - clusters.cx[ic] = sum(x) / ndata - clusters.cy[ic] = sum(y) / ndata - - return clusters - - -def update_clusters(clusters): - cost = 0.0 - - for ip in range(clusters.ndata): - px = clusters.x[ip] - py = clusters.y[ip] - - dx = [icx - px for icx in clusters.cx] - dy = [icy - py for icy in clusters.cy] - - dlist = [math.sqrt(idx**2 + idy**2) for (idx, idy) in zip(dx, dy)] - mind = min(dlist) - min_id = dlist.index(mind) - clusters.labels[ip] = min_id - cost += mind - - return clusters, cost - - -def calc_labeled_points(ic, clusters): - - inds = np.array([i for i in range(clusters.ndata) - if clusters.labels[i] == ic]) - tx = np.array(clusters.x) - ty = np.array(clusters.y) - - x = tx[inds] - y = ty[inds] - - return x, y - - -def calc_raw_data(cx, cy, npoints, rand_d): +class Clusters: + def __init__(self, x, y, n_label): + self.x = x + self.y = y + self.n_data = len(self.x) + self.n_label = n_label + self.labels = [random.randint(0, n_label - 1) + for _ in range(self.n_data)] + self.center_x = [0.0 for _ in range(n_label)] + self.center_y = [0.0 for _ in range(n_label)] + + def plot_cluster(self): + for label in set(self.labels): + x, y = self._get_labeled_x_y(label) + plt.plot(x, y, ".") + + def calc_centroid(self): + for label in set(self.labels): + x, y = self._get_labeled_x_y(label) + n_data = len(x) + self.center_x[label] = sum(x) / n_data + self.center_y[label] = sum(y) / n_data + + def update_clusters(self): + cost = 0.0 + + for ip in range(self.n_data): + px = self.x[ip] + py = self.y[ip] + + dx = [icx - px for icx in self.center_x] + dy = [icy - py for icy in self.center_y] + + dist_list = [math.sqrt(idx ** 2 + idy ** 2) for (idx, idy) in zip(dx, dy)] + min_dist = min(dist_list) + min_id = dist_list.index(min_dist) + self.labels[ip] = min_id + cost += min_dist + + return cost + + def _get_labeled_x_y(self, target_label): + x = [self.x[i] for i, label in enumerate(self.labels) if label == target_label] + y = [self.y[i] for i, label in enumerate(self.labels) if label == target_label] + return x, y + + +def calc_raw_data(cx, cy, n_points, rand_d): rx, ry = [], [] for (icx, icy) in zip(cx, cy): - for _ in range(npoints): + for _ in range(n_points): rx.append(icx + rand_d * (random.random() - 0.5)) ry.append(icy + rand_d * (random.random() - 0.5)) @@ -104,48 +94,28 @@ def calc_raw_data(cx, cy, npoints, rand_d): def update_positions(cx, cy): - + # object moving parameters DX1 = 0.4 DY1 = 0.5 - - cx[0] += DX1 - cy[0] += DY1 - DX2 = -0.3 DY2 = -0.5 + cx[0] += DX1 + cy[0] += DY1 cx[1] += DX2 cy[1] += DY2 return cx, cy -def calc_association(cx, cy, clusters): - - inds = [] - - for ic, _ in enumerate(cx): - tcx = cx[ic] - tcy = cy[ic] - - dx = [icx - tcx for icx in clusters.cx] - dy = [icy - tcy for icy in clusters.cy] - - dlist = [math.sqrt(idx**2 + idy**2) for (idx, idy) in zip(dx, dy)] - min_id = dlist.index(min(dlist)) - inds.append(min_id) - - return inds - - def main(): print(__file__ + " start!!") cx = [0.0, 8.0] cy = [0.0, 8.0] - npoints = 10 + n_points = 10 rand_d = 3.0 - ncluster = 2 + n_cluster = 2 sim_time = 15.0 dt = 1.0 time = 0.0 @@ -154,20 +124,18 @@ def main(): print("Time:", time) time += dt - # simulate objects + # objects moving simulation cx, cy = update_positions(cx, cy) - rx, ry = calc_raw_data(cx, cy, npoints, rand_d) + raw_x, raw_y = calc_raw_data(cx, cy, n_points, rand_d) - clusters = kmeans_clustering(rx, ry, ncluster) + clusters = kmeans_clustering(raw_x, raw_y, n_cluster) # for animation if show_animation: # pragma: no cover plt.cla() - inds = calc_association(cx, cy, clusters) - for ic in inds: - x, y = calc_labeled_points(ic, clusters) - plt.plot(x, y, "x") - plt.plot(cx, cy, "o") + clusters.plot_cluster() + + plt.plot(cx, cy, "or") plt.xlim(-2.0, 10.0) plt.ylim(-2.0, 10.0) plt.pause(dt) From d019e416ba051a08db153c3177ef97a715031ed8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Sat, 7 Dec 2019 14:30:18 +0300 Subject: [PATCH 117/940] exit on key --- AerialNavigation/drone_3d_trajectory_following/Quadrotor.py | 6 ++++-- .../rocket_powered_landing/rocket_powered_landing.py | 2 ++ .../arm_obstacle_navigation/arm_obstacle_navigation.py | 4 +++- .../arm_obstacle_navigation/arm_obstacle_navigation_2.py | 2 ++ ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py | 2 ++ .../two_joint_arm_to_point_control.py | 2 ++ Bipedal/bipedal_planner/bipedal_planner.py | 2 ++ .../ensemble_kalman_filter/ensemble_kalman_filter.py | 2 ++ .../extended_kalman_filter/extended_kalman_filter.py | 2 ++ Localization/histogram_filter/histogram_filter.py | 2 ++ Localization/particle_filter/particle_filter.py | 2 ++ .../unscented_kalman_filter/unscented_kalman_filter.py | 2 ++ Mapping/circle_fitting/circle_fitting.py | 2 ++ Mapping/gaussian_grid_map/gaussian_grid_map.py | 2 ++ Mapping/kmeans_clustering/kmeans_clustering.py | 2 ++ Mapping/raycasting_grid_map/raycasting_grid_map.py | 2 ++ Mapping/rectangle_fitting/rectangle_fitting.py | 2 ++ PathPlanning/AStar/a_star.py | 2 ++ PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py | 2 ++ PathPlanning/ClosedLoopRRTStar/pure_pursuit.py | 2 ++ PathPlanning/Dijkstra/dijkstra.py | 2 ++ PathPlanning/DubinsPath/dubins_path_planning.py | 2 ++ .../DynamicWindowApproach/dynamic_window_approach.py | 2 ++ PathPlanning/Eta3SplinePath/eta3_spline_path.py | 2 ++ .../FrenetOptimalTrajectory/frenet_optimal_trajectory.py | 2 ++ .../grid_based_sweep_coverage_path_planner.py | 4 ++++ PathPlanning/HybridAStar/a_star.py | 4 +++- PathPlanning/HybridAStar/hybrid_a_star.py | 2 ++ PathPlanning/InformedRRTStar/informed_rrt_star.py | 3 ++- PathPlanning/LQRPlanner/LQRplanner.py | 2 ++ PathPlanning/LQRRRTStar/lqr_rrt_star.py | 2 ++ .../PotentialFieldPlanning/potential_field_planning.py | 2 ++ PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py | 2 ++ .../quintic_polynomials_planner.py | 2 ++ PathPlanning/RRT/rrt.py | 2 ++ PathPlanning/RRTDubins/rrt_dubins.py | 2 ++ PathPlanning/RRTStarDubins/rrt_star_dubins.py | 2 ++ PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py | 2 ++ PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py | 2 ++ PathPlanning/VoronoiRoadMap/voronoi_road_map.py | 2 ++ PathTracking/cgmres_nmpc/cgmres_nmpc.py | 2 ++ .../lqr_speed_steer_control/lqr_speed_steer_control.py | 2 ++ PathTracking/lqr_steer_control/lqr_steer_control.py | 2 ++ .../model_predictive_speed_and_steer_control.py | 2 ++ PathTracking/move_to_pose/move_to_pose.py | 3 +++ PathTracking/pure_pursuit/pure_pursuit.py | 2 ++ PathTracking/rear_wheel_feedback/rear_wheel_feedback.py | 2 ++ PathTracking/stanley_controller/stanley_controller.py | 2 ++ SLAM/EKFSLAM/ekf_slam.py | 2 ++ SLAM/FastSLAM1/fast_slam1.py | 2 ++ SLAM/FastSLAM2/fast_slam2.py | 2 ++ SLAM/GraphBasedSLAM/graph_based_slam.py | 5 +++-- SLAM/iterative_closest_point/iterative_closest_point.py | 2 ++ 53 files changed, 114 insertions(+), 7 deletions(-) diff --git a/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py b/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py index 9b38677cbe..89171da212 100644 --- a/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py +++ b/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py @@ -8,7 +8,6 @@ import numpy as np import matplotlib.pyplot as plt - class Quadrotor(): def __init__(self, x=0, y=0, z=0, roll=0, pitch=0, yaw=0, size=0.25, show_animation=True): self.p1 = np.array([size / 2, 0, 0, 1]).T @@ -24,6 +23,9 @@ def __init__(self, x=0, y=0, z=0, roll=0, pitch=0, yaw=0, size=0.25, show_animat if self.show_animation: plt.ion() fig = plt.figure() + fig.canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + self.ax = fig.add_subplot(111, projection='3d') self.update_pose(x, y, z, roll, pitch, yaw) @@ -81,4 +83,4 @@ def plot(self): # pragma: no cover plt.ylim(-5, 5) self.ax.set_zlim(0, 10) - plt.pause(0.001) \ No newline at end of file + plt.pause(0.001) diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py index 9f1e16fc1d..c7ab998bec 100644 --- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py +++ b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py @@ -567,6 +567,8 @@ def plot_animation(X, U): # pragma: no cover fig = plt.figure() ax = fig.gca(projection='3d') + rig.canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) for k in range(K): plt.cla() diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py index 2bcc33d0f7..b435e62d2b 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py @@ -162,6 +162,8 @@ def astar_torus(grid, start_node, goal_node): for i in range(1, len(route)): grid[route[i]] = 6 plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.imshow(grid, cmap=cmap, norm=norm, interpolation=None) plt.show() plt.pause(1e-2) @@ -262,4 +264,4 @@ def plot(self, obstacles=[]): # pragma: no cover if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py index b8c1ce89e9..5a21b806d3 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py @@ -193,6 +193,8 @@ def astar_torus(grid, start_node, goal_node): for i in range(1, len(route)): grid[route[i]] = 6 plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.imshow(grid, cmap=cmap, norm=norm, interpolation=None) plt.show() plt.pause(1e-2) diff --git a/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py b/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py index 8ed12c565b..576bd29a8f 100644 --- a/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py +++ b/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py @@ -51,6 +51,8 @@ def update_points(self): def plot(self): # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) for i in range(self.n_links + 1): if i is not self.n_links: diff --git a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py index e674ae8ac2..134583a95c 100644 --- a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py +++ b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py @@ -114,6 +114,8 @@ def animation(): def main(): # pragma: no cover fig = plt.figure() fig.canvas.mpl_connect("button_press_event", click) + fig.canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) two_joint_arm() diff --git a/Bipedal/bipedal_planner/bipedal_planner.py b/Bipedal/bipedal_planner/bipedal_planner.py index 3cf2936ee4..afa68afb25 100644 --- a/Bipedal/bipedal_planner/bipedal_planner.py +++ b/Bipedal/bipedal_planner/bipedal_planner.py @@ -111,6 +111,8 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False): if c > len(com_trajectory_for_plot): # set up plotter plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) ax.set_zlim(0, z_c * 2) ax.set_aspect('equal', 'datalim') diff --git a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py index 293509157b..6ac6144f36 100644 --- a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py +++ b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py @@ -213,6 +213,8 @@ def main(): if show_animation: plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) for i in range(len(z[:, 0])): plt.plot([xTrue[0, 0], z[i, 2]], [xTrue[1, 0], z[i, 3]], "-k") diff --git a/Localization/extended_kalman_filter/extended_kalman_filter.py b/Localization/extended_kalman_filter/extended_kalman_filter.py index d2d7178ae6..029dac4bf8 100644 --- a/Localization/extended_kalman_filter/extended_kalman_filter.py +++ b/Localization/extended_kalman_filter/extended_kalman_filter.py @@ -191,6 +191,8 @@ def main(): if show_animation: plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(hz[0, :], hz[1, :], ".g") plt.plot(hxTrue[0, :].flatten(), hxTrue[1, :].flatten(), "-b") diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index bdfbb13fa7..ac07c59fbd 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -233,6 +233,8 @@ def main(): if show_animation: plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) draw_heat_map(grid_map.data, mx, my) plt.plot(xTrue[0, :], xTrue[1, :], "xr") plt.plot(RF_ID[:, 0], RF_ID[:, 1], ".k") diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 0ebb5fc3d1..4b9abd78bd 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -230,6 +230,8 @@ def main(): if show_animation: plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) for i in range(len(z[:, 0])): plt.plot([xTrue[0, 0], z[i, 1]], [xTrue[1, 0], z[i, 2]], "-k") diff --git a/Localization/unscented_kalman_filter/unscented_kalman_filter.py b/Localization/unscented_kalman_filter/unscented_kalman_filter.py index 45d5b78132..0005d12fe7 100644 --- a/Localization/unscented_kalman_filter/unscented_kalman_filter.py +++ b/Localization/unscented_kalman_filter/unscented_kalman_filter.py @@ -240,6 +240,8 @@ def main(): if show_animation: plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(hz[0, :], hz[1, :], ".g") plt.plot(np.array(hxTrue[0, :]).flatten(), np.array(hxTrue[1, :]).flatten(), "-b") diff --git a/Mapping/circle_fitting/circle_fitting.py b/Mapping/circle_fitting/circle_fitting.py index dae9413d27..27ceac21f7 100644 --- a/Mapping/circle_fitting/circle_fitting.py +++ b/Mapping/circle_fitting/circle_fitting.py @@ -124,6 +124,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.axis("equal") plt.plot(0.0, 0.0, "*r") plot_circle(cx, cy, cr) diff --git a/Mapping/gaussian_grid_map/gaussian_grid_map.py b/Mapping/gaussian_grid_map/gaussian_grid_map.py index b520b63944..094b094fdd 100644 --- a/Mapping/gaussian_grid_map/gaussian_grid_map.py +++ b/Mapping/gaussian_grid_map/gaussian_grid_map.py @@ -73,6 +73,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) draw_heatmap(gmap, minx, maxx, miny, maxy, xyreso) plt.plot(ox, oy, "xr") plt.plot(0.0, 0.0, "ob") diff --git a/Mapping/kmeans_clustering/kmeans_clustering.py b/Mapping/kmeans_clustering/kmeans_clustering.py index 8edfa11e3a..7900e30457 100644 --- a/Mapping/kmeans_clustering/kmeans_clustering.py +++ b/Mapping/kmeans_clustering/kmeans_clustering.py @@ -163,6 +163,8 @@ def main(): # for animation if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) inds = calc_association(cx, cy, clusters) for ic in inds: x, y = calc_labeled_points(ic, clusters) diff --git a/Mapping/raycasting_grid_map/raycasting_grid_map.py b/Mapping/raycasting_grid_map/raycasting_grid_map.py index 997687423e..cae92a9dcb 100644 --- a/Mapping/raycasting_grid_map/raycasting_grid_map.py +++ b/Mapping/raycasting_grid_map/raycasting_grid_map.py @@ -124,6 +124,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) draw_heatmap(pmap, minx, maxx, miny, maxy, xyreso) plt.plot(ox, oy, "xr") plt.plot(0.0, 0.0, "ob") diff --git a/Mapping/rectangle_fitting/rectangle_fitting.py b/Mapping/rectangle_fitting/rectangle_fitting.py index e40fc2e4c7..77c66db250 100644 --- a/Mapping/rectangle_fitting/rectangle_fitting.py +++ b/Mapping/rectangle_fitting/rectangle_fitting.py @@ -242,6 +242,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.axis("equal") plt.plot(0.0, 0.0, "*r") v1.plot() diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py index 6b0392f515..e4f7dd4d97 100644 --- a/PathPlanning/AStar/a_star.py +++ b/PathPlanning/AStar/a_star.py @@ -79,6 +79,8 @@ def planning(self, sx, sy, gx, gy): if show_animation: # pragma: no cover plt.plot(self.calc_grid_position(current.x, self.minx), self.calc_grid_position(current.y, self.miny), "xc") + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if len(closed_set.keys()) % 10 == 0: plt.pause(0.001) diff --git a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py index 37ac75ada9..46ff3caf5c 100644 --- a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py +++ b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py @@ -534,6 +534,8 @@ def update_graph(self): def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, samples=None, start=None, end=None): plt.clf() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) for rnd in samples: if rnd is not None: plt.plot(rnd[0], rnd[1], "^k") diff --git a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py index 0490727933..d078338d67 100644 --- a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py +++ b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py @@ -135,6 +135,8 @@ def closed_loop_prediction(cx, cy, cyaw, speed_profile, goal): if target_ind % 1 == 0 and animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, "-r", label="course") plt.plot(x, y, "ob", label="trajectory") plt.plot(cx[target_ind], cy[target_ind], "xg", label="target") diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index bb73ed501a..8e719f50e2 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -69,6 +69,8 @@ def planning(self, sx, sy, gx, gy): if show_animation: # pragma: no cover plt.plot(self.calc_position(current.x, self.minx), self.calc_position(current.y, self.miny), "xc") + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if len(closedset.keys()) % 10 == 0: plt.pause(0.001) diff --git a/PathPlanning/DubinsPath/dubins_path_planning.py b/PathPlanning/DubinsPath/dubins_path_planning.py index 706b5a49af..8690fbe8db 100644 --- a/PathPlanning/DubinsPath/dubins_path_planning.py +++ b/PathPlanning/DubinsPath/dubins_path_planning.py @@ -318,6 +318,8 @@ def test(): if show_animation: plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(px, py, label="final course " + str(mode)) # plotting diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index c8a4434958..c2cc358b13 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -268,6 +268,8 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): if show_animation: plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(predicted_trajectory[:, 0], predicted_trajectory[:, 1], "-g") plt.plot(x[0], x[1], "xr") plt.plot(goal[0], goal[1], "xb") diff --git a/PathPlanning/Eta3SplinePath/eta3_spline_path.py b/PathPlanning/Eta3SplinePath/eta3_spline_path.py index 072b0bb46c..51ac612c28 100644 --- a/PathPlanning/Eta3SplinePath/eta3_spline_path.py +++ b/PathPlanning/Eta3SplinePath/eta3_spline_path.py @@ -213,6 +213,8 @@ def test1(): if show_animation: # plot the path plt.plot(pos[0, :], pos[1, :]) + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.pause(1.0) if show_animation: diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index 5c756a9dfe..1abda92646 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -347,6 +347,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(tx, ty) plt.plot(ob[:, 0], ob[:, 1], "xk") plt.plot(path.x[1:], path.y[1:], "-or") diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py index f22b058fa8..049373ece2 100644 --- a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py +++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py @@ -213,6 +213,8 @@ def sweep_path_search(sweep_searcher, gmap, grid_search_animation=False): if grid_search_animation: fig, ax = plt.subplots() + fig.canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) while True: cxind, cyind = sweep_searcher.move_target_grid(cxind, cyind, gmap) @@ -266,6 +268,8 @@ def planning_animation(ox, oy, reso): # pragma: no cover if do_animation: for ipx, ipy in zip(px, py): plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(ox, oy, "-xb") plt.plot(px, py, "-r") plt.plot(ipx, ipy, "or") diff --git a/PathPlanning/HybridAStar/a_star.py b/PathPlanning/HybridAStar/a_star.py index c1c82edd0d..918469f0d3 100644 --- a/PathPlanning/HybridAStar/a_star.py +++ b/PathPlanning/HybridAStar/a_star.py @@ -78,6 +78,8 @@ def dp_planning(sx, sy, gx, gy, ox, oy, reso, rr): # show graph if show_animation: # pragma: no cover plt.plot(current.x * reso, current.y * reso, "xc") + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if len(closedset.keys()) % 10 == 0: plt.pause(0.001) @@ -228,4 +230,4 @@ def main(): if __name__ == '__main__': show_animation = True - main() \ No newline at end of file + main() diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index e82003ed25..70ffcee865 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -327,6 +327,8 @@ def hybrid_a_star_planning(start, goal, ox, oy, xyreso, yawreso): if show_animation: # pragma: no cover plt.plot(current.xlist[-1], current.ylist[-1], "xc") + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if len(closedList.keys()) % 10 == 0: plt.pause(0.001) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 175749183d..ef15022aca 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -266,8 +266,9 @@ def get_final_course(self, lastIndex): return path def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, rnd=None): - plt.clf() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd[0], rnd[1], "^k") if cBest != float('inf'): diff --git a/PathPlanning/LQRPlanner/LQRplanner.py b/PathPlanning/LQRPlanner/LQRplanner.py index 5a0b453f78..d5cda0bc50 100644 --- a/PathPlanning/LQRPlanner/LQRplanner.py +++ b/PathPlanning/LQRPlanner/LQRplanner.py @@ -54,6 +54,8 @@ def lqr_planning(self, sx, sy, gx, gy, show_animation=True): # animation if show_animation: # pragma: no cover + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(sx, sy, "or") plt.plot(gx, gy, "ob") plt.plot(rx, ry, "-r") diff --git a/PathPlanning/LQRRRTStar/lqr_rrt_star.py b/PathPlanning/LQRRRTStar/lqr_rrt_star.py index 2e276b9f9b..c1f45445ff 100644 --- a/PathPlanning/LQRRRTStar/lqr_rrt_star.py +++ b/PathPlanning/LQRRRTStar/lqr_rrt_star.py @@ -102,6 +102,8 @@ def planning(self, animation=True, search_until_max_iter=True): def draw_graph(self, rnd=None): plt.clf() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: diff --git a/PathPlanning/PotentialFieldPlanning/potential_field_planning.py b/PathPlanning/PotentialFieldPlanning/potential_field_planning.py index 1e918fb158..642f1cbff9 100644 --- a/PathPlanning/PotentialFieldPlanning/potential_field_planning.py +++ b/PathPlanning/PotentialFieldPlanning/potential_field_planning.py @@ -98,6 +98,8 @@ def potential_field_planning(sx, sy, gx, gy, ox, oy, reso, rr): if show_animation: draw_heatmap(pmap) + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(ix, iy, "*k") plt.plot(gix, giy, "*m") diff --git a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py index 351232d849..3fef2d0f7a 100644 --- a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py +++ b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py @@ -194,6 +194,8 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): # show graph if show_animation and len(closedset.keys()) % 2 == 0: + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(current.x, current.y, "xg") plt.pause(0.001) diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py index ecef7d454c..b8d533d4dc 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py @@ -151,6 +151,8 @@ def quintic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_ if show_animation: # pragma: no cover for i, _ in enumerate(time): plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.grid(True) plt.axis("equal") plot_arrow(sx, sy, syaw) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 3bcc622100..9d0bc36272 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -138,6 +138,8 @@ def get_random_node(self): def draw_graph(self, rnd=None): plt.clf() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: diff --git a/PathPlanning/RRTDubins/rrt_dubins.py b/PathPlanning/RRTDubins/rrt_dubins.py index 339acd2c3a..2a842aa42c 100644 --- a/PathPlanning/RRTDubins/rrt_dubins.py +++ b/PathPlanning/RRTDubins/rrt_dubins.py @@ -106,6 +106,8 @@ def planning(self, animation=True, search_until_max_iter=True): def draw_graph(self, rnd=None): # pragma: no cover plt.clf() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: diff --git a/PathPlanning/RRTStarDubins/rrt_star_dubins.py b/PathPlanning/RRTStarDubins/rrt_star_dubins.py index 4d7312933d..d4601c0f12 100644 --- a/PathPlanning/RRTStarDubins/rrt_star_dubins.py +++ b/PathPlanning/RRTStarDubins/rrt_star_dubins.py @@ -112,6 +112,8 @@ def planning(self, animation=True, search_until_max_iter=True): def draw_graph(self, rnd=None): plt.clf() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: diff --git a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py index 5d78f98f31..d37ae90634 100644 --- a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py +++ b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py @@ -122,6 +122,8 @@ def try_goal_path(self, node): def draw_graph(self, rnd=None): plt.clf() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py index 54b5adbe6d..b2f8d4a57d 100644 --- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py +++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py @@ -395,6 +395,8 @@ def test(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(px, py, label="final course " + str(mode)) # plotting diff --git a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py index 3ac02993b7..86371b2051 100644 --- a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py +++ b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py @@ -185,6 +185,8 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): # show graph if show_animation and len(closedset.keys()) % 2 == 0: # pragma: no cover plt.plot(current.x, current.y, "xg") + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.pause(0.001) if c_id == (len(road_map) - 1): diff --git a/PathTracking/cgmres_nmpc/cgmres_nmpc.py b/PathTracking/cgmres_nmpc/cgmres_nmpc.py index 74a0f9cc57..1be91b2d20 100644 --- a/PathTracking/cgmres_nmpc/cgmres_nmpc.py +++ b/PathTracking/cgmres_nmpc/cgmres_nmpc.py @@ -546,6 +546,8 @@ def animation(plant, controller, dt): steer = math.atan2(controller.history_u_2[t] * WB / v, 1.0) plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(plant.history_x, plant.history_y, "-r", label="trajectory") plot_car(x, y, yaw, steer=steer) plt.axis("equal") diff --git a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py index 6dec12bd30..0e22529623 100644 --- a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py +++ b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py @@ -224,6 +224,8 @@ def do_simulation(cx, cy, cyaw, ck, speed_profile, goal): if target_ind % 1 == 0 and show_animation: plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, "-r", label="course") plt.plot(x, y, "ob", label="trajectory") plt.plot(cx[target_ind], cy[target_ind], "xg", label="target") diff --git a/PathTracking/lqr_steer_control/lqr_steer_control.py b/PathTracking/lqr_steer_control/lqr_steer_control.py index f977cdc2a1..9cc36f231f 100644 --- a/PathTracking/lqr_steer_control/lqr_steer_control.py +++ b/PathTracking/lqr_steer_control/lqr_steer_control.py @@ -203,6 +203,8 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): if target_ind % 1 == 0 and show_animation: plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, "-r", label="course") plt.plot(x, y, "ob", label="trajectory") plt.plot(cx[target_ind], cy[target_ind], "xg", label="target") diff --git a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py index 0f5104e954..8bff2e107d 100644 --- a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py +++ b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py @@ -429,6 +429,8 @@ def do_simulation(cx, cy, cyaw, ck, sp, dl, initial_state): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if ox is not None: plt.plot(ox, oy, "xr", label="MPC") plt.plot(cx, cy, "-r", label="course") diff --git a/PathTracking/move_to_pose/move_to_pose.py b/PathTracking/move_to_pose/move_to_pose.py index 0814ef62ef..838b780f48 100644 --- a/PathTracking/move_to_pose/move_to_pose.py +++ b/PathTracking/move_to_pose/move_to_pose.py @@ -93,6 +93,9 @@ def plot_vehicle(x, y, theta, x_traj, y_traj): # pragma: no cover plt.plot(x_traj, y_traj, 'b--') + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + plt.xlim(0, 20) plt.ylim(0, 20) diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py index 38a84affce..f9624956c4 100644 --- a/PathTracking/pure_pursuit/pure_pursuit.py +++ b/PathTracking/pure_pursuit/pure_pursuit.py @@ -166,6 +166,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plot_arrow(state.x, state.y, state.yaw) plt.plot(cx, cy, "-r", label="course") plt.plot(x, y, "-b", label="trajectory") diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index 285d9404e3..155eeec2ce 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -149,6 +149,8 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): if target_ind % 1 == 0 and show_animation: plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, "-r", label="course") plt.plot(x, y, "ob", label="trajectory") plt.plot(cx[target_ind], cy[target_ind], "xg", label="target") diff --git a/PathTracking/stanley_controller/stanley_controller.py b/PathTracking/stanley_controller/stanley_controller.py index addd5ad3a1..cbfa4c667e 100644 --- a/PathTracking/stanley_controller/stanley_controller.py +++ b/PathTracking/stanley_controller/stanley_controller.py @@ -186,6 +186,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, ".r", label="course") plt.plot(x, y, "-b", label="trajectory") plt.plot(cx[target_idx], cy[target_idx], "xg", label="target") diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index 27e5035459..33a9b1ddb1 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -235,6 +235,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") plt.plot(xEst[0], xEst[1], ".r") diff --git a/SLAM/FastSLAM1/fast_slam1.py b/SLAM/FastSLAM1/fast_slam1.py index c16407e89f..ef1282995b 100644 --- a/SLAM/FastSLAM1/fast_slam1.py +++ b/SLAM/FastSLAM1/fast_slam1.py @@ -365,6 +365,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") for i in range(N_PARTICLE): diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py index 73624dbf1f..f8958b8c73 100644 --- a/SLAM/FastSLAM2/fast_slam2.py +++ b/SLAM/FastSLAM2/fast_slam2.py @@ -390,6 +390,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") for iz in range(len(z[:, 0])): diff --git a/SLAM/GraphBasedSLAM/graph_based_slam.py b/SLAM/GraphBasedSLAM/graph_based_slam.py index b40ad6494e..e73e8d0d4a 100644 --- a/SLAM/GraphBasedSLAM/graph_based_slam.py +++ b/SLAM/GraphBasedSLAM/graph_based_slam.py @@ -303,7 +303,8 @@ def main(): if show_animation: # pragma: no cover plt.cla() - + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") plt.plot(hxTrue[0, :].flatten(), @@ -319,4 +320,4 @@ def main(): if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/SLAM/iterative_closest_point/iterative_closest_point.py b/SLAM/iterative_closest_point/iterative_closest_point.py index 3512ef976b..4a4d29eb5e 100644 --- a/SLAM/iterative_closest_point/iterative_closest_point.py +++ b/SLAM/iterative_closest_point/iterative_closest_point.py @@ -36,6 +36,8 @@ def icp_matching(previous_points, current_points): if show_animation: # pragma: no cover plt.cla() + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(previous_points[0, :], previous_points[1, :], ".r") plt.plot(current_points[0, :], current_points[1, :], ".b") plt.plot(0.0, 0.0, "xr") From 8c701762b40e38318a4dd03485e9824504de458b Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 13:54:35 +0100 Subject: [PATCH 118/940] Fixed typo in stanley_controller.py --- PathTracking/stanley_controller/stanley_controller.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathTracking/stanley_controller/stanley_controller.py b/PathTracking/stanley_controller/stanley_controller.py index addd5ad3a1..42a446dda3 100644 --- a/PathTracking/stanley_controller/stanley_controller.py +++ b/PathTracking/stanley_controller/stanley_controller.py @@ -21,7 +21,7 @@ k = 0.5 # control gain -Kp = 1.0 # speed propotional gain +Kp = 1.0 # speed proportional gain dt = 0.1 # [s] time difference L = 2.9 # [m] Wheel base of vehicle max_steer = np.radians(30.0) # [rad] max steering angle From 22e92ed5583875fbc4e46fce044059f936b0be4e Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 14:40:28 +0100 Subject: [PATCH 119/940] Simplified calc_target_index function in stanley_controller.py Used: - np.hypot to replace np.sqrt(x**2 + y**2) - np.argmin to find location of a minimum in a numpy array --- PathTracking/stanley_controller/stanley_controller.py | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/PathTracking/stanley_controller/stanley_controller.py b/PathTracking/stanley_controller/stanley_controller.py index 42a446dda3..9b808dd963 100644 --- a/PathTracking/stanley_controller/stanley_controller.py +++ b/PathTracking/stanley_controller/stanley_controller.py @@ -127,20 +127,19 @@ def calc_target_index(state, cx, cy): :param cy: [float] :return: (int, float) """ - # Calc front axle position + # Calc front axle position fx = state.x + L * np.cos(state.yaw) fy = state.y + L * np.sin(state.yaw) # Search nearest point index dx = [fx - icx for icx in cx] dy = [fy - icy for icy in cy] - d = [np.sqrt(idx ** 2 + idy ** 2) for (idx, idy) in zip(dx, dy)] - closest_error = min(d) - target_idx = d.index(closest_error) + d = np.hypot(dx, dy) + target_idx = np.argmin(d) # Project RMS error onto front axle vector front_axle_vec = [-np.cos(state.yaw + np.pi / 2), - - np.sin(state.yaw + np.pi / 2)] + -np.sin(state.yaw + np.pi / 2)] error_front_axle = np.dot([dx[target_idx], dy[target_idx]], front_axle_vec) return target_idx, error_front_axle From 652c32fba9eadfeb1e2200b2f7e475de1acfc5bb Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:10:53 +0100 Subject: [PATCH 120/940] Replaced sqrt(x**2+y**2) with hypot in SLAM/GraphBasedSLAM/graph_based_slam.py --- SLAM/GraphBasedSLAM/graph_based_slam.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/SLAM/GraphBasedSLAM/graph_based_slam.py b/SLAM/GraphBasedSLAM/graph_based_slam.py index b40ad6494e..41b9d52591 100644 --- a/SLAM/GraphBasedSLAM/graph_based_slam.py +++ b/SLAM/GraphBasedSLAM/graph_based_slam.py @@ -216,7 +216,7 @@ def observation(xTrue, xd, u, RFID): dx = RFID[i, 0] - xTrue[0, 0] dy = RFID[i, 1] - xTrue[1, 0] - d = math.sqrt(dx**2 + dy**2) + d = math.hypot(dx, dy) angle = pi_2_pi(math.atan2(dy, dx)) - xTrue[2, 0] phi = pi_2_pi(math.atan2(dy, dx)) if d <= MAX_RANGE: From 1d03241d5d6319fc1cdc42f6a11b560ee23dc0d2 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:11:28 +0100 Subject: [PATCH 121/940] Replaced sqrt(x**2+y**2) with hypot in SLAM/FastSLAM2/fast_slam2.py --- SLAM/FastSLAM2/fast_slam2.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py index 73624dbf1f..b9df694830 100644 --- a/SLAM/FastSLAM2/fast_slam2.py +++ b/SLAM/FastSLAM2/fast_slam2.py @@ -304,7 +304,7 @@ def observation(xTrue, xd, u, RFID): dx = RFID[i, 0] - xTrue[0, 0] dy = RFID[i, 1] - xTrue[1, 0] - d = math.sqrt(dx ** 2 + dy ** 2) + d = math.hypot(dx, dy) angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise From f1926bdd9e08733f7dce997fab3f0e6f4e97476f Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:11:57 +0100 Subject: [PATCH 122/940] Replaced sqrt(x**2+y**2) with hypot in SLAM/FastSLAM2/fast_slam1.py --- SLAM/FastSLAM1/fast_slam1.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/SLAM/FastSLAM1/fast_slam1.py b/SLAM/FastSLAM1/fast_slam1.py index c16407e89f..298cc0363a 100644 --- a/SLAM/FastSLAM1/fast_slam1.py +++ b/SLAM/FastSLAM1/fast_slam1.py @@ -279,7 +279,7 @@ def observation(xTrue, xd, u, RFID): dx = RFID[i, 0] - xTrue[0, 0] dy = RFID[i, 1] - xTrue[1, 0] - d = math.sqrt(dx ** 2 + dy ** 2) + d = math.hypot(dx, dy) angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: dn = d + np.random.randn() * Qsim[0, 0] ** 0.5 # add noise From 02f14e425efab343a26acbbf2feeb139cbe337b6 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:13:20 +0100 Subject: [PATCH 123/940] Replaced sqrt(x**2+y**2) with hypot in SLAM/EKFSLAM/ekf_slam.py --- SLAM/EKFSLAM/ekf_slam.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index 22ccd8d659..66234b57ec 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -76,7 +76,7 @@ def observation(xTrue, xd, u, RFID): dx = RFID[i, 0] - xTrue[0, 0] dy = RFID[i, 1] - xTrue[1, 0] - d = math.sqrt(dx ** 2 + dy ** 2) + d = math.hypot(dx, dy) angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise From 41bcdf8573e4cd3b1773934f8b30d0363edda0f3 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:14:48 +0100 Subject: [PATCH 124/940] Replaced sqrt(x**2+y**2) with hypot in PathTracking/rear_wheel_feedback/rear_wheel_feedback.py --- PathTracking/rear_wheel_feedback/rear_wheel_feedback.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index 285d9404e3..bf4f31b39a 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -136,7 +136,7 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): # check goal dx = state.x - goal[0] dy = state.y - goal[1] - if math.sqrt(dx ** 2 + dy ** 2) <= goal_dis: + if math.hypot(dx, dy) <= goal_dis: print("Goal") goal_flag = True break From e500f65d7ff6f8ddc82b5c9375fe8e423f8af387 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:16:12 +0100 Subject: [PATCH 125/940] Replaced sqrt(x**2+y**2) with hypot in PathTracking/pure_pursuit/pure_pursuit.py --- PathTracking/pure_pursuit/pure_pursuit.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py index 38a84affce..370cac96cc 100644 --- a/PathTracking/pure_pursuit/pure_pursuit.py +++ b/PathTracking/pure_pursuit/pure_pursuit.py @@ -77,7 +77,7 @@ def calc_distance(state, point_x, point_y): dx = state.rear_x - point_x dy = state.rear_y - point_y - return math.sqrt(dx ** 2 + dy ** 2) + return math.hypot(dx, dy) def calc_target_index(state, cx, cy): @@ -88,7 +88,7 @@ def calc_target_index(state, cx, cy): # search nearest point index dx = [state.rear_x - icx for icx in cx] dy = [state.rear_y - icy for icy in cy] - d = [abs(math.sqrt(idx ** 2 + idy ** 2)) for (idx, idy) in zip(dx, dy)] + d = [idx ** 2 + idy ** 2 for (idx, idy) in zip(dx, dy)] ind = d.index(min(d)) old_nearest_point_index = ind else: @@ -110,7 +110,7 @@ def calc_target_index(state, cx, cy): while Lf > L and (ind + 1) < len(cx): dx = cx[ind] - state.rear_x dy = cy[ind] - state.rear_y - L = math.sqrt(dx ** 2 + dy ** 2) + L = math.hypot(dx, dy) ind += 1 return ind From 4ef4658f82c4baa4784b430e67847ed24aa8dd48 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:18:00 +0100 Subject: [PATCH 126/940] Replaced sqrt(x**2+y**2) with hypot in PathTracking/move_to_pose/move_to_pose.py --- PathTracking/move_to_pose/move_to_pose.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathTracking/move_to_pose/move_to_pose.py b/PathTracking/move_to_pose/move_to_pose.py index 0814ef62ef..e161b4616d 100644 --- a/PathTracking/move_to_pose/move_to_pose.py +++ b/PathTracking/move_to_pose/move_to_pose.py @@ -40,7 +40,7 @@ def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal): x_traj, y_traj = [], [] - rho = np.sqrt(x_diff**2 + y_diff**2) + rho = np.hypot(x_diff, y_diff) while rho > 0.001: x_traj.append(x) y_traj.append(y) @@ -52,7 +52,7 @@ def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal): # [-pi, pi] to prevent unstable behavior e.g. difference going # from 0 rad to 2*pi rad with slight turn - rho = np.sqrt(x_diff**2 + y_diff**2) + rho = np.hypot(x_diff, y_diff) alpha = (np.arctan2(y_diff, x_diff) - theta + np.pi) % (2 * np.pi) - np.pi beta = (theta_goal - theta - alpha + np.pi) % (2 * np.pi) - np.pi From 9f5b0a25cc4c0727087dddde445862e727f283f5 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:19:05 +0100 Subject: [PATCH 127/940] Replaced sqrt(x**2+y**2) with hypot in PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py --- .../model_predictive_speed_and_steer_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py index 0f5104e954..a16768e36b 100644 --- a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py +++ b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py @@ -348,7 +348,7 @@ def check_goal(state, goal, tind, nind): # check goal dx = state.x - goal[0] dy = state.y - goal[1] - d = math.sqrt(dx ** 2 + dy ** 2) + d = math.hypot(dx, dy) isgoal = (d <= GOAL_DIS) From db78f07c0bc084748632bf36af713d249bf0647c Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:19:41 +0100 Subject: [PATCH 128/940] Replaced sqrt(x**2+y**2) with hypot in PathTracking/lqr_steer_control/lqr_steer_control.py --- PathTracking/lqr_steer_control/lqr_steer_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathTracking/lqr_steer_control/lqr_steer_control.py b/PathTracking/lqr_steer_control/lqr_steer_control.py index f977cdc2a1..b69577d3aa 100644 --- a/PathTracking/lqr_steer_control/lqr_steer_control.py +++ b/PathTracking/lqr_steer_control/lqr_steer_control.py @@ -191,7 +191,7 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): # check goal dx = state.x - goal[0] dy = state.y - goal[1] - if math.sqrt(dx ** 2 + dy ** 2) <= goal_dis: + if math.hypot(dx, dy) <= goal_dis: print("Goal") break From bc2b7c969cd37b572372c5cdaa36b680a02f7c56 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:20:12 +0100 Subject: [PATCH 129/940] Replaced sqrt(x**2+y**2) with hypot in PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py --- PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py index 6dec12bd30..c7c8e0dd97 100644 --- a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py +++ b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py @@ -212,7 +212,7 @@ def do_simulation(cx, cy, cyaw, ck, speed_profile, goal): # check goal dx = state.x - goal[0] dy = state.y - goal[1] - if math.sqrt(dx ** 2 + dy ** 2) <= goal_dis: + if math.hypot(dx, dy) <= goal_dis: print("Goal") break From 26cff8e69fdbe7c11a55b83a3668e85e24aa952d Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:20:58 +0100 Subject: [PATCH 130/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/RRT/rrt.py --- PathPlanning/RRT/rrt.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 3bcc622100..5b6f3252ae 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -126,7 +126,7 @@ def generate_final_course(self, goal_ind): def calc_dist_to_goal(self, x, y): dx = x - self.end.x dy = y - self.end.y - return math.sqrt(dx ** 2 + dy ** 2) + return math.hypot(dx, dy) def get_random_node(self): if random.randint(0, 100) > self.goal_sample_rate: @@ -186,7 +186,7 @@ def check_collision(node, obstacleList): def calc_distance_and_angle(from_node, to_node): dx = to_node.x - from_node.x dy = to_node.y - from_node.y - d = math.sqrt(dx ** 2 + dy ** 2) + d = math.hypot(dx, dy) theta = math.atan2(dy, dx) return d, theta From 5221a9df2a82d9a527930c59057cfaa398c6f403 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:21:29 +0100 Subject: [PATCH 131/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/InformedRRTStar/informed_rrt_star.py --- PathPlanning/InformedRRTStar/informed_rrt_star.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 175749183d..065868f2d2 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -106,7 +106,7 @@ def choose_parent(self, newNode, nearInds): for i in nearInds: dx = newNode.x - self.node_list[i].x dy = newNode.y - self.node_list[i].y - d = math.sqrt(dx ** 2 + dy ** 2) + d = math.hypot(dx, dy) theta = math.atan2(dy, dx) if self.check_collision(self.node_list[i], theta, d): dList.append(self.node_list[i].cost + d) @@ -224,7 +224,7 @@ def rewire(self, newNode, nearInds): if self.check_collision(nearNode, theta, d): nearNode.parent = n_node - 1 nearNode.cost = scost - + @staticmethod def distance_squared_point_to_segment(v, w, p): # Return minimum distance between line segment vw and point p @@ -232,7 +232,7 @@ def distance_squared_point_to_segment(v, w, p): return (p-v).dot(p-v) # v == w case l2 = (w-v).dot(w-v) # i.e. |w-v|^2 - avoid a sqrt # Consider the line extending the segment, parameterized as v + t (w - v). - # We find projection of point p onto the line. + # We find projection of point p onto the line. # It falls where t = [(p-v) . (w-v)] / |w-v|^2 # We clamp t from [0,1] to handle points outside the segment vw. t = max(0, min(1, (p - v).dot(w - v) / l2)) From 06cbcc3ee55598f54b612c2f842cfb052f8b751e Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:22:14 +0100 Subject: [PATCH 132/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py --- .../GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py index f22b058fa8..9d7e1616f3 100644 --- a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py +++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py @@ -118,7 +118,7 @@ def find_sweep_direction_and_start_posi(ox, oy): for i in range(len(ox) - 1): dx = ox[i + 1] - ox[i] dy = oy[i + 1] - oy[i] - d = np.sqrt(dx ** 2 + dy ** 2) + d = np.hypot(dx, dy) if d > max_dist: max_dist = d From 1eb3ebbf26be7f000275f2a897d46a008613814e Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:22:47 +0100 Subject: [PATCH 133/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/DynamicWindowApproach/dynamic_window_approach.py --- PathPlanning/DynamicWindowApproach/dynamic_window_approach.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index c8a4434958..5c3d128dc4 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -164,7 +164,7 @@ def calc_obstacle_cost(trajectory, ob, config): oy = ob[:, 1] dx = trajectory[:, 0] - ox[:, None] dy = trajectory[:, 1] - oy[:, None] - r = np.sqrt(np.square(dx) + np.square(dy)) + r = np.hypot(dx, dy) if config.robot_type == RobotType.rectangle: yaw = trajectory[:, 2] From 00f8fd37d367aa6409b70e945356f1aa5abc4fde Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:24:27 +0100 Subject: [PATCH 134/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/ClosedLoopRRTStar/pure_pursuit.py --- PathPlanning/ClosedLoopRRTStar/pure_pursuit.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py index 0490727933..32faa51c11 100644 --- a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py +++ b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py @@ -68,17 +68,17 @@ def calc_target_index(state, cx, cy): dx = [state.x - icx for icx in cx] dy = [state.y - icy for icy in cy] - d = [abs(math.sqrt(idx ** 2 + idy ** 2)) for (idx, idy) in zip(dx, dy)] + d = np.hypot(dx, dy) mindis = min(d) - ind = d.index(mindis) + ind = np.argmin(d) L = 0.0 while Lf > L and (ind + 1) < len(cx): dx = cx[ind + 1] - cx[ind] dy = cy[ind + 1] - cy[ind] - L += math.sqrt(dx ** 2 + dy ** 2) + L += math.hypot(dx, dy) ind += 1 # print(mindis) @@ -121,7 +121,7 @@ def closed_loop_prediction(cx, cy, cyaw, speed_profile, goal): # check goal dx = state.x - goal[0] dy = state.y - goal[1] - if math.sqrt(dx ** 2 + dy ** 2) <= goal_dis: + if math.hypot(dx, dy) <= goal_dis: find_goal = True break From 1fcfa72133522ce004b99ad079d9f7361ee8f981 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:30:04 +0100 Subject: [PATCH 135/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py --- PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py b/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py index a07dc48af0..aea0080112 100644 --- a/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py +++ b/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py @@ -6,7 +6,6 @@ """ -import math import os import sys @@ -119,9 +118,8 @@ def check_tracking_path_is_feasible(self, path): print("final angle is bad") find_goal = False - travel = sum([abs(iv) * unicycle_model.dt for iv in v]) - origin_travel = sum([math.sqrt(dx ** 2 + dy ** 2) - for (dx, dy) in zip(np.diff(cx), np.diff(cy))]) + travel = unicycle_model.dt * sum(np.abs(v)) + origin_travel = sum(np.hypot(np.diff(cx), np.diff(cy))) if (travel / origin_travel) >= self.invalid_travel_ratio: print("path is too long") From 0aaf6406d82f7067af460160f4d75495d59fa80f Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:30:39 +0100 Subject: [PATCH 136/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/BezierPath/bezier_path.py --- PathPlanning/BezierPath/bezier_path.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/BezierPath/bezier_path.py b/PathPlanning/BezierPath/bezier_path.py index 516a681e3b..46faf1f310 100644 --- a/PathPlanning/BezierPath/bezier_path.py +++ b/PathPlanning/BezierPath/bezier_path.py @@ -26,7 +26,7 @@ def calc_4points_bezier_path(sx, sy, syaw, ex, ey, eyaw, offset): :param offset: (float) :return: (numpy array, numpy array) """ - dist = np.sqrt((sx - ex) ** 2 + (sy - ey) ** 2) / offset + dist = np.hypot(sx - ex, sy - ey) / offset control_points = np.array( [[sx, sy], [sx + dist * np.cos(syaw), sy + dist * np.sin(syaw)], From 72a28b4d4b850e3c2ac7e13ffacc2ea01736f0db Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:31:05 +0100 Subject: [PATCH 137/940] Replaced sqrt(x**2+y**2) with hypot in Mapping/rectangle_fitting/rectangle_fitting.py --- Mapping/rectangle_fitting/rectangle_fitting.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Mapping/rectangle_fitting/rectangle_fitting.py b/Mapping/rectangle_fitting/rectangle_fitting.py index e40fc2e4c7..2018f02514 100644 --- a/Mapping/rectangle_fitting/rectangle_fitting.py +++ b/Mapping/rectangle_fitting/rectangle_fitting.py @@ -162,7 +162,7 @@ def _adoptive_range_segmentation(self, ox, oy): C = set() R = self.R0 + self.Rd * np.linalg.norm([ox[i], oy[i]]) for j, _ in enumerate(ox): - d = np.sqrt((ox[i] - ox[j])**2 + (oy[i] - oy[j])**2) + d = np.hypot(ox[i] - ox[j], oy[i] - oy[j]) if d <= R: C.add(j) S.append(C) From 2cb9e37792180fed4d73ce5db35a071ab10d2d17 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:32:02 +0100 Subject: [PATCH 138/940] Replaced sqrt(x**2+y**2) with hypot in Mapping/kmeans_clustering/kmeans_clustering.py --- Mapping/kmeans_clustering/kmeans_clustering.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Mapping/kmeans_clustering/kmeans_clustering.py b/Mapping/kmeans_clustering/kmeans_clustering.py index bdaa45455e..c2518b80c0 100644 --- a/Mapping/kmeans_clustering/kmeans_clustering.py +++ b/Mapping/kmeans_clustering/kmeans_clustering.py @@ -68,7 +68,7 @@ def update_clusters(self): dx = [icx - px for icx in self.center_x] dy = [icy - py for icy in self.center_y] - dist_list = [math.sqrt(idx ** 2 + idy ** 2) for (idx, idy) in zip(dx, dy)] + dist_list = [math.hypot(idx, idy) for (idx, idy) in zip(dx, dy)] min_dist = min(dist_list) min_id = dist_list.index(min_dist) self.labels[ip] = min_id From 4545084da430bd353239565715bb22dde1c1c96f Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:32:40 +0100 Subject: [PATCH 139/940] Replaced sqrt(x**2+y**2) with hypot in Localization/particle_filter/particle_filter.py --- Localization/particle_filter/particle_filter.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 0ebb5fc3d1..d14b7c0697 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -47,7 +47,7 @@ def observation(xTrue, xd, u, RF_ID): dx = xTrue[0, 0] - RF_ID[i, 0] dy = xTrue[1, 0] - RF_ID[i, 1] - d = math.sqrt(dx ** 2 + dy ** 2) + d = math.hypot(dx, dy) if d <= MAX_RANGE: dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise zi = np.array([[dn, RF_ID[i, 0], RF_ID[i, 1]]]) @@ -116,7 +116,7 @@ def pf_localization(px, pw, z, u): for i in range(len(z[:, 0])): dx = x[0, 0] - z[i, 1] dy = x[1, 0] - z[i, 2] - pre_z = math.sqrt(dx ** 2 + dy ** 2) + pre_z = math.hypot(dx, dy) dz = pre_z - z[i, 0] w = w * gauss_likelihood(dz, math.sqrt(Q[0, 0])) From f66a10f42eca2a57cb8004f16403fd67e0788d58 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:33:21 +0100 Subject: [PATCH 140/940] Replaced sqrt(x**2+y**2) with hypot in Localization/histogram_filter/histogram_filter.py --- Localization/histogram_filter/histogram_filter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index bdfbb13fa7..8404646ca5 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -126,7 +126,7 @@ def observation(xTrue, u, RFID): dx = xTrue[0, 0] - RFID[i, 0] dy = xTrue[1, 0] - RFID[i, 1] - d = math.sqrt(dx ** 2 + dy ** 2) + d = math.hypot(dx, dy) if d <= MAX_RANGE: # add noise to range observation dn = d + np.random.randn() * NOISE_RANGE From e289d1f9a9ea1a1284ab3f4e34cd89c5c21c72b8 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:33:52 +0100 Subject: [PATCH 141/940] Replaced sqrt(x**2+y**2) with hypot in Localization/ensemble_kalman_filter/ensemble_kalman_filter.py --- Localization/ensemble_kalman_filter/ensemble_kalman_filter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py index 293509157b..3e2af749e7 100644 --- a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py +++ b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py @@ -44,7 +44,7 @@ def observation(xTrue, xd, u, RFID): dx = RFID[i, 0] - xTrue[0, 0] dy = RFID[i, 1] - xTrue[1, 0] - d = math.sqrt(dx ** 2 + dy ** 2) + d = math.hypot(dx, dy) angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise From 84aead6149b885b44ad661b92cd8fa2ac6431a41 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:35:06 +0100 Subject: [PATCH 142/940] Replaced sqrt(x**2+y**2) with hypot in ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py --- .../two_joint_arm_to_point_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py index e674ae8ac2..0e91be0ff6 100644 --- a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py +++ b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py @@ -55,7 +55,7 @@ def two_joint_arm(GOAL_TH=0.0, theta1=0.0, theta2=0.0): wrist = plot_arm(theta1, theta2, x, y) # check goal - d2goal = np.math.sqrt((wrist[0] - x)**2 + (wrist[1] - y)**2) + d2goal = np.hypot(wrist[0] - x, wrist[1] - y) if abs(d2goal) < GOAL_TH and x is not None: return theta1, theta2 From d979bb24d9cf6272a24bd000f5642cc1443c7b86 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:35:44 +0100 Subject: [PATCH 143/940] Replaced sqrt(x**2+y**2) with hypot in ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py --- .../n_joint_arm_to_point_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py b/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py index b232ab33f3..3972474b8d 100644 --- a/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py +++ b/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py @@ -148,7 +148,7 @@ def jacobian_inverse(link_lengths, joint_angles): def distance_to_goal(current_pos, goal_pos): x_diff = goal_pos[0] - current_pos[0] y_diff = goal_pos[1] - current_pos[1] - return np.array([x_diff, y_diff]).T, np.math.sqrt(x_diff**2 + y_diff**2) + return np.array([x_diff, y_diff]).T, np.hypot(x_diff, y_diff) def ang_diff(theta1, theta2): From d26eb04ae2c2f1047271e913977f27dfc129aad3 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:36:25 +0100 Subject: [PATCH 144/940] Removed useless zero in erialNavigation/rocket_powered_landing/rocket_powered_landing.py --- .../rocket_powered_landing/rocket_powered_landing.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py index 9f1e16fc1d..dde76f19bd 100644 --- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py +++ b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py @@ -195,8 +195,8 @@ def B_func(self, x, u): [0, 0, 0], [0, 0, 0], [0, 0, 0], - [0, 0, 1.00000000000000], - [0, -1.00000000000000, 0] + [0, 0, 1.0], + [0, -1.0, 0] ]) def euler_to_quat(self, a): From e467f4fad1d055b947f565ac5d27e6dd21528621 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:07 +0100 Subject: [PATCH 145/940] Replaced sqrt(x**2+y**2) with hypot in Localization/histogram_filter/histogram_filter.py --- Localization/histogram_filter/histogram_filter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index 8404646ca5..db715a6d1e 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -68,7 +68,7 @@ def calc_gaussian_observation_pdf(gmap, z, iz, ix, iy, std): # predicted range x = ix * gmap.xy_reso + gmap.minx y = iy * gmap.xy_reso + gmap.miny - d = math.sqrt((x - z[iz, 1]) ** 2 + (y - z[iz, 2]) ** 2) + d = math.hypot(x - z[iz, 1], y - z[iz, 2]) # likelihood pdf = (1.0 - norm.cdf(abs(d - z[iz, 0]), 0.0, std)) From ccf047135e558332f9e460e21f8263bfb3e2974a Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:07 +0100 Subject: [PATCH 146/940] Replaced sqrt(x**2+y**2) with hypot in Mapping/gaussian_grid_map/gaussian_grid_map.py --- Mapping/gaussian_grid_map/gaussian_grid_map.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Mapping/gaussian_grid_map/gaussian_grid_map.py b/Mapping/gaussian_grid_map/gaussian_grid_map.py index b520b63944..9c1aa27320 100644 --- a/Mapping/gaussian_grid_map/gaussian_grid_map.py +++ b/Mapping/gaussian_grid_map/gaussian_grid_map.py @@ -31,7 +31,7 @@ def generate_gaussian_grid_map(ox, oy, xyreso, std): # Search minimum distance mindis = float("inf") for (iox, ioy) in zip(ox, oy): - d = math.sqrt((iox - x)**2 + (ioy - y)**2) + d = math.hypot(iox - x, ioy - y) if mindis >= d: mindis = d From 1273934a7ea2723375422dc29081a014f649dbb8 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:07 +0100 Subject: [PATCH 147/940] Replaced sqrt(x**2+y**2) with hypot in Mapping/raycasting_grid_map/raycasting_grid_map.py --- Mapping/raycasting_grid_map/raycasting_grid_map.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Mapping/raycasting_grid_map/raycasting_grid_map.py b/Mapping/raycasting_grid_map/raycasting_grid_map.py index 997687423e..a0d9060916 100644 --- a/Mapping/raycasting_grid_map/raycasting_grid_map.py +++ b/Mapping/raycasting_grid_map/raycasting_grid_map.py @@ -57,7 +57,7 @@ def precasting(minx, miny, xw, yw, xyreso, yawreso): px = ix * xyreso + minx py = iy * xyreso + miny - d = math.sqrt(px**2 + py**2) + d = math.hypot(px, py) angle = atan_zero_to_twopi(py, px) angleid = int(math.floor(angle / yawreso)) @@ -85,7 +85,7 @@ def generate_ray_casting_grid_map(ox, oy, xyreso, yawreso): for (x, y) in zip(ox, oy): - d = math.sqrt(x**2 + y**2) + d = math.hypot(x, y) angle = atan_zero_to_twopi(y, x) angleid = int(math.floor(angle / yawreso)) From d433748ef8ab6fba34f7f7882253e2c1f0c31611 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:08 +0100 Subject: [PATCH 148/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/AStar/a_star.py --- PathPlanning/AStar/a_star.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py index 6b0392f515..061aafbeff 100644 --- a/PathPlanning/AStar/a_star.py +++ b/PathPlanning/AStar/a_star.py @@ -136,7 +136,7 @@ def calc_final_path(self, ngoal, closedset): @staticmethod def calc_heuristic(n1, n2): w = 1.0 # weight of heuristic - d = w * math.sqrt((n1.x - n2.x) ** 2 + (n1.y - n2.y) ** 2) + d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) return d def calc_grid_position(self, index, minp): @@ -199,7 +199,7 @@ def calc_obstacle_map(self, ox, oy): for iy in range(self.ywidth): y = self.calc_grid_position(iy, self.miny) for iox, ioy in zip(ox, oy): - d = math.sqrt((iox - x) ** 2 + (ioy - y) ** 2) + d = math.hypot(iox - x, ioy - y) if d <= self.rr: self.obmap[ix][iy] = True break From ed9b84dfc3310e6a45e19c05c38a485560da5c15 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:08 +0100 Subject: [PATCH 149/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py --- PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py index 37ac75ada9..8e7af39f30 100644 --- a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py +++ b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py @@ -180,8 +180,8 @@ def setup_planning(self): cBest = self.g_scores[self.goalId] # Computing the sampling space - cMin = math.sqrt(pow(self.start[0] - self.goal[0], 2) - + pow(self.start[1] - self.goal[1], 2)) / 1.5 + cMin = math.hypot(self.start[0] - self.goal[0], + self.start[1] - self.goal[1]) / 1.5 xCenter = np.array([[(self.start[0] + self.goal[0]) / 2.0], [(self.start[1] + self.goal[1]) / 2.0], [0]]) a1 = np.array([[(self.goal[0] - self.start[0]) / cMin], From cf538756e69713fe5d3d23a9c99a09ba5f62c35d Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:08 +0100 Subject: [PATCH 150/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/ClosedLoopRRTStar/pure_pursuit.py --- PathPlanning/ClosedLoopRRTStar/pure_pursuit.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py index 32faa51c11..be1d223815 100644 --- a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py +++ b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py @@ -161,7 +161,7 @@ def set_stop_point(target_speed, cx, cy, cyaw): for i in range(len(cx) - 1): dx = cx[i + 1] - cx[i] dy = cy[i + 1] - cy[i] - d.append(math.sqrt(dx ** 2.0 + dy ** 2.0)) + d.append(math.hypot(dx, dy)) iyaw = cyaw[i] move_direction = math.atan2(dy, dx) is_back = abs(move_direction - iyaw) >= math.pi / 2.0 From 4c73cada9b1fccbcf929a4520735c590f188a85c Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:08 +0100 Subject: [PATCH 151/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/CubicSpline/cubic_spline_planner.py --- PathPlanning/CubicSpline/cubic_spline_planner.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/PathPlanning/CubicSpline/cubic_spline_planner.py b/PathPlanning/CubicSpline/cubic_spline_planner.py index 071b117185..239ce16738 100644 --- a/PathPlanning/CubicSpline/cubic_spline_planner.py +++ b/PathPlanning/CubicSpline/cubic_spline_planner.py @@ -140,8 +140,7 @@ def __init__(self, x, y): def __calc_s(self, x, y): dx = np.diff(x) dy = np.diff(y) - self.ds = [math.sqrt(idx ** 2 + idy ** 2) - for (idx, idy) in zip(dx, dy)] + self.ds = np.hypot(dx, dy) s = [0] s.extend(np.cumsum(self.ds)) return s From 4c6fe30fb33bff9b85238f26e95e8ae7b9a973dd Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:08 +0100 Subject: [PATCH 152/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/Dijkstra/dijkstra.py --- PathPlanning/Dijkstra/dijkstra.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index bb73ed501a..5c06f53aed 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -123,7 +123,7 @@ def calc_final_path(self, ngoal, closedset): def calc_heuristic(self, n1, n2): w = 1.0 # weight of heuristic - d = w * math.sqrt((n1.x - n2.x)**2 + (n1.y - n2.y)**2) + d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) return d def calc_position(self, index, minp): @@ -178,7 +178,7 @@ def calc_obstacle_map(self, ox, oy): for iy in range(self.ywidth): y = self.calc_position(iy, self.miny) for iox, ioy in zip(ox, oy): - d = math.sqrt((iox - x)**2 + (ioy - y)**2) + d = math.hypot(iox - x, ioy - y) if d <= self.rr: self.obmap[ix][iy] = True break From 367c2c6dc635644b3fa37b5f921b3ebabb1e97c8 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:08 +0100 Subject: [PATCH 153/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/DubinsPath/dubins_path_planning.py --- PathPlanning/DubinsPath/dubins_path_planning.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/DubinsPath/dubins_path_planning.py b/PathPlanning/DubinsPath/dubins_path_planning.py index 706b5a49af..96c9c8e475 100644 --- a/PathPlanning/DubinsPath/dubins_path_planning.py +++ b/PathPlanning/DubinsPath/dubins_path_planning.py @@ -141,7 +141,7 @@ def dubins_path_planning_from_origin(ex, ey, eyaw, c, D_ANGLE): # normalize dx = ex dy = ey - D = math.sqrt(dx ** 2.0 + dy ** 2.0) + D = math.hypot(dx, dy) d = D * c # print(dx, dy, D, d) From 60387ee5f8b5f7898dbe73cc671f59503042a182 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:08 +0100 Subject: [PATCH 154/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/DynamicWindowApproach/dynamic_window_approach.py --- PathPlanning/DynamicWindowApproach/dynamic_window_approach.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 5c3d128dc4..891e68cbe8 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -279,7 +279,7 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): plt.pause(0.0001) # check reaching goal - dist_to_goal = math.sqrt((x[0] - goal[0]) ** 2 + (x[1] - goal[1]) ** 2) + dist_to_goal = math.hypot(x[0] - goal[0], x[1] - goal[1]) if dist_to_goal <= config.robot_radius: print("Goal!!") break From 077120201b41a8c4808a81170679aac7cd077acd Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:08 +0100 Subject: [PATCH 155/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py --- .../FrenetOptimalTrajectory/frenet_optimal_trajectory.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index 5c756a9dfe..f3ae2a439b 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -230,7 +230,7 @@ def calc_global_paths(fplist, csp): dx = fp.x[i + 1] - fp.x[i] dy = fp.y[i + 1] - fp.y[i] fp.yaw.append(math.atan2(dy, dx)) - fp.ds.append(math.sqrt(dx**2 + dy**2)) + fp.ds.append(math.hypot(dx, dy)) fp.yaw.append(fp.yaw[-1]) fp.ds.append(fp.ds[-1]) From d20f1e336e9b2536eacea224d12c59858a9c74bd Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:08 +0100 Subject: [PATCH 156/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py --- .../ProbabilisticRoadMap/probabilistic_road_map.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py index 351232d849..8090e3364f 100644 --- a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py +++ b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py @@ -97,7 +97,7 @@ def is_collision(sx, sy, gx, gy, rr, okdtree): dx = gx - sx dy = gy - sy yaw = math.atan2(gy - sy, gx - sx) - d = math.sqrt(dx**2 + dy**2) + d = math.hypot(dx, dy) if d >= MAX_EDGE_LEN: return True @@ -171,7 +171,7 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): road_map: ??? [m] sample_x: ??? [m] sample_y: ??? [m] - + @return: Two lists of path coordinates ([x1, x2, ...], [y1, y2, ...]), empty list when no path was found """ @@ -182,7 +182,7 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): openset[len(road_map) - 2] = nstart path_found = True - + while True: if not openset: print("Cannot find path") @@ -213,7 +213,7 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): n_id = road_map[c_id][i] dx = sample_x[n_id] - current.x dy = sample_y[n_id] - current.y - d = math.sqrt(dx**2 + dy**2) + d = math.hypot(dx, dy) node = Node(sample_x[n_id], sample_y[n_id], current.cost + d, c_id) @@ -226,7 +226,7 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): openset[n_id].pind = c_id else: openset[n_id] = node - + if path_found is False: return [], [] From c63a80b0ef148d5fb4bf75b1b0da41ba994c84ad Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 7 Dec 2019 22:53:08 +0100 Subject: [PATCH 157/940] Replaced sqrt(x**2+y**2) with hypot in PathPlanning/VoronoiRoadMap/voronoi_road_map.py --- PathPlanning/VoronoiRoadMap/voronoi_road_map.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py index 3ac02993b7..c73d650951 100644 --- a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py +++ b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py @@ -95,7 +95,7 @@ def is_collision(sx, sy, gx, gy, rr, okdtree): dx = gx - sx dy = gy - sy yaw = math.atan2(gy - sy, gx - sx) - d = math.sqrt(dx**2 + dy**2) + d = math.hypot(dx, dy) if d >= MAX_EDGE_LEN: return True @@ -203,7 +203,7 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): n_id = road_map[c_id][i] dx = sample_x[n_id] - current.x dy = sample_y[n_id] - current.y - d = math.sqrt(dx**2 + dy**2) + d = math.hypot(dx, dy) node = Node(sample_x[n_id], sample_y[n_id], current.cost + d, c_id) From bf86cc8096482745acaff354da1f8a56fff4a5d4 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Dec 2019 10:25:08 +0900 Subject: [PATCH 158/940] fixed lgtm warning --- PathPlanning/HybridAStar/hybrid_a_star.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index e82003ed25..ea6a466113 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -150,7 +150,7 @@ def calc_next_node(current, steer, direction, config, ox, oy, kdtree): arc_l = XY_GRID_RESOLUTION * 1.5 xlist, ylist, yawlist = [], [], [] - for dist in np.arange(0, arc_l, MOTION_RESOLUTION): + for _ in np.arange(0, arc_l, MOTION_RESOLUTION): x, y, yaw = move(x, y, yaw, MOTION_RESOLUTION * direction, steer) xlist.append(x) ylist.append(y) From 25cffd70d21389b76760b44da2697cde35175472 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Sat, 14 Dec 2019 14:39:45 +0300 Subject: [PATCH 159/940] fix typo --- .../rocket_powered_landing/rocket_powered_landing.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py index c7ab998bec..51e09b4e3c 100644 --- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py +++ b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py @@ -567,7 +567,7 @@ def plot_animation(X, U): # pragma: no cover fig = plt.figure() ax = fig.gca(projection='3d') - rig.canvas.mpl_connect('key_release_event', + fig.canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) for k in range(K): From 9ca7d8f14808f535b5e698bc57e5ab163b3dae4f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?G=C3=B6ktu=C4=9F=20Karaka=C5=9Fl=C4=B1?= <20567087+goktug97@users.noreply.github.com> Date: Sat, 14 Dec 2019 14:44:01 +0300 Subject: [PATCH 160/940] add comment for stopping the simulation --- AerialNavigation/drone_3d_trajectory_following/Quadrotor.py | 1 + .../rocket_powered_landing/rocket_powered_landing.py | 1 + .../arm_obstacle_navigation/arm_obstacle_navigation.py | 1 + .../arm_obstacle_navigation/arm_obstacle_navigation_2.py | 1 + ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py | 1 + .../two_joint_arm_to_point_control.py | 1 + Bipedal/bipedal_planner/bipedal_planner.py | 1 + Localization/ensemble_kalman_filter/ensemble_kalman_filter.py | 1 + Localization/extended_kalman_filter/extended_kalman_filter.py | 1 + Localization/histogram_filter/histogram_filter.py | 1 + Localization/particle_filter/particle_filter.py | 1 + Localization/unscented_kalman_filter/unscented_kalman_filter.py | 1 + Mapping/circle_fitting/circle_fitting.py | 1 + Mapping/gaussian_grid_map/gaussian_grid_map.py | 1 + Mapping/kmeans_clustering/kmeans_clustering.py | 1 + Mapping/raycasting_grid_map/raycasting_grid_map.py | 1 + Mapping/rectangle_fitting/rectangle_fitting.py | 1 + PathPlanning/AStar/a_star.py | 1 + PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py | 1 + PathPlanning/ClosedLoopRRTStar/pure_pursuit.py | 1 + PathPlanning/Dijkstra/dijkstra.py | 1 + PathPlanning/DubinsPath/dubins_path_planning.py | 1 + PathPlanning/DynamicWindowApproach/dynamic_window_approach.py | 1 + PathPlanning/Eta3SplinePath/eta3_spline_path.py | 1 + .../FrenetOptimalTrajectory/frenet_optimal_trajectory.py | 1 + .../GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py | 2 ++ PathPlanning/HybridAStar/a_star.py | 1 + PathPlanning/HybridAStar/hybrid_a_star.py | 1 + PathPlanning/InformedRRTStar/informed_rrt_star.py | 1 + PathPlanning/LQRPlanner/LQRplanner.py | 1 + PathPlanning/LQRRRTStar/lqr_rrt_star.py | 1 + PathPlanning/PotentialFieldPlanning/potential_field_planning.py | 1 + PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py | 1 + .../QuinticPolynomialsPlanner/quintic_polynomials_planner.py | 1 + PathPlanning/RRT/rrt.py | 1 + PathPlanning/RRTDubins/rrt_dubins.py | 1 + PathPlanning/RRTStarDubins/rrt_star_dubins.py | 1 + PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py | 1 + PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py | 1 + PathPlanning/VoronoiRoadMap/voronoi_road_map.py | 1 + PathTracking/cgmres_nmpc/cgmres_nmpc.py | 1 + PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py | 1 + PathTracking/lqr_steer_control/lqr_steer_control.py | 1 + .../model_predictive_speed_and_steer_control.py | 1 + PathTracking/move_to_pose/move_to_pose.py | 1 + PathTracking/pure_pursuit/pure_pursuit.py | 1 + PathTracking/rear_wheel_feedback/rear_wheel_feedback.py | 1 + PathTracking/stanley_controller/stanley_controller.py | 1 + SLAM/EKFSLAM/ekf_slam.py | 1 + SLAM/FastSLAM1/fast_slam1.py | 1 + SLAM/FastSLAM2/fast_slam2.py | 1 + SLAM/GraphBasedSLAM/graph_based_slam.py | 1 + SLAM/iterative_closest_point/iterative_closest_point.py | 1 + 53 files changed, 54 insertions(+) diff --git a/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py b/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py index 89171da212..413a8625a5 100644 --- a/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py +++ b/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py @@ -23,6 +23,7 @@ def __init__(self, x=0, y=0, z=0, roll=0, pitch=0, yaw=0, size=0.25, show_animat if self.show_animation: plt.ion() fig = plt.figure() + # for stopping simulation with the esc key. fig.canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py index 51e09b4e3c..ee0f5e26a5 100644 --- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py +++ b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py @@ -567,6 +567,7 @@ def plot_animation(X, U): # pragma: no cover fig = plt.figure() ax = fig.gca(projection='3d') + # for stopping simulation with the esc key. fig.canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py index b435e62d2b..f3bd25577c 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py @@ -162,6 +162,7 @@ def astar_torus(grid, start_node, goal_node): for i in range(1, len(route)): grid[route[i]] = 6 plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.imshow(grid, cmap=cmap, norm=norm, interpolation=None) diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py index 5a21b806d3..429cd4d211 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py @@ -193,6 +193,7 @@ def astar_torus(grid, start_node, goal_node): for i in range(1, len(route)): grid[route[i]] = 6 plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.imshow(grid, cmap=cmap, norm=norm, interpolation=None) diff --git a/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py b/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py index 576bd29a8f..854ade9038 100644 --- a/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py +++ b/ArmNavigation/n_joint_arm_to_point_control/NLinkArm.py @@ -51,6 +51,7 @@ def update_points(self): def plot(self): # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) diff --git a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py index 134583a95c..60a7cd5f0f 100644 --- a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py +++ b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py @@ -114,6 +114,7 @@ def animation(): def main(): # pragma: no cover fig = plt.figure() fig.canvas.mpl_connect("button_press_event", click) + # for stopping simulation with the esc key. fig.canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) two_joint_arm() diff --git a/Bipedal/bipedal_planner/bipedal_planner.py b/Bipedal/bipedal_planner/bipedal_planner.py index afa68afb25..6502ce5bed 100644 --- a/Bipedal/bipedal_planner/bipedal_planner.py +++ b/Bipedal/bipedal_planner/bipedal_planner.py @@ -111,6 +111,7 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False): if c > len(com_trajectory_for_plot): # set up plotter plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) ax.set_zlim(0, z_c * 2) diff --git a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py index 6ac6144f36..244cfccd9c 100644 --- a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py +++ b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py @@ -213,6 +213,7 @@ def main(): if show_animation: plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) diff --git a/Localization/extended_kalman_filter/extended_kalman_filter.py b/Localization/extended_kalman_filter/extended_kalman_filter.py index 029dac4bf8..2b057e21de 100644 --- a/Localization/extended_kalman_filter/extended_kalman_filter.py +++ b/Localization/extended_kalman_filter/extended_kalman_filter.py @@ -191,6 +191,7 @@ def main(): if show_animation: plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(hz[0, :], hz[1, :], ".g") diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index ac07c59fbd..79302c8abb 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -233,6 +233,7 @@ def main(): if show_animation: plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) draw_heat_map(grid_map.data, mx, my) diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 4b9abd78bd..3e901f8da0 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -230,6 +230,7 @@ def main(): if show_animation: plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) diff --git a/Localization/unscented_kalman_filter/unscented_kalman_filter.py b/Localization/unscented_kalman_filter/unscented_kalman_filter.py index 0005d12fe7..7bf279ced0 100644 --- a/Localization/unscented_kalman_filter/unscented_kalman_filter.py +++ b/Localization/unscented_kalman_filter/unscented_kalman_filter.py @@ -240,6 +240,7 @@ def main(): if show_animation: plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(hz[0, :], hz[1, :], ".g") diff --git a/Mapping/circle_fitting/circle_fitting.py b/Mapping/circle_fitting/circle_fitting.py index 27ceac21f7..c331d56796 100644 --- a/Mapping/circle_fitting/circle_fitting.py +++ b/Mapping/circle_fitting/circle_fitting.py @@ -124,6 +124,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.axis("equal") diff --git a/Mapping/gaussian_grid_map/gaussian_grid_map.py b/Mapping/gaussian_grid_map/gaussian_grid_map.py index 094b094fdd..7893d6a5ee 100644 --- a/Mapping/gaussian_grid_map/gaussian_grid_map.py +++ b/Mapping/gaussian_grid_map/gaussian_grid_map.py @@ -73,6 +73,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) draw_heatmap(gmap, minx, maxx, miny, maxy, xyreso) diff --git a/Mapping/kmeans_clustering/kmeans_clustering.py b/Mapping/kmeans_clustering/kmeans_clustering.py index 5345813096..d658b84f48 100644 --- a/Mapping/kmeans_clustering/kmeans_clustering.py +++ b/Mapping/kmeans_clustering/kmeans_clustering.py @@ -133,6 +133,7 @@ def main(): # for animation if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) clusters.plot_cluster() diff --git a/Mapping/raycasting_grid_map/raycasting_grid_map.py b/Mapping/raycasting_grid_map/raycasting_grid_map.py index cae92a9dcb..372e31eccd 100644 --- a/Mapping/raycasting_grid_map/raycasting_grid_map.py +++ b/Mapping/raycasting_grid_map/raycasting_grid_map.py @@ -124,6 +124,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) draw_heatmap(pmap, minx, maxx, miny, maxy, xyreso) diff --git a/Mapping/rectangle_fitting/rectangle_fitting.py b/Mapping/rectangle_fitting/rectangle_fitting.py index 77c66db250..1c4d412207 100644 --- a/Mapping/rectangle_fitting/rectangle_fitting.py +++ b/Mapping/rectangle_fitting/rectangle_fitting.py @@ -242,6 +242,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.axis("equal") diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py index e4f7dd4d97..d8ef09de85 100644 --- a/PathPlanning/AStar/a_star.py +++ b/PathPlanning/AStar/a_star.py @@ -79,6 +79,7 @@ def planning(self, sx, sy, gx, gy): if show_animation: # pragma: no cover plt.plot(self.calc_grid_position(current.x, self.minx), self.calc_grid_position(current.y, self.miny), "xc") + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if len(closed_set.keys()) % 10 == 0: diff --git a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py index 46ff3caf5c..e84f65d617 100644 --- a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py +++ b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py @@ -534,6 +534,7 @@ def update_graph(self): def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, samples=None, start=None, end=None): plt.clf() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) for rnd in samples: diff --git a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py index d078338d67..5833f6e91e 100644 --- a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py +++ b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py @@ -135,6 +135,7 @@ def closed_loop_prediction(cx, cy, cyaw, speed_profile, goal): if target_ind % 1 == 0 and animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, "-r", label="course") diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index 8e719f50e2..a8f6441328 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -69,6 +69,7 @@ def planning(self, sx, sy, gx, gy): if show_animation: # pragma: no cover plt.plot(self.calc_position(current.x, self.minx), self.calc_position(current.y, self.miny), "xc") + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if len(closedset.keys()) % 10 == 0: diff --git a/PathPlanning/DubinsPath/dubins_path_planning.py b/PathPlanning/DubinsPath/dubins_path_planning.py index 8690fbe8db..de5db2a5aa 100644 --- a/PathPlanning/DubinsPath/dubins_path_planning.py +++ b/PathPlanning/DubinsPath/dubins_path_planning.py @@ -318,6 +318,7 @@ def test(): if show_animation: plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(px, py, label="final course " + str(mode)) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index c2cc358b13..b0d020302f 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -268,6 +268,7 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): if show_animation: plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(predicted_trajectory[:, 0], predicted_trajectory[:, 1], "-g") diff --git a/PathPlanning/Eta3SplinePath/eta3_spline_path.py b/PathPlanning/Eta3SplinePath/eta3_spline_path.py index 51ac612c28..414f6b4534 100644 --- a/PathPlanning/Eta3SplinePath/eta3_spline_path.py +++ b/PathPlanning/Eta3SplinePath/eta3_spline_path.py @@ -213,6 +213,7 @@ def test1(): if show_animation: # plot the path plt.plot(pos[0, :], pos[1, :]) + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.pause(1.0) diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index 1abda92646..861260e9c9 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -347,6 +347,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(tx, ty) diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py index 049373ece2..5c39a1ee81 100644 --- a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py +++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py @@ -213,6 +213,7 @@ def sweep_path_search(sweep_searcher, gmap, grid_search_animation=False): if grid_search_animation: fig, ax = plt.subplots() + # for stopping simulation with the esc key. fig.canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) @@ -268,6 +269,7 @@ def planning_animation(ox, oy, reso): # pragma: no cover if do_animation: for ipx, ipy in zip(px, py): plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(ox, oy, "-xb") diff --git a/PathPlanning/HybridAStar/a_star.py b/PathPlanning/HybridAStar/a_star.py index 918469f0d3..a27293288c 100644 --- a/PathPlanning/HybridAStar/a_star.py +++ b/PathPlanning/HybridAStar/a_star.py @@ -78,6 +78,7 @@ def dp_planning(sx, sy, gx, gy, ox, oy, reso, rr): # show graph if show_animation: # pragma: no cover plt.plot(current.x * reso, current.y * reso, "xc") + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if len(closedset.keys()) % 10 == 0: diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index 70ffcee865..8a87be85a3 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -327,6 +327,7 @@ def hybrid_a_star_planning(start, goal, ox, oy, xyreso, yawreso): if show_animation: # pragma: no cover plt.plot(current.xlist[-1], current.ylist[-1], "xc") + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if len(closedList.keys()) % 10 == 0: diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index ef15022aca..a77b1cea74 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -267,6 +267,7 @@ def get_final_course(self, lastIndex): def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, rnd=None): plt.clf() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: diff --git a/PathPlanning/LQRPlanner/LQRplanner.py b/PathPlanning/LQRPlanner/LQRplanner.py index d5cda0bc50..ba01526a2c 100644 --- a/PathPlanning/LQRPlanner/LQRplanner.py +++ b/PathPlanning/LQRPlanner/LQRplanner.py @@ -54,6 +54,7 @@ def lqr_planning(self, sx, sy, gx, gy, show_animation=True): # animation if show_animation: # pragma: no cover + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(sx, sy, "or") diff --git a/PathPlanning/LQRRRTStar/lqr_rrt_star.py b/PathPlanning/LQRRRTStar/lqr_rrt_star.py index c1f45445ff..177131ac96 100644 --- a/PathPlanning/LQRRRTStar/lqr_rrt_star.py +++ b/PathPlanning/LQRRRTStar/lqr_rrt_star.py @@ -102,6 +102,7 @@ def planning(self, animation=True, search_until_max_iter=True): def draw_graph(self, rnd=None): plt.clf() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: diff --git a/PathPlanning/PotentialFieldPlanning/potential_field_planning.py b/PathPlanning/PotentialFieldPlanning/potential_field_planning.py index 642f1cbff9..31904fa45d 100644 --- a/PathPlanning/PotentialFieldPlanning/potential_field_planning.py +++ b/PathPlanning/PotentialFieldPlanning/potential_field_planning.py @@ -98,6 +98,7 @@ def potential_field_planning(sx, sy, gx, gy, ox, oy, reso, rr): if show_animation: draw_heatmap(pmap) + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(ix, iy, "*k") diff --git a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py index 3fef2d0f7a..0a8ea037d1 100644 --- a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py +++ b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py @@ -194,6 +194,7 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): # show graph if show_animation and len(closedset.keys()) % 2 == 0: + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(current.x, current.y, "xg") diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py index b8d533d4dc..406dbc1ee2 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py @@ -151,6 +151,7 @@ def quintic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_ if show_animation: # pragma: no cover for i, _ in enumerate(time): plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.grid(True) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 9d0bc36272..f8e9908287 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -138,6 +138,7 @@ def get_random_node(self): def draw_graph(self, rnd=None): plt.clf() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: diff --git a/PathPlanning/RRTDubins/rrt_dubins.py b/PathPlanning/RRTDubins/rrt_dubins.py index 2a842aa42c..4599904cc1 100644 --- a/PathPlanning/RRTDubins/rrt_dubins.py +++ b/PathPlanning/RRTDubins/rrt_dubins.py @@ -106,6 +106,7 @@ def planning(self, animation=True, search_until_max_iter=True): def draw_graph(self, rnd=None): # pragma: no cover plt.clf() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: diff --git a/PathPlanning/RRTStarDubins/rrt_star_dubins.py b/PathPlanning/RRTStarDubins/rrt_star_dubins.py index d4601c0f12..65fac54c78 100644 --- a/PathPlanning/RRTStarDubins/rrt_star_dubins.py +++ b/PathPlanning/RRTStarDubins/rrt_star_dubins.py @@ -112,6 +112,7 @@ def planning(self, animation=True, search_until_max_iter=True): def draw_graph(self, rnd=None): plt.clf() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: diff --git a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py index d37ae90634..6ea66dc729 100644 --- a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py +++ b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py @@ -122,6 +122,7 @@ def try_goal_path(self, node): def draw_graph(self, rnd=None): plt.clf() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py index b2f8d4a57d..fbf9495790 100644 --- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py +++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py @@ -395,6 +395,7 @@ def test(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(px, py, label="final course " + str(mode)) diff --git a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py index 86371b2051..7517669628 100644 --- a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py +++ b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py @@ -185,6 +185,7 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): # show graph if show_animation and len(closedset.keys()) % 2 == 0: # pragma: no cover plt.plot(current.x, current.y, "xg") + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.pause(0.001) diff --git a/PathTracking/cgmres_nmpc/cgmres_nmpc.py b/PathTracking/cgmres_nmpc/cgmres_nmpc.py index 1be91b2d20..98a12ab10c 100644 --- a/PathTracking/cgmres_nmpc/cgmres_nmpc.py +++ b/PathTracking/cgmres_nmpc/cgmres_nmpc.py @@ -546,6 +546,7 @@ def animation(plant, controller, dt): steer = math.atan2(controller.history_u_2[t] * WB / v, 1.0) plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(plant.history_x, plant.history_y, "-r", label="trajectory") diff --git a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py index 0e22529623..77409c7f42 100644 --- a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py +++ b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py @@ -224,6 +224,7 @@ def do_simulation(cx, cy, cyaw, ck, speed_profile, goal): if target_ind % 1 == 0 and show_animation: plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, "-r", label="course") diff --git a/PathTracking/lqr_steer_control/lqr_steer_control.py b/PathTracking/lqr_steer_control/lqr_steer_control.py index 9cc36f231f..fe440a1734 100644 --- a/PathTracking/lqr_steer_control/lqr_steer_control.py +++ b/PathTracking/lqr_steer_control/lqr_steer_control.py @@ -203,6 +203,7 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): if target_ind % 1 == 0 and show_animation: plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, "-r", label="course") diff --git a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py index 8bff2e107d..85aea2ed1b 100644 --- a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py +++ b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py @@ -429,6 +429,7 @@ def do_simulation(cx, cy, cyaw, ck, sp, dl, initial_state): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) if ox is not None: diff --git a/PathTracking/move_to_pose/move_to_pose.py b/PathTracking/move_to_pose/move_to_pose.py index 838b780f48..685df1979d 100644 --- a/PathTracking/move_to_pose/move_to_pose.py +++ b/PathTracking/move_to_pose/move_to_pose.py @@ -93,6 +93,7 @@ def plot_vehicle(x, y, theta, x_traj, y_traj): # pragma: no cover plt.plot(x_traj, y_traj, 'b--') + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py index f9624956c4..473feea5da 100644 --- a/PathTracking/pure_pursuit/pure_pursuit.py +++ b/PathTracking/pure_pursuit/pure_pursuit.py @@ -166,6 +166,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plot_arrow(state.x, state.y, state.yaw) diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index 155eeec2ce..c6a3501368 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -149,6 +149,7 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): if target_ind % 1 == 0 and show_animation: plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, "-r", label="course") diff --git a/PathTracking/stanley_controller/stanley_controller.py b/PathTracking/stanley_controller/stanley_controller.py index cbfa4c667e..604ed93f01 100644 --- a/PathTracking/stanley_controller/stanley_controller.py +++ b/PathTracking/stanley_controller/stanley_controller.py @@ -186,6 +186,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, ".r", label="course") diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index b6698be228..4bcafef2fa 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -235,6 +235,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) diff --git a/SLAM/FastSLAM1/fast_slam1.py b/SLAM/FastSLAM1/fast_slam1.py index ef1282995b..892010c53d 100644 --- a/SLAM/FastSLAM1/fast_slam1.py +++ b/SLAM/FastSLAM1/fast_slam1.py @@ -365,6 +365,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py index f8958b8c73..25712fc0cb 100644 --- a/SLAM/FastSLAM2/fast_slam2.py +++ b/SLAM/FastSLAM2/fast_slam2.py @@ -390,6 +390,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") diff --git a/SLAM/GraphBasedSLAM/graph_based_slam.py b/SLAM/GraphBasedSLAM/graph_based_slam.py index e73e8d0d4a..2a5acfab1f 100644 --- a/SLAM/GraphBasedSLAM/graph_based_slam.py +++ b/SLAM/GraphBasedSLAM/graph_based_slam.py @@ -303,6 +303,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") diff --git a/SLAM/iterative_closest_point/iterative_closest_point.py b/SLAM/iterative_closest_point/iterative_closest_point.py index 4a4d29eb5e..0b2802603c 100644 --- a/SLAM/iterative_closest_point/iterative_closest_point.py +++ b/SLAM/iterative_closest_point/iterative_closest_point.py @@ -36,6 +36,7 @@ def icp_matching(previous_points, current_points): if show_animation: # pragma: no cover plt.cla() + # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(previous_points[0, :], previous_points[1, :], ".r") From c09e20bc45b0c4408878b2d02cf17cc9d333dd16 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 14 Dec 2019 21:41:04 +0900 Subject: [PATCH 161/940] Update users_comments.md --- users_comments.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/users_comments.md b/users_comments.md index 2cfd7a4a9b..792f3a4d0d 100644 --- a/users_comments.md +++ b/users_comments.md @@ -404,6 +404,9 @@ URL: https://www.semanticscholar.org/paper/A-Review-of-Robot-Rescue-Simulation-P 7. Ghosh, Ritwika, et al. "CyPhyHouse: A Programming, Simulation, and Deployment Toolchain for Heterogeneous Distributed Coordination." arXiv preprint arXiv:1910.01557 (2019). URL: https://arxiv.org/abs/1910.01557 +8. Hahn, Carsten, et al. "Dynamic Path Planning with Stable Growing Neural Gas." (2019). +URL: https://pdfs.semanticscholar.org/5c06/f3cb9542a51e1bf1a32523c1bc7fea6cecc5.pdf + # Others - Autonomous Vehicle Readings https://richardkelley.io/readings From ca49613b53d8e45b169a3585eb7d0c8bf5057e64 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 23 Dec 2019 20:44:41 +0900 Subject: [PATCH 162/940] Update README.md --- README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/README.md b/README.md index e740049b90..f48e9c0ef3 100644 --- a/README.md +++ b/README.md @@ -605,5 +605,8 @@ This is a list: [Users comments](https://github.com/AtsushiSakai/PythonRobotics/ - [Ryohei Sasaki](https://github.com/rsasaki0109) +- [Göktuğ Karakaşlı](https://github.com/goktug97) + + From 6132629a70b9b47ec9a00dcf338650e22368d0f6 Mon Sep 17 00:00:00 2001 From: YILUN CHEN Date: Mon, 30 Dec 2019 17:52:05 +0800 Subject: [PATCH 163/940] fix environment dependencies --- environment.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/environment.yml b/environment.yml index 28ff9f1b4e..6866ed93ca 100644 --- a/environment.yml +++ b/environment.yml @@ -1,9 +1,11 @@ name: python_robotics dependencies: - python +- pip - matplotlib - scipy - numpy==1.15 - pandas +- coverage - pip: - cvxpy From 164f82c0dc022e71625b53f8e899e7b361a50c17 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 3 Jan 2020 08:47:18 +0900 Subject: [PATCH 164/940] Delete greetings.yml --- .github/workflows/greetings.yml | 13 ------------- 1 file changed, 13 deletions(-) delete mode 100644 .github/workflows/greetings.yml diff --git a/.github/workflows/greetings.yml b/.github/workflows/greetings.yml deleted file mode 100644 index 3da4a69458..0000000000 --- a/.github/workflows/greetings.yml +++ /dev/null @@ -1,13 +0,0 @@ -name: Greetings - -on: [pull_request, issues] - -jobs: - greeting: - runs-on: ubuntu-latest - steps: - - uses: actions/first-interaction@v1 - with: - repo-token: ${{ secrets.GITHUB_TOKEN }} - issue-message: 'Message that will be displayed on users'' This is first issue for you on this project' - pr-message: 'Message that will be displayed on users'' This is first pr for you on this project' From 0c708766e13a167e5afe4a96ea6d4527c74a3e56 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Fri, 3 Jan 2020 14:01:47 +0100 Subject: [PATCH 165/940] :pencil: Removed unused class attribute in quintic_polynomials_planner.py --- .../quintic_polynomials_planner.py | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py index 406dbc1ee2..e7c744d1fe 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py @@ -26,14 +26,7 @@ class QuinticPolynomial: def __init__(self, xs, vxs, axs, xe, vxe, axe, T): - # calc coefficient of quinic polynomial - self.xs = xs - self.vxs = vxs - self.axs = axs - self.xe = xe - self.vxe = vxe - self.axe = axe - + # calc coefficient of quintic polynomial self.a0 = xs self.a1 = vxs self.a2 = axs / 2.0 From 48cdd0817365ac10fc4031a39110dabf06cf4b75 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Fri, 3 Jan 2020 21:53:40 +0100 Subject: [PATCH 166/940] :pencil: Removed unused attribute in classes in frenet_optimal_trajectory.py --- .../frenet_optimal_trajectory.py | 16 ++-------------- 1 file changed, 2 insertions(+), 14 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index 25fdd7dbcf..1b62ea0187 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -49,13 +49,6 @@ class quintic_polynomial: def __init__(self, xs, vxs, axs, xe, vxe, axe, T): # calc coefficient of quintic polynomial - self.xs = xs - self.vxs = vxs - self.axs = axs - self.xe = xe - self.vxe = vxe - self.axe = axe - self.a0 = xs self.a1 = vxs self.a2 = axs / 2.0 @@ -99,12 +92,7 @@ class quartic_polynomial: def __init__(self, xs, vxs, axs, vxe, axe, T): - # calc coefficient of quintic polynomial - self.xs = xs - self.vxs = vxs - self.axs = axs - self.vxe = vxe - self.axe = axe + # calc coefficient of quartic polynomial self.a0 = xs self.a1 = vxs @@ -184,7 +172,7 @@ def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] - # Loongitudinal motion planning (Velocity keeping) + # Longitudinal motion planning (Velocity keeping) for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): tfp = copy.deepcopy(fp) lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) From 1ac858b075b5db19ef4c6130ecd426d42a23eb77 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 4 Jan 2020 09:43:21 +0900 Subject: [PATCH 167/940] Update README.md --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index f48e9c0ef3..ec42812753 100644 --- a/README.md +++ b/README.md @@ -607,6 +607,6 @@ This is a list: [Users comments](https://github.com/AtsushiSakai/PythonRobotics/ - [Göktuğ Karakaşlı](https://github.com/goktug97) - +- [Guillaume Jacquenot](https://github.com/Gjacquenot) From 811bdc1d49ac5d04ebd05c18de906c0b3c7243dc Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Fri, 3 Jan 2020 23:13:36 +0100 Subject: [PATCH 168/940] :hammer: Refactored pure_pursuit.py - Added new method to state class - Removed global variable old_nearest_point_index - Created a class States that store the results --- PathTracking/pure_pursuit/pure_pursuit.py | 161 ++++++++++++---------- 1 file changed, 85 insertions(+), 76 deletions(-) diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py index dfe8a8e17e..49e32677f5 100644 --- a/PathTracking/pure_pursuit/pure_pursuit.py +++ b/PathTracking/pure_pursuit/pure_pursuit.py @@ -17,7 +17,6 @@ L = 2.9 # [m] wheel base of vehicle -old_nearest_point_index = None show_animation = True @@ -31,89 +30,106 @@ def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0): self.rear_x = self.x - ((L / 2) * math.cos(self.yaw)) self.rear_y = self.y - ((L / 2) * math.sin(self.yaw)) + def update(self, a, delta): -def update(state, a, delta): + self.x += self.v * math.cos(self.yaw) * dt + self.y += self.v * math.sin(self.yaw) * dt + self.yaw += self.v / L * math.tan(delta) * dt + self.v += a * dt + self.rear_x = self.x - ((L / 2) * math.cos(self.yaw)) + self.rear_y = self.y - ((L / 2) * math.sin(self.yaw)) - state.x = state.x + state.v * math.cos(state.yaw) * dt - state.y = state.y + state.v * math.sin(state.yaw) * dt - state.yaw = state.yaw + state.v / L * math.tan(delta) * dt - state.v = state.v + a * dt - state.rear_x = state.x - ((L / 2) * math.cos(state.yaw)) - state.rear_y = state.y - ((L / 2) * math.sin(state.yaw)) + def calc_distance(self, point_x, point_y): - return state + dx = self.rear_x - point_x + dy = self.rear_y - point_y + return math.hypot(dx, dy) -def PIDControl(target, current): - a = Kp * (target - current) +class States: - return a + def __init__(self): + self.x = [] + self.y = [] + self.yaw = [] + self.v = [] + self.t = [] + def append(self, t , state): + self.x.append(state.x) + self.y.append(state.y) + self.yaw.append(state.yaw) + self.v.append(state.v) + self.t.append(t) -def pure_pursuit_control(state, cx, cy, pind): - ind = calc_target_index(state, cx, cy) +def PIDControl(target, current): + a = Kp * (target - current) - if pind >= ind: - ind = pind + return a - if ind < len(cx): - tx = cx[ind] - ty = cy[ind] - else: - tx = cx[-1] - ty = cy[-1] - ind = len(cx) - 1 - alpha = math.atan2(ty - state.rear_y, tx - state.rear_x) - state.yaw +class Trajectory: + def __init__(self, cx, cy): + self.cx = cx + self.cy = cy + self.old_nearest_point_index = None - Lf = k * state.v + Lfc + def __call__(self, state): + if self.old_nearest_point_index is None: + # search nearest point index + dx = [state.rear_x - icx for icx in self.cx] + dy = [state.rear_y - icy for icy in self.cy] + d = [idx ** 2 + idy ** 2 for (idx, idy) in zip(dx, dy)] + ind = d.index(min(d)) + self.old_nearest_point_index = ind + else: + ind = self.old_nearest_point_index + distance_this_index = state.calc_distance(self.cx[ind], self.cy[ind]) + while True: + ind = ind + 1 if (ind + 1) < len(self.cx) else ind + distance_next_index = state.calc_distance(self.cx[ind], self.cy[ind]) + if distance_this_index < distance_next_index: + break + distance_this_index = distance_next_index + self.old_nearest_point_index = ind - delta = math.atan2(2.0 * L * math.sin(alpha) / Lf, 1.0) + L = 0.0 - return delta, ind + Lf = k * state.v + Lfc -def calc_distance(state, point_x, point_y): + # search look ahead target point index + while Lf > L and (ind + 1) < len(self.cx): + dx = self.cx[ind] - state.rear_x + dy = self.cy[ind] - state.rear_y + L = math.hypot(dx, dy) + ind += 1 - dx = state.rear_x - point_x - dy = state.rear_y - point_y - return math.hypot(dx, dy) + return ind -def calc_target_index(state, cx, cy): +def pure_pursuit_control(state, trajectory, pind): - global old_nearest_point_index + ind = trajectory(state) + + if pind >= ind: + ind = pind - if old_nearest_point_index is None: - # search nearest point index - dx = [state.rear_x - icx for icx in cx] - dy = [state.rear_y - icy for icy in cy] - d = [idx ** 2 + idy ** 2 for (idx, idy) in zip(dx, dy)] - ind = d.index(min(d)) - old_nearest_point_index = ind + if ind < len(trajectory.cx): + tx = trajectory.cx[ind] + ty = trajectory.cy[ind] else: - ind = old_nearest_point_index - distance_this_index = calc_distance(state, cx[ind], cy[ind]) - while True: - ind = ind + 1 if (ind + 1) < len(cx) else ind - distance_next_index = calc_distance(state, cx[ind], cy[ind]) - if distance_this_index < distance_next_index: - break - distance_this_index = distance_next_index - old_nearest_point_index = ind - - L = 0.0 + tx = trajectory.cx[-1] + ty = trajectory.cy[-1] + ind = len(trajectory.cx) - 1 + + alpha = math.atan2(ty - state.rear_y, tx - state.rear_x) - state.yaw Lf = k * state.v + Lfc - # search look ahead target point index - while Lf > L and (ind + 1) < len(cx): - dx = cx[ind] - state.rear_x - dy = cy[ind] - state.rear_y - L = math.hypot(dx, dy) - ind += 1 + delta = math.atan2(2.0 * L * math.sin(alpha) / Lf, 1.0) - return ind + return delta, ind def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): @@ -144,25 +160,18 @@ def main(): lastIndex = len(cx) - 1 time = 0.0 - x = [state.x] - y = [state.y] - yaw = [state.yaw] - v = [state.v] - t = [0.0] - target_ind = calc_target_index(state, cx, cy) + states = States() + states.append(time, state) + trajectory = Trajectory(cx, cy) + target_ind = trajectory(state) while T >= time and lastIndex > target_ind: ai = PIDControl(target_speed, state.v) - di, target_ind = pure_pursuit_control(state, cx, cy, target_ind) - state = update(state, ai, di) - - time = time + dt + di, target_ind = pure_pursuit_control(state, trajectory, target_ind) + state.update(ai, di) - x.append(state.x) - y.append(state.y) - yaw.append(state.yaw) - v.append(state.v) - t.append(time) + time += dt + states.append(time, state) if show_animation: # pragma: no cover plt.cla() @@ -171,7 +180,7 @@ def main(): lambda event: [exit(0) if event.key == 'escape' else None]) plot_arrow(state.x, state.y, state.yaw) plt.plot(cx, cy, "-r", label="course") - plt.plot(x, y, "-b", label="trajectory") + plt.plot(states.x, states.y, "-b", label="trajectory") plt.plot(cx[target_ind], cy[target_ind], "xg", label="target") plt.axis("equal") plt.grid(True) @@ -184,7 +193,7 @@ def main(): if show_animation: # pragma: no cover plt.cla() plt.plot(cx, cy, ".r", label="course") - plt.plot(x, y, "-b", label="trajectory") + plt.plot(states.x, states.y, "-b", label="trajectory") plt.legend() plt.xlabel("x[m]") plt.ylabel("y[m]") @@ -192,7 +201,7 @@ def main(): plt.grid(True) plt.subplots(1) - plt.plot(t, [iv * 3.6 for iv in v], "-r") + plt.plot(states.t, [iv * 3.6 for iv in states.v], "-r") plt.xlabel("Time[s]") plt.ylabel("Speed[km/h]") plt.grid(True) From f81140e65bcf4648c8aae4bdf14e48080bfbd706 Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 4 Jan 2020 09:45:05 +0100 Subject: [PATCH 169/940] :pencil: Renamed method name __call__ with search_target_index in Trajectory class Thanks to @AtsushiSakai remarks https://github.com/AtsushiSakai/PythonRobotics/pull/269#discussion_r363005681 --- PathTracking/pure_pursuit/pure_pursuit.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py index 49e32677f5..d7cf8fe9f8 100644 --- a/PathTracking/pure_pursuit/pure_pursuit.py +++ b/PathTracking/pure_pursuit/pure_pursuit.py @@ -75,7 +75,7 @@ def __init__(self, cx, cy): self.cy = cy self.old_nearest_point_index = None - def __call__(self, state): + def search_target_index(self, state): if self.old_nearest_point_index is None: # search nearest point index dx = [state.rear_x - icx for icx in self.cx] @@ -110,7 +110,7 @@ def __call__(self, state): def pure_pursuit_control(state, trajectory, pind): - ind = trajectory(state) + ind = trajectory.search_target_index(state) if pind >= ind: ind = pind @@ -163,7 +163,7 @@ def main(): states = States() states.append(time, state) trajectory = Trajectory(cx, cy) - target_ind = trajectory(state) + target_ind = trajectory.search_target_index(state) while T >= time and lastIndex > target_ind: ai = PIDControl(target_speed, state.v) From bfc874492390a803e803992324777376a6b12e8c Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 4 Jan 2020 09:50:41 +0100 Subject: [PATCH 170/940] :hammer: Refcatored modification in pure_pursuit.py Thanks to @AtsushiSakai remark https://github.com/AtsushiSakai/PythonRobotics/pull/269#discussion_r363005775 --- PathTracking/pure_pursuit/pure_pursuit.py | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py index d7cf8fe9f8..4e8b1bedef 100644 --- a/PathTracking/pure_pursuit/pure_pursuit.py +++ b/PathTracking/pure_pursuit/pure_pursuit.py @@ -80,8 +80,8 @@ def search_target_index(self, state): # search nearest point index dx = [state.rear_x - icx for icx in self.cx] dy = [state.rear_y - icy for icy in self.cy] - d = [idx ** 2 + idy ** 2 for (idx, idy) in zip(dx, dy)] - ind = d.index(min(d)) + d = np.hypot(dx, dy) + ind = np.argmin(d) self.old_nearest_point_index = ind else: ind = self.old_nearest_point_index @@ -100,9 +100,7 @@ def search_target_index(self, state): # search look ahead target point index while Lf > L and (ind + 1) < len(self.cx): - dx = self.cx[ind] - state.rear_x - dy = self.cy[ind] - state.rear_y - L = math.hypot(dx, dy) + L = state.calc_distance(self.cx[ind], self.cy[ind]) ind += 1 return ind From 3bdf2555345b93c89068549fc1fd87ce7a7e92dc Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 4 Jan 2020 09:57:30 +0100 Subject: [PATCH 171/940] :hammer: Removed unnecessary parenthesis in pure_pursuit.py --- PathTracking/pure_pursuit/pure_pursuit.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py index 4e8b1bedef..bfc3c7ccf9 100644 --- a/PathTracking/pure_pursuit/pure_pursuit.py +++ b/PathTracking/pure_pursuit/pure_pursuit.py @@ -136,7 +136,7 @@ def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): """ if not isinstance(x, float): - for (ix, iy, iyaw) in zip(x, y, yaw): + for ix, iy, iyaw in zip(x, y, yaw): plot_arrow(ix, iy, iyaw) else: plt.arrow(x, y, length * math.cos(yaw), length * math.sin(yaw), From 08428bed153dfe49085e63becd6f399a713dd57c Mon Sep 17 00:00:00 2001 From: Guillaume Jacquenot Date: Sat, 4 Jan 2020 09:57:47 +0100 Subject: [PATCH 172/940] :pencil: Added Gjacquenot as author as suggested by @AtsushiSakai --- PathTracking/pure_pursuit/pure_pursuit.py | 1 + 1 file changed, 1 insertion(+) diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py index bfc3c7ccf9..bcaf869726 100644 --- a/PathTracking/pure_pursuit/pure_pursuit.py +++ b/PathTracking/pure_pursuit/pure_pursuit.py @@ -3,6 +3,7 @@ Path tracking simulation with pure pursuit steering control and PID speed control. author: Atsushi Sakai (@Atsushi_twi) + Guillaume Jacquenot (@Gjacquenot) """ import numpy as np From f19fdacb014af4af1395519746b2cd7f6c89b8cc Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 5 Jan 2020 13:47:32 +0900 Subject: [PATCH 173/940] change default mode for DWA --- PathPlanning/DynamicWindowApproach/dynamic_window_approach.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 891e68cbe8..2dab2f301f 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -293,4 +293,4 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): if __name__ == '__main__': - main(robot_type=RobotType.rectangle) + main(robot_type=RobotType.circle) From 5ceb83783e7c2e561afac87f9bb899609fe7770e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 5 Jan 2020 13:53:49 +0900 Subject: [PATCH 174/940] Add node valid check to fix #271 --- PathPlanning/RRT/rrt.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index b590d7b1cb..4acea0c10e 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -140,7 +140,7 @@ def draw_graph(self, rnd=None): plt.clf() # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: @@ -175,6 +175,10 @@ def get_nearest_node_index(node_list, rnd_node): @staticmethod def check_collision(node, obstacleList): + + if node is None: + return False + for (ox, oy, size) in obstacleList: dx_list = [ox - x for x in node.path_x] dy_list = [oy - y for y in node.path_y] From fbeeefb52204ec50dc5686d36b78b83867e41080 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 5 Jan 2020 20:45:12 +0900 Subject: [PATCH 175/940] code cleanup for quintic_polynomials_planner.py --- .../quintic_polynomials_planner.py | 25 +++++++++---------- 1 file changed, 12 insertions(+), 13 deletions(-) diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py index e7c744d1fe..8600f1d7bd 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py @@ -24,18 +24,17 @@ class QuinticPolynomial: - def __init__(self, xs, vxs, axs, xe, vxe, axe, T): - + def __init__(self, xs, vxs, axs, xe, vxe, axe, time): # calc coefficient of quintic polynomial self.a0 = xs self.a1 = vxs self.a2 = axs / 2.0 - A = np.array([[T**3, T**4, T**5], - [3 * T ** 2, 4 * T ** 3, 5 * T ** 4], - [6 * T, 12 * T ** 2, 20 * T ** 3]]) - b = np.array([xe - self.a0 - self.a1 * T - self.a2 * T**2, - vxe - self.a1 - 2 * self.a2 * T, + A = np.array([[time ** 3, time ** 4, time ** 5], + [3 * time ** 2, 4 * time ** 3, 5 * time ** 4], + [6 * time, 12 * time ** 2, 20 * time ** 3]]) + b = np.array([xe - self.a0 - self.a1 * time - self.a2 * time ** 2, + vxe - self.a1 - 2 * self.a2 * time, axe - 2 * self.a2]) x = np.linalg.solve(A, b) @@ -44,24 +43,24 @@ def __init__(self, xs, vxs, axs, xe, vxe, axe, T): self.a5 = x[2] def calc_point(self, t): - xt = self.a0 + self.a1 * t + self.a2 * t**2 + \ - self.a3 * t**3 + self.a4 * t**4 + self.a5 * t**5 + xt = self.a0 + self.a1 * t + self.a2 * t ** 2 + \ + self.a3 * t ** 3 + self.a4 * t ** 4 + self.a5 * t ** 5 return xt def calc_first_derivative(self, t): xt = self.a1 + 2 * self.a2 * t + \ - 3 * self.a3 * t**2 + 4 * self.a4 * t**3 + 5 * self.a5 * t**4 + 3 * self.a3 * t ** 2 + 4 * self.a4 * t ** 3 + 5 * self.a5 * t ** 4 return xt def calc_second_derivative(self, t): - xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t**2 + 20 * self.a5 * t**3 + xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t ** 2 + 20 * self.a5 * t ** 3 return xt def calc_third_derivative(self, t): - xt = 6 * self.a3 + 24 * self.a4 * t + 60 * self.a5 * t**2 + xt = 6 * self.a3 + 24 * self.a4 * t + 60 * self.a5 * t ** 2 return xt @@ -146,7 +145,7 @@ def quintic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_ plt.cla() # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + lambda event: [exit(0) if event.key == 'escape' else None]) plt.grid(True) plt.axis("equal") plot_arrow(sx, sy, syaw) From c50bba7c0489493dc144e9202aad65ab13abbcaa Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 5 Jan 2020 22:12:37 +0900 Subject: [PATCH 176/940] add jupyter docs --- .../quintic_polynomials_planner.ipynb | 56 +++++++++++++++++++ 1 file changed, 56 insertions(+) create mode 100644 PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb new file mode 100644 index 0000000000..bc829f2e13 --- /dev/null +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb @@ -0,0 +1,56 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "source": [ + "# Quintic polynomials planner" + ], + "metadata": { + "collapsed": false + } + }, + { + "cell_type": "markdown", + "source": [ + "## Quintic polynomials for one dimension robot motion\n", + "\n", + "$e^{i\\pi} + 1 = 0$\n", + "\n", + "\n" + ], + "metadata": { + "collapsed": false + } + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.6" + }, + "pycharm": { + "stem_cell": { + "cell_type": "raw", + "source": [], + "metadata": { + "collapsed": false + } + } + } + }, + "nbformat": 4, + "nbformat_minor": 0 +} \ No newline at end of file From e4fb755471bc476d7fe21f17f1125bc311466baf Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 5 Jan 2020 22:24:46 +0900 Subject: [PATCH 177/940] update jupyter docs --- .../quintic_polynomials_planner.ipynb | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb index bc829f2e13..7b83a87b7e 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb @@ -12,7 +12,21 @@ { "cell_type": "markdown", "source": [ - "## Quintic polynomials for one dimension robot motion\n", + "## Quintic polynomials for one dimensional robot motion\n", + "\n", + "We assume a dimensional robot motion $x(t)$ at time $t$ is formulated as a quintic polynomials based on time as follows:\n", + "\n", + "$x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4$\n", + "\n", + "a_0, a_1. a_2, a_3 are parameters of the quintic polynomial.\n", + "\n", + "So, when time is 0,\n", + "\n", + "$x(0) = a_0 = x_s$\n", + "\n", + "x_s is a start x position.\n", + "\n", + "\n", "\n", "$e^{i\\pi} + 1 = 0$\n", "\n", From 763ca4fd15f4ae4bd272709bf5e187475ca4e4a3 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 5 Jan 2020 22:37:08 +0900 Subject: [PATCH 178/940] update jupyter docs --- .../quintic_polynomials_planner.ipynb | 12 +++++++++--- .../quintic_polynomials_planner.py | 1 + 2 files changed, 10 insertions(+), 3 deletions(-) diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb index 7b83a87b7e..804b7fba13 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb @@ -24,13 +24,19 @@ "\n", "$x(0) = a_0 = x_s$\n", "\n", - "x_s is a start x position.\n", + "$x_s$ is a start x position.\n", "\n", + "Then, differentiating this equation with t, \n", "\n", + "$x'(t) = a_1+2a_2t+3a_3t^2+4a_4t^3$\n", "\n", - "$e^{i\\pi} + 1 = 0$\n", + "So, when time is 0,\n", + "\n", + "$x'(0) = a_1 = v_s$\n", + "\n", + "$v_s$ is a initial speed for x axis.\n", "\n", - "\n" + "=== TBD ==== \n" ], "metadata": { "collapsed": false diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py index 8600f1d7bd..5538731dcd 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py @@ -26,6 +26,7 @@ class QuinticPolynomial: def __init__(self, xs, vxs, axs, xe, vxe, axe, time): # calc coefficient of quintic polynomial + # See jupyter notebook document for derivation of this equation. self.a0 = xs self.a1 = vxs self.a2 = axs / 2.0 From 0de06534d22e22d84b4fe65ad973525e16e312c0 Mon Sep 17 00:00:00 2001 From: Yilun Chen Date: Fri, 17 Jan 2020 19:17:28 -0500 Subject: [PATCH 179/940] cleanup in dynamic window approach --- .../DynamicWindowApproach/dynamic_window_approach.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 92fd08bb40..9e9d34d721 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -22,7 +22,7 @@ def dwa_control(x, config, goal, ob): dw = calc_dynamic_window(x, config) - u, trajectory = calc_final_input(x, dw, config, goal, ob) + u, trajectory = calc_control_and_trajectory(x, dw, config, goal, ob) return u, trajectory @@ -77,9 +77,9 @@ def motion(x, u, dt): motion model """ - x[2] += u[1] * dt x[0] += u[0] * math.cos(x[2]) * dt x[1] += u[0] * math.sin(x[2]) * dt + x[2] += u[1] * dt x[3] = u[0] x[4] = u[1] @@ -101,7 +101,7 @@ def calc_dynamic_window(x, config): x[4] - config.max_dyawrate * config.dt, x[4] + config.max_dyawrate * config.dt] - # [vmin,vmax, yaw_rate min, yaw_rate max] + # [vmin, vmax, yaw_rate min, yaw_rate max] dw = [max(Vs[0], Vd[0]), min(Vs[1], Vd[1]), max(Vs[2], Vd[2]), min(Vs[3], Vd[3])] @@ -124,7 +124,7 @@ def predict_trajectory(x_init, v, y, config): return traj -def calc_final_input(x, dw, config, goal, ob): +def calc_control_and_trajectory(x, dw, config, goal, ob): """ calculation final input with dynamic window """ From dc612e6f2000a67b5542cc48303bf0b505350926 Mon Sep 17 00:00:00 2001 From: Yilun Chen Date: Sun, 19 Jan 2020 11:25:52 -0500 Subject: [PATCH 180/940] minor fix in dijkstra.py --- .gitignore | 1 + PathPlanning/Dijkstra/dijkstra.py | 18 ++++++++---------- 2 files changed, 9 insertions(+), 10 deletions(-) diff --git a/.gitignore b/.gitignore index 272dc63b6d..c971b8f9c5 100644 --- a/.gitignore +++ b/.gitignore @@ -70,3 +70,4 @@ target/ .ipynb_checkpoints matplotrecorder/* +.vscode/settings.json diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index 62da6d761b..ee88b3f9f1 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -33,7 +33,7 @@ def __init__(self, x, y, cost, pind): self.x = x # index of grid self.y = y # index of grid self.cost = cost - self.pind = pind + self.pind = pind # index of previous Node def __str__(self): return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind) @@ -88,10 +88,10 @@ def planning(self, sx, sy, gx, gy): closedset[c_id] = current # expand search grid based on motion model - for i, _ in enumerate(self.motion): - node = self.Node(current.x + self.motion[i][0], - current.y + self.motion[i][1], - current.cost + self.motion[i][2], c_id) + for move_x, move_y, move_cost in self.motion: + node = self.Node(current.x + move_x, + current.y + move_y, + current.cost + move_cost, c_id) n_id = self.calc_index(node) if n_id in closedset: @@ -124,11 +124,6 @@ def calc_final_path(self, ngoal, closedset): return rx, ry - def calc_heuristic(self, n1, n2): - w = 1.0 # weight of heuristic - d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) - return d - def calc_position(self, index, minp): pos = index*self.reso+minp return pos @@ -242,6 +237,9 @@ def main(): dijkstra = Dijkstra(ox, oy, grid_size, robot_radius) rx, ry = dijkstra.planning(sx, sy, gx, gy) + print(rx) + print(ry) + if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") plt.show() From f261da52f0301041829dc20d8845372cf98a9a73 Mon Sep 17 00:00:00 2001 From: Yilun Chen Date: Sun, 19 Jan 2020 11:29:05 -0500 Subject: [PATCH 181/940] remove print --- PathPlanning/Dijkstra/dijkstra.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index ee88b3f9f1..bb1fb3aa63 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -237,9 +237,6 @@ def main(): dijkstra = Dijkstra(ox, oy, grid_size, robot_radius) rx, ry = dijkstra.planning(sx, sy, gx, gy) - print(rx) - print(ry) - if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") plt.show() From 1c081ed3e0ccfbc20214a505b2fbd925427e0fa1 Mon Sep 17 00:00:00 2001 From: Yilun Chen Date: Sun, 19 Jan 2020 18:35:52 -0500 Subject: [PATCH 182/940] address the comment --- PathPlanning/DynamicWindowApproach/dynamic_window_approach.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 9e9d34d721..b8395e5ff8 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -77,9 +77,9 @@ def motion(x, u, dt): motion model """ + x[2] += u[1] * dt x[0] += u[0] * math.cos(x[2]) * dt x[1] += u[0] * math.sin(x[2]) * dt - x[2] += u[1] * dt x[3] = u[0] x[4] = u[1] From cd65de271462b9cc50a130c708f1d2c0e005e953 Mon Sep 17 00:00:00 2001 From: Atsushi Date: Tue, 21 Jan 2020 10:58:02 +0900 Subject: [PATCH 183/940] add math descriptions --- .../quintic_polynomials_planner.ipynb | 119 ++++++++++++++---- 1 file changed, 93 insertions(+), 26 deletions(-) diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb index 804b7fba13..f094ae2c15 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb @@ -2,45 +2,112 @@ "cells": [ { "cell_type": "markdown", + "metadata": {}, "source": [ "# Quintic polynomials planner" - ], - "metadata": { - "collapsed": false - } + ] }, { "cell_type": "markdown", + "metadata": {}, "source": [ "## Quintic polynomials for one dimensional robot motion\n", "\n", - "We assume a dimensional robot motion $x(t)$ at time $t$ is formulated as a quintic polynomials based on time as follows:\n", + "We assume a one-dimensional robot motion $x(t)$ at time $t$ is formulated as a quintic polynomials based on time as follows:\n", "\n", - "$x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4$\n", + "$x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5$ --(1)\n", "\n", - "a_0, a_1. a_2, a_3 are parameters of the quintic polynomial.\n", + "$a_0, a_1. a_2, a_3, a_4, a_5$ are parameters of the quintic polynomial.\n", "\n", - "So, when time is 0,\n", + "It is assumed that terminal states (start and end) are known as boundary conditions.\n", + "\n", + "Start position, velocity, and acceleration are $x_s, v_s, a_s$ respectively.\n", "\n", - "$x(0) = a_0 = x_s$\n", + "End position, velocity, and acceleration are $x_e, v_e, a_e$ respectively.\n", "\n", - "$x_s$ is a start x position.\n", + "So, when time is 0.\n", "\n", - "Then, differentiating this equation with t, \n", + "$x(0) = a_0 = x_s$ -- (2)\n", "\n", - "$x'(t) = a_1+2a_2t+3a_3t^2+4a_4t^3$\n", + "Then, differentiating the equation (1) with t, \n", + "\n", + "$x'(t) = a_1+2a_2t+3a_3t^2+4a_4t^3+5a_5t^4$ -- (3)\n", "\n", "So, when time is 0,\n", "\n", - "$x'(0) = a_1 = v_s$\n", + "$x'(0) = a_1 = v_s$ -- (4)\n", "\n", - "$v_s$ is a initial speed for x axis.\n", + "Then, differentiating the equation (3) with t again, \n", "\n", - "=== TBD ==== \n" - ], - "metadata": { - "collapsed": false - } + "$x''(t) = 2a_2+6a_3t+12a_4t^2$ -- (5)\n", + "\n", + "So, when time is 0,\n", + "\n", + "$x''(0) = 2a_2 = a_s$ -- (6)\n", + "\n", + "so, we can calculate $a_0$, $a_1$, $a_2$ with eq. (2), (4), (6) and boundary conditions.\n", + "\n", + "$a_3, a_4, a_5$ are still unknown in eq(1).\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We assume that the end time for a maneuver is $T$, we can get these equations from eq (1), (3), (5):\n", + "\n", + "$x(T)=a_0+a_1T+a_2T^2+a_3T^3+a_4T^4+a_5T^5=x_e$ -- (7)\n", + "\n", + "$x'(T)=a_1+2a_2T+3a_3T^2+4a_4T^3+5a_5T^4=v_e$ -- (8)\n", + "\n", + "$x''(T)=2a_2+6a_3T+12a_4T^2+20a_5T^3=a_e$ -- (9)\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "From eq (7), (8), (9), we can calculate $a_3, a_4, a_5$ to solve the linear equations.\n", + "\n", + "$Ax=b$\n", + "\n", + "$\\begin{bmatrix} T^3 & T^4 & T^5 \\\\ 3T^2 & 4T^3 & 5T^4 \\\\ 6T & 12T^2 & 20T^3 \\end{bmatrix}\n", + "\\begin{bmatrix} a_3\\\\ a_4\\\\ a_5\\end{bmatrix}=\\begin{bmatrix} x_e-x_s-v_sT-0.5a_sT^2\\\\ v_e-v_s-a_sT\\\\ a_e-a_s\\end{bmatrix}$\n", + "\n", + "We can get all unknown parameters now" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Quintic polynomials for two dimensional robot motion (x-y)\n", + "\n", + "If you use two quintic polynomials along x axis and y axis, you can plan for two dimensional robot motion in x-y plane.\n", + "\n", + "$x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5$ --(10)\n", + "\n", + "$y(t) = b_0+b_1t+b_2t^2+b_3t^3+b_4t^4+b_5t^5$ --(11)\n", + "\n", + "It is assumed that terminal states (start and end) are known as boundary conditions.\n", + "\n", + "Start position, orientation, velocity, and acceleration are $x_s, y_s, \\theta_s, v_s, a_s$ respectively.\n", + "\n", + "End position, orientation, velocity, and acceleration are $x_e, y_e. \\theta_e, v_e, a_e$ respectively.\n", + "\n", + "Each velocity and acceleration boundary condition can be calculated with each orientation.\n", + "\n", + "$v_{xs}=v_scos(\\theta_s), v_{ys}=v_ssin(\\theta_s)$\n", + "\n", + "$v_{xe}=v_ecos(\\theta_e), v_{ye}=v_esin(\\theta_e)$\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] } ], "metadata": { @@ -52,25 +119,25 @@ "language_info": { "codemirror_mode": { "name": "ipython", - "version": 2 + "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", - "pygments_lexer": "ipython2", - "version": "2.7.6" + "pygments_lexer": "ipython3", + "version": "3.7.5" }, "pycharm": { "stem_cell": { "cell_type": "raw", - "source": [], "metadata": { "collapsed": false - } + }, + "source": [] } } }, "nbformat": 4, - "nbformat_minor": 0 -} \ No newline at end of file + "nbformat_minor": 1 +} From 33f4b944129b176c760879de7015f6183bb32950 Mon Sep 17 00:00:00 2001 From: Atsushi Date: Tue, 21 Jan 2020 11:12:15 +0900 Subject: [PATCH 184/940] keep DRY --- .../frenet_optimal_trajectory.py | 58 +++++-------------- 1 file changed, 13 insertions(+), 45 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index 1b62ea0187..b113bcbe32 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -17,6 +17,17 @@ import copy import math import cubic_spline_planner +import sys +import os + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../QuinticPolynomialsPlanner/") + +try: + from quintic_polynomials_planner import QuinticPolynomial +except ImportError: + raise + SIM_LOOP = 500 @@ -44,50 +55,6 @@ show_animation = True -class quintic_polynomial: - - def __init__(self, xs, vxs, axs, xe, vxe, axe, T): - - # calc coefficient of quintic polynomial - self.a0 = xs - self.a1 = vxs - self.a2 = axs / 2.0 - - A = np.array([[T**3, T**4, T**5], - [3 * T ** 2, 4 * T ** 3, 5 * T ** 4], - [6 * T, 12 * T ** 2, 20 * T ** 3]]) - b = np.array([xe - self.a0 - self.a1 * T - self.a2 * T**2, - vxe - self.a1 - 2 * self.a2 * T, - axe - 2 * self.a2]) - x = np.linalg.solve(A, b) - - self.a3 = x[0] - self.a4 = x[1] - self.a5 = x[2] - - def calc_point(self, t): - xt = self.a0 + self.a1 * t + self.a2 * t**2 + \ - self.a3 * t**3 + self.a4 * t**4 + self.a5 * t**5 - - return xt - - def calc_first_derivative(self, t): - xt = self.a1 + 2 * self.a2 * t + \ - 3 * self.a3 * t**2 + 4 * self.a4 * t**3 + 5 * self.a5 * t**4 - - return xt - - def calc_second_derivative(self, t): - xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t**2 + 20 * self.a5 * t**3 - - return xt - - def calc_third_derivative(self, t): - xt = 6 * self.a3 + 24 * self.a4 * t + 60 * self.a5 * t**2 - - return xt - - class quartic_polynomial: def __init__(self, xs, vxs, axs, vxe, axe, T): @@ -164,7 +131,8 @@ def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): for Ti in np.arange(MINT, MAXT, DT): fp = Frenet_path() - lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + # lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) + lat_qp = QuinticPolynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) fp.t = [t for t in np.arange(0.0, Ti, DT)] fp.d = [lat_qp.calc_point(t) for t in fp.t] From d4cb0f981d688d8df2c65ca846544a4d8494f9df Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 27 Jan 2020 17:39:10 +0900 Subject: [PATCH 185/940] fix cal_covariance func and clean up code and added jupyter doc --- .../particle_filter/particle_filter.ipynb | 62 +++++++++++ .../particle_filter/particle_filter.py | 100 +++++++++--------- 2 files changed, 114 insertions(+), 48 deletions(-) create mode 100644 Localization/particle_filter/particle_filter.ipynb diff --git a/Localization/particle_filter/particle_filter.ipynb b/Localization/particle_filter/particle_filter.ipynb new file mode 100644 index 0000000000..46825b639d --- /dev/null +++ b/Localization/particle_filter/particle_filter.ipynb @@ -0,0 +1,62 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": { + "collapsed": true, + "pycharm": { + "name": "#%% md\n" + } + }, + "source": [ + "# Particle Filter\n", + "\n" + ] + }, + { + "cell_type": "markdown", + "source": [ + "## How to calculate covariance matrix from particles\n", + "\n", + "$\\Xi_{j,k}=\\frac{1}{1-\\sum^N_{i=1}(w^i)^2}\\sum^N_{i=1}w^i(x^i_j-\\mu_j)(x^i_k-\\mu_k)$\n", + "\n", + "Ref:\n", + "\n", + "- [Improving the particle filter in high dimensions using conjugate artificial process noise](https://www.visiondummy.com/2014/04/draw-error-ellipse-representing-covariance-matrix/)\n" + ], + "metadata": { + "collapsed": false + } + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 2 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython2", + "version": "2.7.6" + }, + "pycharm": { + "stem_cell": { + "cell_type": "raw", + "source": [], + "metadata": { + "collapsed": false + } + } + } + }, + "nbformat": 4, + "nbformat_minor": 0 +} \ No newline at end of file diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index bfef3ed929..6eca4eb53b 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -37,20 +37,20 @@ def calc_input(): return u -def observation(xTrue, xd, u, RF_ID): - xTrue = motion_model(xTrue, u) +def observation(x_true, xd, u, rf_id): + x_true = motion_model(x_true, u) # add noise to gps x-y z = np.zeros((0, 3)) - for i in range(len(RF_ID[:, 0])): + for i in range(len(rf_id[:, 0])): - dx = xTrue[0, 0] - RF_ID[i, 0] - dy = xTrue[1, 0] - RF_ID[i, 1] + dx = x_true[0, 0] - rf_id[i, 0] + dy = x_true[1, 0] - rf_id[i, 1] d = math.hypot(dx, dy) if d <= MAX_RANGE: dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise - zi = np.array([[dn, RF_ID[i, 0], RF_ID[i, 1]]]) + zi = np.array([[dn, rf_id[i, 0], rf_id[i, 1]]]) z = np.vstack((z, zi)) # add noise to input @@ -60,7 +60,7 @@ def observation(xTrue, xd, u, RF_ID): xd = motion_model(xd, ud) - return xTrue, z, xd, ud + return x_true, z, xd, ud def motion_model(x, u): @@ -86,13 +86,17 @@ def gauss_likelihood(x, sigma): return p -def calc_covariance(xEst, px, pw): +def calc_covariance(x_est, px, pw): + """ + calculate covariance matrix + see ipynb doc + """ cov = np.zeros((3, 3)) - - for i in range(px.shape[1]): - dx = (px[:, i] - xEst)[0:3] - cov += pw[0, i] * dx.dot(dx.T) - cov /= NP + n_particle = px.shape[1] + for i in range(n_particle): + dx = (px[:, i:i + 1] - x_est)[0:3] + cov += pw[0, i] * dx @ dx.T + cov *= 1.0 / (1.0 - pw @ pw.T) return cov @@ -125,13 +129,13 @@ def pf_localization(px, pw, z, u): pw = pw / pw.sum() # normalize - xEst = px.dot(pw.T) - PEst = calc_covariance(xEst, px, pw) + x_est = px.dot(pw.T) + p_est = calc_covariance(x_est, px, pw) N_eff = 1.0 / (pw.dot(pw.T))[0, 0] # Effective particle number if N_eff < NTh: px, pw = re_sampling(px, pw) - return xEst, PEst, px, pw + return x_est, p_est, px, pw def re_sampling(px, pw): @@ -140,8 +144,8 @@ def re_sampling(px, pw): """ w_cum = np.cumsum(pw) - base = np.arange(0.0, 1.0, 1/NP) - re_sample_id = base + np.random.uniform(0, 1/NP) + base = np.arange(0.0, 1.0, 1 / NP) + re_sample_id = base + np.random.uniform(0, 1 / NP) indexes = [] ind = 0 for ip in range(NP): @@ -155,9 +159,9 @@ def re_sampling(px, pw): return px, pw -def plot_covariance_ellipse(xEst, PEst): # pragma: no cover - Pxy = PEst[0:2, 0:2] - eig_val, eig_vec = np.linalg.eig(Pxy) +def plot_covariance_ellipse(x_est, p_est): # pragma: no cover + p_xy = p_est[0:2, 0:2] + eig_val, eig_vec = np.linalg.eig(p_xy) if eig_val[0] >= eig_val[1]: big_ind = 0 @@ -186,8 +190,8 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover Rot = np.array([[math.cos(angle), -math.sin(angle)], [math.sin(angle), math.cos(angle)]]) fx = Rot.dot(np.array([[x, y]])) - px = np.array(fx[0, :] + xEst[0, 0]).flatten() - py = np.array(fx[1, :] + xEst[1, 0]).flatten() + px = np.array(fx[0, :] + x_est[0, 0]).flatten() + py = np.array(fx[1, :] + x_est[1, 0]).flatten() plt.plot(px, py, "--r") @@ -197,54 +201,54 @@ def main(): time = 0.0 # RF_ID positions [x, y] - RFi_ID = np.array([[10.0, 0.0], - [10.0, 10.0], - [0.0, 15.0], - [-5.0, 20.0]]) + rf_id = np.array([[10.0, 0.0], + [10.0, 10.0], + [0.0, 15.0], + [-5.0, 20.0]]) # State Vector [x y yaw v]' - xEst = np.zeros((4, 1)) - xTrue = np.zeros((4, 1)) + x_est = np.zeros((4, 1)) + x_true = np.zeros((4, 1)) px = np.zeros((4, NP)) # Particle store pw = np.zeros((1, NP)) + 1.0 / NP # Particle weight - xDR = np.zeros((4, 1)) # Dead reckoning + x_dr = np.zeros((4, 1)) # Dead reckoning # history - hxEst = xEst - hxTrue = xTrue - hxDR = xTrue + h_x_est = x_est + h_x_true = x_true + h_x_dr = x_true while SIM_TIME >= time: time += DT u = calc_input() - xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFi_ID) + x_true, z, x_dr, ud = observation(x_true, x_dr, u, rf_id) - xEst, PEst, px, pw = pf_localization(px, pw, z, ud) + x_est, PEst, px, pw = pf_localization(px, pw, z, ud) # store data history - hxEst = np.hstack((hxEst, xEst)) - hxDR = np.hstack((hxDR, xDR)) - hxTrue = np.hstack((hxTrue, xTrue)) + h_x_est = np.hstack((h_x_est, x_est)) + h_x_dr = np.hstack((h_x_dr, x_dr)) + h_x_true = np.hstack((h_x_true, x_true)) if show_animation: plt.cla() # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + lambda event: [exit(0) if event.key == 'escape' else None]) for i in range(len(z[:, 0])): - plt.plot([xTrue[0, 0], z[i, 1]], [xTrue[1, 0], z[i, 2]], "-k") - plt.plot(RFi_ID[:, 0], RFi_ID[:, 1], "*k") + plt.plot([x_true[0, 0], z[i, 1]], [x_true[1, 0], z[i, 2]], "-k") + plt.plot(rf_id[:, 0], rf_id[:, 1], "*k") plt.plot(px[0, :], px[1, :], ".r") - plt.plot(np.array(hxTrue[0, :]).flatten(), - np.array(hxTrue[1, :]).flatten(), "-b") - plt.plot(np.array(hxDR[0, :]).flatten(), - np.array(hxDR[1, :]).flatten(), "-k") - plt.plot(np.array(hxEst[0, :]).flatten(), - np.array(hxEst[1, :]).flatten(), "-r") - plot_covariance_ellipse(xEst, PEst) + plt.plot(np.array(h_x_true[0, :]).flatten(), + np.array(h_x_true[1, :]).flatten(), "-b") + plt.plot(np.array(h_x_dr[0, :]).flatten(), + np.array(h_x_dr[1, :]).flatten(), "-k") + plt.plot(np.array(h_x_est[0, :]).flatten(), + np.array(h_x_est[1, :]).flatten(), "-r") + plot_covariance_ellipse(x_est, PEst) plt.axis("equal") plt.grid(True) plt.pause(0.001) From 123c4f777ccfc49a0a11a8b99c9a63013d46b9a7 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 27 Jan 2020 19:57:48 +0900 Subject: [PATCH 186/940] update ipynb doc. --- Localization/particle_filter/particle_filter.ipynb | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/Localization/particle_filter/particle_filter.ipynb b/Localization/particle_filter/particle_filter.ipynb index 46825b639d..65f1e026df 100644 --- a/Localization/particle_filter/particle_filter.ipynb +++ b/Localization/particle_filter/particle_filter.ipynb @@ -9,7 +9,7 @@ } }, "source": [ - "# Particle Filter\n", + "# Particle Filter Localization\n", "\n" ] }, @@ -18,11 +18,21 @@ "source": [ "## How to calculate covariance matrix from particles\n", "\n", + "The covariance matrix $\\Xi$ from particle information is calculated by the following equation: \n", + "\n", "$\\Xi_{j,k}=\\frac{1}{1-\\sum^N_{i=1}(w^i)^2}\\sum^N_{i=1}w^i(x^i_j-\\mu_j)(x^i_k-\\mu_k)$\n", "\n", + "- $\\Xi_{j,k}$ is covariance matrix element at row $i$ and column $k$.\n", + "\n", + "- $w^i$ is the weight of the $i$ th particle. \n", + "\n", + "- $x^i_j$ is the $j$ th state of the $i$ th particle. \n", + "\n", + "- $\\mu_j$ is the $j$ th mean state of particles.\n", + "\n", "Ref:\n", "\n", - "- [Improving the particle filter in high dimensions using conjugate artificial process noise](https://www.visiondummy.com/2014/04/draw-error-ellipse-representing-covariance-matrix/)\n" + "- [Improving the particle filter in high dimensions using conjugate artificial process noise](https://arxiv.org/pdf/1801.07000.pdf)\n" ], "metadata": { "collapsed": false From 4e323212e51f32b2e11a94a4c35bd1ca9e1ef4ef Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 27 Jan 2020 20:25:40 +0900 Subject: [PATCH 187/940] start fix the bug. --- PathPlanning/DubinsPath/dubins_path_planning.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/PathPlanning/DubinsPath/dubins_path_planning.py b/PathPlanning/DubinsPath/dubins_path_planning.py index 410e8db01a..ce32a4668b 100644 --- a/PathPlanning/DubinsPath/dubins_path_planning.py +++ b/PathPlanning/DubinsPath/dubins_path_planning.py @@ -212,7 +212,6 @@ def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c, D_ANGLE=np.deg2rad(10.0) def generate_course(length, mode, c, D_ANGLE): - px = [0.0] py = [0.0] pyaw = [0.0] @@ -299,7 +298,6 @@ def main(): def test(): - NTEST = 5 for i in range(NTEST): @@ -320,7 +318,7 @@ def test(): plt.cla() # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(px, py, label="final course " + str(mode)) # plotting From 18ac00dced6448f12241c8d9d42d0e06709cc17a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 28 Jan 2020 21:35:49 +0900 Subject: [PATCH 188/940] fix the dubins planning bug and code clean up --- .../DubinsPath/dubins_path_planning.py | 208 +++++++++--------- PathPlanning/RRTDubins/rrt_dubins.py | 3 + PathPlanning/RRTStarDubins/rrt_star_dubins.py | 5 +- tests/test_dubins_path_planning.py | 36 ++- 4 files changed, 143 insertions(+), 109 deletions(-) diff --git a/PathPlanning/DubinsPath/dubins_path_planning.py b/PathPlanning/DubinsPath/dubins_path_planning.py index ce32a4668b..b72801a6b3 100644 --- a/PathPlanning/DubinsPath/dubins_path_planning.py +++ b/PathPlanning/DubinsPath/dubins_path_planning.py @@ -21,7 +21,7 @@ def pi_2_pi(angle): return (angle + math.pi) % (2 * math.pi) - math.pi -def LSL(alpha, beta, d): +def left_straight_left(alpha, beta, d): sa = math.sin(alpha) sb = math.sin(beta) ca = math.cos(alpha) @@ -38,12 +38,11 @@ def LSL(alpha, beta, d): t = mod2pi(-alpha + tmp1) p = math.sqrt(p_squared) q = mod2pi(beta - tmp1) - # print(np.rad2deg(t), p, np.rad2deg(q)) return t, p, q, mode -def RSR(alpha, beta, d): +def right_straight_right(alpha, beta, d): sa = math.sin(alpha) sb = math.sin(beta) ca = math.cos(alpha) @@ -63,7 +62,7 @@ def RSR(alpha, beta, d): return t, p, q, mode -def LSR(alpha, beta, d): +def left_straight_right(alpha, beta, d): sa = math.sin(alpha) sb = math.sin(beta) ca = math.cos(alpha) @@ -82,7 +81,7 @@ def LSR(alpha, beta, d): return t, p, q, mode -def RSL(alpha, beta, d): +def right_straight_left(alpha, beta, d): sa = math.sin(alpha) sb = math.sin(beta) ca = math.cos(alpha) @@ -101,7 +100,7 @@ def RSL(alpha, beta, d): return t, p, q, mode -def RLR(alpha, beta, d): +def right_left_right(alpha, beta, d): sa = math.sin(alpha) sb = math.sin(beta) ca = math.cos(alpha) @@ -119,7 +118,7 @@ def RLR(alpha, beta, d): return t, p, q, mode -def LRL(alpha, beta, d): +def left_right_left(alpha, beta, d): sa = math.sin(alpha) sb = math.sin(beta) ca = math.cos(alpha) @@ -137,23 +136,21 @@ def LRL(alpha, beta, d): return t, p, q, mode -def dubins_path_planning_from_origin(ex, ey, eyaw, c, D_ANGLE): - # normalize - dx = ex - dy = ey +def dubins_path_planning_from_origin(end_x, end_y, end_yaw, curvature, step_size): + dx = end_x + dy = end_y D = math.hypot(dx, dy) - d = D * c - # print(dx, dy, D, d) + d = D * curvature theta = mod2pi(math.atan2(dy, dx)) alpha = mod2pi(- theta) - beta = mod2pi(eyaw - theta) - # print(theta, alpha, beta, d) + beta = mod2pi(end_yaw - theta) - planners = [LSL, RSR, LSR, RSL, RLR, LRL] + planners = [left_straight_left, right_straight_right, left_straight_right, right_straight_left, right_left_right, + left_right_left] - bcost = float("inf") - bt, bp, bq, bmode = None, None, None, None + best_cost = float("inf") + bt, bp, bq, best_mode = None, None, None, None for planner in planners: t, p, q, mode = planner(alpha, beta, d) @@ -161,17 +158,48 @@ def dubins_path_planning_from_origin(ex, ey, eyaw, c, D_ANGLE): continue cost = (abs(t) + abs(p) + abs(q)) - if bcost > cost: - bt, bp, bq, bmode = t, p, q, mode - bcost = cost - - # print(bmode) - px, py, pyaw = generate_course([bt, bp, bq], bmode, c, D_ANGLE) + if best_cost > cost: + bt, bp, bq, best_mode = t, p, q, mode + best_cost = cost + lengths = [bt, bp, bq] + + px, py, pyaw, directions = generate_local_course( + sum(lengths), lengths, best_mode, curvature, step_size) + + return px, py, pyaw, best_mode, best_cost + + +def interpolate(ind, length, mode, max_curvature, origin_x, origin_y, origin_yaw, path_x, path_y, path_yaw, directions): + if mode == "S": + path_x[ind] = origin_x + length / max_curvature * math.cos(origin_yaw) + path_y[ind] = origin_y + length / max_curvature * math.sin(origin_yaw) + path_yaw[ind] = origin_yaw + else: # curve + ldx = math.sin(length) / max_curvature + ldy = 0.0 + if mode == "L": # left turn + ldy = (1.0 - math.cos(length)) / max_curvature + elif mode == "R": # right turn + ldy = (1.0 - math.cos(length)) / -max_curvature + gdx = math.cos(-origin_yaw) * ldx + math.sin(-origin_yaw) * ldy + gdy = -math.sin(-origin_yaw) * ldx + math.cos(-origin_yaw) * ldy + path_x[ind] = origin_x + gdx + path_y[ind] = origin_y + gdy + + if mode == "L": # left turn + path_yaw[ind] = origin_yaw + length + elif mode == "R": # right turn + path_yaw[ind] = origin_yaw - length + + if length > 0.0: + directions[ind] = 1 + else: + directions[ind] = -1 - return px, py, pyaw, bmode, bcost + return path_x, path_y, path_yaw, directions -def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c, D_ANGLE=np.deg2rad(10.0)): +def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c, step_size=0.1): """ Dubins path plannner @@ -200,7 +228,7 @@ def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c, D_ANGLE=np.deg2rad(10.0) leyaw = eyaw - syaw lpx, lpy, lpyaw, mode, clen = dubins_path_planning_from_origin( - lex, ley, leyaw, c, D_ANGLE) + lex, ley, leyaw, c, step_size) px = [math.cos(-syaw) * x + math.sin(-syaw) * y + sx for x, y in zip(lpx, lpy)] @@ -211,44 +239,60 @@ def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c, D_ANGLE=np.deg2rad(10.0) return px, py, pyaw, mode, clen -def generate_course(length, mode, c, D_ANGLE): - px = [0.0] - py = [0.0] - pyaw = [0.0] - - for m, l in zip(mode, length): - pd = 0.0 - if m == "S": - d = 1.0 * c - else: # turning couse - d = D_ANGLE - - while pd < abs(l - d): - # print(pd, l) - px.append(px[-1] + d / c * math.cos(pyaw[-1])) - py.append(py[-1] + d / c * math.sin(pyaw[-1])) - - if m == "L": # left turn - pyaw.append(pyaw[-1] + d) - elif m == "S": # Straight - pyaw.append(pyaw[-1]) - elif m == "R": # right turn - pyaw.append(pyaw[-1] - d) +def generate_local_course(total_length, lengths, mode, max_curvature, step_size): + n_point = math.trunc(total_length / step_size) + len(lengths) + 4 + + path_x = [0.0 for _ in range(n_point)] + path_y = [0.0 for _ in range(n_point)] + path_yaw = [0.0 for _ in range(n_point)] + directions = [0.0 for _ in range(n_point)] + ind = 1 + + if lengths[0] > 0.0: + directions[0] = 1 + else: + directions[0] = -1 + + ll = 0.0 + + for (m, l, i) in zip(mode, lengths, range(len(mode))): + if l > 0.0: + d = step_size + else: + d = -step_size + + # set origin state + origin_x, origin_y, origin_yaw = path_x[ind], path_y[ind], path_yaw[ind] + + ind -= 1 + if i >= 1 and (lengths[i - 1] * lengths[i]) > 0: + pd = - d - ll + else: + pd = d - ll + + while abs(pd) <= abs(l): + ind += 1 + path_x, path_y, path_yaw, directions = interpolate( + ind, pd, m, max_curvature, origin_x, origin_y, origin_yaw, path_x, path_y, path_yaw, directions) pd += d - d = l - pd - px.append(px[-1] + d / c * math.cos(pyaw[-1])) - py.append(py[-1] + d / c * math.sin(pyaw[-1])) + ll = l - pd - d # calc remain length + + ind += 1 + path_x, path_y, path_yaw, directions = interpolate( + ind, l, m, max_curvature, origin_x, origin_y, origin_yaw, path_x, path_y, path_yaw, directions) + + if len(path_x) <= 1: + return [], [], [], [] - if m == "L": # left turn - pyaw.append(pyaw[-1] + d) - elif m == "S": # Straight - pyaw.append(pyaw[-1]) - elif m == "R": # right turn - pyaw.append(pyaw[-1] - d) - pd += d + # remove unused data + while len(path_x) >= 1 and path_x[-1] == 0.0: + path_x.pop() + path_y.pop() + path_yaw.pop() + directions.pop() - return px, py, pyaw + return path_x, path_y, path_yaw, directions def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): # pragma: no cover @@ -288,53 +332,11 @@ def main(): plot_arrow(start_x, start_y, start_yaw) plot_arrow(end_x, end_y, end_yaw) - # for (ix, iy, iyaw) in zip(px, py, pyaw): - # plot_arrow(ix, iy, iyaw, fc="b") - plt.legend() plt.grid(True) plt.axis("equal") plt.show() -def test(): - NTEST = 5 - - for i in range(NTEST): - start_x = (np.random.rand() - 0.5) * 10.0 # [m] - start_y = (np.random.rand() - 0.5) * 10.0 # [m] - start_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad] - - end_x = (np.random.rand() - 0.5) * 10.0 # [m] - end_y = (np.random.rand() - 0.5) * 10.0 # [m] - end_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad] - - curvature = 1.0 / (np.random.rand() * 5.0) - - px, py, pyaw, mode, clen = dubins_path_planning( - start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature) - - if show_animation: - plt.cla() - # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) - plt.plot(px, py, label="final course " + str(mode)) - - # plotting - plot_arrow(start_x, start_y, start_yaw) - plot_arrow(end_x, end_y, end_yaw) - - plt.legend() - plt.grid(True) - plt.axis("equal") - plt.xlim(-10, 10) - plt.ylim(-10, 10) - plt.pause(1.0) - - print("Test done") - - if __name__ == '__main__': - test() main() diff --git a/PathPlanning/RRTDubins/rrt_dubins.py b/PathPlanning/RRTDubins/rrt_dubins.py index 4599904cc1..55cea0bde3 100644 --- a/PathPlanning/RRTDubins/rrt_dubins.py +++ b/PathPlanning/RRTDubins/rrt_dubins.py @@ -137,6 +137,9 @@ def steer(self, from_node, to_node): from_node.x, from_node.y, from_node.yaw, to_node.x, to_node.y, to_node.yaw, self.curvature) + if len(px) <= 1: # cannot find a dubins path + return None + new_node = copy.deepcopy(from_node) new_node.x = px[-1] new_node.y = py[-1] diff --git a/PathPlanning/RRTStarDubins/rrt_star_dubins.py b/PathPlanning/RRTStarDubins/rrt_star_dubins.py index 65fac54c78..9cfd4e692a 100644 --- a/PathPlanning/RRTStarDubins/rrt_star_dubins.py +++ b/PathPlanning/RRTStarDubins/rrt_star_dubins.py @@ -114,7 +114,7 @@ def draw_graph(self, rnd=None): plt.clf() # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: @@ -143,6 +143,9 @@ def steer(self, from_node, to_node): from_node.x, from_node.y, from_node.yaw, to_node.x, to_node.y, to_node.yaw, self.curvature) + if len(px) <= 1: # cannot find a dubins path + return None + new_node = copy.deepcopy(from_node) new_node.x = px[-1] new_node.y = py[-1] diff --git a/tests/test_dubins_path_planning.py b/tests/test_dubins_path_planning.py index ad140b6c3a..72305530b9 100644 --- a/tests/test_dubins_path_planning.py +++ b/tests/test_dubins_path_planning.py @@ -7,6 +7,18 @@ class Test(TestCase): + @staticmethod + def check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x, end_y, end_yaw): + assert (abs(px[0] - start_x) <= 0.01) + assert (abs(py[0] - start_y) <= 0.01) + assert (abs(pyaw[0] - start_yaw) <= 0.01) + print("x", px[-1], end_x) + assert (abs(px[-1] - end_x) <= 0.01) + print("y", py[-1], end_y) + assert (abs(py[-1] - end_y) <= 0.01) + print("yaw", pyaw[-1], end_yaw) + assert (abs(pyaw[-1] - end_yaw) <= 0.01) + def test1(self): start_x = 1.0 # [m] start_y = 1.0 # [m] @@ -21,14 +33,28 @@ def test1(self): px, py, pyaw, mode, clen = dubins_path_planning.dubins_path_planning( start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature) - assert (abs(px[-1] - end_x) <= 0.5) - assert (abs(py[-1] - end_y) <= 0.5) - assert(abs(pyaw[-1] - end_yaw) <= 0.1) + self.check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x, end_y, end_yaw) def test2(self): dubins_path_planning.show_animation = False dubins_path_planning.main() def test3(self): - dubins_path_planning.show_animation = False - dubins_path_planning.test() + N_TEST = 10 + + for i in range(N_TEST): + start_x = (np.random.rand() - 0.5) * 10.0 # [m] + start_y = (np.random.rand() - 0.5) * 10.0 # [m] + start_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad] + + end_x = (np.random.rand() - 0.5) * 10.0 # [m] + end_y = (np.random.rand() - 0.5) * 10.0 # [m] + end_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad] + + curvature = 1.0 / (np.random.rand() * 5.0) + + px, py, pyaw, mode, clen = dubins_path_planning.dubins_path_planning( + start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature) + + self.check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x, end_y, end_yaw) + From 067304acdbac043cf302a2eb006ee6c767341826 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 28 Jan 2020 21:38:19 +0900 Subject: [PATCH 189/940] reformat codes --- tests/test_dubins_path_planning.py | 1 - 1 file changed, 1 deletion(-) diff --git a/tests/test_dubins_path_planning.py b/tests/test_dubins_path_planning.py index 72305530b9..f9349217a1 100644 --- a/tests/test_dubins_path_planning.py +++ b/tests/test_dubins_path_planning.py @@ -57,4 +57,3 @@ def test3(self): start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature) self.check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x, end_y, end_yaw) - From aa7d48fa5b84259c43ff58e36ec6a5b5a9197f38 Mon Sep 17 00:00:00 2001 From: Peteski <38994044+YAOS5@users.noreply.github.com> Date: Wed, 29 Jan 2020 14:28:27 +1100 Subject: [PATCH 190/940] IMPROVEMENT: Fixed typo --- SLAM/FastSLAM1/FastSLAM1.ipynb | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/SLAM/FastSLAM1/FastSLAM1.ipynb b/SLAM/FastSLAM1/FastSLAM1.ipynb index 9ce48238f9..60faed6e88 100644 --- a/SLAM/FastSLAM1/FastSLAM1.ipynb +++ b/SLAM/FastSLAM1/FastSLAM1.ipynb @@ -93,7 +93,7 @@ "metadata": {}, "source": [ "### 1- Predict\n", - "The following equations and code snippets we can see how the particles distribution evolves in case we provide only the control $(v,w)$, which are the linear and angular velocity repsectively. \n", + "The following equations and code snippets we can see how the particles distribution evolves in case we provide only the control $(v,w)$, which are the linear and angular velocity respectively. \n", "\n", "$\\begin{equation*}\n", "F=\n", @@ -668,7 +668,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.6.1" + "version": "3.7.5" } }, "nbformat": 4, From 29c02fae58bb16dc7ef963aa99a668079d2d8b03 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 29 Jan 2020 21:49:30 +0900 Subject: [PATCH 191/940] code clean up --- .../reeds_shepp_path_planning.py | 183 +++++++----------- tests/test_reeds_shepp_path_planning.py | 33 ++++ 2 files changed, 99 insertions(+), 117 deletions(-) diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py index fbf9495790..9c72a0c9b2 100644 --- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py +++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py @@ -49,15 +49,15 @@ def mod2pi(x): return v -def SLS(x, y, phi): +def straight_left_straight(x, y, phi): phi = mod2pi(phi) - if y > 0.0 and phi > 0.0 and phi < math.pi * 0.99: + if y > 0.0 and 0.0 < phi < math.pi * 0.99: xd = - y / math.tan(phi) + x t = xd - math.tan(phi / 2.0) u = phi v = math.sqrt((x - xd) ** 2 + y ** 2) - math.tan(phi / 2.0) return True, t, u, v - elif y < 0.0 and phi > 0.0 and phi < math.pi * 0.99: + elif y < 0.0 < phi < math.pi * 0.99: xd = - y / math.tan(phi) + x t = xd - math.tan(phi / 2.0) u = phi @@ -68,7 +68,6 @@ def SLS(x, y, phi): def set_path(paths, lengths, ctypes): - path = Path() path.ctypes = ctypes path.lengths = lengths @@ -89,12 +88,12 @@ def set_path(paths, lengths, ctypes): return paths -def SCS(x, y, phi, paths): - flag, t, u, v = SLS(x, y, phi) +def straight_curve_straight(x, y, phi, paths): + flag, t, u, v = straight_left_straight(x, y, phi) if flag: paths = set_path(paths, [t, u, v], ["S", "L", "S"]) - flag, t, u, v = SLS(x, -y, -phi) + flag, t, u, v = straight_left_straight(x, -y, -phi) if flag: paths = set_path(paths, [t, u, v], ["S", "R", "S"]) @@ -107,7 +106,7 @@ def polar(x, y): return r, theta -def LSL(x, y, phi): +def left_straight_left(x, y, phi): u, t = polar(x - math.sin(phi), y - 1.0 + math.cos(phi)) if t >= 0.0: v = mod2pi(phi - t) @@ -117,7 +116,7 @@ def LSL(x, y, phi): return False, 0.0, 0.0, 0.0 -def LRL(x, y, phi): +def left_right_left(x, y, phi): u1, t1 = polar(x - math.sin(phi), y - 1.0 + math.cos(phi)) if u1 <= 4.0: @@ -125,91 +124,89 @@ def LRL(x, y, phi): t = mod2pi(t1 + 0.5 * u + math.pi) v = mod2pi(phi - t + u) - if t >= 0.0 and u <= 0.0: + if t >= 0.0 >= u: return True, t, u, v return False, 0.0, 0.0, 0.0 -def CCC(x, y, phi, paths): - - flag, t, u, v = LRL(x, y, phi) +def curve_curve_curve(x, y, phi, paths): + flag, t, u, v = left_right_left(x, y, phi) if flag: paths = set_path(paths, [t, u, v], ["L", "R", "L"]) - flag, t, u, v = LRL(-x, y, -phi) + flag, t, u, v = left_right_left(-x, y, -phi) if flag: paths = set_path(paths, [-t, -u, -v], ["L", "R", "L"]) - flag, t, u, v = LRL(x, -y, -phi) + flag, t, u, v = left_right_left(x, -y, -phi) if flag: paths = set_path(paths, [t, u, v], ["R", "L", "R"]) - flag, t, u, v = LRL(-x, -y, phi) + flag, t, u, v = left_right_left(-x, -y, phi) if flag: paths = set_path(paths, [-t, -u, -v], ["R", "L", "R"]) # backwards xb = x * math.cos(phi) + y * math.sin(phi) yb = x * math.sin(phi) - y * math.cos(phi) - # println(xb, ",", yb,",",x,",",y) - flag, t, u, v = LRL(xb, yb, phi) + flag, t, u, v = left_right_left(xb, yb, phi) if flag: paths = set_path(paths, [v, u, t], ["L", "R", "L"]) - flag, t, u, v = LRL(-xb, yb, -phi) + flag, t, u, v = left_right_left(-xb, yb, -phi) if flag: paths = set_path(paths, [-v, -u, -t], ["L", "R", "L"]) - flag, t, u, v = LRL(xb, -yb, -phi) + flag, t, u, v = left_right_left(xb, -yb, -phi) if flag: paths = set_path(paths, [v, u, t], ["R", "L", "R"]) - flag, t, u, v = LRL(-xb, -yb, phi) + flag, t, u, v = left_right_left(-xb, -yb, phi) if flag: paths = set_path(paths, [-v, -u, -t], ["R", "L", "R"]) return paths -def CSC(x, y, phi, paths): - flag, t, u, v = LSL(x, y, phi) +def curve_straight_curve(x, y, phi, paths): + flag, t, u, v = left_straight_left(x, y, phi) if flag: paths = set_path(paths, [t, u, v], ["L", "S", "L"]) - flag, t, u, v = LSL(-x, y, -phi) + flag, t, u, v = left_straight_left(-x, y, -phi) if flag: paths = set_path(paths, [-t, -u, -v], ["L", "S", "L"]) - flag, t, u, v = LSL(x, -y, -phi) + flag, t, u, v = left_straight_left(x, -y, -phi) if flag: paths = set_path(paths, [t, u, v], ["R", "S", "R"]) - flag, t, u, v = LSL(-x, -y, phi) + flag, t, u, v = left_straight_left(-x, -y, phi) if flag: paths = set_path(paths, [-t, -u, -v], ["R", "S", "R"]) - flag, t, u, v = LSR(x, y, phi) + flag, t, u, v = left_straight_right(x, y, phi) if flag: paths = set_path(paths, [t, u, v], ["L", "S", "R"]) - flag, t, u, v = LSR(-x, y, -phi) + flag, t, u, v = left_straight_right(-x, y, -phi) if flag: paths = set_path(paths, [-t, -u, -v], ["L", "S", "R"]) - flag, t, u, v = LSR(x, -y, -phi) + flag, t, u, v = left_straight_right(x, -y, -phi) if flag: paths = set_path(paths, [t, u, v], ["R", "S", "L"]) - flag, t, u, v = LSR(-x, -y, phi) + flag, t, u, v = left_straight_right(-x, -y, phi) if flag: paths = set_path(paths, [-t, -u, -v], ["R", "S", "L"]) return paths -def LSR(x, y, phi): +def left_straight_right(x, y, phi): u1, t1 = polar(x + math.sin(phi), y - 1.0 - math.cos(phi)) u1 = u1 ** 2 if u1 >= 4.0: @@ -224,60 +221,60 @@ def LSR(x, y, phi): return False, 0.0, 0.0, 0.0 -def generate_path(q0, q1, maxc): +def generate_path(q0, q1, max_curvature): dx = q1[0] - q0[0] dy = q1[1] - q0[1] dth = q1[2] - q0[2] c = math.cos(q0[2]) s = math.sin(q0[2]) - x = (c * dx + s * dy) * maxc - y = (-s * dx + c * dy) * maxc + x = (c * dx + s * dy) * max_curvature + y = (-s * dx + c * dy) * max_curvature paths = [] - paths = SCS(x, y, dth, paths) - paths = CSC(x, y, dth, paths) - paths = CCC(x, y, dth, paths) + paths = straight_curve_straight(x, y, dth, paths) + paths = curve_straight_curve(x, y, dth, paths) + paths = curve_curve_curve(x, y, dth, paths) return paths -def interpolate(ind, l, m, maxc, ox, oy, oyaw, px, py, pyaw, directions): - - if m == "S": - px[ind] = ox + l / maxc * math.cos(oyaw) - py[ind] = oy + l / maxc * math.sin(oyaw) - pyaw[ind] = oyaw +def interpolate(ind, length, mode, max_curvature, origin_x, origin_y, origin_yaw, path_x, path_y, path_yaw, directions): + if mode == "S": + path_x[ind] = origin_x + length / max_curvature * math.cos(origin_yaw) + path_y[ind] = origin_y + length / max_curvature * math.sin(origin_yaw) + path_yaw[ind] = origin_yaw else: # curve - ldx = math.sin(l) / maxc - if m == "L": # left turn - ldy = (1.0 - math.cos(l)) / maxc - elif m == "R": # right turn - ldy = (1.0 - math.cos(l)) / -maxc - gdx = math.cos(-oyaw) * ldx + math.sin(-oyaw) * ldy - gdy = -math.sin(-oyaw) * ldx + math.cos(-oyaw) * ldy - px[ind] = ox + gdx - py[ind] = oy + gdy - - if m == "L": # left turn - pyaw[ind] = oyaw + l - elif m == "R": # right turn - pyaw[ind] = oyaw - l - - if l > 0.0: + ldx = math.sin(length) / max_curvature + ldy = 0.0 + if mode == "L": # left turn + ldy = (1.0 - math.cos(length)) / max_curvature + elif mode == "R": # right turn + ldy = (1.0 - math.cos(length)) / -max_curvature + gdx = math.cos(-origin_yaw) * ldx + math.sin(-origin_yaw) * ldy + gdy = -math.sin(-origin_yaw) * ldx + math.cos(-origin_yaw) * ldy + path_x[ind] = origin_x + gdx + path_y[ind] = origin_y + gdy + + if mode == "L": # left turn + path_yaw[ind] = origin_yaw + length + elif mode == "R": # right turn + path_yaw[ind] = origin_yaw - length + + if length > 0.0: directions[ind] = 1 else: directions[ind] = -1 - return px, py, pyaw, directions + return path_x, path_y, path_yaw, directions -def generate_local_course(L, lengths, mode, maxc, step_size): - npoint = math.trunc(L / step_size) + len(lengths) + 4 +def generate_local_course(total_length, lengths, mode, max_curvature, step_size): + n_point = math.trunc(total_length / step_size) + len(lengths) + 4 - px = [0.0 for i in range(npoint)] - py = [0.0 for i in range(npoint)] - pyaw = [0.0 for i in range(npoint)] - directions = [0.0 for i in range(npoint)] + px = [0.0 for _ in range(n_point)] + py = [0.0 for _ in range(n_point)] + pyaw = [0.0 for _ in range(n_point)] + directions = [0.0 for _ in range(n_point)] ind = 1 if lengths[0] > 0.0: @@ -305,14 +302,14 @@ def generate_local_course(L, lengths, mode, maxc, step_size): while abs(pd) <= abs(l): ind += 1 px, py, pyaw, directions = interpolate( - ind, pd, m, maxc, ox, oy, oyaw, px, py, pyaw, directions) + ind, pd, m, max_curvature, ox, oy, oyaw, px, py, pyaw, directions) pd += d ll = l - pd - d # calc remain length ind += 1 px, py, pyaw, directions = interpolate( - ind, l, m, maxc, ox, oy, oyaw, px, py, pyaw, directions) + ind, l, m, max_curvature, ox, oy, oyaw, px, py, pyaw, directions) # remove unused data while px[-1] == 0.0: @@ -344,22 +341,17 @@ def calc_paths(sx, sy, syaw, gx, gy, gyaw, maxc, step_size): * iy + q0[1] for (ix, iy) in zip(x, y)] path.yaw = [pi_2_pi(iyaw + q0[2]) for iyaw in yaw] path.directions = directions - path.lengths = [l / maxc for l in path.lengths] + path.lengths = [length / maxc for length in path.lengths] path.L = path.L / maxc - # print(paths) - return paths def reeds_shepp_path_planning(sx, sy, syaw, gx, gy, gyaw, maxc, step_size=0.2): - paths = calc_paths(sx, sy, syaw, gx, gy, gyaw, maxc, step_size) if not paths: - # print("No path") - # print(sx, sy, syaw, gx, gy, gyaw) return None, None, None, None, None minL = float("Inf") @@ -374,48 +366,6 @@ def reeds_shepp_path_planning(sx, sy, syaw, return bpath.x, bpath.y, bpath.yaw, bpath.ctypes, bpath.lengths -def test(): - - NTEST = 5 - - for i in range(NTEST): - start_x = (np.random.rand() - 0.5) * 10.0 # [m] - start_y = (np.random.rand() - 0.5) * 10.0 # [m] - start_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad] - - end_x = (np.random.rand() - 0.5) * 10.0 # [m] - end_y = (np.random.rand() - 0.5) * 10.0 # [m] - end_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad] - - curvature = 1.0 / (np.random.rand() * 20.0) - step_size = 0.1 - - px, py, pyaw, mode, clen = reeds_shepp_path_planning( - start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature, step_size) - - if show_animation: # pragma: no cover - plt.cla() - # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) - plt.plot(px, py, label="final course " + str(mode)) - - # plotting - plot_arrow(start_x, start_y, start_yaw) - plot_arrow(end_x, end_y, end_yaw) - - plt.legend() - plt.grid(True) - plt.axis("equal") - plt.xlim(-10, 10) - plt.ylim(-10, 10) - plt.pause(1.0) - - # plt.show() - - print("Test done") - - def main(): print("Reeds Shepp path planner sample start!!") @@ -451,5 +401,4 @@ def main(): if __name__ == '__main__': - test() main() diff --git a/tests/test_reeds_shepp_path_planning.py b/tests/test_reeds_shepp_path_planning.py index bc4a038cbb..2c3b38dc31 100644 --- a/tests/test_reeds_shepp_path_planning.py +++ b/tests/test_reeds_shepp_path_planning.py @@ -1,9 +1,42 @@ from unittest import TestCase from PathPlanning.ReedsSheppPath import reeds_shepp_path_planning as m +import numpy as np + class Test(TestCase): + @staticmethod + def check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x, end_y, end_yaw): + assert (abs(px[0] - start_x) <= 0.01) + assert (abs(py[0] - start_y) <= 0.01) + assert (abs(pyaw[0] - start_yaw) <= 0.01) + print("x", px[-1], end_x) + assert (abs(px[-1] - end_x) <= 0.01) + print("y", py[-1], end_y) + assert (abs(py[-1] - end_y) <= 0.01) + print("yaw", pyaw[-1], end_yaw) + assert (abs(pyaw[-1] - end_yaw) <= 0.01) + def test1(self): m.show_animation = False m.main() + + def test2(self): + N_TEST = 10 + + for i in range(N_TEST): + start_x = (np.random.rand() - 0.5) * 10.0 # [m] + start_y = (np.random.rand() - 0.5) * 10.0 # [m] + start_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad] + + end_x = (np.random.rand() - 0.5) * 10.0 # [m] + end_y = (np.random.rand() - 0.5) * 10.0 # [m] + end_yaw = np.deg2rad((np.random.rand() - 0.5) * 180.0) # [rad] + + curvature = 1.0 / (np.random.rand() * 5.0) + + px, py, pyaw, mode, clen = m.reeds_shepp_path_planning( + start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature) + + self.check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x, end_y, end_yaw) From c6c0a61d495f234c1cff77f1f79a0676f6aa9f8a Mon Sep 17 00:00:00 2001 From: "Kenta Yonekura(a.k.a. yoneken)" Date: Sat, 1 Feb 2020 22:59:52 +0900 Subject: [PATCH 192/940] [Kalman Basics] Align some subscripts on the text --- Localization/Kalmanfilter_basics.ipynb | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Localization/Kalmanfilter_basics.ipynb b/Localization/Kalmanfilter_basics.ipynb index 374287911b..bbc10ce5f1 100644 --- a/Localization/Kalmanfilter_basics.ipynb +++ b/Localization/Kalmanfilter_basics.ipynb @@ -354,14 +354,14 @@ "\n", "Here for the numerator, $P(Z \\mid X),P(X)$ both are gaussian.\n", "\n", - "$N(\\bar\\mu, \\bar\\sigma^1)$ and $N(\\bar\\mu, \\bar\\sigma^2)$ are their mean and variances.\n", + "$N(\\mu_1, \\sigma_1^2)$ and $N(\\mu_2, \\sigma_2^2)$ are their mean and variances.\n", "\n", "New mean is \n", "\n", - "$$\\mu_\\mathtt{new} = \\frac{\\sigma_z^2\\bar\\mu + \\bar\\sigma^2z}{\\bar\\sigma^2+\\sigma_z^2}$$\n", + "$$\\mu_\\mathtt{new} = \\frac{\\mu_1 \\sigma_2^2 + \\mu_2 \\sigma_1^2}{\\sigma_1^2+\\sigma_2^2}$$\n", "New variance is\n", "$$\n", - "\\sigma_\\mathtt{new} = \\frac{\\sigma_z^2\\bar\\sigma^2}{\\bar\\sigma^2+\\sigma_z^2}\n", + "\\sigma_\\mathtt{new} = \\frac{\\sigma_1^2\\sigma_2^2}{\\sigma_1^2+\\sigma_2^2}\n", "$$" ] }, @@ -759,4 +759,4 @@ }, "nbformat": 4, "nbformat_minor": 2 -} +} \ No newline at end of file From 74b723dc47798e9b5681828066e9e8ab87267bb7 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 2 Feb 2020 14:12:39 +0900 Subject: [PATCH 193/940] #fix 281 and doc clean up --- Localization/Kalmanfilter_basics.ipynb | 13 ++++++++++--- Localization/Kalmanfilter_basics_2.ipynb | 13 +++++++++++-- 2 files changed, 21 insertions(+), 5 deletions(-) diff --git a/Localization/Kalmanfilter_basics.ipynb b/Localization/Kalmanfilter_basics.ipynb index 86966c8d54..c501b117de 100644 --- a/Localization/Kalmanfilter_basics.ipynb +++ b/Localization/Kalmanfilter_basics.ipynb @@ -360,9 +360,7 @@ "\n", "$$\\mu_\\mathtt{new} = \\frac{\\mu_1 \\sigma_2^2 + \\mu_2 \\sigma_1^2}{\\sigma_1^2+\\sigma_2^2}$$\n", "New variance is\n", - "$$\n", - "\\sigma_\\mathtt{new} = \\frac{\\sigma_1^2\\sigma_2^2}{\\sigma_1^2+\\sigma_2^2}\n", - "$$" + "$$\\sigma_\\mathtt{new} = \\frac{\\sigma_1^2\\sigma_2^2}{\\sigma_1^2+\\sigma_2^2}$$" ] }, { @@ -755,6 +753,15 @@ "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.6.6" + }, + "pycharm": { + "stem_cell": { + "cell_type": "raw", + "source": [], + "metadata": { + "collapsed": false + } + } } }, "nbformat": 4, diff --git a/Localization/Kalmanfilter_basics_2.ipynb b/Localization/Kalmanfilter_basics_2.ipynb index ac3101d518..43f34ec6f2 100644 --- a/Localization/Kalmanfilter_basics_2.ipynb +++ b/Localization/Kalmanfilter_basics_2.ipynb @@ -35,7 +35,7 @@ "\n", "If $x_{t}$ is complete, then:\n", "\n", - "$$p(z_{t} | x-_{0:t},z_{1:t-1},u_{1:t})=p(z_{t} | x_{t})$$\n", + "$$p(z_{t} | x_{0:t},z_{1:t-1},u_{1:t})=p(z_{t} | x_{t})$$\n", "\n", "$x_{t}$ is **complete** means that the past states, controls or measurements carry no additional information to predict future.\n", "\n", @@ -365,8 +365,17 @@ "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.6.6" + }, + "pycharm": { + "stem_cell": { + "cell_type": "raw", + "source": [], + "metadata": { + "collapsed": false + } + } } }, "nbformat": 4, "nbformat_minor": 2 -} +} \ No newline at end of file From c632666603c870fa26d895238e3bcbd4f8200e84 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 3 Feb 2020 20:41:35 +0900 Subject: [PATCH 194/940] #fix 281 and doc clean up --- README.md | 20 +++++--------------- 1 file changed, 5 insertions(+), 15 deletions(-) diff --git a/README.md b/README.md index ec42812753..ab62c9af3c 100644 --- a/README.md +++ b/README.md @@ -119,8 +119,6 @@ All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation > git clone https://github.com/AtsushiSakai/PythonRobotics.git -> cd PythonRobotics/ - 2. Install the required libraries. You can use environment.yml with conda command. @@ -553,7 +551,7 @@ MIT # Use-case -If this project helps your robotics project, please let me know with [![Say Thanks!](https://img.shields.io/badge/Say%20Thanks-!-1EAEDB.svg)](https://saythanks.io/to/AtsushiSakai). +If this project helps your robotics project, please let me know with creating an issue. Your robot's video, which is using PythonRobotics, is very welcome!! @@ -561,7 +559,7 @@ This is a list of other user's comment and references:[users\_comments](https:// # Contribution -A small PR like bug fix is welcome. +Any contribution is welcome!! If your PR is merged multiple times, I will add your account to the author list. @@ -575,23 +573,15 @@ If you use this project's code in industry, we'd love to hear from you as well; If you or your company would like to support this project, please consider: +- [Sponsor @AtsushiSakai on GitHub Sponsors](https://github.com/sponsors/AtsushiSakai) + - [Become a backer or sponsor on Patreon](https://www.patreon.com/myenigma) - [One-time donation via PayPal](https://www.paypal.me/myenigmapay/) -You can add your name or your company logo in README if you are a patron. - -E-mail consultant is also available. - -   - -Your comment using [![Say Thanks!](https://img.shields.io/badge/Say%20Thanks-!-1EAEDB.svg)](https://saythanks.io/to/AtsushiSakai) is also welcome. - -This is a list: [Users comments](https://github.com/AtsushiSakai/PythonRobotics/blob/master/users_comments.md) - # Authors -- [Atsushi Sakai](https://github.com/AtsushiSakai/) ([@Atsushi_twi](https://twitter.com/Atsushi_twi)) +- [Atsushi Sakai](https://github.com/AtsushiSakai/) - [Daniel Ingram](https://github.com/daniel-s-ingram) From a061e162d6ceaf83db57e3c48e7792e94f36ad3c Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 4 Feb 2020 20:41:51 +0900 Subject: [PATCH 195/940] start fixing. --- SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb b/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb index 632bf57992..554ccd1a64 100644 --- a/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb +++ b/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb @@ -6,12 +6,10 @@ "metadata": {}, "outputs": [], "source": [ - "import numpy as np\n", "import copy\n", "import math\n", "import itertools\n", "import numpy as np \n", - "import cvxpy as cp\n", "import matplotlib.pyplot as plt\n", "from graph_based_slam import calc_rotational_matrix, calc_jacobian, cal_observation_sigma, \\\n", " calc_input, observation, motion_model, Edge, pi_2_pi\n", @@ -650,8 +648,17 @@ "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.6.5" + }, + "pycharm": { + "stem_cell": { + "cell_type": "raw", + "source": [], + "metadata": { + "collapsed": false + } + } } }, "nbformat": 4, "nbformat_minor": 2 -} +} \ No newline at end of file From 994e0e354637d7bf540b1da8abaec312325b9f74 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 4 Feb 2020 21:13:12 +0900 Subject: [PATCH 196/940] fixing. --- SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb | 156 +++++++++++++----------- 1 file changed, 87 insertions(+), 69 deletions(-) diff --git a/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb b/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb index 554ccd1a64..53364e3276 100644 --- a/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb +++ b/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb @@ -2,8 +2,12 @@ "cells": [ { "cell_type": "code", - "execution_count": 1, - "metadata": {}, + "execution_count": 11, + "metadata": { + "pycharm": { + "is_executing": false + } + }, "outputs": [], "source": [ "import copy\n", @@ -38,15 +42,17 @@ }, { "cell_type": "code", - "execution_count": 2, - "metadata": {}, + "execution_count": 12, + "metadata": { + "pycharm": { + "is_executing": false + } + }, "outputs": [ { "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] + "text/plain": "
", + "image/png": "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\n" }, "metadata": { "needs_background": "light" @@ -55,23 +61,21 @@ }, { "name": "stdout", - "output_type": "stream", "text": [ "The determinant of H: 0.0\n", - "The determinant of H after anchoring constraint: 18.75\n", + "The determinant of H after anchoring constraint: 18.750000000000007\n", "Running graphSLAM ...\n", "Odometry values after optimzation: \n", - " [[0. ]\n", - " [0.947]\n", - " [1.939]]\n" - ] + " [[-0. ]\n", + " [ 0.9]\n", + " [ 1.9]]\n" + ], + "output_type": "stream" }, { "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] + "text/plain": "
", + "image/png": "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\n" }, "metadata": { "needs_background": "light" @@ -138,8 +142,8 @@ " H[t2,t1] -= omegas[(t1,t2)]\n", " H[t1,t2] -= omegas[(t1,t2)]\n", "\n", - " b[t1] += measure_constraints[(t1,t2)]\n", - " b[t2] -= measure_constraints[(t1,t2)]\n", + " b[t1] += omegas[(t1,t2)] * measure_constraints[(t1,t2)]\n", + " b[t2] -= omegas[(t1,t2)] * measure_constraints[(t1,t2)]\n", "\n", " return H, b\n", "\n", @@ -206,15 +210,17 @@ }, { "cell_type": "code", - "execution_count": 3, - "metadata": {}, + "execution_count": 13, + "metadata": { + "pycharm": { + "is_executing": false + } + }, "outputs": [ { "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] + "text/plain": "
", + "image/png": "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\n" }, "metadata": { "needs_background": "light" @@ -291,8 +297,12 @@ }, { "cell_type": "code", - "execution_count": 4, - "metadata": {}, + "execution_count": 14, + "metadata": { + "pycharm": { + "is_executing": false + } + }, "outputs": [], "source": [ "# Copy the data to have a consistent naming with the .py file\n", @@ -312,18 +322,22 @@ }, { "cell_type": "code", - "execution_count": 5, - "metadata": {}, + "execution_count": 15, + "metadata": { + "pycharm": { + "is_executing": false + } + }, "outputs": [ { "name": "stdout", - "output_type": "stream", "text": [ "Node combinations: \n", " [(0, 1)]\n", "Node 0 observed landmark with ID 0.0\n", "Node 1 observed landmark with ID 0.0\n" - ] + ], + "output_type": "stream" } ], "source": [ @@ -354,12 +368,15 @@ }, { "cell_type": "code", - "execution_count": 6, - "metadata": {}, + "execution_count": 16, + "metadata": { + "pycharm": { + "is_executing": false + } + }, "outputs": [ { "name": "stdout", - "output_type": "stream", "text": [ "0.0 1.427649841628278 -2.0126109674819155 -3.524048014922737\n", "For nodes (0, 1)\n", @@ -367,14 +384,13 @@ " [[-0.02 ]\n", " [-0.084]\n", " [ 0. ]]\n" - ] + ], + "output_type": "stream" }, { "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] + "text/plain": "
", + "image/png": "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\n" }, "metadata": { "needs_background": "light" @@ -460,41 +476,35 @@ }, { "cell_type": "code", - "execution_count": 7, - "metadata": {}, + "execution_count": 17, + "metadata": { + "pycharm": { + "is_executing": false + } + }, "outputs": [ { "name": "stdout", - "output_type": "stream", "text": [ - "The determinant of H: 0.0\n" - ] + "The determinant of H: 0.0\n", + "The determinant of H after origin constraint: 716.1972439134893\n" + ], + "output_type": "stream" }, { "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] + "text/plain": "
", + "image/png": "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\n" }, "metadata": { "needs_background": "light" }, "output_type": "display_data" }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "The determinant of H after origin constraint: 716.1972439134918\n" - ] - }, { "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] + "text/plain": "
", + "image/png": "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\n" }, "metadata": { "needs_background": "light" @@ -559,15 +569,18 @@ }, { "cell_type": "code", - "execution_count": 8, - "metadata": {}, + "execution_count": 18, + "metadata": { + "pycharm": { + "is_executing": false + } + }, "outputs": [ { "name": "stdout", - "output_type": "stream", "text": [ "dx: \n", - " [[ 0. ]\n", + " [[-0. ]\n", " [-0. ]\n", " [ 0. ]\n", " [ 0.02 ]\n", @@ -582,13 +595,14 @@ " [0. 1.428]\n", " [0.785 0.976]]\n", "SLAM: \n", - " [[ 0. 1.448]\n", + " [[-0. 1.448]\n", " [-0. 1.512]\n", " [ 0.785 0.976]]\n", "\n", - "graphSLAM localization error: 0.0107290727510571\n", + "graphSLAM localization error: 0.010729072751057656\n", "Odom localization error: 0.0004460978857535104\n" - ] + ], + "output_type": "stream" } ], "source": [ @@ -625,8 +639,12 @@ }, { "cell_type": "code", - "execution_count": null, - "metadata": {}, + "execution_count": 18, + "metadata": { + "pycharm": { + "is_executing": false + } + }, "outputs": [], "source": [] } From 53b5b43a75b1593e8fcbd8f72cd11e7da6178d3b Mon Sep 17 00:00:00 2001 From: Marwan Taher Date: Tue, 4 Feb 2020 15:38:57 +0000 Subject: [PATCH 197/940] Fixed typo in planning method docstring --- PathPlanning/AStar/a_star.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py index b0c718c9a2..2229d63306 100644 --- a/PathPlanning/AStar/a_star.py +++ b/PathPlanning/AStar/a_star.py @@ -51,7 +51,7 @@ def planning(self, sx, sy, gx, gy): sx: start x position [m] sy: start y position [m] gx: goal x position [m] - gx: goal x position [m] + gy: goal y position [m] output: rx: x position list of the final path From b3af4fcf507e9944265e6587c6c991a3b67f371d Mon Sep 17 00:00:00 2001 From: Peteski <38994044+YAOS5@users.noreply.github.com> Date: Thu, 6 Feb 2020 17:31:34 +1100 Subject: [PATCH 198/940] IMPROVEMENT: Fixed typo --- SLAM/FastSLAM2/fast_slam2.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py index 868812225a..4780b57982 100644 --- a/SLAM/FastSLAM2/fast_slam2.py +++ b/SLAM/FastSLAM2/fast_slam2.py @@ -25,7 +25,7 @@ MAX_RANGE = 20.0 # maximum observation range M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association. STATE_SIZE = 3 # State size [x,y,yaw] -LM_SIZE = 2 # LM srate size [x,y] +LM_SIZE = 2 # LM state size [x,y] N_PARTICLE = 100 # number of particle NTH = N_PARTICLE / 1.5 # Number of particle for re-sampling From 03e8969e9d152cd3d0744c7478580fe7bb716b94 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 7 Feb 2020 20:32:12 +0900 Subject: [PATCH 199/940] inverted pendulum mpc control is added --- .../inverted_pendulum_mpc_control.py | 171 ++++++++++++++++++ 1 file changed, 171 insertions(+) create mode 100644 InvertedPendulumCart/inverted_pendulum_mpc_control.py diff --git a/InvertedPendulumCart/inverted_pendulum_mpc_control.py b/InvertedPendulumCart/inverted_pendulum_mpc_control.py new file mode 100644 index 0000000000..d807a688c5 --- /dev/null +++ b/InvertedPendulumCart/inverted_pendulum_mpc_control.py @@ -0,0 +1,171 @@ +""" +Inverted Pendulum MPC control +author: Atsushi Sakai +""" + +import matplotlib.pyplot as plt +import numpy as np +import math +import time +import cvxpy + +# Model parameters + +l_bar = 2.0 # length of bar +M = 1.0 # [kg] +m = 0.3 # [kg] +g = 9.8 # [m/s^2] + +Q = np.diag([0.0, 1.0, 1.0, 0.0]) +R = np.diag([0.01]) +nx = 4 # number of state +nu = 1 # number of input +T = 30 # Horizon length +delta_t = 0.1 # time tick + +animation = True + + +def main(): + x0 = np.array([ + [0.0], + [0.0], + [0.3], + [0.0] + ]) + + x = np.copy(x0) + + for i in range(50): + + # calc control input + optimized_x, optimized_delta_x, optimized_theta, optimized_delta_theta, optimized_input = mpc_control(x) + + # get input + u = optimized_input[0] + + # simulate inverted pendulum cart + x = simulation(x, u) + + if animation: + plt.clf() + px = float(x[0]) + theta = float(x[2]) + plot_cart(px, theta) + plt.xlim([-5.0, 2.0]) + plt.pause(0.001) + + +def simulation(x, u): + A, B = get_model_matrix() + + x = np.dot(A, x) + np.dot(B, u) + + return x + + +def mpc_control(x0): + x = cvxpy.Variable((nx, T + 1)) + u = cvxpy.Variable((nu, T)) + + A, B = get_model_matrix() + + cost = 0.0 + constr = [] + for t in range(T): + cost += cvxpy.quad_form(x[:, t + 1], Q) + cost += cvxpy.quad_form(u[:, t], R) + constr += [x[:, t + 1] == A * x[:, t] + B * u[:, t]] + + constr += [x[:, 0] == x0[:, 0]] + prob = cvxpy.Problem(cvxpy.Minimize(cost), constr) + + start = time.time() + prob.solve(verbose=False) + elapsed_time = time.time() - start + print("calc time:{0} [sec]".format(elapsed_time)) + + if prob.status == cvxpy.OPTIMAL: + ox = get_nparray_from_matrix(x.value[0, :]) + dx = get_nparray_from_matrix(x.value[1, :]) + theta = get_nparray_from_matrix(x.value[2, :]) + dtheta = get_nparray_from_matrix(x.value[3, :]) + + ou = get_nparray_from_matrix(u.value[0, :]) + + return ox, dx, theta, dtheta, ou + + +def get_nparray_from_matrix(x): + """ + get build-in list from matrix + """ + return np.array(x).flatten() + + +def get_model_matrix(): + A = np.array([ + [0.0, 1.0, 0.0, 0.0], + [0.0, 0.0, m * g / M, 0.0], + [0.0, 0.0, 0.0, 1.0], + [0.0, 0.0, g * (M + m) / (l_bar * M), 0.0] + ]) + A = np.eye(nx) + delta_t * A + + B = np.array([ + [0.0], + [1.0 / M], + [0.0], + [1.0 / (l_bar * M)] + ]) + B = delta_t * B + + return A, B + + +def flatten(a): + return np.array(a).flatten() + + +def plot_cart(xt, theta): + cart_w = 1.0 + cart_h = 0.5 + radius = 0.1 + + cx = np.array([-cart_w / 2.0, cart_w / 2.0, cart_w / + 2.0, -cart_w / 2.0, -cart_w / 2.0]) + cy = np.array([0.0, 0.0, cart_h, cart_h, 0.0]) + cy += radius * 2.0 + + cx = cx + xt + + bx = np.array([0.0, l_bar * math.sin(-theta)]) + bx += xt + by = np.array([cart_h, l_bar * math.cos(-theta) + cart_h]) + by += radius * 2.0 + + angles = np.arange(0.0, math.pi * 2.0, math.radians(3.0)) + ox = [radius * math.cos(a) for a in angles] + oy = [radius * math.sin(a) for a in angles] + + rwx = np.copy(ox) + cart_w / 4.0 + xt + rwy = np.copy(oy) + radius + lwx = np.copy(ox) - cart_w / 4.0 + xt + lwy = np.copy(oy) + radius + + wx = np.copy(ox) + float(bx[0, -1]) + wy = np.copy(oy) + float(by[0, -1]) + + plt.plot(flatten(cx), flatten(cy), "-b") + plt.plot(flatten(bx), flatten(by), "-k") + plt.plot(flatten(rwx), flatten(rwy), "-k") + plt.plot(flatten(lwx), flatten(lwy), "-k") + plt.plot(flatten(wx), flatten(wy), "-k") + plt.title("x:" + str(round(xt, 2)) + ",theta:" + + str(round(math.degrees(theta), 2))) + + plt.axis("equal") + + +if __name__ == '__main__': + main() From bd5269b3d2f2e3e73739e51334868adac32e1665 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 7 Feb 2020 20:45:15 +0900 Subject: [PATCH 200/940] inverted pendulum mpc control is added --- .../inverted_pendulum_mpc_control.py | 8 ++++---- tests/test_inverted_pendulum_mpc_control.py | 15 +++++++++++++++ 2 files changed, 19 insertions(+), 4 deletions(-) create mode 100644 tests/test_inverted_pendulum_mpc_control.py diff --git a/InvertedPendulumCart/inverted_pendulum_mpc_control.py b/InvertedPendulumCart/inverted_pendulum_mpc_control.py index d807a688c5..caf0c23e77 100644 --- a/InvertedPendulumCart/inverted_pendulum_mpc_control.py +++ b/InvertedPendulumCart/inverted_pendulum_mpc_control.py @@ -145,16 +145,16 @@ def plot_cart(xt, theta): by += radius * 2.0 angles = np.arange(0.0, math.pi * 2.0, math.radians(3.0)) - ox = [radius * math.cos(a) for a in angles] - oy = [radius * math.sin(a) for a in angles] + ox = np.array([radius * math.cos(a) for a in angles]) + oy = np.array([radius * math.sin(a) for a in angles]) rwx = np.copy(ox) + cart_w / 4.0 + xt rwy = np.copy(oy) + radius lwx = np.copy(ox) - cart_w / 4.0 + xt lwy = np.copy(oy) + radius - wx = np.copy(ox) + float(bx[0, -1]) - wy = np.copy(oy) + float(by[0, -1]) + wx = np.copy(ox) + bx[-1] + wy = np.copy(oy) + by[-1] plt.plot(flatten(cx), flatten(cy), "-b") plt.plot(flatten(bx), flatten(by), "-k") diff --git a/tests/test_inverted_pendulum_mpc_control.py b/tests/test_inverted_pendulum_mpc_control.py new file mode 100644 index 0000000000..bf6c8576e4 --- /dev/null +++ b/tests/test_inverted_pendulum_mpc_control.py @@ -0,0 +1,15 @@ +from unittest import TestCase + +import sys +if 'cvxpy' in sys.modules: # pragma: no cover + sys.path.append("./InvertedPendulumCart/inverted_pendulum_mpc_control/") + + import inverted_pendulum_mpc_control as m + + print(__file__) + + class Test(TestCase): + + def test1(self): + m.show_animation = False + m.main() From cacb6db028332e9ef1b48757d6b7e53e6080324b Mon Sep 17 00:00:00 2001 From: Shilong Date: Sun, 9 Feb 2020 16:24:21 -0800 Subject: [PATCH 201/940] fix RRT rewire --- PathPlanning/RRTStar/rrt_star.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index 09a421937a..7b46029791 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -34,7 +34,7 @@ def __init__(self, x, y): self.cost = 0.0 def __init__(self, start, goal, obstacle_list, rand_area, - expand_dis=3.0, + expand_dis=30.0, path_resolution=1.0, goal_sample_rate=20, max_iter=300, @@ -141,6 +141,9 @@ def search_best_goal_node(self): def find_near_nodes(self, new_node): nnode = len(self.node_list) + 1 r = self.connect_circle_dist * math.sqrt((math.log(nnode) / nnode)) + # if expand_dist exists, search vertices in a range no more than expand_dist + if hasattr(self, 'expand_dis'): + r = min(r, self.expand_dis) dist_list = [(node.x - new_node.x) ** 2 + (node.y - new_node.y) ** 2 for node in self.node_list] near_inds = [dist_list.index(i) for i in dist_list if i <= r ** 2] @@ -158,8 +161,7 @@ def rewire(self, new_node, near_inds): improved_cost = near_node.cost > edge_node.cost if no_collision and improved_cost: - near_node = edge_node - near_node.parent = new_node + self.node_list[i] = edge_node self.propagate_cost_to_leaves(new_node) def calc_new_cost(self, from_node, to_node): From 41d744c67f71de511d22179f2b8999ac41e789e6 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 22 Feb 2020 21:36:51 +0900 Subject: [PATCH 202/940] add error handling. But there is still bug. --- Mapping/grid_map_lib/grid_map_lib.py | 4 +- .../grid_based_sweep_coverage_path_planner.py | 82 ++++++++++++------- 2 files changed, 54 insertions(+), 32 deletions(-) diff --git a/Mapping/grid_map_lib/grid_map_lib.py b/Mapping/grid_map_lib/grid_map_lib.py index fd016a288f..4787238f07 100644 --- a/Mapping/grid_map_lib/grid_map_lib.py +++ b/Mapping/grid_map_lib/grid_map_lib.py @@ -51,7 +51,7 @@ def get_value_from_xy_index(self, x_ind, y_ind): grid_ind = self.calc_grid_index_from_xy_index(x_ind, y_ind) - if 0 <= grid_ind <= self.ndata: + if 0 <= grid_ind < self.ndata: return self.data[grid_ind] else: return None @@ -163,7 +163,7 @@ def check_occupied_from_xy_index(self, xind, yind, occupied_val=1.0): val = self.get_value_from_xy_index(xind, yind) - if val >= occupied_val: + if val is None or val >= occupied_val: return True else: return False diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py index 0d2239a9ae..c51e9393cb 100644 --- a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py +++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py @@ -30,22 +30,23 @@ class MovingDirection(IntEnum): RIGHT = 1 LEFT = -1 - def __init__(self, mdirection, sdirection, xinds_goaly, goaly): - self.moving_direction = mdirection - self.sweep_direction = sdirection + def __init__(self, moving_direction, sweep_direction, x_inds_goal_y, goal_y): + self.moving_direction = moving_direction + self.sweep_direction = sweep_direction self.turing_window = [] self.update_turning_window() - self.xinds_goaly = xinds_goaly - self.goaly = goaly + self.xinds_goaly = x_inds_goal_y + self.goaly = goal_y def move_target_grid(self, cxind, cyind, gmap): nxind = self.moving_direction + cxind nyind = cyind # found safe grid - if not gmap.check_occupied_from_xy_index(nxind, nyind, occupied_val=0.5): + if not gmap.check_occupied_from_xy_index(nxind, nyind, + occupied_val=0.5): return nxind, nyind - else: # occupided + else: # occupied ncxind, ncyind = self.find_safe_turning_grid(cxind, cyind, gmap) if (ncxind is None) and (ncyind is None): # moving backward @@ -56,27 +57,31 @@ def move_target_grid(self, cxind, cyind, gmap): return None, None else: # keep moving until end - while not gmap.check_occupied_from_xy_index(ncxind + self.moving_direction, ncyind, occupied_val=0.5): + while not gmap.check_occupied_from_xy_index( + ncxind + self.moving_direction, ncyind, + occupied_val=0.5): ncxind += self.moving_direction self.swap_moving_direction() return ncxind, ncyind def find_safe_turning_grid(self, cxind, cyind, gmap): - for (dxind, dyind) in self.turing_window: + for (d_x_ind, d_y_ind) in self.turing_window: - nxind = dxind + cxind - nyind = dyind + cyind + next_x_ind = d_x_ind + cxind + next_y_ind = d_y_ind + cyind # found safe grid - if not gmap.check_occupied_from_xy_index(nxind, nyind, occupied_val=0.5): - return nxind, nyind + if not gmap.check_occupied_from_xy_index(next_x_ind, next_y_ind, + occupied_val=0.5): + return next_x_ind, next_y_ind return None, None - def is_search_done(self, gmap): + def is_search_done(self, grid_map): for ix in self.xinds_goaly: - if not gmap.check_occupied_from_xy_index(ix, self.goaly, occupied_val=0.5): + if not grid_map.check_occupied_from_xy_index(ix, self.goaly, + occupied_val=0.5): return False # all lower grid is occupied @@ -95,22 +100,24 @@ def swap_moving_direction(self): self.update_turning_window() def search_start_grid(self, grid_map): - xinds = [] + x_inds = [] y_ind = 0 if self.sweep_direction == self.SweepDirection.DOWN: - xinds, y_ind = search_free_grid_index_at_edge_y(grid_map, from_upper=True) + x_inds, y_ind = search_free_grid_index_at_edge_y( + grid_map, from_upper=True) elif self.sweep_direction == self.SweepDirection.UP: - xinds, y_ind = search_free_grid_index_at_edge_y(grid_map, from_upper=False) + x_inds, y_ind = search_free_grid_index_at_edge_y( + grid_map, from_upper=False) if self.moving_direction == self.MovingDirection.RIGHT: - return min(xinds), y_ind + return min(x_inds), y_ind elif self.moving_direction == self.MovingDirection.LEFT: - return max(xinds), y_ind + return max(x_inds), y_ind raise ValueError("self.moving direction is invalid ") -def find_sweep_direction_and_start_posi(ox, oy): +def find_sweep_direction_and_start_position(ox, oy): # find sweep_direction max_dist = 0.0 vec = [0.0, 0.0] @@ -194,9 +201,11 @@ def setup_grid_map(ox, oy, reso, sweep_direction, offset_grid=10): xinds_goaly = [] goaly = 0 if sweep_direction == SweepSearcher.SweepDirection.UP: - xinds_goaly, goaly = search_free_grid_index_at_edge_y(grid_map, from_upper=True) + xinds_goaly, goaly = search_free_grid_index_at_edge_y(grid_map, + from_upper=True) elif sweep_direction == SweepSearcher.SweepDirection.DOWN: - xinds_goaly, goaly = search_free_grid_index_at_edge_y(grid_map, from_upper=False) + xinds_goaly, goaly = search_free_grid_index_at_edge_y(grid_map, + from_upper=False) return grid_map, xinds_goaly, goaly @@ -211,16 +220,19 @@ def sweep_path_search(sweep_searcher, gmap, grid_search_animation=False): x, y = gmap.calc_grid_central_xy_position_from_xy_index(cxind, cyind) px, py = [x], [y] + fig, ax = None, None if grid_search_animation: fig, ax = plt.subplots() # for stopping simulation with the esc key. fig.canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + lambda event: [ + exit(0) if event.key == 'escape' else None]) while True: cxind, cyind = sweep_searcher.move_target_grid(cxind, cyind, gmap) - if sweep_searcher.is_search_done(gmap) or (cxind is None or cyind is None): + if sweep_searcher.is_search_done(gmap) or ( + cxind is None or cyind is None): print("Done") break @@ -245,13 +257,16 @@ def planning(ox, oy, reso, moving_direction=SweepSearcher.MovingDirection.RIGHT, sweeping_direction=SweepSearcher.SweepDirection.UP, ): - sweep_vec, sweep_start_posi = find_sweep_direction_and_start_posi(ox, oy) + sweep_vec, sweep_start_posi = find_sweep_direction_and_start_position( + ox, oy) rox, roy = convert_grid_coordinate(ox, oy, sweep_vec, sweep_start_posi) - gmap, xinds_goaly, goaly = setup_grid_map(rox, roy, reso, sweeping_direction) + gmap, xinds_goaly, goaly = setup_grid_map(rox, roy, reso, + sweeping_direction) - sweep_searcher = SweepSearcher(moving_direction, sweeping_direction, xinds_goaly, goaly) + sweep_searcher = SweepSearcher(moving_direction, sweeping_direction, + xinds_goaly, goaly) px, py = sweep_path_search(sweep_searcher, gmap) @@ -270,8 +285,9 @@ def planning_animation(ox, oy, reso): # pragma: no cover for ipx, ipy in zip(px, py): plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(ox, oy, "-xb") plt.plot(px, py, "-r") plt.plot(ipx, ipy, "or") @@ -285,11 +301,17 @@ def planning_animation(ox, oy, reso): # pragma: no cover plt.axis("equal") plt.grid(True) plt.pause(0.1) + plt.close() def main(): # pragma: no cover print("start!!") + ox = [0.0, 50.0, 50.0, 0.0, 0.0] + oy = [0.0, 0.0, 50.0, 50.0, 0.0] + reso = 0.4 + planning_animation(ox, oy, reso) + ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0, 0.0] oy = [0.0, -20.0, 0.0, 30.0, 60.0, 80.0, 0.0] reso = 5.0 From 7c8a940ebfd44217ae325470c48b47d9ed35f0f3 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 22 Feb 2020 23:17:25 +0900 Subject: [PATCH 203/940] fixed the bug and code clean up. --- Mapping/grid_map_lib/grid_map_lib.py | 21 +++++--- .../grid_based_sweep_coverage_path_planner.py | 48 +++++++++---------- 2 files changed, 36 insertions(+), 33 deletions(-) diff --git a/Mapping/grid_map_lib/grid_map_lib.py b/Mapping/grid_map_lib/grid_map_lib.py index 4787238f07..10651cc673 100644 --- a/Mapping/grid_map_lib/grid_map_lib.py +++ b/Mapping/grid_map_lib/grid_map_lib.py @@ -32,10 +32,8 @@ def __init__(self, width, height, resolution, self.center_x = center_x self.center_y = center_y - self.left_lower_x = self.center_x - \ - (self.width / 2.0) * self.resolution - self.left_lower_y = self.center_y - \ - (self.height / 2.0) * self.resolution + self.left_lower_x = self.center_x - self.width / 2.0 * self.resolution + self.left_lower_y = self.center_y - self.height / 2.0 * self.resolution self.ndata = self.width * self.height self.data = [init_val] * self.ndata @@ -99,7 +97,6 @@ def set_value_from_xy_index(self, x_ind, y_ind, val): """ if (x_ind is None) or (y_ind is None): - print(x_ind, y_ind) return False, False grid_ind = int(y_ind * self.width + x_ind) @@ -200,12 +197,22 @@ def check_inside_polygon(iox, ioy, x, y): if not min_x < iox < max_x: continue - if (y[i1] + (y[i2] - y[i1]) / (x[i2] - x[i1]) - * (iox - x[i1]) - ioy) > 0.0: + tmp1 = (y[i2] - y[i1]) / (x[i2] - x[i1]) + if (y[i1] + tmp1 * (iox - x[i1]) - ioy) > 0.0: inside = not inside return inside + def print_grid_map_info(self): + print("width:", self.width) + print("height:", self.height) + print("resolution:", self.resolution) + print("center_x:", self.center_x) + print("center_y:", self.center_y) + print("left_lower_x:", self.left_lower_x) + print("left_lower_y:", self.left_lower_y) + print("ndata:", self.ndata) + def plot_grid_map(self, ax=None): grid_data = np.reshape(np.array(self.data), (self.height, self.width)) diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py index c51e9393cb..8d9ccd2e2f 100644 --- a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py +++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py @@ -30,7 +30,8 @@ class MovingDirection(IntEnum): RIGHT = 1 LEFT = -1 - def __init__(self, moving_direction, sweep_direction, x_inds_goal_y, goal_y): + def __init__(self, + moving_direction, sweep_direction, x_inds_goal_y, goal_y): self.moving_direction = moving_direction self.sweep_direction = sweep_direction self.turing_window = [] @@ -88,6 +89,8 @@ def is_search_done(self, grid_map): return True def update_turning_window(self): + # turning window definition + # robot can move grid based on it. self.turing_window = [ (self.moving_direction, 0.0), (self.moving_direction, self.sweep_direction), @@ -189,35 +192,34 @@ def search_free_grid_index_at_edge_y(grid_map, from_upper=False): def setup_grid_map(ox, oy, reso, sweep_direction, offset_grid=10): width = math.ceil((max(ox) - min(ox)) / reso) + offset_grid height = math.ceil((max(oy) - min(oy)) / reso) + offset_grid - center_x = np.mean(ox) - center_y = np.mean(oy) + center_x = (np.max(ox)+np.min(ox))/2.0 + center_y = (np.max(oy)+np.min(oy))/2.0 grid_map = GridMap(width, height, reso, center_x, center_y) - + grid_map.print_grid_map_info() grid_map.set_value_from_polygon(ox, oy, 1.0, inside=False) - grid_map.expand_grid() - xinds_goaly = [] - goaly = 0 + x_inds_goal_y = [] + goal_y = 0 if sweep_direction == SweepSearcher.SweepDirection.UP: - xinds_goaly, goaly = search_free_grid_index_at_edge_y(grid_map, + x_inds_goal_y, goal_y = search_free_grid_index_at_edge_y(grid_map, from_upper=True) elif sweep_direction == SweepSearcher.SweepDirection.DOWN: - xinds_goaly, goaly = search_free_grid_index_at_edge_y(grid_map, + x_inds_goal_y, goal_y = search_free_grid_index_at_edge_y(grid_map, from_upper=False) - return grid_map, xinds_goaly, goaly + return grid_map, x_inds_goal_y, goal_y -def sweep_path_search(sweep_searcher, gmap, grid_search_animation=False): +def sweep_path_search(sweep_searcher, grid_map, grid_search_animation=False): # search start grid - cxind, cyind = sweep_searcher.search_start_grid(gmap) - if not gmap.set_value_from_xy_index(cxind, cyind, 0.5): + cxind, cyind = sweep_searcher.search_start_grid(grid_map) + if not grid_map.set_value_from_xy_index(cxind, cyind, 0.5): print("Cannot find start grid") return [], [] - x, y = gmap.calc_grid_central_xy_position_from_xy_index(cxind, cyind) + x, y = grid_map.calc_grid_central_xy_position_from_xy_index(cxind, cyind) px, py = [x], [y] fig, ax = None, None @@ -229,26 +231,26 @@ def sweep_path_search(sweep_searcher, gmap, grid_search_animation=False): exit(0) if event.key == 'escape' else None]) while True: - cxind, cyind = sweep_searcher.move_target_grid(cxind, cyind, gmap) + cxind, cyind = sweep_searcher.move_target_grid(cxind, cyind, grid_map) - if sweep_searcher.is_search_done(gmap) or ( + if sweep_searcher.is_search_done(grid_map) or ( cxind is None or cyind is None): print("Done") break - x, y = gmap.calc_grid_central_xy_position_from_xy_index( + x, y = grid_map.calc_grid_central_xy_position_from_xy_index( cxind, cyind) px.append(x) py.append(y) - gmap.set_value_from_xy_index(cxind, cyind, 0.5) + grid_map.set_value_from_xy_index(cxind, cyind, 0.5) if grid_search_animation: - gmap.plot_grid_map(ax=ax) + grid_map.plot_grid_map(ax=ax) plt.pause(1.0) - gmap.plot_grid_map() + grid_map.plot_grid_map() return px, py @@ -307,11 +309,6 @@ def planning_animation(ox, oy, reso): # pragma: no cover def main(): # pragma: no cover print("start!!") - ox = [0.0, 50.0, 50.0, 0.0, 0.0] - oy = [0.0, 0.0, 50.0, 50.0, 0.0] - reso = 0.4 - planning_animation(ox, oy, reso) - ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0, 0.0] oy = [0.0, -20.0, 0.0, 30.0, 60.0, 80.0, 0.0] reso = 5.0 @@ -328,7 +325,6 @@ def main(): # pragma: no cover planning_animation(ox, oy, reso) plt.show() - print("done!!") From 065536a47b0c8e692638df288539eb301e3bb086 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 23 Feb 2020 20:35:09 +0900 Subject: [PATCH 204/940] start implementation --- PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py diff --git a/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py b/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py new file mode 100644 index 0000000000..e69de29bb2 From 6f0d9bfd5c6cd74bbd65891570568652c0160690 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 24 Feb 2020 16:15:17 +0900 Subject: [PATCH 205/940] clean up voronoi road map --- .../VoronoiRoadMap/dijkstra_search.py | 106 +++++++ PathPlanning/VoronoiRoadMap/kdtree.py | 49 +++ .../VoronoiRoadMap/voronoi_road_map.py | 294 +++++------------- 3 files changed, 239 insertions(+), 210 deletions(-) create mode 100644 PathPlanning/VoronoiRoadMap/dijkstra_search.py create mode 100644 PathPlanning/VoronoiRoadMap/kdtree.py diff --git a/PathPlanning/VoronoiRoadMap/dijkstra_search.py b/PathPlanning/VoronoiRoadMap/dijkstra_search.py new file mode 100644 index 0000000000..4d294ee5e5 --- /dev/null +++ b/PathPlanning/VoronoiRoadMap/dijkstra_search.py @@ -0,0 +1,106 @@ +""" + +Dijkstra Search library + +author: Atsushi Sakai (@Atsushi_twi) + +""" + +import matplotlib.pyplot as plt +import math + + +class DijkstraSearch: + + class Node: + """ + Node class for dijkstra search + """ + + def __init__(self, x, y, cost, parent): + self.x = x + self.y = y + self.cost = cost + self.parent = parent + + def __str__(self): + return str(self.x) + "," + str(self.y) + "," + str( + self.cost) + "," + str(self.parent) + + def __init__(self, show_animation): + self.show_animation = show_animation + + def search(self, sx, sy, gx, gy, road_map, sample_x, sample_y): + """ + gx: goal x position [m] + gx: goal x position [m] + ox: x position list of Obstacles [m] + oy: y position list of Obstacles [m] + reso: grid resolution [m] + rr: robot radius[m] + """ + + start_node = self.Node(sx, sy, 0.0, -1) + goal_node = self.Node(gx, gy, 0.0, -1) + + open_set, close_set = dict(), dict() + open_set[len(road_map) - 2] = start_node + + while True: + if not open_set: + print("Cannot find path") + break + + c_id = min(open_set, key=lambda o: open_set[o].cost) + current = open_set[c_id] + + # show graph + if self.show_animation and len( + close_set.keys()) % 2 == 0: # pragma: no cover + plt.plot(current.x, current.y, "xg") + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + plt.pause(0.001) + + if c_id == (len(road_map) - 1): + print("goal is found!") + goal_node.parent = current.parent + goal_node.cost = current.cost + break + + # Remove the item from the open set + del open_set[c_id] + # Add it to the closed set + close_set[c_id] = current + + # expand search grid based on motion model + for i in range(len(road_map[c_id])): + n_id = road_map[c_id][i] + dx = sample_x[n_id] - current.x + dy = sample_y[n_id] - current.y + d = math.hypot(dx, dy) + node = self.Node(sample_x[n_id], sample_y[n_id], + current.cost + d, c_id) + + if n_id in close_set: + continue + # Otherwise if it is already in the open set + if n_id in open_set: + if open_set[n_id].cost > node.cost: + open_set[n_id].cost = node.cost + open_set[n_id].parent = c_id + else: + open_set[n_id] = node + + # generate final course + rx, ry = [goal_node.x], [goal_node.y] + parent = goal_node.parent + while parent != -1: + n = close_set[parent] + rx.append(n.x) + ry.append(n.y) + parent = n.parent + + return rx, ry diff --git a/PathPlanning/VoronoiRoadMap/kdtree.py b/PathPlanning/VoronoiRoadMap/kdtree.py new file mode 100644 index 0000000000..d3dc01b1f6 --- /dev/null +++ b/PathPlanning/VoronoiRoadMap/kdtree.py @@ -0,0 +1,49 @@ +""" + +Kd tree Search library + +author: Atsushi Sakai (@Atsushi_twi) + +""" + +import scipy.spatial + + +class KDTree: + """ + Nearest neighbor search class with KDTree + """ + + def __init__(self, data): + # store kd-tree + self.tree = scipy.spatial.cKDTree(data) + + def search(self, inp, k=1): + """ + Search NN + + inp: input data, single frame or multi frame + + """ + + if len(inp.shape) >= 2: # multi input + index = [] + dist = [] + + for i in inp.T: + idist, iindex = self.tree.query(i, k=k) + index.append(iindex) + dist.append(idist) + + return index, dist + + dist, index = self.tree.query(inp, k=k) + return index, dist + + def search_in_distance(self, inp, r): + """ + find points with in a distance r + """ + + index = self.tree.query_ball_point(inp, r) + return index diff --git a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py index 6db4bb26ce..dfac7258f8 100644 --- a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py +++ b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py @@ -10,252 +10,124 @@ import numpy as np import scipy.spatial import matplotlib.pyplot as plt - -# parameter -N_KNN = 10 # number of edge from one sampled point -MAX_EDGE_LEN = 30.0 # [m] Maximum edge length +from dijkstra_search import DijkstraSearch +from kdtree import KDTree show_animation = True -class Node: - """ - Node class for dijkstra search - """ - - def __init__(self, x, y, cost, pind): - self.x = x - self.y = y - self.cost = cost - self.pind = pind - - def __str__(self): - return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind) - - -class KDTree: - """ - Nearest neighbor search class with KDTree - """ - - def __init__(self, data): - # store kd-tree - self.tree = scipy.spatial.cKDTree(data) - - def search(self, inp, k=1): - """ - Search NN - - inp: input data, single frame or multi frame - - """ - - if len(inp.shape) >= 2: # multi input - index = [] - dist = [] - - for i in inp.T: - idist, iindex = self.tree.query(i, k=k) - index.append(iindex) - dist.append(idist) - - return index, dist - - dist, index = self.tree.query(inp, k=k) - return index, dist - - def search_in_distance(self, inp, r): - """ - find points with in a distance r - """ - - index = self.tree.query_ball_point(inp, r) - return index - +class VoronoiRoadMapPlanner: -def VRM_planning(sx, sy, gx, gy, ox, oy, rr): + def __init__(self): + # parameter + self.N_KNN = 10 # number of edge from one sampled point + self.MAX_EDGE_LEN = 30.0 # [m] Maximum edge length - obkdtree = KDTree(np.vstack((ox, oy)).T) + def planning(self, sx, sy, gx, gy, ox, oy, rr): + obstacle_tree = KDTree(np.vstack((ox, oy)).T) - sample_x, sample_y = sample_points(sx, sy, gx, gy, rr, ox, oy, obkdtree) - if show_animation: # pragma: no cover - plt.plot(sample_x, sample_y, ".b") + sample_x, sample_y = self.voronoi_sampling(sx, sy, gx, gy, ox, oy) + if show_animation: # pragma: no cover + plt.plot(sample_x, sample_y, ".b") - road_map = generate_roadmap(sample_x, sample_y, rr, obkdtree) + road_map = self.generate_road_map(sample_x, sample_y, rr, obstacle_tree) - rx, ry = dijkstra_planning( - sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y) + rx, ry = DijkstraSearch(show_animation).search(sx, sy, gx, gy, road_map, + sample_x, sample_y) - return rx, ry + return rx, ry + def is_collision(self, sx, sy, gx, gy, rr, obstacle_kdtree): + x = sx + y = sy + dx = gx - sx + dy = gy - sy + yaw = math.atan2(gy - sy, gx - sx) + d = math.hypot(dx, dy) -def is_collision(sx, sy, gx, gy, rr, okdtree): - x = sx - y = sy - dx = gx - sx - dy = gy - sy - yaw = math.atan2(gy - sy, gx - sx) - d = math.hypot(dx, dy) + if d >= self.MAX_EDGE_LEN: + return True - if d >= MAX_EDGE_LEN: - return True + D = rr + n_step = round(d / D) - D = rr - nstep = round(d / D) + for i in range(n_step): + ids, dist = obstacle_kdtree.search(np.array([x, y]).reshape(2, 1)) + if dist[0] <= rr: + return True # collision + x += D * math.cos(yaw) + y += D * math.sin(yaw) - for i in range(nstep): - idxs, dist = okdtree.search(np.array([x, y]).reshape(2, 1)) + # goal point check + ids, dist = obstacle_kdtree.search(np.array([gx, gy]).reshape(2, 1)) if dist[0] <= rr: return True # collision - x += D * math.cos(yaw) - y += D * math.sin(yaw) - - # goal point check - idxs, dist = okdtree.search(np.array([gx, gy]).reshape(2, 1)) - if dist[0] <= rr: - return True # collision - - return False # OK - - -def generate_roadmap(sample_x, sample_y, rr, obkdtree): - """ - Road map generation - - sample_x: [m] x positions of sampled points - sample_y: [m] y positions of sampled points - rr: Robot Radius[m] - obkdtree: KDTree object of obstacles - """ - - road_map = [] - nsample = len(sample_x) - skdtree = KDTree(np.vstack((sample_x, sample_y)).T) - - for (i, ix, iy) in zip(range(nsample), sample_x, sample_y): - - index, dists = skdtree.search( - np.array([ix, iy]).reshape(2, 1), k=nsample) - - inds = index[0] - edge_id = [] - # print(index) - - for ii in range(1, len(inds)): - nx = sample_x[inds[ii]] - ny = sample_y[inds[ii]] - if not is_collision(ix, iy, nx, ny, rr, obkdtree): - edge_id.append(inds[ii]) + return False # OK - if len(edge_id) >= N_KNN: - break - - road_map.append(edge_id) - - # plot_road_map(road_map, sample_x, sample_y) - - return road_map - - -def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): - """ - gx: goal x position [m] - gx: goal x position [m] - ox: x position list of Obstacles [m] - oy: y position list of Obstacles [m] - reso: grid resolution [m] - rr: robot radius[m] - """ - - nstart = Node(sx, sy, 0.0, -1) - ngoal = Node(gx, gy, 0.0, -1) + def generate_road_map(self, node_x, node_y, rr, obstacle_tree): + """ + Road map generation - openset, closedset = dict(), dict() - openset[len(road_map) - 2] = nstart + sample_x: [m] x positions of sampled points + sample_y: [m] y positions of sampled points + rr: Robot Radius[m] + obstacle_tree: KDTree object of obstacles + """ - while True: - if not openset: - print("Cannot find path") - break + road_map = [] + n_sample = len(node_x) + node_tree = KDTree(np.vstack((node_x, node_y)).T) - c_id = min(openset, key=lambda o: openset[o].cost) - current = openset[c_id] + for (i, ix, iy) in zip(range(n_sample), node_x, node_y): - # show graph - if show_animation and len(closedset.keys()) % 2 == 0: # pragma: no cover - plt.plot(current.x, current.y, "xg") - # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) - plt.pause(0.001) + index, dists = node_tree.search( + np.array([ix, iy]).reshape(2, 1), k=n_sample) - if c_id == (len(road_map) - 1): - print("goal is found!") - ngoal.pind = current.pind - ngoal.cost = current.cost - break + inds = index[0] + edge_id = [] - # Remove the item from the open set - del openset[c_id] - # Add it to the closed set - closedset[c_id] = current + for ii in range(1, len(inds)): + nx = node_x[inds[ii]] + ny = node_y[inds[ii]] - # expand search grid based on motion model - for i in range(len(road_map[c_id])): - n_id = road_map[c_id][i] - dx = sample_x[n_id] - current.x - dy = sample_y[n_id] - current.y - d = math.hypot(dx, dy) - node = Node(sample_x[n_id], sample_y[n_id], - current.cost + d, c_id) + if not self.is_collision(ix, iy, nx, ny, rr, obstacle_tree): + edge_id.append(inds[ii]) - if n_id in closedset: - continue - # Otherwise if it is already in the open set - if n_id in openset: - if openset[n_id].cost > node.cost: - openset[n_id].cost = node.cost - openset[n_id].pind = c_id - else: - openset[n_id] = node + if len(edge_id) >= self.N_KNN: + break - # generate final course - rx, ry = [ngoal.x], [ngoal.y] - pind = ngoal.pind - while pind != -1: - n = closedset[pind] - rx.append(n.x) - ry.append(n.y) - pind = n.pind + road_map.append(edge_id) - return rx, ry + # plot_road_map(road_map, sample_x, sample_y) + return road_map -def plot_road_map(road_map, sample_x, sample_y): # pragma: no cover + @staticmethod + def plot_road_map(road_map, sample_x, sample_y): # pragma: no cover - for i, _ in enumerate(road_map): - for ii in range(len(road_map[i])): - ind = road_map[i][ii] + for i, _ in enumerate(road_map): + for ii in range(len(road_map[i])): + ind = road_map[i][ii] - plt.plot([sample_x[i], sample_x[ind]], - [sample_y[i], sample_y[ind]], "-k") + plt.plot([sample_x[i], sample_x[ind]], + [sample_y[i], sample_y[ind]], "-k") + @staticmethod + def voronoi_sampling(sx, sy, gx, gy, ox, oy): + oxy = np.vstack((ox, oy)).T -def sample_points(sx, sy, gx, gy, rr, ox, oy, obkdtree): - oxy = np.vstack((ox, oy)).T + # generate voronoi point + vor = scipy.spatial.Voronoi(oxy) + sample_x = [ix for [ix, _] in vor.vertices] + sample_y = [iy for [_, iy] in vor.vertices] - # generate voronoi point - vor = scipy.spatial.Voronoi(oxy) - sample_x = [ix for [ix, iy] in vor.vertices] - sample_y = [iy for [ix, iy] in vor.vertices] + sample_x.append(sx) + sample_y.append(sy) + sample_x.append(gx) + sample_y.append(gy) - sample_x.append(sx) - sample_y.append(sy) - sample_x.append(gx) - sample_y.append(gy) - - return sample_x, sample_y + return sample_x, sample_y def main(): @@ -297,12 +169,14 @@ def main(): plt.grid(True) plt.axis("equal") - rx, ry = VRM_planning(sx, sy, gx, gy, ox, oy, robot_size) + rx, ry = VoronoiRoadMapPlanner().planning(sx, sy, gx, gy, ox, oy, + robot_size) assert rx, 'Cannot found path' if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") + plt.pause(0.1) plt.show() From ae85e66d07dedc37739a7f81910befce2e4065cc Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 24 Feb 2020 16:40:57 +0900 Subject: [PATCH 206/940] fix tests --- .../visibility_graph_planner.py | 90 +++++++++++++++++++ tests/test_voronoi_path_planner.py | 6 ++ 2 files changed, 96 insertions(+) diff --git a/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py b/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py index e69de29bb2..06a4d59834 100644 --- a/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py +++ b/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py @@ -0,0 +1,90 @@ +""" + +Visibility Graph Planner + +author: Atsushi Sakai (@Atsushi_twi) + +""" + +import matplotlib.pyplot as plt + +show_animation = True + +class VisibilityGraphPlanner: + + def __init__(self, robot_radius): + self.robot_radius = robot_radius + + def planning(self, start_x, start_y, goal_x, goal_y, obstacles): + nodes = self.exstract_graph_node(start_x, start_y, goal_x, goal_y, + obstacles) + + graph = self.generate_graph(nodes, obstacles) + + rx, ry = dijkstra_search(graph) + + return rx, ry + + def exstract_graph_node(self, start_x, start_y, goal_x, goal_x, obstacles): + nodes = [] + + return nodes + + def generate_graph(self, nodes, obstacles): + + graph = [] + + return graph + + +class ObstaclePolygon: + + def __init__(self, x_list, y_list): + self.x_list = x_list + self.y_list = y_list + + self.close_polygon() + + def close_polygon(self): + is_x_same = self.x_list[0] == self.x_list[-1] + is_y_same = self.y_list[0] == self.y_list[-1] + if is_x_same and is_y_same: + return # no need to close + + self.x_list.append(self.x_list[0]) + self.y_list.append(self.y_list[0]) + + def plot(self): + plt.plot(self.x_list, self.y_list, "-b") + + +def main(): + print(__file__ + " start!!") + + # start and goal position + sx, sy = 10.0, 10.0 # [m] + gx, gy = 50.0, 50.0 # [m] + robot_radius = 5.0 # [m] + + obstacles = [ObstaclePolygon( + [20.0, 30.0, 15.0], + [20.0, 20.0, 30.0], + ), ObstaclePolygon( + [30.0, 45.0, 50.0, 40.0], + [50.0, 40.0, 20.0, 40.0], + )] + + rx, ry = VisibilityGraphPlanner(robot_radius).planning(sx, sy, gx, gy, + obstacles) + assert rx, 'Cannot found path' + if show_animation: # pragma: no cover + plt.plot(sx, sy, "or") + plt.plot(gx, gy, "ob") + [ob.plot() for ob in obstacles] + plt.plot(rx, ry, "-r") + plt.axis("equal") + plt.show() + + +if __name__ == '__main__': + main() diff --git a/tests/test_voronoi_path_planner.py b/tests/test_voronoi_path_planner.py index 3e0ff961d8..5295769b40 100644 --- a/tests/test_voronoi_path_planner.py +++ b/tests/test_voronoi_path_planner.py @@ -1,6 +1,12 @@ +import sys +import os +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../PathPlanning/VoronoiRoadMap/") + from unittest import TestCase from PathPlanning.VoronoiRoadMap import voronoi_road_map as m + print(__file__) From cfd83841d753956ae6957ca101d42cff5e5596a5 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 26 Feb 2020 20:37:45 +0900 Subject: [PATCH 207/940] for good measure --- .../visibility_graph_planner.py | 126 ++++++++++++++++-- .../VoronoiRoadMap/dijkstra_search.py | 2 +- tests/test_rrt_star_dubins.py | 1 + 3 files changed, 119 insertions(+), 10 deletions(-) diff --git a/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py b/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py index 06a4d59834..d00e8f43c6 100644 --- a/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py +++ b/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py @@ -6,36 +6,127 @@ """ +import os +import sys + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../VoronoiRoadMap/") + +import math +import numpy as np import matplotlib.pyplot as plt +from dijkstra_search import DijkstraSearch show_animation = True + class VisibilityGraphPlanner: def __init__(self, robot_radius): self.robot_radius = robot_radius def planning(self, start_x, start_y, goal_x, goal_y, obstacles): - nodes = self.exstract_graph_node(start_x, start_y, goal_x, goal_y, - obstacles) - + nodes = self.extract_graph_node(start_x, start_y, goal_x, goal_y, + obstacles) graph = self.generate_graph(nodes, obstacles) - rx, ry = dijkstra_search(graph) + # rx, ry = DijkstraSearch().search(graph) + + rx, ry = [], [] return rx, ry - def exstract_graph_node(self, start_x, start_y, goal_x, goal_x, obstacles): - nodes = [] + def extract_graph_node(self, start_x, start_y, goal_x, goal_y, obstacles): + + # add start and goal as nodes + nodes = [DijkstraSearch.Node(start_x, start_y), + DijkstraSearch.Node(goal_x, goal_y, 0, None)] + + # add vertexes in configuration space as nodes + for obstacle in obstacles: + + cvx_list, cvy_list = self.calc_vertexes_in_configuration_space( + obstacle.x_list, obstacle.y_list) + + for (vx, vy) in zip(cvx_list, cvy_list): + nodes.append(DijkstraSearch.Node(vx, vy)) + + for node in nodes: + plt.plot(node.x, node.y, "xr") return nodes + def calc_vertexes_in_configuration_space(self, x_list, y_list): + x_list=x_list[0:-1] + y_list=y_list[0:-1] + cvx_list, cvy_list = [], [] + + n_data=len(x_list) + + for index in range(n_data): + offset_x, offset_y = self.calc_offset_xy( + x_list[index - 1], y_list[index - 1], + x_list[index], y_list[index], + x_list[(index + 1) % n_data], y_list[(index + 1) % n_data], + ) + cvx_list.append(offset_x) + cvy_list.append(offset_y) + + return cvx_list, cvy_list + def generate_graph(self, nodes, obstacles): graph = [] + for target_node in nodes: + for node in nodes: + for obstacle in obstacles: + if not self.is_edge_valid(target_node, node, obstacle): + print("bb") + break + print(target_node, node) + print("aa") + plt.plot([target_node.x, node.x],[target_node.y, node.y], "-r") + return graph + def is_edge_valid(self, target_node, node, obstacle): + + for i in range(len(obstacle.x_list)-1): + p1 = np.array([target_node.x, target_node.y]) + p2 = np.array([node.x, node.y]) + p3 = np.array([obstacle.x_list[i], obstacle.y_list[i]]) + p4 = np.array([obstacle.y_list[i+1], obstacle.y_list[i+1]]) + + if is_seg_intersect(p1, p2, p3, p4): + return False + + return True + + def calc_offset_xy(self, px, py, x, y, nx, ny): + p_vec = math.atan2(y - py, x - px) + n_vec = math.atan2(ny - y, nx - x) + offset_vec = math.atan2(math.sin(p_vec) + math.sin(n_vec), + math.cos(p_vec) + math.cos( + n_vec))+math.pi/2.0 + offset_x = x + self.robot_radius * math.cos(offset_vec) + offset_y = y + self.robot_radius * math.sin(offset_vec) + return offset_x, offset_y + + +def is_seg_intersect(a1, a2, b1, b2): + + xdiff = [a1[0] - a2[0], b1[0] - b2[0]] + ydiff = [a1[1] - a2[1], b1[1] - b2[1]] + + def det(a, b): + return a[0] * b[1] - a[1] * b[0] + + div = det(xdiff, ydiff) + if div == 0: + return False + else: + return True class ObstaclePolygon: @@ -44,6 +135,21 @@ def __init__(self, x_list, y_list): self.y_list = y_list self.close_polygon() + self.make_clockwise() + + def make_clockwise(self): + if not self.is_clockwise(): + self.x_list = list(reversed(self.x_list)) + self.y_list = list(reversed(self.y_list)) + + def is_clockwise(self): + n_data = len(self.x_list) + eval_sum = sum([(self.x_list[i + 1] - self.x_list[i]) * + (self.y_list[i + 1] + self.y_list[i]) + for i in range(n_data - 1)]) + eval_sum += (self.x_list[0] - self.x_list[n_data - 1]) * \ + (self.y_list[0] + self.y_list[n_data - 1]) + return eval_sum >= 0 def close_polygon(self): is_x_same = self.x_list[0] == self.x_list[-1] @@ -74,13 +180,15 @@ def main(): [50.0, 40.0, 20.0, 40.0], )] - rx, ry = VisibilityGraphPlanner(robot_radius).planning(sx, sy, gx, gy, - obstacles) - assert rx, 'Cannot found path' if show_animation: # pragma: no cover plt.plot(sx, sy, "or") plt.plot(gx, gy, "ob") [ob.plot() for ob in obstacles] + + rx, ry = VisibilityGraphPlanner(robot_radius).planning(sx, sy, gx, gy, + obstacles) + # assert rx, 'Cannot found path' + if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") plt.axis("equal") plt.show() diff --git a/PathPlanning/VoronoiRoadMap/dijkstra_search.py b/PathPlanning/VoronoiRoadMap/dijkstra_search.py index 4d294ee5e5..7f248cd3cf 100644 --- a/PathPlanning/VoronoiRoadMap/dijkstra_search.py +++ b/PathPlanning/VoronoiRoadMap/dijkstra_search.py @@ -17,7 +17,7 @@ class Node: Node class for dijkstra search """ - def __init__(self, x, y, cost, parent): + def __init__(self, x, y, cost=None, parent=None): self.x = x self.y = y self.cost = cost diff --git a/tests/test_rrt_star_dubins.py b/tests/test_rrt_star_dubins.py index 8ee3d38788..db1ca2bfa4 100644 --- a/tests/test_rrt_star_dubins.py +++ b/tests/test_rrt_star_dubins.py @@ -2,6 +2,7 @@ import sys import os + sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../PathPlanning/RRTStarDubins/") From 2e188f866b0de3e46cca5e3b9f807003be8bc305 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 26 Feb 2020 22:27:25 +0900 Subject: [PATCH 208/940] To fix #298 --- PathTracking/pure_pursuit/pure_pursuit.py | 83 ++++++++++++----------- 1 file changed, 43 insertions(+), 40 deletions(-) diff --git a/PathTracking/pure_pursuit/pure_pursuit.py b/PathTracking/pure_pursuit/pure_pursuit.py index bcaf869726..ff995033a9 100644 --- a/PathTracking/pure_pursuit/pure_pursuit.py +++ b/PathTracking/pure_pursuit/pure_pursuit.py @@ -1,6 +1,6 @@ """ -Path tracking simulation with pure pursuit steering control and PID speed control. +Path tracking simulation with pure pursuit steering and PID speed control. author: Atsushi Sakai (@Atsushi_twi) Guillaume Jacquenot (@Gjacquenot) @@ -10,13 +10,12 @@ import math import matplotlib.pyplot as plt - +# Parameters k = 0.1 # look forward gain -Lfc = 2.0 # look-ahead distance +Lfc = 2.0 # [m] look-ahead distance Kp = 1.0 # speed proportional gain -dt = 0.1 # [s] -L = 2.9 # [m] wheel base of vehicle - +dt = 0.1 # [s] time tick +WB = 2.9 # [m] wheel base of vehicle show_animation = True @@ -28,20 +27,18 @@ def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0): self.y = y self.yaw = yaw self.v = v - self.rear_x = self.x - ((L / 2) * math.cos(self.yaw)) - self.rear_y = self.y - ((L / 2) * math.sin(self.yaw)) + self.rear_x = self.x - ((WB / 2) * math.cos(self.yaw)) + self.rear_y = self.y - ((WB / 2) * math.sin(self.yaw)) def update(self, a, delta): - self.x += self.v * math.cos(self.yaw) * dt self.y += self.v * math.sin(self.yaw) * dt - self.yaw += self.v / L * math.tan(delta) * dt + self.yaw += self.v / WB * math.tan(delta) * dt self.v += a * dt - self.rear_x = self.x - ((L / 2) * math.cos(self.yaw)) - self.rear_y = self.y - ((L / 2) * math.sin(self.yaw)) + self.rear_x = self.x - ((WB / 2) * math.cos(self.yaw)) + self.rear_y = self.y - ((WB / 2) * math.sin(self.yaw)) def calc_distance(self, point_x, point_y): - dx = self.rear_x - point_x dy = self.rear_y - point_y return math.hypot(dx, dy) @@ -56,7 +53,7 @@ def __init__(self): self.v = [] self.t = [] - def append(self, t , state): + def append(self, t, state): self.x.append(state.x) self.y.append(state.y) self.yaw.append(state.yaw) @@ -64,19 +61,22 @@ def append(self, t , state): self.t.append(t) -def PIDControl(target, current): +def proportional_control(target, current): a = Kp * (target - current) return a -class Trajectory: +class TargetCourse: + def __init__(self, cx, cy): self.cx = cx self.cy = cy self.old_nearest_point_index = None def search_target_index(self, state): + + # To speed up nearest point search, doing it at only first time. if self.old_nearest_point_index is None: # search nearest point index dx = [state.rear_x - icx for icx in self.cx] @@ -86,30 +86,30 @@ def search_target_index(self, state): self.old_nearest_point_index = ind else: ind = self.old_nearest_point_index - distance_this_index = state.calc_distance(self.cx[ind], self.cy[ind]) + distance_this_index = state.calc_distance(self.cx[ind], + self.cy[ind]) while True: - ind = ind + 1 if (ind + 1) < len(self.cx) else ind - distance_next_index = state.calc_distance(self.cx[ind], self.cy[ind]) + distance_next_index = state.calc_distance(self.cx[ind + 1], + self.cy[ind + 1]) if distance_this_index < distance_next_index: break + ind = ind + 1 if (ind + 1) < len(self.cx) else ind distance_this_index = distance_next_index self.old_nearest_point_index = ind - L = 0.0 - - Lf = k * state.v + Lfc + Lf = k * state.v + Lfc # update look ahead distance # search look ahead target point index - while Lf > L and (ind + 1) < len(self.cx): - L = state.calc_distance(self.cx[ind], self.cy[ind]) + while Lf > state.calc_distance(self.cx[ind], self.cy[ind]): + if (ind + 1) >= len(self.cx): + break # not exceed goal ind += 1 - return ind + return ind, Lf -def pure_pursuit_control(state, trajectory, pind): - - ind = trajectory.search_target_index(state) +def pure_pursuit_steer_control(state, trajectory, pind): + ind, Lf = trajectory.search_target_index(state) if pind >= ind: ind = pind @@ -117,16 +117,14 @@ def pure_pursuit_control(state, trajectory, pind): if ind < len(trajectory.cx): tx = trajectory.cx[ind] ty = trajectory.cy[ind] - else: + else: # toward goal tx = trajectory.cx[-1] ty = trajectory.cy[-1] ind = len(trajectory.cx) - 1 alpha = math.atan2(ty - state.rear_y, tx - state.rear_x) - state.yaw - Lf = k * state.v + Lfc - - delta = math.atan2(2.0 * L * math.sin(alpha) / Lf, 1.0) + delta = math.atan2(2.0 * WB * math.sin(alpha) / Lf, 1.0) return delta, ind @@ -147,7 +145,7 @@ def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): def main(): # target course - cx = np.arange(0, 50, 0.1) + cx = np.arange(0, 50, 0.5) cy = [math.sin(ix / 5.0) * ix / 2.0 for ix in cx] target_speed = 10.0 / 3.6 # [m/s] @@ -161,13 +159,17 @@ def main(): time = 0.0 states = States() states.append(time, state) - trajectory = Trajectory(cx, cy) - target_ind = trajectory.search_target_index(state) + target_course = TargetCourse(cx, cy) + target_ind, _ = target_course.search_target_index(state) while T >= time and lastIndex > target_ind: - ai = PIDControl(target_speed, state.v) - di, target_ind = pure_pursuit_control(state, trajectory, target_ind) - state.update(ai, di) + + # Calc control input + ai = proportional_control(target_speed, state.v) + di, target_ind = pure_pursuit_steer_control( + state, target_course, target_ind) + + state.update(ai, di) # Control vehicle time += dt states.append(time, state) @@ -175,8 +177,9 @@ def main(): if show_animation: # pragma: no cover plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plot_arrow(state.x, state.y, state.yaw) plt.plot(cx, cy, "-r", label="course") plt.plot(states.x, states.y, "-b", label="trajectory") From ee423e8b94f8ef5b20faa18e510546ebfc05b4a2 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 29 Feb 2020 14:46:43 +0900 Subject: [PATCH 209/940] implement visibility_road_map planner --- PathPlanning/Dijkstra/dijkstra.py | 157 ++++++++++-------- PathPlanning/VisibilityRoadMap/__init__.py | 0 PathPlanning/VisibilityRoadMap/geometry.py | 44 +++++ .../visibility_road_map.py} | 135 ++++++++------- .../VoronoiRoadMap/dijkstra_search.py | 93 +++++++---- .../VoronoiRoadMap/voronoi_road_map.py | 23 +-- ...py => test_visibility_road_map_planner.py} | 0 tests/test_voronoi_road_map_planner.py | 17 ++ 8 files changed, 300 insertions(+), 169 deletions(-) create mode 100644 PathPlanning/VisibilityRoadMap/__init__.py create mode 100644 PathPlanning/VisibilityRoadMap/geometry.py rename PathPlanning/{VisibilityGraphPlanner/visibility_graph_planner.py => VisibilityRoadMap/visibility_road_map.py} (57%) rename tests/{test_voronoi_path_planner.py => test_visibility_road_map_planner.py} (100%) create mode 100644 tests/test_voronoi_road_map_planner.py diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index bb1fb3aa63..ad3e3a85c8 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -11,32 +11,42 @@ show_animation = True + class Dijkstra: - def __init__(self, ox, oy, reso, rr): + def __init__(self, ox, oy, resolution, robot_radius): """ Initialize map for a star planning ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] - reso: grid resolution [m] + resolution: grid resolution [m] rr: robot radius[m] """ - self.reso = reso - self.rr = rr + self.resolution = resolution + self.robot_radius = robot_radius self.calc_obstacle_map(ox, oy) self.motion = self.get_motion_model() + self.min_x = None + self.min_y = None + self.max_x = None + self.max_y = None + self.x_width = None + self.y_width = None + self.obstacle_map = None + class Node: - def __init__(self, x, y, cost, pind): + def __init__(self, x, y, cost, parent): self.x = x # index of grid self.y = y # index of grid self.cost = cost - self.pind = pind # index of previous Node + self.parent = parent # index of previous Node def __str__(self): - return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind) + return str(self.x) + "," + str(self.y) + "," + str( + self.cost) + "," + str(self.parent) def planning(self, sx, sy, gx, gy): """ @@ -53,39 +63,40 @@ def planning(self, sx, sy, gx, gy): ry: y position list of the final path """ - nstart = self.Node(self.calc_xyindex(sx, self.minx), - self.calc_xyindex(sy, self.miny), 0.0, -1) - ngoal = self.Node(self.calc_xyindex(gx, self.minx), - self.calc_xyindex(gy, self.miny), 0.0, -1) + start_node = self.Node(self.calc_xy_index(sx, self.min_x), + self.calc_xy_index(sy, self.min_y), 0.0, -1) + goal_node = self.Node(self.calc_xy_index(gx, self.min_x), + self.calc_xy_index(gy, self.min_y), 0.0, -1) - openset, closedset = dict(), dict() - openset[self.calc_index(nstart)] = nstart + open_set, closed_set = dict(), dict() + open_set[self.calc_index(start_node)] = start_node while 1: - c_id = min(openset, key=lambda o: openset[o].cost) - current = openset[c_id] + c_id = min(open_set, key=lambda o: open_set[o].cost) + current = open_set[c_id] # show graph if show_animation: # pragma: no cover - plt.plot(self.calc_position(current.x, self.minx), - self.calc_position(current.y, self.miny), "xc") + plt.plot(self.calc_position(current.x, self.min_x), + self.calc_position(current.y, self.min_y), "xc") # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) - if len(closedset.keys()) % 10 == 0: + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + if len(closed_set.keys()) % 10 == 0: plt.pause(0.001) - if current.x == ngoal.x and current.y == ngoal.y: + if current.x == goal_node.x and current.y == goal_node.y: print("Find goal") - ngoal.pind = current.pind - ngoal.cost = current.cost + goal_node.parent = current.parent + goal_node.cost = current.cost break # Remove the item from the open set - del openset[c_id] + del open_set[c_id] # Add it to the closed set - closedset[c_id] = current + closed_set[c_id] = current # expand search grid based on motion model for move_x, move_y, move_cost in self.motion: @@ -94,94 +105,95 @@ def planning(self, sx, sy, gx, gy): current.cost + move_cost, c_id) n_id = self.calc_index(node) - if n_id in closedset: + if n_id in closed_set: continue if not self.verify_node(node): continue - if n_id not in openset: - openset[n_id] = node # Discover a new node + if n_id not in open_set: + open_set[n_id] = node # Discover a new node else: - if openset[n_id].cost >= node.cost: + if open_set[n_id].cost >= node.cost: # This path is the best until now. record it! - openset[n_id] = node + open_set[n_id] = node - rx, ry = self.calc_final_path(ngoal, closedset) + rx, ry = self.calc_final_path(goal_node, closed_set) return rx, ry - def calc_final_path(self, ngoal, closedset): + def calc_final_path(self, goal_node, closed_set): # generate final course - rx, ry = [self.calc_position(ngoal.x, self.minx)], [ - self.calc_position(ngoal.y, self.miny)] - pind = ngoal.pind - while pind != -1: - n = closedset[pind] - rx.append(self.calc_position(n.x, self.minx)) - ry.append(self.calc_position(n.y, self.miny)) - pind = n.pind + rx, ry = [self.calc_position(goal_node.x, self.min_x)], [ + self.calc_position(goal_node.y, self.min_y)] + parent = goal_node.parent + while parent != -1: + n = closed_set[parent] + rx.append(self.calc_position(n.x, self.min_x)) + ry.append(self.calc_position(n.y, self.min_y)) + parent = n.parent return rx, ry def calc_position(self, index, minp): - pos = index*self.reso+minp + pos = index * self.resolution + minp return pos - def calc_xyindex(self, position, minp): - return round((position - minp)/self.reso) + def calc_xy_index(self, position, minp): + return round((position - minp) / self.resolution) def calc_index(self, node): - return (node.y - self.miny) * self.xwidth + (node.x - self.minx) + return (node.y - self.min_y) * self.x_width + (node.x - self.min_x) def verify_node(self, node): - px = self.calc_position(node.x, self.minx) - py = self.calc_position(node.y, self.miny) + px = self.calc_position(node.x, self.min_x) + py = self.calc_position(node.y, self.min_y) - if px < self.minx: + if px < self.min_x: return False - elif py < self.miny: + elif py < self.min_y: return False - elif px >= self.maxx: + elif px >= self.max_x: return False - elif py >= self.maxy: + elif py >= self.max_y: return False - if self.obmap[node.x][node.y]: + if self.obstacle_map[node.x][node.y]: return False return True def calc_obstacle_map(self, ox, oy): - self.minx = round(min(ox)) - self.miny = round(min(oy)) - self.maxx = round(max(ox)) - self.maxy = round(max(oy)) - print("minx:", self.minx) - print("miny:", self.miny) - print("maxx:", self.maxx) - print("maxy:", self.maxy) + self.min_x = round(min(ox)) + self.min_y = round(min(oy)) + self.max_x = round(max(ox)) + self.max_y = round(max(oy)) + print("minx:", self.min_x) + print("miny:", self.min_y) + print("maxx:", self.max_x) + print("maxy:", self.max_y) - self.xwidth = round((self.maxx - self.minx)/self.reso) - self.ywidth = round((self.maxy - self.miny)/self.reso) - print("xwidth:", self.xwidth) - print("ywidth:", self.ywidth) + self.x_width = round((self.max_x - self.min_x) / self.resolution) + self.y_width = round((self.max_y - self.min_y) / self.resolution) + print("xwidth:", self.x_width) + print("ywidth:", self.y_width) # obstacle map generation - self.obmap = [[False for i in range(self.ywidth)] - for i in range(self.xwidth)] - for ix in range(self.xwidth): - x = self.calc_position(ix, self.minx) - for iy in range(self.ywidth): - y = self.calc_position(iy, self.miny) + self.obstacle_map = [[False for _ in range(self.y_width)] + for _ in range(self.x_width)] + for ix in range(self.x_width): + x = self.calc_position(ix, self.min_x) + for iy in range(self.y_width): + y = self.calc_position(iy, self.min_y) for iox, ioy in zip(ox, oy): d = math.hypot(iox - x, ioy - y) - if d <= self.rr: - self.obmap[ix][iy] = True + if d <= self.robot_radius: + self.obstacle_map[ix][iy] = True break - def get_motion_model(self): + @staticmethod + def get_motion_model(): # dx, dy, cost motion = [[1, 0, 1], [0, 1, 1], @@ -239,6 +251,7 @@ def main(): if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") + plt.pause(0.01) plt.show() diff --git a/PathPlanning/VisibilityRoadMap/__init__.py b/PathPlanning/VisibilityRoadMap/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/PathPlanning/VisibilityRoadMap/geometry.py b/PathPlanning/VisibilityRoadMap/geometry.py new file mode 100644 index 0000000000..053a2bd70e --- /dev/null +++ b/PathPlanning/VisibilityRoadMap/geometry.py @@ -0,0 +1,44 @@ +class Geometry: + class Point: + def __init__(self, x, y): + self.x = x + self.y = y + + @staticmethod + def is_seg_intersect(p1, q1, p2, q2): + + def on_segment(p, q, r): + if ((q.x <= max(p.x, r.x)) and (q.x >= min(p.x, r.x)) and + (q.y <= max(p.y, r.y)) and (q.y >= min(p.y, r.y))): + return True + return False + + def orientation(p, q, r): + val = (float(q.y - p.y) * (r.x - q.x)) - ( + float(q.x - p.x) * (r.y - q.y)) + if val > 0: + return 1 + elif val < 0: + return 2 + else: + return 0 + + # Find the 4 orientations required for + # the general and special cases + o1 = orientation(p1, q1, p2) + o2 = orientation(p1, q1, q2) + o3 = orientation(p2, q2, p1) + o4 = orientation(p2, q2, q1) + + if (o1 != o2) and (o3 != o4): + return True + if (o1 == 0) and on_segment(p1, p2, q1): + return True + if (o2 == 0) and on_segment(p1, q2, q1): + return True + if (o3 == 0) and on_segment(p2, p1, q2): + return True + if (o4 == 0) and on_segment(p2, q1, q2): + return True + + return False \ No newline at end of file diff --git a/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py b/PathPlanning/VisibilityRoadMap/visibility_road_map.py similarity index 57% rename from PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py rename to PathPlanning/VisibilityRoadMap/visibility_road_map.py index d00e8f43c6..bf9b520a75 100644 --- a/PathPlanning/VisibilityGraphPlanner/visibility_graph_planner.py +++ b/PathPlanning/VisibilityRoadMap/visibility_road_map.py @@ -1,6 +1,6 @@ """ -Visibility Graph Planner +Visibility Road Map Planner author: Atsushi Sakai (@Atsushi_twi) @@ -8,35 +8,47 @@ import os import sys - -sys.path.append(os.path.dirname(os.path.abspath(__file__)) + - "/../VoronoiRoadMap/") - import math import numpy as np import matplotlib.pyplot as plt + +from PathPlanning.VisibilityRoadMap.geometry import Geometry + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../VoronoiRoadMap/") from dijkstra_search import DijkstraSearch show_animation = True -class VisibilityGraphPlanner: +class VisibilityRoadMap: - def __init__(self, robot_radius): + def __init__(self, robot_radius, do_plot=False): self.robot_radius = robot_radius + self.do_plot = do_plot def planning(self, start_x, start_y, goal_x, goal_y, obstacles): - nodes = self.extract_graph_node(start_x, start_y, goal_x, goal_y, - obstacles) - graph = self.generate_graph(nodes, obstacles) - # rx, ry = DijkstraSearch().search(graph) + nodes = self.generate_graph_node(start_x, start_y, goal_x, goal_y, + obstacles) + + road_map_info = self.generate_road_map_info(nodes, obstacles) - rx, ry = [], [] + if show_animation: + self.plot_road_map(nodes, road_map_info) + plt.pause(1.0) + + rx, ry = DijkstraSearch(show_animation).search( + start_x, start_y, + goal_x, goal_y, + [node.x for node in nodes], + [node.y for node in nodes], + road_map_info + ) return rx, ry - def extract_graph_node(self, start_x, start_y, goal_x, goal_y, obstacles): + def generate_graph_node(self, start_x, start_y, goal_x, goal_y, obstacles): # add start and goal as nodes nodes = [DijkstraSearch.Node(start_x, start_y), @@ -57,11 +69,11 @@ def extract_graph_node(self, start_x, start_y, goal_x, goal_y, obstacles): return nodes def calc_vertexes_in_configuration_space(self, x_list, y_list): - x_list=x_list[0:-1] - y_list=y_list[0:-1] + x_list = x_list[0:-1] + y_list = y_list[0:-1] cvx_list, cvy_list = [], [] - n_data=len(x_list) + n_data = len(x_list) for index in range(n_data): offset_x, offset_y = self.calc_offset_xy( @@ -74,31 +86,39 @@ def calc_vertexes_in_configuration_space(self, x_list, y_list): return cvx_list, cvy_list - def generate_graph(self, nodes, obstacles): + def generate_road_map_info(self, nodes, obstacles): - graph = [] + road_map_info_list = [] for target_node in nodes: - for node in nodes: + road_map_info = [] + for node_id, node in enumerate(nodes): + if np.hypot(target_node.x - node.x, + target_node.y - node.y) <= 0.1: + continue + + is_valid = True for obstacle in obstacles: if not self.is_edge_valid(target_node, node, obstacle): - print("bb") + is_valid = False break - print(target_node, node) - print("aa") - plt.plot([target_node.x, node.x],[target_node.y, node.y], "-r") + if is_valid: + road_map_info.append(node_id) + + road_map_info_list.append(road_map_info) - return graph + return road_map_info_list - def is_edge_valid(self, target_node, node, obstacle): + @staticmethod + def is_edge_valid(target_node, node, obstacle): - for i in range(len(obstacle.x_list)-1): - p1 = np.array([target_node.x, target_node.y]) - p2 = np.array([node.x, node.y]) - p3 = np.array([obstacle.x_list[i], obstacle.y_list[i]]) - p4 = np.array([obstacle.y_list[i+1], obstacle.y_list[i+1]]) + for i in range(len(obstacle.x_list) - 1): + p1 = Geometry.Point(target_node.x, target_node.y) + p2 = Geometry.Point(node.x, node.y) + p3 = Geometry.Point(obstacle.x_list[i], obstacle.y_list[i]) + p4 = Geometry.Point(obstacle.x_list[i + 1], obstacle.y_list[i + 1]) - if is_seg_intersect(p1, p2, p3, p4): + if Geometry.is_seg_intersect(p1, p2, p3, p4): return False return True @@ -108,25 +128,18 @@ def calc_offset_xy(self, px, py, x, y, nx, ny): n_vec = math.atan2(ny - y, nx - x) offset_vec = math.atan2(math.sin(p_vec) + math.sin(n_vec), math.cos(p_vec) + math.cos( - n_vec))+math.pi/2.0 + n_vec)) + math.pi / 2.0 offset_x = x + self.robot_radius * math.cos(offset_vec) offset_y = y + self.robot_radius * math.sin(offset_vec) return offset_x, offset_y + @staticmethod + def plot_road_map(nodes, road_map_info_list): + for i, node in enumerate(nodes): + for index in road_map_info_list[i]: + plt.plot([node.x, nodes[index].x], + [node.y, nodes[index].y], "-b") -def is_seg_intersect(a1, a2, b1, b2): - - xdiff = [a1[0] - a2[0], b1[0] - b2[0]] - ydiff = [a1[1] - a2[1], b1[1] - b2[1]] - - def det(a, b): - return a[0] * b[1] - a[1] * b[0] - - div = det(xdiff, ydiff) - if div == 0: - return False - else: - return True class ObstaclePolygon: @@ -161,7 +174,7 @@ def close_polygon(self): self.y_list.append(self.y_list[0]) def plot(self): - plt.plot(self.x_list, self.y_list, "-b") + plt.plot(self.x_list, self.y_list, "-k") def main(): @@ -170,26 +183,36 @@ def main(): # start and goal position sx, sy = 10.0, 10.0 # [m] gx, gy = 50.0, 50.0 # [m] + robot_radius = 5.0 # [m] - obstacles = [ObstaclePolygon( - [20.0, 30.0, 15.0], - [20.0, 20.0, 30.0], - ), ObstaclePolygon( - [30.0, 45.0, 50.0, 40.0], - [50.0, 40.0, 20.0, 40.0], - )] + obstacles = [ + ObstaclePolygon( + [20.0, 30.0, 15.0], + [20.0, 20.0, 30.0], + ), + ObstaclePolygon( + [40.0, 45.0, 50.0, 40.0], + [50.0, 40.0, 20.0, 40.0], + ), + ObstaclePolygon( + [20.0, 30.0, 30.0, 20.0], + [40.0, 45.0, 70.0, 50.0], + ) + ] if show_animation: # pragma: no cover plt.plot(sx, sy, "or") plt.plot(gx, gy, "ob") [ob.plot() for ob in obstacles] + plt.pause(1.0) + + rx, ry = VisibilityRoadMap(robot_radius, do_plot=show_animation).planning( + sx, sy, gx, gy, obstacles) - rx, ry = VisibilityGraphPlanner(robot_radius).planning(sx, sy, gx, gy, - obstacles) - # assert rx, 'Cannot found path' if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") + plt.pause(0.1) plt.axis("equal") plt.show() diff --git a/PathPlanning/VoronoiRoadMap/dijkstra_search.py b/PathPlanning/VoronoiRoadMap/dijkstra_search.py index 7f248cd3cf..f7b8fc48c1 100644 --- a/PathPlanning/VoronoiRoadMap/dijkstra_search.py +++ b/PathPlanning/VoronoiRoadMap/dijkstra_search.py @@ -8,20 +8,21 @@ import matplotlib.pyplot as plt import math +import numpy as np class DijkstraSearch: - class Node: """ Node class for dijkstra search """ - def __init__(self, x, y, cost=None, parent=None): + def __init__(self, x, y, cost=None, parent=None, edge_ids=None): self.x = x self.y = y self.cost = cost self.parent = parent + self.edge_ids = edge_ids def __str__(self): return str(self.x) + "," + str(self.y) + "," + str( @@ -30,71 +31,79 @@ def __str__(self): def __init__(self, show_animation): self.show_animation = show_animation - def search(self, sx, sy, gx, gy, road_map, sample_x, sample_y): + def search(self, sx, sy, gx, gy, node_x, node_y, edge_ids_list): """ + Search shortest path + + sx: start x positions [m] + sy: start y positions [m] gx: goal x position [m] gx: goal x position [m] - ox: x position list of Obstacles [m] - oy: y position list of Obstacles [m] - reso: grid resolution [m] - rr: robot radius[m] + node_x: node x position + node_y: node y position + edge_ids_list: edge_list each item includes a list of edge ids """ start_node = self.Node(sx, sy, 0.0, -1) goal_node = self.Node(gx, gy, 0.0, -1) + current_node = None open_set, close_set = dict(), dict() - open_set[len(road_map) - 2] = start_node + open_set[self.find_id(node_x, node_y, start_node)] = start_node while True: - if not open_set: + if self.has_node_in_set(close_set, goal_node): + print("goal is found!") + goal_node.parent = current_node.parent + goal_node.cost = current_node.cost + break + elif not open_set: print("Cannot find path") break - c_id = min(open_set, key=lambda o: open_set[o].cost) - current = open_set[c_id] + current_id = min(open_set, key=lambda o: open_set[o].cost) + current_node = open_set[current_id] # show graph if self.show_animation and len( close_set.keys()) % 2 == 0: # pragma: no cover - plt.plot(current.x, current.y, "xg") + plt.plot(current_node.x, current_node.y, "xg") # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect( 'key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) - plt.pause(0.001) - - if c_id == (len(road_map) - 1): - print("goal is found!") - goal_node.parent = current.parent - goal_node.cost = current.cost - break + plt.pause(0.1) # Remove the item from the open set - del open_set[c_id] + del open_set[current_id] # Add it to the closed set - close_set[c_id] = current + close_set[current_id] = current_node # expand search grid based on motion model - for i in range(len(road_map[c_id])): - n_id = road_map[c_id][i] - dx = sample_x[n_id] - current.x - dy = sample_y[n_id] - current.y + for i in range(len(edge_ids_list[current_id])): + n_id = edge_ids_list[current_id][i] + dx = node_x[n_id] - current_node.x + dy = node_y[n_id] - current_node.y d = math.hypot(dx, dy) - node = self.Node(sample_x[n_id], sample_y[n_id], - current.cost + d, c_id) + node = self.Node(node_x[n_id], node_y[n_id], + current_node.cost + d, current_id) if n_id in close_set: continue # Otherwise if it is already in the open set if n_id in open_set: if open_set[n_id].cost > node.cost: - open_set[n_id].cost = node.cost - open_set[n_id].parent = c_id + open_set[n_id] = node else: open_set[n_id] = node # generate final course + rx, ry = self.generate_final_path(close_set, goal_node) + + return rx, ry + + @staticmethod + def generate_final_path(close_set, goal_node): rx, ry = [goal_node.x], [goal_node.y] parent = goal_node.parent while parent != -1: @@ -102,5 +111,29 @@ def search(self, sx, sy, gx, gy, road_map, sample_x, sample_y): rx.append(n.x) ry.append(n.y) parent = n.parent - + rx, ry = rx[::-1], ry[::-1] # reverse it return rx, ry + + def has_node_in_set(self, target_set, node): + for key in target_set: + if self.is_same_node(target_set[key], node): + return True + return False + + def find_id(self, node_x_list, node_y_list, target_node): + for i in range(len(node_x_list)): + if self.is_same_node_with_xy(node_x_list[i], node_y_list[i], + target_node): + return i + + @staticmethod + def is_same_node_with_xy(node_x, node_y, node_b): + dist = np.hypot(node_x - node_b.x, + node_y - node_b.y) + return dist <= 0.1 + + @staticmethod + def is_same_node(node_a, node_b): + dist = np.hypot(node_a.x - node_b.x, + node_b.y - node_b.y) + return dist <= 0.1 diff --git a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py index dfac7258f8..d060c8e46c 100644 --- a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py +++ b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py @@ -23,21 +23,22 @@ def __init__(self): self.N_KNN = 10 # number of edge from one sampled point self.MAX_EDGE_LEN = 30.0 # [m] Maximum edge length - def planning(self, sx, sy, gx, gy, ox, oy, rr): + def planning(self, sx, sy, gx, gy, ox, oy, robot_radius): obstacle_tree = KDTree(np.vstack((ox, oy)).T) sample_x, sample_y = self.voronoi_sampling(sx, sy, gx, gy, ox, oy) if show_animation: # pragma: no cover plt.plot(sample_x, sample_y, ".b") - road_map = self.generate_road_map(sample_x, sample_y, rr, obstacle_tree) - - rx, ry = DijkstraSearch(show_animation).search(sx, sy, gx, gy, road_map, - sample_x, sample_y) + road_map_info = self.generate_road_map_info( + sample_x, sample_y, robot_radius, obstacle_tree) + rx, ry = DijkstraSearch(show_animation).search(sx, sy, gx, gy, + sample_x, sample_y, + road_map_info) return rx, ry - def is_collision(self, sx, sy, gx, gy, rr, obstacle_kdtree): + def is_collision(self, sx, sy, gx, gy, rr, obstacle_kd_tree): x = sx y = sy dx = gx - sx @@ -52,25 +53,25 @@ def is_collision(self, sx, sy, gx, gy, rr, obstacle_kdtree): n_step = round(d / D) for i in range(n_step): - ids, dist = obstacle_kdtree.search(np.array([x, y]).reshape(2, 1)) + ids, dist = obstacle_kd_tree.search(np.array([x, y]).reshape(2, 1)) if dist[0] <= rr: return True # collision x += D * math.cos(yaw) y += D * math.sin(yaw) # goal point check - ids, dist = obstacle_kdtree.search(np.array([gx, gy]).reshape(2, 1)) + ids, dist = obstacle_kd_tree.search(np.array([gx, gy]).reshape(2, 1)) if dist[0] <= rr: return True # collision return False # OK - def generate_road_map(self, node_x, node_y, rr, obstacle_tree): + def generate_road_map_info(self, node_x, node_y, rr, obstacle_tree): """ Road map generation - sample_x: [m] x positions of sampled points - sample_y: [m] y positions of sampled points + node_x: [m] x positions of sampled points + node_y: [m] y positions of sampled points rr: Robot Radius[m] obstacle_tree: KDTree object of obstacles """ diff --git a/tests/test_voronoi_path_planner.py b/tests/test_visibility_road_map_planner.py similarity index 100% rename from tests/test_voronoi_path_planner.py rename to tests/test_visibility_road_map_planner.py diff --git a/tests/test_voronoi_road_map_planner.py b/tests/test_voronoi_road_map_planner.py new file mode 100644 index 0000000000..a1f860a108 --- /dev/null +++ b/tests/test_voronoi_road_map_planner.py @@ -0,0 +1,17 @@ +import os +import sys + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../PathPlanning/VisibilityRoadMap/") + +from unittest import TestCase +from PathPlanning.VisibilityRoadMap import visibility_road_map as m + +print(__file__) + + +class Test(TestCase): + + def test1(self): + m.show_animation = False + m.main() From ac1a903ca794ef3e943ce123f06d1bf5443c7a9f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 29 Feb 2020 14:59:40 +0900 Subject: [PATCH 210/940] fixed CI --- PathPlanning/Dijkstra/dijkstra.py | 28 +++++++++---------- PathPlanning/VisibilityRoadMap/geometry.py | 5 ++-- .../VisibilityRoadMap/visibility_road_map.py | 3 +- .../VoronoiRoadMap/dijkstra_search.py | 2 +- 4 files changed, 19 insertions(+), 19 deletions(-) diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index ad3e3a85c8..0ece712ae7 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -24,11 +24,6 @@ def __init__(self, ox, oy, resolution, robot_radius): rr: robot radius[m] """ - self.resolution = resolution - self.robot_radius = robot_radius - self.calc_obstacle_map(ox, oy) - self.motion = self.get_motion_model() - self.min_x = None self.min_y = None self.max_x = None @@ -37,6 +32,11 @@ def __init__(self, ox, oy, resolution, robot_radius): self.y_width = None self.obstacle_map = None + self.resolution = resolution + self.robot_radius = robot_radius + self.calc_obstacle_map(ox, oy) + self.motion = self.get_motion_model() + class Node: def __init__(self, x, y, cost, parent): self.x = x # index of grid @@ -151,11 +151,11 @@ def verify_node(self, node): if px < self.min_x: return False - elif py < self.min_y: + if py < self.min_y: return False - elif px >= self.max_x: + if px >= self.max_x: return False - elif py >= self.max_y: + if py >= self.max_y: return False if self.obstacle_map[node.x][node.y]: @@ -169,15 +169,15 @@ def calc_obstacle_map(self, ox, oy): self.min_y = round(min(oy)) self.max_x = round(max(ox)) self.max_y = round(max(oy)) - print("minx:", self.min_x) - print("miny:", self.min_y) - print("maxx:", self.max_x) - print("maxy:", self.max_y) + print("min_x:", self.min_x) + print("min_y:", self.min_y) + print("max_x:", self.max_x) + print("max_y:", self.max_y) self.x_width = round((self.max_x - self.min_x) / self.resolution) self.y_width = round((self.max_y - self.min_y) / self.resolution) - print("xwidth:", self.x_width) - print("ywidth:", self.y_width) + print("x_width:", self.x_width) + print("y_width:", self.y_width) # obstacle map generation self.obstacle_map = [[False for _ in range(self.y_width)] diff --git a/PathPlanning/VisibilityRoadMap/geometry.py b/PathPlanning/VisibilityRoadMap/geometry.py index 053a2bd70e..c4d73837c9 100644 --- a/PathPlanning/VisibilityRoadMap/geometry.py +++ b/PathPlanning/VisibilityRoadMap/geometry.py @@ -18,10 +18,9 @@ def orientation(p, q, r): float(q.x - p.x) * (r.y - q.y)) if val > 0: return 1 - elif val < 0: + if val < 0: return 2 - else: - return 0 + return 0 # Find the 4 orientations required for # the general and special cases diff --git a/PathPlanning/VisibilityRoadMap/visibility_road_map.py b/PathPlanning/VisibilityRoadMap/visibility_road_map.py index bf9b520a75..fdd214f757 100644 --- a/PathPlanning/VisibilityRoadMap/visibility_road_map.py +++ b/PathPlanning/VisibilityRoadMap/visibility_road_map.py @@ -204,7 +204,8 @@ def main(): if show_animation: # pragma: no cover plt.plot(sx, sy, "or") plt.plot(gx, gy, "ob") - [ob.plot() for ob in obstacles] + for ob in obstacles: + ob.plot() plt.pause(1.0) rx, ry = VisibilityRoadMap(robot_radius, do_plot=show_animation).planning( diff --git a/PathPlanning/VoronoiRoadMap/dijkstra_search.py b/PathPlanning/VoronoiRoadMap/dijkstra_search.py index f7b8fc48c1..7bf5425ebf 100644 --- a/PathPlanning/VoronoiRoadMap/dijkstra_search.py +++ b/PathPlanning/VoronoiRoadMap/dijkstra_search.py @@ -121,7 +121,7 @@ def has_node_in_set(self, target_set, node): return False def find_id(self, node_x_list, node_y_list, target_node): - for i in range(len(node_x_list)): + for i, _ in enumerate(node_x_list): if self.is_same_node_with_xy(node_x_list[i], node_y_list[i], target_node): return i From 881308bc42764ee2652d4f17d5a99d0891fb8e93 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 29 Feb 2020 20:37:03 +0900 Subject: [PATCH 211/940] fixed CI --- PathPlanning/VisibilityRoadMap/visibility_road_map.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/PathPlanning/VisibilityRoadMap/visibility_road_map.py b/PathPlanning/VisibilityRoadMap/visibility_road_map.py index fdd214f757..a677804440 100644 --- a/PathPlanning/VisibilityRoadMap/visibility_road_map.py +++ b/PathPlanning/VisibilityRoadMap/visibility_road_map.py @@ -34,7 +34,7 @@ def planning(self, start_x, start_y, goal_x, goal_y, obstacles): road_map_info = self.generate_road_map_info(nodes, obstacles) - if show_animation: + if self.do_plot: self.plot_road_map(nodes, road_map_info) plt.pause(1.0) @@ -197,7 +197,7 @@ def main(): ), ObstaclePolygon( [20.0, 30.0, 30.0, 20.0], - [40.0, 45.0, 70.0, 50.0], + [40.0, 45.0, 60.0, 50.0], ) ] @@ -206,6 +206,7 @@ def main(): plt.plot(gx, gy, "ob") for ob in obstacles: ob.plot() + plt.axis("equal") plt.pause(1.0) rx, ry = VisibilityRoadMap(robot_radius, do_plot=show_animation).planning( @@ -214,7 +215,6 @@ def main(): if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") plt.pause(0.1) - plt.axis("equal") plt.show() From 487a7e4141dc4e2a0ae887e7fec98251900362b7 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 29 Feb 2020 21:12:30 +0900 Subject: [PATCH 212/940] Update users_comments.md --- users_comments.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/users_comments.md b/users_comments.md index 792f3a4d0d..056a896e94 100644 --- a/users_comments.md +++ b/users_comments.md @@ -23,6 +23,8 @@ If you found other users, please make an issue to let me know. - [CSCI/ARTI 4530/6530: Introduction to Robotics (Fall 2018), University of Georgia ](http://cobweb.cs.uga.edu/~ramviyas/csci_x530.html) +- [CIT Modules & Programmes \- COMP9073 \- Automation with Python](https://courses.cit.ie/index.cfm/page/module/moduleId/14416) + # Stargazers location map You can check stargazer's locations of this project from: @@ -415,3 +417,4 @@ URL: https://pdfs.semanticscholar.org/5c06/f3cb9542a51e1bf1a32523c1bc7fea6cecc5. - Real-time Model Predictive Control (MPC), ACADO, Python | Work-is-Playing http://grauonline.de/wordpress/?page_id=3244 +- 💡 Greatest of GitHub - Python Robotics (Amazing!) - YouTube https://www.youtube.com/watch?v=f_pPaYx6Gu0&feature=emb_logo From 80ebc55c2f8c986ef58aae28c43dcf0bbbaa85d1 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 1 Mar 2020 21:05:04 +0900 Subject: [PATCH 213/940] clean up codes --- PathPlanning/BSplinePath/bspline_path.py | 25 +++++++++++------------- 1 file changed, 11 insertions(+), 14 deletions(-) diff --git a/PathPlanning/BSplinePath/bspline_path.py b/PathPlanning/BSplinePath/bspline_path.py index 0c453ad436..2c3d7ad68e 100644 --- a/PathPlanning/BSplinePath/bspline_path.py +++ b/PathPlanning/BSplinePath/bspline_path.py @@ -1,6 +1,6 @@ """ -Path Plannting with B-Spline +Path Planning with B-Spline author: Atsushi Sakai (@Atsushi_twi) @@ -8,16 +8,13 @@ import numpy as np import matplotlib.pyplot as plt -import scipy.interpolate as si +import scipy.interpolate as scipy_interpolate -# parameter -N = 3 # B Spline order - -def bspline_planning(x, y, sn): +def b_spline_planning(x, y, sn, degree=3): t = range(len(x)) - x_tup = si.splrep(t, x, k=N) - y_tup = si.splrep(t, y, k=N) + x_tup = scipy_interpolate.splrep(t, x, k=degree) + y_tup = scipy_interpolate.splrep(t, y, k=degree) x_list = list(x_tup) xl = x.tolist() @@ -28,8 +25,8 @@ def bspline_planning(x, y, sn): y_list[1] = yl + [0.0, 0.0, 0.0, 0.0] ipl_t = np.linspace(0.0, len(x) - 1, sn) - rx = si.splev(ipl_t, x_list) - ry = si.splev(ipl_t, y_list) + rx = scipy_interpolate.splev(ipl_t, x_list) + ry = scipy_interpolate.splev(ipl_t, y_list) return rx, ry @@ -37,14 +34,14 @@ def bspline_planning(x, y, sn): def main(): print(__file__ + " start!!") # way points - x = np.array([-1.0, 3.0, 4.0, 2.0, 1.0]) - y = np.array([0.0, -3.0, 1.0, 1.0, 3.0]) + way_x = np.array([-1.0, 3.0, 4.0, 2.0, 1.0]) + way_y = np.array([0.0, -3.0, 1.0, 1.0, 3.0]) sn = 100 # sampling number - rx, ry = bspline_planning(x, y, sn) + rx, ry = b_spline_planning(way_x, way_y, sn) # show results - plt.plot(x, y, '-og', label="Waypoints") + plt.plot(way_x, way_y, '-og', label="way points") plt.plot(rx, ry, '-r', label="B-Spline path") plt.grid(True) plt.legend() From 869650ffa93c444bafd8eea2a6f9868c0d53bb61 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 7 Mar 2020 21:57:26 +0900 Subject: [PATCH 214/940] Update users_comments.md --- users_comments.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/users_comments.md b/users_comments.md index 056a896e94..44e9355ec1 100644 --- a/users_comments.md +++ b/users_comments.md @@ -409,6 +409,9 @@ URL: https://arxiv.org/abs/1910.01557 8. Hahn, Carsten, et al. "Dynamic Path Planning with Stable Growing Neural Gas." (2019). URL: https://pdfs.semanticscholar.org/5c06/f3cb9542a51e1bf1a32523c1bc7fea6cecc5.pdf +9. Brijen Thananjeyan, et al. "ABC-LMPC: Safe Sample-Based Learning MPC for Stochastic Nonlinear Dynamical Systems with Adjustable Boundary Conditions" +URL: https://arxiv.org/pdf/2003.01410.pdf + # Others - Autonomous Vehicle Readings https://richardkelley.io/readings From 6cb903a8143064c8eaba811b7f894bd1539ee2ae Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Mar 2020 22:27:07 +0900 Subject: [PATCH 215/940] add mypy setting and update bspline_path.py --- .github/workflows/mypycheck.yml | 3 ++ PathPlanning/BSplinePath/bspline_path.py | 57 ++++++++++++++++++------ mypy.ini | 2 + 3 files changed, 49 insertions(+), 13 deletions(-) create mode 100644 .github/workflows/mypycheck.yml create mode 100644 mypy.ini diff --git a/.github/workflows/mypycheck.yml b/.github/workflows/mypycheck.yml new file mode 100644 index 0000000000..26e5566015 --- /dev/null +++ b/.github/workflows/mypycheck.yml @@ -0,0 +1,3 @@ +- name: Mypy Check + uses: jpetrucciani/mypy-check@0.761 + diff --git a/PathPlanning/BSplinePath/bspline_path.py b/PathPlanning/BSplinePath/bspline_path.py index 2c3d7ad68e..d4b24c7645 100644 --- a/PathPlanning/BSplinePath/bspline_path.py +++ b/PathPlanning/BSplinePath/bspline_path.py @@ -1,6 +1,6 @@ """ -Path Planning with B-Spline +Path Planner with B-Spline author: Atsushi Sakai (@Atsushi_twi) @@ -11,38 +11,69 @@ import scipy.interpolate as scipy_interpolate -def b_spline_planning(x, y, sn, degree=3): +def approximate_b_spline_path(x: list, y: list, n_path_points: int, + degree: int = 3) -> tuple: + """ + approximate points with a B-Spline path + + :param x: x position list of approximated points + :param y: y position list of approximated points + :param n_path_points: number of path points + :param degree: (Optional) B Spline curve degree + :return: x and y position list of the result path + """ t = range(len(x)) x_tup = scipy_interpolate.splrep(t, x, k=degree) y_tup = scipy_interpolate.splrep(t, y, k=degree) x_list = list(x_tup) - xl = x.tolist() - x_list[1] = xl + [0.0, 0.0, 0.0, 0.0] + x_list[1] = x + [0.0, 0.0, 0.0, 0.0] y_list = list(y_tup) - yl = y.tolist() - y_list[1] = yl + [0.0, 0.0, 0.0, 0.0] + y_list[1] = y + [0.0, 0.0, 0.0, 0.0] - ipl_t = np.linspace(0.0, len(x) - 1, sn) + ipl_t = np.linspace(0.0, len(x) - 1, n_path_points) rx = scipy_interpolate.splev(ipl_t, x_list) ry = scipy_interpolate.splev(ipl_t, y_list) return rx, ry +def interpolate_b_spline_path(x: list, y: list, n_path_points: int, + degree: int = 3) -> tuple: + """ + interpolate points with a B-Spline path + + :param x: x positions of interpolated points + :param y: y positions of interpolated points + :param n_path_points: number of path points + :param degree: B-Spline degree + :return: x and y position list of the result path + """ + ipl_t = np.linspace(0.0, len(x) - 1, len(x)) + spl_i_x = scipy_interpolate.make_interp_spline(ipl_t, x, k=degree) + spl_i_y = scipy_interpolate.make_interp_spline(ipl_t, y, k=degree) + + travel = np.linspace(0.0, len(x) - 1, n_path_points) + return spl_i_x(travel), spl_i_y(travel) + + def main(): print(__file__ + " start!!") # way points - way_x = np.array([-1.0, 3.0, 4.0, 2.0, 1.0]) - way_y = np.array([0.0, -3.0, 1.0, 1.0, 3.0]) - sn = 100 # sampling number + way_point_x = [-1.0, 3.0, 4.0, 2.0, 1.0] + way_point_y = [0.0, -3.0, 1.0, 1.0, 3.0] + n_course_point = 100 # sampling number - rx, ry = b_spline_planning(way_x, way_y, sn) + rax, ray = approximate_b_spline_path(way_point_x, way_point_y, + n_course_point) + rix, riy = interpolate_b_spline_path(way_point_x, way_point_y, + n_course_point) # show results - plt.plot(way_x, way_y, '-og', label="way points") - plt.plot(rx, ry, '-r', label="B-Spline path") + plt.plot(way_point_x, way_point_y, '-og', label="way points") + plt.plot(rax, ray, '-r', label="Approximated B-Spline path") + plt.plot(rix, riy, '-b', label="Interpolated B-Spline path") plt.grid(True) plt.legend() plt.axis("equal") diff --git a/mypy.ini b/mypy.ini new file mode 100644 index 0000000000..1215375ed9 --- /dev/null +++ b/mypy.ini @@ -0,0 +1,2 @@ +[mypy] +ignore_missing_imports = True \ No newline at end of file From ba13817862c503c79da0e847d1afd7555cb8015e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Mar 2020 22:29:03 +0900 Subject: [PATCH 216/940] fixed git hub action --- .github/workflows/mypycheck.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/mypycheck.yml b/.github/workflows/mypycheck.yml index 26e5566015..649028674a 100644 --- a/.github/workflows/mypycheck.yml +++ b/.github/workflows/mypycheck.yml @@ -1,3 +1,3 @@ -- name: Mypy Check - uses: jpetrucciani/mypy-check@0.761 +name: Mypy Check +uses: jpetrucciani/mypy-check@0.761 From 5f253ef56229b44cfb5e6ba5a317de5c042efad9 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Mar 2020 22:31:17 +0900 Subject: [PATCH 217/940] fixed git hub action --- .github/workflows/mypycheck.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/mypycheck.yml b/.github/workflows/mypycheck.yml index 649028674a..0e26c1e241 100644 --- a/.github/workflows/mypycheck.yml +++ b/.github/workflows/mypycheck.yml @@ -1,3 +1,4 @@ name: Mypy Check +on: [push] uses: jpetrucciani/mypy-check@0.761 From aad8d4face65a0adf571b01a54b32f307876dcb2 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Mar 2020 22:34:00 +0900 Subject: [PATCH 218/940] fixed git hub action --- .github/workflows/mypycheck.yml | 4 ---- .github/workflows/pythonpackage.yml | 6 +++++- 2 files changed, 5 insertions(+), 5 deletions(-) delete mode 100644 .github/workflows/mypycheck.yml diff --git a/.github/workflows/mypycheck.yml b/.github/workflows/mypycheck.yml deleted file mode 100644 index 0e26c1e241..0000000000 --- a/.github/workflows/mypycheck.yml +++ /dev/null @@ -1,4 +0,0 @@ -name: Mypy Check -on: [push] -uses: jpetrucciani/mypy-check@0.761 - diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index a3203ff1ac..d03d5ea14c 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -29,6 +29,10 @@ jobs: # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - name: install coverage - run: pip install coverage + run: pip install coverage + - name: Mypy Check + uses: jpetrucciani/mypy-check@0.761 - name: Test run: bash runtests.sh + + From d7dddc8772b04a6895902ea6e3f72be1ebf21a86 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Mar 2020 22:51:47 +0900 Subject: [PATCH 219/940] mypy fail test --- PathPlanning/BSplinePath/bspline_path.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/BSplinePath/bspline_path.py b/PathPlanning/BSplinePath/bspline_path.py index d4b24c7645..7c59e99bbb 100644 --- a/PathPlanning/BSplinePath/bspline_path.py +++ b/PathPlanning/BSplinePath/bspline_path.py @@ -11,7 +11,7 @@ import scipy.interpolate as scipy_interpolate -def approximate_b_spline_path(x: list, y: list, n_path_points: int, +def approximate_b_spline_path(x: int, y: list, n_path_points: int, degree: int = 3) -> tuple: """ approximate points with a B-Spline path From 0b9a0c88d6c5fc029bf9b0fb305e977c3b641d3c Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Mar 2020 23:00:32 +0900 Subject: [PATCH 220/940] mypy fail test --- .github/workflows/pythonpackage.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index d03d5ea14c..af761ec7b3 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -32,6 +32,8 @@ jobs: run: pip install coverage - name: Mypy Check uses: jpetrucciani/mypy-check@0.761 + with: + path: './AerialNavigation ./PathPlanning' - name: Test run: bash runtests.sh From 8dc23fec2135f8c376d7aaa7696104d3deb40a8b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Mar 2020 23:15:13 +0900 Subject: [PATCH 221/940] mypy fail test --- .github/workflows/pythonpackage.yml | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index af761ec7b3..c81ce8930d 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -30,11 +30,12 @@ jobs: flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - name: install coverage run: pip install coverage - - name: Mypy Check - uses: jpetrucciani/mypy-check@0.761 - with: - path: './AerialNavigation ./PathPlanning' - - name: Test + - name: install mypy + run: pip install mypy + - name: mypy check + run: | + - find . -name "*.py" | xargs mypy + - name: do all unit tests run: bash runtests.sh From c36aa27d605628238ff4d05e66b2f59d91fc30b3 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 Mar 2020 23:20:10 +0900 Subject: [PATCH 222/940] mypy fail test --- .github/workflows/pythonpackage.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index c81ce8930d..1844e53820 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -34,7 +34,7 @@ jobs: run: pip install mypy - name: mypy check run: | - - find . -name "*.py" | xargs mypy + find . -name "*.py" | xargs mypy - name: do all unit tests run: bash runtests.sh From 14ffc4a2d4e202c49c0ae385b3ba62144a1cf86c Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 9 Mar 2020 22:57:35 +0900 Subject: [PATCH 223/940] mypy fix test --- .../{NLinkArm.py => NLinkArm3d.py} | 116 +++++---- ArmNavigation/n_joint_arm_3d/__init__py.py | 0 .../random_forward_kinematics.py | 21 +- .../random_inverse_kinematics.py | 15 +- .../n_joint_arm_to_point_control/__init__.py | 0 PathPlanning/AStar/a_star.py | 12 +- PathPlanning/BSplinePath/bspline_path.py | 2 +- PathPlanning/CubicSpline/__init__.py | 0 .../cubic_spline_planner.py | 239 ------------------ .../frenet_optimal_trajectory.py | 109 ++++---- PathPlanning/HybridAStar/__init__.py | 0 .../{a_star.py => a_star_heuristic.py} | 0 PathPlanning/HybridAStar/hybrid_a_star.py | 2 +- 13 files changed, 150 insertions(+), 366 deletions(-) rename ArmNavigation/n_joint_arm_3d/{NLinkArm.py => NLinkArm3d.py} (75%) create mode 100644 ArmNavigation/n_joint_arm_3d/__init__py.py create mode 100644 ArmNavigation/n_joint_arm_to_point_control/__init__.py create mode 100644 PathPlanning/CubicSpline/__init__.py delete mode 100644 PathPlanning/FrenetOptimalTrajectory/cubic_spline_planner.py create mode 100644 PathPlanning/HybridAStar/__init__.py rename PathPlanning/HybridAStar/{a_star.py => a_star_heuristic.py} (100%) diff --git a/ArmNavigation/n_joint_arm_3d/NLinkArm.py b/ArmNavigation/n_joint_arm_3d/NLinkArm3d.py similarity index 75% rename from ArmNavigation/n_joint_arm_3d/NLinkArm.py rename to ArmNavigation/n_joint_arm_3d/NLinkArm3d.py index da562d9f17..b411cd7114 100644 --- a/ArmNavigation/n_joint_arm_3d/NLinkArm.py +++ b/ArmNavigation/n_joint_arm_3d/NLinkArm3d.py @@ -7,6 +7,7 @@ from mpl_toolkits.mplot3d import Axes3D import matplotlib.pyplot as plt + class Link: def __init__(self, dh_params): self.dh_params_ = dh_params @@ -28,16 +29,22 @@ def transformation_matrix(self): return trans - def basic_jacobian(self, trans_prev, ee_pos): - pos_prev = np.array([trans_prev[0, 3], trans_prev[1, 3], trans_prev[2, 3]]) - z_axis_prev = np.array([trans_prev[0, 2], trans_prev[1, 2], trans_prev[2, 2]]) + @staticmethod + def basic_jacobian(trans_prev, ee_pos): + pos_prev = np.array( + [trans_prev[0, 3], trans_prev[1, 3], trans_prev[2, 3]]) + z_axis_prev = np.array( + [trans_prev[0, 2], trans_prev[1, 2], trans_prev[2, 2]]) - basic_jacobian = np.hstack((np.cross(z_axis_prev, ee_pos - pos_prev), z_axis_prev)) + basic_jacobian = np.hstack( + (np.cross(z_axis_prev, ee_pos - pos_prev), z_axis_prev)) return basic_jacobian - + class NLinkArm: def __init__(self, dh_params_list): + self.fig = plt.figure() + self.ax = Axes3D(self.fig) self.link_list = [] for i in range(len(dh_params_list)): self.link_list.append(Link(dh_params_list[i])) @@ -47,7 +54,7 @@ def transformation_matrix(self): for i in range(len(self.link_list)): trans = np.dot(trans, self.link_list[i].transformation_matrix()) return trans - + def forward_kinematics(self, plot=False): trans = self.transformation_matrix() @@ -57,15 +64,12 @@ def forward_kinematics(self, plot=False): alpha, beta, gamma = self.euler_angle() if plot: - self.fig = plt.figure() - self.ax = Axes3D(self.fig) - x_list = [] y_list = [] z_list = [] - + trans = np.identity(4) - + x_list.append(trans[0, 3]) y_list.append(trans[1, 3]) z_list.append(trans[2, 3]) @@ -74,14 +78,15 @@ def forward_kinematics(self, plot=False): x_list.append(trans[0, 3]) y_list.append(trans[1, 3]) z_list.append(trans[2, 3]) - - self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4, mew=0.5) + + self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4, + mew=0.5) self.ax.plot([0], [0], [0], "o") - + self.ax.set_xlim(-1, 1) self.ax.set_ylim(-1, 1) self.ax.set_zlim(-1, 1) - + plt.show() return [x, y, z, alpha, beta, gamma] @@ -89,41 +94,45 @@ def forward_kinematics(self, plot=False): def basic_jacobian(self): ee_pos = self.forward_kinematics()[0:3] basic_jacobian_mat = [] - - trans = np.identity(4) + + trans = np.identity(4) for i in range(len(self.link_list)): - basic_jacobian_mat.append(self.link_list[i].basic_jacobian(trans, ee_pos)) + basic_jacobian_mat.append( + self.link_list[i].basic_jacobian(trans, ee_pos)) trans = np.dot(trans, self.link_list[i].transformation_matrix()) - + return np.array(basic_jacobian_mat).T def inverse_kinematics(self, ref_ee_pose, plot=False): for cnt in range(500): ee_pose = self.forward_kinematics() diff_pose = np.array(ref_ee_pose) - ee_pose - + basic_jacobian_mat = self.basic_jacobian() alpha, beta, gamma = self.euler_angle() - - K_zyz = np.array([[0, -math.sin(alpha), math.cos(alpha) * math.sin(beta)], - [0, math.cos(alpha), math.sin(alpha) * math.sin(beta)], - [1, 0, math.cos(beta)]]) + + K_zyz = np.array( + [[0, -math.sin(alpha), math.cos(alpha) * math.sin(beta)], + [0, math.cos(alpha), math.sin(alpha) * math.sin(beta)], + [1, 0, math.cos(beta)]]) K_alpha = np.identity(6) K_alpha[3:, 3:] = K_zyz - theta_dot = np.dot(np.dot(np.linalg.pinv(basic_jacobian_mat), K_alpha), np.array(diff_pose)) + theta_dot = np.dot( + np.dot(np.linalg.pinv(basic_jacobian_mat), K_alpha), + np.array(diff_pose)) self.update_joint_angles(theta_dot / 100.) - + if plot: self.fig = plt.figure() self.ax = Axes3D(self.fig) - + x_list = [] y_list = [] z_list = [] - + trans = np.identity(4) - + x_list.append(trans[0, 3]) y_list.append(trans[1, 3]) z_list.append(trans[2, 3]) @@ -132,30 +141,36 @@ def inverse_kinematics(self, ref_ee_pose, plot=False): x_list.append(trans[0, 3]) y_list.append(trans[1, 3]) z_list.append(trans[2, 3]) - - self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4, mew=0.5) + + self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4, + mew=0.5) self.ax.plot([0], [0], [0], "o") - + self.ax.set_xlim(-1, 1) self.ax.set_ylim(-1, 1) self.ax.set_zlim(-1, 1) - - self.ax.plot([ref_ee_pose[0]], [ref_ee_pose[1]], [ref_ee_pose[2]], "o") + + self.ax.plot([ref_ee_pose[0]], [ref_ee_pose[1]], [ref_ee_pose[2]], + "o") plt.show() - + def euler_angle(self): trans = self.transformation_matrix() - + alpha = math.atan2(trans[1][2], trans[0][2]) - if not (-math.pi / 2 <= alpha and alpha <= math.pi / 2): + if not (-math.pi / 2 <= alpha <= math.pi / 2): alpha = math.atan2(trans[1][2], trans[0][2]) + math.pi - if not (-math.pi / 2 <= alpha and alpha <= math.pi / 2): + if not (-math.pi / 2 <= alpha <= math.pi / 2): alpha = math.atan2(trans[1][2], trans[0][2]) - math.pi - beta = math.atan2(trans[0][2] * math.cos(alpha) + trans[1][2] * math.sin(alpha), trans[2][2]) - gamma = math.atan2(-trans[0][0] * math.sin(alpha) + trans[1][0] * math.cos(alpha), -trans[0][1] * math.sin(alpha) + trans[1][1] * math.cos(alpha)) - + beta = math.atan2( + trans[0][2] * math.cos(alpha) + trans[1][2] * math.sin(alpha), + trans[2][2]) + gamma = math.atan2( + -trans[0][0] * math.sin(alpha) + trans[1][0] * math.cos(alpha), + -trans[0][1] * math.sin(alpha) + trans[1][1] * math.cos(alpha)) + return alpha, beta, gamma - + def set_joint_angles(self, joint_angle_list): for i in range(len(self.link_list)): self.link_list[i].dh_params_[0] = joint_angle_list[i] @@ -163,17 +178,17 @@ def set_joint_angles(self, joint_angle_list): def update_joint_angles(self, diff_joint_angle_list): for i in range(len(self.link_list)): self.link_list[i].dh_params_[0] += diff_joint_angle_list[i] - + def plot(self): self.fig = plt.figure() self.ax = Axes3D(self.fig) - + x_list = [] y_list = [] z_list = [] trans = np.identity(4) - + x_list.append(trans[0, 3]) y_list.append(trans[1, 3]) z_list.append(trans[2, 3]) @@ -182,15 +197,16 @@ def plot(self): x_list.append(trans[0, 3]) y_list.append(trans[1, 3]) z_list.append(trans[2, 3]) - - self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4, mew=0.5) + + self.ax.plot(x_list, y_list, z_list, "o-", color="#00aa00", ms=4, + mew=0.5) self.ax.plot([0], [0], [0], "o") self.ax.set_xlabel("x") self.ax.set_ylabel("y") - self.ax.set_zlabel("z") - + self.ax.set_zlabel("z") + self.ax.set_xlim(-1, 1) self.ax.set_ylim(-1, 1) - self.ax.set_zlim(-1, 1) + self.ax.set_zlim(-1, 1) plt.show() diff --git a/ArmNavigation/n_joint_arm_3d/__init__py.py b/ArmNavigation/n_joint_arm_3d/__init__py.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py index 87907f803b..b3426e53e8 100644 --- a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py +++ b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py @@ -3,9 +3,10 @@ Author: Takayuki Murooka (takayuki5168) """ import math -from NLinkArm import NLinkArm +from NLinkArm3d import NLinkArm import random + def random_val(min_val, max_val): return min_val + random.random() * (max_val - min_val) @@ -14,17 +15,17 @@ def random_val(min_val, max_val): print("Start solving Forward Kinematics 10 times") # init NLinkArm with Denavit-Hartenberg parameters of PR2 - n_link_arm = NLinkArm([[0., -math.pi/2, .1, 0.], - [math.pi/2, math.pi/2, 0., 0.], - [0., -math.pi/2, 0., .4], - [0., math.pi/2, 0., 0.], - [0., -math.pi/2, 0., .321], - [0., math.pi/2, 0., 0.], + n_link_arm = NLinkArm([[0., -math.pi / 2, .1, 0.], + [math.pi / 2, math.pi / 2, 0., 0.], + [0., -math.pi / 2, 0., .4], + [0., math.pi / 2, 0., 0.], + [0., -math.pi / 2, 0., .321], + [0., math.pi / 2, 0., 0.], [0., 0., 0., 0.]]) # execute FK 10 times for i in range(10): - n_link_arm.set_joint_angles([random_val(-1, 1) for j in range(len(n_link_arm.link_list))]) - - ee_pose = n_link_arm.forward_kinematics(plot=True) + n_link_arm.set_joint_angles( + [random_val(-1, 1) for j in range(len(n_link_arm.link_list))]) + ee_pose = n_link_arm.forward_kinematics(plot=True) diff --git a/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py index 44be22709f..a3838a6a38 100644 --- a/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py +++ b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py @@ -3,23 +3,24 @@ Author: Takayuki Murooka (takayuki5168) """ import math -from NLinkArm import NLinkArm +from NLinkArm3d import NLinkArm import random def random_val(min_val, max_val): return min_val + random.random() * (max_val - min_val) + if __name__ == "__main__": print("Start solving Inverse Kinematics 10 times") # init NLinkArm with Denavit-Hartenberg parameters of PR2 - n_link_arm = NLinkArm([[0., -math.pi/2, .1, 0.], - [math.pi/2, math.pi/2, 0., 0.], - [0., -math.pi/2, 0., .4], - [0., math.pi/2, 0., 0.], - [0., -math.pi/2, 0., .321], - [0., math.pi/2, 0., 0.], + n_link_arm = NLinkArm([[0., -math.pi / 2, .1, 0.], + [math.pi / 2, math.pi / 2, 0., 0.], + [0., -math.pi / 2, 0., .4], + [0., math.pi / 2, 0., 0.], + [0., -math.pi / 2, 0., .321], + [0., math.pi / 2, 0., 0.], [0., 0., 0., 0.]]) # execute IK 10 times diff --git a/ArmNavigation/n_joint_arm_to_point_control/__init__.py b/ArmNavigation/n_joint_arm_to_point_control/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py index 2229d63306..55881f4e49 100644 --- a/PathPlanning/AStar/a_star.py +++ b/PathPlanning/AStar/a_star.py @@ -41,7 +41,8 @@ def __init__(self, x, y, cost, pind): self.pind = pind def __str__(self): - return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind) + return str(self.x) + "," + str(self.y) + "," + str( + self.cost) + "," + str(self.pind) def planning(self, sx, sy, gx, gy): """ @@ -72,7 +73,10 @@ def planning(self, sx, sy, gx, gy): break c_id = min( - open_set, key=lambda o: open_set[o].cost + self.calc_heuristic(ngoal, open_set[o])) + open_set, + key=lambda o: open_set[o].cost + self.calc_heuristic(ngoal, + open_set[ + o])) current = open_set[c_id] # show graph @@ -81,7 +85,8 @@ def planning(self, sx, sy, gx, gy): self.calc_grid_position(current.y, self.miny), "xc") # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + lambda event: [exit( + 0) if event.key == 'escape' else None]) if len(closed_set.keys()) % 10 == 0: plt.pause(0.001) @@ -104,7 +109,6 @@ def planning(self, sx, sy, gx, gy): current.cost + self.motion[i][2], c_id) n_id = self.calc_grid_index(node) - # If the node is not safe, do nothing if not self.verify_node(node): continue diff --git a/PathPlanning/BSplinePath/bspline_path.py b/PathPlanning/BSplinePath/bspline_path.py index 7c59e99bbb..d4b24c7645 100644 --- a/PathPlanning/BSplinePath/bspline_path.py +++ b/PathPlanning/BSplinePath/bspline_path.py @@ -11,7 +11,7 @@ import scipy.interpolate as scipy_interpolate -def approximate_b_spline_path(x: int, y: list, n_path_points: int, +def approximate_b_spline_path(x: list, y: list, n_path_points: int, degree: int = 3) -> tuple: """ approximate points with a B-Spline path diff --git a/PathPlanning/CubicSpline/__init__.py b/PathPlanning/CubicSpline/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/PathPlanning/FrenetOptimalTrajectory/cubic_spline_planner.py b/PathPlanning/FrenetOptimalTrajectory/cubic_spline_planner.py deleted file mode 100644 index 98ef8c4ecf..0000000000 --- a/PathPlanning/FrenetOptimalTrajectory/cubic_spline_planner.py +++ /dev/null @@ -1,239 +0,0 @@ -""" -cubic spline planner - -Author: Atsushi Sakai - -""" -import math -import numpy as np -import bisect - - -class Spline: - """ - Cubic Spline class - """ - - def __init__(self, x, y): - self.b, self.c, self.d, self.w = [], [], [], [] - - self.x = x - self.y = y - - self.nx = len(x) # dimension of x - h = np.diff(x) - - # calc coefficient c - self.a = [iy for iy in y] - - # calc coefficient c - A = self.__calc_A(h) - B = self.__calc_B(h) - self.c = np.linalg.solve(A, B) - # print(self.c1) - - # calc spline coefficient b and d - for i in range(self.nx - 1): - self.d.append((self.c[i + 1] - self.c[i]) / (3.0 * h[i])) - tb = (self.a[i + 1] - self.a[i]) / h[i] - h[i] * \ - (self.c[i + 1] + 2.0 * self.c[i]) / 3.0 - self.b.append(tb) - - def calc(self, t): - """ - Calc position - - if t is outside of the input x, return None - - """ - - if t < self.x[0]: - return None - elif t > self.x[-1]: - return None - - i = self.__search_index(t) - dx = t - self.x[i] - result = self.a[i] + self.b[i] * dx + \ - self.c[i] * dx ** 2.0 + self.d[i] * dx ** 3.0 - - return result - - def calcd(self, t): - """ - Calc first derivative - - if t is outside of the input x, return None - """ - - if t < self.x[0]: - return None - elif t > self.x[-1]: - return None - - i = self.__search_index(t) - dx = t - self.x[i] - result = self.b[i] + 2.0 * self.c[i] * dx + 3.0 * self.d[i] * dx ** 2.0 - return result - - def calcdd(self, t): - """ - Calc second derivative - """ - - if t < self.x[0]: - return None - elif t > self.x[-1]: - return None - - i = self.__search_index(t) - dx = t - self.x[i] - result = 2.0 * self.c[i] + 6.0 * self.d[i] * dx - return result - - def __search_index(self, x): - """ - search data segment index - """ - return bisect.bisect(self.x, x) - 1 - - def __calc_A(self, h): - """ - calc matrix A for spline coefficient c - """ - A = np.zeros((self.nx, self.nx)) - A[0, 0] = 1.0 - for i in range(self.nx - 1): - if i != (self.nx - 2): - A[i + 1, i + 1] = 2.0 * (h[i] + h[i + 1]) - A[i + 1, i] = h[i] - A[i, i + 1] = h[i] - - A[0, 1] = 0.0 - A[self.nx - 1, self.nx - 2] = 0.0 - A[self.nx - 1, self.nx - 1] = 1.0 - # print(A) - return A - - def __calc_B(self, h): - """ - calc matrix B for spline coefficient c - """ - B = np.zeros(self.nx) - for i in range(self.nx - 2): - B[i + 1] = 3.0 * (self.a[i + 2] - self.a[i + 1]) / \ - h[i + 1] - 3.0 * (self.a[i + 1] - self.a[i]) / h[i] - # print(B) - return B - - -class Spline2D: - """ - 2D Cubic Spline class - - """ - - def __init__(self, x, y): - self.s = self.__calc_s(x, y) - self.sx = Spline(self.s, x) - self.sy = Spline(self.s, y) - - def __calc_s(self, x, y): - dx = np.diff(x) - dy = np.diff(y) - self.ds = [math.sqrt(idx ** 2 + idy ** 2) - for (idx, idy) in zip(dx, dy)] - s = [0] - s.extend(np.cumsum(self.ds)) - return s - - def calc_position(self, s): - """ - calc position - """ - x = self.sx.calc(s) - y = self.sy.calc(s) - - return x, y - - def calc_curvature(self, s): - """ - calc curvature - """ - dx = self.sx.calcd(s) - ddx = self.sx.calcdd(s) - dy = self.sy.calcd(s) - ddy = self.sy.calcdd(s) - k = (ddy * dx - ddx * dy) / (dx ** 2 + dy ** 2) - return k - - def calc_yaw(self, s): - """ - calc yaw - """ - dx = self.sx.calcd(s) - dy = self.sy.calcd(s) - yaw = math.atan2(dy, dx) - return yaw - - -def calc_spline_course(x, y, ds=0.1): - sp = Spline2D(x, y) - s = list(np.arange(0, sp.s[-1], ds)) - - rx, ry, ryaw, rk = [], [], [], [] - for i_s in s: - ix, iy = sp.calc_position(i_s) - rx.append(ix) - ry.append(iy) - ryaw.append(sp.calc_yaw(i_s)) - rk.append(sp.calc_curvature(i_s)) - - return rx, ry, ryaw, rk, s - - -def main(): # pragma: no cover - print("Spline 2D test") - import matplotlib.pyplot as plt - x = [-2.5, 0.0, 2.5, 5.0, 7.5, 3.0, -1.0] - y = [0.7, -6, 5, 6.5, 0.0, 5.0, -2.0] - - sp = Spline2D(x, y) - s = np.arange(0, sp.s[-1], 0.1) - - rx, ry, ryaw, rk = [], [], [], [] - for i_s in s: - ix, iy = sp.calc_position(i_s) - rx.append(ix) - ry.append(iy) - ryaw.append(sp.calc_yaw(i_s)) - rk.append(sp.calc_curvature(i_s)) - - plt.subplots(1) - plt.plot(x, y, "xb", label="input") - plt.plot(rx, ry, "-r", label="spline") - plt.grid(True) - plt.axis("equal") - plt.xlabel("x[m]") - plt.ylabel("y[m]") - plt.legend() - - plt.subplots(1) - plt.plot(s, [np.rad2deg(iyaw) for iyaw in ryaw], "-r", label="yaw") - plt.grid(True) - plt.legend() - plt.xlabel("line length[m]") - plt.ylabel("yaw angle[deg]") - - plt.subplots(1) - plt.plot(s, rk, "-r", label="curvature") - plt.grid(True) - plt.legend() - plt.xlabel("line length[m]") - plt.ylabel("curvature [1/m]") - - plt.show() - - -if __name__ == '__main__': # pragma: no cover - main() diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index b113bcbe32..ad3da20835 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -6,9 +6,11 @@ Ref: -- [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame](https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf) +- [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame] +(https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf) -- [Optimal trajectory generation for dynamic street scenarios in a Frenet Frame](https://www.youtube.com/watch?v=Cj6tAQe7UCY) +- [Optimal trajectory generation for dynamic street scenarios in a Frenet Frame] +(https://www.youtube.com/watch?v=Cj6tAQe7UCY) """ @@ -16,19 +18,20 @@ import matplotlib.pyplot as plt import copy import math -import cubic_spline_planner import sys import os sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../QuinticPolynomialsPlanner/") +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../CubicSpline/") try: from quintic_polynomials_planner import QuinticPolynomial + import cubic_spline_planner except ImportError: raise - SIM_LOOP = 500 # Parameter @@ -38,36 +41,35 @@ MAX_ROAD_WIDTH = 7.0 # maximum road width [m] D_ROAD_W = 1.0 # road width sampling length [m] DT = 0.2 # time tick [s] -MAXT = 5.0 # max prediction time [m] -MINT = 4.0 # min prediction time [m] +MAX_T = 5.0 # max prediction time [m] +MIN_T = 4.0 # min prediction time [m] TARGET_SPEED = 30.0 / 3.6 # target speed [m/s] D_T_S = 5.0 / 3.6 # target speed sampling length [m/s] N_S_SAMPLE = 1 # sampling number of target speed ROBOT_RADIUS = 2.0 # robot radius [m] # cost weights -KJ = 0.1 -KT = 0.1 -KD = 1.0 -KLAT = 1.0 -KLON = 1.0 +K_J = 0.1 +K_T = 0.1 +K_D = 1.0 +K_LAT = 1.0 +K_LON = 1.0 show_animation = True -class quartic_polynomial: - - def __init__(self, xs, vxs, axs, vxe, axe, T): +class QuarticPolynomial: + def __init__(self, xs, vxs, axs, vxe, axe, time): # calc coefficient of quartic polynomial self.a0 = xs self.a1 = vxs self.a2 = axs / 2.0 - A = np.array([[3 * T ** 2, 4 * T ** 3], - [6 * T, 12 * T ** 2]]) - b = np.array([vxe - self.a1 - 2 * self.a2 * T, + A = np.array([[3 * time ** 2, 4 * time ** 3], + [6 * time, 12 * time ** 2]]) + b = np.array([vxe - self.a1 - 2 * self.a2 * time, axe - 2 * self.a2]) x = np.linalg.solve(A, b) @@ -75,19 +77,19 @@ def __init__(self, xs, vxs, axs, vxe, axe, T): self.a4 = x[1] def calc_point(self, t): - xt = self.a0 + self.a1 * t + self.a2 * t**2 + \ - self.a3 * t**3 + self.a4 * t**4 + xt = self.a0 + self.a1 * t + self.a2 * t ** 2 + \ + self.a3 * t ** 3 + self.a4 * t ** 4 return xt def calc_first_derivative(self, t): xt = self.a1 + 2 * self.a2 * t + \ - 3 * self.a3 * t**2 + 4 * self.a4 * t**3 + 3 * self.a3 * t ** 2 + 4 * self.a4 * t ** 3 return xt def calc_second_derivative(self, t): - xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t**2 + xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t ** 2 return xt @@ -97,7 +99,7 @@ def calc_third_derivative(self, t): return xt -class Frenet_path: +class FrenetPath: def __init__(self): self.t = [] @@ -121,15 +123,14 @@ def __init__(self): def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): - frenet_paths = [] # generate path to each offset goal for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): # Lateral motion planning - for Ti in np.arange(MINT, MAXT, DT): - fp = Frenet_path() + for Ti in np.arange(MIN_T, MAX_T, DT): + fp = FrenetPath() # lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) lat_qp = QuinticPolynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) @@ -141,9 +142,10 @@ def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] # Longitudinal motion planning (Velocity keeping) - for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): + for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, + TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): tfp = copy.deepcopy(fp) - lon_qp = quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti) + lon_qp = QuarticPolynomial(s0, c_speed, 0.0, tv, 0.0, Ti) tfp.s = [lon_qp.calc_point(t) for t in fp.t] tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] @@ -154,11 +156,11 @@ def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): Js = sum(np.power(tfp.s_ddd, 2)) # square of jerk # square of diff from target speed - ds = (TARGET_SPEED - tfp.s_d[-1])**2 + ds = (TARGET_SPEED - tfp.s_d[-1]) ** 2 - tfp.cd = KJ * Jp + KT * Ti + KD * tfp.d[-1]**2 - tfp.cv = KJ * Js + KT * Ti + KD * ds - tfp.cf = KLAT * tfp.cd + KLON * tfp.cv + tfp.cd = K_J * Jp + K_T * Ti + K_D * tfp.d[-1] ** 2 + tfp.cv = K_J * Js + K_T * Ti + K_D * ds + tfp.cf = K_LAT * tfp.cd + K_LON * tfp.cv frenet_paths.append(tfp) @@ -166,7 +168,6 @@ def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): def calc_global_paths(fplist, csp): - for fp in fplist: # calc global positions @@ -174,10 +175,10 @@ def calc_global_paths(fplist, csp): ix, iy = csp.calc_position(fp.s[i]) if ix is None: break - iyaw = csp.calc_yaw(fp.s[i]) + i_yaw = csp.calc_yaw(fp.s[i]) di = fp.d[i] - fx = ix + di * math.cos(iyaw + math.pi / 2.0) - fy = iy + di * math.sin(iyaw + math.pi / 2.0) + fx = ix + di * math.cos(i_yaw + math.pi / 2.0) + fy = iy + di * math.sin(i_yaw + math.pi / 2.0) fp.x.append(fx) fp.y.append(fy) @@ -199,12 +200,11 @@ def calc_global_paths(fplist, csp): def check_collision(fp, ob): - for i in range(len(ob[:, 0])): - d = [((ix - ob[i, 0])**2 + (iy - ob[i, 1])**2) + d = [((ix - ob[i, 0]) ** 2 + (iy - ob[i, 1]) ** 2) for (ix, iy) in zip(fp.x, fp.y)] - collision = any([di <= ROBOT_RADIUS**2 for di in d]) + collision = any([di <= ROBOT_RADIUS ** 2 for di in d]) if collision: return False @@ -213,38 +213,38 @@ def check_collision(fp, ob): def check_paths(fplist, ob): - - okind = [] + ok_ind = [] for i, _ in enumerate(fplist): if any([v > MAX_SPEED for v in fplist[i].s_d]): # Max speed check continue - elif any([abs(a) > MAX_ACCEL for a in fplist[i].s_dd]): # Max accel check + elif any([abs(a) > MAX_ACCEL for a in + fplist[i].s_dd]): # Max accel check continue - elif any([abs(c) > MAX_CURVATURE for c in fplist[i].c]): # Max curvature check + elif any([abs(c) > MAX_CURVATURE for c in + fplist[i].c]): # Max curvature check continue elif not check_collision(fplist[i], ob): continue - okind.append(i) + ok_ind.append(i) - return [fplist[i] for i in okind] + return [fplist[i] for i in ok_ind] def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob): - fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0) fplist = calc_global_paths(fplist, csp) fplist = check_paths(fplist, ob) # find minimum cost path - mincost = float("inf") - bestpath = None + min_cost = float("inf") + best_path = None for fp in fplist: - if mincost >= fp.cf: - mincost = fp.cf - bestpath = fp + if min_cost >= fp.cf: + min_cost = fp.cf + best_path = fp - return bestpath + return best_path def generate_target_course(x, y): @@ -282,7 +282,7 @@ def main(): c_speed = 10.0 / 3.6 # current speed [m/s] c_d = 2.0 # current lateral position [m] c_d_d = 0.0 # current lateral speed [m/s] - c_d_dd = 0.0 # current latral acceleration [m/s] + c_d_dd = 0.0 # current lateral acceleration [m/s] s0 = 0.0 # current course position area = 20.0 # animation area length [m] @@ -304,8 +304,9 @@ def main(): if show_animation: # pragma: no cover plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(tx, ty) plt.plot(ob[:, 0], ob[:, 1], "xk") plt.plot(path.x[1:], path.y[1:], "-or") diff --git a/PathPlanning/HybridAStar/__init__.py b/PathPlanning/HybridAStar/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/PathPlanning/HybridAStar/a_star.py b/PathPlanning/HybridAStar/a_star_heuristic.py similarity index 100% rename from PathPlanning/HybridAStar/a_star.py rename to PathPlanning/HybridAStar/a_star_heuristic.py diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index 725976dc45..41e8b393c0 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -14,7 +14,7 @@ import sys sys.path.append("../ReedsSheppPath/") try: - from a_star import dp_planning # , calc_obstacle_map + from a_star_heuristic import dp_planning # , calc_obstacle_map import reeds_shepp_path_planning as rs from car import move, check_car_collision, MAX_STEER, WB, plot_car except: From ae2593b44425f805da85e245d925554cd8336700 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 9 Mar 2020 23:04:47 +0900 Subject: [PATCH 224/940] mypy fix test --- .github/workflows/pythonpackage.yml | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 1844e53820..b3f1aa364c 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -9,7 +9,7 @@ jobs: strategy: max-parallel: 4 matrix: - python-version: [3.6, 3.7] + python-version: [3.7, 3.8] steps: - uses: actions/checkout@v1 @@ -34,7 +34,15 @@ jobs: run: pip install mypy - name: mypy check run: | - find . -name "*.py" | xargs mypy + find AerialNavigation -name "*.py" | xargs mypy + find ArmNavigation -name "*.py" | xargs mypy + find Bipedal -name "*.py" | xargs mypy + find InvertedPendulumCart -name "*.py" | xargs mypy + find Localization -name "*.py" | xargs mypy + find Mapping -name "*.py" | xargs mypy + find PathPlanning -name "*.py" | xargs mypy + find PathTracking -name "*.py" | xargs mypy + find SLAM -name "*.py" | xargs mypy - name: do all unit tests run: bash runtests.sh From 4107c424067fbbac8a855066e5cae03c9f8c4334 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 9 Mar 2020 23:06:48 +0900 Subject: [PATCH 225/940] mypy fix test --- .github/workflows/pythonpackage.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index b3f1aa364c..574c7be9d5 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -9,7 +9,7 @@ jobs: strategy: max-parallel: 4 matrix: - python-version: [3.7, 3.8] + python-version: [3.7] steps: - uses: actions/checkout@v1 From 19630bc0ce9419a70c3ae301fed0f70553a2e5be Mon Sep 17 00:00:00 2001 From: Chachay Date: Fri, 20 Mar 2020 10:13:41 +0100 Subject: [PATCH 226/940] Integrate update function into state class --- .../rear_wheel_feedback.py | 32 ++++--------------- 1 file changed, 6 insertions(+), 26 deletions(-) diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index 758e9ad946..af9fb0680c 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -16,7 +16,6 @@ except: raise - Kp = 1.0 # speed propotional gain # steering control parameter KTH = 1.0 @@ -26,34 +25,24 @@ L = 2.9 # [m] show_animation = True -# show_animation = False - class State: - def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0): self.x = x self.y = y self.yaw = yaw self.v = v - -def update(state, a, delta): - - state.x = state.x + state.v * math.cos(state.yaw) * dt - state.y = state.y + state.v * math.sin(state.yaw) * dt - state.yaw = state.yaw + state.v / L * math.tan(delta) * dt - state.v = state.v + a * dt - - return state - + def update(self, a, delta, dt): + self.x = self.x + self.v * math.cos(self.yaw) * dt + self.y = self.y + self.v * math.sin(self.yaw) * dt + self.yaw = self.yaw + self.v / L * math.tan(delta) * dt + self.v = self.v + a * dt def PIDControl(target, current): a = Kp * (target - current) - return a - def pi_2_pi(angle): while(angle > math.pi): angle = angle - 2.0 * math.pi @@ -63,7 +52,6 @@ def pi_2_pi(angle): return angle - def rear_wheel_feedback_control(state, cx, cy, cyaw, ck, preind): ind, e = calc_nearest_index(state, cx, cy, cyaw) @@ -78,7 +66,6 @@ def rear_wheel_feedback_control(state, cx, cy, cyaw, ck, preind): return 0.0, ind delta = math.atan2(L * omega / v, 1.0) - # print(k, v, e, th_e, omega, delta) return delta, ind @@ -104,9 +91,7 @@ def calc_nearest_index(state, cx, cy, cyaw): return ind, mind - def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): - T = 500.0 # max simulation time goal_dis = 0.3 stop_speed = 0.05 @@ -126,7 +111,7 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): di, target_ind = rear_wheel_feedback_control( state, cx, cy, cyaw, ck, target_ind) ai = PIDControl(speed_profile[target_ind], state.v) - state = update(state, ai, di) + state.update(ai, di, dt) if abs(state.v) <= stop_speed: target_ind += 1 @@ -163,11 +148,8 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): return t, x, y, yaw, v, goal_flag - def calc_speed_profile(cx, cy, cyaw, target_speed): - speed_profile = [target_speed] * len(cx) - direction = 1.0 # Set stop point @@ -190,7 +172,6 @@ def calc_speed_profile(cx, cy, cyaw, target_speed): return speed_profile - def main(): print("rear wheel feedback tracking start!!") ax = [0.0, 6.0, 12.5, 5.0, 7.5, 3.0, -1.0] @@ -237,6 +218,5 @@ def main(): plt.show() - if __name__ == '__main__': main() From 74739078fdcc18cd12a2347efec0dac4ccca6dc2 Mon Sep 17 00:00:00 2001 From: Chachay Date: Fri, 20 Mar 2020 12:08:19 +0100 Subject: [PATCH 227/940] Replace Spline module to Scipy interpolate --- .../rear_wheel_feedback.py | 139 +++++++++++------- 1 file changed, 84 insertions(+), 55 deletions(-) diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index af9fb0680c..5e6cedb377 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -9,12 +9,9 @@ import math import numpy as np import sys -sys.path.append("../../PathPlanning/CubicSpline/") -try: - import cubic_spline_planner -except: - raise +from scipy import interpolate +from scipy import optimize Kp = 1.0 # speed propotional gain # steering control parameter @@ -39,6 +36,61 @@ def update(self, a, delta, dt): self.yaw = self.yaw + self.v / L * math.tan(delta) * dt self.v = self.v + a * dt +class TrackSpline: + def __init__(self, x, y): + x, y = map(np.asarray, (x, y)) + s = np.append([0],(np.cumsum(np.diff(x)**2) + np.cumsum(np.diff(y)**2))**0.5) + + self.X = interpolate.CubicSpline(s, x) + self.Y = interpolate.CubicSpline(s, y) + + self.dX = self.X.derivative(1) + self.ddX = self.X.derivative(2) + + self.dY = self.Y.derivative(1) + self.ddY = self.Y.derivative(2) + + self.length = s[-1] + + def yaw(self, s): + dx, dy = self.dX(s), self.dY(s) + return np.arctan2(dy, dx) + + def curvature(self, s): + dx, dy = self.dX(s), self.dY(s) + ddx, ddy = self.ddX(s), self.ddY(s) + return (ddy * dx - ddx * dy) / ((dx ** 2 + dy ** 2)**(3 / 2)) + + def __findClosestPoint(self, s0, x, y): + def f(_s, *args): + _x, _y= self.X(_s), self.Y(_s) + return (_x - args[0])**2 + (_y - args[1])**2 + + def jac(_s, *args): + _x, _y = self.X(_s), self.Y(_s) + _dx, _dy = self.dX(_s), self.dY(_s) + return 2*_dx*(_x - args[0])+2*_dy*(_y-args[1]) + + minimum = optimize.fmin_cg(f, s0, jac, args=(x, y), full_output=True, disp=False) + return minimum + + def TrackError(self, x, y, s0): + ret = self.__findClosestPoint(s0, x, y) + + s = ret[0][0] + e = ret[1] + + k = self.curvature(s) + yaw = self.yaw(s) + + dxl = self.X(s) - x + dyl = self.Y(s) - y + angle = pi_2_pi(yaw - math.atan2(dyl, dxl)) + if angle < 0: + e*= -1 + + return e, k, yaw, s + def PIDControl(target, current): a = Kp * (target - current) return a @@ -52,46 +104,22 @@ def pi_2_pi(angle): return angle -def rear_wheel_feedback_control(state, cx, cy, cyaw, ck, preind): - ind, e = calc_nearest_index(state, cx, cy, cyaw) - - k = ck[ind] +def rear_wheel_feedback_control(state, e, k, yaw_r): v = state.v - th_e = pi_2_pi(state.yaw - cyaw[ind]) + th_e = pi_2_pi(state.yaw - yaw_r) omega = v * k * math.cos(th_e) / (1.0 - k * e) - \ KTH * abs(v) * th_e - KE * v * math.sin(th_e) * e / th_e if th_e == 0.0 or omega == 0.0: - return 0.0, ind + return 0.0 delta = math.atan2(L * omega / v, 1.0) - return delta, ind - - -def calc_nearest_index(state, cx, cy, cyaw): - dx = [state.x - icx for icx in cx] - dy = [state.y - icy for icy in cy] - - d = [idx ** 2 + idy ** 2 for (idx, idy) in zip(dx, dy)] - - mind = min(d) - - ind = d.index(mind) + return delta - mind = math.sqrt(mind) - dxl = cx[ind] - state.x - dyl = cy[ind] - state.y - - angle = pi_2_pi(cyaw[ind] - math.atan2(dyl, dxl)) - if angle < 0: - mind *= -1 - - return ind, mind - -def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): +def closed_loop_prediction(track, speed_profile, goal): T = 500.0 # max simulation time goal_dis = 0.3 stop_speed = 0.05 @@ -105,17 +133,17 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): v = [state.v] t = [0.0] goal_flag = False - target_ind = calc_nearest_index(state, cx, cy, cyaw) + + s = np.arange(0, track.length, 0.1) + e, k, yaw_r, s0 = track.TrackError(state.x, state.y, 0.0) while T >= time: - di, target_ind = rear_wheel_feedback_control( - state, cx, cy, cyaw, ck, target_ind) - ai = PIDControl(speed_profile[target_ind], state.v) + e, k, yaw_r, s0 = track.TrackError(state.x, state.y, s0) + di = rear_wheel_feedback_control(state, e, k, yaw_r) + #ai = PIDControl(speed_profile[target_ind], state.v) + ai = PIDControl(speed_profile, state.v) state.update(ai, di, dt) - if abs(state.v) <= stop_speed: - target_ind += 1 - time = time + dt # check goal @@ -132,23 +160,22 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): v.append(state.v) t.append(time) - if target_ind % 1 == 0 and show_animation: + if show_animation: plt.cla() # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) - plt.plot(cx, cy, "-r", label="course") + plt.plot(track.X(s), track.Y(s), "-r", label="course") plt.plot(x, y, "ob", label="trajectory") - plt.plot(cx[target_ind], cy[target_ind], "xg", label="target") + plt.plot(track.X(s0), track.Y(s0), "xg", label="target") plt.axis("equal") plt.grid(True) - plt.title("speed[km/h]:" + str(round(state.v * 3.6, 2)) + - ",target index:" + str(target_ind)) + plt.title("speed[km/h]:{:.2f}, target s-param:{:.2f}".format(round(state.v * 3.6, 2), s0)) plt.pause(0.0001) return t, x, y, yaw, v, goal_flag -def calc_speed_profile(cx, cy, cyaw, target_speed): +def calc_speed_profile(track, target_speed, s): speed_profile = [target_speed] * len(cx) direction = 1.0 @@ -178,14 +205,16 @@ def main(): ay = [0.0, 0.0, 5.0, 6.5, 3.0, 5.0, -2.0] goal = [ax[-1], ay[-1]] - cx, cy, cyaw, ck, s = cubic_spline_planner.calc_spline_course( - ax, ay, ds=0.1) + track = TrackSpline(ax, ay) + s = np.arange(0, track.length, 0.1) + target_speed = 10.0 / 3.6 - sp = calc_speed_profile(cx, cy, cyaw, target_speed) + # Note: disable backward direction temporary + #sp = calc_speed_profile(track, target_speed, s) + sp = target_speed - t, x, y, yaw, v, goal_flag = closed_loop_prediction( - cx, cy, cyaw, ck, sp, goal) + t, x, y, yaw, v, goal_flag = closed_loop_prediction(track, sp, goal) # Test assert goal_flag, "Cannot goal" @@ -194,7 +223,7 @@ def main(): plt.close() plt.subplots(1) plt.plot(ax, ay, "xb", label="input") - plt.plot(cx, cy, "-r", label="spline") + plt.plot(track.X(s), track.Y(s), "-r", label="spline") plt.plot(x, y, "-g", label="tracking") plt.grid(True) plt.axis("equal") @@ -203,14 +232,14 @@ def main(): plt.legend() plt.subplots(1) - plt.plot(s, [np.rad2deg(iyaw) for iyaw in cyaw], "-r", label="yaw") + plt.plot(s, np.rad2deg(track.yaw(s)), "-r", label="yaw") plt.grid(True) plt.legend() plt.xlabel("line length[m]") plt.ylabel("yaw angle[deg]") plt.subplots(1) - plt.plot(s, ck, "-r", label="curvature") + plt.plot(s, track.curvature(s), "-r", label="curvature") plt.grid(True) plt.legend() plt.xlabel("line length[m]") From a7c82ccb9e5cc18e6aaca3b3a8ff4de6fdcf1c21 Mon Sep 17 00:00:00 2001 From: Chachay Date: Mon, 23 Mar 2020 16:00:19 +0100 Subject: [PATCH 228/940] - remove unsued import and variable - rename functions - add target speed controller (as the substitute of calc speed profile) --- .../rear_wheel_feedback.py | 83 ++++++++----------- 1 file changed, 34 insertions(+), 49 deletions(-) diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index 5e6cedb377..9b69f8eace 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -8,7 +8,6 @@ import matplotlib.pyplot as plt import math import numpy as np -import sys from scipy import interpolate from scipy import optimize @@ -24,11 +23,12 @@ show_animation = True class State: - def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0): + def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0, direction=1): self.x = x self.y = y self.yaw = yaw self.v = v + self.direction = direction def update(self, a, delta, dt): self.x = self.x + self.v * math.cos(self.yaw) * dt @@ -52,36 +52,36 @@ def __init__(self, x, y): self.length = s[-1] - def yaw(self, s): + def calc_yaw(self, s): dx, dy = self.dX(s), self.dY(s) return np.arctan2(dy, dx) - def curvature(self, s): + def calc_curvature(self, s): dx, dy = self.dX(s), self.dY(s) ddx, ddy = self.ddX(s), self.ddY(s) return (ddy * dx - ddx * dy) / ((dx ** 2 + dy ** 2)**(3 / 2)) - def __findClosestPoint(self, s0, x, y): - def f(_s, *args): + def __find_nearest_point(self, s0, x, y): + def calc_distance(_s, *args): _x, _y= self.X(_s), self.Y(_s) return (_x - args[0])**2 + (_y - args[1])**2 - def jac(_s, *args): + def calc_distance_jacobian(_s, *args): _x, _y = self.X(_s), self.Y(_s) _dx, _dy = self.dX(_s), self.dY(_s) return 2*_dx*(_x - args[0])+2*_dy*(_y-args[1]) - minimum = optimize.fmin_cg(f, s0, jac, args=(x, y), full_output=True, disp=False) + minimum = optimize.fmin_cg(calc_distance, s0, calc_distance_jacobian, args=(x, y), full_output=True, disp=False) return minimum - def TrackError(self, x, y, s0): - ret = self.__findClosestPoint(s0, x, y) + def calc_track_error(self, x, y, s0): + ret = self.__find_nearest_point(s0, x, y) s = ret[0][0] e = ret[1] - k = self.curvature(s) - yaw = self.yaw(s) + k = self.calc_curvature(s) + yaw = self.calc_yaw(s) dxl = self.X(s) - x dyl = self.Y(s) - y @@ -91,7 +91,7 @@ def TrackError(self, x, y, s0): return e, k, yaw, s -def PIDControl(target, current): +def pid_control(target, current): a = Kp * (target - current) return a @@ -119,10 +119,9 @@ def rear_wheel_feedback_control(state, e, k, yaw_r): return delta -def closed_loop_prediction(track, speed_profile, goal): +def simulate(track, goal): T = 500.0 # max simulation time goal_dis = 0.3 - stop_speed = 0.05 state = State(x=-0.0, y=-0.0, yaw=0.0, v=0.0) @@ -135,13 +134,14 @@ def closed_loop_prediction(track, speed_profile, goal): goal_flag = False s = np.arange(0, track.length, 0.1) - e, k, yaw_r, s0 = track.TrackError(state.x, state.y, 0.0) + e, k, yaw_r, s0 = track.calc_track_error(state.x, state.y, 0.0) while T >= time: - e, k, yaw_r, s0 = track.TrackError(state.x, state.y, s0) + e, k, yaw_r, s0 = track.calc_track_error(state.x, state.y, s0) di = rear_wheel_feedback_control(state, e, k, yaw_r) - #ai = PIDControl(speed_profile[target_ind], state.v) - ai = PIDControl(speed_profile, state.v) + + speed_r = calc_target_speed(state, yaw_r) + ai = pid_control(speed_r, state.v) state.update(ai, di, dt) time = time + dt @@ -175,29 +175,20 @@ def closed_loop_prediction(track, speed_profile, goal): return t, x, y, yaw, v, goal_flag -def calc_speed_profile(track, target_speed, s): - speed_profile = [target_speed] * len(cx) - direction = 1.0 - - # Set stop point - for i in range(len(cx) - 1): - dyaw = cyaw[i + 1] - cyaw[i] - switch = math.pi / 4.0 <= dyaw < math.pi / 2.0 - - if switch: - direction *= -1 - - if direction != 1.0: - speed_profile[i] = - target_speed - else: - speed_profile[i] = target_speed - - if switch: - speed_profile[i] = 0.0 +def calc_target_speed(state, yaw_r): + target_speed = 10.0 / 3.6 - speed_profile[-1] = 0.0 + dyaw = yaw_r - state.yaw + switch = math.pi / 4.0 <= dyaw < math.pi / 2.0 - return speed_profile + if switch: + state.direction *= -1 + return 0.0 + + if state.direction != 1: + return -target_speed + else: + return target_speed def main(): print("rear wheel feedback tracking start!!") @@ -208,13 +199,7 @@ def main(): track = TrackSpline(ax, ay) s = np.arange(0, track.length, 0.1) - target_speed = 10.0 / 3.6 - - # Note: disable backward direction temporary - #sp = calc_speed_profile(track, target_speed, s) - sp = target_speed - - t, x, y, yaw, v, goal_flag = closed_loop_prediction(track, sp, goal) + t, x, y, yaw, v, goal_flag = simulate(track, goal) # Test assert goal_flag, "Cannot goal" @@ -232,14 +217,14 @@ def main(): plt.legend() plt.subplots(1) - plt.plot(s, np.rad2deg(track.yaw(s)), "-r", label="yaw") + plt.plot(s, np.rad2deg(track.calc_yaw(s)), "-r", label="yaw") plt.grid(True) plt.legend() plt.xlabel("line length[m]") plt.ylabel("yaw angle[deg]") plt.subplots(1) - plt.plot(s, track.curvature(s), "-r", label="curvature") + plt.plot(s, track.calc_curvature(s), "-r", label="curvature") plt.grid(True) plt.legend() plt.xlabel("line length[m]") From 7005a664e1b65d6751d1cb323833acff7c7505ca Mon Sep 17 00:00:00 2001 From: Chachay Date: Mon, 23 Mar 2020 16:10:11 +0100 Subject: [PATCH 229/940] - Changed Class name (CubicSplinePath) - remove unnecessary else case --- PathTracking/rear_wheel_feedback/rear_wheel_feedback.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index 9b69f8eace..8f1079b074 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -36,7 +36,7 @@ def update(self, a, delta, dt): self.yaw = self.yaw + self.v / L * math.tan(delta) * dt self.v = self.v + a * dt -class TrackSpline: +class CubicSplinePath: def __init__(self, x, y): x, y = map(np.asarray, (x, y)) s = np.append([0],(np.cumsum(np.diff(x)**2) + np.cumsum(np.diff(y)**2))**0.5) @@ -187,8 +187,8 @@ def calc_target_speed(state, yaw_r): if state.direction != 1: return -target_speed - else: - return target_speed + + return target_speed def main(): print("rear wheel feedback tracking start!!") @@ -196,7 +196,7 @@ def main(): ay = [0.0, 0.0, 5.0, 6.5, 3.0, 5.0, -2.0] goal = [ax[-1], ay[-1]] - track = TrackSpline(ax, ay) + track = CubicSplinePath(ax, ay) s = np.arange(0, track.length, 0.1) t, x, y, yaw, v, goal_flag = simulate(track, goal) From e880b0efe448e7024f22bd3f70c26fe8ba7ef075 Mon Sep 17 00:00:00 2001 From: Michael Dobler Date: Tue, 24 Mar 2020 12:59:49 +0100 Subject: [PATCH 230/940] Fix parameter of jacobian in EKF-SLAM --- SLAM/EKFSLAM/ekf_slam.ipynb | 2 +- SLAM/EKFSLAM/ekf_slam.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/SLAM/EKFSLAM/ekf_slam.ipynb b/SLAM/EKFSLAM/ekf_slam.ipynb index ccf5e5bbd6..a64c145ad4 100644 --- a/SLAM/EKFSLAM/ekf_slam.ipynb +++ b/SLAM/EKFSLAM/ekf_slam.ipynb @@ -305,8 +305,8 @@ " :returns: predicted state vector, predicted covariance, jacobian of control vector, transition fx\n", " \"\"\"\n", " S = STATE_SIZE\n", - " xEst[0:S] = motion_model(xEst[0:S], u)\n", " G, Fx = jacob_motion(xEst[0:S], u)\n", + " xEst[0:S] = motion_model(xEst[0:S], u)\n", " # Fx is an an identity matrix of size (STATE_SIZE)\n", " # sigma = G*sigma*G.T + Noise\n", " PEst[0:S, 0:S] = G.T @ PEst[0:S, 0:S] @ G + Fx.T @ Cx @ Fx\n", diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index 3038e40a47..6b349d858b 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -29,8 +29,8 @@ def ekf_slam(xEst, PEst, u, z): # Predict S = STATE_SIZE - xEst[0:S] = motion_model(xEst[0:S], u) G, Fx = jacob_motion(xEst[0:S], u) + xEst[0:S] = motion_model(xEst[0:S], u) PEst[0:S, 0:S] = G.T @ PEst[0:S, 0:S] @ G + Fx.T @ Cx @ Fx initP = np.eye(2) From 6d178e1feb3740c4b7dc67136b9b701f22c6e6e6 Mon Sep 17 00:00:00 2001 From: Chachay Date: Tue, 24 Mar 2020 16:33:43 +0100 Subject: [PATCH 231/940] rename yaw_r to yaw_ref --- .../rear_wheel_feedback/rear_wheel_feedback.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index 8f1079b074..f6df94ac44 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -104,9 +104,9 @@ def pi_2_pi(angle): return angle -def rear_wheel_feedback_control(state, e, k, yaw_r): +def rear_wheel_feedback_control(state, e, k, yaw_ref): v = state.v - th_e = pi_2_pi(state.yaw - yaw_r) + th_e = pi_2_pi(state.yaw - yaw_ref) omega = v * k * math.cos(th_e) / (1.0 - k * e) - \ KTH * abs(v) * th_e - KE * v * math.sin(th_e) * e / th_e @@ -134,14 +134,14 @@ def simulate(track, goal): goal_flag = False s = np.arange(0, track.length, 0.1) - e, k, yaw_r, s0 = track.calc_track_error(state.x, state.y, 0.0) + e, k, yaw_ref, s0 = track.calc_track_error(state.x, state.y, 0.0) while T >= time: - e, k, yaw_r, s0 = track.calc_track_error(state.x, state.y, s0) - di = rear_wheel_feedback_control(state, e, k, yaw_r) + e, k, yaw_ref, s0 = track.calc_track_error(state.x, state.y, s0) + di = rear_wheel_feedback_control(state, e, k, yaw_ref) - speed_r = calc_target_speed(state, yaw_r) - ai = pid_control(speed_r, state.v) + speed_ref = calc_target_speed(state, yaw_ref) + ai = pid_control(speed_ref, state.v) state.update(ai, di, dt) time = time + dt From b61a8d8fb5d47c89c97ec8081942ce33f673538c Mon Sep 17 00:00:00 2001 From: Jeff Irion Date: Tue, 24 Mar 2020 10:56:11 -0700 Subject: [PATCH 232/940] Add Graph SLAM formulation PDF and SE(2) solver + example --- SLAM/GraphBasedSLAM/LaTeX/.gitignore | 3 + SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib | 30 + .../LaTeX/graphSLAM_formulation.tex | 175 ++ SLAM/GraphBasedSLAM/data/README.rst | 6 + SLAM/GraphBasedSLAM/data/input_INTEL.g2o | 2711 +++++++++++++++++ .../graphSLAM_SE2_example.ipynb | 332 ++ SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf | Bin 0 -> 276368 bytes SLAM/GraphBasedSLAM/graphslam/__init__.py | 9 + .../GraphBasedSLAM/graphslam/edge/__init__.py | 5 + .../graphslam/edge/edge_odometry.py | 180 ++ SLAM/GraphBasedSLAM/graphslam/graph.py | 265 ++ SLAM/GraphBasedSLAM/graphslam/load.py | 66 + .../GraphBasedSLAM/graphslam/pose/__init__.py | 5 + SLAM/GraphBasedSLAM/graphslam/pose/se2.py | 171 ++ SLAM/GraphBasedSLAM/graphslam/util.py | 78 + SLAM/GraphBasedSLAM/graphslam/vertex.py | 67 + .../images/Graph_SLAM_optimization.gif | Bin 0 -> 114966 bytes 17 files changed, 4103 insertions(+) create mode 100644 SLAM/GraphBasedSLAM/LaTeX/.gitignore create mode 100644 SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib create mode 100644 SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex create mode 100644 SLAM/GraphBasedSLAM/data/README.rst create mode 100644 SLAM/GraphBasedSLAM/data/input_INTEL.g2o create mode 100644 SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb create mode 100644 SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf create mode 100644 SLAM/GraphBasedSLAM/graphslam/__init__.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/edge/__init__.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/edge/edge_odometry.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/graph.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/load.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/pose/__init__.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/pose/se2.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/util.py create mode 100644 SLAM/GraphBasedSLAM/graphslam/vertex.py create mode 100644 SLAM/GraphBasedSLAM/images/Graph_SLAM_optimization.gif diff --git a/SLAM/GraphBasedSLAM/LaTeX/.gitignore b/SLAM/GraphBasedSLAM/LaTeX/.gitignore new file mode 100644 index 0000000000..b0b343402c --- /dev/null +++ b/SLAM/GraphBasedSLAM/LaTeX/.gitignore @@ -0,0 +1,3 @@ +# Ignore LaTeX generated files +graphSLAM_formulation.* +!graphSLAM_formulation.tex diff --git a/SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib b/SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib new file mode 100644 index 0000000000..4d3b71ae50 --- /dev/null +++ b/SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib @@ -0,0 +1,30 @@ +@article{blanco2010tutorial, + title={A tutorial on ${SE}(3)$ transformation parameterizations and on-manifold optimization}, + author={Blanco, Jose-Luis}, + journal={University of Malaga, Tech. Rep}, + volume={3}, + year={2010}, + publisher={Citeseer} +} + +@article{grisetti2010tutorial, + title={A tutorial on graph-based {SLAM}}, + author={Grisetti, Giorgio and Kummerle, Rainer and Stachniss, Cyrill and Burgard, Wolfram}, + journal={IEEE Intelligent Transportation Systems Magazine}, + volume={2}, + number={4}, + pages={31--43}, + year={2010}, + publisher={IEEE} +} + +@article{thrun2006graph, + title={The graph {SLAM} algorithm with applications to large-scale mapping of urban structures}, + author={Thrun, Sebastian and Montemerlo, Michael}, + journal={The International Journal of Robotics Research}, + volume={25}, + number={5-6}, + pages={403--429}, + year={2006}, + publisher={SAGE Publications} +} diff --git a/SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex b/SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex new file mode 100644 index 0000000000..25f02cd3bd --- /dev/null +++ b/SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex @@ -0,0 +1,175 @@ +\documentclass{article} + +\usepackage{amsfonts} +\usepackage{amsmath,amssymb,amsfonts} +\usepackage{textcomp} +\usepackage{fullpage} +\usepackage{setspace} +\usepackage{float} +\usepackage{cite} +\usepackage{graphicx} +\usepackage{caption} +\usepackage{subcaption} +\usepackage[pdfborder={0 0 0}, pdfpagemode=UseNone, pdfstartview=FitH]{hyperref} + +\DeclareMathOperator*{\argmax}{arg\,max} +\DeclareMathOperator*{\argmin}{arg\,min} + +\def\keyterm{\textit} + +\newcommand{\transp}{{\scriptstyle{\mathsf{T}}}} + + + +\begin{document} + +\title{Graph SLAM Formulation} +\author{Jeff Irion} +\date{} + +\maketitle +\vspace{3em} + + +\section{Problem Formulation} + +Let a robot's trajectory through its environment be represented by a sequence of $N$ poses: $\mathbf{p}_1, \mathbf{p}_2, \ldots, \mathbf{p}_N$. Each pose lies on a manifold: $\mathbf{p}_i \in \mathcal{M}$. Simple examples of manifolds used in Graph SLAM include 1-D, 2-D, and 3-D space, i.e., $\mathbb{R}$, $\mathbb{R}^2$, and $\mathbb{R}^3$. These environments are \keyterm{rectilinear}, meaning that there is no concept of orientation. By contrast, in $SE(2)$ problem settings a robot's pose consists of its location in $\mathbb{R}^2$ and its orientation $\theta$. Similarly, in $SE(3)$ a robot's pose consists of its location in $\mathbb{R}^3$ and its orientation, which can be represented via Euler angles, quaternions, or $SO(3)$ rotation matrices. + +As the robot explores its environment, it collects a set of $M$ measurements $\mathcal{Z} = \{\mathbf{z}_j\}$. Examples of such measurements include odometry, GPS, and IMU data. Given a set of poses $\mathbf{p}_1, \ldots, \mathbf{p}_N$, we can compute the estimated measurement $\hat{\mathbf{z}}_j(\mathbf{p}_1, \ldots, \mathbf{p}_N)$. We can then compute the \keyterm{residual} $\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j)$ for measurement $j$. The formula for the residual depends on the type of measurement. As an example, let $\mathbf{z}_1$ be an odometry measurement that was collected when the robot traveled from $\mathbf{p}_1$ to $\mathbf{p}_2$. The expected measurement and the residual are computed as +% +\begin{align*} + \hat{\mathbf{z}}_1(\mathbf{p}_1, \mathbf{p}_2) &= \mathbf{p}_2 \ominus \mathbf{p}_1 \\ + \mathbf{e}_1(\mathbf{z}_1, \hat{\mathbf{z}}_1) &= \mathbf{z}_1 \ominus \hat{\mathbf{z}}_1 = \mathbf{z}_1 \ominus (\mathbf{p}_2 \ominus \mathbf{p}_1), +\end{align*} +% +where the $\ominus$ operator indicates inverse pose composition. We model measurement $\mathbf{z}_j$ as having independent Gaussian noise with zero mean and covariance matrix $\Omega_j^{-1}$; we refer to $\Omega_j$ as the \keyterm{information matrix} for measurement $j$. That is, +\begin{equation} + p(\mathbf{z}_j \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) = \eta_j \exp \left( (-\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) \right), \label{eq:observation_probability} +\end{equation} +where $\eta_j$ is the normalization constant. + +The objective of Graph SLAM is to find the maximum likelihood set of poses given the measurements $\mathcal{Z} = \{\mathbf{z}_j\}$; in other words, we want to find +% +\begin{equation*} + \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) +\end{equation*} +% +Using Bayes' rule, we can write this probability as +% +\begin{align} + p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) &= \frac{p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) p(\mathbf{p}_1, \ldots, \mathbf{p}_N) }{ p(\mathcal{Z}) } \notag \\ + &\propto p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N), \label{eq:bayes} +\end{align} +% +since $p(\mathcal{Z})$ is a constant (albeit, an unknown constant) and we assume that $p(\mathbf{p}_1, \ldots, \mathbf{p}_N)$ is uniformly distributed \cite{thrun2006graph}. Therefore, we can use \eqref{eq:observation_probability} and \eqref{eq:bayes} to simplify the Graph SLAM optimization as follows: +% +\begin{align*} + \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) &= \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) \\ + &= \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \prod_{j=1}^M p(\mathbf{z}_j \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) \\ + &= \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \prod_{j=1}^M \exp \left( -(\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) \right) \\ + &= \argmin_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \sum_{j=1}^M (\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j). +\end{align*} +% +We define +% +\begin{equation*} + \chi^2 := \sum_{j=1}^M (\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j), +\end{equation*} +% +and this is what we seek to minimize. + + +\section{Dimensionality and Pose Representation} + +Before proceeding further, it is helpful to discuss the dimensionality of the problem. We have: +\begin{itemize} + \item A set of $N$ poses $\mathbf{p}_1, \mathbf{p}_2, \ldots, \mathbf{p}_N$, where each pose lies on the manifold $\mathcal{M}$ + \begin{itemize} + \item Each pose $\mathbf{p}_i$ is represented as a vector in (a subset of) $\mathbb{R}^d$. For example: + \begin{itemize} + \item[$\circ$] An $SE(2)$ pose is typically represented as $(x, y, \theta)$, and thus $d = 3$. + \item[$\circ$] An $SE(3)$ pose is typically represented as $(x, y, z, q_x, q_y, q_z, q_w)$, where $(x, y, z)$ is a point in $\mathbb{R}^3$ and $(q_x, q_y, q_z, q_w)$ is a \keyterm{quaternion}, and so $d = 7$. For more information about $SE(3)$ parameterizations and pose transformations, see \cite{blanco2010tutorial}. + \end{itemize} + \item We also need to be able to represent each pose compactly as a vector in (a subset of) $\mathbb{R}^c$. + \begin{itemize} + \item[$\circ$] Since an $SE(2)$ pose has three degrees of freedom, the $(x, y, \theta)$ representation is again sufficient and $c=3$. + \item[$\circ$] An $SE(3)$ pose only has six degrees of freedom, and we can represent it compactly as $(x, y, z, q_x, q_y, q_z)$, and thus $c=6$. + \end{itemize} + \item We use the $\boxplus$ operator to indicate pose composition when one or both of the poses are represented compactly. The output can be a pose in $\mathcal{M}$ or a vector in $\mathbb{R}^c$, as required by context. + \end{itemize} + \item A set of $M$ measurements $\mathcal{Z} = \{\mathbf{z}_1, \mathbf{z}_2, \ldots, \mathbf{z}_M\}$ + \begin{itemize} + \item Each measurement's dimensionality can be unique, and we will use $\bullet$ to denote a ``wildcard'' variable. + \item Measurement $\mathbf{z}_j \in \mathbb{R}^\bullet$ has an associated information matrix $\Omega_j \in \mathbb{R}^{\bullet \times \bullet}$ and residual function $\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) = \mathbf{e}_j(\mathbf{z}_j, \mathbf{p}_1, \ldots, \mathbf{p}_N) \in \mathbb{R}^\bullet$. + \item A measurement could, in theory, constrain anywhere from 1 pose to all $N$ poses. In practice, each measurement usually constrains only 1 or 2 poses. + \end{itemize} +\end{itemize} + + +\section{Graph SLAM Algorithm} + +The ``Graph'' in Graph SLAM refers to the fact that we view the problem as a graph. The graph has a set $\mathcal{V}$ of $N$ vertices, where each vertex $v_i$ has an associated pose $\mathbf{p}_i$. Similarly, the graph has a set $\mathcal{E}$ of $M$ edges, where each edge $e_j$ has an associated measurement $\mathbf{z}_j$. In practice, the edges in this graph are either unary (i.e., a loop) or binary. (Note: $e_j$ refers to the edge in the graph associated with measurement $\mathbf{z}_j$, whereas $\mathbf{e}_j$ refers to the residual function associated with $\mathbf{z}_j$.) For more information about the Graph SLAM algorithm, see \cite{grisetti2010tutorial}. + +We want to optimize +% +\begin{equation*} + \chi^2 = \sum_{e_j \in \mathcal{E}} \mathbf{e}_j^\transp \Omega_j \mathbf{e}_j. +\end{equation*} +% +Let $\mathbf{x}_i \in \mathbb{R}^c$ be the compact representation of pose $\mathbf{p}_i \in \mathcal{M}$, and let +% +\begin{equation*} + \mathbf{x} := \begin{bmatrix} \mathbf{x}_1 \\ \mathbf{x}_2 \\ \vdots \\ \mathbf{x}_N \end{bmatrix} \in \mathbb{R}^{cN} +\end{equation*} +% +We will solve this optimization problem iteratively. Let +% +\begin{equation} + \mathbf{x}^{k+1} := \mathbf{x}^k \boxplus \Delta \mathbf{x}^k = \begin{bmatrix} \mathbf{x}_1 \boxplus \Delta \mathbf{x}_1 \\ \mathbf{x}_2 \boxplus \Delta \mathbf{x}_2 \\ \vdots \\ \mathbf{x}_N \boxplus \Delta \mathbf{x}_2 \end{bmatrix} \label{eq:update} +\end{equation} +% +The $\chi^2$ error at iteration $k+1$ is +\begin{equation} + \chi_{k+1}^2 = \sum_{e_j \in \mathcal{E}} \underbrace{\left[ \mathbf{e}_j(\mathbf{x}^{k+1}) \right]^\transp}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\mathbf{e}_j(\mathbf{x}^{k+1})}_{\bullet \times 1}. \label{eq:chisq_at_kplusone} +\end{equation} +% +We will linearize the residuals as: +% +\begin{align} + \mathbf{e}_j(\mathbf{x}^{k+1}) &= \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \notag \\ + &\approx \mathbf{e}_j(\mathbf{x}^{k}) + \frac{\partial}{\partial \Delta \mathbf{x}^k} \left[ \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \right] \Delta \mathbf{x}^k \notag \\ + &= \mathbf{e}_j(\mathbf{x}^{k}) + \left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right) \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \Delta \mathbf{x}^k. \label{eq:linearization} +\end{align} +% +Plugging \eqref{eq:linearization} into \eqref{eq:chisq_at_kplusone}, we get: +% +\small +\begin{align} + \chi_{k+1}^2 &\approx \ \ \ \ \ \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x}^k)]^\transp}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\mathbf{e}_j(\mathbf{x}^k)}_{\bullet \times 1} \notag \\ + &\hphantom{\approx} \ \ \ + \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x^k}) ]^\transp }_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \underbrace{\Delta \mathbf{x}^k}_{cN \times 1} \notag \\ + &\hphantom{\approx} \ \ \ + \sum_{e_j \in \mathcal{E}} \underbrace{(\Delta \mathbf{x}^k)^\transp}_{1 \times cN} \underbrace{ \left( \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \right)^\transp}_{cN \times dN} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)^\transp}_{dN \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \underbrace{\Delta \mathbf{x}^k}_{cN \times 1} \notag \\ + &= \chi_k^2 + 2 \mathbf{b}^\transp \Delta \mathbf{x}^k + (\Delta \mathbf{x}^k)^\transp H \Delta \mathbf{x}^k, \notag +\end{align} +\normalsize +% +where +% +\begin{align*} + \mathbf{b}^\transp &= \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x^k}) ]^\transp }_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \\ + H &= \sum_{e_j \in \mathcal{E}} \underbrace{ \left( \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \right)^\transp}_{cN \times dN} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)^\transp}_{dN \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN}. +\end{align*} +% +Using this notation, we obtain the optimal update as +% +\begin{equation} + \Delta \mathbf{x}^k = -H^{-1} \mathbf{b}. \label{eq:deltax} +\end{equation} +% +We apply this update to the poses via \eqref{eq:update} and repeat until convergence. + + + +\bibliographystyle{acm} +\bibliography{graphSLAM}{} + +\end{document} diff --git a/SLAM/GraphBasedSLAM/data/README.rst b/SLAM/GraphBasedSLAM/data/README.rst new file mode 100644 index 0000000000..c875cce73f --- /dev/null +++ b/SLAM/GraphBasedSLAM/data/README.rst @@ -0,0 +1,6 @@ +Acknowledgments and References +============================== + +Thanks to Luca Larlone for allowing inclusion of the `Intel dataset `_ in this repo. + +1. Carlone, L. and Censi, A., 2014. `From angular manifolds to the integer lattice: Guaranteed orientation estimation with application to pose graph optimization `_. IEEE Transactions on Robotics, 30(2), pp.475-492. diff --git a/SLAM/GraphBasedSLAM/data/input_INTEL.g2o b/SLAM/GraphBasedSLAM/data/input_INTEL.g2o new file mode 100644 index 0000000000..16f3a2600c --- /dev/null +++ b/SLAM/GraphBasedSLAM/data/input_INTEL.g2o @@ -0,0 +1,2711 @@ +VERTEX_SE2 0 0.000000 0.000000 0.000000 +VERTEX_SE2 1 0.000000 0.000000 -0.000642 +VERTEX_SE2 2 0.000000 0.000000 -0.001180 +VERTEX_SE2 3 0.011002 -0.000975 -0.003562 +VERTEX_SE2 4 0.641008 -0.011200 -0.007444 +VERTEX_SE2 5 0.696016 -0.011716 -0.098726 +VERTEX_SE2 6 0.700269 -0.015435 -0.895998 +VERTEX_SE2 7 0.693956 0.004213 -1.511535 +VERTEX_SE2 8 0.699263 0.026693 -2.125069 +VERTEX_SE2 9 0.716114 0.041122 -2.763139 +VERTEX_SE2 10 0.728981 0.043219 2.905515 +VERTEX_SE2 11 0.733203 0.040537 2.231236 +VERTEX_SE2 12 0.733186 0.041545 1.581762 +VERTEX_SE2 13 0.738753 0.059070 0.922264 +VERTEX_SE2 14 0.759658 0.073750 0.314025 +VERTEX_SE2 15 0.768572 0.074357 -0.210903 +VERTEX_SE2 16 1.062493 0.014152 -0.229595 +VERTEX_SE2 17 1.663647 -0.133115 -0.260823 +VERTEX_SE2 18 2.287001 -0.296480 -0.271000 +VERTEX_SE2 19 2.914298 -0.494254 -0.319576 +VERTEX_SE2 20 3.527220 -0.693985 -0.308933 +VERTEX_SE2 21 4.152895 -0.850915 -0.191238 +VERTEX_SE2 22 4.779015 -0.992339 -0.168556 +VERTEX_SE2 23 5.423978 -1.030005 -0.054484 +VERTEX_SE2 24 6.064382 -1.090997 -0.105423 +VERTEX_SE2 25 6.707928 -1.144401 -0.096821 +VERTEX_SE2 26 7.315680 -1.224079 -0.137153 +VERTEX_SE2 27 7.929761 -1.294250 -0.121079 +VERTEX_SE2 28 8.510243 -1.372635 -0.125240 +VERTEX_SE2 29 8.886549 -1.416447 -0.094136 +VERTEX_SE2 30 8.893462 -1.418023 -0.625522 +VERTEX_SE2 31 9.005697 -1.557779 -0.893355 +VERTEX_SE2 32 9.398300 -2.067296 -0.911506 +VERTEX_SE2 33 9.800909 -2.566880 -0.858368 +VERTEX_SE2 34 10.230894 -3.045076 -0.834898 +VERTEX_SE2 35 10.670845 -3.512974 -0.797906 +VERTEX_SE2 36 11.118351 -3.980273 -0.803680 +VERTEX_SE2 37 11.413882 -4.282108 -0.793023 +VERTEX_SE2 38 11.416535 -4.285316 -1.109584 +VERTEX_SE2 39 11.425445 -4.316267 -1.276487 +VERTEX_SE2 40 11.612551 -4.916547 -1.255922 +VERTEX_SE2 41 11.808527 -5.541274 -1.284316 +VERTEX_SE2 42 11.976726 -6.133098 -1.303279 +VERTEX_SE2 43 12.132495 -6.760248 -1.339357 +VERTEX_SE2 44 12.273339 -7.389611 -1.372003 +VERTEX_SE2 45 12.381155 -8.023418 -1.427426 +VERTEX_SE2 46 12.464524 -8.661631 -1.446702 +VERTEX_SE2 47 12.536773 -9.300726 -1.488240 +VERTEX_SE2 48 12.585187 -9.946461 -1.494639 +VERTEX_SE2 49 12.629508 -10.588502 -1.545288 +VERTEX_SE2 50 12.623735 -11.202499 -1.589586 +VERTEX_SE2 51 12.613473 -11.816834 -1.619614 +VERTEX_SE2 52 12.558110 -12.427134 -1.697131 +VERTEX_SE2 53 12.497320 -13.013155 -1.685264 +VERTEX_SE2 54 12.418711 -13.557683 -1.747661 +VERTEX_SE2 55 12.419724 -13.549747 -1.742676 +VERTEX_SE2 56 12.414345 -13.580353 -1.732396 +VERTEX_SE2 57 12.310914 -14.233877 -1.743844 +VERTEX_SE2 58 12.203756 -14.876538 -1.697418 +VERTEX_SE2 59 12.115088 -15.515348 -1.720561 +VERTEX_SE2 60 12.025760 -16.150800 -1.698500 +VERTEX_SE2 61 11.930749 -16.787980 -1.748266 +VERTEX_SE2 62 11.833006 -17.390733 -1.709239 +VERTEX_SE2 63 11.733602 -17.998517 -1.746382 +VERTEX_SE2 64 11.649132 -18.607583 -1.685617 +VERTEX_SE2 65 11.563367 -19.214882 -1.740522 +VERTEX_SE2 66 11.460058 -19.848621 -1.752656 +VERTEX_SE2 67 11.343148 -20.481952 -1.756181 +VERTEX_SE2 68 11.257571 -20.955257 -1.774331 +VERTEX_SE2 69 11.255185 -20.964979 -1.932353 +VERTEX_SE2 70 11.251937 -20.972069 -2.613265 +VERTEX_SE2 71 11.258227 -20.971402 3.020985 +VERTEX_SE2 72 11.258227 -20.971402 3.009195 +VERTEX_SE2 73 11.254702 -20.970679 2.941681 +VERTEX_SE2 74 11.251643 -20.968771 2.313797 +VERTEX_SE2 75 11.250298 -20.968291 1.957266 +VERTEX_SE2 76 11.239515 -20.956998 2.644600 +VERTEX_SE2 77 11.227570 -20.952338 2.874132 +VERTEX_SE2 78 10.929861 -20.969392 -3.076000 +VERTEX_SE2 79 10.295660 -21.019100 -3.083625 +VERTEX_SE2 80 9.648073 -21.026221 3.122276 +VERTEX_SE2 81 9.008652 -21.005804 3.093707 +VERTEX_SE2 82 8.367330 -20.952196 3.043418 +VERTEX_SE2 83 7.730227 -20.888698 3.024388 +VERTEX_SE2 84 7.095779 -20.785072 2.952781 +VERTEX_SE2 85 6.465179 -20.660326 2.966718 +VERTEX_SE2 86 5.750805 -20.513125 2.886729 +VERTEX_SE2 87 5.163554 -20.341011 2.848617 +VERTEX_SE2 88 4.815868 -20.234565 2.823505 +VERTEX_SE2 89 4.792324 -20.235107 -3.054605 +VERTEX_SE2 90 4.149209 -20.288628 -3.081395 +VERTEX_SE2 91 3.497178 -20.337577 -3.028289 +VERTEX_SE2 92 2.861629 -20.387679 -3.140035 +VERTEX_SE2 93 2.221011 -20.339858 3.045531 +VERTEX_SE2 94 1.585959 -20.258625 3.005168 +VERTEX_SE2 95 0.940663 -20.228767 -3.139936 +VERTEX_SE2 96 0.302216 -20.232542 -3.119921 +VERTEX_SE2 97 -0.314018 -20.219530 3.087656 +VERTEX_SE2 98 -0.922581 -20.164719 3.024330 +VERTEX_SE2 99 -1.648795 -20.093526 3.065410 +VERTEX_SE2 100 -2.230833 -20.023281 3.007277 +VERTEX_SE2 101 -2.871354 -20.005103 3.102942 +VERTEX_SE2 102 -3.516483 -19.955697 3.008603 +VERTEX_SE2 103 -4.152223 -19.878149 3.115724 +VERTEX_SE2 104 -4.795838 -19.847155 3.090758 +VERTEX_SE2 105 -5.440965 -19.834033 -3.137000 +VERTEX_SE2 106 -6.074366 -19.819256 3.099547 +VERTEX_SE2 107 -6.721384 -19.784913 3.102775 +VERTEX_SE2 108 -7.140409 -19.781530 -3.121388 +VERTEX_SE2 109 -7.153321 -19.779550 2.708464 +VERTEX_SE2 110 -7.164494 -19.769929 2.111343 +VERTEX_SE2 111 -7.174123 -19.662635 1.600354 +VERTEX_SE2 112 -7.201482 -19.000514 1.652438 +VERTEX_SE2 113 -7.269988 -18.356059 1.697296 +VERTEX_SE2 114 -7.351668 -17.722124 1.732079 +VERTEX_SE2 115 -7.477063 -17.090635 1.787906 +VERTEX_SE2 116 -7.655600 -16.348269 1.827325 +VERTEX_SE2 117 -7.838440 -15.740356 1.917383 +VERTEX_SE2 118 -7.847180 -15.710500 1.574139 +VERTEX_SE2 119 -7.822729 -15.211952 1.515457 +VERTEX_SE2 120 -7.806541 -14.573234 1.599604 +VERTEX_SE2 121 -7.846755 -13.965257 1.661084 +VERTEX_SE2 122 -7.908309 -13.357352 1.710992 +VERTEX_SE2 123 -7.944931 -13.145472 1.692222 +VERTEX_SE2 124 -7.867047 -12.909702 1.255856 +VERTEX_SE2 125 -7.662551 -12.318719 1.238631 +VERTEX_SE2 126 -7.536130 -11.694942 1.435606 +VERTEX_SE2 127 -7.446823 -11.065323 1.432524 +VERTEX_SE2 128 -7.378220 -10.424022 1.466677 +VERTEX_SE2 129 -7.297629 -9.790420 1.431058 +VERTEX_SE2 130 -7.233612 -9.152396 1.479951 +VERTEX_SE2 131 -7.188908 -8.512333 1.563552 +VERTEX_SE2 132 -7.169731 -7.871150 1.508512 +VERTEX_SE2 133 -7.117635 -7.291335 1.466418 +VERTEX_SE2 134 -7.055851 -6.684237 1.442294 +VERTEX_SE2 135 -6.963757 -6.111663 1.409225 +VERTEX_SE2 136 -6.874804 -5.474955 1.421265 +VERTEX_SE2 137 -6.760504 -4.850881 1.369865 +VERTEX_SE2 138 -6.660597 -4.217332 1.438397 +VERTEX_SE2 139 -6.600415 -3.595492 1.503413 +VERTEX_SE2 140 -6.582744 -2.945853 1.533669 +VERTEX_SE2 141 -6.543894 -2.313106 1.484948 +VERTEX_SE2 142 -6.498552 -1.671107 1.480848 +VERTEX_SE2 143 -6.373361 -1.045821 1.369956 +VERTEX_SE2 144 -6.308206 -0.684059 1.387205 +VERTEX_SE2 145 -6.303725 -0.673188 0.888171 +VERTEX_SE2 146 -6.303130 -0.671010 0.294225 +VERTEX_SE2 147 -6.246280 -0.679152 -0.192923 +VERTEX_SE2 148 -5.818303 -0.770932 -0.228866 +VERTEX_SE2 149 -5.184464 -0.911850 -0.204032 +VERTEX_SE2 150 -4.555178 -1.023116 -0.190122 +VERTEX_SE2 151 -3.919217 -1.117808 -0.104723 +VERTEX_SE2 152 -3.282062 -1.199418 -0.172903 +VERTEX_SE2 153 -2.645312 -1.282994 -0.087181 +VERTEX_SE2 154 -2.011150 -1.359207 -0.164419 +VERTEX_SE2 155 -1.375820 -1.453297 -0.137992 +VERTEX_SE2 156 -0.735790 -1.532677 -0.114327 +VERTEX_SE2 157 -0.159947 -1.613323 -0.186690 +VERTEX_SE2 158 0.023851 -1.648467 -0.157600 +VERTEX_SE2 159 0.021228 -1.647288 0.835817 +VERTEX_SE2 160 0.027488 -1.639228 1.877886 +VERTEX_SE2 161 0.027486 -1.639234 2.859828 +VERTEX_SE2 162 0.045975 -1.631965 -2.381155 +VERTEX_SE2 163 0.045893 -1.634205 -1.377922 +VERTEX_SE2 164 0.057499 -1.646265 -0.447964 +VERTEX_SE2 165 0.193934 -1.655710 -0.045831 +VERTEX_SE2 166 0.853469 -1.682017 -0.046800 +VERTEX_SE2 167 1.490484 -1.716964 -0.075973 +VERTEX_SE2 168 2.098800 -1.751671 -0.063936 +VERTEX_SE2 169 2.712806 -1.808931 -0.100989 +VERTEX_SE2 170 3.318192 -1.863258 -0.121905 +VERTEX_SE2 171 3.896234 -1.949098 -0.160646 +VERTEX_SE2 172 4.538410 -2.042425 -0.147172 +VERTEX_SE2 173 5.172424 -2.149723 -0.165214 +VERTEX_SE2 174 5.803089 -2.247662 -0.120052 +VERTEX_SE2 175 6.424807 -2.318550 -0.139998 +VERTEX_SE2 176 7.030678 -2.417232 -0.125711 +VERTEX_SE2 177 7.660479 -2.494551 -0.148623 +VERTEX_SE2 178 8.290147 -2.612123 -0.182806 +VERTEX_SE2 179 8.639509 -2.668503 -0.129585 +VERTEX_SE2 180 8.642601 -2.669171 -0.571750 +VERTEX_SE2 181 9.107062 -2.977761 -0.623138 +VERTEX_SE2 182 9.551340 -3.341562 -0.796106 +VERTEX_SE2 183 9.953562 -3.792478 -0.852123 +VERTEX_SE2 184 10.330878 -4.306658 -1.002936 +VERTEX_SE2 185 10.652963 -4.854256 -1.099221 +VERTEX_SE2 186 10.909459 -5.445570 -1.168989 +VERTEX_SE2 187 11.138453 -6.018162 -1.194573 +VERTEX_SE2 188 11.372847 -6.610777 -1.202696 +VERTEX_SE2 189 11.598101 -7.209159 -1.232095 +VERTEX_SE2 190 11.795596 -7.819838 -1.258284 +VERTEX_SE2 191 11.984938 -8.432395 -1.279246 +VERTEX_SE2 192 12.158054 -9.043198 -1.303901 +VERTEX_SE2 193 12.302583 -9.611434 -1.355161 +VERTEX_SE2 194 12.426909 -10.210284 -1.377141 +VERTEX_SE2 195 12.534319 -10.811416 -1.400368 +VERTEX_SE2 196 12.632338 -11.445843 -1.442220 +VERTEX_SE2 197 12.700713 -12.082422 -1.470453 +VERTEX_SE2 198 12.755597 -12.719166 -1.529113 +VERTEX_SE2 199 12.754761 -13.356843 -1.590711 +VERTEX_SE2 200 12.733560 -13.993458 -1.612475 +VERTEX_SE2 201 12.687026 -14.631689 -1.668718 +VERTEX_SE2 202 12.639077 -15.202899 -1.651577 +VERTEX_SE2 203 12.556158 -16.006543 -1.707054 +VERTEX_SE2 204 12.455302 -16.598850 -1.804142 +VERTEX_SE2 205 12.305924 -17.187841 -1.809172 +VERTEX_SE2 206 12.174405 -17.760149 -1.802549 +VERTEX_SE2 207 12.040676 -18.353284 -1.781423 +VERTEX_SE2 208 11.897670 -18.981299 -1.785518 +VERTEX_SE2 209 11.769917 -19.609340 -1.741125 +VERTEX_SE2 210 11.647398 -20.238835 -1.754048 +VERTEX_SE2 211 11.537207 -20.870318 -1.755716 +VERTEX_SE2 212 11.394970 -21.493361 -1.812926 +VERTEX_SE2 213 11.230953 -22.120731 -1.837752 +VERTEX_SE2 214 11.058372 -22.734177 -1.845436 +VERTEX_SE2 215 10.953834 -23.088866 -1.885350 +VERTEX_SE2 216 10.950554 -23.095138 -2.393113 +VERTEX_SE2 217 10.952753 -23.094815 -2.944927 +VERTEX_SE2 218 10.951809 -23.094487 -3.005204 +VERTEX_SE2 219 10.365803 -23.067344 3.104107 +VERTEX_SE2 220 9.737327 -23.038247 3.059963 +VERTEX_SE2 221 9.095837 -22.994717 3.111718 +VERTEX_SE2 222 8.460944 -22.975047 3.086737 +VERTEX_SE2 223 7.821250 -22.969336 -3.100192 +VERTEX_SE2 224 7.183803 -22.994444 -3.126677 +VERTEX_SE2 225 6.544582 -23.012637 -3.078368 +VERTEX_SE2 226 5.906305 -23.029186 -3.129535 +VERTEX_SE2 227 5.264179 -23.084344 -2.972817 +VERTEX_SE2 228 4.660809 -23.049652 2.951621 +VERTEX_SE2 229 4.059169 -22.969281 3.076549 +VERTEX_SE2 230 3.689211 -22.947652 3.051106 +VERTEX_SE2 231 3.819912 -22.954624 3.124109 +VERTEX_SE2 232 3.476990 -22.813142 2.710350 +VERTEX_SE2 233 2.875321 -22.565879 2.819555 +VERTEX_SE2 234 2.261463 -22.358960 2.781360 +VERTEX_SE2 235 1.979653 -22.255530 2.781875 +VERTEX_SE2 236 1.616344 -22.278805 -3.083673 +VERTEX_SE2 237 0.964219 -22.341873 -3.006771 +VERTEX_SE2 238 0.323899 -22.443278 -3.033605 +VERTEX_SE2 239 -0.317791 -22.494927 -3.094849 +VERTEX_SE2 240 -0.925503 -22.426348 2.978831 +VERTEX_SE2 241 -1.504549 -22.345735 3.071089 +VERTEX_SE2 242 -2.117312 -22.325210 3.098446 +VERTEX_SE2 243 -2.764025 -22.279874 3.087887 +VERTEX_SE2 244 -3.406724 -22.271623 -3.133223 +VERTEX_SE2 245 -4.041131 -22.254659 3.087973 +VERTEX_SE2 246 -4.684337 -22.191483 3.008717 +VERTEX_SE2 247 -5.325218 -22.128855 3.108731 +VERTEX_SE2 248 -5.890123 -22.137360 3.133698 +VERTEX_SE2 249 -5.854210 -22.141017 -2.965499 +VERTEX_SE2 250 -5.862024 -22.141342 2.710834 +VERTEX_SE2 251 -6.210340 -21.788237 2.273028 +VERTEX_SE2 252 -6.584399 -21.351579 2.275461 +VERTEX_SE2 253 -6.971866 -20.886741 2.258217 +VERTEX_SE2 254 -7.349642 -20.406697 2.210371 +VERTEX_SE2 255 -7.376562 -20.371386 2.285362 +VERTEX_SE2 256 -7.376569 -20.370011 1.785796 +VERTEX_SE2 257 -7.435125 -19.813876 1.686629 +VERTEX_SE2 258 -7.526140 -19.190499 1.778261 +VERTEX_SE2 259 -7.676213 -18.571996 1.817167 +VERTEX_SE2 260 -7.815262 -17.997419 1.807084 +VERTEX_SE2 261 -7.812802 -17.957528 1.492756 +VERTEX_SE2 262 -7.748761 -17.305023 1.497634 +VERTEX_SE2 263 -7.704459 -16.684761 1.509160 +VERTEX_SE2 264 -7.686285 -16.075835 1.603801 +VERTEX_SE2 265 -7.713685 -15.464092 1.621756 +VERTEX_SE2 266 -7.659836 -14.884512 1.489698 +VERTEX_SE2 267 -7.590637 -14.130213 1.451229 +VERTEX_SE2 268 -7.434892 -13.512524 1.330524 +VERTEX_SE2 269 -7.285843 -12.888133 1.352351 +VERTEX_SE2 270 -7.181145 -12.258185 1.457078 +VERTEX_SE2 271 -7.046662 -11.629374 1.337392 +VERTEX_SE2 272 -6.916330 -10.998172 1.394889 +VERTEX_SE2 273 -6.887272 -10.359052 1.601643 +VERTEX_SE2 274 -6.914937 -9.718617 1.621477 +VERTEX_SE2 275 -6.859410 -9.108548 1.443918 +VERTEX_SE2 276 -6.805341 -8.498288 1.552614 +VERTEX_SE2 277 -6.805090 -7.914615 1.521694 +VERTEX_SE2 278 -6.706035 -7.282637 1.426405 +VERTEX_SE2 279 -6.600956 -6.648396 1.372248 +VERTEX_SE2 280 -6.468990 -6.023366 1.375327 +VERTEX_SE2 281 -6.315271 -5.399485 1.276051 +VERTEX_SE2 282 -6.134008 -4.785899 1.316907 +VERTEX_SE2 283 -5.985222 -4.161193 1.309959 +VERTEX_SE2 284 -5.813249 -3.550243 1.337990 +VERTEX_SE2 285 -5.683475 -2.918967 1.354789 +VERTEX_SE2 286 -5.554450 -2.315719 1.403911 +VERTEX_SE2 287 -5.547714 -2.274662 1.294491 +VERTEX_SE2 288 -5.541900 -2.266525 0.674528 +VERTEX_SE2 289 -5.522271 -2.259034 0.069939 +VERTEX_SE2 290 -5.061939 -2.331133 -0.161343 +VERTEX_SE2 291 -4.422087 -2.430958 -0.151620 +VERTEX_SE2 292 -3.797538 -2.541567 -0.206901 +VERTEX_SE2 293 -3.169915 -2.679421 -0.230678 +VERTEX_SE2 294 -2.547430 -2.824259 -0.230786 +VERTEX_SE2 295 -1.930374 -2.997710 -0.344395 +VERTEX_SE2 296 -1.332265 -3.234619 -0.390911 +VERTEX_SE2 297 -0.738078 -3.478649 -0.403774 +VERTEX_SE2 298 -0.140714 -3.729757 -0.400411 +VERTEX_SE2 299 0.420679 -3.975672 -0.334750 +VERTEX_SE2 300 1.008544 -4.149557 -0.288323 +VERTEX_SE2 301 1.570135 -4.331714 -0.343252 +VERTEX_SE2 302 1.877809 -4.442855 -0.360266 +VERTEX_SE2 303 1.877809 -4.442855 -0.352308 +VERTEX_SE2 304 2.376686 -4.626875 -0.338959 +VERTEX_SE2 305 3.003258 -4.750507 -0.149877 +VERTEX_SE2 306 3.635522 -4.836601 -0.164412 +VERTEX_SE2 307 4.273138 -4.958970 -0.197471 +VERTEX_SE2 308 4.897872 -5.092864 -0.249303 +VERTEX_SE2 309 5.530724 -5.222563 -0.152307 +VERTEX_SE2 310 6.160264 -5.318301 -0.184629 +VERTEX_SE2 311 6.445365 -5.373694 -0.004883 +VERTEX_SE2 312 6.452735 -5.370466 0.998034 +VERTEX_SE2 313 6.475194 -5.146827 1.501717 +VERTEX_SE2 314 6.500598 -4.513221 1.545236 +VERTEX_SE2 315 6.514519 -3.879666 1.544361 +VERTEX_SE2 316 6.515603 -3.240166 1.596992 +VERTEX_SE2 317 6.494598 -2.602753 1.608134 +VERTEX_SE2 318 6.435460 -1.967773 1.704091 +VERTEX_SE2 319 6.377663 -1.623559 1.776803 +VERTEX_SE2 320 6.378012 -1.622652 2.750031 +VERTEX_SE2 321 6.369361 -1.625849 -2.488361 +VERTEX_SE2 322 6.365946 -1.632038 -1.487277 +VERTEX_SE2 323 6.380435 -1.647235 -0.490000 +VERTEX_SE2 324 6.388880 -1.650346 0.173199 +VERTEX_SE2 325 6.392046 -1.650203 -0.351692 +VERTEX_SE2 326 6.411655 -1.665878 -0.943866 +VERTEX_SE2 327 6.415870 -1.688728 -1.564092 +VERTEX_SE2 328 6.385292 -2.332605 -1.609333 +VERTEX_SE2 329 6.349431 -2.981039 -1.664005 +VERTEX_SE2 330 6.281461 -3.617106 -1.682877 +VERTEX_SE2 331 6.213453 -4.254537 -1.697056 +VERTEX_SE2 332 6.121245 -4.888223 -1.715483 +VERTEX_SE2 333 6.093922 -5.063750 -1.650313 +VERTEX_SE2 334 6.091827 -5.064491 -0.592795 +VERTEX_SE2 335 6.120861 -5.065606 0.404271 +VERTEX_SE2 336 6.129696 -5.059618 1.351179 +VERTEX_SE2 337 6.128718 -5.050440 2.336187 +VERTEX_SE2 338 6.132587 -5.051833 -2.965274 +VERTEX_SE2 339 6.136968 -5.047185 -1.923597 +VERTEX_SE2 340 6.142971 -5.060659 -0.911817 +VERTEX_SE2 341 6.275970 -5.101488 -0.283246 +VERTEX_SE2 342 6.910811 -5.263299 -0.183431 +VERTEX_SE2 343 7.538989 -5.324161 -0.052630 +VERTEX_SE2 344 8.173624 -5.364758 -0.062705 +VERTEX_SE2 345 8.440897 -5.378047 -0.090243 +VERTEX_SE2 346 8.445372 -5.378415 -0.737666 +VERTEX_SE2 347 8.467770 -5.462068 -1.296495 +VERTEX_SE2 348 8.621467 -6.030776 -1.313338 +VERTEX_SE2 349 8.761762 -6.631679 -1.353796 +VERTEX_SE2 350 8.929986 -7.398958 -1.373714 +VERTEX_SE2 351 8.978041 -7.665351 -1.403006 +VERTEX_SE2 352 8.978090 -7.667619 -1.691302 +VERTEX_SE2 353 8.976498 -7.670853 -2.356727 +VERTEX_SE2 354 8.981756 -7.667962 -2.960124 +VERTEX_SE2 355 8.981756 -7.667962 2.602071 +VERTEX_SE2 356 8.978992 -7.664902 2.026818 +VERTEX_SE2 357 8.977837 -7.643021 1.373746 +VERTEX_SE2 358 8.983884 -7.628618 0.758292 +VERTEX_SE2 359 8.989631 -7.624545 0.144263 +VERTEX_SE2 360 8.994126 -7.624478 -0.032038 +VERTEX_SE2 361 9.004896 -7.619118 0.887338 +VERTEX_SE2 362 9.042246 -7.366063 1.421081 +VERTEX_SE2 363 9.090049 -7.072841 1.414605 +VERTEX_SE2 364 8.954880 -6.758641 2.029221 +VERTEX_SE2 365 8.843129 -6.487231 1.532139 +VERTEX_SE2 366 8.933049 -6.331605 0.978068 +VERTEX_SE2 367 9.294391 -5.803956 0.980155 +VERTEX_SE2 368 9.641307 -5.309201 0.927211 +VERTEX_SE2 369 9.642383 -5.307246 0.668025 +VERTEX_SE2 370 9.648356 -5.305144 0.068704 +VERTEX_SE2 371 9.655229 -5.307316 -0.488502 +VERTEX_SE2 372 10.139103 -5.587085 -0.520850 +VERTEX_SE2 373 10.666751 -5.878088 -0.523177 +VERTEX_SE2 374 11.206068 -6.209159 -0.589126 +VERTEX_SE2 375 11.598593 -6.466633 -0.617897 +VERTEX_SE2 376 11.600632 -6.467490 0.080627 +VERTEX_SE2 377 11.643620 -6.425565 0.779646 +VERTEX_SE2 378 12.107190 -5.948151 0.834726 +VERTEX_SE2 379 12.510240 -5.446009 0.920455 +VERTEX_SE2 380 12.867606 -4.912917 1.040753 +VERTEX_SE2 381 12.982544 -4.709680 1.191659 +VERTEX_SE2 382 12.984649 -4.703709 2.244782 +VERTEX_SE2 383 12.988448 -4.705226 -3.058347 +VERTEX_SE2 384 12.986650 -4.707628 -2.101256 +VERTEX_SE2 385 12.982495 -4.718256 -1.078274 +VERTEX_SE2 386 13.111397 -4.840399 -0.855882 +VERTEX_SE2 387 13.631915 -5.191372 -0.527133 +VERTEX_SE2 388 14.188298 -5.499440 -0.516375 +VERTEX_SE2 389 14.722428 -5.830510 -0.596695 +VERTEX_SE2 390 14.780394 -5.868314 -0.117993 +VERTEX_SE2 391 14.643686 -5.885580 0.265004 +VERTEX_SE2 392 14.640989 -5.886114 1.312766 +VERTEX_SE2 393 14.635188 -5.855400 2.572219 +VERTEX_SE2 394 14.626068 -5.853862 -2.712409 +VERTEX_SE2 395 14.810464 -5.693039 -2.372812 +VERTEX_SE2 396 14.810464 -5.693039 -2.371562 +VERTEX_SE2 397 14.809202 -5.693678 -2.381203 +VERTEX_SE2 398 14.806796 -5.697007 -2.182098 +VERTEX_SE2 399 14.762364 -5.814932 -1.881357 +VERTEX_SE2 400 14.564819 -6.441727 -1.829942 +VERTEX_SE2 401 14.377600 -7.049960 -1.921842 +VERTEX_SE2 402 14.049396 -7.600148 -2.188305 +VERTEX_SE2 403 13.678588 -8.113304 -2.221999 +VERTEX_SE2 404 13.306297 -8.574268 -2.300702 +VERTEX_SE2 405 13.304585 -8.576945 -1.766179 +VERTEX_SE2 406 13.302371 -8.571544 -0.786819 +VERTEX_SE2 407 13.585994 -8.797369 -0.658504 +VERTEX_SE2 408 14.069560 -9.180165 -0.696311 +VERTEX_SE2 409 14.292699 -9.377696 -0.795739 +VERTEX_SE2 410 14.294947 -9.381536 -1.423249 +VERTEX_SE2 411 14.294896 -9.380539 -2.012202 +VERTEX_SE2 412 13.969601 -9.830799 -2.215053 +VERTEX_SE2 413 13.573781 -10.323212 -2.294584 +VERTEX_SE2 414 13.168212 -10.809845 -2.190851 +VERTEX_SE2 415 12.788348 -11.328437 -2.184168 +VERTEX_SE2 416 12.618672 -11.583273 -2.239720 +VERTEX_SE2 417 12.365589 -11.724804 -2.664770 +VERTEX_SE2 418 11.973570 -11.921372 -2.710238 +VERTEX_SE2 419 11.979618 -11.915306 -2.279799 +VERTEX_SE2 420 12.016291 -11.860711 -2.064037 +VERTEX_SE2 421 12.016287 -11.845604 -1.097383 +VERTEX_SE2 422 12.016575 -11.841230 0.140539 +VERTEX_SE2 423 12.021144 -11.838978 0.485675 +VERTEX_SE2 424 12.021144 -11.838978 0.485954 +VERTEX_SE2 425 12.020459 -11.840215 0.497589 +VERTEX_SE2 426 12.020459 -11.840215 0.488372 +VERTEX_SE2 427 12.049082 -11.824671 0.491399 +VERTEX_SE2 428 12.625045 -11.496891 0.485740 +VERTEX_SE2 429 13.200413 -11.202813 0.444713 +VERTEX_SE2 430 13.512701 -11.059854 0.398340 +VERTEX_SE2 431 13.491669 -11.069431 0.449977 +VERTEX_SE2 432 13.501654 -11.067336 -0.182740 +VERTEX_SE2 433 13.502954 -11.067884 -0.861102 +VERTEX_SE2 434 13.743529 -11.537644 -1.089862 +VERTEX_SE2 435 14.040604 -12.094609 -1.118566 +VERTEX_SE2 436 14.297216 -12.672347 -1.127731 +VERTEX_SE2 437 14.580075 -13.245886 -1.120167 +VERTEX_SE2 438 14.774602 -13.672697 -1.152842 +VERTEX_SE2 439 14.775466 -13.675785 -1.592980 +VERTEX_SE2 440 14.781226 -13.661057 -2.241615 +VERTEX_SE2 441 14.801541 -13.646476 -2.868987 +VERTEX_SE2 442 14.816809 -13.646193 2.779417 +VERTEX_SE2 443 14.817345 -13.647038 2.207553 +VERTEX_SE2 444 14.811569 -13.629249 1.610879 +VERTEX_SE2 445 14.815891 -13.615770 0.947107 +VERTEX_SE2 446 14.818888 -13.610711 1.145697 +VERTEX_SE2 447 14.818661 -13.580487 1.771810 +VERTEX_SE2 448 14.666760 -12.956104 1.786852 +VERTEX_SE2 449 14.494693 -12.326428 1.885308 +VERTEX_SE2 450 14.289690 -11.713731 1.896557 +VERTEX_SE2 451 14.124257 -11.267884 1.936509 +VERTEX_SE2 452 14.123115 -11.264972 1.553661 +VERTEX_SE2 453 14.123047 -11.266384 0.924731 +VERTEX_SE2 454 14.355665 -11.130372 0.497531 +VERTEX_SE2 455 14.885259 -10.850245 0.477764 +VERTEX_SE2 456 15.454443 -10.572873 0.414138 +VERTEX_SE2 457 15.786015 -10.438633 0.327481 +VERTEX_SE2 458 15.795226 -10.438701 -0.315965 +VERTEX_SE2 459 15.791330 -10.434037 -0.921822 +VERTEX_SE2 460 15.959734 -10.828507 -1.177398 +VERTEX_SE2 461 16.180144 -11.439953 -1.264281 +VERTEX_SE2 462 16.335308 -11.963645 -1.303337 +VERTEX_SE2 463 16.335291 -11.965068 -0.460067 +VERTEX_SE2 464 16.605696 -11.914838 0.220623 +VERTEX_SE2 465 17.195283 -11.771695 0.229379 +VERTEX_SE2 466 17.767104 -11.657874 0.174926 +VERTEX_SE2 467 18.369280 -11.563197 0.132707 +VERTEX_SE2 468 19.009735 -11.482106 0.096378 +VERTEX_SE2 469 19.650896 -11.453733 0.012587 +VERTEX_SE2 470 20.146853 -11.442829 0.030741 +VERTEX_SE2 471 20.150029 -11.442932 -0.170062 +VERTEX_SE2 472 20.172311 -11.454699 -0.804400 +VERTEX_SE2 473 20.175889 -11.459298 -1.446679 +VERTEX_SE2 474 20.174399 -11.466191 -2.079685 +VERTEX_SE2 475 20.170246 -11.468957 -2.655668 +VERTEX_SE2 476 20.165497 -11.470500 2.973880 +VERTEX_SE2 477 20.170525 -11.474309 2.412190 +VERTEX_SE2 478 20.175145 -11.482300 1.782778 +VERTEX_SE2 479 20.175335 -11.487697 1.326596 +VERTEX_SE2 480 20.175383 -11.489918 1.886460 +VERTEX_SE2 481 20.164295 -11.475887 2.884919 +VERTEX_SE2 482 20.162062 -11.476008 -3.063751 +VERTEX_SE2 483 20.162062 -11.476008 -3.070064 +VERTEX_SE2 484 19.701970 -11.512371 -3.035533 +VERTEX_SE2 485 19.076677 -11.593317 -3.038332 +VERTEX_SE2 486 18.439371 -11.653164 -3.029341 +VERTEX_SE2 487 17.807280 -11.746714 -3.001669 +VERTEX_SE2 488 17.172291 -11.839127 -2.966212 +VERTEX_SE2 489 16.696147 -11.938931 -2.936476 +VERTEX_SE2 490 16.692490 -11.941051 -2.452793 +VERTEX_SE2 491 16.691616 -11.944932 -1.519098 +VERTEX_SE2 492 16.776617 -12.175290 -1.217149 +VERTEX_SE2 493 16.974062 -12.765556 -1.272900 +VERTEX_SE2 494 17.150447 -13.373462 -1.334510 +VERTEX_SE2 495 17.352115 -13.978346 -1.223707 +VERTEX_SE2 496 17.581624 -14.577196 -1.102707 +VERTEX_SE2 497 17.847299 -15.159575 -1.186084 +VERTEX_SE2 498 18.054425 -15.760767 -1.285551 +VERTEX_SE2 499 18.205483 -16.382164 -1.300921 +VERTEX_SE2 500 18.520086 -16.898620 -0.969638 +VERTEX_SE2 501 18.848430 -17.411482 -1.035455 +VERTEX_SE2 502 19.181866 -18.047877 -1.113614 +VERTEX_SE2 503 19.382829 -18.470616 -1.125142 +VERTEX_SE2 504 19.382968 -18.471669 -0.242877 +VERTEX_SE2 505 19.636847 -18.373822 0.396037 +VERTEX_SE2 506 20.222463 -18.152233 0.250781 +VERTEX_SE2 507 20.842906 -18.012083 0.178603 +VERTEX_SE2 508 21.473389 -17.912172 0.170945 +VERTEX_SE2 509 22.107555 -17.811551 0.119274 +VERTEX_SE2 510 22.477732 -17.773275 0.109324 +VERTEX_SE2 511 22.480191 -17.776579 1.000327 +VERTEX_SE2 512 22.479151 -17.767197 2.221724 +VERTEX_SE2 513 22.480923 -17.768589 -3.088724 +VERTEX_SE2 514 22.392210 -17.797083 -2.856452 +VERTEX_SE2 515 21.763760 -17.994866 -2.851524 +VERTEX_SE2 516 21.150540 -18.168893 -2.831780 +VERTEX_SE2 517 20.555780 -18.389856 -2.799728 +VERTEX_SE2 518 19.960512 -18.610158 -2.771638 +VERTEX_SE2 519 19.439217 -18.815169 -2.783788 +VERTEX_SE2 520 19.254408 -18.883689 -2.378354 +VERTEX_SE2 521 19.253544 -18.891468 -1.358862 +VERTEX_SE2 522 19.446557 -19.274210 -1.088837 +VERTEX_SE2 523 19.743533 -19.846628 -1.102099 +VERTEX_SE2 524 20.002482 -20.395419 -1.149751 +VERTEX_SE2 525 20.240546 -20.920829 -1.130979 +VERTEX_SE2 526 20.481533 -21.478440 -1.194565 +VERTEX_SE2 527 20.701007 -22.071838 -1.233424 +VERTEX_SE2 528 20.883349 -22.686071 -1.313266 +VERTEX_SE2 529 21.048790 -23.294125 -1.338785 +VERTEX_SE2 530 21.186548 -23.922294 -1.365903 +VERTEX_SE2 531 21.294513 -24.545568 -1.442267 +VERTEX_SE2 532 21.321981 -24.753969 -1.388289 +VERTEX_SE2 533 21.331696 -24.762834 -0.381514 +VERTEX_SE2 534 21.336665 -24.762597 0.290307 +VERTEX_SE2 535 21.336665 -24.762597 0.291645 +VERTEX_SE2 536 21.667408 -24.621679 0.424610 +VERTEX_SE2 537 22.237616 -24.383793 0.368660 +VERTEX_SE2 538 22.783578 -24.188298 0.343558 +VERTEX_SE2 539 23.392496 -23.994630 0.281055 +VERTEX_SE2 540 24.012651 -23.846863 0.190656 +VERTEX_SE2 541 24.616500 -23.677520 0.355935 +VERTEX_SE2 542 25.198874 -23.413487 0.414186 +VERTEX_SE2 543 25.308230 -23.366534 0.386937 +VERTEX_SE2 544 25.311458 -23.363477 1.030295 +VERTEX_SE2 545 25.308953 -23.348021 2.106974 +VERTEX_SE2 546 25.370099 -23.384281 2.942044 +VERTEX_SE2 547 25.364196 -23.389842 -2.309543 +VERTEX_SE2 548 25.360603 -23.401304 -1.377667 +VERTEX_SE2 549 25.371198 -23.418104 -0.563163 +VERTEX_SE2 550 25.376228 -23.423323 -1.037842 +VERTEX_SE2 551 25.379648 -23.436304 -1.657979 +VERTEX_SE2 552 25.377719 -23.441024 -2.284180 +VERTEX_SE2 553 25.238021 -23.493388 -2.855731 +VERTEX_SE2 554 24.607784 -23.677279 -2.888859 +VERTEX_SE2 555 23.993431 -23.860841 -2.797492 +VERTEX_SE2 556 23.396241 -24.105763 -2.659796 +VERTEX_SE2 557 22.822728 -24.393516 -2.702744 +VERTEX_SE2 558 22.275040 -24.674698 -2.623823 +VERTEX_SE2 559 22.270077 -24.676821 -3.034381 +VERTEX_SE2 560 22.270077 -24.676821 2.743761 +VERTEX_SE2 561 22.260080 -24.676351 -3.038320 +VERTEX_SE2 562 22.096754 -24.820650 -2.399936 +VERTEX_SE2 563 21.592502 -25.154311 -2.594747 +VERTEX_SE2 564 21.053412 -25.498706 -2.548499 +VERTEX_SE2 565 20.537425 -25.832798 -2.600465 +VERTEX_SE2 566 20.532490 -25.835035 -1.796294 +VERTEX_SE2 567 20.533426 -25.833987 -0.940208 +VERTEX_SE2 568 20.891388 -26.294540 -0.894012 +VERTEX_SE2 569 21.276856 -26.790552 -0.946159 +VERTEX_SE2 570 21.649420 -27.310717 -0.950967 +VERTEX_SE2 571 21.849361 -27.596250 -0.994364 +VERTEX_SE2 572 21.840333 -27.646492 -1.231717 +VERTEX_SE2 573 21.868880 -27.724009 -0.949072 +VERTEX_SE2 574 21.877216 -27.725452 0.006744 +VERTEX_SE2 575 21.894503 -27.715687 1.016050 +VERTEX_SE2 576 21.893519 -27.715892 2.040189 +VERTEX_SE2 577 21.885895 -27.713246 3.008947 +VERTEX_SE2 578 21.866274 -27.704702 2.643177 +VERTEX_SE2 579 21.298924 -27.387881 2.657278 +VERTEX_SE2 580 20.716909 -27.105551 2.731333 +VERTEX_SE2 581 20.125767 -26.856860 2.772637 +VERTEX_SE2 582 19.523535 -26.633599 2.814640 +VERTEX_SE2 583 19.213810 -26.536403 2.892766 +VERTEX_SE2 584 19.210319 -26.535584 -2.550218 +VERTEX_SE2 585 18.716874 -26.893765 -2.433208 +VERTEX_SE2 586 18.264978 -27.304159 -2.336932 +VERTEX_SE2 587 17.844050 -27.776684 -2.312675 +VERTEX_SE2 588 17.404102 -28.246717 -2.309353 +VERTEX_SE2 589 17.007668 -28.742973 -2.229083 +VERTEX_SE2 590 16.625023 -29.262060 -2.155304 +VERTEX_SE2 591 16.286319 -29.796280 -2.152683 +VERTEX_SE2 592 15.939159 -30.336565 -2.150686 +VERTEX_SE2 593 15.791190 -30.564791 -1.938181 +VERTEX_SE2 594 15.794250 -30.581455 -0.945084 +VERTEX_SE2 595 16.194292 -30.997078 -0.704760 +VERTEX_SE2 596 16.636104 -31.366417 -0.722635 +VERTEX_SE2 597 17.103989 -31.796447 -0.756770 +VERTEX_SE2 598 17.538795 -32.215917 -0.796372 +VERTEX_SE2 599 17.800839 -32.499098 -0.859831 +VERTEX_SE2 600 17.808423 -32.504032 -0.045074 +VERTEX_SE2 601 17.830600 -32.493623 0.983541 +VERTEX_SE2 602 17.834247 -32.474305 2.007952 +VERTEX_SE2 603 17.607884 -32.374428 2.788384 +VERTEX_SE2 604 17.046943 -32.100473 2.547892 +VERTEX_SE2 605 16.511286 -31.761753 2.630512 +VERTEX_SE2 606 15.949994 -31.464096 2.672598 +VERTEX_SE2 607 15.464785 -31.153778 2.591564 +VERTEX_SE2 608 15.140800 -30.969820 2.636022 +VERTEX_SE2 609 15.131468 -30.966068 2.972317 +VERTEX_SE2 610 15.122044 -30.973580 -2.378251 +VERTEX_SE2 611 14.678938 -31.406105 -2.375287 +VERTEX_SE2 612 14.313602 -31.741587 -2.372510 +VERTEX_SE2 613 14.338061 -31.720011 -1.908805 +VERTEX_SE2 614 14.338698 -31.726674 -0.870968 +VERTEX_SE2 615 14.768768 -31.977559 -0.566453 +VERTEX_SE2 616 15.311642 -32.305648 -0.617609 +VERTEX_SE2 617 15.760313 -32.746217 -0.834639 +VERTEX_SE2 618 16.193436 -33.214065 -0.824521 +VERTEX_SE2 619 16.601337 -33.656810 -0.825989 +VERTEX_SE2 620 17.000072 -34.120401 -0.922318 +VERTEX_SE2 621 16.788426 -33.839458 -0.973924 +VERTEX_SE2 622 16.630958 -33.597689 -1.048966 +VERTEX_SE2 623 16.629619 -33.594321 -1.586115 +VERTEX_SE2 624 16.631309 -33.591662 -2.228805 +VERTEX_SE2 625 16.624999 -33.596266 -2.887438 +VERTEX_SE2 626 16.617480 -33.597475 2.777619 +VERTEX_SE2 627 16.349285 -33.346497 2.366813 +VERTEX_SE2 628 15.919513 -32.868045 2.265896 +VERTEX_SE2 629 15.485805 -32.395397 2.336946 +VERTEX_SE2 630 15.046318 -31.973583 2.422035 +VERTEX_SE2 631 14.646636 -31.639639 2.442255 +VERTEX_SE2 632 14.643929 -31.637238 3.118464 +VERTEX_SE2 633 14.589597 -31.712326 -2.089116 +VERTEX_SE2 634 14.266192 -32.277649 -2.063889 +VERTEX_SE2 635 13.925936 -32.819825 -2.201180 +VERTEX_SE2 636 13.554818 -33.335756 -2.220264 +VERTEX_SE2 637 13.147645 -33.820778 -2.320948 +VERTEX_SE2 638 12.855265 -34.121161 -2.351695 +VERTEX_SE2 639 12.424371 -34.596136 -2.272930 +VERTEX_SE2 640 11.985578 -35.070016 -2.342632 +VERTEX_SE2 641 11.552638 -35.529379 -2.352802 +VERTEX_SE2 642 11.112191 -35.949492 -2.400353 +VERTEX_SE2 643 10.731895 -36.277399 -2.465381 +VERTEX_SE2 644 10.729340 -36.284109 -1.701776 +VERTEX_SE2 645 10.869715 -36.451460 -0.744873 +VERTEX_SE2 646 11.382066 -36.817597 -0.447477 +VERTEX_SE2 647 11.978978 -37.021611 -0.156322 +VERTEX_SE2 648 12.612056 -37.054234 0.012089 +VERTEX_SE2 649 13.205551 -37.119561 -0.322437 +VERTEX_SE2 650 13.749716 -37.452144 -0.576811 +VERTEX_SE2 651 13.876986 -37.522144 0.229018 +VERTEX_SE2 652 13.879256 -37.519914 1.262617 +VERTEX_SE2 653 13.872372 -37.502026 2.301465 +VERTEX_SE2 654 13.581181 -37.403460 2.818912 +VERTEX_SE2 655 13.048482 -37.219840 2.815600 +VERTEX_SE2 656 12.474722 -37.010334 2.804516 +VERTEX_SE2 657 11.844104 -36.899464 3.083365 +VERTEX_SE2 658 11.204549 -36.869297 3.076381 +VERTEX_SE2 659 10.709556 -36.810477 3.005332 +VERTEX_SE2 660 10.703219 -36.809512 -2.677502 +VERTEX_SE2 661 10.609221 -37.000250 -2.023854 +VERTEX_SE2 662 10.337163 -37.568215 -1.954223 +VERTEX_SE2 663 10.139552 -38.159090 -1.853215 +VERTEX_SE2 664 10.135226 -38.165415 -1.314901 +VERTEX_SE2 665 10.170577 -38.183639 -0.436050 +VERTEX_SE2 666 10.743964 -38.430041 -0.401598 +VERTEX_SE2 667 11.280508 -38.651643 -0.399484 +VERTEX_SE2 668 11.840921 -38.888748 -0.376305 +VERTEX_SE2 669 12.435464 -39.121854 -0.404047 +VERTEX_SE2 670 13.006910 -39.403898 -0.466305 +VERTEX_SE2 671 13.282608 -39.541377 -0.414044 +VERTEX_SE2 672 12.769426 -39.275957 -0.506105 +VERTEX_SE2 673 12.545541 -39.138628 -0.639846 +VERTEX_SE2 674 12.542473 -39.133012 -1.294945 +VERTEX_SE2 675 12.544204 -39.117309 -1.910166 +VERTEX_SE2 676 12.549939 -39.112303 -2.540226 +VERTEX_SE2 677 12.562810 -39.108340 3.120460 +VERTEX_SE2 678 12.373080 -39.013683 2.669222 +VERTEX_SE2 679 11.859571 -38.764102 2.729006 +VERTEX_SE2 680 11.438738 -38.641448 3.069344 +VERTEX_SE2 681 10.825052 -38.579071 3.043558 +VERTEX_SE2 682 10.191857 -38.531816 3.093190 +VERTEX_SE2 683 9.891918 -38.522270 -3.028351 +VERTEX_SE2 684 9.884198 -38.525775 -1.959011 +VERTEX_SE2 685 9.893810 -38.971112 -1.519535 +VERTEX_SE2 686 9.862204 -39.454619 -1.666211 +VERTEX_SE2 687 9.788467 -40.084236 -1.702984 +VERTEX_SE2 688 9.681861 -40.709183 -1.716237 +VERTEX_SE2 689 9.605655 -41.306367 -1.689887 +VERTEX_SE2 690 9.568647 -41.883115 -1.616935 +VERTEX_SE2 691 9.547797 -42.313693 -1.645939 +VERTEX_SE2 692 9.547338 -42.304642 -1.113930 +VERTEX_SE2 693 9.542348 -42.304320 -0.077783 +VERTEX_SE2 694 9.537355 -42.304058 0.754255 +VERTEX_SE2 695 9.537558 -42.302067 1.551174 +VERTEX_SE2 696 9.534841 -42.288755 2.572731 +VERTEX_SE2 697 9.523163 -42.279299 2.318206 +VERTEX_SE2 698 9.451431 -41.889589 1.660453 +VERTEX_SE2 699 9.371393 -41.248546 1.772879 +VERTEX_SE2 700 9.226326 -40.627573 1.824729 +VERTEX_SE2 701 9.049173 -40.073867 1.881983 +VERTEX_SE2 702 8.937709 -39.503989 1.764440 +VERTEX_SE2 703 8.820349 -38.895181 1.796436 +VERTEX_SE2 704 8.652821 -38.280287 1.812200 +VERTEX_SE2 705 8.469818 -37.662927 1.876685 +VERTEX_SE2 706 8.352303 -37.160636 1.599049 +VERTEX_SE2 707 8.353815 -37.156710 1.065513 +VERTEX_SE2 708 8.350433 -37.159057 0.410972 +VERTEX_SE2 709 8.285591 -37.179408 0.069240 +VERTEX_SE2 710 8.271325 -37.178203 -0.506017 +VERTEX_SE2 711 8.272256 -37.177853 -1.117758 +VERTEX_SE2 712 8.271421 -37.172816 -1.692402 +VERTEX_SE2 713 8.082147 -37.631033 -1.986694 +VERTEX_SE2 714 7.781665 -38.118818 -2.191858 +VERTEX_SE2 715 7.436278 -38.650634 -2.086627 +VERTEX_SE2 716 7.101560 -39.196310 -2.222833 +VERTEX_SE2 717 6.732648 -39.710336 -2.136309 +VERTEX_SE2 718 6.249991 -40.323558 -2.309481 +VERTEX_SE2 719 5.841996 -40.813346 -2.233064 +VERTEX_SE2 720 5.439595 -41.301667 -2.290296 +VERTEX_SE2 721 5.032639 -41.793490 -2.219961 +VERTEX_SE2 722 5.017459 -41.813716 -2.151150 +VERTEX_SE2 723 5.020505 -41.823419 -1.052793 +VERTEX_SE2 724 5.031411 -41.829247 0.024382 +VERTEX_SE2 725 5.041952 -41.823519 0.663795 +VERTEX_SE2 726 5.186097 -41.536150 1.121855 +VERTEX_SE2 727 5.441157 -40.953385 1.154429 +VERTEX_SE2 728 5.708786 -40.374749 1.157456 +VERTEX_SE2 729 5.942746 -39.779976 1.216830 +VERTEX_SE2 730 6.141286 -39.181998 1.255908 +VERTEX_SE2 731 6.337960 -38.578088 1.269244 +VERTEX_SE2 732 6.370731 -38.458677 1.718146 +VERTEX_SE2 733 6.369310 -38.458803 2.719136 +VERTEX_SE2 734 5.849568 -38.267284 2.798462 +VERTEX_SE2 735 5.287090 -38.058027 2.767482 +VERTEX_SE2 736 5.282360 -38.056088 -2.913613 +VERTEX_SE2 737 5.275781 -38.066121 -2.109607 +VERTEX_SE2 738 4.978024 -38.585828 -2.089531 +VERTEX_SE2 739 4.620518 -39.102322 -2.146106 +VERTEX_SE2 740 4.357016 -39.553955 -2.081799 +VERTEX_SE2 741 4.357431 -39.553064 -2.448926 +VERTEX_SE2 742 4.347527 -39.558696 -3.099199 +VERTEX_SE2 743 4.342558 -39.557580 2.569578 +VERTEX_SE2 744 4.336078 -39.550170 2.032393 +VERTEX_SE2 745 4.335980 -39.547933 1.441244 +VERTEX_SE2 746 4.573919 -39.080308 0.968419 +VERTEX_SE2 747 4.940154 -38.557294 0.934212 +VERTEX_SE2 748 5.302092 -38.106400 0.867038 +VERTEX_SE2 749 5.345738 -38.052022 1.298344 +VERTEX_SE2 750 5.342230 -38.047361 2.229268 +VERTEX_SE2 751 5.083575 -37.967511 2.872246 +VERTEX_SE2 752 4.493353 -37.766114 2.770046 +VERTEX_SE2 753 3.897446 -37.540993 2.834236 +VERTEX_SE2 754 3.312644 -37.288841 2.673214 +VERTEX_SE2 755 2.737782 -37.020556 2.749498 +VERTEX_SE2 756 2.174638 -36.731322 2.558054 +VERTEX_SE2 757 1.632084 -36.401074 2.656949 +VERTEX_SE2 758 1.085717 -36.165115 2.783429 +VERTEX_SE2 759 0.594312 -35.911010 2.644238 +VERTEX_SE2 760 0.049628 -35.662561 2.758388 +VERTEX_SE2 761 0.027544 -35.652794 2.941901 +VERTEX_SE2 762 0.026506 -35.653762 -2.331733 +VERTEX_SE2 763 -0.256374 -36.186295 -2.039623 +VERTEX_SE2 764 -0.462375 -36.581571 -2.067616 +VERTEX_SE2 765 -0.464849 -36.589741 -1.429340 +VERTEX_SE2 766 -0.458452 -36.594227 -0.430727 +VERTEX_SE2 767 -0.455458 -36.594045 0.498539 +VERTEX_SE2 768 -0.452643 -36.586959 1.219631 +VERTEX_SE2 769 -0.342345 -35.973305 1.375930 +VERTEX_SE2 770 -0.198947 -35.353053 1.308266 +VERTEX_SE2 771 -0.182607 -35.284960 1.867596 +VERTEX_SE2 772 -0.189467 -35.280006 2.733492 +VERTEX_SE2 773 -0.733580 -35.074067 2.818690 +VERTEX_SE2 774 -1.260348 -34.911848 2.840206 +VERTEX_SE2 775 -1.264437 -34.911446 -2.599985 +VERTEX_SE2 776 -1.363996 -35.119485 -1.984041 +VERTEX_SE2 777 -1.608279 -35.704951 -1.925618 +VERTEX_SE2 778 -1.822302 -36.299953 -1.947124 +VERTEX_SE2 779 -2.047440 -36.894571 -1.929730 +VERTEX_SE2 780 -2.139238 -37.102862 -2.060860 +VERTEX_SE2 781 -2.145402 -37.110533 -2.636030 +VERTEX_SE2 782 -2.437259 -37.141405 -3.067105 +VERTEX_SE2 783 -3.047824 -37.175458 -3.068514 +VERTEX_SE2 784 -3.287219 -37.194026 -3.090710 +VERTEX_SE2 785 -3.295317 -37.191509 2.638474 +VERTEX_SE2 786 -3.298918 -37.188857 2.048008 +VERTEX_SE2 787 -3.298039 -37.190654 1.555448 +VERTEX_SE2 788 -3.294912 -37.183493 0.924060 +VERTEX_SE2 789 -3.288075 -37.179210 0.370053 +VERTEX_SE2 790 -2.810788 -37.026036 0.301996 +VERTEX_SE2 791 -2.219090 -36.811172 0.399811 +VERTEX_SE2 792 -1.939736 -36.661187 1.102401 +VERTEX_SE2 793 -1.678873 -36.103497 1.143891 +VERTEX_SE2 794 -1.429675 -35.516238 1.211715 +VERTEX_SE2 795 -1.418449 -35.555793 1.634956 +VERTEX_SE2 796 -1.418085 -35.571576 2.285912 +VERTEX_SE2 797 -1.667269 -35.397655 2.541335 +VERTEX_SE2 798 -2.187789 -35.048694 2.588216 +VERTEX_SE2 799 -2.741194 -34.735022 2.650579 +VERTEX_SE2 800 -3.307545 -34.448654 2.720068 +VERTEX_SE2 801 -3.902341 -34.216184 2.802965 +VERTEX_SE2 802 -4.505679 -34.024853 2.857856 +VERTEX_SE2 803 -5.085804 -33.763383 2.689794 +VERTEX_SE2 804 -5.662771 -33.497682 2.743005 +VERTEX_SE2 805 -6.261534 -33.279468 2.816554 +VERTEX_SE2 806 -6.840015 -33.097367 2.855463 +VERTEX_SE2 807 -7.023476 -33.048729 -3.135502 +VERTEX_SE2 808 -7.026802 -33.056076 -2.177404 +VERTEX_SE2 809 -7.281242 -33.594521 -2.029487 +VERTEX_SE2 810 -7.631595 -34.121859 -2.166451 +VERTEX_SE2 811 -7.962424 -34.637653 -2.167266 +VERTEX_SE2 812 -7.965744 -34.642706 -1.427803 +VERTEX_SE2 813 -7.950068 -34.658744 -0.442321 +VERTEX_SE2 814 -7.946972 -34.656894 0.560269 +VERTEX_SE2 815 -7.933401 -34.640091 1.489098 +VERTEX_SE2 816 -7.934735 -34.631584 2.177465 +VERTEX_SE2 817 -7.937452 -34.619639 1.515677 +VERTEX_SE2 818 -7.834770 -34.423652 1.032291 +VERTEX_SE2 819 -7.526530 -33.907724 1.048948 +VERTEX_SE2 820 -7.214976 -33.390015 1.010358 +VERTEX_SE2 821 -6.920703 -32.916256 1.028688 +VERTEX_SE2 822 -6.919798 -32.914444 1.802164 +VERTEX_SE2 823 -6.939217 -32.906160 2.735576 +VERTEX_SE2 824 -7.523314 -32.665202 2.656921 +VERTEX_SE2 825 -8.081019 -32.349406 2.627743 +VERTEX_SE2 826 -8.677362 -32.112604 2.791147 +VERTEX_SE2 827 -9.263427 -31.871967 2.742741 +VERTEX_SE2 828 -9.860125 -31.638542 2.778381 +VERTEX_SE2 829 -10.419194 -31.408540 2.739767 +VERTEX_SE2 830 -10.979677 -31.164322 2.732511 +VERTEX_SE2 831 -11.504644 -30.911305 2.686863 +VERTEX_SE2 832 -12.017274 -30.666706 2.684351 +VERTEX_SE2 833 -12.247951 -30.553587 2.823368 +VERTEX_SE2 834 -12.252957 -30.553546 -2.400674 +VERTEX_SE2 835 -12.257933 -30.565509 -1.619664 +VERTEX_SE2 836 -12.250730 -30.581427 -0.672599 +VERTEX_SE2 837 -12.229702 -30.583353 0.368164 +VERTEX_SE2 838 -12.218778 -30.573267 1.234031 +VERTEX_SE2 839 -12.217846 -30.572182 1.017315 +VERTEX_SE2 840 -12.205638 -30.563033 0.457221 +VERTEX_SE2 841 -12.186893 -30.559209 -0.157128 +VERTEX_SE2 842 -11.953603 -30.647983 -0.386378 +VERTEX_SE2 843 -11.425785 -30.867365 -0.387868 +VERTEX_SE2 844 -10.836985 -31.098902 -0.394843 +VERTEX_SE2 845 -10.253132 -31.347696 -0.408511 +VERTEX_SE2 846 -9.662939 -31.589256 -0.405754 +VERTEX_SE2 847 -9.086083 -31.851482 -0.431429 +VERTEX_SE2 848 -8.940268 -31.914214 0.052760 +VERTEX_SE2 849 -8.937884 -31.910733 0.981233 +VERTEX_SE2 850 -8.846299 -31.550192 1.337597 +VERTEX_SE2 851 -8.670841 -30.931185 1.246884 +VERTEX_SE2 852 -8.462808 -30.325041 1.262739 +VERTEX_SE2 853 -8.280607 -29.742061 1.236186 +VERTEX_SE2 854 -8.076287 -29.173781 1.239399 +VERTEX_SE2 855 -7.887388 -28.592768 1.238706 +VERTEX_SE2 856 -7.661883 -27.996043 1.201622 +VERTEX_SE2 857 -7.435282 -27.400366 1.195491 +VERTEX_SE2 858 -7.181293 -26.816604 1.144746 +VERTEX_SE2 859 -6.975384 -26.352422 1.141340 +VERTEX_SE2 860 -6.975931 -26.349425 2.005134 +VERTEX_SE2 861 -7.070368 -26.315710 2.933845 +VERTEX_SE2 862 -7.703743 -26.156922 2.877954 +VERTEX_SE2 863 -8.318477 -25.984947 2.848940 +VERTEX_SE2 864 -8.894038 -25.792766 2.850044 +VERTEX_SE2 865 -9.480815 -25.646186 2.911227 +VERTEX_SE2 866 -10.042232 -25.502772 2.913209 +VERTEX_SE2 867 -10.195104 -25.469004 3.098784 +VERTEX_SE2 868 -10.213426 -25.478919 -2.146684 +VERTEX_SE2 869 -10.215119 -25.492408 -1.155028 +VERTEX_SE2 870 -10.214332 -25.494499 -0.141931 +VERTEX_SE2 871 -10.213017 -25.492991 0.844964 +VERTEX_SE2 872 -10.207635 -25.487052 1.539524 +VERTEX_SE2 873 -10.203844 -25.478644 0.974807 +VERTEX_SE2 874 -10.191816 -25.467641 0.422903 +VERTEX_SE2 875 -10.178876 -25.463448 -0.155631 +VERTEX_SE2 876 -9.623904 -25.632105 -0.308985 +VERTEX_SE2 877 -9.083899 -25.830525 -0.389894 +VERTEX_SE2 878 -8.876969 -25.899540 -0.000578 +VERTEX_SE2 879 -8.229916 -25.842173 0.054103 +VERTEX_SE2 880 -7.774580 -25.835590 -0.054479 +VERTEX_SE2 881 -7.817933 -25.833359 -0.045761 +VERTEX_SE2 882 -7.174094 -25.927843 -0.286988 +VERTEX_SE2 883 -6.578127 -26.179696 -0.472812 +VERTEX_SE2 884 -6.240032 -26.360890 -0.535840 +VERTEX_SE2 885 -6.234259 -26.360820 0.054937 +VERTEX_SE2 886 -6.226914 -26.353411 1.089009 +VERTEX_SE2 887 -6.223165 -26.344082 2.116331 +VERTEX_SE2 888 -6.228613 -26.341527 3.115899 +VERTEX_SE2 889 -6.233959 -26.343474 -2.255359 +VERTEX_SE2 890 -6.384262 -26.679298 -1.975677 +VERTEX_SE2 891 -6.638596 -27.241278 -2.042104 +VERTEX_SE2 892 -6.943864 -27.800951 -2.074085 +VERTEX_SE2 893 -7.222566 -28.381189 -1.832614 +VERTEX_SE2 894 -7.306963 -29.019629 -1.606544 +VERTEX_SE2 895 -7.223579 -29.638727 -1.302591 +VERTEX_SE2 896 -7.217764 -29.658031 -0.821107 +VERTEX_SE2 897 -6.741710 -29.937142 -0.546756 +VERTEX_SE2 898 -6.211746 -30.256253 -0.528856 +VERTEX_SE2 899 -5.784445 -30.515658 -0.593948 +VERTEX_SE2 900 -5.213641 -30.892109 -0.593973 +VERTEX_SE2 901 -4.743942 -31.232862 -0.655646 +VERTEX_SE2 902 -4.223039 -31.613559 -0.627847 +VERTEX_SE2 903 -3.820846 -31.901295 -0.669947 +VERTEX_SE2 904 -3.815849 -31.904352 0.045079 +VERTEX_SE2 905 -3.263955 -31.843907 0.103405 +VERTEX_SE2 906 -2.639473 -31.754495 0.172374 +VERTEX_SE2 907 -2.019027 -31.639234 0.167356 +VERTEX_SE2 908 -1.390615 -31.531155 0.192144 +VERTEX_SE2 909 -0.774159 -31.409648 0.174319 +VERTEX_SE2 910 -0.621113 -31.427046 -0.195369 +VERTEX_SE2 911 -0.014492 -31.535247 -0.134304 +VERTEX_SE2 912 0.586470 -31.609953 -0.123402 +VERTEX_SE2 913 1.163336 -31.678045 -0.116774 +VERTEX_SE2 914 1.788505 -31.757735 -0.141346 +VERTEX_SE2 915 2.338537 -31.842759 -0.178606 +VERTEX_SE2 916 2.533087 -31.771891 0.368065 +VERTEX_SE2 917 3.132539 -31.589985 0.113800 +VERTEX_SE2 918 3.652121 -31.566106 0.038805 +VERTEX_SE2 919 4.280972 -31.547492 -0.003530 +VERTEX_SE2 920 4.910829 -31.560372 -0.019732 +VERTEX_SE2 921 5.544993 -31.581438 -0.071106 +VERTEX_SE2 922 6.178198 -31.632867 -0.095979 +VERTEX_SE2 923 6.782469 -31.705277 -0.156454 +VERTEX_SE2 924 7.306767 -31.788672 -0.137071 +VERTEX_SE2 925 7.316981 -31.785338 0.373816 +VERTEX_SE2 926 7.870711 -31.558218 0.392795 +VERTEX_SE2 927 8.451492 -31.319547 0.372320 +VERTEX_SE2 928 9.048413 -31.086577 0.366185 +VERTEX_SE2 929 9.642832 -30.858817 0.368104 +VERTEX_SE2 930 10.245448 -30.641674 0.289261 +VERTEX_SE2 931 10.860347 -30.480136 0.213162 +VERTEX_SE2 932 11.487766 -30.354631 0.158095 +VERTEX_SE2 933 12.113942 -30.270301 0.098329 +VERTEX_SE2 934 12.615349 -30.217794 0.093110 +VERTEX_SE2 935 12.620802 -30.215724 0.789990 +VERTEX_SE2 936 12.621200 -30.213495 1.735352 +VERTEX_SE2 937 12.506666 -29.673239 1.798228 +VERTEX_SE2 938 12.424893 -29.074588 1.624736 +VERTEX_SE2 939 12.382460 -28.442898 1.652316 +VERTEX_SE2 940 12.358048 -27.806499 1.569594 +VERTEX_SE2 941 12.373922 -27.170573 1.518896 +VERTEX_SE2 942 12.403040 -26.619551 1.526103 +VERTEX_SE2 943 12.433212 -25.976160 1.617626 +VERTEX_SE2 944 12.409024 -25.337583 1.563948 +VERTEX_SE2 945 12.425512 -24.701834 1.511054 +VERTEX_SE2 946 12.438281 -24.522578 1.577626 +VERTEX_SE2 947 12.297194 -24.116617 1.909253 +VERTEX_SE2 948 12.106012 -23.569193 1.887290 +VERTEX_SE2 949 11.964410 -22.979201 1.728071 +VERTEX_SE2 950 11.889816 -22.346608 1.484552 +VERTEX_SE2 951 11.958985 -21.712798 1.409506 +VERTEX_SE2 952 12.033066 -21.078819 1.656468 +VERTEX_SE2 953 11.960841 -20.446967 1.733995 +VERTEX_SE2 954 11.870328 -19.821157 1.720988 +VERTEX_SE2 955 11.840813 -19.182342 1.553709 +VERTEX_SE2 956 11.856933 -18.549356 1.547775 +VERTEX_SE2 957 11.900583 -17.914412 1.456986 +VERTEX_SE2 958 11.980717 -17.309521 1.428422 +VERTEX_SE2 959 12.082916 -16.713544 1.360362 +VERTEX_SE2 960 12.156646 -16.109750 1.448732 +VERTEX_SE2 961 12.237458 -15.513097 1.428643 +VERTEX_SE2 962 12.263723 -14.879685 1.501648 +VERTEX_SE2 963 12.237575 -14.246674 1.697303 +VERTEX_SE2 964 12.165060 -13.610953 1.639856 +VERTEX_SE2 965 12.127557 -12.978752 1.638378 +VERTEX_SE2 966 12.104648 -12.566160 1.581231 +VERTEX_SE2 967 12.101573 -12.558682 2.440323 +VERTEX_SE2 968 12.096363 -12.554972 -2.940213 +VERTEX_SE2 969 12.095404 -12.555254 -2.878924 +VERTEX_SE2 970 12.095404 -12.555254 -2.879037 +VERTEX_SE2 971 11.746171 -12.650445 -2.877325 +VERTEX_SE2 972 11.152947 -12.816606 -2.870194 +VERTEX_SE2 973 10.545291 -12.861291 3.130276 +VERTEX_SE2 974 9.909280 -12.851322 -3.119743 +VERTEX_SE2 975 9.273543 -12.871196 -3.113968 +VERTEX_SE2 976 8.636290 -12.899229 -3.099985 +VERTEX_SE2 977 7.998434 -12.914064 -3.126289 +VERTEX_SE2 978 7.362084 -12.942484 -3.081464 +VERTEX_SE2 979 6.727323 -12.975809 -3.095884 +VERTEX_SE2 980 6.088538 -13.025797 -3.052420 +VERTEX_SE2 981 5.456362 -13.081213 -3.049818 +VERTEX_SE2 982 4.878233 -13.153816 -3.010682 +VERTEX_SE2 983 4.276746 -13.227843 -3.016388 +VERTEX_SE2 984 3.677713 -13.322859 -2.961936 +VERTEX_SE2 985 3.077590 -13.433257 -2.944700 +VERTEX_SE2 986 2.454219 -13.573733 -2.911877 +VERTEX_SE2 987 1.831643 -13.709396 -2.952510 +VERTEX_SE2 988 1.208691 -13.826413 -2.942854 +VERTEX_SE2 989 0.584787 -13.958913 -2.938610 +VERTEX_SE2 990 -0.036556 -14.080445 -2.953180 +VERTEX_SE2 991 -0.661927 -14.209275 -2.932525 +VERTEX_SE2 992 -1.260572 -14.319726 -2.969755 +VERTEX_SE2 993 -1.888936 -14.441757 -2.941917 +VERTEX_SE2 994 -2.487885 -14.558335 -2.956980 +VERTEX_SE2 995 -3.058043 -14.679439 -2.909164 +VERTEX_SE2 996 -3.642056 -14.831099 -2.881732 +VERTEX_SE2 997 -4.264284 -14.974196 -2.946069 +VERTEX_SE2 998 -4.649607 -15.053751 -2.924278 +VERTEX_SE2 999 -4.656689 -15.065859 -2.206631 +VERTEX_SE2 1000 -4.965388 -15.623496 -2.058280 +VERTEX_SE2 1001 -5.318062 -16.158055 -2.379913 +VERTEX_SE2 1002 -5.750626 -16.618291 -2.287924 +VERTEX_SE2 1003 -6.211655 -17.061941 -2.468589 +VERTEX_SE2 1004 -6.694526 -17.473495 -2.405819 +VERTEX_SE2 1005 -7.127979 -17.892536 -2.338545 +VERTEX_SE2 1006 -7.533434 -18.348428 -2.255884 +VERTEX_SE2 1007 -7.879092 -18.809574 -2.158490 +VERTEX_SE2 1008 -8.039907 -19.059004 -1.992248 +VERTEX_SE2 1009 -8.036682 -19.246221 -1.535293 +VERTEX_SE2 1010 -8.014039 -19.881169 -1.488904 +VERTEX_SE2 1011 -7.963340 -20.508886 -1.536571 +VERTEX_SE2 1012 -7.940438 -21.138959 -1.498741 +VERTEX_SE2 1013 -7.851368 -21.773013 -1.387987 +VERTEX_SE2 1014 -7.817932 -22.401411 -1.567544 +VERTEX_SE2 1015 -7.777031 -23.038795 -1.486212 +VERTEX_SE2 1016 -7.720006 -23.818187 -1.481750 +VERTEX_SE2 1017 -7.654678 -24.418258 -1.539186 +VERTEX_SE2 1018 -7.642739 -24.996103 -1.532186 +VERTEX_SE2 1019 -7.587869 -25.606880 -1.473009 +VERTEX_SE2 1020 -7.542280 -26.239004 -1.487341 +VERTEX_SE2 1021 -7.489141 -26.876264 -1.528391 +VERTEX_SE2 1022 -7.485868 -26.947021 -1.536042 +VERTEX_SE2 1023 -7.484661 -26.958141 -1.449942 +VERTEX_SE2 1024 -7.409816 -27.598995 -1.424093 +VERTEX_SE2 1025 -7.295845 -28.237813 -1.407035 +VERTEX_SE2 1026 -7.266936 -28.415848 -1.400374 +VERTEX_SE2 1027 -7.264213 -28.420001 -0.485709 +VERTEX_SE2 1028 -7.082225 -28.411802 0.076550 +VERTEX_SE2 1029 -6.501990 -28.370465 0.054524 +VERTEX_SE2 1030 -5.899285 -28.359129 -0.023135 +VERTEX_SE2 1031 -5.264812 -28.390632 -0.074570 +VERTEX_SE2 1032 -4.627186 -28.437737 -0.067955 +VERTEX_SE2 1033 -3.988448 -28.495960 -0.110249 +VERTEX_SE2 1034 -3.830826 -28.515420 -0.320119 +VERTEX_SE2 1035 -3.824146 -28.521449 -0.932344 +VERTEX_SE2 1036 -3.823513 -28.519287 -1.496421 +VERTEX_SE2 1037 -3.907010 -28.904450 -1.730668 +VERTEX_SE2 1038 -3.935283 -29.554657 -1.636155 +VERTEX_SE2 1039 -4.005708 -30.240003 -1.664719 +VERTEX_SE2 1040 -4.005908 -30.238599 -1.026894 +VERTEX_SE2 1041 -4.005975 -30.237093 0.002348 +VERTEX_SE2 1042 -3.997565 -30.235981 1.002167 +VERTEX_SE2 1043 -3.992361 -30.227413 1.983494 +VERTEX_SE2 1044 -3.977187 -30.235628 2.989203 +VERTEX_SE2 1045 -3.975026 -30.236085 2.875365 +VERTEX_SE2 1046 -3.962563 -30.241673 2.490123 +VERTEX_SE2 1047 -3.950447 -30.258328 1.934722 +VERTEX_SE2 1048 -3.961452 -29.893794 1.621975 +VERTEX_SE2 1049 -4.005576 -29.246490 1.639262 +VERTEX_SE2 1050 -4.077126 -28.603234 1.715064 +VERTEX_SE2 1051 -4.144972 -27.965909 1.641633 +VERTEX_SE2 1052 -4.202505 -27.357765 1.700204 +VERTEX_SE2 1053 -4.242648 -26.957178 1.653111 +VERTEX_SE2 1054 -4.243150 -26.953596 2.434770 +VERTEX_SE2 1055 -4.236475 -26.953142 -2.756219 +VERTEX_SE2 1056 -4.223234 -26.936933 -1.722386 +VERTEX_SE2 1057 -4.227338 -26.917941 -0.719127 +VERTEX_SE2 1058 -4.226406 -26.918299 0.214528 +VERTEX_SE2 1059 -3.650549 -26.814433 0.137155 +VERTEX_SE2 1060 -3.017058 -26.728657 0.145123 +VERTEX_SE2 1061 -2.566458 -26.676490 0.026280 +VERTEX_SE2 1062 -2.547934 -26.680711 -0.534242 +VERTEX_SE2 1063 -2.549662 -26.679283 -1.128091 +VERTEX_SE2 1064 -2.494849 -26.986675 -1.390919 +VERTEX_SE2 1065 -2.341227 -27.585706 -1.267035 +VERTEX_SE2 1066 -2.181042 -28.156133 -1.321458 +VERTEX_SE2 1067 -2.176008 -28.167308 -0.885641 +VERTEX_SE2 1068 -2.171515 -28.170280 -0.208552 +VERTEX_SE2 1069 -2.166440 -28.170156 -0.036102 +VERTEX_SE2 1070 -2.158515 -28.171216 -0.571481 +VERTEX_SE2 1071 -1.728296 -28.528563 -0.696733 +VERTEX_SE2 1072 -1.327331 -28.874102 -0.763594 +VERTEX_SE2 1073 -1.328212 -28.872089 -1.271112 +VERTEX_SE2 1074 -1.186974 -29.415680 -1.303788 +VERTEX_SE2 1075 -1.030631 -30.004733 -1.285588 +VERTEX_SE2 1076 -1.010783 -30.067165 -0.872464 +VERTEX_SE2 1077 -0.990761 -30.068841 -0.051064 +VERTEX_SE2 1078 -0.349127 -30.042537 -0.001133 +VERTEX_SE2 1079 0.251517 -30.025133 0.066104 +VERTEX_SE2 1080 0.250521 -30.025208 -0.411064 +VERTEX_SE2 1081 0.710773 -30.299114 -0.528492 +VERTEX_SE2 1082 0.906064 -30.410866 -0.239852 +VERTEX_SE2 1083 0.893124 -30.419745 0.817776 +VERTEX_SE2 1084 0.892987 -30.410710 1.808848 +VERTEX_SE2 1085 0.877326 -30.393872 2.785923 +VERTEX_SE2 1086 0.299041 -30.311718 3.014416 +VERTEX_SE2 1087 -0.304600 -30.219651 3.001192 +VERTEX_SE2 1088 -0.901080 -30.145015 2.983479 +VERTEX_SE2 1089 -0.971780 -30.133164 2.884958 +VERTEX_SE2 1090 -0.973114 -30.132686 2.263087 +VERTEX_SE2 1091 -1.258802 -29.655877 2.082828 +VERTEX_SE2 1092 -1.565146 -29.096531 2.065302 +VERTEX_SE2 1093 -1.831232 -28.571344 1.997715 +VERTEX_SE2 1094 -1.829673 -28.566075 1.590728 +VERTEX_SE2 1095 -1.822889 -28.540013 0.997280 +VERTEX_SE2 1096 -1.811806 -28.530957 0.422426 +VERTEX_SE2 1097 -1.452357 -28.453682 0.204872 +VERTEX_SE2 1098 -0.806231 -28.342284 0.146524 +VERTEX_SE2 1099 -0.207476 -28.279115 0.048016 +VERTEX_SE2 1100 -0.187763 -28.277509 0.407350 +VERTEX_SE2 1101 0.022408 -28.110407 0.670039 +VERTEX_SE2 1102 0.031962 -28.106738 0.272412 +VERTEX_SE2 1103 0.639388 -27.958876 0.236513 +VERTEX_SE2 1104 1.275605 -27.810841 0.206756 +VERTEX_SE2 1105 1.907140 -27.685723 0.186870 +VERTEX_SE2 1106 2.395193 -27.596899 0.159641 +VERTEX_SE2 1107 2.402168 -27.592873 0.412775 +VERTEX_SE2 1108 2.958139 -27.302229 0.418732 +VERTEX_SE2 1109 3.567153 -27.081855 0.312557 +VERTEX_SE2 1110 4.153225 -26.897988 0.261047 +VERTEX_SE2 1111 4.708902 -26.834648 0.157605 +VERTEX_SE2 1112 5.252614 -26.628115 0.500855 +VERTEX_SE2 1113 5.822286 -26.335525 0.403408 +VERTEX_SE2 1114 6.390291 -26.092686 0.418701 +VERTEX_SE2 1115 6.922867 -25.852780 0.400788 +VERTEX_SE2 1116 7.511667 -25.579208 0.435293 +VERTEX_SE2 1117 7.600383 -25.536976 0.305438 +VERTEX_SE2 1118 7.602610 -25.537159 -0.306056 +VERTEX_SE2 1119 7.600066 -25.535572 -0.741091 +VERTEX_SE2 1120 8.016891 -25.978082 -0.806559 +VERTEX_SE2 1121 8.158671 -26.132496 -0.927181 +VERTEX_SE2 1122 8.158918 -26.136107 -1.481463 +VERTEX_SE2 1123 8.202585 -26.722199 -1.466214 +VERTEX_SE2 1124 8.300951 -27.294198 -1.369439 +VERTEX_SE2 1125 8.427601 -27.927776 -1.357617 +VERTEX_SE2 1126 8.448389 -28.015008 -1.020843 +VERTEX_SE2 1127 8.448797 -28.014120 0.029251 +VERTEX_SE2 1128 8.446703 -28.014495 1.009931 +VERTEX_SE2 1129 8.448367 -28.002253 2.018659 +VERTEX_SE2 1130 8.179683 -27.484075 2.030704 +VERTEX_SE2 1131 8.020715 -26.725314 1.595581 +VERTEX_SE2 1132 8.007311 -26.085207 1.574275 +VERTEX_SE2 1133 8.027146 -25.500857 1.533912 +VERTEX_SE2 1134 8.037276 -25.234473 1.435052 +VERTEX_SE2 1135 8.041135 -25.225813 0.875236 +VERTEX_SE2 1136 8.045119 -25.226197 0.309468 +VERTEX_SE2 1137 8.350426 -25.173106 0.123314 +VERTEX_SE2 1138 9.001574 -25.103517 0.105516 +VERTEX_SE2 1139 9.526482 -25.047001 0.028463 +VERTEX_SE2 1140 9.524465 -25.046883 -0.458084 +VERTEX_SE2 1141 9.526460 -25.047900 -1.013894 +VERTEX_SE2 1142 9.607360 -25.436185 -1.384688 +VERTEX_SE2 1143 9.757086 -26.048918 -1.299305 +VERTEX_SE2 1144 9.911339 -26.642229 -1.333595 +VERTEX_SE2 1145 10.051242 -27.237116 -1.362737 +VERTEX_SE2 1146 10.176396 -27.833614 -1.346612 +VERTEX_SE2 1147 10.348017 -28.420420 -1.277963 +VERTEX_SE2 1148 10.522608 -29.006300 -1.265737 +VERTEX_SE2 1149 10.546607 -29.077059 -0.762568 +VERTEX_SE2 1150 10.540261 -29.074848 0.225763 +VERTEX_SE2 1151 10.553029 -29.065002 1.213625 +VERTEX_SE2 1152 10.547143 -29.052737 2.249842 +VERTEX_SE2 1153 10.539006 -29.045893 -3.036684 +VERTEX_SE2 1154 10.279724 -29.230068 -2.499597 +VERTEX_SE2 1155 9.768765 -29.605741 -2.552981 +VERTEX_SE2 1156 9.258910 -29.939074 -2.546643 +VERTEX_SE2 1157 8.791360 -30.283703 -2.440027 +VERTEX_SE2 1158 8.293580 -30.637927 -2.573320 +VERTEX_SE2 1159 7.766648 -30.929430 -2.672819 +VERTEX_SE2 1160 7.188507 -31.197997 -2.815407 +VERTEX_SE2 1161 6.565573 -31.348475 -2.910356 +VERTEX_SE2 1162 5.944969 -31.503360 -2.857013 +VERTEX_SE2 1163 5.325232 -31.686006 -2.866763 +VERTEX_SE2 1164 4.712273 -31.878415 -2.786199 +VERTEX_SE2 1165 4.215997 -32.064635 -2.806894 +VERTEX_SE2 1166 4.211816 -32.067381 -2.313330 +VERTEX_SE2 1167 4.212397 -32.068184 -1.368491 +VERTEX_SE2 1168 4.215987 -32.071852 -0.457146 +VERTEX_SE2 1169 4.277451 -32.051395 0.371897 +VERTEX_SE2 1170 4.829613 -31.826964 0.380849 +VERTEX_SE2 1171 5.421192 -31.572841 0.415111 +VERTEX_SE2 1172 5.981253 -31.335402 0.355461 +VERTEX_SE2 1173 6.575628 -31.109741 0.367274 +VERTEX_SE2 1174 7.180922 -30.893036 0.301697 +VERTEX_SE2 1175 7.792370 -30.719051 0.271366 +VERTEX_SE2 1176 8.409541 -30.550025 0.230936 +VERTEX_SE2 1177 9.024476 -30.404549 0.236005 +VERTEX_SE2 1178 9.647424 -30.266268 0.192062 +VERTEX_SE2 1179 10.265276 -30.135370 0.224605 +VERTEX_SE2 1180 10.529482 -30.074919 0.220636 +VERTEX_SE2 1181 10.535574 -30.072977 1.058820 +VERTEX_SE2 1182 10.524149 -30.016817 1.779823 +VERTEX_SE2 1183 10.386448 -29.400748 1.808327 +VERTEX_SE2 1184 10.207851 -28.783707 1.881370 +VERTEX_SE2 1185 10.025332 -28.173735 1.852352 +VERTEX_SE2 1186 9.825515 -27.568409 1.922073 +VERTEX_SE2 1187 9.605142 -26.948356 1.888299 +VERTEX_SE2 1188 9.398682 -26.350552 1.909670 +VERTEX_SE2 1189 9.199117 -25.746642 1.931343 +VERTEX_SE2 1190 9.094298 -25.467233 1.939338 +VERTEX_SE2 1191 9.094967 -25.468452 2.859515 +VERTEX_SE2 1192 9.008026 -25.506399 -2.626152 +VERTEX_SE2 1193 8.461781 -25.785098 -2.758330 +VERTEX_SE2 1194 7.923840 -26.019541 -2.716510 +VERTEX_SE2 1195 7.347445 -26.288871 -2.664510 +VERTEX_SE2 1196 6.780364 -26.579172 -2.837709 +VERTEX_SE2 1197 6.180419 -26.774947 -2.826952 +VERTEX_SE2 1198 5.583380 -27.006326 -2.569041 +VERTEX_SE2 1199 5.035569 -27.311853 -2.784743 +VERTEX_SE2 1200 4.440692 -27.555930 -2.716631 +VERTEX_SE2 1201 3.868153 -27.824566 -2.661795 +VERTEX_SE2 1202 3.307623 -28.126760 -2.639885 +VERTEX_SE2 1203 2.784459 -28.432197 -2.731103 +VERTEX_SE2 1204 2.199445 -28.603325 -2.879452 +VERTEX_SE2 1205 1.642686 -28.765416 -2.851240 +VERTEX_SE2 1206 1.070524 -28.960362 -2.791568 +VERTEX_SE2 1207 0.458097 -29.116494 -2.879433 +VERTEX_SE2 1208 -0.157073 -29.300653 -2.816562 +VERTEX_SE2 1209 -0.759388 -29.505640 -2.820223 +VERTEX_SE2 1210 -1.349503 -29.728180 -2.801535 +VERTEX_SE2 1211 -1.962101 -29.894344 -2.871965 +VERTEX_SE2 1212 -2.570554 -30.072460 -2.819915 +VERTEX_SE2 1213 -3.165262 -30.298664 -2.744821 +VERTEX_SE2 1214 -3.865282 -30.564861 -2.965631 +VERTEX_SE2 1215 -4.462533 -30.687173 -2.905497 +VERTEX_SE2 1216 -4.996128 -30.904402 -2.687065 +VERTEX_SE2 1217 -5.548071 -31.150837 -2.705863 +VERTEX_SE2 1218 -6.079683 -31.407444 -2.756532 +VERTEX_SE2 1219 -6.680544 -31.658044 -2.725934 +VERTEX_SE2 1220 -7.206328 -31.919274 -2.635196 +VERTEX_SE2 1221 -7.204948 -31.917957 -3.087949 +VERTEX_SE2 1222 -7.218143 -31.913501 2.597929 +VERTEX_SE2 1223 -7.226028 -31.904243 2.038302 +VERTEX_SE2 1224 -7.405412 -31.351278 1.855394 +VERTEX_SE2 1225 -7.584838 -30.751843 1.869158 +VERTEX_SE2 1226 -7.616041 -30.650012 1.852427 +VERTEX_SE2 1227 -7.616041 -30.650012 1.851765 +EDGE_SE2 0 1 0.000000 0.000000 -0.000642 11.111271 -0.249667 0.000000 399.999840 0.000000 2496.793089 +EDGE_SE2 1 2 0.000000 0.000000 -0.000538 11.111224 -0.209222 0.000000 399.999887 0.000000 2497.312169 +EDGE_SE2 2 3 0.011003 -0.000962 -0.002382 5898.288051 69216.359995 0.000000 813797.504789 0.000000 2488.132420 +EDGE_SE2 3 4 0.630039 -0.007981 -0.003882 11.129692 2.115033 0.000000 251.862638 0.000000 2480.702442 +EDGE_SE2 4 5 0.055010 -0.000106 -0.091282 274.195567 -2936.281177 0.000000 32782.895793 0.000000 2099.259006 +EDGE_SE2 5 6 0.004599 -0.003282 -0.797272 97512.798743 -544001.571431 0.000000 3035217.135802 0.000000 773.949086 +EDGE_SE2 6 7 -0.019286 0.007346 -0.615537 14562.788488 -56611.041711 0.000000 220247.580117 0.000000 957.869160 +EDGE_SE2 7 8 -0.022127 0.006629 -0.613534 18833.046432 -56332.014355 0.000000 168606.730383 0.000000 960.248785 +EDGE_SE2 8 9 -0.021138 0.006734 -0.638070 21300.350989 -62226.140556 0.000000 181891.375069 0.000000 931.697855 +EDGE_SE2 9 10 -0.012731 0.002805 -0.614531 88261.230144 -210099.692864 0.000000 500201.721901 0.000000 959.062847 +EDGE_SE2 10 11 -0.004733 0.001621 -0.674279 455441.532335 -1269769.465818 0.000000 3540210.494348 0.000000 891.834664 +EDGE_SE2 11 12 0.000807 -0.000605 -0.649474 3209.969094 -560838.218926 0.000000 98328698.890567 0.000000 918.859395 +EDGE_SE2 12 13 0.017463 -0.005758 -0.659498 33087.416467 -93212.317327 0.000000 262692.689594 0.000000 907.792399 +EDGE_SE2 13 14 0.024327 -0.007794 -0.608239 13237.887356 -43033.186144 0.000000 140019.158071 0.000000 966.582281 +EDGE_SE2 14 15 0.008665 -0.002176 -0.524928 94975.828833 -331589.466697 0.000000 1157826.108740 0.000000 1075.081358 +EDGE_SE2 15 16 0.300013 0.002659 -0.018692 11.945981 -30.290393 0.000000 1110.094393 0.000000 2409.096616 +EDGE_SE2 16 17 0.618894 -0.006590 -0.031228 11.216951 -5.142163 0.000000 260.940781 0.000000 2350.880836 +EDGE_SE2 17 18 0.644399 0.002908 -0.010177 11.160679 -3.373944 0.000000 240.764207 0.000000 2449.881377 +EDGE_SE2 18 19 0.657345 -0.022632 -0.048576 11.155234 -3.115574 0.000000 231.108306 0.000000 2273.736754 +EDGE_SE2 19 20 0.644638 0.002939 0.010643 11.119605 1.396220 0.000000 240.626947 0.000000 2447.622654 +EDGE_SE2 20 21 0.643768 0.040732 0.117695 11.791489 12.469629 0.000000 239.648403 0.000000 2001.213355 +EDGE_SE2 21 22 0.641586 -0.019837 0.022682 11.775592 12.387374 0.000000 242.038634 0.000000 2390.335076 +EDGE_SE2 22 23 0.642142 0.071066 0.114072 11.114499 0.879730 0.000000 239.576730 0.000000 2014.250547 +EDGE_SE2 23 24 0.642775 -0.026027 -0.050939 11.136380 -2.413434 0.000000 241.616002 0.000000 2263.523413 +EDGE_SE2 24 25 0.645593 0.014612 0.008602 11.156105 -3.207460 0.000000 239.760661 0.000000 2457.538661 +EDGE_SE2 25 26 0.612608 -0.020554 -0.040332 11.122880 -1.732513 0.000000 266.150269 0.000000 2309.915505 +EDGE_SE2 26 27 0.617908 0.014448 0.016074 11.124480 -1.830524 0.000000 261.753630 0.000000 2421.527089 +EDGE_SE2 27 28 0.585700 -0.007698 -0.004161 11.133727 2.517886 0.000000 291.434633 0.000000 2479.324138 +EDGE_SE2 28 29 0.378831 0.003536 0.031104 11.435983 14.920983 0.000000 696.414325 0.000000 2351.446301 +EDGE_SE2 29 30 0.007031 -0.000919 -0.531386 303620.480641 -715329.968352 0.000000 1685390.466875 0.000000 1066.033037 +EDGE_SE2 30 31 0.172814 -0.047579 -0.267833 11.113242 2.570601 0.000000 3112.523002 0.000000 1555.306207 +EDGE_SE2 31 32 0.643089 -0.013458 -0.018151 11.112884 0.639397 0.000000 241.693017 0.000000 2411.657469 +EDGE_SE2 32 33 0.641505 0.012210 0.053138 11.380647 7.899680 0.000000 242.638725 0.000000 2254.080602 +EDGE_SE2 33 34 0.642958 0.012818 0.023470 11.113996 0.815809 0.000000 241.800271 0.000000 2386.655713 +EDGE_SE2 34 35 0.642138 0.012026 0.036992 11.188281 4.224347 0.000000 242.355561 0.000000 2324.819270 +EDGE_SE2 35 36 0.646989 -0.005904 -0.005774 11.113668 0.763126 0.000000 238.872355 0.000000 2471.378132 +EDGE_SE2 36 37 0.422413 0.003265 0.010657 11.115820 1.608217 0.000000 560.397185 0.000000 2447.554843 +EDGE_SE2 37 38 0.004147 -0.000362 -0.316561 298816.394178 -1278713.788579 0.000000 5472166.543975 0.000000 1442.308081 +EDGE_SE2 38 39 0.031682 -0.005795 -0.166903 29.991712 1348.903464 0.000000 96382.012864 0.000000 1835.990780 +EDGE_SE2 39 40 0.628745 0.004932 0.020565 11.150244 3.076040 0.000000 252.904983 0.000000 2400.262103 +EDGE_SE2 40 41 0.654706 -0.007135 -0.028394 11.179108 -3.886059 0.000000 233.200483 0.000000 2363.855583 +EDGE_SE2 41 42 0.615233 -0.005892 -0.018963 11.133406 -2.375163 0.000000 264.145862 0.000000 2407.815356 +EDGE_SE2 42 43 0.646018 -0.015551 -0.036078 11.144050 -2.742429 0.000000 239.441473 0.000000 2328.922864 +EDGE_SE2 43 44 0.644889 -0.007273 -0.032646 11.215795 -4.898393 0.000000 240.317651 0.000000 2344.428944 +EDGE_SE2 44 45 0.642617 -0.019475 -0.055423 11.256800 -5.797160 0.000000 241.788650 0.000000 2244.330959 +EDGE_SE2 45 46 0.643577 -0.008674 -0.019276 11.118853 -1.335200 0.000000 241.382966 0.000000 2406.336795 +EDGE_SE2 46 47 0.643124 -0.007411 -0.041538 11.318826 -6.918261 0.000000 241.534792 0.000000 2304.569286 +EDGE_SE2 47 48 0.647528 -0.005000 -0.006399 11.111509 0.300792 0.000000 238.482697 0.000000 2468.309505 +EDGE_SE2 48 49 0.643552 -0.004657 -0.050649 11.544947 -9.986829 0.000000 241.006497 0.000000 2264.773140 +EDGE_SE2 49 50 0.613650 -0.021431 -0.044298 11.133509 -2.385631 0.000000 265.211665 0.000000 2292.403781 +EDGE_SE2 50 51 0.614419 0.001282 -0.030028 11.372766 -8.144597 0.000000 264.630129 0.000000 2356.361658 +EDGE_SE2 51 52 0.612275 -0.025515 -0.077517 11.439261 -9.144885 0.000000 265.960759 0.000000 2153.236570 +EDGE_SE2 52 53 0.589010 0.013532 0.011867 11.145260 -3.075254 0.000000 288.053971 0.000000 2441.704725 +EDGE_SE2 53 54 0.549942 -0.015900 -0.062397 11.469128 -10.685144 0.000000 330.013480 0.000000 2214.962293 +EDGE_SE2 54 55 -0.007990 -0.000400 0.004985 3173.514815 -70220.700546 0.000000 1559251.248529 0.000000 2475.260146 +EDGE_SE2 55 56 0.031075 -0.000065 0.010280 26.926592 1279.597558 0.000000 103540.680562 0.000000 2449.381862 +EDGE_SE2 56 57 0.661651 0.003067 -0.011448 11.167314 -3.494319 0.000000 228.362912 0.000000 2443.728134 +EDGE_SE2 57 58 0.651514 0.005099 0.046426 11.445370 8.655456 0.000000 235.239298 0.000000 2283.089649 +EDGE_SE2 58 59 0.644894 -0.007287 -0.023143 11.143280 -2.715787 0.000000 240.386652 0.000000 2388.181524 +EDGE_SE2 59 60 0.641666 0.006484 0.022061 11.144235 2.770355 0.000000 242.816230 0.000000 2393.240674 +EDGE_SE2 60 61 0.644092 -0.013088 -0.049766 11.310377 -6.764558 0.000000 240.749901 0.000000 2268.584724 +EDGE_SE2 61 62 0.610542 0.010202 0.039027 11.239154 5.735944 0.000000 268.065336 0.000000 2315.721577 +EDGE_SE2 62 63 0.615687 -0.014578 -0.037143 11.156928 -3.401279 0.000000 263.609811 0.000000 2324.142368 +EDGE_SE2 63 64 0.614457 0.023223 0.060765 11.244984 5.822514 0.000000 264.348682 0.000000 2221.783030 +EDGE_SE2 64 65 0.613126 -0.015622 -0.054905 11.331684 -7.492495 0.000000 265.618387 0.000000 2246.535610 +EDGE_SE2 65 66 0.642083 0.005221 -0.012134 11.206140 -4.688688 0.000000 242.448428 0.000000 2440.416656 +EDGE_SE2 66 67 0.644032 -0.000439 -0.003525 11.112971 -0.654045 0.000000 241.091541 0.000000 2482.467756 +EDGE_SE2 67 68 0.480969 0.003132 -0.018150 11.367193 -10.381901 0.000000 432.006963 0.000000 2411.662206 +EDGE_SE2 68 69 0.010004 -0.000372 -0.158022 14522.704416 -119457.061100 0.000000 983362.087562 0.000000 1864.259601 +EDGE_SE2 69 70 0.007781 -0.000530 -0.680912 544035.164858 -773651.719241 0.000000 1100214.270443 0.000000 884.810063 +EDGE_SE2 70 71 -0.005768 0.002595 -0.648935 125743.539339 -546312.647396 0.000000 2373762.361377 0.000000 919.460202 +EDGE_SE2 71 72 0.000000 0.000000 -0.011790 11.165166 -4.584575 0.000000 399.945945 0.000000 2442.076380 +EDGE_SE2 72 73 0.003590 -0.000252 -0.067514 59.238767 19279.280557 0.000000 7723027.108236 0.000000 2193.777612 +EDGE_SE2 73 74 0.003377 -0.001263 -0.627884 547328.125180 -1977782.419372 0.000000 7146917.196299 0.000000 943.393977 +EDGE_SE2 74 75 0.001263 0.000666 -0.356531 27289611.550657 -24363663.505902 0.000000 21751450.848890 0.000000 1358.565441 +EDGE_SE2 75 76 0.014525 0.005731 0.687334 38537.927166 119650.043523 0.000000 371599.899935 0.000000 878.087699 +EDGE_SE2 76 77 0.012722 0.001600 0.229532 6624.040036 63075.527086 0.000000 601638.946912 0.000000 1653.713745 +EDGE_SE2 77 78 0.282617 0.095127 0.333053 11.189119 9.319517 0.000000 1124.510027 0.000000 1406.840866 +EDGE_SE2 78 79 0.636095 0.008032 -0.007625 11.207888 -4.778031 0.000000 247.011069 0.000000 2462.306663 +EDGE_SE2 79 80 0.646911 -0.030410 -0.077284 11.319895 -6.885926 0.000000 238.216160 0.000000 2154.168095 +EDGE_SE2 80 81 0.639697 -0.008063 -0.028569 11.170556 -3.722959 0.000000 244.273973 0.000000 2363.051282 +EDGE_SE2 81 82 0.643152 -0.022848 -0.050289 11.161415 -3.403565 0.000000 241.398318 0.000000 2266.325966 +EDGE_SE2 82 83 0.640259 -0.000745 -0.019030 11.185422 -4.158907 0.000000 243.868413 0.000000 2407.498744 +EDGE_SE2 83 84 0.642213 -0.028725 -0.071607 11.278239 -6.209353 0.000000 241.809620 0.000000 2177.051366 +EDGE_SE2 84 85 0.642807 -0.004171 0.013937 11.207431 4.714878 0.000000 241.906303 0.000000 2431.743719 +EDGE_SE2 85 86 0.729089 -0.020666 -0.079989 11.582543 -9.118938 0.000000 187.499441 0.000000 2143.389493 +EDGE_SE2 86 87 0.611674 -0.018501 -0.038112 11.126983 -2.015351 0.000000 267.015944 0.000000 2319.805566 +EDGE_SE2 87 88 0.363613 -0.001497 -0.025112 11.439512 -15.640496 0.000000 756.007915 0.000000 2379.016060 +EDGE_SE2 88 89 0.022194 0.007878 0.405075 748.400424 11505.714792 0.000000 179562.707200 0.000000 1266.312242 +EDGE_SE2 89 90 0.645333 -0.002553 -0.026790 11.230485 -5.227171 0.000000 239.999401 0.000000 2371.246746 +EDGE_SE2 90 91 0.653796 0.009633 0.053106 11.438992 8.540445 0.000000 233.567599 0.000000 2254.217590 +EDGE_SE2 91 92 0.637138 -0.022076 -0.111746 12.505303 -18.044302 0.000000 244.649107 0.000000 2022.687812 +EDGE_SE2 92 93 0.640542 -0.048819 -0.097619 11.218480 -4.981269 0.000000 242.212560 0.000000 2075.089230 +EDGE_SE2 93 94 0.639915 -0.019948 -0.040363 11.130823 -2.142336 0.000000 243.948392 0.000000 2309.777849 +EDGE_SE2 94 95 0.643361 0.058181 0.138081 11.634914 10.928304 0.000000 239.112551 0.000000 1930.161562 +EDGE_SE2 95 96 0.638452 0.002717 0.020015 11.169275 3.690420 0.000000 245.262988 0.000000 2402.851280 +EDGE_SE2 96 97 0.615807 -0.026362 -0.075608 11.382661 -8.269572 0.000000 262.946629 0.000000 2160.886525 +EDGE_SE2 97 98 0.610633 -0.021924 -0.063326 11.304343 -7.040699 0.000000 267.649507 0.000000 2211.093675 +EDGE_SE2 98 99 0.729556 0.014258 0.041080 11.193076 3.804772 0.000000 187.727053 0.000000 2306.597420 +EDGE_SE2 99 100 0.585696 -0.025742 -0.058133 11.167610 -3.975845 0.000000 290.892636 0.000000 2232.849702 +EDGE_SE2 100 101 0.637186 0.067759 0.095665 11.135663 -2.388768 0.000000 243.522972 0.000000 2082.497224 +EDGE_SE2 101 102 0.646556 -0.024441 -0.094339 11.838827 -12.853666 0.000000 238.145742 0.000000 2087.546965 +EDGE_SE2 102 103 0.640410 0.007435 0.107121 13.227361 22.089363 0.000000 241.679335 0.000000 2039.622675 +EDGE_SE2 103 104 0.644201 -0.014336 -0.024966 11.112805 -0.623830 0.000000 240.845479 0.000000 2379.693860 +EDGE_SE2 104 105 0.644960 0.019675 0.055427 11.253454 5.708380 0.000000 240.033921 0.000000 2244.313947 +EDGE_SE2 105 106 0.633327 -0.017685 -0.046638 11.194517 -4.454694 0.000000 249.035067 0.000000 2282.164848 +EDGE_SE2 106 107 0.647889 -0.007117 0.003228 11.156976 3.226972 0.000000 238.156676 0.000000 2483.937815 +EDGE_SE2 107 108 0.418841 0.012880 0.059022 11.557560 15.782621 0.000000 569.050200 0.000000 2229.102528 +EDGE_SE2 108 109 0.012870 -0.002240 -0.453333 45067.256701 -156114.787673 0.000000 540932.368601 0.000000 1183.612533 +EDGE_SE2 109 110 0.014179 -0.004043 -0.597121 45347.441263 -137112.106751 0.000000 414683.621097 0.000000 980.086413 +EDGE_SE2 110 111 0.096952 -0.046958 -0.510989 42.005133 -514.703903 0.000000 8586.236292 0.000000 1095.008280 +EDGE_SE2 111 112 0.662640 0.007778 0.052084 11.463505 8.729519 0.000000 227.358980 0.000000 2258.599235 +EDGE_SE2 112 113 0.647895 0.015723 0.044858 11.207376 4.673389 0.000000 237.990065 0.000000 2289.947176 +EDGE_SE2 113 114 0.639175 0.001049 0.034783 11.367673 7.738365 0.000000 244.514402 0.000000 2334.755667 +EDGE_SE2 114 115 0.643430 0.022360 0.055827 11.213458 4.852193 0.000000 241.150882 0.000000 2242.613753 +EDGE_SE2 115 116 0.763396 0.014434 0.039419 11.178609 3.289916 0.000000 171.464543 0.000000 2313.975233 +EDGE_SE2 116 117 0.634411 0.022615 0.090058 11.812568 12.875464 0.000000 247.444399 0.000000 2103.976068 +EDGE_SE2 117 118 0.031050 -0.001921 -0.343244 7981.193322 -27566.715976 0.000000 95358.161435 0.000000 1385.575483 +EDGE_SE2 118 119 0.498463 -0.026118 -0.058682 11.126767 -2.471741 0.000000 401.352854 0.000000 2230.534528 +EDGE_SE2 119 120 0.638636 0.019165 0.084147 11.796072 12.637674 0.000000 244.278828 0.000000 2126.981262 +EDGE_SE2 120 121 0.608883 0.022686 0.061480 11.262812 6.257264 0.000000 269.206349 0.000000 2218.790906 +EDGE_SE2 121 122 0.610979 0.006491 0.049908 11.507132 10.075663 0.000000 267.458443 0.000000 2267.971114 +EDGE_SE2 122 123 0.214919 0.006655 -0.018770 16.427458 -106.823784 0.000000 2157.570163 0.000000 2408.727735 +EDGE_SE2 123 124 0.224600 -0.105868 -0.436366 11.138335 6.622207 0.000000 1621.948711 0.000000 1211.740925 +EDGE_SE2 124 125 0.625260 -0.011376 -0.017225 11.111340 0.236437 0.000000 255.702505 0.000000 2416.050226 +EDGE_SE2 125 126 0.630905 0.083897 0.196975 12.098786 15.227356 0.000000 245.877115 0.000000 1744.897213 +EDGE_SE2 126 127 0.635911 -0.003633 -0.003082 11.112746 0.621349 0.000000 247.280806 0.000000 2484.660949 +EDGE_SE2 127 128 0.644637 0.020444 0.034153 11.112488 0.561814 0.000000 240.398060 0.000000 2337.601172 +EDGE_SE2 128 129 0.638546 -0.014303 -0.035619 11.152032 -3.094288 0.000000 245.089747 0.000000 2330.987741 +EDGE_SE2 129 130 0.640721 0.025473 0.048893 11.130575 2.125338 0.000000 243.187509 0.000000 2272.362609 +EDGE_SE2 130 131 0.641480 0.013548 0.083601 12.014929 14.445918 0.000000 242.003477 0.000000 2129.125269 +EDGE_SE2 131 132 0.641305 -0.014532 -0.055040 11.354232 -7.504896 0.000000 242.779959 0.000000 2245.960726 +EDGE_SE2 132 133 0.581934 -0.015905 -0.042094 11.173057 -4.193601 0.000000 295.010721 0.000000 2302.110777 +EDGE_SE2 133 134 0.610231 0.001805 -0.024124 11.299860 -6.968043 0.000000 268.350792 0.000000 2383.608476 +EDGE_SE2 134 135 0.579655 -0.017960 -0.033069 11.112368 -0.599782 0.000000 297.332685 0.000000 2342.509439 +EDGE_SE2 135 136 0.642725 0.014632 0.012040 11.137646 -2.474784 0.000000 241.922944 0.000000 2440.870018 +EDGE_SE2 136 137 0.634138 -0.020053 -0.051400 11.204026 -4.694831 0.000000 248.333522 0.000000 2261.538905 +EDGE_SE2 137 138 0.640742 0.028547 0.068532 11.244796 5.567274 0.000000 242.959321 0.000000 2189.600800 +EDGE_SE2 138 139 0.624343 0.022436 0.065016 11.318542 7.127247 0.000000 256.001043 0.000000 2204.081980 +EDGE_SE2 139 140 0.649355 0.026111 0.030256 11.133375 -2.241330 0.000000 236.751877 0.000000 2355.318828 +EDGE_SE2 140 141 0.633752 -0.015337 -0.048721 11.254069 -5.827843 0.000000 248.689278 0.000000 2273.108048 +EDGE_SE2 141 142 0.643523 0.009872 -0.004100 11.198132 -4.475923 0.000000 241.330701 0.000000 2479.625389 +EDGE_SE2 142 143 0.634003 -0.068517 -0.110892 11.113575 -0.760641 0.000000 245.906731 0.000000 2025.798896 +EDGE_SE2 143 144 0.367489 0.008323 0.017249 11.132342 -3.934021 0.000000 740.076637 0.000000 2415.936223 +EDGE_SE2 144 145 0.011506 -0.002421 -0.499034 59809.374609 -199183.039696 0.000000 663473.241646 0.000000 1112.543606 +EDGE_SE2 145 146 0.002065 0.000912 -0.593946 14068785.759218 -8838843.642003 0.000000 5553100.053245 0.000000 983.994793 +EDGE_SE2 146 147 0.052046 -0.024279 -0.487148 88.850566 -1532.993200 0.000000 30241.168070 0.000000 1130.398639 +EDGE_SE2 147 148 0.437634 -0.008022 -0.035943 11.269607 -8.996749 0.000000 521.795770 0.000000 2329.529896 +EDGE_SE2 148 149 0.649282 0.006558 0.024834 11.160187 3.330542 0.000000 237.137078 0.000000 2380.306915 +EDGE_SE2 149 150 0.638778 0.018547 0.013910 11.164529 -3.533262 0.000000 244.815913 0.000000 2431.874707 +EDGE_SE2 150 151 0.642396 0.027197 0.085399 11.539278 9.931167 0.000000 241.460866 0.000000 2122.077176 +EDGE_SE2 151 152 0.642196 -0.014560 -0.068180 11.589745 -10.509493 0.000000 241.870955 0.000000 2191.044127 +EDGE_SE2 152 153 0.641634 0.027219 0.085722 11.545124 10.011045 0.000000 242.028095 0.000000 2120.814737 +EDGE_SE2 153 154 0.638389 -0.020707 -0.077238 11.580742 -10.472604 0.000000 244.646718 0.000000 2154.352072 +EDGE_SE2 154 155 0.642162 0.011168 0.026427 11.130001 2.090263 0.000000 242.407116 0.000000 2372.924244 +EDGE_SE2 155 156 0.644865 0.009414 0.023665 11.129963 2.079071 0.000000 240.400517 0.000000 2385.746522 +EDGE_SE2 156 157 0.581283 -0.014428 -0.072363 11.754151 -13.514232 0.000000 295.128631 0.000000 2173.984116 +EDGE_SE2 157 158 0.187127 -0.000419 0.029090 13.902620 89.068131 0.000000 2852.990445 0.000000 2360.659192 +EDGE_SE2 158 159 -0.002775 0.000752 0.993417 10949150.533757 3540503.247990 0.000000 1144864.853964 0.000000 629.134778 +EDGE_SE2 159 160 0.010178 0.000761 1.042069 650920.894971 448555.873968 0.000000 309120.571532 0.000000 599.513799 +EDGE_SE2 160 161 -0.000005 0.000004 0.981942 2693538350855.096191 -157146640359.091309 0.000000 9168262482.076782 0.000000 636.440966 +EDGE_SE2 161 162 -0.015739 -0.012123 1.042202 35897.561333 88343.035344 0.000000 217488.511233 0.000000 599.435534 +EDGE_SE2 162 163 0.001603 0.001566 1.003233 1029828.017450 4408843.295789 0.000000 18875113.167768 0.000000 622.984264 +EDGE_SE2 163 164 0.014062 0.009080 0.929958 43510.337182 116762.574144 0.000000 313430.450998 0.000000 671.188169 +EDGE_SE2 164 165 0.127064 0.050581 0.402133 14.003612 124.194925 0.000000 5343.652150 0.000000 1271.632407 +EDGE_SE2 165 166 0.660048 0.003938 -0.000969 11.121614 -1.514549 0.000000 229.516161 0.000000 2495.162033 +EDGE_SE2 166 167 0.637952 -0.005107 -0.029173 11.216206 -4.964111 0.000000 245.589760 0.000000 2360.278446 +EDGE_SE2 167 168 0.609195 0.011564 0.012037 11.123559 -1.792903 0.000000 269.346120 0.000000 2440.884489 +EDGE_SE2 168 169 0.616410 -0.017912 -0.037053 11.127238 -2.015259 0.000000 262.946448 0.000000 2324.545784 +EDGE_SE2 169 170 0.607779 0.006983 -0.020916 11.383588 -8.405441 0.000000 270.404841 0.000000 2398.611924 +EDGE_SE2 170 171 0.584191 -0.014911 -0.038741 11.160361 -3.724488 0.000000 292.775082 0.000000 2316.996943 +EDGE_SE2 171 172 0.648836 0.010594 0.013474 11.112953 -0.645665 0.000000 237.471401 0.000000 2433.967559 +EDGE_SE2 172 173 0.642894 -0.013166 -0.018042 11.112478 0.561628 0.000000 241.844714 0.000000 2412.173920 +EDGE_SE2 173 174 0.638185 0.007116 0.045162 11.382152 7.965912 0.000000 245.229896 0.000000 2288.615243 +EDGE_SE2 174 175 0.625733 0.004082 -0.019946 11.282223 -6.462935 0.000000 255.218243 0.000000 2403.176400 +EDGE_SE2 175 176 0.613713 -0.013173 0.014287 11.435899 9.081745 0.000000 265.055874 0.000000 2430.067237 +EDGE_SE2 176 177 0.634525 0.002256 -0.022912 11.277271 -6.276557 0.000000 248.202540 0.000000 2389.260272 +EDGE_SE2 177 178 0.640137 -0.023037 -0.034183 11.111855 0.416076 0.000000 243.719928 0.000000 2337.465554 +EDGE_SE2 178 179 0.353790 0.008069 0.053221 11.839402 23.935910 0.000000 797.785636 0.000000 2253.725346 +EDGE_SE2 179 180 0.003152 -0.000263 -0.442165 1233046.693540 -3286666.439106 0.000000 8760647.410566 0.000000 1202.015605 +EDGE_SE2 180 181 0.557570 -0.008188 -0.051388 11.529199 -11.385701 0.000000 321.175409 0.000000 2261.590530 +EDGE_SE2 181 182 0.573085 -0.036151 -0.172968 14.630195 -31.871096 0.000000 299.756322 0.000000 1817.053357 +EDGE_SE2 182 183 0.603594 -0.027970 -0.056017 11.135892 -2.551709 0.000000 273.866587 0.000000 2241.806837 +EDGE_SE2 183 184 0.635433 -0.054532 -0.150813 12.107735 -15.262873 0.000000 244.855650 0.000000 1887.689196 +EDGE_SE2 184 185 0.634881 -0.022979 -0.096285 11.965079 -14.190439 0.000000 246.914669 0.000000 2080.142393 +EDGE_SE2 185 186 0.643298 -0.040128 -0.069768 11.123925 -1.715150 0.000000 240.694352 0.000000 2184.544034 +EDGE_SE2 186 187 0.616544 -0.013175 -0.025584 11.115593 -1.062453 0.000000 262.945790 0.000000 2376.826796 +EDGE_SE2 187 188 0.637286 0.000267 -0.008123 11.128264 -2.008140 0.000000 246.207666 0.000000 2459.874568 +EDGE_SE2 188 189 0.639354 -0.005159 -0.029399 11.217330 -4.979110 0.000000 244.512278 0.000000 2359.242182 +EDGE_SE2 189 190 0.641605 -0.016631 -0.026189 11.111129 -0.063557 0.000000 242.757543 0.000000 2374.025058 +EDGE_SE2 190 191 0.641101 -0.008160 -0.020962 11.126855 -1.911760 0.000000 243.247747 0.000000 2398.395787 +EDGE_SE2 191 192 0.634787 -0.009757 -0.024655 11.131543 -2.200448 0.000000 248.088013 0.000000 2381.138634 +EDGE_SE2 192 193 0.586234 -0.010454 -0.051260 11.423659 -9.345831 0.000000 290.571036 0.000000 2262.141300 +EDGE_SE2 193 194 0.611583 -0.006689 -0.021980 11.142360 -2.829372 0.000000 267.292453 0.000000 2393.620056 +EDGE_SE2 194 195 0.610567 -0.010284 -0.023227 11.121593 -1.641455 0.000000 268.159748 0.000000 2387.789433 +EDGE_SE2 195 196 0.641859 -0.011003 -0.041852 11.252480 -5.719563 0.000000 242.515471 0.000000 2303.180363 +EDGE_SE2 196 197 0.640092 -0.013813 -0.028233 11.121429 -1.549936 0.000000 243.946727 0.000000 2364.595903 +EDGE_SE2 197 198 0.639039 -0.009178 -0.058660 11.569437 -10.339579 0.000000 244.366482 0.000000 2230.627234 +EDGE_SE2 198 199 0.637088 -0.027408 -0.061598 11.192373 -4.367444 0.000000 245.840841 0.000000 2218.297682 +EDGE_SE2 199 200 0.636910 -0.008520 -0.021764 11.127669 -1.974000 0.000000 246.454469 0.000000 2394.632181 +EDGE_SE2 200 201 0.639616 -0.019900 -0.056243 11.258405 -5.857515 0.000000 244.050370 0.000000 2240.847600 +EDGE_SE2 201 202 0.573162 0.008125 0.017141 11.113691 0.869688 0.000000 304.336907 0.000000 2416.449299 +EDGE_SE2 202 203 0.807715 -0.017801 -0.055477 11.269967 -4.748397 0.000000 153.046283 0.000000 2244.101317 +EDGE_SE2 203 204 0.600516 -0.019464 -0.097088 12.222178 -17.152147 0.000000 275.898243 0.000000 2077.098438 +EDGE_SE2 204 205 0.607570 -0.009135 -0.005030 11.137105 2.598215 0.000000 270.811426 0.000000 2475.038492 +EDGE_SE2 205 206 0.587179 0.007336 0.006623 11.120721 -1.637028 0.000000 289.985432 0.000000 2467.211100 +EDGE_SE2 206 207 0.607993 0.006080 0.021126 11.143219 2.885684 0.000000 270.462940 0.000000 2397.625450 +EDGE_SE2 207 208 0.644034 -0.008545 -0.004095 11.130455 2.108903 0.000000 241.029670 0.000000 2479.650084 +EDGE_SE2 208 209 0.640840 0.009001 0.044393 11.325040 7.046915 0.000000 243.239179 0.000000 2291.986757 +EDGE_SE2 209 210 0.641153 -0.014043 -0.012923 11.129806 2.082671 0.000000 243.128297 0.000000 2436.616291 +EDGE_SE2 210 211 0.640990 0.006728 -0.001668 11.145470 -2.824640 0.000000 243.325777 0.000000 2491.680820 +EDGE_SE2 211 212 0.638573 -0.025254 -0.057210 11.184192 -4.132365 0.000000 244.776704 0.000000 2236.750195 +EDGE_SE2 212 213 0.648396 -0.008808 -0.024826 11.139763 -2.548475 0.000000 237.786398 0.000000 2380.344078 +EDGE_SE2 213 214 0.637242 -0.004643 -0.007684 11.111148 -0.093735 0.000000 246.245036 0.000000 2462.018335 +EDGE_SE2 214 215 0.369747 -0.004429 -0.039914 11.673090 -20.110851 0.000000 730.793592 0.000000 2311.772848 +EDGE_SE2 215 216 0.006980 -0.001179 -0.507763 222524.090867 -628114.036197 0.000000 1773063.824260 0.000000 1099.699039 +EDGE_SE2 216 217 -0.001832 0.001260 -0.551814 52174.391125 1025898.356469 0.000000 20176415.615022 0.000000 1038.151360 +EDGE_SE2 217 218 0.000862 -0.000506 -0.060277 20602967.870958 40459206.697150 0.000000 79452073.533188 0.000000 2223.828683 +EDGE_SE2 218 219 0.576874 -0.106568 -0.173874 11.132755 2.459345 0.000000 290.557594 0.000000 1814.249623 +EDGE_SE2 219 220 0.629125 -0.005523 -0.044144 11.413053 -8.534327 0.000000 252.332357 0.000000 2293.080041 +EDGE_SE2 220 221 0.642903 0.008921 0.051755 11.442103 8.733716 0.000000 241.563444 0.000000 2260.012484 +EDGE_SE2 221 222 0.635198 -0.000697 -0.024981 11.246132 -5.652071 0.000000 247.710771 0.000000 2379.624210 +EDGE_SE2 222 223 0.639045 0.029371 0.096256 11.701399 11.718901 0.000000 243.764798 0.000000 2080.252449 +EDGE_SE2 223 224 0.637940 -0.001297 -0.026485 11.251362 -5.734476 0.000000 245.578734 0.000000 2372.656095 +EDGE_SE2 224 225 0.639421 0.008657 0.048309 11.393218 8.109986 0.000000 244.256072 0.000000 2274.895125 +EDGE_SE2 225 226 0.638048 -0.023812 -0.051167 11.156122 -3.246372 0.000000 245.250378 0.000000 2262.541595 +EDGE_SE2 226 227 0.642744 0.047412 0.156718 12.692747 18.992206 0.000000 239.168545 0.000000 1868.465232 +EDGE_SE2 227 228 0.588969 -0.135551 -0.358747 15.698176 -34.406864 0.000000 269.191657 0.000000 1354.137035 +EDGE_SE2 228 229 0.605993 0.034684 0.124928 12.304340 17.583695 0.000000 270.228487 0.000000 1975.560427 +EDGE_SE2 229 230 0.370582 0.002463 -0.025443 11.849164 -22.992568 0.000000 727.398994 0.000000 2377.480475 +EDGE_SE2 230 231 -0.130796 -0.004868 0.073003 18.577316 208.431226 0.000000 5829.807352 0.000000 2171.391514 +EDGE_SE2 231 232 0.345343 -0.135465 -0.413759 12.252120 -28.551107 0.000000 725.536788 0.000000 1250.803404 +EDGE_SE2 232 233 0.649941 0.026872 0.109205 12.147339 15.241388 0.000000 235.289518 0.000000 2031.965694 +EDGE_SE2 233 234 0.647791 -0.001996 -0.038195 11.391127 -7.971100 0.000000 238.021188 0.000000 2319.434660 +EDGE_SE2 234 235 0.300180 0.002544 0.000515 11.180724 -8.744740 0.000000 1109.628316 0.000000 2497.426988 +EDGE_SE2 235 236 0.331863 0.149674 0.417637 11.138398 -4.503817 0.000000 754.488686 0.000000 1243.969525 +EDGE_SE2 236 237 0.654682 0.025212 0.076902 11.438281 8.513385 0.000000 232.640473 0.000000 2155.696624 +EDGE_SE2 237 238 0.648140 0.014417 -0.026834 11.656908 -11.112994 0.000000 237.383264 0.000000 2371.043534 +EDGE_SE2 238 239 0.643519 -0.017811 -0.061244 11.370468 -7.722173 0.000000 241.033805 0.000000 2219.777847 +EDGE_SE2 239 240 0.603843 -0.096900 -0.209505 11.761203 -12.890609 0.000000 266.717846 0.000000 1708.931569 +EDGE_SE2 240 241 0.584456 0.014283 0.092258 12.403890 19.031519 0.000000 291.281847 0.000000 2095.509047 +EDGE_SE2 241 242 0.612687 0.022692 0.027357 11.134913 -2.463133 0.000000 266.004463 0.000000 2368.630078 +EDGE_SE2 242 243 0.648066 -0.017400 -0.010559 11.171248 3.692755 0.000000 237.869261 0.000000 2448.029575 +EDGE_SE2 243 244 0.642215 0.026261 0.062075 11.214953 4.895996 0.000000 241.951020 0.000000 2216.305562 +EDGE_SE2 244 245 0.634243 -0.022273 -0.061989 11.282517 -6.373688 0.000000 248.115451 0.000000 2216.664530 +EDGE_SE2 245 246 0.645668 -0.028614 -0.079256 11.390140 -7.976362 0.000000 239.124210 0.000000 2146.303161 +EDGE_SE2 246 247 0.643529 0.022831 0.100014 12.068378 14.809059 0.000000 240.209522 0.000000 2066.063111 +EDGE_SE2 247 248 0.564321 0.027061 0.024967 11.270232 -6.932385 0.000000 313.133504 0.000000 2379.689217 +EDGE_SE2 248 249 -0.035940 0.003373 0.183988 5772.276933 20220.354842 0.000000 70979.863375 0.000000 1783.386223 +EDGE_SE2 249 250 0.007750 -0.001049 -0.606852 338497.920927 -662461.020100 0.000000 1296530.178991 0.000000 968.251297 +EDGE_SE2 250 251 0.463939 -0.175406 -0.437806 13.410741 -30.065645 0.000000 404.193089 0.000000 1209.314960 +EDGE_SE2 251 252 0.574959 0.003510 0.002433 11.115040 -1.069896 0.000000 302.485346 0.000000 2487.879253 +EDGE_SE2 252 253 0.605120 -0.005928 -0.017244 11.125640 -1.950811 0.000000 273.056569 0.000000 2415.959973 +EDGE_SE2 253 254 0.610735 -0.012632 -0.047846 11.300633 -6.974744 0.000000 267.794244 0.000000 2276.905934 +EDGE_SE2 254 255 0.044400 0.000523 0.074991 213.390433 3196.298492 0.000000 50517.134043 0.000000 2163.367754 +EDGE_SE2 255 256 0.001043 -0.000895 -0.499566 2299182.592246 10791888.202847 0.000000 50655150.120270 0.000000 1111.754353 +EDGE_SE2 256 257 0.555824 -0.061442 -0.099167 11.147977 3.373126 0.000000 319.742706 0.000000 2069.248487 +EDGE_SE2 257 258 0.629719 0.018359 0.091632 12.050310 15.010875 0.000000 251.024412 0.000000 2097.913089 +EDGE_SE2 258 259 0.636152 0.019457 0.038906 11.127473 1.964002 0.000000 246.855618 0.000000 2316.261026 +EDGE_SE2 259 260 0.591139 -0.005281 -0.010083 11.111475 -0.316152 0.000000 286.144813 0.000000 2450.337378 +EDGE_SE2 260 261 0.038207 -0.011731 -0.314328 28.012479 -1028.395525 0.000000 62585.773083 0.000000 1447.213112 +EDGE_SE2 261 262 0.655511 -0.012976 0.004878 11.245910 5.462837 0.000000 232.497259 0.000000 2475.787308 +EDGE_SE2 262 263 0.621841 0.001156 0.011526 11.134237 2.392264 0.000000 258.583295 0.000000 2443.351271 +EDGE_SE2 263 264 0.608889 0.019368 0.094641 12.130010 16.192201 0.000000 268.435238 0.000000 2086.395259 +EDGE_SE2 264 265 0.612314 0.007199 0.017955 11.120930 1.584091 0.000000 266.671128 0.000000 2412.586253 +EDGE_SE2 265 266 0.576085 -0.083302 -0.132058 11.148980 3.279437 0.000000 295.110014 0.000000 1950.754657 +EDGE_SE2 266 267 0.757425 -0.007866 -0.038469 11.239778 -4.580310 0.000000 174.161685 0.000000 2318.210856 +EDGE_SE2 267 268 0.631857 -0.080953 -0.120705 11.121739 1.581391 0.000000 246.417934 0.000000 1990.478036 +EDGE_SE2 268 269 0.641922 0.003817 0.021827 11.169502 3.676650 0.000000 242.613796 0.000000 2394.336911 +EDGE_SE2 269 270 0.637667 0.034307 0.104727 11.718968 11.913668 0.000000 244.612698 0.000000 2048.472187 +EDGE_SE2 270 271 0.640010 -0.062261 -0.119686 11.230091 -5.238185 0.000000 241.725444 0.000000 1994.102659 +EDGE_SE2 271 272 0.644232 0.019193 0.057497 11.287428 6.360389 0.000000 240.553533 0.000000 2235.536271 +EDGE_SE2 272 273 0.634342 0.083237 0.206754 12.465423 17.719715 0.000000 242.954542 0.000000 1716.732048 +EDGE_SE2 273 274 0.640984 0.007900 0.019834 11.124210 1.744119 0.000000 243.341574 0.000000 2403.704272 +EDGE_SE2 274 275 0.606472 -0.086361 -0.177559 11.443959 -9.213419 0.000000 266.144138 0.000000 1802.912528 +EDGE_SE2 275 276 0.612197 0.023588 0.108696 12.366721 17.860495 0.000000 265.168738 0.000000 2033.831865 +EDGE_SE2 276 277 0.583581 0.010361 -0.030920 11.779645 -13.724550 0.000000 292.866956 0.000000 2352.285755 +EDGE_SE2 277 278 0.636078 -0.067917 -0.095289 11.139759 2.584894 0.000000 244.345909 0.000000 2083.927264 +EDGE_SE2 278 279 0.642761 -0.012725 -0.054157 11.383584 -7.926158 0.000000 241.680475 0.000000 2249.724898 +EDGE_SE2 279 280 0.638781 -0.006089 0.003079 11.148313 2.949856 0.000000 245.014031 0.000000 2484.675811 +EDGE_SE2 280 281 0.641856 -0.029617 -0.099276 11.763757 -12.263888 0.000000 241.562200 0.000000 2068.838150 +EDGE_SE2 281 282 0.639782 0.004798 0.040856 11.370470 7.772433 0.000000 244.033931 0.000000 2307.590321 +EDGE_SE2 282 283 0.642050 0.012891 -0.006948 11.280026 -6.249342 0.000000 242.317369 0.000000 2465.618735 +EDGE_SE2 283 284 0.634635 -0.008598 0.028031 11.520810 9.848040 0.000000 247.830973 0.000000 2365.525243 +EDGE_SE2 284 285 0.644186 0.019368 0.016799 11.151476 -3.044364 0.000000 240.720053 0.000000 2418.075116 +EDGE_SE2 285 286 0.616883 0.003268 0.049122 11.594142 11.014881 0.000000 262.290847 0.000000 2271.370705 +EDGE_SE2 286 287 0.041606 0.000178 -0.109420 754.499701 -6510.220695 0.000000 57024.326077 0.000000 2031.178201 +EDGE_SE2 287 288 0.009415 -0.003373 -0.619963 74221.251106 -262085.361102 0.000000 925608.832783 0.000000 952.642204 +EDGE_SE2 288 289 0.020008 -0.006408 -0.604589 19113.152514 -62948.109898 0.000000 207447.816761 0.000000 970.984702 +EDGE_SE2 289 290 0.454169 -0.104092 -0.231282 11.127187 -2.688060 0.000000 460.591382 0.000000 1649.016296 +EDGE_SE2 290 291 0.647578 0.004260 0.009723 11.113360 0.715048 0.000000 238.447481 0.000000 2452.084944 +EDGE_SE2 291 292 0.634089 -0.015008 -0.055281 11.348399 -7.502724 0.000000 248.336711 0.000000 2244.935000 +EDGE_SE2 292 293 0.642557 -0.005982 -0.023777 11.159473 -3.342559 0.000000 242.132375 0.000000 2385.224555 +EDGE_SE2 293 294 0.639112 0.001322 -0.000108 11.112218 -0.508677 0.000000 244.817748 0.000000 2499.460087 +EDGE_SE2 294 295 0.640372 -0.027705 -0.113609 12.259570 -16.292856 0.000000 242.253178 0.000000 2015.925806 +EDGE_SE2 295 296 0.642975 -0.021060 -0.046516 11.154844 -3.174767 0.000000 241.583458 0.000000 2282.696976 +EDGE_SE2 296 297 0.642345 0.000782 -0.012863 11.156958 -3.255777 0.000000 242.314814 0.000000 2436.904980 +EDGE_SE2 297 298 0.647985 0.003784 0.003363 11.112504 -0.562400 0.000000 238.150885 0.000000 2483.269445 +EDGE_SE2 298 299 0.612845 -0.007635 0.065661 12.664708 19.847274 0.000000 264.661036 0.000000 2201.414711 +EDGE_SE2 299 300 0.612360 0.028900 0.046427 11.111248 -0.186667 0.000000 266.084327 0.000000 2283.085285 +EDGE_SE2 300 301 0.590205 -0.014952 -0.054929 11.352681 -8.158527 0.000000 286.648280 0.000000 2246.433393 +EDGE_SE2 301 302 0.327130 -0.001110 -0.017014 11.282416 -12.575459 0.000000 934.273069 0.000000 2417.052846 +EDGE_SE2 302 303 0.000000 0.000000 0.007958 11.135739 3.094647 0.000000 399.975372 0.000000 2460.679983 +EDGE_SE2 303 304 0.531735 -0.000572 0.013349 11.182383 4.940694 0.000000 353.608097 0.000000 2434.568072 +EDGE_SE2 304 305 0.632029 0.091742 0.189082 11.583394 10.503320 0.000000 244.699503 0.000000 1768.138981 +EDGE_SE2 305 306 0.638032 0.009278 -0.014535 11.309292 -6.814055 0.000000 245.399171 0.000000 2428.879337 +EDGE_SE2 306 307 0.649045 -0.016359 -0.033059 11.125080 -1.777236 0.000000 237.218596 0.000000 2342.554790 +EDGE_SE2 307 308 0.638862 -0.008726 -0.051832 11.451746 -8.918684 0.000000 244.624962 0.000000 2259.681604 +EDGE_SE2 308 309 0.645288 0.030453 0.096996 11.678208 11.369540 0.000000 239.055109 0.000000 2077.446846 +EDGE_SE2 309 310 0.636777 0.000884 -0.032322 11.378630 -7.932902 0.000000 246.350008 0.000000 2345.900799 +EDGE_SE2 310 311 0.290424 -0.002112 0.179746 51.710880 214.552149 0.000000 1144.926065 0.000000 1796.234285 +EDGE_SE2 311 312 0.007354 0.003264 1.002917 471360.416969 711283.404228 0.000000 1073363.876974 0.000000 623.180856 +EDGE_SE2 312 313 0.200119 0.102327 0.503683 13.003444 61.001684 0.000000 1977.575148 0.000000 1105.674845 +EDGE_SE2 313 314 0.633848 0.018391 0.043519 11.161147 3.447475 0.000000 248.643057 0.000000 2295.827675 +EDGE_SE2 314 315 0.633704 0.002276 -0.000875 11.115856 -1.062415 0.000000 249.007791 0.000000 2495.630735 +EDGE_SE2 315 316 0.639305 0.015820 0.052631 11.292626 6.506496 0.000000 244.340479 0.000000 2256.252482 +EDGE_SE2 316 317 0.637745 0.004302 0.011142 11.115650 1.032197 0.000000 245.854624 0.000000 2445.207439 +EDGE_SE2 317 318 0.636745 0.035394 0.095957 11.494620 9.481044 0.000000 245.500106 0.000000 2081.387677 +EDGE_SE2 318 319 0.348842 0.011538 0.072712 12.383431 32.072340 0.000000 819.582938 0.000000 2172.569763 +EDGE_SE2 319 320 0.000816 -0.000527 0.973228 106005797.819726 2536098.274165 0.000000 60685.105012 0.000000 642.074570 +EDGE_SE2 320 321 0.006777 0.006256 1.044793 102222.634261 331234.073682 0.000000 1073432.269379 0.000000 597.917382 +EDGE_SE2 321 322 0.006473 0.002839 1.001084 615262.184536 923437.444301 0.000000 1386009.040037 0.000000 624.323050 +EDGE_SE2 322 323 0.016353 0.013170 0.997277 22353.154021 67589.307695 0.000000 204482.767224 0.000000 626.705357 +EDGE_SE2 323 324 0.008916 0.001230 0.663199 311347.556233 536104.854899 0.000000 923155.252921 0.000000 903.756801 +EDGE_SE2 324 325 0.003144 -0.000405 -0.524891 1487579.272379 -3549001.141685 0.000000 8467125.043520 0.000000 1075.133530 +EDGE_SE2 325 326 0.023808 -0.007961 -0.592174 11258.329132 -40719.337055 0.000000 147431.069280 0.000000 986.186273 +EDGE_SE2 326 327 0.020978 -0.009992 -0.620226 5671.563195 -31879.996101 0.000000 179561.107529 0.000000 952.332958 +EDGE_SE2 327 328 0.643658 -0.034894 -0.045241 11.129369 2.047184 0.000000 240.647976 0.000000 2288.269306 +EDGE_SE2 328 329 0.649334 -0.010852 -0.054672 11.436629 -8.570843 0.000000 236.780423 0.000000 2247.528337 +EDGE_SE2 329 330 0.639632 -0.008474 -0.018872 11.118489 -1.311825 0.000000 244.371181 0.000000 2408.245480 +EDGE_SE2 330 331 0.641038 0.003713 -0.014179 11.203728 -4.636800 0.000000 243.249680 0.000000 2430.584821 +EDGE_SE2 331 332 0.640252 -0.011677 -0.018427 11.111120 -0.044254 0.000000 243.867115 0.000000 2410.350498 +EDGE_SE2 332 333 0.177633 -0.001729 0.065170 28.796073 235.654693 0.000000 3151.244188 0.000000 2203.444704 +EDGE_SE2 333 334 0.000905 -0.002029 1.057518 13067665.297415 -9690930.296947 0.000000 7186773.836950 0.000000 590.544626 +EDGE_SE2 334 335 0.024703 0.015296 0.997066 21742.343151 45843.877395 0.000000 96722.659299 0.000000 626.837793 +EDGE_SE2 335 336 0.010478 0.002030 0.946908 412732.144616 438156.323325 0.000000 465170.257567 0.000000 659.552164 +EDGE_SE2 336 337 0.008745 0.002954 0.985008 440385.721295 568301.950425 0.000000 733402.863015 0.000000 634.476419 +EDGE_SE2 337 338 -0.003685 -0.001824 0.981724 1470665.482891 2556461.697178 0.000000 4443948.812959 0.000000 636.580801 +EDGE_SE2 338 339 -0.005129 -0.003808 1.041677 377018.548764 884152.776785 0.000000 2073514.322517 0.000000 599.744033 +EDGE_SE2 339 340 0.010570 0.010289 1.011780 25946.779143 106050.417947 0.000000 433649.108522 0.000000 617.702041 +EDGE_SE2 340 341 0.113717 0.080150 0.628571 12.212286 75.337385 0.000000 5165.350612 0.000000 942.598218 +EDGE_SE2 341 342 0.654766 0.022058 0.099815 12.080273 14.632015 0.000000 232.019342 0.000000 2066.810844 +EDGE_SE2 342 343 0.628741 0.054742 0.130801 11.574390 10.533194 0.000000 250.595866 0.000000 1955.093991 +EDGE_SE2 343 344 0.635892 -0.007155 -0.010075 11.111438 0.277943 0.000000 247.273507 0.000000 2450.376193 +EDGE_SE2 344 345 0.267580 0.003485 -0.027538 13.388942 -56.127772 0.000000 1394.149289 0.000000 2367.795687 +EDGE_SE2 345 346 0.004489 0.000038 -0.647423 1844936.688291 -2397918.213433 0.000000 3116674.368121 0.000000 921.148732 +EDGE_SE2 346 347 0.072838 -0.046842 -0.558829 13.253512 168.933111 0.000000 13331.862665 0.000000 1028.828663 +EDGE_SE2 347 348 0.589079 -0.006098 -0.016843 11.122785 -1.798313 0.000000 288.130205 0.000000 2417.865855 +EDGE_SE2 348 349 0.616820 -0.017333 -0.040458 11.149561 -3.109556 0.000000 262.589175 0.000000 2309.356075 +EDGE_SE2 349 350 0.785503 -0.000917 -0.019918 11.164179 -2.829897 0.000000 162.017193 0.000000 2403.308352 +EDGE_SE2 350 351 0.270645 -0.005037 -0.029292 11.265595 -14.459903 0.000000 1364.581559 0.000000 2359.732718 +EDGE_SE2 351 352 0.002244 -0.000330 -0.288296 389945.087215 -2724716.373664 0.000000 19039335.129753 0.000000 1506.290344 +EDGE_SE2 352 353 0.003402 -0.001192 -0.665425 800995.211276 -2349889.351851 0.000000 6894005.592158 0.000000 901.342500 +EDGE_SE2 353 354 -0.005763 0.001670 -0.603397 277124.929036 -832459.339385 0.000000 2500747.295676 0.000000 972.428940 +EDGE_SE2 354 355 0.000000 0.000000 -0.720990 180.577269 -192.833418 0.000000 230.533842 0.000000 844.079125 +EDGE_SE2 355 356 0.003943 -0.001205 -0.575253 444990.541595 -1555501.608157 0.000000 5437532.684522 0.000000 1007.486830 +EDGE_SE2 356 357 0.020153 -0.008599 -0.653072 12735.537924 -49883.324785 0.000000 195567.746252 0.000000 914.863854 +EDGE_SE2 357 358 0.015309 -0.003110 -0.615454 66643.110857 -151211.449053 0.000000 343163.086320 0.000000 957.967591 +EDGE_SE2 358 359 0.006974 -0.000995 -0.614029 417035.012297 -816381.545249 0.000000 1598190.077659 0.000000 959.659886 +EDGE_SE2 359 360 0.004457 -0.000580 -0.176301 10913.841058 -232052.237339 0.000000 4938979.710352 0.000000 1806.770854 +EDGE_SE2 360 361 0.010594 0.005702 0.919376 117786.647020 259806.659966 0.000000 573130.987341 0.000000 678.609427 +EDGE_SE2 361 362 0.219803 0.130838 0.533743 11.126432 -4.821230 0.000000 1528.288566 0.000000 1062.759073 +EDGE_SE2 362 363 0.297072 -0.003532 -0.006476 11.143964 6.070793 0.000000 1132.926894 0.000000 2467.931845 +EDGE_SE2 363 364 0.289348 0.182399 0.614616 13.404127 43.923133 0.000000 852.466620 0.000000 958.962236 +EDGE_SE2 364 365 0.292841 -0.019896 -0.497082 210.238012 -435.053006 0.000000 961.616130 0.000000 1115.446721 +EDGE_SE2 365 366 0.158985 -0.083838 -0.554071 25.686079 -211.524041 0.000000 3080.923734 0.000000 1035.138105 +EDGE_SE2 366 367 0.639497 -0.004946 0.002087 11.133620 2.291973 0.000000 244.487349 0.000000 2489.597576 +EDGE_SE2 367 368 0.604131 -0.012617 -0.052944 11.381139 -8.419024 0.000000 273.602223 0.000000 2254.911286 +EDGE_SE2 368 369 0.002209 0.000313 -0.259186 3043052.869717 -7202482.111400 0.000000 17047344.890980 0.000000 1576.740546 +EDGE_SE2 369 370 0.005991 -0.002050 -0.599321 177021.973379 -640449.340665 0.000000 2317243.809168 0.000000 977.391885 +EDGE_SE2 370 371 0.006708 -0.002639 -0.557206 63344.214539 -343349.901593 0.000000 1861425.577547 0.000000 1030.974377 +EDGE_SE2 371 372 0.558575 -0.019962 -0.032348 11.114630 1.042696 0.000000 320.094134 0.000000 2345.782636 +EDGE_SE2 372 373 0.602488 0.010152 -0.002327 11.208284 -5.066873 0.000000 275.312725 0.000000 2488.405486 +EDGE_SE2 373 374 0.632591 -0.017325 -0.065949 11.465862 -9.193251 0.000000 249.351067 0.000000 2200.225307 +EDGE_SE2 374 375 0.469417 0.004030 -0.028771 11.728554 -16.521047 0.000000 453.167816 0.000000 2362.123399 +EDGE_SE2 375 376 0.002158 0.000483 0.698524 4333313.980583 8354996.990813 0.000000 16109195.449061 0.000000 866.555999 +EDGE_SE2 376 377 0.046225 0.038326 0.699019 12.380728 187.607270 0.000000 27733.237753 0.000000 866.051140 +EDGE_SE2 377 378 0.665310 0.013616 0.055080 11.368301 7.426696 0.000000 225.566926 0.000000 2245.790433 +EDGE_SE2 378 379 0.642743 0.038423 0.085729 11.266862 5.984327 0.000000 241.043246 0.000000 2120.787390 +EDGE_SE2 379 380 0.640645 0.038346 0.120298 11.958441 13.985039 0.000000 241.931786 0.000000 1991.924564 +EDGE_SE2 380 381 0.233459 0.003584 0.150906 44.408710 244.130938 0.000000 1801.027395 0.000000 1887.384136 +EDGE_SE2 381 382 0.006327 0.000255 1.053123 1795131.477569 1120171.329981 0.000000 699008.143264 0.000000 593.075621 +EDGE_SE2 382 383 -0.003556 -0.002021 0.980056 1193066.389244 2388759.272445 0.000000 4782832.968807 0.000000 637.653764 +EDGE_SE2 383 384 0.001991 0.002244 0.957091 138704.428768 1233640.966374 0.000000 10972926.458664 0.000000 652.706547 +EDGE_SE2 384 385 0.011270 0.001792 1.022982 445019.439592 379059.233315 0.000000 322894.736351 0.000000 610.880091 +EDGE_SE2 385 386 0.168577 0.055826 0.222392 40.994230 -305.838725 0.000000 3141.216954 0.000000 1673.088872 +EDGE_SE2 386 387 0.606264 0.162988 0.328749 12.170230 15.994975 0.000000 252.669738 0.000000 1415.970180 +EDGE_SE2 387 388 0.635832 0.013644 0.010758 11.138130 -2.525694 0.000000 247.211302 0.000000 2447.065724 +EDGE_SE2 388 389 0.627947 -0.024187 -0.080320 11.534345 -10.113978 0.000000 252.803888 0.000000 2142.077483 +EDGE_SE2 389 390 0.069191 0.001300 0.478702 4122.849667 8300.847325 0.000000 16769.002054 0.000000 1143.348663 +EDGE_SE2 390 391 -0.133725 -0.033239 0.382997 112.537800 723.030020 0.000000 5165.300931 0.000000 1307.066045 +EDGE_SE2 391 392 -0.002743 0.000191 1.047762 10690557.469801 5209631.734700 0.000000 2538727.272155 0.000000 596.185006 +EDGE_SE2 392 393 0.028217 0.013447 1.259453 54184.105027 51083.362632 0.000000 48181.052425 0.000000 489.703700 +EDGE_SE2 393 394 0.008510 0.003621 0.998557 368727.424224 543264.764209 0.000000 800454.686659 0.000000 625.902660 +EDGE_SE2 394 395 -0.234595 -0.069505 0.339597 15.518106 85.399492 0.000000 1665.996927 0.000000 1393.130101 +EDGE_SE2 395 396 0.000000 0.000000 0.001250 11.111719 0.486111 0.000000 399.999392 0.000000 2493.761699 +EDGE_SE2 396 397 0.001351 -0.000419 -0.009641 4125762.827775 13757530.022207 0.000000 45875198.303653 0.000000 2452.483262 +EDGE_SE2 397 398 0.004038 0.000754 0.199105 1257.017158 85923.998064 0.000000 5925765.672764 0.000000 1738.703710 +EDGE_SE2 398 399 0.122070 0.031296 0.300741 26.669772 312.344207 0.000000 6281.503348 0.000000 1477.604991 +EDGE_SE2 399 400 0.657179 0.003449 0.051415 11.580586 10.161892 0.000000 231.067499 0.000000 2261.474377 +EDGE_SE2 400 401 0.635899 -0.025106 -0.091900 11.758968 -12.342900 0.000000 246.266720 0.000000 2096.883376 +EDGE_SE2 401 402 0.629497 -0.118990 -0.266463 12.583010 -18.442000 0.000000 242.178169 0.000000 1558.672941 +EDGE_SE2 402 403 0.633089 -0.005208 -0.033694 11.265698 -6.068382 0.000000 249.328787 0.000000 2339.677603 +EDGE_SE2 403 404 0.592291 -0.016693 -0.078703 11.809289 -13.806384 0.000000 284.130876 0.000000 2148.504341 +EDGE_SE2 404 405 0.003136 0.000509 0.534523 1319098.360620 3365183.519520 0.000000 8585083.951642 0.000000 1061.678944 +EDGE_SE2 405 406 -0.004868 -0.003220 0.979360 434468.323030 1042340.456046 0.000000 2500772.052588 0.000000 638.102476 +EDGE_SE2 406 407 0.360175 0.041381 0.128315 11.256473 10.438221 0.000000 760.666018 0.000000 1963.718742 +EDGE_SE2 407 408 0.616703 -0.006846 -0.037807 11.290664 -6.721434 0.000000 262.722906 0.000000 2321.169297 +EDGE_SE2 408 409 0.297889 -0.008429 -0.099428 16.743853 -79.045672 0.000000 1120.378773 0.000000 2068.266140 +EDGE_SE2 409 410 0.004317 -0.001082 -0.627510 701653.157370 -1746561.647658 0.000000 4347637.661335 0.000000 943.827609 +EDGE_SE2 410 411 -0.000994 0.000097 -0.588953 22378715.073239 -41773418.211876 0.000000 77976755.075261 0.000000 990.188564 +EDGE_SE2 411 412 0.546073 -0.101761 -0.202851 11.219546 -5.824669 0.000000 323.987402 0.000000 1727.890996 +EDGE_SE2 412 413 0.631438 -0.020731 -0.079531 11.633150 -11.167657 0.000000 250.014003 0.000000 2145.209801 +EDGE_SE2 413 414 0.633214 0.018368 0.103733 12.438356 17.726525 0.000000 247.864474 0.000000 2052.163475 +EDGE_SE2 414 415 0.642786 -0.007808 0.006683 11.192966 4.346517 0.000000 241.911433 0.000000 2466.917009 +EDGE_SE2 415 416 0.306053 0.007945 -0.055552 18.109521 -85.672115 0.000000 1059.879484 0.000000 2243.782429 +EDGE_SE2 416 417 0.267976 -0.110772 -0.425050 12.399497 -38.940001 0.000000 1188.028820 0.000000 1231.061654 +EDGE_SE2 417 418 0.438509 -0.005278 -0.045468 11.679675 -16.999880 0.000000 519.402521 0.000000 2287.275721 +EDGE_SE2 418 419 -0.008030 -0.002982 0.430439 7637.313369 101662.498186 0.000000 1355241.825942 0.000000 1221.803385 +EDGE_SE2 419 420 -0.065315 -0.007710 0.215762 233.503005 2255.992653 0.000000 22896.400499 0.000000 1691.386574 +EDGE_SE2 420 421 -0.013305 -0.007156 0.966654 91010.544219 177739.023434 0.000000 347168.883115 0.000000 646.374313 +EDGE_SE2 421 422 -0.003762 0.002250 1.237922 4986989.532826 -1042930.375544 0.000000 218119.888862 0.000000 499.171886 +EDGE_SE2 422 423 0.004840 0.001590 0.345136 2976.169439 106843.491501 0.000000 3850030.373965 0.000000 1381.680463 +EDGE_SE2 423 424 0.000000 0.000000 0.000279 11.111141 0.108500 0.000000 399.999970 0.000000 2498.605584 +EDGE_SE2 424 425 -0.001184 -0.000773 0.011635 14427656.748816 -22661090.484365 0.000000 35593138.003454 0.000000 2442.824774 +EDGE_SE2 425 426 0.000000 0.000000 -0.009217 11.144147 -3.584186 0.000000 399.966964 0.000000 2454.544407 +EDGE_SE2 426 427 0.032570 0.000297 0.003027 14.602102 -573.593983 0.000000 94256.571445 0.000000 2484.933444 +EDGE_SE2 427 428 0.662478 0.017221 -0.005659 11.327981 -6.850147 0.000000 227.483295 0.000000 2471.943383 +EDGE_SE2 428 429 0.646109 -0.008556 -0.041027 11.287389 -6.342667 0.000000 239.327268 0.000000 2306.832289 +EDGE_SE2 429 430 0.343414 -0.005292 -0.046373 11.913023 -25.889333 0.000000 846.935174 0.000000 2283.320937 +EDGE_SE2 430 431 -0.023101 -0.000669 0.051637 107.302578 4242.658469 0.000000 187139.464787 0.000000 2260.519686 +EDGE_SE2 431 432 0.009902 -0.002457 -0.632717 138557.863737 -337512.999974 0.000000 822224.717657 0.000000 937.817169 +EDGE_SE2 432 433 0.001378 -0.000302 -0.678362 9999210.149914 -20053649.036543 0.000000 40218116.393371 0.000000 887.500758 +EDGE_SE2 433 434 0.513100 -0.123605 -0.228760 11.131390 2.656033 0.000000 358.981365 0.000000 1655.792374 +EDGE_SE2 434 435 0.631214 0.005719 -0.028704 11.453001 -9.049106 0.000000 250.621585 0.000000 2362.431102 +EDGE_SE2 435 436 0.631793 -0.021639 -0.009165 11.261393 5.992726 0.000000 250.081133 0.000000 2454.797368 +EDGE_SE2 436 437 0.639424 0.009664 0.007564 11.124412 -1.761949 0.000000 244.511544 0.000000 2462.604819 +EDGE_SE2 437 438 0.468926 -0.010782 -0.032675 11.152708 -4.294523 0.000000 454.487167 0.000000 2344.297271 +EDGE_SE2 438 439 0.003173 -0.000464 -0.440138 821397.131579 -2704073.669587 0.000000 8902055.008072 0.000000 1205.401670 +EDGE_SE2 439 440 -0.014852 0.005433 -0.648635 34474.470288 -112210.861458 0.000000 365363.698028 0.000000 919.794858 +EDGE_SE2 440 441 -0.024049 0.006849 -0.627372 18805.328328 -51499.965243 0.000000 141131.456239 0.000000 943.987688 +EDGE_SE2 441 442 -0.014780 0.003839 -0.634781 59210.969468 -147922.954315 0.000000 369626.867304 0.000000 935.450222 +EDGE_SE2 442 443 -0.000800 0.000601 -0.571864 520464.172419 7194009.672200 0.000000 99439862.677541 0.000000 1011.835875 +EDGE_SE2 443 444 0.017737 -0.005934 -0.596674 20918.075426 -74425.493858 0.000000 264954.124953 0.000000 980.635254 +EDGE_SE2 444 445 0.013295 -0.004859 -0.663772 47441.842994 -146367.463524 0.000000 451689.453992 0.000000 903.134403 +EDGE_SE2 445 446 0.005858 0.000522 0.198590 34655.344042 314604.971132 0.000000 2856945.136973 0.000000 1740.198174 +EDGE_SE2 446 447 0.027440 0.012672 0.626113 4057.920343 20653.549968 0.000000 105419.866954 0.000000 945.449998 +EDGE_SE2 447 448 0.642139 0.024176 0.015042 11.228997 -5.217769 0.000000 242.055366 0.000000 2426.453558 +EDGE_SE2 448 449 0.651924 0.033077 0.098456 11.620735 10.662081 0.000000 234.177343 0.000000 2071.928088 +EDGE_SE2 449 450 0.646061 0.005408 0.011249 11.113005 0.657701 0.000000 239.562562 0.000000 2444.690013 +EDGE_SE2 450 451 0.475342 0.014049 0.039952 11.157786 4.485326 0.000000 442.142124 0.000000 2311.603906 +EDGE_SE2 451 452 0.003128 0.000025 -0.382848 1482988.188246 -3599772.040321 0.000000 8738081.943140 0.000000 1307.347729 +EDGE_SE2 452 453 -0.001414 0.000044 -0.628930 15847694.024322 -23260624.874036 0.000000 34141069.617498 0.000000 942.182786 +EDGE_SE2 453 454 0.248647 -0.103850 -0.427200 12.471635 -43.090213 0.000000 1375.854801 0.000000 1227.355391 +EDGE_SE2 454 455 0.599080 -0.006587 -0.019767 11.131695 -2.346400 0.000000 278.577271 0.000000 2404.020135 +EDGE_SE2 455 456 0.632985 -0.015395 -0.063626 11.479192 -9.358780 0.000000 249.066485 0.000000 2209.846555 +EDGE_SE2 456 457 0.357560 -0.010532 -0.086657 13.629849 -43.977817 0.000000 778.975316 0.000000 2117.166652 +EDGE_SE2 457 458 0.008700 -0.003028 -0.643446 108644.728053 -340906.127357 0.000000 1069817.962261 0.000000 925.612330 +EDGE_SE2 458 459 -0.005152 0.003223 -0.605857 5968.917352 -126872.556203 0.000000 2701785.030428 0.000000 969.451909 +EDGE_SE2 459 460 0.416054 -0.104238 -0.255576 11.165314 -5.371986 0.000000 543.523585 0.000000 1585.820389 +EDGE_SE2 460 461 0.649228 -0.030811 -0.086883 11.462229 -8.893307 0.000000 236.365424 0.000000 2116.286282 +EDGE_SE2 461 462 0.546102 -0.010087 -0.039056 11.248462 -6.670465 0.000000 335.062438 0.000000 2315.592315 +EDGE_SE2 462 463 0.001368 -0.000392 0.843270 40115968.021050 19291406.563907 0.000000 9277076.794710 0.000000 735.803923 +EDGE_SE2 463 464 0.219986 0.165070 0.680690 12.900768 48.403186 0.000000 1320.227268 0.000000 885.043825 +EDGE_SE2 464 465 0.606621 0.010649 0.008756 11.131273 -2.291927 0.000000 271.643258 0.000000 2456.788366 +EDGE_SE2 465 466 0.582724 -0.019176 -0.054453 11.242627 -6.100006 0.000000 294.042673 0.000000 2248.462015 +EDGE_SE2 466 467 0.609463 -0.011568 -0.042219 11.250443 -5.994134 0.000000 268.982117 0.000000 2301.558596 +EDGE_SE2 467 468 0.645554 -0.004365 -0.036329 11.311111 -6.762186 0.000000 239.747111 0.000000 2327.794866 +EDGE_SE2 468 469 0.640915 -0.033457 -0.083791 11.342903 -7.324322 0.000000 242.550344 0.000000 2128.378819 +EDGE_SE2 469 470 0.496055 0.004661 0.018154 11.141432 3.461691 0.000000 406.321439 0.000000 2411.643257 +EDGE_SE2 470 471 0.003172 -0.000201 -0.200803 186163.578620 -1344733.466553 0.000000 9714134.809108 0.000000 1733.789946 +EDGE_SE2 471 472 0.023951 -0.007826 -0.634338 15457.850073 -46841.273730 0.000000 142054.355974 0.000000 935.957765 +EDGE_SE2 472 473 0.005795 -0.000612 -0.642279 770586.651464 -1294281.400636 0.000000 2173924.317941 0.000000 926.928274 +EDGE_SE2 473 474 0.006655 -0.002332 -0.633006 171083.550792 -560999.777087 0.000000 1839703.994891 0.000000 937.485259 +EDGE_SE2 474 475 0.004438 -0.002279 -0.575983 41353.024051 -405427.745271 0.000000 3975919.455633 0.000000 1006.553705 +EDGE_SE2 475 476 0.004920 -0.000853 -0.653637 861490.486597 -1647075.461555 0.000000 3149079.624245 0.000000 914.238796 +EDGE_SE2 476 477 -0.005593 0.002916 -0.561690 16496.747941 -202882.586381 0.000000 2496811.464145 0.000000 1025.062106 +EDGE_SE2 477 478 -0.008770 0.002879 -0.629412 110767.500374 -343119.326612 0.000000 1062982.494329 0.000000 941.625450 +EDGE_SE2 478 479 -0.005316 0.000950 -0.456182 260653.569609 -908664.641767 0.000000 3167842.768150 0.000000 1178.986119 +EDGE_SE2 479 480 -0.002143 -0.000584 0.559864 1701134.587605 5621159.573829 0.000000 18574462.284739 0.000000 1027.463821 +EDGE_SE2 480 481 0.016780 0.006185 0.998459 113112.243905 150237.129574 0.000000 199577.592411 0.000000 625.964239 +EDGE_SE2 481 482 0.002129 0.000684 0.334515 11133.789831 471436.097728 0.000000 19981887.764379 0.000000 1403.760085 +EDGE_SE2 482 483 0.000000 0.000000 -0.006313 11.126610 -2.454990 0.000000 399.984501 0.000000 2468.731408 +EDGE_SE2 483 484 0.461514 0.003388 0.034531 11.449878 12.456397 0.000000 469.130063 0.000000 2335.893245 +EDGE_SE2 484 485 0.630348 0.014297 -0.002799 11.267128 -6.122690 0.000000 251.389266 0.000000 2486.063539 +EDGE_SE2 485 486 0.640080 -0.006164 0.008991 11.191872 4.336635 0.000000 243.975902 0.000000 2455.644098 +EDGE_SE2 486 487 0.638592 0.022157 0.027672 11.122603 -1.639115 0.000000 244.911905 0.000000 2367.178245 +EDGE_SE2 487 488 0.641671 0.002950 0.035457 11.331743 7.147283 0.000000 242.644669 0.000000 2331.717176 +EDGE_SE2 488 489 0.486254 0.015193 0.029736 11.112036 -0.616989 0.000000 422.520775 0.000000 2357.698224 +EDGE_SE2 489 490 0.004012 0.001331 0.483683 148092.465768 898284.334868 0.000000 5449142.422335 0.000000 1135.684680 +EDGE_SE2 490 491 0.003142 0.002440 0.933695 460500.560493 1642380.154927 0.000000 5857718.767430 0.000000 668.596440 +EDGE_SE2 491 492 0.234443 0.072984 0.301949 11.111148 0.245247 0.000000 1658.639702 0.000000 1474.864302 +EDGE_SE2 492 493 0.622117 -0.019196 -0.055751 11.264294 -6.149470 0.000000 257.979045 0.000000 2242.936641 +EDGE_SE2 493 494 0.632902 -0.009810 -0.061610 11.617811 -10.980862 0.000000 249.080844 0.000000 2218.247533 +EDGE_SE2 494 495 0.635286 0.054465 0.110803 11.261154 5.934337 0.000000 245.819252 0.000000 2026.123532 +EDGE_SE2 495 496 0.641209 0.012116 0.121000 13.521763 23.526915 0.000000 240.723619 0.000000 1989.430553 +EDGE_SE2 496 497 0.639602 -0.025661 -0.083377 11.547127 -10.068553 0.000000 243.615831 0.000000 2130.005800 +EDGE_SE2 497 498 0.634982 -0.033636 -0.099467 11.622457 -10.978306 0.000000 246.809304 0.000000 2068.119413 +EDGE_SE2 498 499 0.638794 -0.029903 -0.015370 11.341287 7.326250 0.000000 244.297416 0.000000 2424.886152 +EDGE_SE2 499 500 0.581639 0.165523 0.331283 11.876261 14.147113 0.000000 272.681816 0.000000 1410.584918 +EDGE_SE2 500 501 0.608658 -0.019295 -0.065817 11.412115 -8.816677 0.000000 269.359185 0.000000 2200.770331 +EDGE_SE2 501 502 0.717458 -0.037860 -0.078159 11.229253 -4.643405 0.000000 193.613030 0.000000 2150.673003 +EDGE_SE2 502 503 0.468033 -0.006282 -0.011528 11.112706 0.842757 0.000000 456.422908 0.000000 2443.341609 +EDGE_SE2 503 504 0.001010 -0.000329 0.882265 76783402.732445 30131648.184749 0.000000 11824394.003794 0.000000 705.632337 +EDGE_SE2 504 505 0.222895 0.156032 0.638914 12.174041 37.721370 0.000000 1349.770700 0.000000 930.738499 +EDGE_SE2 505 506 0.625769 -0.021473 -0.145256 14.102191 -26.846905 0.000000 252.079673 0.000000 1906.052494 +EDGE_SE2 506 507 0.635814 -0.018204 -0.072178 11.558631 -10.268279 0.000000 246.715411 0.000000 2174.734405 +EDGE_SE2 507 508 0.638204 -0.013687 -0.007658 11.155629 3.229265 0.000000 245.359315 0.000000 2462.145389 +EDGE_SE2 508 509 0.642039 -0.008726 -0.051671 11.446573 -8.804866 0.000000 242.212186 0.000000 2260.373525 +EDGE_SE2 509 510 0.372102 -0.006043 -0.009950 11.139237 4.471542 0.000000 722.013535 0.000000 2450.982789 +EDGE_SE2 510 511 0.002084 -0.003553 0.891003 5160201.305808 -1945038.253710 0.000000 733157.306436 0.000000 699.126192 +EDGE_SE2 511 512 0.007335 0.005942 1.221397 297144.725264 495141.758266 0.000000 825112.510283 0.000000 506.626201 +EDGE_SE2 512 513 -0.002181 -0.000566 0.972737 8538321.615481 9762487.124922 0.000000 11162190.656524 0.000000 642.394025 +EDGE_SE2 513 514 0.090094 0.023767 0.232272 18.681434 -295.052416 0.000000 11510.742828 0.000000 1646.367741 +EDGE_SE2 514 515 0.658710 0.013018 0.004928 11.159348 -3.251856 0.000000 230.330528 0.000000 2475.540949 +EDGE_SE2 515 516 0.637378 -0.008635 0.019744 11.371458 7.817478 0.000000 245.848124 0.000000 2404.128580 +EDGE_SE2 516 517 0.633811 0.029113 0.032052 11.156620 -3.285893 0.000000 248.362090 0.000000 2347.128404 +EDGE_SE2 517 518 0.634675 0.007993 0.028090 11.168044 3.673667 0.000000 248.158131 0.000000 2365.253746 +EDGE_SE2 518 519 0.560153 0.002654 -0.012150 11.198833 -5.193662 0.000000 318.608437 0.000000 2440.339501 +EDGE_SE2 519 520 0.197101 -0.000544 0.405434 414.955475 933.778631 0.000000 2170.216473 0.000000 1265.665952 +EDGE_SE2 520 521 0.006002 0.005024 1.019492 163989.160959 490677.362406 0.000000 1468282.469392 0.000000 612.993310 +EDGE_SE2 521 522 0.414779 0.108184 0.270025 11.229248 7.935203 0.000000 544.113259 0.000000 1549.942078 +EDGE_SE2 522 523 0.644866 -0.002177 -0.013262 11.133525 -2.267210 0.000000 240.444921 0.000000 2434.986160 +EDGE_SE2 523 524 0.606582 -0.016880 -0.047652 11.213538 -5.164087 0.000000 271.469885 0.000000 2277.749269 +EDGE_SE2 524 525 0.576823 0.002529 0.018772 11.171018 4.163585 0.000000 300.483332 0.000000 2408.718278 +EDGE_SE2 525 526 0.607148 -0.019364 -0.063586 11.372241 -8.233863 0.000000 270.738644 0.000000 2210.012777 +EDGE_SE2 526 527 0.632532 -0.013902 -0.038859 11.179151 -4.029527 0.000000 249.750981 0.000000 2316.470615 +EDGE_SE2 527 528 0.639965 -0.031254 -0.079842 11.335080 -7.212289 0.000000 243.362638 0.000000 2143.974316 +EDGE_SE2 528 529 0.630138 0.005118 -0.025519 11.383434 -8.091842 0.000000 251.553301 0.000000 2377.128104 +EDGE_SE2 529 530 0.643013 -0.010371 -0.027118 11.138973 -2.535041 0.000000 241.767362 0.000000 2369.732519 +EDGE_SE2 530 531 0.632204 -0.021106 -0.076364 11.552220 -10.254093 0.000000 249.479589 0.000000 2157.852130 +EDGE_SE2 531 532 0.210203 0.000529 0.053978 17.069737 115.687987 0.000000 2257.218094 0.000000 2250.489117 +EDGE_SE2 532 533 0.010481 0.007945 1.006775 71059.615350 189815.528908 0.000000 507128.543079 0.000000 620.787044 +EDGE_SE2 533 534 0.004524 0.002070 0.671821 233294.669406 942460.043629 0.000000 3807527.338703 0.000000 894.459037 +EDGE_SE2 534 535 0.000000 0.000000 0.001338 11.111807 0.520333 0.000000 399.999304 0.000000 2493.323403 +EDGE_SE2 535 536 0.357295 0.039869 0.132965 11.474755 16.648687 0.000000 773.337063 0.000000 1947.632537 +EDGE_SE2 536 537 0.617574 -0.018145 -0.055950 11.288271 -6.664110 0.000000 261.790435 0.000000 2242.091332 +EDGE_SE2 537 538 0.579730 -0.014385 -0.025102 11.111136 -0.083914 0.000000 297.359512 0.000000 2379.062475 +EDGE_SE2 538 539 0.638569 -0.022758 -0.062503 11.280003 -6.281777 0.000000 244.755892 0.000000 2214.520366 +EDGE_SE2 539 540 0.636808 -0.030043 -0.090399 11.550435 -10.149862 0.000000 245.607132 0.000000 2102.660323 +EDGE_SE2 540 541 0.624998 0.051843 0.165279 12.763015 19.972919 0.000000 252.600591 0.000000 1841.111831 +EDGE_SE2 541 542 0.637879 0.044546 0.058251 11.141827 -2.677719 0.000000 244.543713 0.000000 2232.351783 +EDGE_SE2 542 543 0.119005 -0.001027 -0.027249 13.554992 -131.231977 0.000000 7058.031360 0.000000 2369.128157 +EDGE_SE2 543 544 0.004143 0.001613 0.643358 365523.202414 1309813.828807 0.000000 4693733.444673 0.000000 925.711464 +EDGE_SE2 544 545 0.011964 0.010101 1.076679 54873.490374 139170.850294 0.000000 353049.492454 0.000000 579.697285 +EDGE_SE2 545 546 -0.062408 -0.034041 0.835070 2157.534535 6151.646423 0.000000 17641.720853 0.000000 742.394487 +EDGE_SE2 546 547 0.004683 0.006620 1.031598 8884.576322 115819.915331 0.000000 1511737.642851 0.000000 605.709415 +EDGE_SE2 547 548 0.010894 0.005062 0.931876 157491.371124 290395.414023 0.000000 535503.600637 0.000000 669.856096 +EDGE_SE2 548 549 0.018521 0.007174 0.814504 46970.071545 98477.220300 0.000000 206526.818200 0.000000 759.318793 +EDGE_SE2 549 550 0.007039 -0.001728 -0.474679 102346.133104 -429334.075047 0.000000 1801229.739954 0.000000 1149.595399 +EDGE_SE2 550 551 0.012919 -0.003649 -0.620137 63414.169645 -176527.986637 0.000000 491503.647693 0.000000 952.437591 +EDGE_SE2 551 552 0.004870 -0.001510 -0.626201 393240.954950 -1165183.372361 0.000000 3452577.879626 0.000000 945.347676 +EDGE_SE2 552 553 0.131013 -0.071366 -0.571551 34.798953 -324.963500 0.000000 4469.148228 0.000000 1012.238963 +EDGE_SE2 553 554 0.656516 -0.001289 -0.033128 11.325592 -6.879883 0.000000 231.796023 0.000000 2342.241894 +EDGE_SE2 554 555 0.640736 0.024110 0.091367 11.781224 12.453936 0.000000 242.565349 0.000000 2098.932021 +EDGE_SE2 555 556 0.644807 0.029102 0.137696 13.068095 21.074909 0.000000 238.068451 0.000000 1931.468129 +EDGE_SE2 556 557 0.641564 -0.010754 -0.042948 11.270029 -6.066916 0.000000 242.724912 0.000000 2298.342233 +EDGE_SE2 557 558 0.615263 0.021826 0.078921 11.588181 10.969921 0.000000 263.357654 0.000000 2147.636202 +EDGE_SE2 558 559 0.005363 -0.000612 -0.410558 293857.680729 -960260.813810 0.000000 3138046.146667 0.000000 1256.487325 +EDGE_SE2 559 560 0.000000 0.000000 -0.505043 102.152456 -164.670704 0.000000 308.958656 0.000000 1103.677058 +EDGE_SE2 560 561 0.009398 0.003440 0.501104 22371.403618 147733.503165 0.000000 976080.093687 0.000000 1109.476905 +EDGE_SE2 561 562 0.177331 0.126693 0.638384 11.791812 37.750509 0.000000 2104.689083 0.000000 931.340765 +EDGE_SE2 562 563 0.597201 -0.094603 -0.194811 11.484023 -9.885231 0.000000 273.150922 0.000000 1751.223531 +EDGE_SE2 563 564 0.639558 0.013847 0.046248 11.252240 5.735744 0.000000 244.222662 0.000000 2283.866567 +EDGE_SE2 564 565 0.614599 -0.011365 -0.051966 11.395132 -8.481100 0.000000 264.363876 0.000000 2259.105962 +EDGE_SE2 565 566 0.005382 -0.000625 0.804171 2155482.804415 1641813.690713 0.000000 1250573.669361 0.000000 768.041369 +EDGE_SE2 566 567 -0.001231 0.000678 0.856086 48423129.554559 10395439.301461 0.000000 2231696.342135 0.000000 725.677769 +EDGE_SE2 567 568 0.583042 0.017568 0.046196 11.184172 4.544849 0.000000 293.831241 0.000000 2284.093607 +EDGE_SE2 568 569 0.628101 -0.010139 -0.052147 11.425095 -8.716657 0.000000 253.098625 0.000000 2258.328765 +EDGE_SE2 569 570 0.639821 -0.001979 -0.004808 11.111796 -0.399705 0.000000 244.274090 0.000000 2476.132272 +EDGE_SE2 570 571 0.348563 -0.003118 -0.043397 12.074353 -27.948587 0.000000 822.042846 0.000000 2296.364589 +EDGE_SE2 571 572 0.037203 -0.034953 -0.237353 9379.952208 16482.424026 0.000000 29008.326343 0.000000 1632.874389 +EDGE_SE2 572 573 0.082599 0.001138 0.282645 1044.389047 3750.080318 0.000000 13621.294688 0.000000 1519.592228 +EDGE_SE2 573 574 0.006029 0.005935 0.955816 43915.035779 243749.664142 0.000000 1353281.899972 0.000000 653.557826 +EDGE_SE2 574 575 0.017352 0.009648 1.009306 58713.654313 106982.648688 0.000000 194982.001569 0.000000 619.224094 +EDGE_SE2 575 576 -0.000693 0.000729 1.024139 92116121.130465 -24932672.587732 0.000000 6748430.711509 0.000000 610.181931 +EDGE_SE2 576 577 0.005808 0.005602 0.968758 61460.098525 300963.429168 0.000000 1474062.832839 0.000000 644.993297 +EDGE_SE2 577 578 0.020578 -0.005874 -0.365770 1686.236926 -19051.115635 0.000000 216678.422748 0.000000 1340.246481 +EDGE_SE2 578 579 0.649778 -0.007064 0.014101 11.251830 5.633981 0.000000 236.679123 0.000000 2430.958734 +EDGE_SE2 579 580 0.646533 0.021127 0.074055 11.501231 9.420338 0.000000 238.586536 0.000000 2167.139990 +EDGE_SE2 580 581 0.641277 0.007721 0.041304 11.309760 6.786133 0.000000 242.935131 0.000000 2305.605160 +EDGE_SE2 581 582 0.642222 0.008953 0.042003 11.293216 6.487457 0.000000 242.225126 0.000000 2302.512889 +EDGE_SE2 582 583 0.324533 0.007424 0.078126 13.971366 51.714099 0.000000 946.114403 0.000000 2150.804664 +EDGE_SE2 583 584 0.003585 0.000066 0.840201 4172109.666193 3878928.313892 0.000000 3606370.037121 0.000000 738.260001 +EDGE_SE2 584 585 0.609333 0.022255 0.117010 12.778611 20.669000 0.000000 267.307574 0.000000 2003.668573 +EDGE_SE2 585 586 0.610182 0.017652 0.096276 12.276387 17.274488 0.000000 267.194725 0.000000 2080.176547 +EDGE_SE2 586 587 0.632351 0.024309 0.024257 11.158994 -3.379740 0.000000 249.665755 0.000000 2382.989492 +EDGE_SE2 587 588 0.643770 -0.006740 0.003322 11.154886 3.173805 0.000000 241.219104 0.000000 2483.472403 +EDGE_SE2 588 589 0.633840 0.040950 0.080270 11.169866 3.729294 0.000000 247.815430 0.000000 2142.275779 +EDGE_SE2 589 590 0.644706 0.014870 0.073779 11.700561 11.612184 0.000000 239.871719 0.000000 2168.254200 +EDGE_SE2 590 591 0.632424 0.012303 0.002621 11.178752 -4.018640 0.000000 249.862554 0.000000 2486.946343 +EDGE_SE2 591 592 0.642169 0.006914 0.001997 11.128903 -2.028750 0.000000 242.448415 0.000000 2490.044831 +EDGE_SE2 592 593 0.271993 0.001273 0.212505 68.183858 270.652782 0.000000 1294.612122 0.000000 1700.485497 +EDGE_SE2 593 594 0.014453 0.008841 0.993097 64316.365031 135154.721370 0.000000 284074.972077 0.000000 629.336815 +EDGE_SE2 594 595 0.571176 0.080832 0.240324 13.980407 28.672593 0.000000 297.633480 0.000000 1625.061173 +EDGE_SE2 595 596 0.575835 0.004878 -0.017875 11.312665 -7.648565 0.000000 301.358130 0.000000 2412.965503 +EDGE_SE2 596 597 0.635351 -0.013108 -0.034135 11.154253 -3.193993 0.000000 247.578146 0.000000 2337.682549 +EDGE_SE2 597 598 0.604127 -0.006451 -0.039602 11.330957 -7.598611 0.000000 273.744081 0.000000 2313.160651 +EDGE_SE2 598 599 0.385673 -0.010715 -0.063459 11.952011 -23.555254 0.000000 670.939617 0.000000 2210.540655 +EDGE_SE2 599 600 0.008688 0.002526 0.814757 314076.796383 533827.575685 0.000000 907375.060518 0.000000 759.107091 +EDGE_SE2 600 601 0.021686 0.011399 1.028615 44738.476040 73830.093373 0.000000 121880.188267 0.000000 607.492253 +EDGE_SE2 601 602 0.018101 0.007667 1.024411 88285.368598 122674.329555 0.000000 170491.062574 0.000000 610.017974 +EDGE_SE2 602 603 0.186319 0.162792 0.780432 17.405089 100.856712 0.000000 1627.271409 0.000000 788.658931 +EDGE_SE2 603 604 0.621077 -0.063008 -0.240492 15.850028 -33.777361 0.000000 251.864479 0.000000 1624.621039 +EDGE_SE2 604 605 0.633484 0.018906 0.082620 11.773196 12.531662 0.000000 248.305264 0.000000 2132.985568 +EDGE_SE2 605 606 0.635159 0.014918 0.042086 11.193000 4.401211 0.000000 247.658010 0.000000 2302.146123 +EDGE_SE2 606 607 0.573078 -0.057501 -0.081034 11.215573 5.506259 0.000000 301.350193 0.000000 2139.248825 +EDGE_SE2 607 608 0.372357 0.012526 0.044458 11.194332 7.682633 0.000000 720.342546 0.000000 2291.701491 +EDGE_SE2 608 609 0.009981 0.001237 0.336295 44194.195786 204270.386082 0.000000 944408.518792 0.000000 1400.022844 +EDGE_SE2 609 610 0.008024 0.008992 0.932617 5618.242041 61880.517104 0.000000 682926.927594 0.000000 669.342525 +EDGE_SE2 610 611 0.619179 0.006175 0.002964 11.123375 -1.749910 0.000000 260.797662 0.000000 2485.245630 +EDGE_SE2 611 612 0.495865 -0.011645 0.002777 11.383631 10.376429 0.000000 406.201910 0.000000 2486.172625 +EDGE_SE2 612 613 -0.032580 0.001507 0.463705 22407.672171 40045.920128 0.000000 71614.770023 0.000000 1166.898001 +EDGE_SE2 613 614 0.006074 0.002811 1.037837 720992.332387 1043867.597380 0.000000 1511367.480327 0.000000 602.006419 +EDGE_SE2 614 615 0.468918 0.167392 0.304515 11.688040 -15.032631 0.000000 402.805589 0.000000 1469.067849 +EDGE_SE2 615 616 0.634148 0.014484 -0.051156 12.408628 -17.503753 0.000000 247.240026 0.000000 2262.588948 +EDGE_SE2 616 617 0.620915 -0.099361 -0.217030 11.933466 -14.077035 0.000000 252.081317 0.000000 1687.863964 +EDGE_SE2 617 618 0.637519 0.006833 0.010118 11.111196 -0.140914 0.000000 246.016254 0.000000 2450.167576 +EDGE_SE2 618 619 0.602001 -0.001093 -0.001468 11.111143 0.091989 0.000000 275.933653 0.000000 2492.676131 +EDGE_SE2 619 620 0.611116 -0.021079 -0.096329 12.090448 -15.813910 0.000000 266.467179 0.000000 2079.975428 +EDGE_SE2 620 621 -0.351742 0.001000 -0.051606 13.005075 -38.809484 0.000000 806.361703 0.000000 2260.652962 +EDGE_SE2 621 622 -0.288473 0.005647 -0.075042 14.769187 -65.879798 0.000000 1197.567688 0.000000 2163.162499 +EDGE_SE2 622 623 -0.003587 0.000519 -0.537149 1119299.663768 -2695881.271885 0.000000 6493221.297933 0.000000 1058.054588 +EDGE_SE2 623 624 -0.002684 0.001648 -0.642690 84963.761375 -921398.117942 0.000000 9993513.245668 0.000000 926.464498 +EDGE_SE2 624 625 0.007502 -0.002176 -0.658633 221323.684950 -560152.893180 0.000000 1417785.340096 0.000000 908.739498 +EDGE_SE2 625 626 0.007582 -0.000720 -0.618128 430777.189603 -746427.081854 0.000000 1293412.370737 0.000000 954.803710 +EDGE_SE2 626 627 0.339972 -0.139061 -0.410806 11.481721 -16.444927 0.000000 740.815480 0.000000 1256.045618 +EDGE_SE2 627 628 0.641810 -0.041240 -0.100917 11.422475 -8.468830 0.000000 241.456222 0.000000 2062.675227 +EDGE_SE2 628 629 0.640763 0.030371 0.071050 11.241212 5.491249 0.000000 242.883687 0.000000 2179.317557 +EDGE_SE2 629 630 0.608678 0.024217 0.085089 11.641507 11.694459 0.000000 268.956806 0.000000 2123.289866 +EDGE_SE2 630 631 0.520687 0.012252 0.020220 11.115021 -1.182335 0.000000 368.639644 0.000000 2401.885734 +EDGE_SE2 631 632 0.003617 -0.000095 0.676209 3189142.029325 3767706.315238 0.000000 4451258.564395 0.000000 889.781790 +EDGE_SE2 632 633 0.052581 0.076324 1.075605 146.388666 1246.996416 0.000000 11505.997044 0.000000 580.297357 +EDGE_SE2 633 634 0.651291 -0.000853 0.025227 11.269271 5.958489 0.000000 235.590568 0.000000 2378.482380 +EDGE_SE2 634 635 0.638650 -0.043082 -0.137291 12.248607 -16.238485 0.000000 242.925867 0.000000 1932.844002 +EDGE_SE2 635 636 0.635527 0.004328 -0.019084 11.269630 -6.120407 0.000000 247.419146 0.000000 2407.243610 +EDGE_SE2 636 637 0.632517 -0.030952 -0.100684 11.749524 -12.316243 0.000000 248.715635 0.000000 2063.548601 +EDGE_SE2 637 638 0.419086 -0.009115 -0.030747 11.156304 -5.021448 0.000000 569.055296 0.000000 2353.075434 +EDGE_SE2 638 639 0.640680 0.028288 0.078765 11.389438 8.031492 0.000000 242.870396 0.000000 2148.257386 +EDGE_SE2 639 640 0.645185 -0.028949 -0.069702 11.252424 -5.682397 0.000000 239.608542 0.000000 2184.813613 +EDGE_SE2 640 641 0.631149 0.010125 -0.010170 11.275857 -6.284012 0.000000 250.806675 0.000000 2449.915330 +EDGE_SE2 641 642 0.608456 -0.016443 -0.047551 11.220217 -5.312718 0.000000 269.804578 0.000000 2278.188510 +EDGE_SE2 642 643 0.501922 -0.014902 -0.065028 11.592531 -13.614212 0.000000 396.111379 0.000000 2204.032313 +EDGE_SE2 643 644 0.006192 0.003634 0.763605 103362.922493 435664.745636 0.000000 1836493.394795 0.000000 803.780315 +EDGE_SE2 644 645 0.147583 0.161030 0.956903 45.062660 263.875747 0.000000 2061.986889 0.000000 652.831965 +EDGE_SE2 645 646 0.624864 0.078137 0.297396 18.253618 40.874666 0.000000 245.025960 0.000000 1485.234058 +EDGE_SE2 646 647 0.626416 0.074352 0.291155 18.229469 40.732090 0.000000 244.184966 0.000000 1499.626982 +EDGE_SE2 647 648 0.630437 0.066336 0.168411 12.070691 15.073373 0.000000 247.888334 0.000000 1831.254626 +EDGE_SE2 648 649 0.592663 -0.072497 -0.334526 23.127883 -55.612924 0.000000 268.484510 0.000000 1403.737590 +EDGE_SE2 649 650 0.621511 -0.143009 -0.254374 11.297892 -6.619122 0.000000 245.678334 0.000000 1588.861060 +EDGE_SE2 650 651 0.144853 0.010732 0.805829 2122.876396 2350.861156 0.000000 2628.138776 0.000000 766.631681 +EDGE_SE2 651 652 0.002718 0.001656 1.033599 2156297.352241 4079208.548390 0.000000 7716956.136248 0.000000 604.518184 +EDGE_SE2 652 653 0.014957 0.011986 1.038848 34378.938116 90407.858801 0.000000 237837.637992 0.000000 601.409535 +EDGE_SE2 653 654 0.267736 0.151078 0.517447 11.125502 3.881714 0.000000 1058.107188 0.000000 1085.707770 +EDGE_SE2 654 655 0.563434 -0.005218 -0.003312 11.121867 1.807836 0.000000 314.964252 0.000000 2483.521908 +EDGE_SE2 655 656 0.610635 -0.014726 -0.011084 11.154711 3.346600 0.000000 267.986619 0.000000 2445.487982 +EDGE_SE2 656 657 0.631799 0.103933 0.278849 14.219359 26.720114 0.000000 240.811095 0.000000 1528.626076 +EDGE_SE2 657 658 0.640227 0.007103 -0.006984 11.187191 -4.208049 0.000000 243.861599 0.000000 2465.442445 +EDGE_SE2 658 659 0.497774 -0.026439 -0.071049 11.237681 -7.036752 0.000000 402.323496 0.000000 2179.321626 +EDGE_SE2 659 660 0.006409 -0.000096 0.600351 810833.659716 1147194.412851 0.000000 1623122.139710 0.000000 976.134174 +EDGE_SE2 660 661 0.169432 0.128488 0.653648 11.162367 10.620021 0.000000 2211.525163 0.000000 914.226633 +EDGE_SE2 661 662 0.629749 0.003998 0.069631 12.075080 15.212434 0.000000 251.179162 0.000000 2185.103670 +EDGE_SE2 662 663 0.621897 0.037784 0.101008 11.511766 9.929781 0.000000 257.209513 0.000000 2062.334274 +EDGE_SE2 663 664 0.007280 -0.002392 0.538314 970988.716591 843174.347297 0.000000 732204.084386 0.000000 1056.452618 +EDGE_SE2 664 665 0.026579 0.029587 0.878851 111.857316 2521.446990 0.000000 63117.159733 0.000000 708.199031 +EDGE_SE2 665 666 0.623804 0.018831 0.034452 11.115596 1.049644 0.000000 256.744183 0.000000 2336.250038 +EDGE_SE2 666 667 0.580478 0.005759 0.002114 11.128518 -2.229713 0.000000 296.729354 0.000000 2489.463423 +EDGE_SE2 667 668 0.608507 -0.000467 0.023179 11.259577 6.198692 0.000000 269.917040 0.000000 2388.013473 +EDGE_SE2 668 669 0.638606 0.001692 -0.027742 11.327262 -7.110068 0.000000 244.989751 0.000000 2366.855797 +EDGE_SE2 669 670 0.636315 -0.034673 -0.062258 11.125493 -1.838895 0.000000 246.230714 0.000000 2215.542002 +EDGE_SE2 670 671 0.308072 0.001150 0.052261 13.564460 50.513802 0.000000 1051.177078 0.000000 2257.839465 +EDGE_SE2 671 672 -0.576602 0.036531 -0.092061 11.350145 -8.300360 0.000000 299.337680 0.000000 2096.265145 +EDGE_SE2 672 673 -0.262392 0.011580 -0.133741 22.638322 -128.254010 0.000000 1438.090461 0.000000 1944.967298 +EDGE_SE2 673 674 -0.005814 0.002674 -0.655099 120542.083833 -528941.427411 0.000000 2321232.182459 0.000000 912.624358 +EDGE_SE2 674 675 -0.014637 0.005942 -0.615221 20765.078980 -88798.929746 0.000000 379950.502646 0.000000 958.243990 +EDGE_SE2 675 676 -0.006630 0.003741 -0.630060 23265.609241 -198963.775781 0.000000 1702330.544222 0.000000 940.876947 +EDGE_SE2 676 677 -0.012856 0.004015 -0.622499 54491.338930 -164518.778220 0.000000 496823.064188 0.000000 949.666532 +EDGE_SE2 677 678 0.191689 -0.090627 -0.451238 11.315076 -21.245540 0.000000 2224.105339 0.000000 1187.032313 +EDGE_SE2 678 679 0.570835 0.011396 0.059784 11.579724 11.761290 0.000000 306.296841 0.000000 2225.898166 +EDGE_SE2 679 680 0.434701 0.056384 0.340338 33.525701 104.470312 0.000000 498.028172 0.000000 1391.589518 +EDGE_SE2 680 681 0.616588 -0.017915 -0.025786 11.113788 0.820773 0.000000 262.808564 0.000000 2375.890788 +EDGE_SE2 681 682 0.634780 0.014947 0.049632 11.272332 6.178273 0.000000 247.873967 0.000000 2269.163993 +EDGE_SE2 682 683 0.300050 0.004977 0.161644 34.081549 157.239703 0.000000 1087.465169 0.000000 1852.652221 +EDGE_SE2 683 684 0.008066 0.002610 1.069340 655223.236656 694424.027218 0.000000 735993.720066 0.000000 583.816417 +EDGE_SE2 684 685 0.408559 0.177472 0.439476 11.545242 14.621378 0.000000 503.554260 0.000000 1206.510628 +EDGE_SE2 685 686 0.481253 -0.056338 -0.146676 11.487851 -12.495538 0.000000 425.557060 0.000000 1901.334651 +EDGE_SE2 686 687 0.633778 -0.013418 -0.036773 11.168993 -3.709053 0.000000 248.788111 0.000000 2325.801528 +EDGE_SE2 687 688 0.633546 -0.023306 -0.013253 11.242546 5.587827 0.000000 248.672293 0.000000 2435.029417 +EDGE_SE2 688 689 0.601923 0.011148 0.026350 11.127352 2.073709 0.000000 275.894586 0.000000 2373.280306 +EDGE_SE2 689 690 0.577060 0.031776 0.072952 11.203899 5.171117 0.000000 299.300801 0.000000 2171.597942 +EDGE_SE2 690 691 0.431081 -0.000968 -0.029004 11.488376 -14.095403 0.000000 537.744126 0.000000 2361.053797 +EDGE_SE2 691 692 -0.008991 -0.001137 0.532009 190083.391915 441924.473409 0.000000 1027500.439761 0.000000 1065.166196 +EDGE_SE2 692 693 -0.002490 -0.004336 1.036147 719.063258 -53205.166853 0.000000 3998572.017505 0.000000 603.006163 +EDGE_SE2 693 694 -0.004998 -0.000127 0.832038 2085335.472274 1998610.421428 0.000000 1915513.414270 0.000000 744.853827 +EDGE_SE2 694 695 0.001511 0.001312 0.796919 166502.359918 2031923.976353 0.000000 24798401.868961 0.000000 774.253197 +EDGE_SE2 695 696 0.013256 0.002978 1.021557 279104.028874 270742.205141 0.000000 262652.464508 0.000000 611.741616 +EDGE_SE2 696 697 0.014932 -0.001676 -0.254525 8971.193925 -62353.454280 0.000000 433930.455572 0.000000 1588.478599 +EDGE_SE2 697 698 0.334592 -0.212289 -0.657753 16.435194 -57.473689 0.000000 631.541865 0.000000 909.704543 +EDGE_SE2 698 699 0.645635 0.022320 0.112426 12.493854 17.721303 0.000000 238.228242 0.000000 2020.215724 +EDGE_SE2 699 700 0.637453 0.017479 0.051850 11.251293 5.735412 0.000000 245.770774 0.000000 2259.604267 +EDGE_SE2 700 701 0.580454 0.032375 0.057254 11.111784 0.437751 0.000000 295.879739 0.000000 2236.564024 +EDGE_SE2 701 702 0.576635 -0.068380 -0.117543 11.111180 0.139782 0.000000 296.573785 0.000000 2001.757773 +EDGE_SE2 702 703 0.620013 -0.001990 0.031996 11.419637 8.759800 0.000000 259.823358 0.000000 2347.383139 +EDGE_SE2 703 704 0.636789 0.025712 0.015764 11.253257 -5.779092 0.000000 246.065659 0.000000 2423.005361 +EDGE_SE2 704 705 0.643209 0.030107 0.064485 11.183283 4.074239 0.000000 241.110228 0.000000 2206.281466 +EDGE_SE2 705 706 0.514363 -0.039200 -0.277636 25.728836 -71.533878 0.000000 361.172137 0.000000 1531.530774 +EDGE_SE2 706 707 0.003881 -0.001622 -0.533536 106334.972814 -767757.982233 0.000000 5543943.675681 0.000000 1063.046000 +EDGE_SE2 707 708 -0.003691 0.001823 -0.654541 223240.622476 -1125745.646018 0.000000 5677142.471470 0.000000 913.240034 +EDGE_SE2 708 709 -0.067573 0.007248 -0.341732 1183.126036 -4897.853094 0.000000 20479.250565 0.000000 1388.700057 +EDGE_SE2 709 710 -0.014148 0.002189 -0.575257 81786.222098 -182245.919313 0.000000 406168.616806 0.000000 1007.481714 +EDGE_SE2 710 711 0.000644 0.000757 -0.611741 100340028.914478 -9326915.500645 0.000000 866976.800978 0.000000 962.386453 +EDGE_SE2 711 712 -0.004894 0.001455 -0.574644 304805.524713 -1037473.284048 0.000000 3531410.530133 0.000000 1008.266280 +EDGE_SE2 712 713 0.477793 -0.132293 -0.294292 11.342379 -9.563968 0.000000 406.624099 0.000000 1492.366443 +EDGE_SE2 713 714 0.567602 -0.077796 -0.205164 12.504613 -20.177539 0.000000 303.276539 0.000000 1721.264882 +EDGE_SE2 714 715 0.633486 0.028573 0.105231 11.969833 14.257268 0.000000 247.822982 0.000000 2046.604352 +EDGE_SE2 715 716 0.639776 -0.022007 -0.136206 13.517556 -23.552031 0.000000 241.616372 0.000000 1936.537236 +EDGE_SE2 716 717 0.632432 0.018685 0.086524 11.885459 13.573115 0.000000 249.026579 0.000000 2117.685003 +EDGE_SE2 717 718 0.776383 -0.078919 -0.173172 11.900522 -10.964942 0.000000 163.414455 0.000000 1816.421486 +EDGE_SE2 718 719 0.636837 0.028128 0.076417 11.355832 7.579234 0.000000 245.847108 0.000000 2157.639641 +EDGE_SE2 719 720 0.632529 -0.017060 -0.057232 11.329664 -7.218698 0.000000 249.541537 0.000000 2236.657107 +EDGE_SE2 720 721 0.638105 0.018029 0.070335 11.525887 9.849065 0.000000 244.982458 0.000000 2182.230164 +EDGE_SE2 721 722 0.025289 0.000135 0.068811 640.196727 9897.678857 0.000000 155735.617178 0.000000 2188.457812 +EDGE_SE2 722 723 0.006445 0.007867 1.098357 43580.586864 200575.333708 0.000000 923374.631033 0.000000 567.781519 +EDGE_SE2 723 724 0.010463 0.006590 1.077175 158723.565692 280363.009735 0.000000 495267.878673 0.000000 579.420471 +EDGE_SE2 724 725 0.010678 0.005468 0.639413 19006.567647 113303.006550 0.000000 675834.367551 0.000000 930.171994 +EDGE_SE2 725 726 0.290588 0.137540 0.458060 11.355500 15.286330 0.000000 967.259181 0.000000 1175.950976 +EDGE_SE2 726 727 0.635716 0.023142 0.032574 11.114541 -0.899732 0.000000 247.111115 0.000000 2344.755903 +EDGE_SE2 727 728 0.637440 -0.010740 0.003027 11.203891 4.667737 0.000000 245.942991 0.000000 2484.933444 +EDGE_SE2 728 729 0.638658 0.024646 0.059374 11.212224 4.859951 0.000000 244.701967 0.000000 2227.621438 +EDGE_SE2 729 730 0.629725 0.021040 0.039078 11.118875 1.367234 0.000000 251.883563 0.000000 2315.494262 +EDGE_SE2 730 731 0.635128 0.000033 0.013336 11.152896 3.145232 0.000000 247.858605 0.000000 2434.630538 +EDGE_SE2 731 732 0.123756 0.004174 0.448902 1070.432039 2403.087812 0.000000 5462.557297 0.000000 1190.863501 +EDGE_SE2 732 733 0.000083 0.001424 1.000990 11773189.473890 -20977730.743166 0.000000 37378633.397513 0.000000 624.381709 +EDGE_SE2 733 734 0.552572 0.038413 0.079326 11.142093 3.122929 0.000000 325.902343 0.000000 2146.024772 +EDGE_SE2 734 735 0.600091 -0.007820 -0.030980 11.196982 -4.783337 0.000000 277.560623 0.000000 2352.011970 +EDGE_SE2 735 736 0.005111 -0.000077 0.602090 1281626.650843 1806077.209424 0.000000 2545169.768506 0.000000 974.015847 +EDGE_SE2 736 737 0.008677 0.008287 0.804006 1211.768495 28855.042050 0.000000 693475.760746 0.000000 768.181871 +EDGE_SE2 737 738 0.598858 0.011099 0.020076 11.111750 0.413426 0.000000 278.741652 0.000000 2402.563911 +EDGE_SE2 738 739 0.625793 -0.054407 -0.056575 11.331296 7.301220 0.000000 253.215672 0.000000 2239.439570 +EDGE_SE2 739 740 0.522300 0.024647 0.064307 11.215445 6.082008 0.000000 365.653135 0.000000 2207.019506 +EDGE_SE2 740 741 -0.000981 -0.000074 -0.367127 18919361.341981 -39981559.645604 0.000000 84491555.069462 0.000000 1337.587765 +EDGE_SE2 741 742 0.011219 -0.001990 -0.650273 160936.661861 -313150.446277 0.000000 609381.105788 0.000000 917.969856 +EDGE_SE2 742 743 0.004918 -0.001325 -0.614408 456134.364729 -1245052.232453 0.000000 3398555.362562 0.000000 959.208992 +EDGE_SE2 743 744 0.009459 -0.002723 -0.537185 66620.250624 -253582.580605 0.000000 965406.035238 0.000000 1058.005031 +EDGE_SE2 744 745 0.002047 -0.000908 -0.591149 593780.161881 -3389363.396311 0.000000 19347237.473549 0.000000 987.457262 +EDGE_SE2 745 746 0.494445 -0.175533 -0.472825 17.183290 -45.841209 0.000000 357.183969 0.000000 1152.491455 +EDGE_SE2 746 747 0.638469 -0.005433 -0.034207 11.265722 -6.015279 0.000000 245.140841 0.000000 2337.357068 +EDGE_SE2 747 748 0.577733 -0.023010 -0.067174 11.326766 -7.878192 0.000000 298.912675 0.000000 2195.176966 +EDGE_SE2 748 749 0.069701 0.001911 0.431306 3186.109937 7428.826456 0.000000 17392.995499 0.000000 1220.323642 +EDGE_SE2 749 750 0.003545 0.004632 0.930924 530.021459 39050.161440 0.000000 2938698.139852 0.000000 670.516775 +EDGE_SE2 750 751 0.221430 0.155717 0.642978 12.335877 40.697289 0.000000 1363.426091 0.000000 926.139724 +EDGE_SE2 751 752 0.622533 -0.037077 -0.102200 11.559653 -10.494975 0.000000 256.672582 0.000000 2057.875967 +EDGE_SE2 752 753 0.636978 0.006588 0.064190 11.792803 12.647310 0.000000 245.754530 0.000000 2207.504825 +EDGE_SE2 753 754 0.633682 -0.063409 -0.161022 11.994454 -14.394628 0.000000 245.680720 0.000000 1854.637814 +EDGE_SE2 754 755 0.634065 0.020125 0.076284 11.582011 10.562020 0.000000 248.011279 0.000000 2158.172928 +EDGE_SE2 755 756 0.630931 -0.052093 -0.191444 13.935694 -25.795248 0.000000 246.683906 0.000000 1761.135371 +EDGE_SE2 756 757 0.634731 0.023338 0.098895 12.024248 14.675298 0.000000 246.962348 0.000000 2070.272980 +EDGE_SE2 757 758 0.593380 0.045763 0.126480 11.775379 13.406035 0.000000 281.667065 0.000000 1970.121623 +EDGE_SE2 758 759 0.549299 -0.065716 -0.139191 11.238871 -6.348958 0.000000 326.618479 0.000000 1926.401990 +EDGE_SE2 759 760 0.597230 0.041521 0.114150 11.646967 11.969500 0.000000 278.475751 0.000000 2013.968527 +EDGE_SE2 760 761 0.024133 -0.000801 0.183513 7939.377412 36011.249548 0.000000 163579.039427 0.000000 1784.818025 +EDGE_SE2 761 762 0.000826 0.001155 1.009551 175055.866129 2941983.942252 0.000000 49446048.586526 0.000000 619.072925 +EDGE_SE2 762 763 0.580729 0.162376 0.292110 11.211099 5.135900 0.000000 274.918098 0.000000 1497.411049 +EDGE_SE2 763 764 0.445705 -0.005172 -0.027993 11.243315 -8.065663 0.000000 503.190215 0.000000 2365.700131 +EDGE_SE2 764 765 0.008361 0.001719 0.638276 244331.555302 525026.230585 0.000000 1128252.931867 0.000000 931.463562 +EDGE_SE2 765 766 0.005344 0.005700 0.998613 53037.087612 289905.348468 0.000000 1584991.089178 0.000000 625.867778 +EDGE_SE2 766 767 0.002645 0.001415 0.929266 1998232.117440 4267585.657123 0.000000 9114261.878773 0.000000 671.669747 +EDGE_SE2 767 768 0.005861 0.004878 0.721092 1261.041135 46349.790224 0.000000 1718749.770688 0.000000 843.979381 +EDGE_SE2 768 769 0.614146 0.107525 0.156299 11.182444 -4.189539 0.000000 257.172044 0.000000 1869.819603 +EDGE_SE2 769 770 0.636280 -0.020581 -0.067664 11.405109 -8.318026 0.000000 246.451563 0.000000 2193.162494 +EDGE_SE2 770 771 0.070000 0.001891 0.559330 5261.360007 8913.246458 0.000000 15142.958000 0.000000 1028.167661 +EDGE_SE2 771 772 0.006744 0.005112 0.865896 64935.054362 294012.600872 0.000000 1331467.660768 0.000000 718.067286 +EDGE_SE2 772 773 0.581158 0.026914 0.085198 11.541618 11.055471 0.000000 295.017264 0.000000 2122.863350 +EDGE_SE2 773 774 0.551019 0.013319 0.021516 11.113346 -0.843063 0.000000 329.161850 0.000000 2395.795043 +EDGE_SE2 774 775 0.004023 0.000830 0.842994 2110367.484852 2837367.218934 0.000000 3814842.025573 0.000000 736.024077 +EDGE_SE2 775 776 0.192558 0.126940 0.615944 13.158809 61.827681 0.000000 1877.920658 0.000000 957.386713 +EDGE_SE2 776 777 0.634282 0.011394 0.058423 11.499517 9.594027 0.000000 248.093510 0.000000 2231.626302 +EDGE_SE2 777 778 0.632295 0.006026 -0.021506 11.341246 -7.412667 0.000000 249.873975 0.000000 2395.841950 +EDGE_SE2 778 779 0.635747 0.009144 0.017394 11.113255 0.711673 0.000000 247.364613 0.000000 2415.247629 +EDGE_SE2 779 780 0.227263 -0.012780 -0.131130 21.872372 -143.298917 0.000000 1919.305655 0.000000 1953.956841 +EDGE_SE2 780 781 0.009670 -0.001829 -0.575170 148004.400196 -361794.734360 0.000000 884479.796277 0.000000 1007.593008 +EDGE_SE2 781 782 0.270298 -0.114336 -0.431075 12.208626 -35.507762 0.000000 1159.889369 0.000000 1220.717636 +EDGE_SE2 782 783 0.611405 -0.011479 -0.001409 11.188373 4.449352 0.000000 267.339350 0.000000 2492.969862 +EDGE_SE2 783 784 0.240113 0.001039 -0.022196 12.323249 -45.688698 0.000000 1733.239839 0.000000 2392.608572 +EDGE_SE2 784 785 0.007959 -0.002926 -0.554001 55828.680061 -272963.055421 0.000000 1334874.506740 0.000000 1035.230954 +EDGE_SE2 785 786 0.004434 -0.000587 -0.590466 980656.281246 -1985068.949325 0.000000 4018282.809762 0.000000 988.305540 +EDGE_SE2 786 787 -0.002001 0.000044 -0.492560 5130982.209484 -10089392.987608 0.000000 19839501.318078 0.000000 1122.215884 +EDGE_SE2 787 788 0.007208 -0.003016 -0.631388 88847.369552 -370943.890957 0.000000 1548921.124356 0.000000 939.345765 +EDGE_SE2 788 789 0.007538 -0.002876 -0.554007 54527.813069 -284219.801981 0.000000 1481775.284964 0.000000 1035.223369 +EDGE_SE2 789 790 0.500376 -0.029812 -0.068057 11.139386 -3.307267 0.000000 397.957897 0.000000 2191.548808 +EDGE_SE2 790 791 0.628826 0.029153 0.097815 11.750061 12.398882 0.000000 251.712715 0.000000 2074.348338 +EDGE_SE2 791 792 0.315704 0.029420 0.702590 333.591596 461.723980 0.000000 672.202381 0.000000 862.422051 +EDGE_SE2 792 793 0.615391 0.019005 0.041490 11.139594 2.682653 0.000000 263.776793 0.000000 2304.781716 +EDGE_SE2 793 794 0.637735 0.016326 0.067824 11.529260 9.895724 0.000000 245.298956 0.000000 2192.505307 +EDGE_SE2 794 795 -0.033087 -0.024410 0.423241 2638.528642 -12185.315173 0.000000 56523.600693 0.000000 1234.193106 +EDGE_SE2 795 796 -0.015774 0.000648 0.650956 163376.535826 197117.295726 0.000000 237853.533044 0.000000 917.210485 +EDGE_SE2 796 797 0.294705 0.074097 0.255423 11.199896 9.754709 0.000000 1082.852214 0.000000 1586.206944 +EDGE_SE2 797 798 0.626641 0.006060 0.046881 11.448159 9.053531 0.000000 254.300351 0.000000 2281.105507 +EDGE_SE2 798 799 0.635666 0.023992 0.062363 11.254358 5.812774 0.000000 246.986103 0.000000 2215.104071 +EDGE_SE2 799 800 0.634468 0.014510 0.069489 11.626291 11.041861 0.000000 247.771504 0.000000 2185.683957 +EDGE_SE2 800 801 0.637847 0.031241 0.082897 11.380932 7.942930 0.000000 244.933506 0.000000 2131.894492 +EDGE_SE2 801 802 0.632634 0.019958 0.054891 11.241159 5.567715 0.000000 249.480486 0.000000 2246.595241 +EDGE_SE2 802 803 0.630127 -0.088612 -0.168062 11.300661 -6.683601 0.000000 246.777787 0.000000 1832.349094 +EDGE_SE2 803 804 0.635077 0.012853 0.053211 11.368430 7.800535 0.000000 247.581479 0.000000 2253.768144 +EDGE_SE2 804 805 0.636519 0.031282 0.073549 11.251547 5.744442 0.000000 246.083247 0.000000 2169.183365 +EDGE_SE2 805 806 0.606343 0.012170 0.038909 11.203672 4.912129 0.000000 271.793935 0.000000 2316.247649 +EDGE_SE2 806 807 0.189729 0.005119 0.292220 201.113736 699.449492 0.000000 2585.968127 0.000000 1497.155415 +EDGE_SE2 807 808 0.003371 0.007327 0.958098 50103.576561 -272947.437303 0.000000 1487266.786417 0.000000 652.035379 +EDGE_SE2 808 809 0.587431 0.097914 0.147917 11.191667 -4.670314 0.000000 281.877711 0.000000 1897.225851 +EDGE_SE2 809 810 0.627956 -0.080646 -0.136964 11.131446 -2.201546 0.000000 249.460063 0.000000 1933.955965 +EDGE_SE2 810 811 0.612576 0.015533 -0.000815 11.285797 -6.674619 0.000000 266.143624 0.000000 2495.929976 +EDGE_SE2 811 812 0.006046 0.000091 0.739463 1201081.516913 1357305.749329 0.000000 1533875.311129 0.000000 826.246472 +EDGE_SE2 812 813 0.018109 0.013231 0.985482 23964.289238 64716.524103 0.000000 174861.749709 0.000000 634.173515 +EDGE_SE2 813 814 0.002006 0.002998 1.002590 3587.558087 165756.923868 0.000000 7682316.480714 0.000000 623.384389 +EDGE_SE2 814 815 0.020425 0.007022 0.928829 67887.614244 99709.570495 0.000000 146482.982663 0.000000 671.974131 +EDGE_SE2 815 816 0.008370 0.002024 0.688367 256339.335199 529144.216869 0.000000 1092335.622944 0.000000 877.013540 +EDGE_SE2 816 817 0.011362 -0.004578 -0.661788 50470.023799 -176289.897436 0.000000 615920.695413 0.000000 905.292186 +EDGE_SE2 817 818 0.201346 -0.091729 -0.483386 17.453139 -113.332496 0.000000 2036.370991 0.000000 1136.139494 +EDGE_SE2 818 819 0.600994 -0.000021 0.016657 11.185144 4.434946 0.000000 276.785971 0.000000 2418.750645 +EDGE_SE2 819 820 0.604107 -0.012016 -0.038590 11.203011 -4.913481 0.000000 273.813863 0.000000 2317.670726 +EDGE_SE2 820 821 0.557707 0.002574 0.018330 11.169482 4.256080 0.000000 321.439373 0.000000 2410.809711 +EDGE_SE2 821 822 0.002019 0.000160 0.773476 9984938.759006 11985389.451377 0.000000 14386651.191718 0.000000 794.857685 +EDGE_SE2 822 823 0.012515 0.017002 0.933412 12.904840 -634.367588 0.000000 224360.656810 0.000000 668.792184 +EDGE_SE2 823 824 0.631778 0.009322 -0.078655 13.193602 -22.229505 0.000000 248.399474 0.000000 2148.695562 +EDGE_SE2 824 825 0.640608 -0.019581 -0.029178 11.111552 0.320195 0.000000 243.449875 0.000000 2360.255512 +EDGE_SE2 825 826 0.635727 0.086901 0.163404 11.286990 6.382404 0.000000 242.719295 0.000000 1847.051069 +EDGE_SE2 826 827 0.633058 -0.024805 -0.048406 11.131451 -2.200226 0.000000 249.121319 0.000000 2274.474191 +EDGE_SE2 827 828 0.640515 0.016631 0.035640 11.132900 2.250508 0.000000 243.562272 0.000000 2330.893209 +EDGE_SE2 828 829 0.604311 -0.016371 -0.038614 11.146008 -3.026498 0.000000 273.593060 0.000000 2317.563615 +EDGE_SE2 829 830 0.611353 -0.005562 -0.007256 11.111980 0.472139 0.000000 267.533817 0.000000 2464.111086 +EDGE_SE2 830 831 0.582292 -0.023325 -0.045648 11.120035 -1.590099 0.000000 294.448496 0.000000 2286.488316 +EDGE_SE2 831 832 0.567969 0.005415 -0.002512 11.154466 -3.599292 0.000000 309.920273 0.000000 2487.487168 +EDGE_SE2 832 833 0.256920 0.000340 0.139017 39.444586 204.467263 0.000000 1486.640047 0.000000 1926.990602 +EDGE_SE2 833 834 0.004768 0.001527 1.059143 1850884.389821 1989766.154557 0.000000 2139092.913935 0.000000 589.612746 +EDGE_SE2 834 835 0.011746 0.005469 0.781010 68236.467078 189689.298378 0.000000 527410.776663 0.000000 788.147120 +EDGE_SE2 835 836 0.015546 0.007972 0.947065 68058.939717 132897.198385 0.000000 259558.927707 0.000000 659.445803 +EDGE_SE2 836 837 0.017648 0.011594 1.040763 44125.577264 89148.384604 0.000000 180165.948528 0.000000 600.281370 +EDGE_SE2 837 838 0.013822 0.005479 0.865867 99632.035075 187458.017071 0.000000 352753.354065 0.000000 718.089607 +EDGE_SE2 838 839 0.001331 -0.000521 -0.216716 1187297.905481 7527754.381697 0.000000 47728231.706064 0.000000 1688.735256 +EDGE_SE2 839 840 0.014201 -0.005576 -0.560094 14691.670684 -78049.547320 0.000000 414963.402725 0.000000 1027.160891 +EDGE_SE2 840 841 0.018508 -0.004844 -0.614349 33618.056740 -89734.585298 0.000000 239613.242398 0.000000 959.279471 +EDGE_SE2 841 842 0.244308 -0.051175 -0.229250 11.937138 -36.275589 0.000000 1604.181092 0.000000 1654.472583 +EDGE_SE2 842 843 0.571578 -0.004308 -0.001490 11.121898 1.783710 0.000000 306.061619 0.000000 2492.566618 +EDGE_SE2 843 844 0.632633 0.008356 -0.006975 11.208334 -4.816449 0.000000 249.718690 0.000000 2465.486516 +EDGE_SE2 844 845 0.634632 -0.005065 -0.013668 11.118782 -1.348758 0.000000 248.265069 0.000000 2433.036002 +EDGE_SE2 845 846 0.637586 0.012768 0.002757 11.181094 -4.052879 0.000000 245.824022 0.000000 2486.271799 +EDGE_SE2 846 847 0.633522 -0.013243 -0.025675 11.116535 -1.135991 0.000000 249.044882 0.000000 2376.405061 +EDGE_SE2 847 848 0.158686 0.003991 0.484189 788.091041 1572.022678 0.000000 3191.702019 0.000000 1134.910441 +EDGE_SE2 848 849 0.002564 0.003351 0.928473 680.469413 61313.177701 0.000000 5616294.276467 0.000000 672.222250 +EDGE_SE2 849 850 0.350597 0.124336 0.356364 11.283371 11.069863 0.000000 722.488046 0.000000 1358.900004 +EDGE_SE2 850 851 0.642798 -0.027661 -0.090713 11.635228 -10.977882 0.000000 241.048137 0.000000 2101.449848 +EDGE_SE2 851 852 0.640836 -0.004293 0.015855 11.229301 5.239393 0.000000 243.375111 0.000000 2422.571276 +EDGE_SE2 852 853 0.610781 0.003140 -0.026553 11.369134 -8.138170 0.000000 267.793422 0.000000 2372.341770 +EDGE_SE2 853 854 0.603861 -0.006364 0.003213 11.160858 3.617435 0.000000 274.156807 0.000000 2484.012095 +EDGE_SE2 854 855 0.610860 0.010420 -0.000693 11.192009 -4.557204 0.000000 267.830171 0.000000 2496.538599 +EDGE_SE2 855 856 0.637641 -0.018640 -0.037084 11.125605 -1.844014 0.000000 245.725607 0.000000 2324.406817 +EDGE_SE2 856 857 0.637311 0.003614 -0.006131 11.143851 -2.774089 0.000000 246.164229 0.000000 2469.624632 +EDGE_SE2 857 858 0.636231 -0.022329 -0.050745 11.168921 -3.690286 0.000000 246.680327 0.000000 2264.359323 +EDGE_SE2 858 859 0.507785 0.004334 -0.003406 11.164814 -4.497374 0.000000 387.747642 0.000000 2483.056613 +EDGE_SE2 859 860 0.002497 0.001745 0.863794 679539.881456 2619251.092498 0.000000 10095943.152469 0.000000 719.687882 +EDGE_SE2 860 861 0.070325 0.071481 0.928711 191.497025 1326.435969 0.000000 9764.823807 0.000000 672.056358 +EDGE_SE2 861 862 0.652508 -0.024736 -0.055891 11.183497 -4.020862 0.000000 234.461196 0.000000 2242.341901 +EDGE_SE2 862 863 0.638309 -0.005836 -0.029014 11.203612 -4.654534 0.000000 245.322644 0.000000 2361.007908 +EDGE_SE2 863 864 0.606532 -0.017964 0.001104 11.356731 7.994878 0.000000 271.342913 0.000000 2494.489128 +EDGE_SE2 864 865 0.604147 0.028266 0.061183 11.165720 3.784052 0.000000 273.324162 0.000000 2220.033054 +EDGE_SE2 865 866 0.579332 -0.011435 0.001982 11.246334 6.225212 0.000000 297.699601 0.000000 2490.119385 +EDGE_SE2 866 867 0.156548 0.001719 0.185575 133.883281 696.034953 0.000000 3957.157327 0.000000 1778.614047 +EDGE_SE2 867 868 0.017881 0.010690 1.037717 52749.955417 96798.086518 0.000000 177676.543047 0.000000 602.077325 +EDGE_SE2 868 869 0.012235 0.005926 0.991656 143324.570378 238746.643887 0.000000 397740.398080 0.000000 630.247818 +EDGE_SE2 869 870 0.002231 -0.000124 1.013097 15395648.131442 8450866.436031 0.000000 4638802.180641 0.000000 616.894084 +EDGE_SE2 870 871 0.001088 0.001679 0.986895 2024.695825 -224276.785530 0.000000 24980373.832027 0.000000 633.271838 +EDGE_SE2 871 872 0.008015 -0.000084 0.694560 653702.249121 768245.705891 0.000000 902886.231030 0.000000 870.614924 +EDGE_SE2 872 873 0.008522 -0.003526 -0.564717 34612.893765 -198701.425503 0.000000 1141058.001437 0.000000 1021.100307 +EDGE_SE2 873 874 0.015858 -0.003778 -0.551904 36802.135033 -111762.498404 0.000000 339519.358447 0.000000 1038.030952 +EDGE_SE2 874 875 0.013521 -0.001487 -0.578534 110429.389804 -217905.190004 0.000000 430036.577843 0.000000 1003.303038 +EDGE_SE2 875 876 0.574406 -0.080596 -0.153354 11.166806 -3.991544 0.000000 297.175644 0.000000 1879.380673 +EDGE_SE2 876 877 0.574770 -0.024813 -0.080909 11.525988 -10.980326 0.000000 301.721640 0.000000 2139.743633 +EDGE_SE2 877 878 0.217632 0.014817 0.389316 219.643265 626.455159 0.000000 1893.056212 0.000000 1295.203276 +EDGE_SE2 878 879 0.647020 0.057742 0.054681 11.377140 -7.747124 0.000000 236.717936 0.000000 2247.489979 +EDGE_SE2 879 880 0.455025 -0.018050 -0.108582 13.346224 -32.372663 0.000000 479.986413 0.000000 2034.250181 +EDGE_SE2 880 881 -0.043409 -0.000133 0.008718 12.813581 300.540520 0.000000 53066.151297 0.000000 2456.973472 +EDGE_SE2 881 882 0.647486 -0.064933 -0.241227 15.572920 -31.371721 0.000000 231.690918 0.000000 1622.697550 +EDGE_SE2 882 883 0.642883 -0.072854 -0.185824 12.322147 -16.564386 0.000000 237.676574 0.000000 1777.868098 +EDGE_SE2 883 884 0.383517 -0.007350 -0.063028 12.396618 -29.287057 0.000000 678.343333 0.000000 2212.333526 +EDGE_SE2 884 885 0.004929 0.003007 0.590777 5527.682570 128525.333864 0.000000 2994400.210829 0.000000 987.919146 +EDGE_SE2 885 886 0.007741 0.006994 1.034072 79878.863906 258839.772996 0.000000 838873.176713 0.000000 604.237070 +EDGE_SE2 886 887 0.010004 0.001000 1.027322 633501.134354 474724.505488 0.000000 355759.975090 0.000000 608.267401 +EDGE_SE2 887 888 0.005011 0.003332 0.999568 444415.889744 1014710.716533 0.000000 2316903.025310 0.000000 625.269895 +EDGE_SE2 888 889 0.005294 0.002083 0.911927 808634.909964 1357982.238784 0.000000 2280571.939853 0.000000 683.907547 +EDGE_SE2 889 890 0.355203 0.095914 0.279682 11.296105 11.600417 0.000000 738.538555 0.000000 1526.637360 +EDGE_SE2 890 891 0.616728 -0.012401 -0.066427 11.650788 -11.642307 0.000000 262.267312 0.000000 2198.253354 +EDGE_SE2 891 892 0.637263 -0.017865 -0.031981 11.114783 -0.928852 0.000000 246.045454 0.000000 2347.451378 +EDGE_SE2 892 893 0.642710 0.035710 0.241471 18.981950 41.834853 0.000000 233.470505 0.000000 1622.059760 +EDGE_SE2 893 894 0.638528 0.083732 0.226070 13.210427 21.873674 0.000000 239.022296 0.000000 1663.065968 +EDGE_SE2 894 895 0.615722 0.105457 0.303953 15.507767 32.534377 0.000000 251.859007 0.000000 1470.334450 +EDGE_SE2 895 896 0.020155 0.000491 0.481484 47934.902135 97432.832108 0.000000 198099.713240 0.000000 1139.058627 +EDGE_SE2 896 897 0.528670 0.158235 0.274351 11.197167 -5.224460 0.000000 328.288174 0.000000 1539.436858 +EDGE_SE2 897 898 0.618615 0.002949 0.017900 11.154262 3.285463 0.000000 261.262932 0.000000 2412.846978 +EDGE_SE2 898 899 0.499807 -0.008373 -0.065092 12.019606 -18.779145 0.000000 399.287489 0.000000 2203.767446 +EDGE_SE2 899 900 0.683722 0.007464 -0.000025 11.135386 -2.218523 0.000000 213.865098 0.000000 2499.875005 +EDGE_SE2 900 901 0.579956 -0.019520 -0.061673 11.335628 -8.008145 0.000000 296.748861 0.000000 2217.984277 +EDGE_SE2 901 902 0.644996 0.015819 0.027799 11.113573 0.751022 0.000000 240.226171 0.000000 2366.593280 +EDGE_SE2 902 903 0.494510 0.003386 -0.042100 12.063405 -19.440085 0.000000 407.959954 0.000000 2302.084267 +EDGE_SE2 903 904 0.005815 0.000708 0.715026 912712.732392 1351574.977076 0.000000 2001492.072759 0.000000 849.960204 +EDGE_SE2 904 905 0.554057 0.035513 0.058326 11.121228 -1.780350 0.000000 324.412517 0.000000 2232.035396 +EDGE_SE2 905 906 0.630376 0.024475 0.068969 11.329543 7.239573 0.000000 251.055279 0.000000 2187.810926 +EDGE_SE2 906 907 0.631021 0.007133 -0.005018 11.175042 -3.916492 0.000000 251.041590 0.000000 2475.097597 +EDGE_SE2 907 908 0.637636 0.001891 0.024788 11.222935 5.123325 0.000000 245.840507 0.000000 2380.520611 +EDGE_SE2 908 909 0.628314 0.001550 -0.017825 11.210816 -4.913046 0.000000 253.205497 0.000000 2413.202580 +EDGE_SE2 909 910 0.147710 -0.043678 -0.369688 39.436166 -343.900479 0.000000 4186.479576 0.000000 1332.590482 +EDGE_SE2 910 911 0.616085 0.011620 0.061065 11.560202 10.634138 0.000000 262.919471 0.000000 2220.526856 +EDGE_SE2 911 912 0.605554 0.006436 0.010902 11.111131 0.071773 0.000000 272.675019 0.000000 2446.368619 +EDGE_SE2 912 913 0.580860 0.003431 0.006628 11.111259 0.205638 0.000000 296.374652 0.000000 2467.186590 +EDGE_SE2 913 914 0.630196 -0.006309 -0.024572 11.162137 -3.503890 0.000000 251.720029 0.000000 2381.524439 +EDGE_SE2 914 915 0.556525 -0.006690 -0.037260 11.309630 -7.863953 0.000000 322.627351 0.000000 2323.618084 +EDGE_SE2 915 916 0.178865 0.104304 0.546671 11.926058 43.487541 0.000000 2331.711773 0.000000 1045.066974 +EDGE_SE2 916 917 0.624756 -0.045966 -0.254265 18.993145 -43.113795 0.000000 246.938496 0.000000 1589.137227 +EDGE_SE2 917 918 0.518933 -0.035276 -0.074995 11.129291 -2.552939 0.000000 369.618783 0.000000 2163.351655 +EDGE_SE2 918 919 0.629099 -0.005797 -0.042335 11.375987 -7.994276 0.000000 252.388154 0.000000 2301.046350 +EDGE_SE2 919 920 0.629899 -0.010656 -0.016202 11.111234 0.171926 0.000000 251.961442 0.000000 2420.917100 +EDGE_SE2 920 921 0.634457 -0.008549 -0.051374 11.451756 -8.983787 0.000000 248.039729 0.000000 2261.650760 +EDGE_SE2 921 922 0.635258 -0.006313 -0.024873 11.163905 -3.534345 0.000000 247.721599 0.000000 2380.125761 +EDGE_SE2 922 923 0.608430 -0.014168 -0.060475 11.469047 -9.619410 0.000000 269.629762 0.000000 2222.998344 +EDGE_SE2 923 924 0.530888 -0.000682 0.019383 11.257903 7.101435 0.000000 354.661710 0.000000 2405.831657 +EDGE_SE2 924 925 0.009664 0.004698 0.510887 2959.553169 50448.307002 0.000000 863189.572650 0.000000 1095.156133 +EDGE_SE2 925 926 0.598427 0.009230 0.018979 11.114501 0.953220 0.000000 279.170216 0.000000 2407.739741 +EDGE_SE2 926 927 0.627907 -0.001812 -0.020475 11.186132 -4.264817 0.000000 253.558182 0.000000 2400.685500 +EDGE_SE2 927 928 0.640773 -0.000139 -0.006135 11.119254 -1.375744 0.000000 243.544155 0.000000 2469.604995 +EDGE_SE2 928 929 0.636560 -0.000176 0.001919 11.112246 0.517244 0.000000 246.784978 0.000000 2490.432549 +EDGE_SE2 929 930 0.640386 -0.014253 -0.078843 11.855260 -13.135681 0.000000 242.981611 0.000000 2147.946760 +EDGE_SE2 930 931 0.635431 -0.020570 -0.076099 11.562880 -10.322123 0.000000 246.953500 0.000000 2158.915046 +EDGE_SE2 931 932 0.639769 -0.010067 -0.055067 11.471607 -9.160668 0.000000 243.895776 0.000000 2245.845776 +EDGE_SE2 932 933 0.631644 -0.015304 -0.059766 11.413371 -8.500896 0.000000 250.193846 0.000000 2225.973780 +EDGE_SE2 933 934 0.504140 0.003029 -0.005219 11.159305 -4.292306 0.000000 393.395672 0.000000 2474.107872 +EDGE_SE2 934 935 0.005622 0.001555 0.696880 504282.663987 1107982.483573 0.000000 2434463.693063 0.000000 868.235915 +EDGE_SE2 935 936 0.001863 0.001286 0.945362 2184651.299423 6152115.682451 0.000000 17324844.542602 0.000000 660.600886 +EDGE_SE2 936 937 0.551720 0.024485 0.062876 11.219817 5.867053 0.000000 327.765518 0.000000 2212.966335 +EDGE_SE2 937 938 0.601673 -0.055314 -0.173492 12.866388 -21.406117 0.000000 272.165004 0.000000 1815.430979 +EDGE_SE2 938 939 0.633059 0.008315 0.027580 11.160855 3.443094 0.000000 249.431085 0.000000 2367.602135 +EDGE_SE2 939 940 0.636273 -0.027491 -0.082722 11.479060 -9.300191 0.000000 246.180789 0.000000 2132.583702 +EDGE_SE2 940 941 0.635944 -0.015109 -0.050698 11.282417 -6.356188 0.000000 246.953620 0.000000 2264.561906 +EDGE_SE2 941 942 0.551791 -0.000493 0.007207 11.131937 2.570602 0.000000 328.415327 0.000000 2464.350846 +EDGE_SE2 942 943 0.644097 -0.001397 0.091523 13.123577 21.416835 0.000000 239.030853 0.000000 2098.332107 +EDGE_SE2 943 944 0.639009 -0.005732 -0.053678 11.578073 -10.437551 0.000000 244.411524 0.000000 2251.770804 +EDGE_SE2 944 945 0.635846 -0.012134 -0.052894 11.381001 -7.978646 0.000000 246.980906 0.000000 2255.125454 +EDGE_SE2 945 946 0.179699 -0.002044 0.066572 29.818272 239.512661 0.000000 3077.654110 0.000000 2197.655692 +EDGE_SE2 946 947 0.406915 0.138311 0.331627 11.119495 2.108463 0.000000 541.380410 0.000000 1409.856218 +EDGE_SE2 947 948 0.579846 -0.001426 -0.021963 11.220001 -5.582502 0.000000 297.312605 0.000000 2393.699690 +EDGE_SE2 948 949 0.604761 -0.049058 -0.159219 12.704160 -20.309811 0.000000 270.041237 0.000000 1860.411550 +EDGE_SE2 949 950 0.636468 -0.025408 -0.243519 20.734999 -46.608998 0.000000 236.840951 0.000000 1616.721292 +EDGE_SE2 950 951 0.637412 -0.014316 -0.075046 11.760145 -12.330103 0.000000 245.353687 0.000000 2163.146402 +EDGE_SE2 951 952 0.637647 0.028692 0.246962 20.543292 46.058094 0.000000 236.016458 0.000000 1607.805725 +EDGE_SE2 952 953 0.635715 0.017895 0.077527 11.686555 11.642681 0.000000 246.671765 0.000000 2153.196604 +EDGE_SE2 953 954 0.632201 -0.012369 -0.013007 11.121379 1.566520 0.000000 250.095671 0.000000 2436.212212 +EDGE_SE2 954 955 0.636040 -0.066402 -0.167279 12.043873 -14.725801 0.000000 243.592003 0.000000 1834.808164 +EDGE_SE2 955 956 0.633169 -0.005303 -0.005934 11.112531 0.581642 0.000000 249.417984 0.000000 2470.592019 +EDGE_SE2 956 957 0.635780 -0.029022 -0.090789 11.591896 -10.635874 0.000000 246.396892 0.000000 2101.157024 +EDGE_SE2 957 958 0.610078 -0.010922 -0.028564 11.140389 -2.745454 0.000000 268.560860 0.000000 2363.074257 +EDGE_SE2 958 959 0.604449 -0.016600 -0.068060 11.543478 -10.642379 0.000000 273.065197 0.000000 2191.536497 +EDGE_SE2 959 960 0.605875 0.054020 0.088370 11.111191 -0.143784 0.000000 270.268197 0.000000 2110.507423 +EDGE_SE2 960 961 0.602054 -0.007561 -0.020089 11.126126 -1.993676 0.000000 275.827437 0.000000 2402.502675 +EDGE_SE2 961 962 0.630743 0.063738 0.073005 11.293528 -6.582439 0.000000 248.635890 0.000000 2171.383420 +EDGE_SE2 962 963 0.629692 0.069822 0.195655 12.835701 20.187165 0.000000 247.411650 0.000000 1748.752064 +EDGE_SE2 963 964 0.639791 -0.008273 -0.057447 11.572861 -10.365475 0.000000 243.797913 0.000000 2235.747685 +EDGE_SE2 964 965 0.633282 -0.006211 -0.001478 11.127639 1.984141 0.000000 249.307749 0.000000 2492.626351 +EDGE_SE2 965 966 0.413197 -0.005006 -0.057147 12.275386 -25.836778 0.000000 584.463061 0.000000 2237.016798 +EDGE_SE2 966 967 0.007510 0.002997 0.859092 325478.163261 626027.365559 0.000000 1204158.381440 0.000000 723.332943 +EDGE_SE2 967 968 0.006374 0.000527 0.902649 1307259.212480 1219284.216016 0.000000 1137250.475138 0.000000 690.593544 +EDGE_SE2 968 969 0.000997 0.000085 0.061289 54733.539945 -2337658.966155 0.000000 99861248.240381 0.000000 2219.589608 +EDGE_SE2 969 970 0.000000 0.000000 -0.000113 11.111116 -0.043944 0.000000 399.999995 0.000000 2499.435096 +EDGE_SE2 970 971 0.361971 0.001286 0.001712 11.113656 -1.383525 0.000000 763.211229 0.000000 2491.461932 +EDGE_SE2 971 972 0.616031 0.005441 0.007131 11.111841 -0.429263 0.000000 263.487396 0.000000 2464.722790 +EDGE_SE2 972 973 0.597393 -0.119850 -0.282715 12.960368 -21.775201 0.000000 267.516438 0.000000 1519.426379 +EDGE_SE2 973 974 0.636084 -0.002771 0.033166 11.443293 8.848623 0.000000 246.819403 0.000000 2342.069601 +EDGE_SE2 974 975 0.636019 0.005980 0.005775 11.114215 -0.856039 0.000000 247.181135 0.000000 2471.373217 +EDGE_SE2 975 976 0.637784 0.010421 0.013983 11.112413 -0.552665 0.000000 245.773095 0.000000 2431.524562 +EDGE_SE2 976 977 0.637920 -0.011711 -0.026304 11.125929 -1.864213 0.000000 245.637352 0.000000 2373.493056 +EDGE_SE2 977 978 0.636711 0.018679 0.044825 11.167625 3.646515 0.000000 246.400847 0.000000 2290.091830 +EDGE_SE2 978 979 0.635616 -0.004880 -0.014420 11.121860 -1.593981 0.000000 247.494628 0.000000 2429.430070 +EDGE_SE2 979 980 0.640402 0.020748 0.043464 11.139636 2.574932 0.000000 243.549790 0.000000 2296.069703 +EDGE_SE2 980 981 0.634599 -0.001102 0.002602 11.115574 1.028911 0.000000 248.309152 0.000000 2487.040602 +EDGE_SE2 981 982 0.582350 0.019314 0.039136 11.121253 1.695467 0.000000 294.536681 0.000000 2315.235788 +EDGE_SE2 982 983 0.606004 -0.005123 -0.005706 11.113084 0.717739 0.000000 272.279670 0.000000 2471.712344 +EDGE_SE2 983 984 0.606209 0.019467 0.054452 11.241333 5.825396 0.000000 271.705807 0.000000 2248.466280 +EDGE_SE2 984 985 0.610191 0.001384 0.017236 11.168792 3.853233 0.000000 268.517439 0.000000 2415.997974 +EDGE_SE2 985 986 0.638807 0.015817 0.032823 11.126330 1.886242 0.000000 244.888150 0.000000 2343.625460 +EDGE_SE2 986 987 0.637113 -0.009662 -0.040633 11.263641 -5.987507 0.000000 246.149046 0.000000 2308.579426 +EDGE_SE2 987 988 0.633843 -0.002158 0.009656 11.151672 3.105391 0.000000 248.863041 0.000000 2452.410392 +EDGE_SE2 988 989 0.637783 0.006714 0.004244 11.120373 -1.474376 0.000000 245.804243 0.000000 2478.914326 +EDGE_SE2 989 990 0.633086 -0.006222 -0.014570 11.116473 -1.130568 0.000000 249.472636 0.000000 2428.711760 +EDGE_SE2 990 991 0.638433 0.009419 0.020655 11.119271 1.382293 0.000000 245.278829 0.000000 2399.838818 +EDGE_SE2 991 992 0.608534 -0.016202 -0.037230 11.140243 -2.745311 0.000000 269.821049 0.000000 2323.752499 +EDGE_SE2 992 993 0.639975 0.012788 0.027838 11.125497 1.830546 0.000000 244.047684 0.000000 2366.413689 +EDGE_SE2 993 994 0.610172 -0.004541 -0.015063 11.126066 -1.962186 0.000000 268.563253 0.000000 2426.353160 +EDGE_SE2 994 995 0.582700 0.014385 0.047816 11.262674 6.550087 0.000000 294.185844 0.000000 2277.036316 +EDGE_SE2 995 996 0.603243 0.013060 0.027432 11.119936 1.525036 0.000000 274.662056 0.000000 2368.284283 +EDGE_SE2 996 997 0.638105 -0.021586 -0.064337 11.329213 -7.143676 0.000000 245.093679 0.000000 2206.895091 +EDGE_SE2 997 998 0.393437 0.003178 0.021791 11.230485 8.704766 0.000000 645.865055 0.000000 2394.505630 +EDGE_SE2 998 999 0.009526 0.010297 0.717647 5765.419520 -53770.217970 0.000000 502458.344534 0.000000 847.368232 +EDGE_SE2 999 1000 0.631982 0.082779 0.148351 11.188179 4.255373 0.000000 246.074510 0.000000 1895.792072 +EDGE_SE2 1000 1001 0.637485 -0.061202 -0.321633 22.788129 -50.803890 0.000000 232.146590 0.000000 1431.259099 +EDGE_SE2 1001 1002 0.630663 0.034533 0.091989 11.444015 8.924103 0.000000 250.338290 0.000000 2096.541587 +EDGE_SE2 1002 1003 0.637376 -0.055899 -0.180665 13.130018 -21.602372 0.000000 242.257264 0.000000 1793.439086 +EDGE_SE2 1003 1004 0.634119 0.020824 0.062770 11.323812 7.101476 0.000000 248.209237 0.000000 2213.407797 +EDGE_SE2 1004 1005 0.602568 0.019724 0.067274 11.426188 9.115028 0.000000 274.805024 0.000000 2194.765624 +EDGE_SE2 1005 1006 0.609599 0.024909 0.082661 11.561301 10.758208 0.000000 268.200258 0.000000 2132.824020 +EDGE_SE2 1006 1007 0.575806 0.024121 0.097394 12.004289 16.068550 0.000000 300.189527 0.000000 2075.940233 +EDGE_SE2 1007 1008 0.296743 0.004461 0.166242 36.620925 167.418708 0.000000 1109.865632 0.000000 1838.072567 +EDGE_SE2 1008 1009 0.169516 0.079531 0.456955 12.060231 51.919506 0.000000 2851.251647 0.000000 1177.735408 +EDGE_SE2 1009 1010 0.635352 0.000090 0.046389 11.616830 10.927244 0.000000 247.219830 0.000000 2283.251111 +EDGE_SE2 1010 1011 0.629760 -0.000818 -0.047667 11.628961 -11.160233 0.000000 251.626406 0.000000 2277.684046 +EDGE_SE2 1011 1012 0.630488 0.001328 0.037830 11.417845 8.582558 0.000000 251.254815 0.000000 2321.066416 +EDGE_SE2 1012 1013 0.638821 0.043192 0.110754 11.546239 10.055629 0.000000 243.492562 0.000000 2026.302298 +EDGE_SE2 1013 1014 0.624005 -0.081360 -0.179557 11.711863 -12.027816 0.000000 251.923335 0.000000 1796.809951 +EDGE_SE2 1014 1015 0.637514 0.038828 0.081332 11.209468 4.796725 0.000000 245.041047 0.000000 2138.069893 +EDGE_SE2 1015 1016 0.781423 -0.009024 0.004462 11.150231 2.443265 0.000000 163.706442 0.000000 2477.838437 +EDGE_SE2 1016 1017 0.603503 0.011706 -0.057436 12.662554 -20.153468 0.000000 272.907609 0.000000 2235.794200 +EDGE_SE2 1017 1018 0.577934 -0.006330 0.007000 11.203996 5.173502 0.000000 299.265589 0.000000 2465.364100 +EDGE_SE2 1018 1019 0.612439 0.031252 0.059177 11.128209 2.087199 0.000000 265.898770 0.000000 2228.450161 +EDGE_SE2 1019 1020 0.633556 -0.016343 -0.014332 11.142340 2.725270 0.000000 248.935660 0.000000 2429.851626 +EDGE_SE2 1020 1021 0.639472 -0.000168 -0.041050 11.499240 -9.510600 0.000000 244.155855 0.000000 2306.730360 +EDGE_SE2 1021 1022 0.070832 0.000271 -0.007651 13.732233 -228.486723 0.000000 19928.608606 0.000000 2462.179597 +EDGE_SE2 1022 1023 0.011155 0.000820 0.086100 139.654009 10135.503712 0.000000 799187.396127 0.000000 2119.338762 +EDGE_SE2 1023 1024 0.645203 -0.002963 0.025849 11.323339 6.969723 0.000000 240.001559 0.000000 2375.598978 +EDGE_SE2 1024 1025 0.648616 0.019366 0.017058 11.148143 -2.895107 0.000000 237.448652 0.000000 2416.843718 +EDGE_SE2 1025 1026 0.180366 -0.000503 0.006661 11.384697 28.945754 0.000000 3073.606781 0.000000 2467.024836 +EDGE_SE2 1026 1027 0.004554 0.001979 0.914665 948112.591095 1716536.548028 0.000000 3107798.392242 0.000000 681.952949 +EDGE_SE2 1027 1028 0.157112 0.092209 0.562259 14.094418 94.590688 0.000000 3010.265300 0.000000 1024.315957 +EDGE_SE2 1028 1029 0.581697 -0.003158 -0.022026 11.189449 -4.719569 0.000000 295.446261 0.000000 2393.404593 +EDGE_SE2 1029 1030 0.602428 -0.021526 -0.077659 11.575380 -11.062953 0.000000 274.727843 0.000000 2152.669156 +EDGE_SE2 1030 1031 0.635032 -0.016817 -0.051435 11.258521 -5.904986 0.000000 247.654252 0.000000 2261.388344 +EDGE_SE2 1031 1032 0.639363 0.000529 0.006615 11.118933 1.351453 0.000000 244.619567 0.000000 2467.250316 +EDGE_SE2 1032 1033 0.641217 -0.014716 -0.042294 11.197935 -4.487022 0.000000 242.999818 0.000000 2301.227383 +EDGE_SE2 1033 1034 0.158807 -0.001999 -0.209870 162.997809 -759.872169 0.000000 3812.666625 0.000000 1707.900606 +EDGE_SE2 1034 1035 0.008238 -0.003621 -0.612225 47839.602807 -238285.590348 0.000000 1187170.073357 0.000000 961.808711 +EDGE_SE2 1035 1036 -0.001359 0.001797 -0.564077 2434530.032209 6484761.501388 0.000000 17273293.058299 0.000000 1021.936120 +EDGE_SE2 1036 1037 0.377894 -0.111886 -0.234247 12.927670 33.853486 0.000000 642.006396 0.000000 1641.103033 +EDGE_SE2 1037 1038 0.646416 0.075596 0.094513 11.219032 -4.926286 0.000000 235.981250 0.000000 2086.883283 +EDGE_SE2 1038 1039 0.688482 -0.025514 -0.028564 11.125452 1.691699 0.000000 210.663547 0.000000 2363.074257 +EDGE_SE2 1039 1040 -0.001379 -0.000331 0.637825 7632266.679736 17921038.113983 0.000000 42079787.422993 0.000000 931.976618 +EDGE_SE2 1040 1041 -0.001323 0.000722 1.029242 43947061.658526 1853405.592364 0.000000 78175.908225 0.000000 607.116902 +EDGE_SE2 1041 1042 0.008412 0.001092 0.999819 812869.525001 684736.258072 0.000000 576819.734984 0.000000 625.113140 +EDGE_SE2 1042 1043 0.010022 0.000228 0.981327 666387.833541 467987.047537 0.000000 328671.866042 0.000000 636.836128 +EDGE_SE2 1043 1044 -0.013611 -0.010605 1.005709 38168.445431 106580.996550 0.000000 297712.956067 0.000000 621.446905 +EDGE_SE2 1044 1045 -0.002205 0.000124 -0.113838 68490.084727 -1183057.512679 0.000000 20438767.774721 0.000000 2015.095849 +EDGE_SE2 1045 1046 -0.013495 0.002112 -0.385242 27867.951272 -118972.940165 0.000000 508129.060237 0.000000 1302.832870 +EDGE_SE2 1046 1047 -0.019733 0.005898 -0.555401 16179.611132 -59582.091055 0.000000 219575.422578 0.000000 1033.368600 +EDGE_SE2 1047 1048 0.344577 -0.119470 -0.312747 11.437653 15.549100 0.000000 751.519224 0.000000 1450.701098 +EDGE_SE2 1048 1049 0.648714 0.010953 0.017287 11.111148 0.091735 0.000000 237.558159 0.000000 2415.755736 +EDGE_SE2 1049 1050 0.646643 0.027376 0.075802 11.366332 7.617483 0.000000 238.466970 0.000000 2160.107247 +EDGE_SE2 1050 1051 0.640459 -0.024485 -0.073431 11.399152 -8.175325 0.000000 243.147148 0.000000 2169.660298 +EDGE_SE2 1051 1052 0.610691 0.014345 0.058571 11.427186 9.005158 0.000000 267.673485 0.000000 2231.002333 +EDGE_SE2 1052 1053 0.402418 -0.011887 -0.047093 11.297991 -10.639018 0.000000 616.787282 0.000000 2280.181912 +EDGE_SE2 1053 1054 0.003611 0.000205 0.781659 3360883.673888 3794299.768961 0.000000 4283634.029810 0.000000 787.573032 +EDGE_SE2 1054 1055 -0.004781 -0.004680 1.092196 217607.587361 662404.612456 0.000000 2016495.376692 0.000000 571.130228 +EDGE_SE2 1055 1056 -0.018363 -0.010043 1.033833 59014.075212 99936.588877 0.000000 169279.247866 0.000000 604.379088 +EDGE_SE2 1056 1057 -0.018154 -0.006925 1.003259 94181.986455 126785.732418 0.000000 170707.431880 0.000000 622.968093 +EDGE_SE2 1057 1058 0.000938 0.000345 0.933655 30225249.079874 45961533.817447 0.000000 69890696.274135 0.000000 668.624102 +EDGE_SE2 1058 1059 0.584768 -0.021106 -0.077373 11.589927 -11.588453 0.000000 291.578229 0.000000 2153.812205 +EDGE_SE2 1059 1060 0.639269 -0.001644 0.007968 11.137057 2.461692 0.000000 244.671355 0.000000 2460.631159 +EDGE_SE2 1060 1061 0.453408 -0.013544 -0.118843 14.861134 -42.033048 0.000000 482.248782 0.000000 1997.108732 +EDGE_SE2 1061 1062 0.018407 -0.004707 -0.560522 25818.783584 -80519.505627 0.000000 251230.619305 0.000000 1026.597536 +EDGE_SE2 1062 1063 -0.002214 0.000350 -0.593849 3568021.016682 -7633088.462779 0.000000 16329573.254319 0.000000 984.114566 +EDGE_SE2 1063 1064 0.301240 -0.082154 -0.262828 11.122946 3.465125 0.000000 1025.683739 0.000000 1567.659011 +EDGE_SE2 1064 1065 0.616850 0.043972 0.123884 11.806351 13.175109 0.000000 260.785525 0.000000 1979.233494 +EDGE_SE2 1065 1066 0.592225 -0.017770 -0.054423 11.274422 -6.684300 0.000000 284.699249 0.000000 2248.589962 +EDGE_SE2 1066 1067 0.012072 0.002120 0.435817 44661.394679 166520.359722 0.000000 621038.078606 0.000000 1212.667746 +EDGE_SE2 1067 1068 0.005144 0.001599 0.677089 463864.684926 1176104.562755 0.000000 2982033.931716 0.000000 888.848590 +EDGE_SE2 1068 1069 0.004939 0.001172 0.172450 14196.268745 -234184.920951 0.000000 3866205.524763 0.000000 1818.659296 +EDGE_SE2 1069 1070 0.007958 -0.000773 -0.535379 282034.324000 -601390.067166 0.000000 1282423.325271 0.000000 1060.495466 +EDGE_SE2 1070 1071 0.555140 -0.067868 -0.125252 11.115112 -1.111199 0.000000 319.703282 0.000000 1974.424001 +EDGE_SE2 1071 1072 0.529254 -0.007703 -0.066861 12.056408 -18.055610 0.000000 355.981837 0.000000 2196.465215 +EDGE_SE2 1072 1073 -0.002029 0.000845 -0.507518 262958.959876 -2318685.557147 0.000000 20446281.115523 0.000000 1100.056511 +EDGE_SE2 1073 1074 0.561059 -0.025535 -0.032676 11.161259 3.916370 0.000000 316.967702 0.000000 2344.292731 +EDGE_SE2 1074 1075 0.609431 -0.004618 0.018200 11.282578 6.650541 0.000000 269.060256 0.000000 2411.425356 +EDGE_SE2 1075 1076 0.065495 0.001481 0.413124 3385.912605 8198.067984 0.000000 19925.858335 0.000000 1251.928321 +EDGE_SE2 1076 1077 0.014156 0.014258 0.821400 271.376246 8025.080869 0.000000 247458.480551 0.000000 753.579966 +EDGE_SE2 1077 1078 0.639455 0.059020 0.049931 11.521069 -9.730785 0.000000 242.081388 0.000000 2267.871749 +EDGE_SE2 1078 1079 0.600624 0.018085 0.067237 11.477555 9.863097 0.000000 276.583452 0.000000 2194.917807 +EDGE_SE2 1079 1080 -0.000999 -0.000009 -0.477168 21861087.771847 -41382475.748765 0.000000 78336011.010556 0.000000 1145.724571 +EDGE_SE2 1080 1081 0.531360 -0.067180 -0.117428 11.134556 2.812802 0.000000 348.582744 0.000000 2002.169815 +EDGE_SE2 1081 1082 0.224996 0.001967 0.288640 161.010437 521.488265 0.000000 1825.328808 0.000000 1505.486248 +EDGE_SE2 1082 1083 -0.010460 -0.011699 1.057628 18726.686416 85143.154920 0.000000 387354.631781 0.000000 590.481488 +EDGE_SE2 1083 1084 0.006499 0.006279 0.991072 59854.087388 264007.010053 0.000000 1164720.918244 0.000000 630.617587 +EDGE_SE2 1084 1085 0.020056 0.011249 0.977075 38176.449616 75898.227624 0.000000 150947.567649 0.000000 639.578299 +EDGE_SE2 1085 1086 0.570700 0.124357 0.228493 11.165939 3.931749 0.000000 293.059740 0.000000 1656.511362 +EDGE_SE2 1086 1087 0.610443 -0.014761 -0.013224 11.141951 2.815599 0.000000 268.167634 0.000000 2435.168807 +EDGE_SE2 1087 1088 0.601056 0.009570 -0.017713 11.411487 -8.927269 0.000000 276.432474 0.000000 2413.733758 +EDGE_SE2 1088 1089 0.071683 -0.000572 -0.098521 170.122570 -1751.356223 0.000000 19300.592801 0.000000 2071.681742 +EDGE_SE2 1089 1090 0.001412 -0.000123 -0.621871 12937756.646628 -21836745.706848 0.000000 36856777.365825 0.000000 950.402110 +EDGE_SE2 1090 1091 0.549397 -0.084430 -0.180259 11.352156 -8.676436 0.000000 323.419744 0.000000 1794.673157 +EDGE_SE2 1091 1092 0.637703 -0.006996 -0.017526 11.121203 -1.539154 0.000000 245.862562 0.000000 2414.621027 +EDGE_SE2 1092 1093 0.588555 -0.015042 -0.067587 11.600931 -11.646012 0.000000 288.008196 0.000000 2193.478870 +EDGE_SE2 1093 1094 0.004150 -0.003600 -0.406987 303638.185583 955915.435697 0.000000 3009539.565685 0.000000 1262.873468 +EDGE_SE2 1094 1095 0.025922 -0.007302 -0.593448 13559.452360 -41040.960104 0.000000 124333.371329 0.000000 984.609944 +EDGE_SE2 1095 1096 0.013621 -0.004396 -0.574854 32930.237834 -122414.831277 0.000000 455229.472232 0.000000 1007.997402 +EDGE_SE2 1096 1097 0.359533 -0.076883 -0.217554 11.145668 -5.017901 0.000000 739.746128 0.000000 1686.411461 +EDGE_SE2 1097 1098 0.655276 -0.022381 -0.058348 11.240870 -5.359644 0.000000 232.489049 0.000000 2231.942602 +EDGE_SE2 1098 1099 0.601562 -0.024926 -0.098508 11.973250 -15.083436 0.000000 275.001216 0.000000 2071.731935 +EDGE_SE2 1099 1100 0.019767 0.000659 0.359334 26235.559183 77565.286776 0.000000 229429.617699 0.000000 1352.968387 +EDGE_SE2 1100 1101 0.259176 0.070164 0.262689 11.115050 -2.328152 0.000000 1387.055621 0.000000 1568.004174 +EDGE_SE2 1101 1102 0.009767 -0.003058 -0.397627 8459.012576 -89410.542255 0.000000 946310.626975 0.000000 1279.845202 +EDGE_SE2 1102 1103 0.624811 -0.021021 -0.035899 11.112369 -0.554908 0.000000 255.864408 0.000000 2329.727795 +EDGE_SE2 1103 1104 0.653192 -0.005160 -0.029757 11.217748 -4.878085 0.000000 234.257657 0.000000 2357.602064 +EDGE_SE2 1104 1105 0.643770 -0.007193 -0.019886 11.128584 -2.005277 0.000000 241.242039 0.000000 2403.459167 +EDGE_SE2 1105 1106 0.496058 -0.003395 -0.027229 11.275339 -8.055101 0.000000 406.199361 0.000000 2369.220411 +EDGE_SE2 1106 1107 0.007526 0.002867 0.253134 18856.773417 -169404.055090 0.000000 1522787.727562 0.000000 1592.007032 +EDGE_SE2 1107 1108 0.625868 0.043204 0.005957 12.073074 -15.257830 0.000000 253.117791 0.000000 2470.479046 +EDGE_SE2 1108 1109 0.646003 -0.046291 -0.106175 11.383719 -7.866802 0.000000 238.127651 0.000000 2043.112734 +EDGE_SE2 1109 1110 0.614215 -0.005255 -0.051510 11.579361 -10.894385 0.000000 264.581538 0.000000 2261.065764 +EDGE_SE2 1110 1111 0.553199 -0.082221 -0.103442 11.711068 13.593477 0.000000 319.104424 0.000000 2053.246012 +EDGE_SE2 1111 1112 0.569389 0.118635 0.343250 16.481962 38.719218 0.000000 290.243375 0.000000 1385.563104 +EDGE_SE2 1112 1113 0.640195 -0.016890 -0.097447 12.284559 -16.483251 0.000000 242.648861 0.000000 2075.739728 +EDGE_SE2 1113 1114 0.617738 0.000372 0.015293 11.165263 3.685922 0.000000 262.000150 0.000000 2425.253974 +EDGE_SE2 1114 1115 0.584111 0.002651 -0.017913 11.253226 -6.328745 0.000000 292.947350 0.000000 2412.785348 +EDGE_SE2 1115 1116 0.648872 0.022176 0.034505 11.111138 0.077459 0.000000 237.232680 0.000000 2336.010662 +EDGE_SE2 1116 1117 0.098251 0.000884 -0.129855 209.328151 -1418.352583 0.000000 10160.208546 0.000000 1958.369267 +EDGE_SE2 1117 1118 0.002069 -0.000845 -0.611494 987546.746516 -4336045.136437 0.000000 19038602.480542 0.000000 962.681493 +EDGE_SE2 1118 1119 -0.002904 0.000748 -0.435035 368477.951626 -1990623.945676 0.000000 10754258.868008 0.000000 1213.989755 +EDGE_SE2 1119 1120 0.606241 -0.045059 -0.065468 11.130843 2.262698 0.000000 270.573321 0.000000 2202.212316 +EDGE_SE2 1120 1121 0.209582 -0.004500 -0.120622 33.301618 -223.063126 0.000000 2253.383418 0.000000 1990.772900 +EDGE_SE2 1121 1122 0.003037 -0.001969 -0.554282 3351.615045 159642.761466 0.000000 7629342.430661 0.000000 1034.857076 +EDGE_SE2 1122 1123 0.587650 -0.008795 0.015249 11.365183 8.406488 0.000000 289.256608 0.000000 2425.464195 +EDGE_SE2 1123 1124 0.579143 0.038116 0.096775 11.386604 8.868243 0.000000 296.584474 0.000000 2078.284141 +EDGE_SE2 1124 1125 0.646108 -0.002624 0.011822 11.168733 3.627591 0.000000 239.485218 0.000000 2441.921916 +EDGE_SE2 1125 1126 0.089655 0.001862 0.336774 1211.106301 3670.039910 0.000000 11235.483551 0.000000 1399.020340 +EDGE_SE2 1126 1127 -0.000544 0.000812 1.050094 84031228.496092 -41585087.528682 0.000000 20579500.003262 0.000000 594.829446 +EDGE_SE2 1127 1128 -0.002103 -0.000314 0.980680 12093669.618717 11006276.376659 0.000000 10016675.597149 0.000000 637.252248 +EDGE_SE2 1128 1129 0.011252 0.005103 1.008728 198520.561371 301067.442842 0.000000 456622.144090 0.000000 619.580502 +EDGE_SE2 1129 1130 0.583423 0.017793 0.012045 11.207158 -5.207167 0.000000 293.417741 0.000000 2440.845899 +EDGE_SE2 1130 1131 0.750481 -0.194337 -0.435123 16.183680 -27.603353 0.000000 161.320023 0.000000 1213.840879 +EDGE_SE2 1131 1132 0.640243 -0.002464 -0.021306 11.182068 -4.064051 0.000000 243.880425 0.000000 2396.780386 +EDGE_SE2 1132 1133 0.584277 -0.021867 -0.040363 11.113568 -0.831424 0.000000 292.516553 0.000000 2309.777849 +EDGE_SE2 1133 1134 0.266576 -0.000300 -0.098860 24.404478 -135.580323 0.000000 1393.907817 0.000000 2070.404863 +EDGE_SE2 1134 1135 0.009102 -0.002652 -0.559816 82791.558254 -291964.753439 0.000000 1029764.152962 0.000000 1027.527058 +EDGE_SE2 1135 1136 0.002258 -0.003305 -0.565768 971762.123150 2263140.796874 0.000000 5270709.266319 0.000000 1019.729968 +EDGE_SE2 1136 1137 0.306973 -0.042413 -0.186154 13.568352 -50.253896 0.000000 1038.871344 0.000000 1776.878994 +EDGE_SE2 1137 1138 0.654763 -0.011031 -0.017798 11.111312 -0.211469 0.000000 233.189098 0.000000 2413.330616 +EDGE_SE2 1138 1139 0.527941 0.000918 -0.077053 13.265063 -27.280422 0.000000 356.625570 0.000000 2155.092221 +EDGE_SE2 1139 1140 -0.002013 0.000175 -0.486547 3709493.048971 -8779833.609002 0.000000 20780669.837336 0.000000 1131.312847 +EDGE_SE2 1140 1141 0.002239 -0.000031 -0.555810 5310315.218372 -8816646.759236 0.000000 14638204.801536 0.000000 1032.825356 +EDGE_SE2 1141 1142 0.372375 -0.136555 -0.370794 11.343901 -12.055726 0.000000 635.453819 0.000000 1330.440997 +EDGE_SE2 1142 1143 0.629856 0.033762 0.085383 11.354434 7.641679 0.000000 251.102091 0.000000 2122.139741 +EDGE_SE2 1143 1144 0.612945 -0.010504 -0.034290 11.186135 -4.373095 0.000000 266.015507 0.000000 2336.981945 +EDGE_SE2 1144 1145 0.611105 -0.003802 -0.029142 11.245917 -5.880472 0.000000 267.628650 0.000000 2360.420642 +EDGE_SE2 1145 1146 0.609486 -0.000759 0.016125 11.188979 4.482263 0.000000 269.120272 0.000000 2421.284019 +EDGE_SE2 1146 1147 0.610275 0.036873 0.068649 11.128787 2.128847 0.000000 267.508800 0.000000 2189.121374 +EDGE_SE2 1147 1148 0.611337 -0.001965 0.012226 11.172242 3.959007 0.000000 267.506715 0.000000 2439.973063 +EDGE_SE2 1148 1149 0.074700 0.001638 0.503169 3846.534249 7344.890200 0.000000 14076.680961 0.000000 1106.431132 +EDGE_SE2 1149 1150 -0.006116 -0.002785 0.988331 626799.870889 997506.113526 0.000000 1587497.215478 0.000000 632.357453 +EDGE_SE2 1150 1151 0.014648 0.006739 0.987862 107400.301813 172549.549763 0.000000 277258.261675 0.000000 632.655875 +EDGE_SE2 1151 1152 0.009432 0.009802 1.036217 28480.057962 120720.157191 0.000000 511914.710091 0.000000 602.964704 +EDGE_SE2 1152 1153 0.010437 0.002034 0.996659 458897.357799 441929.724577 0.000000 425610.882022 0.000000 627.093176 +EDGE_SE2 1153 1154 0.277143 0.156011 0.537087 11.691675 23.815732 0.000000 988.073623 0.000000 1058.139946 +EDGE_SE2 1154 1155 0.634179 -0.005082 -0.053384 11.599710 -10.761566 0.000000 248.138569 0.000000 2253.027920 +EDGE_SE2 1155 1156 0.609122 -0.005838 0.006338 11.176606 4.113232 0.000000 269.430259 0.000000 2468.608751 +EDGE_SE2 1156 1157 0.580367 0.023367 0.106616 12.366206 18.881213 0.000000 295.153466 0.000000 2041.484648 +EDGE_SE2 1157 1158 0.608842 -0.050707 -0.133293 11.757739 -12.869932 0.000000 267.263428 0.000000 1946.505325 +EDGE_SE2 1158 1159 0.600995 -0.037895 -0.099499 11.464087 -9.658719 0.000000 275.409224 0.000000 2067.999033 +EDGE_SE2 1159 1160 0.637109 -0.021604 -0.142588 13.876030 -25.338115 0.000000 243.313239 0.000000 1914.964342 +EDGE_SE2 1160 1161 0.638306 -0.057065 -0.094949 11.118890 -1.344463 0.000000 243.484624 0.000000 2085.221653 +EDGE_SE2 1161 1162 0.639583 0.008532 0.053343 11.484272 9.323139 0.000000 244.042318 0.000000 2253.203316 +EDGE_SE2 1162 1163 0.646089 0.001306 -0.009750 11.142767 -2.689017 0.000000 239.527759 0.000000 2451.953812 +EDGE_SE2 1163 1164 0.642172 0.018842 0.080564 11.717339 11.822667 0.000000 241.677018 0.000000 2141.110196 +EDGE_SE2 1164 1165 0.530061 0.001899 -0.020695 11.314294 -8.367588 0.000000 355.709513 0.000000 2399.650727 +EDGE_SE2 1165 1166 0.004850 0.001220 0.493564 239307.954224 948357.988051 0.000000 3758451.305300 0.000000 1120.707645 +EDGE_SE2 1166 1167 0.000199 0.000971 0.944839 17209450.782475 -38137417.374455 0.000000 84515406.833935 0.000000 660.956228 +EDGE_SE2 1167 1168 0.004314 0.002779 0.911345 419892.583640 1190803.974162 0.000000 3377188.237646 0.000000 684.324107 +EDGE_SE2 1168 1169 0.046124 0.045485 0.829043 72.075115 1203.501414 0.000000 23769.649842 0.000000 747.295174 +EDGE_SE2 1169 1170 0.595970 0.008443 0.008952 11.118461 -1.409691 0.000000 281.483079 0.000000 2455.833943 +EDGE_SE2 1170 1171 0.643652 0.016020 0.034262 11.131351 2.158066 0.000000 241.208530 0.000000 2337.108483 +EDGE_SE2 1171 1172 0.608254 -0.008594 -0.059650 11.647713 -11.779607 0.000000 269.699888 0.000000 2226.461162 +EDGE_SE2 1172 1173 0.635753 0.004699 0.011813 11.115733 1.045017 0.000000 247.395251 0.000000 2441.965358 +EDGE_SE2 1173 1174 0.642740 -0.015092 -0.065577 11.519977 -9.706025 0.000000 241.521390 0.000000 2201.761802 +EDGE_SE2 1174 1175 0.635529 -0.015560 -0.030331 11.119207 -1.383209 0.000000 247.431148 0.000000 2354.975943 +EDGE_SE2 1175 1176 0.639892 -0.002591 -0.040430 11.419513 -8.473235 0.000000 243.910274 0.000000 2309.480375 +EDGE_SE2 1176 1177 0.631909 0.000862 0.005069 11.114395 0.886514 0.000000 250.429122 0.000000 2474.846416 +EDGE_SE2 1177 1178 0.638012 -0.011209 -0.043943 11.274194 -6.181646 0.000000 245.425622 0.000000 2293.963142 +EDGE_SE2 1178 1179 0.631478 0.010553 0.032543 11.171171 3.792944 0.000000 250.644522 0.000000 2344.896698 +EDGE_SE2 1179 1180 0.271033 0.000088 -0.003969 11.136010 -5.798071 0.000000 1361.277228 0.000000 2480.272525 +EDGE_SE2 1180 1181 0.006369 0.000562 0.838184 1136739.900794 1219876.425763 0.000000 1309117.124470 0.000000 739.881291 +EDGE_SE2 1181 1182 0.043362 0.037473 0.721003 13.218472 253.246510 0.000000 30444.337192 0.000000 844.066675 +EDGE_SE2 1182 1183 0.631233 0.006864 0.028504 11.185650 4.227407 0.000000 250.864920 0.000000 2363.349975 +EDGE_SE2 1183 1184 0.641740 0.028391 0.073043 11.303273 6.663120 0.000000 242.151864 0.000000 2171.229631 +EDGE_SE2 1184 1185 0.636568 -0.012623 -0.029018 11.131008 -2.164911 0.000000 246.663116 0.000000 2360.989552 +EDGE_SE2 1185 1186 0.637011 0.023759 0.069721 11.358319 7.617657 0.000000 245.847739 0.000000 2184.736002 +EDGE_SE2 1186 1187 0.658018 -0.006443 -0.033774 11.237521 -5.269863 0.000000 230.804698 0.000000 2339.315499 +EDGE_SE2 1187 1188 0.632380 0.009510 0.021371 11.120695 1.513079 0.000000 249.993325 0.000000 2396.475334 +EDGE_SE2 1188 1189 0.635906 -0.012539 0.021673 11.515314 9.760309 0.000000 246.794097 0.000000 2395.058778 +EDGE_SE2 1189 1190 0.298422 -0.000493 0.007995 11.214542 10.722954 0.000000 1122.783078 0.000000 2460.499340 +EDGE_SE2 1190 1191 -0.001378 -0.000184 0.920177 25978781.998107 25880314.470994 0.000000 25782242.304073 0.000000 678.043383 +EDGE_SE2 1191 1192 0.072942 0.060647 0.797518 130.506556 1145.096181 0.000000 10993.483679 0.000000 773.736998 +EDGE_SE2 1192 1193 0.612651 -0.026766 -0.132178 13.102394 -22.437131 0.000000 263.925490 0.000000 1950.341157 +EDGE_SE2 1193 1194 0.586582 0.016272 0.041820 11.166533 3.933966 0.000000 290.352323 0.000000 2303.321852 +EDGE_SE2 1194 1195 0.636169 0.007659 0.052000 11.487698 9.418662 0.000000 246.677289 0.000000 2258.959939 +EDGE_SE2 1195 1196 0.637063 -0.002513 -0.173199 17.787125 -39.066310 0.000000 239.717067 0.000000 1816.337880 +EDGE_SE2 1196 1197 0.631038 0.007284 0.010757 11.111259 -0.188614 0.000000 251.090831 0.000000 2447.070566 +EDGE_SE2 1197 1198 0.639335 0.035252 0.257911 20.557528 45.933130 0.000000 234.460604 0.000000 1579.938488 +EDGE_SE2 1198 1199 0.625974 -0.039991 -0.215702 16.676523 -36.355580 0.000000 248.600846 0.000000 1691.553532 +EDGE_SE2 1199 1200 0.642662 0.020896 0.068112 11.403588 8.210051 0.000000 241.573905 0.000000 2191.323116 +EDGE_SE2 1200 1201 0.632369 0.008692 0.054836 11.514278 9.806016 0.000000 249.617869 0.000000 2246.829525 +EDGE_SE2 1201 1202 0.636732 0.009332 0.021910 11.123506 1.708394 0.000000 246.587725 0.000000 2393.947989 +EDGE_SE2 1202 1203 0.605583 0.016194 -0.091218 14.730772 -30.544741 0.000000 268.864904 0.000000 2099.505256 +EDGE_SE2 1203 1204 0.604704 -0.076543 -0.148349 11.241024 -5.788533 0.000000 269.030303 0.000000 1895.798676 +EDGE_SE2 1204 1205 0.579744 0.012270 0.028212 11.125345 2.018565 0.000000 297.379849 0.000000 2364.692492 +EDGE_SE2 1205 1206 0.604024 0.022981 0.059672 11.234092 5.681316 0.000000 273.569799 0.000000 2226.368715 +EDGE_SE2 1206 1207 0.628833 -0.063349 -0.087865 11.148708 2.998873 0.000000 250.310531 0.000000 2112.467324 +EDGE_SE2 1207 1208 0.641879 0.018435 0.062871 11.381019 7.898378 0.000000 242.243300 0.000000 2212.987156 +EDGE_SE2 1208 1209 0.636239 0.001912 -0.003661 11.121595 -1.572688 0.000000 247.023047 0.000000 2481.795033 +EDGE_SE2 1209 1210 0.630195 0.024749 0.018688 11.212716 -4.940152 0.000000 251.306983 0.000000 2409.115535 +EDGE_SE2 1210 1211 0.632941 -0.047678 -0.070430 11.116473 1.127530 0.000000 248.202543 0.000000 2181.842838 +EDGE_SE2 1211 1212 0.633914 0.009606 0.052050 11.434554 8.761975 0.000000 248.470147 0.000000 2258.745224 +EDGE_SE2 1212 1213 0.635719 0.026579 0.075094 11.372749 7.851816 0.000000 246.746209 0.000000 2162.953249 +EDGE_SE2 1213 1214 0.748508 -0.025001 -0.220810 16.915079 -30.604005 0.000000 172.484342 0.000000 1677.427863 +EDGE_SE2 1214 1215 0.609440 0.015872 0.060134 11.410886 8.788375 0.000000 268.756514 0.000000 2224.428662 +EDGE_SE2 1215 1216 0.569604 0.086391 0.218432 12.447317 19.645507 0.000000 299.948223 0.000000 1683.981886 +EDGE_SE2 1216 1217 0.604098 -0.020910 -0.018798 11.176666 4.148410 0.000000 273.628656 0.000000 2408.595337 +EDGE_SE2 1217 1218 0.590246 0.008252 -0.050669 12.262477 -17.784784 0.000000 285.827155 0.000000 2264.686919 +EDGE_SE2 1218 1219 0.650992 0.006557 0.030598 11.205817 4.613431 0.000000 235.846718 0.000000 2353.755880 +EDGE_SE2 1219 1220 0.586496 0.026678 0.090738 11.682801 12.616550 0.000000 289.544235 0.000000 2101.353517 +EDGE_SE2 1220 1221 -0.001846 -0.000482 -0.452753 11628909.160981 -13576008.003722 0.000000 15849147.678198 0.000000 1184.558318 +EDGE_SE2 1221 1222 0.012937 -0.005157 -0.597307 24124.307745 -108858.692621 0.000000 491452.172995 0.000000 979.857795 +EDGE_SE2 1222 1223 0.011537 -0.003845 -0.559627 37585.948232 -154900.759550 0.000000 638583.281939 0.000000 1027.776110 +EDGE_SE2 1223 1224 0.574470 -0.089064 -0.182908 11.352146 -8.281702 0.000000 295.661931 0.000000 1786.644187 +EDGE_SE2 1224 1225 0.625700 0.003903 0.013764 11.124947 1.838454 0.000000 255.403355 0.000000 2432.575223 +EDGE_SE2 1225 1226 0.106504 -0.000109 -0.016731 13.283390 -138.281257 0.000000 8813.714781 0.000000 2418.398573 +EDGE_SE2 1226 1227 0.000000 0.000000 -0.000662 11.111282 -0.257444 0.000000 399.999830 0.000000 2496.693284 +EDGE_SE2 19 166 -2.459689 0.241111 0.252800 11.731352 1.696454 0.000000 15.751178 0.000000 1592.856013 +EDGE_SE2 19 172 1.067903 0.915786 0.149470 22.211594 -17.729393 0.000000 39.428022 0.000000 1892.102792 +EDGE_SE2 25 172 -2.539634 0.852630 -0.029860 11.348228 0.783018 0.000000 13.696833 0.000000 2357.130503 +EDGE_SE2 25 178 1.225223 0.672079 -0.102480 24.051651 -18.745770 0.000000 38.266385 0.000000 2056.830811 +EDGE_SE2 32 178 -2.020007 -0.239771 0.715180 15.237484 6.070047 0.000000 20.040376 0.000000 849.807581 +EDGE_SE2 32 183 -0.092559 0.424181 0.041600 515.079071 88.191252 0.000000 26.544031 0.000000 2304.294940 +EDGE_SE2 44 189 -2.265706 -0.570857 0.197720 11.128469 -0.353246 0.000000 18.300012 0.000000 1742.727183 +EDGE_SE2 44 195 1.302289 -0.133004 -0.005280 11.549680 4.530716 0.000000 57.916501 0.000000 2473.807626 +EDGE_SE2 50 195 -2.374379 -0.253682 0.216120 11.188114 0.699234 0.000000 17.460612 0.000000 1690.390904 +EDGE_SE2 50 201 1.291572 0.086248 -0.050700 11.777215 -5.648747 0.000000 59.014090 0.000000 2264.553285 +EDGE_SE2 50 203 2.550695 0.035722 -0.084650 11.152401 -0.417172 0.000000 15.326014 0.000000 2125.008969 +EDGE_SE2 61 203 -2.852494 0.122053 0.077870 11.127858 0.138148 0.000000 12.250754 0.000000 2151.826441 +EDGE_SE2 61 209 0.730780 0.072970 0.008890 12.538871 -15.710166 0.000000 183.975779 0.000000 2456.135792 +EDGE_SE2 67 209 -2.822142 0.138051 -0.004460 11.113900 0.062754 0.000000 12.522981 0.000000 2477.848305 +EDGE_SE2 67 220 0.783704 -1.176736 -1.412900 17.863537 -14.737201 0.000000 43.275118 0.000000 429.399329 +EDGE_SE2 81 220 -0.868391 -0.009825 -0.046880 11.522030 -7.053327 0.000000 132.179889 0.000000 2281.109865 +EDGE_SE2 81 226 2.836453 0.058719 0.049150 11.112174 0.037334 0.000000 12.422974 0.000000 2271.249469 +EDGE_SE2 87 226 -0.459640 0.184679 0.343830 185.785423 196.810927 0.000000 232.864045 0.000000 1384.367338 +EDGE_SE2 87 231 1.060624 0.863823 0.294010 34.429085 -29.740516 0.000000 94.681322 0.000000 4479.050905 +EDGE_SE2 94 231 -2.231597 0.316386 0.180250 23.930088 5.134954 0.000000 37.661225 0.000000 5384.101583 +EDGE_SE2 94 241 2.816677 0.483252 0.041400 22.259441 -0.288013 0.000000 24.450978 0.000000 6915.540303 +EDGE_SE2 101 241 -1.436886 0.314097 -0.098870 23.168499 8.096966 0.000000 91.505166 0.000000 6211.101543 +EDGE_SE2 101 247 2.168416 0.280309 -0.003870 22.564171 -2.567078 0.000000 41.493789 0.000000 7442.285250 +EDGE_SE2 107 247 -1.536762 0.375104 0.051050 26.954959 15.833327 0.000000 75.192472 0.000000 6789.136027 +EDGE_SE2 107 254 0.592787 -1.020976 -0.778000 30.649088 30.837091 0.000000 135.066803 0.000000 2372.453724 +EDGE_SE2 107 256 0.707309 -1.207974 -1.163740 23.417473 -9.695697 0.000000 100.872264 0.000000 1601.957964 +EDGE_SE2 107 258 0.976528 -2.202656 -1.227730 22.289493 -0.904508 0.000000 34.383996 0.000000 1511.249453 +EDGE_SE2 114 254 -0.931502 -0.024068 0.567580 77.556805 91.947180 0.000000 175.007037 0.000000 3052.121623 +EDGE_SE2 114 256 -0.723652 0.045801 0.181840 43.302820 84.297616 0.000000 359.313621 0.000000 5369.624220 +EDGE_SE2 114 258 0.306031 0.086093 0.117850 69.684517 -301.023297 0.000000 1931.422497 0.000000 6001.975262 +EDGE_SE2 121 266 0.737190 -0.017200 -0.118240 25.326151 -32.604829 0.000000 364.715589 0.000000 5997.789466 +EDGE_SE2 126 266 -1.480397 0.199141 0.062860 24.793867 12.913265 0.000000 87.064919 0.000000 6639.098888 +EDGE_SE2 126 272 2.350796 0.151313 0.025060 22.243466 -0.541415 0.000000 36.020406 0.000000 7137.772305 +EDGE_SE2 132 272 -1.375990 0.193564 -0.069560 22.622461 5.692420 0.000000 103.182984 0.000000 6556.181353 +EDGE_SE2 132 278 2.220707 0.319882 -0.000500 22.580601 -2.479176 0.000000 39.372548 0.000000 7492.505621 +EDGE_SE2 138 278 -1.378019 0.626427 0.016990 34.209796 25.223836 0.000000 75.297341 0.000000 7251.500784 +EDGE_SE2 138 284 2.391863 0.324204 -0.075755 22.750660 -2.473459 0.000000 33.799752 0.000000 6480.884307 +EDGE_SE2 151 284 -2.650853 -0.975732 1.454550 24.484817 1.146301 0.000000 22.802974 0.000000 1244.851357 +EDGE_SE2 151 291 -1.498500 0.364159 0.021790 26.317431 15.382872 0.000000 80.005044 0.000000 7183.530951 +EDGE_SE2 151 297 2.217429 -0.068852 -0.223460 22.895631 -3.456384 0.000000 39.962710 0.000000 5010.507463 +EDGE_SE2 19 305 -1.044094 0.006772 0.289080 17.951036 22.463977 0.000000 84.888274 0.000000 1504.458692 +EDGE_SE2 19 315 1.796874 2.231292 1.917670 11.894814 0.476141 0.000000 11.400392 0.000000 293.675468 +EDGE_SE2 19 337 1.676359 1.138847 2.369960 23.812750 -2.606854 0.000000 11.646135 0.000000 220.135719 +EDGE_SE2 19 342 2.451034 1.014379 -0.106190 11.820054 -1.302086 0.000000 13.502599 0.000000 2043.057325 +EDGE_SE2 19 1016 0.039741 0.374380 -2.852145 602.592071 -246.735273 0.000000 114.036309 0.000000 168.474698 +EDGE_SE2 25 315 -1.587705 2.017012 1.738340 12.043194 -1.708941 0.000000 14.244392 0.000000 333.399749 +EDGE_SE2 25 337 -1.901147 0.963583 2.190630 13.452340 -4.476777 0.000000 19.671370 0.000000 245.576678 +EDGE_SE2 25 342 -1.161097 0.702932 -0.285520 13.939899 10.682557 0.000000 51.452426 0.000000 1512.802847 +EDGE_SE2 25 367 0.878430 -0.159970 0.910020 100.995987 46.868336 0.000000 35.549493 0.000000 685.273881 +EDGE_SE2 25 374 2.840920 -0.557124 -0.601610 11.240233 -0.298749 0.000000 11.802326 0.000000 974.600130 +EDGE_SE2 25 1008 0.839778 0.868849 2.614245 65.217790 -13.300389 0.000000 14.380585 0.000000 191.383617 +EDGE_SE2 25 1010 0.208016 0.817490 -3.078070 128.288560 -37.883138 0.000000 23.358623 0.000000 150.324807 +EDGE_SE2 32 367 -1.650170 -1.061836 1.727680 23.555966 5.481395 0.000000 13.525417 0.000000 336.010748 +EDGE_SE2 32 374 -0.018221 0.098268 0.216050 10000.716890 -326.857444 0.000000 21.805806 0.000000 1690.585519 +EDGE_SE2 32 382 0.235335 2.451229 2.821510 16.224704 1.166981 0.000000 11.377430 0.000000 171.186695 +EDGE_SE2 32 387 0.993162 2.566664 0.274705 12.448992 -1.004261 0.000000 11.864945 0.000000 1538.582680 +EDGE_SE2 32 1003 0.362306 -0.196467 3.066965 108.121054 215.919400 0.000000 491.692649 0.000000 151.146840 +EDGE_SE2 32 1008 -2.427177 -0.386394 -2.851280 11.206045 0.712595 0.000000 16.460019 0.000000 168.550413 +EDGE_SE2 32 1010 -2.821790 -0.882420 -2.260410 11.209350 0.150567 0.000000 11.341881 0.000000 235.177395 +EDGE_SE2 44 437 0.696650 -2.771050 -0.205460 12.032017 0.446847 0.000000 11.327933 0.000000 1720.419675 +EDGE_SE2 44 454 -1.152851 -1.893499 1.516715 13.178717 3.850191 0.000000 18.280745 0.000000 394.704273 +EDGE_SE2 44 467 1.218289 1.232598 1.113140 13.331453 6.657638 0.000000 31.073862 0.000000 559.865191 +EDGE_SE2 44 494 2.154809 -0.649767 -0.306530 11.112721 -0.117867 0.000000 19.740180 0.000000 1464.539994 +EDGE_SE2 44 988 2.712903 -0.996652 3.047100 11.166944 0.211947 0.000000 11.915683 0.000000 152.634299 +EDGE_SE2 44 994 -0.892482 -0.642947 3.093485 38.865579 -34.860363 0.000000 54.896672 0.000000 149.194749 +EDGE_SE2 50 467 -2.756210 1.060141 1.334540 11.461044 -0.046083 0.000000 11.117180 0.000000 458.709115 +EDGE_SE2 50 494 -1.429190 -0.570621 -0.085130 17.367850 -12.471280 0.000000 35.969560 0.000000 2123.129418 +EDGE_SE2 50 500 2.268340 -0.490379 0.263640 12.680013 3.039151 0.000000 16.998309 0.000000 1565.644941 +EDGE_SE2 50 982 2.823043 -0.459737 -3.096925 11.157700 0.222838 0.000000 12.176961 0.000000 148.944310 +EDGE_SE2 50 988 -0.808543 -0.786485 -3.014685 35.481589 -32.415484 0.000000 54.227361 0.000000 155.108998 +EDGE_SE2 61 508 -1.449200 2.112314 1.477670 12.801726 -2.029955 0.000000 13.548517 0.000000 407.242490 +EDGE_SE2 61 522 -1.053664 -0.045704 0.099000 11.354883 4.375854 0.000000 89.660307 0.000000 2069.877405 +EDGE_SE2 61 528 2.466833 0.101003 -0.088240 11.198948 -0.676270 0.000000 16.317799 0.000000 2111.011691 +EDGE_SE2 61 976 1.165811 -0.076649 -3.054440 12.551016 9.349655 0.000000 71.820715 0.000000 152.082153 +EDGE_SE2 61 982 -2.503567 -0.322810 -2.934405 11.139618 0.360303 0.000000 15.665017 0.000000 161.503454 +EDGE_SE2 67 528 -1.085869 0.142906 -0.101590 11.172968 2.113193 0.000000 83.303853 0.000000 2060.155675 +EDGE_SE2 67 532 1.038480 -0.184540 -0.187270 11.121355 -0.898278 0.000000 89.877742 0.000000 1773.540133 +EDGE_SE2 67 556 0.875960 2.072499 -1.608750 12.194562 2.861649 0.000000 18.669404 0.000000 367.345805 +EDGE_SE2 67 564 0.934530 -0.521388 -1.425090 59.070878 -36.808963 0.000000 39.361868 0.000000 425.093327 +EDGE_SE2 67 567 1.078640 -1.127738 0.068640 28.794636 14.729412 0.000000 23.379907 0.000000 2189.158247 +EDGE_SE2 67 570 2.695842 -0.809094 0.129960 11.364179 0.564364 0.000000 12.369693 0.000000 1958.005326 +EDGE_SE2 67 965 0.918287 -0.079133 1.692110 113.199731 -21.468798 0.000000 15.625907 0.000000 344.948615 +EDGE_SE2 67 976 -2.389147 -0.017363 -3.067790 11.139434 0.425047 0.000000 17.489953 0.000000 151.085560 +EDGE_SE2 81 528 -2.540636 -1.571989 1.264430 11.150293 0.045554 0.000000 11.164073 0.000000 487.553422 +EDGE_SE2 81 532 -1.788049 0.441390 1.178750 29.071227 2.714944 0.000000 11.521516 0.000000 526.653783 +EDGE_SE2 81 564 -1.479377 0.271115 -0.059070 11.602730 4.003639 0.000000 43.715888 0.000000 2228.900474 +EDGE_SE2 81 567 -0.856391 0.288913 1.434660 118.478978 -20.563824 0.000000 15.049634 0.000000 421.758037 +EDGE_SE2 81 570 -0.839522 1.937122 1.495980 13.560960 -4.662733 0.000000 19.985567 0.000000 401.289509 +EDGE_SE2 81 575 -0.874481 2.499055 -2.998155 14.149112 0.594261 0.000000 11.227354 0.000000 156.394216 +EDGE_SE2 81 588 2.585410 -0.398590 0.032990 11.230814 0.636285 0.000000 14.493300 0.000000 2342.867749 +EDGE_SE2 81 959 1.715988 -0.147087 2.880085 11.804020 -3.896236 0.000000 33.019679 0.000000 166.057104 +EDGE_SE2 81 965 -1.915695 0.345142 3.058130 11.248005 1.439837 0.000000 26.255228 0.000000 151.805707 +EDGE_SE2 87 588 -0.567044 -0.325829 0.327670 19.376959 -42.100418 0.000000 225.541056 0.000000 1418.272639 +EDGE_SE2 87 597 1.033167 2.497995 1.747590 11.858143 1.168127 0.000000 12.937699 0.000000 331.158689 +EDGE_SE2 87 604 1.169979 2.733059 -1.279630 11.194520 0.099906 0.000000 11.230777 0.000000 481.073330 +EDGE_SE2 87 953 1.577352 0.448961 -2.823050 11.155436 1.074029 0.000000 37.135844 0.000000 171.048808 +EDGE_SE2 87 959 -1.472035 -0.337676 -3.108420 12.306884 -6.140766 0.000000 42.646361 0.000000 148.112032 +EDGE_SE2 94 597 -2.073375 1.943112 1.633830 11.708877 -0.635533 0.000000 11.786797 0.000000 360.383193 +EDGE_SE2 94 604 -1.910764 2.161126 -1.393390 11.355872 -0.402293 0.000000 11.772326 0.000000 436.428461 +EDGE_SE2 94 616 -0.567925 0.985809 1.728270 19.547380 -22.065015 0.000000 68.822033 0.000000 335.865437 +EDGE_SE2 94 632 -0.258230 -0.057031 -0.961010 1222.393668 -501.336231 0.000000 218.608540 0.000000 650.100338 +EDGE_SE2 94 637 2.180403 0.487495 0.048180 11.371804 -1.502621 0.000000 19.772123 0.000000 2275.455104 +EDGE_SE2 94 947 1.819562 0.355845 -2.812985 11.439117 2.406258 0.000000 28.763471 0.000000 171.952995 +EDGE_SE2 94 953 -1.765303 -0.154451 -2.936810 11.396122 2.414195 0.000000 31.560619 0.000000 161.306214 +EDGE_SE2 101 637 -2.066317 0.407256 -0.092090 11.230841 1.163903 0.000000 22.425529 0.000000 2096.153815 +EDGE_SE2 101 642 0.702540 0.058990 -0.158060 22.012272 -44.195550 0.000000 190.288971 0.000000 1864.137257 +EDGE_SE2 101 645 1.268565 0.117224 1.302975 55.348130 16.649223 0.000000 17.377280 0.000000 471.369465 +EDGE_SE2 101 657 0.970735 1.275733 -1.200065 31.327289 12.383774 0.000000 18.697009 0.000000 516.498549 +EDGE_SE2 101 663 2.721944 0.234701 0.154665 11.121870 0.156475 0.000000 13.386764 0.000000 1875.114422 +EDGE_SE2 101 665 2.743644 0.343689 1.484400 12.992900 0.403085 0.000000 11.197453 0.000000 405.039117 +EDGE_SE2 101 939 1.736598 0.040097 -3.139770 11.121070 -0.468281 0.000000 33.131371 0.000000 145.877255 +EDGE_SE2 101 944 -1.229619 0.290529 3.034680 11.913468 6.379852 0.000000 61.839764 0.000000 153.575457 +EDGE_SE2 101 947 -2.442020 0.327348 -2.953255 11.646767 1.607820 0.000000 15.937136 0.000000 159.966957 +EDGE_SE2 101 1138 -0.044980 -2.128090 1.406340 11.334711 -1.549412 0.000000 21.847605 0.000000 431.743719 +EDGE_SE2 101 1188 1.043367 -1.716987 3.078145 20.296004 6.412523 0.000000 15.588077 0.000000 150.319256 +EDGE_SE2 107 642 -2.988279 0.073654 -0.103140 11.111606 -0.006296 0.000000 11.191151 0.000000 2054.370375 +EDGE_SE2 107 645 -2.426303 0.162871 1.357895 16.787995 0.834037 0.000000 11.233646 0.000000 449.666954 +EDGE_SE2 107 663 -0.981564 0.359950 0.209585 33.867694 36.211234 0.000000 68.731953 0.000000 1708.704657 +EDGE_SE2 107 665 -0.965880 0.469964 1.539320 74.030616 -28.201297 0.000000 23.751280 0.000000 387.708339 +EDGE_SE2 107 680 -1.101202 1.597727 -1.082720 11.315853 -1.766538 0.000000 26.353031 0.000000 576.339299 +EDGE_SE2 107 683 -0.373238 0.237253 -0.978670 91.473664 -183.671027 0.000000 430.896755 0.000000 638.547590 +EDGE_SE2 107 704 -0.174419 -0.744617 -2.364960 56.805507 -72.228521 0.000000 125.281768 0.000000 220.790405 +EDGE_SE2 107 714 -0.001585 -1.518738 0.040750 43.298168 -1.345998 0.000000 11.167398 0.000000 2308.060399 +EDGE_SE2 107 730 1.719547 -1.998733 -2.849795 13.843772 1.215931 0.000000 11.652154 0.000000 168.680442 +EDGE_SE2 107 929 0.482300 -2.592003 1.960350 11.247596 0.654505 0.000000 14.249748 0.000000 285.268546 +EDGE_SE2 107 935 -0.294578 0.372182 2.191385 12.146819 -21.145445 0.000000 442.825321 0.000000 245.460450 +EDGE_SE2 107 939 -1.954743 0.111552 -3.084850 11.304032 1.688716 0.000000 25.893149 0.000000 149.826206 +EDGE_SE2 107 1147 -0.324254 -1.481983 0.140150 39.532534 -10.553850 0.000000 15.030118 0.000000 1923.162692 +EDGE_SE2 107 1150 0.364219 -1.279939 1.435915 18.388124 -16.646666 0.000000 49.191505 0.000000 421.323458 +EDGE_SE2 114 663 -2.629135 -1.250276 1.555165 11.663410 0.273309 0.000000 11.246360 0.000000 382.914669 +EDGE_SE2 114 665 -2.732868 -1.210420 2.884900 11.143210 -0.040214 0.000000 11.161493 0.000000 165.645759 +EDGE_SE2 114 683 -2.373686 -0.684712 0.366910 11.150086 0.451690 0.000000 16.345825 0.000000 1338.012489 +EDGE_SE2 114 704 -1.372213 -0.710183 -1.019380 41.720375 -2.264013 0.000000 11.278569 0.000000 613.061308 +EDGE_SE2 114 714 -0.579045 -0.714588 1.386330 35.416827 44.860054 0.000000 93.907456 0.000000 439.014644 +EDGE_SE2 114 730 0.273187 0.855886 -1.504215 26.282898 38.481991 0.000000 108.717525 0.000000 398.654506 +EDGE_SE2 114 929 0.575175 -0.482602 -2.977255 107.010292 82.154133 0.000000 81.490248 0.000000 158.042201 +EDGE_SE2 114 935 -2.487642 -0.577907 -2.746220 11.227888 0.692283 0.000000 15.215150 0.000000 178.136720 +EDGE_SE2 114 1147 -0.686929 -1.020901 1.485730 24.072771 23.324553 0.000000 53.083724 0.000000 404.605797 +EDGE_SE2 114 1150 -0.730123 -0.304695 2.781495 80.988104 -74.193686 0.000000 89.888157 0.000000 174.828760 +EDGE_SE2 114 1158 1.965070 -0.055808 0.083960 11.296704 1.644922 0.000000 25.690196 0.000000 2127.715200 +EDGE_SE2 114 1175 2.570804 -0.255481 2.913020 11.175699 -0.495876 0.000000 14.918247 0.000000 163.273564 +EDGE_SE2 121 754 -0.176774 -0.090674 -0.104160 764.277342 -1154.350823 0.000000 1780.343146 0.000000 2050.576559 +EDGE_SE2 121 759 2.795658 -0.372882 -0.047990 11.121537 0.122936 0.000000 12.560684 0.000000 2276.280256 +EDGE_SE2 121 923 -0.359940 -0.158411 2.816780 299.677751 -316.410365 0.000000 358.051835 0.000000 171.611249 +EDGE_SE2 121 1158 -1.765259 0.015433 0.094390 11.333442 2.148138 0.000000 31.866199 0.000000 2087.352405 +EDGE_SE2 121 1164 1.939145 -0.416391 -0.071910 11.388217 1.971985 0.000000 25.144479 0.000000 2175.822000 +EDGE_SE2 121 1175 -1.157476 -0.177912 2.923450 19.220682 -20.867733 0.000000 64.808438 0.000000 162.406633 +EDGE_SE2 126 754 -2.366181 -0.037747 0.076940 11.136170 0.410365 0.000000 17.831325 0.000000 2155.544499 +EDGE_SE2 126 759 0.608470 0.220030 0.133110 21.370901 -47.238010 0.000000 228.603826 0.000000 1947.134106 +EDGE_SE2 126 762 1.256487 0.430359 1.248090 39.878585 21.991658 0.000000 27.922912 0.000000 494.666638 +EDGE_SE2 126 923 -2.534151 -0.137367 2.997880 11.281716 -0.850942 0.000000 15.355440 0.000000 156.415757 +EDGE_SE2 126 1164 -0.226200 0.022965 0.109190 94.980319 392.781106 0.000000 1850.606209 0.000000 2032.020653 +EDGE_SE2 132 762 -2.439040 0.574751 1.153470 15.760986 0.874518 0.000000 11.275585 0.000000 539.091342 +EDGE_SE2 132 778 -1.013501 1.621706 1.561210 15.810999 -7.362314 0.000000 22.644082 0.000000 381.109374 +EDGE_SE2 132 792 -0.882133 1.768911 -1.797920 16.975203 -7.109142 0.000000 19.729650 0.000000 319.351840 +EDGE_SE2 132 800 1.214689 0.372313 0.005900 15.310892 -13.996183 0.000000 57.754774 0.000000 2470.759036 +EDGE_SE2 132 907 2.246094 -0.166035 -3.063890 11.307039 1.283425 0.000000 19.518199 0.000000 151.375685 +EDGE_SE2 132 911 0.287430 -0.091199 2.898905 15.641604 70.080974 0.000000 1095.174761 0.000000 164.457860 +EDGE_SE2 132 1084 -0.744736 -2.350749 -1.849821 11.115227 0.148119 0.000000 16.441489 0.000000 307.825761 +EDGE_SE2 138 800 -2.384799 0.661256 0.023390 11.548813 1.446295 0.000000 15.890090 0.000000 2387.028865 +EDGE_SE2 138 806 1.314158 0.976356 0.186155 16.125723 -10.306715 0.000000 32.294877 0.000000 1776.876918 +EDGE_SE2 138 821 1.339602 0.836157 -1.728640 27.615689 14.355051 0.000000 23.596586 0.000000 335.774357 +EDGE_SE2 138 823 1.391787 0.830084 -0.201680 23.357993 -13.427129 0.000000 25.832230 0.000000 1731.260189 +EDGE_SE2 138 903 0.257877 0.385262 2.468460 462.130945 37.644489 0.000000 14.253118 0.000000 207.810089 +EDGE_SE2 138 904 0.211460 0.361905 2.918540 518.619452 -160.188745 0.000000 61.672712 0.000000 162.813885 +EDGE_SE2 138 907 -1.344137 0.141028 -3.046400 12.828819 8.485440 0.000000 53.029004 0.000000 152.687113 +EDGE_SE2 151 828 -2.783661 1.064375 1.529770 11.244135 -0.044701 0.000000 11.126133 0.000000 390.641099 +EDGE_SE2 151 847 -2.892269 0.357584 -1.720550 11.773808 0.017727 0.000000 11.111585 0.000000 337.774286 +EDGE_SE2 151 855 0.421564 -0.036975 -0.072980 11.226261 7.937694 0.000000 558.283669 0.000000 2171.484605 +EDGE_SE2 151 895 -0.308314 0.072387 -2.940720 183.554391 374.539119 0.000000 824.593387 0.000000 160.986275 +EDGE_SE2 151 897 -0.653297 -0.340780 -2.145820 53.093226 74.186112 0.000000 142.204535 0.000000 252.622641 +EDGE_SE2 151 1029 2.658346 -1.322835 -1.612160 11.303644 -0.086066 0.000000 11.149585 0.000000 366.387340 +EDGE_SE2 157 297 -1.431635 -0.047784 -0.192100 12.991577 -8.198575 0.000000 46.855781 0.000000 1759.197636 +EDGE_SE2 157 305 2.323872 -0.569035 0.026110 11.551318 1.614103 0.000000 17.029536 0.000000 2374.390623 +EDGE_SE2 157 1029 -0.951615 -1.287326 -1.580800 20.706819 13.256279 0.000000 29.424395 0.000000 375.345582 +EDGE_SE2 157 1217 -0.999593 -2.295582 1.588120 11.945029 1.827929 0.000000 15.117890 0.000000 373.225399 +EDGE_SE2 163 297 -0.152489 -1.643361 1.294160 11.969142 -4.607638 0.000000 35.854192 0.000000 474.998898 +EDGE_SE2 163 305 0.683999 2.054722 1.512370 11.800954 2.562970 0.000000 20.633308 0.000000 396.070787 +EDGE_SE2 163 1029 1.123157 -1.269718 -0.094540 22.165118 11.817460 0.000000 23.744753 0.000000 2086.780326 +EDGE_SE2 163 1217 2.123761 -1.402656 3.074380 12.166102 1.857716 0.000000 14.382333 0.000000 150.597217 +EDGE_SE2 166 297 -2.448623 -0.097923 -0.181930 11.379485 -1.189522 0.000000 16.383459 0.000000 1789.602165 +EDGE_SE2 166 305 1.311990 -0.580954 0.036280 18.290583 14.744491 0.000000 41.391889 0.000000 2328.015008 +EDGE_SE2 166 1016 2.453320 -0.496114 -3.104945 11.376696 1.103524 0.000000 15.696336 0.000000 148.362881 +EDGE_SE2 166 1029 -1.956023 -1.332520 -1.570630 15.716267 3.136091 0.000000 13.246776 0.000000 378.321363 +EDGE_SE2 172 305 -2.223813 -0.584373 0.139610 11.218103 -0.907468 0.000000 18.807912 0.000000 1924.985691 +EDGE_SE2 172 315 0.916741 1.192284 1.768200 29.887371 16.398688 0.000000 25.433291 0.000000 326.245913 +EDGE_SE2 172 328 0.389353 2.701274 -1.418880 11.306838 0.643966 0.000000 13.229838 0.000000 427.278816 +EDGE_SE2 172 337 0.634889 0.129966 2.220490 195.557030 -88.592401 0.000000 53.663494 0.000000 241.043874 +EDGE_SE2 172 342 1.382392 -0.108475 -0.255660 12.384043 -7.102031 0.000000 50.735268 0.000000 1585.608223 +EDGE_SE2 172 1010 2.747473 0.046909 -3.048210 11.123505 0.162102 0.000000 13.231218 0.000000 152.550608 +EDGE_SE2 172 1016 -1.097321 -0.382262 -3.001615 13.480215 -11.980076 0.000000 71.691915 0.000000 156.123881 +EDGE_SE2 178 342 -2.376956 -0.213431 -0.183040 11.578392 -1.671546 0.000000 17.090523 0.000000 1786.245513 +EDGE_SE2 178 367 -0.259854 -0.863160 1.012500 18.840526 -28.383170 0.000000 115.336891 0.000000 617.260137 +EDGE_SE2 178 374 1.732968 -1.057467 -0.499130 11.142356 0.640290 0.000000 24.232266 0.000000 1112.401122 +EDGE_SE2 178 1003 1.826983 -1.529516 2.351785 11.166956 -0.600028 0.000000 17.558198 0.000000 222.529516 +EDGE_SE2 178 1008 -0.403552 0.156306 2.716725 12.710306 -28.871300 0.000000 532.343545 0.000000 180.975206 +EDGE_SE2 178 1010 -1.026746 0.040588 -2.975590 14.592518 16.700937 0.000000 91.228510 0.000000 158.174631 +EDGE_SE2 183 367 -1.618063 -1.419954 1.686080 18.191945 4.896376 0.000000 14.496941 0.000000 346.499109 +EDGE_SE2 183 374 0.060720 -0.328723 0.174450 894.828841 7.251305 0.000000 11.170611 0.000000 1812.470490 +EDGE_SE2 183 382 0.411911 2.011657 2.779910 23.397894 1.979206 0.000000 11.429930 0.000000 174.975438 +EDGE_SE2 183 387 1.173883 2.095476 0.233105 14.481439 -3.100632 0.000000 13.963629 0.000000 1644.144968 +EDGE_SE2 183 1003 0.428660 -0.639029 3.025365 102.305125 77.922908 0.000000 77.694205 0.000000 154.287027 +EDGE_SE2 183 1008 -2.366308 -0.712782 -2.892880 11.121230 -0.230529 0.000000 16.363269 0.000000 164.967341 +EDGE_SE2 189 400 -1.948699 2.200613 -1.116370 11.144116 -0.119102 0.000000 11.540899 0.000000 558.157565 +EDGE_SE2 189 414 -0.254807 -1.783532 -1.508360 11.922188 3.913799 0.000000 29.996898 0.000000 397.338159 +EDGE_SE2 189 454 0.831360 -1.515476 1.318995 21.578630 -11.156350 0.000000 23.001623 0.000000 464.879365 +EDGE_SE2 189 994 1.332308 -0.340434 2.895765 11.111898 0.181350 0.000000 52.882967 0.000000 164.723074 +EDGE_SE2 195 437 -0.591701 -2.641206 -0.200180 13.648824 -0.051289 0.000000 11.112148 0.000000 1735.590395 +EDGE_SE2 195 467 -0.091210 1.365140 1.118420 21.523802 -18.224556 0.000000 43.008191 0.000000 557.077827 +EDGE_SE2 195 484 0.655807 2.573505 -2.009240 11.219291 -0.565783 0.000000 14.070164 0.000000 276.074540 +EDGE_SE2 195 494 0.855236 -0.512254 -0.301250 16.102937 20.540136 0.000000 95.628725 0.000000 1476.449250 +EDGE_SE2 195 988 1.415155 -0.856188 3.052380 16.022409 10.041613 0.000000 31.642140 0.000000 152.236812 +EDGE_SE2 195 994 -2.192048 -0.521524 3.098765 11.750475 -2.253964 0.000000 19.057069 0.000000 148.810613 +EDGE_SE2 201 494 -2.683977 -0.793909 -0.034430 11.276756 -0.496479 0.000000 12.599187 0.000000 2336.349413 +EDGE_SE2 201 500 1.004735 -0.526385 0.314340 45.186413 33.298498 0.000000 43.650514 0.000000 1447.186686 +EDGE_SE2 201 982 1.557172 -0.467671 -3.046225 14.919173 9.340266 0.000000 34.020554 0.000000 152.700298 +EDGE_SE2 201 988 -2.053188 -0.978041 -2.963985 11.683303 -2.092334 0.000000 18.762142 0.000000 159.102109 +EDGE_SE2 203 500 -0.236863 -0.548090 0.348290 153.663942 -134.464803 0.000000 137.946777 0.000000 1375.223806 +EDGE_SE2 203 508 1.553867 1.875066 1.399800 12.536000 2.482853 0.000000 15.437455 0.000000 434.100125 +EDGE_SE2 203 522 1.780329 -0.307182 0.021130 11.822071 3.657498 0.000000 29.926926 0.000000 2397.606666 +EDGE_SE2 203 982 0.313263 -0.470658 -3.012275 253.866414 119.649456 0.000000 70.084044 0.000000 155.295388 +EDGE_SE2 209 508 -2.161765 2.058644 1.468780 11.180293 -0.053576 0.000000 11.152602 0.000000 410.180706 +EDGE_SE2 209 522 -1.785428 -0.102806 0.090110 11.132515 0.656456 0.000000 31.244975 0.000000 2103.775347 +EDGE_SE2 209 528 1.736233 0.012599 -0.097130 11.350617 -2.286079 0.000000 32.931671 0.000000 2076.939411 +EDGE_SE2 209 976 0.433683 -0.153481 -3.063330 87.280240 171.295909 0.000000 396.336584 0.000000 151.417412 +EDGE_SE2 220 528 -1.597199 -1.638814 1.311310 13.034804 3.414597 0.000000 17.172093 0.000000 467.976033 +EDGE_SE2 220 532 -0.939792 0.407621 1.225630 94.950637 -5.379789 0.000000 11.456320 0.000000 504.700895 +EDGE_SE2 220 564 -0.623480 0.251998 -0.012190 38.845567 71.101745 0.000000 193.391889 0.000000 2440.146629 +EDGE_SE2 220 567 -0.002013 0.298972 1.481540 21.284937 -105.664807 0.000000 1108.540123 0.000000 405.973278 +EDGE_SE2 220 570 -0.062402 1.946160 1.542860 11.165977 -0.913492 0.000000 26.320380 0.000000 386.629607 +EDGE_SE2 220 575 -0.123656 2.505837 -2.951275 15.792523 -0.664538 0.000000 11.205444 0.000000 160.127317 +EDGE_SE2 220 959 2.587973 -0.016000 2.926965 11.274656 -0.773198 0.000000 14.766597 0.000000 162.116000 +EDGE_SE2 220 965 -1.062787 0.305497 3.105010 15.212918 16.523642 0.000000 77.674651 0.000000 148.358205 +EDGE_SE2 226 231 1.660221 0.126920 -0.049820 11.505996 -3.114430 0.000000 35.674411 0.000000 2268.351350 +EDGE_SE2 226 588 -0.273207 -0.444423 -0.016160 274.806053 -156.291042 0.000000 103.744249 0.000000 2421.117227 +EDGE_SE2 226 597 2.185242 1.674700 1.403760 12.078039 1.038206 0.000000 12.225850 0.000000 432.671013 +EDGE_SE2 226 953 2.006857 -0.437847 3.116305 11.557944 2.329386 0.000000 23.254435 0.000000 147.545120 +EDGE_SE2 226 959 -1.129223 -0.150509 2.830935 23.235807 -25.544568 0.000000 64.928953 0.000000 170.345385 +EDGE_SE2 923 1175 0.749610 0.273000 0.106670 19.536607 -34.047517 0.000000 148.697481 0.000000 2041.285424 +EDGE_SE2 929 1175 -2.005899 0.102421 -0.392910 12.648561 -4.320259 0.000000 23.251108 0.000000 1288.528106 +EDGE_SE2 939 1188 0.696432 1.755817 -0.065270 26.430265 -4.946684 0.000000 12.708437 0.000000 2203.031036 +EDGE_SE2 1029 1217 1.008685 -0.037889 -3.114265 11.476877 5.630362 0.000000 97.781127 0.000000 147.691473 +EDGE_SE2 1044 1217 2.098504 -0.838430 0.479890 15.976239 4.188481 0.000000 14.717054 0.000000 1141.513725 +EDGE_SE2 1050 1210 -0.300235 -2.565672 1.536560 11.137270 0.317303 0.000000 14.960021 0.000000 388.552520 +EDGE_SE2 1050 1217 0.231465 1.668290 1.559140 11.493589 3.014437 0.000000 34.868922 0.000000 381.726156 +EDGE_SE2 1056 1217 2.128743 -0.472375 -0.931160 15.353750 -4.908186 0.000000 16.789250 0.000000 670.352902 +EDGE_SE2 1061 1210 1.269232 -1.441319 -2.909610 23.568115 6.644624 0.000000 14.655385 0.000000 163.558506 +EDGE_SE2 1075 1210 -1.662329 0.436026 -1.599840 32.701727 -4.997844 0.000000 12.268023 0.000000 369.868006 +EDGE_SE2 1084 1210 2.070374 1.896269 1.836205 12.355692 0.641825 0.000000 11.442098 0.000000 310.788312 +EDGE_SE2 1088 1210 0.609503 -1.485166 0.536770 38.204841 -4.021013 0.000000 11.707874 0.000000 1058.576530 +EDGE_SE2 1093 1210 -0.233452 -0.529583 1.494360 42.853783 90.090527 0.000000 266.801722 0.000000 401.810926 +EDGE_SE2 1098 1210 -0.378280 -0.172442 -2.937025 38.903093 -122.470929 0.000000 550.803768 0.000000 161.288572 +EDGE_SE2 1138 1188 0.583736 -1.006358 1.671805 21.764394 -23.563240 0.000000 63.228969 0.000000 350.211491 +EDGE_SE2 1147 1188 -2.232188 0.113982 2.992915 11.195782 -0.864255 0.000000 19.932721 0.000000 156.804966 +EDGE_SE2 1150 1188 -0.789302 2.834301 1.697150 11.120354 -0.063189 0.000000 11.543094 0.000000 343.660651 +EDGE_SE2 1158 1175 0.586855 -0.249767 2.829060 13.000858 20.975969 0.000000 243.941877 0.000000 170.512281 diff --git a/SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb b/SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb new file mode 100644 index 0000000000..cd3d9fd5db --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb @@ -0,0 +1,332 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "from graphslam.graph import Graph\n", + "from graphslam.load import load_g2o_se2" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Introduction\n", + "\n", + "For a complete derivation of the Graph SLAM algorithm, please see [graphSLAM_formulation.pdf](./graphSLAM_formulation.pdf). \n", + "\n", + "This notebook illustrates the iterative optimization of a real-world $SE(2)$ dataset. The code can be found in the `graphslam` folder. For simplicity, numerical differentiation is used in lieu of analytic Jacobians. This code originated from the [python-graphslam](https://github.com/JeffLIrion/python-graphslam) repo, which is a full-featured Graph SLAM solver. The dataset in this example is used with permission from Luca Carlone and was downloaded from his [website](https://lucacarlone.mit.edu/datasets/). " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# The Dataset" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Number of edges: 1483\n", + "Number of vertices: 1228\n" + ] + } + ], + "source": [ + "g = load_g2o_se2(\"data/input_INTEL.g2o\")\n", + "\n", + "print(\"Number of edges: {}\".format(len(g._edges)))\n", + "print(\"Number of vertices: {}\".format(len(g._vertices)))" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEMCAYAAADHxQ0LAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\naDSaNoI2+BqNRtNG0AZfo9Fo2gj/D1KYU/J75gHUAAAAAElFTkSuQmCC\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g.plot(title=r\"Original ($\\chi^2 = {:.0f}$)\".format(g.calc_chi2()))" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Each edge in this dataset is a constraint that compares the measured $SE(2)$ transformation between two poses to the expected $SE(2)$ transformation between them, as computed using the current pose estimates. These edges can be classified into two categories:\n", + "\n", + "1. Odometry edges constrain two consecutive vertices, and the measurement for the $SE(2)$ transformation comes directly from odometry data.\n", + "2. Scan-matching edges constrain two non-consecutive vertices. These scan matches can be computed using, for example, 2-D LiDAR data or landmarks; the details of how these contstraints are determined is beyond the scope of this example. This is often referred to as *loop closure* in the Graph SLAM literature.\n", + "\n", + "We can easily parse out the two different types of edges present in this dataset and plot them." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "def parse_edges(g):\n", + " \"\"\"Split the graph `g` into two graphs, one with only odometry edges and the other with only scan-matching edges.\n", + "\n", + " Parameters\n", + " ----------\n", + " g : graphslam.graph.Graph\n", + " The input graph\n", + "\n", + " Returns\n", + " -------\n", + " g_odom : graphslam.graph.Graph\n", + " A graph consisting of the vertices and odometry edges from `g`\n", + " g_scan : graphslam.graph.Graph\n", + " A graph consisting of the vertices and scan-matching edges from `g`\n", + "\n", + " \"\"\"\n", + " edges_odom = []\n", + " edges_scan = []\n", + " \n", + " for e in g._edges:\n", + " if abs(e.vertex_ids[1] - e.vertex_ids[0]) == 1:\n", + " edges_odom.append(e)\n", + " else:\n", + " edges_scan.append(e)\n", + "\n", + " g_odom = Graph(edges_odom, g._vertices)\n", + " g_scan = Graph(edges_scan, g._vertices)\n", + "\n", + " return g_odom, g_scan" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Number of odometry edges: 1227\n", + "Number of scan-matching edges: 256\n", + "\n", + "χ^2 error from odometry edges: 0.232\n", + "χ^2 error from scan-matching edges: 7191686.151\n" + ] + } + ], + "source": [ + "g_odom, g_scan = parse_edges(g)\n", + "\n", + "print(\"Number of odometry edges: {:4d}\".format(len(g_odom._edges)))\n", + "print(\"Number of scan-matching edges: {:4d}\".format(len(g_scan._edges)))\n", + "\n", + "print(\"\\nχ^2 error from odometry edges: {:11.3f}\".format(g_odom.calc_chi2()))\n", + "print(\"χ^2 error from scan-matching edges: {:11.3f}\".format(g_scan.calc_chi2()))" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nAAAASUVORK5CYII=\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g_odom.plot(title=\"Odometry edges\")" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nQmCC\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g_scan.plot(title=\"Scan-matching edges\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Optimization\n", + "\n", + "Initially, the pose estimates are consistent with the collected odometry measurements, and the odometry edges contribute almost zero towards the $\\chi^2$ error. However, there are large discrepancies between the scan-matching constraints and the initial pose estimates. This is not surprising, since small errors in odometry readings that are propagated over time can lead to large errors in the robot's trajectory. What makes Graph SLAM effective is that it allows incorporation of multiple different data sources into a single optimization problem." + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Iteration chi^2 rel. change\n", + "--------- ----- -----------\n", + " 0 7191686.3825\n", + " 1 320031728.8624 43.500234\n", + " 2 125083004.3299 -0.609154\n", + " 3 338155.9074 -0.997297\n", + " 4 735.1344 -0.997826\n", + " 5 215.8405 -0.706393\n", + " 6 215.8405 -0.000000\n" + ] + } + ], + "source": [ + "g.optimize()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "![Graph_SLAM_optimization.gif](images/Graph_SLAM_optimization.gif)" + ] + }, + { + "cell_type": "code", + "execution_count": 9, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nBL6Dg4NDK+H/A7aRY5b1tCw8AAAAAElFTkSuQmCC\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g.plot(title=\"Optimized\")" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "χ^2 error from odometry edges: 142.189\n", + "χ^2 error from scan-matching edges: 73.652\n" + ] + } + ], + "source": [ + "print(\"\\nχ^2 error from odometry edges: {:7.3f}\".format(g_odom.calc_chi2()))\n", + "print(\"χ^2 error from scan-matching edges: {:7.3f}\".format(g_scan.calc_chi2()))" + ] + }, + { + "cell_type": "code", + "execution_count": 11, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nRqPRVAj/D0Fj/txvoohWAAAAAElFTkSuQmCC\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g_odom.plot(title=\"Odometry edges\")" + ] + }, + { + "cell_type": "code", + "execution_count": 12, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\n", + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "g_scan.plot(title=\"Scan-matching edges\")" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.5.2" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf b/SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf new file mode 100644 index 0000000000000000000000000000000000000000..65c868246c0ca8b4c93122afa111070654a39624 GIT binary patch literal 276368 zcma&NQ?M{R(5<;`+qP}nwr$(CZQHhO+t#~nW4<#p=jxxTIk`x6Dp#qbs-LwwO{yRw zM$1UY3PrlGGP(i9#6ZA6U~gmv#lr(dFJo$F?qWf}%)rh_@P7{|dNE5I7gHw!dNCVA z7gG^aV|x=*C_X+YXBQ_^Lt7}1ts8C4Nf{<7WveXCQ^Puw?!QCBAGgXW!`STp; z+@FP3`fMvuXAM|w%9Q=6lLxh(8iPJ zivr2)>vk)~mfdXy&&}3s_4H>&_(JPezR*JdHQjDKMNSzxXEnpf%c|zRfjsq@T<5T0r_ z5-;VWagQwMD%^O)Dt2BffV4}89Rrhws2CVlx~y3ynVEC_T*cObBytw^ph}(55W4jW zozRJsZ)&P%_0yuDL8^AmSt>WQ2+mYWb%xRzj|TtJj9F;jwsJED1HIQVdC}}KX|s+v zlI_tTTk|K${02*&rNf{h2J0K!w3JCw!Spg~Am!MD%@5PirO0P#jE+35sX8d^X5~SU z_@Z~U`EKReL8zhpQ3dvwE%a%+M)b)MxxC>`b<~NuPt;m=owQ+%s;-7!E*rDmrMn`~ zCr{Rd2nh$Op$rWX1sc+gu(s-9&z|joWb4ur2-m97o8ScJ00X z08O1&7Q+-&1kdf8be(gcUk9ygtE;7fpqEvKflO~Js(WD{XR;X|tMyE4-zc3?T@K7Kv72xQUf12YaD#*NlO@jM_*f>zvC@ zLQ;t;WkTXbn(=yb z`BggLv?*}kVu;p-4sM4;~5A^0LhViqVD!N=_s~YjBx9J8I z0I7%5jN*QYClz~z<&@)&$hHkn0BV}4!t3-@eD6OaG@v`rWBNp#CUIs_QQejV_E)p3 z%WkR`Vke?k!^z%ku7&!e+bjXH!+uGBo>eVmkHi42ls9U1{qlHx>Du)WWbFI@Rprjg z3xE@(Z(D83M`8l%Zqf4gOUMB7vh3G+CW^$4&b9VQ58%u`3W+eBw~q)RY@ygeIqQ+e zj?Dpk76T5ohq44ViCoGixF9)zdpmdo`3dktAJ(vrTAP)l-G0KD1* zP0hOC2Nu=K2R8zC73e;OXtq>W&mveUibrOu2}_U|nW_CK1dkP4J~oVC-$nHMG0YEo zVIdH5#1tp~N#eNWHRG7&$#?aNH@K2)&{3{?nYSv%fTa}0LH9i~I_CXC_^gS8=yxkS zkJL3>_bVn-nWPZw5swG-7J}%A-|7ag-_MNO1%7-O+jXd8v?Y zQZ6+50l4i+dAz=Nw(lI9Bm{{49!EU`I!Ah!Kv#XI%Svbs3{m?bh{LXyw{tGBJ^s}dsh*j@M1C?gxJ@&Sxj^U?7+`m0HcT( z0BKD#C`WYq#uzo1VI>V!V(x=>+`+B>B{1?t{wvL7Iy-gQJ`U5mvtOt#%!9?~?13$7 z6(FcE>gk`K?4&S(cxgDHb&sqJ7K&{cKZkFarDlEMf3d)t?sn0$xRQb|XV_L_J>G!E zSO}z)$e@Vu7dgC5LXMVAaX~!5*iyj?2NqItmyGJf?x_cd$N@ozhvrD;Xf4)Fy2i6Z z;1##ez;44AkT=00?2I2N#oGPHq@o-%4(KX%^;91LV&8@zb}jB0lcFd8?rXHOPxxyZ zDet~4WrE76`X(yXK(My#KHWC9DF{5qua){V;-rz}UT8)G3O6K&PbpRAaw28BmCRRz zu_Ja8hZNj`PaF4C{I(w44Lws!;aD-P-<0p$H+_+j~qDh%u3UswkBVL}QkM$81Qs|JXrD*OHl0r|sFh@Lm< z;dWOh$DoPgKJ@J!WkBSj8z!uWBva(Vy=VZgU#>_8AUo&ue5s7{RYo``|{%)jn*Ru^5QRD zW9k!i@6S5#7C?I>-2|ciofMsN8`wAwy^!51z+6tOWNabqEW6G;!wE-~yzT3ZAe}EJ znB|5&8lq24)?KMW1FVKBUgp1oSPB192$H^^g3^y}BO7KvelxY(LYY#F8wNlnPv4So z$q*FYcTSl&$esI9vdrq1VK;tuw|E?Uvm3p68%H>$KWFm;nCV-wAQB{zue`?Sai`lq zPI*2%IQp;Bd_xMIi_0KaR&Z`4Hp`ffKCZ#)>?cF!iK6yapH+f$4~HlZ=xul9u8lom zX&(#zGy}UtTY_PaDaAHxN9?-QT+HU-re13?xb3UtWH_2}F6fMJUd+J76RPr4~ zJE8k|!(yxyOaUvnrYU$LfIDsnZe$_3*+`}Ukqf;z7dCGbA=iWeq5>u(uBc&s*g?TP zd@|6sd^{eH*DFUWnVI|ze-JhNYH-g9u`m-OAEK-S>`N)e9uE&lfzL$gp}4Te7uI2I zY+_A%N`7)3*heVWKt43MLsa_@BBPpNGM*PSlVLGA32(5d=`BAr91Xi`ZX;Q{t9^8; z4lhU(hfZ8NQodp;-Bo!xbczMCciu*CAPvU`636fMcm59i=B|e_ z7a1g4hYS&mPXGnpan<&ZjD7d)fQcnnc3U3h7Wo}8IX0i+P%bYo|JyOBDSMtHfMXCR z0<#?nD8#5uBlr8;nonEkxcwlIgyU?z?`n$wr3EQ+V@5CM`{^X|4?QXZ5~`VwAv5v! zt#7H$&O`h3^-O}a=zNYL##can*TRQi-qIq(B`!TLo6V=$>rsBoV(;A_V4T8&ijFbP zvKn3=0)LEj&^!=bm*f~J_dP$(+vy47A)7k;D*(`6`ZIHkLM3=QRn~(;;kaAurg>nc zOA|QZ$9K1A+rO7D$G9EgG`5g|@8&Vpw_h`~$zLeJKo|}N`SDnDN}er~-SiynFSuBn z^^g#}y}}p4I8fzGNk%SW?4=*TXPg_#)XwDpRRaG-|4T)%u>Vgv!NkeI@P95RwC%Si zQ2plX5k8e5BRX=v76kE{ERW`!Wsx0<@)M zOZIE}B9yO#AV-Nv`|-R{>bp0j4B1taVo1ZgoCO>L#ZDmR@$wYnP(E3R2_1i%EQCDW z9LatL%9tB{meK9#gmCvnBm_22FkmYnKDZ|&jHCbMD!5XD$WQXe%>DRC;Du-zJBG8M zL38?C((!tUtd5gW2$L`8-n7`|jJ>=MuY|*@f^&8D149r5>F}k{CP9i?{A-N^O~_(E zv&dM(1r>G%(Key15eOL9$r>j{g&J%U%fGx!rm?1 zgaEEb=zt}sfxpCZhHNp!kw0VnB(#daf^F!L>rGh{7LFN(nFj+Ql!-%e7&(gr+lE|t zBPvmZ1XpG&Gyh>8f`{M$wZ{Bbwi{j5?Gcc}IMkQfUXTdWb69gl1eP5W*yWwf2M{M# zf!x3tttkG__QV(6aCsR*I}U*jlho!FHq_T*Aq+GySM0zrjtPz>5KjrJ!WE`snhGon zKoKb)uJY8PM65i(3Z%gUTqT)glqBG?Uwln!aQF~Wg4S--QUjFj!SNH4E#Ke?lC2-y zrpTCwBbtEBkbuvCQxE{!t+s!bBy&q^y$PUlxhjH`mL}Mk+GPrWI-xi?LW3*-a`97a zh6M+@iJ@S9C)?$fDa@4$)C`0y7!7i$bvR$>0ZW~ijdDRqQ zCJC6`KNpc__Yw^3+e`cUvWSw3wV72mEcmGuYm%f*;k(!_9z)8VH33Ro17)DP52h0|uNrtW#Osn}R#dpc%=iqL1w3wZfPbQar7AI)nHCpxD_yX*8Z4iXW$ORJL!k7T2vn z!A0e!*hnqyxsdtD@%{qBPj&Q2KS8*j^3Keeth~P1mm4qbrZ?`x3iYr5dP=lU z&mWVJt^O2M?1Bl<)YW@mBUp`^$$S@I2?uhF5mbEg+pU;Y=!#aAU1zbwo@kp1qFmGc z$aH3idF^2>&0GR06`dlE%60}3&~s88I%YZ?B1R+dfd(N%B6h&QgMz_h1zJWcaFBk`jP}(h)3hz83u)NHq5el$woooTrW;K90>ugSD1rQIjPs^HA_WHbpm*lDz;DK zriw^|iyY-zIv>@^E#0w?_xTe%LJBStxGoVvu{BVcD4r28F1VSlCQ=gU2;#HEuXuId zLE93T6aYc(Xvn-%#seNI|J74_MU@4(paJ-f1qCJBDOE9GS}*G~+x9wx;@@$KDU7D) z7*9u8j0~uU-eA+-Q4S>83a8EF^h9 zJj~PDKo0iuq{XPW+p_LzIG#3&y0h&#s^+RYxZuLw*tYAFM z+pJiizm~P?Vfk;S{&5M8)qC_x)RI`mI61@gOj+DEIWIgC0iJDTdz=W3rHlw0l?6#a zP{d}20uPf}2t@XM*jOwqliv5mS)1}p*n!g z8XK9b;fuqIjm*VkB1+#lVU$1uD}@F>M<})h49`_=s#ED&NzaAb3o-Nj0!opre+ZbLn*P6aqeJ`ta$_kQF#ro|@5!sIlwUxLul*j{g=yi%` zU(KyZ`(=s4-Jls$?`8aAt$j{EJ$l8-(-t3YncWsHA+OX2!SgK*n5Ow90{X3zV}!fg zm;0TH*X0sXT(*0HzeYANSUJ#NBO3~17Kw%%$DQxnL-BmU)H$c5mz*Pa-0v2h1_jA? zE4`K4Sm*M3GnArj#BrG{@sfT-3(05ojp8p)+>j4-H$*m({i|z3gVd6U=y;0WFj+!Q1f1tby=R%ZHVx%T4aW0lxXDtP7wXL=Lgs&ZZ%NKxK?4 z=G8BAQ1G!!Wm0;F-?DF)+>;A_6Z4A+lbq%>{tpHV$^PX0ibHK1?8N}Q)Rsv=<`&)P zCeYw)Fpy{N_(pvc`p{uD1NPU}A!M?^S zJGB~rV&-uf;xH1gNGpSihxJ(ols<+MT~Uz9eS%Y6QrdzX{BOCOi-^O?GWTnAMd zlYx^jTa%$N2Ss*s^6v8JL=|tA1I_!h?B(a|$dark-~aRZWPemXPd~4Ib$WJmdGYd~ z&;K(e>vI^(;DXPV38}|1cx)R-k0#E1`0f%o)7V!! zZ`7qZYMp&4Xa1Bd>uRaz=jBeag{&g6JYPTE-`;Mb!_KQY#~!`x@j#}dxl4D1 ztE%0blV}|&)sh`!QI;Tfha`)}gc=KDzw^9(y87tU*Z2J}F=?q#6tgEBlsYGXpPjmZ z&v*c%^C^U(D*0uq52tUTO6?T_@00uhsOm6V4H&)b+{7m~xQK!y^SH7|m7Y*4y>Wo_ zjPIA3xj!}Z&+Auo4LwH2_i*2rlD5y)S3jYYegY#dg6a```#l(Cxq9^b^~TGwwSx?N z@1zIFi%m*RsBa#k68dbEj<9f2MdA@EWKmxV(SA(;FJyh0Lc=9S$@SDK?Q~&w^pP#D zswXT>!y0d)Q)7JIzW)3Qzj!c2B@~^Db%VNWvq=L*9@5Q30KdE}ozYH>{XJ`0oKv^< zSlvGDFz#LC$QWVwaMY^VBh8tf5^8)$;_H(3)l^7M%h(De90zbv7gN%O@Lj6|r3nDG zlY(9)BHEhQrQmK~(DmVJ*N-rur4H~I*RQbsGt`!zZlfqf{oU5zj1+2qmaXY_nv>Yw^a@t`%~_^OpIouQ|1o0k5pwo^Z3MuS)PKbp2OxVkbp3|+-!Bv8<& z&?7q7s%_B-5l&x9J#<4HgB4+5N0rKd{)%W6;9xMe57!)!DF3V_!HPPT;gu zP!=RPP%3(XMx%{vlG+h|O6c_Akva*Gkb4VQ&pkOTryx7tItpbv*Y23dgEnK60;^O* z>U0Cb5O*ChmPjlHV^DXtMutAyJ5a$C#O%Q%>6|fPdW5V$hFqBlFlE?iwWxUJA>gAd z1{7`!S1yIE`2jeXn*Va5XJTnoOr10dVbAQeHW26k)gpykB$VJh(;z<&C9Nko>KHc0 zG2CB?vOQ^(idQhFV*X{8-yUlxTC>6~TV=mcj~SyMFws5`tPm7xleEp5kXZ;`m)*U(KFrhLC= zWWySt!!$%7xt}Gjd5qppp-KYe&FL`LTI(*l@K?f&>Qik;_f;Cemf*lj)Wr}vr!`?p zZ^o3`j45#)Pcjz3QY7`6uVe>oly=JNowV2=%mqQfHi^>p($Ui&mv66{*2qzdM2K|F zHM?Fb&pcVGE-wE~&l<(n8x!JKcO(tM7nHkA1d(A|V^X)Rz32C#Q&CjGO~`wcDFA~n z5S7_yj@g!H2_97G7UUs|mq|=_%9(kOV$7!&?5$v|!u%U)F)_lAR0@oFh!o&lF$xtk z^T1ePDpru*!EH6!dL=Mh#d6W;y#p*pTFpfII=&cqToKpVLo*21#_(o0Sl15F4VZMw zMFVmda?7k5+;W^kB2FQ7rAX zC@Zp3XN^7P3k-8jd5NtGlcL-_E8JA75*9|kda=@FYLQKnOR#0KWrV8C@-$zZWBa~F zRuCaX$a&~%?+i^WM>tnc(2J=?F||6Ei8N^|qwZwZopeKN?cGobr)HbYFj_7dC7WN# z>QJ%-5F~vp#Z|SfGkDFb&C)9l*5P3;h7laV%d#ej?Xr7a@2Rh%kZbn4kTjceT2j7v zSy6p+{L>S;WnrbLAl3aCo@cq8Odps3{R+uiu^A#C8qzPxmssgs>ztfiO}+;ensTg2 zsG4{&a(X?vlkY3=tzwa32(R$RDtrIu>kl_6u#mfJ4M!QEK31CSbD>SRa^3)3idUNS zz5SqR?+Lv-N2S!F+OqCe;70G0`oQZ&q@8^WkIUg?evp9}$Q;~RA_f;IF3EdwW$-;1UQ+6dqxwZC zEO6r_oFb#g#*h2zik)rsHFGF3*dlj6(FtML-db8ey(0N(HMY`JiRD?x47D_d1|=bI}gqmb(Z*r)n9-XMrHVdNNvbE0XyiKabexNUzmxRz?+2IM}Aq6 z%+t+`2X!uPpNZ%Nq4SZ9BVGm-wA>lw^lpynBv=5zMvMvnBOh=$y>8iB| z9;Rn#G021Y?eu618#n25+8a`?wa|WcZO6{xN-&P7Q7Da)#s*c}CeoF;Kvex{DV@S-NTdK$ z2Ujs1OG_nfSg5)}p)IhxFcz~3b~zSGS1}+_Kcc1}pK<=1u@3%%bJi-x+oAc1WXeE~ zND=NCfdazih^!rqsh%lj_|}BY%0=4Tln|t>F1?xeM3q~kP;FP!@+DK%AVzT3gRY&? zyizz+2hKY`H-f!j;`U*Y!yuQD$k8aj&4o-9J_vca zf#Gzw%K>P09=jWayfm8o%gFJdScK##hU>LyBaM^AyZ+YC#rLL;}C9h51Fa`DN(@0sm=!EpCR>kQ}XWQ-@ z*Tj1uZOMS`QBmWSM+ynh#S#oe#F@TEH))Ho3j3-)+NwrtIk2o4Dx)R4T;{gi#fsn> z`_clZ`-0v#9Rb496yuh|bJ4%QB(_d;52tARlG-C&u{LXj-^*HYS!}(i2MF%6IRQ8A zNIz{@M(bbLy~CKO6BzudW6hr_0~T%#YsEm92@8E~8&AIckBITkpUIhWLnO(0y6mC$ zNPVUBmWiY^uLdM;T8F$}x>4qJ${9Hw4EgKm>!?8mCvIgBG z2cL0CfPdb?>r8h?2~f>i{RZ$26}IDE=o{|)YdoOMJvMLw4ioa*3Fh9~Pz;#god`h5 zIy&r$al+n$zx(?^?Sx(KhBG?yREKFA;d%MkI$YQflpHhi`*UD|-kq@jmbhOacg(jv zJOx2f-(ic!+V<2h&C%k7#~dD+-^t{ALYFf{?%>_da$^UWjUd4?)+#DNgkq>l#x?^& z1ibxw7j%lWRiwZMI&!d9k=JP+3Y`5eEexT=j<8V(GA}JG(iJoq3qTWvYOAc&kVwbq z;LF4(~azg`=?lhw;&_xLfQj}{vUy8)FB|;fPD99 z1MC~xRag&NvZLY?`9SSPCNjuUS}B<8$FX5rnU6%x*X+?D{aksoi6vI<`j{5L<_q9h zN*QTf){Nt5z}Gj3!y{m!I8#sui=RGVz50xw3=5pkkO))zTF?;X=oF!()P^dV7 zSc|KredFiDS{vQD+q`B8XxpbtnoXE8mr9x~lXE%>`;4iaGXTKZ$RRfpl%LLSVek#Z zw^g^W7D0P8qe4?Rw@BvAoIq2(?4tzJ3T_hqI2EP^wgvp;S8MnVZ`OZ4astLSUQ>Jz zZ;O7|flRm<1aC;i%Kccr!h@pRkpAVa`Ys;y#;b7`FX74*zP)FN^oY9cHFLBIUrzv0 zCTTX&g{_a?o$?)=jfI6rZGOnP>GSdS`!SUNm7>CR5o688nXDd;od6h?@PM>_(FfP^iX6KJ; z!)v5Sa$l<98O!ND<*es*vasF(varpr%EEti8hSiQ8QlQEQmZ9}j6+Rg>R{~{F< zd0XXj!`tUOF75u2g~HG~8LU=ge3cTDJ#EH@&Q*538!fG|jqbsCj;BdT!f6*zz1VI> zL)ybS^}p-I>{K=Jo1eLarhEdZikn$FT`m1)corizM%^

h@}?sWJZXhc{G<|4(;= zo%R2tqRGt6@_+1ZXldK;tRecX*B>0yA>`$Jl?numg(i>1LanGJ0JY&$L?*TEMo*Pq zkH!6Y_d6d(?eMPDwMXfqdnQWUCNP_u_1T-jeVkmMT;16mMl9=~o2!Q&h8m_Q7)CWu zADy1u$nLHzuba>J{mM<{;T(rh>Za%%`zP_rJJl_WU>f%3kO@@_A&r@!a77FG=B7c| zMKzH>%c2-*L*@2MA9)I1+(|~fuB66TOdFyR??NTLz=?58homEoY!sD@aN?T&CgPEL z#Rnmri^@mv@3Q7H9vQU!i6?8)Gw&UZSST+93Icbd9!7ayl_moxe@>a)3&@|Ls-sm4O&y9Wr2PR6<9OPQC{wRdb-pR1nzf#1H--B zH%*}stT-E|T)e0I=2v(mq}zB#PIM+prIHGNA?t6jN#h*u(&#Np=`WhO77NC<5WNm$ zGv+oNW6m@Q`pA^Q3IVo$;h;iQl)PMjyW=ytHXa%1TRKu}UbGGigZl;+2E+!05=<(= z_As~5Ujo!`7(ftQj{41*GzF!9@|`#gCm6?xz-bN532ckN5oB2gK8XMf2ZGYjl!y8? z>Q?(8UX13Q)&Q|9`NoJ2n|Ak@SRfc>8gPh%Xy|GyunoZ-@c76=OMidB%upZz-UnM0 zEksT9z@R-FjfR!`JUm6QXc>qM4D>=U=tkYogNHk7j)CVG*%?-R0KL+);-UI>ENZe= zB%=ZjM%fNU2?%Nt6+M2NNY{e_0~nag_%`)kI3=`&OfeeJMYddt0}mq=nY1l=maY*Q z6&5P=dJF{q@5&_F{@0UGLxzq-1G%X4Mk$owiL)`r?n5*jG~lEW`7GETh$>bcAH6JP z^`R9}M<^kTo8|=#l*XgdcE7V&6$~U#!K)kz4ERV(!qH8qke89xcQZL(iECiCjAA0F zxXSVVScj3dhMF!RcUdg`XAf;WuXIV^q?(_gvr2eUg-4_wXmUbP1fEc>RJaqDOf4W4 zGhZ5Sygq)~WauC624NZFB-e@oij@>gajMP214on1FhF@IaU9M_&;hOM;(kZ55Yhk; z$s-pDv~aKx_+J(j9HxFy*#zDK;|~Ud>XCKrAD-^Yc#547g$pB9PqDBa9x2rzdf+!F zN2+E^@bgGW%6CsN>JCN`Kcjvy*tdv0qFZO*YHWLWGo#^)(1v8dHvg{h{wVfHQ#mUgp+&$oEh>*&j<-V6T=fB`5GT9Ap>ddN0N*q zf6qyVnT>rzPV}xD-8MYb27{H2y(;W{Jg&?Rf!K?zICe_tS`-^P0%U(LW;fBKq1RGz#^Ckt#)CT$wNKU$64l zo+@=)sq+1#R%I8yT!K6IFepO70AjjLdRQ>~-*?GCAuIdc#2NSxajFMwdYLom`3t!6 zcO!QW{zDvx0frxrYbw?=9#TA0aX~Gy7VZcge`YFfqhMt#@U44<0MobZZ}1ylDQG+u zC+9nkxtx7(9;xu5in9=mON{;fllYE)OT3-^lQ4hxDcXE^x8qZ9REu!jY2R%-WyC92#}o)j754`XhMz@|~hysPXEjwk+CW4ew>$9$WKhD?IsI zyK;k-Nz>Ib{c6{P?famW&Ia1c49}RBC;Pk+if5QbF5ghXFz&A4c*magPsRdF_-uya z<-xHBf}}Ww1b6w>pWvAdJy*NKBnf7Q4<7NZ!)^jDEK4v3iNddtYVNfM%YeF#5(bim zU!K;YXa`qs?mts*Vj+cDvWkeGDrCv_(Te)D7p}biOjX6DYIH$gpYKN|JQmlU(z>k_ zj%iAjmgW?3^yB9l`fhor`+{FT8ij7aon+6}9t}VU3s16ni4WpQ60DfU?B{p1rWLuZZnxDL9tsjy zepKRe@(xC zM&tMM%#Ks?aEDU>9)_38<%{e6HQHEN2ELv!?^j-lR^BrRlI?!}RF}(a9{c;>LCI>i zy&B`r%OP&NH=E+jd7gSvKjHo|)wK+%h#vD`yDZA|LA>LmP>82VCuSRKC!&55dAlur zQf`H2nH&%$!5M`(ICKp^pld(_U;A_p876bghDN^0VwK+J@;TRN76`4;8-v9NM#$a0|{XJ2~?| zJ4Tybw|8_~++};`NWqN@vcIIz(Nmg=G{L@vAjeD1tGRjFHgm*H$WQ9#hWFjv8uxTg zlf7^S^jHxuDLGZhxP7vTcGTP|l-{0**Q)89D?I2suNvlID)is$iGJ+Ve4?(gdj9~P z@Akj{Cv9;u{!iLsWa0dOV2j}Yza52{afO*xi9vw@RLGba)Yv%`MYv9g&KMXJfrSl7 zn&jMx)6?l+I5h^g!#{5T(avXHUsS0mDdo=RT%a6On9gTilp_(u#(cp01p%z|dXHUXQUO~@zg z=+x!w1n2<9oLx=+=OGyxnf}Kq83`C!SUCT83l0+j2O~Sv|6VZ@F#PY3fRmB+{}?@E zTR>G-w$a&OAeLx>l!T?+-Pt9Ap8J5R?;Ij|{^eoShw?oSlst znXCX4=Lr10H)6mFFmPZ%A^yOJ;J|>0@VuV{Mt~Q9p#UkkIs@I`1A2gndWMK}b^`Y7 z>=69{6f!6V@GRik052SXR0t6gaG(|Atc*f~wKa?LTtCet4cN>A9Uvki8vP~1B{+f& z4y*}42mnVkfOGO+Tfn*iT?o|<5`?V#ry8KOixcRGbawFY@NfjqIml7W$R&m19sr7M z0J{h{Ak5&J0KfAx2_Rp?xDD)w10Nioe5iN!H~XUl3ICD+*VY!!(FsJLV;F%qfN}={ z(4(w!BIZH30U#JXVMDkC3FAKo-U>7zFI)oNm%9=OD2ibN_+;GQeH^SYG(ZE*L4tGt z4-zD03ZFtn?i?eZ2aO4kIjZk z;{&<50#{D_#dC@X={o`-`pksp{AsUdI9xtf`9YjzA!t(woYcGF&;83!+xVJAlg7aAqE}O(DoNi=l}8I z4?PPB186CDc(5-I9S|Iz{pD{2f7#^bwp%A#Cec9rJb=7RZ3H z0DX0sgiiw)z&;<0V=Iv7uK{y#6e55KPZEZ@a6yI;Q^>a_Xl_g=HU4o{(<28GX7o9R=aD^0N(gZxFkI2f6Y%13~>V4 zG?tYerWM`mTH&?rqev)xIM~Qa!#LPsnlUqU$P4~;#=o6|WC?g#I|5^yiMM9SKn{F` zC=0OcoMi=bM=%CNy8X`d*#{KuBGvGBO3RySmxI^@yPfWK*%nOvqo$VMVZo%BH(@_K zx6)4%v97)J17c5y?~DpOp0cutWSf}w@0?Yi2N!>7_EmM^U$FSviC4DEuDP=x*SUko z3Bu76nXtcz|7)8)q9DSeM z#h11ls-BW&&+w7Uq2B5V>TMI=MWl!YxbJ{RbCFl)t5%8~Y zf?S6aN!z9fhIv$U|L6rm=}P#3>|rsC;zgZB?=N$^&WDFF@;Qogou0wX$WhxLi$9WB z?XvvuUPooQHiWAqKN;5WN&ynQYe58VBAQrt^-q?Yz@@|5G8_0?6JuI|F|$W$HQerv zg{M5ik1WhZMQjz{!z0?P#;m^d2MJnP2AN-7!Dr(omuifWYmD-;eLus1LD3MZux{$C z5zMe*kr^(uL)Jb7{(x>Q%p}nw986KE~A*7 z|Nis9-+b|mYK*lD<$yM7H=?3Cn!>Wxc?7#wTHJLhI(uqb!BOJL!)YjqLPTSY_`rW1 zmgxP$_U_eAkL4+mIhO zY(&UR1FJg^LF$9gWQ)K88)5ElsywpnY#tV6-H{eM-5EpSDg(KQ&q8J@*)L1rLY{$J z=J2L_WS?ad05`CL<==lY@D>ZXyo7o-E8H6u`%ZsQ{n5*niohLpC(nZ7*Ffv9^LCA5 z$178fvyDW-*xU-tB>QTEHBw?xd}EMtvkwFrRl{+o+*;mFF$u3u9~TXgJ}}rAyX#)b z@b1dX;@3%K=Aj8nPs-9%&9)Bh_akl(YUx?sAh;5RJ8DIOa%Z#T`Jh~DcM%E`e~tn$-AkgBf6ZijeR?Bio?~2PKaWuNpT6Z~iX(&a_ww$^X!+o* zO+}22<-Rj7F$^?C$@-nfRac{vE+%AF(9uzEGGq>v;=&ugP5Y?7UZ_HBe5;mJI2Y{i zNE=7%hXOmYxRGM4jjYGmeE84ETb?wkZkZi;eD+W95Z5i^Zx&VWVrd2qikb}H9e4`I zwozuF$!z25>FWD={l`(#iUw6kRfIPr-ti23oMNq@iXYz)B~~Wv5elmPX1A2$_N81I z`pNYW8FMJ`Q59$RO8l&@2GS6`7xo`ZT>(DU{mk^aa>?DtJ9&SKk5Ji>|9S4W=5luZ zW7qIyqiTez$+!jxU$bq#p>v;e3o$1KlO#NI%qbT7k}i)w&G)et;@}jh+Ssr1o;xu@ zTKwUcTtKO^<*7{_cMV9XUhw2)gen}+OsRkBG_ab3`|&!X=meItzs=w#5bzSZ)uZ20mhiTg~g%W>+R zEtYzj01{kzehZGMW5ZHT5p7m1uF)g!o)rJl$2p$SYmzA*I-6Sv$;bCk)6qm#nwzm| z61j~LvVZm8(;OFq82;?hW5-j?tz2Q(jZ1oaNNm*4+G!`LaqyK>(Ft|vEMx7HVcECz zMmX^`|Lp>Dw1K=aE!c^TJU>V<$1D+^OYKY3ga6J6au9w8jUy-)g|HreK1S*|p7k7J(i%-)LjzuAt zIkmy9CX{?NwV(#c2T{DlBPJ=x%V*}hvnBf?r+k{(=G_OuKUH1!<^IilJ{R~75WxVQ z>hrl5m8vYzsc#YlBD=DFX!f`{Ur_@3j=Ri9##L#Z zngkR`l{jJ_y=3@e&XEW5YWk|zf*l72+|_F;L`b!P?)BO$(EHv@F1_&6H}KT1IAh8Y z#^&Ig3LRy z9BVAru}p~-imGo#Bo%4)v>rL2L8n+fc}ThTa{p$1t zIoLzH?c!F;mVOA7pUgCFhI=?K)XHB;I=E37FMLHM2=KJlzKXxZI?k^o#jd)6d{d&G zmOVig)A6_1N0e_XexHXg>?W(`%?D6JJpM}M@$r1X#9duh$)kFLJKGSQO>cfh-C znIl` zvwn!&5=ybGK~ESj=QXmC!$N3}f-z}*?75p0ZF8^zc^U1WXZOHv1fnXXc|cJ0mCn$1 z{?PZ?vhmN=d#&+frfbRoHX>n8>`qvl;@wi;H%pO`@fH@eG~7ndvJT6YV>0#Q)qj;^ z*{RO?X2VSg92HkilWs>E#fVfYvy0TvbGh{kb4cC>dpMx8T%!0W7FU=m)rbC6s6Yud z{}F*I4EQxMstA2I@~#)6vY&lr`hu{eM|buR`-tu(Od=E6(I!(Ux`i1#C#Qvq>NyIV z$xoi19-owa6Yo3Ft1n(ucPm_wJxiZ*A?YzetN)9TbBfW02^#d6XKdSNY}-6z+qP}n zwr$(CZQJwC%zpnSo9x9Vd(oA2Cw*J#>U!#dCgcgEpJth@J=BV3b<;(Vm!yUdb0ZJw z7_$g_=G-^iMdA~V=%SX!AT^k-hj$mr+d5Li3CclbyEnvvdqaXU0q9tdJMCxF$zR4H zDM0CW2_tR6Vc5c#l5Fk3K2|=28_1XY9EDN2C1RYl)h^+gZA{BKTnW5|+SIm*%rGLW zY570zg!!hhi^7Al!wl@zJgdjvPdzl969-k1S@F82ZP!(;d1Fd&e!LxOlu+y|!m95_ z%_CtHV^`I>C}ElwL*>dmtf?41NV~Nb{*0YmI%dg63|WIK!wym|$nPrYdWJZ8PR7i+ zm@)O(uFy+7=P;{mc%s7;N#6BcQmC{P^-J1mq3r0!rxAOpt|NpCo5_7WMAzp$eFLWm z6eqyPlC2G{q=DEuBTX?Ks2~H*?_Xv;M2S7fU)F;7(3RY>eaJK%Zu@&wc4|l&iF`%{ z#T&$NE;$+-Q^ldiwDn{{Vrc=JKuZcHc-yx`TqDUn!X$x_hdmZgWngTk{{av`)7tj84}m}hBgK=+e4NPxMK1Yr2>)O)fagsVB)@wuUE)b zk*ox2=kBsNGwbZ%6x1aKgr^`p6eD)kItKJ1wx`5rX0%QXG&;^Dm^l4>pa*GC1f(d@ zPi3lyX{bWj$Y}(lArc2ZMe&h&MqmexBA8F90ft%Lt)v?FlGU}7`3pejiO&_kd zY02sF?bk=aMyD~!V8`}O znrP%U9P`+AB9c*IXSPSZKQ3>RR+|=yCqJpRF!lD1rKz$!jSrWbh-LS`BUB@Huswix(7E-Q@ejjTZOiWcI7IGXF3iST$=%&=E!sSZc?qzl3+yJf2@ny+H+}Lukp1gnn{bw3D~-&G4{yF;%c}WygYCK zkE;~?LnbIu5$}O|deQOUtY!(C%kDO?ka{1Mr=y*@96K$F@UGsrG|LL;%4v(*dHLIm z5;v*r#(I4|iUn31+^5yNjy5&mabg*=zOu;tP{vfu5SkS#uHM*+BK(o&P@M|OcyoGGF2knj0mfiD4a4tAI+ z++#~J(-b+DArh{ZxSM0(eMMyoSf{4DZO|n=piE%^m>ZQm+X38~Bqc~mM#ktf{oRnoUPjd*x z&#|}2*=XbvwC~-A#h|v)lw-dmWQ8|#okbJ`r*x-$VCL!5r|fTB}oTmruqUuYp#>;K&lj-i=Wy<8*;N3Kv4pZf&yf6B-@0^Sx(5Bu6i`d`)0&)EX96XgMnVTu?)5!36h`D;as-LW?fOjnPtxtH!Uqs}&rb`mS{+}(DCOulFw;yykCH2i|X|1=t zTKoqNgW(HRU4PDYIQix>^6vUAn-fax+wK=QvhFWAp)oVGOA?kVl%BGN1ws9Uaq3FI zfmHzMmkoGhBR;p^4Y1ZbbF#0U(v~q<34h^8&4HJJnbkz+cF9(`Sk-F=o1vnpXDA`L#l)fq!#`7K=d6${`j zlSg-9-2Ix3c!=oJTfeG9+mi-4zsxH76DBUKAH=`0S^t)ut9fIP~X50Q|wz<9;v#-V>;z-X3RJWj;;TsDU6oTq?G%uIu*eri5jjnV_Y@HRQi=`P3^}zBw2vVDj z`_xnTAd>DOR_QQb9#J}pSL5m*$>T*))?`;{<79>gWA?iHtPuV3>MPa+j&_;u?c7~|g*_41?I-kT8qES6j=n6Vb{uJ@Yr*QHxX{S7 z7B$i7a3t^R2E@&u{&lNFPOT}g?_Y{V@>Qtwi>A9**ti0%P@%1hRR@R{j1M3v*wvO+ zsI?5yj#{a9EUpkDXa62(K_9P36&l~wi6p@y#5fB%Ne(A^<{8>x!_TUK*qmExQKiIg zhU>*apeEgREUFxIvDE{yhy^1wE6ta93I{eesY8&6^^VDCqL8F&4*%GUC$rhJF;qwY zc7APt^<>dfY}vF#zpI*!Ie^ho%Hg~QE(Tyn-AX*0zqrNI4F{&l_K90qNp{7YoU zc5<`FuxrhDnyo&pn8>B4Sq8NY$}1gL?od^QvO6+zrsd+{Md8wNFdE8%Z55<<$WdZu_gUydj{q>PTdWqCu-DrCEQD-raIg5*CX=H#(wi4D%fuG z*+qcsHE*JxPz#LKY$~R5;Fx0dXwVcHZ~hY>q=ePl<2*SiVy`1-{GM+uE%KmjfR`Wwvd4JjKzmK{52Ri_L5<{G4oPv%2YcRHSWlHd0S|@f(MTB(DSdA6j>aIj8ZH ztp}(;LD&*V$sa`d5iF|a{cPpiDRK5NW%&_iKyN!_=KhDLPV_im>DF1@hWep>_Crbz z!1jnm&Ph*y#A{+DW497La0q}_BrCC87MwXc7)5o`_0ZPR&%I#E>XPPyz0iStf*XbJ z*Djl+g|#m$&psUC9?Y^TGb4Z|%Ux5LhRgp&O&r}CTAq2ML)7!v?Z_&eRp*R__XRJ& zN-X+!K;G_{$yJu-x22zYQd{)?wKdJ&{^tARkHei3YcM)J6bzGW7C&55{7Q zYgEw-jxE8|0uEgVLocesbkCtK0FH*~NkYWd!2I=5*u{Vp0e>~(>87r|@V6yGh5;+K z4t5=9SJP7@ZxHtre;89P$g4T!a>e;UGDz`u2_J6kD?0L%_1=6ISU4|GYFvBZ`*T01 zLTm8Txc3lw?TbH0*s|ySmDXib$|!~xB;kq+&%b((Far-mMd@Q4J?B>v62PE0 z7V7z*V;TzS=?DWqaFvZ)cXJ82feQWIiXyVX>TA(FjYcxd)$diOlj zWkxsG;8!zE(`B09Z@4^Qm{|R0GdHZRa(cCfc5f{Mm17oz>E%^w@ zyd>-SFcbC}fl?Kgcz@xN)^;HrS)nA7XOEWengQ7XYSCxl?=6?HV<5r28iK9P@%6Mx z##Keg_F*x2C7jw5u!^+l1D<~g-FM=pQ|@iKcx%>X&tre=w_0(-Dy&;3&|OPRS@)W_ z3<5CR{qhk+inv-*V79mEve%Yfn*H-;4-sXJ>mUqC+%9(5M0Fs#8BYE_0Yn@@DbUD& zw+)H>QDS~p3b}I|r9N5ndnshCwc3FE+FsQFX~vSyOGhZ!K|0S-QvS1NJ%%&* zgiW~_5h%ttNpg6VaRqG5Acu_!iv(i9xiDpOeXD(42Mk72Zv?OmpVO(%=5LuSk6!UH zUdJ8Kz)QT94HZw`d5Nk!MFeFZ9&05d^q)bas&0A4>S5G8@^2-$`R#WTru8d2J|oY@ zQBsCpD}cd=DalYyKa8@`O^ zYkVBzc@CfY50JJ7WQd4&l(r@*~YOhL0>4QY9wJK6jy+d=9LCYPh`Kqs# z8vI<)t!@-?QC`2-BOQbs$?2yCqy zfO~eOoM7|6n`MW&I z-{II{qXaN(4%pm-m$bEK(a0Lg6UPxa6L5mRF(;WJ53CFJCM2m%eBQUbq{Hlf+f4+= z#w0}!=kBnSeAWX6L(NN1E#FMkf!#*X9VvBiyIt%S^f7oum3k&@ZB7XlhM%$dV$-yH z^4{!}vrsey9?!mzJy$$35M%tuwY5o@`ST!rUKk1&0;9|be3gMJ~hg}H>BYc{Aq%hG*! z9-cF-WQ|(fp9Kf%gzv-x$C4ETp^oHv2`5^bqCIo0WyXb}%G92k#`0OYQy1VBqkW%; z($B2y?Pv;AKbl%bi$O&|d==y&0mu6+BgIjPJ~MkYH`Df~8nCqAy0yK#$c1~T-=pc& ztqap|V78NYG;%NoQb~Sk&WpY-bJav|1JN0LRvCGK_rZ|%f?_fO$(Y#CY^L7~e_7jq ztxt)O(TqjTk%tzv$81SN#ioH%BvjQplLS$s6)ryvEXm(lYC1lkOk%&Tf2!ZAJSU9h z@4I^ob-g0^H=a0ZGU$^;Ez2Pni_&_JOrDEY?>N^slSvg}ThPfsWSDkUEamr9I~6Tr z@av%9H!D5ouJRqhh^Zm-Ot8@xT>7{J%?QbqM(?Ue5R%;>h0`CWTvwQo_ zm^oXpY@S04#<9kesCNY|APzA)~K4 zw>Q>C?UvpaO^^f%0<&5=k7a~{&2$gGw=9~4ok z8u5Gt@Rpc?d!UKx>O@@oVNRC8;75S_R$oc{6Tr>nn`(Al5sO}>4&euCrU1(U`2w+k1*YZxf z)S*GuBi~>|byu&rE_@5=$!{cxKQff^b$9LZ&Ju*?WOgsA#1BtB%^co$tJrL+(OS+% z(6TuLW>g}OUjr%+glCny467%jT0f6>&J$Pw9*d>Obl6O>PUQmvQyHBoDO|o)f=?A@ zW4qkjv2dj4S23`mDg763dEpfNqI^Z*#i8=N*lE2)UchONI1yIt^F8!U#0xFN$o@y0 z;crNV`SV%O8&MZGZNIsgDAK7@Zg&A%aLyOP@PB0&{S*Z~V9B&o5YO3|#kr#~0392L4MR zkm2)ve@P4U39lu|!Gn3RsJR7zVCYC7M;;NTw`KlYH}TR{b@r~i>dSWrzMTl^+0 zkek3PxYIQQ3~|3O1B8a)L7XrRO=6c!h>*zulS7(;D9v%wxGv{IxJKK@pZXmJ<;`annvwMeS_}<;Pc(}mm@;3fH)wKQc zdgi*b0%{CE5H7%9?%!Gud%>d<&_Ehl|Mj)>rLCYg`4{qr^`rPdE`ADDZ-GE#%N~xv z>;XT3@2PW(K>>I~?l`~c-*!V+&XYE#Or~kS7C@V#(BJ^x{>bDMoc_t-37Ea3BP__f z2PY8UFP=D@`L`M#?(h4g@Lyb@K)=*4XSrXhjh8ws{dX%tOyFNU>5&5q#{r;FKZu?9 zptK>t1;W|yQ~U41<1hP3UlBkL^4pIl(V?N~OL*?SY~WWMp}DQ~>3!hU=Yrr6vYzHw7DV3H@)r@qU+0_P5Tf1+AR8#}+wXTy)wRJ-3Z>8f zo8_Aa$9=B%t_=6C_ntg__+J=#)EfuYZ~MgHd$Ine_m;AHqxYV)`bBW$I|%{6<~?!& zVtC|R<>$WomgQYIeqi&Eg?~fjBXa%=W>8-^d9Fctrr_YeC^r|g8wR%UzmD!)bZLI^ zR}(`=2!Of-2DbpAJp57q)K?4LpCP~QLH&B}bzB?Y(E)9a@lvkxmrlj(?HCuQ;}_EJ zQaNOjsx_YGnGe{T_svab0@%7D)*gN62j$C z7OlCHkw{Nbhu0yi9@Rf8b=Ey=4}K00tFJ9$mH{`)c{8pKDE$hPBfYMd@y<1G+8;ht zrvF+BRe|zI-@WdEFFmTs1%3mlKB*d;EYNVs(J9Cw(0A*2UYCcC$n-|f2~r23%$ajP zUbj5--zv4|Sr&68in4TPa*AAvKFCtRu-yd@X}ZYV5ir9|x*;EoFhmI-=*gqZaD_JO z0u;H_m$4oRhXV^Of{8jPeiMe*F%R*WPi-W*jP8D?is8Aa1?}Wa!&JEyR9~Y za2}GWQa)kO5lzuRfShx$epsuV=3(gV?FR zu%`DTu;;NJ^FPtQpTlO(%IJZKw)V9ZZiJPb5aNsiuz*nu(Hx>^W6${7r9G|KH**>o zdEIAUKt|z=!b+r27{#hlo788nNB(+X!}#h9PPAE7lU!yNouE^`A?Urkb7V~XAjbHU z;7AvgCSA<6R8X9k-V*8b{cxyM$^j^DVC4r5OhEtk@cp%#aZEw#8MvBdvJgqjktmA6 zc~?FRv_keUa1@ll+>VrW+n2xczSMl1HMES^=7`^)5#*WSAHy~dh`&iuH`JN>YNJ33$V4$ZP_aeyYq8fn5 z&7~iNaOSKGt~l9>OR;p9Ja8|>mlq|fo1U2nyg;EU!*58CW4Ie(<$WP&TYPOcrpG;8XXZ@Dbmdt4;yqEBJNSO&T zE;Q7F95Hk?@J*>LolxJoi@DT=Cfy5Dy~OZ`&@;S{@ypxpvl%Ym9*T^q8KT=KuUgrS@#uc-DDBs6K=F1+C~X07^?YGWw`*urBUbjq$}YGjcI^GOgIl= z5f(67ISpnQXF*PIo757N3U|*tmZUQm;3g8Vc6_&0ncNKZR`pFYKbWS-{)1H;dZ?fU zlNDLU0rXaE_ydQ2;gmDkdvnXJoiN__}jo&;>Gz<@K9REng zNqZi$icoz&Jf!_%;=>@7OPt`8+j#0nu*k()rC>d%oC`S1OM7{lI6ONw(@1f6i5xOMoX3o=s> zp~e6kW4N0bsh37t8D>KWMjqEGrmz|lT7}|g$e@X{q!(!H!FF|@+Wy4M zkbHz1n}stU^wlk-QzK(RTN`=-ufhKWCd^)qCoV5n=>YrXLFKu9-t6?XRw+3K3RFuJ z!0;PlfFFzvf{U!%o??~h|$Qv+-bitWI_`v#Dv0^Ut1 zv=ERBJc5ZfIxR)OIhL27AT}x5AODKwVT__vUljQdt2;%W$ZJBVE!vz!_p*BLfNJKqviK= z%93te2c%F9tln%A>cL>K-EZ`v9jY~D`P2c7vmdc`eqAN3Eo#s6vX_WMBWveW4p4TJ z>L~u19p>LJEZ*dL+?=*sf4ko`mIQtgWD?Mo34S9*K+-`OTI$Gu?H?1JVEN~9tK+~8 z=htcYMangJu;My(5f@JejG!V=ymnz>UF%j_MRgQK$5w#|19MybQ3EF038omBjkkQP z3IyAx=OT4Doap41iRv(QS^R0_?yZ|fZu;Ft^hAA(T>Fg>@ci?JuNXSn(vBVI=rm@x z*CtmcNIPo+8+`}o;USD-&VH%`4Hx(#W`zaa7J=$#evGBG{3(=~IF&r%e5VekdwLJb z=q2df$45(+k2AFHat}D;5#t7Mc}l=2%u0D+?@@a)&i3Jl!mcJ*f=9G+#0U7%otJUV zQp9UOHUu{8m5)&IW{$Y0=`L~+FW$RQ_KqnQDlXw^Kd=l<&dnn*=Cwb1JoD=pQ>bPt zH7lG9>QcYy>47tp%dA+AsMfCr5^UxBV*M+l!@MMu#s8Pt>MBw=Q>R*W0#DAE3O)v^ z&d;>#yxpN(;L^!}vc3{X=X<|=!{&*eLBkm~ilSphO^5|Wl-d~^zXNF}8gUU^r7cd4 z!o+H%T1lu$fJd#7tuZdsfDvAB)(_|7+>eFD1PrfaMrT+n4G6~4afiTcMJgjsrSnrZ zlMj77zP-6dqS`|zN0uEbnVoF^cp(Vz&=bYU`CPeltAy*bzYdGb&8e9SQw@Kq8UYD{ zs25K@)N3G)_Y=ior5L7-)$Tq_eVJGarr7aKX^ck$y(qq6NB2QzPT+i^PGW6&_~<%u zi(*>4v7M~UZ1|5(gpmxgo5-@V>jU#7D*6x9wxDZc&vr_&O7f*tbI{EQ@8uqOwJJ-4 z(you>`j!)CoN9C>|L>xd>uG(}yG4K)olP@{6%04Zy!s$3aez`e>-4WwL1e*Cc}OF@ z3!r&ATS?ZJ%Jn94hVJPGwR^_@PmiovfhH~XnL$(;)|!Av%50a3$$wg*(EQR}K3Mcj zQCHi&>|B_Gt|^fpYu6uolR8K|^|qCZJyGi#A!I64(o3pcf!2M3k6}*Nu4*pmWfL$O zW)?GsZbPg_J#xII8nCfXXt-Q0mv|js-C;`pO=nvY3{(B-guA7&Ngk3_cu#GpB%M1q z8z=!}<`qQE9TY_%?#eg#6$E{~uNv6W)P7MDc)Eyl9V~%Q{*|SX%9SU`OMyawzFlF%Ip@xAxC_|xp)XT%H|Trhl*rj`yG*$ zaMP8Ys1E2>C?(nqUJb{8Q>yy&nOTj0MXr)@1{FOf6EFz`o5HQJqj0Wvz1VJ{;5Q@W zCy$xw1c?)IJkRc_dMm*p^|K$WC5io65QjAv$|@76J=Jb-0E~#%?N86ZZA51{C$p~z z^=P=3wCUvpXn}A)-89aiY$Bo4p24)&Xhhw3c?dt=6PL<{EmRwZVTcV@n|X;yH1c6P z)BEpYs#(EfHodgc)x~ZrI^a|DdAtuz0Aye^U9W3TJO$@b_l`*Bnzg0>5^+*r5~UVe zG6BV{Pd-84>6-HvOv-q2D{WDRH~9*Ey^ltd#gi*92!?_hqr;L~?Na#QPO7)=C$QpE zx5OCTZ{FggYl;X<)_%2E55uUMr!$jCW3s&Ep_5ckwi7gBw>z4S;!M0owcoH-ILXQ0 zt(23?Z50>;55n+PA5_VWhUNEVo?FSAv`gO6Iy^ExrjqEH(tJ((&|ja;#y8%yG5Oe~ z1G@l6)Mi8JX|P8mWi=Coq7-tDr$6k&6VRa}X_fm{~=NIwz zA9rEBeYylY>NWQ0>e^8rc^0(P2}kTc%-$l#?BXr-H@d={5w3^Mu_MSM`$XC&kkies zugW!kj)Qi2B;+1qpdDfI7VDa6o;Fc);|4IvHHv5K0Szp--evSEZ3!-bq_lXu*7NK5 zh92jeQYU%oKd2RT9o~qHI#FN!ad*dz^R+Bw`|thnZQ9=VO1d2ezS8CX>vn=s6P;?m z+Lt*mccGC-W&UD{t*&f&`6%DelmMO;hAjG7WX_9V)X{jzkE}3ziuElSaM?jZ+03Zi zWcoCPf9aV}>54BKMTMOfVfZ@x-E1;+TuJ7qP|?*u0lHH}TFk*$|LC2J;idfz*OfN1 zt2Kd=hdkdVm;AFKz1IO}K11gM4kAA#JnDWeDxDmn87n+A&;@@YX?mpgS5iI9oBVpu zrMvnx6fzcKeP~R{7kACX@Bi`2koBpj{Tu6=ZsQF(kqY714y zXCOL;Np)ONSdia*ENEbqz5CQaAKM7e*P3<+eiVF~ewSXz7szo?gAHjY1C$tuoj@N{ zUbp`_b=z&SMt?OL$3htpeiLm|(Am9pTvvmrOb+5t&Ed2n`h3TUv}UHAz=1)lGt#>E zaKCc@HKpTAxLNe$qFUzob3a1vrIQlYSRbR`yJLOfz}$Ah%kx+Ibot1+%Jk{*_#|O1 zV@nIv^cyOq-MUPS<+QYg{ahU96)_bJ$0WQtgeR2Ov!L^@NyzF`qb6@POh9e2Rf_)M zVD=b`Xf_m)V^OX)^yOjQFty!Za%wO-3x+7 zP_rVx8O%0^>;y6?A!2yGrt*L*z*}2&aYU{5#I-<*gxBj#oYU32^G%byRI50R8pUhdpL{(h2ngQo2$=Un zXm5&U-{)ICMQ8b%-oeDa@tN09B6ircBM-0*#&cGh9~5W z_k?afjrn71&*6}qu9wCJdydyllw8}0{o8%$I2tW>D|2T3|7(q(M$aD4w3ij$}i&sGt+bSWf zltgcM|4g6)f%uo(_p{^l_{OdETKn;(^`LGNW*c!@B$O2Sp04LB_+^zpKh163Wzu~H ztqD=rcXtv+WXNxX7~8x}JfZ0B__=g3nKC3=qIVrwCA)9DUJdfUjDPZeY;u+n zAa0xTr6pgBmK@Rau5v9tU)QcKQf9$blkNe>T3phK)%EW^b)f zd3V4Qn*|Kx{BmN&`n?%d6pldM0fOd8(&>PjWm|g-Mc-; z>a5};0#Kmix?u;GJVw?E33c5mybAh#gXPX>B(Y?5x^9yqIv#F28V%t(-Gh4PO~@_2 zFs2a*aJ`{ICrx%uX<Y`ms3?v+D%A<0JWh}4g%zOypjm%w3& z`gUb24kc!bTx)VKiq-5>|JKU;vDPSR!||w|lQqAHd_%Y@U4(aHdZ1hi(Tjlb zb~QSwgM#nYm|qG@774<4Y59o}ITc$)psvV97^@eqOZjmr!RW>92YNC7n4;!oPn?y4 zNO<)~NIiL~vh<4k7-#1s-y{@aZ_jr>FTfx^jDj|M`Y@h=yjl(wvf+JTRE%170EvMI z^87Rw?6f_-J*W8=4pMO!)akr_gVNdS@|@_GsB3c)jE96If!u{%;2=&dPr!`xq%#wv zt5M=-Q&zijpQNXbp*#>r)l>Z9YJQd ztMdKOQ9FTO=3*VkJroh3k&+18bI(If>G7KFK)({cPq&T5%$Uf2!O6o`l$ep@7unbl zfM;;jbS<76LJW~z%;CBk{6>?2@nJW@#@jzVR#_ii9~ z^Cwx+J*L#g!NThj#ZGyR|5rkv6(42J#RE--R%XF)VM9h-7iJx9Dppt63S3OLBi(k* zqCGGd0ecn)deU3A5EgAjR*_+l!udiZQc3ecnjdg1=jwmw!9bMmtKCpsqC(C4sDA+_IFMxupbJB~+tH+}Z+Y8Hm0l=4K%>dQ?%qA??U-sVHU8!mu*7 z=d{|*=2z?{tSy3<``0uN5DFF+Jl2e8Z{5w4f`y9F>SW}k?JZT*Pg0aUhtKqJ_#Cm_ zr=X1_B|mKuQXSmd;D8{Z)8=}5)){8|iaIbjXl4m(1TWnHsn%Prt+^JrnU;W5@v(hB z4%9IM~^8UlDU1;lFbz_+-J+}SfIdwE9U49 z$EnWhdnu4TZ69QO)!Sn__>c94x6e=Bdhef`#R;8b@Hs<*L-M5|gybzS!#uS~&(_4K zU|HijajrYdh zr^^*Hil!dQg9s!h_8jeoM3u`Xap zhDvl!+Oj>4=)NZiq|X)A|EJP5^SKycyKN*o_%B6h>d~es^e?YTN_`LK^QxV@>SRyq zu*I!1?_Ft+yOBz;E8K@!a=mZQy00#{Xa4A#;N1o0_VK)W zu~6eJ`d#O09MGNPyNq@wM)$0beZDm5mJp}Z^K18p&^CMfTbO<6s;7ZU{+o1fe?3bM zRczap*v~FzovK0V411e_HlKalbC%EJdBS4!U3A0Xm@vmZhusl7dW3A-;$Len9a!H# zN~)g?KLTV#YyuVV`uYE55A}%5Kb=bRZz-VV_Lou%94BK4jO}aSe!mff<5W5^(|xo{ zfzU}7JGSs>a)wjhMZbdCZXW)U3(7ekA!|6=blYGLxB$5umn;mtwsoJO4CrK z-3cT#BzrMb{8+`g{ipB3BC;pt<%`8d^5+kLXavdaeIIkZGG9ql}IbZiv2;_5YY>Aw12!r9~ zL{>`9tS8Z)@NKQ5#zs#f(7I*B8w>3>jm!i=IYTdq^vm@D~Hm4YeKtdYqOCU|^j4|8KXOEgnwYTHPz zgWQ*%okSPI+^eIH@`jQ26#;KPqJJyDI?#Z=o ze~pO1P4)5aGf-`FFb^Q8R*FOiUQOYw|Kj5`@J;6C#4!bi zd^c@BkvgtBui05PkS-F~(<-ab$yKGwT#%+nOOOj6hzgMyJ%Trz$rps7UoerH#a{md zX`FLo$kh4A&&u6>v44P+eZfxU3;xxi#&6nab%rJygT$qCb050g!~UU`93IQ2-9B?N zE*nbruf&}F)(u+^l^EE|!{Y%zdF!mf{W}R;&4pA4t|>zy7U9L?%2}?Iz9CV6H!u_d z;lX^oS8^bWql}VWJKAP$F)D4iKqVXAR z2(w*18;dGi<2G(FmP4Vs?Z&M1XdrWR4%;>cWp}7x&tClI7D#V5W5wWg5DQ*B2KP^j zUTJUVYGuK&REvuP2cPjFD;kFm*H4KuPD3^?zAnUyK5sj#>LZP$M$VqfWl zg7}9m(cB`8@jcwvaPj+YMBn#C9_DT1EA&(gmSH0d=H-b-aJsd`qoiQ0HVzF2euX8G z^}{l3BLR}5MbL<}$)r<@PQk-<@6~P^3OdnmL@U4?PfJ14bz99_pKafz!CRk5q&P>| z0L%9x)Houm|LtBF0XYYC^AZ{c11*oGN!qSa>rY@Nofe2fLHiNSik&~3?p0?I={9~Y z%?Vp|!Y*utR~qwwCMkZ51$x8f^}Rorv=FA45T|5Rin()b(q-@c+M^BP5#mv?Y7ETc z@V(fsTio=1&eYQRRWrB`k}_5H0(VCJG(R2(ss)=^7mn!@e~H`rb0jN{P(=ls4C+w} zH1qHsXlDC*r1#G41pPx{C0{i|4hrA>9TVBC_+*Py>lbaU;5J!|3P0YJIj~L z-v7@Eqsox8ky?AhMb`DIrgKA``Bl_?jY0fLOLCfbo45I}@lkSStZ?G))mxhUBSD8V z{X-=ro6`y> z8$a3Upis3clcoxopB%M{icc)7RLHIzhCvZjJkl zFaT{hz~uA6HEoYR`{cIla%0KI%;q9~$?%5z9`*@`C0;6RS`R+fq{FLpR`@gR6Bd;bvM2~NWLhNO~cdp37c8b#e zoiK?0D+p#-_Ml9f_o+9H#oTBksejEzd0+AQu1;xp{sBeV7(eC$j)hi{+Ohm5R3&Pw z2r78pEI8g$1SVy~>GTu10*Odk``zPhU=y$a>UGptr{q}=M4kk z;7FJLO*k=JYsOC@0Uv5fJBCV}hhP}G3)cB5hFP*^|ESf{-|9&E?uH6qy6Ij%(BQh zK}w6I_Q~8-4=+ueU+Gw$&yrUF)u@p<;p6xv7K2q2!+Jhs#Y@;(l0EPTde%ZvtmR0t z;(AP3N?L$85x~O=Z&72GO-trdM$cN4`kE?X4+C#a z90XLJsOS58E;UI=PQ^5^M2ThV&bLB-VrH{eIXDxnh@6h>{O*5l!QnB*ksdB~Bg6OQ zyPMDpkGT=#MDr+Aqe=`b(yU z?hBRQ%meHW$8V#Tl;d6qOzvtVm&!*QCpHa7tg3bDo|sKrRnHO!7;g0@WwU($4Snr1 z#)OyGUyE2DmcG=8Q>1pc9aP0j!_pS=*86Z=rl=fR3Y_FMOT;O;%vs0bj`#Uhg=$hv z|D#3o#M%)^8s9Rgbh(!hOwRo)M}+xh(PZazKI)t++3Z)iGN2 zKv0ImPOR!;?({@JEayTo9?CP43Lh9L=+8lRdSb;fH_cI;^0Z5)Pp_6(Y63%(<>4I@ zJ#=4Hj*E>)lBQ?_S8E|IDOgqR+{cERVw~aP+JBL^C$ zsAzMds>(BSO5^$=-aWFhmUoaj(+;+$mE~hm1BKnl9m2F5zH9Vl358TB}7w-|bRiTVz;~VDl{j;qqaHQ?Iz1W!w=r50T zrCLkfdODc)dF5A`LOnQ4U%OiPMzv`_j}Rr=N+kbG2Fu#>eE%M~b20~BQ*nEP)xG8Cq5s>^#SIUAkZUYV zV;+4StW3;8b^fqyOyuVFb@j*!_ZZ;jT2iFXWh0YM;L47W`G?3!{esXN0i$l_l0V1} zlXhmKvg4Tmktl+Q!($&^X>!ry)}|lPl0GIl+wc&zCE3k@yHw1RGXj5Xt^C)Uu_6d7dH zI$oUC#s3E|XS!n9S$J$d&&{<@*bx4csVfnY3?ROGz)&t;32) z6;XHXIl)QD2g7v_32tyA;@nVOPi%=6``i9@z|-&ycLVK z+ozs>mxj}`Y9^LA7Vo!M)A&(~p?skgKug*=SO>o%w3wAMN8B429aM!9uetng+OE&2 zm707s0y86gQlC3fS^O?0;IC2f&yA+=&;kvhjxLq9nEKP?a-`x);f-Ln-K6lT&%gA5 zcCZ~Vame-Y2{zQkBjqQpC^9j%VoIVpBy*y{Y(Q924QK^ZDcE$V8S(`Zy#8eSb?3!9 zvyTa(V#h6_emOK;!gfVPNd~0n7gQqP2p*qLmVT)fTIei0@~sbemZjUFxCbMrgob7f)x zlugJDYXf1Y9p!fC9qhSDA!YXEL$|%o*mfv+!IGg zVDXJteSDJ)Bav2yd5@jk$zkrpbODs!`JLn6I1(?zG6IwtXHW$PoYg{{uMusC)r{ps zsN2m(+t9QWlqf-vuwzRf6ejn!JKP5If$A7NXO_KvKao4%f=Ftl(O^s+< zi%YkgN8rM%{c> z?8q0_m=k*o+Im(U@Iz9_h=kH~J1#oUV~-xi*Vr8{P<`v@Q$kIeDF#vm#j!|ZN||nG z``xSQcUSnBwl7hYEUYUQ_Q<|yAb$t5C39TP6l4~^hzQni2*z@5FkSLeHJZDl)L)$t;I2;-q8&UlUUc{*=q^+EgPJix8 zERW#LLmq9G^LP=cb+v^ ztjgT`77ntK?iGJ5#1m$Eh?%cxJ?+-}o2;*)@nW^8Zeh4oxT&D?rlEVKE@y(Yp-FS>*>QS>0 zxnkO6HKJqDKXb)}2Ay^_#d)3zB&}8OaD>;^Da`_J3chin5AB}zM_)#y;-L7oJBKuM z7fAhZ#}5fztzgMSY*g`G{eLJIWs5P)+a`d0aOmoa*A!2Ix#Ap#6Hzm)y7`jP$Y5%+g( z9UTsVduBGo6QU7;$a_$OYd|^t^YTg1C_rz`^!(5up+DqhVa$o6U*0q-0hf3$CEuXKa;!gj|A z=rJH&K?t|>A+Y^erU0SlR2KF|+Vt502|$ki^{4uY>YN5@@zaCHEwk*s9ufE@RM7%B zb?@n3=J%7Q{Q;Yf4&nIHh(A?Lzf@8Y=0A$JV@L59K>p5<0}KfWsEysuKAoN3_!CzH zG207ci2-ErZ3!9H_-9rLWNI9VU5r*Cr+@f@PAM+fKvwlPHK7ty^yfL0y=>=@?xUwk5%Y7oaj zK_@+ox@-KJuY11lVg_&wpo&1@K_BnG09sxAd%nXp!JsX@KX!Swknda|-7C|*nv_I+ z;$w9F_mEJ4{NyNO*=HXSwKM{LWVg*ogz~MsC}4MXf8x?EQTm=8b^t7iBhFU6AAo`Z zxnFv{e5H8_{6?>BmH0vW4gp07eYt*?(XXNewV`j>=xRbgV!t(y<;$>9q?x&bK_bC7 zltEd)tKy2Ck2SF4v-Gr?q)+x9vP4+8auW{79FlsW)P!*-Nnc#!XsXB?@W-bZblhyZ zEBoQi!&a@iA30mYyct_o#F?2qT2H-qQmmZWcnEP*d#2E9p~>igeLb^W*Qzb5)MaOg zia0q?__RBdwktX#PeKDqSDbp2pv#eS(W4zjc)j&cem{UMTa-VDS(xxbB6Ic--*Yyv z;l)OgkJ4{zF_sPRk=<>@9!@aid<|r z8tVwENIwUUEKy&#N0x6by9<-!z&ut*hOF6JJ6_v(vyaZ4^j}-zve}gMd}Q0aWA><@ zh1-7RK_JEyE7zCZ`Sn+UcQFLCtz`XqrlIj}om!vdcD;{1rdU{-f4%Ttlji?A61Tfl zq}O6g*UXv7pQ#5iY0p%uSF5t0t3Ttk@zlt+b&0q)B_(}Pg@maT2>3i30qcv$6|;J&v^{UQS{BK_N=7Lp;VNB?|{9g9tIc{~+5S?E~E zA>*fPHHNPM-Z`lpyMBHeX#sAVzB!?*LFAqR%~q4IoDj#zN$p_A7FJ zMc;4s*Qfbzy&?zsOB8YP`HhBGQxe4C@uInIQsHXlNZ?EVV3G9O^h$XyBzMPfzhNh#v&bGl5ymLHB>Q1rdxGpk~ zNjs1imE_O)^DT6dV2 zBE@(gNv?#E8E=;@iq9Q5qb)gzX)5S+zd)07zfCSM^wRR~I;Es4Rwtm!v3_rUJ^48& z55L7xa$|1`YWLn#$|D%CKG?Zln}gz%R`K>6<+SFI^7W}ZQ zubXvds(!Yiim$~Q1a+7v{v+OHKJghD-SzEW=D}F*!6~~IXh|1j2w){@{@rwb^RM9+ zO=^?Zc+&YAsuTC4YV_7qX;H5ItH|W)>Z53`db6*^g=I5wq#^mEMsBAkoMW+6UMm1y zDK?cXOc>ZavoweZw?;pUYK!}2O3rk`kP6aKJ{ zZLVV@ZyU3GNk*rB%xsstdhZ5pb*!gUGJf6Tt2}dn+E{Y>%OhIi%$o{Pn$p<7HN=Ao zhb-Wtqi_q7?PQv)nELgdGr+w^$_Tvz%xXF+8r9O3EmV4u&O{n)En|DW69q*UU351G~}fr@?{- zN8rkViI6fCXJKRU{a0`vptQA1))!`dOaYX<)(gK@>q$c z?ULpYY9nniZyv914z~L*=uX9WS3N`n`3tVph2BjM^uJdC*&6anR;e=La4^)EX16!3 zxKEAuv@gW9>0r(q2YG8H%EjC_g{)G-2bf$W9>;1v)YDsHK`Mx3aS&A%5C}C8)mDk=ZzzFZt zd6I&*n>9Jb&c5%@!XmCoJV?IUN9`qxzH(hE~1wz%TRMOw7mScZ~`dwOavjz&QKXF%XVtE z75MB}-QcD{2WE*t5JPtCGU>uS=5;Z?YAHgh+iZSFjZwK0YP58roLY676aXTOu~Xq~ z)9tmr9QnV>_oDb$8WAvaYBIKTB-C~^&0+Sc@2`m&^~diZ514&(meHdlhm2g^W6Ero zuGQM@?2OaPQHkpmlf?^nDUjKf&Yva%$LwCF&$%H2T++ zQ(%hqG+Px{8C$=>*yEw0~B!02Hen2 zdN$l0)&YQdQjaDBp%no26l$*ix12A?OUAqpm*)YDpITx=EsC$8?q2@zBH;(4wZ$zD7#vi>zp(Qs6#CO#!J4We1d-X$E5E7{Qv3+?bb{OK|WnxMrN4kWTC!no97u zUb2(6>6cK82zf08($ZR7eMr!xKK2C(MXUQ0%i5BjvRp1Bbdi7maFekV`F&a{e0W&F zd;)c!+DrJ5L&mjSh;%~^i8Od>O%gb)(Rm8%G)SF+20F|qZ(E?6Z%`37+Mif-pfHXn z2c-76URNkMXt`5zV90DpB&Lch`HVs-%qy&5GP>+Ax@@&fYKeqe!HPiiE()>0?b4;! zLz?Rz3>gvl`$V`lvr)p3?>)4Vm|4=Cki#h|D8(KjzXS!2r^6FRfy@F%Y<61ds&_J` zWLq<}96U!xMRS2w(h@*0G)T)jC z9nKf`&R9mVo-i>~)Ox*-NrEufiseS)elsKQT2G~s(tHz%X1$ZvqpPYVr@5eUF=#_*8kAWgUeZCcgu$se-6Qf_UgXn zz@{6kUy_1{ShR;~)jPu(o~Dcq5<{~-BcpXn4!bL};G*7B;RP$hDS(N+eW3>fg~pfe zU{m{x`&n4Ph6i1?Ry`kiJU1ycMTdP(J;l{zSW_W{Z#Ik4263p*x-{zY96}oe7bjA+ zgmo~-jVoOjwmmH*E&$6GOmo^Le5)wfuEF_6#FM#DxW>QLe{Q$LR9V`S}`y?7a{sEdR)bT`;{`ero1JF4@$@ge^7o?BYicrHYLf(KZ_$ldaVIW9`6twUb!Y6_sud8% z8c2?FuE`C91#4ODoU=BwV#m;+2{&I)9zD9p zy@WiRHVWWFr*{c@g?Ai$#84FNrrM_AKakxT)`VR$U{z`A@-VWso(+q+xcQB!nsdlZ zou);;e5#l!rooG3={xtpuKv?yUTU^2kyZf*3)!Vnittl&I+gr$o82qI=X-cbuE_~C zd$UyN-y*D55re^iq!saYj(-)XhK-PP852C~dQO*3@i#Kwkn`IX31h z;+wI1NX|d{+kNi8<5pa*6Pu|{X zS3~YF+c|dCFcovn;Ngg{`Kb`c$?XG zIJJ#U{P3C4LMOY^(UY8!hc@ww8pTc#SBL1*o<VE^|`B=?yAz00G$&Idc+qQD~ZSb zW}sNCS;dG+p?2vtOTu|GWa3b{q-hqI{5+b*i{H4KJ$Bk65C?DeZIc&koUL5apfn~7 ze{=pQLrvI}509bMSQ7Uw8Lk7S_l56_l>{fbzO?IWLKl&6Zts!jKHJ&LQRY=vI}}ODqtqJH z{rs~(XmntEexC&}oDTFVd1_KAtR5SqzD7VO6UigKtcaQ!r#b=yCEO9EE824?F=z!) z;;uN_7}t^^rn=bfTgzzcYaf{sQ+#p9sTZ%z>Oj*SDg^B^o7tc?K-2qz777#V7{(P+ z_9cSd19H=lNB^T1t#qWgARC=ui_CAOtz~dTAu_zC@uI;k2UhA*{+9V}H_x8}iY%Gh*XML7k_@J+fXZ8pFZY#!T{%v!I)a|VOzHXA{h{6_i^-l{ zi$y`SR{)zmvtL>rbRB%LAr>75GpkMbSw`HA z?DMW3-FIj=4&l5bgkI+Je~RpOhTe5}%Ry**t(%)X>fAoqlivJzd!CT^I~kgA<7-<= zR|_k&`HGCjd36O&75?oP|3zYs9*m*+E>=F=GxSL3?%C_wualL%9H*>)GQ9VHU=lTN zN17$m<}*&d!rzWp_83S;R6^7_f?rhU91N>|mf}X76=06=x??d-jN+nug!M78T=2W_ z9<;Jn258rp6CK=3?r2EqhLmPVF~KaR!D0U5g#zlv>`L12AF;mg7M~K4hkc=u z%KnS<%-ZN^{vF>X?bu;jFG=?7McfIN`&(U8RbDI!U(f@&E}bB!%fQairPH_W z3zM%D$rP`82)@2l%F73$KOZD5q3AN${D6WFte`?XbfzY7aTkVv5h(ULel`{f!3vcC z6?ON)I&yE3#!GemsgU&aq(Z`V3=1ue>mj_QJe6MLdm%q!p@rb!G+*ux(~M>Y3(DR6 zi}(F9Z#Hx029-s=!!>}2_J(jLe0I$wyBEBDu>ra$efxEd)-vB}$#}Eo(NKkJ@f^h4 zd902zxqxE@q%7>va9gShx09+;l}$5Cx<qT7J{5-3&>-fcgla$mRH~STyAD2%`2D zy}g48dC%b&}=gQR$*-d{RD5L-Ge`?Uryfoxcq~7kYlz`B=n<$p8 z#Dw*sUT{s+x_KISGaDJbiD%Gg-CsFn2tQ#3;L`1LK98Sm@ukVedv|(ZeAw?)+$EkJ zxqi`{GVUxnb1xIVeGYG1$78sHF6z z{nVtR%85~CL5Ae#+`LcOyv-}40072cx&w!-xdT@XvrmD2+=^ZILEdrC)E-q%%*N-M zsGaJ#_tJh@H5R>b9tZKUt)H4ni!z1W0-x2u$+yHf%<1;JZ6$X--xRuW*=0GYpy9P2 zvIP4Xa-!R*R4*v|yC7QUMFxGIsw76@XRMW|zY=EK3bmqxItR}}szo>_wcY?HUM-7tu!5A-4NW+n?r16y*2*8VYmLUR?Ub2%19X5q1{K>=@)Ij3#&Sja;Qx@_1i z(u=q`M6Z}S`|7=*hL2nFV6S$2%r9Q9w7VLsOpJq1qESh`BU>E4g?#ZhgWY!HftW&# z%GC>p*v7u#N;+@Wj{!15wyPG*8_ zYmm|lhOMXzOYpt|HD$5(tQ>3!YP$IWKbG~8x!rJommcNi@U$19wgOqlgA(i|1Gmy` z;L^N6zn$Mn%R*CG)Lkei>Svr>NQ-&Pzq`6QSGa?uraq?k%O@9>CxxLJiDi&LHFO z>xoXhroro0m|f8W1<4U|&Pax2FZ*gx+m=#yT>8D|ia;{6O)Q8%;sBNFtl1*0aDPc~ir=k?TZH0$hp@hMb<~_>QpDG?Inf z7G5r5;c!vYi8{r3X>xtQFdT~DJFKP#AoTtZ_Xm;po-4S-Q~QH)+^!Pb65%eor4y#m?4I^36>Qrm(GphY zNa*b!{F2t-?EeI8+5Z!;Wv2h%yp^nMjQ{KOe*jxn4yON4U|SOqBrd@w{ht3ZN z2S#w~^GG1fGm8@jO5Wb}|JGIl4(t^GxW|DHf#uCW%KHoS+hD*r(4*V356$4&@1F40 z0+?8$0mO!dA$;CC`9(2dz}15Z0A3IT@vOb~6tav#=0P`x_#y86gSFH)vHWde4)*RI z9u5In+wA&wToPz5eqW|&F9@xCKH6zC1IQrY zz&E(E2$u9q*Sv$c7Qi9EH<`dr$;$v4w0dXwbsP8qT>q2S+C6;z7p*0j`$uanEz=sI zAueG3Hvp{&W%c|><)e}JgZ04u@>qNQ2*}vhym`lfLF|Flw}E}+;D7*(n*j4ZL4P%7 zr?KGd1={R81hRap$DS*vzA32qt&j9(X7tDhU=LTl9uU~qK7Q7^+kdvI{-B&dK7UWv z1@l{5`O@eg{`*412e)+uCLjL>Y<1HA+^_p10sz|B*boW;0<56|yfn0&ekkkAZi0Ss zjXh3!_xktNLQjF}dG>;=;Tu5r{0`nZ1H1bHLbP$M?Y{bg|5)qa-2qq;tU&mouE7Bf zzmVn^PBN~j}Pv}v}7SPtpD}2tcZN;zbdoRP6YVt4o_^&5HUT5OsE&b!|+b<#* zhfr46FVI%v3a&jJfb&{6Ox`c7H`vb~4fV9dY2VQ##5_;TG5+hUA70@wY=i^QmiYjJ zs_S37<5=C_)R8O#`8u>I*oVtPpnsS6D1l|NRT4uShL8CY0TE;vcNO(S;-)ePI7ug! zu3Q~@RChx6@k)(cj_`@SQha}*UJ|-TcA(C*0 z5(*G+P#B4lFRa5@$FpEH&<8zWdZ)k?a3V1wxb)w+*x(E@q+G1y<41+h02;w*>>zVF zI<>~}H^KY~X+pR%KgZmO7rt_!*yHFyy&)k@Rj#{3uBIBBjb&>UE_u$TCVNeb9Rv_ zrWdBZjYS~jkEu_ss#oaF2C~~H$jA{rBzs!n9s1-wEcB#9z=^mUa;UqqU2cAFHEPIp#!Je76JCDi_m!0;kHw-D&PexLD$mV(?IRl4N{p(y)ma(cGpMk))|Q zGr7h?pno>N5k-H@bd;QhpxjCUu3C3_5vK`xl1UNZU2{Ki!pz5J%bnfyfP53mf{*Lm z=na+`YN@sgsd%c&BQb+64&_KimCi2Xl%EkSUsyf+I&QRgi8YWG6fGzft_!gzk5-M7 z-z3JcMKwsB*7%feFB%_%VLLq39ICy)M3zhI zvyGqKeZzz8*_kw)_RhHg200-pRPN1hd)*jE>D}_<68K}7`@MMTQmZ(gXiUr~N`c}; zBj96PwPy^QE-+Ga>DJTMtOz9bO+${Aebb_4Ihq#FpGr3^DEr0jSuE~;C1Ncyhbm>~ z1?1bBru4U>{_<6D87y}BOIW-}+cid8uJjBU1C9ku^?MFvlpyLkMD=uzM<&7%;!}{E z@Lp>E#n964;A9dgP|~4t6Vfg8%*oTR6*;?EGpWZkl0EK=$eelrYDXnp(}yVCLXXsB z9^#>4D^71D8rko5YnuVQ%|kr&9U{3K*qj}uhg$ytw+Lr#xP8<+YB%1mt5gq(7&#~m zH$N&?9PuYvtu4UU!jpy=VcV}?qE5Uc2alXfOQlc(0_WgI|h>&Zsng~UScsOVvp zy0(Sxr&G==+AdR_dRF2tg&FUJ0qp^@mja>X%DOJoi(^Eub%DBxcn8!*y~?^!k;Wr) zyjdM#?dGhe$$b(~=>1FcWkbz@tv6%Yh4Wz2@$QaE>YQ66Kj}iapr_~Pi5}b%Hz446 zdPQR~sNxkeaRVREi&Zc6M_EiJH=>H7f+^AU*)$ogUCt7Cl;pfsIv&MPvNy)78Io~@ zK58XOM&sU-2XQ;x*e8vWrHb6D>!LnoVSU7_xh;~1@>DIm={R{qEm>4Uu5?pF8g(2o zg0`~f_)W`hKhpThsQK5aJtM_ti)%^cr&cHoDx&_0NCPz$O7iL2Fw4M)WGSfaDD=|S zPNG6ux)UlSQ!60S&%8nGVq8T0tTTEiMluYdFe`$~kV#w-l~$s@{}|oth=VjSso)vC zx;E68;4P@rAtHM5`^APhs;7zLkh1aU`952K*E01G(XKN$mdjt%Lh0MldDhm}(RRY0 zVrto6MU4xCi+1xF25VhLfUw?{3BQH8cj^i^pGFEhr4On4&zt`9drTs;7L0^(F$HZ6 z&y-7|om_?dQ`wPfZe?+Go5b;=O7_FZ`j-=HS-6(2qG?@kWpN=%IVMUckmWHgk+w&k z9H?qx^efBbM<-Z<%hout$_fZCZVjX(G!Uy&9J$Aw;vRH%=L^hvc#vWKj}lSxKT#Ex ziBG3`0FjRS8mdOfH>qW?$`y1HTxpIPr^w<;1s$8M!C|8_@M_XROJRs^`<@hqgd&Qh zJ`3#`)w&vRH2$CPvVY>N3$^5Erzy#>I)U-gg=Q4Nd5?5Xi%`;2u4cSSk25BX3y-=2 zM_kBLS%aH}a1ZP65<^K1)In(-h`AvWOGtEClnamCh+DEypFi2H*8agB-^F}WoVGqF z;-x0sQ1cteAl{pc2VeJo@xZZ17e#8Ztp4uBXV^nM*@>zLr2|L`$!H1wO5<))9on4P z9!)7bBkM1qWWe%}HD#cO4W$l2RVY zOOW2+Isiq^*p*{;towKDtiyX`2`voSx2{${kmB+8|ec|*|x z?NL|=Ez)5qaWwLd@;4s!$W6M5?u!167=B9nwlO`S=fC25U^bVnN_2(wBvG$3!cr`< zd~x!$1AF$@k7t{!O%cu`zAkLyTv#*!dB;B8u47n;2ph(1qGKb0`v8aJ!U^Wg9Cu-K zi-FR&KiF9ocljbhf)7h?y7YKXPQxsE<+F`!b2a`a*_mqXMbI{#D2g*J&tJKATYV-3 zvM`fM)f?`5L=2D-x_9Y4t8X}5c_qV@xkmMuJF-}NNs2s{rUE~lSG>8 zub0s8)G$}6SSq>3qrQD2-r&l$nwXEw*geLyc;I>Q#KBG0K?U?huZCRJG+vAJ4Ra_+IUsAHn^(wN zBLJySfiH~nvG2}6!Zzry?11HHrcDUw2RNL{*iLj#&_EaE-O|X`%-r81k`nz8ipNVG zC0}c#nH>wrXyajnzV}!lkaGQ}b0MUq0uoo5pn5__(PPHhvN6TmA565}gt2gr!NEN) z=RP=02=Tgb?u=c0O^dlKFX0!LX1n;5Ye}CchbR^9xwh$QFUgO66EBDg9K*tfESz@{ zeBt%}sBLc3{LUr8%8AZ};fZG|QDRo^< z&R9c)9}){G5uUEAcLi{`(Bkwu7w9LbruvzQuf_q|!7DutRbd__nTAy@FCv+m_|-S! z60G)4$0HrFQ5s*Z7A~R9#RXy6@WIQG6bgFK8oCo=YYbjZxy-aw<8aIq4_Difb9l26 zNmEum0_v#wCMBn;1H~YuG2ESOo|@NU?0>qCr#4L8}Q3`l% zx5IG^B&9#fhLpT|_GiFDN^6($%FnLhD;Tn7==?wwNws4_m=R*F`>;RvM!ENr z?zgiYhaXTGrsbO*;ga}ZAt`E?=ERO(saU1MN*RElA6ZNmN-ag%EtFzn8S(YxVjtyb zW5+yd%!c>!djS%P6Y{hOxs|q(X!-DafiON!i%AHEDM%PyID)03mIMh!Alm(w7iUpt zHYZ61`kU`cCESF#aA`7@L5q?U%|;pt>;A7Mf~OTyUW_vC!y?%Qw*$WQPhT{6YPv@_ z%3HU&K=_=z@|Y)MG0~e!nv?3TN!8S*#%Uly(uc5acf!5MInFckC=YC>lB7z+?T?eT zZ47&v+^xp$X_C*ui&i{ZLAMP^m@)B1qxAXG`?CwB@Q4K{o3Ul8?*@pL+1UawFCqSv zn2-SjB4QP>hCB}%ZF9HufY0M~H+ym?H6d%r!JBy4(B+T%sXHr42Mbl7JCsHZUXpCk zBx1D{`_67jMlH(a&HCh)H?|NZmIluD;9hk0$L*Witk`p|vMy)u3>;d;Q$#~Y#S&bu zna0t8rqi(@->ywYIqCg~CY%mZ)#fO(s;{##V6)FSLIj7eu;`m!UzvsP&M9Kr4#M(L zy}h(cQ0qM~>B39Gjgg z@8dNU-9NVzFpp;psZdpCeC%TvWCGcKU>jLhmKPaFC@RG! zW~bExL57&Py*xjIwCq!Pcb81dTo^DuxrH!~47YTLJXCX!AjjsM{MmFeI6j_5f?Zdp z(Q)c5bvd$M>mj6-Mi}CPB-`fcNMlWBVEUyi6$2s zh9{czl%;c{j^>Xa!re*`#3l1Y!~VE4Ds~<{esA$PSEvR*jHeR;lUHxbbk`W{{Ro2? zEYd+bk-~hIU^bJ?b|fN50l7KYK!_&JT{(pGgl3JMNID}4pN-!b$3rJg3$I7jlB>ON zg;tJN^-z~XLS95r-hzE5tP(_)7<&sptm{i+6&EtXmn@a$9g_t!Ra;G62y2eK@)l$CWLYrlMovhooEOpEI~~>R&k-0A18^HOFy0 zxNgQIumr>h%8}8zsk$g*qoA3v4a#7ZRq@PHsXl6oVxN<#Xuy%HNiC*%&f|3 zQ<*D;W?w1hX5_PpPybTlm)gweOnULIplU(^6~*QzbqqK)&t>LVzzV!s%E);-UC9N* zklORg!1)-8I->v`v}61}9m$l>dmPHSUz5pO+{utBfz{BxO?UK^#iBViqEZ?*Y>6V< z^X~KKUF`z9nN_51Sia**EpnOsCwu7l@~f^5-8(@2m$#$KF(Phu?pQ5uJ7S~U$MZmF z5z@?`qFC518s5Y)v+d`yfyWIAyB=x521kT(JmC=9{NeQoltFmZ64#k*0h#Gmk41Et zX5k{29Qn0uNRcm)15$%@bM`-$ZAr z=Meq~ ziuQ)vp3vZQ&%FpF*mGe$Va1EvQiG^wB^q-R#F;EPjcqS#@@eaIMDTXfECltbMQ7#5 z5o3_-SE6^ymWEUeBw{T4fXR`v{ADDHjmtD?IdTQ95)2`p{a0;JW-unN_{U4_YC;51 z0$B8jj*d+0>jPmTPnapLPKFO~77%HI!ujQK{d&AA{GJkP)`?u(8);B_IQySU>rIW` zl`OKqtdE0Owj*VVg(E}A&$L&22vnZU{g3H*Wss(kV{>PH9WNdqCr=DP-*b0ec1^}Y zWNqsiN6SiMrNCWI7wX125;5-^fDlrlCYdy<<*IZm70zn45ReVn?x-jzj}4Vlk?DK+ z0w;q2&EK!%oKa@ESmeoOXmRFI$Bjt$2izp&D3~}9pk2M1WYe9qO?&siQHh4nSeUem zCn?YdFmF*M?ld6j;*A3P%&`l6NX zd!_hHBY5LhYTr$#{ml)_0Qb@9Yx(9oItMN)O?uWyS}b1(mB?pX$Sj#`u|?pin-}SnIgH1U~X{u2mf= z>nJk;*vWtFg*}S7TwS^?d?+=>2=bNk%6zQ9e~=~-bSE;5ZvUro~5#T7i=n3-3}a&f0d zurU)b<8MjN6X3$GCjCo8r&MGofVvy6#P&3$_3bncd%Gg?&Y`HLS9f5ie$_Pz>~d%i z7cW~9dpvoM=0BON>LFXPOMk9AGn5(`YiBZ#6~y|W7(_^2BnSr`@d(~C8EZDugTvhm z3O|p}t;3*OfGH|972S-IPD(T@4)jjX zC11caM*A+q&n>E^M5dQPBEHBUD__&?k;xOZkt2enaF^oiG=CA<-rN4(hL)`bfya@TuZSgJ?NGb%#rTa38RbiB0g zBu%@7c_10OtwJNlZwT8w<$4GbSVrE0g!yl^g<3b7jr43(NF&jhJ)$RvOu5R7bjbc= z>8{skRMJ$R=Lu1n^>Ju|)?KQ&sN240DK`4UKP5ql%OCNH7}DL6W#p-Az@>yKjB|R0Kpp#Z&xspYT3J-IXT7RX%rPGv(W;^yX!Cq)Env z<(I&iCpTcltT`53>zLq&DwKoUB5V4lWzg)CfIY!Hx@D~Am4f9rd7gom9dG7Wtq5d6 zK(^I4&k)Ta^nZZR^nd>ogl1r)`=6fhzt%7V>)-$R`(F^6fu806453xP6&JobN|0lv zi-Mv22Zc)_hhi@?AN+ZeuoUb=rgX4+mZ zGp{}#|0y$PPF%bXbQhKn5<&>7@+d_Esd9jLL{V}}i*5x$fIy({0(kugad6)Ms<1xB zq^Axbh4T-@LXG_#=Z5pcJu**@B;zMi2>7zAwdy9frx!hAcw_+ zk^61wA^Bqb6Um49=7+JN#Z7CIr)G6g6;Jj=1JPnz`}zh3V%^l(`gWqCfj0mX0jcY% zc$A_R=fh(m%nGdc=2mO}i1v|K-JG9OLxZ`yy50t4&3=j|X2G!ldO?rP5od$)^T=Ju z!EPONdx>gMA72bV2XTPBJh0wdv=PlN&VhybfU&@Fj6sER>5#3VpwPg3(I8LD%s}us z1dw~On0z>HLB2QPd3|+uch0^AeRtd5)`=9_={Rq0S0Rq4=N{nw>Tv~3x zx?qPTL|Dz`tQFgCOY*@L3HK0HS5T6Wq>k!}$&O#3bdbc@5AU?%?oAvY{ z`Js;X{)C!ygFGJ!{&~5~sTMCF-`kZ$AZLEJZ$zv8NJtww0=%11>3x^dC~a*rzB53%{aaP%zoWr1_v)B>kW|+#OWm?2LXYC5)B3V2Mc?A zisv8(z8itxIh5h`BEUpHuQ42?e$H3F5P@31V*{{nXEbACu@?D(HGKj$;fO)%`#hmP zd-A@i4t)e(XQ+QLM}HdrptG=krleh@eEFpIN&jtK!H0x1-O{83o8{Lx^?j95Av(30 zrzF^m{b?*~^QU8s6PX z{m~mhnixiY*yS|zIXhPCe+lP6^GotTRr}2 zf$T*6v%jSg{-$J9P1MG=ERj>S;uN?y6~<0;(v6us<2b_If;1C3{}hd8Ikxir7nSbr zY@+HzyZ!Yy1lxZ1u(is`sGS`u*}`-I_uZ-TQ{@%K7b_O?mzqhJxMILzzGEg}m|&gy z^oUrb+UXc=02f4s`xyJB?3r_nEGC+)v|glIZ7Jst>BDLS3jIBm8hSWe+6|C+0h`ZZ zz13yZ-y7*6$izB)R&Yxqmh~MVV<(sCuBsSE(=g;%AW6lxD%2WW<)z&I_%(X(5nPkZ z7hZH&VW4Nn%ua;^bJN}bRKI~$YHvQI9jybSdW>4&w9ZU>)>)u^9X_fkh%r821s6l!$@0Y?-f6YI=;Hn+9D^3Ph3L8tGiwC<8LDv4RrruqD z$AsSZNKckdroGNckco=Yd1X6xps9Vw&-~6(D6y?PYp!QH`}toB4}Lly>wQVRLe;={ZdWV2}j#2c=R++neNK`IzUb!>k;Gg0Oa6*FZIdm^`LLiA{sx&#E<6A-Nb{vv*-dB(Q2jI_ zIxEX18W*4UA|e&R-&tFq&%N`N0uL4qyo`9-i9?u;UvlNU)IIT7==fsmMUK|I8fP># zQ$g5OLMIWny6GKm!$kSXM+sGAc2Q_N1j+mgidN}JQOT2jTSZH?=t$|feP=LTmPz{{wV_-dKn^s3bHr}&c zs7xr%Qb(n?ZrMJ0HzpWiH=Pyh{a3tf`t4RGmKy_)JoL{K{?s5jIL7pRk^~narZj@@ z%)TK&aPa5>Z0;^De}8nK#Xr+bYz?u_vo(~UMc!ZJDJ>*m!{xOp#GA@L4$LnHZMR2s?iUEA%W+s?irK_Y% ziWD$uxJZ!UbH35Q%E#SVSfwgD>vEpf@BV>DaO?JF%1KlGw~pgLLpFeKl*?(;~jp9i%wsk+SbVGh0T}{|l`Go@@r(6XNu`09@ z4VzwKfXIK0m#FlP-MmTaEuX`qE3|3idm&xz@|6;j$Z9bED?p@ZL_lI22KI+Gg`Q#A zDEWkmAGDauR@%;}N1URfN*5-fjo$irQT={+FoZO5M}0Ke&(QD6oJFLgFpx9!%4hJO zcf}FNJ%kYeO5;kSrdq#UE4?i*Ic5H`<4Oa-*g9&xpKH6L%$HulOW9Nph@~JUi_U{e z^uprc3tQ$ZE2@(C1xa26+d;GYAZE-qlkMqhuuA*)WXMg(gMjPyG-Dks7DM<`&XQqY z;)1MR;knfWKK%)VdjC#mqzCqr>Sk=o{z65Kf;xNEp3#1qUsyX>W41A8U3Y3m7H5M> z^gY5X&JBUxoT35hwF1AWlH=F#%A-IMlux7dsRW{8K;Rf9f0Zg}K%<93&*rk=ZR7!) zGJE+Uwum7x|G3F^7>7w>gvfGO$U#NvzenKY;#qPcdf=lFM8oH#5ykoK+6(@7Y~+(> zk_)aF>pgUe7xxWwdsz5c_w~6EXm5;tQs-)A=Hl!F*RNAC_vHtb`wp_UnxjZZ$L>dk zIOj&Lw(jl-!l2MSK`b=3BR5?OxbXW%*m(41`e}c%4ws1TlTOtl&2r<>10hCnEOksR zu)uK%QqO%144&y^8HDc|`gS;)S4LB4& z-dVCtXd5-m(pby4K6?!O65l*w+)kuaS|ZJ;0j6e5!4@t%5|p5u&9_9CEZ(mr`9l!# zMaud)wlE_T`YM}qtDV1x0*}LspTK&PLZC_DhYMY5W%np-cTzZ-nhwV&6Auc~Fnq{P z0alZf0-!F5lsP00jB_~4Jwt%=pdoa5ql3G*!P)s@j8^yU7j>7S_~evjgJan5N%rw3 zyak1h zAIg}jgx%c?&oj4}MxrV3o#P0%!g|HSVGNe#Zfo)uaV|y>q81oQ%ueY4!aOrmoDj#? zHy^fMc2EHqr!FlH00c@r;7rmURZXDmjxFykydM~;J^ki=8AMR_BNQqYd!|`e)W3VYRO+MaB z7H)O@t2)0`N?=te(TAY~qh$rM%^Te|)1WKrjIa2!s0oa@JDak=HzGoebn zsi~JRq~8hy8LPSD<*P+fjf<9xE&8z$Srbg~t+MI|2 zL45w6kZ|c!Kkz9(tIE;)MZwF$oTlP%18X8bdg4SLB#njA%`_+xl_9F|K5|!tF=Dkgt`+#kqG#^)LVEblqx;O9Lx?CQU8B`A zIg}C4vL=TwIgNFSr4B_8n~$2*NyA14>XW122sQ<`NR*h0TC5l9sJ5Y&^vUXU&`s>B z$D(G~|F+tV1f=gk;g871>k*Uy446La;Ke@Sor50(!NsGidYvMy3db8vR$WmkClg&8yv84jxLWM<|{+gL-ULp`pZd8P{ikF578UeSj0s z+<0X+WzgpD98}^TQSluEmk&~dF<8hgHB{}H$lzcJ5WV)@C%XIomF4xJ?#W{2&^$l~5P9Kvi z%i508AN|c5i*W~m$f!erVAeWGx5z;&Yo9m8oUgKE)Hqi^tnOHP68TO>t-ENophQyK zMTk(28Zp0lU)y3LyDNfs2Srn3gVGSJB+RpWw!~{sMyWGPH9l8Lu11qD@OFvy8;B;F zjJXYhId*<05lt{q!7>r1BV(}^yIP+h`?05rbad>fu$Aw?Y)b*|$l`zl^GCPNsII2~ z=0_H+DnHG+7{c{q#TkbV5aO+2gf&OOg~9Yg5W?0Z9xon(1F639A4}|gPSTz2Ntot6 z)!RlWgQB8tV*RIS!=t|dFBNXpsl@w2ZiKtGybb#wMeqYByNBYm7+=r$6A>nqf z|4X7;(Dg?9W*O%$$$w1~9X>n6)QqbNc(v8Tx~Nh9f$!w$?AC+Tl0-bRr6{)_BzFjm z1sXM{5;r9~%h~2mCe3mnN#8KjELNK0WtW^}@dNBz@fyLyf^%^ozA79-6m4QIy=1YK z!4zJnK2d8(P#!#dB=VTYPwO3x_guwl^Q3h)ET0v{)Fj+a2-cRqiw_5}>( zzH{nSIT4;RFeP&vM5%m&RmAI(X!94f;fZxNqXnHumC`N5qqkw;&<;0pjt|lL5pPdurymNOos!ij0KP zHoY1F?IGQK#M86yo8%}<8^3x1)O^r4r_8ymgN@63Z|W{w$|bX&!eP|juW$V>YKr8< z+!+eTV>CJp&0xMyHi-ao)hr(@{KRG($Ut*OY(~{s$emui3Bu(h3xkQww!|^Su%x+= zp{?ZYP>NKMYaFhqJjX4^L))DdiTqlMv*2GNXJwO;VYm6XA7-YUo3poPQ!%Q*nbPN` z9al<1(uiJN;7h3Bm>4)`lTygFbJYaC?1~|@r=pgcV_bBnsuc9FJ8!CKV#fb zYyyEBeT!bNYSsyRWG~dRM}=UwO0%aC7pC6RU@Fb)rieGYpV9fyt&V+2L(UB2V!OQ* zvQ38HD6VZrE&1B_jt-;DLV+}5JDnC`vsbu+SZB9SIlnh~Jby_ZEcYI6b_EiBGS4?c zF|R*N-RuPn@>6jIP~cb@*UBhdAe?TuN*}e)MGCp4TAXb>>Hiuo)%Onj5`lh&8!6kq zb-`vX^36@`O}?_+Jl0yzL&a&*I4;q3)t;b#%f$+y{Rp>BdOTphW&>>N zg_l9fy9V%uJrB{yh&-#sG@glV{?R{k%jB}yRMyHS|8Wm@7y4cSXhD`}bCP@1Qd!cN z?t)Px$gOx5OgUL7kY>b=|15o#7m+0KI=}MSD znC*_sKj7Q_F1{QjRynNOIL8<)%?5qR$Y7fj+8W8XEoO2r8+C8X2iMX|}Y$~q(=ld>{~c&(UmtT2w}9^2O>RQs-oH-?YZ zSMJafXEPR5n#kvR_y{?kT@`k-K@S&WI^EUx49j%BEQug8_vDg0Bzzjhrhm<#Y|{P_ z>v1NYES+OfxKwbySaG(EL!~~_+5K|I)cWs|8$5)cB`8(bInQ3lD)I%$wp8l5a`(*S z$&FXMDDE49K&pHGGeZq;h~!LepU+j`4mLou3Y_=t5S^`maU3 zg^A~bVhWTTyYnQ!RKIe}fK{6&l?>Q9yLj~9awE2pPxBxsxYDUv*P0<)`br4Yzduh% zx?anrGY0Ki4B=Y3_Wp~EgHG~~y;G7!MyQ&R+b>6vyPvQp~*z%$cO$Ur<{fm*lJ99i7*XDqSq-^;v&X zO*H!iG^rRfet~l1E+3w+hbE*O)f|NIT(+EuchdHqErWsibdCuaDa_(t)oU`-opbf* z$O5-h0ps9Cdr0-;nw#=-C)RA&rzRQ!pr$Nv- z5gSmhFS7Qs$#h4p9C!|wvzE%q#%^TjaNz54%)FJtII5X{3pQ)>#LThDe-z)%+Bx#t zV%Mxx1lwRQx&68`0N(63glIxtrfF@gKnQesp0}L1Oo}4dLa1I#{utWd6I7YfOXxO+ z#O!n8GaJ5(8LrOzBbI=^P{ByJ;dc~eAjc>Vq^Eb_3v}uw~rkXtgJo5dxPHnSWbei3)2Qu@hvJ8)Ioqm(RpM&=My8DXZdpC0d+u zL|t0bV=Ri2;lQOA5?h)lchERm_qi~SjhPSoap~RcH@hu4bpH6h-V+FkQ)I%PL+hl( ztEr9V3&@p`XC09&e01z+ob9WGB$3p3rk9&%#n`}B`$TDAyWoe4gSafkLO5>iQ$xWs z5SD_>A{xekaN8RR-W#a5Dpf>)m@4dy<(zRbn7P?-^0T~PysN<3^`0^sE9sB{ftA>e zpWqTFn5d@tHrK0EIovbB#k=xcmbO$?$X1`5n311kYYRl9svgdsZD1FCgp@eaTybbm zS9p$WHS*p;g2u#;zHugCF-qV0-8*BS?u7@MG!YNq|ou@Niwz9EHjIk_el* zrKsI~p1HKOh`*wRT4x20ey@3X=f>pO$xRhIi_194D>|4kM_mz}%`;^zs`H58D}03E zt(U%<52~Py0EReI*H3My7ype^KP05ID&r63YNkG!M6GS89gy=#uP`GC^vOvY@`od% zuWklrg!iUqOttByMfjWoF}`{}i=;c~*G-A`4#gd~_HeVi0vC-y&@9LB?mBl`km{1N zh_XeO@o8=~qlEh=^Kv?oE5%CBeJH%agn6vxsqe!i zXq^gaz_)mwsU)8s~qL4^VSYabt%o-krZR`t=?mfC!{O7wL z#nZivN$Jv)e}6^|JXkHUm`oo@Ur;7|__AWhs%^|)OVj`CdPJp_#mZ*`p`69|++QVG zGDp}2khfc&s>&p;50;6`L0@xH7$yi>aTQ7-x!n_m4$E*H98`nMSa;_TOlKSx8AW67 zMgxaUPX^2kM&38wC>`wF>a|eMhhq(TYL#K#bF5foes<&jB%w_tG$|2in%m>2iE1yr|So(pY7Sx zqKLyWj@W=<&&O&^={;v}>{=d6{PlXPyHG<-7zS*@$^zvwxVK0U#Yz1PE3TP^ zg!mc|RP#jj&$cEzZpmk4PJq__VxyU6J=J(IcIbEcfh{IMxBpLAl>R?qQC7PDZ<#V3 z9TPpnf8wHa^vulvZ=Es>K-kRE(a4?vAZ)4UXe4N4U}Iu3GhO6{Yfr;I{zF>Pq_Pcg3<)M{E z4M;S-)qfH=oEnG?3hOjbk_Nc$#THCWovjDwF-HU_>lc@AR!&aJ8KR4CD()<@p)m*q zc{-~G@RhbSBSRf{slX&JuSv`g3?G@{(WNDzcl`YLcvxTmWDvxz5v|w+q}4C83do$7 zEVqDa7U#CZ)Hgm1_m-!rjz9sFv65HX$9(Y*#Gq>_kM;JhO=wq17YXZcAjSs-Yh6FkV0&34ttNZ5W9~i)U4T=A1c`bs$2Y7^X z_3jrT~9vSY#fU$D419^3RSH0QC5i-ZJ|ZSP4A#Jk<;OC$hX zf`goX|LFk6X31Ea!2I}OIQp@D`!RUGA^&ly|FIFDr)_Tb!J7Rty8EH~TL-%4{%Lg2 zuY-A#q9hyGNe%YuBh}>RLt9HYi*u;|(xa|sl8};w1gf$Ay(JNwz&MI)S`A{)-0+^j z;4{wTbCW>>1*ho8>gTOP2W0Hb-25}wMV*#5HNmw1$Un)WL@EuyKKUF$^D)?+kp6Ok zk=JDieY-h2*gXbLWo1uyCFqg-2Dj@$+B1@v^1Jqt#qJ#k31;nS1=1dW0#@b4iSv<3 z3xVvV{ML9R+Xt@||BP~71Foe1A)p1S*yIVt?xp-ebPvnF{qN5!%l-jSZTVLKD{$rc zPi{);@1I;uo~s_@A6WV~$U9Kgsc&ITfH&YJdW+|Mr^}G(2h(#5_Z9GJUwPEC8_~1G zGpB7{cVFA$-Ujkh=Njkt4gLmH+5F=VSX=!9)maXH(&+|h%)q>ny-V0!>Wm`3sW=0$ z$It)!gw%z9Cxkro>`D-6e*69~xiMghj9{97*3|$SUlG3#5FkLd{ESB<9FQ3LbT8U> zn={nu^jVIt=>D`OG-Bf-9M|=~gid?OD+pslpR3`g98MHrdaM=gXtq?F+h%9P9^PM-5Q; zWjQDC&}~n8X=Ouz>&s^$WpS(Bo2wGYElBxQ`mbf3{9J{{ylohMq*O{~4PIGh?$A#O z>ICyo>acm%qE&%p#`UwM6$4jnd^wRhG*0fo(mij*0{m;uX_50&R|XiDmc7)*RVt!Z zZdbT2!IPf^tIx$!S>Gwv_v>?Ii2wst|NR258&oKPZ@x*3HeOrqIKOHC;lWGiot9Hj z26bhmFl;8MNN{3#UWX;UaI5+j4m=yZF!FDFurnCsy|eJd{_pz9z*Ad?M$R6G7Vrqq z4hhVA`IWyszq;HQe)wj<>g@9;i?1o!J3IKYlTBq<73MK~&bSH)$5RhSqTF~EQE3F4~~e})mT|v803MWKBbP5=zZ%#7sk!<6LTjB|xL#xM*J)nK!$lo3^EvB6RIr$kg(5+=k{b2Ni__25Z`$Az z_r`=X40hP+bc^mtOPT(gXS{H+5H&GOTG}Rx>^`i4JmtD}hyWgHPn!hj=0-q^63r5Y zQKgaeJJqRlk3lA$2bIPe52fmT^z zj@X+upuq5T+B1jVXgXb^L!&jY%4M~OQQ6L_ydnLJUBtxOWaiB@+sA5rFxb#*Y)OsY zp+1qbtpTZ>a*u8hN4P6jA-76##BaB_z4H0+PaZY8W%;Q&no+S$_Vsn9j+6g8DVp4^ z0i-mxyeT;TI}6<0U1@*g8y^Ml+rhJHDj7tPa93VeLp1V%bIcUtTcGdjVl>xqKU7KP zQ6T!2U*aA5+V7zTR!yrcfVs}I_>uqD|nDUdyJ5#f@Trl>Z_l^gF$WJzu;t|`ae z(#CDxy5B5t?mwFY-2@%g&Qe~kPm@cLP>1uxbA&_<;|B@_PuUmX+re^T$U;3B^}naL z3@0MPt|1E(klIVYLUoVUIw(-4A65V>lfn34{`^J5Ly+=Xt+RIIqu|ai`g`sP3(C;} zQSxnZ*Ni>Ec$8YGdzRfv6Z}eL!g|N74b%rP>m-_X>TsKGw~^3nyt!O$*^@6yhvjKu zE=l_tif21Zva{rI9+Xw+f9~0P@9-#0rHCUr!37f7D`R5Yceh!& z#cd;`+A(!go>FZ);``cOX}T?c(})k>mQRk}2^7pNBdcx7b$u66{T8RbI&xV0J8FO` zwUB{^L?r!(+u4r4_;v|27xvW}^%)rXZ$lS(RZb>)6;khp0&JX%mvV zm49f+MrBxUP?&3sKXg_>h#gx*r1Q-1Hp?6xm%Gv)RnzU+LN6ekV&1rV&R!pTOLZhA zg3#429ft3#fkX`7`J~XfLT%FIFOAsM1HQj}L*}3#&*Hv*GK#CC)l4L1fvGquwPo~d zixq!l1(7*FJp*@4vo)gRAq{Xz(1;VvbS*FhjRV58-u_4X#*;+q)y|( z&7Ko!@s5v(!%6G56;;No=A4Dk8@r#X^sD*FF1(^&a5}U1Y>z~s;NO-Jy}_=$;*3Z) zOD2*>m>-6Z96cjA&guzE_6QT{>e>UMg)R3gU6pX0wEWuFJ;Fmsw>o>HVafx3dE@Vp zK2&NnM_JUYrr(+*pbM`?oZlMv?&KzN`E!7Qb3;g^U2P*D2W8P|^mE_hx)x~h2zKQBv)(<*_hTjqQfFMNCvn((%Ol0YER#3k%VYTbiB?mKm?HVD@=U=S5{`3KcaUr02%?l#0|3MUky za*9yN8}mFvYUFp7r>m~Y1H@m`_?@#uLQU{``lFs!5^1uFn7Dh1qwfrAi+eAuRcQ-k zROC^32C_L0z?+~tAz^H$CNwICOcajQr;eUDw$*ddG3L(O6D!SSwCR35kP{FXV3b15 zCa-AWiL1kmKU@Ff7k-_L&ff*hlSh5y$7E$vr6Y9xG_>2H9w zmDT|{IhUgKj7y5YMCuUDxiq&iMd{?cY5TPWhi8k1SyJf;7FW_tz-asLfMEaTJXWdj* zkL8uy5h{M=5#O|oS!w|RWe>+eM#h7%_m7)r)!_mA$VBdxu@!hYhce64^ zxh6@L<%TllP3sN$aAeYB|HWIAH~`5xwgS!_Qxzp+5G@pQ`_mnEINus*N4;f!1y-AL z9GqtoAMSuK24bZNJ}bIiGg;iPQS@@EN!NMzjS8>c1}DYy!ZE*pozwIZm3yL6VF{$n zG1>7l8h@!(Yr_JyRTb6Rn(Q%hQhf$8$3faXg(-+}1pxq$ag`w0?j1+$Llne%AgR8l zsMeNHL=0V5@&-eLlF(Fz<{TWY46}t@Jb8I(ymC=#5rbJYWRvLTL%YvEk`$7!WC`a( z+E*m?8FMXTalq0WQS?sk0yukOmz?$Y;Sh1l6xgJS%QhZ+{;6>hPqbq145gLeD)Vya zLb9i@?DlK{nibIlkz0r=v&^Cz+B?!xd8I0H6_E(UcwZRgo4qTrr`~yqH#t~tJZo{S z6Sk%NC@QhwDThNFUHc0jnu!jOCKs8k7OG;qB3H(|a7r7W5zPe33nzBotEtdNO-y3y-F7 z(MF%#D=BzFsr+S~bt0qBo5C-M-Ar`20%I~VJgky>pOnQD*UvUX>&y+q^9fvil z8dLTT7FZl(e-}u%V!t>Wj7LgNcpmvudSxSbvXzey7O~& zBt5!hHOAyfj=;p=63Te`ah*D+uus%bi|PG;Rh_t+RgqiA={eE$!f+s)xv`M+F4N;A zTVZUW<$teMu{XR`OS3+0ajeNP<0>N!4aUDNIZV9!~59ccGG{UpHHR;p1aHWg0Go#l3DEJg`FnC|6Y?Hc;AEMFLzu%%1R2fYTvwHvNnP*tBw6KGI;2*HeTSW zst9g!$*Q%5xMwiXNUOzlqb`u9xmVFYVfY}!%*6UD6%y9{F;tKCyFzfl(Cl3;R|J|_ zJn}66FM@{Vl2G8g}7?T zWc@Zpn^lWD+96L3{-1&eIBKB%D9hvC)@jQjD^Z@9XFhO%xy-OC!jjCSLE+ zDgqb~TNTPwtYDG~)9L8_fm#pPk>xI-+=Q+WgKzb|v>q4i9NH zZX6XWiz`b?QjJgoSF-}nOLj>yjwo#%EUL1JP#xt&n?<|b58G#N@AqQh9qI=lzZ0^8 z^eqbWCjSO(#a~T|@HE1=J`q0!Ze6O>W&$LKjb~tzf|e1`~^IP`)9zw zm^`}67B}TuZIfs_)oNTvV%jVD(sfH$Hic}`eJ5X*yWBn}Ox1+I&lsHb)7_I8E^pgK^oug0WzRXn=Bc47h=bXM(QsDf(j8{*V1orAF$skz5o^ zYCsZ}^7p@dXT{H#5xNPInIKWvm0~~=TdcA) zdN~ica`Z0Fh{2Z^u&umzTP0Qk6c|DGC+wVD~kATVazt8#{ z-b|17et`VFk>#8o@(U~s{x+z?Ii1X-18_xQiu{2f0%9$@P9YZ7jY_PcCMfm06DC$o z_;2V}VMPbio%r+Nl5Lk`>SE(SWmoNCzsibpBv+Mtwd!^~vrf&%Y(())N`}GLgw&VZ z*mOM@csLWYk^VI_qlse2R&J!ODmNsP?lR3Ev4amtCyPTpVs}LT2&soB6D@nc=YLgK z3(ey?E#f2l7XQUwt*mtczy#4sXX5?{;(iwyIyjnegxz%XZB|lQv8=N5c{RF@Fs+J< zNqtDx7Qoedjj^4bbZ7Vjt7yIp+zMJ`?&Qx<0m3MhDI9jWN08`_Cx5m>$d90NFOfRR zxgF3#j)>v)l5C{1l-sJ}*sX8%l6kz(;gZvqa$Me=gg|k}%HVbd#c*LVs{2Q%3vWf9 z0Y+}f!8@`U=B<`!2V{HU&07Psv*5tpH$;L7fOH2tAySxiNaIM%DK6KlGhQc0isoY- zgW7{z(DCw#Gcc6cD?mP~g3nkcpQc-MR3}lecK|TypOn!|u~H?C?mW{YvMc;N?qhUM z3hyGGNhGYcM=FpSvZBq<9B~kpo69%Yw=rcL={g8~3UOtuyrBQXoR0AaCkMvIG*O3| zDz!15qTKanO|xdl#)m84WI$82GGR!oVN3IU5V~m&HH%2PEo@=Gn`OgKXcJ41U9hl( z{rPO^HQXAmrZ45g(cebtkNEtH8#?YU3d(>GZCX7Y0rf8GgSjo)2Gw9&g5f+2m*=$a zjsDr|un4u=w=ud z0*nsoM)i>~wr8j%gIj(D5pQvB!gNSh8m3+xGHy0(>#2>m1^kPbHnJZxXez zU8d~8g)b$yX7V#Tuy+*rr4TK8jVcT0Mj0qd^Ck5mbtL3kBX!+_j}7`5>hI2vjc@j! z#wwDum>7@N-MZ%(Z*q{c>zsu;^0Qa)Zy4%A0`_Kt9(?QsJ|OILROH-Ax94?cSQCXS z6njM+DOk?PFV|oQyMhpaOWOXq2THWTy*mM0m2gz5d}vo<=iWbF@=xatP4an?*Rg!@ zEhO1|VS5=mQsrOCgJJf;QMQ=DJkZ6}hV|2~;n;~S*Q(pcn%BcNLUJ<7Ih9gJ{CAP| zGd_t;_*f7;v+~fo)%rx~>v1X0UO_k3Inl3fNXo~-+G^%9%;sjCP%bn>)5%GY8Zp0UX9%1K|nTq-TnuQR_Z$wjDiPUra* zf@=qskJeoHjm%u|EH(jadii1l<)RC5SawzFRq7(L_e~tBtb*2VsLi;?rZlz!#$+jl zL~%{v!AQq)uFPx&{zopOYlVAtu{nBLq@PR*(Jz8C^(oMjs-R89?X2*{*{k#|_pmEE zFYJDw5V3u1ueMtucpOS*lFv)-Pwws>B?7o9X${7QbbCVhbXx1@!KaCSBoCUdBAW$l zH)3t<3J&uY=L`Ms32BkBG1NxY5l#}nplsbSxDO+K@+Y*a&E?rb6B2qlOgDn3uEA-w z1S7=U9CdwE(T78rpkueGkf9{%Cu6+l5x!iL3y+oK*$RWQ_qE%YGD`=^z|dtFO62<@ zk|ZKC@HmsUoSyc}5r5p%yPkLQ=s_&E3fV|cvG9}EMV>M0+{NUc{+F{VZfvcR{@MO$ z6dhw5yq9k*KHL)r6`i!y-28L+AHE>N)D}?}S2Ytu0GEb?_6|1KH8WZG68D8dVSw{# zfmU11b9xFJsvgE*dfS{4L^_3`O~*19i4+F~PMi*d26)*lPrD6_LyBFzto?TVr5J`! zi281KN$V+g50>Ki=Bf+#H}Hp2pach1hORvq;k6Rg1U5wNN9W0UXmN=4T8 z8t(!EE4U7i5fDJr`hr^LJHr46MtE2%_c(z%J{7A2|hP-cgc8V|BGvL_@6tI1U+PVh#dH;n-WT`Ah4Q&=t zHUhYGyV$*J>cG^XFFU?4NItIy|J}fXQm{x!##q}oOc4B?PW*ANg{?!X!?}Y{6qKH< zA+jHWwTs?~HzdMU)vE@$Ci@Hngu%7SYN$vZi1-b*#tl11Et<-Dnw1xvMB@J;$Dk2sP5}(}Nwe`Cm}3&AT4A ziJ&G&`MoIJHNK5OcDrL*dVQwKaIQs1Lx&AawuCO^tGEv;)xfjcQ`Jv4iO#3S--f?> zrBs0kg?wna7xQ$E!c4@dD-kK1al+2E*}$JFTtg;1S8;K5gavtxaY;?Kw5 zRq=RutZ&SuzA_=^tz>~+cih;#=9!>JXd?>`b*}+9hKCpe^z^zcOE_>6x=~!Ce~ZDB z^62;hYrgi!=R4|c_NJ~GLwboZMOH#6JysRR?zhoN=d;J_Q+;s!Q#^12isupFoi2F} zXl?8Tp;t>z&*XZwgp?vFHdm?zSzC&oHq)S0{-nY#byX2G4fW}6ptUT@1|%43{9zy3 z63tK)u}+OB+4nH!Pl4Gav(i|Gj@Jo1qwH!cCU8<+3+*LfnyoJ-SoMg?hNC^DR?#!3 z)+8xWu@-W5#)S%4hR^b++&`hUwdgXHQv<hE|)YXiO%18B6MhN~N8cPc41>OJHd^>bHc@k^SVH z=HN?`>Q|^tx1-~}o4{k47uklfh}hG1j%~R4HU^CfqCxt<>ta~E$(4Hg5FXC+(%C-B zE|Zi6k0$us%Y19zn(H#9INRi6vz$gSUNZb!Q$o-2jP<%qo0xyEYFSk@PMmEabCU)^ z%Tl8ajv1N z!*!lNVwNXojV+Oq5Uh()#RYbbkR=d*B=LI7NRvOP;4u5@?F0S&b}5tum6DFWvLF|7 zN8Std(Ukh*aL05#P8s=kVnPxI0JR3EW`RUUpsb4DS`rPF*qjn79!=w_qGI@{-~C)q zOLWj2j;y>OR{vEx?5SF-hA1HEfi&pN^!sTT*c;mNYU$3p*dwV7Q+495T#mw8v@%{q zk3S_%6+95$DtG{x@K4z=36*B6i!al;KgP^Rh`q2p2_IcxJrV{Y! z)=|hy&)2Rq$uzo(-sJDxOIMtsskjVQrd(!^&V?TZ65|t*!@nG(yCaQp-7)7Si}_P! z4anwI(K+^19ertOIQFBj-+Bh_zrggcD?%(DplA3>8SAAe*BPIedW3O~5amLix2^D~ z^-85Wit-nOf;P%zbGDS|M#9eKaiXfebJtC9jM^EgC`gM|(?$hKa zlD^DHNzY`!mUuojyciljH>kozJgf7W<&a0b4`_S@?I%KRtALt|5hmaK>OziQ-kmhq zzlNFby*Z7!lQRx$#ej}yDv&^j;p~x}u(w+&sCpGh!mAy4aQNPo*WB}wwy$OS9PiHq zG_pTfTDUCUP9^bzsgQ~+c&Sp>CttGFNhK!jD*sZ=hQv9xsi%t|^Vg5U)Dm+W)DnN$ zXbC-x1#}<)lBQ!2*uHhW@KV)`y?=CDJTf-Qu00LG z^29}a%FXzQW$!zC<~boh3G8Wof9n$t^2mN@DVPc8oRdNiN_m5KiK8AXl+#$XrY> zq+G{b=}9Ot+90bL^0*s^f<@|71axWg_gpJqw{ym?adAP#_Bz`j!Xl6@>&o^8RMJYR z&`2~14>39C>h7f%#@^0!|22d4Ijm$~;crA%3j&r)gM1k|56072iqwLx-&@;Br99~? zv*+Eee@x`j85|U5=K{nEA%lGMBdP2trPa{EIPrb9VL6RO^v$-_>K8B~RsHSN*)b&g zNVAA))pU;d?c(EKKT(e?)?1{DJ1{TdNLfW4k%)ZhB;u83xW~zV>VH*|`FcNmbgM;2 zX;7A6vg#i<>3UXRotthI)^fdOA7PT%2pHvZovn@*3Do}_bUUlGiE?bOCL;cL)}^E5 z^bw4n<>eC=SjANx5X;=ck`YW$Yz0F@!uWh)?(jdSszt7tx~xkRij_JtV?lUG9cQl1 zS8ft0h!oA(oC&(6_zqLAVSr8%q#XyP>o#6bzT>~{hXfZQpP$#B%gzpiv8x*qkco%jikKczrP!%}e1P;9L zK%IP4>xj_`D}0R|Au;j77FH0mh|zd!7jdKsgrb~G#V{<0Eq0V+IySv8t4qtLeA8|Q z<6N=9S8{?<^XlM#q>^5a;B@nMePcPQk@%>_UnTC&ZJ_?CabzZ>$seQ4+-c9#496Z4 zSMHH3E=uz12?~=V(ER>njzbKge;DE<;yOJEThvi89jCCJ&q;k#8x6V=&r?PvRu=C! z`MziAOZm*m#4nDgLLC`^o*g-_hTm5YmJbaw5ipGRv{OtW5x9Fox`{|jU5k_+fGkhb;2OwqKk8TlB>!;!G33W` zlPD-N2R1*2jy|RT11o)bR^a408tZb);98Z6LFZ+5lt|rlg z2*c_qM*z!GR#fwgu7?Xk^)r@>r3K!pv%;(lC@q$KASN?aj3;@0smU93?SR*KZkVPo zVT(ZxF^EeH6x40|$dmZK6gwy+?c3Sn{C#Sh_2n*+?NA*CSUkNdN<;GGG%8s{BMpjs z{d_$r2XGPubUO~S4rUk0y>iY&9h_nz@!O^}%DEUx8Xlg7^N`o=SxRiSm^luAT7U*S zX<_u?_>VU4`<-DBtY?ln|1uE$#7v>;aHUQ~x9_kQ4W-bJ98qA$zrBA|=GvzO2mjOk zTyXE84NoGII*_$SSKdL!jHPCa56pYlp(aE!1oq2yJg}}!(p%b^4B)wC9Wsf3=r^2G zc*4buCL2ancE(HB;bBv?bKpCi2BUaG;jGq7ZTh<%_a!0xoRFuIoi(+7?5SCyj@)d| z2Ws`e2drKZg$elTpk%4ly9HDqSetk5ycX4d>;ievHeF#SZ@%`-D*K{J-Sw3J8cwIu z9wRGMPr@2i-aDp1ay9;Qs*j=cy>rS=G!vkW^IjmGuyDwUh(ZF;9n4ar;z#z5yjfIl zw57f8ek=b8RQ7p1yd{V1giWzJ%Lhn;T}MZD`^X=kXK;iWH8s-{$29&+jtC{yzGo5G56=S66{G4UX6PS!1cyzBC0yN@w9`rGRqLH)MJ zO4oF|S|2D0ZUSul%fdE5t{E)zYc^}71k+U`;y;#!xORPc0cYzO)+1$8QDcdkLZctF z4g5oHHS^G#v69RW$&qtsjq1+_tFS)-2_&QaR-E2-?_42+R7AH}<=&pU@xq}_{s0{i zW%2EE*v0)FsnVCkxGl5}VUUQUSon&OVIqty*z3nsm_I6{%Urwpy=jca;yaUz7A(xx zmetDO!rT(@=#W$bkt#e#O4jYvx$xf$Y^w3xIJ~-HQMhnq4xG#EE*96!7h5X+Y)q7%rA^aqU$A2x5~#Nxa~C61?D1~AH7YV-j+L>tDX&Bs zl8D|fbepL7uO$T9m(su``##NOs(D{*l9+(+mg9k(DNY<=PWl2uJQBqQO)pvUYtoM^ z%nct%!ar10;uXYoH?D9}CGQ!DF?)b8owb-vm;tW&2s=~5OlY} zsSN7(+ZJt2|A|>$dmkBzFtsW#irDt?wZ`<_#RmQ3F`w-BXgr=Q))jE1O29%lecvxO zFX^kIxjj@Q4Li|+;YHIhbz4H6j)=0j&sfKQh|Pmw7=;YJwQCzy1ilBITW@JC6&rs` zCt(AbMzoV?&}cs(e}rG+MG?Q;20~3&x^;5@@Vzqx_Ne)~Kx(kSvDJPmP2^}#v#u|G zvdH++6bHpxs6$i>*2EySX#*z2NmuZx<-gi`qD%@EP#^3!4u!jr73s5*O(161TAMQ3 z!))9-&u!Z{*?fabw4~X^J`Hv+`=6|0oT8Ctv(hNe@Cv1ck6mVyF19E`pNJIu$1x79 zYS3sJnkVm6GK@=O=qz5={pMHII!->jbhPMjeXw}jxHkfW(~+21=-}VUYT`JmnADHd zIk44`FNauaJtbc1s?2Is@D_b!{2k{aURhY)rXalq+~*v@WQ`xz@de%KRNL5uMp}(Z z!r}KEPE>!Jj{x?k<<=%fFeH@q8V>5#CZGHs5dJf#i^yyrm&qL2-J{0X%xjjVy+Lga zY$hz;$(FCB)8lfve?ijJ((>+>#N{uE??798lmh|8qP0b6pQ+zBRG(m8El2RgTdk19 z7w!sSwC+|}asZ~WD=Dji##WWRyjpWY8Q?j}I}=vp$ME>6E1Ye6FAFUeuattugQFqT zOr6RB=Rgy=+$nO<^dbGmuvf3ciR7?HZ%Jd;{Y~XP2`ZZ$+ICwMo?Y8hAE(vC+=8`7 z2E^Ngv(NvsLQ9Re;bRu-DpT7=5&_A-r>358cPXQI#}P`@CuU8%zz&hlCh!(Cx|gA- z&qEre_oiZeqrAmvnKpNL%|%7rS#tjPH~rXoHpdEoKu4kdbk1Jo@f4N` zTYF#f*cnDi$Z@Ee*@Lv^DW9v(@_ww!&oB?YUA%s0R6qKlV)`>>wYA`si^Rw9Q5;N4 z*D2St3p>>@xjt5;LY_fhcXxc*V_*zVxd3Ta;;cQ)k3H;WE<~vuiK;CVu57Dl2~AQ? z#HqDg{fOE*i*U9&%mc@Ll4;a@3DD(Ya>))9#NQGmo4LmCP?s{b#X*CPH}v|CVEn_P z@J^W$?^GUaj&9}IlqlL(*O>XhYJ$X@kqPt7Bx2M1A*&_kxgG1ZepEO6RszfFFoDf4=b= zvD7f+csxVo*tj;Lx*_+m-8N~933=e87B?#sV0#{M*(+>VL0?6wQzm)a^r#ARFpP2r9xM0*Madkp9kzJra}Rsiw!-zB zhawx7d)^4-y>h+S5Y>*qYqqKsGRVmwUaE9;627mHMoW*11SSsI7VpLsLGck2!=R)9 zC0iHCS+oanxDLV}O#f14^1T$RPJFsjwHFFgc|M#u5BMAeZOKM&oAQoJMQD9iQvG7* zE)SdCHSc@UVv&mSU(>u{acdcgND~$oNnZ%le0e}YJ@Q7m^cRYg?wfCeItot7o_f*S z9zMBVu%q2o0%16lqK2hU^cf;AMAh|>Sx}p6?pjM>4#g76PA#I zS>H2Qv^nI)uVHwzGUfE6%?wwnd2FslS9J?f8gZB04o@u=rn|vKF$yR5CfGsKMR;yc z*7-mQ1(^jNzY|Rrpay^g7wXPJ2S_&bTZGUw&CI3h1+Vdui-JjJqAwGS3`icxW?>H& zra8pNRrd{vB9Sws53Q;C$S5(=$|F0QTb6)!FA%uGHRCE~M%9Dcj!EVaSDK7eFezg2 zuD3U$Jn1nt&%jjK8TmMLSdtzd7EdfN89^5%qQJsqgBY4%inD7QZ@k z$ovg5W+NM=ozG9nQGE)2eYQ&XpAuW|MHkdYyeZ|(4ph4ML%S>+L-sAG!|%TIY_NxV ze>3`T=N3M*PPp<57;`aJ|DW0(EdR0X!Or&I^$sS2e}r$=|9<^%2p$I~3+MkCg4YJB zlDvt2CreDMy8uI!BV6XfzEA)&_5WRLM+DmoN>aoWN(&O~5K>am5Kt1(Qc}KW&;Ga1 zy}MesU1l{Ir&qf(&M$mTcx-6j-ab$WA+#!}fa3RoZ=fXsQe0GK1cLeb`3!ye`3M0q z(-2`!fj{za2F!s(yao{MOMNWK@d^wVTBR^zy3`j0djhiZ=mZiN5J*Wtk!ZLAHt?=M!#Vrnkl;J_-WFaQQtQGaS@hu|Qcg+1@Q`*r+Q zDDD=gpV_MV38f&^)hTd}0pBw6m|!4Vx^~?419!tOVZ=R#=6|)x(gop(A2qhT> z2_!^RKq%uArRnziS+~J9En~ z8RrCb;DNvTDof}3%+$f50zEr_(ya3PR}b?6+#TM%i4E~88Sp7Y@WUFNzp9LX60v`? zS$xk2;(C zBKPn?j$hajf3Uy){EFxQHu{SqeItK!qnyb<)oH9sw(IIw-u%G-Bzp+>zL?KDigRmx z6wwP8`Nn#;Zuzb8*F8`uhhKtY;0~=%f^)8fv*xT&$$vf3#!dB|ZMDiA7!J=BZT0#g z7?D5rNRHx^!e4({%YUEx{Sr*vU$bI1FiY;VFLsbF zC{0TU2%MGhoBkc#-X&SX>_TkPO`@IMRu0nW3pn`OB|cqN+IBS56;YuY+@fxz#Xc)N z@_rC)Toa@(Q-8c^Ccm&XB7D!dvq!f3NSMLF<0YTV{Vx!c@fX;m9hY1uq*Vjy4}Z>+ zHU%@%!&!chu(jY&gs;SpT{Lb@dv2+xHI}YU^P5c&>CVozlB! zJcuuL<58Ugj)Kg#ng~QG3}O$n;MSUQ5}e=5G`D-yPrZyJcwy*l0PcXDsa=TKGZnED zEYvS+dX{-!cGX3_DNPpBk>D0QgJgo+l<|ZtIUtwhu8)>5xl!?4Cjb zs^jeTa?wn_$+l7m_J0~&PWN6Z-&2UYsj!kDrVW~R_3Mj!CMY}h}9JhrTXDc9Ly(%QeOp$M)^ z)|=??t(Mh``()k7{IQf6LfSbrngllSbw zA*I!)`lagUPmEeh2yrB#{N4@SJZvlUb-7sAkR*$&M3TByam_HK5ZWoi^(5^*F>UTVJi)3H`1*n$!yAxASl7Ywj^YQQpMq?4DofZ zHOMHm=dn3Cil8jpXV3{WRvK}Te4Fh$5X*6ezPaULnBPuf(Ry)`rWSN9z{Tp=CWTn- zjnsi8Is~UpLE|zJKD4d85H)gArkkEH6df>~e|r+OU3L?5tADiPRrdTTgCC(<|Be z?IwaB7ws{XIo2q9sX}j)>)9EcjB&$_M!_|^-DD3v zS47K9-G(8zMPAWzcvAv?+|thTgz1s?cd6XO$mPiK64HCgeqZasU~!K7y;cE~7mC`; zIupn^K15%6zU_9RD%H8CjdhQD0E1xGXUrRK&CKM;OsdD$E1c8}0pg!(t9G_ICmO~8 zuSBvre8`5z4_TP%!TIztE_z7h`geww?kqT_jfH!s&{Du(ZgjxS^pF>~CS*Jtm|qWG z$78(N+4w_V?3t|A;PeVZVfXeU_EfKy;c>+zH{v36 z5Yv#Mog-GfU{AH$Ht9(tiiFzdY|K#Hy6b=r8ILwwr3m)NC_HPzaGTrCEDueN7EgPt zZAovNla_a*Yc?>JclDIXQyn|LZY&EDskz>ag)1sc1*tGZYI33vT|ea4gB0wpY??RQ zB=c025PGKS6LFAvZR+LX6WB7&JZ-I%UjmUN1V!D6P7HSdASf1@p$h8yKGn5ATgn=`M8wK~O| z=|f7I0}5#{F{}@dvPyJk=#sIW8Sf}eQlANPC6=Dd`T4k*3Bdoh^+Bv_$OJCJDH4k@ zkhq`tzK6);{ifT~%^CtNM-xqccL9-?1X+t-rCN;Cg+_wtunMU(n>eb+qc^ebrbKWmp zn~{zsR|#UDXO~6nuqQO=oR`{xj?T4=<%Vtau*Bk1>HT<$T#q?#!ibKRPLFeYNwvBa zj<#^?@YNTVn+5fTj~GEze7Lv689P`g)6aP0YpauGhb#^hY(qRxU0pLobx`uF&p0_W zW9#tQiRNw+EZd%68p*8mE4n=Ol#M0#Bqk3j zN-N=C{NWs_!w~thXsc~CI5J)-L&(=a=rSa-K}xh#T!p9Q<)<;-IlZD-Au(xU-z10L z+pY8;fYH0Zy{d4IR$GIW=2=bL9%zew#@L9>;QhUW_7#MLthhOhwl+PzM-E(& zH%Wp$GHU0q%MswC@~Cq)1Xt;#3If`jP#1+`O}UtCuk4!|uqUP88LU=fU%Nc951uOM z>X*w-`{_gNCiWX0LQ1}gr9um4V*|7Fy_@bFL@AyEos6i=W)q9w@G?R{;dw|b>V0Do z`n1vtBV+ZNdyG>HDsImP)joV_)ymUZ68VmF}kubebs(yZFkRaFpV2S5)X`MRIZzuhZo{YI<9o zqO4iVapldLF|{BhOJ7h1wv#^l%yxM~nQxjaKF|n06HR|3k?kdoB5iR8VbTr~zlYMu z&7{9IhO4*WKGYzS_K!-$hiB?`6(TEge^aH&C?i# z!0y&b%`k8n3v3X{^>8bJ*Yx#wQGCn0_d0Tsb*7+S0sN z9#aUGCWxvS`1)ipxiuV506swy5l^f*qYdla?NHeKC?cR&E6N!k=k`zHjw18AX+LBZ6a6#-46daF8Bb8*N?$7~-y zk6^1U<;D+HTkK4|xvPW{P-DU{Cd06=idr0Z9adgd!kFJ^KbhGTb4yPZUt zc|fu_EWx+?e6Wt2q8zn`lELl(qz8n;xx%8`8GSEt=X? z#yOI&6(+()`ZzGN&I4N#)jSzhY$EqF8FTO$QDWw*>&xT*a3;be8?MNcaNnO3Q(}I$ zxY?jz?_z&-NN?enleNFQ_8S}JThB649ahitP;yr(b+9_tyE>S(MlUIK%wnTc1-l1}hHvGCAZPTs#v&^M7=u_9~wQ)eyV3>Ch8A(iu{ zHS{A76c;hh&J73-KLutMrk=Uk8lQ^;g}=>HfWl*cZZma%+bIqp+m}(%5+T?thTEnY zPlnubtDJ@;9NDNwNmOSSQjBx+JH}+iLy58W{z1UhJ$e2^+}pwkC+$JFl_oWNkdeGI zaU7EE=p!Y$7xkCTkl#|3#N!_a=yZ5UBoJIA!$-Pkq5~(w3Jt6W6*yKrSaoAa`~fqB z-uz87+E=U(G+qEU$0WuyJSus6wX!+aU&d_qK6#5{2-9g6M=dqs1ESjdIl@MBvo%G( z-Sn4=Vao0pDb03fw9|!43#+WKy9qqY;a2UE%A<^LXpWsI?JRgWd&xwnOD%K9_J|q~)l8l5&tXe$22YU|rKC7`#1E z?CymwR_I(!Q}>q;<=v!%Z=DoRTQQA<3_gQ8fwxt`@`n`Qocew2Ua@YgH0RJp4r?-w z!HgTAgmWfs&7ntQVFjN53Thnw6u&d6Ir8A7v`lmPSK`p-A;+XZuHD1$ckv31t?VW0 zBa1+BUz5B}q7Qg9-7#z&c0495`A>R_i`P9RRFp93BQej^a(ia}h`U#gG^tWI4eU7j zNbqmmRf(wht2mh!q1&*OTiq6pMo&pRr~LAJ z^ymx}$|$QS7%$~@VgGWyj%PU(-}Jo{2H)n+6g~guk`0c+OziCY_Tbrkh2dsX70r?j zdzmHT@RVH$c}x*23XE0+Wi?V)H}ic$d5T2uqAeCu2J%M;c8h=D;a1+s39XW~N#NZ+ zZMjWMMO}H@sMvc++=JwZ7hu{vB|)Jse+iF6vgd0nM#wzPDgw) ztR33*iX(rU>GF3|(92YbUhIhq_EK(1O437F6REo*LIHWs?GP+x7hW&bJ+^pA^7LnH z(gAT#G=>y7=a6gm6sm#mhZ&h_M<3%3b+vv|?Z?5_8tsHptb)+m;PddWqi;68=3Ngn z3L!k`4sD5j4&Pd@-aw}10?V2us)U;)kL6b#!l*gptnKeDsC~UH6#Ih^YXFmARS0fy za^tN)d_Vr;{rs!c7*)gL8?f}ubcEIuOPX_R37dHkT%X?lUhW1I2;yv%f(BR8Ga_o2 z&>YZOK3p5@!_~G5HdGv}Lxc}J!ge;+IL0g2lj}iySl^=u6BZJO@OziQhP0AF9^P$w z=ZlxkD23&?nJ{7b3-WMv&&j+E4*DkEiMhLG(7d4|^Nk%npT1TM`6y4fn#R93((o)tB=MMfk$)FJ(1$Q`#q{PtLxFWSupe3S@vx zkw~CivlvFvKf*Zn-2+y6R4r`p0F^n}5SuedR0P>RRk(pEFh?dcc23l8;$j^RRcpW55#p{LM9}^`n}b?N^y_!gO9g zt>9|ZedvIGqXBi>^k^;=2mb}T`6{$DaYxtU^`2L!2xvBS zdKG<_IOX|Ws?avl{zg5SkLW+lt%V^JTLb2cU+7gjb!)4fAg=ofA9D5G>n~p025SIB ze%PNT2D*6Gx(_ccUs#?*cRZ*C7jOC*nP7~P56X)J?+4s+> z*ILq00R1PD-f_NWkBJa~ zWmt3C>E@f(Z^*#3y}4ygIP5d8@99&Y#gPnD>`qmxu==NgBs5ZXeo*d!gnb|}wAtFY z_po~>z9ZYH?t+8UU! zaxE0RC^kF1^2Mu5vgqD*xXmj*C3o-9O(@;fx!e{^SErp4w`8k;h^zj~R$((M!+NOr9foRP(+xU#O%f9Q| zI*SnR-!UU1lRIk=Xli+JvVE6$uq<5AeOS|4Q7Ny9kJL_}GW5Y1gH{d}7qwM$^!}bH zoTVp;WulWNM?F*ueE}6aX`e_6o?F9+LiV}7wl{sW)X4!R-RSKRc8ko+31p_OCX6Q0M6t?@JoQqo*Z4~ zXDce5_YqP;Ajh0qy%st{z%V$sA8HYNrXwALZI(~7pL?3=3(yn&0t8}7WvoLKM0$05 zpwKib2RDs9e`W6$xq-IqA8gQ!J}2YE`vDY(&{gn4Y(Pnk@}i^sqZ0H}qtt);H%S&l zw6PW$H^8q>%Vi>(c=%Lcv3Hlr{{#y6Be<7kGDITxQW~2Eucwa^O181MbVr7QMtF4Nzmc+%Yz5AnD^K>-7qaiS23pzb- z4*9_&0SQN&@*FjbSo~#r`aYz>kX5##tq&Y9J|w_ zGeQZ?>9Vzk+fxdvh2}kv0?D;w*66af%ksA0CRHYi$@l8|Ev^Zw99tKv2kmi^2kLU& zM5c-Ultb3(>FMP9N(|GGD`_Wvx;a>m9`zD(s~GQ1q#|9#WU>PvUy(Sfb6KnZALTmZ z=oJtb*7t8!G$o)6+-ukFP5jcP9j`tLUOhO1jn6t(f4|OIMa{nSMppB2Ak598Ixp5~ zvKowItOdk&NkTjV5yDDSez*Ol0NLOI9HI)NS#73^*C=h>vZHaqDoVU86GAlfH{V2` zOW!mP@p&bZ+t73g>E(^i2@Sy91al<4yl z_=nVn*dlbau>ylA7vYm`flvnoRFC2$vh>zo*?|^Cx4KMKNGlA(BU`nXb?UyCu~RG? zcpE{qQfB`7^26}Sy<#s}{b|}*Bp={&?}FE_VgQk4f`a&J?1HS?f$doq(f~-TGSYi& zVMP^`Wx!!bq)Z&xGZow{i~#?rA7V?m)*M_eYR{d_tiAH`)o}FG8dE`8c@zHVh^uw! zGizUc?*)`6*SP*N3(WE4L7g4~$ek?sBgl2qocu|HwgSJ=ldJS!7g`7xEad@;ztmj9 zqxR;$nLMb9ol;K0J+XTlL%0!?us61i%BcFDAQ#Q89V!_8B_N=?v)9qw7g?GyIO3wn{5 zb3`QnhzDx!tE1~FkQoxQvl%n`@E9`Uv!ioar+UYS-Kg+Z#rhYtH_1?Yjyd0lt)_Pv z*567SiH&gE9qbVxfvn7PDsLFx74+u`w6^4>7! zdfwsIjRFG+azvkAYNYNCG@!uhE%t!>acgA7`y$pNaTU-xe?PXY&`*xqLDoxTI8UuA zCJOOxqU=_@J+@R7gBTVVuA7NZCe0puTr_^q*6LH@IEQH>^D*3xHjf++F;7T6vCc?b zwDHy6*G}?H`yhr%p~rs9X!O#&dkxPle9wJc%(n;I zy{1|X+9HAWH6X48U#G3Fk%L_ixV>0$)Z>ZQu?2rQ}LU%TS?(ayktxshzYOcrg-Y zWH>S7NatO?wL8mkE_8=~b6cjN4o^Y9cR3%jQDV1{q6JC$JtP7wTj;akCPi=-4wZI}{j{S?-5 zmxWeJd#pKWZ?9e7?XehVp+^D%qj+*Q6Ti_!-2;$j;Amf|T6ZbM2R9B)FR}8qk1YF| z$-7f79T>Ba5hE$&lC*miemeD@3-9=nIG`fs7RdHy^j9q5-#VF@AF*Dz;-|);Vdyke zWg*l#Tt)7+3oAQLwD!_rwS8Q0M7FksBcJ`WGt9#Aee^8)^`{wNz!ES=F0s^oRQlz1 zSr04}A$exSyOYOIwA@~kf_ULQJmRJY5L=DrbgP31Jx^D8LyDk%?MC(0ZN;L5xYSaI zjkJEh?>*fh?L}J?(u5joRU&(zjViz<>7fIX^T&H)$fb{(2A+?0nm7b_1zGA&DcKLXxbY`Bq78>g1>IOI@>@Dl`mepIlV7VIA^^9i#TIp7Q!S z`ly3CvCEI4HtD$J)`Ai>LJ_Y2;|O4h3ixD4iAV13kzNO7Q?%NKz>r@2@LFnC# zom4bb%~pls#*TJh5hKZ|D;Z@Cu|%Ursjm>Uoe*4M`p^zxN4bAvsIuerT9|2b^a0?v|cjm}mbg%(tfh+HU!8GJVH zeani$9IR-Tj%oTYkV{x77DE7`ShR{j7;%p{HpMGa{^|u{Js?4sjKWCRCVxa}NpNvxi|GfCvLC>^YPlpbrZC z)PGaYp8}cS3@DSmf5z`-TueLy9vuYe0LIP%5+-oS(~Y2j0Tmz($FQ;lc;?-Y;6KLY z4*?X==LL*_i1cp%|M;q)LBxLC!Gs9KUEmmjp~Tq$u@3AQ0{XJz5QkBS00D?|`Xcq% zSdow5-og8J2H-gRuQLMxtfImI80vfa#|4BG?ciXvAz@wLRElrv7&>XHhzh2~UEDB% zf=Ry{c~Cf@!FwCAs6Wn)wGhSdgTHm5#5jPiU#cKWlfr8#fUi$MmX%+k0~uq#t(*f4 z0FL=65(l*$04IPJLG02DYufE@kVdk_zOMTb)iqx{xe`$c=b0M-O@-b4UKfZqDvJw8GkJf0qbMl}eF1-h2pj_lB&2kZ2#Cl?;o{=~0D*onM*(1d zt?~Q+SvwJ9B?6Z6t`9z*@@Tz(O8|EIN`v9=W;MJdvTY3iy;SXhQNV>9_=$dJwSKQ3 ze#!6k6@ToheqY0uy0^CchPwOif8k-=!n+KAiS|@3LkDC7=#bdKBm9-84gE{i(7{5z zJASd3{{}cF> zG=Vw}Z{u2IllcoXY@K~Emrwx(h5TeP#=q$TV1xo0j|Xy42L2re{2^*L3>ozCufiap z2@x=IpaanH3@)9$j|X7Nc0!xzcvxT5Ps|Uk-GqRYy8|^BRpba1?U3^5^-Azg~$G&$;@YQCV| z4?!ap{1<%ufA(S}(-%EP7}eBoM}iL~FQo=s7tW7S^bJ^rebbyOP~f>`H$DPdtxUtp z&WyErLq!6Ec(ofB;F?2Ftra`lmPT|@fgB9Ci1UGk+x62@*<5DM^Ht!t`~e(kC%Tlc$;!+oxWkUp1nvjg7eG8NK+oRrtj^ z(7SzT%j(NZ6}*k`jLTOg_08Kxi%obSvG&vr)$y@D6zdIQRx_yS)Ve+eA9iUkoESER zomVKt#18|+_{eeMk7~kG57*49V0ybEU)nQfV?WJ>lbIUu`qc(Gz+I1&LW!k}Ix^ZQ zQN%EExbZSNi!rxI7VRe1#!L}8sg~W2X&SPrTc3;bw5|mEP010MhPT$FnqD~1mS>@+ zU_H|mUz_RmHX<905(2}{;cpPGR|2ubGDId{UzIz#7!#r1c~QBL61U8Q>S@#99agsc za|3lC|q*jz~T}fxxviM~JooPHELvdUXmp#NuM=OEhpii4tkxhw((rk+wOn*oU zuX{3p_I+&!tPIZ+fQQmH=yj9KM>x>8GQ(UhPOCg65k-a*J?hp9`-*45UYp%KR@@iG zQpBs!!%8dqP|FBYRc$yn(&uPaob#ZW>U3bHTRg`?m<|k-ry!*T#_R^0Di=7(Gls>} zPbbvKaLbcxOZCvGEZ{#rPD}IrAWxT6agTVLK~=98vB}XH8^!M?GgVD^D5P0q!w!9$ zs60Ehl(vrg+|<7lW^!km8TZt-s#?VEX@hyE6?$-0X{+vV8{&nR#Qt2PZ0buXdtx$+iiJ@J5o)@}Zh2 zjHAx5QalsWu7gcIPcjevWnb&RnSo zFLNe4<{a55y7<+%l}cPho&U_~l0Y$~jV)7k4SD#+t7YjAfcThvIJF48Don5o>d7ll~--Q zxz0ah(vYiMEFhnnD#h55$CZz%hujgp(-P~H&fp;r*Ozg=kn?n3xXEM4{PDLc_xpP? zsRCp~I{6#+Jhk_Lo{~=$X=wBly9r5}68GB=o=NiiX{|(WvJSYCRGGgD#m%m1&$!`b zaNftSGRN2KnwS(F7|RIEM-YamQo~I5IjXJGSr0qTT{)eSgP0}C($*QOxk~uRXl$sG z8IE z(;MbWKk{lvxYN*92IN~+1B&FUYZj~S-yIZscwor7b^v`Ic9SkWuUK~qN44uXGxnIY zrgv1qU2N}IY& z&zlg2zRpu9ie6b6@^!~EgG|_=)ta($(E)7(r&A163DD$B6;XV>K$iaUTt6@n4AAoF?+jbK~Cw4e! zUbp5Zxx{T?k84i^{X27%^>Dq=-pV(|1bU7isYne0BNtqPBB)-!dF&}xy>5fE_Je`s z(XUybWcxhNw4G~dWGNnp*Xg9xz3xV2Z&BsXwyVt9vgRK=k;&=1&NxvYRcr86^<`22 zlpom{6);%w!m>f4o3m-yXN1a9%+{t@9-(+>(etJ1h)B4R?_cNLAW9@3^{GRsEhXww z;pm*M44umJx?#k2nBftfzeCh`YcbO87A+3h{SA0FHZXROl-9=+N5DLA?hqg`#_xKV zKAuLq8Um5*l;J`V)i!y!gy9s+kwkVL8O3gq!^>wkyur%Z>&Q~H@7Wn4e>3;LfR+r{ z{%IEz6g9^ae&z7vffEcTVQaNzOGhXn&wZFeqp4V`S-*VKDbO=YChstBGL!M~o}_m; zOG=5`#k0MLflx!=|C=_1ufhR*2%{5vTx`;-5ATkTUEXZ3qf6YYM5Jci%LvB|wjS*ofDm33r-v>UQ_Z)o*^Ug2)E# zAuzn+BR15#+6^?=?K@551U(>Iy5B(nRr%TSu$TG;`S@8oyXy0oTwmQ((p>uKBnj*? zh8JQ!3Ao9w*RQ~5waoARQ@KmMaNc6pXHm|lq_k)tO`u74=7dtIdXrk_Nf++Y07YC=S4rzJHO6Fn);j5~xq7-J!~ z`7U*-2*N{#z8zlkkd-X=gSk2yW%m(B){L}9np;bfMXA@Zb+NQ-5br4;8g>$%*sg5g z_HnQr*I%QA*pznB3L=iF4DDb(jlpd{yJ$qe4Fzp}ZMjkMFv8I!K3Km+#pGhmbRO<* zg5Q6++&2^Nk%qhPsf4I&pzZdx>!B#)?-k~0w`=IcX6rTZ?@xK^5ryfz1sN1%?ciXmY z+qP}nwr$(kZQHhO+xFeL$;HEY_#WyPR8mQ;HRl){t-Ua-IlG;>>GM&RFI9W(d>DAX z&y3DrDGr9e3Q4&XZG9PTn#=avWHAHXc=RuI{UA$;x6nEomz_Bo4#q*{;wqo>!*99= zEz`VRIZN?$klUO&TXAgt#T3cc)EI(GjgzeKz0&F>1M9JDmze+t|NPAy0zL*Z?k*NH z(`X4i2fs+dERwB#e$4Scx(-Q;+Z$jS{Q|9D@}~-qI5PigEZf^-R^8D*|IqdSdg9Z~ zR1vq=JvKOh^muU|wvj4VvVY-o@QF4i$xc!vGxL^M@w^LLBXWcrD-bo-u$E(HHL19q zvSY6kx>GY*Jed(D`ZP231()3V5FH424h!1wb6-SAp;ZjEg6d?`d3o_|63b1k#cGaT zq*%5&%|Pp(_s1tNzs~Jbp^>_>J3Q9uSc?8^af8*kj=G>R}wD`Dk zFJ$*gXd*^lVGyqrh^aYdBLnyzadgW-w6o)w8pO*(phL2ZRMgPskZ=vZRSLXF$DvQG z2erZ;a?1E(Yk6dj!`7H%Nga_LHMsKKpF?Vj&kLdc8m4d5X~PB7a9y7^q9X*2(c1^G z?o68CmXo^qac0@vLX49-|D8#X*qh-u>I*gUf^tysFE(Orhn8D}>CZcXM*jnun3e&~ zlPsg4M}pR(Ix2g5y9Bo=U(xJCyP3XLHe*}WMMhFKX&3x@*sayDe-+%a|D{$T`RKu^ zv6o?=|00fMJkePru}xcV0blDC_ctSZO(S%N6vbf~bNj z^z`nrO{qujh9BPr0!+8xf6y`_sL}X4qoGI0E#tKk69dC!bb9avOM>;7P5Dj>L+<6q zAr~8aVng^iM->zt(2U3>>p`Sg=Pgh9e2Y={QK-H0k$O;p#EitPFGnjlbYs@8ynZ*z zR6EA7F}p(|>TQPD+~m(@ZjnMhxp)JvYfp+IX``_yWXW2M@Q?8T9JO;W6_e_fPuKEs z9;n>)!Z6lrFLAHf*J6$;oeZ~ZMD*3)>!kEQeag2?c$?Ar??-3fTH`2RQU!7EJeDeK z)WclT=^S(hhJ{SgN2S#&0~y{|$lAp~Fwk|u7~r0nV2+Us zqm-N^sW&~0Itg4Y?jTmIrPf&~A@vVQ!UkKSW`J&`E4;6%BKF-Z4E3lz-zl!n)ux36 zuh{z*tq(Do0&29euB=f7E^Ih$&ogW-ehltKLOV#LcIJ8Yw0#arH0i&W6jBYN%cUM0 z^1r5Wt}k)8Ix#pIfq@Lt_rg+nL9^S}!{f%xWs#^EHQ-wSlJWx|zh%WEh;MQ1J zo7H-^l!B^icL3-yn%l(8&=k#&Ze(etSbz@cY8W#}K|9`)V50Q=vy6>2?z-0C?0@gU zt6|$2->MQqnqK2siA|{$EX}sM+2eikq*Xm%)M*GO+*Bp5co(kkwlyUW zDvn-NW;>($iiGm0?^iBEJnDQ|#nZOupO87YDV&EJdRx3=E~q)WX9RB7FRv7h7^@_? zQdZgFY)X!}0wYhe`0n_Sk$kMnC}i#0UZFX3RW7<2QS1q?aTn4`@unY~cXOC}6da!} z%31!sK3V=^9x*!J#aP=G=WP11)F&h)@GX$bgaq~a>8SawSatra-FZfyvlL;nkx5YL zIxxvh{yp}`b+OVd5yOc%u2#uR!qq$<78+aiE{!4Im3_0>#NxItcx}Ybmi2?l*~?3P zl4c8C_3)>P{L_+lJ3h<~9*uoEk*2%1qKiJE{oT!M5Y~d^gTR1!FDo3p%&JbIc(RS6 zsj1+(*%=gPzK``5S}qqJ>ET+SBSYuOpPL$&O0Yazd0O zcB{}}P?l~}XhAVhJuZUGUP3xJCZN+!+=K-dmHq%4F7k5biLz}xZ7)$va*AU4)o`eZ z_*#la^8J+C>_2NRFl`)o&I^3oC%iwsG6hJs=m`15(W91t03lmMau)Qbgs~V!vbpzz zlSV-U&ym~0Jr-da^*GpbVA+E-U=G>h&{e2h-?A@(PHnM!HR5k7~8b)Kd>P{;{K`dgT`a0v@~O{!r4j9v|mgHQi93gi=(6J>Mh) zmrTK1McKeI<-C8=QkBbzT?ieZ|EKq;gThoQ^!vT5@`l?Slo4gO1>E(Oe2IX=!z?z$ zWEHsC8L4R_Y0b8FOsrvG=1RdK)2;f(R+d$A#m;!m zN@3v6CGmxr-mAtfh>`LLlFo)9&FaCEa-I`)%8I%?&4fa~K!S8wuC<-?sU#Jc!t*K(1*hnseLYt$*)dlr zi<|qiNWRf2?>w+zbr>HG+XE0Osi() z(dQg-J_A&B@W=Q|peKj26&x7jho742zF-+HAzp0^t6~ivcCxW>3!mn& zBm4k3gaW{bmYUKCnj=}<`x?K@F?9@X!{dU37F`s~SytQw$%8Gth~0_<*gw$E-6#p& zWkvNeqfm zu^VRBY!Mh{^m`0xZcHkNed-`KtaBhU@w;3sbVjDzU}`|7+LW<*Z)eZu-h57wPg=T0T0C5`_RBE>;*zD@ z%(ftNxY=Ff^(@$RZc0|`Pw{xOLnzrsiU;ATNy4{beaRXJ+BL+g-F}`iPbpaRaGPSH zUHHe492EQ=eYO%+$u7~mH(i#TOf@srTB2yBGr*+{7nH=w6hzy+g>v2a@0!=LokP57 zMEWmBQ>fr!!i8&ovih8r+KfW8qE-D@ynnixYAR!LE8*J;sFe{+jTeYI#^XO=%`!%bjyuXKnHRcGc3 zZWI)2**0>Pj93PY^q*iBL7=mUwc$^?IgUO~>%`GGO)e7uev~}0I8d~ZJ3cX%=>OBX z^h79U$!3BD{cR!=e~fSo_$h-1246zJeB+-iSAVe@kH@Jbrv~T+4_5%+A0wM(SN+THr)$P^Svq75-mX1{hd*MZ# z%;Lk5?nP3gl5?H8XvsK?TXi`4=f^|zlk<;`36?~Ca z!(fIdIdpAzF@D3X_acdWE=Y+)gEALNb@V2l&eM2^gsHny;(5#+jm7EZV5XD()U<)6 zLFIQkzhz+~KpU8n%o-l+)26KU^d`|c;abwZ?v8jjq#G3q8iEw)Ih>b}NqZn$)U3eG zejX;%kd^^+2YEBe&E~KRQkc|zoywIfd#8|%EvDTs4#DAKL8hX|jqB$AboDQcPNiFP za_15so0gUPd82}ir&dVp*gHGH5#8{FxV|@tXk=(T9A#hZLJv#~E)8o&Ao*C+xZ^d( z*@SaU!7%GQ3*$9wAE2X(c5_j@_H2>`ENT;sAB`qY?rxJVxc6^#J+vCamxtG;OPs;t zNgTG~9C_+%YDdNw5yZLH+#ZVBVd;^W;JUc3!vvb=e?UiD%|_CDHRx#QMFuPF6e8+z zVBGl4&MF0y?4wOIr{2jj0y#*&T6wxjx070rRe% z`W`;CC+IO=tvHu^O1S38JJuAz9(j^!e z*w`8W_s08wsuD${jph;v0>NT#ccZ$azLKqnto}qw_S5;9tIsmbE ze5iABbTpbVEF51fp1 zU`R7E1ZfXEXbqr=Pd+w`V*KZAn~@*p4B(@Z#TDAqKNbf4qf7|P5Y!2{!yiBn%&QJ` z4B-R$VPzii2*{liC%?KJNZt*I<3~dEJ*f}!?a~oI`%2rd?33!ljj-+zub&?ZDm(~j zZXWo`9HtIvGYH_qk@AY(4V?<$%=|qIqA5%;_aLB#zm8|_E8(P55O^4fWdc_4A>P=gL}IZd{l3+*(tb0g!(NAigsMX7m==nLC@` zkGuQGQ7;N8EPUrrBQS3aK#0>H@w>f!#Q^{^KK3=ORh(HamqJ*cWb z7X8=Qk1?p~XGreR4X_h<$DVgQ4yy0{^YJz5K52lOAod0KckUORAuJ%ZBRQ0CQjg~M zIyo`04Y+H~y$#TM%R3u@R#sQQzi%;U*6(y4An^C^pF z+`#WBoHM|t*VnLn;*HkYB4)W@ZfgI%U&Tj0pPSmhEB3v->(v!Ozq7z0#;MLDo*o&V zoEiTt!+}l#?hK-4>7$3r;xll=a;kD)U1(+KKJqx&J{vsO!zdP{MRFaDS#Jd2q zuj3Nbmm}~m%k=?Jg-46t4LU&svLE|l{SE+W1H^{>#RmikyWkUt?<;tL^Ndvb#rpFA zz~1yLDk#Sr)r$bPiqru38}sh#mFJ52)_VNPW3T=L#Vg|f6CkJJum5ZM2+VH%3!3-k z`paKahMN5o`qd=|aRvkod`;7@s``t3zZAWgL{9MgPxC-CyZ;5}ZO9$*ybJ!z+WrIF zp7+=FpNRDD#-ZL_1?()}p5OH3L3PyRBLA;?Q<=dJ`0xD%NWhi=Dtgo-JXC`IX2)J^ z9!sLJtu@zSZM@uqFQ$EC3|dBhKbUcu3>#8&V`FOa7nWtpS`WLgJwpM|{e{!4z8mL{C};-PzQ z)#Yd6(FngfDOo=9Lcz+il2U4kpfGK*+mi~^iY0GVJGc@M0 znhqO!gza)0mJrb(mHRhxw*sJKO#oM!a{)cKMuLGOhVGJOcS@jHucMR>9MfI*)bSr; zSQ>E3l?+9{m5Q8o>pUDxB_`5Wh_!SQEfFUij~)3vj%s+xlJ+B%8&OT#(_jSxR=5Zf z9iiusg?>o9Rmxt)HHwfBaxd!X7a5x`&&n^^`{^NldZJ3p!n47!YodQG(;0NNO8MZH zG?ohY%?4^=4QX&*RRPc-=YJ_wwP=FIk1acpMQcvyAxYKXz|Ak1J9qawoqh|Ij#+lh zUYG(@EL{(e2VUfCHx~&8Y7R9qj*&evFWaSBcQfSU-CTPIZ_7II+L+WAXQ#EUhZ@&i zW>pMFf8mKeI=RtzBDPNss)u4>uy|CyVk}351rc1|~jRfY}#<+T;9-KhpiM#nq+vZ znf#IN-YjAS;!TDAZeuI<`Cpv|-9GiP`slOR0RikxXBk4ruRnTTT<6_#SmxL{E2WS4 z6aT%;K;Z6HLQ;I{znT^_lCBpz&rmGbsK1oYjc8-<HKsI5Sr zSOElN{F&I^d!t$XGr5Gg1I;~?;A@2Q8jeIPbwXQ72vk3*V?AUkQ1J5tlTsghrBZ7X zx?*2U2R?~&^1?a~h))FLwybNvxu{PvUvWdo#-tUXdFx5i*AUS$t~Zp}nlE35Zk8aI z?sB=362BtI5$j>18$9fE!0}hWnWcxU1;@Wl+{tv?h9CNj+kB>X5T(d{ld~pz5}pt? zGrLn39)_>Z(#F%pvhs_{HFTzC_{TD4=V>5d2AxgEJgSG`# zhOT}cJ+=#O`L+ZH|B@^F@CncRAtyD0rq^Q~{ytLVK&&vcZ9F+!(w~`*I`5eX7oa~i zREZP|aXaR~TvlBl7vZ4;pdvt30&;E}=Xh?I1oZ$}rleu`r-lM-BxJ2tuGbk~sZeC< z2!tk2)Q%_e3(X=2LjG*QWpq4%dJ-{jLHXh4uf+7ujm+)L=FozXN!^)l|)wqG*A z<2eSUf;^Ct7hx6}$!9d~Ri#a0=2%7MB6@6F)Vj8!NP@x%HsymJIekorx%L2yg897$ z^4nQ_O2wOfXypCsE>65ggk>9Y2@fRv%{OE*@lP3b9qL&oVug7)88d7Qe5HiiwPmI5 zbb#DRUD}Xh?mmpHcG#`{_1B((Ze7Xp?PMwk{8m&USJpl6WPxpJlr|nll(mO@eQ$9h zvEfCSK}E*jV)50b)D5$LlcSK}F@Z^sxV;Yfa~O%j+GTFqLU=1nP`__AL#3L{0SrAh z0MpNXFGm|yV}}~{dwk}pN00IK02er~kv6u5{o3h9g{y|R3HETH=nyo;d*XqTFII6kR6$>ET}(0BW=?UiHR zH~*?R)(@R{@>B)sOM<}V!Z>CcFdes!lk}xvu^cDMG}C4@L28B*WTiV|LiL}hT!w)? zI}M#x1$>t9{$^$uve{B7j5GZs%sTbT9Ho#zV#Z%=`=}I! zQhi?=Kta9S8Z%Gqt6ILYM&%j+q6Z?8ZlYRIMHpEkRE(x2rEc!^umm*GfWUp}5?C{tTq@>b$oa7a=W@sU8_TJC{$%}r^ z#BCC_`|@xZo3?D5P)!9y@I$|L@Xq|+3$zC3zNh9*olSZqE!~(dC=OI61mVP(bCL;f zO8(~d`?T_^LqN4z!)U7%EAwV8ep#W;RcLY3dqQqASx>gW+*9O9 z_QkJn0XD_udj$x5YpI`y7`Ia*p1@x8pcgTy<{n`d2{GDRL)p~7C~js5`QK8XTtwFr}-JnL5K`; z5G(Y;PP^kgZ?||##mbwN7$Ih*z`7$o30k$EpjxJE$*VsNkM-{k#6l@fHe80GvbJ=_ z9_>p=4}KzM}b4Kz_j-o)9dFD1Vw$j|%+=G1}PqaSU~` zW2KWI&$?cL_7BA$?~3zSTewbA}YiQg93So*Z(Dzc|`TnOyqBEFEq^&_$T|B*>&T$ zx$<^0_G@saz_ibSQz6>zXFd&LaH+%`ENrkFhnD01c0c zkRl|i3G*UDO%6=f*#o>Xml^YvZmxBX6w#tGcZaK3v-Sq>UjJ}-+3`+Iw4~w`^X)@@ znm|Zrbl8|Ma$BV!=jG6KC)Ncu#CIi)GSn3-kwcbv{I@-jBxMAqR2<;p$Po=#u6~6Mg}KzRH*Bt$ja| z3h~Gid&S`J>$#tKNbv;(>>Axv&m)iT`76-FN`18jTi#f(gKe>J$QiAIA2d$loCzb_ zBboLN>}K1Zwjy|eQUGuGRSfTA-U^;RUE@=Cs^4C+%qF&27?ozy-i9q@tONL}@I?xj z5lM8jvKq14!3>vABdubP+atYh9@~UwfFl=|w;%kh!LMS~ma`Yhfs04Q;sjPW)<)7N zLydCvo-wK$aLMG2ebKJtV7J=5sH!u0Idj(<`}`Vce$v`u(DsWC!`%&gl2=MoBx)x+ zG{yJ6{vM3yG*@)Ha8&CnZgqzypet7Ry&h7?_tEy7|<}xeF})jaQ8f z4!e81>&Qz*f4bACud({xzD3W z7hoKDMed|J3gox3iqveI<0&(3V-^44w14)<335b*_kk9YL61wn5Y30`i?$QrI}YYy z!4y@3=Vs4Kt1mVy^caA76wy^?8#S+K^-OiJ|DNagmqC4PhTakue|XC%@6f(2R4(j{IxDT9UC zEJWU6hQ*sDpJD`MEpO!H&J|^ni7De!W40J_2l~82(PFno_=$a<+rfDt*Oz5^)^9%t zM0)~8KlLo=-H#?>Bcp_xy}daA;_Ma3Fkx?hDosyAD-}zc{gN>U9@4yIxa*We^xjK4 zL^Ua-uJuEK^{&#+Z(&s#lCT!Rn;{b?*|3Ca+oTOKmszCv3J@L>MeD6lUirbXuW-de z{Q7yBF)%63Yf|&jxBHN)W9H&z_mr4S)mhhJ6AM3c4q3gjIc)2V`I-}5VoCGUZBHr#Mjl;q zbb^Ee_>VeLxz3Bo$u7eOJQ*Ga+KDc@kK6^{%(wl^jh?R~cwIY0Ms251*zMfHi{(-= zWbIIV1iCQF5H}eoHk+DqjNd2$V~`^dbk_d1{A~!5Hhs9`ly@0PRa+|V5mj0VcBqnY za#zyCuZFz5GW;63hmFr=1D*w-FgZv@VjRE~n!-+U>~bo_{@Q1q;f(bR0GT9G4JZ(hwK70p~}F zx4cr_mKQGsxe5|_jfmex)3b0%*{cd~O6R*#I>xRYcrM?+F3b&D6s5ER4+swWcU_I+ zH;wiX$99Kw-N%UOT#Go*($W`5GsOV$l)AUm?~tci?I}O|`19H9;Wx%dYLcrDg$J3a zDf;U!3FbYdpIk`efk8SGaP-#8AXSv=bQ`a4L+0}mqGueQ7Lct zvWSEC_^#W=-sY45KC!A0w6KmX$nHw$kFE<@eJsNtmvWV!foi2%u`kfQ{}If?99+50 zMLlmsTSl^$)(^&m^?baH##3fgY<;RO+8N|)i;i+!I&fyPA3uK^!~8wl8`q;-E+sRQ zx493eU{0o$6lLpOx1@+L5J+?Os?iR2*#3iGD?KJimwdciTDR)<$17yu^G?ZS=qaRL z*1h9)l6loKlFLB`4tg^temuKy+PGJDirKCO6ADGUcrOYJhq!C&Hn(Tc-5o+B&X}^5 zP7u^Iit1QH_ci)NQe?G8%oQ)ZC7*#Q8uSc88RFw3WO%Vu#tzzbv&7!# zu*i8;dm&3qx6d5w(Y$9+n)m`Hiqxn%UG`uIZ?DOYx5DBL+NWgo1nkuy+=}y`QY12i zQZ|

Z6Q zNlR+ObV1!d0B8n3Cz`NuLG5HXT~@ZPWeI|Z~V%5$0H*;0M@$&`u0=x9F zV3IU`*W`Rpnj}I%eV4wWmxu?j&O}FdsoanP6$c?SKRPpl#$lAn>`6yUMxDMl{;Y&$ z!FQZ9v*rzR@ue!2<9lfvk+@@>&qj_q5znjAZ!C=hMu!KX=-@j(0BhF_HgjIauJege z6rKVHd^}T8B#qm2QWWuc&cqIuqwIntcxA*w(k!p%*BU%mhAK{>D&6A?)u-diJUxqU ztJLVWcv>qV=hmh+qf~VN*&9D;J?{0EnI$aq1;ejE_mT8Ip?E1P8LS!<9Pw|Bn$Q5n z+}lyc^bnubctxs#-P1eYRE&n*FfRMEI!!eZJ0WkM%RP+azPc~Dr3}034d0MoQQ-dk zLG%v(@}lr6*?l6jcd%cc=C3`l5%-Vki^pQV;pLxSxfL#v9Nmt(^e~6Gso}a?i95&& z*}au*F&?NaY$HUk(Bo(C_8yh}mAJMGkx%EQ!36Uq#sL$11$TRbCuxZCVE)8vX_eRF z&wT<+r4+Z;gCjhe`wY8~!4nR-wiwVYjJOT=9QsOT5U%v`^#tvAa>x9llUiD%%NP}A zAr858KUNC7e}6q@sqlcc^;G<0CI>ILg<_RrcJYe$pr03_HnJck(Vk*W>e+McPy7nT z;d7~#f=hEaTtGH(4=;X4NI>&#e58co^Vd^X?OAoms5P%!KY3WUp4l%9At`2J0b_-7 z#Q;#!#%lzH%0C;M@u?4{)MxL?-_08JCZZv&4XI9Nu602MA=EW@0dwB3+NG^UxNv+E zx58v$Wu5iM!*u80f^BMr>WnZe+q`_loWoQ{W}QN~Qs!=En54A4QE`;{O;{>7qI{_z zwRj0KB&HVlyrgnnP3N&NeM9L*CQLq`jglwGP}?)DFJ`a>#HNN?r>rZZU4|G7%II^0^<1fY`=hwZEUh{sIrhS^-nwY@C!VyNO z2}Uj=H*V_QO3f@Ad+6t=z^UaS9iWNA%jZe0qm0RFNPf{Wn_XS5#;$sH?c7&z$U3{l zRNECix7U4LTX=^pwkFP$Wy*nky%(yg)M5S# zzJHD@U4$MEGn9SCRaOFnmRC_Y7pVkl{oAXPlI$FMT(}XG{)**Ztv$yC)p6o%LAFPv zt@zqi0+xA?+4p#D5oJ}Xl<4q^fq`P~_=0eYGE3~)UPu4%fxJR;x<^Mii=5}~DR2y7 z0%yq=vhj23_Vs=2*xna6*uR=IvcT3rV*%T&qe&BCRBE??B@YF&yWBBLwOS7?)~*X0 z=l0r?8qRWGzA|VKufRiCn{KPs#gN?JkBmdeWROAXMJ6G>;)CTg2e(uG)YS|vhH!g} z2_6e%yyiLh+VGSLI4-~SbdZ5h4az(fN*4f&0W&kZVw>)s%yo>F~%Z6#QNnnLbHh!hR^;W;5GrC2f>w+I+S6{dBoUo z1dLSHt19e(c>+ISvuumvIo~$-z!JJo2w@hLqo`-HQFb_oFEFbMnYZx6oTgeRSj!f$ zqRCj^9n)_@dvXkTEIsZ-V+anCCa;glPLM;<3dY0O=vE#?V=TH_vsRh5Sb4 zHxFPIv!yK*e}maCfUm=3{`iR{&GSI3Y>{=;6cCo?k>Kp8eAFZ~x#~is$k8X3S$2jQ zxOyloo%z5a==Jz6P1?YWei2sN)maMe08y86kL*?4zy>~L-|kL$D}}u>H|L|Yb832~ zsl#iU(Lh9J*}x9m!md=N&j+W&FoPjAks*8QYqIV0AsXa~E9%_gTODpj>zzd$4w*Dr zR1vi=;aTiNUEXeW6Ve0&k02onR&lkeR$5CI?C%B1O zkX$2IuYUT-pT~|VSd#fasL^9?dw^hymkM#sH&n2OvuR$)XzkhVuX$M$8IBr$5GP9y zs}0F@>&fgCP}^I#rZ4@URAlXKJ;>x_A0fhT((yPI!9@!NUWysI>^=7%t0$zhkJ&~h z2F0_jufpSbZ#iM9wY5f5W>p0Zgq*Wh8K)>iMt4w;w@PviUrDp(kdBbw6-=3j^Uz1l zmFZ=v7_ZSGg)$b%Oj&e2c;^^`tuUA2+w;~hF(2RIYYv1SPmw$!KD2^hKnLU2BGznR z^}=^-yrqL=X;~!ry}=;aNTiOU2`0E2^xju^nW?}E`w_;hE$s*BGG;qh_JSO|4eL4*7CX?UP0AXq7vv4P};*pACY<;o@+s`Ui#+Dg)j(J^#7ITZnrQ}YROOoLOpoO&a$tVz<$=wJAX97N6s zCvOH`x=*>}Rm2SWv#25na(p=|T}b+t_|=x;jb85%+X)NmH5A>hIl-Rqw{$JjVOp#S!|Izx}z`!nWifu=t?V z%NaK=#+(HBQSTAukIGlzv{RDh*L2h>8|v2T_$329&_hie5 zViS&=JKSmD={sr2{*md^fj7TGhfvP`?QWPREx(|Po~hJ`EH*GM@?bH@Y(_Sj8tOL+ zwy7a9r#P$v{SICH+3heTu|qmIqF5yQ3p&y{Bs|?kVPkI>c%Jyy4uSW?ZF%`X(C5(( zC9{xEz8~&4uMps8$t{&x8+=zNIs{J3bv>q5-7Eaaf$Rf^8cf%-363C`x#Lo|b_*f( zo^W(ma;?cJaB1|-C-sW!lj5XP6g8L+7;Lt?mZL6cObV1xMk+3QK6( z0+(nUv$)%BRniI%E!ePPXp=%l>qeu3UH{$Bo%K528N>8CQxx?Pjw>+3gdsgVqGkca zjUGeBl!t}jQjJe^crcQrz+itY@`-I}y&=Ypq>rl{DbHXs^CNA$=$Rv$n>SJX)=BL3 z`@2nD_h=JdLW5oTuX;BGbj|Q!JE)DMX_{}P`jHVLPT{82QKa;y!_(g|o?2G-&&}F| zF>syYl~1db3Q9g=X2lL|Q2s@yU3E!nVjz=cVB1#ROiuLfH&DOP&lbgDiFq!bf0;z7 zEB)W%#*I3)CA8RPMO9aP8yZ)0k+PaKOr-bJ{JPNNDaI@+%`~e48JmTws599hhghO+ z%Fs6-e1m8K=*}m52E6`iQeO?CVUo6nxuTuUX3oTkX2yl96c{}7$O0Uh4H;K@&p!sf z&1nr<{&gM(6&&4Vaa?dd27B+|AxE_=UA67Ss{I~zkdq!7>?daP3$VrJMOfk&=)ApK zCDV{a+$6oLWJB2ki;uPUW<}89#_K5h7enV&aX(ETxfY!KO3bG#9>KqT6JVJ&DsECJfY$x`gF-cPo5N z`?UUBVI)qd*OY^g42C~1%K}w2Xy(s^Eco8#DK#B^1=42>7EKD7--n?eh1woj)E)_L z4|E!vOTj6w_D|{WOCP{8jyjHGKyq-Mp8@;D%Jimlh)Sq(K+UnPG`kER^=DA4X-3eS zsGuw?s-?!4G;+jB7J61V<+O*+ zA~wrt`A9CA5e=mNhEH#iKeCK#Gos=M=%8gN>t-E%x{=$Ri9pj{RDHOZHs|$W-N`e= z#=H@Lej(xh{;xAacj<5g4e_FAh;c==0)mzWw<`>~Syn;c*`}nQSx^~d@-kk&TxNgj z!Z2li3mFzCgNqvuaeJ;3y?oWHxf!614?m?Q@z-Ww4lw)6L)RcRN|PXRJ@f5Qte$eH z;|k~uW)5YfL_CyNpoi9xG6eL6v3ba zRnNkPkSL>+*x5MG5Jq|NgLoM@t8MHtMqAJT8W*4}lWxLj*O}a7n!pZ-rOdhdf5r=L zxSPgT4AHs@T+(Y!R(N+%T!GF+jD=XNO)V^7W+$v^FGvMJIFjzfAA64U4YV=)68f!o zFQ2Ma<_TaF|DJID5TAvj`whUYjqsr$?J)HN|1T9D~OLdb}E##Xv~)w##| z6IHt>c9-3UzFA2Z2KauuCu`!#4SrlE9L|m)T-U*%wuPMYEB#hn{5Z~?iR;2rMw1|R zt6SZ5o+v}@IGr&+#qaSRJeA&VSf@kN9hWcj$ksUJaW z7rx4GxO4gLXS8qZ*jSVVyOv8Zc_?r(REVauEsR+C+p*krq)XQZ+KUvJYv7EQj5qxJ zQ|SU$$zCmg*}lz2W@TX^zfd(vTZoPePGXl-RpA_z|NR!vv6g0AeLWS6wN{Wc^t$xT zh;SnNTc7nkedMvZM7BJzW8|rTEZKdc9;3U2!)tAa1A?qsg}0_)eUX6^vhGtnJX~vy z8rSfd22x&1N>Z0Zl`u|jiBo7i<<---OGe)gtsJA|6l}@FRMJd`>W5erG z&sv>it>8Tpv=emF-}^_bwb?~ zQ~0ZG`f{TdRbw9eSkIb{?oj!Th&=3zrs+v8iAE}aQa!OPIS%V%zdaSWC&-zrI zPn?Zj>qc4__abe;hq3&)9R$oiwW=5`CHyZ0xN6?5NweGtClX*5pimJ(ux;DI5_5zIr`ou`y}wtIx>|=%k+Y=KTFd!m&-GNK zCwQrb{`jx6>=uXy9hB(5!jfTq?=!Cl>DO{0iJ~;A&^B( zTf>C!f_rm06l4oZ8c~!CXZ|EjmfLN|kDGgGp6>1X9FPLl&qX5<<>tiULm+e2g+7=Y z_p?QK`s|;!P5l+xIwiwXv~RuX6h66nzAp`ladjsUM-YjZPB@gM&r+j1*6OjKWWr9~yjW(J@nJLaSt(FRSEf~QcZ zrI(OBy_98i(_8IlPDi*U{Wj9gkjjP4#$rR=kAqCnT;`r$j$dHZxRG?_tn*AyM3uXO zcY~$CyNlD<6_=NpR`JSd1755(@_F+Nkrg!XB-{Qs>IL6=VFEk0O?c@2=?W!2wPVsp3Gcy zY?DYZ0kO1ll2j?}na8;xaJPpP6OddeOiAsmGbXEFU3yq43=S61E`@}wD3ctAbgdps z7`j*|!LKSO7G+ok#PXGT;8}qn|0tZ7SR7#L0_BV7{rH`CA8g~s22qXL*!;+w*wG6U!g+rxKA5;{COtdKa&SCW_ zVcAd6f>IS)@Pe1e`&v4eZ_c?10P{@-hWHNi18oWZwW`NRTE>(p z<kO)Frs@1B8LR4J7NnO-tFg2f;HiIB&h^w>*UDEA#`zAlp z;;awvnAA2^Lal@_&iBVK7Ij&6ITTPBYw_A|6lQQW(MZ} z7e8lZ;rPF%!~frH$i~9T^gqU}x&Ct-UazojSNMzb`a8Q3ZRaF1_5l#l3qivKI!j1K zgf~Gf;84aCJEu8^Ej-733%#w)GJj0wdLjXqqoldBY&%jy7Vc@rLuY%d%`Xv_h$^Z zwsLcGweiW=Xwxfmkg34;{se3Scj&X#Rf4a9y|K{e|8WHR&4`8yLzrs~Yx};x?6=;} z#aE;Ew`Uiu>X&B|4&_<`yMn}r1%Far0;Dmce}Ys0hVuu0yR-$+rQPvM`=t6*BY=2v zV;tMSJUN06^c2c>^`{v^fHtT2>(t-9hYbK>`3ME!=p01wAb^V>PBaDy__oafA)h=C z$R7^)i#a>JfpP%tcIX(y{)3tDsfIB`L&a}%q%SM0Pre0ns^<3quU5x$u+iQAYrXQn z7(0jNOt@%m$9B@OZQHifv2EM7Ivw+gZQHhO+ve%7zR4N9gEQHGVAZbLd)>HzVID%> zzfD(#bJ?4F!fGAekJ$r+bvFB`@BM|4=(Bo!-3&MhM@fh$8Tvs3bb)G9oA_R8?%%hk zcXx!g_3Z}1zPqOx&3nVo)_megNZs-w!~wQRq)k`|cZ$D!3IasE6mbOLS|ozw6~42C&9A z3M9?#j8O(7m~|h}#11LP0rFv;xX;};pzNFH=x5|sU-g^g?~l7k)OB23&j4-D!H)vw zA(-RiH*5f56%Q^E5Im+Z#OzNPcHmEh8mJAZqx<_!DGY81QV`rCf{>ZK9xy$ApnzXQ zCh;JwO#ytM_Qp@%BtcIfLm8KFu7PbD&f!W2c*4-YgFaJ8cO@Ru4I&2^!%v8y9aLSP zf6ZMgy!hxDz?V|6%8zBXqz))iG)_DHx+|O5vO*=-VAh8M-dY@0ff-( z8PdkEnzLt_mKMap`rGNN*~2pg=-T|p5C(J;p=Zh;*Xru}JnHnELmdh4YvQ}ghjA6w zCYFT{xB(r}Qw?k0M~`0QZ0ujpZlK>Ex9^a6XT}*2*zGdLdlxPxhKH$`b;zMJ1U<26 za{!yE?(`15?Dws1ReseoI_FWL>Skj>Qxu?;M+{%)p06MuKv*d;&Muu$giPadB|2Xm zNB$o4wK`m_5}z;|-&XHSJ(d`G*p**vWzle4!f>< zevO9FiDHbNUjCM$C%3-1zE5s~Vr%G$3Kp$2cBXps_Au_Gkb^2w)E<&25gQil-onmr)HaP4U&V=! zEme)lcabDJ`HK^bDSLav&+=EV`YUzM#i#afM{n;~*?JnXixslH3Ys2da~2XuE`h3| zcwT;i0InHnyh-WHH|Q;O+CK4c&-l0FarJx>V#1<~PYF>ad5SJ2lGls%uJmDM0#Vh; zXC+W&6#M-#Kz;#p76LnOPyaNZ-`G%y_NE@fHkrZ&nk9v2MEXZV9|=LBQvrsitTn^& zO=#47twx`m(Clla=i!5um7)J*9o2M7y>T*69pG<<7KNJ7ekxdaWh^9yMX{_XXzJ z5QN?_ELHq6&rmA4qEhQGSGFo=d{U9wgnX&uY4hfKgN?3QmCD~*td>1{yAum9j-Vy) z!JJ7`^;mUG3n4~eCOc@)xKv@}6JF)}!;9b!4wF}SPYOc{b?8vOHVe9H(_LdS)%QiB zw+|kXJFdfN^~)TI$rTG+M)OHCpOYGeNkpuz3G|4n1es~yW<=WyPD3}bX~h+1$* z#m;&^81LMn@b@>FE3~T+YOrcBXNc44%VBT@V@+WhZ!&`KtoKb{js*Aj+Z zN5)D1h_ZuT0})qvv4)Q92@o8^$+$#}K9?dfHJAdkYm09BdLNy9qIth{N#l#fz9M48 z`p{o3-s(j-6GG5t8`wEg+*RAj)l(C;1tpr|4si?T(MCr6?%_k|%9rM<%dV3cMtl8C zc*iq{j?Oe(jxd`)SV()GwZDifbT6Z^FOgl!9?&;|n;$8c(796&mU#AcuIhVjCNdgg zt4O1fc)5NZ(tO^q*n*0D;~Wz9AvRjzW=Xih;_b(BB*ot!9GP)%Fl;bCv{ zO}K)=gqKTAI6Wo)<4ujpGWIxS`|(GRvocgjl&0m4q_tDAvj13Wh=9;@!U=jF=`X`( z5+yBPIN3tfNs<+Q+SuoSQ>&p$U(2#mo~w!dmkh(pAm<-j8v1B(yCCLMss8Qg-DJ5u ztv~D6#7#!>RmW;LZDc*ZdC8o$6%Wk?xn3QKkY|O{jnPWeqP+JG9lNFcn=D8qNe9^> zs9w_&YVNW;H-ws9cAtl3E0XkO7DgS2&(aG`(th%%5l)(BWQ_DLd}dKFCer$9m_KHF zd7B~Bm8Pafm$ic1+G8seWyYHX6P&JvCzE+nX*+F?!wVm?HK(#kr&JQfzG*)m>;q?z zVfY1ndk+g6Pt@@R7edEH!=5dX*elJu#rb1A(;Ee_6Cq|%NIiPPFirx}^O?_+o09B? z!>J0Y?^p4XxpWh>)53J(`~qT?s9MipoZO>;KxU7I@4 zEf%Amx5Xr_9oA*q5h&4OT7sdYKsh9l_}XF?m>kjG?2`~-=0Rz#=T+$yC%l$*#gSF+9_$|j62#IvWesIg1oLB1a@SyW$s zR)eTCAXCl5qiWF)`NzE+fsT=?a;juqsM8NFwrX%XfF~MZZ~5CK7LDPA!!UV>u)4N9 zjkJrDCWgvPSTXjJgZ5{Fj@xxOp!3$7rt8L6|MzBr*=n`sq{npMt|48~x`oDQ0fS6& zASTR8v&{igcHc(nQuXu%tRS+Etz<>tzYcaCqc#ShH3&sPXHy;Jg;dC$oSHrDn9pkT&+XA0&F0YoLic z%Dwkp(EUjz_nY*nxLzJ@XDUJ?VerHyV#p7KY?Ex6tf*7?^ zeu?Q#Nv8c3O`5fdHA@j1O`6-E^c7tsPM$p@y0FQW=Xs!b~i&B1JUvIbajq0R!o8eTRfq;_^Uan}CDa@^AIGxdKz&+e02{_(? zf0A)i*nB=6nz1Ru*I}XzSYB_JXsGaxwA}d&*}?Zl-y`_cjbu@ciQ+`FDLp_jKf*pt z|AMHTA@OjhZ#qvF{>0t~gL{vOjZ59m)_|s(Tz0`OhZIHq5J_K|f-2fpsr)FfRwK4| z(b)sr*gVf3MMD?{uW&BCt20nPJF1E1c>gZVEP&c_8^(jSxAxo|=vUt^O!LV`b8rf9 zAUkB1;0|hv6+}JGW`7#K1CVabFNW!b8TmD9Xu;GZo97q;EOs!cdkt8K2 z5Dx`=8skLJVk3nCyZx}vl=N)mPm7i=;cx|ElH+*Dv|98r>( zia!oVbmPMkYo=9go|cP>Dy;N;fG&~>{L5TZ@5Wc2;zjY;FHFo&vi{67>wtzPDL#}X z<`PE7BoR`;LGOJ!A8+hL&nO{xjc(50XSUmnRqw;m&o73CCYFeSB)Vjntck` zn86=Sez9{J86Cgr4&@AEdJpwJNAr|77l>i78Z=2`2mBGY*5!o9Kmc%Z%#kT{I>~wK zb~X$SOF7^uIh-$~n0`As-V7)>gj-~Uh(t&(YX)X@E|s)9{U}()=Kie%;SJ7UAXrYr z5G}R$Zo?fv*1OMNzf^Nh%C5tZGI(_=fO~m|PI{lB@_IvJES0eTXD8?-#ZVNZA9;%+ z&aDfIc{(nTVjn8)IDaKMuG;=WB%$hgs0y*ic7=S9gI*;gWk8*O4O=PVJW^vGJcDNt z_{KM{eW9&W?8roBAldV_iuyJ6U?P|nZ{l<;X4)#1f$E(jVxVqej&-N!y@Wo)BP;RU!DFrB8DhV zx6F~X1T~bp|11Q?$Z75XwYZp8&o!FHqOPPyKe6xCj=H1Uez8_=!mNEbs1gtHjsKMf z-YU1l<9a)__BP@Ub(6Hq{;@lF0uVA^kbc_JYA(xJIX+<}Fy__JV#u>ZconIx4TxzU z(l8BMY?;_+XD%6!8ge)y`OJN8`q4AC6bNgPMq!yS8}_qDev;N4&T}5X$oZPU#0|zz zNJHE_Erd3+ya2xWn>nxiDK&mF9#z@O+6Kk%zM+s8oVoARZE_yh*td`y zj}7aD3cndOMnOum$O5~^a_bUXG#}1s`n5w<_;g+m-tjg0O zCtLlln7C2SB8X-;A4H~kO(ms*0JYLHEbj>~7r6XCp=xkZV4;&^4Ix#5)+I6fL;#5I zi-?ZbP}BW~CM8vcmyg@@4}Ib{>akAqo|AK}_|-d9saFGB<_`(oo+5{!$esjMqMykc z{;`mH7K=ZthP7hT#7N_BApp#leEh>)GFPLP3Z7opsyVf<`bP7L}SCD(!&Zlud zOEv-NOPxOo;V+k#(A%1va@P16v{4U!BEcKU?U$zv9doeTI_ zFdbam#P|-!<7->ebJmL(A`E-Iw7uLZ+ssj!m*`Q&o%Os)4BIW{Nk-FKXvGH}s%A{7 z{H#m!(h4p&7@$8!qMTJX)?phvv2ra)VASY&YF+Na%2cX#b> z_pF@P0%57@i*x5ngjnrW8FNZ_J1S|H*KMduavEfm# zZ$KSy4;Y7oeya=wc|bgT(TDkEucQjW+Dz1j(K7UpQK^0MZowoosS=Ip2bK&qdft_a|L#4{xVB>n2H%mw)sf) z+KZ?v%feK46t6)O;ADNK!)irC_!hO&PqT@1-CDKIvsqEFtgA1pVX$t=J+gj#293I1#CXhr<{t3M}dwdXCJ?yx^YSYok= zrAoGm1IKvyG~vf<#_Zzk!M?tzXmdtCX;*3lTc-Kor5X0p_KHQ}fo(8vZw8)1;SaXa zG$?Tyn5&SB*m*mh78u!XfpvaUI&mbVETa&!KrzcL+qTqnntTD`)nU@7M z4WoqF$F9wd@~}3`hz&`TSf-d#u<_(?1`W9J&9C9rcdPd<4M-{NRBr)yHvHPxQz8R9q~PFMCkXL z9CgAW7@y*e%i;dvgO8VKy}wN8!~FXpu&tB)d5Ll5u-bH+(`Y(GP)mtGo}zk~d~N%; zs7Frz0~u>QMmUx?jf+ez{e}6&g0qE6pET0G;WP49e=Jh>8KHh~ z1GH`;n)%5%X_{R4g>$*|^KnCsqTQ?}f-XL{Xl&|G2OutJuP7~**POiDJ0_2WLpN5k zyFk(FM7^L%>sJc9ygskd06p$}n6VQ%2j)FrW$h5@4aL&yO8^66czQ|xF*&#gChoC- z1)ccGt!LMag+qb|FG7Fa&2^k@wMOE08exBbJ8t~!6#2F<6Gsn&8CuW@sb>Fdd$X`X zZSp=2ULlvrN*_N8(K=+VT=N}K#X$f5YTnl}t|{URj(3&Z zl=T;wYvYK-Nw?c)+P#rjGjdB<1JOksDS;e*&_eh+>!UOw?OY}@uB_Nu8JqjPp>Odv z>zeXz3nc_LJe6s~sqNXe;L6#qtngd#P%?k@beRwx97?R_;zn|h=CdNiR8>K6yM9B0 ztIL;8bR{#97UXk7D=y|u?)dL+f)rpwV)B#PZyidV zyYn@8zaw-f>EE0&1Y$)6$NnNj8?P>T7~pL;{^nk}e4Tn72XREpY8EwCpd<~59=JoF zV255yen@7NCE%gtLh5!TB__(w_kL$%;jo5P56KzsN-t(8du_~8gn*n;G*=^EY}WYW za4cl9_FGXS-2-4F;;^d85{W%7{6*uF`)>)4qoC&3p~;gVfG-k_Jw(x7=qnV6W>xwg zmB{>AS}+T&KY-u1m|5TsPIaI$(;aoc){0Uo_DR3=DyVdBLXuK?-2nfWYJ(yu;$w_c zV=XXmPpnSTW#@Q{YFLUR{eY4&mSd`*_V6Hcdc%=NLlVX*Xw@=wZ75j7Bp}~dRNR2A9NM+D~E$k9b_XyRxONi7h)rVV7&a;vJ*t_|KT|S!X0uRV2 ziMO-tI{WjM7N;Prhm$G`vrv;7rt9*tY7Y$ogetkXTXHu`eFX%-&D*7GqEI@%@-~lt zu;H$=QS97lBbGP}balt(38|6ud*WovLQgWEq@rqP zPb?m$5rzi#hmel%@_{rBwVlX!k0DTl;^O<9^(3VotJ{#+cGfSlfgdxd>(A~v47#N$ zM$xu-YEW=?Im36v8qj2`00$>(r)<2UmOI;JL~N*XRMV%cPH*5X+V+m!_4o_Ta1~I@ zuV;8X@`%V!E4$4hV}s0NviA4M?cFh=F0p^r9K)SECmSE%fnUk`n8NtUwVk7*Gvw~f zE<{uIKwIbA>_lq|JWjWsqbhv^c+^usJNYma5{mxrY;!@n6%1ogjR+0dn77;1XO6ga zrs4!n%zPx&wUC6Wkx_Tnpz8>I|D?!6p|q9nSfDy1P!(udEO3vdgXnNrIB0UDx4d+B z5cb=rY>rDAm1DgzTo!{q8k#zXr)oO++Bg@3%|k%9%@hyq!RDSyU0JddwFIyYk#Z%& z$(-yxufkXxDzUXu64|cNDfld5W+(iq)ZyaJo&cW~+~C4-vWlVd`=kt^#ub}+8GPdj z&x7|RLe}KDh!66nrI*K|X1v3KwV_$@z%~_71Y_^0#R9a=4c!S%0Xl;3%UNljo(b#N z2cI?rZN(oJQ!vdkslQO&bSmYzfTX)Fjm%Y!gj~|m5(^_79bu7+d$@~x zFzY-WAyh;XAsOC%tk*T)%jS>%#m90bTLYlw`Q!4d(|a|It;y4bcJ~+w2{-I;?*u#w z^l))0Sqw-pmyiL8GGJ!77*uRs=$rYV;Y3;FesovqaTXh@?w{ZJlLalkcx76<8o3 zf>@Wi22hjG$$M}O0fa!MQ^4!vRskglNUH#YCIR5hfSzfH-kFJ?8z=vNWOT65FL`#* z;Js&rf3|7LNf-m@reL6)phb@aJ4w3$tjT@#-1KZz++_P>BZwvz776gr>rFVIzjGjI zc~IYCGte;s+=SU4*|}~#l=olM!Q7_cX`#5A+xQ?N+ARpJM&}Yk>+F5Uws^loLO{f|&PyY#V|If%|(U@`K`EfsrJD2H|a{UMf1{ zIzSIw9$K)5dM6fuuYqbs69PPh=!i-Qd=w~HFra`U9m4)8vn2-rC;))K02rJE_!x#1Dg3U- zx4zziBY?t60Uy}#-*5#Z2neIJJiZ#Dim@JR=mY#qs0V2Gfc$m=c1k0UHF3J%C_w)z z)%u`c&6(girJIm|Ms|ofKwv=oN*TU?8W#OaK7Y`@E5?7w?|3{lRlZFJeUD1GsV7AZmXQmcl==v|J;=7uUXfy2d40770gtD;157_b~RsVZQ1_ zvIP}6B0|a0pqsx*(gobM^b5=&LxouPCpp z{PhnQ;Dllq1U?i40{75+j^zb4zzo6!)7lOSs_{cZl%xgWOTh=PTIzv)IvF`pl0gI= zpFuSGkzaeNH6M`!6b@3)I8abQZv%f~{hmh5?+E@7^g_NNQiAL@{5xTG8@}Lw<_K4@ z0tJ~~t7v||{Pg$eLqiS1gA4-zp}}MzHszpNGc=~BI-biCWOXlz)9_#(;yYLe#NNNi z<*lIGROH6I& zx;7$GssMx&lzIWDVhbivWS;RagZ<^|nOD~|&*#@|8Y_^8p@d4wy=t+~FUg^nR!NUW zULE>5M46M2F3X|uWos-ws}k=up;+J)R)w4D$u>Q`@s3r5nr8&K8l5WxvsmX9`}-|^ zz3&j73PMH!dU{YL!uCwzuiOp2rWB!z3pxq1amw0!nQvHZ-vK)EIt%|4JLOlBRgAUoQq>h4$!wBqGxnUUsxXJ+vh019Q6U?B8GA9R8l$;Cq|iR^au0 z+@Z&@rl>Ffi=Odsi!iU}u}dB8V(@mpYyQ!!zr>#puQnj;(@Z4x&o9&#zv(C_d=_-n zwRS7mm^3OTzc*Ke2m^2BGF*%y8lm4Ey&}dgfnVV86lX*(TY1l0E%8NPp}h$U_dgr~Mf{3^xGT%a(x|sgng6xTAwp7n!FAm=4Nk@|O534epA>*j5$Pr6{yU zSHgrZdV9)vhVIqihzFYE^_$MW4wV7^8c>HAJj|5o4wEIe);Uy7p=A|n`9BMZ`2AW- zZF)H=z?Awl&FwoMvOpZ;6xH8AIqq~^%Xuq3A};7H+#1|bV4*m9BQ$)=buqLc?6n|z z1SaT?nGa{yl-W#Gc#DoMd@^!|IO*wqOV}rAJhCmmU&7EIcv-uKs4jR5hV<)X9XI8E zYOdcd%dPD_>GXJy^wwYu*Q4pS_<#|`#I+>WOj+qnlF<+cl2n##O=e4!)hMnOII)1i zM{xF9yON6keV_x<$)oe*fy(lxnY|Tc=lJ4S?ZH_?18kkkbmAS?5s5F9g{Cv*n3m8w zUeFXmOSSs0H4j3te}*wVfKZ()Vvynxj^ z@k9PT9s|W_ypgEnk~|(&F_vAt^AA+v=1=d~xCr^~5j~OkQp3e;a4cR9^*MIN*4UYl zfSu&zkizP;G$m%Ub#UYQN3~0HDDx|v6q5h~2sV=zXx`;kH-Y_iuOQ*p+WiPbh_4M-ALt@r! z+y10E1ZGax^Fleqdpwg_zKATKZ5%|oA4Pxj0~O40cHY@XTtmy%V*-LhWps7fl0i%{7y3%;BugD!VR~6(0vxlw?^C-_Rt&7 zqGqM}hNz(es%M{e^6kwXguAo#2pd~bF7XpeZ1TG*k5TIO@efq6$E6L)>uf-Ml&U+X zv16l{+IIy=%~hg^W`&%?%pv|gJ#oT0ndVYD2+Lasnp;NoB7b+_1WA_Z; zCfd-+wKI*mQ~+$Q4)!Wl{VNbL8*%rbk?JvzR^ZQEtD8%wFlUz*=wST+@ts1T@rCB7j-*1dIOfPZwk8E`cZvSlU1?Xt+%#`$2M23uR zy4>PQLKM%Wq8!#CMZd$-qH)6cW`k&#s?~3^6ne8Xo@+enA|xP+9d0D?x1nsG)UX5I)QZh#j&p1~MgZ@PDc4dvi>r)gHR?zP3eA zE>&RBR~^W+7rxp=5^XEISV48lsT^RXG0BZ=H08-(FzLuAfiv2=p)--y0t;3~661^N zGjwqMOQtgAmTS0`{r9YWht#Slvr$Wqr%EVqiKa&K*Q7avpG60-%mBcb6vo9w%w6)E zbG!bVCQfPcMp@774KvM}m$~oM@93h7gVcn4yH?)O=n;4W>W`FK?MUEQ(<};rkDh57wlIn z4_q~rd>}TY2QvSWxvFRo?b2uv&Mi2-?cj*OdAGe1*`_wYD;4;w>-%{$DIdEhGOl|2S11`8LpfkUZ4!WZ+D_ z@TfLt|65PUllI$Eti$>f_$eM5%UN${Ev<#tw3VDuUI4Bz}n|d-~v~6;9kT_Q( z_RjXQLTxtbJw#U~4R>AU{;Y&cBdI$wZJqWSbw>vA!laU``iFvFm+GJsP}v>+f~{8a zH;wU5B#8bb0rMq#2`>N7eCToqnke&Ig5SN;P5)uS%$~w z9#+i^KEHM<_B91-mfRdc)OM$HQkm0~KOf4}u3*tgN8cerwbuDeZ!!<`UF&LPu~u$T zcE)$kO7COFja1kW^h}eYZ(6vs_!H2-YhSz1&(UnM$gf^&XSj!UjjR2)w)yK~K!{ zH^Q9<(ONmFC^i%FZpy210tB=}(G62RMi=jN_)IwK3&AWRer$?%iT?T_R$@=|P}0-S zg;sZtcWZDhWhmcfjT;b$-lOvP=Ec(%1zK&&)S|?RZuwPe#T=am#;Jm%$F@i$arD(! zx-*?I+~IF3;4IJNk@5z}s(f=&HUXu^qc2FKgI(|7+P_>YCUl}gjJrea=Egj^px7`= zS|Ki%rnN9z)gYW?prV=?&!U=ljR?GLoA0(&_u4nkUtY2ZMtC*1vlT3h+$223 zc;t1H+!}9MNj+Ja86Zk(Ma^U48dd7HdtTF*=o;9BQUK)wldh1^^(YOl<5?#QqYAaD zY;>`^i*L^`_u{l>|5_wbAA37Vh~w1+D27>52JSHPh)2$=zY ze5Ch_XBF5)|KWO`t;%B?f=0ibsc;f4s*;=eV&$vJ+aZWpQD$ny7~|Cr z8zuQC!O-9cUgdKW^J;s@sJT}?NC~GBx_>FAT>{2;&X#GpaO;Vwe!d08BvTzUi|~QW z-;CQWensC?ZO=ln;&C$y19Ewbn8J2Q=kURJ*7Q(KEO4`orkOj*@mFD5AnPqo_O2Ie za-!$URA%=6E8>zcL8-&I%-5(9tmV*NG?wOPxCt+NJfy{60)K0oX|f&H z1^V@OVFrro@GK@BJv%jFCBKFu2wbn1+QCXTnm z@3EGSuzf9`vJSlxW|#~z$vp*hR0hgwoXYIMcGZz=?W}sywulvyUtdS?&Z7(V<5ISMO2FB_19R0_<{f-qRKZ0!vX!(z3T|Sj_Rr*+o zOl`4Ze|>eT_E@T9Pw_jUs=qPuU2dI@5Rmk(|31Z1*ug+jyH8Tt=Q<6b$CD{0Syt2L z(H7I==MFMEf+q+xyMMtpgnZ)Uib#rU3bRF zg}Vhd7>TqOm$7T#wA^K?&JeuEZc~w1@TCEMLr%mIJ=!T?jxa-9AJz`G@^O{(dhB7) zs}5(|@6kKI__RMPvGb!U0|*<(gzd1nS6s5oC{bhcg12#M{qefa*jTNJSHN0e%VEN& zeLsC94H+y@kaGFb8$f9w61#bqtN)E$9rWw)7Pp9ZBeP}x^Y{;2hM^~qw-#A z5)rEZA8{nmH>&*}fmsP)&&x~og?qJi}DL(jy3_#<4t7I zXRhl`q`-`_0={^nkBip?1i#srsLQX67V$5mPCg~vgV+3R;U`nBxFU&_(qCAbk>(wY zb7rNOm-%LGYC+{o#HhA=eM_*Xj&bNc*kxUuV#^)Yfp}*%I$+n^(p*&PV@u`JgHH+X z^hwwTa?6C&&MtG1eFI|d{~Akv!&d*=h?liYcTGCNdZl-@m3uYcs!=GCb9H9HIUTvf zBEJ7K_@`jQc%-IWM3&+-v#Kdfl?z+qtVQDBTYOqZUGuLT-)!vQ z#G8B+LlG07G^Yn(s$x+%P1}qS0BT zyZD*32XmqD2+SV1k+#?J@y|)>(ns3bdJ~s!@AXwwzXW>?u!cL376n?>?U-m@Z>M$c zzT18^j22UHXEshxljTEl`h|sC3%lCKPf{QJDauSY4ISw(@a_p^b>+j3*Y!7KIIKVW zE6YT}x-QjLOd^zNS6uh7^&D1)9fV3mG~bbV(xnw)-qj+@PEeaAPyE9T#D)uU*qMNM z34Q_0l?PisJ6ir07yc>;arCBjVaC3@85YXu=^Yn`xg+y3AshL13>Zx00zWHlOxVRI zLU5HXZnNqZ1%mU%BPPQ%h2v3(bE@KJ1dXpW5d;B5OcQrz_!A@Q7uJzKAl8_D=7~I7<;+soSj9^%MZHf|ul&}qLE+y4}XC1Bp@4*WN)y|0__61x` zu)F0!@j;u9d%AQl(xTz>%`|2U{T1AUCpikzPw^2sRNXcoPI~>;J+64fgvMMK;F?>C zm+dn3R%bs?zf^{1j^v=F#C{d8Y&bWq3pQJh7_t1FndC{~ncq!Bju++_jw5eZ&`!3} zE~t~?neYpqEhg8Y<`2?cPetb}G`G{(j_1_76Fq4#L?@?@Yc)XunsB5+agK_L9MF{` zv59)52<%IK8st(6T;Vn5^;v}cBptn8{DtK~eEZm%>3mO`cb};eU+sb~;}4aQ+OG5g7RIfL8vM}4W8n4d=_q4P`lrOJ+x(BMM1 zZcNtm9)>buDsA4-(j1Y@3cgfuFFR-{PtXe;$OVtETPq2f3&qXSIBGkDw{9>Dp5!qo z18T}G+uQCG7L{g2sCygM2D6hUHnwn;-scob>v9x|M(~qHK@)Ra;SJ*hua;S5=YYpu zul_cZli@3!r~>(CObTnZx!UxVJRbHoSs=W!?k~LiV?{$xM}Bqa zFCxOFIL*CuT?9@w`r-j3<=*S5++IL0K;dl~wi%46`Br_WWyv*PAGc9{4ZM${#Pz9m z5dAxNOLL{BDH$kD=D;CAK0FpjWX@*#F^@$BJ()7L8cPjv<`-ELMB8v*H&%0tRUY6+A{-Fpve7XK!h%;Zs`0rtf3yTO=(?sF(H z!CU-;4m!W#eYLxeGv=j0=^d1(502J9le6Tr&dXnz3Eo-LG5>=lM&ev#WBecue|A>) zRK|!sw#EsV1P`j|s6`g(fNQj3>nr$AQ8}C`+n~Ex80cGt!U=;K@#EuFdU6gbnCpXp zjbifMaU3Jm8Dcvke2`YzUjt_HXVJKODt6lNuAz#9n2E#coUDv7bj~ZClTQcX&pB@! zveuhNQ0I_QtfXbT!4Po?iU)K%*A$6lY1|rR5#pjlAX>$xLVD6>5N;$P33Ss-)tdyJ zakVTCB`~Qp3w|BHWj2pjWn8Q@dfTtE2R;V1c;M$qzP^vvN=5&@13S9dD#ds80?Y-_ z^k(3lw}R-ddu4~nB0eXECVBb|la_6rNZ2WS#tV0e8mLS9^TZXGA~+4UJ_!8dO9vaZ zjRfvqGU0sYSBqnZ`^xtaD${r51N0fLmG<>FenT58SD)IurSx`<1JCpGp7qIv9?yu! zM1LTe8s}1-k8%RMh~g_3ctDar1Pff6VK666&vki}fbd2D3X+D?Z2@H4peMbMX5}p+ z4&MN-T=9I4k8h)>nkg{wm3n*iQYlOoJ)TlKVkCiZIWzshC^Vb11|wFhuzLqJ##w>m zfChXNko3$Dt_*CO`0ymtj0%nDGuu1?@BKCvl~tx*fz4aO0`Av8qcis7ldF~wU3#2r zVDtyDFXutaC!cW-Xa#^L<<8Yrv;__NLV`1A!U-{!}tx4?AUFEdi}H z@lU&e9}6C$L0WxM6^#x4n8o|8Yt!kbxi~8sj*&a*yJHWBFkBF2yq}SNzIQDNn;kC7 zJ!|@kI_Ye~=&a5A+2RbC@cN5-ZUCu1H(AG6#K&_NYGyJTJ?2>PS&%7z4!_?KvD=bM z#o9E77Rk+=X@@=&qk0v;yq{&cr#D%oCXsknasiwLOXLP-`9C`GhQtv%3zHg`bifK_ z_lSWu5$H#M9l9Rojz5;p&;DNQv^7&sMumgSQRQ4{o<=G(pnECLfM1;OPO%J`M7|xh z_Z3f|zywS;H6(&dLPlc!L3)P*A76N@sCjv8@FY~1fTsH{KQMm%cwbpso?pcua+5A~ zE9%e^l}DeM;)bGDjhgdxVd$F_N5PM=by~RfiS#EiFcmWa=FD}}B(uet*oAE-lr-i1 zVpLB9aDKR*)ZLuInY1g8GGmog&7u;6yy6>hQ7bRgv#p{+(tYAdA(zKwT5ZgUuOj(O z)7Al%#;iKQuWv`z4e~@*#BCjA#xu8nUZw0gvwkACCO%U4V)xs7_sK8{LU#euNRZoy z=t(e#QYa@_uw#jL8p56ul!~-tmdF~OAw9lh%%)E1jt{_iXEJX@?f}n~rz(SgF!_XA z5I79^aZwe0voZAo{brcs%U~jN%QJkOzF&Ck<>gX9m!3(M@2ZMxT0W{M2Z7j;85Q4C}Cml^A^x#49y3de3giE~?T z`oK%EQXDM8M-pW6RZsqvyGMSlJIP}=g0qOZnI^3r0BP?v*j*QNw0yLIL)uum2j2z^ z>r6@-!`Z|Xeq&o2BV5P;kQH~%>yJ0T^tebh6hDXJh%XH%%o`c++99~^!B!H;DyQK_ zs)i`_3aF&0t&4mlY`?C89OJ%<0mD@u&%&wU!9mpG&_n>l?&IEn1Z|*)xJLt6C|Of! zGvny>yMGz!Bg^vaeR>2#l{Lq$^ri5?DCeV-X3aLyRKPJ>A`M0t1}7b~jG7qlJUnCN z{Jk2`OseCGP3QldlTH2m`kwj{{ zxH!1}KZcC(|G*(@{C`Psbaq*oe3us_k(Jq47kAisP&lT=SwhLwe-;4AV3!hB$>5+u zR;c;Ay$kPY&zZNMrf&Nwt(nc0>#iH?9YJa~IWTeU&ba_VI;cs6&lXJhQcyRyKu$sMA49@3IQCG!u|iox1-Eeo#ekp+JfJ~vpgWkL zS1>M4pe$TmkRN6j2XrvW^mZXypm7@@a7fBkaCpkI-P1F;y81A_qPG>~UV~{UAZV!D zy3Zp7q!vgXkx98cAXAkzw$*Q{g0?a|!G%6tkTB10btni!Ys^WdKiOMbTiH{K+o4l^ zYtl&x;JXNcnxL$`^akb}wcxw%13bk-3Q1Z~B^WRqKqSa2RFt3s1~ zim4Qc>ZRbTShq>Ixl}b^imqTHKbSOMOa{Q8d^kW6@Q*hR{@yusF8Z<+1s!k4mBIdI?Qn`ne2)d-BfR<}3L zI+NK%af}%37!g}H=xhGro*DJ5i^B7L+xT#yZMk373NZU{?Ecst6d!=hrcmxyk**(z z6r|G7qZ@Ks9lW)sJR}PB+Rnutas}eXpV7)*Mj%8;0RjvG3ZP3cAn!Eoh988Qqcf;) z8R&O9zw_Rejk!K#gSSPnRSY9&zju)bHzrq5P=o1e1N|F+>TjI9KtUkb2rf7Sh~^-{ zxo^}jDY)j(U;zCN);=)fuE#z;RPWu#%gsV2g_kC$;1%zW@%PGCy)~8P7|j{e&)Mq^ zH#9UPVgLsXRPXrM05DMCs~}K!N$`!ogc3{Wr!M%2zs^x!3IY()2*3(3{8$sU^-T^m zurtvI^?GAKji68o4vP6L;v|BAkMK}}c>0rm?%($L!}RH%^n)|@(?W=)&ePGe2wY8{^a5GPw^ON&VwzX?#EyfG&h<^(1PhhQxsb z`9i=oCFEJnJUv~UW1*n_6XF51om&Fl1oRJxW&^~7 zvk3hB4_$Y@hGB5F8}s~;@%9RIIo>1Yk0cPFd$c1d2-Iu$Z9n*c!)Kd!)K<4I?A2A@%ADDyE{sZa6PxkN%=_7sohByjs z@bV7(z2Y&co1G0fe!-{!n7uH3uHb+}cn3_)p`YMRh6dSK1+Q0^4@qrlwhV_R#H-Xi za%zsi#wr?q%`Xh^9I!Por=kgr(mn^8#Mp4Fl4e!c_e=pi?U$97y`A)HmB&A8^I4;_ zy*mQ{Qn%ft1vvvYK@$sdDY;0rj@RKTB=LjiUi4;$OEu7gk9jp$x{?kh12oBdDo}PR zXQ$=#Q@@D`QD?a{Rsz^E;Vo_NvQXzvDmO;J>_oA`N=ge=XkgrR3Whq=4XfZ05UUJc z65J)aRUBYfx%1!y4P{{A6QmpqexFqy8gCvYwO*ARcw~<4OOG;P%d(Is4cnPMUR;yB zg{u7zW9Qf-SlDgb>ayKs+qThV+qP}nwr$(CZQHhQo!sOid6RQK?jP_ZYp*ru7%&?) zJv+|S@aK0eYd^Lrd9dt zea4&YVwKjOk_-SESH}J^+2rE&Jv^Q~BxJ48mM_f?@+mm+jN3Qx&^>P1<$Cm`&hm@s`A3k#jbD zj99bJ0n5$$StSM)V3j#hfeT%FR`+h7V@r^Q# zm21F9=UJ%t8lNG{TQ2WS9Nz{y1LpO&7a%@VaV6K`brt#0?fW66N0Dkn>E5TA9vKul5hBY~G%dK`DojR{Eso@Z2Fohsb@(rc%B{sQv&q zOvegs|DOi>ADoe~!nT=RLy*vB_Jx#Pm9oJeDy_wUqlCTJ#=R}K$}!>8CMiW_G3yCw zgCO$EPE;1K>Mx(T{|Z?4_Mn8x!M@B(;lwVne?fRM5=Q* zhbcC`q@XS#S!WMx+M=#XXBkGdE8H=4}Pt98| zE=G*kFlTOxyT`Ypc^ru#=*(Q&ZR$peFVFQgPdFfpTkuqwIL@y`FypNu3=K{@vL_kD zz61CB5Q^fwk`Q+PE+WPgs3^|>I^W$h}H;6;??jMPa`}oa!&dbbxyjX zK46$962@@s898GLv~#y?>p`>njaJSf^QYTSh=JETIWsRR#}{;a@rD?6-N_B!NFH9e z#hVuN{3=)0XYj3Sx9!ubgjWgX-UBI=YG7G`H+-X9Jt<-=*|)l)8sOE(7<;>6tN~NN z8TrB9i#5}no){~!1%=1iQG@%)rNgh6n)<3ah_4AF-Y1vR(?I63ILS1`W}GGBGZ9H7 z9{wV}FYdWKB@f%B1(C)oNk(H5ffJwTppo(A@;Hpwy7<#5I_nAy0{J+WO#j3@NdY|z zXi01vMme5vhAS!mh*pqC2Y*Qj#oQFw_>;;|xrG>8WyI3;h^}<5e04X*$j$>|ys)u_ zXbUb#BRqjZS@zcrl}`~T^Lo!neJ$BXiaPdJ?c+!-K4-xVPo2k=mY)s?&lljO0AfiT z82xtXk^}I(T6xEQWsDs89;%KtG(50S*>@0oaf`%8lQH5DWbQ5xjFy(!tW#4jST(5` z3IvkKKzTim?vImagtw1Z!L~v{BWNvSwXK3TuGv~jCh^1m;|*_A0{gfyUG^`Nz*~IF z`+>2E%TQUBW+suN^;}vcP(-HaR1VGiA1n}YiBfc?QCRc^UOR7orfrJA;o1supjn0k zGz!*c0U}c6`BBQVl9Uljb<;oIDnUHDb!@58vG(+Zq+^KF(h-<~Vs82pi{JJFe8DE2 zaH165OHC-Z)Qt-yidhgu}}foi|5$wIisLjB~_udq*~$GjuGGt#cY`;0hyU z0jBbKiZE9_;lhoXhnz%aY38r=uh&^MWFqNe7!a;u{!WlO%x@GsYYyNy2{&bc$bA}* z#IcY&qXvi|_B6~(hD(+ZG+>{Ve%xA&B_hT+&@naO+3Ua&H2M3k73G%T#yRQz#HCb; zcODym|DGT`l%6vmSHnEisnP;JLofu622AXNEzQwwWdQXj`m!kX?@%L@TwCm0y2FJRo<$J(hKXgky?F*_ib)(*oStyYC^$ETrpj7yth3wdAJUc~GgiGpu6 z2LvO-r3;?psvJ_>eYBkZ+%%wRaalw8ti=xOjjOJb3SH$vlN?^g!rg12vR(uv1`j^* zTONvfYy%!kt3HPt%y+ZBgd~(ALy`U+H)hHE`Rzm^F+*-DCX(}6H^6~LJurk|KQ76Y zP?#xYfioQAf;>!s3F$zvt@rt7etWlx3Jx~-kBB|3>u!2gZgD!2%NRG7X@ikWQ~%Q8 z_aW|ABD{4IP?~sF>*?-K4rIO2v9i6}6mG1k)6q_p;S_Cl(y zj}L+@f!yQdC}~4Pnk)JsOmL+-IoNyooe*xb?OZM~l-5%#MU4c=mK>qcZV z*7&hI61c9W-wr7D2^Z44a#`>rZg__;5*R2-!#Eu$bh+u)O&@i=51aYI1AhYzrWehi zLnW^@cT!Xi&9rhRYr^U{?GdDNX3u)by)S1{**oMMJoN!eRj8>SMj1pg*8Nq9g$WXe z1o`6R+LO*Rtg0+}>IR%-}K-uG1I7P$R-ntJH&R`MI8euZcqV zs5B7hp_Se+eQzMca8QW@42l#2oCB^cpvlklbQF;_JPk=|v_B-#jJhar?<|<+1Qg-m z0s2#7Wa$L zQFk<)1J5mF$J1LSwbMiZW1e;`T{!MF-5fTF))@_d{)Of2B{WIp-Cn3$_BV5~C$;no zY?}E{28T`9x-_LZb(3M#{ zjCvlQl9eX+x* zsN2yX!itiip&fp-xz17+CXojo?m{q%M`oKEt^o;FR!d!9e&^eJY8HZ#ah&|x18=Y@J1_U zrrT5=zDT10HU*r`OS;f3n+MlUT9W?qVubL?dO};Avu(=VSY-~baMG01w%&KV)Y%Wx z(5PkL+3$*wwTLIRWe4${*mK3*%yO&ATnotOef!x&+|*=49P6!Qb|xN%+1dAjSpgg| zi<(>H!_HiAyl*1)z?}7q4ou@u`yNPj1V^Vh&NN6DzxPQ8ea{waCnp|>nLwc7pua5l zMsAATL;%W+q^g!9>-mACa~yOD;Taf?vk2@)*|O2ONy$8w#Vc|8F%@dShq5>t+TMBj zeCg6o&7Y}aZGvnnX(+4d`|46a~0gCEp;J#cb0<5 zQlJAcN3<*WORfABjCJzi!%mS>aNoPR&b7^%AK!z#c%o{;B4Z#ZB^&sf=)Pt3!yI~U z2nk#fp&vYcBJLHeP9sb0uu6oeq`tFae@0!>2Wr8L_-?a>1rrZdjOtxLm$-<>=uTms zVf>ZClc)kHbzpZ_#M-ORhvb!dWOp!HPt(1Wm>dPTWkel9M|Ag<=1Yk>j&g65=xlQc z*zfZUmNL<2wnFKWuXlTGqa%wT*A#evYy>aeH*-bI$r^x{hG&Gb5Bnbg90 z+i1FY*Ns|V8gFv7g{q_dKceNS`Q4~>(r~LZw-x+tqdL==;Kqx6c><;fz#LMk$`{^ zd0M5|KH%Qc;)x=31Bk~RUh0&c&IWXKVi#gOsSS$5SYxB`F_(LTd9M}^Th=>Y}U<$#L)+o5E2;uu%Fc-YK&5A&mRm?T;52FrR6eF>8Qfk}3CA-?WUN+hKilbwUmY zb{U_TjjR(_91Y6^m2ZEbU4{dMar4PQq&i0i!*Pi@nr!5bmEB3eX{Oa;&=Y{AF~6X_YG{65Pk>u=%L01K~> zeZ({RyFX2%*j&84jF_lglR&$i9OZ< z-W^>e4c1B?>xWgmo>nUW*$xISI!>2xci&D7-8Kw!=Nsv9<5Np~3=5=EQ~D`nsy=ldK0_>a83Jph#Drk#8d%*F{2(mpE^;K`E7WUg+N; zCgutSi=%Ys)_ZT6L_x+gg;{@C2#*vSEfS8(AJSClcT(| z=dh7Cs^_%rr99qL92CA2n%>c0_u4ev?uBoXTD7|lEbQA8xL6J%QSv){7Z>6FUu2U6 zF3=}XdLI1lDXOPOPt2N_P?f>(IOZMu=R6B<`DEZ-DfTkKtN7H!Tb z^WjUo2;z_5dAk~7Dx@!G9V$p$XbGr%*aWrNfgpaMY|0f~F(229+VK<*wQxtwSCTK= zz7r6oxeB{ybRHqg6>K6x*MTLk|9Y&TI26^ec;zxqDY`cgo3~?rbL8kmvU>5~c){{Y zXBkz7%TVE-Yv@#8F>R>OuqfJT@ zDZKYS@HLLZBUmlMNE+LsTLmy4y*7M+jAoTB?-yRESZuBiX(xRFq&~7VEM$>8^B@sG zE4ikj82^CbQ5%AA**)yN{k8ZyJqe_KE@pl3iwiCgK9o-jq7FMoRjNO5!TYl=$ zso@^)55z++N75Xa-tJK6LVSr{Ce)x(>I#B0N@4>{_GN!cC|;h8xZBifpQEvUZdj3l z!Nua@nYYgYcV+dX*q_&+llCS5WYf2|zgJ28LJZN`{w>I+sKGu2#j0n{aHZ&X-lI7- zY0YoRY0tG0xZ+=Fn5WcjH&M36OF#TkrRWT#fdxq=l2%lay(A_1)Cuje@a`N4%PXkK zjs1D?#e+b%Bm{95NQa>6$oDxWs!h-J9i zGCLL~dk>B!l=1^I529w=nR)#3@>*hmfIX{k zq+Zre7-s68sT{t?dc?VL*G^1M>EFoBr0*$`4nlQ z!(my;)x9~x>!Sj2cp}kP%8ka0u8aGPgY;_Ea-8yvF#s*JFMM%S~ghq zyWY3-3;2Ju14zN%y-RN7&cF8>LKw)d(`)`?x;)10=KXt zrV)xG;t2vfg?q5+lftFAwM)%X!@Q50d=vMW2H4wdwUClF*%JtMs~pTWrp)@?=|9Qi z6Hkh&iI!Fd+TN6;9kcbrOg&wqI_|;xt=l&!k}2?JaBh9yM=Ah{2!rm@RX?;Gx0r5- zzAvnYBPrCa=rwB++%DX@SR8L?oowxF7FFS_GBoN3Ya19Fm}6jfq}b#?z+7y{xCPzv z%KW!0tFO})yl~B*1qL9dkG_aJ7=d=h-yG0k<_Se{6-H7t-3?N>W%fQmUe*c*L@T;S zCOtJVi14v(nDQC~tR`M*5ZHs+DO~(tg%lJ7TwVfIPt-o2sj$f*sU`jt=~|$#Q~~(U zj17-&m@r=BQx;k7R2T_{XyMfmy&!h&vAY2(UyBz6hQeQ{P_T!X7;Q8jy+NrVej!cD zqYQazLm8iUE^_hq-XknNQ-X4=XUn`Kn^Q&n6CM}l0-Bv{M!qXswvHPj_!T%dz@!TJ6 zw5VYw0*jo9Qyqf-<5#7m4-<<>oOB^7G*Jt6BNxn)<(M!ETX!tO9|tFpp!d7S^mWcG zv^5xOOp5w54r=-e1BpZfYtk8c!=peq$~8^(`T-}veo$e2u9fPo%btsnN~hwgR-8*N%^;h{ zpOkjJoci}8L6nSo1-qxw6G{9VBQ)e1PwuwzoawKVYDpx_BqvX3f$5mIRd-gVSbs1I zpNV8$CO_Tj-(tb{Dmbb~g-&Ubx5FTR-cES`G6asTN9~}zQbnH<8Ukrhm&z4>x9CxC zO*NGu?uIJ7z;EF+RTTsoz3!(b$0R*Gfjm{GC693Q8gnj4P@D6V8h2{&BfbamMT$Jq z(kmryP3Cv~Iu;-aPL=PtmT;2B&WATSNAya|@_{nVuyGPT(s<^BZ;v8k+_^z&4j6j+ z)%7ZAEy<|V+O$!%Bvb?{(kcxqxeL+)Mkw+-TJ>XnOm3y4e{l`Tem0v);sT6}^!pqa z?%!8UkFe{=5Bw=s9JsrpAH)6j1r62y+Gvku>D}~bA%r6+D%O}|%tJ;;24Q$ve^1<7 z*ejsX+M&@Nf6(0a!iCQlrC$kjC}w_RXx|pcNuhzcyqDb+a2}5GCf~DLU4Lw1Q!0ao zqE<1t_a@8mbzE0;pz~%5R^?L>ldprt0iXpJpPz6742nE~jGmj$DR4T)vigx>c+_~c&uYW_Ctci2`=LV5mN9&;)38iRN)bM!s`$gK%-5SPXfmIi z_62b{gc7C3K;CLD#D(!=89PSg`TY4bFhBNZ0Rf)8jReDm@U5A%=bufiwfPicK!i(% zEPHmdK$09t<`PpZNs0SFo8Ht+Y(GjQFE<8Bf`o`jB%j^DHor@8cAZC6!|asviCI3! zXVps&wHV&WOY4fdQz2X5rDx$1^Fkua-0 z2ywRy9k^*=6merQnrd()o001-%QQx_5nFkq#<5e0R76fV6sRlffg7I?%VP%^ro%b{ zao11r9K~BinyM7K3nULYApxCK+l?xaW{W*dzysSHkwjl5G_3t+_+c)p$vXxzVuZi- zBh-*0EQx8X6Y2JyW%mYw1 z{#Wo{g-P+&+ey_^XP;ZrvI|5wSI7H(Nui;QvF0#?)3@bWd&^9Aam%7 zSooO{F`kIWbkQgH0-^PQuMX7AF;MmN7GW9S=EZDuWmQxe9}4YCaS-!vU0(>gI_nC? zMVY;Cpc0Qw4HYNP^J>`0v+&ez$1!Uo5f%_0@X3_xThh;}_Bv#6-3-_CLDU`QJphN> zZj6wJ%)1R)*2|e{oV54kVE&?QYZ`t5nC22%5wam<%3Pr9yJG65qaTW=&=kIiz7g;*&cN+-Vs?3=nsdpq=AK-y`6DU?fw!{wnDU6@eJ1SfWBn4VLho*b4 zwBHt+E!_Eo`%wwEl{tz829X$t5Up)uv}+`kGfWUT^|^Q2s8q4u&&#MYT;-M>JED;K znmeE9hzk+SsonGf(PqRt=@|sdY$i!7vo|y)T#>$rX_B}hF4+5CE>joXz{4(BgiVx=ZtF~{uc3hOhY9776`xaMP+WC9kiD9AB0Ig1# zS|*}E5+g6chwHihfvUo_L6eR$Rx~i<6ju^pfhYw*o0$`MVvL6CW2AM6c+c5KGXv6m zh#`+jYfV9QB;HXK17;d9R0*zo)FN#z+cJaON{D07&1~~<4*Z>b!3_Ob11z5_FELMO z^~_xe4IiKlV=vk^@Sx^-d8~~xMzudZyW?)@&TH8sUXzK11|q<7@gd_T>PulkS`@aF z6LK1zXm}sx(iwudLtBpzYAUN%7rEt=z4`Cw!B20=we@N`r@rw6fNE8Om{C+M_0*jGS#i9dU@bZDu1MVE|AiiHpE{R+jmmh#&7$q z#I+k_ams5nFeZhR{P}?8x;_K){23GrHPt$>l?gfS^W3Egn6SJ&mKIB)c;PI#!H6Mm zqE}`1v=@}-6p{aIQwHR8D}(&2q}Az*NeWP_nh+F@6%jdi<(6pOJzPm3zBW}VmjErz zL3JEw@zO0c+diOjSsUZjYBoHxAFXzX^(ZBwzUS}Yhxx}TNgOLwkUOf(1#HR31eAy= z5rQG$WArlQQn=zm*3|F7Mg`?X!iF}2XnD_Ij80h?5`QAqeepMPoEs9``<9^(N~I*P zz%q?|Ynxv;mPhAB+!YV=ugB6&cS_2daldjIX=C`uJtu(6%=p-nMO$tw_h3W~`rO*A zK%HSC#b_*EDU0bh7F?NJPQUXgl23Xr8|Ma0w8?FX81#q-QM;5G!>h>-O7te9i9CSY zX#n}X9C@me)7ixN9oMqISgL2=ZL0>Pk$&q)i$0Q#Gqd6X;qRraY=qoyl-~Bf^z8T) z4((a~1Cvcm!BA5@ zgJo#PUS%7z%Ectpax|Fcl9}}-r+B7X6O;y)e6?+?r?66KlJPBlXqs7Ssy_ttMYcx9 zPB#CueS9KJ-bbHBP%@}Ez-TYTQe!{jxjQ%`FJ?>nQ+;9jtwmL>HN%Xu3R}H23e(a3 z&5@!=LsRFf!6GCgQZ*4Ly`eGM#G~x-9F(lT>O&8g$>sw zai}uyCidKsw3Pdvod-jq?}9)TB*2uul!@cpIBI*!Q!0lO&S4F%g#e8Q$5lQ;iuU@6 zJMbwBW#qk%JuQQ|WzSgF{YJr-4naK&X7}@CcOdinu6;QHMJSD0?m@cz9he1MIVFZ{ zMbBAwFyWZXQh z6P@hKgA-)u|M3rFht9JWMFWI=*ZBi!ElUR(K<+P>%0>;0m3w^+3=av7_OfOKcjtLO_F4Akqrp{UqWZ!O2LLWSM{~8GNOK{&6Krv!R@aHuav~2PMh%Y_RH!}|6KBxmf{#z_v zi4NiY4@CgG5pio2VE-CAqzHbP&r=DwLx2F?$o16Ei81ybxJ>JfPB1mJwZVr4IHn7# z_pfVf3A?=b^*69b@D0`wkPkq>XGf23rw6e37vRZ%_2Gx2=H?3U>k9c5#DL`X#fiTa zz>;2&?@O;)b`rOa7V+{ANbcrl-go!U#+^-sDj$F@P(UugvMeWB=4;M58k+gX$gpNN z<|LFZ=%B3(0Kn(dhli10UJ4B0_2HMy>&?ee3M&h}lJfBzD z)^EKwc3EKXK2PB9p0@wemIM zXSF8>glrKC5|n_2;al zwR`SD(P2z3(rNKN!J6&v*m`FJ&N-ov#Q+{oZU^flbl&N2QWZ9t$Hvw++(TiI7%_x1 zY?F}FP^v^38f!B|BLf6Fp`o);DF~QnCxSZh| zY)J#5)vOk!blFDWUw~T!2@lAeI4nh(adJCgCCZ@m_%)&XLRr&V$#9o6MnpVdMf6+- z7f5iY%3_Y73W&v5zj!A5ZY6jE2zV>DmAr|EJWiJrB=AZ#ZuUnN8hO(y7BREM<23WrmnrpTec5hq%Ru9j11WuB{3W3>rK&6L#SRgL{G+n>OiB}fEG_JlPF)MNF3)! zh+DJ3pBY&i4Oz~hr85r_QCT#`e%Wr?e5eE3686HR zXmyXX1aKq*l-;{5dLB?`Di!B+m^=1kqR@L+S7Ljh90=c zZ_e38yl)R*@vLiX+}-j>De^XFPx%hP?`s8<%GF?I{Se2*wf24rVVA z7ESEq%lFZBOV7+Ppqf+hvxFy4KfLXH!>X5I>^#AZHEJ|CDDtG5qZ4{L2* z%7M4gYU!^GlRbEYbb8;hFL7!M%Qkm)5e?fLgGLu&P|MOt=?&{l-gnJ!{WVFOfKS@= zl7}q(zk0);TrgoV>HOX(ViYREB%6|Q%Kzf__aus2TcKS*yK!_y>5O^yDdj3K-XZ06 zVIKDVZdZq|<0~5Nqb{knG^LcI9;eW^=Q-fx!R13s6Gdj^0;R{2W1O1?S#>A^d8pdl z2y<4pSx<;c^L9{Djs+3s))X>GzH2L)qpf%En;msWqvh-oSSDDd&b??2Bsgy_YY_Lp zK{7lm4A^I)f$W^x`pMqVT!`7i;4~dV&y7k$jq3#bTQ2KYCzZ>V`Kfm-*^~Pc6;kl; zAQm7Ef?p91r*PI=|2aN#;aj*?d-|0{5QGbzvcJ*6bi{NLvlS(bshv(+Tab#dZ*vJ# zO4p*F(8t4r1d9-fM47~RqJ9s8x!KbDeVxO;u@t=c$J3`i-wo-1T|;m)8r4|_jJ$YS z-Ek_nnTV*&6lcGy`nZS`{*eiap5XV~qKAv%HxKH~-T2L9<&8TmcPe{-+j#7wOdYak z@O1U;#A?#Y7ucH|1=V{+A=Mb>vdifJ{d;XP)76lbUY*R}TJJEwzl&dKk5lF8pT%T0 zc7ww}iRwDP;@Y50%hpDRT9$IW0R$td|SoYTFBanPL?@UV` z0ixX3NrI3KRg2Zw(`j&=5me(|H$wIabQn@7cwVlY3!%4)*N7#vHRIb9w3(EtPm5Hu zw|gAU<`I;{_oBQ8PR(i+=6fG0d6T?e0UW)RVkJL0s4CPw&se$RqRdj6eNS}V4mv)g* zQ$(Nt^OdVSjF-HJ0?zK=Dk{^z2%4tS^yioDZX154OERyx^jn#87=(ih;C2NUkq*HVWGEUQ3SOigO++UIU0n>% zHB7S$kKq;5YL>tE<>@y#3@9}YY%%Vw$PqE6Oo>AAhB0(h%YtFX-&2fmm&;BO8PN}d z*b3Ht^~3aeudtv6d*%jiV+hNdAx}?fcJ3k6#N6VT@1aUeQo;Z>U-90-hF&JuX4wo0 zV+P?DQ7Tx(Z{Apl5$Gx)N=yHgTnpZVXtCs*%k|q;Q{z>#AxdV@AXSBNkwA6@5ok8- zSR};n&^1^BKc&Knm%Y0om>wf?P$LJ;EVhyehA!SM4rUJm^U#-C(2+%;Lw8)PHJ6pHGcEn zT>8;!Bq#hYP2bNjsPeaq9)3VAjcp@W2WJ6Cv1#?V1T9ZxCY8FRS%hOp)=CdVUAZxD@i2C9nvm)l=QxBkfQ=w?fU>L`3Ej$%p z|Ph~3ODac z5LvGja#}4PcHHGKyHmEk^at@(p^mt$noo54v9Psvu~^4VW`b0-Ke#gD?r$R%nqv#i zRUuNoc1Ey`?ZhK^R`%ogaEs`R@dK=OrzFyo^{o*bF^9VT>ZS7%t6#W&Ic;O7OgCZc z-j$iaqO1Oa!fsUh9Oq5pJJ|;gWW8_UKU#G623o){Ro=C-Gw-!D;DgY+bU8{n&$0w+ zZvlg$9+Hq{S(OPN4m^X$$l|Cn0qKRPcd)%Q8$?Uq=jn))T}BU#q;fzsuiBGYySIAA z)ODieH9=Nm8B8$O;hHbGy2VcfB5yTPgI`!?|Xnwrz^1hG4eagJ< zv*x|kA_wzl)Y^C=L)LB{UfKkh`X^`^(zdKTI_$XFHrX7Xg$ZJ-pQ*JMjUna^1-!l{ z%OD1O`AmM+Cg8Wl3C7OWyGIhibnv!9ndU=X+Aw!oJ;sLHj zWd)+J8^V9yyY$HvA+Z8F*og`ZD_hbMK@tlrDZ8p__3wlQ0(fYVv^Xwas4aE*Y0$HJnD_q%D(Wn*U!k&3 zyg;to6w_C#P!OrxC4_vQ+HcBA-0e7DX@F;M&?Mx!V9hwR7y+ivk);2WQv71wgI8kZ z5c1T@C4~n|ZyVA`m->)OYxjuKa@=L~;%nwexmTm8D>=@&Ao}Y`m+e4JCfS6%18f4o z7{UeP+l)&v0Q{xFhSf6^V_cE^%vh^!5*9?*&ll2cI>2yr;>5uGhU8OQI6Mf>~^ z$lFkWx>B-U=UJ`y9bMN1Oiw>8j>hZQEb@0n4-dyB98(g@FZ4?mOs-E;jxaeBJ3FpZ zE`;->Xb;N`YZ{4Qn9%*>@5IP@Vs>^-+!E}~W)>$j&kC6y9nZEc;qhnm!c-{M0u}`J z%8>JSg-FNoMYYQVN5e4q=yq?HK1^7=U2ik`*RB4ZG}goyZ{d`_2Fz19O*iOCF8*D6 zvqkcu{|07RfCwA*$Om7!IkSce$hcV{@$sloF~y}nxY_MN&~U8RU({qNr} z8-y&y(tirAwiyFl%&R0BUxFUuBw)BAwH|dik^bF}GzHm+&$Ba?XR^6O|NfHlUWa>P zPHz`d@~@E`I*{8)Wwa4RiZt04a(MY2=2?ivwFoB+G2hzin55iK ztC^^driIt6+>|$@XJon*`*_I78X?Ih5dn<07VL$9d9kx>qA>idwU&;>d6iP0*!BGW=FzrTl8q$vzr)sFB742pRJ0uUDoN=1kC@n~NcA830T69~VW#a}9S zd48L=nKqo?l>k%s@r7IHdyzf4V+=BsJ#(0qDEOSRTXVQ^j&(zvPo>_*Bs)Gps8<9x zoZP-1#ZYzUeax^X&nnVu-=pvabp?%_F@mFOv&B~>;Kjfppl4~?L}1Tp_T z$CS^h*Ng)`o4?-2=qLyxT=95H#@g5vN#6&pr%Wi?49`ex0Jd&|Ji2aUFmyMXvW&+ z8Ns{hxHYTSjwnxe28iq;sj3TPWZv=|O5-~5SlsP8C`jbx2^QFCm8EMh2ivEe zj0L|?=Ia8OV27ERheevWBZ;f3nwN=G(78bf<|gbGWjAY0x7-droc(=({%_gtme==KO3P;%bx@Q9>W7DH=m(+B(mu7bmJAs{{s!PtqroHvHVZ68dY&TW6k+rnMkX8k?Dao5H5lbnz z05>&qb8pH%hnnhe9n^RJjwj+r=mnsmi4G z?fhHf6+>8`57+k%;V&Be4x3Zum5EFbM1-SzTHdL@9*I!pP6*Huclwj)erTR)37W-VCb|VY`@onc+ns0V7C9)~tXzUqh?bwfGk`|jTTXM%; z_Ki4o<|n(?j@l_tQ4sDS)d(Tblu1f8K!9y1^V$RVBlwHyhhV5Ue9Xauc+cK}_nD5D z=PFlfpvpe?T~BIR8{h1mQM?r%pzhE(Zo^4j1+A_>R(M%24lfrm0UjS(5@!vGoPBe= z)Fvs(w=wBVFON7S+gX{eIVnWwnyBdynTLAu6>*nn%uUvum$HX6mrfQ9|EOp)DWsoZ#xTz8N^KOv;aYYGQXm;zKb*kzy#;X(o z&k;8286e>EHnyOQWC&VQ5T8R(ZUT5?LxGh~wb}(87dtluij7r=-nh(7WYLR7#bwX; zAblb@j6_|1aeN7iz>l+g+%pJdYg)O6?4Sn=<&GLgmrsArpUf6fyKl%k%hhCh6I_2m z0_pm}rkkS^iq1iKiH3NOgr=u>B>3Ct_kzpZnPISrbrEsF*Lel)B=Dvch5x%Qf_rVb#PJ2oid7>@79z;WG-lEIr@Xh{JVijb2N_4ZF2$rqTi3 z`NfR-Zg!okP-A(R(uy3CdYGy#rY#ybzomj$OH{Hx7(j3l%7s37=EURWu4h0nw=`4joD*bHsV zvZq(mt7JehRs%!U4)QwvbeGi|R!l^AnKqpi*}gFUIY<$r)UeEyO7;}3Sxz2>22wGQ zk24;s<;(h8)q<*bJr1cd;9RBiO`WsSkQ8(&Cy!gCxJ=C$c0Od%WAkijam39eI6?v3paK?a6ZeN>3|yI}y_#+j!CSkY7u>hWPu` zO*WJIAjE{~#)rcd;q2i~zrXgUhgfVQ%qt7#QVIOKs)E!gIhJ*}%mwlzyfJ;A&7M6d zGb%`Uk{7JNzB~v(D7nO0iR6U3@nC+)9~R;{P&(^F*{qH1`Qh(hbNT|@16W_Thz{Z` zlwl~?>Rb#B5K# zC{6@Co;5o(|3l`HdviU8v&#>)3K_LC4P>rQK<~x&I;!n$ie9(mMxPn$QzCCaexpMW znuT>`j8Tyo$zSXu=%9YplzX9d3y={GNnBk=PlQzy_u{|~vW}7BN+(}hcmkPTdJ1bB zp>3^9cr_;)A$XvWDBl@n_rp8y$imz4Cocu+s_cKdIJ5nSi!%c=9n1f{I5W^Ou>Z%C zGXp&<)Bk3r{P(Do$Y&5)&9HTl@O_#-YQBSOl+7*fR+ib;4ngof?p8rt7pUv&YaBpe zf6z8=#*<9L@0apx>T=zhndK4>L80ROX`)|91Z1Lpt&5Sqf$aUEn%j@X>Fy+0ES()#8W3{YAA8tmK2#zKJ1`Milh~pp%GBeY7yxxf4ggGATDXIq zYXCXUT*lGKL7ZIEeRGgTAjb5xRlr5;Nj^T68lRxtzyAw0K+3j&V`1^|@L)Ev zb76LHwiKdc1bBd4tpI937of8{&>Zkr!2l%_JK#T+F(Xj{G^{`_|H#!HEL=TIoPhwa zz!qc%w08k}xY?TnodIBSfV!*#K-m#!|Btc4KL(6||MUjH#?1D=aR2fCD-g*3Z)X!T zGY30I6MHX^y(Pc`WD5i+ODQnBdb%0gI4+%PfJe04`QmRvums0MH2l^fa?# z`76AJmm~0RCEH(Oa0Pxojt-6h3vdxYKad3w{0GU$#l#&5aCLSA`uY5+_%}jgV*{9j z%v=GcKueH4((mYCG0@^43?9BS$P=K)3f?_70P9~r|9dh3ua~)ly{*@8^S|fIA}+2Z zEw97yPsRV!iHSLQ0(_V_SpiJ!T&w`Lzm|*#{NVTRFe)aX|D^GUudKa=1AzCRY{6~% zZ^rKbSpeGq90wiX-?5Y&z*`Fh(EeU>eO4}3Gw?6A|Ie%bx6A*(4gV|3|J#!P--M*x zY;FHm)Bdgh|52ORfo#40V*p-SH&^fhC^~@8!2bW5Y6Jf{T1B8a$j$EmYGqwbz=t4e zZ)y9#HiBHFK%PKz6_Bf$)j!+vk6iPwE3*aJ163ScK!3ef08HS~{2v|ow9IV4uMQXR zO8%_^f-mRal#=#l4(5NI7&{j?z{J_v#0v>LWH90a_^^R*(H!Xc_YwnGnC%^0!7c!B zd42#32WOA`K{&!ut@$7@vs6|q<$l? zwe)Yq0br5+jld)dzY!0BMe#QRQ!4$Y1jkgi16uy(dc0^ufJNgs0vD$F z8-ZE0|A%u*cxc-)N{7?SRO8-v*ZiCrx1Wv*XE?VR=+3kmxYrX z_-KARu>)8venT*cg$3x3AYl9(a&i0x-G7sC{iSzsbN(Y9*u?S=2oCt0pA+0;D=$YY zp#2{fVA&sptl(i={{g|BxA_Bt+wy1f;8xoGhJTI!cVsTGt3CK8{?LQVclezQ*xBJ< zYH%@*zt!Mij^Iz7{lBKl$@U-Vzh}w`&e{?Da&q`R4o+|*9BtiP{)i8jIQR2RF#o!{HAHaKqjHfZ$oV{{g{yc>J+gVDCT3*umkw z{(#`-c>iuCIFdKe`5&r(z0J(roWZkj{rh_Z-u3_DzyEsx0zH9dNGppDX8fVnb)g;i zHKIfwOb3&Kb5sY~sdP*}E6$y6k7)48bk&)`Th6zl$s@gQ*7qc7Z$wr}pMAcyHo$*u zOH^(D<@;n5uQqegjCg?h!N;9FFn!cZ*J!> zbEaNN<>DET{LZ2|ihOjp*<&6Syf-Q|*j>5_C<%1&iJ@;W$7iU0#Ew(s@Roc^iq;30 zJzE8eNOMpbKd&>rVLoQhs0OJ;+Bf&rx{t4PvF+z3143zt2C?=NYfGE4jhxAqajM&m zBC%X+Ic$K$$6Xd;8y&Y=Jr>rV->&k`*1rPgQFW}o1-A6~{AzI87#SU8x(oZXr z?H01K>b`^RgB*W*&Xw!?BgU_?@lvU4dmdxS)&tWZDBb>=gZ4N0xJ$lqA6NY9FRW| z_~^T0uq;v3M^FX?P7YRVp~*8DKw&9O=B7ds1NQ4;Vz%|Jcb3Q_X>5yNm5YAeCiacM zhjKyvZXHO0y_j=tzLFI z#?QT?06MZLix2OE5zLM;A`u|=1QuwphwEZfeyCxoa7gBng);HgV$fi0zf6mw$)Q&> z!>;t#iOWqw$hnq5Q1|)pz{PRbB2ffsP4`WAe_L3TSs+Thj$|nvMUz^x^dOhwN{aRP zp&m}@Tm2g3peitVH2E1BdB)hkNg#`ajkVMlA?;P5{lxB~q4{Asb92P%ax*t{tMVie zp|P>1CPR3Hz*zX2C*>P1ve9@htX^{0^*c`$0Zz6B;%h6+pYu%L9@1{v4Nx|un@TQ7W)#TS1w5-R;Ir;9-Swzfk~Wlnc8y$qu}*|z+e zi~8y(oWVo0NJ7>v;_@p+xd+7@9oCBRSa%=pE&QZK{rf%ulyi>LNIE$Of#4l{OOXrq$jb@8re_(iq(w{1q$M`|-Uu-4fDr zKhAU0r?=A=qYm_=KJ0~&)^VzCBB8PAO`)pb)QNv<_BDFss zzmu^h^yuU{ct22nf0(`-3Z&|<{5ms&$|Y*_T!SH=XOrLsXQxSK85;lP3#i@T|Z$raB|?fONUwHLxF@e3>M)=jBc zS5jf=AC1$$!T0ASZY8o<-1KGHc2cQGvgh%UXo=FPiz%=i3Y6iVb77T*Z~HC#u)J;_)kYV0mt>VdtHRYc?r@h%(!^JeDj7sUM_CO&ne%6lr^A=!%L< z)6xUF&l`Hsb``H}-cwOh0dR*~X6AOgm` zi=fRf7iyTeEx1LU?NZT0&}E$}Sm9SYp8DtZhE^QRBVN!BPXw$|QvL>hwVfb$32% zkUZdp04JRVga}%hbwf1GChQeQdNQ-5nh2khW z#jM9!puWs*>XF1?25>DcJXZn|;#<9y7_Zwv9w1L6Bk|ua=V#z?)Gze#B*4_!l}0k$ z;F7GGSU*n0!F-!zwBDK`-FUZic@juVB8p<$j5Tx4X1xB+jrrP*;e2m}{P9|d|B^Al zd!%883dy0pdMnoxdYCoUB^YCIm;h6oP0DlXeE#_J7QphwE)k}W#%FjcO~y2rfrly&PU4E zK<3Wz7j&P_C)x%{J<`Gv?Q92e?T+;Z1)=9qAcIQYx6^?4+q*RfEN@xG>3`R%*Wm#M&`3wg~$DIoA z67QLAvJh9aX3~FhMXL`;>8BfDHHv?GTb)0~H z9kt7EQHmn(mUTX=JpM$Ql!DZh%s;z+iMpJV59wY&mx-dOYZQXiRTY^;mtEO*r7GBe zP08%mE1~1*r|x>nwVJfgLa8M<(V>}NGwE&8==(wQ-Z@}?D~-k8$UYfbP9YB$8G$xM z1gY*QcWgQxsj^Xt*hgNfack|;&?dulv)BIAANRYlLUn-w!kS5;W*%hgfX`Dnru*)N z!q$4*VLoT#PqtLb04!%a(bsdAWbEF->nnTREol0*cEQrSQJ0%bhYV~}5ubRkMPvjr zadFZ}A3QSzX6*porn3u@LsmR{(eR z0ogl(g+e=|l(moemL4l)@JI;vJO@&UIwD@`2L3-jbMlYRKsi?p08nFM8IRkv{#}x5(Sj}VzDm#usyJnN9MO_oOJ$8f?E4+;BeXg zqU!rrN;sLVFGuL(uCj%d9f$$L3(PAzZ-0m^+vAiwr@S%xd1k*J)Qf=HrTnz#Dyjs_ zq=0Il68Tve)@T#g(CEXOC3Zrie>U!5EPu2yNzL^45_z$Yo0r_c{-&OF((3pYB%!2Z z+pnsQ@nMAJ`2llu-C<2x4~<1vEYbY%>I5_>hOIYz`>rr@wbml1*q-I}A(FJL(xd#7 zZ8&SHPEawWLrFFoG_9A}Z}_tX;+%-=m-pR*Tx}J^*%IIP1Gpv#KO;HCFZDak76l3K zM^1aQiK{bozb#N<>+>f8jzFoiPat!Y%cUr;j)o@N(*Brhq(mTT1CFR3u-G{&amn*Q zYCi)beChhumN!izWKt@(bzA4EIo+Z){k{(LANBn#fy34W%#e+x=p>(=LOhVoL&_q| z>l~EKI-Qek&v5#csXmxtAx;k&l=5y7mZ9hMCN;QSR(Q10l6)=v@VrE~;JHxnn zs989FPu2`VL|ukDMc@^-BjFqd=xz`34l5{2D)_Dbo>pxc$H28or6`$~SH~XTk2wbH zY%{U~&r8^pVACnZm&H#zEEawoTPYde#)^mb$fZkDFe;B|EEHX4;O9x-YimCHJ>51o zx9IdYMjIjr&M#3}PYjXCbX`O$%e*3tOvI2HJv2q~AAhWyyb6flm1}X&L#qoiSf@au zT!Ak`U!xJX5)R@@69`queV@E>qsg%$a?rBXH)R`WNDrxMtG;s*xSH1tXE!<&; zEthbQ%QVLkdPfY}Tapo3j|;Mx3VF6^QDgp=ar5j>6F6kYj7c-0zSk?!KE7h>^+bx# zlZcy-qI0t-USBz2chYFsR4whsWh9*ef8V&mR{RUyl_hE(`DHtLeD@M*oAXmGTcv%t z(Ju)hKSwx*LyIy?UMouC$C3d^1Ca~G2jgYK*;Z-!TYj!`xI&MiZ|yMqvd&Hyq9q&_ zqQP4_7$CQbz}}7hzN^lei?dlw9p^VE#1c2Re6i81<|OcHMbI07L{V1^ly6LBag5k> zyKN?Ag(GcNyHmV+^IzOv5!8?HdF2xbLNWR^c}5aB4TThV z!N}64ymnZ>;ZpcgCfjY+=;v!i(oGrfEwPKGIn^8I(XJEC(D_`U%Qty()IU`?kjeJ- zs?j!J1=vkA1ZnJcF9JpA3sZ4MinF*Le%z2gXt>Hvbk36PHS^2ZG#|8TTVdT&@9W6qQOro8mZNvyNgbIKW~he?enDTz8w&x98%n5pjZ^Z^ zH@=RzlnJ-FkF^gP>OXy=PrzAxRvq0bQ8Kmoz_8ZQwHcc2K#mx_@;0qGMoU@6G}I$~2h_0T?JKA7dv=4~IL;E8^ojh8rK@zqo@plq zphI0|s^<4=f0VnTgoJ4xp)R;=Qn+o%(o*Ww&<8Ve3uzTKfL`(Npi5HW z9V$`kDuTjs2gFRz$T?PA77?!Ww+vMV6&5@Q##Tk>SWzv%_T^iznr8l;PPE9RjVH?Hft+KA~~wW2m$Uy5`~=Zdqh~(zMW{ z^;@AQz7Z{>Ur-}L3&p(jvaEi%bB+4sKFc@=7aW?a-h)3z-1en1EuhC&3P0SaY?X}C zNydf0Ll1t^EXsWJpsTvH#EKZhahm7bHn*lIYOP+!3AciG8bU70>~L{FWoi{kK$3@+ z=84@Suk=-&{s?tg_ILo$z4CVP{SfR|(66x2ppF$$#208$wqV!srB{^WB6jgo9htpf zkRX0huim_QIq^v@Q-8f4m!$IT6|ULYDt_S81G+EVm}{3c+st5w=#leF1Wr}=Ow|j) zxSV@0qdciEB;r-WhpA+(&A7Nsq|~Pj)zAjL^-TfIp7(rjVS-oJgv}UkskUnozbmz` zi>Y(*hTVts)I&y>Ws~6W(g1SLt?T9KyrKQkJ(GQFuAz>BXkvwwMx_C1`mFxQW;)iw?*h6)O7VREXy%wxI0O~gsn@Jfl3e!1O zBvOCr2V_b9m@<;#G#I7Nvr-*6-9Puu9qu2j1|*ifAjO+yI8^O-50J(K_Zi30tn_fj zsZkM|267-kIleD1*T9no7eOv*Lh=3z7yecTb3|gckHa@Q`LH^e{4B+@urhBA=gpdj z?W~f5V9=@H5>a2t8;H+vmCw304o3pCpG%kR$bqGz5)){dz}2SpdNw?51@V%SX{WY8 zjZRM)mN-#J`XxxW9qCFF`&3$`;9X=f_v3GDd8zv54QRxoUuSE{p?-0?C=O^}iY z+wN9J*QwE-ivuHT?0OWv8sv$AQ&G&V0rP;@)@J9=x7iSu&!b*^B-w1#4x1DVH(ehb z*2L>nAth#5R zZ(U&L^3`Hz`M62OhcVQ!lBAhVLD|e}$i2ZeS!sxVF$ZHUNcGSVXZO*c4w|ej*up3g zlq6D(4=oK?inOT**gYOOMumwLi!rD0&nU!yxhoOE7A`7Jm%Ew~a#6rQQpmH(5bMSjqU$5zXZXQz$-Xe0DaV=HEbPW?Qp;C3W_j2hZOgt#qB+)~_)Q-t49GA=C!jA)H8$N~4Pu-kBX(l_b`)^{d9 zd9r&bXg9M#>`1ec&O&wHcwBch?u)w9R_T!vUtVwuEs{|rsu*SwziS=Yx_s>$%34qa(xatI4$9Meu6MMD4%Sv)=Q9pzF) z+yU~rQ7qz!6xK!)%qL{MfNYVcoMc9TI=i*>Oc}dB@QSm>(n5OzygCW-JUH+MnEa4 zsT#VFmwLg@F=tM<>&;kNXV2%pE|xQC^-W(n;oZ7^T&ucZ;y!ab>ZY*6g9 zrUrQ3qiW5#HeDZ{EGW~+i`-bO@CCl1pnlSJNoG-aZd>r5;HMshzsOU#)g`|P@k`5v z95YqiR^T*kg^a^bsOH(YP~ef6OCKIOz_z#>0!foG$0&O;!=jJDhpZOV4U@+M;nq-Yk+m}I z22*4g8NVZJN`1OGt;pN%p-wncoEA+I=6H3~jAy!>F4IkWQ|cuBlOFB+Xdohm6bXWZ zc)Hfs6GYUgD4ed{$NmZ}M~vX5__zAb!B3PJ#9b}0ak?~({x+ydCc$QPz}I8(Zd-iQ z>>tkwceKV}Wbm^`Fr_7DE9FZ>jXVX(7xAK1lf`l2uNN>3KOr9#)~@-iG|p+CiCEMc z-(`JDE=b#&8)SqbWAiaTek>7Q#EVvRie&c~&cuDc)e+uY(;QJZhfK8s@xpwJyPx-s zgWu({TDYBec;lfP${Lm@G-drX@CcD}@@mqh4@8Od9^Y@?ce7tIZ<9LW{3U;p$+)ie zJwn@b?!LlKjG1aclRbx!cQu0XOLSqXx)V+FxF@l-J3fB?8u`yLSjWyFcCt{HADutf zCiqxV^S!Ae~gb`clq@=w$c;&-+|M|c#r}!SPtK39E1NMa?2|~}%r({45TY0u{ z?it;^&pQ>Mg|@&}!7sYnY~8Qfd)zJC zgy>wYT70`e@9$6+vmMPy5&V!ogtlJ~Gn&vZkfh{J*Vdm|dvt*P9wQ=(t78N15dpd;;Y0e$90aI%$Z{vUG4a8tyR z+ahk_+`q=!kG#G7YVZ|?k33KNUgC7py=&@dMk%$RfKZnNdgtE$eeBXIob8za8@t3P zek_dXY@dsU2cMi-dsZI%X)7Dfiz-}3S@|-uo;}b=h*AVS&sYC2F**p zcCD|llV1h^znUzq8ap#+PGG3VTZ-Q`O`@(U7k=7Z!!GUpZvCS*Q9j$=B3YV~%!L2E zwLrxpPW~Dv4nyQin}96@LL+15Qq?i_S~k#;wn6n`D_`}bU*;Syu!zU#m+d1C4CKA} z(a9spix<>*!{c-4H@#oQNZ1r+Oy--3Ig5+w8|Cn5tF7v7!{iaqkbYE(#X{`w%0+D? z+;0!4>aj3GbbRg*Q6$ZskS->cirz}?9S1qe;EnYOf#glZ)clbYQaEetKVPQS3ttVC z-U*^|Y#oi+5k1;4y}|h)r&z$8k-86?>~Go6J~zmND+-%c4ZX_1a*@wa1QKuFDirXG zdTYvH5{WcPVz_tq*-1{_>0NmdRJZcPFDhNX&^~m^XrhaP=sQmxDyh?2jji79*r<$s zTlRrZbRgqs|SM#T#ElQf>g`^ne%0dibpGp;fXCuwro4 zqSX1qt&54qo_7x{C7LX2@eA`mQr$gQMNyaqAjO?a7+)?LR#U&A;{1$aF^RI=Btc^)4;k?pYlbXP+|GApEl!I9;+M%EP48{jF_JhO~t9O~5z zH+(Ak3uYG;ZZ1&i`zL@;+f{}g@#&`3!Pbb}VGJK$N=@A-y!kmAxFOvO5p%%20iT>= z=Co+KlJC5sv0ksuWCzWi2_^ErJFeJwv=Y#B(w?$mKM%UF)4{52ipMI%ub7kIi^w?O z#z6F|9>+Xo(`^TaaEMf(ugd&;)gLZBITiB8cXZX)dHaFq^AII`LdLcgk???Qeb08~ zH))$c=&&h4*#U4X<+SZSok`{G9B1$ zyV9q_Az8YC?_cI?7J!@Vhtdi|8}Ntm6V&2g-44%Hb(N+}T_z9epBiL?NhR!fly!zu zMvbh8_=Svg-T~;aV}xpV&EBwvb|EH2%#+lAuFbnOUhkonKj7VJ`gr@fv2}ao2I{ty z`hW{5|qlFv($jB!T1Juonl>xHhM&ofzTWa_`(ilsQl&HTkXs< zcql&cl?CyJRMEN7LR*VHKj<3TB5W+c`FD!zMpr*;)jb~c8M0W>pZEBRo|Sh^BoBOO zD5u48zbabGW~8%se2cNdyyh!`@0w>*>woTTyS@7y`gIIZj9isf7V*dJjJT^@UHjfQ zaf1va`_IfI%^RotE5c{+9)6o(xSp#@8+v}?PT1+f$n`p}vSTi{eG3gBmPOs{ZUn!vo zzR*v%HekdixCxs=dnDYK-rdx5HFu;;c$Ee*K2=HRpzcJWmhEA~_ZT)oAtO2lA8{43 zHcgrBl?3p6wq?U1I85MHgsRPrAz(=CGVghN3;lP3~~%DoNXoCZ~&dXeu4KMGb# z-yvyq>q|LX0EOO8JcYMR+VDhTIP5_e;Vf3yBNtlEynK+0A{^DVo;`ezsfT^k(Av8u zPeiYp5PU>Ypgdnc^}}@{n29~kTP-B%LWimZhwrSSoEH-xUv+s@hNo>tB$gXViwB_T zG7_FMV)soJwKwWXkHnL3oGd{!&V7O3Z*f)7pJ7@PST3)&2Q1?IZb|Bm_*KxY<4pB4 zSr}KCb9PoiGc0O%Z;O-*kM9TJEa!2x=f!2^6{ZRKq^qwc@9u>AhQ+y9@z%%`X`uq( zi!8)IB_g)dE}Qiv@Yrr;D)Ala!7yg&UvN(hqV}?0Xe=CS5$R<Ktmkhod4taB>aGXg76e=%Zea4t; z^HuAP0bud=Aeqa|6LUtqzAYcKA16WYG1E>TY+7>REt7x-p%HS~a}RD{F=`UFZ+y%3 ztW7*kqeut2ag!CI3+LKg0+Q9KMU+xx8hHmfYfDnE9d3AiUCqFma7TbfzkQ4VU2e zw9wEvA#tlzklcttGRjL(*KHYG_aiGaDrt%VddBVzJIfL-D(f%h(G)-PFz3!^O_J7+ z7J3NT@l>uPlsig7u67C`A+}bO?tr{Hepv2^cD5&da+Ldexkeltc-$C)cG>3UD7nvw z7TRq|kE9#zjlPa_$BS|_{6g|bY|xgikaXVS5=k=kY556MEaVv@Rjm&%X<9$z*XG?{ z<0QlE_`c2rl|f5|WWFlJua3 zHU6YW|99bZ3`?jAC3l&+yD$ib0nUjJDm_whXr;AkK3kP5Re7G- zDhnoYtOUU&a?H=4LKS*5I3f&*dS)a!b_%!vthfWvL$7a#nt{56iet{E$6u$fyh0sE z*7`O0+ngB-?a6NavOnLpSS>6~LOxFA+}cT}e4ob4?<|ywr%(rJ*Lp9@qlhYsZm|ZZ zm&fB3vaJY=nKslk4Ub=IYJ4paJ#y%qRL9V0NKu@in(qRLkGW;ZGTc5207&Ub1an+t zoNGV}~(rwirNx;W;^ku)P)-a8BLOe-&U0a3i;aJL(aD9Wpy86JXJhPZ6h zJ$#u}eP)Ul+!kMV*bAg#Ha0YMj*w$MH*V|cSXc5x@ZZCJYG|uq_0o_~QI}vFL=#z{ z-{v=sgQZqibdi?GhCV(qCos#UX`ewfv$jgnWE1KR>oFavRrPke>9gTWulS1bcs3ZB zkc`uZx2kih*E$^79x9hI_&om&xGeehm86a~JKPB`o%TWU>F7n8_{<6KVV zoh4AoUk#HXRNS1~`A(uFuV;fjmjcREq)V~rT|I%?j^eUmH!1UMq;%*7|Ni~lOV7r- z5v*&~7Q*Z|)=)(YUhl&hix+?dOiCO*Zb7o`DcbDvf;?%?3I5MXbi~v+#$XUivpsG& z+DGB&S;!G(53Ih{EGb z)Ivu2k;4zeoGFwNy;EjYCh)YUBm#7F;&e5%*EJm_2SIdH8sJWryKdk4%M2x9kn=5M zvPOYN_n2L_q;9)aswLYo^hJ@KyQ$12c0JQ*BeU^dvto4NbXV%d^Zj@wS-d4=ZK`AW z&axT<$n|cvzr%$+CznZ3P$FmDY;-b?jaflp$D+Wb8=;ryT^R$heAMjLna_}9Lw@;J6e>h>vQ|`@TjY9dApqv$g%ke-LBz#!IW%!GA){Y0(#3;mDH~Nonj}sUg z1!cv=sW5HJ$Io`SizN3=BAnvdu8KpFPQKPzza53&gc4!#^L32$2SqG)Q@@Dco6>s?~|VTCzS?mBfZ_3Bo?}wAEPJc%w23 zg-l9!*e2{!{(bn~-oyU#)Ba{T`$;}2?>qKWTbmX9D2O|NYCS|5=v_od0Gvg@X+xLx zqT&ESo-#@U?!9;Q=U!N+#mmluW{QeaLA$gs7r^+r1oQ93*x9x+OfNZFFh%BjvuiU? zv9leGZV#eRE``2K5)ed>0x|72Wfg43Y8+^ha}BFYFNxCJF6UN6Y3>hhjr5$J$u$?n z`{ds#Cg#v*iRM5kb)**?i_vGlboXH!xVqHMqvomVllzr5f8oV4F?J|eO>=E|H+;-H za|w#F<6X9K41%~&;qga4H0;)QlA%>DhZ!zlw|_2f{WY#0s3#cgR48X3jXW;k!uOe% zG!b1dad_<^2KMbQ>q5sOE|-F+T4(xGfKsh+p+1kgQB>s|DPx(Wo_B5afKH~b-%jiE zLXC^OM~}G2BRxm=H__Tge@;st%uRLA46+nL34Pgz_twKz{GkU6zXbAL(cN|u$*0|- zf|Z+yFtalQJ&Bkj&PB!d*OZ3FD=$V%YdnAEbq5jjA_Xa1EryYJl6U(|B=d!gZ;g!X zuv@)E4|PqxG6gfa&vv1_%%+a3p=pVkxYx6Phw*2E=%jJOjN?9O{WMln=2uZX4`Dft z2j~6_VJkc#6q%};ERx6VcnBHyT5V$-UFKa!v89VJrh@ggup|JV5}_n;Lp*PFr_&uP zw9)?Mdw=@)dgf=ArdKTExr#MkJxJbF(kg6e9wX3_`g~p`^SJp)vDz99nn^v2#TJ{m zjZs~e1$qFJPi?d^YwlXQ9J<*m@u;o^InNN=SObYv@ogiLDVLsn(MB9RnsstX0YWer zk&^uaPx`@EX1c$}Zu$QR-Pik@gf{D+so`S_16p$by$Q$-roR3vw1_F>91(&9S^y8CQx{0|>8HhxB|7s-D;xI~R<;FMINJlcHyr*_q0SJ}$+sG= zjC*Z%2okd7rEj-sr|0+7`A`wiQMczzhjK$&(-+|b#4pei83-bX7MiBfEE|Y>2sk^5 zNl9-?(Tu7F9Qc2gT_?-ZUFpzN9mn2=gbC$S%dT3yN5s)3sKgw!GSc54)~$&N!E$xS zxxM_ZF_feY$h%F`y3=I46g9z{F(iX7LEqIF7j+9`ZhbB;JemFk8#eb&{w$V`>0QM4=FCxxwasB+s7FM-J*+tzm2&`*`q66SK(>p2lrP?@p{zVti3& z0DeZSh#exXXE^cVq9tqB_tU|;V;aE6puFWD+>F;=yCZ9Jc+k7l#w-3O5Fsw5ZjRc% zCF^iJQ~D_*7Rr3K_(Qnq^dIZor-vLqko`iFu}`PrK;lm_zoHd7Q&NP_fGYBv@IW$z z9gbUkM}k~7b=#{sZM>U9F}kshU4uH5m~MltRbhYbZ%XKj zSvR*56NjqBbt=f|&8KMhMBj6ZfP^;PD6E*aILD{(M8VZs=vPWdtBVW)J-6;zf=PP6 z%Yh3`hx&sg8~U&kwk+H+DGEM))OUi=WK%f9QVaoe?_U*PT_`OeONKkP3giPhj9W3_ zx!Xht&f?zUSiy_efy&`%RwfN;*tyz_SnD;uDD(w8 z{p*mcZ@ztSD#T>4UD!|A054RgmWN>+*r^VdPt1e-D4H)WX-*aAXOD?Q4RsYt#mU-R zW0RT{i59K$UQ*%_h?QI*q0^yj$ENv}>>!5Om^ZQkecN$g*2pJRLtdpN?VqZJZ%!by zA8V~L(T`g34$#W~MfZSl zcOELachOs9#e4T6mEiu(G1jYW6E;Tar90OY+kZ zjt8P2JsC_O{n=Kvzo)nvF`9`Z4C ztjC3+ug*vQQlq6z7S`HF5;GpWFOZ%jji2iskIEMPBXeB1JAr5}7!K%=LMV zy&*H7it7A<@h}N5R!Y!w?($TAm(s?XM{xT3e5pZBh@7Q#lApww*-ReE6M6I+j)c5t zdUmGvM?|6!PC&7XmaVvZO!K<66kd!8*_A>YHsW5haUBj@oow2D$1-V7+&vOuCmdZk zUEUHL3esFypOVhAav)Dd$%-lKadE@&tL`@$g2Yw1ro7qE844T7_=%WBi*PhYo!wXn z4BdX1fi9`(Jm&8P>gLvtnnpVnoDd-K~{7-8&7!5WI-+ zRT0alo%G;BKW~ZqaZ&$#!<2LZcwdpvy8BtKtRH7^yPYbEHqH&9(9?Dr_vw zmx*5^A+p>FlmtHNFF&YE{b;c81{~XLYE6dQp!$gr41;yu zg`zsr;e*dNp(0^vbDWK6DDZQ`_FCm<0XSL+Wil12@^q*BnCx0cY5FiXMm_Mqd^!cj zswsz}d+hWK(*zBQ$Md6>@?APNab#Y%GCUY@Qr?gx!=iQ#*iLvkTqb+r$);pg^E*$u zAL0wE-^*Tf!gHgJosh$51hwnF%-ka|I&Ze-LAn$7&JXYru;1WD=?ZIv!pBuS!rl|8 zCVa@%xH;7bOP27siL}k4=MXwB1yvoJaemluLiyBRIqCR1RbxjZDhla^{N~HfCRJ@G zL<;-GPbIiREmQmf)E1*WP?*PNnB0x|rnXV$vF-yYcO2vW`MC?kxa&!;F*5Yn8~2TZ zOKUgmuR}wyw0%D>FHcJdp;i4srwzSEN`!_Tc>(4+8JfxyFS(u^uLm!CAvYD5HN1US ziocpS3a$^d2_CP|jSpt@21k_9`LjMc7EmUK^d>^{&LJ@5qr9PHA+Gq?3S%1Z$*!Hf zgElEcwvj0J8zN{|E6bgy8I&76E1A7=`Qw0q(I3}mqyb#3q|B&npqW_&Id*T>)y=IiOt&a<+K1tnL*m9<6fRsJpdc` zEZbgvP7T7Li$46^6f4-`@^qi%GIoJnMR3RCgk=9Y44SJ z7DR$j$?7c?`T;@$H-6dxH-1};r~0ff%>am@y4Bagjh~XmM=utQ_*g0q@A!OgQGR?M zTWOqwq?(5lu;4%DzjyAmM~`NDUZGZlp%+X2f{o;TxRfhgeHcD$aKUi!s^dwaloCTD zu(T*gOQ~Ny?A2JE67~S0lji~*vS_s_-KG;wUx&F#oypvIl_VKZ6L$X zU)p4tyT;8)-bq|%LsLAVL_*{=jn?^Y5kt>M9V8su!sRmNG}+2j<*?*B!5}wC04qID zplj*^-cq<3rh!4SvcpAojEI+#Y=k#d(fGzPUWvl{ul;^cu5FCp=omx0qrTGBB;#C? z>+3_icc3or?6M{Hgvuy~YO9mR zRoD?4J5~PTOk$kOhjw29EG6a#4RqQZxa^XSw+>Yo#VCe3HjkSdon(j>9<39Z7k!B> z!-osC!%(j%cYvpp1l+EU%48HZBng(07Pm7HeF{piwjB@^`9e^a*N8m{_cq~s5~1nf z+uXFU7ZO=j8AY@9#d`BwoPk(ijyY?w#QS*_gpiz#S1G=e1M19cD@rx*xW#_WFM)f8 z7<+=Po)k+T3w~tf56@-|`P&wd;BrK^2{;_*p%H~D8H;CUlcRIl26W}es1#ErWnvyl8}&Fx zE6ONbLZNC1`8(ttlU(n*0IMYNO>EmvzB6^I&Z&K|tN#D8`=T$qSM_?=^AI_?{J9sl z7`?Y;Z5iD=u8jB3$$Pp>mN@EI+(u)hn=i$~WQPw9)N>`GS)i<;)L~7$@>Am&nA>`V z6-0Wb0>Ykp1qs$|U`-Z`gnx{z+LzQ14T3Q@Z{ zfELGrIeu)s-GLa0k;QG##S0~{ap#TyI7J8rEjIb`FwD*;O*rX)dtFZ?I?q?&#Zg{e8kBebODh8OVn$ zhCc0+O%W(q|K+S1VW=qmr6Yl~$6$u@E9xaib73m=Wqo8U9 z3XRO~U>)Bv_oL3i**1eYshky+dQ~u?Ay|*T{k!kmjw3Hqt?@m(xa^f!k8C!+#J+1@ zT=F14O|lAwyk zne*rglD{h?*uG^mbpSuAtK*Y|>+je-4(PnQ@IbrFLSDb=D&GOHp1&!pG46c^jv9gc zWUTaDb(SOXw=K`fJn4)keM>Zv9w0o7m_?zQOMnSUNSNAV2aVzyA%`27P)AdE#?z~9 zPd*s^iK1?GnQK1MLa@TX1_R{MZ+5HOBXj#H)wAp5FpZq5NggGcQhv|FZY;d9=vKaJ zxhz4>@rn>^Yp#fDa{ezqZC5RQ%sZfoQx>WWOUU1x*Jo^VPs!Gj~KC2p)ePpj@(MJePxR>xQv-JmbE;V1< zPi#^s3IX}8zfb%*4-YvwrHMr&xe`wPwXDUs6HDFpmMl95Eb|^{)I!MeGp-x%CBK*#G{CClNKLaV{$*?$(%r&9<1X^9)3S97_t40I6Vk8+>}K zVvh-ii!N6WMo8 z;Rb3+fUvJa|D>dU=w<7Dni3fKATeFJaCB#X_iU%E)Z4gd3!AcPZ?R!jZ`izIYd%p@7iEOK6@(Lnl}3|LGniDs@o8@3U7jZsta_iv(5^To!B}R>?;n;zBMk@ zA)#OoC6od$7?8?!s`1`z|F$Y2>Uk~bg*u@s)emS4Y#I-BF{UCo&^6R;ky5w2nAdW za!FwbTk8n#6VheBk)Ht%`awGCGCak~d&iW-zTo^PcS3cWvvN`qjXKw|!23A&(wX-X z@jtG`o8l(vo(t}mIF3dH#yS~)?yuk9IOwTf`e50&;>M>5S`@(tmXe_AL3cxL?w+jx zRTCPut?Ur=!+;S2m`52FO?ytWzH;Qu?Ftgqz7Sob{y_K;)5DkzI!H`v4($#8B`b0D zo<7-vc7ZA9I8EyC9$E0d) z#XU@IwvV1bC)#b9#slGGXij+HlAPn8Ty^AFMe4R+w@Q*pjk*YWdYha@Kb2g@exz1q zpx&*&5gDGbJ(~+rdQh>2A$HB`Yq6W94@d}J|7*+aujj@MRe>YF)1(?(uuO2~0rLXvD4<+$w((+yxXBAYr2;{oz$gRmM}LGALK-GsTY@4Uu_4rg_y^u;?e3 z)=6gTQG9zgMB=U%;}b~=O1a>o!3vBc<^bkMQMLQ9MiAj?j|s^<_|RQ!%CM`@et(6u zq)*!nxVw4N%WQ}O5{>h5%NytUA<8y?(!j8ylb z`$Ue&LoOVJ39tIGF=*Xe#nT~{f=9BpY6U?_7PJ~)Bi0g>rGPniTZ}BSBhj{?^GR*!$$v3Ou79 z3?)(Y;-76UHH_i#lNyrz)X$nZm2;042a8<*Z5XX!*E+#8Y7Mdpx2nLc+SD;rmKzE* zH*Om5H(PrmLLX}bajh+RHoRfCH-2I_64>(Qy$E>VC90VB#AjMhwvsAqw%Ak6M*6!s z-VXx^S;k{n-r)wVK8X9cvxgkE#}7asbqe)?gi=VPIUZRJ#q~vSEvxTqNPbtjFdW^l zB6kB*%Vhu!t-Y7n4`)&awQ~{i7FKn3bL_R}WM7_R!XXf;2bCFYb7H_RQmFOuxGi+i zM1q}UZVWihgDUdr9MTkTcBqZgwH0yZ=Bp^h%F-DZ^%S4kwXp+rIa2q9sH#z{kek^f zrhTd~-Yq=S2ukDxUx6TN#N)?1l5*oD)!&Z75Elc|`Nfnh%z;C`h=jk-a?@^L#D`IR zuyOE?f8Pn*bR`Ib>*CInbAG-p9R?%rJ7fD1^;&LQA9W#1VDDLfpE;yO2GY|vArNo= z=~WKI61MN@dg{xIQXxl2zm(!fbLQ*($FgMHSdgPm+|4mCs4l3`p_)RtPZ`68T59uZ z@TdlnUi&*#`g*{c>HNR|fhFE%Fq3L@beVqW)*g4{;Zh=BaM*Vcpyrpf-GI04xk~aX z%ZG1pGN58#a4|nUSe>z}nnle!uT~qcGCdgRiyb3oDf|V>i@~3pNd@)}TFZ>-A1c+k zi4+}`3=xymT$~bw(rPH5ZVlYbvOwXA9dxqiSUvp8Ya&?5SOxGj??+mPW;= zKgd3Z56Q!sN>7wwJ3uGQ=-cDP%>Ika=X)nTJA7VVPQ$?l=art@u@o&-uQ}lxeg_xRxv(tNS8Cfq>n>i-LAsuIgqJ?|&a{X|tavou`aa3pzU z&D4ukWacq5wq(a#py8~@UahS$fn%i?sEMdTnFT?1Z0cbXhWI{8Y!0I{3o|JPvXu;F zpjbcRZBii#K@=o6k7*7epoy9w)?y8GV#@@N@m~}n$E(E*AhV}L$%$mzjl=Yr=4}>~ z4oAP<4fC3!Kwsz-O0t%OLzq-+nzQ${3L8emOyR-LIiA37aLpW~yR4Y>rHuZ>sXfl`a{QE18B$u!`NXQK~ zUoV-ziTW0b;sBFaau|e4rhBVo& zSitayZ(A`6AZ(nXacn3HLU~!r{?`$jzs1tm+R?VQI^YYGwK=*#dUHqvF9cz-OmS7* z$NT2u;p0%00N+Hh-kXN zq#$dA2&Xab=O!v6&39Y5EN1%Rmz%jlY8A`h>&%Y=hV^N)y9LGg*%yW=Fp_haa71{MtF@bzrbeEdV6aOE7% zf}nfcS$8v%|3-}0Q|uzd?IBLkeSZLVjpdqH`a}fC)?tr!zWQLYpz)@6;it)XxGD5j zHjqb8%E!_o-dcicE5Rt1?Tf_`aB^-G+TB4;t|rimyqpumwAFXgcS&($p9;ROZEr;J z{FOWe4$2p1gRn&T7-20qMsT!0iT{qs3QkdFRZ7+soGc)UZ?g2%8hY9F5Q#H9UGyH- z(HV%&CoO^+}Wm*h1C6L<20YoLoM%Inp(Kr#?H@cG8Y_B1AtS# zYn={WYHr;upf1Tp>|0E{g#HwU_uLatdC}Tkd^<;0NiGD>TE6-{`in+1V*nRm--m&p zyUnE3d%4dt?Ik1hS@9S>{e{Iv8+8HhfMds%&(XswW1*4r$0=jB@kRdpPWtjpjOUD^ zQf3YP)yyiEXYHTp&e$P=(Ig=o#wr4C70Lhw(q+P=4NJUQeQDq(9S0P33;8@JnXy@I z!;x^S!R$xtBrKLJ)XU#^-b*lxHlr{4j0^tU#3a?Rme<0O+4pSn*QTXA7{tEP_bWm@ z0u5qkgEn1r9h_nsUM`R!gPRs_l}hRj`ov*={;V1qcTSRD!CM|IiErT};w@k*Xttwg z4Ld7|w!zJuh#v&^4iBB8?(y7^7zqssp353T8zBkKi@A(@#7xDcvZb3Tc3m_yk)UR$ z^T?R>r2Q1gBEAGLL?j)Vz`$o#p{4}VjJ0ydF4;N0j#rxbPX{R+kE_)HWHPHx$85`* zN$mr~uDR+@;6A6~=&#flo2gg*ICil-E0codDXiTs+@77KZ(>K zB-C$6nl$BRV5_P&WN-5XkyJCR#5aiEM<8rSfxYodH|bCPT(9F=s3Myc3`BFMjw3Ny zXnR#mtuPr?=mEN~1_3k0j(0DE6e;m50rJB&2p>2i4CmN(;rExQX#Zi z4^ch6sYdnr(@Q?MYgc%+p~YywhdPQCeyUo-gJn+md$pM|n%8-PHJgjRxGnL);4i7- zk&@;qARDE9wtx!x^?W_PPckP4LBe|4JVC7UGrU#XNfUTJKF!unoQRcRjuN-4{|Vh@bQDMnd9*nK71 zEKD=$NTqUI*CND}V@Z!fFX2Wt%H6;z{^aDlxmPJsCUDz$lW{{==vh^xX^1~?frlxo+9r2u z9)qN3Md5H^;hlL;ARE{N;hwdBYgPBA=FJ=yAP_o&NwPrH;M|cYA?%j;=z!5QZ znb(*mzShj<8*z%Wy+hHjB^22ipYk3kn}w?>42W#d{xj_ySP0JG@)N9}F9?)`815GK zCmt9{;6dv8#e={@7lx&p6#_zU1Z25=^AnWF2jNhjZW#+gH5{KqN}94?N*k{0p;7HA?u zT~qT&K@$sn%TD}exo?2APktBL7hX9wH#RpuHy=IE(=*0~Q?=ku%^?+?q)MM6ph8xG zku?eN%m8R~6aeV2yR|iWLu#%^rXK>GIOt~}F5*(aki6i~V5L?Lb>#Du(u+udrOyC} z2q}QX$%+KViWr#~9$e-t{4_EdvMjjE5IL|0Ahdx2^3-Rc>E!kxK7fy}+&cMrg4G9c z3<)hQEq(ii2u0m4l)%gk4KfFjkDt%jN*65b7+6n-4JrQiO$U)$MFx9B$v}O2b;SU1 zzC(5t=NWT(0O>NKmJCE$0*ibM76J6)LY@Zc<^}Me^;tlraSiZ&ug2(IDQ^>#qdVFJ z4)!U9j@pG%fr5&I+G9as+nfO&xAGzcO|u2T1^Ntpz>raq-yJ%73j!#DN&KNg`V2L( zIFSdi!W;psgS$$BJsq)t38-Nx010t#1aVvV#lN9LIPj2=OM94JIw+8(Kky)V8<0Tj zS+MBP_Iy5YKEqoB2H0;Im(EFR=!nS5C^+<>`#zw0E-gF^#EyMu?QU+8n?##8*(VV6 znHhZOTN4dgkyBU|d}<4=qWB%_XeAWbIt>yD8UYd{1Vf_?SRw#Cf$;u2(P94r@}JoA z-K^(|cy4EU8No1M1Dp-n9I5+j_roW!D-VFafQEYtR2=O^>4`@MfPxhQ+?AlPL4h}y zt>$H4M7}<+QfWwisGgPlB!Jt$4?BVvKfQ!?Q5<)A&w6Jyl|&^CL=BQ&6i0ziG<2Qs zfX_E^F_6yzV-Wz2v~*x7HZt<-4Lv0Bs)0HHh`21W+6h|pjqcO=@9tf_sC_tjx8Z05 z0nQYkc+=@n2VOYD`~(>e+}%i>12!%Mgnt5IJ~dN-nIphfVmC#u&(_R~Rv_>Ivb}G& zCjiBs{o;4Wa&OJW6*}>Esx{)*kH!uq=&8k{fNmY?xhs5X68v4@mPA@O&lD6aOJIIq zY{1a{sQtUm*e)~pQs44FqM!!IEgVP?@SroBzV6{_de5nHZ0FyX=I*DDG&}ez#=Xrz z=3i}ike1~PO*U!4A;I>DA#V+%>{mJWaRI=tV^`q_W3oAZ5M^mh=d~=yQ z-)8Jb@lt|*;t>OTjq0%YG0}If4xVG-x(fV8FO;sJ3~R=w)o5;jBse}30V zax&mmLm-eH)2ywMhxgv=XK*}a1!#}sI@5pgtDn4vP5vNxB~0Ck&6$UA2CjyM_=#jh zrAQzriCjo;>SUTX$kNEN##&zgHM?Rbsy6wp!HXpDWx5(8pj)6n6(M9@dP3W~?SPaT z)o=}>n4CanX3hVjK#@KYg}*l^gu26X)aaBa$9vftx{I|#WPX)Y+_Z9JbseYcEME15 zprO}zfVJWBM-{tE(G@4gRdeq!Sn2CKLe>?}YBTROh*N&Eu%elRE&QL2N-NoEO^V&( z01@@v$x|=NWtlj6tl5l=B=tGk1xq33$FUCk6EqMH_b2_2K+bRR$G%a9Naw|SyyEi- z&~f~Q6VHq`MKs1tmI96u{&Kc$JE_W=L~%PyNvhAoNO~TY+Dm?%06%9-y(y$*3~CQ% z4NA(T5J9rmu|>rt?kq+*(jzl8a?mc7%1M|C?0>y*O&kUctaN2HeZbxhZv5V zP9G@9X5Uh@Im)dQRh{g;KE)X*zYi$k4-^&xW}N{P936uwln_-lxD^c)$UmR*SDy_V zP?Y(|CXKj{eWjucOdXn&!c@q4Ccvx!rT8ki86TsYkowQ2N~sBGsQUiVw0x_(5%(d za&HXI;iH5@Xv;@VY%(5SdcdqTAMp7 z)BY<7Tw(9N`x)SzgkevEdlAa5#sd|4NH5DU^C+s-!P**Y=*_cg&tRum%-wjG!>4`& zIdc17uD_4;AqL?QD{Pgc{iD8dt{-z}z0Qnv;Xk;?i-$Omo5>v`g%WwQD!8$eUebsF zQE?JK8yLL=6@)aZ{=6(wmt51rQ}8AS`(`5k(O;5Zx8+RT*yrQ_Q!s&wwi;f1A2!^* zGV)wbnS4#Nt(U{)i*5O6G+<;YdG7So>9-`X`53tnSG<|=1GfBDFK9H!>xz{4?rV)) zGhv-GCa0fK{L)=SCDi5Fq?iA+-}q9f{yW`w=RCz-U$@=x7%op zM!PzCUS>R_1xrZ0LKd|#?5DJRg0vc_01d;S-iW_?p6oQ2LN&du`2GC;)IcFx3 z9De>_gtatwhzA+z9iMG=bJ=D$sT?!z!uvG+_Wni{ugy|8|zG{f95LmQrO;8~M6 zzpZm#-n3;=H<&okXcawR2R$wv0;I}YV+cS7?ZIsgHMa|NDv-(g+zu1Alh zs0unKu5Bbs%Kd{l181&+=fdbLe~T|eIdLLU3&0~eEt84F+Y@nkzz^qo0VC;l4<-2A zTl(^Lcke~sF@n(1RjQt>5)~|TA{7(V*@V`Mk4^QCJc0?~h3b!Ec7*L`XaU_Mki(|5 zp4JCaSyxq_rk|GdM&a5J_9h`eFxys#ZWxPKIoct+wTD%!?0|2et$EzUD?d3g(?Lt( zb$;X>uFoX7rPz*Er${rTVlSY}(b!|kbLuP=Sz-C;aT7%U=rmcE;vOxXL1vz5#K**n zmHwv19O^p26cs}&v5KPdA>5`!f8`KRwh)HA!d4$z`-H|?t3cs2a&^DLA=hHV06 zJ|#2^*3P%U(QJUqWY87^N%+Qwjpi;nF&IBkO($&DQqfe?%yFUD2V#sc;$X&--j=Rl ze~U$vx$pXM%)1REU&XqucH~yVWZj*lmBb90}Mss(nAI4re(9~IMUeK?Sn3O>`ScgmJ_9#zt z*7Pog-^D_JoTto66KgJ;^1jroog}FkTugV3LX*bxDM@h2XR`1)%g=wvZ79K9xbomo}w6(QJdd_Rjm_;%5+76_54;E(>NkM%xDG7;9(b z{5;#W2<3AgS#uh=6H^s8@vSrzN%s@E3Xezmqen~5!p(A;(xQ)ANQ)v*=VeX)k-PF|NP-7?-OSDf#RW&!$gjLm?SAf2-fP1mq2l^EC7a#z44BIY~n!dvyT6+)nBw?o0 zF(!Of0tm1bdGVzoA&tTE&sB0kyTT*ITxem5I03-lX#Tn}!J z*8Y}`D%vRBI!2pjsv7SXnf>D=&N>SR=by`}e#L0=E)!jb4j9iHUQC3ZOn&JV4?27T zksx*3jcqJj&_=ZPi{MJ~VSRqJecatm#aPUR8PZ+KqDsmD4hGIhB_$VGsZ~IG66Uau zx`F@Uq5p%FYtWtB?pOG)<*t}`Z7;mriZ!%5Vb;8iVd6-KS11T>h8Mb397;CmyjfiX z?rf$oVn1P|BsI*B@kUFj!1*&+YxQfQTcD!;sWi^YnX4@oC@U;Gc47o@%7dY zfAcy0uLR!KJeCGdCFBu`@S&9Qy8V#z@%|PGeKXS4Fbn#R(^OE%EdxI74ze2~MuXtQ^@K6MnGrh$wE| zhI!LPlHVpf5%;laX4w+dyQfGg8+)_paXa zH~o~tP$KHzn4RdY zao{zH=7<9^)9oFKS*zNEOd0w2qSRu~TGY}EO-ik#j$AqRkHH_W92Aqg@Q@S`7yH;m zK#7}3io~2=6`({E#eYQezteuIdCM?y9u}1m3>_j)+4+u)w$=HG;J!OxJ}d>NS$ktD zCoYi(dB5$LH>0Xa4(3u=47sYC{$cj04<%oSHmov++G#`-b5JQg#XVKfQTjoGMd;2F zJigz3DjxZ-J0hA3sg-ugnH2t9w_y_F!Zk(nHGOI^U*VWSxV6bZrE|k%hb}kE26Yg= zxrHK=jy3rrpIB9jMQ)op%wn@q!T8mpw7%|vkD4JnU{XjZH9A!xWGU2}IfptG=i>Lu z6*E(OQ@{Avf_vO!sT+F=5@d?yrFRA{epkmyfSw0W?$sOxH&c;t78{KpuTGY7I4ENH{)JMju1T4%)Am32<5Boy)j&r3wMy!Ob0?VSo*=5wy5 zA{%~N?SVTz0NP8!tV!#LW`5WI#pUBy5*)rDD~Bw3uGt%1H99NzCz>7~yhHBLN~1wy zu|jlA4PmspyOni@SG6GR1D9iYbla~-P*Ng7UO5koWJ~(1d&Wl54I5os*S53fO3m@O zRbTyucb~9Jf9Ee-vl7eGoQCP-^?eE4GmAomNfTv##>$PSrOVP(zpJ+=RrHnGLwGgN z!P-%b_TI3+MTs8o)J#YN zwgV(IRZ&@Q((hb(F(t?-sa$I=3W;nNL3f2|+@EttYThaxrsTB)b1fw{Xr5*SF!RdK zwtM$8*o3=)uD^4~Bm!ApcKAr}d8?{-IIdT;LI1KzJDN+XQxP9x2~PF~TfN=RIFwyF z4_#OsQS`}aL$Rh7)TA%Jv+=PQ5uPB4w%2j-wAuNGNGmYX?pJ=6e&?%X9(Enb>fd=Tt0uYS$|hQhC>9Xzig!_#iBF5| z5;vxTE;W}v3R{wT{Q>%s`+|~DcKlbTBXb2$0)J-WQFUWIGAvP3C ztd$Gx3F}5nj77*{Mwk<1Jg{RoGqn*?m|zeaCfArJLk(c_MQ$XJWjOx1gPiqd9g>Wq znwNx|4V0mGNGs$lH3At#@M(6>Nji)tJfl1z;{J;8rn)1HSD(Mle0 zS1xO5@Dl^EyQY#T#KLZ42HMH5Kq^au)<8dkdWQ#%61*nXzFD9h3rM)es#5F!GvUmX zw8yR$vyS((kj%-?!f=*VAvE*5X8vYudWw1gj;Cj%U5R45NR4Oyi3W!0JV()6Giu8) z+2mW;BGeR*Yt`*1Y*2Zef>6}pY~T+T2*7zW7JapRQYe1v%Kw!mn4CKP_CzAA8!X@d zG{Lg)sb$3&|1(c=e>>LcQ7pGfkDj|89~OgPoDzoBN4}Xs7n-Reir_|jPH~>o>9%86 z5=`yC%h7P%?xd#GYDQ$iJee% z7}vwEusTPz65pl}!!g{k%B}Nsq;Ao~4kOxa&s^Jx#_g#Kk2l3p)k|HeN>xUqpn4OQ zkDrWxn#0>y`_h?=5iLdO_la5ExO|PWUw5;K(4c~@g~Rl>8W9HSW0RXj6r}x5{$X^d zwiKlxYbH_s{22af5%!m5LA(70^_1)X%E(o+>s z6?E69ZVm4Lq-nWl?V>YH1rH!`L&d{H)naArOx$5YUltOwE8ICj_MWou>hpPNW`rN6 zQ*I%%$2n%2&=DIlKUo~c+0bUftHkP7q?@oIfD7s{#O}o)zzXN$CaDiXnM_#uc=%z;wJksKTIl zI6dkif9QDclC4!VrPhQoQ_4287SIpT+{$ZaZWAMpUk^`RA{2ULv~eV$7I3pk(THns zGWa%fz?|kjf}6irXI_lp2Ex(NvAuTtZy z%;CM+B(}70>uAQfPb0lAq@_zL22GJbkN zooxQpCCSN1=+P#2Y*#m>Dp5GgCA*b7=6rN@lb!Yh);@MV4ur_ToTpjI2lQ3R484Q> z$mXi84U#s8oHQ1SxQ)3ZetWw`O^E|%XlA9hfQ0I8+WK^v-Ar?mYr048-UC*}yy--> zNwS~nbe6i|ESpgzrM#3FuYvQ<<5H#vGSX?9Oz`(-+a*{T9b7r(jc zC3WwS>TRT{Shi%RVUQ_PgPVYOtW0lG;t{uigGgtc94t=OXw9armu_R6BU*R+0p6n* z19~FXR#!gWVV~hK2OoLdRNM#pGfTeT#YM@2yGP{->5MA)NCOh*=mGkBdJx5v4wcb@ zyT({`7+kzPQRfQ%t;O89h>qv$Yh_Csd*CZ7yVTcvZ;2F>R-6gxo`<= z+uhsmIegxtSYk7l0=ui5Q+SR0>4fE)8Qs^3>;q)8R8r!xk=uksvk=|0-x}zY$i`W} z26^SG$AmX=GEJ8St+ujlEP6D?REk=4_FIHt&OboqS_0NV0y=^%b4N5)W2kKZd6ra# zWr&uum=mw3d^yPb6X~`kWY-H<@h90GibjhPA1!2@m07YKQmi<{zKV7xnyVt4wdknG z+;FF?p*A}{T$OL&QJP(_;y5?>{UsNXro~h7fTNN_sBltN>|MyYk$i~dFZRP z6>(2dekJ+ctFkXgu|U)`wmiwxQ9`Guk2_NsqF*cBNqi;+Z9xh`l{*sWazGcAg`x&N zDU6(cgq^+4mpjZ0@*tLt@o%q{(E2~yCspa(ZtD(|+m5+JW7XuR=wnpQ_9x9kI$$5b z;PxH$4K#_1y$mA@5t`bp&<>on;TYroA*16$IqC6XObcIjfToK$WJer+VsS`+k&_y* z`H=R-XbafPRKeUZknpD#^*R}lnPj~L*~q!dCnFG0jTHLI&gWZDEL4G+rsXx^zpjZO<&S|*sw#V#`yQk2Ot(X(pk~`UI5Fjc zn%4Mdx7wz*7Tty~c~9gtFhn)O=mnRSM;GgyvriC+gg=!myOMzo1qnDlv%y4})Ldwb zh=s6@jumueZGI>GNI5L&Q=WOHbMtiqZ?Pf0w|LLrig5HfA03xIq42iu$c92K>l!j= z>vPO5H%+5h`T^c{-E-t2NCcV2Np#*er~-E?w4mrlVl=^W4zxaCggczImAW36VH^vP zA=!yMBhM~YcL6ghL0tTs4}y;|Uc`Urk7l`FS90s9*?XJ*QVTj=|5)~d_m4p7ZZEUX z``L-UK0sO5F+!SDjww$Zn=Iv^HM=2S%H0^m{fm3*hs9fmH(G)vUv#X=Sj6>~4+W#g z8paxuF2~|)U_ZKCB^Ox%YatL)4yg1N`AHGnepP%n1(}kVI+V--&M$ey+3R{`fX@^?CI4Ku@ z1?_4wNX@j{M91xl&-oNjp|2fPkk32{JABc%9b_k&UAkr93ENiU*r-@>o!zne}~=jR?|@Utyd5&Badnse{8&@zboJ}T0?6F4Q^H!yyo zM%k9n$6#m$M0|XWRQmqLB!l1OEL`EM5vy83csGXH3OmIkWK1JzdSjSzr)c;3_*NbD zPmNy#rv5FGiWRXe2bP!bd3Qw5IZ~Uo#|bU$Rt?op0fQBfL$J>Cbe?-n#HaX?331-4 z_|=hd8_7Cz)2tw(#^oD^&5l*aE>-+hNi-&R6+>G?wS;s=^9#!qmn6GhuE22BcT|bK zyncRv9uF*?(kjUd@{Y6H(MjDDrd|C>tNsnTpmblbCtUw;awb=ZnpS8jk7)h(t;Jz9 ztdz{vU1@~13kibclC&xNgNBtq5fZaIm+t$}M;=eF%QOKd${oEx%9Tz`OcaAl?%Z}4 zr{Oi>)wP_g&#n^v9(}ztsGy+xCF98%lo^v!{8p2CDNJ5<<;5PpxRp+)SgMq*7&(fAzr>By!%m7wS5k z3`uF2ZLO7>W>{=^`Kasj3U|(N!XimK)YfBPA+**0pm_}doPyOz{wgO#uyg-M z@PLb(^Z&2@GkCzl%*@L2f0GCQv)(nP<)7Yl4U+ z=B6~U*1wIHT~rdwTcH86A1)Th+rV1yS_Spo2L=P102|F8bC#AaQtN$Hea_5fP*7M@ zQrN`R6~hz&K#(VwFtNQWBqTvZINB={3r`5)>NEjp2rO_?XdS`!?2bIC{?W5R^_MV+ zOpXG8kr05@%bXg>3=O^u85H_$0_}nZIi}?;YzwH!0#IP1U&hW5Be>kTg{-dm@D;z! zQU$JMK=e_NllOgx^9n8CTte2jgo3Iu@L%@NDB@HzWCPZjZJ<{NUwTEDd;c-n9Z?`b zySux&8M3#yjqKfx=`R5e5#jtoaF>Yg51<92;;Rh@fKj2Qckt`zix(OE zJ-o5FnSE+)81)=3XdT3sM8PnyBMY`PJPwMt57qi%V{T!b;Q7$u%nZh_gc57lbW|65hs+{HkXMz%3tHQ?agK%79Xl^fAEH-4F>t1PzXgybl(r2VzKM zrMeg&xr@aKmgac@K?a7*!; z%L^LDAB_jSZYnCwM1e$5NJxPpnMmNs`$u5Vx3D0f-@K7w6o<96Lclg!5j!J5zF?GJ z#zFw>^ZUhTI&d8UvoBy&C4@f#6W;JU{D6{JApU6)=`ZldBGB;-NcMU|4djdkItV-G zC@2J!r32@H0ZS<}$W%MM@Ht!;XLmyZ>Z^;GLcqUjM4u-!6~T7IIWxdY^~XBjbuj6& z?8P0E(6&io-#!jpWF(sp!SVZ2-Itd{Zs9ybgf!m6muk@6UC^L!$(JVWl~_g2@DDUH zpi)pS=1H&Wgh;g!M=xh|X57DVjbrn(C`4~kR8AtIzPJl347)yo07q=VVdwx~jxIp) z3IbqjWPjSLn4F6QNd9Da2ZIR&2(1NNK;HR|R6G=5=^GD*|BN0e zp-Zd}nEN)kr6D^sP(lW{zGI<-0 ziiroLR|Bx7XIB@W4w3J?*F{%g2(YcT&yc8&{rwzuN{4(ipRwzpMIv!C^T1HXHD^yq zFyz;u!*ccF0~Ci0?qqn@97C(kc+%kQQz_qj;MsXC)_%m?d)3e1`F+c($Uh4sc2|6awoCo%J`cnW z7lMvUkv=D|k&ayOVLI+8Ns8g%e`&NwkvEMI;wP6?y;=xx!D;?|czs)pTauBsJq3}3 z;dA(kZfQrm!8EW}J9q4SiC;*uj;PSaB?+9Q$Uz2S|JcC?nQ+!7WyBFv#u$#$1 zuUk^)Q?T*WExfP?ZivsC6t6ANlSZgBuYi}?G_rHtwg2QH;c2YPQPzLE0Jtj>UHwVi zuKCePy4H`~>fbLxBg!XwImi&>b;tJBTmY(D6o;D*s>g-5)}6aBOus*+-0RVlv`-ab z$Q$0%7GsdOsJzvkyW;b+qyo?@+S7YhdT=0U2RaJk8<;5B- zYZ1ohJ!H_;5N1&sK&#>;Aja2c&QaiYA*X)yp1DfYf*8K>*ttJAv*vb=RbCyY%)r4t z>S~)X{uZ#yvhkUxw1gU*&PgJ zJp8G^kEm^y+fI%T+n+ZJr43ySQ(Cn(|I!|oG`nWPf_t4Sj+}L6E$Dg(pI!AfX5Bj> z*L?{?UC`>oV6;&IsnYr)1YYUuf+xhUI-iDqD-!i}u-BPO}yED8ptH9~YO6>AxZ`QF|1xo?NbJU>V5Gm`faH?NLI&JQK z4_^^^FXH6p6tnAhU*L-jI3;w`e{7~Sy~vdr5+cpSoaJ7oP$3I`593Fnx?OyUGs(gl z9oL3&@)`8-6$@*hkq>WAqs<_l!)J4O+X)N*9{o}fI}k2Or~1$x*byZG{cRg-JTjO( zSFfo_%B0wrGCC}#ehiM`qm#1!I?sY$+LbbBIq{a+1eyxop4EX3Ir0lJ$;$3w9RGCs zbzP@0egzfexaQ5-L3g2`%k<<4hC@N+Ze#wriSatN#Gt?3O((jEnxXKHAdw

AjtuitFH26N|N26+TzqxqP5D6=HK8-2?VnqHuZVW zFP|e+DcvxPtghshkMEN?UA(HVbu+&V-6!TDx+g-N9)Tv$A|ed4#XXs&z@d6%gLa9o zsDm>+fh;{7wj5T>DFqA^gAy%Kulsz(8D;PXiKs*eEBXBUsNcW~6YPD0iD?o$pyMrw z&Ad{YKcbYEE~N@pBWR&NgRZ~%r?H*|%O#uN&K;(gOdCQs#eKT}N z<3dYAaMqJn)5{Ic_`5o!PLDs+tpzn5 z>P)qoUv6f`oImI=545P_w4pR-y-(PDvpVmsH_H%nZ-!tLzz{}UrE=k1t$)da@WZfl zJ0P@)+JiogKJHtC*cq8~KC{LT-XL^u?c!S#B(NSZ4eRQuMfoH~>P+qJwi1va;jZ!_M?EfM>OB+j&m&x2YF{(9clOxceq`A9OUn1V<7DM(V zFs74cS}U4lBm;@uyR=*vo02p^6wAV%C7$cCt)*o zopZEQbj5QxHPXIEp2RBt1^THxD>viCFVXZ$p2c%G8u#0jeyv$*l&^mI<3c>l+yD00D(|KfHtXY@Mp5PqYe;nobvPITn@u$z_xrUfR9Qd4vIdnfENapr+#m}~j z&@id5@@xaTP}0^?e!O^Zq_3LE*()C`h}fMzS;vqYn?Vz9plH^avOFtJ35}D~GIQgPT%|hZmpMRCnd+H*E{jT6O)%yF3K#X}fx~;^|}YOrDu= zQ0D*5sqsebSJ}}XjNt4f!>?LzGT$g=fL)-o zECrR5)>l2C2p@e|eG2IB7F+PMIZd=@?;_slJwmnnuC8&)fwq9CI+5HB{V$eMDc z{n~!ccB+cLMqEQ%;8<-)Z1E7(%eH~fI4cDT!dgvJ^ z>`$l)yQa;l7JUaW`W=o{wU3Ceet%=tdG6>Y)(Lpo9;{0X)6AsE_{0-656x%sQsYn* zk-1~DlO~r>ob^+S#B_|B$<(GT91rQb?7}ks#5*=K?gCl|rZ>nb<5%fbBACcP?slbV zx#vz2;TK24eH4BUVe(ccH`=PpUo}YuM>kHNKMeB#Ga-bohF-bvKwJJR^W)v#*H=We zo*9QJ1J%$`aQSGZiQ19>c-%Yp;*Hs7xtF%EZtAT(PX-#}G@T6r!&Sa%hvs4hgewF} z(mke_b9>we7)NqdfBTFVN`AbRlF@NXDTufxUDl z=MP%JEhH6_T`qT95S|h<|`Z6ygoj5@83!oyg7R!6copmTiG43$h5@YMw+F$@Ql* z`uUEw;|mF`aZNB|RNG*XMJEVW!-hT*RCd_z+7FHg;At->W@)3(lhdHlS0t4ymG*@Z zO_Sc-v`TO26RHX(ge!sX@|xuKw)3fAZ!>Y#5pezbFjkX3p*Lqvxifx_ae`!ZRew~$ zver`2B-DXE9y$3KhCmr5YwXDm2ApD%c03koA=~*qC|=Q<2xE$OVH?JAn;?i4xBDiN zHDX7eDnkqG+YoV53OE=R)&rl|)bFmK z%B)#R;>%H?ig){+H&y?@t68qxuW)tr5?UAGwMX&8qU-Bu=&c972G3k8T>l86+UdH- z8Hs35M5N#IRF4)qGNR92w!APwn2Be>xI_fnpegj>`rXrcMF!-gJ8eDbtnoi8$y8Fo zylQB(O?y+TJP{-H3>}uP}JBTHTZ zO$R*v@k(lrjj-57$$_kAPDNZ+Ml^s6~?9f9*mIIqYnV%LANlwJ0N#Mvl&#gj>srHChG*&1+53djC% z)Bclz*KVCBfc?tZQLA02#X0SvsIGogsS}(BZClsEk-B{O_@cpVPX*pjcV{t(PJ-;T9lU0&7(gZh? z?p~e2Bi_=~?&46#kHczu5V!M@jB;hA(-$deMcAyZ z=!Jdu>N_pUAzomC{n{+mjy_9@rhZr9`-r}LPrgtiKq?Q;<{2U5wdCJ(X*qhwg7rtl zk?dxCceJKU;v`BJOkGt=HGBsAs7z?{m`IYg0Nopu0z1^kVcAcK3KR z6;1nD^TQ)cF9N)e=(~}zoBAUUm7n6#hr;YKshNTL?)@cv`j%dZ zAh`&fj|mO7Hgl)dl+K>(c#^+$D`kn1npA>;5M=r(GFL)zL4zl|2?yQ%FJD+Wu;J`& zw-KEKjuF;H{vh*Sou~b2&YE0h=H86w;Hj}taTC9c;lGi$NM(4-CBr$kB2a5=s4;YK zq23e<4w*|*7$sDuHQ!&wBNBAcnbopWiZ6x~&0SVfU(TFT9x#%62p>g)qpYs4*bl*0jDqh$Cy7a@H!5l^ z8FDW^#AbcL*RPm&rG($AmgLB5kx;n(D7EFBo0O`J-EoIrd}d7a?siwqrseYcybVI= znA}RL_>wfzlE{ySy$z*)5k{JA#m>O>I}f?uf@FV34iIT(y*3V2?-ECZh7Pmk6<%$W zFM=on z!CkSvtY3z=V-oK8#_Y#)-eR!qyTzej=Y&@cp2*U-L8(R)Km9c3{JG=efGU%P)jv&D zu}T!A%a>Fm>$7qcXhufI{pG-kfs`bqVb5#1Q-h zF~G}oQHR3pD>*#E)X#(G#5%@;J+y{RM?rL`g5Zq#N>DGBL{BpRtmB#POCrP7W*ASj z@|hgLS|>D+=7gbWyIdu7mSSlYRNc9DPMD6V)r%5i*h8@*#K2!}+%L1Qzf`wsbStZXL|Y5U$Dl^Oy#JFL>`R^DazybJqA`Z3PB3ZxG0Pae+H9{WdMW=Wa~hSuBa|!Vw^?3j}>3;{dszW zBJ0Ev!Cpr;y;3O#Vg2lwTw{+2p8``YE9oKv$E#YFZC*-Vhi%#I(DBcg!#b3?LGHhx zbJQc6l_@1Hr^}Oxee?3f@nuQW3`CoeqeGuk1U?!QX;jE~_@@CEBFwO1Zw~RAdF{Sa zE}n|)06}7ZYlC$L{l98tiUg|(8=>A!fJZ4A#nN0qY0TmMK27sWl>+Y-Oj2!}K}w z`^MNJ2GE&k#ygC1yb^5Xa!>om#oJ!~ec&D5?n=8hA^oTjpi7gpn02>}oYAy5E1f@m zuVSmJ3d}fZFM$Yl*G6~;`~7|(Ks5b`iorR+`dB88o>E(w!V=gKszI0yc$Ac!%(PLF z9brOO3k2K5(rLT)MkmPND@O~wJCbL|otv{B(w7Gv9 z^FDbDeM)Gzv3}nT9Jx`xM5|7WU1-*V#gkl%FLX3Mwx+jV6}hv+sr2EV38Sl^m^9wyd^S|IG}c-9G>+CF^18-@D4`fxT{1aixx(_s?63M~W7%%2pkZbk3R+ z$b}EsnRfTb#?S@Kup2}5DWZR-8n zt4NOt{1e2)gP?SCvUp)3#bMix9vk^=5kvo{VFlfQm3qr13poc9U|hh?$7b9Em|16R z5p|(8tX6mT>0bc446{^yLFN$FpJdVqkIllAkxqvyx4SF-M-I)R1eF*&vF7^Mn~;$? zH$C(vPO(OVjO&aiMEAStaE}rKh`te)$V^p;b3zJxLWkph`}RJoCG}fd*!qGIPsD2C z)cH=l?V1?aO>1$|!=vk>j))XIvkOjLFYP$ZE`=Rb>-!|I7(C_YyL{^2M02#$?xxdzsY8BHmQpB*f~2nU6z!H zdZZbZg~c;5?>ToDmGCx^*g5?zM&E-RlB$zqn`DPI@VXc}|1c`&p7;ZV>rH*sGy30# z^$p6?YqTzU?5K?7;-z;j`}UV$_O8&+QMGg~meG5i(A}pp^QleuM&vtC7{k^^G~&0A zwaVfr#Bpd{AR1(PXf*Wed0#~Gvy5($=`^_YNjH+)338M0@$$E;GWt*tdK6+PAI+Fa znGB%mTV(hf?Kqft+T(MImK;3>aX1Zim<4>X%YcX(QC+-VTc^}iJYl1EHuoyXkDUV< z{p$jU@NqcsP&q#FKgL_v3;Y*TXB;B_uT7n>y-G%^RBVB!)Rh4Px`Lum_m`!fZ}+yxrNeWBNTD*%IYnqJb$>r<+!3ALz_8 zDasjA6b(7=O2IXh|K=WMTJ@!k%zM}GXVf_&d6Z%32dj}iP95?G)Hvsr`3wHY6r>QS zahO^DttNq(6qNMBu%cyp)CHh{#Ri|@aez5i2kkKr7tVkSI*;>ByB{l7XRIW`?taHs7H3n zbdIB_@h<%%sMyeGC+Kb^&u1$ijG>((8>SQB$Lk*AgOP%k1U3`9)?7PEQ*B!l(murm z%0S79iP1j;37=Qp_!EIq(6Id7PuPzDLnYs>o+8_Iy9r9{oS1x;^zJjub_~%ZFCK9$ zU|#?3W4aZ)A;_{fcCrh-uYdT;Qq)z`!a=Q)M52|{Wx)sXuq)f%k3h$H&4~YrN`je^ zi}WoapW&`;14^aM@Tu1jz}7BFB0!4s?k|#4JDQd|8g@)xt%6#^g+T-6lEQXjxi|S+_ zgReVqJ%(N4sfh;#0ouC<2%aw>Fh;5Y#2L4aYFNsw-J2wM3MVbD3Us?g|Agr4NXfG? zce5go?U-&V=*$;i)KU`7d(7k;*#Af_ojef;a3E{L^{_awo0^_`A7sf~G<9X^iU;2P z^yUoOsB58IkUIOYsOhEYhjnVU*9jBNs564}Rz-XO{LPfFdy^;ax@L*PLzLnNwS#h| zb#K*gg-z_3>sm<*_}8}XU`(l0WVz&|A!I%nT4-)w=gC40Xfx@m@FOX@gInf9SSS^( zn0H#_YkFnEkmf@D0IC`}&gVjg(v>PVe0~8HQvX*6=A7{OHZ8`V(T#tBa>A+5VNY*> zz$1pR7kQc)KI6{tZ&8nRp2kEjn}BY&Y9*8+-rvx`pX)sa|KAySL(wPhs;GW zDtN={jr-G{-qZ6^bxpG*G z7M(9#X>#TX-IHbaeJSa}wodj|t-MURBMKFKzR{q0D#SKchpPqPVOAEeWM=IF3!ZfK z-<0R-6p?H|Ukpt5q4?2j23x|nsz589OBd>%WqK{EX$v!Js_XfA9&1aj^GwqXir*J! zXsj?=0~FYbh6v)Cg;*z3BE@%bp9z==7DKiNxbw&>7r}!Jg~;yC$2~aPOKKLErVzv7 zH2Xze6nL3hqZ!$eb+mI*9dC%py?Qwv-Fftd{a+L;r3_bE z8$W8Ki$&Xk@2QsPYWmLK*is}8Of;#tp-oMV5G$C7SVndD!aHfQL4L^TrbIcsrSpI0 z(^CNpo;m?lwwTa)BF6Ij{FTv0zlw=?kkXpV-is924#Q|~gnHG;1(1<-J>2v?{E?j| zrG=P0ckt#S=%{nL)@G7Pc&*MUef^Kn$K)!y!x-_X6va*{T|#cj20bhLCw~FjR+e)7 zRJ~uHi`Q;mhV^;YF5mPs&&1prk_x=7zZo)FcBiyzW_zgCmIohQ#Of{8kINr`SCVxo zr*c?y@?>2U8gRAUOm@YZ>{zhuPi6aI53yZTYjy#U$`!1)klFL6Tyh1nII{QNs(A=O zm9;j3pzxyCbI8PT`WE~~u_8K*sn13si+FDr6e_=Gq^IGY@Uhb}z z-Ou%pUbwf)4mZ72@b-JJq=9v;&a<6@z?Gr zd8!+rt}h!`{*hGb99&Uc2-zgW23<1{T5l_~T*bwLf~&F?j+(oj<9x(e%j7)@;rKIJ zs`V4p%}?12IRb>|-PPl<1?M^SPtV|)4*(HKndk;}Z8;`jrW0ZfA5fMd*)a2u`D){p z`b&?{(54s(FTUsw*5w(&>5(HHTnTxG&xoJSuHN>-60s)~L@C0*(?-EJzXt66+6FjrgA2CqT0y;bCYkRwA}dU zGqT9;Ql61g13$;^br9llB5M{)C~~VoPlmzxsp(_n;!wI1m*2BMhbC2(vw)yKo_2M@ zGJ-#C#=~&F5teiX!~eAYi33lP6+LOiukaTGf9QW)eME|8=8;jDxKAIx7*820&yt! z4yFrC{VU6jM6kZ+yhMz}C6%O$KLngPzc!n#y8s6rYHWbi?l=WLk;)Sd0!`3AKmNvd zQ?(fUPvJb4{}j$+W@Z0x4-gXpD<><%f3N;`IFF5kgY*Av1yTc5LD6a})$T;Z5sXvrViRWI z&H?hzLSg@A?9KoY*hm?GK*27Hfs%i+4}*XJ1Q8(x6(I=}2p~wHaG)Q@;4T>eG>&Wp zJ%0pTK9Fy~0k~b*wK9PzH-GARr_ZbL!3^FbjGG*8nI8m`M-Gr$Ywx+gSrRU0@?+vU=IAG!U~{OYjB2d z9?K8M6VO)+M$k`wckALW`YQzz_yY&_cfDUnM^FJDVj0f>+z|}8`QP;vVFv;a0K)2X z3h@Xgyx>4Emmq?99P9Y5%KpZYnhZ<$QFM{ zN2gx_BzsTY7Yf0>9`<6@_su_k1rq8p=;K@SUvjS1txv1|+2NQyKxm7nzY@ydGhYV8 zfAeYpA^-vb0tFczJYXBZz#bd?M}OkkS7)G4Fi_u2GjugYYgm zm}dYWqzjy*|F#eKcMA~$0>Fll4I+Sb9S?}~jhlNCruDN)Ty_Wd0G0u?FoGNa;OFDZ z+cfSVl@{jW>ap$fcK^ZJ8WR(P@8oCuu8+{uGo8IZUL62p4;2NlupJ5oETRAn@OQcp zHt0(g^zK$ewHz0Q;J!>_nfANNV6Lxp?mdm69pHER86?bz2BZI-ePAYlNC0~|t^YUc zq)+&V-R*bs!5`s^|5EY6!R;s3=_lwH9Lgz>GLObOtLUpKbj|ELnO zHPoa1i@Y)lpn!z{yv6ybc^R01M%c zpW#oXO}0Wj7|zJpE&>K=raxWAo0{UkRJT{hPR?mD_k_wM+EZK*@E`F3$>Tpb4pDNKgOPlCRM^pxwj^hAofv$4Vrd`r0bmLEJ`gj91wcq z9pDH29g^fS^Sp`Oxa}R~=u^B?i5xkJvjK>CfzfQC3QJt+D} zRZ*9ewA-4^2VNw?pl>_Y@X?jOLmJRZG&%Drd&-2TG2&7sxDetQlz zwO*yLb!0D|i?U-kLiBOKTYo>^->;OH-6GzsQ@}`4ir|iI3U%M}Y7jj&M(ot~7^%_A z!z-tpN8fX11lOZ2OIgyhnCmX*$yrnSg(<42MD$`KD(W75Bz>!vyx+$d-l}^sIv!A{ z4HmzY5x;E2Z@gM0`4<|)(uO=T=<}I7ukHEo|UV z^s;w1c{Ok-^^MIA?25SQ7@&#qOGYi-Ma0_f8aEs?(GA6oQ}zI!TPrsj&0Jo>ht5D2 zT%3B?$DR!vZ#Nv~YNDTBKJa3~F(9B4&0;`Gn5vSX=and^J^7O}4m{Y{Z}0Zcvm7`@21`*hvg(r29ix{2=E?P=;rcFkAz;m~+V@M@mw!eIwry-NiC<@PM9M8h9T(V*KOpS%_cQG<1 zAG)Wp4DG>Yah@ok6t6A_{|bUcQ*MWrB2V4O5L}a6StO6r_dn9|{zF@yyUh1;1VXS| z!tA!TDwS7sjqsAT2Yrc$+nOpPIno>F1@Y*FMZKkz1X^q51k2i2*;8(o6bl~9ok^bsT9|(CHfMR@Ap;c=5B_k{J+fcw*ede%m zuvzR289Ar@2{o;<)lfbL(_nVVS|D_&NPMw1tx{Tr=q&0)5kSLfalmYiWOu z6i?{1pS$$;isMq(u4Ia~lXo4;W1Y3BQKq;0qufaJ%ffr4{c$EoGdke&`2YX zzrf}LMYPE8Kq;$&rrD1rb5p2k?Iq(EQ|IEcsHd+ZMT*TJ=vAh{I&~1XMwX=X!%qaM zw#%N}oty0R?BWcjuvwTiwHsb-?@_;=-EP3t#Lxo}bf^Ly*F-DX7FxNyvq(8KVp+#U zF4q!93R#8iPB^(lnNV$-Z6o&eO1PUBDkD){Ucqi84+H0L#flJC)7FOBLFUVXL9n;+eN;*B`H$aTUi}f>Kiyfrmrx|A;E^J!vVLg{MYMH@&zRu^81#y z-ds<#O+MPHQEcW_^i)QQbN7(^oHofoX`hPR~GWZG|(Ie z{-Z>=+5F9GnY?JI<>hR!*^vR4iHF&U$Ejy%=0~z95(#xHT4n#MpA8Ce287Sh8mFSq4+#e!ZJN9Fq;Z9n=PBN? z6iC9KHBDqFs}(KZ+WdTW4`EdJ$7L1obx|t(3FzJ$_QQFdN)W_L5g{FC<+>zKWG7yh zv*`8KbI4<&K@I%G71jK0fz+c{11&8m={vtp4)@OJ3)fN>4;f|I;JOp&%FNR;mcsWd z@)6D6bi>7hg)yTE9@yNY&{{Y>MV3gVbp1h}d-RI(S>|j~*|VGLlxL-^HBL1f3dIZh zYs<8eOU(L8YoZZ*zoc>qzklJb`=~w|Z!s`pzh7c&z?z>F#eWFMQZb*>88MlA@Hj~# zwu8)w#OsH}OY16@ZR(#3D&+Ib_&4S?cDR@=1MEmXZ~E|ox5vSts!IifJUl*Mxivw; z534Hfkfv+1r*=U}SK#-p9C~|$ze+$Xe$~a{$FF_DQYh0y*Od6=sM%sU3^*D;z(R;B z_p^po_8|9;b&VY!*OfiUJS`QNh8!Ksrokk8szt%cHRob&vc4$KO^Ha{z-5SuTCApY zE+QMYM($ZTLhfBnlrY{PATE=aA2pTmX@)u zgaage?6g^Df$ z;>ddPD#d)p46{EKMKx##S8cR6f@SVyD6MWEr*{5>G8Fd%(bENafEGch_QjwtOZw1* zEv2G6pYXT<6%*VwM1g%}871{XcY?w2x4?~ORs{m*!)1Ntvo~3*s54r~A0mxB`dqx! zQAvqWjMXf>NyK1r;A!nBBd51G*WOx~hdej54P!HT?7H-uQ1CA&!@=T3AbdR6p1$Vz z2KATSy)SbNk_jt@D>pChWJ4~e2(JoGRdJy-BSEZ9o_eYD)g_{})~<;54QVPe--$}b ziOE)Vo!bXyPK>-o-=36fFhU_RAyv0G>*;)uS;69x^+R0s4p&c%WgLWO!AMB%@xI9| z=Vb-T{r702Adf1^7`dvAhzz91M?>_*Uh3+z05jp|Or)S%Gwkm$`$8c8EcgX`gWV^; zIe*1VE|Ut~LPz(JY%HBx9o1sx;sR-lR<*em_$+EMHn($ao{=?_)XQ3*1GUEd< zKk^;)cx;lRE{~7w`*w|5(n4tVylddx&BVpNH}-kz7rDdlP(#JU=oL`gDy0_I)1Ri* z_)AGuG+@2UqOJ@1%kxZBz+!v1V?1VO{l7L-9`0w-e6WyFTWA=6CRapfK~r%N;8Ty= zQP9byh+x%Vk|{QlTCyOYWZPd~rr%Re?H6XSSva)3eH>P7n0>!(b4rk-K3r>hk!*h~TBoiwSL=r5O z%#h0(1uW73G^xpV`K?L%Tv-KDD*SDSlBUE%N6+136b;)yuR5lq$O|t;=1aVdOXjHJ z{{h*vkcr49WxHLS&6e#=J3D-1JweXIHBR3iJ)cKdb?K_tCS!I#wTnD?CGUSoZ z-TOv~Et8w99Fy2X-N7C6a-V2yI&#H4sF)e>*2ngSg@qnsJeU76Ppi-qIJUkXR_B;e znxhEKAlWzJxJ(|nNkZ*!zGWuU>SRk2t;fkC!Jm`ge=LHSgBV@X$R8dLO6 z;`Eb<8hcp*DC{VmyEAZIzrjVjFypR8fYic3N2XFht^{ItAqRz5Ix-Pzk zY_Z>_axAe(Ve|rOyVgeVJAiXsFRd&f{LGp1^Lfh?S(tXNoofwk6#Xv?4)EzE$j zr!zqO?<4T*Q#^Fm4dccb6ItoDSD-B%9&^11r-7wspYap(8beA#HfoPV@_1I}?YGu|!4i1=?pF$WTNs3fTPA_2MHgCHwvT}P&HyeJ@ zP-{H-U)QpLe|6UY{h?#{k|*X4c$4QCGke>aB+^no2CJM`^EGNBG)y$eB@8c?WoB#@ zNp2zFGp)68bz~F1Nwm_OwFc;B7%SV9?}LWdbf!aYvT2n?5`L|!pgKfH6^RocS*n;j zf?Y5Bq!b5TZ=YdgrRIsNJuJDDKYDpA6fK{g*>_6T9CM1BM z8#)e--C~UnA7vbqjf!3NbZzL8=d04%_`};u-p*yYN?p2>XZLM_rf1U&9z1IRjkm5R z>yr7rGt=51h4=5Ea+w|j$A+VvUeE8br$*hlax-+S#p@y$ZBINxfpc6o&8D+C$YAKG zJBZH^7|sdE7d?IJWVwD>hiyun2ObE7rOC@2$1pXdEjR0p)kAG*Dg}k=6E+!}q1upCIfi+v)pia148&q%})aSps|Yn5A-8o)LmeribNmN^mk zC#fK9s;m_aXdmC0juVqxB7HAK!yCYOw4GJ*)UL~wzBsjGe_29v&?p-X;&TcTpCa3& z5x6|@xb`Hep}%EsAGOr+HW8*pOV)h%F?Lrocx1_UT9HH?zGP<0+gjVD>Qrb?YHU2m zrCr?Ye47XHFzD*sR(}FydC0o0D6H)4gzH#4{X4CbcsCH~t;9}mB$I=A#{XuZa#XMc zGcdE_lW*3!ICojhbg|dblwr_@bS#uGR|G-90D1WI#^Ky^H)WEhkReDO8$gj z_J1DITn?btc)$`rs4|er(9yW&VR_@E3b`JJ?m2JmednL6!!i!#f_-EbW%;Fxc(~=k zy{Hs29`EF?l)AC{7^P9XqhYJ9-E%em7QoUCiFeu?t}_dV3oF%O_o3jm5ZA!FKpfzA z1D?Gb4wT8XdjLTro;w#X>A{o7T`kY2nh-~>D3%={1lrhnlAw?ezY)J|ouw6q zEU#d%;G-5qV!o>xbk5P030$1N%WpvH_y%Gu7u?40J6;Gql$M3NvsLv`T3DFXJu`I) zp7`!=I@N)-_7yVvyQ5Anl5KtY{T${N|C{&zv7?afo|mk!PyarcY0(JOY1!w@Y|u{| z{;@d~&c1!j;Bp@fPqq{Tm)}s)EXG%vqQ@GFcKC}gG7*waS|{53o2v7@VqbqtxvPqd zRx8-qd>n1NHDOh7Q5nnLFte_x=bR|mk38x(<#WA^9I|yHozIaIW?m?yc|BC5zBzok zdV4AZvird&!KL5FXmF{)88=g8p?~h;*eK~+1S{kw>^c~_jU5YLR|FMZDV2V1JQq!G zfqg!q5-W7^?QKI(xn0#QEH4O2drfI$<%4hTVcoEc_|j<2#eS;tUF;iS=E?s<8#3{Z zjcy4nt0TF-)#LrchC1mi`g(hoxn$$Ken@R@y3>pVMiR~9KZ8k^OMcErbsh2D$THtO zBwHrYlaAb-N9Hu1nm5ldM$a2lyRH~m05i%x;nAYAOn|qA=A|D>pne^AwUo}8R|=(<)QE68Sfm1Y`8|B_e%{Yt*N@NsB^$*kOckJ`qU zt6X_42~PIXbLS(AV@I!EnVD!P{l4dRh^OHGsKX6}zPlf-`wI;@E7&|_Ev{Mtu#Lqp z+a11m-^&tkN>XVDUB?c9RSQ0ZDia2)&6sGwbBj6<9oV{kxUdSehM5$Usg-fyDd+Gt zxT%{>eQFa82e&SJV^g>wm04V?qJkgN+r0%Ybfl6N&c_#utO-K9dF$eeethkpnan?W zo64;_23TdGoVmQRJA-wd3V?I6>LKb~=C0CGa^7~ntkW7>mehF2jV1<~0^e5K@zBj5 z3#8yURm?q|v){-C-pFPP2~KpecHS5EaRwi0XssPu8sEU0@cK+P3Rcfd$?+z6ZZd9g zaMD|Wd@0kmWRgMopvF4woIraf$U{#b3*(51yWb^W#;nFxCTAG^N9dJn;OT^mhc7>A z4cM5o#`KOY&r~^8r{c4}7{RA$hH`g<^`5Aq`XSlo9jB}YE?zR^*%b}p-if@Ln+1z#NhN*X2L+vl3NTHq2l`9~??o6AA?ma_Bpe<;tG%z#N1Dz$jQFfxDOab{_mKI2cHms8z=3q~gNC3CC zu@e#>5oI^@Y)^cCibC44^X3FwBwko)mTd2DU46 zsN2gsd%r-Q5B5#}39zyKC&0$S^gl%#OayGqoSgp&u(30(lqvdt%ZY<_?Q z1OYz-!wf)KtN)~bS8{Q#-*?!04xggfB*ym0Tm?y86*%Oh#&zZf9yfTBmmQT z@MXCC8SwdlA%dG>0n+v=bfAm9h~ce=SHyn9DM*Bb1cbx)Yd8gmK!W^M0}KJ|7?+TC z1G{EWZeW=GRt1Q~OMOC)V%$UtbxA)zd3kxh`e<%^oPC0+3E;aBB3wW)1b2u*U?cE1 zRXPFiE1-8>417iegChvnUtsLP>%?3G5Rd@C?1EN=bna0=(57Glfb=fFunR2!U3G}7 z_=Z({V7z|)8bF9U$S?9O{hdA_LBqbBf!0SRB09{pDJ`$`6V1S`3 zKg^(T zxin1M)gFU+o&U5ye475!vdVcP;_GeDZ;_HpND&}kcMt(UT|NZFzjH|lf-r>h^@A%4 z5A#h8JHQ`ex0@0r(qN0zAfm2DJAUzK2GDm_U0Xz4!m< zn(mMN)eq|Nui)M9tT^iN)tC0vz4W)g#Q>dxd0pQVMsHyP#*Ot5BR0UNy|VInp6g23 zx}YN6Z;h&W5F>X!fV0DoJaWNJr2@;a9DG!>>z8l}fBStMsB_pLftQ2(*+0D2PYnR{ zod(yW+A5bWK7>0owo3(JX8Ge=0yT|h_iEh*@~=O{00ihtGzODV3<>ZJ!eDhCF6jUB zHJG^Jb^wOscfhNChy(pc6o5Nw;q1gc{WE(3lwg4^g>=TRSO{r=H%9t3{zim=-4)E^ zAAEphZ2m>$AMGD?r&bCOpr*{eiQtJZ`}bFFfWUmh*5RdO2knY^a@7J^b5y8T9?vvz z)6sybQhH8L-%><;1%3(0WX`FjV01)ss0rTdw$t7U2b`%n2E7j(wq*o9Tc6tBpR(If z)u4g#2k(Qqq2(Omjx4AZ+$WJ&&)6e%ANp+{*`RC(?0RjM08KjzN2MN|DCRkNtFw!^ z!oNRv6Q^@XXYv{OKMZ#x zq>}xfu|wXPV|y?Ses}4x93&Hh(nImm6?nK!>u&@LB>|L)0vyKna>j@?e*Z)?hqFal z5Iw7|XjOyMm{aCj4F%nO!rvawj;6(C3GTw8sVe0FlqF&q#62{}-SqE?XEgF_4DW8U z=)!cm9q~xAn!?db`l(8BR5vEMBMfm{r#)U#zfB2y)5v?r0>p78$3GC9nsrGoOV@&- z)D-Hix0IG^O!rvvn~S41D#Az^+CHKjq>7Qy9T|-!8urG)wa9guE8QdNLwr$C^es=u zHEZH&l9v1TTrLOvIC{2_7szjtwf@sRJqMq{k-uEj)J>&%H>V!*L60?wr+G#xFDIZi z+Q5g+3PQk-CepVRDd6|^4vDf9uBcHAJ{Xd^Zus~MP>iLng^r#IKGG|;tK+?EF|OAZ zbuP>7u68AQ_4wC3%B7zutf6*tE(+R*uOnm$TSiNPpjQo6PvvKIS6;f+bRiJ>_;FKc zon8(8<_KPxPTwG0bL`%XVrwbC2zBy<{1=;h0kCIeR-{8>QY{kM!t&3EaknTXjf4yf z(kE0~fTP9uCNBr)cT;PqqMh??i2LN!CH9B-cOi8_Bh~Tx!?hY2lDEnnCRbT4I(Bd{ zTNRXEkc1l3(=ZU}<1lX0aeJ@i9)otZL=5sSbz@6`W!ge_T@~B?kIuweehW=_S+^7k#^ng&?Rs97V3CT$-VNN21bL5WJAxkEstx;zS3sPc6 zSm%f8rM(+43I~>aiOrM`9r(N*1Johrmn|cLI zX@7jNd5-0Lu7egAiHeP4dX&<8uvUU@|0Y*-ZtW>Hm}BX3xM-?#Kv5qRFSv`xWFe;^ z?*k8nU30*z?7JaIsp#9n9kcEfs1P>Mvd0Qj(TKE7j5W(*m^8SKD=SJZF#Fz)2p3kzIKFc` zt`L^nd4GbPkkrXob`_}!o4A+Wi}$tH=2Y>xG}t?pyN8p%R$cYSI4yvmvIjx!E{~-CJXku!6h^ znYfvO-$gq#5!=?+2-R5&hFKT%(2HOd4Tga5wY5LxtDER=WqN29W!(p7R~Dx16DGg6 z?VZnQdN}@TT*dQv0q^zGhw&RmhGZ63Mt*ZnLe4L5<+Y=&tj9txW78JtV@}zK@swq+ zgrw>r{m6A?sxu(v>Q$MOtTpbx>{)XSanK+RW%-%-8r0J-%!*0EqBgj_iT3jBI&YQw z;`$xJ0|oTGHvrY!9g)BWw7y-OB-aSYd_!+~M>j)jbAIbY=n8FX{OWV>Xe(ywYx>)6 zZMm0{nK>DDrUtg{_Fs(MQ?F=Im!RQo+qQAGb+&EWwr$(CZQHhO+qU|2cdAks-$ng| zm8{InI2!&5tXm7OmK708ReMELwSMk||!qCTh#ijx0^ z4Lqc)Wh-Vzd6AwWl*a3Bhf5!&W;oG&xFGB=yjZ)-jcOC{NFD^287q1t36QNBam*BYUceJkcLj7v4v*+m~~~`Nf;sP$3vZL&1|BrE$6$k z1|QpG-~Gr#6kM49Tv43x#F|MX!7;Tun0^xu$V+Y{$oXqJ2^VS~W)EFFSV?}tDf{i6 zBb$@?nD!sAQC{z|X$YPDO{CVut&y%n?hL#6OUA(|MJOynC>@hHi^e0?i)b|tIS3A%MTO|?Tb-|!Q(dq;L_YLeuy^x z??;TU1-?2SRF@rnS`Z-hX?ZDO?+ zAw!;MYK6UO?Y$8@nBv#`*IHUGBM2%6)ufSk%d4jC_7_3pklw;CSHGlR@$7?VnqM&~ zD~oo)Sa-Bdc?S?rwy`#sD%5qlmAU19%;CX399?}xmx~s_*TP4-O9O13E19z=J=7#$ z3-4D5?Nt*@B+E5y;k!F+`Qjr-GF|c@uD#q3=4^Vh1HglsuM>+KPWGt0bQHT*HxnX_ zxEPfpVp%0>v>GB)bZq$35Q)SV6dD?``f{%EaY2>cUR#aaQ@Bd!FI4;t#hN{haNkq^ zEn z4)JG4nKdpujY}LTf(}`Q&H(lR_?y+NjMawi6XaUE$fnywxSVRw!P4`YzQH8%ob>ln_C?0#wa@2a%)^VR z1?DBlCH{9F6Nti@)mAZxF7J8s+lC|MWpmP zr!c+9anj@6?2guanYrGc%g5$^@BuCIYMK?f=iI}Z~pD!p0F@Y*}Ay#Q6Ybq|_)OHIKY^ODm zKp~Sxf;U8kAYYVsWR>l69JYwWqXl#P*wK~3q5uw%-i^;_=6Q^|7_kZFnhMn4`i}1Q zJRJ4KO`27-!-Jk36=V8I78BDBm~*Jk<&O=$$~1$p%FNta?s8cIAkGq6N*&{qMj_}i zj6X_GGizUjt!gSIhvr|aF&S}nEY$5CQ7o)Zthd$na1;C4$dy`D{5wYdcTbk+g$|h~ z(dZOC-$|%wwG5ipO)|pQlijiJdWxjZrywfA)XL;Q9bnB{WpHXwcboD7*TTk)4o`1k zvy+V&;>^^6pMey3adIqGq)gd!U5O-d3~^tK*(>kjcK=VZDo(|K4Xy3d;vM*PgboBm z1>huF>`@uS=Wz_Pnla+QE(>02MT=Qe?K7n4)7KrSvDGNkL`a6|4MMsJ#2}1<)};Et zVay$r-9X#o8t?mb@7)fa)|4C9z`SAP5yOhsRAKd#Z>UpYsg5O*R(=r1DWkppAGUP= zOtiwXFOgxRftYJSLpah{87T`nVB%c`A?alWjA`sso0f zwTd~b{tmsF2E?1@; z$R;h&=w4`u3^`Zirt;S1cB)fkjUfC~zW-QORaNu-^rh{kS zrO&+H8J!Te8QvI1OR*&3<-o>Wjhrsgtj>GO5v}8sPTb$(m&Od2(tZ1Sas(cRkPVwG zYZ?WZpEnZMHa$^6^?P3Z6R8Ln7huH^lU^Z%Z{grBlsR4 zCu*}6onY9MX11*C64J=9m4>FD$Y8KNW3VYke$=_n*uE6S@{~NP)vp1P{w6g*=dVX- zCZeX=Pa($VX`gBx37o!4adIP=;b!#q^Vy&@yWDJD)Vg`yL?c8qtnI^@x^_9os34#B z;s?tE^Y4%H@f}dja}tHY;rBUmi2wtIoI|C6YRMrdP94~P1e72>{05MZLjwRqUZ?aK-!2>v_8H3%HoP_AUY8&bbb%MwLe9T#)Jm^GB0s*d zk8Dxu|Ikt;_yC{vZjg?6%xF&gFHxQko&Y9o~@Im|zsiU4nLshdo<9a(Bxk4Hd=Jk-=N_-b!)eUkjn8h16*<^0Lg_BfU=nXW#Jk{%n~ z_oxb%r6G+`(3XdQzwdi5pb?%)l;_$1eU|%$7laa;1Cty-y){P0e(~N4O;y^*C@+8i ze6Ty;(@_(n?JWs4_WWrhl>M`5w_Fka{oL^0#W$< zTxX>qR_wX$LNz95pGTCYDFPXY(tB^9MI4Aax+CN>qFKrXDu_*pO_EmHAFjG(QbZm6 z96G%@*u`zNVFNM18aCEB2jnWQCH+!rjNH^dy_+*%H{QVBDQgi$(-<*{N;RW)8uCY- zQtY7I=~Ufa3+NHUu+%*|)uCR54Sv#3n$NRH-7E+)6$3!J=S|_UbLsM|ZJ(r;C$`TB zQr=m{*@Q@?BuEzd%XW4*oDF{vnd8Z!3x;*WVoWd!c2_MiL7XW^k@0;_RN>A%VL`1+d}vJQsb9 zw3wY7ohBIb)s0p7wqUNMQezP+c`xpKRO(-aqex9TK72}@;$k(bwg>68=yUQ2mJ${^ zID-xN4P=O}{xqj7_m_U*yGmA|3g1C``0ekwWel-wa75*Esg)$;=fUDILOcW#m}r8Z zTw-66yJb$ZA$(9AqIcGO+U&tII3d;c$@=6rOy$NJ`}uVL9K$iKO+kR=6{u(hXvY{8 zAy~wY9@IJAq+Cxl_bj+m0;*wPl{6bjGDpD0pGV^eN!N%`4CZ}OOqnXoZC5Cbwjv_u z5bzveH7RA=21L09)SQN>pDG>V(tgw!(&x#0k+kvWt!sS_qxx;$nT|%@r-*v&x+r)Z z9q}l8?&nw+an1)Bx7OludEr7J4xo@tS?oWa8`++3C1%W~Alpxl~$uiXn^VA0hSsF%~_byuQf-0#cTSbTrvcu@U z3)lvdlBHY5Ex*a^P5T=#9-elE4^H>)p@ti?G>+zAg)(BvbOcUhD`Adt91yzthl8hd zKqXohl09RYWSeL(De1NeOm&%$M?0owyShN4TRdcX?1Hra3J3!eBt+(>4L!BBx+wTs z)#0&LX77!oJn7u&)9dXQL!P9WmlkfAcAG)R?${CvFM-|92$YS<24FZTLr3L{Sq_e4 zk-FkX(+C41Hei?OYqR|CYz|xcWJL4GFoKz{JgLbh$kZc2;jAw?R)hH7TdvS=Pi;yh z<5Q?|p?m3yQeB^Kl_WJXpYvDpIDpk8}B!SaFcS;JY zdjYmMfi(kGbkk}sEyNx5-CtVi=A)CwR(3Va)JD&SaPKSJAQxkLr$iYEF6bwhl*HtL zfy#~Wi?|3JSG4jH%-Nene-JCH{;qqAYUzQ<`P4xw%zpHV{h}McvAZnG0D*Mu#N^jY z&S+@0sGgM%HLrh9ts-SwCtp}Y3?6(Jp5G*WBesOUXGLb zQFU^89Z4VE5)!)gruij3VdB3>rbH-~n%{Zq4{=s+?ehMM{lun;MPalLkuw`yL(8HmAfi{0Qco(OGStFQ4w$ER(S*OqrA z$J}g}L2q_nZ6`mC=P6 zPCgQ}l578J?e0Bo8f*nSD1)gqzPQ?aUwFYI9YW}PJEj)%hTQD=x{U<+^;H%`noHOX zHtomu(2_53i$J9lBcC8fm(MEseR9CAOP@GlAA1>b%_%&aLZ4N=3Sn;%KE05)Jw~&% zAlD-)WD&n+UH}OPe1rxZsk=&~DX!NK_lL89b7f~C4cA8pGM@Mh^@VN~;m&3?@ZA9m z*n^ZC64EOMafz_~Je3I1{$Yx1!)iFIIz;kQXP)f}|^8TW8;Ql8@W&e+i%FOg%aQcr?S=j$$M1YNjmGytk zs4oAXQS*n)^5X?bA5D_3rNs365lms$< zmrmVte;<8zId)xLW?Xc8sc)!#R=r0Y2j_%@)*-JUR{09+h!EuKaO9L{)vzGIA|nI( z4FK@)6hT&if51WS(gqoJAebd?e9x5`>?qJ;%lYfwn7Emt%B~LqgTjCb6&w)EIp{Gc zz`!Pdtiwje0GIQ6AjtD_DCDrC13ZDqab0I z*Pe!julgQgA8#5o4s;SoVE;mc9>Eqg#A|4KfDb4e>|M~Wihxi5+gG4{j+ty8QxAw6 z{QzdnFW_ERevcgi+95Ff$hYlqFDU>Bkdr`P9iM0$G!W<;`Cq&c&foa^#8HATf7d>@ z1Af0f-Q3?StNSenfkG~zABJCUt+?>^`k3(Mx&Mc#^8BB`_Cy8?e25I<^awzR$iNbZ z@cq9r1`xtu$)Ioey0l45SQMY+>RzcoGHb83=a0Y57(oB>0Slssn9$%4zk>gGj|3y+ zH{i>6@vC+6H+s9b;ENaHXZPLg&CTs=<>6Q17hi({X&><}6>nA*|6g&(!|V$z?`Lxf z=*Lw1c~1rc|H#*}xlZm2j-pVD>t|6Ys19ZfufCY1N;7x zA25QiZ|`?uzZL2v#+SM4-s`J6;4t-MSGA&0&#Y8;la!1SG{}H{4gkPs$W0t6EO2ji z4)W$Vv!5@H0xEjA6X5k2X4IJ$Q`WsekAF(YJ-Ur5)7^#5|;pg~6 z6b(Fpi`%Q~7kJMUYM{el?>B9)5mf(suJ_ot82Yha?{4xVQ|3+MC&jlH#;%PQ2P_Ro zbkJtU(bMPlSU;MvGI#7D?+aqKK{&(@!UpMa;xsLTS$R)g<_+hBkE6LZ@#Qh$?{Cin z$|$By_dBS$l4OJYrTARAcfx(>u}a_2U306T>`L-w$NKoXkW{itz)V-b)ZkWlCgf(b z`$M;vQ5h^WCfxUq*~kBVBiS2^qsyw{PF5^vuW>I=vO_aNR^^mb+IN4CflLmm5|k|! z=QEmX;`FN*#AACFAjl~WfzX9WrxVqfgYN0ZjK;2LOm(u|KQ(PNJtWg5`}+e-Cu2-2 zoq3O3Q{~oTwlq>oBJ$-3?q6*(_D0nHR1F}MAXRNZcOQ+K8k~!LjUxR`p+9|gQQkyO zZ90(bTFD(wqN*a>|LNZCYTjyhc!l}|JIk>tn=4j{*E81DL4k@~G3^{EtmBhQ7iL5aPP;P`UqC=<&4Kiu9U#<-_UuM zv_+||wpr8g!$bW@x}QzBY1b*hw?{=xJSobr@__#=Fn?2XOe|yr=3`mQ<7tf$f7|v5 zMP9o`9b(eMdm9;|eJUkFiI)Tuqb@`aeMD9o&Aq30riW=n{)aHu^;SYNT-tdps?}#B zZ2@#cl0Lt*Knxj2PO6%`9U7YGJE6g9{yM-$azo-TwxPS~_trg&zzFJ%_nL~KP#}BH z>M9Xoo_w6s(B9_L4FUC1+=7>7`_+b!K`8kEclmg~wWrl-q@bwFx8<`06Cm^YN~=dC zE)*N8_bGU7DQ5-|%%{{LnV5zIkHB?%YwrS2@x`OOV+Rrk;m=&y6@hl}`o<7PpJ;#s zZR=F8V^5K>{!QS|eDz}&`xwaO=rGVE=&O?X2x9e>2`JvmV)I^nrypd`x$)u@wEsg~ z<(39lAiBw1>`)jWz7k_(zsV_@Rv%AeaonA~!ZgAR45Y{;WiIP5Hf z`dt&|#y30dI9Xf?nLrCdz?8HWrDhA@%OS>Rp85Qt*@w&VFD@73T0VmlT?Enq}EF9rj*vd=SIO?KtHnIJsQ zh7`lRwib5NQ>Or}u^Y?9wpxd6NdS%Re?h|B!huw4!^H;qN!|1^+tmZ%9pr_bLk7@a z%H^4e7w2*KR3e3!7TY(}s5Nit60Q!$`x3VSw%}a1+rXeYF?sf`$Ir?56(UCAIQyvu zk&Xkw=D&1ptCvkO9i#WjRz}W5pzp>;KNp#rd^g{-nD?tl(4fQfbm$dK1JxqIee8tZ z^M{Qeb2h>GXJ$O_Uv(pRwAaWjfBYJ+KPi-DY-N?)q9 zRR7Ar@ZDMIk_*kzRSDl`+1+j=Hq+KLp})tc8d0m++yLrmDfH098DsEC6XN22t=Hh4 z4_4GCGtCpb;AqAvC?DbnBwdiS8{3o~@=q~fnB^ecHGV*rdep;2lU?igOT4DCMcZyD z6>RIs*Y-qRGmhJdHPsjDw~zfrq-vQy4sp?Zz^v#fmNHME8Vm+#P}!P_AxDMH1q)SV zYAH8=;Hhrh*0Fy-@{(92CDG+auk%I>(Z2D`HO!>>dCnqQq;bRWR>(sU?ePrNa2#3b zEmKu^aaR$fA817B5cNp##Ta<6!DS!bTauPBwaxql%!#08mTr#Caltb(tjFIHr;0zg zu0zpZAE6muf-AwJ@+vRdkJ}?%yiyrL*#r?cPL(%(xq#~X{wtZ5z~gFM2B9yajHF+= z*#3U-s{0Aluy|_QRh9sJ=#}OSxY`L7np~SG(+PUmHAH)*1TpcBH+z@MK(CI9{M1p< zcZg;iwTdK#h63qz77J0bBbS3{U8L#ixWrr}LQaq%N0&0PGcMa>kuh;Qj-Vzxvh2y5 zs4KV;6dGLG@;T?eX5Mk}>L3+IkzF&TbBC=C zjBhV2-n!Iqkb3N_)al^E^oP8aEK#tH1sN%NQiV5c2LYGuMf5_FzO`+(`c9Yd&T!1; z1p)jLcU}dd^;Ei+W~~f)h;daP0NqlE?qrPdm3x*Iye<=v>4?VhOd2bg7=W^_aDolB1~1jAV>DyL4a?xC{x(pt!;Q zr{k&+wln7^LWA7aoqUpobZ2!JO+1N6yuF=jEPVa1l%-W{r#W#W?KyJ8zj8^8pqL_y zlFe;<2tp|jt)5%Z@r_54GgtzLHfE&}BTAD!eNt!^T0(6(z3-r1<`B`Yotw^==p3Yc z4>=?9)Vju&$q7mK#$9=I`)f?Q@r_G`8RW|{Q?#pfe_DNrpGjrhR{^@zjN)@`$f#S* ziwF*w!`1HUQYIS|X0or@T5mP$5&xaBZ0gKXB|Bjsbdqj)yi4@)(Vcl=EG`n z14nzk;hvtcjStMVMsIXcR#ovjc%CLry!}fSbm}#0e6XtbOpCLk`htR`*~+EQ(wJBe z)%{`fHNeakM#J-|jg|m+BzHG!`eECVe^Mu4c_nIj%V4b;44kA|$@kKJEZ6vytcz@b z-)w+PvsHC=g^FX}^Yd8?D!HSzP4PwEHTbHoFyn|kgb%f$`6S%kX1j}sq-c4fD3jBn z=spHZn}@abSKQjnwwYH=%bfN1G&Sm#Ua4+iRrQpFqp1q=^^}k4ci)$yGCKdyQH=83aoD zF8H=CtREcist*Gb;s8N)sUE>&G5gB1V@sJsvyOl4i2lj59~Y9Ct5a~n&xi8yE!R=L zBpp;>Ty^Lf9+uv%cO~m)Gs?k$Jb$(%TzG>(VwBCMzB=wf;3iA6V8E6szs{o}?zRjo=@YK1EH$0^XV$sTgQ*tsJ z=jB<{_wyZrC7Dx@|2@p=f}u@cSBadNQHDJUUKzG+Yec@5OZq#-ik|!nFzz%QB(y(a z89!=|ti>-5Pieb@tJP%)L#UHO3D~u|Gn;{>q`&K(tsiRsr~Z7)JM6c71Qf|nBLQ)W+qjVk zf%gE#nGoWg%BFx(-r11gd(`i>YD&@}zrQ$LtfEOtNM!LymF4`T$I_y-T6DQnYjXCb zlymNa+#_TUvCfpE;@}(DIkS!}ahY5I`D(%Z_KH#?+9v^21fw@RAIm_XEMFP#cntjb zw6N`8>ZUfs)wosN?#g;qmtp6AeY|1Qti_v40o6_z&Q=J~o)u+@4 zU~~sDzuT)sWb+ZKdy02(%~he(!c_LneHL}7u$HQ(w)9za@+B+E(9TqXP#k6yrN^9| z$MnOZm)xfb0%r5=VUH}0KK>NLcH*S6jJVuY-Y%Xu%t|c@Y^im#s&-9=QhPIn?s-Fv zAs;LtuAuJrS{EWq#?)=z_U{vNW0jdwti8OiIzZ4;bkk8MIF)wmP3d6$m)3X`4KF6ES5n)& zG^I2-f%Ofbgqcy_c*@9f`+NeQ-^w|EpazJ<_?rJNW`AuxiSEuJQ}>$;{mB$B#ts9oX^KJ*x1F=;Lm1&{EpC?kx-Bj6)C9 z(Cm15Zfs`me9D8xR$vQ8C&7~B_$6#9)P?#)gj-nw^5v!>xrRRVqt$UY?B~9b40Bix zt9V~i_xw*>#PO!~YXcf*=8VWjb;|-KXVK`@RG&Qe?laB?8Er86C)}KnKdJgr(&9%; zyzyzStXP?{vKwLYKqK@^UwKBfW15=y^mnv+RH9be! zFUecS%XoKfBr(z1sMNYYSfEOYc|{9#*gW3c{iZEBAFfH~M*;;gl3DGAvk>5)m?N_N zfkX$71y8tQ`AjxI31_qlrf=SD!=Wmh*~JnP3x`@u*`9TLX&JUM)j33{LIdQ5v>nvq zz4`Ypb+`L*gNP81i_5CuXX6Pae2h#)>;3Vx`$1~b@X8Wdg7#-wKPITnwC1qDtETC- zwoI(SRhCi7-pB0b`bqBFKXeWq9rn|V77(aK&knmTc~xV(&`lE{gpq%(??sZ%963Eo zf_x{OcS;7=|jsd}sHdmNQUS0B^oA{h47Z|m&Lefj4zEpG=nr6u2tG(Nc$bKiiv z6(#vW^c!rC#FJ+Kj3-1tL|6XR2oy7xoH3N^+Pc|JMhH>Ag}<*HkB9yNLS8-Rs%7RI zwOO-rv4iPsL1ev!Ey~oZL73GNR*X;lRFl1I)_zd-w$XKiV~iGp*F~;J7~Sp^)1KWIxv|sh{+L`;lmM$wUejMX>;3{@bI&VtIU@_8tOWXc<miga;x5wW4P^G?aXxQuofbrD7}`+jRIoT1E(z>P zsw{^`O`t3t^kU9*oH(s~w^(foAvh^(x2M{VwB-IeRfA3;zU^{*87b%C2{Sp+zHhgCgoI4*6OH-v4!M@OUqX?g}^W4;VPH4{VA=J z?j#mLPbId{QiN zSeP04BLN?VtBuA_uxPpKEt%Ta!Py=THiN!xCy*7IoCc#uWDlXWKv!-q;NeoFbu}yI z-l^*wanI(asr=G`W}jTXs?K1e6Y%w$<5+N@cI zv|031C&SSa-6KrMKa5NoUW4iP{HZawaSkvbMd&Si>eV24jOb^2~^{?UYKx7P-uswG)_ zQzkM>Q6i1AIJP7!{I-+XDy>?cQAW%_WPC30c5O}0f1VXf;yfi@kxeMJ0Vk+$i>n|V z1&92+SbjBjEo|4ZEF!EfnN$@Fcv|MlEy-+1mr#H7;>GNdhAZU09_dj2f!%&;y~+OSyUPZx8oDqLm7#eKyQM_C1rd;ZifaiK2hm$&bGB>i(_WW02oYX zVL%axfJ{DC@YY2^>$d0Yie5gJP)hN4O460darC|~?e*3aizc60{W~;3pfjH()uoxG zmMd`hBc>K}MNeqXvj;~`YHG<1rVctAE~7hpHYy#J6M5-SCq`b?al~~~F6rBD<2Bwd zCR&m*cw%R2NyV~+dDW4t3k}n)>`mxcyvL)=H#DT_XXVs8Ejid;2-`en(pk!lu&qA! z>B;)q4rykow8@Oq>dO5T1p$00%%Smt4(-xZl8d-B#?0}lpb{YkH-mgHb&Q4`6kV2< z!P_z9*6FnoAzwDA$hihWzxs-EzFsm-gQvb?>ii3%aVE`?xawZ6GdDCQ(JDMV_apOW z9VtomWE-WGrRoRAX>CPVbcQvt~hb@aF5+XT7M))?S)B+p|$_s^w{HrRI}_(r_0T(F|N+*yA#~Om$cm<-q^_# zkW*d-C0O4k#nyiiZ5|(I6vKpg&e*viI%#&BE6nV>f2R`|>0#5(jmRbzXE$lpGF7#P z?V}oJh@oA%_^jU%w7Z>8_SDvbh$)~&?AnF`c++#m5bBxMKu_?86lr)*o}*$6qlF1m zA6r(4LuBpSAeD_3t6`HXkJO?d)!Z-+q;}gxNFh)0LaoQD#{T<_-8w7R;k9i`@o6TN zwo&6xE5aWv;W*S@ocimxwJeg?`%{dXpXyaPn{q)6MbY?Hv60Yd;?qo#%9~FW{g;Vs z7w*ugV}W)UcPOzQM&g~q3Fxu|Wt@hcfTxn+_02Jo8vBoA@#`@jRoFM92U zzBqYh)esXDFUPu*oDzbQ59C zD*>(?23Ay_vlx%Zl_f+O#QWYC$spbOO0ppJU4*BTCsw(5GwX=*ch`Y}6E7y5 zmpV%Y0=rZTqRbUnSV)>Go@1+qV|!Stp4}AI_>+$%kDv1?J?eo9aIx&hkOHziU>q%~ zIZ5ie(6_^2F^(3tHhLRIqTE9wohkcUWF1oD(741dqcPdc_Ms@n54;*7ZkOjpFoTR3 z0#_<4QyOmu94;syV3V@jXgxe0eSmmAP8T|8V>{&oU=hFb{GY^DTSDg* z{kd94jnaH)GDdwJ%BatLH(`Z%;O=Ucn2hg^k^jbgGTL|ng}-X}8XJ*|>LO5PC^a<2 zE7b-Pakv2LX}_Yvz&Wv14(%y`RPoC^ter9>8GtZjWm~g86o#&OyCfR*D|2k_Z!98# zg;aom<1Mkun4iWWwjhS6J1!_mu}fOC*pJ$qh}}eQkxqGKG9$0!gbF%}7g2azPHE+R zN{hcv7=(nt_TNsa8ta!1Z? znDZEm>@5D#_%J#;eYtJ?YkgA7^tb(+iy{eUd#25D>al##w1@IRJz)t=iR=fAv~x*V zndPfK_sk1q(x80nyY^84a!e;GOw`QUoZ-j^MtsE#_}^y7MR;ZE&!9`H&3}VyM*Rqz zd^%aKwmM`5BH!22Xg+Hp@5PL1Q|!>jlYm}Pa7p57=)Cr0h# zG#o2l^wXLNqM_oKl7%YY`H#FJfHBVhL4jH5|C0i;$fqsJU1Ju}~}_uW^aZ~?(C!Ka2m0xUPrk^tt% zR}erD2f;vI3JG%z_a2Dkn86>nLl2^L;=8UKhd>V%Ssoy-#->w1;4ME;jYWd-<0Y7xo^Bc(cg+ot$!dpeziM;#ABLJY;g>ne&?W_Ud zw;_W-_T|9RuPgzcc?#_LW;y?`-vR%0VENVM-T9vVMEnSY1pdN-asDOZ;_ANxz`%jB z3uzYw__+8RK;etR3jpK#aSY+|Dx!DT-=mktxdwQ7$7xT`r#+4UFtYNh>bw&pmPS6I zIfs4nQz?+I%e*G363AIjz{N#im&A5o`=z8W7DoKC0vzPix(pk07YP2N&N;XzGt(#j$5;7d;d0*V0c&zG=31Q3P}aBzD@^c1;8(ue%8N$~|ea)OU@ z7Jdi9ZYb#oGMGiU#(ThLTSo`tC-A`+0Q}p!zsqT$ukVLEg$Qcr$ER<1;Ja2&KlDC} zx9LtYg|7!Y040k7@bUaPI{{WnOAfNdy@&t0JB_Nathh4Ia{Q@%=PNZa0pZJ+=U2we z$0vjXf&dmS0YFk8x#!!6;ivCw4ERB=f_xJNAoeSc<|*k*e)XyP>hB8+2EVtf9_>24CtN2Qn@*CRs%Zcxd@A|r{vPbv$s}Jhgw*~yuVEB9y zIAEcR?w<|t=G&Pe_!Cw6X9)7-@P1cC8U=$BSi-LC)AtYJNj2PKC_84KT+AQeq6cuc zZx+29diEiJeb~?EJOGd&{=DA?{nCkf*iSPz!{@h6kbb!7-dLqTPNFOy>C~_`5P&G5 z0N}8C+L4vX?2B(0xUln>jF@zXCeL;Y=hXBAC2$K6+A1Ff>V0%%2-+W&H1U|7{ zV4!dC_>m8Gg8mpAgsaK3s1I=TZ}^|mVP9;LIzR+Ed@J%_k)gVxoHcT=A37k0{oXm> z&`5oE?rraXXsl<6F7Qt1bNj2@RS1uS9sNNob2a_d{rf$`NAQCndXPQ~A-XQM+A-FW zh(!v<3;1-mZ7Q(aEnJfZnmAXsSDlN4yg^X_eR_x$Tn_0&d7u*0e+wQp2Cg#?!77ZaPP-BD2JbQy*DfG#51-tJgo z&hc61W^--TnJnAP+(m7(opm&)M`cVL##T*)T4@UZnRHEk#wp*k+|a4bI*Z14_@^h? z(I_JCmS(buL)0bS840Uwi{m->VXeeb+P`uwv^dUWhbhSBvMypj83Sfo;lF;Y;IcYp z!`9}oUoVrNE`buPtARIlN$ws?4s|TcG@Q~Q&8HfS8!=lkL3*cqpv?y%r2R8f)%aDn znloLz@^FoBK~u8(kiwGZ0%}S^Z$OE>pNol(cdS<6sJYXk?e|B_%Vj@XH@>n|6^v+~ z%qz^_v@FCu6}x-qKOz-#i8)R4Ye^9T;##?-BSfmAJ=M^I`kO_B^Ok^R_< zRVp0Bu_z#H*q@(~uA%f~c(u9|x^1=FoD(znN=(f$O$zX})QxOhPdIK`Q~{(t#x zDlJV=h^0Yy%!9QUhTaYHI1S`C&^nXZ5`j8R1gI}!6`2-oL~6us?6g?(;B(HYFLIL6 zskUaZhQJxmwj%mJ6;jf~-~5>1Z69Ji1?(kf!N89?z2@kYO+=NS;^^ z8rKX+uQfMM6urrw!=R&GX;FF~2Sz;K>AqP`8{D6R*A_U%Gs5Ht8gOp*fdy5w*ggTm zL33xh)}fQ$bwFgNd91iO^Y?vJHD4FT)>wPfT(}0n!9`5mp?^(mOl@$NxT6zS|9ensDHmMLGw#_KL3F<`$9BNKjm=T(P{=Dn+Vq^ zb~i^FQg#mmtkgLsls8stO`PErF?QqbWrw*b{`;1oi^|j~_DW;$siNb9G;L&M>h~1nVs!l6 zSZVNKtk&%W6Vz%5&+=2;&$xxJ$*{7X2A{a0Rk}5Mn4eq$_(fRB-xYCwEV^Sr^k#J^ z#?1h5%V0lP?owA!)^lcD@)F8}<=Tnc8?^DLeQBs91{x_YJ(G9>*_r&&z!^n*%$gN7 zbB*2E-TP^PZtLJzhBJ9dAX!B>Z#T{=wR|T*X~ER%1Dx%)!?4Bq42U9;~`!r9!-y&os`|o4@=DxKtMJ~zwffSwoM+Nn zc|X??#TZ&l@ce8KVZUR?V)zZ-`!e8cNz)X89C4NCMjYg9q?$3)N2g@KQu`3Gb6d<8 z#9^lm3HoL;idg1{vN=xEUdPz;AlBV)r8axopMoB?rh+$E`(AR+W{sc1>Y))f@pA|n zj4Q_L>Tncd{Z=|&a@D*c=1j6o|Jbf_&hs@%HW=H=>g|eY|ux* z_M=xT>p{oH911QY$vB0I>+k{bC|lj7o+5{O%QA-Cv{#MKHEwujy3HWt1Lj@C$;Y$B1eHv&U}W--|OYYmT3bkHD!d+9!=pbvL%Ax$o!kYYxiJ6l|>Gni}FCstYpI z?%)$E>w%sq4lT@b6Q_v&2?g0{NeP`U_t=SE!fPpr;G9Ezx*8-mSwvbhCU<($c#uy` z!w+@PYNb4A3HMS*R2o5yEn*JyT|^V*y|To}CkS3g9052b@%ekg4E5IjfvTV^_~-XAjq?o6MKH1W`emm)Q=Cs zrTJ$U{8$1_u5poYHBviR9M-WCL?|$~6t!V06JeL}1+gxF^l-bh0shDr7mC^PYw3eF z*Z7?Dx5`#fRF(vqdUwc_Ix|(Y50@4C%}|Za)OlzTY4S&~yR!n2w&3Nj6VF?Hfoq8d z*sQ50L;Y?AZmIFm;BF?sK#$ao17N3kh+j&8fD=X~Tw`7vJCAtr{GDFCL%>Mrkf|g# zZP6qPpf&B1qhUd*7T03s!J^eiNlrTdE%ya<(?#96Ee95la=K$eVhb)|gS)gN!*7sY zyp6mCqnnlMBh>A({k&#vfeHTLT37uWW>H+_%ox9Bm!HD4L2-b=kzL6ueaXqtl{LN{ za8&!qj|7$8`c+KU8aJL|3Ep%rr9!j~Y@m2Ie)J4Ie}m{C{N4MFF>ElJCX?DJkedD| z(S%?E|NB>)%WN*g(Qdv`K$*H?)52`X;ZM0cE<_ZE z8}$P%)ekXKofI3|YE7<`t;%@@z_RFVve`gEo`4Umg&S>8&x1FKmNGiVW+z}MtxUg3 z84C7oQLTiCl6jhq#}U}QC>|;jvd6paVn22k_cvz^(7xGUEEj|Y&nKiamTd7~hqP^? zV-JrV)fA>|t}*CB&84(s0o<^2gSX_1|I{Ew=&f30#I9aH&YoNzYUtCrGP+Z!#a$&l z{+X{n>&IOH?cG7^@jBRNHefUd>g7C`<<{&S0}sB$Y_&^I*47?trmx(yg6^U5?$2sh zpHIO=>)19+aca41m>9IJ5+Vi?S|sJSG)kB5u#c6*!a^3m6Zmlwaf2B7+UfdRD5|)x zEn=km-6x3{Qg+kiExGP@Z$}aE;#6`ZeXV}!yqcz2XFJV0oP1&$qPz|0f{WDJ{208u zPPwoJ-Si6oDH4C=t0rg#ULCk|yJ#gaeAQsIOg17M>G|Yv!jBOf$j6x-uTc$>MKUKGFX+JqV;E0_uz=pf{LFx#&+jerb({d$1urCt%BJH8qv0p-W^W^ z51#+im#deyz6L(uf_e09PYo5mZk!W?CY(>722wdz} z_!aJ6ey#g!q2Vlh;RBH2m<2`!-B za`HBDYDJ_=2vuBLWiSH2kSDBhoV-&-7S@8~tIXB+=Vl!V(BP`8hT+@js}`x3*Rxf^ zyuKZk-)A~1$+_&(>NkUauqgy2hd)7{*xVGygAA^x(_}MplJB{LCe(OBp471oJWi1bh3YJ2TS#8DPWS1o8{cN|P5<2y}$?}owi5^oL>Yk*#x62N61EZZ5 zR7sjjEuFrn;tmsfHS-yGQ2&Rra|p8p*w$>?c2(MywsF$7ZQHhOv(mP0+qP}%RZm{u z!5wrDV;-^Ni&%TFAIg_VR%%*BM&#Z9HHP7MyWG*y}6a^C0mDKn}H>#=zNY|ygV%+^>c-N*}BmPqa|Vv$~;>tiTuHPmr!A# zQU z!GyV7MXPEu;1JTnduRnd@z=rYnV6|0?x1#*Gn^89&WCH$GQvW9=OA`1*{v) zJF-gdN-w>q^EjI-cS|Km3#xL%S?eyQYpqS{}!wgnUvj@ju3b9n;fm4@1k{A z3TyF0BI6EU?_UoNFim5Rci2ICG%>Z-V?=+(Mp&qk33xxFS}5pQ4uFn!nE9^x9@;D? zzdR^Y*G>$8EOYlJqF)0cokJV%E4gRBsv2N1F$ddJxaiWa8>kZeCI8CW&2W?shH_{@ z5s4T98r-;vF1WK}K(QZr0^ zEXyUIOS%xiI%{5soib{;CF9BZBLuF{ofP41|XFC@m2Ho3I!isu{JNoVE4n!l9D1cODb(S&$8NY5rsR$yaOA-mk{)dhh#L zf1RGmiCAplG)NDt{4(S*a4)?H9%)uqqKh=f1s4EA^mW;|^{{s|Ih4HKg;r#}W@J|gej{dVpnWQp<1%HAhPUKN z#;2$8^PA3u6z>gQoX|Q{q97HOn~R)3Ll?9@QZSS87us2vE_a*4zSJmKpEhAoEcOwK zu<|df(TOpv{cA?^8`&gH@P|JGvzNdlF>V@Knl@Ctxolm6ba@NMY#7(2>J3;7b8mYJ zV=}jBb6?EzEm|fGf;CTIIlw2w~4 z@wh5VHn;4%ym{it!_bBQb7j&Cp41}>3Y`SDqZK(c0dli#ys&e? z{PM=m8X-*3X^=JGVkO0aTIQHu-3z998jvM`iFr-vpW_GMMarlcsx6e$$;iEFvt*n( z1ogRQMr^#FZVr?1dk!>I(xsQ1O1iyBk$?pXDiUo3jjv=;xOEcwLUO>W#;G3s6P(7d z3=yx%2X~NM<(yk|m~D&Ard+n-Rs=q9fD)sQB~t;$k383NJR4If(e%nSZ;cI)?N;r| z{m4tO+?O~;*Oen|kE>9}cXospMK-H{eI78D|3qo&^!k@*neL6TPHw?Q=VjTPo>t=9 z?A)Vz{BB+IP)qXa){;c6qM+m=N`cbmxIeD>Y7B|Vn>q8?W@$MvI+bo;KE{}8{2HB3 zqaz|fATK&TDgb@!H4pK|SlZWI&u{exi9#%GQ^w<23qO{1(KDtd?l`e3D`5WZu!nwk z#e{2SDl^N$Bo7v2FLXPi%#S%(5r4B*kl_nvE##pTIEV=iF=q%>MLe_Zc?U@eFAbH; zmw-!Fo-YZyr?);MMDIbHm}#R;r}nZ{NnkCAzgw#|dp00gCaQ;6BUf+!GKsOw?htJ6pT`qNgt703l8}+*hOaphxA{yCH2Tz!%49gxb+12q={m~~aam6s*z;#DP ztoDqTkMwwblEVCM^|a9BfLQRron`NA$(^!!2Tq-3MOetpOlt9syT`sp$MlyvHrf48g^RR1r)<~jHaUOVe*f7DpW1xWu zIRN|Y#rOA3^=E5fPM>7`;^P{^-%F9vaK;MD}2Uu6Ns$UEekqax*C)-L@g+Wu0#ww`d5#Eq5IA`!*{PW?Mmkt_gzL| z1NKElUxYEQtRe^gh)Ndr_&xGav%ZF(>UPn#Ye8GzT9GY;SuKqc_;28GUbl@(LWhOdGQR+;YOJSm^*y{VAd9MtH7L+j^Chk0MJ*$T zQ`&W(Xrh%9OF$VQTgjrQP?uzKCnB>?el(_SDVcKIT!NJkLk9feIR4t0Rx$>OpQs)w z2^KI;FJjUz22DhcAh8m3pz5O>$K`HIiR$8)74RGY=-v@>E=Ji{z=sPGIjR0J6AOSX z&;~lZg)DGHD#$tty}VV7t!cq{vaHsf7MlBT{y6)%J%7rLYtw#kjhb@zF;-!pBh|LA z*^n$3IrN@`Dmv|p+`HK+5g>1f(Gh|Q`DMEQ06$CN5Z@Cm-MzzQv5KFpC*#IkHFJs{-tKruYgIZBW7RTy_QdvP@j9`I~{$~z#BLvOO6}Cr5Qm5z1_|M2E z3n*=s5`klVXvCRQqE#Z{d4fL6NIT`SMOjwF{FAncU>s?69@a!}Mg&eYx{;AbD#9K5 zm*Nv46Qr(+g!wTI=_kZfO!LfOQCj=6+j5!4E+g`p%ch0iP7#`K-6popL$5@+IW|hiQ$isHC-JtHjvpqn&xle?s)%y1i^EByfLYbV%TCiq+x&SOmq2`vGI5`z_w}a-e;G+ri?#dV;A(GOKy+A??&WEdMhh;{oi5s^N5B zO`4lAw7WSXahU@_ST0p_t?n>5vRq(D3%7n}BkJy1%JZS6(amJTal?P5L(f?XGL~_~ zkjBSo)~M4a>^ar7g4OsiRpmK3;8?|);Ob<_m6km==iH>S{F)G-{*s1U?Fb+(?q2k^nD{U8+u*qx^Q%BtrQ176-4Q z@m3TEaFUQ`1Pu`dv9>XY#fC@N4|WF>T0TFiKH?eYDjyXC1W(r9lpZ~%O+Tsn zMu0Q>wfQN-AKH3Tg&DfB$ZtAh|L#qFm>Cm-(BM+U6kxob(A8 z*!r>dQF=Q4Bl<17-8%bekgSivO>)@76SxllvJ)^;iYSN0&AdTs{=-1IbFs39$U{qx z8|7#v>~WsH`zg2+yc#5Gr)O?iSFCw!n3m^!ea)E3!VvzO9# z+%R18KAm0y=Ci92(=zG`0c1lf0!5=DG6VyJY|D6hRNj`fADm(+6&!)8kpb2!zc#wC zQKhZn72=%G2{~0YgBH#(lXIY6TMIOSr;uBx5dpTs5%N$6o z?z=jsNHEOMpv+X0EZ2bBO(cIMu__B_b=%A@5QWdXLG%@h67e$t zkF027ZAB-sryfr+AEeA1vyLa+JSF5i%y@2aPw(8|A+!j4TV>NHZKSmDK5a|F*%yFa zm#y_T{s1x1GNss8HC_jH>JR9^6!FJ%<3h&MizgobkW0b0*gRrRD!8>6Ph!N&0`Xb5?fN{|^y0 zq+H_FGL4u#U%8)?j>k<`n84{gAsRnH9GHMO0d$u*YT=6xm@p@ia*|FV#lOL9VL46- z#X{)U5r^rw9><%>uEg|1?`NG39?vRQGHx7^Vxn@nBv2{T;K2y7um~y;0&hh{cRnpG z2_-G9grv|BIDhBBFP6mnw1HVHFqpE}9v}i{xPYOxMM5;#PXbL_76?p*} zc`ckcG)&c3Or&5Hutmacs6T({U{3Sn=;0_3p^o-KMc6qE?Tx>mpl-QffKXsy9Qu0( zfR$abe(yo?gS;bEGEL&D&LQtZq~+rv(^u{Q6mF@w4D0YB3=DXAdGnE6qyE5L6%rA^ zy%N+;`$5Bj3VIIw?XB?#1`Xr7oH5ETVO103+3YkwhO|B zqhDM^9eOti28Kd;hlR2q_-l8EWDC^~zwZb7d5r^NR{k3lY17YlWPm*%8BZShTwYzz!~iKaae~7pbn7fES&EZ2keVz2ZjRk!veNAAqW>G zhYnnx&`4C!(dLrK1Jn=MF-zD{5M&dp7mSt=E&?Gt~+m0KzSY2ZX~0 zMhyiVy5}PXN{?iVq@CaD5H^KUx`PJgZ+>cp{ zF=8(Zg7owB_OhUj)AjdHVdjqSZqExptUtOeh@uGiG@O(d~2 zWSGF$CkCp>Vxjd z4r554mwrs)O^IBL1Tw8Na@9yv`6Mq4unpcx=me;%3AcP|5gvs>=SDqy)TGeN8} z!J1~ypy>H=p^Q_vJ8>IaDW;-(6bx}8#E>npRkxNcG`l_2Oht`?k1%lfojl=HE7g^0 zH7Q|kD{VHFYQf-)L9s&9q|@;H+KJoXBf7`5i@?oMxId~lJY0d%=-Z8EIn?)s%w=RO zn9LX0Jbll&034g68zD@BQ`R)hkn>8TNp6HlLk)M>b^fpXYj|~>lvzD}Sw=N}x8r~h zP<%x>jk&i^VR7rQqzlTqD>wAZ7E*;gg;v~D!io}#RlKq2D*zT1y zl7e@v2Zp4aW3gCww(&i49VeLO6C9r@SJW8 z7bJ@=B(XpT&pa|0NSqgxa*g~gKrh5Gs-fQ4tGgr?RM=m?McUNgvkD?HqFwtZ3KvI(i9TdYG#DQ zl}TVMpW6PcR#c4B*DEJ<<0|>YT89N^5^{1m^IOyd)F139}JUm3sL!2bP*^RLOXm!7&<=G zsE7(<-1g!K#`x}wQ+`KE;UV_TUB0dGaj$|7*UdZJg)PN&0od7VBTvkEc&hC`0xG(~ zO_x8^{kW#>FS{nFX`2+@aq=d~{&@`=s1f)(Ws-gyAu71t7l~tOglE~p4GB|uRMZagP%mU_zn-l~diJjdWvr)^n9Il&2?coh>x zp^7;sstUy2i8YIwpWH6vR=?w(%zpJN0{op5W6TAu#caduNdkNWlAEC+JI`hE!9Csu zfGZmabS;^oxdd0&}u=@Hd0dj_t5;a!E^#197&{3n+rG$&6zaMs=U?>h>Dk!-fZY!YEI_d-EM5Sv_b!opFFqN&;RIeIntEZ4_ zJTO!a(m-`zo8E1_xG}r3`Zd~7u8^!Ls6=aUGSkZgiF~}CWDUQc3{8P^hjz}O=UA~)}nK|<94Pq z>?~EaJ4a@fkuqs9T4M*cTtJ%p=RiUEStd<*Qs&L~(oj?L%(#z^D#Lmz zr{m+C$ksXMZ{?7zg(mmuX&&>}V}9C_F1Byap+f$fH__`s(fhvY8yY(|;%KSE6j22n zU9y^4NE@_k+=CG&@6yaP&hupPhdP-h#Yk6pJ!>M5R^pzARI;QCHs!+eoUdx%T93op zD|Kl&YnhPSBS$S3n8Ha%0@1}@mnbj4vQu1#xf??q>7`d>5U<~tet`=evoXcl4$r>3(66i6NfEILvZ=?$I-e&41s{9|i7Fmj*9G2M;(=han3_zc zRa;UK{7^Pr4y~5=y~#}xHtU3|!b;mIt$}o(tE=>eaZ_yBDk0|;^ADlm%(xc(siRZ& z97T~S=7$tQ)dEB%m?ZFR<$9%T-jaBZdZtBI%OZS6cwK@~UR|j@n%jMp{ge1Y*alcG zlN~%aw~ADW=sHt&X?#w#%RD3e87m>5=({-~v(0N2sccL6qt27e&npdL?vH?1n)++B zLIs9BOwf<)T+b)VrZ5pg1q=(4oi~G=gTDLGv@*M}+^TO))Uy-aD2q-yN3`R#tT!M3 z!+wvLJ(WwR*i6=cB1C0L2X9TRh_r*XK=$d z@lc+a>wKLgz&kXz*H!P1s7v9=dG269ljyaif$(_TcK=mWWJ1yMmhK`6Z}YPkHpjet zz>W;GY`-7hV+0jSKbjO|5MViM^%}#9bB;>1hEq!SWpcPwIUTgs#TXfzYtt2c%g z4rjKcNJ;SAr#WC(r_$^I-p@s&QOjIRv|)1;UWecr?$%eoRnmWw>q7NJ5CKzvK*Hbt zIEg>1(k6_asxi8*!^Ca4-Vn0-Rx7GH@~B&nt{7$G8!J}7rbVH4$M1ElRCj{rwxtQ= z%>%7{!WE5P3p0Nw|Ip)qrE0l3jh*DIWoeMp>oOY;*I1Nm`eJfKWQn$<4wU-P zy82r^nOXGrsh|9V}3WD7A0n6J?4T2&#IUo7fpG!vrFcz z3gj47X=xUGKO-y2O!L4#ulu3b)*;CHSYO^{cT&zmcN`|IUa zmf-DzGneQ4^xd1LyqIhGgW;0#vWfCUd`Qr|;^ane;zn#*f9o2SLx;2_-q3VC)nj+n z+L%4Nc;fx|s%Tx+uzV^d3~5De!|I781f9w&yl-U^9IX*->vLoJoJ}V+aoM)=-fAKF zR{=j%ALbEh04XY$ZL;g82H>Ui7Dk|WlR^$p7vO4jYL~`^y;OIY(rz__$P{?vXpBj2 zo(MrcWXygU9V*y_HfbLFs3kExJiJ++eA7)9dt$X$`cPcqPxJ;KO!`nn!OGb#)QA#r zu3>T@^32Yy$i~#qZc4PCg8yggCZ}eUp4ZXFipi3iF--0(W@m>ZDk5vP3)|1aL-2em zb4-1tOGlVzh3cyxZot!(WcL$;T_Y)O+aJuVQ3l0)u?eR)QFdnX@SOx@8waAMPRWm^#`9u z>FFBqIxRXIB;+hdry1WlgZAcEovbgOBU5_$v%x$BbJ&yJB*@|nj~>eNK^uHHj?#as z9HX+&9w*!PQAn3Av)9%omv9q~C_IT=5sdUqHkyafK{ViZS=-(Fu}yFWFsI#$aDm4{ zq#PBtHe;Z5yC{3!Xt!0)+yiZ5cwvZn+cXV9b{5z`Iog(#wMO4S8FwG1c{_6q1fOQW z;TXZ-?Lv!Mo|f=Z{iiByG*9MVmpq@r)3{ZG)97+jIAF7N085`De+eVG&)TkPvIU!> zi>JTvY@KTGT@JTqFaCOJzt<1@&wt#}r*b|FRwcHHK;CBN;;9#qn450w;QOD$jEC*R z>x%IVgmJf!zEuYPNEc-bUAW}w_~tiIAX2#+ot;Fr)I}CIzL6MqwNo}X+Z>Wn2bm~; zWtNyosn*o%*WCVevR9x=+Mt_g@2Rxht3a=FJTk&GrDVmHCl*4_8ne=OBaw3LtOL`x zU7$=`E@84|&bf6>S&4$ClVw@wH9Sp72-sRXgw`Auws-%#T9+JI_}8Uv{oxu9zphP0 z4j2OZxFd@)e?NU+gskviMS$?0jvd#*7&9&K=;+jY-5)%jxaT}=L$(dAETToa*Za^? zXy;seGL@Qs=J%#MIcB(9*?2QVi&%^kl@^`81*(Bz=iPqujDstTFVdSF!nYv>1aEaP zCp1c{;qls_$1TbuTJ0(u&voK60DztQoY3zhCX23PS}2IEc%z<(&)Wgs9e|&|sAFKM z>}(`g^R)5wD#u2pI*eMvvykid$!(85UWbXhg>;I(_5DXRRbtew2z5g)8=adwQChAn zV`?3>EZhzqNn}kB8|Do%n`X&6o8vxnR5fR)-5(6U#}tVA9FUhIlngpEj8jeDMy+zy zYP6FdRv|iMvg=&)aOv~JTvnTMpzJimgte?a0e>I@IglhMV?*xcAEVIFgtfh9cv^3E zhxu)8bu3t^ehL^L4Hx%{a~xG^(gwg~R5!NiP|r_L^c6;Dpi~9iIs0CUKY?%?^P{y@ zwRggxp`{MNvuftO!HW&x$p3b?qPzH%X@ z$ci#exAAE5*4P;9O%bz?T~LCt&E}cal{6Q%6L-AcVsT04+!X=Hof8ON+d+~VU7|_0 z6dH*_4p<%SXHuAma))ods#WcHzr~OTxl#+kQq1o+-EF3bfMXlGW%$dLIn$rdL?p%I zmleB}5eCx>$7IIlkh(2&tiD4Cr6*KW&Q)gO2eh39r{@r1+8iRvT!d=3xVHMZD%ey8 zmd6YylFry)e@otilQAAsSK{Hz+<8_(V#zFv%W42TkEU2FHj!m??uuxhPsD}iu&W5J zR#^jZNZYxT$~^enWS+5;gd9VDDJAHJUe}Iu1lC^O^_f^AQk4dcwkJc1EHWFWD_It4 zq<3lriWh5QnM&!1c1LiPVKKi2xgayUy$qUrqFgDKM$!qh4zCI>{C#qKub2Xk>LfC@ z4n|%2PB5_wk{)%jO{;7p>@%re`p&z$$m>r{#Ls1xHD}bE#z$)%b?Jcg=xNO^56*I$NsAyh)yv zDbLsH)z6IJL)jQ}A?sM4h!-<6ChWJo|08lYWlhk>o(g>O8J2(C9tc_?Ay_R>{C>Lg z-1!$f0?AJAK&~UsXfkTs`>Df5vS3^P!tki-R5PF;?O3e*J`u3_&;$dqf?(aAw!qx7 zt!90?HQFNaltm%~8z=qDaOc&NtftuaLCHnF=RsjoZ1Di~2zrz6KIXHvQa2J+^%DR$CRo=}4zqB48%#H9}PXEP!#ipcvVfg8HL( zZ~iv;oGxv~s5l$1pz#{{LF5Q9KhUW$JF+6#UV-(VR%M5zam%80*=A;vquR9k$Wcu_ z(<8uZ+LUd&J~V_1zcqE4cOxE<+xS~?B-&Z?)#?(Qzw1E} zbX+iKhgJtZyvgw zOoaV7{jyTLZ0HB-M~K$VQ^)n@aN7-eB9^iibQ1RG5>7B0K7fNRp^OoWd^0+~%jXZ} z)U{lZ^0;)7?eJv^xzTCMbftRR6^0w$kzA?3J444!M{OHI@o>RNFa&Ywo&)wTBCz05 zk|uF^sK#acf;E%L1N_C)(@?y_ltyV1Z3@M!42?epeKuR9z*^xRRV@eMC2$yOFX7Iodu9ko4b1lCl=b8LO^`F1W@l$N=k8&lJ_P^QBGabt3=- zc2%2X{hGGeM%LmUCoA%JekcMaK82X;z#doFfggW?EX5m&&{6+h%rivkor_q#2g^ph zHEFX4pjldzho?g*%y=t5baNVALz8&9s6)C7Qo+z=ZZQ=peI&mPf1_~c+XK-{Z-K&Lx)2i|5Z%m2o>Lh4VWWJxvQW$tR68w}Q$Q5yt+3MPlF!8Z3kY+x! z%YOrD%>NCfu`>M!NMmRGzpMWQY5({d+yAqQxD{L}$r6(_$}dSQkXbObcb0T(i-rS^ zV-iWwwZtiqU~68Cn1G0oBAS4P0-k7;&4c^Id*qf3&kfQJrafu1q9;G;m?OhEh3`r$qx3(7Bf_e=;GWE$}jvq@lUU5 z1ud#qpJEr3_ZtpI&LtG6)g5>fglIE>h>ySz5(@2m1L>F&B(CYPwgsZp9wbR$t`-}k z0B&+^V`+OCA%^|rMidA(4850zn)>yzg^O<-`qBciJ_uxyde23Vd@!6q5{eHJq8@Uf z>jypHC>ft z3%K3o*~XW`NsrY|R#KH72$=7ZU#}Fqe+btC-UXaM2J-Yz83=P$-)v8m@(-gM%&glmq%SLrCU5&$PSY=%2MlgDPW33rvo9BfI&ZlLj)u^NKB%WC zw1{VL9!CF`%URN|GYO*?MSd^$eUq>HdD@OmhRt)d=69P$z=7k^6ZjyMu?fi~r0%}3NaV2p>^k}hq@A2~ikoTbcVQkkwrtLp2Z$E}_ zHGh6o^M7nb?yr$XZFweiA%5_?iV}GSKVrcH+OF*eF-rT8I)J`(6+v%xD=HwGn_XSs zb*oS|QR?6o{k?qmo^9@*b@VKyJ=sUE>6Sl(FTU2;fNGtbn;wS+CVvy&fqJzeYnsD9 zze}3{VUnXkh_(VDvAly?=~b)sKu{6D?IwJHf2Dwd18Z6QhzWoI(SG@o=o9!&yyAz4 z;`bV#U0%XGfONDHhrF;&!wa#itG9n+_67oJ(eUd*twMb3(%;~}(&c;x67Openm~Lb z28|*a-M|F+Wnbo9+x+x~#n=%Ve7D1V_aV*pM7O>HY0(dAKLZHgkerDeTtnKv&p&e? zf0k6^Ix47$?r*^Pn7{tz#zsRxc>43J!8XvxnWYH|s+~AzqXmZSHC>+y75M-0 zVPDv!(&bWqv5(TJs%G@^%fEKPtyU@TyViqbJEq;M|BqQW=GQI4}WGD6Oeaf z+SROQVTsjt)v71*2=U!QLPMzqi>icrj25`IVb{mIoxQR#Ff z1Q|PUXv5STNWeivK$;ZIStFF?1^K-s3sV^MSviE6V)mh?3ZFCdgD6%XPE=`7u`fJC zd+p=qIbr+Hovu&+ifJOM-%7<~pU0#+>OD#^Xw$=k91B-Fx==J}@Co@T%A>nItkd0z zld@|Z;}S!(P=8TC@tqwMZY*V~4xI{YR5uE&Il3e&3E$a= zJwN$^0TVGKUBaiOE?YRAvw<;-Zm!!HaQ9r%IHz=5w|gnk{V3bT=h%Pmck;$c=QF5# znZ@Qi!IoqZ#TX(~@+<{zlZF|s;QXs6wq(+a%YJreD69FPXw}Ox+(XKYrILVA3{wT9 z%tCzEHudc@hh1alu&c=8#GNX{a;H>!;?32{CXq_MdrHr=p=RoQC(Bo$}Iei1fNk1Ab8kfLYyPV6n@KgO|4yjAY!` zq~VG*8=_;DNc%;@yqLtL(si&#e`4;bw4eg4DD^P3@3YS$EW+G4vbk_3bG!oV>E-Qi z_*X`-D4QnLL&GC&DTO}T>pPIbnHW`o*jM(RTMivxeIw?BrO7L2N!)y@72rv7SU1^3 z@wd^aEEb$NYJR{30%P2UNhYJB*;j1g)E7MdFIZib&>Zek8n}h3ZKevRu+_eIJsqrK z*&UP`!eP598fKozw@td?{}wgW*^K&kcck zehovi2s2BIj+K%6r}^qfbba~tzYVpcIbWYEWr5H8IGZA#Nyk66l+ZLlG?1Rc?3=+R z#+VSfaU{lf-#-pfPh8|wWgeonmUh$@C#_~t#awuLFbdMX5C8NYFNVv6=Jl7UvZQR$ z?4W{CoPQ(M{ai&^BpPJwi+X4_3@yNvDr53)T$otW zA5WY~c87_1ZtX0&OgxM2TC%c;yEqD9+O|StO*{yf%b|ry2t0pP89qKgckILJxC?#PS0TIVXGV@?AtGZEs?oCKs?l z{WvwQkt&0|mig4<{^3J76Fm~5emv=E+%@fW`}Alju87nmC&81XH5<&4WcA@Mu}G6! z5VD#$kgJ@~;Nf?8Z#=p%lR@9MnoPbCGn!k!Y6r%kB`1YpK8H|kvmG_%o9%;e0mYDM z=r(}X;_PA(K?f!-x$1SWJdB31JdxbmZ8Mx9UD5GGJ9>Zj>t5q&u3zZjx42y@g0{a| z|4O5#D-%h!88yZC0yVHX!)K8I;;BN)HH3(?ioloKzY(27W$-)-%yrQiKHr_vu@}LF zw}rFIx}>#dcEoE+z7)gh*}S6Y;xjs??&R1dDuKA}HHLQYnoXW*P=cnZsxr*PAS)Z? z3p$$^_>gBc6{E}?-{ds+h-fc23vfEWLZkIPXp${UA@|4h)I9T>7*-habD&8%W<>L* ztQvYxREp|#E%0hiPhrX5(F;A#ojZ?dB^WM)&%?3g<|u_w%uU=yL`?L}?%82B+u%eJ;PDYgoETeN{^%h?&2iz4pM(4lCVp zL>m3Ha1#s4)$Yr*jo&^iNn=?aK(k3E!C%_naZR`Ky#lb_3h&ki< z@ULP5-nd;mefH}?sug*aqAY3d+P34clH*7h|1f`UB^R{wH_UAazP*|17JXqaxZ+}` zzR#&PA*y4T4o|rq|GM)VRcLXAl+ni(vo~z*KmwG=tv-eZ!tgRyRk`eE)Pmfk2Ki7x zN8&Mq?W}^LL_U=56pgb4?gLn;|B_U6?c^Smw-pkth0cT)Y*Gd^5MwYKXSnbz#=4xM zfqm9VBI4oaot&hzI%10PhTX)^5_Zf)$OO)0B9e1 zd?yoHV{9n;r4WCN&j_z%D`Hs$j#n^fKK$N!@FA~XSpIJ2IZDE{ z)lExZq%ZDj7_o>b9fY#fzp0c>EjDk{vKMyvNZnQUf{C-OPFPD-#ZhW8WmKJ^V`;_9 zStzbYAD*>hiA#7_jZRU9$>-?Fz8K{HXhMO;S$vz?DJu7L2YDj`^Eb|{#ms&H_vE11 zUwA^=Ze3#beNDZ~1aADYG@>;wXl5KR5;qm!Io@eD1t2}Uuhtb|lQy7?J|W=E<}k_-;I2VP?@@?(ua`BJ?tHbfM8W(fw6<4*0UzOMY*0_k~F(!B`e%P4scRSa2a%wR$ z^0Ac}m<2-{FN>{Fmu;qib%sTVm!PX^Q@)4Attb~U#NmZhK{t@&^XHYNMAuQQnrjv6 z5npYoq@P_keuT~>Q?@b7WTPgdyF3V{atGaU#+Kr$=i$-A2a0oW#)oXw8=}4*a|Wx9_oI zOf;?!{KJ(@XAen_lIUz8Pr26IBNJ>*w<=eJ=q}z9yk^?>YNZrm5s!}Q;l%M>YA@2l zgx&+7vKM!@LKk)a**L3Cuk?P)7C);C+h|CgsN(i+Bp0Ich-dTR5IcJ`+j)B$c(x{c zGI-Wv4*aUIDft|{KB!0TF@1k!`DFf>>uxuO%}tUY`LMMqs@0dT+u)Q0=c)2sr#e27 z8ybkEV?rZJb7Tn2{-o(@<}l1bp^I}&mF&(6FetSKQ%gfwnbx+91&@zd?Z(iu%fp;{teUC(vpYZtWsKUU# zyrJondLCqbgIgQMiYV?R0o3tsQhw5sVah9JWMGhqtInG8yzl)&tP3j=P@^qJP_MKb zo8`D75BmkInr95{TMYd0f>;=~mWz2UI^~V^Xpkw-YwvxJ|_E#=a1#)q6 zCrNm`j=i%huD@3q(Y3U(T0IoUI{rY(g6dQhBqf-WT%a~tZuVki_g{Gy zJc9pI1dPHmH&zDyDt2IPa4YX4Io6CLLAmBUqglu#>@lq{1ReUNy0w^i80rl6;t894 zSw@hR@i)a39C&+D2GVAx{?R2cINN-xBYvWh6O)cLU2@40Eu*`NXA*6MAMel4>vCUX zIFQG%<)3P;UE(?dPb`vRAKdT16EN>-=fO1-s8qxl_U+(=%{6sfg7~--UG6pd7Yr+6 z6Mlai%!Z=7N1*F-F05CIhxk{u(ZUBmmTSC@62e0z-wk;JG5=Z5ZaIF1J*~K0j_$Rk z^2Wf$#K0AMeKZZ0ju2!n2V`n=BK%ScbQ)WTZ@}-Qqhrc4C(vlBQD|&#$d|8L9uIHJ zn!#hv?aE)2wm(bBMH688;UEsq-2~ktUwjYp(LF6hxtTa5ezz(nN2FOja~c@bv2)5Q zGzYYt2Bk+IP7l$Gy#PO=eMcFPP2VNK3g!olgh#R18f_kTRz1^OTX)^AXXY3eEC<-n zwIqPlL^Uf$a;CzL9yXsZx!5!iYY*x09Q^)}wt32g_Hvk05e&W$RzV(s7YxKgeoKvO z(+cOY6xTtb%Av3&b?2PkhC6~oA%=f0Bjf3wg&cK7IDqOyR$AYGr)a?G&$6j*-$mC~Gyo;lVk(#5l<2P-Jgo>`Ir4=ylp`b6zwlY zBG~cAFa@1zqGCI{o@Zi>6TuT8;K}aN9m7CRWQi(DMfwk2r3AmC47E{mlPRz#aVJd| z&dTgt`VgsKk#@!%HXFt#vt2E7e^GxnG0fQs&SHY*rb6!3R6MY+qiN*yZ6<@e>q6{b zv1EHxUOi<&mQ(-wS4pL7ZY3s3J4@xbSiWct_{b!JZuk?iVp88`?X(~D)0m|hO`OsR z^+8IGGZIRLc&lve(fl6fu-OtolO%Z-rdIOC3=%^a0Qg&^4{Tl0&<^klfsvk(OCq(_ zV47opogmYAt^*L|#M+iI`O-A2Ate@UX7IQHJsC6j`AYC2+lVx?Qu-)C1NQNBTj*Xw z%2sdxBGYu`BD?KPi#Dv$y407&C2t;1e{*zq#X*}ToysFz?MkGSpw1ptf=1l@CCqK0 zt1y!e1s*#MDXAbEdJdG`bWueR?9v-AwscHxEXZjA`JK!0W%v-V`$6pg`8pE(enE^L zeYx~XYFlo(y{!N}%zWM!Y}Aue<#yB6!1758uFVFJ3Hed!TXNAxyu!u%`6DP`B!ZKu zt1aLt3n#+2ZW=s3<(}6W)ina%WM+YUEw!Eeh@sHIDoUjumDVRC=WVs z7yU+Z|A!oBx;6hb!%)gP@tPbpo&L!b;c){CkS^%5?d-6EG=0#C{#4S(gWy|@@ruGc zLBxnCQ<~Ze7rRQpJiT9_5?&uIRE71bv8h@YDEa4CYK3MtOqzakXQ822&Aw?~(f&`- z?Z9wZhn0|x1ar*KFU8p{E<*k3jK(QUH;N{sw;cM zHn`^6R{KMIo8Li4k|pk4l?#UfLh0);Ryq=Bnndj6at6I_c4xPhv>!k%Izc<6(H7Da zDh}`_JGNrFC?9xoOcPh|7j_y7_HlbDJ}57wh8-^oMw4KDRLsOMn94~h{)rfPLsD61 zJpTrZOmdUk9@MX=T>_LBQpxck?ssDAxG1gfu%IG03O`gkfp?{~dMr6kf<>E^wpuXR zl|+)BKjxBItaI^6rwxt}5z>)lD~4B(h)1xIk=W{|2VTK(!&QBYXPF@KsmK7L9vW9H z$FA2Z7st+O`DrgwI^e#BOb*|BBZ3|EqSnJ8sD*oC|HIfhMTru$S+;E3wr$(CZQC|) z*|u$0-Lh@lw)*zN%=E1FKlEe1M&`e{>sa5_S=ohozGTUZOadBPsH%Ask&B&8wUYI1c7CCNt!$3v=px)-F9=pAt`@2VoKwxdKo&l%wy?NVs={wwJZnPF zV89=z{qsrJf?11FC(e4Z*C`e^szPfDJqrwPLz9<9ySme@FB;`r7(FJV!&nBKELut;}nJ^1`_=ZYUpCS?t9xTU<| zMr7IZD0f;*OdoDniT^!Kp_W&1#QUgYcVl=vrq|qL-BE<~f-T81&d0F0sorgw z@#kmXqJ3uhg@bGw1*xPSa>_39SwVrwEsK4Y9Q;$m}x zj;ZfTL)4P>Pagj2xd6liE*KqPq{$KA8J>xR2esfOU`%!h72oV~B$Uyhn;m%K zo?XDRXX)MWQf@zlW+X>YieT`^ztM%#v1c?7GVS5;_M#KM;<^173(V#|sO9#qbeRL= z#k=?U8AvN$XMhqlOvde6y4l%yWHOwq$ZKe%Vypx+R$V=Rjva5RVR&3Mt(17l!-STfo=WVc)nCKi7R2-tI*^eH+IwpT57^8PU2q|=Qzgj#F=R&>H@?B>I z)8gPK1fG@_iVzor-tRG+)a0)2)aPY9^R7K+S4krn1emQWXN~WRVs~$j_zFu@xYi>1 zZ;u=HB2&o3R%uMH2}YRzK=(&l9z3R*MPn&8fIG$5eQkp|Z@u%qNA{lYTa@1D zo01j&#c5kOB=oShufp~>mv*hoxNcs@&=zGau3%REbE!)mHUCAxv$Sk#G_4vlo$+3| zfFVitvjGFV8DuM#auBV(G5Zu*l$zy;krY0}jy%g}XE`Ms=GS6~(_b|g>~MV6R+!4# zb;ikzSiRJRd``n$f~k8*E z@ej zwOboa$O};{!=1hctKye+@_tr*Zo$<6ReLvu8rei=DAmc`9)HN3ez`P>fr~yZ9swi` zu=wsc93YwLiuWu!P_y{Zd)ro=b@7LKVUOGILuJHxX_f&3`e;d#o7-k|ig&b=50P7t z4(cRq|FlmLw@$qU(s7iF2r`34_L1Z2nmCWWIb`^%1L#neuFLBU-JrJXGMx{Eky)wb z^-Cnf;lnNArug98k{0tVF48~7H#HPyL*99Fi~<6!DGI{HL;$CbzeT-bChHOL7Jqyc z@=Vkw8GK(5y%4}TWMzo4{z|qeMw0LfnF-rM%i(-8!E$)C8OLnf)_XTSGxey7{9xx0 zeZ(MZl^8nB_9=)fAEUZ1g$Xkt!YR9bW6$0{f?Rk^wJ|J>D4Pz^eTT|22 z;qG0ATosjL(N(5TVw1I%nmcB4pdNqUG&trqywDFZ@aYYut44~l&61Y0E0Hv0?BkNM zh9$Z%8NDn?n*3eT-OUSxrdja(kqA*>XpK|m0qIzH{ozWd>k_^2 zV9V4C>HZ!FfgD}*@k4o%lNg^#7cvP>0Q~Yxk8~itbn)jxdu|vpdj4#`$aT_hn*!9k zG-otOfBlMHKHCW>bmydaA<>RQKPi<^Ro{?~Pv)X_1zw?CiGhb(_Awq4b+p3m+i`i~ zBX&wSvyn(S!w)nE2u_1#uQBi1rZl)`4DHXrk7wX$dk5k)4S9=zRH{Ari;0=r$M5%W zV--kA$Mw87PB{arwz{#s>78{1U>s&rBU9ln1H!z1VNsBrfn+1n2&vPq*{*J;Z;%$( zhJk_xrpgq!wxQ%}ER)-`*IJ$Iq$56#74&v?kr%BB3VU#w+w_|HwY?_aP27WQQBj%m z(f62~U?uhJwMHXd@U$-KUE(o=ofwXj9)(yq#$!fZN+JCUb$yONh(E8at6 zf!|j8?G1`E;*3J5l2d3o* zT3f|zxKL&U>>7jD##QlzanIRb){MgXdD(w+?dj}ulxe%z_!^^mFslSsfT08G?B`r4$N}}-k_}$eFvx7tz z6z?jbJD+zZ&z@<(XEq`-xBo7f4Ttg&FMas&Otcz|sKS{i>+X~okHx@n*`vHlc(z8& zj)q93Q={F-p7Rt_1Um-H49+S)3!goE$_fPExJfq0poIkZ6mPf+t{2imaSWVFJzO~N zjYDRE1X2P+y=Pu1Gk!q9EdGrLA9v*e^Zuj!VYLU#HGGnSXXIGHb%K>g7+SFGQBUZ` z#nE`PnT~~2y!(gPZ6Cxw=E0h%lX(uI6Oc{$qssM=?eL8iBLjlT7VVH6dylqCCp#?V z_0-OhRY}8Ez6OC))0*ccr-Z_6NO-&I87Ae$nbS|t#s34DUhS${3Ou22khGxzKC;)LWEGP|f%k+zXpt6_T z;*)1w`31|$GB>L^H~)B{6Nm&h(tH1zeGa` zRoIuIPzflcZE!h|!4lUof=VV@3Ez!;u4pSg{wMp%kb_xqe;ub#_XZcltDr-XXUbY@ zD~he>88|_NIlm4B-5^e-!Ian}5R-5V&|K^a2A9>p=fY^wb?!Zo0!Au&Jv0qGQA6Fe5zFH!-u+0-0~f_~x>|hM=XF_eX?x34Q-u9(@Vqx2 z4EZEUR8jxrXm8f;dcN!X@ARS2>Mbkc&p?EGm`H&8sjxTgA1Pe-CiLgvsmhMF2#qd3 zV|aGkp==SawZX=$t+3W{Ww>akXKR~{X-><1SRN!EF|#LO63Ue2fE*+g?s6pDX-G~! zdS#;=-(m~=?gQ@^m8=eXh)0`c>50x_H`AiJmlE1On|hA6`WLBuk&JyOwz`l`P{+(srg&y06@_XnVqgW~>Aa1+~qf}2>F{%^DT zfA_5aKWD)Igqzq|S^oEy05@84L&%(&H1hFk>A9|AFGIQU-SxoY3TNeGpT342O~K!HsD$ci_O0I2okI8bw_U={^`7+5IVm?oA-ac}k_ z21?&Qk^7Tk6A!3tsv%1H9U!(h2tM@EBxM`Y1Fap75st!vG}!Oi4(GO8^+y0j97IC?2T0 z8{(<2+7O?hN8AwhPNSSa*Nn3QK>M!^*U&5Qv92J24Yqg<0R4V9?`}~kAwU8K2{8h2 zrvT$f{(((sVe7w|#_+qiH?Z|UMlIk#0RFtc?_L2Z=qRBs_wV69pFW~A$*L+cvYW^w1ojBY)*-1Aj9$bg)owf}hRGNI>IL0mSowT=LC5YX>r7%qJT^UH^TvFZCJ$dKG@ z-(w{aA;no8BXY_gkbv#&0ls2^>P!(*5&%DfD;^=koxV^Q1Vphy1`Tw8)=_`}-ie&2 z)dr~v01*{`!9H~Y$bbl3x1oBaU+h6Lw7`yjzv&Hs2E_n~!68s!_hGbq=udS~1bBCM zn)fz``s1ITA7AKxgB=El^D7i6qSwC_Cz6wvDMU?aa~BNz2Ts~1-JziaUtMLyJ1aSw@#spdPK+Fty!y#6ArGIkaNM{CZTaO{ zaJMB3M16BU(hLSAjV(m=ojE3Ku8362q^)`lFJFzYJ$95$umS*jILb|BOvXm2&Ks@w zg|urOsf@sAD@%^6+cgWkF|4vX`Uj#zhjPhUM(Hy?y&A)&FjKRyrahOE$lMfjH?_$$ z@I|JDkIP20m@-$Uh4NzyRsx526p}d9eNvI922?^J_cVLNR%8M+G&+v<837OijM0nv zL_9$3^SZ?H`zvwEp+eCUgNj1)!Ty_y*25bx$Et(ADp=)r^Fje zXhRF#tbZ#$oSeX;9r!fTh)6s4WBu!%f%xdhODQe<78Kv+TMmR%(h*~gx2xtPDGRH+ zQjwtQl&V`?7oV#qtn~6p_37-=CzV8FT6>crrm;+}d<#KqX*7yauh{P-60rd$gN zwH6E(H#c7|HJ17j6XDl*5?6q)!8ug#CAJ)Zw9|~d*e2>heXuP~IY*HVRx;Uw^1Iwd zaP(qq0e1hZu)1-r>wy%8SE8G22}oLgAE=ZvNAD}kcyt> zn7?^Pw6GkX>Knf$5-n&t6y))IN>LZ)P0#E++5X}gK${cd*P1QpuTF6 z^@8e^Gn(s?$>_1ySM^a8CnIN5ZP&#zm2zCpsT_}j@Ww0q zi+6Vo@*631@UCUv{Lfn6gazW|DO=fWqgSzFpk*ULcNcG2?ryowR2rlKizIT~P!+j<;VV$;>t*iDY4xqLF>`##nmT=pnpa5T zO6{KR(flYoH`rj}<5>4ZYOb1xBv;z;FQQ8m7=TD;(TX05^PXGG7t}wojC>@IAK2&* z)0_%@+QePargBC2+G9lBp*e6_B^V&*mM;s!*o|}XsWgU}MNi^s@T2{;n5RE!%u`V) zlnQdFyOYcRHGq(o_iyCdCeO)>oJ38e(%wOzi3dWaA~&v38+=3JEPMBkNxT=J+Rg67 z|F+0YFRGt->J=Z>S(c>IN_P@Aph#Ptsb)$g_DX%k99IL}Mo;7JKp}Aa`Z+)KgD}m7 zuR~oWIoP`)X@pGh@#{L>WrOnPU>UH*0C5?LgNeYWc&TcNr)cycx9wPGP5$1`lA1QS zA-B8_z{YWZkxIrRK4Q-=^Hv8OL^ITn)`bccoJZc6$e&Xlt_cO+`XiQFt$I)7m!9dV z@Q_3K*-qfdXKvY;d>@^B>E)=?s>H8XR>EH_MOV1o@SDN!OP7U{W2Swem6o#rh2{ZU^}v96 z*eg);Y+=PGL!@(JYQVR?R80Qch%4`ue`+zw-sEySF~k3d2tu8AekAy9dLY5Swh(ai zbX4y=q+AS_=#PT;P%I5??%M3N4)LzWo=aH!cHsNvB^DQQE^_SX{%8+xse5|OW*pm) zAjpb9kP{T*J3Jp2_fKN<@aq>-BmM5k7%QXS@b^`j*uapuFgyqxM1_O{?^VV5So#tE z=_=QrRdd1&AH@Mr2kD5^0th`^$&ICvfvy~joMNa?{ z$;6YkwVMO#jzebL!4?4@lzQ=LDZXC)%yqG8B)X{{#uwwH69qht*IqP|#X4U{x|M}3 z2%i7i-PtdtwX3S0Lu^R{pP;j(`>~EZWM5$;S7hs_>qU2`;A;Pg-A_{H2}Cqyy{2zS zR^Q8#b;Y49>jBe?^xja_9I9GJoFU#!Kx3XT@!!nh)bH7IxN>e|OlL~4P5Tg1H^F9e z7!_@4c<%_!iL77<6EtY>L2NY33Jy;r`R=hAcyM1}1*TW{Vt*Ko#=_;BqjJ~LiQ5nV ziSvlRteMQeB)z_@32uffvrePGE)FBcEZ@=R0}E&g&6t(twn`f`%N=eEU>iupMs`vHiV4@^70gN|P#Hw7%g5$!^M+XS5RU|wB4HG*3nuXa^miFIQ?9HS*ANy$z6x%l5(_aIs z7H7+WPY>shW}Imj7;H4c$qB@f?z&u@aYcUG2rKA2uN7CmKL@P5Hh7FCw0~f#h-mgJ z>r@rlsG+O7M+$UIzrLk+@x=7L&fGp(6dwYhQBH66_|9bYCk^mO&U4X=?pAl`=%z@I9pPa2StQ}p%>l*?@PLU zEJ)-+NZ~|{3 zuNc~FrTJfoH};|Bs98~h2;5jl;i}cA2x#K$xx;J$C1kZ@@gfy`jg@`?zUp9eXRZ4~ z)FktyWiGew9dybiMd6;^ZVXD4&Hl3MnwUo`s<{c_%8^n>*YX;7ccS^s^QUVYRmhE3 z)#K50cinJX>|cAZye*-g1RfEJ@{^En<&c}A;i@uV;p1WK%qPUtXG{!y9s>J;_MCb0 zV3@6w-)d2*()oE>W=4AFu`HRSsZuZ(BvAGsT{Q{OIzM?r8xQ@~H1g%n#7o?Ieq?Jq4fnMBl1oa& zxv1d)1jf)iyXtMDlzN? z?7@7^R%Y@~eo_znZo@vh2G5;ld2~hWrSL_{FR1-Tw_kg+8dx=p>aQsHvN(6(9sXQs zAjD(dnfwHMGbXW~ui9e+5!GsP_q0Q2O83pSlspI4-H-O|pHtxm=~aaTH{eHVXkS;8 zn=dxOK)KJoIVoSfpeL3RlHv5^69H$VxrF$}fUd87^E5*2h0Ev)P{56>FqeA1aeH0L z64JB`{8}|1cqJkU5_uWjD&4jVdwMZkr(Rv$6bx;Ms+Qhq{(l=c>BfUXv;+S+a%3+IhoxLF!J29SL;8ZH^ z9vhMQG`&9ysx7!m#n=OzhZacRwYJD|PS1dxud52kmfUI!jYdsVfQ#z&g`^CAYQi{U zcuE6|Tdh6@{p>q~mpHW(grXO6IRx6Lsz+R(I^8)7yIcwS-L?K9U)E+G)lwIoWtL3x zK#qsldLi`{&py#~fx$fIPN|~~+Ol(7Zcr9QGRed%UgUIx;%!t9p2P22>m72#l+W-| zlu1&sOhAHF>QpS*q<~1^X_P$W^7!4nU+ZzR2 zdWa-Vu*)q0=&xFtZSPf*aIVm}$tm6>!Q?~ykUbT2r;?kHUNVPbK!ia=Z!YLTpgO#7 z)Ma7uC2Mvb5q_zKkD(8}PJzB6knU zKWUK*+vOkwrcmN&$Lag9W$x-@Gqb#C^k_D8(^acUxhhuG@sNjhpQU%Yj3^u9R?@#} z`hRdF0>wI>A^ol*w3ZdcQOh5PMe(QrA5gW{En< zUV|5ee`J4=rt*I)N{pqx%8u<|{2$Wlo{csAY>@L^VA(E zO+C^LnJ_t+nxU_~q62BI!|1QJkzF&%+GYsN;I+6u9?z@#`>k|1dAE;PD9214!8}&i z8&B|SZ7{0v*M#zsufdEC$9hu@hM$>oDz2kkl98VPrp;Nk7iPE<;b;p>^0K*oXbMbc zfvv}gySQ{c-dLp%M1i8k`^~x9>5)n`A|A_dm|2&lWpzHbhY=E0_Me&2od4OX)`p^PG(e-_oPFFvB!A@_CH@nPHGxiZ08KlhV()g zt-~>TUVcEw3iApZq-g&-iaz~aX#Tmhs&KrwVPsf*CO=GtaHwB%My#bD#u4V`U#QVGf#eHfCTu#_n zE>34xWHoxbw2AUw7KLCiUqkjGu5?p5y7p#$vH6AgS%sPXeLVo%{%o1cDRFlN{mS5* zFvw!fjNry^OYCx!;fxcz#fL_a+Y+Dm+yUWvM0tGi`dEp!A;3B*EKI4qrf@9TF+=MY z(!?*L!7%Xs@Uc!Q6YwXy;YCf^a0l1-t+}f_EHnLVh-SgBE9Q{_mvSoC2N|9|XZVP9 zqLMN(5@XusX`I`Ot5REd&)4?Fm6Z|DtQh4B!JDJ&iu8+ve=AHf0U;o4NuGji>EJEe z_KH8Nr%`ls)MhNoxl(SjJA{S&dbT1^KSy7mc0@)4*5WC4G0xQmKWEw_YmukwYsyda%^O~G#oC(s z`Q^S_U&Ck6in_3Jaxjjpr|LM!?nVRpL)oM1fmtG4TaX7^VOoWU6At+SW=YDK0`ccd zu_r>3y_@1!S_9y#Z4qe>kD!bV!O$o@IG!m=+CK;GzWV5ni3#1R5+M=0V_P5Pgu_*Or?*)4*m=k0f=)#;+c<4<%Fz!sU{$Cg@CnrkayVAk2S8$Fgp z`YuM(2TBpfsY$;^O|}Q1ozogrNL%N{+X<%ZZZG$YWjCZGUHYBJVl-t8YzG|Mr>*63 zV{W}z%evy5`a0W`UQ?T1kJ;jrOZkdMG*|5rG>ck8$msHm1+ChGd+Vwh@E;D!FXLuu z_#`~oN5(lic@`do9NUwf6x<5vw$7L_E#*BgX2 zj&86@$zKHT++W>1;^E1mWXjd?k=(B2fL^b<_NHu~p}Zqj{wJ!ch_%eOEiNoOs7?`7|D6{Q1rr58S*xhP^aT$4rKF#$_RHJ%qZD_HchN5w`m1@$fLN$k%7-6v zM*6&jJum!&k%W-!4`pdpiBu2OR!bX+$S;z+4>W??T1l{Vq*Hucx+RUxpA}o2C+kIv zo{PwBZZ`TM7LkXN0p1Oy_1(T&R!{Bh0r@+piH---2_>24K#$Gw`xEB`+Tlv?3(u2f zrD3!0*9{1r5{xOy=3ClZVSRhK<-=4RM7S5*b1e!movdy%j{ecq5}o5QCS@nAnm5x( z6EUlRX}gdOFnv=7&FZI>ha)NDi{cbvi3q#++jS#iXZIQE5s*Q7n1V^5qLp*yG^wyl zGEz`qPhx$-2-Cw}K|k`ULA&zxN0TJRJhcxT%G`^%#wl_~^Y%zNF)T`!hAn9-r{jdm zKp%>lxUhKkZAhGWeM=ILsH&Z%E@?L@SyLE+$Z`x~QjuUrOHNu;`ideC7Ji*LT_QPr z#xO*9{18?<QgLD;&3*3J|IzojDBBN@{ds20Erdb3paf4NHm_ z(D3P*+7z-fXe@BK&!(7HE?BM~y5omyY``K2Bxgw;em>~vc9xjT=N@7G1IN5xoUNi5 z;)eD#5HQLTxApxDf^{26F@}YU!5fj3vY<&DsoV8XM^^=NFT|+Trme=%+M=W7rzLb& z?ZT%LxaOsAgb0R(P^L0!M}EPr$TIl2HX{WAAq+4~NxlpF0?-gcKLYdLIa(woAgMAXD%>Cm_cVg-oCOGqyI8Lo z&%Vc>U#;Ihvl{c<&yCfc*PT~iU3l=URJy!o)CHu{0FnGRfiEB=08Lk2V#R=f0EE7P z00Knta6Fu2fKO<$gSqgI_Q3>*$Y0Svu7QFI7BX-_LXS%c5CKtHzyKs50Fe>_BBUT7 z06{=N2mZ(jbVvZ45!_o)`7`hefuj+LU?YhCY2m*_Z~%C<+b{8T&@E#h0^0ilEcyZALJ4)|G3_9z z)1d)+I0e)-Ve`*Hgue)@z6rO$zg*b>5ctpXocv9HsX)ZPOVw7INFKk-x1s)wg8PH$^KgmukdFDOkfW9hc%aa3G^n!>DWD# z`wI*4tqSHN`4~~HQ9@iC1L#=lsfwSo9U3Nz&y9XBFRMkIfER(!pSF4*g8EWlSfhgz zFppqw#*V?XqmRNO;*38X76$a6^dmX~A{x+O1|Xe$3GJ<_J2wsa${pbeT1;`A_z51;McvC~pr+-3vicNf z^1mbRt3Ck`?{EH7d#AsP=8_uF?>{{E6SPs(hhJ-<`vW&H_wxSQ`v5_)aFI3(GVrgW zJ{tOOv;+VxxgZ0^9c6ik`4{wCuOJ1e zSp*+L>(XENEH;n8JGg*QoMUkM8D9Vaww*J7PwuSN&+yj@@#5qlXy&Je#O2q& z&fg#1fI%K3*}@73()Vtw_Q3PoGlQiFe0Kw2XHe-dTB9h=fg#G7XmeBzmS6Qgx+x}9 zl~GqeapmZ9F2PY>EZ6=tIJcDcT<|ecN|OTSJq|SkxR;$5eUz4s0gaj@c>0gULNw~b zH;3)XCK?$B*{dFA%r6Y0E$Rk^=4_9Z%QgerE+7Zc!|d1^5~kw(LPjjNMuM2lm2|lt zv2r5@6nc^gJMS^Mu)0RVUHUE4v*HuF9yJ*wWskG-_IVDjq>#A1>ZX)vlrZIaMYrl2 z)8|3gS;gUks+A5ShiSig<1Mn$?c6D6nA40gw^~eKdit92#yKbsAgGL+@4}tKln46s zCY7+N>of6pQ1&+bx}TT#zNxbW+*YOgy!2d%fncZT{;iJL0`W@>#C9!kXK#-h-Fmg>ki;o)i8fYd8e%jyEoFn8YvSENS@i~~K?mZY?*kuD!e-zL-2?x58zSVeTEy%f`jy};h23o zO+}VIRRw5$Un28*jE8;lm!? ziw+mr2+NGAS7G6EQqXJa%pG4Si2-6K&D?H@#twj(yu;f)4b?-)*ScHVv<_1Il5HNU zy^Znv!u*&|l@10kKoj>3*l~yJbXQC$^W~Ht0VlsgylWhaB*q)#^O%8X4V4Og!=+j7 zp6Qw;Wlz5g7)b*ezonS%4}+jTtYmDvH^^$kn?`I6=#)n_tgr3ey2T(0KQM;z4JIOe zI;LuQqNj9oFG2n zA7naDSqSsBp7pFWincUfrQLFKTZ?AESXM7`*HyROoCW1DE^UMmPi6(*xrd@K+iOj6 zbs?lvU?TQZ2>}Aqsx_sr%qu-K3zupzHlV8O+@QWv%KFdW|Lh^?xml| z1vg~aW(DDdU*hidbhQN>H*@k=kM7EL3nQ=i#X@82p>)`C&^|?!AxS*w^5|F+b{`CU z2&g>d{07@cK{{J{v0jX5%`rEM=Sd|oI88_yimuBmOXrd^R6H@0^xm-B2ko@8zSs`||j~c)AJi~z@}!&t%K)A~UsIIi_A|IqO0E&A1@ETdl$nD%n#H=>@_gI}BP)K#9i&ow)lfFS z2;Tv30OU#8)N%1tDl!s4%18Ucdyg;4YQ!s3(N$oPP+Hj&xSW40fTRxS?CdSVJ#4|u zoza4)B1GcBArtiEY(oU6@Px^4KB0X)>&rI^x1B1F(`=Y`QQwF!6KLaBZHDvbmmfik zyuqD1SgIYL;zv^LRfG8_o{6}_h41~h+MPHdEX6^p54=|}w4#Yh(NXhY8{jw;VcU7Y z1I?bsss5G{;V`3RzMsl|;rZz!_7LUNMyC!PDrTWSugp&>?#y%^ybC#$en}8)DKevAM>7?JAqz1`^K45z^@{b z&olXzb>-u*65-0lD3^)!%;KILy84^65T)3?tf;kkI7#aAC~ur~z3Q_y<&oOs8N`f$ zTujd^pmmw;M{E-1WH9NS3*XTF1}F@SlXb2c*CAUpa7Gx+OuKugkFJB%orXX&x+t&Q zpeTA>RN@~~zi2X^Wb;_>!{(LuJ%1#j0{b@yNN0BP?4KJ&s134Z8a z#ivHmcLEs>j!Dlh0<*uAJ#r|%Mj0N;=LSn|K{xG@$RiL2RqU7AE}6WV$d`W(D&$KtIl$n29#`R zHLtqLYzMNO>(tXNw+WYgtB(UuMTSxE@%z5W7GSZ~ZCPf0)fI(tqOZXgEe$#!3e!bh zk|ivDQjh+Ch4&bfz@!VQ!EcU94IVk|HB%@*&NX&p|L&3PeO5=b|9qv}w>3T}1A`Fi zXuf@Z1T8*eff!JBAh$SEZ}7FLz|JG!K>Ekkru7c4CW3JF*FlFpZe68kP3R}3zDFc9 zkKDifVB$O!J0kIe6^~Qk86VfdIo3Pgn8hZOg^@sLMw`ZR>)2_6{;I4>9&UEh-|6iG z1rE#P#5vBM$;=y@j9zPF=W@zF#U4{hmk`=TiZ>KDCp0akoC9ZMSH$@>R%$5a64I{1 zM&53Q&_=SxhU&dEV6TUvfpX+XB8E*pqjqfZNzSC&siBWGWBXtuUi8zmNaGT2i3KYW z4cTyq6<5joK6~TN-Z|1ncMFsTCAJx}M?-1n1RaK9LgDAdEY?gC2$LRPYUVs?4m9C3 z9)nfL+77kBjX&)W4_3u_W=n#EUM_JQemg1me|!f}yU{3=32bB%(UCzvN3O@+YaDzp zR|3^(wB0`6Z_3X+jF_MvJ**7cEeql@_ztmlLozRqxN8z!YrIiyj__s{v$4?LY+XY1 z9l8)^h~mh0G-_QQPp9&JfF+4k##$m<`kU2(C*d(1f42UH5QU-9=Z9y`#OkP#tTPo9 zx<$I~7W8GnJ>VjVcyP;lAdUd_{Cum-FIn(dI;p1A_bUA0zCTDlv%& z3mt3m5PAQl`_WdPd23vht?$HK3wqomvGKFIicvBVmKPASbMq03<=wckJ}?YmmpV# z4Cu&S;cAvCRBK8SJJFR(U)<_Q_v@Z1C1iD7MP zzF5a|Xw2vBG3^z22&5Hp_3QJG??7=*5B`?%O2wJ?7|>-rNJ}&*L_CGFo6V)s?8U!t zir+4V``~)n-DY%ViUgihT~Y`2?-VtdTk4^+L@5lk_*=lt{=6Kt-#k(s>|#K6DQbPa zo2?8ns$A9471o=b$=S+?`XCPR)y^kL!Z3`Or#u=}*|l&wocJI4Kd9lP^?aLiUs2UU zp2bA+i2sac`;m z^bp(Io2t9=y^usy`Bg*uN%H0wWFt-uiKz`8M3_$-g>06jlNrr zq13^FUs(~v(|(Ymf|yl~z^&lh{5dFfVVdy+6*rKh6$z-;~ThIp)sGVyfjmwjcjmLGnV z9`#sD>1$i4oo6KsOY~aFws^ z-sT%4+m5+|ddEK9okp)ehIolvDB2JGd*->)iXW~T$3xB+e4a>yaFDE$?3wmXA(s=- zWk9iz$AbKACYs!f>OEy$nQYLbqTz8sg{7MyTk0+tGBj3I8ijs-c{h7;CpAfTJwESv z11QN6MCAr9vG-VmV5o0hi0>C>y`F|kvH)#snGbG?7LN_e$?VJuQC|dDe^aav(W`z; ztzyLT>I#!jzXm5Vtm?N+xC^IkB3OKgvTa)MfH{sur8n`!xt!(cdvWw$=FV_|EZC+k z7!{^TUcbKK?AaKUwzuSaoy{xA#X_S-4X!%H!up@|{AJ zSbqp7S=SARHnXnDuZJ_~rn0Pk5PeQR?G;5b=H%ki1i{w0;ze4TDT6LoL+X_HF80Kb zD)l3HCT-J=Fds)C3ZQFon1}YgmKwhlgY`h=&JjC*n^;bu?}~0d&Ic=5?Z5`+LDsvF z3U!@+pW7F`HC1|}Ss}6ZxRXDBNVWk4y)NG3#iaxbmUxuW?bVD{AOc8!`mrbF#?=h? zf^j7#@}T5r%tESeL3Q=}G;=|(`nOX;Lc?%fDJXwQ53kR+Ucu{6nT@}4O8MWt7$;D{ z;UurJ);;P6ZcMU9GeA`G$}%Zfot#^^VyIQF{WCoc@&p|Nou!#}t=8!1OUq9S&c|E| zBUQXL9TA^b4)!bmqyj4#M6&bxTVI+M4_927uDDip_O!He@M_kSmNyyBSyhud#*Y=hsikQS|Cg)6Kr9vcsgR;r;?sk!T0$UDeItVz~!IwV#o0hYojBqWrS)@om(1KK4sK+ ztDe1F2^bA|*3Axz8c?_)MdIfbagrqK%G{SqQv)z7ny0>!VO%i)94#C2L3FUO)6z(< zH9%=3s971?x6RCoyrl)i;a(hB4of{b+#YjH%_RP+eW5RH z|1ZkUAx5-l-PYx*UAAr8wr$(CZQHhO+r}>2w*B_G$-Bu*PUm%2>(5$QotZi37~dG= z843+~=WUO8B%wnyY-R*cDJ8uKb5Rj}8>&m8({IwNso9lVoV9yd)mts@#~QVCuT9}d zR3n2HdFc_a==R=KJ>D4uvPp8l+Rgz{6?(P#Ywd{(@$=1II`QxWNco(PMLcBF%~QT9 zeb%?h&JpVbtM!U#od=hW--|~S>--OGcpKRUA_>+@@on3oB;^NBOQAwYY04_3Ir*AS z`xh0kIdsFk9Cd5zVI0BaC+2S!LEot1q;JNa9(k{AGi6)V-9HO|@_Hc+|Cm4iVrqZN z>pU6lDVw(qU9R*r5NHsrsz9qn`1VQng}N5_+R}mSNcF%O4!R_-iB$av;&>AN3s{A; z<;pIJ+d&joU2QbEPepXee)Qt^b2jSrBPwh zwsY2GIRG!cMNH;(U?6KD<@NAK{e&1q35c>x%I|DH6t8(>_xt|*&%Kg$l%Xu~HlSKx zk9-g^uJLpMFC<%r$*Z^U!w8c~HdrC(9$UfK^5Rf$ih5-CqbFm676#`fIMP6|VCG@i zA{ApEwx*c(iVn_=JS=WtZxoO!*tJ(5efrpds@NO3tznB0OC)mh5>VfwQ7J;tPpUio z46vPb+E(QNWUdPQ=5d9)P|G+$h3@oOILd~#BK_S7MXGtsVw3*fiaDDu0n(KV1APG) z=BuRd2 zF9!Oyr_~4@mGS+=0h3x`f6f8Lo4} z2wv~%xh5<{;m5S)Ywr9lFbkbVwdzDc4!57IzOTu^TE{-w$5kOO7K4fi<)a-?inYMu zIMS_m&|V(*pd61@hTA5ewSKEI;*Inl4qVpo?r&K8^=2<6uK4c#lOKUefth}yI0>mC z4kH-{-VK?%;Jc6KHmovmr-q$t;>na&kB-Ey$r;L&;b~!~F;2dvtff^L2MdoX3=4Wj zN%q1Cl#MYLezF}AVRsO{qfU}~^E4Yu!Z`2A=-98|+--Sr9bcsNyiI(98)X^J`Bokm z{O&y8DgSiJH_y$>POrV%S=BAF)?TW}!$ zf~vuwjq{{$Qx-K9P3|_{)}lt6@a@`k;gNGpq z2yk@K;}Vy)U?XuX(KfQV_id}K2n+1dm+>*$JrF$9^^b$Lyaz8%?g%sbs-y*BbY@}O zTo2;{Q&;YV9U4$>hsdZoV^;pQ`piPE$V?rhJuYVgC@3ojnSBC3=onjtYu&XHkLnhbH@FRhm$Rh@Eg z@J*|)u2xS;dP$sx*mJbH_|zgkjL4Q!zY;Rr;Nns|MJ1rJ>HH*x^0syuOEgjO&RjY* zi>Zu(XWl3zuory$>LIqz-ze6wCN{j9v7d(aU1MWwuwKtzWa08Z#bS*b&|;IXWv;zr z&Yq&y9zMv4Vpk8=W!75aIy9;$pgC{SgnR1Y343&J6aBrb$Q{Fm=ULsB&@RbIJZK?SvuuSq0y*iCNs#x zAM=c=lIQEnd4}ck8u4@FqOLv?ELrM@YVjj(x7+jYR|du4&4x7oHm&=vE2Xf?jdf-sB;A-c z*m2}$Di^JdP819fwt0CQ{yYhKUgMSpeIm84wdw21wI+$yQ0k__2W3re;2K34Pg30O zP5a_JydLABbu*a-+~W}TN=-MpB;;axIUr7^lAY=`@L-)igavgFnF)s$PtX8}i3BEW3%5`892y0<-)#{vp-6*YRZ7OmCb}^mI+SoYO#X{YE{W^Y zoH0Zf8SbTdtmWAhgFy4VU@w+*Yhu>vj9fZt$xX}R;fVE~$6d=4Qs=oKF14hkYKo!U z%r=dWOI9(4Ua|e*bXp=jos|6bpk=O1r>rwR_0gh0&1phQiZ+ja(VuI*(;fz`c^JWJ z3vC&)3)8~pLV$)xujtpZD%ty~Np9sI$osRhf%cX@LS;$rfIwf-$p7 z7A?N5uhFH35e!!u{s!@ZgY5@*Jt68G*eVEJqBf2$2= zrT=gGFcTa5|5b$l0m1a_|Em`NKl(5|)Bl$~ti1cdTC#_)xX4mmK0Ln-5$H@rFf`b}6ov(;Um|q+jzPKnZ4)uU{xbykDeXDi(xuS8I-L(7aVRd`D{ zq<{z-HY^Pt<;C$a36SepWIp}uN$5D=n*K7V}>RFQCSufTnXdLqEP zE+=|ob@qeR@WQ@Dc-MDS#L56iw=e<+_5Qja=6!VZ;QDLc z!hbX{%>U59I_v`p@@0BL{P*SxPQ+Wla7zncPz31!zYQEi_WTs_+0D(!5Ds#Z|E&7b6`SyIcSKF=daJXSbjQk$cVdlxUbju$V| zFQ)rGpNk7}yZpTRc5HcdSxHoKQc?<-gsb3!2Jio;G(6yspu7+#(l|9WDFsmC zmrip zvu!PL2*?j9vjfFNetIzA7eIdqXT-EbppOUykUt?Fzov}x${-Pg2!j5>7{LCrgcqm$dh8Aj+q4&Xdc; z9vV;FN&KRH`S(093*7cR< zD5oA^Y&1>HTleCYk!btu)G=`BV-d%3l;}#=OB?O)VjM}WPQ`Z6CgT~QKQ&Ov6C3)i zL|9+pd-eK?B6};Jlk8q}^SN=08Q^#5q|K))DKj|qiT$vOITc6iE-);>A#praff8gM;k1Qgtp<~ew2 z9$b{y>S~5&OqllUi>N#{4g__gX@}bVHFxckkZdm_`P}__D4bJB)ti2$gad$rtyt%^GTzLcmS0|0nqIw)%XZwxQ*xwItKR9C{*mi zv2RQ&Rw+||N3<7suYf8*m6;oX+B$ZS&b#<>RO^V$yh(+WEu7Xa^ zRcT%5v2QONtT-RtZ6}q-ImP^bx3unS+|=z#;5#&(8D1mGii-)$${DJ5b`L&~jTzuQ zKCCjyqpGSN8lSdYm=E9`z!$!NM=G4rWl+>qPQv;8xYFU(2Cs6yboB-x{_QR5)cZ0vD16$!$b4GPI zP`||%NrOohiwec#CMQz%H#d%CXVI6LKctW3Zw1%<0)(No>PpZ+a-A(3zfdi)E-=J` zyY-<-=?#w5A<06-pCT$@(W0ZS?H3^tS0^B(J@tgT4$h3r&^VUd0J01c7bv6{%g6RB zs$4q)?y!>G6t;>p#?W#UCm%JM7)w^3!$q{L8R`&_N}mwoSUe1~Q^5e1ug-nxGh06qy@qGe%%TGTdLFug;V!O3m^1wHF86PK*anrqP4R~>;WL*vaWUWUw#vr;F zI)V7O+@iPEl^sW&X{cY$_hq9BRvxlSd%g+R&pQk^DZqFZ@rk+ij+h1sAruAtB?Al+ zEM0R1H=+%Dq|00uwl4MKsbrtsQ+kSg`)I)dF{~Ae%Tko`tB9?b37_kC5l-Cef_e8< zywCEmTU;?on?`B2(~L)+b(fP{yK7UR?!6<7&0A^JygtJgSnZMd;WPP}rfXC%4^6o| zFsbXe=#A8?+362E=K@6%YaK2$j+tUy-gP8|&axjEsE`CS-0O zAamwbtcnKHYnz4D=)GB*=80uY``1p#IXzEJQsQDskHeW8;O*m-)c}+%RaJtM}{e9k&`(vBPpW2HK<( z&u@t(f-(!S5=}??Uz1chQ8^Ce1atTMnx7rzyX>`Nr;op|fAveQX|~9otu6gKFQ!~? zO03fIc>6?Nj~!iFrgt8nzE)RwJL9Wo5AMp)aE~r)_0$B@OH;UT(JC@Xp&5(+TnUax zCs)te4$)BN#Bzq7o2jMXwimh`Rd*&Pj@dd_`AcN$yPaQ&lM;XIoDYvzur8wGH1tR_ zQ!KgMG`kV?25r{>-&JRU5|X+xF}~pX@H&|GsMej~WJ^q$iD#oNE>wS7a7evyKD~g1 z1)GzaWF*%LN}>(XV8UL(gr0u9)~o)t%d4Qdgxr*3fCLAioTM=m9Cm!YWB6Wr7TRD|U62Ta;moC(1H1_IAv>O$PuxBF>fO&kxM3+|i&@hH1F6mm~+Vvsf zF|f~D&Eq%0HkW9B#O!UD@ zwdQRYOCBF?1@oYvy+`)}`6&OwzVN11iv@83E;hc@Br|o}z3Dn7>#1caU}LlEkHHb+ ze4XNBV=?VR5Ovw?mr)H()Jr5iY^nMxWGwHG{$PJLcT006$3OHqdIhR1%4ftIpvN{T zm@&W9!rNz5M5_~r{JI0JBU9?`y$u<35E^Nn4Ey>#9?E$_<)}DmTClYu(aZ>k!x`XG z3KV(Ow1(u#;`PFB%ZFtGBX_UreB?9X2c|U?TJJ6i`e9atiSCFRrA4 z;Y4m7EH8qcFR!(z#V-tUwa)Z0;v#uO{YDh7`L*cMb4p`Eq#^Y9`xr{xb@ULP((x&^ z4O<2s6>@t$@EU-bleQ{Jr=xEvBy}6s$F`(S2i4QmoqbZ%`MQ7>oQ>E zaK4aJAA&+lh6%>Xn_NOG60qKnmE0jnM^aCErU+$Kdc(2x|9#i`3 z%8H1#Du>ETw$3I-<$P6hTlVL>qsv9CyvQX=?@&4pa&jHRwT#^w=42@C zU*qw4nY3jBf+q44r_W|qS!oHVv)V1ZYlGbQKKO~hl_E;5jvlk9P$KlF8V)(qa~0B^ zD~8svkZt>P)ok?=IBd$T8(Lp9E-Ex=Yfhw(lTeT5%|;>*Hc zG2cs(`^f}(w2+TzlkBnt5vS!AL!<2h=G4{o<(CHYCgX)h+uh#!abgM|5%Ij@t|aUS z3`#P59`mu2?Kf3dHE0Cbd<35rYI0p#Tjpj0Ug~zo3mSF44q_p$;HATPjVgHEcgU>g zgCoAlZfx=r%PB`o#k|l793s?wZ}ARz;-M+*Lp=yKyM*a_+7xes28}GHnwy8y+$~sP zGW;236tWAE7IF?}6r8iIa#M-6AP&B9jYOE9{W_p7GouxPs)U!qtu-feE2PSLe$F!U z`38Kc0=hZ)N4QBO@jEf4!B(*;N5uI<(ruBo}V2T29F)f}W|FGn?!5nHy2) zXq1-D2raSmxa)B^iv%}nBFn2Jf2Bu@^%z?h_7Tbubj963FZ3;CcyvrlO59z?)QXWo za55%lM76X^up93mC9m-2>eZ5RyDX{^0juE?mG{589?WvCeGc?;%+TyHJ421uSx+U0 zUf@3m_VPQB9OK-S5<_cUqKBHucRqW;_eiax2F;w=>rx7-#Kyg((fG~*iyp*3od-I+ z!S3&2X)%%Wsb9aWvQ!nwN0_veYtCBbJc3&)O&5QVSKYjn819XWy~@7y?4U!hbQ_e8W6KPemDNu3OY3iV8WB10Gsw)*@6 z;yJ_|O4a*TIKpNs>KA|)b{iCwmg-Br9$ej|C~IMRJp&pS)KU>Q##CN(Le^M##LG}m zGIqz~wKioRD>#L%Rav2voJ*B;KIv950?#MQjD*E3acS@6E4W&UH9==Px=(6+RCzbZ zMLRvS_jNsQ-3!|kYXDXoy0-!>E69jzN|J=J>J=GT=uKWtRqwW73{hxfCTbn(%83{D!+0j($ots+SwSuW2 zGq}tzRVUPr-JPxtt{gW3)(xKIAn0;$LR=j#4jcL9JoC0sYP_G&3Hv?4+Bj*#*U>47 zx|XgsT>jg6*FKI@DGA zxjc8u^es&5c}X*UJBEeI`)O;jhvjG7BLZ))C6eqPERj4$McQ#OGG85>*Kplf;f+DX zZ)adTl-Z5o-IsSvLJEpnQ-SpYYf>q%`$XxegB-XHjRQT#T~P#!y0zI54aTKW*vivr zU*x```Sz$v;tm8B$rLY>d)X*L_lM!yPCuWuRp*EXLGA~WeVgP)C$>mB^`6jl_mDohH*B8!!{&D8 z48JbKR^++pONSrsuOV`89ipmcmN*MJ{{?I|^bINAoqtVdnJbdJvy^hF*W9f1#e|Nd zUp9YdU0yodnw6@tG3p@E~3N?zcgL+ zy!CD(h%p$g6m#meeOh@o?5nD+JmW2uWd2rrl59*ND9RlO#8C*4kLN(rB&7?%Mx`5? zI1$e_-*V-QB=e};iSW^y?aLKuxEnY{ME3lleY5?MQQ>*gfWXswtO8?uILj-0-CNCvkbXu$nf-&ZZY##7t51v z%*!x3(9=yrW54SO|AZ*mvCszeXJQziwJ!a2uPftNLj1)h1>^4QC`s7ny|8PRiaEIj z&7ekSv31#l73bN@Cv@!Y#M}9a-gfkq06OzLH^F)_THFE0t4Ie$hc9o*PbhVDGM_Wj#3R|Gz228U0*L)tgR_Etlvz6&> zDt$UAcwg1Lg}^I@%!O5$WEaFt3!h%IzXzNA0elL#zn<))lL zx!BCuxg^8pU)En&mdTaS!FR_CjPrb_M~TL)us+4|W=?+n__GY?hCf%rL=|@au~)6S zr*J^i)1em66Y)r1EHu|*1`{LaH8_8W8yU<7qYLMY9Yw>FU!0O8Js`mBmA%+e*j9M% zv2wHM-n$0M=C@?;&ku;-S;4cC)2ZO7Ki+COUB^N(JqbU@=*whku+x3krk8Ke1G2p> zWUtI`&W}NzsPUb@bP``%`~x%D#S9j5g@UJIXYZ9 z5q?ACq7m)6>Tz6bh~8h`9*!fKBG!?C!no=PCX<{}6TRy7-x;)EowlGNdJC`2C>fa*`Kl}N)T`3KiE$j^oO%rTq~qL)8{wBI06Y-gNy)5e`&NWsF0L5)>B@GI3*bA?6dKpn zwc4a;6s919o1k70RXBlSCV^fR$UtZczb;NAb4LTNCuLte5mD)yedV=AcKXn;LzmI<3^oN z%%%0+;NRrJ0<#?P%K%0d`}$HewmNRg^_@jI;{T!P-bdJk$``ba`CNPFVk2XKb(t6* zq<@}Hu$%aawp5%V-sx-t(@c2*BLAA%TuMB`ltO}WZJxHxrqmMtccD?hOoVLhurh8P zU7AC@u#V-2hI<%mg|m7+#gy$u+?HK~=4;H8(Ti~41@*B0P}xT0qOOp*D_@XI&M92a zdfG85oh!w-!CkPi^KO*G<x z#PnZ*PzDwj28RD3LLuoyEv%hQ9P#Nytqq(_giVa>j7=bUc_E#g9Zd{uAl)}&UO|;N zH(x*@i9j{Cdf>OV3);OJ1RbE@u@Sc-wH)YfZfTM~N*h&7hMTn?mRt7@8h{hf$VI*3|*4tFfo6tFOY9l`rtaS?>5; zg)8Ow#puUpQ-Adk4r2L<#;aroAs#Tx&CQ_Vof^UF9RSwa-`CyWG&BIOs;j+!|1>)t zfs3Pa1W5x%P6KdoY2l+MNN&yU%pe%s0($72^2GsYB5?v>;o-p@=A8p5VC55y509hf zn}aj}Y;@O}8ydsNH!%SM64?GK1-=AK)AE0|4WH!-CIQ_(^ASO+H-O7 z&#VUGU&l57RI4A<1B~|XV*~FWoqpMM^fUWafH3|vYfOlU$cgDmsKFXv!PW6@AMD$ zfan{X8i3Z;);IvU>)>>MwN8r=&g^i1CsSHjnt<=VMP6OlzWq`^^C*6Qm4C!ie$@(o^+XkAS62K!EPf&1e($l?{j0Zs zV%=40k&av-k*{^l23~$cErEV9bwu(h#wSjGJxvHi>z42>t$r%aNm*r0RcHII@avJs zQOrLOKo}a{q*(mcS$@*ltm0|zig3`M#$X;ZMq8^JOQV#un~UQ z)opnJqK@!N`4Hg7sxp5BvH?&#{NUmIMeh5;({TC=Kj1uPls>_GPAYzb+5xCBe?`3O zRHA#VyGsfG=JT=dD^%;*{Em9Rdf5728T&U+x#u^q3KZ}6;i&^l>=K_23K6*bm0-8_m1s z^o8zia{F8EjgOJZ!O_{f$LY5lPM75k@9Pv44x|%E20rcNS{ek1+6rjHwn{icJKc3` zokIbPcF?zPc`Jd~en;sZ>DS(EA_1$He1qka>B|=BF}&xjWI+-tZCTQ9h>0W{&#j^s zW_H>=YrzRo>Fx)jdT;ngskcdKGk$30FZOG*gv`h%>6BeSeqVJ4jz3*R%Sc{fSqmS7r^^3yIS`-SAEyCB7yM0GW2GGGyr&@@+H0Y~A3w@SDTWUs>$<;-~GSY#GY0VOe^ zB_0q=smBnNAHn+dt53XBwz=1i`EvgZ0{ooCcK^nii#8zEH3GJFAXKk;6DrE#`Nq8K z2-ct+7dlA}1o(60x!*lbD7WdAQ5SZdNWh~RKpC? z%rwvOEzNjBeA6xR{7X#=UGdk7aFalAH<&@bn0kPy*fqFo?DL;nOIo(3skFFm-f~GX7H`^u18LF97gP+}$NRC{SnGaP z@KQs_pFXc+H#}L)%03fnbO=j;VZ=wy6re)M2a0BYvJqe44N7-+=(EP|?jzg@67?7b z6s{3oo9^kgpCZ`C`XZJ`bRiC=&Ad|0tS@vc_=1C~Oe zk|@Evs(RdFac0UwDV2`C#1rEr&8OG*ifAO)FJ*1H*m_wkn>T0u+Fu~4 zsKixUrR#zb=xCAzIgRXQU-yc*ui>E}4FiFM6n=r^zQi^h>F^MOK8}RQ_qJ{xB9QP!(*t-s4<-@bW{_`=V|@uN z%o8{^wry*Eggi#&T;k3!EDz_-$nq(>)W-@Sc~pW!Z^fxL?Q$?%TiPFSgBH58Smdi1 zHTn5~TY5qa+UHoVk3O!$RM2JbZFbG8OWz;j^04ZF$gxWv&fX@J02uX-_G4($u+PC3 zvb!I|wkC~!M+dFh-;90NhIQH;YVW$@_*t4%jbGrE&5EJvGz}jol1sU-(=b3r@v7Hm zkG0ogrPSo<1vduu11k3+!KJp+ST1y(yryk0_Jc8Ei026j3%nJ{EyJh~DN41Qff9KE z{RjYWaZs{9Xbgee_t)1~ML`n2vioIUN25e_&jY=2R78!;bCrpxRWw2MaKytkdigdJ zS8|R${53gxH8{rR4~8Lw`fIm!@^?Z*&f9+v=uUk>^8qdgP(tQzye5;I@qZ7zZbvKET<}i|&p%y6pHFT`P_SG< zkS3A|2|T;SIZQGty z_Lz8YCAxqBy0w;kSQ!)|E@R9%7ekJBQJ0ML@XbGU&~*b}usKY{D$h4Y@H*O9 z`Nt{-=ISUGjdM~;x1#*jkm%IBKKazF@@#a<%PPT>)9)E`(SE3iT3i3Hj{Hq zS}+BlO1s(r{!~V;SxM(&kOAa}!f1MpT+|xUF8xv)Q&d1yAmEbmxMU8T4fy~;I`kwk z*c}4J)XF*h!ht1mQGge2z`b8tgG|EOkIR69(5V=sHrbY5PeNK5hjKk_H)$~s$LpK? zw8;-hmWd9ix;85TZ}$aV7Lm)u1GI}P*88wdk;J{{BL%xMlQH_v zgI#iS?z{LA7bOp%JNwBl@=A6H!_GL|%V zb2X)4cpDErYccMBCh=ZiF)&&x-`ibgEZo%e?VHh}f1=*P^7m-LWQV(^lD$v=uBY!! zK|D<@?#HAs>}bKz=9mUy{1qy`q38_S<#!jzy48B!{eIKS&0I4jnvcOUkSB(G%f0Is zErt#5g!~dK+ij zD=uy1s{R+EYf%0s0+#QFHP}NS*1SEY%CA*#^arZYA!1F)Q>#?2E+PfVPFX2A4;9gJ z)&2**^%<9i0C(miILE&>7Bk!>?r^SN9nF2o;3qo^Gw|sN(SA)p)krt&A!M{#ZLMIX zgax@Vo;0tB=M|u%qcAipaKiA5AMjcD_0Wm2$m>C;&+EMz^wK15xe4skC zas&TgU1C{;7=QPS9g&JyYhjGd*w`2)HNw5VCh_-^D6;s_N>nAUm4N(PIycDUU!z*2 z8SUzq0B_r(yA$QXt5j+Fq#Olx+kXNBacH?Iy(Mh=xC2#apBQmNDtmnQW-TB?V zH+_fivo&+-V36sUa`tFdY`PL@DXolXJ-ZzDqmsTyYGs>_AP+@4tzM|=B0ZPtN{A#rJKz{aB{0@%-y!s7ToG7F0mt91f2UE--e+C zyQ)(Fwlk^rbB5q~uR|z2Y}k&B&UkOm&cQbiP!Ss+Yr9oV({wBfRz1SAu%~q(7= zk>#J@knPEYJiEwqh{n0fDeZ7AGsw0Fve=!#r?xwTwHhOt5S?(jIvCem6X>%TiU%aR zPA>*qMFg_Jc7~JG5|?ES^ZYxOz2>|!K7LzRZiFX=Y&T&d{ij~a9}Lh~3SvB3=Pg^} z39`SgC=R)&yyEtB=_8N5y4-qEJl9iK;iR@`8Bykobc9s}2AD1*aDhgeo+1$W(*FaJNl`P*ba3;&k|1cfNX|h(b2iwMj!FW0f^l z2OF9gPXX44=o3WhW$gX|^J7O^uQpNJ!=AqlzD}oV4q1rX+a5lF zxZ8>m@$9(R6K=wV>bT6z9+1tH&P%}Ku<*9Gj z_L{}!^WKnRIgy z1PrIP45V|{L)enMZ`pPl2~D;wFqcXxz57FBn?0=E_d@9+S`pxnbIGvoaO%QLSy;Lg zt{b#A#CJ~Lt_np9FV1bhp6*n5&H?Vd4RJNna7gRE148^D(pH>`QX5ZZU*8?DO1XlbFElSmPVeMG(J9ZSIGX_9$yYlq1B8Oa!^R zouO0sb(ybM%*OTxvo~XKUk*f1BdbXMXICJ&R24UE?;Y8XsILUfO%bn$*lYy7p3h8E zG021osul%mRE!VCMk?JDRI zMe`@XvLp?NWo>9Wo3`-H5^g-7jVA?z?hjw%!lwJV3u_gV8mTImDma%c7tK7@g46OU zx8yQt42@g64Qz0&p1|GEjoP$%&&Jses#Y7I%;Vrm5`Ld{zAA+Mx4I!i*1U(^;xL)& zMS4NEU5HQfvcDw*I3{EH{4A}cZ^|xE>I%Gc<6RC(R7w#=L^mH0FjKH1?*dl! zGl8OCIgAp^SrR~hn~@gNG_@79aNa8Le`?doar-TDRRTFuujRDB6N`x3;}wOW7;cs{ zeWp%=Obl1+m;^@$eOVe!8YTm>UB@r`{K%(Ja<-3jR(Wql*hyz*#rs1az+oN|)miwO zpui8S%DOoWy45J&x?g2m-}mwJRiz&QWNU*q8e}%#aBf~HOXWXpv+h*f7TpBf&d6UG|mx;E6Pa%ZQuYMF!Nig zBT``if*5QV(z(odLq5b}i)9u|Xa=$%OjXXW(-;=;^<^Xg{_6Yf0D489c*zNS1Qc5a zA5idvM#5KHId226GcaK zeXD)z6z{LX#48%y2X4ffD!PZP?uzczFk<15Ek-8M*z!xEyXp0i;L3!gQM;08Hx_f+ zW`1~Y?K)A`y(3S#CSW$?wx`WJtV0qmCX7s<4!Jm-J`|{d0)z}37lK_LzGoktj>JN% zoEICwvsfzrUDcB17Z3@c=7Y_Ql?O&mbv+sX?EOvnQ;CX-_W&P=?w8r(0fY-#im={Pnv zWksb4PqHDtBfe>6GHt43XNCdMjCjM|GiDTkF7HOzvaEb&`$=L_0#(xEyjM2Lla*3TiEw!8XIt`!OtmnCSRBG{SG(8w{PmSAPX$B5Y9@;BfWKv8rx97joxF& zOG%4wQUH890|Mkd+7JgqEe|&GW%f^ePTZaOvZo)OOh8S#qIly2AT&H!S@f@ey&uZF zm1MlhQWhin!_J_{6p4OdMHM>I3Qk<<*33yXx;3Q}?#_>Jvjf)9OxM47OxR=-$3#Sh zyJ3P#Ybgvl)JZ1Ya|u6k!DAW7NzNL+_-CHTWiQjI!C;wD_N&HK>(Ov`WNbbgnkFZ> zri=yjviAFSAq{9pZqltAhS>nMuXhto{E&$;i9wrat_c5G47I0Chtz+hH-q&yo64C? zG)KgxFM6YNJotvl&PE$(!nXs9FZ%{<_0}vs3d^lmsd%weICD^~7!M+IbJ2v9fxq^T z@Vf1&{7UE?$bnMa37^AgGw- z7H8UmnMp^$=dGFm`jT8bva>!00qf|o?Im@S;(E7M!Cc?gA3r8M5M3AXIzQhHs-v^) zm5LZ6)!31V2DR#Eg573kQf5xG;0bp?dvuv-cCR*JfIb}hz)(NYD| z!S#PwLB=aB4%Z=nyN!S7k7O&16_sCW>ULlcu0$gqi6nk#L=rwvEaRea#hYt*vb@EC z55#@o+;_;5uu+Cdxh}=SK7Tgd1-WcrJn+NbY`%}56cm`K{EA63MTY_a)hMvonPxZk z#OQe)43(i~UN`^lpJUNTJY<7sPE9GbE$`QF(%Yt1>v@>tlsZOIfxCLsH>4oHx!d_jo9Op6k%3FQWSM^7iH8zIEriN#flHZ&D>sMIbkei*9TU41&uVA+}%)#@1DO76xD3gvD zO%9)vs`@`S`aAS@kmr*r@~v;%@G)gMn`5Y1`;nNhu!IFYysr||&3mc3PwDU|Uc@)3 zR7kQ$<=TV+rLw#Ko;FXHxcTa0B6xobW|-t}Nkh(b)J|bJF|?X!O!YhgM%YqP5L2pl zncH<3bi(mX?*SQ5;5ioWgYMaKN@)m96w3e$qP`@;1 z*Faa~cn^tb&+JtC+k}ZmQZ|DDSBC}MhD9Lt@fVkD${nx%lZy!3eJzYdlJ_pA=~DgF z*p=`FK-XW!1F>iVOWmpunf>j9+1Cl?H8SbYX)T@2sP*@BYga@K@1R8sy?cb&z@EYI zwEJCPJW}4$lUW@w-0Y)@qpJh5(!WCbro2--4=>}iV?aKWvbj#c)38y1`^vqgXr$Av zyufhcDv}JY5T6AbefHd4juUv8!9qjU%@Y~$ke$%7$ud+nz-wGz zSIcZdds9gi>L-yyqt`P}9s^XIGk6$zt^`%rTnL{j&OEa;&d8h&0`XbI8rl#>v!sNU z{BxzZe+h-QAJB;};AE`17C}tB!%-#G-w*wg#l5D|Sn8}{V6V)#;lh^=Wjs{kLOa@V zgt;yWWAb|Uobb8Nl?`_+S5+z;b#a^NUrtaNnfzbEH&TvKxv85bd?Io_ha>Htbkhes zQMQ_mSetNH(rB+}_&6xgv*2PqUL@Ntq^aLRz0-SP4^7Pk4+yIAG%QZOY?9V*l7@BRG0vAs)RO|ZY{$wCKr$`pG&r0CV|65(S zGyU5vQ9(x13bYtk$weQQ`w-rv~NPA(V314IM9T=XGA0>Ai zq8dP!rY<=6GkJCFBOG53kn;y#9{uNDxxiNPZ*OeS?73LOI5ao!8H;AqzbJu-4Bcw~dJD1k)wZK95XUNWHJ2S$yFT zsFLKI1P-N4b!nm9X&sF@MBN>6_U<*%23JR zQ%0{MacHrI1(>0`-%&*t2B*=j9+E_5`%N}`Ikr4OBm#g?3Eq5I>H~8LZ5$%4Gc_77 z{{p)Vv2?L61$zrAQkCua@Du@5^QBBeuB+v{d`wk`R;z>v`)*N(5g07-^fE{d)|h;v z-BMKq?Bks}s9llV^Cg)h{wZ8sfmOt0irB38fbOEgbRswv#v!zaJU7Zxj?Iqk{B*7h z(fK(|aq(AB%_wl@;3QGlgv`XIBBo|KY!n9fF;F$UFj`2$f@a=mqijOv%hrkBs9Ky8I(?ZWMX+D$<|l9^#<>Pp1X$Eg}dMLV63-Ry}p&XDa0QutgDee{a>u?%u_ zATRytu;#xsYj6`E=`J#WP@VQFe^LZt7&0uXM|YY6d-Z3_lB=qA-hqqtU*-ZTT%I+KI=^gPoE>@ghv&*Mx`*d!_Hzq4{|tQ z(r6IsZ%z=C8%)X;|BOW!^AMQWmEd>A_hn*PKB1PiGClYgN#;;)sd~kTjh*~yH}qLt zvf9#Vh_?STBk1AD)xO@#JX|^Qr22tvligHD33H^OdpoG4=u1mHf-nQB2 zE2-$$m?zQWr$GAi`WT%2FJRP{lPwVd1H+)qv4!9(UwvBbDYQ^=7ogMSCEuGKx`K=Y zL7viq%4B4f16KfL${$70o;Aa4D~bl&SwlbfLJftf2p;+ypxXy=1*|9EbDf*^w=AZo z`q%SLSUN|ZWyDmgSmDvU*#c&l_(ymrPAIqc{xL%)S|Cx1!29(mBI}%r2dV4Zu$I$! zUkG6Vj2^{R&wzGx%Wq0zSB<49KoXmG?=Rqu9!Fod(G*~E9OtLqeS0-9D39X9QZ&x} zTmAspl`R&cL(Snx({NV(&m8PbU$HA|>!Up*8Xi+`Y1^uR-?XZ1DnUZD9x>K^)xA%8%Kz)cfy42RU+N6Fi0Y^a#eILQRD`FyeX2ZVO z6iYe;z)>q;br4EJK?5V@7Ks+Tz*vWKg~I5cD^(uQ9?CpbEn(9$uMf&go1{TkF(fAk6>Z$X8ugy01YNfimd>wx8XnFqD?eAA@yM--^c)!a zXi`y9X)IhVFB3#b1+ojZ^=!Xmly#FaWP0KJAjHpSrwuad((fofOy!maTS+LJn%OqE zs%4N0d2G<1DAnYt(p?%U8=;*ccEqtnw<34@S9E~ybTz|3b1u>0I@=?t zzCe2mCzy?ance}j6kNo*-svxxYKmb_bR*x<;@v~oTWIE<*AXaqvR+U0*AP9Es}SO|RQNIA@FUa+zOO3B>eeh&^;N%H}%vf%ol$ zK~%vDb27Ka@Q(w*q)#Kq4Bqo}Z}}0eWFTA7L_MUI%e(3S_B!Ms{Tq#YY0p8@^L1W* zHxR$yoU)5&Yo9UnStEO)?AOXmR=Xz1fXeAdBKgoago!C(KA8<%a* z*(d3v^wvS19QoA4nPDY2(n7L*5!iq85*42jMN;79>HLu#%*!3hOT}q_XWHV{+5IkE z+L|=E0@U$8X#HxQA07nExB4fD6CjrIq4-PbFp&W4D)OUdMkbolG{ruQO)cwabM+>W zN%=9wAHaJTGT9JkpVwLPT_F)-6jLP#l+{|AKVDRUX0gb5MpK5x=SbRtdNqCCrI4K| z*X?`e7Hb@D;h|qa%Zh7GM5Q24kAE6wJFF0edCj(Ii0Ar8MQ(FRgeXF2H?RVY^qGmy z_gy+ck(h_?Waq0U2V6}{uk=nfr->=suRdbaonV0Os9U2{f+}Fby?VI#~dfx+Dc=hu*V!rVG=S`WG}sX*DV3J=iXFIMWK?5 zP+V%afe|rhQ@vIoV;5o=w=&Q_ID0uaVt(#n*|&H^_vcPpQ>Ug!b=tJ5SI!_@?VJ3Z zP8@!XMrgMkWa@?NcxJtKeoP?sjUhC3Kf@`$dePR;Z~h&Ay)8+=R#+_JnWktm)(yDbq-Cna z-zw+y*pQ*Sj2su(AIe4j`lI9T^~HQll8S+fFfs#q+mO}}#Ms`n<3PkaMQ_1zx3gGG z?EyjzeGFcv3fcF{$-~s`h3xaYA)~3i2dP#8b57a%M1Q$7ZGkthI8sV{dyCzvP*U;D zto225EbZC_Zmd1TzRAqiOjpOMbNK7b>lBMikwR=JKP1!JR>8*t&z+BB?se({vI8kV z1DWp%1mfrQPuEoZ+O+Fluy{vQ8j|u@kF2>ZPb`6x{NmMqb-JF}B~Q;V?Hc>=Ecd4u zxDJ)XfH!|?*2_BQmV8qRt;&r_S~g28p2aJ#Xm+3#={t8 zs2)NhYllpQgPe{Z%lV&>SOHsH11QuE)^hQ0ru?iBo1Yv;k>*@q@2(~R7=NmbymoG0 zGOsg8ymq$n#s?s56o6YF6G-}H%_tfAl~iZ5j{(fi0q`yf~1JIXUI^_ z)?&nFwPk$|Vwc76&e>g&WG_xtjK}VW(EXbxOtR!4_`>_ja$p)d7CaOC2Zof3IJ0!N z!a>v4!<^kt?2}f*P|zn^FUewM%l`0xOp;x?F`UqoXmdj|4rOUymY=3Z=LeIBV3!vX zy)cM2cVs=>wO}*-WpV#eHW)=sCG-JJNEWek5~MiS%6j|lA3>jajhuTa9@i}3G#z`W z!t)XkSmDjG&3HmM9kxv4A zIo!4#UohO~JsC7T-k>#&Ov&yPD+h03EU%)ssm^@*N}&eO`e~~D zj4ewKdm*ipQz2Q*QzSbQd98n#G1%{R`Ssv`JBM_Bj zF}&vmu|?WaTtu?VDvK{>{4CzQJ_+%h^y&Dc&3-Mt_98$6g`Jt-yTeuY&6^oTCu@i3(DFOG=;Ywd1LAAXTQ=yzi4^fPqgK!9-*%M z<69vjX*lxDF>SHoY2h;~0SRs`5O`)Z8M0V{I8JU9iR^r`f4X%q1U3|vkd$A;g3-VB z^9#qP^M(%&zRBZBV{EM7FF=`R8D?tpuzjX_ZXbFMe6mw|mYjpUiuzGN<>#otJ`` zjh#O>or5%`*&l2>lv135oS7`3C+R9=djYzm>jGlzNbZc7D@O9JDUNY$TSl1;lV^?@ zCvX%pO8>Q`7Rp*FrF#gK!47qWM)v+_kqI1?y(&5l#^}8PxZc^(A5N%0tTm>pbaT{N z{_>JOTdh;LF{SCa&dxBqv#hPJp9Qs=VGGp^Q|Z8>A&9Z_f#Q;z~R$s z9=fG>XB5?y<@L<+RBpSZJ7V{$S|q8Bbk}!d`Z!CA}j;D3j1>OgRhKf==yDJD?D8s={i@E5`Z}RfeV; zWeYFfeHLL!YxC&1!-+%88Sy{`ttBg|PdW1=MoU#>6BY6Y?bNHi-t9a*uh+4**5&LkjwsanYSnaiUY)O#iPJMh|lC%tC z97UFcJ?p+1mOps&Wve5Pv8B0gI_fOPu*W_$zl_zvLOB%o3Xit=^>Ma`{^0Ba5?RQ` zu{&gd*T49)POm$`fTE~YODeGzbsc;(Z%RX5dC_ldpxYKt6#Xvpw{1zjqTf^wq2>+5 z&Rd$v3PmS_eT~;XeS+oSL<`7F(8yL6tvCU$`=>V*oec~8JKa)E>TaO@}C%0}z zuib;53T3{DSJD7r)lexRuWxmdlz4}c_ajfyK=y2xHqmPF8Qn_>9m`04c>9V)WQvE` z>qhH2XW0yrq_6gNS5~`XMLDIOym)aTdPtaP8yHmkFwiR5!f(P$I6G zt}~`JtOQ&*;Nj=e8D6(65@4_4tszR%-`0StZ#rQydZOV?+b8`2m1dXi2c2D=1utJv z(>SqkKZ)#mSsfj7wRP6c2=C)~3LrE?ejVQO76g7*_a@o@{YXJOdiuUK1k z()a}Jmq)*28s!hV6ByLlYp=JdWn*6?MA=$A3-nn$N>9ur9XPD`H>`sWHfx`d9F;pg z(`k=$^VQN(oFaEz*@I3ef5skZOe0n}ZP1gRg5+EBC2Y~EQ*^u*Z!5^%-cgwb%9mRX zY78vaz1b~SOsS$&-`k~nMWT|X=+jEupxw5Uk;lmk>I-ZUB*nOj&LCbRxdlNlLex@H zQZ5roLJmA{AYlt*#I}FwngC-Ly?rT-H_+ ze1b`Mb53xYlyxa4RAQ4d!N;B+sC{)~kG(GIiAU#{<{CoBbK&KY$MnrX=8BA#^4MD446+Y&8^C9PaMC|LG)?w z?1}J{*cmKX>klZUA=n>+e?(fsSE(dmTvsX-NFR^2dWAByroC{KJuadZF$$Q$yykga zwMM+vM6liyII1q1bjNHGxGLbC(za11>Uwb}p^Ocx;9zmcRkr}rLr<3%Vtct zQK57nxp29LpX&S#T#xM=FipW8x(5+M3OB6+mFrV;tGK2luBe8mW@L zmbVkXT^3)p^~lL$p>2Rhm{UD2;swnHLR)K<<|Zl@h&>D&4*YBN@)?!dj4pD~$<-Zc zZ(x$9#*q}ow1_Uq%0 z!IrG6mv`joE>^_3pEt_4p8D2=pp88&K|IjnC z7$tndj>r=h2G<)^>zX*Dv+GoTV@h=KIPulWk_TA-uA-3_I;7~t-AlKhoEDyb4DF?5 z;UM2)>Bqz*Mq?ZHByQZ1i%EImRlYFEebTWiOMrNjNARp%QFj8*P8cHOch|&)BDpL~N4W1J{pq%iM#(N@r z9q+?j^HCMOZh5ArKYwv`b#?8Ha7LN#lsvvIzIwy|)R^zNH7)-Zb_GG!hjPk6zII%= zv0j8)OD>cws&KvL^O<4E)W}OSAd@>hFhqFXj$k4WyCkmN;4T-5@jRSQ!KpeL5e?+j zFu^MUD}&V5$YrMY-Vu#^wsB7a3*`*jCUjCAeI6l%^f31-XC-w%2M_GLEagw|P#R@O7`|d zZ0thjpI!XJQIt=ay;o1n;8PpIgxZfer%J>hKh>H;aD!Od=s!2)tx)Ysut@>eNa{6d zh#R1l6p29pGx@0lN(8t5<|O7nsVc~e^XD$XpXd(MYA%vnXLZ3y!^ERh;tlx_i1pv# zrVGXOv7!3!%bMX}TqU)<-7G5`=uUPY0?VGXb-IbPMob)y8T81x>X>_;6&h;ZB@3$i ziq3F+j_mxpmkEY0s?1qoNYT(@;|e&EKECR(MOsSG+E}i!22&h?5a*s1k4|KXYk>>S zmnzu^!+b#ja7 zAV?NHc-r0}m{RbhTel|9(S25LR@UlaouMczDJ>+Hm{ypng*AzWQjdmV4a1pELigWNt2KJ(LX2>%zBcK&RSt|?`#AzSIcMG(4yiC^ z-y5Djm{<)ig~K}l9pLkSz2Jd{V!~K?ddy<}MM%f>s+e{9;16u$Pk^^Ej;jNjqWou_ zHTjfZ_5%C@0`Rp%EJ! zum%?3XM1i&FJu2g>tO-GKfr|XAwdgkY@iGu=m>z|2o0tosI_%D1%{)mDE|H6T3YZBt*^gF;~Y=arVItKtXr?9*& z+*s%VV8FeDf^g>}tlb-^GfV^8c*4HraAD+=R6zsitG|`;C8Hvpgoxc28Nl^fp}dJY z@0f{lh~Vv?L4+154);AM2M`vht@*wpyfN!|a}2`XJikt0frV@QQUMBBY~Y89=rK4n+RW_}PYO{krz%@*|zVF@Wk# z$s+)KJ-@Fdy|)Y!K(q&s_3ihG)8xO2tY}E)oyt%AI!#UxZUgEe0q`L@XtgTH0(d0ECwcIa^pn5)xaphgV@HB=4c9`PlO?Xk1KCssZ_QPkWNN>+h2hUO*kkY- z898MQw{hkqCzkkIDFLk^lsiuL)Kl_SUpnsjWs!TlXx&zkN>I!x*LFPk87>;LyDkQO ze?=iXC$U>=Gs8_rB*qskp0%4cyBq&~?U+^1y}aI(txGcQ;#4lb)0whky^Bf@114{O zW~UZWvG=9OGmCDCVR)j?F_CMV!6)jDjz2RdGA{c(lH>F6W)ei@d=w>08y3E9POrqV zH)WzpabYv*+^{SFu_8GqW-l}r;w{6 zyXBX#opxk}i3cXja39A-5UVk=QHkvvC`%QKqckd(a@EJbVuT+yUQC-?=6aH?oFR|6 zi=sSrO;v*tRF76Z#|HA8-8_<*x>^)yG@B%>j#yCx& z+yWB@Eg+NU7|z`{l@Q}$x|+P@BVeyIHF5Z4LLABGiZ4zuxaMd(W_E``yeqo3BgB<^oGLeXock(T4}0D#5bXOStnRu*_f9W&N8;-awc7ehDZd*JTTVE^oo;05m1oMH`+w=<#NGW4Ni zy1CcZMMP-A4#21wr{Cl!@+AOpiuPSdzk}OaOPxPrR7L|WI@G3i?{~*DRTBcRSZ1puX(I6>xn!3oBOG@3T45P$TOve#zSc%hG zk_C2wlqbc*(Z=EL5N~jCf^GRYY~&O+D5D7n7Eu)}QDm@n#1D*`51Lditr>)@qL4cC za}S1#ZzlMclN?FCf+U&cj8>2Xyf3i-@r)XISs>rLMt2#iwA(|5AMIBDjH0jMP3uRB zrA*}sQ}|0T>@?P#@1A(gQaFoxq2l%el#mC|xFM0Nd~TgG8ckcUzE74zr?IrkE6Z!f z_4fSS+&1d8$*p>`0yObDFJvX_G)Bf)7TqUc`l&mI_qQo?mzyHuEzhY;iF=VJd*7u! z6X>5H*|p;Eksxu<7pbXA{pEElwo zzE*_p`#guAYm@)~rN6Q|*-j15A=H4=jN=aTjccGn^{u#KPUa9bn)3k;O7={dVleT6+}H zWT6!D5~N{#4YDfiH7ZR??LRQjeY8m*6Mi?s< z!4%boFZT?RfIu!XuP}vwkoJdp2bXgetTI!XK6FCh?BOSQ*bhR2P>^~kP>(Hl6Jgk0 zTYUT5nlXjdE|9Z)i)9D@j6`hPRUYc%leDiipakHbogmo=UoJY;sX4)>DdS3Y;)w;o z4?4StIm*h>e45EqJ}>d4SQA8Wu5dbqKO~6l5B5;e4W=Bi*O=w*FfPKQ(0;wcQfstP z-!r*Mq)7T`c98MdT18Or0b{eP+3{8gW(Y`3(QYQM$IF@!$pX7&T8iEN21k@czuR!K zvoKeB%!0etZVn~2V4!3_TqSZ*@SQ-V{CDe8{7Y}@LYY;%Gmx88#ODoaO$oY$I@!S|knU6$x3qWwk`k2F~Gkd&Ks3u{s? zFyffOY?3FWiG^MI86_;Pc?N& z(Up-IrI{*^8 z#8(ryP@-tQ84wp(Yr-U9co6*6An?;q?w4u>4`eRD=Fgd*zj(G>V@BCq1JIAZpBB$h55-qa>lp7@;l ziJY1;5ks)KTSe^k-Ae`f{a&A6#={TUE0>P7V)pidXD}pr4*0FZv2i6&M)_P+lyu?J zK7+{}h_ai+!EY@Z?EW>e7`pOxqkp+Q695ul^*;cXYJ8!gX$V$;O#lygW1FtfYAJE zmP(Dk0XBbK|G*2rD#>HCu@#vt$A9EODGif50j7wqxeJOw9Qalq!)wf8p~sinx?@lA z?@AU6M|XPciCbj0sl!G)-&ScD+2*Wjm@^n5s>EA_>)fC8kPdZs^L$D!0ViLJELfvY zoNlkJoZtKtnwr1ul@Ps7z$Q?gqQpJ7yB8{N1~kNp7sZ5F(^ilmqRhHFypcWpa!k-Dn^29cmY-1z*P(7+qwd<^kFq5O|LNnv1XI)elE6iB#Un zhY9=^k9DW-T?(N$f^@ow(>9t#A9 zErcgTtFN&|R)m|+m4yED4HVTl7TLGGvP*uk^F+_! zjUZH5q%QesOOHaP41@xXYGjjm+<1TdUea}8b7F1MMp;uf8}$AxiNd7rd}7fA`+|^z z1l=#&BuUS(6S!^uB}GX>|LbvXbcx(Ox(Hk6xX&}$o!TZM{4AYnyI^n^hMpYn*2-FO zkg!eCco&NNShETi+wXm~Lcqj(oz#`|&z;a&bdXNHYuNkIcaU8(u%Nar#3Q1Gh=VVO6$>bwy;eB#Wy_eC$fJ&eO%>4;> zFudIM+bS-{inbi#u9lbl*&shsrR3t|AA^YLJ_y67T~+FZeJq%`R9n9tD&s>)4kJ^_ zCi9IlvPhWPx(%-iMDDNo!{pSoIXMXP#a7t(e#=Tb7-BPsNmO;H-FG*AHq6E>hiwMV z#!Lq|;3eELH;pe2|2|RBZ`$fnnvkz1&Mqk_wKKW3 zS?9FYX7pFuZh;DWW^7~1Z?_}-;VqeUaMvcF^wU$Nk!xdvX|JvVZ1&WvqNrk11Ci)r z9i%Il)7R(SGbc#TRA|Mjq{Q6Qjel(9I_?wt&y|Fe$r|oQTiCI-#Dia%CbmM)(ucoJ zxfYpQBF0R}wl69xyQ2mfs}jt`11a@+ipm7;^j>_%SN5#H@pwj9c|4j%?J^=gC9j%HbmA zdCL~ddS@rc-LY-Lx&Ucre`QN3bHtfbVt$;Fj$I4tFs)CQU9v8GyFdq%md_y92#)l} zO{l(OQ>E7rsdmMkr!b@Bs65*Dw5Vv^G3@wqd0fkQ-1bY~=cgcH<%ALvrLU%Dv6|t=2Se@%3Z0K&SJeLGoO(5qX=LB@#=uF;wuZ zMj$)J(3rGDb}x>ny5vDO+?uG$@|$77dHzF-b@Z)R)2f9JLE>*+cuYwY)>?#Dl!jOuLYP>Kmn}UJ6LT+^gAp^?@llgOrQu{WT{l{%K5uJ4M33 z<%0F7+-Ewzl*yp{V!J@E$?@+(yt3+{!l-$95#Rjv<>KTA2cr!3Y~qM8ZGv3=meRXO4G`*G{%*l7iJ|5u=5`qGZOjsJ_5clp}caSa>GL1u>+CkN}* zw&AEv%S48tm-&{Q!z=h9XyGe!wZ&u>?L-GygIceN&j1zLAM zMkm`DvSsLAQIriSL)(9)JQB2b(YUxYbK2;Rq!HMTq{!2OiD`D=+1V_r-<|k;Bc{W>GE?>t+~?bCn9sbY;A$J~TT2!PdpeCNwwSG2>6 z=^$3`)7+T6yjs9J(}hQ6#Qw9A?<@7^3se=0<*Moi!7i+W3FuWZN_6+mgkis?!7zxh zYnSh{ay1di^EnQFTZ2VZBE0>^JFgQ=#R}|d%q~xR`z=GJ;H72x-w>{e#CW(EFy%4g zU1&xOiFOy@JwI$fH|(=+9F6J(oea1)<#THx+$m3ti%)~A3v#y-V~jc*#j!xnW08+V zLQU!YhY;~=U>-v8NX-xZ#X@WTAj#%-7Bbq%t7z^CCVf4ml8&v$uPDGPCCl9LulZI%3PI zbU+VoVBmp%hlSuD9>6=|Z$@SUO{8Ro{o{Mh#+n({y*d3B7I(g8PLlkT<86xdnQ<^* zQwmX@j}MMkpWEf50})}$0o)SOWmT;kb0)u-9|~cjvMDZb-JrIv*_A7XWcG%9 z$6avS{bF15MvOMZs24WC z4dm^kaCSLoQ(~C|Fcj~7s9G03qwF$T)KytHn?vHPk+(UuB=yJ9*7Z6a-($3X zq2+DNcGDGOp9X?s*Z$LNf6AjqWuv?{XA+2xNia_wreBC{qj2{`WKjT=vt7dUmD9an z=^XJTH+DHrHV%mDpnW3dL<|Btmsz{7LgFGXTftM)#?e9PEjnORZcmZP#%-_hNJ}+k z#Vs#3dmC>>2WL<%>xGEA{6f*V}p1D>6U#fEd^_fJ$t zU;d8J;g`$4@Mg7w8?v|7?tW_+**nvFZ$y%}eFib^QR+nsV#BXZG?!-E=x6k z{)myzr&0@A|H{o8pgb*D;d>H?cJ^SSoUnNd87O)jc9cjmcQt{_#anMTgnbw5LVW&V zC%d3i6fb62NHrC!ORPadrUCan*z->#L#+829&Jdjpfir)FN`$YdI)6d@^7p;-~T+1PkhdyqFj zPcS}-j06JUhiQUMn*}tEaw{geP22H(Ea{eVEX<=)%v&zINxdNLepj$dyTfcF zRseAi<|{1AA{#mKg|^r5a}0L|@QnE`muNquYPGxM!@iEIx3iCvd+-6{o|Tx0;B#(r zNejf}!hp=O(Y5hopTE9avU+Kv*lZiu>gbm8GWw z9rPCL3J4@`k5Qcw>lJ6*cWi^WM&*A027kcSlZCqQf=#&|UB?h-98RBT99m5EnIWk* zc7&(MDvwqZ)vRpws@wA_dpYj;{ED*ZD?-xSr>}fpV12#f6u()bSv{LW!%ieLgIQ9{884R`YRham*6mEW}ANzCNju6`ErAY_Dot4G_{K zmUbjpm3e$#Xe@wjR$IgbO^+E1N6{_i=CY8_U{uvYk@Dku{Tc}HUG=*KKHc3#eSne( z42ic^NnT*+A6w~~n@R-ud>e3)Sjt|i{d%?Bl#I4XyS<0a6um_{PL1q$SxJvk2|0Z? zDQ?Gj|3j^f|4Xx!aWZCvj?&?cb?T!`oTnCUR%o^erE%gD2@O~C8=*&4(#x=n_q&kB zNoC8z6yc=QSWcfao(pr15cB&26N_RWD%`Xy365@)5J_q(u{@dBlEOB8A3fH44}`0Q zn$g@@zLYli)|z5kVJfjHjsC0_7X`Sa9MZyYPnrj(>|*n{Kw=s3Cih*NpE0n!^PQ8Hs_vuh<_g5mm$Q;vyP*F0ss4Fxa^bH1Qi!Ow(EDK7TRbL{rz{sGzqAu4)yD-rdY3gzl2Z5%B+eF>9{rhP6thIhZU|Zd7;M1F z{3E+Nw3futDp5*?tF?zDN3a&>P3H7lqBB_)04PPhpHepjKT0&enM*e-jttU390ca- zl~0dT-$>1SVvovrvVeJfiteUX!MTv%__q1sbpe0l&d0*Z>ozY0 zqR9a$l;HIX+-2Xj_MX>SLf3p`1-j=S^BfWNdvygJxC(`W^2VfidPK z41rjL=G^-;dEc~E1=d0U4EZ3Hs=B$Us@ZW*h-(qnp2kYZXcig!1dA5y=DOGtzdZih z8AkaQMhbQjq#FAu%W4?y*1806uOrLY`KTw*Z0uBnV?iVvD;EnTQm=$YV5C?xxyGP1 zlHfuUvB=Y==yaJYL`vCnVVU`K{)i>E80H>=S5dH?Pa&?!U#pmw*865gY$aqB^LTstEn*?r7g;3{ zntRd(k5XBrrtFzY$<$Umr6iq0RNB;f)k3~dG7BRJMXcsX*+SaIAZuBduZ~J*8yC@FQkNM&l^9xYiHkO>OQd^Ji0=@iWmWEu1zh4C8 ztKi{DC3+-g7TImec+3#1m{%bp;@sh^^|`mZ2U5s+6%j56QCSs~dTe}D!~V0u9;!V8k#uG>m^EjG=YhBTM>EPossIkjZW z&56IIAM5;WzYm{%UXD$iHm{~n%F@V5H0Qet@?brvr zkj4Kj7>GwMH-dKx^H}yz;A%)}b4ZlVwJ(xa{Oi|DxP`)nT&d9bf@7leevwtvReXfxM6N}7csFs6ic9SRWSr{ZSz9Gh4IJoM1{CgbXLua zD~+D8xcBw*G)smWQy^ch&fAVZ3Af`vY85kCo^%_pjSFgG|BuGL0;Y~=>$*@1#ih6x zmjd@*oZ{|Qio?Y&aB+8vySo%A?(S~I-HW@s6qlcuPxA7=mwYdoWX?IWk4$DVdu7i) zYgw6G?(L|{$^eBw+oW5-ld#5l6}cfCv+lzJZa!#e$~LP z+6aT?`%ENQb80oUnFmH96b|KLR9kFHnht!TqZFX=rKHLa(pd;9C90cwsVj2Nj0t3l zdyDnt#zPJ29~XbAna^#~CahM_x4lZ`Iai~zEM1>|uH)Om^!+I)t%QFVE7B6`RlO`Nia&eOni-zIh@C@DeT)bPK}`)2?Eww| zwt#6bZ$zsVjT=z3RBDB$_8TsEN2;Ct1Nm!DKIUoXz7>z_pp!U3U0xNu_Mt{ z-S~tNs!6nED@ecK;e(@o&3|**(RqykM7VJQ^M{Dg>ErnGzH*qRxdwI)6+)(rh(SBU zlExQItc)%`Lap*XHt&YD-!UFG47Q*Volv>*=Zz50b1g?F2jqqpRuc^5wdx$XAG#}! zkaba&Nlj48zz@~Xpw?A~Uj2a*6sg9$fOqoylox3@fcA)>kUx%l>8xk;kCrptV4Vqr>RQ8aqaf#Hl$DbQO0R_KS7()zI8P zB(BoKRAf}sKB~>y+frNn*W=_{_^tEOw%iO zKl@Kj7CncHjU;?*08^rBiNzn@OFR!7BUY-i&H*Q7c$T~q4sa>K0{;aw9MPvQWCt9W ze(J$4Ox**7VsjJ;xK8cnJLPKzHz25(V`C0GXxG{2QRvDaC<8?=F5Gl zKPs!2)x3vQ5T3{4*V3#4a5kje+9j#3n?JSHsh8*BObhNVVavhg+$*_9;Tu#|#QNcf z)om8l)oEGR$pESY&`TiYP&g=R(eHJ{(7!Q@@z+$p%*^GTYARk0x*x#3i7Ir&<)x}* zSSo?~TNt0Wv42wLD^rb;3&dTT;!b@GLYUL4*TK>=t#DxvaA8h;2UCkVr?D|`SYMHu z(Z>G78H<}CG}vrxE=dt)PTkulD^_1NVYElpX@Dm^2AD2~LKll6O<5-!24RLB#5UCq zKS4)2>Z4!iBX#-o$aUot;NDdk8i5$^?sUt zbvO{%jo95_LHo*_`^w@5LJ5_v=C{WztEr28fo8^dJcnUiB@&L2_6u}`LY5f==by7l z_Zvm#)D7dja;zm%@Q^>dx$!#fi?P9)BylgZR(%W=3zEJug@(j$gg@6!(u*yAD;DfIWp z^`oxY)P0@4?=^UQbdgu3v#4X~|2y4sFyDKNygXt@y?L-Od3>6`7q z1MG=QFde{^fQtzE7+0G=f@xUZ8e|wzN%g%16MS?k)0Z8b#pT$45ij->jKynZMY%v= z>(`iW(jXfsGNIquO6ifEzWN$5{KA{Jr4f} zvO263JC%x>APnPg>47nv_XQ!B7z6*LHc1G`J)7u4uDN{quoolbNmI&)hHe zLG_(@%fswu9rTlpyFuMf#ufxqy6skO%DkVyjwNo*N_w@;Y9k&uPJmAXD?CQOaP9kA zdFIl})S;+Yj;f`&*U_6Eu{a5|6&(R}hAI>0q|d|KlN6oHypmMS6B$$L54OK%F@t-o z59=PS-M&2q`3iXmxbZ``g%sRR9fgZxR|J}+NNTwC!; zgKuzYR-F$aCy<>Us@h9_KM=|iKHj;^b5lPD@;@;S^5$#moHgG?=&7m!5>tgmhE_$l z(>k^Y>IG@n?FRVW1$kEtWnt4fhQ(9 z*3Aw_SJ^%HEavub0Y!?Lu(2;Hx!WN|KQ>%l5c?{YozzjDeh?!J)?lyjx)_)26JA%N zaW>a=UxeT;@5GgPAsR(P^T`r~R+25rm7A^)@@tPWqA={-GIUq9QQ@A&Qt7D-8#Nc+ z`u=T~$UQgK59$68vKp1s(pItTQzm5;lcwse@rg?kF~C@Zu&Bh4emi&mvco{Ph>Pw7vLf?X3MHkX0td{PBj5 zK@3eeX70B%%qsegX4U8wqMqcY_;|4gtVb#%F#xv@WUEiVX@Bv&p3g|H zox}zi{DC_BWvhE>f;D!kypaNt^i&fT94y>JKuP5BCZ|e!jNP%5XkUxfYOb>`Y-ndt zB&!`G+LjU#U2V~=p}>pu8ab+1#4E}#6Btg+=f>g1%*f%IvBfVX844bjt@N`(!JYuZexWM~A zwRO#A_pm7R9Sx~lCZl=IRUefT#Rz=8(7T1+l_DP6rYYGh@QKaIqh`uEQA!Ep?35XVG%N{R8Eequ^N!i)Vt znnUu;n>slpX`I=4l~{SX>U!M6t&QA_gWd57O)66>P2MPyr#~~7+lV@(lk7uP`lk|( z3Go+4e{eTqKjkZ%khpTUJO~^$#I+TK(4SVsOOGrIP}?IB6OG9&RVv}I-e+YN~< z;ujqPn1nki30kE|N5@Zh?wEMPisxJKxalTC0dfptO09Svpqh2#@pr3u%ih(6e~KzS z&X2iN;cneaXn)0QssBAR{Jno@+J;v86sR%Iny7dgxd8qlW5jJ*sa=ao42RGz#7lPb141R*-MBs>H{60;XfLlX^TSjPi*%e)(Co zg^%BhKZVq*pdY(l^NXKzhgs{gPPjt8MATTM0u5@GfV!;w+GeV2i6@vQrYTW|NE_if z=Xpwgad2V&qWAWu^?CB;jHNmuo&NJg^KFuJL(GlGnZVbeufnMWyVs1_^UgT>afNp7q%{S_%BZ1wy1VDDy8p(oex#2CR zpEGA`C&;QobnE($k@4q+e5vUfks6p;fore)ul(F4wHF?s%&~S{$JS$eL&~`8v)iCE zw9l0a2xVn3oOYe4;r%3q8dW_-sYJy*T0;l$e>OJBzqXI`OT?Xp9o)|^c#X@`tl>V# zaPO7|GLJu!C+#tM3(z39K7sg7`EGROf6OR^U7dzhsj%+2PP%K4?ntD1M0QB*&y|u5 zO=Fp#g^=#mR3u4+RZNFn#a*nOym69#eR2CmbZ35PD0I4KfW&-*?nbHgczp761wF`P z;=QJYUP`sX)9swv*n-86vB_tF%qvt`{?*_pB8|J-#|qMpRcijz6Eym8_Vjz316+Gk zYfw-}_n&1mk&OEBL8qtHc8Vh*r>)1@YLd9##%Hn{*xwnw4jz||4<}kCyf0J&Xx<$I zVo#pbt+QcBqE*2`QC>sc9vY?2f`?y-LW|7=1B|fQj6X1`54af0(Zfmo#?=kse^47*@X|nKRJn)J&IPW#v_C&@~?7+r>$wX z^`eYvYibsgrLY18D!yi2Z!a}KhhJZ^jUZ0kX9&{KG>C~~`SDE-_rp^rDlge_%~x^5 z$e>U!-7(y_3a~tWu{(y~k631kim<^06%JS6eVA%n@=IeZ@$+oRr5lPBXLaScZoAvf zA$R7D;HGIhRU~&_5cjdZU#$!#wNQ01`S5#G?JpC zVdwl|^oboyxuip6+awf9%xO15eH z&~ZBRES|VO`Lki1R7eONZR#%yqRx)^hjKM^R=6l<%%cs8e*MhY2-(rFlPHDEws+KI z@Za2cw8r+8RzoK%B(wZpn%4V^h(PgeHp=;Exs~`Gd zXt%-R`+A7G@pINYP$zzFMnV5m4-W9Tm&dHhA947To|`yY>orhM;865$<|hf`xpf5I z4VXVW*3$b(t}@Lm3UnuY2Wpzn;vAN*Cvht$A~d#i53~nkbi9Nn!hf=bYS93(8i zr)K-SV&feQ+mgET)6TXMX|6*`?}rC^M32zr^Y;fKADzlF9Wb=#=pk@fgBwFc6Skg z#YUwy+Y*k0>Kw&{?WOjf_VGDGc zC#1|UJVIELtYJP<3Zzjg|C*~4qkOn8pDXz%Kw3=dqmKV{qT&>DgANzE32L)x<{tN6 z%AUs6>)LJm+N;j0f>%gO5HKw0zQ+QkHv(!@{K4j`(l$p4CSi#DTaiO-dpoT!@`i#_ z>2rDqmWeHy7Yj@GeH4 zixD+VPODZakCO9AZywPbGuZ;|R}3_>N3J@-2g4x^ z#kMI~5+w@>4)vXf=tn-fh!A1w>>*t{xBq z-jw9c0E#ZqpFt}ukz`4*1q=W!Sp|M{IUH?W?_H4H2kf2q8Aw3h(_H#dQPd5616h6%eD2MRX<0CyA)V1~FMYW~_+t<$ae z*L*uj{44#nHLJm}f46N%7u>q_4@v)zIG;Ycr(h&{AfE@);?AM⪚i8=+Y8XIC%%a ze-vmykExDPOx}xJ*Y5I{?K=Tvy%cG?$A?|Sn+uzy!b(#3U{f( zdOu_b`(?h6G}%g^u87uTv*-)1Jmx+7MwkCps#g_xqnZm*(BLHe`YGro`EOtbw<>n6 zEh)R{(G>|a1otWxNjm@Pc`3qaW>k~!N&Ju@$GKU%qkS;S=Mr|ejd6E50lgFoNVCRX zUb>)ruJfB^>1`ro{UqM9&CVpxjgUL0 z=rlvZSZhJeoHgwy?5D-UQ_pP{X>QY(9|Dix&BNkfJ=m1BX0aDY_Z}h_(wfTT6I4jI z|J0TUVuDw}sk2UX)dx3iMk}p5$A^yvhBiI#(~l^KGx=VJmlSaNahLD*f4XY_Y5c%= zdmHM&O2%cVIc*QRV`kdip01*+$E9U&aeOzlboHon5?BvaqOjwz^<3{3kTW-10b8#6b39mQldZ-}f zVcW`{Gt#ActE_uq*VtU~a(Hu;A&s@>o2+jJykgnukJsjSoFYYQ6)J5YBA#>MhfYql z+ABv-Ph8?LV+)OMYD^6Bhpx~R7Syo)@I}uym(qjhn1$__XE%vc7gYqM?wX^Mz@=TD zsF%kJ)(WKNTUP|}m-g;7Zf0HUP=u_NzjGk7`?^s)9D6@rbEzgCW7-@_T-py3%?=Um zRACNbF69F0-vllTXAh%rZchccisN>8tZglv8~?7d%b<}Eq7)tMIz*TF=WJ*M86?3M zWH##IN<{rVOih^bG8_&yzRkYXkCw>kf{YKNS&C@VO7}kdon@R1*!)RVyC27sy79&0 z1AmXY?Js5Rc6wf9_fn$k1~#Ue?rt8mG}#cq;Z_xHh9$D*Ur zO!jqKv)q7;c{E38$YItCMfQP}*x@%6nIfFQ53~BuK0P6nZs$d0bStOC(B@ zZflorsPy2cAJRvLH8cPB#i>-}*>*WKNGw^dxuyr7RaFEFaN?J9ivAtGLE22h=C?+h zwcAOA58oRZD>tt0@s}LF0PLuxmO6$0XOA?2b2`vNxY$?=*~;i5{3E(r4eo7vD2LZl zv_{+KWDRH$U)pN)kFwoPpOb=JT<1!o>Xu80efu$RCNE3W$)nN6dD};U({RnPe}jEE{~7xTIXakH+tJaps6ZVoAaCbyjs|8BLx;DL z$eUuc!`n4keHDm0xii$kl-%?!SHjK?VoYwMZ)mP>0-G66Vg0RY-J zJ2`8k|I0+hPT$4`V)UkOt#4ruL1Ix<5mRRtceJoD(6_RB)4irsF@@Tbza9Uzo-gF8 z5Ig&~smWQHfowo_ZV(4M6Ns7Pf7bbC|8{S(P$vjE2moYf5rr5)^{wd1&297@Ozk21 z=bwP*TW;6kzfDQjY}v>xmQmauPA{-K`?lR=0uZrbA66u+}_M7Q#R(dz>T&FjUG$2-yW6MXd2_wUwS-6WA2}6(IeSBb- z9@F0s@%nVCfVYr{M}QukVLbWLZ+&7hSvp^?Cuy)NT&tcmRweEe1)&gL85IcEM&Ck| z*wD1z@S`7kDA#nK2mGX7KDvaqfsH!i-LJ*R>p}DI7k4?uoEi<26QhPd`4tPsM+=uC zPwzD|7IUBz&l6Fap1xW7I4sV=dwiN@qYBqMIT-tt1sI-v1ef$LhwP~>V%1~buzY@Z zf0?C{SO{VlZwcWI7xk(EVQL52O}gb+-@>c6`{9<)32UC;F%yJ)g)}I|W|j1v^Xxe( z;|uB`0twwR1v2koKDBucTTH58RZNCDhd_lQR-X=-J)SVGwOEhj1}#O&t&E4nX;)4` zJ!0)Qgtr&%f^^BOavdftUlkQlpLAY}SP!>d4m-oX@!ra~D0e<4ZTX#FG|e`+9Q-Ol zYCGorQ6RFZje<^=z3O4HF$8n_iho)%yiqoHweM=W@dHPG&^obgox6>A^Kr zTGt+W%W?CV8SMn`aT7p!OEB`q|aXVj*KJ_cBi@}4X!iM^9Qq= zbQjwjUT*0&@fiiO9|ilNiw;Uw&HIg8V^8=jaU`uL9M-!j`|NH9w&+OTD_O!XHgXQkW;YWIcqGWtHdrU)=t@2MSlzsEE-HTn>^ z9Bm%Iwj^D5O}I0UAUYn8k^r$N%UZM%usGDDOEfaM!N_I2pN+v{haoEiL zM6m@V-BPYO*W&tIl6WoV5K&y^=H$WxwFY6X1#*vq>;Ij<Py7$_U~@ zt_2_ma&qY)v3!HNLHkYNF&? zyxbshA#N@aEPg{bMg$o;4FEU zgf(Ghvd{?iaY_T-#MqiILF!{{tHynhp*{F>WX)X~IuT?Gf7A(Sp9Ctxow`mLT81ljlx#A=TNS=N^fN^Z{dzzbV;V#> zQai#A7^8mdbn+f|psi(We$;MyUoS-K=NY_GiR{!vy6@9Af$Uj{&M;9?*y_;s4EQKw z^A4^1Gkzc@7m9=)c4Rk@3ypT2D$RG=27Zj;fvjbcyLa1n+O@Z4PaY5ZEHIs!fuD&- zNBQaL)Ir1S;n+cpu$W6HfrcloTuMQgJ3^{rjVnTiZ0)N~(vMN@6~*GmUA8PXzD>5G z>wUjzxx9ut#+JNVt}_R%gMP9C`n-+}2MIAP%hTG>t^#>hhJ54n(_$B{QwN3KFa-JA z?<4c7fRat;lZ7 0: + rel_diff = (chi2_prev - self._chi2) / (chi2_prev + np.finfo(float).eps) + print("{:9d} {:20.4f} {:18.6f}".format(i, self._chi2, -rel_diff)) + if self._chi2 < chi2_prev and rel_diff < tol: + return + else: + print("{:9d} {:20.4f}".format(i, self._chi2)) + + # Update the previous iteration's chi^2 error + chi2_prev = self._chi2 + + # Hold the first pose fixed + if fix_first_pose: + self._hessian[:dim, :] = 0. + self._hessian[:, :dim] = 0. + self._hessian[:dim, :dim] += np.eye(dim) + self._gradient[:dim] = 0. + + # Solve for the updates + dx = spsolve(self._hessian, -self._gradient) # pylint: disable=invalid-unary-operand-type + + # Apply the updates + for v, dx_i in zip(self._vertices, np.split(dx, n)): + v.pose += dx_i + + # If we reached the maximum number of iterations, print out the final iteration's results + self.calc_chi2() + rel_diff = (chi2_prev - self._chi2) / (chi2_prev + np.finfo(float).eps) + print("{:9d} {:20.4f} {:18.6f}".format(max_iter, self._chi2, -rel_diff)) + + def to_g2o(self, outfile): + """Save the graph in .g2o format. + + Parameters + ---------- + outfile : str + The path where the graph will be saved + + """ + with open(outfile, 'w') as f: + for v in self._vertices: + f.write(v.to_g2o()) + + for e in self._edges: + f.write(e.to_g2o()) + + def plot(self, vertex_color='r', vertex_marker='o', vertex_markersize=3, edge_color='b', title=None): + """Plot the graph. + + Parameters + ---------- + vertex_color : str + The color that will be used to plot the vertices + vertex_marker : str + The marker that will be used to plot the vertices + vertex_markersize : int + The size of the plotted vertices + edge_color : str + The color that will be used to plot the edges + title : str, None + The title that will be used for the plot + + """ + plt.figure() + + for e in self._edges: + e.plot(edge_color) + + for v in self._vertices: + v.plot(vertex_color, vertex_marker, vertex_markersize) + + if title: + plt.title(title) + + plt.show() diff --git a/SLAM/GraphBasedSLAM/graphslam/load.py b/SLAM/GraphBasedSLAM/graphslam/load.py new file mode 100644 index 0000000000..b0dd023d93 --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphslam/load.py @@ -0,0 +1,66 @@ +# Copyright (c) 2020 Jeff Irion and contributors +# +# This file originated from the `graphslam` package: +# +# https://github.com/JeffLIrion/python-graphslam + +"""Functions for loading graphs. + +""" + + +import logging + +import numpy as np + +from .edge.edge_odometry import EdgeOdometry +from .graph import Graph +from .pose.se2 import PoseSE2 +from .util import upper_triangular_matrix_to_full_matrix +from .vertex import Vertex + + +_LOGGER = logging.getLogger(__name__) + + +def load_g2o_se2(infile): + """Load an :math:`SE(2)` graph from a .g2o file. + + Parameters + ---------- + infile : str + The path to the .g2o file + + Returns + ------- + Graph + The loaded graph + + """ + edges = [] + vertices = [] + + with open(infile) as f: + for line in f.readlines(): + if line.startswith("VERTEX_SE2"): + numbers = line[10:].split() + arr = np.array([float(number) for number in numbers[1:]], dtype=np.float64) + p = PoseSE2(arr[:2], arr[2]) + v = Vertex(int(numbers[0]), p) + vertices.append(v) + continue + + if line.startswith("EDGE_SE2"): + numbers = line[9:].split() + arr = np.array([float(number) for number in numbers[2:]], dtype=np.float64) + vertex_ids = [int(numbers[0]), int(numbers[1])] + estimate = PoseSE2(arr[:2], arr[2]) + information = upper_triangular_matrix_to_full_matrix(arr[3:], 3) + e = EdgeOdometry(vertex_ids, information, estimate) + edges.append(e) + continue + + if line.strip(): + _LOGGER.warning("Line not supported -- '%s'", line.rstrip()) + + return Graph(edges, vertices) diff --git a/SLAM/GraphBasedSLAM/graphslam/pose/__init__.py b/SLAM/GraphBasedSLAM/graphslam/pose/__init__.py new file mode 100644 index 0000000000..afb8549087 --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphslam/pose/__init__.py @@ -0,0 +1,5 @@ +# Copyright (c) 2020 Jeff Irion and contributors +# +# This file originated from the `graphslam` package: +# +# https://github.com/JeffLIrion/python-graphslam diff --git a/SLAM/GraphBasedSLAM/graphslam/pose/se2.py b/SLAM/GraphBasedSLAM/graphslam/pose/se2.py new file mode 100644 index 0000000000..88518510e7 --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphslam/pose/se2.py @@ -0,0 +1,171 @@ +# Copyright (c) 2020 Jeff Irion and contributors +# +# This file originated from the `graphslam` package: +# +# https://github.com/JeffLIrion/python-graphslam + +r"""Representation of a pose in :math:`SE(2)`. + +""" + +import math + +import numpy as np + +from ..util import neg_pi_to_pi + + +class PoseSE2(np.ndarray): + r"""A representation of a pose in :math:`SE(2)`. + + Parameters + ---------- + position : np.ndarray, list + The position in :math:`\mathbb{R}^2` + orientation : float + The angle of the pose (in radians) + + """ + def __new__(cls, position, orientation): + obj = np.array([position[0], position[1], neg_pi_to_pi(orientation)], dtype=np.float64).view(cls) + return obj + + # pylint: disable=arguments-differ + def copy(self): + """Return a copy of the pose. + + Returns + ------- + PoseSE2 + A copy of the pose + + """ + return PoseSE2(self[:2], self[2]) + + def to_array(self): + """Return the pose as a numpy array. + + Returns + ------- + np.ndarray + The pose as a numpy array + + """ + return np.array(self) + + def to_compact(self): + """Return the pose as a compact numpy array. + + Returns + ------- + np.ndarray + The pose as a compact numpy array + + """ + return np.array(self) + + def to_matrix(self): + """Return the pose as an :math:`SE(2)` matrix. + + Returns + ------- + np.ndarray + The pose as an :math:`SE(2)` matrix + + """ + return np.array([[np.cos(self[2]), -np.sin(self[2]), self[0]], [np.sin(self[2]), np.cos(self[2]), self[1]], [0., 0., 1.]], dtype=np.float64) + + @classmethod + def from_matrix(cls, matrix): + """Return the pose as an :math:`SE(2)` matrix. + + Parameters + ---------- + matrix : np.ndarray + The :math:`SE(2)` matrix that will be converted to a `PoseSE2` instance + + Returns + ------- + PoseSE2 + The matrix as a `PoseSE2` object + + """ + return cls([matrix[0, 2], matrix[1, 2]], math.atan2(matrix[1, 0], matrix[0, 0])) + + # ======================================================================= # + # # + # Properties # + # # + # ======================================================================= # + @property + def position(self): + """Return the pose's position. + + Returns + ------- + np.ndarray + The position portion of the pose + + """ + return np.array(self[:2]) + + @property + def orientation(self): + """Return the pose's orientation. + + Returns + ------- + float + The angle of the pose + + """ + return self[2] + + @property + def inverse(self): + """Return the pose's inverse. + + Returns + ------- + PoseSE2 + The pose's inverse + + """ + return PoseSE2([-self[0] * np.cos(self[2]) - self[1] * np.sin(self[2]), self[0] * np.sin(self[2]) - self[1] * np.cos([self[2]])], -self[2]) + + # ======================================================================= # + # # + # Magic Methods # + # # + # ======================================================================= # + def __add__(self, other): + r"""Add poses (i.e., pose composition): :math:`p_1 \oplus p_2`. + + Parameters + ---------- + other : PoseSE2 + The other pose + + Returns + ------- + PoseSE2 + The result of pose composition + + """ + return PoseSE2([self[0] + other[0] * np.cos(self[2]) - other[1] * np.sin(self[2]), self[1] + other[0] * np.sin(self[2]) + other[1] * np.cos(self[2])], neg_pi_to_pi(self[2] + other[2])) + + def __sub__(self, other): + r"""Subtract poses (i.e., inverse pose composition): :math:`p_1 \ominus p_2`. + + Parameters + ---------- + other : PoseSE2 + The other pose + + Returns + ------- + PoseSE2 + The result of inverse pose composition + + """ + return PoseSE2([(self[0] - other[0]) * np.cos(other[2]) + (self[1] - other[1]) * np.sin(other[2]), (other[0] - self[0]) * np.sin(other[2]) + (self[1] - other[1]) * np.cos(other[2])], neg_pi_to_pi(self[2] - other[2])) diff --git a/SLAM/GraphBasedSLAM/graphslam/util.py b/SLAM/GraphBasedSLAM/graphslam/util.py new file mode 100644 index 0000000000..070dc1aa06 --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphslam/util.py @@ -0,0 +1,78 @@ +# Copyright (c) 2020 Jeff Irion and contributors +# +# This file originated from the `graphslam` package: +# +# https://github.com/JeffLIrion/python-graphslam + +"""Utility functions used throughout the package. + +""" + +import numpy as np + + +TWO_PI = 2 * np.pi + + +def neg_pi_to_pi(angle): + r"""Normalize ``angle`` to be in :math:`[-\pi, \pi)`. + + Parameters + ---------- + angle : float + An angle (in radians) + + Returns + ------- + float + The angle normalized to :math:`[-\pi, \pi)` + + """ + return (angle + np.pi) % (TWO_PI) - np.pi + + +def solve_for_edge_dimensionality(n): + r"""Solve for the dimensionality of an edge. + + In a .g2o file, an edge is specified as `` ``, where only the upper triangular portion of the matrix is provided. + + This solves the problem: + + .. math:: + + d + \frac{d (d + 1)}{2} = n + + Returns + ------- + int + The dimensionality of the edge + + """ + return int(round(np.sqrt(2 * n + 2.25) - 1.5)) + + +def upper_triangular_matrix_to_full_matrix(arr, n): + """Given an upper triangular matrix, return the full matrix. + + Parameters + ---------- + arr : np.ndarray + The upper triangular portion of the matrix + n : int + The size of the matrix + + Returns + ------- + mat : np.ndarray + The full matrix + + """ + triu0 = np.triu_indices(n, 0) + triu1 = np.triu_indices(n, 1) + tril1 = np.tril_indices(n, -1) + + mat = np.zeros((n, n), dtype=np.float64) + mat[triu0] = arr + mat[tril1] = mat[triu1] + + return mat diff --git a/SLAM/GraphBasedSLAM/graphslam/vertex.py b/SLAM/GraphBasedSLAM/graphslam/vertex.py new file mode 100644 index 0000000000..6fb1f0d098 --- /dev/null +++ b/SLAM/GraphBasedSLAM/graphslam/vertex.py @@ -0,0 +1,67 @@ +# Copyright (c) 2020 Jeff Irion and contributors +# +# This file originated from the `graphslam` package: +# +# https://github.com/JeffLIrion/python-graphslam + +"""A ``Vertex`` class. + +""" + +import matplotlib.pyplot as plt + + +# pylint: disable=too-few-public-methods +class Vertex: + """A class for representing a vertex in Graph SLAM. + + Parameters + ---------- + vertex_id : int + The vertex's unique ID + pose : graphslam.pose.se2.PoseSE2 + The pose associated with the vertex + vertex_index : int, None + The vertex's index in the graph's ``vertices`` list + + Attributes + ---------- + id : int + The vertex's unique ID + index : int, None + The vertex's index in the graph's ``vertices`` list + pose : graphslam.pose.se2.PoseSE2 + The pose associated with the vertex + + """ + def __init__(self, vertex_id, pose, vertex_index=None): + self.id = vertex_id + self.pose = pose + self.index = vertex_index + + def to_g2o(self): + """Export the vertex to the .g2o format. + + Returns + ------- + str + The vertex in .g2o format + + """ + return "VERTEX_SE2 {} {} {} {}\n".format(self.id, self.pose[0], self.pose[1], self.pose[2]) + + def plot(self, color='r', marker='o', markersize=3): + """Plot the vertex. + + Parameters + ---------- + color : str + The color that will be used to plot the vertex + marker : str + The marker that will be used to plot the vertex + markersize : int + The size of the plotted vertex + + """ + x, y = self.pose.position + plt.plot(x, y, color=color, marker=marker, markersize=markersize) diff --git a/SLAM/GraphBasedSLAM/images/Graph_SLAM_optimization.gif b/SLAM/GraphBasedSLAM/images/Graph_SLAM_optimization.gif new file mode 100644 index 0000000000000000000000000000000000000000..2fabeaafc9cd4ad4b71bbf451637bf2560f1be5e GIT binary patch literal 114966 zcmdp-`#;nF|NnP*ZgxOBI83Nv=FCW<)O(xb80HXiYD6ij5v5XXvyC~_oX?t5A!fU?vKay;lXfsbc#*~tAc-m zKoAH-RaI3(Lu1{#btDqW($aFnh7Hcn&aSSmUS3|2k&%IcfxC9?N=QgZPft%xP3;41 z`w3F{1A=@9A^(LTSCPmCi1s(M#tIIonzzYkNL6_g!@K8sD^U#m#*+Jp7M;;78ApY0rc2g7&V)$Nv`_zjFBSr})E1!J=4D zc>=sVS*<(`U+x4R0)to4=v6#^RabYFL|V19T(!4fb#`8LMGv{4hM4%Fz_ml$^@buz zL$MbB=ZPDJQk;iUorlt0hFn}$natIopw)^A#*4zP`1!wWFis`t|FpBGGDj`LCk#51Hk?8ABNvt2sHVMMbMsRjc*&tF5i8 z9UZHGM-Ai*jTa70Rt-IE7@EH@^s;4W@ygJ*>;LBi0|R4YV^5zxefaR<>d@cj>iGET zg9ocmo~*ul^=ff(@#V|a#l_Wc|7WXz4fOx18T!4P;T60zfl|emZ25K%wR_rFshXz%c>1&g$IkPj~Dv$K#;Y=hECKE@=$22 zc~B}bsoXXSyV2#325=+mbOzpYLJ4P-{Zkgr|h(m zSwR-T5UA+jt4GsavxabVf6r0 zvG37jY&pWa3Z!J-IobGmtOrKv*~s<>gYJ%bsma(pDDTGPktqn@tl*!x8(0C?2#RG< zk6Zv`URKCu<9s8i<-B}1R$U-J1>N7I1b@|Z1(6_IL3&~ptLbMsrZoO~8p_py3yyeN z5Nrjt4;V87am%z$IF1HT#b;7}dV-!BJ4!&!sw6$5s|00<5k!vz%7EsJrb>}|DWEK* zIL$i~Vu0D5RcQclc~E;I!D#znfII|bNvBqcHZFm3xdnn~+8QEtr}-%A9^L$Y@O zoaQ5I!#TXaon3)&tANsUYH-j z#EA{gnbQE`=9V(8_s5i=h;0GXHvUoO&fDwH@3p;Q8bZ?D->J#o-XZ?7P@hYLH$q9tDg+wRS;#fI!X{%hvRNi<1{xQwiL%LPH4^Rotfu+Vw)#CAiF#=3c{HI6yl zCUwHe?pa{+J{Oe!@dW58Iwb@RO&K#|CB$W(EC5IB8z?#O!i-YmakabE|NZqH8l?*z zrv#{wT*@#1+Ah-q>f%)uo8MNsj^WK8-aV~Dfgh`X`u$buVe{wP!;pi2zO#^Q`Hz_+ zpZ@%u&9qrro-aMP@@wJzrImjdyFRV_w{+X4Zy6#Bviz}}k$TGOzc-&&1OMngU4DjM-Uyz|`z`eUW1cNEDQo%J*G0tUF ziIl!QJ1rcUxhF?Af~z9y<^hLI!MG|qaivuPScE!i;JxOtQ%Qooh?oKDTTZ6gtic)+ ziqL{d6xPYyFqxjNHTGCTPv<+h4ZA?@Fh8hsFIVH}vS{NX1>!RmJ%s*sw7a94xDYm@x4sLmz*h*0}=`lfmCyr}FYv?TMvVA&q|H(?icN)VI`VjIpCPz7 zXq<1X#zPzk0BKxY;R;Q|ni zeEu4jnHQvF3X-cXkZRJ*8Rm0idcAg~dE>?~h{1!MCA$jo*SJ(RXy%|Z zpy~;Nu4u$~{BKlX+Z{t(w;!fcz(I$XZ8*(9xWazC^Yjd!)oA3-Z{0WtH;YO-=h9^E znkV-$yQpmPs`iX^QJ{8eO%naSL$&u+j9Rh_A@$R@bl-qf*45D3tE#zc)yHnRl47bo zJy#(3ZdPW%G{0Er2{9x^XOU!=yVl=$t#^Oa&Ho`7<1@Rs_J|qmKrl$-a9X`tvzhN! zUkAgfKUuURrbtn@;WcLWZhg@LiaOAaF2N-34D5dP#=I!=L2*os*^UR5hS7~~G7=6F zeUEO+D{YUY8wwUs%=Bnv;vWb(f|s?iW)8L9jjm%k=hf#+mj&n@uoIU(%}nVwDvq%`)-kr6u*or_t$|YFHQ``3@hsY9<Nh7WXuJO^TKbZg6l$9}QiXS3l3j=Rzf@m?zTNij%grCE`z&^1 z;l?B|swxyg=A(s_VTbOhvO$Z2EwctE!N@e_RpWvsR0JJ&9xFSz#h42(S4;o_z!mF8 z>D_RXezZUiRoh1u%w8-)xC|?5wk*$y9v(M3=6Gn`%kYdu4>{(bbiOl_C3Ff?Xf{e* z%_1zrnaUT$&ZX}jSZ7f%@UyH{b)i6NU|i4K=> z0g2!>*L`*-evu$Nvoeg+%sxgs(D2`OfAzqk7^nL}w1$s_i~u=eI*D8_ZX5#xUl(_1@>^0T<**m~RJ81HzZ)!#ir790v10rE zDyG-`@MkY^e&PAb27JB=vKj>2zVRr)i~IT$V-<=5cez+eclu#qx`)vf5<&8j#AxZh z^XHK=(BbvPryz5vl}nr8-ZDUa8EBKh16;wLRQO5=H*q7nYZm6c1nW=Dl%xbcehqDv z|4rb~6CeccP1drDXhRX+z#Uw-33ksU1{R(4AOzbT%djS<9@0RyYM|ci-t$8Rw#Ea^ zAi}+gNuo4#`xGGKpvQh3$DIeH++CU&SpOvOU>bE%3iwdb|Czw6X1R436}u20FDlF- zHE`xONA1YgR!=X-e1y9Q_N~n8f2>GI^x^e`NrVX$NCZrYVA+GowM17JHbZ~u@>kpz|&7k8A|DYgDN!P`m1T0Nyl(Ukhc+VFDkk_)^8itXC27TLfZp9yf=(;!tN-hl5!%2=oY3E z6~)0Agd{fIKI1)$Z0L5`Ms%&ua^ErlzNsDI#eryGApa6JA30j8){n~Ej_fY?au31$ z?&cG06K_8Pd}OCq95I!WL+?|)TuNf`Y}l8SglL(cy#wYzCh#!UCw4^&_<_oRq?mpo z(r*@~Ws=0loJfBgw`BlYz68^Ko1jm0yTWj|T8=+S39~Uhir@(jreVJvi5uB|n87Mn zdUBx#L9SO%;5mprQr>R%-ku^Dm*UaDVKy!Sx-xex3vj`}o`=RfdYpOt5z+@#YR&~a zEcsK;705b0@p88-O5`pjY}(9i4;y*3%Y}onGKCs`Od7}v#L;=j?;H|Pu;t0UPxVUnd+m6og83u-UQ?Z=eOHa6(t8l(Xj3X9%_8TYJ$FKXW;QhcUOs z(S*{7^{_yu9NPJ72}#Gt-w*dd0#Hr_XqU=P+B&|s96$xGATa#x*G1E z|9)-wP6_9o8JH$xl*@qLSXelGg&`(k63XdLL~on!3kQRmEZ3^7FWmmve zh;sv&C0Fdo}?4bXoK z_z^J)rH5g>Vb1>tRqsbpG2)zSE(ck?O>bbk zB*+@B_(6xu5Icebqsx`B zCO6=4&drNKDlbI4V_Fr~Nj*3voOl(eecy3YE2=pJORDO{U*`^W=62|%J1!r8Gc@L! z*3_hu-{qm$#lDMacb6w(lHIa=D2TJukn^1`2{O6UmcSx;7sYPK#z5s^k;-kYP6#$R z*EDH#3%1iVseB1&J`xj4J+57Os+xUD8jdMvpVB^pe1<#{?hXH_hfN5I>{PBGqnD0F za*^-RFi+5h9+JxbM+cZ3WTmdFiF51bcjHz`7oF!-<|8JcU^rsvT$UGh*9b7OvAu$w z6rfui9TL*_7?|8Maq~@rEhE2t>6jPj{@TwsG%1)Xl<{yhyh4VIVYN!KLfvP}F1>+O zu{w}X9+V~Gf5Feq{Pd5Mj6$$UCmav|9>)x&B_@XTUXee1oNzdDiF1*vU{h~gVT)-q zz~z}3To*9;5B6j#`XUwn%^6<7Me=|9?_?i$y8wT-+sBs(AK4yTtg7T4pR#YS#LZsc zFo@FFBt2XbH#Z5p8GK*WfP3S1Y8eRTCEL>>OM=)Y;!1~H7i6@R-`6Z1;N>?Sugkx0 zvGqhL7a1+f?^A(qbwVx;!1s$%{XL<263F{l8A;fMJMpd^I&J{(VBbcIisrqZu#Xf~v9%r}PZ(@!-qCfs3*M zCg>@14Ef|wLNo?0SjY=R!mHS?%icg8wZMs-I9r)}s$<|i5|8|z?o*#=?VEz7+`RfcR1m)heewK!`hLuPtGwH$q8j3`k9>jGjEtfbM`7UC zF3$UL*_s#cVv>3^WILD`Xuvsd8)^AA%%~ry_senYIw;8B5Cc!vLbSgqi;F#|0kinw zzim39%Ja>g1Fg9BfzlBm^fhWO5xv_ZKGNMm%9BK&U`j`rEZD@{!`y^V_sNuc9t+L2qxOtgkrB51~IsVd`Wf z8#ao&BoWn|&u9Op<@HgDJWQ^|sm9;_mF)KA%=t7C`^XB4l(>*%jj5z6{AQQ%wNEd- z0isx3FC{Dn1SeejOrYI7KY;3Bzw)7=8)fOApP+7(#FbONgU5vOw7M;Nd|NS# zJGg@kFOxm$`w5G?i+%FbozFoVbbVLranV&mG1?PzR%8FxV~^Ni)a1shp!H?#TX&Q2 zn;Zg9H_zV+u9Dvs&x&8FtxPPY*ED$CnZC%53r$R9N%slL=c7RA4h~Ws0qb6m#XQe! z-}ZK=6j?=qU&{QqEDDS8Wc2S&4C5C30HX6xU}zGs{cM8oEC-b2Jxk@o)YiF{vF7L^ zgql4mODZ1_p8?i+8q0V_JXOne=?MRM&x}^GrI%M{kP0fpKBE21K&yg-nY;U7y zJ{4%v3toY5P**0KA)8bTr;`p$Ol0{J|~c zVMh(WJ?OBnk4GAW@%G4PP1_+44vxo_2cW zB7^;C#vz3^6$##AYdfABF=Uvv9Uly<5*FI_E?|d@tI}Q|O`1a2O!XLg){Y>;92sMz zPFIMyI4dh3X(C;MsM_8nzDE+jnlIY$LVwMv1d~4(gcZ~km+YxVuEY%9GfLmjKx#(v zr_K7~`Az8Fuq5%d)Z5h2TbMmh_g}EiqQ5)O)jbBo+g*PYr0O@jwyf1!RsEorpY<<= zC1GN}0%`JE6D7uR+NNWyXrg>XoeiLe)DDYBinTDMF~&x93)e?bCq=`1_E?>-lAyj4 z9vk--E_I?sh123%*A3TRxg~84L7_mkqNLG^ySSI{h0dQ3d~dLC-@3ng`gCqda8a+W zdqvnTL*>gV_O7kykJm%_NM=^=MX!jxgN4416S2d!FPhK-9cLL;WSFiw)A7xCx|^YG zc`oORh~igxvie@r1ra;%)Lt`k)>^0wd+t)W5|U8k%}-o8Fo$npHYRi=Xwl=_#U~;c zkb4b=Erw@->ev@-BWw*>fw6cw@;<)(xI&vUhYX%mJxOX(U?g(DqICe0TAuMio~&yT zBs~^sM=RuqYU|mLs0_ZlKR@4v`A@%De1G4%|5%jn78VS3$6&Nv<3$HI`kmwHy@PKC zu4>L_8Svpq-SS6`)ob=iG8(>0Jq2Az+Z0;vbteN7OOU}jDaj)FJ6A*8kV?Dk<^63{Nn(NB`RXM4Di(p^z6@>s)yjn}Rq?FK$@>Ax0w zq!_qQnxX<7EgVn$EJihg8o6^QH~zEV3#QPX?PuGqkS zp`O~Fp>HlyS=pi#Leem>qc;b#Q9yE`%0yt{Yi~>#C+3Py6odITVf4Y;$uOLRcWip9 z03F>{YCTa$yXdLqVMa?uG-%`Pz}le^bvL|i-_R5gQD?m4^%;Ho;3yZ4*^_{nuI3t8 z(!i+2?%O9zQ)2rcuYW=* z;YYS_BG%ombp3JehQ1%AyiPsBaTZr2v7@BX4qQy(Yb&VmvnkogD&oj~5j9HJqlftK zew~=zqO}#Yu-O5-Yc^zkXl$@ zT=A2$7*doy?@Z8xbw(DBr8b<4(`%oxY`0atm_B7aXhG+xusAXJ3OPU?riduqIdmjf zfxlSj!MmrHu=*cF$G%_OdxVakoO8;pP{Js=2Kbt4p;ei(MCYLp`lDp8Nx_y2YE{RD zvf+Us1?PTvDEe9LYIbA2$-{k{d&)qTY|R5s8)`#yEe?^+Vm2u94b%^{S|Ll8&0Af^ z9NqtOsMke?PdA3hYd$;{Fy#VoBGeWHHI2U%-?HtPIKSuG>B)?Ze`<4nqC4pEr7ssC zwx-Q-mthC}A$Daw<<}gEOH@$R*`t-`A&Z~_2H%^AZAemooUp=gPUG*8HXBIzgCK`< zF=rCRP?z@`+#Yl%c+-C+!StI^wiH@tnD#A~wVLTh*RP!ho)lY)K?Tte8v@j4!6=^# zYh?3Nu3uXR+G?yyCF?bsd?kp!=xNNYHw}dtQosaag*w{d!7Smet&94+qnmTqj@hE8 z%aCU}H8yfx(`i9S)(u;Xby%A4`=JUGiFE``?UX@=Z+x#HUO33%TjCK3BRqQzw+xKj z&C=@76RpQNEiYN;t#$a0yVj`dLRg5wT_mwgZr^wf8>Y+)`KO|vn5B&@wTt*}+dllMQ)4+u#ep=%Bb?-_0BNP+iLpLW1-mhT(2XDx>dds!`r7L#f8#@X&P$6|} z$O+ZFjrQtfQ1*2v?Z1Uc^?i+PC{&L(B-Ko?zQQJa31D*bo-RP_*tH@#@MjAlxXk_+ z-;*3OV0_GOD@T1}og(Bv!j}bILiZKb9E(D|>Q& zh-*P_23P2V$dDyN3NCwONQF;Wd~Ys#tC(9y_mVU*ejyY*-_Py+T@pIAxd6)VU!iPhm;zQuCw?p$P{zZ0{`A;h!qugI>WGQvdf6>Qeg4zZpK(m2EC zo*oi%JfRKb|z-fX6@ee(W=lH(4e;mF(8ijC$E^n3`CCG`)I% zCXdYJ+h8)h9s7dQgn1y|*0?WJQ|v{Gq|aH`!~1Bd`HOEJ)g zSQNS*tt?Zr!2K(mC}qM&rgq8^fklEk`E5a2*sb;*6BLTmtLANm27MIFgU8-Oo4ahSg#2nW{;ulw0m&udU|No3bqn~{KQ&&^Fzjk`DI7N8a`PQJdUnUw*VVPUH40EVS}?7 z!LWROJRlCSUtbJqKyS;UBR1wa=e4c<9ArXlD8t+hKcT91O~4IwZf!vlC;j@oqVLYdPyed0Cj5E+MWRTwuJy!D4VJHi5lful$5P|^$%NO(GWI~wUJ zY*9ZJd+*V%DUd&Eo&P$A{|Grdpg)thRe$*#Y;Krzp)WCGa$2nrJUsL718e1ug~~Dm z_V$IfPPTI3-a9ve68!g0rbaw{R*cCj=lzU6>pXZ19;V&ae_5h-=3~=86$^pUZP#MU z^=;)f%xSMv$u1#W)bAWq({8|z3k#WF_bTCL+cgDR%-X=|Zwd9cn+E}o6Hw8u+w^k}0=R(*Jy(1+dC_rz$W z5Qlp?U47RG5$GoS34=dSF2zGa8|@?P+x z>yl0XpgS}{=B&4*mXk8tFt@aHolXu{To-m^PIc8ZQNac z?VYGS_{Vbg+e&_GnabovhAM>(u{0|y^@g99USqqnZm!I z$y$H@bH{5hsXDb*&AzjyOCPS;E@xP`^IQ{5IQ5r&g1zha{m=4;&5-8*jMIcoEvGN! z&>y`bju}6^+T@~&GgXg)tU*?P5B$5wsV{#hAZ?2cSr9OZ83ilo-OXN%!SG;F*~8ma zr3p{*6gYLS`_O&!I^D$rLqbtA%q&lUd`an^4M0(p(QX|uUl4Q>L=eefXQ#J^Ei~F9 zvgw8>W@tOPmKz}5b6hLXsmNT@N9WpgK~Lr5cO1SA2>RxU)4o(lq)!d-ATCjJu;Dle zV#Z66I{zGR*Cm9l~ww{9b&NK|M{@fz`6-OVi{c8Q+L9Jm3VimR|3{C;D`6 zQG66ormp|h>0OrXS1UXfmP=DBG+yRMJl$?fcz2;n_{l9;Gi;=LLEx*CeNUKGdkZ|J z^^z|^WSfGvjO03AgJJt%XJ+TgiRL82r$e`RRvNnI zY*6tT8=G=A5-04apY$%df7<+sja>*iIQjV2`|x|Zmi?Ob|LxfxQM!05`%T_~8XPhh z#CKJ_(YQ+hl_lPpRlV1}=&o9VY06P6%P3jetue`v`}4ahw!Z#iy;uignF?Juz|L22 zO)&zRx85gnC;6yR6)ZeS8IS*z*?R&_OPv-^aAr&V==>UM4Z&uj zFtGv9B|==XGTiPDSRkN|gpiLFkS|iM1bf_jK|qz%lDQMCS!lpg6e%skER^s2eCH3I z0(X>u_KAQR@icf?pzq2keagugUa;6T_|>h`|5ZnW5f@yR1!uq8eDs&`z8-{35RQPT z6HI#I!7F=iSw)=H?c21@L#sOk*S82A2z)Dm;s9Yr@oP@3ojiyapItu?ccnea{MJRA zIjA1JouaDM@nGOng=0=Lk9D%YXv6<-Exi>(7@Vpe`jH>N|haZWm5u zf&SMGYx*TvSD#cAkNgCjApGK6{A>C?t7n>5wqX}PKaBd9)afvPa?k(;>k~c!VNO61 z#(omj_JZah7*f+csT{+DSOjYtGKr>hFC-)vYcIlOtWg0HXUfrgoUv<&WWL=z`f_X> z&X`h2;Xz*CKNo!Ez>R-M@N8zWpCUFn?!DIihORJP{$t>QZ=>gq{9I*5@x#`zuH+9Z zJ(JuiSxnz)tAxY*=*YqYd5oBx?d4i};T_Q%zkVDqP1|!g`tqiQNaJJ0j(h7iiSaf& zd#O(8T_fbi&WN~okSj=n9bE)1 z7W-7&W1n^W)GpF^`v*mhSpS3E2so0?zejEE#2z7L%a6bn@bt87pNWEL#h39ct^#hSU*FLwf2?ip9$8rzi)en1#^|Gg94 zt^cdutL*hZqZXx!Gl%fN#|1ZSUq^VLw~yoJZ$no8zmf>PP2b#1&P&g;t}WJFy*L%d z)Bh1%L(G4s<)ciV*6yP6gd|-KX_Na}@SBN)`X@Aa9;U+iPtP@B)>&E}aA%rUFs8~V zU(a6vXb7ikg*>KYVw4=49(|S1%Hmm)ZLIE8F}<@Uyn;t3?7Z*U8-v|Ux)yo3{h|$- z2KXp$^jo%N+~$4ENcR2FcWtpaQIT&!*snbt&bJllcdu3ah^aoq-i9 zAh)GXagMV=sP}Q_nG1J-R!le7pNRE94(c@#TUR6I)K22X0E;Tv#G*yhFVppKpRAzu*k_dVFF-<6q?GFqGh!3WFp z4@uZ?i?AeA@P=v4KDoHQS5cPxuWs*B5bj%2ASVYsqfsX9J5bP`6Sz$7Z;(J%z{tW| z5$p%lUpjvTG}RaxM#nlyY%AzTk51qSlzwDLH(g^pm_D`mZCH>DD~UQ3Kdm5M-ZuOx zbt40!Gb9y+FW^vK2CQtRshJ6}Q4^OpviGL6_q5gSMoVyp$*2JNnP`qW`ttd+*XO%_ zg3qf(b6&d5&Tjj+|I>=+*O%cx77pj@nHi|*UCSUlBst&xWxcmH_Vj(Wu#}wDkGDu> z<7%iP-!v18&IP1SFQ~Un^%cgxJL}l}jmXon(#+OzlCSB9BZe3FG zr-PcFt_DiR-PEW7K>Y6-Y>D)&P1YPPMy}3uF17Wy%0q_!Pyxji~07m=aH0J~B%xChex%mo3-C+2w0^s|DLD4bNRE z!aN9{u0yVj#ElRJsJD*T?Q!?49V7>tTWVvX5n)V-0Vz7$mkajyW;YNzxXf~Zfn*U} z_1(c}Q%nQOHqz8`b99yi6D(nP_QL}xg>%c^4e&1%!eMQVm&srFezOt9dN1dW8y=)v zBBdsh=3tzE!^P;F;M{T2Xz~owV`nFd}%pqhbaZpR+5t>)T5tpPID!rB=Kb`m3 z!BXeY$9RyIj{C^0$7y6&JFw;+Loc?Ica7x)y39UR$CRBwkC_Duu71h|#&`VN2 zhEl3EAC!M+z@Pt|bKrS7*>?}ZJX7sfMlb}%l(uNf6Vx+$mI_Sf0lZx82xmjWBcElY zZFKkDm{n@qXgHCVcaIEWzrG7KYV>IdLRtJ^Bkf}QIn6~}bk>P{ z-SO{+h3r9u^_R%lGa-*t%rAkh^1Dz>-lh7>xxlUhjdIgy6J~@j3lzv}HQ4ZKCPq#Avji1l-!7zEaa{SZ2=Ts3&xl z4U$2&BRL)1y%$l?FD+LC$SDSAqgmhcngx29_kaymS*Y#qUy>)Q_#}-odi(OpeUv}!^nV&&CTQ6HZ!9Q*F0&EmqZSz#75;y`1_(^3;m3@X0r>A zAyBDfa3W>1IP2k@F&17Vf0__TmV5f5?u2XHISw{gVsJt^RF4&PhThdc)p zawp>?G~gO!yN-7C+d+IcpWLd+Ues(gfIaIE$0vbQgVu&x@w6qh<);u6jVjS1$O8oS z*rA4}j6_C6`;XIA^LW~hYt_Fqq5GLbI@&MqxTN7BoLbxnuD!#b+Ws^-Jz6U`SZW1+ zq&G+&1|)w%MZJ6zfd+mUq|yL7?Z_jL6#7|o3&g0KoO?Q5ojg-fn74hS7!Ibd2}o2l zIrcZl(>tEJiR0<#`sw7f{)JHQB1hiJ7m8NYc%_A$Zo#3G1#ms5yAIKE-JACp^4DFD zUmY0-zL%03CU~tX= z%ynYTZ|XHiHi0x)EK}qY>08L)Q%yj5gio+Q!^GYVKLbHPM3+nva^xU04csEKE91^fAvR8debpDgJAJKZJ?WduodH1nzN?pn>(eq?O@K2N$jo2xDh2NFH>U znC|{fTMzWBVfw}2!8ih6<8+QGanL(A&H|xNF$Q~+g;?9#Ef>|~k&p)wC57o=%W1{< zQn8h#KA~Gd`l!oG@84thvM|O>1+&45oZ!@4O-&Vrw|NPw0XAZ_TOcguA zf&dzW1qu>f=!TeEY{jWn$;TSq)`7qmPd@VVa=&o*e&s9EO4x{T8c9_EHdu>|At8Ex z!E`i&vpMI7?+(13J#R8JKv2?2`uLY16%@uJV`HfK=M|rt5&%U6Ux|chH|cSDLAX%$ zf~%12d9)onUU>@meYLEXb;5EfgAnv`tY)xdohS;!D|t1{&GlG=XaQ!yO8AF`ybB?Y z><{e_Jz{@2bKriI0G2p7w#-;tz%Po(8b0x^Eo2==h?EzC{Igxs;U_9qN;knhdos|fQx~}epAdi#DyEW zmV`zHJ`CFPI_6l!CoKwhj8H z@#8TJ+;Ny?L}U)}PL)-n`9YWkMpZv$;aG3Ad?>e419F<6e@-bnI3O~X^WQfQ9F}U(_D${y>c?@wVKru8>#Z=xz>q=(5m6zh?~86)t~-51c7XK+g5q7FC-0l6)7+t~hO@Xlk6 z%9Y#e#<`U#^+nM_@W0+KHR95QDHcyBwatamIwrc`EMd+AFA*`ph-%B~HLksUuc}Xs z$9KA=;8UUQEN=gJ)=)J>Pg-^cZ6i}jX)>k!g~h+3GhD46xa%g;n26`WDT=<0zAE!C zar(9#!P+P;kCx|6HnL3bP%y=mf1*pxmN#^l4ALJf3ig|MP_dq$lD~aR4tO|cCFd*l z2d<%@4x7PlbmS#ZKkQ}?7NrF#eZ-1X`N_Nw+795y`mZ=F?@jIW zV)OJhcxRSX+rK3^;`5fN6%PrDbMjW@QG5iZjkbR%mKY8Jd<>7EU=d*=)0#mCe|;whfye z_dPuK^Stlp_tVR@;1d?bQQ|-psncU|E_{E0Yc)K?B4U| z@Ph+Nd+s5lH+gLXR!k}nQhmjVeU|8)jzbHr;cb-M?2eh)@U-Q_JIntoEG403FKFx4-jFH!W~)ybmnrl+*F% zG`9toc799%Nj)HcFvNVAgfd1@%L(_PnD)?hU4u3~9uzvvRQ%m;1mZ0mPr`4;NO^iS z5Zv@wCSgF2;}N_2hr@07078K2KJDBpyzmm%7%@?kPxKX*jq8jiiJ;w^E^MRkuI6Y~ z7W1COr0I0$&jdhTLu!w1Mftk7nLXvdH|~D<6r3&{SzH`_v~ueFw+D3EYxJW5=9qR* z;xhmW-?p%b2_Nu%$5T2FWU)_flgminG)*4tl&#S7^k==@?M#faV~S5r#?Ey!}^^4waXr=YQrHmoBRpAn_Wv* z*Txn=O|Mln953PIL^3*OF}YeNyGtDQo3#nC$-x|t@?9Zkw+&?B% zB^W&5pyjTL4j*4e_{dzDdu!3D3+x~Q1!xEiVGR5HQ_|pF5-P2-*c+7n_Tg%a-8Y|< z1;k*izyrY|ROF2Kc$~(&S}~jfWYTSX_fF}?loXlo3cf*FjB* zYD#%#r;Dl*__;=n@J*lr%?$dAp+HMJY z+nxurQ=$QdB^^v~c@624uV~97N5i5(S$HW=uq2qu5oIxFnlByWa(AkYkuEisDI1ID zDtyhJM3bIh6Ac=YSkgkt8q^_mY_P^x086@sXsBPEBK`s|z_( z45zT*uL7fB&Tpc)O-vma$?S-&%QT&6=a-Oc5uc5$DO^`<#go9CMk*Eg7r4n@(Phkx zEPg#!9<$rq5452=n3CSW4&SsDkaENXgXlwzTf|j~+%Pa@`9HkPP;G3Zw_VA&7Sn`( zcJlCoaksOIGKF^rV9g--z0urZh?26bvel{V^PJOnQtr-#kS|90Q0j|A zOgnuNjI8=EZ%5bMEO#t^_qb`W_Y=tWdp83o(u^nqA|{t7dVXM#rnL#<{|RZ*068MS zkbJrMr=z-Jo*Ab_kLRo$HmS;eSHN4G2|L2|=Q;oL4$pr-0X;p~dps7hk5dh=kNzq& zS%mI!9g|HZKvgXk>f+b$g^sM8ExX+9ii)8L_DlD5*hTL$JVseTq;b~>K0=m<-Uc3q zlb~wPW^tzDFWjp_im5%`q;7&+l2$bO&2qzY?GFV^5$<0?vaLgH=g_B8X9ad2hgCTD zgEJn=Gp#Z1`+*iH{qrc!ugo2cG!t+TUr!+M;vz1eur+X?*uz4$5rLRo^+yM*#x{Y4 zN`}-aP<+;z9b^UtP@f-0@5!+g;`og7W|MB9eKg`=qMH_13;OfZuyTi_PAlHu&YMam zW9md`8|fNlhcV1*tyP<3`&Gk|-+~)ehZ3_Ml2^x*4&nH)XCdnSr6WsrQ<@<43+goE|~D1Qsz`!(Lal)j^pJQ z0K|l4;`qG~(pYIegQlJ}&sS)CN5DB6nFOHm(5fcxTH%k&WPxH|++$mOY| zbY-iFZevbg9CGW3Q>~cyFwV(km}WslVPYtFKng4LkwRDcWMY4RxQWjk#OwWpWzM_0wN7W6_FhZ7daPA6{ zi&_;`d|kJ5I8*y*HEVPoMrWk>T40gUChDTWazXoGsQQ8|WmsQ1hzylycC87qT?ZB`cV4ZaWNN0F@R6cyGfzVV$W-{~ zEzU&V!YvJu(jhCqzB{PuPUWMgCvwNX*=p6=1C6byjk`lfZ`dA#HR>ec+%CInH7KdA z%%=htWo*Og!|JZ|&1)(~Xm!aIv~|XlN)D)K!(Fkcw7U*Cldd_{gLT~E_ey!XiJWqb zjtk0Fl9BSFfIw!?qmbyAYq9d1$Ped3*!*oNib4}hh!LuH5P70uI^3DFEBxtul?6+! zQe?Gjh2C9>o&9?cYsb=U2w1jh(bsT|z6o^l;D@Y_b3o_%N9!zQrA{jT?dx?-q~F^8 zc8^9+IUgJ`rw+dU5uaqDwUiKcF6N4|2SmBU<=*)Zmp<*uZjAp{<34CiQ+yiSdD$X5m6QylfR}m5S%jtbL#Amh07c_{zItC!y_eTeV>=3Qg~^ZL{)2UDp&GSJ=LZ zhol(O&lz))7Yv~8TH=9f@noVPnK0$1?LC^e!J&10$0?V52GTJim2u(tMr(hk$ zb|ny`(~ObrEZ&AsltJ)RzG)3d-5lnK9LA6Fh@^Uumtk(^bvwGv3|4HiU2Nu9L`XuR zKV+yZWaxb{rc!vY2?mTV!!jdZ4cC)w(CX+{=IxVS9WCZIsz#V0qu-}7F|HJz(ASx( zM&++8Rnd4ySuGG4+s$cMvouUwG@y4^eagjsCtPf9Hy^y|NM+s}^aTbt=^akI*}kB6 zROZ2wz0|0~>G|C3734C_k1~runLxjMLcyK23K*ns=dY>Z5Mqe<5LZwL5S{9*+u;YR zIH7)t_(M@3mET$>(pHp0x;_qTRJ&gAYfQ6wXP$7&gCg5YxqDNq(+pZ@!W=+@gVREk zmTi%lEqpUEkC@wO&J>u6@0wp60;`AcSs9?d=TyB={jt#3ekSC7^BO_4mrbM9x=4I_ zlWMLB`O7dKVpGGe(@gd&vfHD3&=qJ6Sm+4Qvy7aja#Zd!cuc-cnkdHAWwD8C+$4y@ zyfU}>fHQX`w{Y#pzTyj+;H@OHW|8p;f-%KajZ}uhH$&Fb7TFK90!|hEsM2U7{bi?!Swezv!TEAOdK0GJ6k0= zuk5C=p(?3F6&k~g(;(ou<@NIIq42@3xCbnWP19-8dq=EGp}TN$&Qu*Dj^e&I^AX;;bm$w>Uu&q zm(jC!dr4R8*GVMMp+Ri00KBNiIJ97HXXtQ+)>l7{cZ@^^&8k)rd+ZaE$~bDU$*u8G z8;{-7Xr2zYSo9;7bd}uaHSfFmvty3b>2NBLhm2HD;i@BD+*db)D0lL#4_QNzxtcNy zT;*cdcN(RCFz2|$)=Ge5)3{g{-=INoYNTU(9l3&|7SA{si1DL%XbR4-Xzv&*Yb}V~ zR_Xhl+fV6!BCW@{s&@!bwUSM4YxcPt-zAT#$^yaZV)McY?NPVbL79G$324jjm~XKIO7OtqbB~oqk2j+E%U$S?I%%OZaW+^69~B!cOV&i5%D=nceU# zPP99cRlg9VIdh396-EPT=t( zG%JbPe@k}$9iedwY=@|{G{hUrU_V>6de3h#cct~unTijX#q)hG%W}#P_RSO{<^@xm zN8R=3H+Q*ztXgwG_OCu1WwU*d*#Tre+WlI)@E8V{=ZEI3D|99zN@V@whu=)gHtVy_F1 zy?3zJ>Par%0-BG(y`@ODuDj$*;Kl)3B<@1kTpse434lnXGga zw!)l%=7zu`AjyZ=q9D@FWghl9kewvHzpE}k+a081_L0)h&ryy(SFIiw;$*#+Co37|?^ zcC{0gT`(7KJCf=Su09{u&(Y*&Z>|h|X0^p8+Yw!vd}b&mWc(sQf6$RK!!xlucXRDyjHtSCROD?-U*BcX}h@4sXEn0*pXO;cjSzbul7%b6CJxfys za=Rns@bAFGy^Yvb1Cr8L&UQ1Jk{+<#VHVp^&3i_%s;;L z)=l$9g5j?{3dB6^lRZfNE`tN#@aG#2Ke*{=#y3frbc`UV&2x&&LN6bX_Wl$0dw!b! z0l?e(!pKRth=iD^*=>7|8M(jPbSmjK?+JWj9Z+H|yBa1P3>z96JY`G+y3c5)Taw>P zTr|4PWKk%U@GGYRpUI50mb}egJ{}5t=!ajnBHvqLvh#P>5;gNoY8*Ay;?4bL)Wg*o zrw4act@*09LbPW_7yLcC@Xe14g(7HpOqa!LyEh7WEcKxDfZS8)22&xT6a#| zy}ega>AaG^NqKr3>p@gSk$gx2k~9{D5cqPjggOZg`n<=?pymW^04|+4GxcUX81sV1ZX={xB!*WTxDNU2+3v zRaRcMR-Aov_^q52c1w6?ox*(Z($HIj;XA+m$WV9p^tpwtueP2j+P->^bp7L~m9Eg= zZxkPl>Tdn5XBhImB&hPvGj%iuhS*>{A z^P=)}`iK4#ANDCej9iJhl>YH%MA~)5#|O^w_tHN-R~#Nve0m)*5BG*>y!pJ~{N-Ev z@&#E^e1UG1qdn!|Rk_MbIr`|Af1DR||9sZIy0GHUg5jzK#yjZ2wFmvUD1tg3@R2z#~o5CjB+5N*3V_~V;0rs^pAXUn#`u6wj-5UqK9H1s-} zb{)4}@$1s6pK)6wxib*OwVzi{LIziD>$nU-NYDu`Xz8|}1&49LGZ4gf98!XZ5b^vl zKvmC4M4fR_$5G*ovz*}c3KGN6*1V0viU+L&H^L8mEA*ZhHH zPTNXbryrQ88`VH?-wn{VnN_3`U1M=j71~;-dDP~J2nluZpr3Tsm)&V~3$g%*FB-GV zT|0o|xxQ6|k`SrVZ9Sh|56?X7L*&~fx{C)+^;v>i9C6TRBW1u~?ewn6vrtdb_zMgR z_4OIs0;j&Tg5A*y?IFEH$`0(aR7r;#Ie$XC@E^4O{lbhXPl$Nr6Lii>KEKOb0Z&uW zcFzB4{4P7nbU%WxaAy@Hpp&m}1; zsGyTP7pkfTkwNmu1k2xuCO<4@*mOlfH%w$AA#J)4hJ~;5yWk4A4hupGiul2;+1W9^ z{aC^ka7S&@Eyj-HDKBz%oH+D(e8Eot*ye@dC}JSGsXVte{jzi z|ATvOfQ9vGZ2nK^d0BbRQ%b49q?}TVZN*xDQn33>qbKI|(*k$qgPfE(C?f=6)r=b5Y>sep_kCD+IbMybPo;}pAd1L;y zo`Vgpg&X}h^t}H6f}S^TUY4c*L`D4zJ@4E1=kVcwq3101tbFYMD9;tv|0>U|Hd)g3 zxy!h75372_C+o)MtOwy)LtCq#MQ2UKR8Q^u*LQxkGwW0Gzr^#mw5*x5e~IV3fNSO9 z|KiRKyZ-f^mvQHw|HhqbYHF5o=Z1!cwzjr&=guwT&Wfz8uld#g={vs@{_8sng@5w% z|CE;g>pM3z{6Br?`^Wwzo}Zoimv~;j{*!qA-v3|3^Rn-}tUNCh&qG8163@%p^Rs9F zMLf^V{r`e^URIp{&(AXE9P|Gf=FC{eoFT0b+SoB&n0bi*!?T=9JWJ~?zb;era+Ytb z2-D1khrKu6TAn$w@}UYNTcqcCI+6P8@rP|txw1cQsoYydGHpmqEp?@ae! zYe^%~o_m8SRKN6nzD0(4$H4dRG++NXhlYUu=k1|2RK)dK)qJ5ycG& z=nLYm%(D}cwys-lJFdWptCilMyPI4D8jCcg3?0cGN(DwpOYA@fB48>w^E^X=dIOzz z-Y-{dx(09ikrp{of`E)oxSBUl=bCk-LbU8^PV^ZB$YLRcYpq1l(nL_=h38DM(p`=F zO*D~Hm4T<4zP&+x7sU*9N=4T~br7&7ob33aXG=eK785@Qg%PB*#N%12t(6fIHb|)Q zbNoC7rpsfG)tjld(JrWC7L?gpw|GY+Iv+w#}`(xVs$|;X_U#yi@nrb@V69dVi~b;{c(V zYj-A%DYi|Xxh8||+q1)+dvZ`?cCQ$ z*5i^E8|`XHSx=H-RGhQq*XJ(6>~ zvz^fNuo))kp(!2!15-5Se%#`Y(Wdx%tvHNFVc_0egu@8Y&jn?fw3iU^aTeb>FE+nb zl&`rkjCU~1_G{o`wU)ILf3P|U{(nUg&g38~RjxLCgG$iVN6@l*4 z#YwgT)NcyZP=5wdx_HXiS{J%ZAD32_(R7K$Io4JsgzY!zW*PIj&H*JQiIeX7=94)= z?JzBzmCS;|qPiNIphQ7JbaC5dx@{aH*YP8?^z6rI>XA4m z-|615=Zi50`H6rHD*!QJOR~isWKyk4HBUguMkjc;EIGqCx`Ms~?mVN+%pFiYig=4Y z9f}q>veXr6BWo@tGDz*S#7?>ZJq$r^ds6}nO&zpxSnwt2B@5(%6HZgw)RKsSS8&z3Utjcpv6Cz!-s1ZCdF9_P2|)t#oq)7J?G0y}-tZ#@}>5u|t*r@dtMRZWK7(wFieV6DKmr zKro?<{f=aT$?{H_X}PG?qjThdO0elBPE!Re)I32{U@~MqHlFv$e#j4KNJL1@&j;KnvC%zN45Gm?gBvSF)9iy+Q;3 z7UZ2aBg%r=h8xw_EodE-2x6?)qo1$j%aj=K9YxYi*!pOkH+io+K0MQ#In#9WpE5rs z(FuO+1YyOk+orQRe4nW$!z%Vy1)5?lW|!f>mMW3?p~DYNi|*h`?T50@;RDz@GV^T_ zhAv3-K!EOoMtZv}aLrewReLhX#ElsTKY^R9nZtQco$>Hn7z5=qH-3Pou$4_w&~G~B zUdbcn%MQ4Av#uKdlX*axS}|L#yiwaBQzu{S_a^JZDb?7T3s$v}f#;Gy`V%#(x_y{fQ8n?rm~SE{x4?!0b%uqD9Wc86b3m9UqF)3@;TgALQQSWg108HAB9c|O;e7FnVD_n2A9rMrVj z(#!J&W8Is=i|2@u=)N+DK6hoJ%86Nx0N$ErH)2ltO6ZfCt#RXq0XgMe2Z?RH4Y;JZ zfQ=R_ENr}dA$PXq#4DxIgbZXdwXrk6W!U`DB!(*zZNTENjoz`Sw!Ua|jt3yFA*d_+E=)|uhO z*{Z=m;6;d0sspe02)z6SwtJC=a%Q@%%8pTi@rZv^Hxls{_#BL_m^{)S6V^GI6yhZW zBcnOIJ?b72kOCY+h?)tz{ygAy z$rBY$Qz(}5=I?-KWlR8v#q+q6WnG+=n3`=i1MZ*#_Up1DQTz}SFslkvE(Yk3LtjJo z)5|jvor%qFQHMuE8%KRlQv-O9w8{|JA~|!F9O^KQh}Kr|M_>ff@B(VSQYUisQRqu! ztjYnv7saP@z_!UuwO&*!LWDkz>XZW1OyH?KYLyAp@Pby~JZ29Y>L3l;B2?Cu?KCz7 zpOMiAWA}&2a;;pJ*Arm>X?Pn?bkt)P0=MM(-#N%rO;ulEA5oa|roTj@DKOi+2( zbkDTV0l(wrJ!=Mi~v30la-ryIu6kp>P-gK zIuEElI0~Rs%&N2EIhB646_zvLS@&Z24CpnFu9FmpKztH@pw2={f=A&?shCdb0VYJu zpn-cw0nO^@Ci-sGI|bh2xCg-~v<^}`2Jn%UyWS}^xPw@iSb^Zj=HL%wAEQTN>0SrX ztsE{)tm3e2R$-LK< zIFxG339FP)v>2{$SadwOn6i+$uMa4h%r-)+HZ}sq@||0!fSWl-%^##9(WQqgfssc^ zbV%A+9{hri*2NZd41=L9Mpa8-PEx@Z0O2WBt`3bzO@w>#;8o+8v&${FZ-EL)mG0gn zUUE2X6kvivIG6zj$ zZBj2*Dl1cRm_c$NxjYIedxBm!1$>(d-Pr^;I+)QPl)=eNyY&#@wYXPyO$maA#Xwh78FS0tc8*!WmY)({3=tELbElzy!x;>{HatgZ_T=V#_ z{S@ma9i{mwOnnE+x*EC06xEqnzNS@djDv%_PUsr8!6G~6cg7o`8^yUfFBX|W6DTpY z4!IY(N3H-^;`$9})lzCDhuKP4$oAzS_hz?;p?Hmr*^uoh=iCE#n&8hz19!Ei(GDGU zuFC4RV8&zb)~O?%IjBwosF~7bgAUMN(X6w*?SffQGNkM@PidKY&HIVk zV-Jlbux^(jqr|aae`2XwiAP^=Ae0IST&29Y^NH6=eFCVa0>Mao0v&|e(^WlsW}nx}P^0P@FD%M`Mc z+I2;A8VKy#e|!76E>y&!W+3QsP;ny1OMZlr80g0XEHf*jcK}}xU~x6*0$R_x`-qqC zz3`GAof#!RHk^TCrn^JyQ0F%mBO_SneZJQl_?Lu9k&AEpErQbGnt(2juA4 zNjO7((Mxt}nuJuX1o*PkCjM7-tc#0SC&|-7!3S<01X&Boww{I`m=hjr(<<9?K>anG zdkAf$a-n51Gx#*{9PBjAFIQTApq><5(cV&smwZ`~7M$27OwJdb72nh1BLgK}=FcYK)``Vsed#2XHrlb4n2Bu- zDwV0w0y(lZ5fsRjL!^M`Bm+wYu4}=A#L9-b967T^pD;n7u`b^>`Gu`D~* z3C|k*@VLF``_T-lM`O^Wh?6M9^%wxZ6}le+CQPbqU7jVf;Cf5ovD0)d3Fx?lY~g?< za(EbRG~JTxGYK!JPI)O7kZZgL&Wwyj(VJR0(ZQp@UVJO(Vs4l8z{}BnDi2fXtjE|p zyKwL)pZmLJ~xZ<~hi*C;NtM*@n2V9l)zHxLLf1`td9(!GGR;fGGp~WN?@PSjqt_Su@DB-ZWHDA|2|k z94$^vWAdit9~e#qM6u+Vuk0Cfa(Ov`7qh@h>6dHNtmg zJOC7}^7JD&-)4_RquJmabJdRd*vRRNE@{C^^fO>R6!l!6}Cq9vdKKySG29;LSwH-z(nyQBE< z!n|}jIHH2~mRdK_-w&j;SF61SG-IUZ#tQ?lfplDH`9IseB*qC(bc6l#4!l6%tU6Jg6fT%{}rt@(MgEVeZQd_*U9t zoyJ>cq8vPlJxc>=X_8;>P&-wtI;LC9jlr#t0H?~hN^t=v_tO)r&f{>;Bn~k2?UR|m z`yL8(Um}>*j_ja)L8BW#uq#G~J+9%PX4D%@3DD;7m-)!UVj--o4CW{Q@-^Xa%nY(6 z5$sO*0KW=E-2P(z`O(@hi^xrww#0i0dOyP;w^a=;LV%cB3VY7<(HgiDtX95ETw$fmvS#?o+1V5BzYK2<&?=o zJEh3T)o;A1OLYyfFY{iykheAm=LU-2l<}4~s%4LkPJ>sz=+pn=7YzVk`k4|q;^mK( zd%+*)qsF!nAZdmxprc~@F)silUN06DHrz6Ihk&b1u8 z)lL#!M2LK;Qw;)4q)>zhezuR)&x0n=qH#$$7T4K?dH1f6F%%_}qWah5W z{2t%?DJFOp$Zrg?Hdvp&HV2#$GG)!&KIBZr==`SpE{157MAfbL06vX8_V`_$M! z9$ZfIbGEasT^p8>(%#?v8|K_f%1QaDI%BhU@U^!Nvnue;oB8rUt7?+k>hm1#m7h~d zbZc*!+2_tcQi-MEP?e~`x}2=rjL9G*dACrtxX=v-+@ZO~A0<;n<1SJaqzti7DdF0S zoq?u!qbd9GYi07@T-Y-^$3_jKR?3jbiZw7?vYNb}*lE>EY0WV%BfvH+`i*@)^SNe{ zn`d=-YV~q0s-?lq%`J+7aB{Se+X>Ve zY1#UyG9wraoJrv{>~5fP7$S#`an#)4kBI`yktY5vbfa#_B&$3z5JwL7cg!S}Zh76@ zRC4H9bFs!my-Z|Dcs_<>klh4%-u6ginB_Z36cA%7SIS@AWIMt9flrPFe>dH&f4cK* zpf~H&<>4aLi-RJ7BCBDso(;=-qss$VopKSZ5EMk`e6sKnsd~RDkGV%GEQoPGZ)b__ z_h5xHwh3(mTS|m}EZL8Sgok=KoTydZ*<4?E(PnZ8xq==Z|7BPG&W0z)pX4ml zmAyu&8y72$0xzw7pOq3=XG@|9|1kL2@~mZAgK-~B9$Oi>r(|U+cm6+4Qcl zm;cnqnj-{BoYP7$%-858llIC#El&)HixUSu+jma@~M{Iw`3l$~;3VoLx1H%H0=l!+p z85bl&qI;&E-b=Z=dU+h*C6pvy-a->pdJp+0zaMecYnJ7%%y|vxO}0MkAFOmUdSWJ4 zoXVYRa5eE698Tiw$g%z5j-mNSt!TM#X(F23slVJR^Pa6UG2OX2J-SXcSSld0tdLx) z>+h1#Vyeg(|9OQVROdjsAql{xei#cdTR8r#od^c>4q5KDWxgZ{Ab`&BwTjqMvs=yR zd27ZvV3t=h&f#zQNgE+yuwIJ`W|z{q^f;VqNJBkF`L3&AcF}hcg06+kLC``}=IY)e zuw{yFeB(elj!A=qp@N@Qrg@%MW)a1c>Lw_Y2@{M=tBXQ2O?g$tLdcohzT_BZ(IyTvYQ;nN{kO9-9Y zttG?_q*kNL^{R|{b?iCW_$(@Lorojz)VKpF)EZpQKj1}i_qRP7Y*nej!kKejC7Wvp z5S|ooc=F>2w~-1=u{{b~CUF|9l^&zLcGWRkST!n~w%Ev8{Vo0av&sY+&xa$hXe9`V zGDBpz+;?1&2>j@oxYP$dn>zk9wD5V>)t*QW-sc)xvFs-q*DOaJIn_PT9u;m-suz+T zuATmw=oNNtvnUpEPiW;%jCi)8>;z?jL`q#WlUN3gSkWRAH6oW^Bm#6aZ>7r(k!^a_ z0_{t7=*^__MyJBRv>)~VPiFk1Z9h3 z-?UOwVQS&=Vk7#X(OL-&%%|~@V-5`pV_R*-+{5#PNYHOy@Lq60LYA3=tF+WMmr3Ez zzdkgAm7Ecm-;CYsFhCCJll{YdhzL?t=xvCB52}QFKi+y<^q|O^;)>J5(hx45yw3>2 z4OhNH;0>G?Wz3W7pRp)k-X!Cav;!tSZeQ)9dgp|@vBlnZPq;|XM}jP`<(ZP>T?Se> zn%m6onB=r2TPing!d&6$=AJMH>dK{;ZYDtkZin^bL^5Ea{f)y=bzP6$huZ-Jb3e8X zI}AcRykxL zicA;0G1w~&CH#I;;s8@}+;}~1-)0+g{Q5YF}XX&*j&Zi<)rrReX!Lm=~SnXicr%D+!*@{#*hfTB?f0pg-VZI zG9k{F=x}dP>B$Pk6)Fw>IT!9jlNm{EK$){!A7IIYEQ+C4Jc1SW@-sS|EI;>iZ@wnU zag-`pi*O5KwB0xAwn7=`^qtkewAye?pV7ME&pB0})DvZdmiyR2sE4*C4>bMWi`*a zd7v_N<5jt!co*``3?4mLc3x`#oGXPaT)ete+C=vdN+gIe1dD?zS%dvcd zUd7|W+oIFw*q#+j>(wNb;yB>ga>x%-a%>0@p(g3SuKwX?{%R3?MxOE6)pL}6`PrD; z&0P-L_aVMClXrnyBx&KNr=|xTl}xFEb<(O8mxcP#F#Ej-$0R)?w=R!60`FSeLi_&v zVH?b!X^>xOI^8*b=(1NbX&rg0<^{&eN9tAUbcxJXU3luS<;VJsxebu7LZ%#c5o(f~ z4+btTt5b%Bv=Tv?+wkVq$EbEiOP%+l9Ae#V6ReR?@9}R>FDCr1R!`+$nXM&LVKI+A z0me8JaQFwc(kc<#B)QrE;GvxWWS2)1rO&8axIa86P%NCZS9{YrXe<{nCEW@)MkZrk zurIneIc}nfV+tZXS1g!ExM*Uf;tD5z$mQI=@Eo=XXoo7bgrCi-xl)*{=ECByoCYr0 zZY;^qdwz`ka$nw#dl#8BcgilOc7%jTgKa!UO1)9Edb!A1Yv99fyU}n7XamYtFdwL@ z?aDac;Nx4->k?eM{xJl5uQ}g}=3Bo2r%prg8i*FPzy{lebRTq{K5mX>odY1f0U z7p#ZWOU}WP+BU?VEB%y4G@EZ}lR`~WbGgS>`t^E%RT)cbn2+QFhREQX1@os`|9aE1 z(W(IW2Ej?KT!UH>qj!A<4bG4tE*#5yVx#uxsSEU8Vcu7V*QZY84iK;Y9MrZ~wRb9` zvQWnNV6V(^b~*y5-XZ7LW6>7p&)F+k+27aOz1m>1Bs5a#TysWg4fNa?&yd$<peXS+h8Y;rlwkIQ=)p&r&GM@B19Rh^lNrN+&R&4YU5owyX zy^NK=1D!gHeuKeHVDyAyFS4-ncv-#^j_iXhWv zIp>b#Z~vOb1ZBm+=)@acVaj}fDHd=S(n zSIc+&cX8X?s%0~cu%35{pp7;H@3~wOLMccNdn^JV5g>)0K}`;RxkNKVZoO(5N}Y5W zPBb@`2=ZWlWPu>BKZAe{zNj^`uUp(ZHaaqvm(nj@%^GCNAM;0~1CtWcvGA6Uh>$Vu z$FZTtrPn+_C5C;srZ3{<;whxgt7!M4m2#1Z20_0HmKh7vPJcc-Y=(-+S?zocad2C~ zH}w$KCh1U3Su||tall>QKa*eXu_PR)o!czM)omXB)Dz`d_-uj}sT`Qen1;cveQk4u z)&JO|xmv{T$4(o{ysM^sj=jiDjW(99*WIq_u@k9P#XJA4Z54g?#dNFPb}K8!2$h|S z3c>-~!61dz^sMyl^v3|k*dsTkEA(Df_s@u*YxBZ!6Xp>8!S#ZTY$1!VT^ZVUznLuy)Y^^QDydL{sl6&|+`UBn|gBqi$l_H{|VyUTFS%IR0 zBhEPEn3k5BV`Ty2JcRR*6`HeFR;FgQHxQbom6@8h8?sL*W$zd`CRYobve8Fqg{NU8%$gwrbOK1*BhHlsPT%Y1sr#6*d$0(Oz-hUEX_7 z_%0vP$JK699e&A)fAkuDanQCf5YPsB`MU}5wxM|qAY;&@_wa+DOsHXEX zW0T4XQd7@=)-@FIeg;bzX!a3>IOpeZb`=$QI-c*tFer);HndbjnC&I>*&FRYqjA={ zh`bm2*V13NHM333aAr%lAWsBLT26&kf$7laXQkyw6V$3gi(VtbHfe_GxNpi93BS)H zw@NykiPbh?XeV39r_7w%L#G2VnyWMA{&!XP9`4vHg8DAK_+_N8#YLhcQ+WU&u8ygQX0IFUCuvWQ)J@8 z_E;*xHmQEr)I9xcFF9T7K7|F}7F+DhSzgN0()NL)E1=l{D0KL_Qi)Ix*7RD^<#^oR>f_Gd#7Tq-JRq7K4Ux6O+^;|T#u-o|-6F2S2es}dV7~7I*pP3mD%d?+_!)U_a{>FT6O({Xt z>2Q-kO?)e{;IZSw2T;iM=Im`mC6UZsOGg`poGGf;n%6QPHB>lEGRGub5}D5i?luP~yf-J; zWi>g!Z}=&#S^vE2(ie-$EQ8J2zah11KzL52r-wsnZ1fk3_)jarn8pfrR?ToWKxQ82 zIwv@}0QU!FUkRvWO3uuj)NuyEO`Tv^Do2FCX1i9ZFv$xU>;mI$%~*>?&Stj{BzsnM`?{B!#oNdk z$aAr7FTaKNN1mF-`o-^@e6{t^Y40#UQ>4`nH-H&kWegg_gByP5UmEWf+&=i49vM>D z-11VSy8S2jXmmwhd_}A=_P8AZ*ka^!-o?KI=^9B6^Lm)_>eUqo=UhGgDZzp1P$i@A zI{G33pKI^r8pXzyAu5IH%yt1X%6Zfd!DvCmdXgR6(PvpE`IB(?LV;a@!~0i#qb$OJ z`gF2HmqY_Wh$1|A9UwO~6dJ#`mKsD}z8y^MV!s>~Adk{noSo)^87SEoBy_=PTxM*n zk;_P|^if$05W1#;(l5jG=IC2pNY;sV^&yR!z_l+!v$R-vF&)4*J0#!CRrC{pkx&;L`QpSg<^XAfG6#qXCU3{ z08XW@q8+Sf`}QJXmOV*I@9;vDV@(lehe~SkvZB2wj9V@irC_1H`;J?b=@e~l@TOJ- zyI?fFOgB5}1IxeZBR=iN1v3SAuOMH@XV8bbcUq}!pmPG-Ee!* zcCE@G6B}!Ym*x6Oo{-7YS8N&ejs&+5&6zDX?L>`N*crfY_TL!R`4~BQ{X=xzE#t0d zH@-S{K4VN@c*!~5<8ss45q7{_Ut|BTJ{LTBt6$ZL6u>~6ejQto>*_jb?RI+O6g0Mr z_hH!hvqgP#hipIW6GQ{v)VP(=inyegPnJysK4h{=M~|D+6W_9jK0>SttGt`mcCmD- zi+E={Lei{*4ePViLDe(^z%Cx#zw7*ty9N#CpeKJkFBB%8ACXKAXUc5?T4fga7T z;_}J@JV0WvC(zGvZ!b2OLa?#FarY|XSv2OVAZ*4`w5|Ikp*$miNx^j7=0@;Dd@cmH zSi9BL4b{~S->5jW*B`PYl+k4$HS7xLAyK5TrTptKEUb#N-bC!(l#d~D`RbLhFvkqA z95#JT50AiAuG(+xwbEN{0^4v@I|`c;>z(!t(;#=lhVw2Z(s z5bJ=8HCIQtYR4_(^ynfG>~~8Oa#&)Hac*m)srY4})}V^93ZCdXwbcVszTrlw6rJi8 zV}1g1OZk*pf#ceKqSry@>MrcX?H7`W7>jUL=jXx{H~BW}BnM-vZo#(raD;{HYiwwa zbAuu~>fcT(j?e7Z6BMXAR<=t7Ry)iJ5P9SPhJJaaX{7d}5*A$P@sk!;|6n^J6BNv( zdTuu$x}nm%CIq5+q(3^AUQsZfOVd%XumiKk0>^3c<9 z`6@Z=^35rL1Edk~i)ci8>~@q3H!bc)bqPt2~%-nGRYCTiu}lt z?M#ZR11W-%8xKqAsC|PmGq1y3Y%*_g5p1NT3s)M5P=n=HMh)z;jy`2^6)0OB2Hf;= zq^le`h78S#aM69XAGNV$t2^YfbA53O&Lsn~X&nvK)o3)SBNpm20yX}eHb9ioh9?@h z2$c{6Go?=gurjuwN&ho^JupA#&|gzRrse@Q6Yg@a9<6>ve}Pmca<~C#Vog*2f^(rP zT=9O*yIA15lIEQQBpP^+C>`+z_l~SFuzN9~rfT*~*E35C=uX>>H$IN(x)Z~VOibxj z(uN==;)>8YzOx8lz|api9`q#}U7x)ow=y|sE|9Cmv5MYbkD>=m_*ki&uHT>Fy7{7z zDMN_gC;GE+7op}tH`v#0bnBi=@OJS?gFvWtR*_Af=j3JNTz+P`fJ4si9GnT#aSH|K zl4GmL2WGum7P&a*A=fzaaW+}IOUN98NEnaU8i(q8YqF#z6%yPu#lq^0=G*kZ!423$ z21PGSDcG)cQT)K#fMI|y2X$Iy`@5(4wy)~|h<^Co^i0laP@O`mOa>Tj}E zE7S`dJ^KaQjKsHtpv4lX=hW8?zT`(^_(x?f#g2*^{v}*K6*aZcMsj85^t=y1C#P!c z`}^kjmbjyU;b_F!3ihxd%DV30H4}mg-3}M*c{j>}e{^H-JtvrK;Uup4p`z;p6S0%O zp)nek3_5g*;i<1j)>ReZCPP4H_SBiU_RQQ|b4#2n^G(zxoqk>^YIV%f{z=3Kh@FY8 zM(=JJFQASs3&t50u9H4w>{7C;A{YK>E`eDFB;{PiTKG8xn(F2jI^3Wc7HlQcTUhAz zKS4T^WE)j8Dyq}4;om6W3O$10OT3hsU!oqjEeRtAWotN-@;DitkUJx)_nxU|MxV3O za}kpkP7RnKe}d54{*&j-k6v95I_HDu2Y7rboWEd2+;$sTcZk3 zepD{d)J1K*u03A2{X6f%i-dO2>pzoDAT>pD=R-(j4T+ey@0;-UX?B3fRJzBCKXm6& z-@M=SLw`PAh!bmJ$pzBG%ZeaTGdqEBa810eTs8W3#S!$*syw`&>D`CQ`$IxBr!NzdnDYWz15<=r2#SS{-EW?NzZ3@O+UeMn|XASVN9Nq8w>Tay3N*Lv5G7`q+ z&b4EdmcWl&_$o5VkX-NVqMGLbWaIpLFk0G6s*}*6n$~2z{bB3Tg}1c`ctd^75k!h~M0IYI}x3oRVR#>(`~2yLNi9 zo6yHW==_Hj33p8Z^1I_wT*C{_@#1AwA+86ny|d8NqHsnu5=!P*18(PjmSKIK4u=b! zEq$POWKrXcn?82uIQdkv?~U;yV-@&ijhQJ$3r0yUrjo|`2Fk(?n*ea9t)5jr(x=1I z$#&0=BtLGm@i_2ubM1ODjnxBs$0+KZ_2XY$bSim4T|kjJtpZE*dryPo@h)^V#>Ow6 z70cRK%cok36=_cG#9f9{&s{hEbSMLvN~D`VmmjytKe-dU*ZGbi@X~kntV3|+CW@|O zbnJKnCA~w1X(l!NGW}ih)aWVSpqI{S&jn(6gVHp7%varo}Smn0`wTMFWl*UEj8HUS=8Sat@H!ehfeOB#^U5lLdYk1gYg{FFibs{CA{&R=Er?AkOr{N>t*w7rw zU~HT}vpy5gH<8P-#QOyzCw&S(ZVvS|<%fWUYjq!&_(=8*=lU6YLX<5Ox`v^fAr;oR3MHK|-)2BM@U zl5(mh9ly#`wS92T#?5yN1(rL);L*>CF&hWwqS+fhVq75q#@LtTT~|Tlh(N`Nw>$fM zRKXi;C3p@5wJbFmqk{LkOSFUiQ@%$3epjGm14_d4sI@ZCw|Bp%F$_g+p|Eka4@EFJ zV`K2r_(0k1XHqf}jOT#=YTylDDb30+QvU`W?0NHX$Q9{FXi@=2X76O5SzmGH#%)A5 z(QHso=wXn9{Pev7jGWh(%HT5d#tywgn% zlpdASI!L)9o24VLFDr}GT7Kh5#Sg$W;nhrtcVs$3w>qRsM1!sU5sPN zb>a(kYoQ6_F4jk0vX|pIe}+EFb+_goVzj%Czq@up2eSV3Ao%!dspUmTiu|uM;TJpq zwN8d%J5ROQ*pDj{pj#+C?MRiFy<1caDjn%1o}s;knIfIfv&P?VHa_4u#@>;MV&Ms8Tc_HjtlvCnHm@}?4-uHp&?bhB*da0`*Mn^oDU_d%fJ#lFKQ0e z5{hi=p%#Ztt&Qpj1Hbi3Z*#G%RY{vG0=~!#kpvrv=$Tb~m0Ag!!v6wQU9P_f2;1`7 zc^IZlD`4biCIe!m;rl57Wz-b`tmSVyoHuPl{_O6P!tx&Q=OlGTumrMvbNvRTY1!3cZSn zU|B+LTJgu>G6EL(jRx*dJu{L}s2WkyJyn$83mp2oys1UTBT4nC3`i#5Jme`5Uc^tK zKUiLI_TkXQb{g&I?oRpYP%?W32IUDh|E&*JktlDM{HB&*zW>s5HovvcNgvOLPMt$n z0MKzMcMYtg5{UV7PUXJjz_=uOw)JXSm@D~#IG{Us>GR+odC5u4$J!=0tDdQ@^Qmk;&^RT%REb`s_BXbLThzGfIkuU>V>NmU0~# zoZmP+J1Rz#wOQlqlG$$(9Vbkn3Vn%+Qm$uH>x9czu)W8G*Uh9k^>uWK6J6?ZBbL!R zGZsrsby5*!5lrYqEJ#9%JEsl{0y}^4eZTVA&Byz5YfnwYOaCswP$jUlPbIU*GBBUQ z`XbT!<8JWnJ`uhb)&L-*J`XMz+%CB{du6|B=}1@?<77C>_)EjZt@N8fSX)R{kwE>jif64gRj!=Nc zAOBL)@NMIWr3}gip~sWbPRF^Ev4r*!n2J;=LwIS)_aMOs|8jPncvX9-OrF~6B!6>D zmrjcd)_F-`cmJB-aw%(^wh!#Hst;h_2sF%b(}_a#wR6xAhE1 zL$2dd?(@&xxxrT$+BBJVaN})L+16)&w;kVfLFskC<_M?mOqLmiHA-aJx~@xmXsCj} z56U4#ai7>DXkzQJEcoG22$LcHW@UlHHT_>53fmcBkg93Tl+#z&FX|2eI^wO|0e&)@U8e6?DcM zq%{DXsjAVil^Pf45NPzXPbAP@o}is^gU#PCrSlt;)faRpu-%n9`+4x=1-IBWqgMH$ zs1KNL^nVPb+U?^Phk#3C*T-(8Z7Eti8f5DNxDeqU_ePazI_uk_cS=nfAled8Y1YsH z)h44-p64&on_Ug65hA#U6n2>w^+9Q)MDnPaI)uhI$T#uqLY9XxKVNh1YBepbH2XL# z>qgG}d~GBI!Gxd_kE~jTu3z;YDk|I46(+@eq5qRBteJCbKD=_V;pM3W=jP2m2kuK* z#dJ!$iXyd8DLirZ?>+P90N58gCYE>56XtMlyKUt@!)&aYL`~uCoPkxgEa6 zIZKyDprV`0%ERCOm^8LM{ZG_}rGbA-%H$gwf_zYO_kvHJev;$3dKuu+{`SY{v`c1t z(KO3?Vz`|mNNUVvxA#DVIVgHVx&FH`OcAp(wr*hE6H!yZE$x0{lf2j=#GJ6Su#x7Q z1SneSNjr~3wQ9n2_BLOy*za*}U%D1(SLG6;(V@)1Vesx9j4o1->h)uL6}G6#I=3*q zN5BZUSk1xjUSrmBuDCzsXh?JA{=ud3h}22s9cQO<4Gc+ts>!?ki&lZ)O=W2Vj=H$A z3-gG>a@tzrlPWCl=CEwnZKIV8r?%t#0~!>wQ-Y0l>iE?T)?a%#({<{%YPY{CU(|Kh zb9_jY1;FG|%;D|~#@Jjz6U^`10^v1=9Cb>A|Iq$r2OpK`>PqmNls^%ag05UZoz$41$%UZuFVxQBwkJPnkOF2z$AvNntxRU# zJY~hG4|#GBeQRckJ8BZZ4!7IkG86=q>nZwh`+Uk1OXVeux^Uf&2u-y?y$*tK|yt_pxt}Gf+E;p zdbF&MZy>RAD0c@p3J^QGA6e}-l~-7~Y5$yOGHd-wp1Tn z*hVg9)1i7zkE&a?L&$KL)5S=>>ZQG9*%dCthkm-qV&){`Pb%i!SP3QbfUd>;w33KpF{|?+!ZRp$?~`pJRdW|d*A$V?v-!4{d+ff#-FE%; z_LZV|C2$F-x5;QOjartyZ{C_Q`e#8inuIn>-u>jmt$@8x6PH+|e{?O#%O;5ulP7lg z)0t1c!?zxFbWtOyckxpkIY1ZA#9V+QH5LfP#Yc0p6w(!k^hBW+&wKCYG^iLU8SA zqZezJ-AZt}(7UlQQa>~QStuXaHZFImxihY5lE~MNlJ3mXSWsQoxQ&BVP$ml{FWVCV z%4`q$gJ6+qW`2F>;RwtyBOh5F3DdO=XU=5iZ!WL2K?vuwGHM?%LoWm5&2A9SQB?wB zwuL+-!(F1X-doGg#T_E6cP?(&P-fTaxCXXyCmZxGa@vI2_>&35>~&1#M2-e^Q8n?d z(zZMM>r6RvR30E(S39CO$&wy$nb(>lnE|>QQdHY2dpqB%yu{IP=h6K88jxHd*s67R z^h8 z-ht1nHP*`JF`T49EGVKcRG}!`YsR(O^FzvptSNG%;yS*}ZVdv1zPg`_+SOh~U zAPC3242Bkin&g1gs zp*RD&fC;v`hY#L-haq5<#jl=V>AsY+Q(liY{Rk_K#$0frfcSHA$&Ax#!~`ul z`h{1Kd)ja_z56|QV$oBKp}KGW0)r5dt+OZ@srW9t---x1ORXW7?BsfeUVgae=jW$O zYNbXuZZ^#xha7OJq_2kQo{)fNTc16qNCpv{ zztV2}u{M6S)w)zv4&|A@m*tztC-$0ixj#(7B-iS%?zMM9dTO)8 zPg|0|t4#jsB-^pBv**RDh}M0}{uzS%Y{>{&`V#ZxFxdvS$|R}RigPJE{d`G?tuEg0 zZZV975H;IW$`I9D!+P1*&{K%<_v=k<>$Vd!>U>Ppd@Y%$)Wr0xU9>%Fw`@K7n>xRy z)DhlbD0>-WpsmEJK1?xCN@!?5SIQfkc&S=mfFSZ;*-Z#nwjunpBmH2LP!y^a|cmMAkyI%B_&g_*g_!@##re-g)mxt z9%#Se6Z;QZIH3L#AV)(W{5=dcwK$UcEXYs}a`J=VL2Ww)B66<%$9$4{R2=EJcn-F{ z4K>K!P->JedIkN&{;RqNUm+`4bvjjlkJQOCiQm6+bX0Y*)NN+?>6BtlhM{G-1X*Qw zE{cxti^Vm0Kt{O;M^DIeE}>VIaQY+uj3?kBg>EW9{*b_SfsBP>#JBmVU5&VPCK^V9 zus=fmn&1?W?hu4rJ1?LX`wgiYgYUWymyWhWkveKf*6%xO;=4|Ml zkL`)`I$)1$poNoY@Md@2&yoUzKj9ORh(iS*X>LZAbod&P>I&0&kH-A^)baB&nf1UL z%hZjbp(oh|>N40bz7Bt`0Ymfvzu zHVRVu(BQ86dS1EuR<8l?$XiDRdTeOORa?*BS1Ga4R&c32dCDdx8tI=E8rJfa;?3ZaAiUIrIpVaWWoqmW-lEaU!S1C`9tncYKf|+rNNtRXoJbZk96*n8@ zysHemi~p(~w|8M_Po97VwbXetzspwqBR0Y!ce_R;Ws*!&m5DX#ywx}KnkHf&Z4$WljxPY=mcW%fz;Y1;wEufoXj7?iOt{y4}mF#+;~3z>Q- zhEzIkaCXd+G2`$jcj>BBigS1AZK^xKEU26k`Fv?ju~)gPmP}F>tvWAXa?X~y)IdKB z+BpyR-jjTJeIM_!vZVId(s9QZw^w*a(<5k*{M&4j&Iy-vny_t9qT&fpz$`nJFZ(dJ*9wnV-l4fE`yy&UB9wj{MHo>UO-?FHh zw)XXKBDvXr^|h+Ba{gaFCl|!wgVA8GTX?^$RHMd6o;WbrbvzM5n-N(BRHX*gT~pja z4OW3IR)LMFffv38c6|-JHXU#^HRz^Qz>Tj#zgqm~6F^D} zFz^d7_Vd`P?qMgw%In0#OLD_wXbNZpkWGK)fwrs+NPQ-7Ie5Ax->jI+&w zglH-HZZZ2`zXOIcu+L1wg5M#NX1p`sJDQ&Km%2TCeg!GUuSDUQy04?8;O;cEPoEt} zdV|XcIZKa3gHt-3z=zhJb*FjzTG?oe5Baa9Vu)$k_F$&e^Fguyjwm#vJ3VfzS4|q& z>v3Ar4jZ-kX&5-uBnm&%m-z{JZO{a|Qbf?`cjx%uyK8;y;d`(OH}hHQYsFdd^&;@z zZt!UO`fGt6#>{uxhmdRp#CW?sf7!o3S`R$onq}B@+?;XzcK^xr)VMKMbv3$tMR+t? z7i2Bqzmwwukort2X)`Bas>BD^2x7#iE6t9>GK{xoJVQ%gZx)Y#^H*1&&#oc~FQ72) zzUp38&pFvSsQGMPfA3d2jAAo*%DV4&&7P#!`c$NmK;MM?3~RMUUPZ>yo&5sCZ--U6 z{^!0GKn=lx{jZxhrs>$czVa>2D9Z2PSHB>7#&!S0k)_22{?-wyi8pLA_bc)K_?GFi zlJQAMu&FtAx!)ZvKJ;n!SkMUinH`lOhU%it7TOEg+sf$Vq>uX^8H z)_20tE}8JXB<%emRGppiMs*d?5nSyNPybZ&C@^~9$i5vZ8Lk zG^p+%tS%kI=s#q$ z_t;2Z)<|w{Zc$Ou|8h3FySvYyKmWg+&0h*aQC&e#whQ?p2N`oXy8)N1ip0D3Hxp-T&ikejOSa9UYyXp8h|P&9Sln z3)y`4?%n@KkWGcEdHDY|RnvRR|6kP{=}aA?pYP`0+G+|iT2yjG=^Q7Vp5PhxC7P;H zcKaU+C`Q2m%IcDs3J%6yv_O}Yfk7&;nFt#9a2OvB0^l@aBNeKcI)EK8rh~wW9T}RI zSr!ciS)wYdh+ks_T@WgIw*A13;m#>dPxX<6mQ}ymD4s<(h;m!G~^P7O-t?MrMp0e z9KP^UUx|w%??*RP0d~pH1TZ< zNu_c$eqE`Tg$_e~9*H!Ds7y7}fT7oVcJQA}G-&zRXPQz0I`?7w+P}5Vrq_6LPn#|v zdq=@!h6V`KdT+PC-rcmS zhQs4;>p`u+otduRUfzPX)qdT5oLxPTIaRaL$_n;SPH)f0{x?qZ?IO*EWR&5Z{SSX2dRp#-;W(GSg z?GR+Q#S+#oA_~N}^5W4|gfZyyerh85azIdn=1|xR0k7NSAOD(relgvl$86dtPuEG` zp4+A07fspG>h?o6e>GLvOtYjbHY6a>&wpP_GL-b)d#LHGptXgMnQbpYz!mG$)Y3$U z;4oC8`?Wj>P14{!u-WBP$r{%-TL!`d)~s+njofOW6FoBF@0n%NLD z9@2kQrariuV^-X#vY&ZN>&a@a&3L0)`sgj~AFB#gQzb&>$hGnlXIAr*%t_9b`ErAp zoB{)W6RvFuZ&WTX^cg34^-!=|4}2=J`$S^O;UgBGg~i(R^O}!iaaPtn1@u)K8YwGe z_Q;6cqf%u9sbj-HlHN%bE}Bf_!@m%5brL|AMC2n>UScD7%|tkhxp(cd0e_rna3me< zTnIvlH$(LEKzG?*UJ#oBvO&O=I|F=PIZ+HXjpr946+~zHX1Ixa9Lx7^bCo){buf)J z8jNf%9hqv;KDIno3$GwOU??IUiP=%sILgCHrge+F5Wy5fW`<%s`Vg4pABNbXTE%mwFMlagCLJ&oOQY7_Bq!hP}Uv=y9Pv{ z%!yJ&GdBt-WedHrSX59xReea4Pfd}c!oJBixwH6oQFge~OAJF5dY-2wLjCH{u-9_C ze@LHSL+tQ+oJT%u^w?dYy5i_%W4yVtb3GVdTE)|BSQQ#J(3@joA-L)u0BciS*`jh# z?-cr3yL%(TEm45Gi1wv1EO6C{Mhca*;By}Yl}O1k-L(vUtd=Ice68GL?>whmCMUSi zWCpPq7^!y}zSWehd-KP$q1R^#m$!d0v8Ft{NSqH#(|!k?d)Wg z7QDW0V-c|IE`e0`f;Rq~cSCYyxQjffsn0)w=n;S7j-pN4^kT{i=}K`we|IBgeEf?v3GEl_8=v z>XZ`%Ww_Lb$onccWh~s=rUQoV5q~f}vGUGzT%dp9o1pfz2oab8M!2;Lw#4oB((?Fz z7t%OvvO;6o9G9XtTPxMO)B(nfDs(;X6E)`FrPld5LmTm;a_A&NpDcasGApMIB?@=; zG~xYQK3qK`7P^w@h%+>VsRek2e7unWxej1eOmg{ht|a?H|ABRB!mGpOGTdniLt}2zu?9w!mZ5Pyh6<7w!RLi9_raC=!ob)-t^iR3%dSAYEIetr7s2>ws(TQfUep8G zkevacRDo99YMOA#Hqjdn{9AGCuSMm`pJ12Zqyyv>usV!xs5^ZfFjiTBe^2;g8rvu| zgv)W??=hTgA41uCb>G42phxyU6`I23>R#xBRrK`;l>2er-}7!V3>l|{rud(wXSoN* zEgW7gXsc`9?P`ba7E>L_6^!G|HiQjY(T5 z=rA#GwGSG}4%%*}gx0|Hh!DXbXO;w7zZwsOqaKey3-frjAm{G{SYKks7LHSsC<~Lw z-P@SGQ;JNA4kLx5_&xawh$@+@L>h+GeT7smLJD7Tw)a4XTMo6v0HxFWRXlUMI42r- zIS45t*a_`20qyTe&0)v$D44!^L^vpurVcyHErozl5`zR?%2^5#%r$VVmfTNkr;z1b6cgR7oTXjH=03 zRO4awv+L-pzX9*Rk;<{Cu3RJ~QR(yJgsOH#ILuj~UZMODvEdD(hjz4v7}He?g!S{8 zJ?YRHrap%ui?Ju#>YMA&by%fluR#{M%Sr zWHnN_L-892oZ0(%;-IojoID?Q939M%0R9qKb`RpB8LCCB%vlSJdV_3w3}F1z^z(eL zP9W>wa5hRHg$^OGo#8(f{h(Od3_?pe{#9neOddK{F{{|d-9HYOiuO0H0h{JQoVXEF*ZdBy zLBq}9FQLdwW`~=5V3Hl8sJ7F$@!T_xEDQ}03wcm5ikVydxF50j78ybGGCojfhG-5wL03@rHTm%S^;H0&`|g&_9n@$5SGk9`pCXinemjBQRb!YK|Of z!|e%B8fP*U-k_%gQ2T^g|Ad*41F8H1iKewwHbY{>P(HWzQp*`SnyciOf6y%2o()8c zT>8X_#W&Dl7G`M)s@$05DgpYq$SkLji!;nX+6m`*sF4lkq~D2Nkm&3(*Hr`rWfUE2 zOLA#Lr^Df*CwaTVv$1R?eQ~o8fP{`9+r`RzX{>}*<%2!dIY5i}ZF40d1IGp`3Aq>% z1pkD|F@x@3RX!|XZhei&qOoixNMH6P?7R}WBk*M^kS$V9FH}tHMjl&2SG@s_e+RCQ zLVX8e7bg%-v5nh0P7)p-+_ZlkWnT?Q{6ZD9nenkAhVm7rS$(eod{aNJB@Wlf?Rm^( zX062rTRrQC5(N69Bk%BXGz{8HD1z42p zDw^jA-xTDh`w4DW~iejSeRDalsZp|4{(5Ps=9%9#<9;_V9_O2o}jv6)RP z&QnA2_?3=AQ4NWRAoj79*T8{{E#bg^tOPUX z!+bOYQ`m>N^UxqJ?7UEdq2)VshwwCb828j+hmhEvT%u%<*Pam~zN$<|bt#4v)d4j< z(PLFXgR$sv5pb3gb7l$M_Psp;z;>)!Zm_%lxeE8)k*UjuTuX(A_dt)t_Pee^Popau z%{m!0R=Nb?W>)C@cba`Yx{9V$ZX?AKA)09Lb<}MV(a(hKe4yvLHw)YjLaqPCVnuUf zOr0V?g@E4*r(F!&PK@qPEPDNqg7eMff--}}1zqq=jRWX|#%LE&P|y+@N(BLD- z%5a;NgT;Uo=ynk&pLC70-2^(rVQ!^{V7ZNx(JfnpTbi4}($s64GnFq%;@egSVC}&5 zVLrn_JG;H)p z{%{T8uf|+7LmvIAh|3# z01S0su~};C>M;*dAVLatOGE`p4!9@sgJ!rrAk?K*?u7~DSuXU`tdEYa&1aY2PgLM4 zk4p8?%Jys|G8~yOf9Zx(TAv7r?U~bDU*RM^OZE}N>|L0fxIJw)X%~Et?09_J3_Zy7 zd*pKf_*M@MP7I(rF%?~#@ovnYJNv+$53y`uJZA(e0;_8cZOF^Vtttx=m3FKuziAB* zmW2QM=kVFgI2W_4MKS%@y$jJ@@}Yk*r)VI1-wDq3eAqvTJeqQ=S!#Ep66|0t5*%Ou zuh&)3XgV<;&jpgEU*N_Yb;5f&U9j^9A`VDkLJ2}lJbh_*6~T-tltX^sk(Xc?v*yNR zh!iIoQ0GI}rm0YAVTk-Iu>IY^;B_c>^;I|#R+fUORVPLQzIu7nq_`>LENcgbtBYmWF!Ync^=#SNiHVgUf+^JY|LP+7=Vx zD~2X;;rZ;qtBJ_3noe{s>S7|IDLww@u8h;Gr+ug}j#rhwpJ@=!|(TRwz-RM#{ zj5VLCx^QL927+TNbrNcRGxjb!`e*ugF~a;QmY5H51m`_3zUbWeRcr43Oa$Ky-sW>R z>qOR>d1%HTOmB9?^a^KT3(kIh>Do1zIBQh=T#Dn+J zA+Yf>4m;}lA`mPAf_WE^;i%ISwM-E7FH>-32Eu6`mT=bb?>Y=Ngy~PXJh~NK#9$_| zAv#>Z(QF-3IWb5eUg}SAp-GUfW;gN@5hgpFqpBea{xnFj<6cA5_7t9fr(DfGcX1w8 zDFnAMPHqqHCFhBRmdbS?RsxL`HxIZH%k+vR*L<0ZQ5)@CR2Kz$@c@|3hHMhU`a~%h z32eYWi^)T*9p|4lD^=KoKm9))_F37C$$4-Mpx7cAf5$42i+zc;(so#A+AM|*}mgdbKKvCjbB0wXM7yNjq{2G5rP!oF>_FgO>BAU z%G`m57Wx9YXs&|@2sDHF@&NX2C~N`g=d=*z$UL};RE<+M`}A4^^Ja6VOVYXoX6)hY zD(=Pep5}#uAFPiMR!6X_Le7Q2z4H*NnNoe0N8Fo3`YXy2_hJ6qvY))+oPB{M?fBIj z$4%AYR<0)V?$@L;Ti7bnD84ZDNB6>z9 zLhznt9IO9SP3LOUkmnYwUawv2%;TOj>arsX^z8FBifMF86a8Q)yx2?*IBmj^eU{91 zWkM3ns6mdnyDTA=?ac}xB^BxJ;T*pFgwyC_;ub!cDEvq1P4Hmq`-@T077u7TaqM^p z^M!d#;btev7LLJ`$o{H?(LnjcB1&;rg0X+?cdIgr6cg8Xk~ntfj07gNH%~u_IWXNF za^+?ITY{mDlBdc}Y@i*`Mu?D9S-f&mm13eM?iL+2=r&K>&v2cL#$Bks z_}R_24_B`-M|zteE#Ga*@+F9OnEp$yHp$pgdze~*tvRA%J2S6GlT!ZiZD4}rG}2O3 zrE|gzb)k)&l+(u#*7!637R(|XuHL7`+*$9ec^>|MaCe_UO*L-2=u=iIplLv;h88*k z(iGGrw9rGZLO?)3)F53^lMo;jF%*$*fPko|hzKaCNd!btpP;Cys6kP&Jc=C~?)=~L z&faIwoH^h2m%Sz*^C8J()|z#%`}$qefZ4Nh|MWJcVU8K&tifs(o{a|r)-J9+=j(mF zE=%;)O^)r43LSkOt@*iNpunCr`*B6$(%F^;x0RVO8U z_SQb*t7PsCm&Usd0VAf!)oIL?Lwvm`VcVf$=GM=KFb#`!GO$5@4LN!PxC8aL*oAvl zLcVdc(D6B(JSucFVk9e|hSA0`(DA+*enW7x#cjBfY-%NLNKe&At#Og*ZN0x= zPLC|v6?+|r1QKTLqo1v??!Szl{{$*L^!0IWVp@Z$Nwt1Till${jt7uZ|IvO<$Lqrie*2YO@tSiVMp{Xg z8@nR7Y6OHb@vM?y)8M~RPi4$Pt%&KZLaar@Yb8T#({p&)yV;++qW$WGA0!4pprvFB z4Vp^BzX?T$oWfL1cBE+4#mwa7Zgnrm!ghHn8;+XPsIDs`c4XbzUS$5oM4ofGGq^`{ zqHqmsi1Ph$&Hl@JU5_bT_z|4pPm8#kL`5oIzPC$SDFM9y_m; zKI@I#^a5q*63>b2@ZhKZUZEvTqo%#7*K zB6V|4--d@8LVT1d<(Nm1WdRbl_c&q*mZ% ztF5BqXf;tEb@1Uq!bmSFIGqRaOriBGwNw2yZFVnh)hy9xYeqZip-y4$nhRdHGwW)s zsF>SWt|8|A+%v*{q1doF&JS3I*VFFE3*?fPz$hR`D>p)L>{)m5QoMiF)5!0 zkV|Xpbc`rqB1!46#ea}WF*I8rqv?C*q_JYuC1#j!MixUZm7WMW$6pC8y}QfVEFt^9IgDtAW`QzOL|2DCyApha5%QM?uoFRA*y+S;wjLad@VqZPGQ%m}$ zR>lBrkL)OXU!-ILy?zkAA5^Ax&%t9Ok*^|Pn!fnZhghbZRG|#`fkux&9)Q$t49gb;(!h;!o;IAT$PFZ@l{LL0S2ENj zv3Kl0;rVYCrRY$J(Ip)5szrAZvbru;vj5zeu~{KxWhfD37nGm8->@3^Y0W|T3Ai(E zV{OMpOd6>`hAP2=}Eh>ovH_aYiXU_@f>Ww};!M+&7_%FC3reZ z3TYUF*9zm|s#nG=nq@S@W!!^*tcJ4x$-!tU8G8M!5o6dp!B2Rf4n+jvbexXp`CIWv7_-5aO||G5rzQrXG9-cZOfQ1pkb%WciD zu`I@f(XWb+Y^pi8^~1kiY?yAHli=FpguZCGfoZ8V+;mpI*W|SuPI2RHBq~q}?fv?F z_x_VGKYd&c$R?*s$Q$=sp#YJKT=is@!`apJm@P%OpB#tnL5cQ0ZrO~lYmEIxnwUqT z?Sc!-J{Lc2aNp-&4^ywUp40JB5a?U^&DDm9NH64!>JduN~D~ zzcG-(#R)NMbieO$G@hNDu02Khnv_tr<=vVuSNeZldD8CQ`0|R;?cs*SwquM9ANP`c zoV0#3xVA*3W6C;;9I4DdI1Db_?n4rvwQXLf-Zxyi%ci_uv;N#8F-Q~opw#4|tGKDH zup9;RU4#raf-EP1*hb!|Aq>YFdhjBwE)eo2LUd2d`A<1EI)bCL$i^*!XYxiim~eD^ zLEx;W;SDMwvnv->zciI=@#_^~!g{DBvV8gx_fh;|4x4-O0xZeZHJS}^BvQCbS&g}=Bbs>mwJCegeB zTWryR3_LDEHFi#gr8HVAH!IF}NnU7t)Lyl1y2=`P)q+)vOwqY7G0nXw{rz@)ZT=@(b37~6fg1GgQ{AL2k9^I{_y$aS)S{9 z$nDar`zx?rsdyFZB0n}{t@AHR_i{Lc!M!J+o~t&^tPK>k4C}YjXVD3O4@zno=0sRa zhg2+a@foEcLbYE$dQI;^d&*d+$mhU9Q!z_%If80dK@FLZ*gf9*GSCWA2;PRT$?m6p z-*6-IY-gp6J01eTf3&J4NjOetLFU&UcXI`zbv5Y*|1#7pSYBZ)SouQ}GuE1hbb76v zSM_^xHnG%M3nG}}`N?_yOS~{v5qj79{if2wcdsn}#TyX&jQ^#5IgCMo~B=Cg30b00r zNx{H+OP#pe8`x$;5dY&4BT5}~%Vv&{_xE+Bhsg>EM2FSV0SJk`zxp&0tE*-tI!@so z1{J9gkvziT_34KrOF>uD1BvVVEJf=7%0NUStP@h`Kq<2U9VCNQD#fe+NFct%PT27- z{UBH7~T78-FXlmt4$|EF=Gp=SBKBOfqJfgDD{Jmc@Y7Zgfe%J*--b7!6}9WIZ6 z`iDnwjghpmW|)6(H+dN{$+MHmG2M?0FETrzj2SmNub4h#nZ0qQly~1n1=xTs`>i^( zJb5v}kV>BnJb&2nrp}%W!bbb!zD|%6>3m<|p%K)ks61FeH&nBYYbZOa*9*~XE8P+r z0%!4xnQRY}ljpq6;bmSfJ2azL=vT%oDqZE6`d>IB8P{i;yQ*5zWgq;Ztz2va<9b8L zrbYDz-Ik2AN0zFe?m6;K5O9&yBQ*ouh`a3DhG780UEW*>1G{4E#;R2l?INrBG&QNZlWt4T<|? z2s-XMDMv#C7+lMV!Q_uE{>}sbu!mRjEn9Z**HNmCQ%s%r4tM>#s(J^~<5E%RP!O;S{#Cf%$6xT#XzThJf7XRm>3yv>HMi}vdbJA$g2MV)YNDr zRh>A>d3|!))ne<`@Wp`L=8A{693!_<8j*XWf6L~CI&EPi{lVaqKMdz{Xj@gJF4A)A zM~Hb_ks(9>uQG|F6g__GNpaOCJxs^?=dsVeR604~&i*SI3WC&nyDshX49p){54!vP zW_wl@TZ4r|v*H5ZK5=qa*3X03fR2S@IxKswzt+;IHZZ+&MXx!2(EUO(p07%Wm=L)e zx*xB4bmIfbmp=v4B=Q=xE?LQVKJv3ZONBkkm%*=rH!kH4PTcBlf2{w(o@pv&`N6Am zaXA_*M>sAjQF5SHz$f>1o96kiy!4rJtBJ}4aji*I3YpXaMnH9$EB!U4q-hgv^F+PN3(8R18h_WfcmC!irFs9&Lk4nw z&TYR+87TU(ikn=fx=AU`9u=s%@bNiDf$zG>64jCuh^bYM#2^9^IB*UY1!8)s9c`g- z(U%w|bl)r&e00i~*F~6VM4{`-!UYpvnj&4Fr)%f2@V*x|W5F@av-AF4h##V49QZh%DuU4xhM$;!MpNS-sAr7U{{D zC^jeP^r+gmO22(*EfUv-bPX-$8s9I%hS77`?m>MK2WiR>nWS*ZQp~XC9-+ zUUS&LG*F30khQI{dc2XrjdVkK5&2q6p4+6t*%NFhBG&}E{mS~GB$wxiE}i2xvd1R8 z8du%gUSCcpe|-70>K3i>C7bQFq&^oD-=r89ODEHn&dCiS>!(5JjW0Xj z70*ZOBi|e!Z@8hWN^GkLJL_%F;t(h>?n8h~Z;s}7<7%tuEDO2+zi0pWp%%-EimwK* ztRjoKK7lbJCz#Eru!@x(_g8R4;mcYE}|BmGk)UFC7>c+pO_f6;-cAx>n9M(0DI zGFW=1mWOXje_x5!6N8?}1=;ze*<#fFjw!uB z>CER1-&c{cSM}7gZ85hJ-&eY-+#B9<>V+=m!gw7_#1EY&|De<?a#o4W%6^0tepgK7}gnU9?pE*VJ zj+>!GcNZmntMn3sy@vo3Yn=DcfFA~GQ>OeKgIrzDTXo7&Z4V@}#BMDTx;C%;3XEE| zRtoQA5g79|CgSfO0h=i9p)*e}v_#d4zaO?zwL1u+4#T3Bpqt#e_nu^oSeI62K}Z$6 zAWX;FUd6LS(3&BT^eu;Ava72E>pDSIi<>yyy~j{dBLT|4nR&1#*J{M*WZp|>?d2a8 zuNkrT3Imq_|9WVpfXmObTlqoxWw;$>oW?D8M@92bl4rMSS6$wl&oy!?xO@y1dF1?5 zsAEHF(TPB=Pu?HBh0iztor@OS-iO{&y1(>6qAGeBx^@Ec?SGH=r~OsU)MK)=%51c}LA|Q(sj|`<_D`z~6wX{RLv`XRGUJ8taFSQGoARk>{W#M| zTOY&8+QF0zs`Q1(yDGYFw(LKuX7h&JPw!rTHkJvU9;MV`IMUT&rWu60^^ogWRb|tH z_7`PSReFUqG;AeJXdY1;mm8ZBl|i3IMXvask_lAJwM-1%gWjA#&DeFc#<&I149d!* z1tyY2rF%G|GwJ?P8&ne6(8uM$7akBid!x}Y^ZoCdy9aT~bXhN@}Iu$C($;;0LvS#-=qy zoW1F-xzXg(SM;v>MzcYaz@xu5{$BnVd9ac#MP5a}2oCFG)N)NSMcJcir>HOBTYlva zG!@v`@PjeBKpW0HyKS^AT9vdLMNB2;RS|k_7LVc!lZ04=55?Y%)NH61X{;($^)lL- zcnk|$!9PiuQl~qC%e_yLGQ0{E8S}(|f%?E1WyKE5yk&1XZd`3`dlF`qcf1KWsHBIN#GtCH8?Fj{;jT@ObzE)KFJb(|hPCV)!4jI>k zbV^l=o|r=}_?b)Og9wkXJ-Z#8%I z|7khY8cBl_j*1u%L~d+95ARptO(eKtY5nnr83X4`Vz{?rH*G;O7{%(2hnfxc3|Pg z6t2zpC)U2U0JE)aMUzUQ+jRy ze-m(nw0pT0zk#Y0z?3SL7NXIyGX475WL(ED-Q~-w7Y#~%A!?X8z*mU1FVIuw$f^4mhL>EDe)u?Pc*%s;N@-i%XR2S@XD~{Dwa(gAy3_jH4Fy zXkf@X$iWJ+L7z03Lngt(HAMRRj&rqERTb$mz^FgNdYbdkiy(m{^kTUf{ZsXd{+{;Y zDj7YsmbmH4B?v}S1F(ny1H>7h0JseYPNqPjzOI0<3VV^7Oo9<8>5Ky#Xu99-blL63 zne?y=-GM-LH)Rg2uYrrJWn63G(?W;~k8snYjzJS`Xf-WA-Q0fZ+a8d;<`UkWFYdYL zCp_YD7UT(RJKAU}K?hgynsV-6PYp`ZSEW8Mi3skdXF*U6;!-sRh!-y1eQ3VXT`h4d zGB}Y=?eCUi6lq@9o9D7Ura{e(Qb>OwuNtmF4MS%GX9Ago_YVy1cXcBUR!|MMPrL$@ zGn7(LAJn>8FI2W(*EqPdSar|R)pyE4ni`=ggy23d-=Ep7#Sk*4Dz*gMf+XQBmihPy z`tF%dz<5ML@^VX|ZAmUS=hIg(J-vlCMi?HQ2}ZT{R*=(gyIQ@teL(x}jnJ#R-O51R z78Nkf#6b^kIb(rJlJU`ujx{&!7gmP|!avP?FAMVxg}6pYRl8C!`FBf_c|j^6=G->ReD#BXnYvpVb9sYF<}sU~zk1THjOujY4g+N9v}Z z?L@mtkWRPn-WDb*1%MKiJ((OB2~=dvY{#9stq`}VCj%1ONqhgjb5x{iZiZV7EtI(# z$5PR$XEPrNs-aqbgLJy2-he^8M=L?Ro}gvY@Z?;!c<$k%aB;#mwJVZ)bsyV zkjooT=o^?H~$wttXG$c0ro)r!Wz1y)TGq~-P(aB8=meloibj@9I{YCwc0O8!D z8ns6f|2GL-b*W<2@{5z?UO!)HMl~MwyEFUjZqu74)m(#-BR*+MT=mOKh$xK&d<(^m zys?=PjroG1BgZs-f7I2dKv4HhKUn&60_~FRE%y1BVytA)0i=^i{}Sv_wt|diwNF~T zzg|bSMz0}^p+9KW>bYc8ue;7yYZTK0odd%ywNfVcoZlAsY5AI)A& zk5^py3bK5~Oj~mIHjK#&-6|gB6J-wt9s zzPBExf7|+uDG!{)Rcv-{pelylYyy8p;)c9it7kZ`tgK4ty0M#w(J%yPtj2R!?>@Ud z6RC8j-R*XG^^nmV_fd)e^P|JnU!&O|ds^{7VIPI`pc(l&gG7%Hl6!YjnLm46_s;p7H;L}xQ)g)wi?{fY1Kd|j03cwh^|Pm zK@{Fb^EMdLN@(z-mli^ky*sBc+cC{gjC)?;%$f5jYmFB(F54j98D4rRw0{b?IwoaAHt-XF_L52oQ^-94}IOg>6DU`C3B@b@(R8DkG6+-w+^v8 zVl0N&GZL|<2xiFVL0!a_-8Arw)C|M^5gJ~;QTg-_o@R>MpX{+eHcwat8Zl2&a9$^5 zv_gHOo;yK89Kv3j*9xfss}+FB>0EODVtT&^}mH9@L!GzlkK>WIhwv9mrkOX%>l36(fjP&pwHGYWNeQZr2^K&_rk}f zH@N1r97U}VnaAnrk*F7dAK4edEA-sy9DE8`n?y5bhlh28F#@k^Gmo^AIK)J*-U8Un z*#0+;vHwBO= z;N}IdoDLFP-yzMwQU6(qDj1OkYN%MK#845wx=%?2bC-MWE)ol(*GB`;Tb@Wk%QkWqICN2&;bHw9kv_k5IlkB0m&LDWIlh%^jPYvR-2Q+C*RX$USSC*vAQr$DEOU--}0wLIB5A6z& zkwwCqRfou$Jf(?Z0%QD;{xr6>0(*mvk%5l`9V9-VVDchXn6B>C#JEP8{_HY0b48G4Gp_9Q`zZHdmjP45VJgz;tkik`NZCOj~=jbFC|dBxzVr5uI;fZB`F5m zW|<`|_k9qoNC(-&U?I{|ZZuOO1i=&F1TV*m%g5i3-tm97FKHaH(5Yg%MXSO~H(T1S zxZ@g?Rd~$k*-hZN8wmEoOK&$NWb6nXES@9QUmjhaWf~&1*SWH>siTwe#c(%f&`~|0uqe=5w$| zZ*f8N`}Cn03C6-am43pc!sFX(3amg}@ou{-a~Jr@`} z@r9fc+#xRn5DhsV9yC4Dhr#|cxB|(g2Nb^?rN4n7WpsC)(?LWC1vyg^h?xYI!XM@P zHC{&icryOOW66KCojOCQcnDYs5o&xx?Uk4%(FpCC`~#8z#w~NSFdSVW1XuCklIA?i zm#bUw#wU=XEe5|Ox@qvJ#@%(x`)>_;TVvwrZQazghdj%rMKz)XnaN#4$oTYamAmZ{ zAw+WKuGQuC$BNm#M&g4&me;Gv@_ieu-@!A0nv<|u%6uBPGi=oG0b4Z}PNsXT%vDpx zZ2b0d@<&O%5OgU-a_S&wjf`Wsz((Xzus@eXF4h|639?gb0(v^BV!xM{GPdP z)(llEQIcw3WXLTtD<4}iTWf1B6L~n<253t$0`9KYeak%R?}{CP4BPTB{YwqD^(#v@ zO>2jLcrZYbt1IA+=PJtU!-9XW9qRvtVBRGj$V~Vn-&ZW%@Kk30F8-69^^klL^j5q) ze$M6Us~I>9cI2(f$Ct-dK0B(PqdR?}Ohv3d2~?y3$gH3?2F1_fG#AH6BJbYeqClfjf7p$F_E%5ApUNg=HB;U)G_ z$Lwu#Js>g9%_u8h!P@PP+zzJ`=eIol8hOOfyDM?oh)th?EO$ylqn&<8kdv-Mg7H9t z!8ee_z}C$UiJk+Ajta_QASupa%hrM9T>}Zh4%-emB=2=dIh2!F{!Jk^B##)yA9IVj z=IQzBd_LrS`qf!cZ?c7uxBWC1G}IMwCnx=v!^e>Ue~R56O$xYYn?bV(Tzho;uXvWT zqdhIxZLL%#a8M=k`(NhZ-xSA>EXUXbj(H`6d50YHj|}D?{qAe*2%0!gs$7#fd;==l z1|Aula*;0Ie6ch!$m$q{ASvNbxfUc4m;~BY;&b3{Zh^XZw`aduH*Nb7FNC13OSjVMlJsRAspv zNH|*e)``3BLd~_)UhmI)YhG}$Vtac`)^{Wt484T9U6`U=pj$u=ul{Gp6b;;)JC*pu zGV6z>aNtP!=#Fjn&8xG@pE_-MlP~=2chKPCU(EWaOY6bQL;Mfx1?9j|&o6~nyLiJl zgys;RPdAIU4V8cQvm8ybB!a^B{ygAJDLUfx6#2tad4mD(r=z131Y(0`^Y#uKKeZ5h zk;Oj3&jD5|fk4pJ)%~AB!p4moJv=-V zHbQW4@c+Xj?Ay05J3IRdXww{M&36#u4+#7fg!&0X{Y9Z(K{WoT5tpE=AAt<+fK2C* zrvK$6tiQY3=`F$duc6@|Q}Y#j`<0EG{xx<~I0?hh|2PREX!Lnx;2!x5W?4zuDOyW&&M2QRr5_xk)dm2fAjSh}TQZfo&$dc(W_LK2>5 zR49am|H&gXC5(%moBuZ(;cD4`+X(ks#^*Zz10%dVHU745{LAq8@|E$W!ST`2(W$Aa|9>Ij?c2X! zzkdDl<*(uZ{au+C3J#Eji^3l8dBV6Y#^%G5%Md)$$;DcY3xW_0V-iUeE(ZYuW_<)$&ZX|1 zHht*9{;A>IfA3xDHtRJ5A6F(v2^se|q1foBLH49?JMUkD>C+iLVc>p*#`*+Sq#Qg7 ztbrXGJ6{Ki>^gT+)C6L`bQ?@qF~wMeez4tOpgEdoP<;RW(_N24vq|hO#9+`9 zt~f!kqnJWf&I_j;a8*mC94N!6Pwi8W>TUxCorZ(-0k?Z=psOlUj?ugC7EOYndb=Nh zXipNv;l_>2NCk3GOMwEL7TJxkjh{qR(2x-Ws%%Gz@aXo{Y$<~rPhjV2=r2%;j{{xE zL-QJ_1+ao}`n1^6zo+&Xr6Q&HMO~3uP-NA<2lQ}*rpdJUG$MHvv>PxjeY>qLxgT^6 z>Srzk1x&V6db(&o^`iPfOC*D)+mUZCXg=PfWCjpxqbxu?a!Op$?V|4XiYIxg$6=PF zNGj50=uwmM#(@WtXx)V~RHc$~Lj#yeZ4VX6HhwyUjn*)^sJ%HWyacK$;BPcMwGt!$>El0>s|9U_2{r#^GV#M0tOHNyMia$;mpZWdihU16d zpJkqF|9qJV-}UF~?6zGL@Wb2>f4>_ z-oUQX-{tFNm^LxK?k5A1o!;T|%mllsH4$MyCke1(d14ihnj9*QuF>n8sHSr(H)}|A z^2K<v4YCU_|~qlzBk}c-@+{J+;k0 zqRKtt8&A!T?ds!0LZ@rm)&KqCWgLcq9)2>a>}x%0ZOZ1kEccf?K1R`uFoo+_&y1a0 zB!Q{6O5_R&&PVRL#@d=wg`RHTh@z=%6$4~Du<~J6k$*&EP^*B0I=9T#i~yI`1EW=abd2yn{><}1BSoFQfdn#_0`;5NZ-Ysa88yZT{lY5bz+{8FB^g-?aDV` zKe1rzDaTFd!{8aEzA0Q>4yMQwc{`@8!d9>WRftc?P}X#IO5eaqn9s`rO$WXi587#K6Y!xIB_ z5<*)s=?M5OF>4n$~r9PnKNI$of`5tt6fcH&2L9SGj`6_)ubwSOSn zo(Fbw%rISmJ249PAma~`OB@HXJ?Ok#JFu4+Ldo%5!3uWkzl3K{kPULwUNKrEPRq(p zo>W(BHrxxL?j?8P8$JD7$jI?)m@`7SQWv&gfHJ7xA0-dTS=zT&T zh5sKprxt|TPX<$Em>w1)gbB;cJ*Y8{K5Pw33We?FCo0naK}<~6T_}m|wPj#etb#S_ zjY)i&;?)ajdX;j}0sP!Pu`~siB6r0LfkJqqqtl_{98WkZem%2Pzt0=k#(JEB?_|Rx zNf<6Ol}d>`R1_;B?b59(+sashd9bQB86uLthUiYmbqGpKM|qakzF0Y`1B9vq3A&G^ zU(2agm4g{!u-Aitt#yT$kX4LGYyqKZy^$+cI1VR1C1c`^Z+=D5%Y1j z!d?WgUtyv}8rYsCuze!EDSsQWs{Bz-tds~YlA~R(R}ErN`pkVfvY-c{m{)X|zZhke zj|*o4=}e$ao}aLU8#0aKQQ%BQyp{USmv>{CB=~+%t@$93!U9$^T&*y$Bq8d?eZV!x zlOTYR-2KnwV@}CopCj6hBn>COG?)VZPZcP99bo?jJfIfjo{adKh<@h|7Gdy=^&ty~ zId+^T=nIqrjH#CwnF5Gl5G)mw`L!h0M-I`TK#wqx`SQ$NV?bGP;%cE{1Pkmj1?Q5m z17cLXbtVRm06XF>-WSFH&WqN|SjIR3couzg$f?mLfff)OOUim!8T04)LP6iT5 z{-?WY#|A2eVpOA8Wc9t);Dlfy2}ULJAnssKR-unItVPxWiC1du?V5ktHXQ~IkpV@N z6UNwMCfNG>_tUuy=q3VWPyk~ocEM%rl?bGt@c3j``x@|(=ij>Au)Au9Dyzk@SjOSk z+4;C$$n`~6^+uXC1@>yJ^7vxGd>w2DE9ppYOow%oO=-vY8?0h9=w@2KNd!H1Jl)1R zu)8ES##-suaYfgu|Fai}sIxKJ_Q2k-7$@(Y+23;?CFcNb%}d0c3>N$VyCV(+|E{*v z!Z>cb5VdytwEaA4H4|(l1~M3~>tv^1&DPm{1mZv|sI1=ncSzM^FW`)PQKIaq`L+_g ztk5(Bif~5elaTT1I|Jl^1)}(y8a!Eu>R=sC+4E zVZim&&RKxb9xP;|Y&IyiX-sxI^~m_O_OkR3S;R4saug}}k{XDlRP2Fb9xmx!c1)kC5_w4^|CtYX1F zZ`l*{{Cf8f1C#_x)&a@LOGTCR?;0 ze6KY;*$D2#3~6Ft8f3tIL9pvesxA$U_-T0VmzdlTpWaE#v89Y3uPz}9E)=L1hD{z? zYonw&2W+D#ZDGTsL*OBx9>_HMgVq(F`G6}6af|L?!zFl)SG$HD@^d%M{Grrb5~#xj zYt|K5Q0<$2`zW;TU5l$2dM!t(j@h5U*arOw6NDlS_a>%Bk891L zeKUM}HbvecZ8tn-#7NVMEsNAKF-=RLuAeav(QL_bq z)a!=kM|6ZhP$fo8*t&O$+ceQq!Ty(X9iOos`=N_iU!JQCHr$TCOZ1cEGNGbGq(Q z{AlocES|BymYEtyg4&b(>wzPftbL@fDf#GS&8+s_iSO?&| zn-W6~3=}-N?16udL`*I|wVFnQRxpR$9{^Ty`w{U9AwtLZ*@J`lqvl{w5EA14#QE%O zsI?3uLHP*NF1m)N%U$ISG-L5u^%=Q=B+!GRe)ybidC+_LiRU#v(_3D) zLITm7*)3)Jl|-y##Y~h@x%aESm@_O?0vjfKc;e)CSdc8^wqe|zR_v)PGUv(bO`~(& zp*W>?u4`o_kwSnhPO%?a+{;8J$N_^lE3UQ{`bSxVx2(WBtl`_(s1{jtofufHfGv;1 zcY@}~ZC=cC$kxor^%*bpyQEL8aF55tdk5Y<%>@q%%8rJHT`NMhi{JdJSLOBJ`i4Ta z$qM{sySFpphv<`2*NWpQXwR3B6KcqaTXNkh(7Qqq6JKo?uTYja`>%`}9ENHxAgeXZy7#jW__EB&x;jIZj{<5D-QZoe+pTn^qWTZ%J$0nhkiyao&USi%LkP@@oLw$D7RSVdV`CDPm9ib*V61&CWDhKj3!wEb zTrT?MaJ!PO6nV2b`pEp2usx(0448{N=^R$y+yI-ZX$d&xwBw-&Fo6*q^u}KNBxHKs z+(i|yh$Kf|*Ya7Yg?Z}ZD z!L?|s->bd5(#j}@j_5D)45MtZR|oXsZRZ`MW2Z%<_?C46Wj43OqOo#%19U_EbbGkzAPP-PQYI?c}^y5WV|hE3MDhBkjQH)Wvs_5Bg@%M@2+ z;f5@J4XME?;S{Q%S$J2+Qgu~y*M>-?wzcHU@*3OZO9wlwH^lb|@OF#$9`czF7OEqz zzd)jzBKY7E(p+{5qKszkz#NK*EQgRi8{I3pVb+{>Tpwonx_4pWC<&V8WYXRD-Vd#|^?~3*(CD@$dPnqLnQPrOsKEyA$LQ zr8^-)vS7d&r5|AqnVG#P>H6>t7Y5N4K7)4Yq`@DFj?N}^)P#@QdFF9LKy4Z04hvD+x zJMQd>B2`D!z=5Hi*KTj$y{VI1YJHU;5W-I~a#@>6nnRu&t&8&4N~s$0JeTB3Z=0JR zODe>V^$Z0gUUmBI|0o38M-3UOB=Ec0eKg}CJ0j!3|1<(RMYu+?7PG|&mWhPg>lIe}Jt!V@`1(AEcTnmypU zRmfXk%W>Lvl>t3T@%r&`7ulK~Z>tbDB=>zcAD+SVXHtf4nFRHw#-UPMzlbAtZ0F)K z=^V$bp)^pC7~F@_-Brqf)t)`0MvQ}7`V8(H#Up_6_i}95@&6$9!1T143EPKv;7+5s zmN5&en+wK@Ev|s&gYY~^BoJEwC|y*@1!awe`S#7Ktc5l3XCAwyH>!&|g2acD6y}Nz z`GhDJ7X%Fj*0@8-^-YMUZ|?wmkm#&d^e`$x!eUQc**<1I0FRx0{`XCi&dlRP<(i}s zt=e6~@3g%^{jzS7&pKMqTRf)uV;)3f~$|L?@7l|sNN|i zOoc^QDsl$l8?AZnzS#ZHpOk#;47nJ0PJA5I0>N4gprZ9hRjY9@C_pFMTqOr;_a-Ui z^7J}5@2k+Tn(h9O*6FniuEU8|jQ;vHw@G4eiPhpY|M-y=M=gK{()RuA*v|^T zJd(whqv;M-#wB)%xE5{%9rMis6W{*COJSAx{`&sXmU7b=oyM%G`0;}NNyXi|tFxC@ zs6{$^Xs(79R8>zE0HB2m(}j^4+uakcwx^l9z#LlI6>&HC?av_}O{D(XHDG+?n9Qh< zos#CE+DZbPJWzuG&%~=jRu0U&BCrqlkM0b2BBmEp{9RNERL?gjyV8P8*XKb=S78#O zE~*9v5rTC8j1_WQSzAM}qzJxqDBob3j-UD5wT?lSS3xAIe7P$pHXB zJXzk zvB8Up=;?!R=e5<9PVFy6^_x%)(q`Y<9XS5w6LRm0t;>Q?+v-KtR=Gd>ho=-uA3wY! zdcL2e{|_VE+w3mNZ_Q0MK1$yBz+pau>pwQxBS!Ry<+d|YwS+M#{=XIC{N#_X$C3&ztIBw~yYWULl&)E@ZKE zR5lvy++y+VxI1fDetFsNsMFolG|p5--pYcPXuoNpHA~aN9e;bsOr#=Qyr-5w98jJa2 z=U&F@n7CfVHE3q5iMjW+Z3>^_+SEj+lan6M*(4mwPbr zAC%b-P@Uq0^Ck!?4(_TzgfItgTQovUU5#wun#*L(pi+^LQm1tK7U z!eRk9z7j~_EZBRU0eP@@m~y-~{b{i;6{Jxs<4;GUz1oasA#sa&zxp(=|`tQD_ABYU`^IKT^qE?zD~S;A11Ff_EgO9%sL zeY))2wrwc3Ew9a16YMGihx8QJ+uW6spn4Qm>)W<*m1_MMTyjMLMR2?5iO=&Gn6sYe zvy=((ylI}0UWvsLC(0TDM?a8>| zv0TlqW8g|D^PvXGbecFH!<7yXkqeX%R3OhKcVjaE%~PyIaSU&g9KF1q7u8kSJu0KO?W-i4q!4Z1pLvo#>hq?9L!=^(0bN5y3%{qg$PmCL5|D%*NT!PZeS4m_ zG^8Hq>BF@7h3DGLf?OE6+Je?nZ3{}Kk(1(pms7Q^gtd)a5#9_T(v^r5Wh=_26czX+ zadU{jvo1=Z<4x^#6f|HA;tPZPsd3LEc{usI9rf85-h+Iu>lCx0Fu4L?Dh}#i0nN?A zt-XZ)fQRsxmrBR-m7WcAXA9vlP;k;luXPfXy3BD{fsBno+yn*Na9|=IWCqYITyYT2 zY3<7bKdD!uZslRun9+W>sv^~uW(^5=u>Y)LbPp#oleOX3^c{TehBLCknPI~~P{J3S z9+77wswa|BhmS#{$eQdRFBT05W8}gZK(*!ar3zFujYY<>7}!VC6$^)UbYrdgz zhR68z(fp))XGXNxqVO#QoDY%XyzN2?ViatbRz3=S@f7WI+8%U`wI;Uu=jg z5j5E!-3;Tp#sJkN43v-^FajBxiTzHMfrtoc7MS zqno@JV1zZ6y@c)D1FXY=Hh2NONiVMP*zIH`B5zD&AC}!SSXXw(bRHDd46F?e7LYuU zghGC5T;c3}$Ie>CJf-x0TDBOZSfG?hSUx_99M&i$Ho z#62HaG(M~wMztokYM|K0IMdq2QLTWy+fl5Hm-i}x@wq@P_%4D>dJ{4b^dcEV_5#;c z!lTS%e`RnD8C&IDYsy6r+C_1jpM#cdK})}P!G=c}^N?dYu$1_h7o(Xblrl=s&Qc+i zkim-VLAp@d_7`x9u3Tf(BRB8PbCJxu+ATh7sF?qTOYS8EE|0zgvJFvBxiGLHotwSJ zwxP$ewI|B-UzYw;)KQ`T*O$Z+0@#o|%xzxu-OVHNKtU(-%_Q@&->0+8%T1HmCe&?T z&0t?_;eMv<96C307t9z2PI{GRC+^5oYoKINc*HB@&v_=F$I*rj zE=vIN^8hs}a8<}iIK*6F08Cq3+;b=4Fpi&;vmQZ!-gMsRMdU_`jrYePeP$sO285~Z ztqpw-s^wm>*&J6oXmua#V*|%i#|I{fn_@DqmNOhHWApg)xDkR817yx)YD$1EJrF+$ zB!CX33ZT8`awBDmP$F33*zLaRu=L>lpBl~sV(f7?*Bbxo)v?!4_9J%X11td0$(DB! zc&fb5J0&^_&A$$|0IE8tj8ypyba5H6P@1NMLjmR8;>S%@w_%u8Z}P@R=NxbZf1E- z-W$LIqX^uyK(01^gWRL)6DjL++WrUo?IQ#$8mR^*`b5Nr6^P%*@Yfw-Y!TCiDA~F{ zXjZ9eqD#?;Z>aLezy|T&=qYe3zw!PVz!tt?g#nC2V*BwIUt>;(Q(3mOE73%@euepB zOG@0XR3siWsUws1a2+YZp3_V(<^9_~RF~Jgrydk00TDQXf};ee-5gp)wmWzNi1lJU zB6XXg*ggbE<&Jh3wOmqgq6;n;^l(O3RWM^5Z0I=UbGYFvOq#jd(P_QpoTg z13S4F8f`jkez;OU@UD0JQBW^XD+4&53#binYRs%0-<^-~O36Gx00%su6R}v9kne&= zJOS5-*K9@ShV#dX!p^1Ww5-F+^|Ww25lq?!GFo%*R5`>GL2+kCdE!<$Ju#{|kvR5j zN(mmP#R{Qw9V93h68QN9&_~Ky(+YFubMk`&^2Qj8EAPNf<=*!ZhfZlS9AIPsczv_E zU|SC)f^Hqs39;^p{LD~0x*O)75kVaLSA|>6@VZW)qJ1XFi>#r|+?2V?>zYBA_!^3o zAKDaNTTwnmpq8i(_n|TIB9O%xc!=7TTK~X%y-m;*rXyfh=N!b{Lr_mpqY))5_y9AE#G@nFs{hLEk^!x|{I5~@D4S-Rv?T_6%xL9zJd1*qw zSjrz0^Dsui?MbV;qXlTiq?xrOAz1!esA_Xpp4g*sg9D4cEMedFGTjqwbCm^#S8Rwg zZ*kkh;=pT?Fx6uSjA`!n(!DV+gF#SqacWnm%FC7^4HZ#%^Ex2xzP9=Hn7#DgcsL~o zTTaw?M;tG+I&jdd)#Metv_E(v0mDtF)i^x{ z1lmWtJKo*b$1GFL$$DKJ4v!(|D}n0K(=V60H2Z6QGARj%NVDW;m9wlbHam zAGq2W#Ix|AF!yab3FE5GLK{ZRd~~{owd-e@s-f%KiOg_H>MCg<(xI^{e1}EBEq8dJ zOVeD`wpQ-b5HxaLe`8$q>zKN=DS)^-tN}u6&Q(+yA7q$; zby%?E#<0-$qM->X>cWZV9UQ#b9e(`PO8=+GsSOxhs(f%N~$NkIY`a-eIwgb>G$N8a< zf1J+@hL{|m&uVn=6sg{(|Ly#K{nqr?yv**fvXFBO@X(i?9yh;%r#yz$LTDhvR698f z;XI-Kx;D0vF4qq*_57>KBfWeDS`R4Pay|G0IZLL?(KjGkR-A><0ogVM{;2Xbw{|sK zsC5!ZdtOD!m!PNX2SwQjJ2Yey#cWmDXq4H4xVnkcy+AqGe!E z>8deMb&v)RTx5iJ(pfk}hrGuxPd@VV65fF21;<(Ca*&PvZ$*$mSWTu{g+5kE#{wZ5 zfThNfl}XpSRlx-00)b-^u8$i`WW-T7Z6!)UP0YfTX}_b|(#R49()!je}<7_jfH4(*uYOGOuXu$w-^an1<_HB@HQ-&y(FmK%iw2_C+CD<9l#4YzA)fIDM< zMnyAehGuKY`;wWgG-zm>NrH~A?8&R3YlLDHP}zB|Qxxyfp*i2W|7`w!fkng>?#tA~ z9|q4pD!F624vxWg59;K6?Y{o*jCrOtc*os4k52XGUrwDhj%EGK?_d99KsdS7_7s5a zAu#3!GLA`fKEJZN4lSHxY%+^`%)3T7+}V00a4T!ox#yI$bT>jkQm>Vj_^&-HCz zP`#3&hu&{lu*+=M>3ZCt^-asdw3wHL?@70u*H`nIutgo&aLwu7SaE*)qQS982fTM% zmDQ!b9E1bh!f#rYUuj=b*w=e|$GVlE%aK7W?Y)z@@k+&X`);$k%)9&T4pqG{+e5td z_%;Z?T6($fq2u(?`zMyZ;DP_dZA%H0X#8!>S3Di>3J#mJPWxKNZ0B_aM75ofd)uH> zne6Y|JAHoLrrFK>ZBS|7Orx5u9syYpadC3TO3pqWhWAGmQhtgH&q(c{roh08zkNb44ie}p5a+hnL) zyB`U=_6Ntj7Hz`3s)!@qA(;T(sWb@d_lsAJy#>nWKSkfss=ym9+&HTgbo5mJi$6*v zw7he1({0j{e(#7kEBULtK3*{Q@%uG)WPa4sS~a=mINQnFCq7D=9X^6J{;rC@!vo5y zx@$^z+t?L=>pJ4)?$K{IAC;x(8ZthCDI8I*)8|2B@oFCKI8cSQ7INt3m-Bxdm)$o1 znk>EfwQ-x%+mOq@9$dNk?b0cy_q#U#{rHD1{{MoIfx%z}1%>|;A(KUReSCZ(BO_%9 zS!!zP$&)Al6Cr!{FG42w-x0D`K-{`IZdDFF2h^Vim^_A<$PlvIK$~HR^8*Fj_iF!> zBKtSEOR)PNwcUD9beBA(Pd!>jkyV0|F2Mf{?w*DoIjj6{aJLnkbXhyK+i?GwiuVHo z<(-|^ZQJB^PtPA@&oyt#e+GAdghjt|kC<~$n)W;LE;Q+Vc=Er^-K3-+w13OHANTw> zoJ^r2OZ9)^WLWGUZEYFd_P@t>eKG&CWZ@hB#mRP={1;1h%XO{Ygpr zlb-%ZR^DYJvSs)GEbpGt{;%?Gu71T?s|s0mx6vxE-#xp-uR>Pa9SzQx)pnm8uDG+O zVktHIKS8o@$FpCa{I|AS81`>!_e{*_f3jq<&TiN7e_68Z|F^SST3Y&l1<5}A2S~=@ z{Q2*Z-L|$rSFip@WVc{c*4e#N`oDB`U$%~ZxcXl#+5ZNT4G;ghbLY?W^q;3s|12#n z$x^#7U;cUj{?FHcZ~y-U$z%xGq5rQUyA*><{{tbbKWuuIy*+9u&m#&S>?MC%&5oWv z1!(J_*C-Jk9>vF=ZU<3qy;8`JI9C+h704t2Kn|p;AUjK&6oUaUENYqH^7OXfI}9;; zb-yPhOxYqzxbl#B4SN78EvP)h2m>jT3^RPiW_Nmu_J;%TpKD{TU|=}D-6Mtv6tEcV zF0)^B_n*+(a{Db{mlwE5UGn!?+LGKcR3DpV7JSO?i$SDL7#iS z$X|T-n9Pp3h+EDJuE&T-2egX?X{7T!K}C$1mGgBexjhaeJYHVoOLFVpZ>~5KM~OH zB}hE))L9)@xUW1`zo^W(iG1|17s_-?_M3S!KDZkvP%}OVa7C(YM}bBxrQ~Yi^LmZq zQq}YbQ(&{Mgg33Ixm30ucJSd6IUhpQj>}d`e?e{stjxK>RKjr}Ios?vMOA9oQkw5f zgsQiJR7GA9?cyU5mk(Hi7`r6hJ`6Uh_Q<1loqO?@z;H>tBnfN}VD#ZyFyy0G9j8<| zvy+(dD)g)1xqWx#-j@jZX5Z(`5dCAjGT++^>%iYswZ#VxhaHvW5-ff!lk+|=MN|PZ zc29yfPQ_Orx-uEhxQKimTp=djdiwDy)TUNkV%lr)PF!`ErbcJpsDp%E7+3*{0netQ^m^uxDDv>fyAvk7PSeSe(Pbn*L>)N3EU&(Tkr zC*BKxbo#-RwjzbR4$OExb?q5L@7qyNu=ton$~3Z2Sx`sQdRz)jE$jn}kCxlsYYVva zlX4~`y^7n481{PTxqp9FV0FYVQsxFYxQ|qw->BJZ7p}rQ$VXQ)-W1Y5jGS)s70I8qxHWQLz;o)Lg*2{1@ ze!TC3qh+QUYRG`b%-6EAI_s$6rjoGA+3Gh~F{Q6*E8lr9FD3+J-waX_%9b27T{Y4= zP|xJhX9OW;0qe8I(Kqw*F!wxYROh9K**5^Uro^2O#=9A=R5;kPLX6`1Ad_?UaPW@M zy&t~L1wsZ`+PomOD#DP;D{rWEYONY^U<5PPESnnYU@>Lxx>PbJUCF#&=L}49dj=Z; z&{69^d2IC4$#2YB!0ez5Vuh06fOD=GyL4zcvNr639Y>|wZ->fZ7SfagRKG-S(vd{k z3V+o@o|ZD8<>CpLkO2*eZGadO!wAcVK~y12^`>|N4%1aUOLA8-^J0c5)VE>Ly1HqD za6+oCdOghr;2$j69aKI}9y!o~h#8Lpz>Cfd!%T>*i-Yc1igeg?89(Poz$gV0!AbHhSXCdX z+|#OI2V(%j4+ervTw$u5r-9xW1{OZqun#iW+7Fj>T}_rXh&yHTMgKnPNAt#U*t z=qd`vh7AXaIU(sGc=1Tb2}@SKG45>l>Cgif6ZSAd{XlQcjayZ7W}w(rE$P{6 zRxTWADhfrMyfL&swRMn824clXxIS#f+~PTaQF zDQNR$>V~q4XKn+&IiHKwNXobzYxlu1G9^07C=edR1MQvs9kID!K!HuOFg}iqiAiuh zPvNsJw5>o5%7{&g43;5T69cMm0hCQ>2ae_D9BrM%cS#|d!~Eo|Jm6^a#adHg%wXtK z7p1)!t}0^;m^Xoxx$%-Yikt?6?98|`QzeUp<*=|Jm%*P42mQ|6;uvvyuljji0lqk% zZ8I~^qc;z#IBGE;uiK&`#?n>SYfTRLg}P?y(l$rm;=gFlq^J%@6|(m~Ds>|;RT`W3 zDSzLS-&7da@b&7ThMh}LpnDur)hlbOQ=FVI-vt|S7-}S5p~Lxust|*HkVO&@d-Nwf zke8xqsc^)A)E-KBp*0js{&DlXgm@2o4vN}jeETj{(=U6HNSwMEJMCKFYwHq zK#_IUj-}bwA?*+r_&EmN&Nkq zI!J+ZPoP+i13>oDd}Kw+K-7VgVe)4Hr&P%x_CxT5H9YEprz#Qty2;VMJT^)SwGziC z9XVzujW83&qUed^*yD#IsB7OL!6K*)EojH#Ef0?Ddu$lI)dk^0lm8wbZG-o3Ain7QoUhazxG#(eBK}-puXT9S>w(|X8z{prz_#xim@hcz;z>&iq$BuPDg1OY*0=o&em^$^`Hf-mUjj=O;?452FD(Dvact{sWm)E!+f-tqqM$>()BGhYA!_%MnT zG_eari(qxi$4^+pa_H^}1d?|nIz%6GN}MP23ajGbc0b~VY*8Ju@r{164ii~Uck#vt z2H{yoH97hT$ZC4pHM_uQaZHWuytaE!MzeepF^fDJ5lV;KQdnJwBTB|V*S0|LOt31& z8<2ilBh4em?#QxjQdV}3t2pNMu+y>tS&f25NrN6_ppTGGPpU!B3o-VFMRlTec(Qos z4;(ZcAlG*WCIbd80}z=E#54Vqu|f!oaG?HL(9=?2Q(_ra?4(RN8jq(KWuk<_y;`Bz z``^&&w7BS75kCcv_H)f}HE-j*WbS zma}uMwXej87RG_`+K#SQh zYf|>Gz%gY71Xn|t5g}Z9lsg3ZYAwvx$`tksV0Y0CONI!z85MV6nae_#dSOfS$70B+!W8=1g=Hw`QlDrIK z0_F}&`n^y%76mN)iue{uAu`J_G+%*b zXyajMJ^f@o5w=efF#@k1=R)ZKxf4Etyxx@k8BiHi^|U@m_mvR7Tyr%F>lF#i1crajC&RN8$k?X_g+lx=@`$_%1-w z`{Z+otW!(h)2i{vuURNe8P@?1nqXhjt+|vj9>nEBdx+rD2biiAN`$m(d>ULqt2ql* zr_Eee(m{gr{L_}!K{9rsY010TqfWl%sGduQ6rS?J5sJ)xA&UOdum zEwYCW43?xyoHXt3hIJ`KG0AEIdKak zVq}L1;g2eiT-0tXAV7o<+)e3?h(q*nDwx9PP7<(?i{_|B1YSqSnmTQF2dC0#n*p+J zI5L5s>N6466$Yy3An$rZFAG)cg+MC@^b!^r)9UE90@*34Q4T7cmG9Xz6jN z4Bdp^UL%A)F-TC9(Rjq_@gcciS%VMru`T(sbVE?|*}rtqv30hcLRE2L}-k=d`pf$M?Bg~LmZYszm_#&$q0+I8|#aQT$+VYGgSBs0>)B1 z!iXPRrwU8rQ|~~_R+kV}v>mcMZ`(0X_H}d?K@dwLqs5S`zJ≻MieUHv{SR=GG|% zu~~87I5@lOO!;PoA$Tgg$7Xb@L9U{)b;6T+Istx^PxIC(a^ZwkGoXD-d*cmI%?uef zlf_#*eM%jAXl^1{8+!y5&ayu@&IWgx4SwG}^!;Jhj8|fln3}_v+f9_?Wt;;0dOLtS zF(}Bz1en+nNaMrL?Yj~hv#}hsUV$V^p!QMlUOhOx%u$yg)|+{79GV=el1 zZuaZF$eFOoa<~<6>_=}wtO!maHh%gW<4RixZsZ5>!@P9(Tb&g zOW@Q8_FfeUG@9;XyL!T?8l|gpkB+Xyh)>yZWLW_@X~kWl3u2%NVmeo0Q!|OOyj3z` zqgd@YT;=E}3R?@4qrRCK?4zp)WwbDR*tQ{va4EFUx|Dci6DmRofX0h&ZXTHa5EAVx zoeZFXj?l0oX#@&^?mGngMitNV3y$ zq4SX*G5wb47W5lb#D)^b_35x0v6C?!v{~3Tc;fM^4nUC}b4!qy9|M`4bV7{_X99+=Y?0SRQG-#r*D`E%T+E0F^=y!Z0>%pk zS~+~}Fn{QYEfD+@5<-U_KMvO7g9|s9I3f|rsDsV6@(0CEkJ88XY`_fZ&4oJNwih1t zGDpdUgK8=r9K@-d9@@XrlFhXz_A5vf=pD0V`wmK?rB*t=)9ent4vjf=jm|zJ6 zU<7ocxnNN*C122hD=@9PeWaR>Zz-pyV$u20QM8;me}3Gn_Y%^PlQn#~cyR>=1p=|l zI=?sVr9syd7;-su`FhD73grq$I+!kooD?oCd_f~bTiy&VkR~B(jnDx6kz>E`} z*T!PhA|4J=SSu}G^wWh>`JL5^&E687<+iJ(~-5>acfd zA(C_VKSQrQ0M3-Ynz)jz9txlIaXQFI4WjRV8i7(Qd>b_x)E|QErXx<$5obhTZ%N}0 zKDglP)Eys`Hxjx_czGuv^Hb<6SuWyMs`#rmaGxpAK)BR^54&*Au?&T*BExL);LH)e zuUL+T3cHpAdVCaqneteG9zu~{U%VOLdJLtf1qEz?&4fUH?t6UQ0{u_jJ4L4K;rgeu zO6c*ez-E4~pT+(NK+?K;eES`${)dal%v}yBOI&qfp!M+`~thG@U~h_>`dEJRjQnodQ5H=Nh9JP!QKTeLgQR&_#E@>8xwqUr#%fs|{y zI~%-Sp!Tc-)zj+JByyXQpKHhvGRHy@1HQO>|Btf1EWCA(U(Y)A#*4QI;}gKGQmG?S zF6%^=uTn)f1z8vkFDdj5R{r#9Kf2~8Xa|28>(XLD{tH6~#WCRLr7K5o%UgJ4j^s~F3`^vS5C^9re6q6#?n)xX4ZrAjI7brD&;D+_TP(1*zf^&`s z@%%8FoZ!|kdEo7ErENV@coHKum?F115%qEILD-kMPE}|q|I1+p-17TES|Tt&^eyD~ zYDm!%UK^MxMPW<=0ILZygbZrnHIdjBQfV11B=Fn;eahSALbY`<}bM*-PWH98I-lhs;6_yv{;%)r&uRubfmpWwR2x zceFWVXWwVGfzo|=ppy6Ayw72prpkAZ=*UKUF6D&8eXfTR^;L}Hr|7NRN!8%m6r=?+ zc*)Nw+NM}!i+T7qe)RN)I)$OpFoc4$o!!W{JW7>O`t8*9tsVm}<aE0moZc;@W3|(8{>f^eE8Cd|jAo5~IrxF?`o*E}uocQcZ$u3d1TTGfrITY-o z-*)4ayfW5L%jatBlP95uN3qz=G_38W^Ig9M7lYdLNwqmo@Fx^b1TEweuEHn^0rWHj z5F*c4BAiZ|Fe|lcW`Lk<-L-|12zsVZ4$ED**&TgxYP?Q9j@7_t8d4WHEGlKN2OZma zU{rI%A#PK>+~@oeCP7rEbLa=4O?lwyp30K%o9Vp9_CpX!|Ttj?{(-Nz52!np5ELUxGjjO$Q|B$(BO6# zfgcA~JLx_WSa7did1~Zf3>@XwF(VTkm39K|R~k;<4{=qjoem0dJHC{Q|9EvAqvp&w z6vUqCsV8nXP*jeL&L^hyzRy3m)@~!iZQ=eyI0^$bPXrC~C{(#D%ObmLf0pjFKKgaKlC()L3$5nUQ89 zA`U1vefWt52>7c${3Khx{z{AUq^CU#ZD^cPu4~`(Y8DfNfId z6IAy&H9BtHf~+-e?TJ^gx<`Il;%E0}QPmkyvgo5k5iyMr2n}}rXbok-!_*M7v}+V_ z;d!98$?UvpfKr89p{fJB7R>hKf6r#Er8@mn;A-qu6d=29m)b~(yA&+jg|2zMcQji~ z&BM)Pl74_Qfy5;3Y#zj}XK|o4;!&kVpVQ0DSJ^Cqct5lSh;Sy?KkzVB+7P-Ec6U1} ze|}J{gTXZ-4M4PJfr`<~B?{&0*Udx&NZnjlMMS6Et8cQY0BJ~vM)hH-3z5Y0=Z!nlKXVeQr zp+emOzoGN4vRJSUt<~RJ>o$K7>E~n}Wrx>7J3j|dT|)?_Rp z!qgxYCo~N*NUIRFF)5UpJ_8$2^Uqq)w<^zYWk~q>VQE-B-SH=(yN#J2$MmZM?VFF1 zR}EPzGeOBZJmt6cL9VL=5L!T%IS1~?)B_QfGzE;SRPu{BiiQHjCKk0Y5DJeWdN1$& z-h-JrArFC$>v|mC+pzm!JY1Xn)MG0UYE3GzY^RL?Lo1QtDpIwJcz|E-!$53>3H<5f zZt?%f~NKG*Et*beM^=>q2iuH&NbW-($TmSt=F$U=E z-B;d`vM z1@CDk2UX)JH?@%&wOvEj3_xs3AijU>0i_>q%haW3TLAmo}w1#aCjFK zIoROx!N_8aCTHHkGV;za3DpYS^><5K`v+)_A%qFNAh311z7iQBbtO#xTs;SL+**_* zeYmQ6mnG7FpKyQd48{whA`qi_oS;0dTUB+UF){~&nf6^~3 zMl(~-&OQ5TSqV8W%syWA==Qd`(5r8DMfb*! zl?UdUNFgM$BTQu%O@%`XIesa_pzUTXfkni8Q#uU`91$i_vYWvojx;%ZV&hQ z{<(gE(Kybc30J>p{N0lG?gxL!bLZKj-y!a4&8o}mPOC5GNdeN2#o-aj%0`kQ>D`A6YvI#DgJ_ucrl(zOu~5pwI&i32aRm29Ka`D-KOC2VFpYQA5-T2}^Hh2l(Vh|V`nQY>P&_8r!bK1>+ ztoNcdGgPl!;ra7z0!U6gU=NDakT0z&5N~6P`kd_{KKWgL>duqHV50MiGz(p$nUpIKn3c-YwYpl^w>SLUr z#03b<<(7LsNlKfd&m&8!3O<*8g#te`jYOv0ywP7z88w)Hbq9BKBP}f_DLaIWdNU67=YfoqE}nL{+)xSC zcLemrZ$4l>a+>F|tHPyn4LCb#+ZU&0Do`{_E;~Eh9Q(z6TV|twByy7u!l4HoB7r$C zgK9NhW`=UXf{Ur`7h`%ZMhm$yR4%XwI?-u%r&T>PiK!$4C^7&@JX5m{?)s#rFH_k< z#5z`{!=kWWKZcMcK;!imSsa+b!e7|+zSMnI#j{SZF^;8L3^rJ1;T5W1yXMZh!lhSo zA57O*)0pPXxy%yA?ow{WUa(%i60rwlNHb)KwFnu?_EuviaP}DmP25+wk9fq+zWkCD z=Q9rJ&fW! z?*l`FjVQI~{&7QHSfsJJ9MFej)dIuhgTX zAXa!%cT%%Rr8uDspu}f)&mg_=Tt67ZF3GvzAhVvYikM|%ngO{7Z?Ee0CAQ<;B(|Dm z@b#O;E@*dlBHSt`B)d_L_(gHIyHm z3Nqk<&qgcWPSby9Wjz~n+KQn$(hLnCu{$$(COB~KSd~Ai?KUwmMxRHqx;Bk%c?(f{ zDR67YLjz^4TomV1@fNn2u_+lOiyfK7Y46eqcxU5gz|iz&K;bp05-+xY4+K%nvKCed zL>_D$Wf*%mUzS2dfr6LWAq1#14!WwF=ROAU>w&nC$~KEH{P|guBe69g+w`^o>;y6v z4*bMdV1%prrbl`CyO_menBg?6#1QIOffWvJD&g#{hex28_siB11@(wZF~I-veOB%n zbvS>cF3%3dwi1B<8e>z*s7vH377yqY%HKT8x?hF%rGOk5)0@62IlTd>Ewgf)p-LTG zzh)4RPiblUOTga_7X$9b6es>>5y!fn=svABf!+XU-sG)zGoCtyCGFQkzv;s<{2USs zI^6{M8BhZ*$nfx#>pz1Pd>8!{nK}yUQ){wC$U45)S*CcjV6e$}PAZm5ZRVC~RRw#w z>6|Wvqh$CAhk|42CFO=)2b_&m*tTXK^sO+2q3Qf{ntU2$&G%Y09XQLs_v82N_(@D8 z%4#bPY$^Z+<}vKDct>?*?Pk^wJ>GyGPi>vTiZRDomXd??M}8FKQl*e=0ccu>oO+^w zp$Bs!vJLi4Wz|e=cR9WGHMiwXH)R&$-@~z#@e_FP-Ggovzq~{Uc9zE`I zD#$kw75YkQ_U)Sen+QW?u%E#qvRY>Ir9FPb)Y@4VRSNX1_x3b{8AxoIdR;6O-#CLU z`(QV`89sLyF>1-P7~_PUDHnFZI=H!~aWX6uWSFaImI=OZD$o=H&Wiy~Jz$41I~N#) zodh-^`JFfp^F2{?ZtBVC7zb>t)oBo2!GjtTh4oT~5e-aX$lyG%8sPleZ=8d1A(b*4 zJH+*&HVhmtFeLu9ep6d>*r1XsVX*`Ntbm~eC{?2abhTTQ9l9*2didE}(VHAxh)J6)?o|mu5dQTw4Ip#_bqg_F3Edbm8gsPnl1+ zhx6W!z+wc?3&>!??2b_e^JvhyMT5#Q5lM48xC`gmglnyR+xVL)v}|U5@5&1%#5xq* zOlvs1DmEfTvJ7OzCKY4?m=o}2@2Bl0k9Vb(HGq-UuJYPt?a6Q55D*YC zQ~^;#Q@{o&f;}oK)*B0ow~8nC^Souhdp~=hebzer%UNfweB={rW|En?e%Ie#HAoD% zWPxU6#1}&o|8ig%!;lLU#O@Q^ii24?aDBz*35MZOBPSP*Gwg2)tMWJDzA8sIw4(sX z<|x7tshVHLtGrLZlmW^DWx`z1oRp=O&88X&6a^ehG0fo}S6=xfNjblENNGt4O}(t= z`{NN`>D~^!0R1Q5Iv{*fq;ubG_|@M3FEDT( zrC$Wmu$y``z4Z294nA7B=CRblg?(U`%H{o_xkysDNqfsF9PeC*j48C@S_}tNXS0kC&4#uTP;g z5Pr=5z>z>j?bG=Vd;^Er{aLo*4sfgH6(_72t?=YO%MjWUZXxlWLpm~s%UwN=NWZ%_ z&bxGF2H%x+?jo_qp%=CcfZ<63Z7JN1$or5KX##gg0tL+lfZ7OXAy8HaRLm1Nb~7AH z)-pXQtD*Mp>U_R!IPD>;gB4;F|L< z3c8h4`(mO<-0B8aY^%5EXr;QK7==w)@<(s=-$FhjgSFjx!EA#3=5OZIV*JZY9bTsT z)C=hv9QkgjgA)1*a@vsbOodExtV+G*efg$)10*l_^+WwPT3EV*ke*S%{rHM~Nw13i zQ#n$W_RMitBu9_T52xtSkf1(E{x&C8ey_&iY#FBTBX@2e7QH?{$}`VKntO5iLXNKt ztD-z=_U3J)7l<8UryPwm1K#b)+g>i=+w-23jTax4@)zpBxk_Q1lA6ZDv@`oJTgk7x zM_CjNUfvaaeCdkQhlf$DRWRfHZNyiE$b zlfKI25_%>a^c8t*=?ga?!p!btnvD`1rv>TTP}3dT)Q_>07&RS)cN}&vhnB3-x@rIQ z(|;TW>>EIH)@ogRnq4=z+AA^i8Nxy}nyR z?^Y%idAa%H8uBo3|HU;g_;OHSLknvL2YH4$v)7=r6$Z;Y~&ma|xdc|3}oq-UwI*Z*3s zdiTD)?5{{s)KRYE41B#;BnJy~E`zT-%%Mnn4k7u7c&^>-$~W_ZXdmwH_~SeuU}WrU zw8$c}&*BbqK~RA+t3s`x$HWFz{YcC(UA!0VrLuwe5!egH-bN-(DsaZDrbVj;8t59*OIt4-4RPD3CtRR zb46@ZMwXGr)~v(RX1duEk4roX`2s%2n(@;+xnOJ{vn$g)Vkl>?&+VlHllJ4Fe>Qm1 zVnyLP!muZ$Km_l4aK3gX0X>&z)38JSO}3f@4b}T>Ojez)1*kG+4QZ#Pf5eeF=^PVA z>sZUlk{|O2W|Ne>NUT$St3pl=(^BWl(YL2A)yfy`07z0rCT^#liz{S+SJNuA z9Tnihdg4<8i-v=(qAPnz6Pcr-F5Y<5%S@x9#L;4e$!kjHWC)*6bxj#-rMc!B(Zm)# zJ=ozQ=fovN{#i}IebkNx?3uYnk@bfSAm&jrYOaY;aBLbsMp)Fgc z+g^;lO6C_v#{|xsHd;RJGsNlC5^c9>k^HT3B|C2mo^%Jn-Edrtdc7&f&V4Fpsy4bT zJ#cs|_{(5LO^xT1pM_^`mzww>r`q0WrQV<3lW?u&?Cv`*sNxx|T=QxB^yuI|?F>E7 zI!#ijSZun7EI)KFC)x4a8r3RDw3eM<%U#vOmAmbpR8ddZ?nSB93UKtWfnuB1zH9aV zE5H8w8NSXrBk=jR(AoWx$^&hhH9Xz@qx@?cfdw#k%^vNVA=938*um&y?-KbYNlZ@# z3n)HGgdh~yj{18Mh7?uOc;{(;ue}+A8ZlK88e++Zx!GOMOxRtze?twSR`ks%9##Mx z4(HJb*l@$B(_f5qeY(SO?wJW`pAajHonHA^UUP}d)u2%`JW^?)d;xyrNRURs?iXM_ zf!_Ce5Lz!FSp?sun!~0VDGXva?O5c=&nlh`WV&?NgMTF`9YR z-^2;WSLgePhXT$VSo^weLuizF>6;chu`+CC5yJMvDSv( zt&*KiEQ&xx~Xx|o#TiYrO0DK zeV^th6Xd9cyRLe(?&_`^2bv=gu>q+eCJ&q^IJ6I(2HOzB0Fk)5_UGD_`-`4^8q*%# zo8jTV#?(63xRVkcHTmtuvMzd7T9suf<6CHdK0ZCN)R6P6)gUB zDw#mg_aJQiX~9+xn%~*FH793t?{mYojmL&D-ZwJd5{9Z}p_>SiP0xdIHvPBcJK1|g zgU_DbbG3RmyC+a%`k>{Teb<_o!cc1p0sA|6me>X5o^Bqpa?Ml8#peeemdHoh4n{Vc zcMoxznc1sPu8TVRwtgB~6GQA~x+|8gFq#i@f9Cq-o8|H0IpeV$|IZI!ZD==)L70t1|Zh!#V==<3>w-5u4-7khdK9*Yw(qfSYIBivblZ8 zBD2u^Q35imIlN!&zR%b;=k;}F&<;5ZGPW1)xe-EvW&{Ga;DtF3WxPFmQIn z9Txu70W2$7+TIlI?xQ0Lba!ASc>2E%SZ8{>b>3DTN#j$`pzTA53=7Q{4}iR}^P#mR zK>G+}nK@?NhBs`gqDuWV=aC!>Db6Q&C`^qQn&%h~L+s&&FM0q+->4*~-Ed!n!UKb@ zcIR^34M3@W#D$mfO+6y>7}Na55uYyLFsTXt6Wx9Z&%?2y2N5ZOK(pCM(1yZxyb3M5QPaHnI6pF}GN@?&YvIweDOTxuksJ$G7~``k zjgRh%dZ@2{o@qLx{1!N2Q`(AfOtotA_4ZT(0C3(i;yP##v5a7Id`-hK{KLCGS(lv% z!7KnE10I5s+9PL6!TakNf2m0?A@`Gc1{P0I!QBIDm&m!Ro1ZS*(LJcUL>9PNJi`@t z4;e27QhYqMHUYVlP>2e~Jnwt6_m8pM4gfxHS@xNB+d{V^!w@PRfT=O>( zQYHNznj)FWLsN1h^vTrj@6Z(Z@1d#xfe6V%Q)Sq!ntu=>iB9STBW9af)~Jg2lv&Vw zd(Uh3De}tHxBnnQ^r#P1x||5z@ymMd&y*{n&(X{u|0quV?-L{}I3@r54Tbjq_e!Xy zrl!5U{lbL{zjJf{nVXU;p$nWV|5QTq+*D=d@7mhm|5QSKeZPkau3Rhnn+Q!+{hgbd zJ#$4)gxp~1m_O@#ix+M1I4pk4pxd{CQBI^&;-san48F|OA?d=NwK zgN~@JW$m1#{HG5pKmrIPMaHm%#i;bI#TNFn00qNk`w{{9tydv(KBf*+G}T>p?CwS1 z!uDbKVS;_U7(2~AzdXY+z0NlXxLayuo$Zu935<0xUk?~jcE5b$f$|FiDBBHUI@IJ) zD0G_T0ReOIJG+6XXIG9_Zrw$sz=pw-OX^4oah@`c#<8Z{#jFpZu*dr3sEM^MinX^6 zS~ci)|E{i_IGqnuo_m&;{;p?Q)v(tc&)QZsL;OX%J169A}9DR%)S z`l6I-RZ5(p-q$rWFb5?G15n!3YkasPrIG^Jy0U;}h`UnwZ`JR?EU;ByN-1!%XB|ZB zKmCZZ<7`_k1w)v7xOe&N8mxKe+%x211dLS?w#nceLa{=WZih0$o-)rlHbfx@_v7|vSHdOQHr4pZO#xHY6DtoLp_ zAjbW$ql7ghWcR2oa|^HbDigx0j`rFD@uJe0-1(bMIh|W!M@ZvueYP#6eYv@uDBn`= zvr_JZj7&%Gvk$p$U6=~r{O>+U8^w_R4?gIs<+q1Br?-B4l>O@L`K9||O?0~%mfON^ zPdI@lm4SM?i_g4GTPA>Sy0Z??OP1R?dLXFV#$S}~eys8;>yY!-XD5zr+vC+c5hNAF zA9iNFmi$Jn^(fE|8-LgO>I41*{?~=5_)2y60fZX8CTF_Ob2jg(nNL6oN`<TnKU&` z$5MYe!@zIv)~Ngn8Dg33;Ungzi&v(d%R%r^poxu3iDcv6k~tyNwV8d=P;akccr;{S z<62B2?^Oe20l6m5$WOD}NsOM%XA!GaL{+u)g5l}i#ozrYxl7JC*mrRAU@pPh@LU7s zOLn)4uUI5p%Z~fvK^a@PEPgWSvTqnR4K%2356$@dZSK^o$Sa2Zfxyt^cE321g z)gr|SI?MNTIv5WXYnwhtSo9P-ryVJ_^M(_gupScjQalsdj?mrV6a(+oacsSATrEZjVi_X|3xKAMM8Juik4< zVr!svtQt#)I0ZAH1ig8VXUQnS82e?Khy@&D(o;_#iyFwI`}9QkTCt_oIOr&)U=#H) zL9(ZWb_w5-QYc&{?=%E9fLcy$w9ov!YO*CVvb0weB$+I5>H$@ET6@MB51iPPU>0ly zI)92`p(^}bFw&-LC>qcl$O3gtC494Jm{PtGPs^qs*#BKUw+#}(r&h>^%lH*#_9%-iT8Gz61{dT6JKv#wE_Ud$t7-E&4KqQjkpXy|1 zrq3Fz{7ano;*x9o&POkxB2k2oND3M$YRllt zp{^xrQl7CAj*}GNg6Usq5yY9Z&-)w!UzbYdWAuCrNj1t;^jM`y#-IPxhAkf-GG1#f za1?WngZ8`~YuBHy@fi>+G!8Ai z2nXJ7VY?thYKVmhm@(p-?)uI?q`#NZPN|}8vDzhsFiOrNmigK5-=&_h!wOscgr0S#3tH;mYB%5 zVSrfm!@7CDG}Hx@6ZS4 zIk7JOV#H?NYqUiQ=hH5oP}yv%|LH)j(y;H zM6$C)${2lnHRe?4;^xP(Xxno5I++V0l*Q5g;5%E#sr?9MAZBxxT8gJXXXf-9yBSle zqj@`39;p`cwQBZ5)HLkp1X|j_ZC{v{^y{TW554bx*OOOll%DU|9p3gLU4K`FhsFI>aIou^NoEzNfSl@F{0s4fybzijQrZd*~Na$17OqM#OPz3f;%O%z2M85y*jFAs`TvY^~h@@}MfW*O$KuntZnLX{fM zcEFZkGRDi0v0p0m6~(GbkagG{)+W1h2w4x{u#NM(t%%MhtgOy@u;;Ybix6bqd~keg zOlF6(8>`^iEN93Kwc%K7uqU={T;VJoe_n!okp%OZ-xwt2nBcNZcVbS?XH2MUjwa^U z&_WlUA54Y>IikH;q(4*vC`5#^pN}+47g$P!DyGiv0Di5!sY9m(ci|Y+^$8}hJ>!b` z9*HamM2>y#ix3V7LkEeV)UqYK+dMT1OOuEwV5pxO16DhZ+QMS|(x8Q675X}mCjhj3 zkae##v6qM`mqCMzA>v%9)oc9ah`WKSxufF`!z-qXyL!3>{St(DF>yJDTpQmY`B73aPSG*6#3N z8nlU+AH_K6GXt6toh@jJr$iWmI^@3?87G0v?)t{PMtxLF{e!Bq`5rEa>Lk&uRFNvc zkkKZ|P9YI6|Maa2)o2VIwlIuOF+>1KI~;LLVIu4_5hD>RP6jJ7X$l##vLh&nEQL8r zHrFkQ6=0?1=U%{QtG4sEN<#BcU`%B;>bA-fX@b_ zYQ{loIu7Rz^ zdNdI8?aFFQV2b8lr>L!=R8?nJiGr8I=0H(Ch2*?pEmk5{Xi}ufdq+!LN%$rj^dY(Y zqMGwg+KD)Hy}dQs6f6G$pV7udUH*=4l^$+XRjC(yH#w+HBA_rDIw%aylPUCF5u96q zO_f3!SOuXL?WlK}HXqt7MZG0tVS1|Ziw&gKFic@3ua4O(hHCl9KjZMO{JUI+4Li?m7MHb3?QK2_y06$Cpl>8VaspF_UEbRb+4pBRB=Ct_Zba ztT8w=pLh?=lC!KcAJega_cQ#z8}+h!Bm^!hujPmDFdxd5#usk@agqxD0zFfewnp+;yK)D9?lNOXI<;b`AT0W zfqBz9IgA-C=tBB6_B1{j>Okg zqPTS3D6fZHMhDQkD+r2quoZBveJ{6TP+3ofgp8J7y7Bj)Mv zp|D;tdN&2xq%KsWpiZLD_}Wp6IK}OqB1+?B3$xq+i`*T8ZHpS{DiMk)xiu)iBn!zm zy-%m*BSlH!aZ*(6`CQwp0}IVpOwV}P0#Fhl!Q6rG+=pW>RNUiLrOqu~oP^)3&+K}P z;#XCqe68F1E$aH$W_$_{jGd3Lk=`QrD{7C!EPl20%91q6cP#x;jp;p;28zKJ*c2>O zE-louTpu3_+a!Uy=qj()^eb9#h&@C;=Lj>E_&V8^F~?7Y=&01CC;QH~Z=tGeqtUT0 z?WBjRl?|Qmt#Ec0g(8v_468;{Zv@v|36IXdV_JxbZKB6GPi8z#B2w0C8q?U8GlfG} zDuxgbzamT+iuN#!(7gzofe9ibogS_}M^W^XOphIeO1IwAehS1J7?mcgsMBG-08<>P zQi&DgKJFNLXty5`MPv=rAK{c4>rR%a#40HEiag?u<8_uCq$s@|^5^K2J5UaBZk=#X z$3l;7V$9&9#?`pnsxnsyGrfDOZK@G^_LThjH2lgI75iC$KL}Ku+IZd4*$+roR)3`M zKsdpLZ($*Gz9!sj!r0xF9(GpiA)=>-|5!yv_w9QqPbOVYa8PKyyk`t#KI12 z>3Yx(PxC-5YrzB&z%l^cmX7w6CPii;a%hTsl%gILqyIdO+`>}0J?df>YnfV#X_cVj zXfgU`e~4Zq&WB!7lN|Lwv0>%Y6^F#DAMRFJ`l{}1&qx4taVb5LW;0kvee7d*cehZq z?Nr^835Z<%@Iw8GiFSoBnnH>gnN36U)S%^>&Yq(C{*0mI?>IEW0VR3@&zQwLMVNO% z8!1O;FXDQ}Z_AG5kjUBRhT+T>RHC?*PE)9)pi4y4Dzuls18;6ghuS+8!dVJ=^LI@9 z2G-Mau>p@PR_{+frnzM0Pn9TS>Wi;|zu?arR>Msp&TB z=uw`0z~-}(4-n>*Gfv)__Fz6nZDuuCZgh&@XO?B*Z0)~Zm8g)=GXDDRxjl9&l~5AtdsIR&Fu zl)&zx1^c=~-O^#2Qn=|7nuS$3b3S;C+q zYwEmCvRMDhOQ7qViERj>DO@`;_{0LcG4flu2*rKdC%O9rsP>gnIM6a(Y8mYxi7De+ zTbE};Lf_hO;p*1I#{QLAw5sfi*$Nnc0~tvC19$uW&z{XUFCU0vGKbjR=Z z*zDM9YsOdav~FB)PWf7YPt6)9}xhyI+|L z$g?=giZ2Mr+{2fKQ7f4}Rd)xk!}AP@RP&?RWlRKm_bko~ZAeK4)m8Fdh|ZH3AYT|6 zUL)02Y@5GK8qRBMF(@ZaoGpLX?MBcsb_G52s`fP~=82HLokFucZ8vnSt0*0P8l0te zzM7#(N+!J|wqG^<@nf|`FQv%Z78O}G=c)F#f_39qY&rAhF` z#u8b-W|^0A3!Qvca)Z*}WE13aphkcU*Q}f4tY5ho5(W%%cKXx*C|#yT;!$o@(;|WX z`dPIkw?k1@F(F;dl~bKXLp4p*vtg2DHbEl8;V<~*4#fUI#;qyyz7dKJUN6Gl)F5BM zbdgzu9+Ue{>M>h3ddFa&+<@~;0tEKGm`(ep0 zZh3!t)XzV;RPy+v8Y$F4WyW_Ozh}$FBeibg=(H=2=;M1n_^C%>>r36;DZ)A|{;G82 zSkb1?#ED$?R4qzdyKC*AyhM=z?CM?G`-HnKjuV;}DR8}pst|zr8^NPrw-!GFe4g5$ zba265T(gl>>V8aIQ{cZhxxt~^EG435`OyN-vOLyp{J>0^aemfIPys@VL+jI*H#sWC z5}nnco7Scc5-{KTx`V+XIUE{N3IB_U3s@c`b*V=y>v1u8M+NahqjL`2;y|X_wXa_u z+^Gh2W)7Rc?TWxi{th9 z))ap7*(NE@RA0~P#9LJd8RZ3e;h8yvt%1^( zE(pKv)7zvIELTi2z>Vwj&ONktv#XBl3O@>)nlcWx8rp1Rvl_Nqc)vs}7GK+T!kl0c zKjHDn7NPcwQf;yjST#>&7g@Llv;?{l9Q2MF3MjSc2_r)^0E8;>a0sH*5I=Bj1`8v} z-UK3zKY5hccM?m`c~(ySyybH&o0Eb8&FtE1p&icvXSwb|voK*;M#HLN=73cl@0Y{W zS@1gndaTb5nsX&&S&Uj(;g{^sAA(?vB!mHi!wMnt8YC`5fj3N7L`jL@n*FK4@6$nJ zCm7^M;#z&7;CyBW(81)m$&pVXY+E88i~|hO&ya8p2C%9a?&T^8zelWr?8RFX*Mu2i zv^>;mrRF2+pKdJH76VtETMQAdkuhazolSh@p}kPiLom&+cdHrQNP<``Z`SFK^qU8i z3lF#Pde}N?ai@Ne8$71`OWL%vrkO{bgdSjwz!flRJ4h1s`%{xz!bi7+4pyWQmYF@T ztIwx@*9|5_L=LDGcqrzj!%hy#?+5>mEE!UW8q$qNwVW$EuTC{P+(85NLY+M&TvIsDxJNQrUx01+my3C zyRqpM<)9fVf&4PoYQrnZ>xxq09$sG1p@>_1^G{Lbf$pK!@0a-p@OQFK%c$J%6QQRF zIt6Ou1T6dJUdJzL6Gljnz%Tx0KfWwe-D;92!3o`D#@c`zXiPX{YSqV5 zFzRu&+$Cs?URQgMaZeO4e63)Dt%hnezG_{Tfe&BSnB;%jxyd`X<+TqFe%08x`GEd~ zw51&Z*Yj!m_q27YH-GyaUEAP$;`i;x>E|mi5+dM-i~w+d{@ojweaxFr60V}Dx1W6I zQYYLM&-<>_4)J8rFPFP166hTJfddXlGF?Jert6^v6v>rkhf;J)FH~*a%U7T*@Ell9 zvxH~dNY)O4TCJ?^da~n@igdQHR;Fx!lFnr9``lETgW5#CiS7vhn31E>udA`#+C|l{ zboE95^dgpnAFEq*LRXD7O+YJ4O5h?y+?d{@{Fy!}&7 zg3J64ag=rlb!E=AFt^1^Zc5Kzo)Dk`_Ll|C*nT1m_9DU+6_<7Kg4X zKmB>UoijDCccJqFgE*>^JR#Wn>?ue<+$X3uK9W?S_m-x+hzU%Ou zIx^_(8n7elr_`+eA+ZD_iqq@(Q;|Z~B;+};?{}9_DJ69mHqgEChrHEX-y%%QI051d z)3QrpSlA{lLEJmcpm966T95Z+E>w&vk+i^$uWlfxLq_lM0^aLImhGae8!qO~QTIPdV=juxK zh-*C8ep#=NU_CQn&E=mVuHwS;TjH(4NI*{hq0HMbvtp!mH^-h_HF6ss_nZ>#g6V({ zF3ocY#7n|w)izA+ei)%`@eC<#aQ4D+rH+!&jFQlvK~=hZ@R@~^8qlOXMNKGbuE5zA zxqhCdO1ikgNw^Y@UOxw?Q*d7<_{b{xrl|80hE-(Q0GxJi0lhkW=%_BC{y~(WpaPK5 z?A5*UOeLH*P^h=KS~O3}(jK%Nh>Vz|Bp$P#_zOB`e3Ii`W7CIb%=uY`?2QDie=I=rg7 z)o}N^LQyYOn8Mt9aExg&OmC>@}4itt3PAiQb6rOHj z!byu{fAqKbQanl{tr5Vm467|vF}=!x(ZZ_x zWEcgA8E*v1zzZ|-PIk?y8hH6LNTNdh_6!WU~fk@u~x z5*r*of~#g+M=Ay1kvAOf1?Sx3hVDc6HEV99!EMAG*WPuzUZ{S40FPY=(Ws^GeT#uT z3hSOcAzx${Fv4>v6*!RK+P2zr%@_n99A?99NN`&Xgw_n(MR2Q@0cwlj{v!dtvop1o z0xXLwDi7O<3g(FVfra4#85l)Y8T>fvqhyq1ekC$rh2)@Ht^>OJ-Y@lnMDv_Y`^y{n z_{`wTrebhhT#9CK66w`qye*>#j!{7NkpE5S8&n1d&Q`lU;O0K+cAElquCWzj0uTQyT5G2U$wZ9ZwXYZ zh=J?N8q^ymO=-O1&KqG3CT0}K5Xj3_Z?%0b#Vg!bT1~))5*E&POK1qdpi3q9qL+l2)PWlUxCNmF<(g!-V@} z$G0j5D2LKgso7aGK~w{1MxokBIDaLff|-woYNr{_$AFZEo_Nq$#!_Z*%*0Q4axT;j zYW$R8bp>?{hQphq9Pa(k%i6D20{(-3A`XZ@Ac*b;$9<3+N6gN;)TyjT`MieRWXH_J zAb&Mc@r{n`{@ACH0$b6NsagSu{_^yo27icKuIF(qdLCgB{sdJ93qCFwFJWm&I5tGY zTM{InRV+ewtga1@A#zD9NXKfzG#P2ljM2NNZLw4uR0hX2fmCe$R<_(A0zq1bOpB01 zn$>Riz*pWp1ozAknPHaxOu6g%vXT|Z!!qM{g;C_9@{!&KFAfJM@S&M`^spYpln^Av znkj4z;%#{r+f>HUk`UJe{Eb)~{2}Gt!qbj1)~mBx>th{!ybzJ`Pc|t$)_QT@h2FR> zZARFA5217+AIVk3@%Qg}-hKnp@YpD`P9CmAk%>^}OlbrXa(VNtE~dl@hFVu0Ask8A zd$f|UM42jaoEqB0Rt!XJ6hL?8UUniNOaEYJwRkn2T_DWH##XFZc9G7f0;&H>qwXb!uw`vfD5i;giSDK3$dJa z6rL+_Qwu+!;t(M30=AU^>SD2b2D=h!G-hxu7bn!FfEL>@(_+Yuk|z^@f0iRxvO>~J zWYZ&j-vRIX^;|zG;z?b&zo@%V#MLAw8y$eO3w((epw;7e3H zh~#EUgTvnU&*{cs=3$*!pFHBJZ2QYWdL=%65zoh2I;<0JSdN?sMJ!g+NPh-*^M#gd zrJ05^S%>Jzm}%Ar!<;bncOiCwrYUnn4DhPoIBnwrl#yJ?j3jSq0f$ad8QTO=61Sf( z@(|Y`lNQdqACK$;#(XGXoEC^EW^tXb$#s^SjM>eM9gN^C@Y&CEkGs319y%^Ra-%Cn z@_4H6pu~iCT)0XKTCmo3Yar}qc4`raObh*)GbQc@)2MS3`w3O#RP7ZPqkbF1VBs8FPy_Htn(eQdHT;ex?K;%sJ zWkd)Y%x@~;Nex*lBygQZDvH68pO(wJ0o865VfqWrLO>&&u*YNPK@JW#f)f{=LVw5kB6#3LMWCP~)+(5#+RI82Y3VxbRF*L)_~lcDtPuNghPwvDxg0Ru{^cqw$I+VHybZ5!jve1obw%RqA9e9YbV(y zWpGWHY%Ofmk|_Y)w7vTo$g>yBvz@=#OEr^D$=MNipbF3?a>-(WrkJy36Ij~v>iwJe z{as&gx8w)wX=(oW+4t1Q(}A_?;qLx7-(m>C{DIr)M}yXkfB`J9Hf`-&QSr^w?i>;K z!goU4C-gc#=lV0tR(E)?!@YA(Nnd3Cm~fu_8a%nQO+@P-Plr_;FOC{PRP}&X7voz2 zq&LKTZ8p;cScM_bHfc<;-q61#rk=z#meM(B~+p5w{+j~PYTJThC%EApiAHEu|DK>v?=c^%pX4GG2qdYPXaFJ%0}RHt{amjw=E>{*)&ImGno>P>kT{Rj7jz6kOlBvRu%tjua^^3|6z!s~<)q0;zV zLSRXpUS4;dT8I(C_$hs5Ku0w^Nom`VtL7%LBoOjNq`2#`3&IWEG;2u4WtEor{@tb* zGkG4WRpBq)8)k-rlA#xwe8Stpk0`=kdi-tku7|3_nl?V{D;DXl9V2*}VN?F@@?jfD zRk+0JUycrS_Du{y!mQ1RP-bvfi6=jK;q%$=KE*6CzH`x;wah5RU zBHJu`6f{gYyQfggcQ?XuI3}1pWljyIJk9m~SeQ6jTk3&06C6`&i_x_>4!9FGVY?^r z$r&(abLS-btWV1Rh>5d12Ubj2M%I3%?!}I}LaJ3386TDqDjuy#Tff=Yjuf_0S`oC8 z^>1*^ijk~5la!%}BB*R12dQk)Qz*1}nETC&MKX^LG_ov|9aBnaQF@|HE79j+^5}$o zLMSxzyS8Ckqn-u|cIXn%`4L)2993ajG^V-wPzF4^WuUOrRwU0pV{H?rL`Yu)?N9NV5v z#uEC#^}7Kgm?H7#ERJaLntblz`|TYrD&x~zKAQK8;6Fq?G9UXj#yNjnn#eNJEGyql zf^TSIUd2Bi^be49NR?f-uCbWVO$53xDn?QdKxjXFcw23$DRQ+*kBh`%1WWIJkr`8* z|8Coj@~&{q~DT; z2u{;q_WR(l<$7aPG!=zy33oF;d?a5Z^O)vsLDA@(p^-ka27NGlyYQ#I5_vFDmLYH2%ySU7OrieB$S< zAqF)TSQJ!LNgXxyZ5#{f^38AFXJp}6=Hq&$?PyokJ&PmRavwBVnvQ3|IREB@v|0b~ zK{oB>BWcFAr%Z1!*6*me+h=TjMtEbZPjKbKpD%4LHu}MsHhX&LRo`y*xZG-NPkrxK z<9J(hV^-6r!9ZI;xfTlc=jvLJ(l7 zDtY_CG}>(xf!lyq$c&-FAhHKn5B%yt!VxqU=MD%%P$-rkN+(O-aByY|Op~aIJa{-= zUD12Q)&9QxZ>3ABy(EfxuRW_wYpZIr_%+;POrZGiTBFM@Da~^4Nb`|DKAAoa5zhU0TJiZO>gZR<`DNl{e@ zixIUGVKfW56a)r;h8#kYl#&;k^3T2*Xvv;RE4RwO2U0l1-gFiisy4%MsF8RWAT81I z0e#D^)`F1mw1`NNBC@M^r{$Tj&Fk8SLra_O-ZwpztZjezCjM+M(>zhn^`T$pS7I-1 zBoi|!xYN?y;OYP7dO8~uBYOs{yr{n8RAg{d&9VCWtwZ2i6iWUN0j~I8k58^=4H!y0 z+|k9nc#&_^b+kq-1`7ZPnc(Q9j<&qD=^UNbP4F*kYW^oaXuWk_@ZX84?qO9F^8XwZ z()gc2p}WiEQ0N~mp?`-$A4&fYpisLuvsNdo@87M^9n+xqYrOs!R%rIWTA_bY6k7IQ zib4d!e-?%QTP`Fo3ei{m{rS5nWd3hOq5l;Z!sN1%|5gZiOD~ zD!;M0TyBMCQ~y_1=+u_~_o2|E+W#9U^dBvuN00tXOX&ZHLf&n)qs64)rs&bOx@*VC z31d~>?e#Y*9d^8VINE;t)=3H%t>e?tFmcMO*eqtOqw)4>n$iCR3XRA^LjM&CJt`kj1BJZd;je4luQ3c1&>1?}Kd{H(VZDZsJUvrnsBlD)qvju} zZUw7bjalQvC<5i=u(qy~B4v4kinfzy@+Y2xX-7;pMxCEx0}x@!^Q11rMaEXtHgy6* z)!ATO6qKDWO>=*T&=Gr_yF}!C9fUOQB!7J!&w}@MyRzc{%m|4}DMZk;Ht)hokygdm z)sDkD?gUZ(fWxFn7~D4fF$EO7jN02vkP55{k?GPu5Jp%E06x@^m%S%IAQf~JRZ{ee zm^GATPDEMJ1{`VJ46ZbU+yZBL(XxAK4yY3OA``~Z_s)`&l=Ycj*I=9QU!GHxZDlN& zmfkqU#Z{SZoWfLaG%Vitj2?aTt4opg;dS6zTI?E7{P^UAKOR-(@?m$_arjhC14Tsf zq2<9{GBreMmQsV`Zjtw6>%GkGy=t-#VLmZiLTKzfW)Az3B;Fg@B3Dc3eU7hBFybRw zF1BcS!6?O&N2ytRcLxWmc5b08M#S z6tzx0<_jD-H|aI$vF5$4PcsszsfRDD>&>%~nZOFGoL7d{MHVg% zw_4Wu_4wM#=fE}Z6iJJ)I%HGe+Q4621#Lh^XE)l zfK9)dc#6<=-tezek72t(-k<#KZ0kKls%?1DV&DWWuFR|eL2*>Lx8clH;>wW~nx?6hnwpiBHm$3xsH=UI z?+?8{=X<{2pT7S9KX7=R^E@w}x5wS_+*lI`^DAG2X6{(O&dXAxsQzG;u-|HoYf0Au z;HQ0AZ_h~6J=weEuWn&?dhrV!*U!uSmXnbe7hmXOw|=~Dw>{r(5As>wlw)EFF%;Q|k zTaKzV)(N$bW4Isci?uE<#C#F0&6bV%sILAuk|` zKd_c!D0Ff?U$2eMl@GxqQ%P+rr-IQb5$Y8N+76mg#f9~bbaDIvEE}i7vGSj&eYTxe zVD=ugipwW6MkB;?JOM{6`|cQkoeo9&KoK2VEHe~)sb>!VTYh5X%lk9TO90*VJyYN z4qL|4)R0?bslDhwXn3Z>(M`ugiAI9=iC>F;r4jH!EB8$!Ldnq>5G6WRlU`JG?Clv+O6j;6)yax`(NV6Q6s zM6C^`96b`ck~l$XrGwtOl7>V1K)k+yOI-)`B!_c%9SA86qXAKw9KGNnK=APU`5x;x z<4MzxAXBIAit9mfG`|hdM4&gwi1PlMFD2srlir=DDA2S6AA`pZe*(FS^fbscAja{V zMqL$4ixw&I+$<7XU6&)XED9+M>CLhv9ngq62=qv3LaWf?WQQs1A8Rr%W2zFrXm3Oy z^eRxH^cz@T%2n+!pyb|P5m3qE{P_$PI-TTX1zkFzy63y=)v3#&5t{+sf09H!Lc2N(DnqPS&Jn{J7t0;aZNQTmLbXV7-jU8!2p6wu6hE04} z;ihDQIpng1W!q#mmxS{Ux&;TF-DbZ;I@3{*7HNB#tqSh1u1nT$rjShC-@0G{sP;vl66u`W!f>mDS$y z4MJ!?UhIuCkRgy@rh?5KE45&`?QT+%0jUBV0vH^ebBB6{HHjbg#E2j9Flf-SS{F@G zEyDj!gLab`3OSuUO&5kSzDQarCCDuc5$v}h8UHO7yd#kpmTfPU-@sBZFAfaIjFOZ; zPa+f?kCI1)Aq^M4Kw4-|J^+1dFtiicCIJZjVzt-e<_)cwNTjwKA002|nIV*jvF9~^ zGtV^cPN827qx_5g0!FBR#pYWeUZlggO43&!1-P>|yxRZpL-W?*I zgjmZVPi%ZBKC^vu;?{vDpN603|NT4+Y8>+nd)JAq^8Ju>upshtFnMxW)+cvba~-kk z!g$h;&^TO^_f+!DL(6Jm!fEQDmilSqs`l09K>p@p{6 zvbMH^J!y#+TcIRDXtkNN7(3)@LXR-uy?hjl7^;JZCiAGr7|6&NpoTDEKgFh87pWv~r zw*g8DqE1Xly^M{(EI{vnfjw1&MG+-}bECZYi83NKcr9ba80@eRn*)6OHIKnM!>#y$uKru!b-_8{0n{0EZ#04N=w zn3(uKP$+4E25^N^iLmA7q6QH{fJUBJ2>wuope;bWgeiUTgi<{sAAtIAvW5^Fw9taEgj68-HeD$*yxEn2Rzi-eNZ19HF^O$gv$dLqZ%lu z1z(-_9E?;t>NN4WMqmLvOkqq8M%{8KmlZ({Q=B?P$A3;?luaPu6@+72Ou_#uA%Vn7 zs>C5WEOmn>`6I&@0N%w1&)tN9x6`YcFM)%yDPG^uBMXS-uZhf7i7tevN-sn~kaGme zrsK{mKZgRD?luz(yVSJ{4z)N@+EczhI)MG)=mNkGF+-> zpnfEn)(AS4+5jm}IIwWKs2tiXDt~LyL|8oV1(rAX*+yL$e^Pj=hcDr~05x!`*`-pv z>?h%_l3;0>Ucm<%1X6hc*%Pg9M%p!XX=nm28JwQ~s|_*2M>2@WLW)E*4f^%+#J;cjE{h7a!BS#x&N{;Bw5H#GlMozZK^XR+9gm)=o4TLG!eiW zmV*Ut94>p1xV;=Lv3aXTY$}?0AQd4{_E=%1=y(qr^-xOSD zMSOryt2whae=uQG2<<3``-#)m zA%7sxRV`pTBTL)>T5g6rYyQDOguEh8Q8tlLbak2vb`m2Ss3|o`h5>KDqvmyJJ#-Wo z5Ui$+CNY2{5+=kAt2`hPgz%?{GGgeclgBYbLa~p6KK+Mht{@+2;*J#KAR3Gxcs@_Q zvG2{{uP#8g2$3D!CiX#o@wqlc&JA4`#YCtcP}C-SW%tH;tn_}&HlS@K8sdwG;U1xXyV~qu0F!834a1?( z+4!M$u#y1ckcjD{qz2&m62)gXspx)EavbjzMLOgJDn!*0xJtI!C-yTSL0BhH-?-`d+q+6%qlf7!t1$c(mFk*ZQ;Un$d*K(zdj*P&2W+{w+ z`i{<+qz3Vjk5QN%zcAbdNH!pGS_8_$k4UP7E~|l$(-6t6rKuYbec@%e3Mw}j_OrHm z3p@#CA}utL;rxi}5751QSTf!-c_D8k_5I z1fj%YdEp4UDo}*@ts}F2*aWz1(=G$huTO(N4n-aVz#vYrUB{3P&#&w?4DZ~4l42@V zRVJC7IIWDNTQ}od011nVs35#x8A~HeJ6G0959&Z^8^^qbry#|w;{3z{I%-H%)*`~} zTgUve0w%*J)O-*)y0tqcPEK^_m`TJ@V#=g5CF!^eSBS6>*~Fk^VuofFKL(x`K<8wI zTHUBlz61w-f_33+JpwtVc55$FLYY)g3cjuhWV=YxGjU`qg+DUr5c)19-&VQ9c;3~< z3GXS(gO_s>qXmfWed(Q)RQ0ht(POO~C$KLa_5(?_72fRjKwNs@VwL5w_E(OxLxzm7 ze)--u=yg)ZVgYQu!tUKVMwtzwkwT2{ca0YR_@MhmmqziS3JdqTCIUOqQBNHtJgm`) zL})b;d$n$VbRaNt;g1jcD}G$k&ULqv{3Qz@T-%|B2$gxYZ1@<{D$4d0_A^bebH?V_AQjd+s*23xSASnAxsdSS9}^x%^Pw<$x2d^z;?UZekx4#N;4ChVEy3Hck3b zz3_Y=Iw7n z(!UDQ`-kQt9LkwckdMcz@}exDQc!3yN4lL`aD$D=MVm|xl;*%XO*%h1hIq$(sUi3eNEw^hBQf217MCqP8=!^h2g zsc`6J*tMX;FBBW?#~0z1n@o$w)8hZozyB@%sszbez-`$v_x^Gx=Rl-IY%9nds45_K zY#ci?7@5POwKRAf^=_HmSpoXKN(LW{>i&6W2 z+g$%w<2KZs}{AyRFC;Rg64P-K!YWaS<#gb%Cbtke)Eq+4=Pwi_L1 zFq2o&p|uw??!01FU%ol?`s5CW9Qs9rg zCIm0ZEHApDzjdXb)P_w20edH(FGZ|Mf1KWFxL^}%qe3cplmy{wz;5~@M$o82A=q>S zTCPw|TY!oeM8!7fx<1~1H}LE9HX~UC?WneuP?_-OkAdvqPfHC}_2VZHFD z*bMUnmt)&b(jl+v7kq$;oMWG39zMId;@7d|2aFNC1SDTir^2H2(ErJF$!8!gv70izUQ~UC=?l`I+Jz7b5yOsMjX8pPJW(^S!tKAV|@fEaD2achi zQaKu@+_;AH^5=K)rE0F#0#%{&71sA02oWOS`u-JoDg5fGlTMK=PFJ+-N}1|q5TVF5 z#Y>Q3}RlMQE|5`Xev;Oj-6HYH^fz9)g|k?dgC?u1wDL2w}46w z%-%iN?KIz)l3Jl!m6F{&^}ixkFNUAi_~%tQQi@a-cN>b7-c9i9LtU?I@-aahbtqtt<26Uq@tsz{TtO45a`8<(vg!*bth+It))Xv@{7UVdbibe zrNjEd{&Q-3^ro=a@zN)wzE-SBCmLCRrQz=MPOJWPq~(?BWP<%_cMXHRCqfZ~cA7^Q z6zJFRn#52Dk=Pv+@xw#w;vM(9IV^SU7@eLh{C}a4PnS$%EnwtajGdz%vW~>$e}lb~ zZqd|T{veA-87(0&_i7j*>(B65308@)7q98_sgbY#*76MBts$o0Q}QTFq$U}fux$sb zXyG-TH9SASo3QJ3 z?bKUzk~3kuMa$VfdROUbQWEBWpSUO8{M9HiyHQZ2b8QW2Vs2PnrVzR9q%Vd-J~;)1 z1zziPS$OE^bZ86lyL-xBAHTS+D{epcQQs4GR(DmVuHP#dRQtZu_ zw7qcbBX?chrl`7i)+S#RvupV*w}^~)V2uk2&HN{VZvLYloeQXM_qU-=1$9Xmc;`Cz zYc(|6#01Sp=n58^ij0@2YT{ArACR*BXKyUz$fV%AK#ud@oA{b-3HG=2mNsH!Y6&hQ zx0Up^R4Tk>I&yZXov58iXOZzi5-hxa1i;V;$r1r&8aCLP+vr}HiMZzzJj{|Us<77c zVW2+DE{%mSt`i(1@iI8DT#HBnnPzwN#(2(~l>67TuD*j5s?A9G0ziAE_6DU08Ucl` zuQUCp)kcP=^rDWEv}fX_4)C#3la*rx`lb|38!X#S2eSs4*+Iny!iz%P=a9`ypLKKQ9mx$f;*MuLaeowBa4?eMd}NkHc?t5MO5k2pYPN_=iZd3i9U zjaVZ){1_;!)dRYm4okvnh>WFKq$T zQJC-ATV=0M64me5>Xi>IMiX~^E!a&5q&9*k4J&_)#DRFay*?aIvO4OxC#@7W!jZki z(<`%fH|^n)&A-H&dXpQW#*FbE^{E?(?v(nSf0L7lDp1VTr6BOgYo}T9=JrBsHFoCi zUJ0FkO7<&bl`}HZwqOYNa+*4!59_Yi$IXvrOZja;A}a8pvQv)7c-jB}l_~9vW&lb> zT=j52Nb*IW{VI64Qn+QnS@T(^2Kt0VhM>mVLq*DSDO@+?D5LRhlPpxo(S`H;yTU)y zN}@og+AV_^n`{j|0>{9yciW|Ko`no6`yyY~ce>jRI__T3 zRJQ?C8fz-AMr(yPB~mAKR!5EcI}24`w$G;@tM?u4ioPaJic03~^dmaZ+~;bx8cZ)H zhIh|9FXBxP2Q_|8@6f)q4B1Ow+yVUv+F$ywEcwr@CRyktKCNB8`3@Zuiqo<{gYxWg zXRkKfq2MYq+s4`{_|ufYtn^kS>b$OYqfTZ(N z&yDgx*ldg2=XJy2<|GN7q$s3f>4&=Ub-|%mlXrjHaW1fbz4nev2Kf@-!}sid1++?n z9*OKrG-~y5JH6zS!E3Vfqp&H)o{PnblU+t`v4_h?mx3%f¨k!z_aNFW=6G#yxJ? z-Vp=8czN*BHE|}Hs*bwyF0wsae<>w-t2a5zX?GKmEyq=TFejOV%BV%v4z$nL+deQ? zn_$LmyS#NV?|3|vo*C!l5sC7dGaem(OFVCpb?tT8F@Vwv%+p;sclA_y?RrR}S!^e0 zRWcLMUu#L2^r}a^zB_QGi5*mLWuHm1)3}MRwD&$X@~rjq)46mPz+~I{BVmy888&>{Bd>iD`zr zX+rc~ukIWB1Q`b#U2x3$@*I)wxfxtt-tW8QP8!ek9w&H#)m**bcahY? z7~Q=9+U-{FD1uPUp-JNvLB)XWe<}<8#>tCdJ42A>El%wy>ul5hQGib4=(d;)0bU&f zbcgP6AzX2c5(G6eRvs1TxKB`2a)|TBR0i_%(!L&a*H#J#^nLIpV^m4lhrs9P5u5u) z#%zX1W-3LKs- zORCB$;O^srNC0KL0Dz%Nx%Y8Hg?*DgM&jSaQ(Oge2GF4B_8-3+-QOz@KCoy_+t~}a z^w4#RI8nIcUm|1y$`@ybs4kJ}@;Xa$)(bc7-@)x1=cwAP%wdQZ30$blecLtnLg>7c zpMze9w`z-%ub0D9bNwm1ao}-Yq+lw?+Fnq>S((PsY^`bSx7s+}5cZFgr6k^Gq7VufR za4AZmb^^#g6SLeg^JV>95FISjEVe@I3-Dqi8rXY=&F6zm$u&<+y#97XY&~}?=5{gh zEMEY`p9tNLhx#z~IfCn zrC1HJK2EtI?qZN)M$>#p& zxt$oW5o5>}?LM&X?Iwg&C~!3s=9mnoX2NY|yE-ybx`GE>^6-CWDZ?A*8kpAT3B5nw z@ZSt$)jt{uB60T9yUYckf{@$#fE)`v+kr9U!{dZ*<#Z7_*6Q%&^;P=?wilYCDxO%| zDw0IkjG`g$M_2BXpfWjSp=%H~{l#L)D)=+^9}mRuZg}T5X|7NJ)$0Nq&xpGhmp@7u zuodA%Kn`&?yg7U4;WWwpPExiaaL9a6a5cw^3O1&$vP8GjPj&=sf=#wo4(Q9vrI)PY z7ouJkzDIDpHrO8gd(5gF;|;t0MN>l*inYQH3o#cWgYEf1WjtH23a>Q-v|M0|9Q}E% zC>MlymaEc)f4}slSGUUT^4plbRUD&_4$Utn{W+K2!EVz$kdA;=tHIix@^F;Q;R3*= zX0K$rHh;M*T^QxFaX7V`0b_Q&{)nJcjvlw8#4G%vI(mxs9aVT_b z4I=e&*A-dW>SB%#gEb@qi0eg^D%Q4r71-<|JZhjiX}mx?S-Nlr+PPRU`xvE-D{D)~ z-Clt{Rzd`Cv65|oNO1)wi>Y^!oJUfaXVT9p1db)KQJ3_DOO@W@ zGo;9^EIP=%o)I^RLC{@IXCTuBW@wK&_{1~p`)G!RjMS42LQz?$c8T5_%T_9jIl^^g zbOwz8Hj|5G_}Fh;rg1$0&Ij#n2X4FtQ@=x`BS~I6UY?BXk9gr)WbD>e=+l;vcPL_fUE@lF(IT#g)@F+ifhzH1{P)f|f8X&-_K z+m1whYcK5szF@9xvdF-IWVe}emOLQLNyMgVpGk4P^H&wfOe!Y*=JI`>|2~RlK!PL^ z0B&YpwnB4~ZvkYvbNKw12so2oU+Fl*&PtI@o`2BC1acc<0s;cmKCbRj=gdDxg#=6a zo3lEvNKr2LQ7JivOhsbctMpd|ZfihmVohy1xSes?f|Bz&^1|pUSzAAJFCJSI7)92+|?4V`oF&1&@_+6EtvG{&oH?$yJ{J@ z@9ULYAcAk-!KFu>+a<&WkUnozj{q@SU^|fx-!ePr1=ubo2w5InPHhd#bmKzM@Z&uU zwa3Q+ATfj+o|O)rms=ss2;*J|*j%v^O5oYgD~bo%j;gzqPgU&6Y>s~*=h^*FWI=o( z@lKug6}dfJDMk*9TxV=%l~3OpU@BMe>D4|VOOIr-PkTvciDj~O$Z_y&4fUMqe~A#p z4t%eg;}#!kcN5jJ#E}r6r<)uGpG}OSfdu1sMHIH2h+%7$zi!FWCYD?(IXn(SG6c)aB~O9 zG@&+Z3(`*8bw2Zsdb+I=OWl}Jxm1l(EdCX{B536&9 z1CfEq+_fRlS@p67$cKDF!d#%KcAM^JCe2-^`meJC#|da(Q=1Z%lOW6{D0hY7li=9% zEc$M+B7|n3ALJs9GJNBE@qCW~@hJ)~1jxQ5U0V`yfw#=K={~7B+F}`G9;zdVx`yBB zzxA4#nPY20-A*_GhA_>nNaFj5^N1OsF)oM2XX<8t)np_fw&F#W&k?u;X!$`FK(@(H z(HH=&pGJv&(D9aUH~PNOJRamd^sAnfG2a4t@jxBfmV=qR{(4aOB;0bQ*2BWNdq!rQ zlvBny+aE4&X1+hQB0fQ(o)0jbM6+tHe~S#b@YBdPIrz=s1}77X!BO~toSY&!ng{Xu@MN+;>E{Tp zgNA8r6OG?A&U!@IR<3Z|%$?=U&XV=4;4#rRy8Be`30vQ0;Ml ztDq*%JlvSb+4|}4Tu|$9Il=foXL#i1>xByr>R*o9x0YxrHMcdG-Tg;T&HLF!C7RN#5TFrn1Ks4^`~@oL8BK zeHE*cJLURuLh7+=3?BX@0loq>H=9+K9G+Xf*_HP!K-#UWda}M7y<%7s zM^H_hlMQHxIeQQ|0Z=(zrSe4k05UL->|m=|*ivL08{tdkn7Av;*W;&TXpuk&%CM=*2>3_ z5c5hZfk|i(7)rRw(LTAVT7=2CX!Z>}d^(D)NTNHI^BqAEW>kOm*`8$;CxXK;pX}I6 zVLGYq@!{E{Hr`I}nQipcjFumzppHhV?V^I^`8R{@aD2_AzEP*=D^*Ua^NQHoPoplt z^R-T&5waoVO;D%rul6r~vSbo)k8P#z-)Wa$f@YPTuo_`OffeKV`f8yWeaE;r>e0$^ z&tA4){ABsI#i`h8649;|2AO##*|EgNDu*sR%VMI;X;5yN9Y^Lrxjr1K?!C6}X#;z0 zW1x|hF}IvXjpwY$X?)#cT+`2oKkT>^q9Qb$dSZL@_{guLi>Sy!FS)t$2T#_&hB#cS zM97z;`(qU70G5{`FlBMaheJx-An&SETa!I6RNaRTDK(gW!UE4djxeGZOY-M^hMQ*6 z^%k!`{Dq3^OHn**P;zxD?MMcy4E{@Js8SJ!@ok<0~7TYcVjhBhtJW`QDqmJzgpHP&tKySaq0W)0p$dC3T%# z?!#tPIc#&m;%;wMQdJYWRr{Kr?-nP<`nlt3P-zL5pC|uo69VTtmrxfusbkTSx1BLN zEbnk_w(!c$(Kkt$CAwO$JYw=E_k-ET%%V*KefaC%0`O1c%Fio^S@9CtgUJE zCnRL_Pt~80P&2|K-mSl8b+@KzPsi|P_ORRd`3l{QucXVq~>NEUb zYZt%1qtlSm&`=g{eK+6R&k}U}_q+A|z_)jq@B73dq5lho(*JiQ2_Hj*5{t%nZ&VgG zC1FlRLe|X=-7O}P08n$XzW5F~WSJGNVbft?5&{6z%1SOKOaZk!QB3qCULhH>4&OkA z%kZ~lLw1qe3oj!Bg`a`=*h%o(pnsJmpuKUvgGTB^LAsw^2nmIP`m&Z=V;6(#q{St-LQvWYEkC?F>gC|W9QIcr z<918f)ac4;lU}c{RF?s+F<^Lng*G4}gsjZ2hW+@8zul@H2W={3@%0AI;4Y4{-Ta%I zB;|+2w}p04{4z9FJI2rGT#4&K{bhhJ<>AB(2(Ugb1B*p|cL&+)?sY}S4U;alcAu^u n1bp8i9={4d81rZV00i)b-%LrT_UQcoLPCF_P*NiU0I>QW)2;|X literal 0 HcmV?d00001 From 9b22d3fb88cde649a0f7b0d20b7d4a5f08cc3a99 Mon Sep 17 00:00:00 2001 From: Chachay Date: Tue, 24 Mar 2020 20:12:26 +0100 Subject: [PATCH 233/940] rename yaw_r to yaw_ref --- PathTracking/rear_wheel_feedback/rear_wheel_feedback.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index f6df94ac44..4141cfbff3 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -175,10 +175,10 @@ def simulate(track, goal): return t, x, y, yaw, v, goal_flag -def calc_target_speed(state, yaw_r): +def calc_target_speed(state, yaw_ref): target_speed = 10.0 / 3.6 - dyaw = yaw_r - state.yaw + dyaw = yaw_ref - state.yaw switch = math.pi / 4.0 <= dyaw < math.pi / 2.0 if switch: From b6e89c6d8b15a4907b47ec8bfee145e36a54c783 Mon Sep 17 00:00:00 2001 From: Chachay Date: Wed, 25 Mar 2020 16:42:00 +0100 Subject: [PATCH 234/940] rename a variable --- .../rear_wheel_feedback.py | 24 +++++++++---------- 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index 4141cfbff3..52b4a11a0b 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -119,7 +119,7 @@ def rear_wheel_feedback_control(state, e, k, yaw_ref): return delta -def simulate(track, goal): +def simulate(path_ref, goal): T = 500.0 # max simulation time goal_dis = 0.3 @@ -133,11 +133,11 @@ def simulate(track, goal): t = [0.0] goal_flag = False - s = np.arange(0, track.length, 0.1) - e, k, yaw_ref, s0 = track.calc_track_error(state.x, state.y, 0.0) + s = np.arange(0, path_ref.length, 0.1) + e, k, yaw_ref, s0 = path_ref.calc_track_error(state.x, state.y, 0.0) while T >= time: - e, k, yaw_ref, s0 = track.calc_track_error(state.x, state.y, s0) + e, k, yaw_ref, s0 = path_ref.calc_track_error(state.x, state.y, s0) di = rear_wheel_feedback_control(state, e, k, yaw_ref) speed_ref = calc_target_speed(state, yaw_ref) @@ -165,9 +165,9 @@ def simulate(track, goal): # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) - plt.plot(track.X(s), track.Y(s), "-r", label="course") + plt.plot(path_ref.X(s), path_ref.Y(s), "-r", label="course") plt.plot(x, y, "ob", label="trajectory") - plt.plot(track.X(s0), track.Y(s0), "xg", label="target") + plt.plot(path_ref.X(s0), path_ref.Y(s0), "xg", label="target") plt.axis("equal") plt.grid(True) plt.title("speed[km/h]:{:.2f}, target s-param:{:.2f}".format(round(state.v * 3.6, 2), s0)) @@ -196,10 +196,10 @@ def main(): ay = [0.0, 0.0, 5.0, 6.5, 3.0, 5.0, -2.0] goal = [ax[-1], ay[-1]] - track = CubicSplinePath(ax, ay) - s = np.arange(0, track.length, 0.1) + reference_path = CubicSplinePath(ax, ay) + s = np.arange(0, reference_path.length, 0.1) - t, x, y, yaw, v, goal_flag = simulate(track, goal) + t, x, y, yaw, v, goal_flag = simulate(reference_path, goal) # Test assert goal_flag, "Cannot goal" @@ -208,7 +208,7 @@ def main(): plt.close() plt.subplots(1) plt.plot(ax, ay, "xb", label="input") - plt.plot(track.X(s), track.Y(s), "-r", label="spline") + plt.plot(reference_path.X(s), reference_path.Y(s), "-r", label="spline") plt.plot(x, y, "-g", label="tracking") plt.grid(True) plt.axis("equal") @@ -217,14 +217,14 @@ def main(): plt.legend() plt.subplots(1) - plt.plot(s, np.rad2deg(track.calc_yaw(s)), "-r", label="yaw") + plt.plot(s, np.rad2deg(reference_path.calc_yaw(s)), "-r", label="yaw") plt.grid(True) plt.legend() plt.xlabel("line length[m]") plt.ylabel("yaw angle[deg]") plt.subplots(1) - plt.plot(s, track.calc_curvature(s), "-r", label="curvature") + plt.plot(s, reference_path.calc_curvature(s), "-r", label="curvature") plt.grid(True) plt.legend() plt.xlabel("line length[m]") From e3190328128bd51c4b25665d2268e2c9ac18ea4a Mon Sep 17 00:00:00 2001 From: Nguyen Dinh Tuan Date: Thu, 9 Apr 2020 15:12:02 +0700 Subject: [PATCH 235/940] fix compute jacobian of F in ekf_estimation --- Localization/extended_kalman_filter/extended_kalman_filter.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Localization/extended_kalman_filter/extended_kalman_filter.py b/Localization/extended_kalman_filter/extended_kalman_filter.py index 2b057e21de..2d0d86bf77 100644 --- a/Localization/extended_kalman_filter/extended_kalman_filter.py +++ b/Localization/extended_kalman_filter/extended_kalman_filter.py @@ -117,7 +117,7 @@ def jacob_h(): def ekf_estimation(xEst, PEst, z, u): # Predict xPred = motion_model(xEst, u) - jF = jacob_f(xPred, u) + jF = jacob_f(xEst, u) PPred = jF @ PEst @ jF.T + Q # Update @@ -128,7 +128,6 @@ def ekf_estimation(xEst, PEst, z, u): K = PPred @ jH.T @ np.linalg.inv(S) xEst = xPred + K @ y PEst = (np.eye(len(xEst)) - K @ jH) @ PPred - return xEst, PEst From d0d4f1116e70987b8ab251a137ae3188bd464c9d Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Fri, 10 Apr 2020 15:07:21 +0200 Subject: [PATCH 236/940] add Depth-First Search --- PathPlanning/DepthFirstSearch/dfs.py | 273 +++++++++++++++++++++++++++ 1 file changed, 273 insertions(+) create mode 100644 PathPlanning/DepthFirstSearch/dfs.py diff --git a/PathPlanning/DepthFirstSearch/dfs.py b/PathPlanning/DepthFirstSearch/dfs.py new file mode 100644 index 0000000000..4ceb0e2bec --- /dev/null +++ b/PathPlanning/DepthFirstSearch/dfs.py @@ -0,0 +1,273 @@ +""" + +Depth-First grid planning + +author: Erwin Lejeune (@spida_rwin) + +See Wikipedia article (https://en.wikipedia.org/wiki/depth-First_search) + +""" + +import math + +import matplotlib.pyplot as plt + +import random + +show_animation = True + + +class DFSPlanner: + + def __init__(self, ox, oy, reso, rr): + """ + Initialize grid map for DFS planning + + ox: x position list of Obstacles [m] + oy: y position list of Obstacles [m] + reso: grid resolution [m] + rr: robot radius[m] + """ + + self.reso = reso + self.rr = rr + self.calc_obstacle_map(ox, oy) + self.motion = self.get_motion_model() + + class Node: + def __init__(self, x, y, cost, pind, parent): + self.x = x # index of grid + self.y = y # index of grid + self.cost = cost + self.pind = pind + self.parent = parent + + def __str__(self): + return str(self.x) + "," + str(self.y) + "," + str( + self.cost) + "," + str(self.pind) + + def planning(self, sx, sy, gx, gy): + """ + Depth First search + + input: + sx: start x position [m] + sy: start y position [m] + gx: goal x position [m] + gy: goal y position [m] + + output: + rx: x position list of the final path + ry: y position list of the final path + """ + + nstart = self.Node(self.calc_xyindex(sx, self.minx), + self.calc_xyindex(sy, self.miny), 0.0, -1, None) + ngoal = self.Node(self.calc_xyindex(gx, self.minx), + self.calc_xyindex(gy, self.miny), 0.0, -1, None) + + open_set, closed_set = dict(), dict() + open_set[self.calc_grid_index(nstart)] = nstart + + while 1: + if len(open_set) == 0: + print("Open set is empty..") + break + + c_id = max( + open_set, + key=lambda o: open_set[o].pind) + + current = open_set[c_id] + + # show graph + if show_animation: # pragma: no cover + plt.plot(self.calc_grid_position(current.x, self.minx), + self.calc_grid_position(current.y, self.miny), "xc") + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit( + 0) if event.key == 'escape' else None]) + if len(closed_set.keys()) % 10 == 0: + plt.pause(0.001) + + if current.x == ngoal.x and current.y == ngoal.y: + print("Find goal") + ngoal.pind = current.pind + ngoal.cost = current.cost + closed_set[current.pind] = current + break + + # Remove the item from the open set + del open_set[c_id] + + # Add it to the closed set + closed_set[c_id] = current + + # expand_grid search grid based on motion model + successors = [self.Node(current.x + self.motion[i][0], + current.y + self.motion[i][1], + current.cost + self.motion[i][2], c_id+1, current) for i, _ in enumerate(self.motion)] + + random.shuffle(successors) + for node in successors: + n_id = self.calc_grid_index(node) + + # If the node is not safe, do nothing + if not self.verify_node(node): + continue + + if n_id not in closed_set: + open_set[n_id] = node + + rx, ry = self.calc_final_path(ngoal, closed_set) + return rx, ry + + def calc_final_path(self, ngoal, closedset): + # generate final course + rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ + self.calc_grid_position(ngoal.y, self.miny)] + n = closedset[ngoal.pind] + while n.parent is not None: + rx.append(self.calc_grid_position(n.x, self.minx)) + ry.append(self.calc_grid_position(n.y, self.miny)) + n = n.parent + + return rx, ry + + @staticmethod + def calc_heuristic(n1, n2): + w = 1.0 # weight of heuristic + d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) + return d + + def calc_grid_position(self, index, minp): + """ + calc grid position + + :param index: + :param minp: + :return: + """ + pos = index * self.reso + minp + return pos + + def calc_xyindex(self, position, min_pos): + return round((position - min_pos) / self.reso) + + def calc_grid_index(self, node): + return (node.y - self.miny) * self.xwidth + (node.x - self.minx) + + def verify_node(self, node): + px = self.calc_grid_position(node.x, self.minx) + py = self.calc_grid_position(node.y, self.miny) + + if px < self.minx: + return False + elif py < self.miny: + return False + elif px >= self.maxx: + return False + elif py >= self.maxy: + return False + + # collision check + if self.obmap[node.x][node.y]: + return False + + return True + + def calc_obstacle_map(self, ox, oy): + + self.minx = round(min(ox)) + self.miny = round(min(oy)) + self.maxx = round(max(ox)) + self.maxy = round(max(oy)) + print("minx:", self.minx) + print("miny:", self.miny) + print("maxx:", self.maxx) + print("maxy:", self.maxy) + + self.xwidth = round((self.maxx - self.minx) / self.reso) + self.ywidth = round((self.maxy - self.miny) / self.reso) + print("xwidth:", self.xwidth) + print("ywidth:", self.ywidth) + + # obstacle map generation + self.obmap = [[False for i in range(self.ywidth)] + for i in range(self.xwidth)] + for ix in range(self.xwidth): + x = self.calc_grid_position(ix, self.minx) + for iy in range(self.ywidth): + y = self.calc_grid_position(iy, self.miny) + for iox, ioy in zip(ox, oy): + d = math.hypot(iox - x, ioy - y) + if d <= self.rr: + self.obmap[ix][iy] = True + break + + @staticmethod + def get_motion_model(): + # dx, dy, cost + motion = [[1, 0, 1], + [0, 1, 1], + [-1, 0, 1], + [0, -1, 1], + [-1, -1, math.sqrt(2)], + [-1, 1, math.sqrt(2)], + [1, -1, math.sqrt(2)], + [1, 1, math.sqrt(2)]] + + return motion + + +def main(): + print(__file__ + " start!!") + + # start and goal position + sx = 10.0 # [m] + sy = 10.0 # [m] + gx = 50.0 # [m] + gy = 50.0 # [m] + grid_size = 2.0 # [m] + robot_radius = 1.0 # [m] + + # set obstable positions + ox, oy = [], [] + for i in range(-10, 60): + ox.append(i) + oy.append(-10.0) + for i in range(-10, 60): + ox.append(60.0) + oy.append(i) + for i in range(-10, 61): + ox.append(i) + oy.append(60.0) + for i in range(-10, 61): + ox.append(-10.0) + oy.append(i) + for i in range(-10, 40): + ox.append(20.0) + oy.append(i) + for i in range(0, 40): + ox.append(40.0) + oy.append(60.0 - i) + + if show_animation: # pragma: no cover + plt.plot(ox, oy, ".k") + plt.plot(sx, sy, "og") + plt.plot(gx, gy, "xb") + plt.grid(True) + plt.axis("equal") + + DFS = DFSPlanner(ox, oy, grid_size, robot_radius) + rx, ry = DFS.planning(sx, sy, gx, gy) + + if show_animation: # pragma: no cover + plt.plot(rx, ry, "-r") + plt.pause(0.01) + plt.show() + + +if __name__ == '__main__': + main() From 39d12558e99b14e79bb5333b9ad54b24d2a8fca5 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Fri, 10 Apr 2020 15:07:54 +0200 Subject: [PATCH 237/940] add Breadth-First Search --- PathPlanning/BreadthFirstSearch/bfs.py | 270 +++++++++++++++++++++++++ 1 file changed, 270 insertions(+) create mode 100644 PathPlanning/BreadthFirstSearch/bfs.py diff --git a/PathPlanning/BreadthFirstSearch/bfs.py b/PathPlanning/BreadthFirstSearch/bfs.py new file mode 100644 index 0000000000..d20c608006 --- /dev/null +++ b/PathPlanning/BreadthFirstSearch/bfs.py @@ -0,0 +1,270 @@ +""" + +Breadth-First grid planning + +author: Erwin Lejeune (@spida_rwin) + +See Wikipedia article (https://en.wikipedia.org/wiki/Breadth-First_search) + +""" + +import math + +import matplotlib.pyplot as plt + +import random + +show_animation = True + + +class BFSPlanner: + + def __init__(self, ox, oy, reso, rr): + """ + Initialize grid map for bfs planning + + ox: x position list of Obstacles [m] + oy: y position list of Obstacles [m] + reso: grid resolution [m] + rr: robot radius[m] + """ + + self.reso = reso + self.rr = rr + self.calc_obstacle_map(ox, oy) + self.motion = self.get_motion_model() + + class Node: + def __init__(self, x, y, cost, pind, parent): + self.x = x # index of grid + self.y = y # index of grid + self.cost = cost + self.pind = pind + self.parent = parent + + def __str__(self): + return str(self.x) + "," + str(self.y) + "," + str( + self.cost) + "," + str(self.pind) + + def planning(self, sx, sy, gx, gy): + """ + Breadth First search + + input: + sx: start x position [m] + sy: start y position [m] + gx: goal x position [m] + gy: goal y position [m] + + output: + rx: x position list of the final path + ry: y position list of the final path + """ + + nstart = self.Node(self.calc_xyindex(sx, self.minx), + self.calc_xyindex(sy, self.miny), 0.0, -1, None) + ngoal = self.Node(self.calc_xyindex(gx, self.minx), + self.calc_xyindex(gy, self.miny), 0.0, -1, None) + + open_set, closed_set = dict(), dict() + open_set[self.calc_grid_index(nstart)] = nstart + + while 1: + if len(open_set) == 0: + print("Open set is empty..") + break + + c_id = min( + open_set, + key=lambda o: open_set[o].pind) + + current = open_set[c_id] + + # show graph + if show_animation: # pragma: no cover + plt.plot(self.calc_grid_position(current.x, self.minx), + self.calc_grid_position(current.y, self.miny), "xc") + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit( + 0) if event.key == 'escape' else None]) + if len(closed_set.keys()) % 10 == 0: + plt.pause(0.001) + + if current.x == ngoal.x and current.y == ngoal.y: + print("Find goal") + ngoal.pind = current.pind + ngoal.cost = current.cost + break + + # Remove the item from the open set + del open_set[c_id] + + # expand_grid search grid based on motion model + successors = [self.Node(current.x + self.motion[i][0], + current.y + self.motion[i][1], + current.cost + self.motion[i][2], c_id+1, current) for i, _ in enumerate(self.motion)] + + random.shuffle(successors) + for node in successors: + n_id = self.calc_grid_index(node) + + # If the node is not safe, do nothing + if not self.verify_node(node): + continue + + if n_id not in closed_set: + closed_set[n_id] = node + open_set[n_id] = node + + rx, ry = self.calc_final_path(ngoal, closed_set) + return rx, ry + + def calc_final_path(self, ngoal, closedset): + # generate final course + rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ + self.calc_grid_position(ngoal.y, self.miny)] + n = closedset[ngoal.pind] + while n.parent is not None: + rx.append(self.calc_grid_position(n.x, self.minx)) + ry.append(self.calc_grid_position(n.y, self.miny)) + n = n.parent + + return rx, ry + + @staticmethod + def calc_heuristic(n1, n2): + w = 1.0 # weight of heuristic + d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) + return d + + def calc_grid_position(self, index, minp): + """ + calc grid position + + :param index: + :param minp: + :return: + """ + pos = index * self.reso + minp + return pos + + def calc_xyindex(self, position, min_pos): + return round((position - min_pos) / self.reso) + + def calc_grid_index(self, node): + return (node.y - self.miny) * self.xwidth + (node.x - self.minx) + + def verify_node(self, node): + px = self.calc_grid_position(node.x, self.minx) + py = self.calc_grid_position(node.y, self.miny) + + if px < self.minx: + return False + elif py < self.miny: + return False + elif px >= self.maxx: + return False + elif py >= self.maxy: + return False + + # collision check + if self.obmap[node.x][node.y]: + return False + + return True + + def calc_obstacle_map(self, ox, oy): + + self.minx = round(min(ox)) + self.miny = round(min(oy)) + self.maxx = round(max(ox)) + self.maxy = round(max(oy)) + print("minx:", self.minx) + print("miny:", self.miny) + print("maxx:", self.maxx) + print("maxy:", self.maxy) + + self.xwidth = round((self.maxx - self.minx) / self.reso) + self.ywidth = round((self.maxy - self.miny) / self.reso) + print("xwidth:", self.xwidth) + print("ywidth:", self.ywidth) + + # obstacle map generation + self.obmap = [[False for i in range(self.ywidth)] + for i in range(self.xwidth)] + for ix in range(self.xwidth): + x = self.calc_grid_position(ix, self.minx) + for iy in range(self.ywidth): + y = self.calc_grid_position(iy, self.miny) + for iox, ioy in zip(ox, oy): + d = math.hypot(iox - x, ioy - y) + if d <= self.rr: + self.obmap[ix][iy] = True + break + + @staticmethod + def get_motion_model(): + # dx, dy, cost + motion = [[1, 0, 1], + [0, 1, 1], + [-1, 0, 1], + [0, -1, 1], + [-1, -1, math.sqrt(2)], + [-1, 1, math.sqrt(2)], + [1, -1, math.sqrt(2)], + [1, 1, math.sqrt(2)]] + + return motion + + +def main(): + print(__file__ + " start!!") + + # start and goal position + sx = 10.0 # [m] + sy = 10.0 # [m] + gx = 50.0 # [m] + gy = 50.0 # [m] + grid_size = 2.0 # [m] + robot_radius = 1.0 # [m] + + # set obstable positions + ox, oy = [], [] + for i in range(-10, 60): + ox.append(i) + oy.append(-10.0) + for i in range(-10, 60): + ox.append(60.0) + oy.append(i) + for i in range(-10, 61): + ox.append(i) + oy.append(60.0) + for i in range(-10, 61): + ox.append(-10.0) + oy.append(i) + for i in range(-10, 40): + ox.append(20.0) + oy.append(i) + for i in range(0, 40): + ox.append(40.0) + oy.append(60.0 - i) + + if show_animation: # pragma: no cover + plt.plot(ox, oy, ".k") + plt.plot(sx, sy, "og") + plt.plot(gx, gy, "xb") + plt.grid(True) + plt.axis("equal") + + bfs = BFSPlanner(ox, oy, grid_size, robot_radius) + rx, ry = bfs.planning(sx, sy, gx, gy) + + if show_animation: # pragma: no cover + plt.plot(rx, ry, "-r") + plt.pause(0.01) + plt.show() + + +if __name__ == '__main__': + main() From 89ef0a9a5287695c928db24a0fa7e15c51c02206 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Fri, 10 Apr 2020 15:08:27 +0200 Subject: [PATCH 238/940] add bidirectional A* --- .../BidirectionalAStar/bidir_a_star.py | 331 ++++++++++++++++++ 1 file changed, 331 insertions(+) create mode 100644 PathPlanning/BidirectionalAStar/bidir_a_star.py diff --git a/PathPlanning/BidirectionalAStar/bidir_a_star.py b/PathPlanning/BidirectionalAStar/bidir_a_star.py new file mode 100644 index 0000000000..3c709c64c1 --- /dev/null +++ b/PathPlanning/BidirectionalAStar/bidir_a_star.py @@ -0,0 +1,331 @@ +""" + +Bidirectional A* grid planning + +author: Erwin Lejeune (@spida_rwin) + +See Wikipedia article (https://en.wikipedia.org/wiki/Bidirectional_search) + +""" + +import math + +import matplotlib.pyplot as plt + +show_animation = True + + +class BidirAStarPlanner: + + def __init__(self, ox, oy, reso, rr): + """ + Initialize grid map for a star planning + + ox: x position list of Obstacles [m] + oy: y position list of Obstacles [m] + reso: grid resolution [m] + rr: robot radius[m] + """ + + self.reso = reso + self.rr = rr + self.calc_obstacle_map(ox, oy) + self.motion = self.get_motion_model() + + class Node: + def __init__(self, x, y, cost, pind): + self.x = x # index of grid + self.y = y # index of grid + self.cost = cost + self.pind = pind + + def __str__(self): + return str(self.x) + "," + str(self.y) + "," + str( + self.cost) + "," + str(self.pind) + + def planning(self, sx, sy, gx, gy): + """ + Bidirectional A star path search + + input: + sx: start x position [m] + sy: start y position [m] + gx: goal x position [m] + gy: goal y position [m] + + output: + rx: x position list of the final path + ry: y position list of the final path + """ + + nstart = self.Node(self.calc_xyindex(sx, self.minx), + self.calc_xyindex(sy, self.miny), 0.0, -1) + ngoal = self.Node(self.calc_xyindex(gx, self.minx), + self.calc_xyindex(gy, self.miny), 0.0, -1) + + open_set_A, closed_set_A = dict(), dict() + open_set_B, closed_set_B = dict(), dict() + open_set_A[self.calc_grid_index(nstart)] = nstart + open_set_B[self.calc_grid_index(ngoal)] = ngoal + + current_A = nstart + current_B = ngoal + + while 1: + if len(open_set_A) == 0: + print("Open set A is empty..") + break + + if len(open_set_B) == 0: + print("Open set B is empty..") + break + + c_id_A = min( + open_set_A, + key=lambda o: open_set_A[o].cost + self.calc_heuristic(current_B, + open_set_A[ + o])) + + current_A = open_set_A[c_id_A] + + c_id_B = min( + open_set_B, + key=lambda o: open_set_B[o].cost + self.calc_heuristic(current_A, + open_set_B[ + o])) + + current_B = open_set_B[c_id_B] + + # show graph + if show_animation: # pragma: no cover + plt.plot(self.calc_grid_position(current_A.x, self.minx), + self.calc_grid_position(current_A.y, self.miny), "xc") + plt.plot(self.calc_grid_position(current_B.x, self.minx), + self.calc_grid_position(current_B.y, self.miny), "xc") + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit( + 0) if event.key == 'escape' else None]) + if len(closed_set_A.keys()) % 10 == 0: + plt.pause(0.001) + + if current_A.x == current_B.x and current_A.y == current_B.y: + print("Found goal") + meetpointA = current_A + meetpointB = current_B + break + + # Remove the item from the open set + del open_set_A[c_id_A] + del open_set_B[c_id_B] + + # Add it to the closed set + closed_set_A[c_id_A] = current_A + closed_set_B[c_id_B] = current_B + + # expand_grid search grid based on motion model + for i, _ in enumerate(self.motion): + node = self.Node(current_A.x + self.motion[i][0], + current_A.y + self.motion[i][1], + current_A.cost + self.motion[i][2], c_id_A) + n_id = self.calc_grid_index(node) + + # If the node is not safe, do nothing + if not self.verify_node(node): + continue + + if n_id in closed_set_A: + continue + + if n_id not in open_set_A: + open_set_A[n_id] = node # discovered a new node + else: + if open_set_A[n_id].cost > node.cost: + # This path is the best until now. record it + open_set_A[n_id] = node + + for i, _ in enumerate(self.motion): + node = self.Node(current_B.x + self.motion[i][0], + current_B.y + self.motion[i][1], + current_B.cost + self.motion[i][2], c_id_B) + n_id = self.calc_grid_index(node) + + # If the node is not safe, do nothing + if not self.verify_node(node): + continue + + if n_id in closed_set_B: + continue + + if n_id not in open_set_B: + open_set_B[n_id] = node # discovered a new node + else: + if open_set_B[n_id].cost > node.cost: + # This path is the best until now. record it + open_set_B[n_id] = node + + rx, ry = self.calc_final_path_bidir(meetpointA, meetpointB, closed_set_A, closed_set_B) + + return rx, ry + + def calc_final_path_bidir(self, meetnode_A, meetnode_B, closed_set_A, closed_set_B): + rx_A, ry_A = self.calc_final_path(meetnode_A, closed_set_A) + rx_B, ry_B = self.calc_final_path(meetnode_B, closed_set_B) + + rx_A.reverse() + ry_A.reverse() + + rx = rx_A + rx_B + ry = ry_A + ry_B + + return rx, ry + + def calc_final_path(self, ngoal, closedset): + # generate final course + rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ + self.calc_grid_position(ngoal.y, self.miny)] + pind = ngoal.pind + while pind != -1: + n = closedset[pind] + rx.append(self.calc_grid_position(n.x, self.minx)) + ry.append(self.calc_grid_position(n.y, self.miny)) + pind = n.pind + + return rx, ry + + @staticmethod + def calc_heuristic(n1, n2): + w = 1.0 # weight of heuristic + d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) + return d + + def calc_grid_position(self, index, minp): + """ + calc grid position + + :param index: + :param minp: + :return: + """ + pos = index * self.reso + minp + return pos + + def calc_xyindex(self, position, min_pos): + return round((position - min_pos) / self.reso) + + def calc_grid_index(self, node): + return (node.y - self.miny) * self.xwidth + (node.x - self.minx) + + def verify_node(self, node): + px = self.calc_grid_position(node.x, self.minx) + py = self.calc_grid_position(node.y, self.miny) + + if px < self.minx: + return False + elif py < self.miny: + return False + elif px >= self.maxx: + return False + elif py >= self.maxy: + return False + + # collision check + if self.obmap[node.x][node.y]: + return False + + return True + + def calc_obstacle_map(self, ox, oy): + + self.minx = round(min(ox)) + self.miny = round(min(oy)) + self.maxx = round(max(ox)) + self.maxy = round(max(oy)) + print("minx:", self.minx) + print("miny:", self.miny) + print("maxx:", self.maxx) + print("maxy:", self.maxy) + + self.xwidth = round((self.maxx - self.minx) / self.reso) + self.ywidth = round((self.maxy - self.miny) / self.reso) + print("xwidth:", self.xwidth) + print("ywidth:", self.ywidth) + + # obstacle map generation + self.obmap = [[False for i in range(self.ywidth)] + for i in range(self.xwidth)] + for ix in range(self.xwidth): + x = self.calc_grid_position(ix, self.minx) + for iy in range(self.ywidth): + y = self.calc_grid_position(iy, self.miny) + for iox, ioy in zip(ox, oy): + d = math.hypot(iox - x, ioy - y) + if d <= self.rr: + self.obmap[ix][iy] = True + break + + @staticmethod + def get_motion_model(): + # dx, dy, cost + motion = [[1, 0, 1], + [0, 1, 1], + [-1, 0, 1], + [0, -1, 1], + [-1, -1, math.sqrt(2)], + [-1, 1, math.sqrt(2)], + [1, -1, math.sqrt(2)], + [1, 1, math.sqrt(2)]] + + return motion + + +def main(): + print(__file__ + " start!!") + + # start and goal position + sx = 10.0 # [m] + sy = 10.0 # [m] + gx = 50.0 # [m] + gy = 50.0 # [m] + grid_size = 2.0 # [m] + robot_radius = 1.0 # [m] + + # set obstable positions + ox, oy = [], [] + for i in range(-10, 60): + ox.append(i) + oy.append(-10.0) + for i in range(-10, 60): + ox.append(60.0) + oy.append(i) + for i in range(-10, 61): + ox.append(i) + oy.append(60.0) + for i in range(-10, 61): + ox.append(-10.0) + oy.append(i) + for i in range(-10, 40): + ox.append(20.0) + oy.append(i) + for i in range(0, 40): + ox.append(40.0) + oy.append(60.0 - i) + + if show_animation: # pragma: no cover + plt.plot(ox, oy, ".k") + plt.plot(sx, sy, "og") + plt.plot(gx, gy, "ob") + plt.grid(True) + plt.axis("equal") + + bidir_a_star = BidirAStarPlanner(ox, oy, grid_size, robot_radius) + rx, ry = bidir_a_star.planning(sx, sy, gx, gy) + + if show_animation: # pragma: no cover + plt.plot(rx, ry, "-r") + plt.pause(.0001) + plt.show() + + +if __name__ == '__main__': + main() From 01596296c41b0a76775b64378734fa0bd25c5662 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Mon, 13 Apr 2020 13:45:22 +0200 Subject: [PATCH 239/940] change breadth first search file name --- .../BreadthFirstSearch/{bfs.py => breadth_first_search.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename PathPlanning/BreadthFirstSearch/{bfs.py => breadth_first_search.py} (100%) diff --git a/PathPlanning/BreadthFirstSearch/bfs.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py similarity index 100% rename from PathPlanning/BreadthFirstSearch/bfs.py rename to PathPlanning/BreadthFirstSearch/breadth_first_search.py From f2c651ff5514109e5d26bce8dff234b798048d8e Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Mon, 13 Apr 2020 13:56:57 +0200 Subject: [PATCH 240/940] Changes following review --- .../breadth_first_search.py | 20 ++++++------------- 1 file changed, 6 insertions(+), 14 deletions(-) diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index d20c608006..3f5c95de02 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -17,7 +17,7 @@ show_animation = True -class BFSPlanner: +class BreadthFirstSearchPlanner: def __init__(self, ox, oy, reso, rr): """ @@ -48,7 +48,7 @@ def __str__(self): def planning(self, sx, sy, gx, gy): """ - Breadth First search + Breadth First search based planning input: sx: start x position [m] @@ -101,12 +101,10 @@ def planning(self, sx, sy, gx, gy): del open_set[c_id] # expand_grid search grid based on motion model - successors = [self.Node(current.x + self.motion[i][0], + for i, _ in enumerate(self.motion): + node = self.Node(current.x + self.motion[i][0], current.y + self.motion[i][1], - current.cost + self.motion[i][2], c_id+1, current) for i, _ in enumerate(self.motion)] - - random.shuffle(successors) - for node in successors: + current.cost + self.motion[i][2], c_id+1, current) n_id = self.calc_grid_index(node) # If the node is not safe, do nothing @@ -132,12 +130,6 @@ def calc_final_path(self, ngoal, closedset): return rx, ry - @staticmethod - def calc_heuristic(n1, n2): - w = 1.0 # weight of heuristic - d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) - return d - def calc_grid_position(self, index, minp): """ calc grid position @@ -257,7 +249,7 @@ def main(): plt.grid(True) plt.axis("equal") - bfs = BFSPlanner(ox, oy, grid_size, robot_radius) + bfs = BreadthFirstSearchPlanner(ox, oy, grid_size, robot_radius) rx, ry = bfs.planning(sx, sy, gx, gy) if show_animation: # pragma: no cover From 68c4c78e089d9a41eeeb50dad50fc9481649138c Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Mon, 13 Apr 2020 14:02:07 +0200 Subject: [PATCH 241/940] Fix path not connecting to start node --- PathPlanning/BreadthFirstSearch/breadth_first_search.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index 3f5c95de02..e67a478848 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -128,6 +128,9 @@ def calc_final_path(self, ngoal, closedset): ry.append(self.calc_grid_position(n.y, self.miny)) n = n.parent + rx.append(self.calc_grid_position(n.x, self.minx)) + ry.append(self.calc_grid_position(n.y, self.miny)) + return rx, ry def calc_grid_position(self, index, minp): From 6f358adc5ea9c3a80ef6448e69006540f7f726e3 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Mon, 13 Apr 2020 14:23:13 +0200 Subject: [PATCH 242/940] shorten motion expansion loop --- ...idir_a_star.py => bidirectional_a_star.py} | 70 ++++++++++--------- 1 file changed, 37 insertions(+), 33 deletions(-) rename PathPlanning/BidirectionalAStar/{bidir_a_star.py => bidirectional_a_star.py} (84%) diff --git a/PathPlanning/BidirectionalAStar/bidir_a_star.py b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py similarity index 84% rename from PathPlanning/BidirectionalAStar/bidir_a_star.py rename to PathPlanning/BidirectionalAStar/bidirectional_a_star.py index 3c709c64c1..37d14eab68 100644 --- a/PathPlanning/BidirectionalAStar/bidir_a_star.py +++ b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py @@ -15,7 +15,7 @@ show_animation = True -class BidirAStarPlanner: +class BidirectionalAStarPlanner: def __init__(self, ox, oy, reso, rr): """ @@ -125,44 +125,48 @@ def planning(self, sx, sy, gx, gy): # expand_grid search grid based on motion model for i, _ in enumerate(self.motion): - node = self.Node(current_A.x + self.motion[i][0], + continue_A = False + continue_B = False + + child_node_A = self.Node(current_A.x + self.motion[i][0], current_A.y + self.motion[i][1], current_A.cost + self.motion[i][2], c_id_A) - n_id = self.calc_grid_index(node) - # If the node is not safe, do nothing - if not self.verify_node(node): - continue - - if n_id in closed_set_A: - continue - - if n_id not in open_set_A: - open_set_A[n_id] = node # discovered a new node - else: - if open_set_A[n_id].cost > node.cost: - # This path is the best until now. record it - open_set_A[n_id] = node - - for i, _ in enumerate(self.motion): - node = self.Node(current_B.x + self.motion[i][0], + child_node_B = self.Node(current_B.x + self.motion[i][0], current_B.y + self.motion[i][1], current_B.cost + self.motion[i][2], c_id_B) - n_id = self.calc_grid_index(node) - # If the node is not safe, do nothing - if not self.verify_node(node): - continue - - if n_id in closed_set_B: - continue + n_id_A = self.calc_grid_index(child_node_A) + n_id_B = self.calc_grid_index(child_node_B) - if n_id not in open_set_B: - open_set_B[n_id] = node # discovered a new node - else: - if open_set_B[n_id].cost > node.cost: - # This path is the best until now. record it - open_set_B[n_id] = node + # If the node is not safe, do nothing + if not self.verify_node(child_node_A): + continue_A = True + + if not self.verify_node(child_node_B): + continue_B = True + + if n_id_A in closed_set_A: + continue_A = True + + if n_id_B in closed_set_B: + continue_B = True + + if not(continue_A): + if n_id_A not in open_set_A: + open_set_A[n_id_A] = child_node_A # discovered a new node + else: + if open_set_A[n_id_A].cost > child_node_A.cost: + # This path is the best until now. record it + open_set_A[n_id_A] = child_node_A + + if not(continue_B): + if n_id_B not in open_set_B: + open_set_B[n_id_B] = child_node_B # discovered a new node + else: + if open_set_B[n_id_B].cost > child_node_B.cost: + # This path is the best until now. record it + open_set_B[n_id_B] = child_node_B rx, ry = self.calc_final_path_bidir(meetpointA, meetpointB, closed_set_A, closed_set_B) @@ -318,7 +322,7 @@ def main(): plt.grid(True) plt.axis("equal") - bidir_a_star = BidirAStarPlanner(ox, oy, grid_size, robot_radius) + bidir_a_star = BidirectionalAStarPlanner(ox, oy, grid_size, robot_radius) rx, ry = bidir_a_star.planning(sx, sy, gx, gy) if show_animation: # pragma: no cover From 6d4ea8bd1da771ea1315a73f0759c5f732fe1b99 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Mon, 13 Apr 2020 14:24:16 +0200 Subject: [PATCH 243/940] change file name --- PathPlanning/DepthFirstSearch/{dfs.py => depth_first_search.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename PathPlanning/DepthFirstSearch/{dfs.py => depth_first_search.py} (100%) diff --git a/PathPlanning/DepthFirstSearch/dfs.py b/PathPlanning/DepthFirstSearch/depth_first_search.py similarity index 100% rename from PathPlanning/DepthFirstSearch/dfs.py rename to PathPlanning/DepthFirstSearch/depth_first_search.py From 18b73652f6767aef8a32da970f4f82387182d99b Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Mon, 13 Apr 2020 14:25:35 +0200 Subject: [PATCH 244/940] remove heuristic method --- PathPlanning/DepthFirstSearch/depth_first_search.py | 12 +++--------- 1 file changed, 3 insertions(+), 9 deletions(-) diff --git a/PathPlanning/DepthFirstSearch/depth_first_search.py b/PathPlanning/DepthFirstSearch/depth_first_search.py index 4ceb0e2bec..466aa1646a 100644 --- a/PathPlanning/DepthFirstSearch/depth_first_search.py +++ b/PathPlanning/DepthFirstSearch/depth_first_search.py @@ -17,7 +17,7 @@ show_animation = True -class DFSPlanner: +class DepthFirstSearchPlanner: def __init__(self, ox, oy, reso, rr): """ @@ -135,12 +135,6 @@ def calc_final_path(self, ngoal, closedset): return rx, ry - @staticmethod - def calc_heuristic(n1, n2): - w = 1.0 # weight of heuristic - d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) - return d - def calc_grid_position(self, index, minp): """ calc grid position @@ -260,8 +254,8 @@ def main(): plt.grid(True) plt.axis("equal") - DFS = DFSPlanner(ox, oy, grid_size, robot_radius) - rx, ry = DFS.planning(sx, sy, gx, gy) + dfs = DepthFirstSearchPlanner(ox, oy, grid_size, robot_radius) + rx, ry = dfs.planning(sx, sy, gx, gy) if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") From 952cff6b34e6abf9c52469952c20373c8d842f40 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Mon, 13 Apr 2020 14:29:12 +0200 Subject: [PATCH 245/940] fix path not connecting to start node --- PathPlanning/DepthFirstSearch/depth_first_search.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/PathPlanning/DepthFirstSearch/depth_first_search.py b/PathPlanning/DepthFirstSearch/depth_first_search.py index 466aa1646a..bb08080734 100644 --- a/PathPlanning/DepthFirstSearch/depth_first_search.py +++ b/PathPlanning/DepthFirstSearch/depth_first_search.py @@ -104,13 +104,13 @@ def planning(self, sx, sy, gx, gy): # Add it to the closed set closed_set[c_id] = current + random.shuffle(self.motion) + # expand_grid search grid based on motion model - successors = [self.Node(current.x + self.motion[i][0], + for i, _ in enumerate(self.motion): + node = self.Node(current.x + self.motion[i][0], current.y + self.motion[i][1], - current.cost + self.motion[i][2], c_id+1, current) for i, _ in enumerate(self.motion)] - - random.shuffle(successors) - for node in successors: + current.cost + self.motion[i][2], c_id+1, current) n_id = self.calc_grid_index(node) # If the node is not safe, do nothing @@ -128,7 +128,7 @@ def calc_final_path(self, ngoal, closedset): rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ self.calc_grid_position(ngoal.y, self.miny)] n = closedset[ngoal.pind] - while n.parent is not None: + while n is not None: rx.append(self.calc_grid_position(n.x, self.minx)) ry.append(self.calc_grid_position(n.y, self.miny)) n = n.parent From 71daa7898d88f590ee4e65935e239115cb431fb5 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Mon, 13 Apr 2020 14:34:47 +0200 Subject: [PATCH 246/940] easier path retrieving and shuffle children node --- PathPlanning/BreadthFirstSearch/breadth_first_search.py | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index e67a478848..f4c0fcd0bb 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -100,6 +100,8 @@ def planning(self, sx, sy, gx, gy): # Remove the item from the open set del open_set[c_id] + random.shuffle(self.motion) + # expand_grid search grid based on motion model for i, _ in enumerate(self.motion): node = self.Node(current.x + self.motion[i][0], @@ -123,14 +125,11 @@ def calc_final_path(self, ngoal, closedset): rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ self.calc_grid_position(ngoal.y, self.miny)] n = closedset[ngoal.pind] - while n.parent is not None: + while n is not None: rx.append(self.calc_grid_position(n.x, self.minx)) ry.append(self.calc_grid_position(n.y, self.miny)) n = n.parent - rx.append(self.calc_grid_position(n.x, self.minx)) - ry.append(self.calc_grid_position(n.y, self.miny)) - return rx, ry def calc_grid_position(self, index, minp): From 81622428ef03cf27123cf9c79dede051cf8d1b89 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Tue, 14 Apr 2020 15:27:33 +0200 Subject: [PATCH 247/940] not adding parent if node in closed set --- PathPlanning/BreadthFirstSearch/breadth_first_search.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index f4c0fcd0bb..f25802434a 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -106,7 +106,7 @@ def planning(self, sx, sy, gx, gy): for i, _ in enumerate(self.motion): node = self.Node(current.x + self.motion[i][0], current.y + self.motion[i][1], - current.cost + self.motion[i][2], c_id+1, current) + current.cost + self.motion[i][2], c_id+1, None) n_id = self.calc_grid_index(node) # If the node is not safe, do nothing @@ -114,6 +114,7 @@ def planning(self, sx, sy, gx, gy): continue if n_id not in closed_set: + node.parent = current closed_set[n_id] = node open_set[n_id] = node From ab05ac600aeb9bc5d80947e5a2ba5694a07e0a66 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Thu, 16 Apr 2020 16:00:11 +0200 Subject: [PATCH 248/940] Fix typo in url and variable names --- PathPlanning/DepthFirstSearch/depth_first_search.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/PathPlanning/DepthFirstSearch/depth_first_search.py b/PathPlanning/DepthFirstSearch/depth_first_search.py index bb08080734..d2f41347c3 100644 --- a/PathPlanning/DepthFirstSearch/depth_first_search.py +++ b/PathPlanning/DepthFirstSearch/depth_first_search.py @@ -4,7 +4,7 @@ author: Erwin Lejeune (@spida_rwin) -See Wikipedia article (https://en.wikipedia.org/wiki/depth-First_search) +See Wikipedia article (https://en.wikipedia.org/wiki/Depth-first_search) """ @@ -188,8 +188,8 @@ def calc_obstacle_map(self, ox, oy): print("ywidth:", self.ywidth) # obstacle map generation - self.obmap = [[False for i in range(self.ywidth)] - for i in range(self.xwidth)] + self.obmap = [[False for _ in range(self.ywidth)] + for _ in range(self.xwidth)] for ix in range(self.xwidth): x = self.calc_grid_position(ix, self.minx) for iy in range(self.ywidth): From fa5ca3cd7c88736d28ec96868328637c3772b803 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Thu, 16 Apr 2020 16:01:19 +0200 Subject: [PATCH 249/940] Fix typo in url, variable name --- PathPlanning/BreadthFirstSearch/breadth_first_search.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index f25802434a..5a38035507 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -4,7 +4,7 @@ author: Erwin Lejeune (@spida_rwin) -See Wikipedia article (https://en.wikipedia.org/wiki/Breadth-First_search) +See Wikipedia article (https://en.wikipedia.org/wiki/Breadth-first_search) """ @@ -186,8 +186,8 @@ def calc_obstacle_map(self, ox, oy): print("ywidth:", self.ywidth) # obstacle map generation - self.obmap = [[False for i in range(self.ywidth)] - for i in range(self.xwidth)] + self.obmap = [[False for _ in range(self.ywidth)] + for _ in range(self.xwidth)] for ix in range(self.xwidth): x = self.calc_grid_position(ix, self.minx) for iy in range(self.ywidth): From 0400ce3ad962f9f3ec7fa27455ba106abd580bec Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Thu, 16 Apr 2020 16:11:18 +0200 Subject: [PATCH 250/940] Replace meaningless variable name --- PathPlanning/BidirectionalAStar/bidirectional_a_star.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py index 37d14eab68..4ffd34718b 100644 --- a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py +++ b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py @@ -256,8 +256,8 @@ def calc_obstacle_map(self, ox, oy): print("ywidth:", self.ywidth) # obstacle map generation - self.obmap = [[False for i in range(self.ywidth)] - for i in range(self.xwidth)] + self.obmap = [[False for _ in range(self.ywidth)] + for _ in range(self.xwidth)] for ix in range(self.xwidth): x = self.calc_grid_position(ix, self.minx) for iy in range(self.ywidth): From 7993d7ca8b594fdaa9e8b8071f540cab079670e2 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Thu, 16 Apr 2020 18:11:47 +0200 Subject: [PATCH 251/940] use pop instead of min+del --- .../breadth_first_search.py | 22 +++++++------------ 1 file changed, 8 insertions(+), 14 deletions(-) diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index 5a38035507..d9e2aa5bc3 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -74,11 +74,11 @@ def planning(self, sx, sy, gx, gy): print("Open set is empty..") break - c_id = min( - open_set, - key=lambda o: open_set[o].pind) + current = open_set.pop(list(open_set.keys())[0]) - current = open_set[c_id] + c_id = self.calc_grid_index(current) + + closed_set[c_id] = current # show graph if show_animation: # pragma: no cover @@ -97,25 +97,19 @@ def planning(self, sx, sy, gx, gy): ngoal.cost = current.cost break - # Remove the item from the open set - del open_set[c_id] - - random.shuffle(self.motion) - # expand_grid search grid based on motion model for i, _ in enumerate(self.motion): node = self.Node(current.x + self.motion[i][0], current.y + self.motion[i][1], - current.cost + self.motion[i][2], c_id+1, None) + current.cost + self.motion[i][2], c_id, None) n_id = self.calc_grid_index(node) # If the node is not safe, do nothing if not self.verify_node(node): continue - if n_id not in closed_set: + if (n_id not in closed_set) and (n_id not in open_set): node.parent = current - closed_set[n_id] = node open_set[n_id] = node rx, ry = self.calc_final_path(ngoal, closed_set) @@ -186,8 +180,8 @@ def calc_obstacle_map(self, ox, oy): print("ywidth:", self.ywidth) # obstacle map generation - self.obmap = [[False for _ in range(self.ywidth)] - for _ in range(self.xwidth)] + self.obmap = [[False for i in range(self.ywidth)] + for i in range(self.xwidth)] for ix in range(self.xwidth): x = self.calc_grid_position(ix, self.minx) for iy in range(self.ywidth): From 0dca0e328ddda954f149459073a944fc80a3452d Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Thu, 16 Apr 2020 18:25:00 +0200 Subject: [PATCH 252/940] Use pop instead of min/del --- .../DepthFirstSearch/depth_first_search.py | 23 +++++-------------- 1 file changed, 6 insertions(+), 17 deletions(-) diff --git a/PathPlanning/DepthFirstSearch/depth_first_search.py b/PathPlanning/DepthFirstSearch/depth_first_search.py index d2f41347c3..54bbc48fdd 100644 --- a/PathPlanning/DepthFirstSearch/depth_first_search.py +++ b/PathPlanning/DepthFirstSearch/depth_first_search.py @@ -74,11 +74,8 @@ def planning(self, sx, sy, gx, gy): print("Open set is empty..") break - c_id = max( - open_set, - key=lambda o: open_set[o].pind) - - current = open_set[c_id] + current = open_set.pop(list(open_set.keys())[-1]) + c_id = self.calc_grid_index(current) # show graph if show_animation: # pragma: no cover @@ -88,29 +85,19 @@ def planning(self, sx, sy, gx, gy): plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit( 0) if event.key == 'escape' else None]) - if len(closed_set.keys()) % 10 == 0: - plt.pause(0.001) + plt.pause(0.01) if current.x == ngoal.x and current.y == ngoal.y: print("Find goal") ngoal.pind = current.pind ngoal.cost = current.cost - closed_set[current.pind] = current break - # Remove the item from the open set - del open_set[c_id] - - # Add it to the closed set - closed_set[c_id] = current - - random.shuffle(self.motion) - # expand_grid search grid based on motion model for i, _ in enumerate(self.motion): node = self.Node(current.x + self.motion[i][0], current.y + self.motion[i][1], - current.cost + self.motion[i][2], c_id+1, current) + current.cost + self.motion[i][2], c_id, None) n_id = self.calc_grid_index(node) # If the node is not safe, do nothing @@ -119,6 +106,8 @@ def planning(self, sx, sy, gx, gy): if n_id not in closed_set: open_set[n_id] = node + closed_set[n_id] = node + node.parent = current rx, ry = self.calc_final_path(ngoal, closed_set) return rx, ry From b827b3e2eef46a393cacd1fa31f2cc1acafb84fe Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Thu, 16 Apr 2020 18:38:09 +0200 Subject: [PATCH 253/940] add plt pause in astar path display --- PathPlanning/AStar/a_star.py | 1 + 1 file changed, 1 insertion(+) diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py index 55881f4e49..cd5a365c90 100644 --- a/PathPlanning/AStar/a_star.py +++ b/PathPlanning/AStar/a_star.py @@ -271,6 +271,7 @@ def main(): if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") plt.show() + plt.pause(0.001) if __name__ == '__main__': From 6c977850c6e8e31fd136b265a515d84709bfe610 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Thu, 16 Apr 2020 18:39:01 +0200 Subject: [PATCH 254/940] remove useless import --- PathPlanning/DepthFirstSearch/depth_first_search.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/PathPlanning/DepthFirstSearch/depth_first_search.py b/PathPlanning/DepthFirstSearch/depth_first_search.py index 54bbc48fdd..d42aa5f100 100644 --- a/PathPlanning/DepthFirstSearch/depth_first_search.py +++ b/PathPlanning/DepthFirstSearch/depth_first_search.py @@ -12,8 +12,6 @@ import matplotlib.pyplot as plt -import random - show_animation = True @@ -21,7 +19,7 @@ class DepthFirstSearchPlanner: def __init__(self, ox, oy, reso, rr): """ - Initialize grid map for DFS planning + Initialize grid map for Depth-First planning ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] From 97978ce51fcffeffd141bc4fae48e653b5339fc3 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Thu, 16 Apr 2020 18:39:35 +0200 Subject: [PATCH 255/940] remove useless import --- PathPlanning/BreadthFirstSearch/breadth_first_search.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index d9e2aa5bc3..b4a5c38a8b 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -12,8 +12,6 @@ import matplotlib.pyplot as plt -import random - show_animation = True From 5ba82c6ced66004d1bf8a8dc0b91672394c5af9b Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Sat, 18 Apr 2020 15:27:59 +0200 Subject: [PATCH 256/940] replace meaningless variable name with _ --- PathPlanning/BreadthFirstSearch/breadth_first_search.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index b4a5c38a8b..dbdeff47c8 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -178,8 +178,8 @@ def calc_obstacle_map(self, ox, oy): print("ywidth:", self.ywidth) # obstacle map generation - self.obmap = [[False for i in range(self.ywidth)] - for i in range(self.xwidth)] + self.obmap = [[False for _ in range(self.ywidth)] + for _ in range(self.xwidth)] for ix in range(self.xwidth): x = self.calc_grid_position(ix, self.minx) for iy in range(self.ywidth): From b7f18b8416603237793effb70ed519d61c38b557 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Sun, 19 Apr 2020 15:02:08 +0200 Subject: [PATCH 257/940] Improve readability to fetch lowest cost node --- .../bidirectional_a_star.py | 40 ++++++++++--------- 1 file changed, 22 insertions(+), 18 deletions(-) diff --git a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py index 4ffd34718b..1924cf59b1 100644 --- a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py +++ b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py @@ -75,24 +75,20 @@ def planning(self, sx, sy, gx, gy): if len(open_set_A) == 0: print("Open set A is empty..") break - + if len(open_set_B) == 0: print("Open set B is empty..") break c_id_A = min( open_set_A, - key=lambda o: open_set_A[o].cost + self.calc_heuristic(current_B, - open_set_A[ - o])) - + key=lambda o: self.find_lowest_cost(open_set_A, o, current_B)) + current_A = open_set_A[c_id_A] c_id_B = min( open_set_B, - key=lambda o: open_set_B[o].cost + self.calc_heuristic(current_A, - open_set_B[ - o])) + key=lambda o: self.find_lowest_cost(open_set_B, o, current_A)) current_B = open_set_B[c_id_B] @@ -129,12 +125,12 @@ def planning(self, sx, sy, gx, gy): continue_B = False child_node_A = self.Node(current_A.x + self.motion[i][0], - current_A.y + self.motion[i][1], - current_A.cost + self.motion[i][2], c_id_A) + current_A.y + self.motion[i][1], + current_A.cost + self.motion[i][2], c_id_A) child_node_B = self.Node(current_B.x + self.motion[i][0], - current_B.y + self.motion[i][1], - current_B.cost + self.motion[i][2], c_id_B) + current_B.y + self.motion[i][1], + current_B.cost + self.motion[i][2], c_id_B) n_id_A = self.calc_grid_index(child_node_A) n_id_B = self.calc_grid_index(child_node_B) @@ -142,33 +138,36 @@ def planning(self, sx, sy, gx, gy): # If the node is not safe, do nothing if not self.verify_node(child_node_A): continue_A = True - + if not self.verify_node(child_node_B): continue_B = True if n_id_A in closed_set_A: continue_A = True - + if n_id_B in closed_set_B: continue_B = True if not(continue_A): if n_id_A not in open_set_A: - open_set_A[n_id_A] = child_node_A # discovered a new node + # discovered a new node + open_set_A[n_id_A] = child_node_A else: if open_set_A[n_id_A].cost > child_node_A.cost: # This path is the best until now. record it open_set_A[n_id_A] = child_node_A - + if not(continue_B): if n_id_B not in open_set_B: - open_set_B[n_id_B] = child_node_B # discovered a new node + # discovered a new node + open_set_B[n_id_B] = child_node_B else: if open_set_B[n_id_B].cost > child_node_B.cost: # This path is the best until now. record it open_set_B[n_id_B] = child_node_B - rx, ry = self.calc_final_path_bidir(meetpointA, meetpointB, closed_set_A, closed_set_B) + rx, ry = self.calc_final_path_bidir( + meetpointA, meetpointB, closed_set_A, closed_set_B) return rx, ry @@ -203,6 +202,11 @@ def calc_heuristic(n1, n2): d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) return d + def find_lowest_cost(self, open_set, lambda_, n1): + cost = open_set[lambda_].cost + \ + self.calc_heuristic(n1, open_set[lambda_]) + return cost + def calc_grid_position(self, index, minp): """ calc grid position From 63a920223b034296edc3c4eae75ac4c0e80bb120 Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Sun, 19 Apr 2020 15:04:38 +0200 Subject: [PATCH 258/940] Fix pep8 indents --- .../BidirectionalAStar/bidirectional_a_star.py | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py index 1924cf59b1..3839e4dff3 100644 --- a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py +++ b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py @@ -82,13 +82,13 @@ def planning(self, sx, sy, gx, gy): c_id_A = min( open_set_A, - key=lambda o: self.find_lowest_cost(open_set_A, o, current_B)) + key=lambda o: self.find_total_cost(open_set_A, o, current_B)) current_A = open_set_A[c_id_A] c_id_B = min( open_set_B, - key=lambda o: self.find_lowest_cost(open_set_B, o, current_A)) + key=lambda o: self.find_total_cost(open_set_B, o, current_A)) current_B = open_set_B[c_id_B] @@ -148,7 +148,7 @@ def planning(self, sx, sy, gx, gy): if n_id_B in closed_set_B: continue_B = True - if not(continue_A): + if not continue_A: if n_id_A not in open_set_A: # discovered a new node open_set_A[n_id_A] = child_node_A @@ -157,7 +157,7 @@ def planning(self, sx, sy, gx, gy): # This path is the best until now. record it open_set_A[n_id_A] = child_node_A - if not(continue_B): + if not continue_B: if n_id_B not in open_set_B: # discovered a new node open_set_B[n_id_B] = child_node_B @@ -202,10 +202,11 @@ def calc_heuristic(n1, n2): d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) return d - def find_lowest_cost(self, open_set, lambda_, n1): - cost = open_set[lambda_].cost + \ - self.calc_heuristic(n1, open_set[lambda_]) - return cost + def find_total_cost(self, open_set, lambda_, n1): + g_cost = open_set[lambda_].cost + h_cost = self.calc_heuristic(n1, open_set[lambda_]) + f_cost = g_cost + h_cost + return f_cost def calc_grid_position(self, index, minp): """ From 38519b5df83141f6fc6bf452593fa748de2eae0f Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Fri, 24 Apr 2020 15:16:05 +0200 Subject: [PATCH 259/940] fix requests --- .../BidirectionalAStar/bidirectional_a_star.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py index 3839e4dff3..ed1e58699f 100644 --- a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py +++ b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py @@ -126,11 +126,13 @@ def planning(self, sx, sy, gx, gy): child_node_A = self.Node(current_A.x + self.motion[i][0], current_A.y + self.motion[i][1], - current_A.cost + self.motion[i][2], c_id_A) + current_A.cost + self.motion[i][2], + c_id_A) child_node_B = self.Node(current_B.x + self.motion[i][0], current_B.y + self.motion[i][1], - current_B.cost + self.motion[i][2], c_id_B) + current_B.cost + self.motion[i][2], + c_id_B) n_id_A = self.calc_grid_index(child_node_A) n_id_B = self.calc_grid_index(child_node_B) @@ -166,12 +168,12 @@ def planning(self, sx, sy, gx, gy): # This path is the best until now. record it open_set_B[n_id_B] = child_node_B - rx, ry = self.calc_final_path_bidir( + rx, ry = self.calc_final_bidirectional_path( meetpointA, meetpointB, closed_set_A, closed_set_B) return rx, ry - def calc_final_path_bidir(self, meetnode_A, meetnode_B, closed_set_A, closed_set_B): + def calc_final_bidirectional_path(self, meetnode_A, meetnode_B, closed_set_A, closed_set_B): rx_A, ry_A = self.calc_final_path(meetnode_A, closed_set_A) rx_B, ry_B = self.calc_final_path(meetnode_B, closed_set_B) @@ -299,7 +301,7 @@ def main(): grid_size = 2.0 # [m] robot_radius = 1.0 # [m] - # set obstable positions + # set obstacle positions ox, oy = [], [] for i in range(-10, 60): ox.append(i) From 18fe1960fb65ecfe1cee299b29ab4221cf03cc1c Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 28 Apr 2020 21:00:04 +0900 Subject: [PATCH 260/940] remove say thanks link --- README.md | 1 - users_comments.md | 2 -- 2 files changed, 3 deletions(-) diff --git a/README.md b/README.md index ab62c9af3c..9a9bc9502a 100644 --- a/README.md +++ b/README.md @@ -8,7 +8,6 @@ [![Language grade: Python](https://img.shields.io/lgtm/grade/python/g/AtsushiSakai/PythonRobotics.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/AtsushiSakai/PythonRobotics/context:python) [![CodeFactor](https://www.codefactor.io/repository/github/atsushisakai/pythonrobotics/badge/master)](https://www.codefactor.io/repository/github/atsushisakai/pythonrobotics/overview/master) [![tokei](https://tokei.rs/b1/github/AtsushiSakai/PythonRobotics)](https://github.com/AtsushiSakai/PythonRobotics) -[![Say Thanks!](https://img.shields.io/badge/Say%20Thanks-!-1EAEDB.svg)](https://saythanks.io/to/AtsushiSakai) Python codes for robotics algorithm. diff --git a/users_comments.md b/users_comments.md index 44e9355ec1..43ffc7cc36 100644 --- a/users_comments.md +++ b/users_comments.md @@ -40,8 +40,6 @@ This is a list of related projects. # Individual users comments -These are comments from user's using [![Say Thanks!](https://img.shields.io/badge/Say%20Thanks-!-1EAEDB.svg)](https://saythanks.io/to/AtsushiSakai) - --- Dear AtsushiSakai,
thank you for building this cool repo for robotics.
I am still learning robotics and this will give me a good starting point.
I hope this note gets to you.

From e8a006f747f9fbf4821a9e14033d21aa8c5e53b7 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 3 May 2020 23:02:59 +0900 Subject: [PATCH 261/940] Add code style checker CI (#321) Add code style checker CI --- .github/workflows/pythonpackage.yml | 12 +++++------- environment.yml | 2 +- rundiffstylecheck.sh | 15 +++++++++++++++ 3 files changed, 21 insertions(+), 8 deletions(-) create mode 100644 rundiffstylecheck.sh diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 574c7be9d5..defc159687 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -21,17 +21,12 @@ jobs: run: | python -m pip install --upgrade pip pip install -r requirements.txt - - name: Lint with flake8 - run: | - pip install flake8 - # stop the build if there are Python syntax errors or undefined names - flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics - # exit-zero treats all errors as warnings. The GitHub editor is 127 chars wide - flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - name: install coverage run: pip install coverage - name: install mypy run: pip install mypy + - name: install pycodestyle + run: pip install pycodestyle - name: mypy check run: | find AerialNavigation -name "*.py" | xargs mypy @@ -43,7 +38,10 @@ jobs: find PathPlanning -name "*.py" | xargs mypy find PathTracking -name "*.py" | xargs mypy find SLAM -name "*.py" | xargs mypy + - name: do diff style check + run: bash rundiffstylecheck.sh - name: do all unit tests run: bash runtests.sh + diff --git a/environment.yml b/environment.yml index 6866ed93ca..da1c3c0a6f 100644 --- a/environment.yml +++ b/environment.yml @@ -4,7 +4,7 @@ dependencies: - pip - matplotlib - scipy -- numpy==1.15 +- numpy - pandas - coverage - pip: diff --git a/rundiffstylecheck.sh b/rundiffstylecheck.sh new file mode 100644 index 0000000000..627e4a1b63 --- /dev/null +++ b/rundiffstylecheck.sh @@ -0,0 +1,15 @@ +#!/bin/bash +echo "$(basename $0) start!" +VERSION=v0.1.3 +wget https://github.com/AtsushiSakai/DiffSentinel/archive/${VERSION}.zip +unzip ${VERSION}.zip +./DiffSentinel*/starter.sh HEAD origin/master +check_result=$? +rm -rf ${VERSION}.zip DiffSentinel* +if [[ ${check_result} -ne 0 ]]; +then + echo "Error: Your changes contain pycodestyle errors." + exit 1 +fi +echo "$(basename $0) done!" +exit 0 From 614e18d246109566f3e071b63a57c5c87cb5164a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 4 May 2020 10:12:41 +0900 Subject: [PATCH 262/940] add test for PR --- .github/workflows/pythonpackage.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/pythonpackage.yml index 574c7be9d5..76196b6ed0 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/pythonpackage.yml @@ -1,6 +1,6 @@ name: Python package -on: [push] +on: [push, pull_request] jobs: build: From ae19d07bc3fd2a79d5b6c45ff614ddb1ef84a1d3 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 4 May 2020 14:22:25 +0900 Subject: [PATCH 263/940] bump DiffSentinelVersion --- rundiffstylecheck.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rundiffstylecheck.sh b/rundiffstylecheck.sh index 627e4a1b63..d170973751 100644 --- a/rundiffstylecheck.sh +++ b/rundiffstylecheck.sh @@ -1,6 +1,6 @@ #!/bin/bash echo "$(basename $0) start!" -VERSION=v0.1.3 +VERSION=v0.1.5 wget https://github.com/AtsushiSakai/DiffSentinel/archive/${VERSION}.zip unzip ${VERSION}.zip ./DiffSentinel*/starter.sh HEAD origin/master From ab49acb1acb2f60334febf6dc44dafa42ff6a836 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 4 May 2020 20:34:03 +0900 Subject: [PATCH 264/940] bump DiffSentinelVersion --- rundiffstylecheck.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rundiffstylecheck.sh b/rundiffstylecheck.sh index d170973751..8a19842c6e 100644 --- a/rundiffstylecheck.sh +++ b/rundiffstylecheck.sh @@ -1,6 +1,6 @@ #!/bin/bash echo "$(basename $0) start!" -VERSION=v0.1.5 +VERSION=v0.1.6 wget https://github.com/AtsushiSakai/DiffSentinel/archive/${VERSION}.zip unzip ${VERSION}.zip ./DiffSentinel*/starter.sh HEAD origin/master From 734f3aed20cfbbd634e0fe8f342655458ac3b2ff Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Tue, 5 May 2020 07:06:01 +0200 Subject: [PATCH 265/940] Greedy Best-First Search (#315) --- PathPlanning/AStar/a_star.py | 2 +- .../bidirectional_a_star.py | 78 ++--- .../breadth_first_search.py | 7 +- .../DepthFirstSearch/depth_first_search.py | 7 +- .../greedy_best_first_search.py | 278 ++++++++++++++++++ 5 files changed, 326 insertions(+), 46 deletions(-) create mode 100644 PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py index cd5a365c90..14c51ad9a1 100644 --- a/PathPlanning/AStar/a_star.py +++ b/PathPlanning/AStar/a_star.py @@ -237,7 +237,7 @@ def main(): grid_size = 2.0 # [m] robot_radius = 1.0 # [m] - # set obstable positions + # set obstacle positions ox, oy = [], [] for i in range(-10, 60): ox.append(i) diff --git a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py index ed1e58699f..65d1fc31a7 100644 --- a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py +++ b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py @@ -100,8 +100,9 @@ def planning(self, sx, sy, gx, gy): self.calc_grid_position(current_B.y, self.miny), "xc") # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit( - 0) if event.key == 'escape' else None]) + lambda event: + [exit(0) if event.key == 'escape' + else None]) if len(closed_set_A.keys()) % 10 == 0: plt.pause(0.001) @@ -121,61 +122,50 @@ def planning(self, sx, sy, gx, gy): # expand_grid search grid based on motion model for i, _ in enumerate(self.motion): - continue_A = False - continue_B = False - child_node_A = self.Node(current_A.x + self.motion[i][0], - current_A.y + self.motion[i][1], - current_A.cost + self.motion[i][2], - c_id_A) + c_nodes = [self.Node(current_A.x + self.motion[i][0], + current_A.y + self.motion[i][1], + current_A.cost + self.motion[i][2], + c_id_A), + self.Node(current_B.x + self.motion[i][0], + current_B.y + self.motion[i][1], + current_B.cost + self.motion[i][2], + c_id_B)] - child_node_B = self.Node(current_B.x + self.motion[i][0], - current_B.y + self.motion[i][1], - current_B.cost + self.motion[i][2], - c_id_B) - - n_id_A = self.calc_grid_index(child_node_A) - n_id_B = self.calc_grid_index(child_node_B) + n_ids = [self.calc_grid_index(c_nodes[0]), + self.calc_grid_index(c_nodes[1])] # If the node is not safe, do nothing - if not self.verify_node(child_node_A): - continue_A = True - - if not self.verify_node(child_node_B): - continue_B = True - - if n_id_A in closed_set_A: - continue_A = True - - if n_id_B in closed_set_B: - continue_B = True + continue_ = self.check_nodes_and_sets(c_nodes, closed_set_A, + closed_set_B, n_ids) - if not continue_A: - if n_id_A not in open_set_A: + if not continue_[0]: + if n_ids[0] not in open_set_A: # discovered a new node - open_set_A[n_id_A] = child_node_A + open_set_A[n_ids[0]] = c_nodes[0] else: - if open_set_A[n_id_A].cost > child_node_A.cost: + if open_set_A[n_ids[0]].cost > c_nodes[0].cost: # This path is the best until now. record it - open_set_A[n_id_A] = child_node_A + open_set_A[n_ids[0]] = c_nodes[0] - if not continue_B: - if n_id_B not in open_set_B: + if not continue_[1]: + if n_ids[1] not in open_set_B: # discovered a new node - open_set_B[n_id_B] = child_node_B + open_set_B[n_ids[1]] = c_nodes[1] else: - if open_set_B[n_id_B].cost > child_node_B.cost: + if open_set_B[n_ids[1]].cost > c_nodes[1].cost: # This path is the best until now. record it - open_set_B[n_id_B] = child_node_B + open_set_B[n_ids[1]] = c_nodes[1] rx, ry = self.calc_final_bidirectional_path( meetpointA, meetpointB, closed_set_A, closed_set_B) return rx, ry - def calc_final_bidirectional_path(self, meetnode_A, meetnode_B, closed_set_A, closed_set_B): - rx_A, ry_A = self.calc_final_path(meetnode_A, closed_set_A) - rx_B, ry_B = self.calc_final_path(meetnode_B, closed_set_B) + # takes two sets and two meeting nodes and return the optimal path + def calc_final_bidirectional_path(self, n1, n2, setA, setB): + rx_A, ry_A = self.calc_final_path(n1, setA) + rx_B, ry_B = self.calc_final_path(n2, setB) rx_A.reverse() ry_A.reverse() @@ -198,6 +188,16 @@ def calc_final_path(self, ngoal, closedset): return rx, ry + def check_nodes_and_sets(self, c_nodes, closedSet_A, closedSet_B, n_ids): + continue_ = [False, False] + if not self.verify_node(c_nodes[0]) or n_ids[0] in closedSet_A: + continue_[0] = True + + if not self.verify_node(c_nodes[1]) or n_ids[1] in closedSet_B: + continue_[1] = True + + return continue_ + @staticmethod def calc_heuristic(n1, n2): w = 1.0 # weight of heuristic diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index dbdeff47c8..198ddd2e3d 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -84,8 +84,9 @@ def planning(self, sx, sy, gx, gy): self.calc_grid_position(current.y, self.miny), "xc") # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit( - 0) if event.key == 'escape' else None]) + lambda event: + [exit(0) if event.key == 'escape' + else None]) if len(closed_set.keys()) % 10 == 0: plt.pause(0.001) @@ -216,7 +217,7 @@ def main(): grid_size = 2.0 # [m] robot_radius = 1.0 # [m] - # set obstable positions + # set obstacle positions ox, oy = [], [] for i in range(-10, 60): ox.append(i) diff --git a/PathPlanning/DepthFirstSearch/depth_first_search.py b/PathPlanning/DepthFirstSearch/depth_first_search.py index d42aa5f100..229eb70c2d 100644 --- a/PathPlanning/DepthFirstSearch/depth_first_search.py +++ b/PathPlanning/DepthFirstSearch/depth_first_search.py @@ -81,8 +81,9 @@ def planning(self, sx, sy, gx, gy): self.calc_grid_position(current.y, self.miny), "xc") # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit( - 0) if event.key == 'escape' else None]) + lambda event: + [exit(0) if event.key == 'escape' + else None]) plt.pause(0.01) if current.x == ngoal.x and current.y == ngoal.y: @@ -213,7 +214,7 @@ def main(): grid_size = 2.0 # [m] robot_radius = 1.0 # [m] - # set obstable positions + # set obstacle positions ox, oy = [], [] for i in range(-10, 60): ox.append(i) diff --git a/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py b/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py new file mode 100644 index 0000000000..c29e37e896 --- /dev/null +++ b/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py @@ -0,0 +1,278 @@ +""" + +Greedy Best-First grid planning + +author: Erwin Lejeune (@spida_rwin) + +See Wikipedia article (https://en.wikipedia.org/wiki/Best-first_search) + +""" + +import math + +import matplotlib.pyplot as plt + +show_animation = True + + +class BestFirstSearchPlanner: + + def __init__(self, ox, oy, reso, rr): + """ + Initialize grid map for greedy best-first planning + + ox: x position list of Obstacles [m] + oy: y position list of Obstacles [m] + reso: grid resolution [m] + rr: robot radius[m] + """ + + self.reso = reso + self.rr = rr + self.calc_obstacle_map(ox, oy) + self.motion = self.get_motion_model() + + class Node: + def __init__(self, x, y, cost, pind, parent): + self.x = x # index of grid + self.y = y # index of grid + self.cost = cost + self.pind = pind + self.parent = parent + + def __str__(self): + return str(self.x) + "," + str(self.y) + "," + str( + self.cost) + "," + str(self.pind) + + def planning(self, sx, sy, gx, gy): + """ + Greedy Best-First search + + input: + sx: start x position [m] + sy: start y position [m] + gx: goal x position [m] + gy: goal y position [m] + + output: + rx: x position list of the final path + ry: y position list of the final path + """ + + nstart = self.Node(self.calc_xyindex(sx, self.minx), + self.calc_xyindex(sy, self.miny), 0.0, -1, None) + ngoal = self.Node(self.calc_xyindex(gx, self.minx), + self.calc_xyindex(gy, self.miny), 0.0, -1, None) + + open_set, closed_set = dict(), dict() + open_set[self.calc_grid_index(nstart)] = nstart + + while 1: + if len(open_set) == 0: + print("Open set is empty..") + break + + c_id = min( + open_set, + key=lambda o: self.calc_heuristic(ngoal, open_set[o])) + + current = open_set[c_id] + + # show graph + if show_animation: # pragma: no cover + plt.plot(self.calc_grid_position(current.x, self.minx), + self.calc_grid_position(current.y, self.miny), "xc") + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: + [exit(0) + if event.key == 'escape' + else None]) + if len(closed_set.keys()) % 10 == 0: + plt.pause(0.001) + + # Remove the item from the open set + del open_set[c_id] + + # Add it to the closed set + closed_set[c_id] = current + + if current.x == ngoal.x and current.y == ngoal.y: + print("Found goal") + ngoal.pind = current.pind + ngoal.cost = current.cost + break + + # expand_grid search grid based on motion model + for i, _ in enumerate(self.motion): + node = self.Node(current.x + self.motion[i][0], + current.y + self.motion[i][1], + current.cost + self.motion[i][2], + c_id, current) + + n_id = self.calc_grid_index(node) + + # If the node is not safe, do nothing + if not self.verify_node(node): + continue + + if n_id in closed_set: + continue + + if n_id not in open_set: + open_set[n_id] = node + else: + if open_set[n_id].cost > node.cost: + open_set[n_id] = node + closed_set[ngoal.pind] = current + rx, ry = self.calc_final_path(ngoal, closed_set) + return rx, ry + + def calc_final_path(self, ngoal, closedset): + # generate final course + rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ + self.calc_grid_position(ngoal.y, self.miny)] + n = closedset[ngoal.pind] + while n is not None: + rx.append(self.calc_grid_position(n.x, self.minx)) + ry.append(self.calc_grid_position(n.y, self.miny)) + n = n.parent + + return rx, ry + + @staticmethod + def calc_heuristic(n1, n2): + w = 1.0 # weight of heuristic + d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) + return d + + def calc_grid_position(self, index, minp): + """ + calc grid position + + :param index: + :param minp: + :return: + """ + pos = index * self.reso + minp + return pos + + def calc_xyindex(self, position, min_pos): + return round((position - min_pos) / self.reso) + + def calc_grid_index(self, node): + return (node.y - self.miny) * self.xwidth + (node.x - self.minx) + + def verify_node(self, node): + px = self.calc_grid_position(node.x, self.minx) + py = self.calc_grid_position(node.y, self.miny) + + if px < self.minx: + return False + elif py < self.miny: + return False + elif px >= self.maxx: + return False + elif py >= self.maxy: + return False + + # collision check + if self.obmap[node.x][node.y]: + return False + + return True + + def calc_obstacle_map(self, ox, oy): + + self.minx = round(min(ox)) + self.miny = round(min(oy)) + self.maxx = round(max(ox)) + self.maxy = round(max(oy)) + print("minx:", self.minx) + print("miny:", self.miny) + print("maxx:", self.maxx) + print("maxy:", self.maxy) + + self.xwidth = round((self.maxx - self.minx) / self.reso) + self.ywidth = round((self.maxy - self.miny) / self.reso) + print("xwidth:", self.xwidth) + print("ywidth:", self.ywidth) + + # obstacle map generation + self.obmap = [[False for _ in range(self.ywidth)] + for _ in range(self.xwidth)] + for ix in range(self.xwidth): + x = self.calc_grid_position(ix, self.minx) + for iy in range(self.ywidth): + y = self.calc_grid_position(iy, self.miny) + for iox, ioy in zip(ox, oy): + d = math.hypot(iox - x, ioy - y) + if d <= self.rr: + self.obmap[ix][iy] = True + break + + @staticmethod + def get_motion_model(): + # dx, dy, cost + motion = [[1, 0, 1], + [0, 1, 1], + [-1, 0, 1], + [0, -1, 1], + [-1, -1, math.sqrt(2)], + [-1, 1, math.sqrt(2)], + [1, -1, math.sqrt(2)], + [1, 1, math.sqrt(2)]] + + return motion + + +def main(): + print(__file__ + " start!!") + + # start and goal position + sx = 10.0 # [m] + sy = 10.0 # [m] + gx = 50.0 # [m] + gy = 50.0 # [m] + grid_size = 2.0 # [m] + robot_radius = 1.0 # [m] + + # set obstacle positions + ox, oy = [], [] + for i in range(-10, 60): + ox.append(i) + oy.append(-10.0) + for i in range(-10, 60): + ox.append(60.0) + oy.append(i) + for i in range(-10, 61): + ox.append(i) + oy.append(60.0) + for i in range(-10, 61): + ox.append(-10.0) + oy.append(i) + for i in range(-10, 40): + ox.append(20.0) + oy.append(i) + for i in range(0, 40): + ox.append(40.0) + oy.append(60.0 - i) + + if show_animation: # pragma: no cover + plt.plot(ox, oy, ".k") + plt.plot(sx, sy, "og") + plt.plot(gx, gy, "xb") + plt.grid(True) + plt.axis("equal") + + greedybestfirst = BestFirstSearchPlanner(ox, oy, grid_size, robot_radius) + rx, ry = greedybestfirst.planning(sx, sy, gx, gy) + + if show_animation: # pragma: no cover + plt.plot(rx, ry, "-r") + plt.pause(0.01) + plt.show() + + +if __name__ == '__main__': + main() From 86c511efc022c613979c949bacab5dd079aaf36a Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Tue, 5 May 2020 07:15:03 +0200 Subject: [PATCH 266/940] Bidirectional Breadth-First Search (#316) --- .../bidirectional_breadth_first_search.py | 311 ++++++++++++++++++ 1 file changed, 311 insertions(+) create mode 100644 PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py diff --git a/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py b/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py new file mode 100644 index 0000000000..d29112eb65 --- /dev/null +++ b/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py @@ -0,0 +1,311 @@ +""" + +Bidirectional Breadth-First grid planning + +author: Erwin Lejeune (@spida_rwin) + +See Wikipedia article (https://en.wikipedia.org/wiki/Breadth-first_search) + +""" + +import math + +import matplotlib.pyplot as plt + +show_animation = True + + +class BidirectionalBreadthFirstSearchPlanner: + + def __init__(self, ox, oy, reso, rr): + """ + Initialize grid map for bfs planning + + ox: x position list of Obstacles [m] + oy: y position list of Obstacles [m] + reso: grid resolution [m] + rr: robot radius[m] + """ + + self.reso = reso + self.rr = rr + self.calc_obstacle_map(ox, oy) + self.motion = self.get_motion_model() + + class Node: + def __init__(self, x, y, cost, pind, parent): + self.x = x # index of grid + self.y = y # index of grid + self.cost = cost + self.pind = pind + self.parent = parent + + def __str__(self): + return str(self.x) + "," + str(self.y) + "," + str( + self.cost) + "," + str(self.pind) + + def planning(self, sx, sy, gx, gy): + """ + Bidirectional Breadth First search based planning + + input: + sx: start x position [m] + sy: start y position [m] + gx: goal x position [m] + gy: goal y position [m] + + output: + rx: x position list of the final path + ry: y position list of the final path + """ + + nstart = self.Node(self.calc_xyindex(sx, self.minx), + self.calc_xyindex(sy, self.miny), 0.0, -1, None) + ngoal = self.Node(self.calc_xyindex(gx, self.minx), + self.calc_xyindex(gy, self.miny), 0.0, -1, None) + + open_set_A, closed_set_A = dict(), dict() + open_set_B, closed_set_B = dict(), dict() + open_set_B[self.calc_grid_index(ngoal)] = ngoal + open_set_A[self.calc_grid_index(nstart)] = nstart + + while 1: + if len(open_set_A) == 0: + print("Open set A is empty..") + break + + if len(open_set_B) == 0: + print("Open set B is empty") + break + + current_A = open_set_A.pop(list(open_set_A.keys())[0]) + current_B = open_set_B.pop(list(open_set_B.keys())[0]) + + c_id_A = self.calc_grid_index(current_A) + c_id_B = self.calc_grid_index(current_B) + + closed_set_A[c_id_A] = current_A + closed_set_B[c_id_B] = current_B + + # show graph + if show_animation: # pragma: no cover + plt.plot(self.calc_grid_position(current_A.x, self.minx), + self.calc_grid_position(current_A.y, self.miny), "xc") + plt.plot(self.calc_grid_position(current_B.x, self.minx), + self.calc_grid_position(current_B.y, self.miny), "xc") + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: + [exit(0) if + event.key == 'escape' else None]) + if len(closed_set_A.keys()) % 10 == 0: + plt.pause(0.001) + + if c_id_A in closed_set_B: + print("Find goal") + meetpointA = closed_set_A[c_id_A] + meetpointB = closed_set_B[c_id_A] + break + + elif c_id_B in closed_set_A: + print("Find goal") + meetpointA = closed_set_A[c_id_B] + meetpointB = closed_set_B[c_id_B] + break + + # expand_grid search grid based on motion model + for i, _ in enumerate(self.motion): + breakA = False + breakB = False + + node_A = self.Node(current_A.x + self.motion[i][0], + current_A.y + self.motion[i][1], + current_A.cost + self.motion[i][2], + c_id_A, None) + node_B = self.Node(current_B.x + self.motion[i][0], + current_B.y + self.motion[i][1], + current_B.cost + self.motion[i][2], + c_id_B, None) + + n_id_A = self.calc_grid_index(node_A) + n_id_B = self.calc_grid_index(node_B) + + # If the node is not safe, do nothing + if not self.verify_node(node_A): + breakA = True + + if not self.verify_node(node_B): + breakB = True + + if (n_id_A not in closed_set_A) and (n_id_A not in + open_set_A) and (not + breakA): + node_A.parent = current_A + open_set_A[n_id_A] = node_A + + if (n_id_B not in closed_set_B) and (n_id_B not in + open_set_B) and (not + breakB): + node_B.parent = current_B + open_set_B[n_id_B] = node_B + + rx, ry = self.calc_final_path_bidir( + meetpointA, meetpointB, closed_set_A, closed_set_B) + return rx, ry + + # takes both set and meeting nodes and calculate optimal path + def calc_final_path_bidir(self, n1, n2, setA, setB): + rxA, ryA = self.calc_final_path(n1, setA) + rxB, ryB = self.calc_final_path(n2, setB) + + rxA.reverse() + ryA.reverse() + + rx = rxA + rxB + ry = ryA + ryB + + return rx, ry + + def calc_final_path(self, ngoal, closedset): + # generate final course + rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ + self.calc_grid_position(ngoal.y, self.miny)] + n = closedset[ngoal.pind] + while n is not None: + rx.append(self.calc_grid_position(n.x, self.minx)) + ry.append(self.calc_grid_position(n.y, self.miny)) + n = n.parent + + return rx, ry + + def calc_grid_position(self, index, minp): + """ + calc grid position + + :param index: + :param minp: + :return: + """ + pos = index * self.reso + minp + return pos + + def calc_xyindex(self, position, min_pos): + return round((position - min_pos) / self.reso) + + def calc_grid_index(self, node): + return (node.y - self.miny) * self.xwidth + (node.x - self.minx) + + def verify_node(self, node): + px = self.calc_grid_position(node.x, self.minx) + py = self.calc_grid_position(node.y, self.miny) + + if px < self.minx: + return False + elif py < self.miny: + return False + elif px >= self.maxx: + return False + elif py >= self.maxy: + return False + + # collision check + if self.obmap[node.x][node.y]: + return False + + return True + + def calc_obstacle_map(self, ox, oy): + + self.minx = round(min(ox)) + self.miny = round(min(oy)) + self.maxx = round(max(ox)) + self.maxy = round(max(oy)) + print("minx:", self.minx) + print("miny:", self.miny) + print("maxx:", self.maxx) + print("maxy:", self.maxy) + + self.xwidth = round((self.maxx - self.minx) / self.reso) + self.ywidth = round((self.maxy - self.miny) / self.reso) + print("xwidth:", self.xwidth) + print("ywidth:", self.ywidth) + + # obstacle map generation + self.obmap = [[False for _ in range(self.ywidth)] + for _ in range(self.xwidth)] + for ix in range(self.xwidth): + x = self.calc_grid_position(ix, self.minx) + for iy in range(self.ywidth): + y = self.calc_grid_position(iy, self.miny) + for iox, ioy in zip(ox, oy): + d = math.hypot(iox - x, ioy - y) + if d <= self.rr: + self.obmap[ix][iy] = True + break + + @staticmethod + def get_motion_model(): + # dx, dy, cost + motion = [[1, 0, 1], + [0, 1, 1], + [-1, 0, 1], + [0, -1, 1], + [-1, -1, math.sqrt(2)], + [-1, 1, math.sqrt(2)], + [1, -1, math.sqrt(2)], + [1, 1, math.sqrt(2)]] + + return motion + + +def main(): + print(__file__ + " start!!") + + # start and goal position + sx = 10.0 # [m] + sy = 10.0 # [m] + gx = 50.0 # [m] + gy = 50.0 # [m] + grid_size = 2.0 # [m] + robot_radius = 1.0 # [m] + + # set obstacle positions + ox, oy = [], [] + for i in range(-10, 60): + ox.append(i) + oy.append(-10.0) + for i in range(-10, 60): + ox.append(60.0) + oy.append(i) + for i in range(-10, 61): + ox.append(i) + oy.append(60.0) + for i in range(-10, 61): + ox.append(-10.0) + oy.append(i) + for i in range(-10, 40): + ox.append(20.0) + oy.append(i) + for i in range(0, 40): + ox.append(40.0) + oy.append(60.0 - i) + + if show_animation: # pragma: no cover + plt.plot(ox, oy, ".k") + plt.plot(sx, sy, "og") + plt.plot(gx, gy, "ob") + plt.grid(True) + plt.axis("equal") + + bi_bfs = BidirectionalBreadthFirstSearchPlanner( + ox, oy, grid_size, robot_radius) + rx, ry = bi_bfs.planning(sx, sy, gx, gy) + + if show_animation: # pragma: no cover + plt.plot(rx, ry, "-r") + plt.pause(0.01) + plt.show() + + +if __name__ == '__main__': + main() From ada734f6622bf6a380266344c01601f97aedece3 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 5 May 2020 14:17:28 +0900 Subject: [PATCH 267/940] add an author --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index 9a9bc9502a..aa9a47ca77 100644 --- a/README.md +++ b/README.md @@ -598,4 +598,6 @@ If you or your company would like to support this project, please consider: - [Guillaume Jacquenot](https://github.com/Gjacquenot) +- [Erwin Lejeune](https://github.com/guilyx) + From 2b0020764b63b105ce90fc880d7e200203f44b2f Mon Sep 17 00:00:00 2001 From: Erwin Lejeune Date: Thu, 7 May 2020 13:06:08 +0200 Subject: [PATCH 268/940] Fix Hybrid A* (#327) --- PathPlanning/HybridAStar/hybrid_a_star.py | 47 ++++++++++++++--------- tests/test_hybrid_a_star.py | 22 +++++++++++ 2 files changed, 51 insertions(+), 18 deletions(-) create mode 100644 tests/test_hybrid_a_star.py diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index 41e8b393c0..14e4ac5aec 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -12,19 +12,22 @@ import math import matplotlib.pyplot as plt import sys -sys.path.append("../ReedsSheppPath/") +import os + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../ReedsSheppPath") try: from a_star_heuristic import dp_planning # , calc_obstacle_map import reeds_shepp_path_planning as rs from car import move, check_car_collision, MAX_STEER, WB, plot_car -except: +except Exception: raise XY_GRID_RESOLUTION = 2.0 # [m] YAW_GRID_RESOLUTION = np.deg2rad(15.0) # [rad] MOTION_RESOLUTION = 0.1 # [m] path interporate resolution -N_STEER = 20.0 # number of steer command +N_STEER = 20 # number of steer command H_COST = 1.0 VR = 1.0 # robot radius @@ -131,7 +134,8 @@ def __init__(self, ox, oy, xyreso, yawreso): def calc_motion_inputs(): - for steer in np.concatenate((np.linspace(-MAX_STEER, MAX_STEER, N_STEER),[0.0])): + for steer in np.concatenate((np.linspace(-MAX_STEER, MAX_STEER, + N_STEER), [0.0])): for d in [1, -1]: yield [steer, d] @@ -225,7 +229,8 @@ def update_node_with_analystic_expantion(current, goal, apath = analytic_expantion(current, goal, c, ox, oy, kdtree) if apath: - plt.plot(apath.x, apath.y) + if show_animation: + plt.plot(apath.x, apath.y) fx = apath.x[1:] fy = apath.y[1:] fyaw = apath.yaw[1:] @@ -337,6 +342,7 @@ def hybrid_a_star_planning(start, goal, ox, oy, xyreso, yawreso): current, ngoal, config, ox, oy, obkdtree) if isupdated: + print("path found") break for neighbor in get_neighbors(current, config, ox, oy, obkdtree): @@ -437,12 +443,16 @@ def main(): start = [10.0, 10.0, np.deg2rad(90.0)] goal = [50.0, 50.0, np.deg2rad(-90.0)] - plt.plot(ox, oy, ".k") - rs.plot_arrow(start[0], start[1], start[2], fc='g') - rs.plot_arrow(goal[0], goal[1], goal[2]) + print("start : ", start) + print("goal : ", goal) + + if show_animation: + plt.plot(ox, oy, ".k") + rs.plot_arrow(start[0], start[1], start[2], fc='g') + rs.plot_arrow(goal[0], goal[1], goal[2]) - plt.grid(True) - plt.axis("equal") + plt.grid(True) + plt.axis("equal") path = hybrid_a_star_planning( start, goal, ox, oy, XY_GRID_RESOLUTION, YAW_GRID_RESOLUTION) @@ -451,14 +461,15 @@ def main(): y = path.ylist yaw = path.yawlist - for ix, iy, iyaw in zip(x, y, yaw): - plt.cla() - plt.plot(ox, oy, ".k") - plt.plot(x, y, "-r", label="Hybrid A* path") - plt.grid(True) - plt.axis("equal") - plot_car(ix, iy, iyaw) - plt.pause(0.0001) + if show_animation: + for ix, iy, iyaw in zip(x, y, yaw): + plt.cla() + plt.plot(ox, oy, ".k") + plt.plot(x, y, "-r", label="Hybrid A* path") + plt.grid(True) + plt.axis("equal") + plot_car(ix, iy, iyaw) + plt.pause(0.0001) print(__file__ + " done!!") diff --git a/tests/test_hybrid_a_star.py b/tests/test_hybrid_a_star.py new file mode 100644 index 0000000000..8cf5c30ad6 --- /dev/null +++ b/tests/test_hybrid_a_star.py @@ -0,0 +1,22 @@ +from unittest import TestCase +import sys +import os +sys.path.append(os.path.dirname(__file__) + "/../") +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../PathPlanning/HybridAStar") +try: + from PathPlanning.HybridAStar import hybrid_a_star as m +except Exception: + raise + + +class Test(TestCase): + + def test1(self): + m.show_animation = False + m.main() + + +if __name__ == '__main__': # pragma: no cover + test = Test() + test.test1() From 3607d72b60cd500806e0f026ac8beb82850a01f9 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 8 May 2020 22:15:43 +0900 Subject: [PATCH 269/940] Update official Python version to 3.8 (#329) --- .../{pythonpackage.yml => Linux_CI.yml} | 15 +++-- .github/workflows/MacOS_CI.yml | 58 +++++++++++++++++++ .travis.yml | 2 +- README.md | 4 +- appveyor.yml | 12 ++-- 5 files changed, 78 insertions(+), 13 deletions(-) rename .github/workflows/{pythonpackage.yml => Linux_CI.yml} (82%) create mode 100644 .github/workflows/MacOS_CI.yml diff --git a/.github/workflows/pythonpackage.yml b/.github/workflows/Linux_CI.yml similarity index 82% rename from .github/workflows/pythonpackage.yml rename to .github/workflows/Linux_CI.yml index 7d1014ca57..293c5621e2 100644 --- a/.github/workflows/pythonpackage.yml +++ b/.github/workflows/Linux_CI.yml @@ -1,4 +1,4 @@ -name: Python package +name: Linux_CI on: [push, pull_request] @@ -7,14 +7,17 @@ jobs: runs-on: ubuntu-latest strategy: - max-parallel: 4 matrix: - python-version: [3.7] + python-version: ['3.8'] + + name: Python ${{ matrix.python-version }} CI steps: - - uses: actions/checkout@v1 - - name: Set up Python ${{ matrix.python-version }} - uses: actions/setup-python@v1 + - uses: actions/checkout@v2 + - run: git fetch --prune --unshallow + + - name: Setup python + uses: actions/setup-python@v2 with: python-version: ${{ matrix.python-version }} - name: Install dependencies diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml new file mode 100644 index 0000000000..3a28347b18 --- /dev/null +++ b/.github/workflows/MacOS_CI.yml @@ -0,0 +1,58 @@ +# This is a basic workflow to help you get started with Actions + +name: MacOS_CI + +# Controls when the action will run. Triggers the workflow on push or pull request +# events but only for the master branch +on: [push, pull_request] + +jobs: + build: + runs-on: ubuntu-latest + strategy: + matrix: + python-version: [ '3.8' ] + name: Python ${{ matrix.python-version }} CI + steps: + - uses: actions/checkout@v2 + - run: git fetch --prune --unshallow + + - name: Setup python + uses: actions/setup-python@v2 + with: + python-version: ${{ matrix.python-version }} + + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install -r requirements.txt + - name: install coverage + run: pip install coverage + + - name: install mypy + run: pip install mypy + + - name: install pycodestyle + run: pip install pycodestyle + + - name: mypy check + run: | + find AerialNavigation -name "*.py" | xargs mypy + find ArmNavigation -name "*.py" | xargs mypy + find Bipedal -name "*.py" | xargs mypy + find InvertedPendulumCart -name "*.py" | xargs mypy + find Localization -name "*.py" | xargs mypy + find Mapping -name "*.py" | xargs mypy + find PathPlanning -name "*.py" | xargs mypy + find PathTracking -name "*.py" | xargs mypy + find SLAM -name "*.py" | xargs mypy + + - name: do diff style check + run: bash rundiffstylecheck.sh + + - name: do all unit tests + run: bash runtests.sh + + + + diff --git a/.travis.yml b/.travis.yml index 042c69ee42..da82e6062d 100644 --- a/.travis.yml +++ b/.travis.yml @@ -5,7 +5,7 @@ matrix: - os: linux python: - - 3.7 + - 3.8 before_install: - sudo apt-get update diff --git a/README.md b/README.md index aa9a47ca77..4a64f53642 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,8 @@ header pic # PythonRobotics +![GitHub_Action_Linux_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/Linux_CI/badge.svg) +![GitHub_Action_MacOS_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/MacOS_CI/badge.svg) [![Build Status](https://travis-ci.org/AtsushiSakai/PythonRobotics.svg?branch=master)](https://travis-ci.org/AtsushiSakai/PythonRobotics) [![Documentation Status](https://readthedocs.org/projects/pythonrobotics/badge/?version=latest)](https://pythonrobotics.readthedocs.io/en/latest/?badge=latest) [![Build status](https://ci.appveyor.com/api/projects/status/sb279kxuv1be391g?svg=true)](https://ci.appveyor.com/project/AtsushiSakai/pythonrobotics) @@ -90,7 +92,7 @@ See this paper for more details: # Requirements -- Python 3.7.x (2.7 is not supported) +- Python 3.8.x - numpy diff --git a/appveyor.yml b/appveyor.yml index 33d4d02970..f34bcb2b28 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -1,3 +1,5 @@ +os: Visual Studio 2019 + environment: global: # SDK v7.0 MSVC Express 2008's SetEnv.cmd script will fail if the @@ -6,7 +8,8 @@ environment: CMD_IN_ENV: "cmd /E:ON /V:ON /C .\\appveyor\\run_with_env.cmd" matrix: - - MINICONDA: C:\Miniconda37-x64 + - MINICONDA: C:\Miniconda38-x64 + PYTHON_VERSION: "3.8" init: - "ECHO %MINICONDA% %PYTHON_VERSION% %PYTHON_ARCH%" @@ -24,13 +27,12 @@ install: - ECHO "Filesystem root:" - ps: "ls \"C:/\"" - - ECHO "Installed SDKs:" - - ps: "ls \"C:/Program Files/Microsoft SDKs/Windows\"" - # Prepend newly installed Python to the PATH of this build (this cannot be # done from inside the powershell script as it would require to restart # the parent CMD process). - - "SET PATH=%MINICONDA%;%MINICONDA%\\Scripts;%PATH%" + - SET PATH=%MINICONDA%;%MINICONDA%\\Scripts;%PATH% + - SET PATH=%PYTHON%;%PYTHON%\Scripts;%PYTHON%\Library\bin;%PATH% + - SET PATH=%PATH%;C:\Program Files (x86)\Microsoft Visual Studio 14.0\VC\bin - conda config --set always_yes yes --set changeps1 no - conda update -q conda - conda info -a From 03a92fc23eb97b0d58bea37c4f8cf22c3ef02fb3 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 28 May 2020 22:03:17 +0900 Subject: [PATCH 270/940] fix bipedal_planner and add its test (#332) --- Bipedal/bipedal_planner/__init__.py | 0 Bipedal/bipedal_planner/bipedal_planner.py | 103 +++++++++++------- .../reeds_shepp_path_planning.py | 22 ++-- tests/test_bipedal_planner.py | 24 ++++ 4 files changed, 104 insertions(+), 45 deletions(-) create mode 100644 Bipedal/bipedal_planner/__init__.py create mode 100644 tests/test_bipedal_planner.py diff --git a/Bipedal/bipedal_planner/__init__.py b/Bipedal/bipedal_planner/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/Bipedal/bipedal_planner/bipedal_planner.py b/Bipedal/bipedal_planner/bipedal_planner.py index 6502ce5bed..60c03024bf 100644 --- a/Bipedal/bipedal_planner/bipedal_planner.py +++ b/Bipedal/bipedal_planner/bipedal_planner.py @@ -12,13 +12,17 @@ class BipedalPlanner(object): def __init__(self): + self.act_p = [] # actual footstep positions + self.ref_p = [] # reference footstep positions + self.com_trajectory = [] self.ref_footsteps = None self.g = 9.8 def set_ref_footsteps(self, ref_footsteps): self.ref_footsteps = ref_footsteps - def inverted_pendulum(self, x, x_dot, px_star, y, y_dot, py_star, z_c, time_width): + def inverted_pendulum(self, x, x_dot, px_star, y, y_dot, py_star, z_c, + time_width): time_split = 100 for i in range(time_split): @@ -37,23 +41,21 @@ def inverted_pendulum(self, x, x_dot, px_star, y, y_dot, py_star, z_c, time_widt return x, x_dot, y, y_dot - def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False): + def walk(self, t_sup=0.8, z_c=0.8, a=10, b=1, plot=False): if self.ref_footsteps is None: print("No footsteps") return + com_trajectory_for_plot, ax = None, None + # set up plotter if plot: fig = plt.figure() ax = Axes3D(fig) com_trajectory_for_plot = [] - self.com_trajectory = [] - self.ref_p = [] # reference footstep positions - self.act_p = [] # actual footstep positions - - px, py = 0.0, 0.0 # reference footstep position - px_star, py_star = px, py # modified footstep position + px, py = 0.0, 0.0 # reference footstep position + px_star, py_star = px, py # modified footstep position xi, xi_dot, yi, yi_dot = 0.0, 0.0, 0.01, 0.0 time = 0.0 n = 0 @@ -62,10 +64,10 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False): for i in range(len(self.ref_footsteps)): # simulate x, y and those of dot of inverted pendulum xi, xi_dot, yi, yi_dot = self.inverted_pendulum( - xi, xi_dot, px_star, yi, yi_dot, py_star, z_c, T_sup) + xi, xi_dot, px_star, yi, yi_dot, py_star, z_c, t_sup) # update time - time += T_sup + time += t_sup n += 1 # calculate px, py, x_, y_, vx_, vy_ @@ -77,19 +79,22 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False): f_x_next, f_y_next, f_theta_next = 0., 0., 0. else: f_x_next, f_y_next, f_theta_next = self.ref_footsteps[n] - rotate_mat_next = np.array([[math.cos(f_theta_next), -math.sin(f_theta_next)], - [math.sin(f_theta_next), math.cos(f_theta_next)]]) - - T_c = math.sqrt(z_c / self.g) - C = math.cosh(T_sup / T_c) - S = math.sinh(T_sup / T_c) - - px, py = list(np.array( - [px, py]) + np.dot(rotate_mat, np.array([f_x, -1 * math.pow(-1, n) * f_y]))) + rotate_mat_next = np.array( + [[math.cos(f_theta_next), -math.sin(f_theta_next)], + [math.sin(f_theta_next), math.cos(f_theta_next)]]) + + Tc = math.sqrt(z_c / self.g) + C = math.cosh(t_sup / Tc) + S = math.sinh(t_sup / Tc) + + px, py = list(np.array([px, py]) + + np.dot(rotate_mat, + np.array([f_x, -1 * math.pow(-1, n) * f_y]) + )) x_, y_ = list(np.dot(rotate_mat_next, np.array( [f_x_next / 2., math.pow(-1, n) * f_y_next / 2.]))) vx_, vy_ = list(np.dot(rotate_mat_next, np.array( - [(1 + C) / (T_c * S) * x_, (C - 1) / (T_c * S) * y_]))) + [(1 + C) / (Tc * S) * x_, (C - 1) / (Tc * S) * y_]))) self.ref_p.append([px, py, f_theta]) # calculate reference COM @@ -97,11 +102,11 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False): yd, yd_dot = py + y_, vy_ # calculate modified footsteps - D = a * math.pow(C - 1, 2) + b * math.pow(S / T_c, 2) - px_star = -a * (C - 1) / D * (xd - C * xi - T_c * S * xi_dot) - \ - b * S / (T_c * D) * (xd_dot - S / T_c * xi - C * xi_dot) - py_star = -a * (C - 1) / D * (yd - C * yi - T_c * S * yi_dot) - \ - b * S / (T_c * D) * (yd_dot - S / T_c * yi - C * yi_dot) + D = a * math.pow(C - 1, 2) + b * math.pow(S / Tc, 2) + px_star = -a * (C - 1) / D * (xd - C * xi - Tc * S * xi_dot) \ + - b * S / (Tc * D) * (xd_dot - S / Tc * xi - C * xi_dot) + py_star = -a * (C - 1) / D * (yd - C * yi - Tc * S * yi_dot) \ + - b * S / (Tc * D) * (yd_dot - S / Tc * yi - C * yi_dot) self.act_p.append([px_star, py_star, f_theta]) # plot @@ -112,17 +117,22 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False): # set up plotter plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: + [exit(0) if event.key == 'escape' else None]) ax.set_zlim(0, z_c * 2) - ax.set_aspect('equal', 'datalim') + ax.set_xlim(0, 1) + ax.set_ylim(-0.5, 0.5) # update com_trajectory_for_plot com_trajectory_for_plot.append(self.com_trajectory[c]) # plot com - ax.plot([p[0] for p in com_trajectory_for_plot], [p[1] for p in com_trajectory_for_plot], [ - 0 for p in com_trajectory_for_plot], color="red") + ax.plot([p[0] for p in com_trajectory_for_plot], + [p[1] for p in com_trajectory_for_plot], [ + 0 for _ in com_trajectory_for_plot], + color="red") # plot inverted pendulum ax.plot([px_star, com_trajectory_for_plot[-1][0]], @@ -137,22 +147,39 @@ def walk(self, T_sup=0.8, z_c=0.8, a=10, b=1, plot=False): foot_height = 0.04 for j in range(len(self.ref_p)): angle = self.ref_p[j][2] + \ - math.atan2(foot_height, foot_width) - math.pi + math.atan2(foot_height, + foot_width) - math.pi r = math.sqrt( - math.pow(foot_width / 3., 2) + math.pow(foot_height / 2., 2)) - rec = pat.Rectangle(xy=(self.ref_p[j][0] + r * math.cos(angle), self.ref_p[j][1] + r * math.sin(angle)), - width=foot_width, height=foot_height, angle=self.ref_p[j][2] * 180 / math.pi, color="blue", fill=False, ls=":") + math.pow(foot_width / 3., 2) + math.pow( + foot_height / 2., 2)) + rec = pat.Rectangle(xy=( + self.ref_p[j][0] + r * math.cos(angle), + self.ref_p[j][1] + r * math.sin(angle)), + width=foot_width, + height=foot_height, + angle=self.ref_p[j][ + 2] * 180 / math.pi, + color="blue", fill=False, + ls=":") ax.add_patch(rec) art3d.pathpatch_2d_to_3d(rec, z=0, zdir="z") # foot rectangle for self.act_p for j in range(len(self.act_p)): angle = self.act_p[j][2] + \ - math.atan2(foot_height, foot_width) - math.pi + math.atan2(foot_height, + foot_width) - math.pi r = math.sqrt( - math.pow(foot_width / 3., 2) + math.pow(foot_height / 2., 2)) - rec = pat.Rectangle(xy=(self.act_p[j][0] + r * math.cos(angle), self.act_p[j][1] + r * math.sin(angle)), - width=foot_width, height=foot_height, angle=self.act_p[j][2] * 180 / math.pi, color="blue", fill=False) + math.pow(foot_width / 3., 2) + math.pow( + foot_height / 2., 2)) + rec = pat.Rectangle(xy=( + self.act_p[j][0] + r * math.cos(angle), + self.act_p[j][1] + r * math.sin(angle)), + width=foot_width, + height=foot_height, + angle=self.act_p[j][ + 2] * 180 / math.pi, + color="blue", fill=False) ax.add_patch(rec) art3d.pathpatch_2d_to_3d(rec, z=0, zdir="z") diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py index 9c72a0c9b2..3bed9e2997 100644 --- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py +++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py @@ -369,13 +369,21 @@ def reeds_shepp_path_planning(sx, sy, syaw, def main(): print("Reeds Shepp path planner sample start!!") - start_x = -1.0 # [m] - start_y = -4.0 # [m] - start_yaw = np.deg2rad(-20.0) # [rad] - - end_x = 5.0 # [m] - end_y = 5.0 # [m] - end_yaw = np.deg2rad(25.0) # [rad] + # start_x = -1.0 # [m] + # start_y = -4.0 # [m] + # start_yaw = np.deg2rad(-20.0) # [rad] + # + # end_x = 5.0 # [m] + # end_y = 5.0 # [m] + # end_yaw = np.deg2rad(25.0) # [rad] + + start_x = 0.0 # [m] + start_y = 0.0 # [m] + start_yaw = np.deg2rad(0.0) # [rad] + + end_x = 0.0 # [m] + end_y = 0.0 # [m] + end_yaw = np.deg2rad(0.0) # [rad] curvature = 1.0 step_size = 0.1 diff --git a/tests/test_bipedal_planner.py b/tests/test_bipedal_planner.py new file mode 100644 index 0000000000..66049c68ec --- /dev/null +++ b/tests/test_bipedal_planner.py @@ -0,0 +1,24 @@ +from unittest import TestCase + +import sys +sys.path.append("./Bipedal/bipedal_planner/") +try: + from Bipedal.bipedal_planner import bipedal_planner as m +except Exception: + raise + +print(__file__) + + +class Test(TestCase): + + def test(self): + bipedal_planner = m.BipedalPlanner() + + footsteps = [[0.0, 0.2, 0.0], + [0.3, 0.2, 0.0], + [0.3, 0.2, 0.2], + [0.3, 0.2, 0.2], + [0.0, 0.2, 0.2]] + bipedal_planner.set_ref_footsteps(footsteps) + bipedal_planner.walk(plot=False) From 26b2c552efe7eec8f8f1505aabbf5591627878d8 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 5 Jun 2020 21:21:35 +0900 Subject: [PATCH 271/940] fix inaccurate covariance calculation to add a new landmark in FastSLAM1,2 (#334) --- SLAM/FastSLAM1/fast_slam1.py | 108 +++++++++++++++++++---------------- SLAM/FastSLAM2/fast_slam2.py | 68 ++++++++++++---------- 2 files changed, 96 insertions(+), 80 deletions(-) diff --git a/SLAM/FastSLAM1/fast_slam1.py b/SLAM/FastSLAM1/fast_slam1.py index 2d7c003785..c4beaba257 100644 --- a/SLAM/FastSLAM1/fast_slam1.py +++ b/SLAM/FastSLAM1/fast_slam1.py @@ -16,16 +16,16 @@ R = np.diag([1.0, np.deg2rad(20.0)]) ** 2 # Simulation parameter -Qsim = np.diag([0.3, np.deg2rad(2.0)]) ** 2 -Rsim = np.diag([0.5, np.deg2rad(10.0)]) ** 2 -OFFSET_YAWRATE_NOISE = 0.01 +Q_sim = np.diag([0.3, np.deg2rad(2.0)]) ** 2 +R_sim = np.diag([0.5, np.deg2rad(10.0)]) ** 2 +OFFSET_YAW_RATE_NOISE = 0.01 DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] MAX_RANGE = 20.0 # maximum observation range M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association. STATE_SIZE = 3 # State size [x,y,yaw] -LM_SIZE = 2 # LM srate size [x,y] +LM_SIZE = 2 # LM state size [x,y] N_PARTICLE = 100 # number of particle NTH = N_PARTICLE / 1.5 # Number of particle for re-sampling @@ -34,15 +34,15 @@ class Particle: - def __init__(self, N_LM): + def __init__(self, n_landmark): self.w = 1.0 / N_PARTICLE self.x = 0.0 self.y = 0.0 self.yaw = 0.0 # landmark x-y positions - self.lm = np.zeros((N_LM, LM_SIZE)) + self.lm = np.zeros((n_landmark, LM_SIZE)) # landmark position covariance - self.lmP = np.zeros((N_LM * LM_SIZE, LM_SIZE)) + self.lmP = np.zeros((n_landmark * LM_SIZE, LM_SIZE)) def fast_slam1(particles, u, z): @@ -56,11 +56,11 @@ def fast_slam1(particles, u, z): def normalize_weight(particles): - sumw = sum([p.w for p in particles]) + sum_w = sum([p.w for p in particles]) try: for i in range(N_PARTICLE): - particles[i].w /= sumw + particles[i].w /= sum_w except ZeroDivisionError: for i in range(N_PARTICLE): particles[i].w = 1.0 / N_PARTICLE @@ -101,7 +101,7 @@ def predict_particles(particles, u): return particles -def add_new_lm(particle, z, Q_cov): +def add_new_landmark(particle, z, Q_cov): r = z[0] b = z[1] lm_id = int(z[2]) @@ -113,10 +113,14 @@ def add_new_lm(particle, z, Q_cov): particle.lm[lm_id, 1] = particle.y + r * s # covariance - Gz = np.array([[c, -r * s], - [s, r * c]]) - - particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q_cov @ Gz.T + dx = r * c + dy = r * s + d2 = dx**2 + dy**2 + d = math.sqrt(d2) + Gz = np.array([[dx / d, dy / d], + [-dy / d2, dx / d2]]) + particle.lmP[2 * lm_id:2 * lm_id + 2] = np.linalg.inv( + Gz) @ Q_cov @ np.linalg.inv(Gz.T) return particle @@ -146,10 +150,10 @@ def update_kf_with_cholesky(xf, Pf, v, Q_cov, Hf): S = Hf @ PHt + Q_cov S = (S + S.T) * 0.5 - SChol = np.linalg.cholesky(S).T - SCholInv = np.linalg.inv(SChol) - W1 = PHt @ SCholInv - W = W1 @ SCholInv.T + s_chol = np.linalg.cholesky(S).T + s_chol_inv = np.linalg.inv(s_chol) + W1 = PHt @ s_chol_inv + W = W1 @ s_chol_inv.T x = xf + W @ v P = Pf - W1 @ W1.T @@ -187,7 +191,7 @@ def compute_weight(particle, z, Q_cov): try: invS = np.linalg.inv(Sf) except np.linalg.linalg.LinAlgError: - print("singuler") + print("singular") return 1.0 num = math.exp(-0.5 * dx.T @ invS @ dx) @@ -201,12 +205,12 @@ def compute_weight(particle, z, Q_cov): def update_with_observation(particles, z): for iz in range(len(z[0, :])): - lmid = int(z[2, iz]) + landmark_id = int(z[2, iz]) for ip in range(N_PARTICLE): # new landmark - if abs(particles[ip].lm[lmid, 0]) <= 0.01: - particles[ip] = add_new_lm(particles[ip], z[:, iz], Q) + if abs(particles[ip].lm[landmark_id, 0]) <= 0.01: + particles[ip] = add_new_landmark(particles[ip], z[:, iz], Q) # known landmark else: w = compute_weight(particles[ip], z[:, iz], Q) @@ -229,28 +233,29 @@ def resampling(particles): pw = np.array(pw) - Neff = 1.0 / (pw @ pw.T) # Effective particle number - # print(Neff) + n_eff = 1.0 / (pw @ pw.T) # Effective particle number + # print(n_eff) - if Neff < NTH: # resampling - wcum = np.cumsum(pw) + if n_eff < NTH: # resampling + w_cum = np.cumsum(pw) base = np.cumsum(pw * 0.0 + 1 / N_PARTICLE) - 1 / N_PARTICLE - resampleid = base + np.random.rand(base.shape[0]) / N_PARTICLE + resample_id = base + np.random.rand(base.shape[0]) / N_PARTICLE inds = [] ind = 0 for ip in range(N_PARTICLE): - while (ind < wcum.shape[0] - 1) and (resampleid[ip] > wcum[ind]): + while (ind < w_cum.shape[0] - 1) \ + and (resample_id[ip] > w_cum[ind]): ind += 1 inds.append(ind) - tparticles = particles[:] + tmp_particles = particles[:] for i in range(len(inds)): - particles[i].x = tparticles[inds[i]].x - particles[i].y = tparticles[inds[i]].y - particles[i].yaw = tparticles[inds[i]].yaw - particles[i].lm = tparticles[inds[i]].lm[:, :] - particles[i].lmP = tparticles[inds[i]].lmP[:, :] + particles[i].x = tmp_particles[inds[i]].x + particles[i].y = tmp_particles[inds[i]].y + particles[i].yaw = tmp_particles[inds[i]].yaw + particles[i].lm = tmp_particles[inds[i]].lm[:, :] + particles[i].lmP = tmp_particles[inds[i]].lmP[:, :] particles[i].w = 1.0 / N_PARTICLE return particles @@ -259,37 +264,39 @@ def resampling(particles): def calc_input(time): if time <= 3.0: # wait at first v = 0.0 - yawrate = 0.0 + yaw_rate = 0.0 else: v = 1.0 # [m/s] - yawrate = 0.1 # [rad/s] + yaw_rate = 0.1 # [rad/s] - u = np.array([v, yawrate]).reshape(2, 1) + u = np.array([v, yaw_rate]).reshape(2, 1) return u -def observation(xTrue, xd, u, RFID): +def observation(xTrue, xd, u, rfid): # calc true state xTrue = motion_model(xTrue, u) # add noise to range observation z = np.zeros((3, 0)) - for i in range(len(RFID[:, 0])): + for i in range(len(rfid[:, 0])): - dx = RFID[i, 0] - xTrue[0, 0] - dy = RFID[i, 1] - xTrue[1, 0] + dx = rfid[i, 0] - xTrue[0, 0] + dy = rfid[i, 1] - xTrue[1, 0] d = math.hypot(dx, dy) angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: - dn = d + np.random.randn() * Qsim[0, 0] ** 0.5 # add noise - anglen = angle + np.random.randn() * Qsim[1, 1] ** 0.5 # add noise - zi = np.array([dn, pi_2_pi(anglen), i]).reshape(3, 1) + dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise + angle_with_noize = angle + np.random.randn() * Q_sim[ + 1, 1] ** 0.5 # add noise + zi = np.array([dn, pi_2_pi(angle_with_noize), i]).reshape(3, 1) z = np.hstack((z, zi)) # add noise to input - ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0] ** 0.5 - ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] ** 0.5 + OFFSET_YAWRATE_NOISE + ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5 + ud2 = u[1, 0] + np.random.randn() * R_sim[ + 1, 1] ** 0.5 + OFFSET_YAW_RATE_NOISE ud = np.array([ud1, ud2]).reshape(2, 1) xd = motion_model(xd, ud) @@ -332,7 +339,7 @@ def main(): [-5.0, 5.0], [-10.0, 15.0] ]) - N_LM = RFID.shape[0] + n_landmark = RFID.shape[0] # State Vector [x y yaw v]' xEst = np.zeros((STATE_SIZE, 1)) # SLAM estimation @@ -344,7 +351,7 @@ def main(): hxTrue = xTrue hxDR = xTrue - particles = [Particle(N_LM) for _ in range(N_PARTICLE)] + particles = [Particle(n_landmark) for _ in range(N_PARTICLE)] while SIM_TIME >= time: time += DT @@ -366,8 +373,9 @@ def main(): if show_animation: # pragma: no cover plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', lambda event: + [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") for i in range(N_PARTICLE): diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py index 4780b57982..7cd708df81 100644 --- a/SLAM/FastSLAM2/fast_slam2.py +++ b/SLAM/FastSLAM2/fast_slam2.py @@ -113,10 +113,14 @@ def add_new_lm(particle, z, Q_cov): particle.lm[lm_id, 1] = particle.y + r * s # covariance - Gz = np.array([[c, -r * s], - [s, r * c]]) - - particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q_cov @ Gz.T + dx = r * c + dy = r * s + d2 = dx ** 2 + dy ** 2 + d = math.sqrt(d2) + Gz = np.array([[dx / d, dy / d], + [-dy / d2, dx / d2]]) + particle.lmP[2 * lm_id:2 * lm_id + 2] = np.linalg.inv( + Gz) @ Q_cov @ np.linalg.inv(Gz.T) return particle @@ -224,11 +228,11 @@ def proposal_sampling(particle, z, Q_cov): def update_with_observation(particles, z): for iz in range(len(z[0, :])): - lmid = int(z[2, iz]) + landmark_id = int(z[2, iz]) for ip in range(N_PARTICLE): # new landmark - if abs(particles[ip].lm[lmid, 0]) <= 0.01: + if abs(particles[ip].lm[landmark_id, 0]) <= 0.01: particles[ip] = add_new_lm(particles[ip], z[:, iz], Q) # known landmark else: @@ -254,27 +258,28 @@ def resampling(particles): pw = np.array(pw) - Neff = 1.0 / (pw @ pw.T) # Effective particle number + n_eff = 1.0 / (pw @ pw.T) # Effective particle number - if Neff < NTH: # resampling - wcum = np.cumsum(pw) + if n_eff < NTH: # resampling + w_cum = np.cumsum(pw) base = np.cumsum(pw * 0.0 + 1 / N_PARTICLE) - 1 / N_PARTICLE - resamplei_id = base + np.random.rand(base.shape[0]) / N_PARTICLE + resample_id = base + np.random.rand(base.shape[0]) / N_PARTICLE inds = [] ind = 0 for ip in range(N_PARTICLE): - while (ind < wcum.shape[0] - 1) and (resamplei_id[ip] > wcum[ind]): + while (ind < w_cum.shape[0] - 1) \ + and (resample_id[ip] > w_cum[ind]): ind += 1 inds.append(ind) - tparticles = particles[:] + tmp_particles = particles[:] for i in range(len(inds)): - particles[i].x = tparticles[inds[i]].x - particles[i].y = tparticles[inds[i]].y - particles[i].yaw = tparticles[inds[i]].yaw - particles[i].lm = tparticles[inds[i]].lm[:, :] - particles[i].lmP = tparticles[inds[i]].lmP[:, :] + particles[i].x = tmp_particles[inds[i]].x + particles[i].y = tmp_particles[inds[i]].y + particles[i].yaw = tmp_particles[inds[i]].yaw + particles[i].lm = tmp_particles[inds[i]].lm[:, :] + particles[i].lmP = tmp_particles[inds[i]].lmP[:, :] particles[i].w = 1.0 / N_PARTICLE return particles @@ -283,12 +288,12 @@ def resampling(particles): def calc_input(time): if time <= 3.0: # wait at first v = 0.0 - yawrate = 0.0 + yaw_rate = 0.0 else: v = 1.0 # [m/s] - yawrate = 0.1 # [rad/s] + yaw_rate = 0.1 # [rad/s] - u = np.array([v, yawrate]).reshape(2, 1) + u = np.array([v, yaw_rate]).reshape(2, 1) return u @@ -308,13 +313,15 @@ def observation(xTrue, xd, u, RFID): angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise - anglen = angle + np.random.randn() * Q_sim[1, 1] ** 0.5 # add noise - zi = np.array([dn, pi_2_pi(anglen), i]).reshape(3, 1) + angle_noise = np.random.randn() * Q_sim[1, 1] ** 0.5 + angle_with_noise = angle + angle_noise # add noise + zi = np.array([dn, pi_2_pi(angle_with_noise), i]).reshape(3, 1) z = np.hstack((z, zi)) # add noise to input ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5 - ud2 = u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5 + OFFSET_YAW_RATE_NOISE + ud2 = u[1, 0] + np.random.randn() * R_sim[ + 1, 1] ** 0.5 + OFFSET_YAW_RATE_NOISE ud = np.array([ud1, ud2]).reshape(2, 1) xd = motion_model(xd, ud) @@ -357,7 +364,7 @@ def main(): [-5.0, 5.0], [-10.0, 15.0] ]) - N_LM = RFID.shape[0] + n_landmark = RFID.shape[0] # State Vector [x y yaw v]' xEst = np.zeros((STATE_SIZE, 1)) # SLAM estimation @@ -369,7 +376,7 @@ def main(): hxTrue = xTrue hxDR = xTrue - particles = [Particle(N_LM) for _ in range(N_PARTICLE)] + particles = [Particle(n_landmark) for _ in range(N_PARTICLE)] while SIM_TIME >= time: time += DT @@ -391,14 +398,15 @@ def main(): if show_animation: # pragma: no cover plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") for iz in range(len(z[:, 0])): - lmid = int(z[2, iz]) - plt.plot([xEst[0], RFID[lmid, 0]], [ - xEst[1], RFID[lmid, 1]], "-k") + landmark_id = int(z[2, iz]) + plt.plot([xEst[0], RFID[landmark_id, 0]], [ + xEst[1], RFID[landmark_id, 1]], "-k") for i in range(N_PARTICLE): plt.plot(particles[i].x, particles[i].y, ".r") From d1bde5835f7f6063bcff5675e138d57644bc6d4a Mon Sep 17 00:00:00 2001 From: Justin Hutchings Date: Fri, 5 Jun 2020 16:21:00 -0700 Subject: [PATCH 272/940] Add CodeQL security scanning (#333) * Add CodeQL security scanning * Add configuration for LGTM queries * Remove excess whitespace --- .github/codeql/codeql-config.yml | 6 ++++ .github/workflows/codeql.yml | 54 ++++++++++++++++++++++++++++++++ 2 files changed, 60 insertions(+) create mode 100644 .github/codeql/codeql-config.yml create mode 100644 .github/workflows/codeql.yml diff --git a/.github/codeql/codeql-config.yml b/.github/codeql/codeql-config.yml new file mode 100644 index 0000000000..4542231f10 --- /dev/null +++ b/.github/codeql/codeql-config.yml @@ -0,0 +1,6 @@ +name: "Extended CodeQL Config" + +# This file adds additional queries to the default configuration to make it equivalent to what LGTM checks. +queries: + - name: Security and quality queries + uses: security-and-quality diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml new file mode 100644 index 0000000000..526b465eec --- /dev/null +++ b/.github/workflows/codeql.yml @@ -0,0 +1,54 @@ +name: "Code scanning - action" + +on: + push: + pull_request: + schedule: + - cron: '0 19 * * 0' + +jobs: + CodeQL-Build: + + # CodeQL runs on ubuntu-latest and windows-latest + runs-on: ubuntu-latest + + steps: + - name: Checkout repository + uses: actions/checkout@v2 + with: + # We must fetch at least the immediate parents so that if this is + # a pull request then we can checkout the head. + fetch-depth: 2 + + # If this run was triggered by a pull request event, then checkout + # the head of the pull request instead of the merge commit. + - run: git checkout HEAD^2 + if: ${{ github.event_name == 'pull_request' }} + + # Initializes the CodeQL tools for scanning. + - name: Initialize CodeQL + uses: github/codeql-action/init@v1 + with: + config-file: ./.github/codeql/codeql-config.yml + # Override language selection by uncommenting this and choosing your languages + # with: + # languages: go, javascript, csharp, python, cpp, java + + # Autobuild attempts to build any compiled languages (C/C++, C#, or Java). + # If this step fails, then you should remove it and run the build manually (see below) + - name: Autobuild + uses: github/codeql-action/autobuild@v1 + + # ℹ️ Command-line programs to run using the OS shell. + # 📚 https://git.io/JvXDl + + # ✏️ If the Autobuild fails above, remove it and uncomment the following three lines + # and modify them (or add more) to build your code if your project + # uses a compiled language + + #- run: | + # make bootstrap + # make release + + - name: Perform CodeQL Analysis + uses: github/codeql-action/analyze@v1 From b8afdb10d8d8f57f5c6bde9b41ab64911d01ef8e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 7 Jun 2020 20:28:29 +0900 Subject: [PATCH 273/940] Using scipy.spatial.rotation matrix (#335) --- .travis.yml | 3 +- .../ensemble_kalman_filter.py | 40 ++- .../histogram_filter/histogram_filter.py | 121 ++++--- .../particle_filter/particle_filter.py | 16 +- .../lidar_to_grid_map/lidar_to_grid_map.py | 187 +++++----- .../rectangle_fitting/rectangle_fitting.py | 74 ++-- Mapping/rectangle_fitting/simulator.py | 81 ++--- PathPlanning/AStar/a_star.py | 130 +++---- .../bidirectional_a_star.py | 22 +- .../bidirectional_breadth_first_search.py | 20 +- .../breadth_first_search.py | 20 +- .../ClosedLoopRRTStar/pure_pursuit.py | 6 +- .../DepthFirstSearch/depth_first_search.py | 20 +- PathPlanning/Dijkstra/dijkstra.py | 4 +- .../DubinsPath/dubins_path_planning.py | 96 +++--- .../dynamic_window_approach.py | 36 +- .../greedy_best_first_search.py | 20 +- .../grid_based_sweep_coverage_path_planner.py | 187 +++++----- PathPlanning/HybridAStar/a_star_heuristic.py | 147 ++++---- PathPlanning/HybridAStar/car.py | 50 +-- PathPlanning/HybridAStar/hybrid_a_star.py | 322 +++++++++--------- .../InformedRRTStar/informed_rrt_star.py | 91 ++--- .../probabilistic_road_map.py | 128 +++---- .../quintic_polynomials_planner.py | 6 +- .../VoronoiRoadMap/dijkstra_search.py | 4 +- SLAM/GraphBasedSLAM/graph_based_slam.py | 104 +++--- 26 files changed, 1003 insertions(+), 932 deletions(-) diff --git a/.travis.yml b/.travis.yml index da82e6062d..99d239217b 100644 --- a/.travis.yml +++ b/.travis.yml @@ -18,10 +18,9 @@ before_install: - conda update -q conda # Useful for debugging any issues with conda - conda info -a -# - conda install python==3.6.8 install: - - conda install numpy==1.15 + - conda install numpy - conda install scipy - conda install matplotlib - conda install pandas diff --git a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py index 58a998e2f3..1307b1ebd1 100644 --- a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py +++ b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py @@ -5,7 +5,8 @@ author: Ryohei Sasaki(rsasaki0109) Ref: -- [Ensemble Kalman filtering](https://rmets.onlinelibrary.wiley.com/doi/10.1256/qj.05.135) +Ensemble Kalman filtering +(https://rmets.onlinelibrary.wiley.com/doi/10.1256/qj.05.135) """ @@ -13,6 +14,7 @@ import matplotlib.pyplot as plt import numpy as np +from scipy.spatial.transform import Rotation as Rot # Simulation parameter Q_sim = np.diag([0.2, np.deg2rad(1.0)]) ** 2 @@ -48,8 +50,8 @@ def observation(xTrue, xd, u, RFID): angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) if d <= MAX_RANGE: dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise - anglen = angle + np.random.randn() * Q_sim[1, 1] ** 0.5 # add noise - zi = np.array([dn, anglen, RFID[i, 0], RFID[i, 1]]) + angle_with_noise = angle + np.random.randn() * Q_sim[1, 1] ** 0.5 + zi = np.array([dn, angle_with_noise, RFID[i, 0], RFID[i, 1]]) z = np.vstack((z, zi)) # add noise to input @@ -79,10 +81,12 @@ def motion_model(x, u): def observe_landmark_position(x, landmarks): landmarks_pos = np.zeros((2 * landmarks.shape[0], 1)) for (i, lm) in enumerate(landmarks): - landmarks_pos[2 * i] = x[0, 0] + lm[0] * math.cos(x[2, 0] + lm[1]) + np.random.randn() * Q_sim[ - 0, 0] ** 0.5 / np.sqrt(2) - landmarks_pos[2 * i + 1] = x[1, 0] + lm[0] * math.sin(x[2, 0] + lm[1]) + np.random.randn() * Q_sim[ - 0, 0] ** 0.5 / np.sqrt(2) + index = 2 * i + q = Q_sim[0, 0] ** 0.5 + landmarks_pos[index] = x[0, 0] + lm[0] * math.cos( + x[2, 0] + lm[1]) + np.random.randn() * q / np.sqrt(2) + landmarks_pos[index + 1] = x[1, 0] + lm[0] * math.sin( + x[2, 0] + lm[1]) + np.random.randn() * q / np.sqrt(2) return landmarks_pos @@ -148,8 +152,9 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover t = np.arange(0, 2 * math.pi + 0.1, 0.1) - # eig_val[big_ind] or eiq_val[small_ind] were occasionally negative numbers extremely - # close to 0 (~10^-20), catch these cases and set the respective variable to 0 + # eig_val[big_ind] or eiq_val[small_ind] were occasionally negative + # numbers extremely close to 0 (~10^-20), catch these cases and set + # the respective variable to 0 try: a = math.sqrt(eig_val[big_ind]) except ValueError: @@ -163,11 +168,11 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] angle = math.atan2(eig_vec[big_ind, 1], eig_vec[big_ind, 0]) - R = np.array([[math.cos(angle), math.sin(angle)], - [-math.sin(angle), math.cos(angle)]]) - fx = R.dot(np.array([[x, y]])) - px = np.array(fx[0, :] + xEst[0, 0]).flatten() - py = np.array(fx[1, :] + xEst[1, 0]).flatten() + rot = Rot.from_euler('z', angle).as_matrix()[0:2, 0:2] + fx = np.stack([x, y]).T @ rot + + px = np.array(fx[:, 0] + xEst[0, 0]).flatten() + py = np.array(fx[:, 1] + xEst[1, 0]).flatten() plt.plot(px, py, "--r") @@ -214,8 +219,9 @@ def main(): if show_animation: plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) for i in range(len(z[:, 0])): plt.plot([xTrue[0, 0], z[i, 2]], [xTrue[1, 0], z[i, 3]], "-k") @@ -227,7 +233,7 @@ def main(): np.array(hxDR[1, :]).flatten(), "-k") plt.plot(np.array(hxEst[0, :]).flatten(), np.array(hxEst[1, :]).flatten(), "-r") - # plot_covariance_ellipse(xEst, PEst) + plot_covariance_ellipse(xEst, PEst) plt.axis("equal") plt.grid(True) plt.pause(0.001) diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index 135b476cc4..7f453d69dd 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -28,11 +28,11 @@ RANGE_STD = 3.0 # standard deviation for observation gaussian distribution # grid map param -XY_RESO = 0.5 # xy grid resolution -MINX = -15.0 -MINY = -5.0 -MAXX = 15.0 -MAXY = 25.0 +XY_RESOLUTION = 0.5 # xy grid resolution +MIN_X = -15.0 +MIN_Y = -5.0 +MAX_X = 15.0 +MAX_Y = 25.0 # simulation parameters NOISE_RANGE = 2.0 # [m] 1σ range noise parameter @@ -41,17 +41,17 @@ show_animation = True -class GridMap(): +class GridMap: def __init__(self): self.data = None - self.xy_reso = None - self.minx = None - self.miny = None - self.maxx = None - self.maxx = None - self.xw = None - self.yw = None + self.xy_resolution = None + self.min_x = None + self.min_y = None + self.max_x = None + self.max_y = None + self.x_w = None + self.y_w = None self.dx = 0.0 # movement distance self.dy = 0.0 # movement distance @@ -64,10 +64,10 @@ def histogram_filter_localization(grid_map, u, z, yaw): return grid_map -def calc_gaussian_observation_pdf(gmap, z, iz, ix, iy, std): +def calc_gaussian_observation_pdf(grid_map, z, iz, ix, iy, std): # predicted range - x = ix * gmap.xy_reso + gmap.minx - y = iy * gmap.xy_reso + gmap.miny + x = ix * grid_map.xy_resolution + grid_map.min_x + y = iy * grid_map.xy_resolution + grid_map.min_y d = math.hypot(x - z[iz, 1], y - z[iz, 2]) # likelihood @@ -76,16 +76,16 @@ def calc_gaussian_observation_pdf(gmap, z, iz, ix, iy, std): return pdf -def observation_update(gmap, z, std): +def observation_update(grid_map, z, std): for iz in range(z.shape[0]): - for ix in range(gmap.xw): - for iy in range(gmap.yw): - gmap.data[ix][iy] *= calc_gaussian_observation_pdf( - gmap, z, iz, ix, iy, std) + for ix in range(grid_map.x_w): + for iy in range(grid_map.y_w): + grid_map.data[ix][iy] *= calc_gaussian_observation_pdf( + grid_map, z, iz, ix, iy, std) - gmap = normalize_probability(gmap) + grid_map = normalize_probability(grid_map) - return gmap + return grid_map def calc_input(): @@ -112,8 +112,8 @@ def motion_model(x, u): def draw_heat_map(data, mx, my): - maxp = max([max(igmap) for igmap in data]) - plt.pcolor(mx, my, data, vmax=maxp, cmap=plt.cm.get_cmap("Blues")) + max_value = max([max(i_data) for i_data in data]) + plt.pcolor(mx, my, data, vmax=max_value, cmap=plt.cm.get_cmap("Blues")) plt.axis("equal") @@ -140,43 +140,47 @@ def observation(xTrue, u, RFID): return xTrue, z, ud -def normalize_probability(gmap): - sump = sum([sum(igmap) for igmap in gmap.data]) +def normalize_probability(grid_map): + sump = sum([sum(i_data) for i_data in grid_map.data]) - for ix in range(gmap.xw): - for iy in range(gmap.yw): - gmap.data[ix][iy] /= sump + for ix in range(grid_map.x_w): + for iy in range(grid_map.y_w): + grid_map.data[ix][iy] /= sump - return gmap + return grid_map -def init_gmap(xy_reso, minx, miny, maxx, maxy): +def init_grid_map(xy_resolution, min_x, min_y, max_x, max_y): grid_map = GridMap() - grid_map.xy_reso = xy_reso - grid_map.minx = minx - grid_map.miny = miny - grid_map.maxx = maxx - grid_map.maxy = maxy - grid_map.xw = int(round((grid_map.maxx - grid_map.minx) / grid_map.xy_reso)) - grid_map.yw = int(round((grid_map.maxy - grid_map.miny) / grid_map.xy_reso)) - - grid_map.data = [[1.0 for _ in range(grid_map.yw)] for _ in range(grid_map.xw)] + grid_map.xy_resolution = xy_resolution + grid_map.min_x = min_x + grid_map.min_y = min_y + grid_map.max_x = max_x + grid_map.max_y = max_y + grid_map.x_w = int(round((grid_map.max_x - grid_map.min_x) + / grid_map.xy_resolution)) + grid_map.y_w = int(round((grid_map.max_y - grid_map.min_y) + / grid_map.xy_resolution)) + + grid_map.data = [[1.0 for _ in range(grid_map.y_w)] + for _ in range(grid_map.x_w)] grid_map = normalize_probability(grid_map) return grid_map def map_shift(grid_map, x_shift, y_shift): - tgmap = copy.deepcopy(grid_map.data) + tmp_grid_map = copy.deepcopy(grid_map.data) - for ix in range(grid_map.xw): - for iy in range(grid_map.yw): + for ix in range(grid_map.x_w): + for iy in range(grid_map.y_w): nix = ix + x_shift niy = iy + y_shift - if 0 <= nix < grid_map.xw and 0 <= niy < grid_map.yw: - grid_map.data[ix + x_shift][iy + y_shift] = tgmap[ix][iy] + if 0 <= nix < grid_map.x_w and 0 <= niy < grid_map.y_w: + grid_map.data[ix + x_shift][iy + y_shift] =\ + tmp_grid_map[ix][iy] return grid_map @@ -185,22 +189,26 @@ def motion_update(grid_map, u, yaw): grid_map.dx += DT * math.cos(yaw) * u[0] grid_map.dy += DT * math.sin(yaw) * u[0] - x_shift = grid_map.dx // grid_map.xy_reso - y_shift = grid_map.dy // grid_map.xy_reso + x_shift = grid_map.dx // grid_map.xy_resolution + y_shift = grid_map.dy // grid_map.xy_resolution if abs(x_shift) >= 1.0 or abs(y_shift) >= 1.0: # map should be shifted grid_map = map_shift(grid_map, int(x_shift), int(y_shift)) - grid_map.dx -= x_shift * grid_map.xy_reso - grid_map.dy -= y_shift * grid_map.xy_reso + grid_map.dx -= x_shift * grid_map.xy_resolution + grid_map.dy -= y_shift * grid_map.xy_resolution grid_map.data = gaussian_filter(grid_map.data, sigma=MOTION_STD) return grid_map -def calc_grid_index(gmap): - mx, my = np.mgrid[slice(gmap.minx - gmap.xy_reso / 2.0, gmap.maxx + gmap.xy_reso / 2.0, gmap.xy_reso), - slice(gmap.miny - gmap.xy_reso / 2.0, gmap.maxy + gmap.xy_reso / 2.0, gmap.xy_reso)] +def calc_grid_index(grid_map): + mx, my = np.mgrid[slice(grid_map.min_x - grid_map.xy_resolution / 2.0, + grid_map.max_x + grid_map.xy_resolution / 2.0, + grid_map.xy_resolution), + slice(grid_map.min_y - grid_map.xy_resolution / 2.0, + grid_map.max_y + grid_map.xy_resolution / 2.0, + grid_map.xy_resolution)] return mx, my @@ -217,7 +225,7 @@ def main(): time = 0.0 xTrue = np.zeros((4, 1)) - grid_map = init_gmap(XY_RESO, MINX, MINY, MAXX, MAXY) + grid_map = init_grid_map(XY_RESOLUTION, MIN_X, MIN_Y, MAX_X, MAX_Y) mx, my = calc_grid_index(grid_map) # for grid map visualization while SIM_TIME >= time: @@ -234,8 +242,9 @@ def main(): if show_animation: plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) draw_heat_map(grid_map.data, mx, my) plt.plot(xTrue[0, :], xTrue[1, :], "xr") plt.plot(RF_ID[:, 0], RF_ID[:, 1], ".k") diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 6eca4eb53b..89a43ea600 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -10,6 +10,7 @@ import matplotlib.pyplot as plt import numpy as np +from scipy.spatial.transform import Rotation as Rot # Estimation parameter of PF Q = np.diag([0.2]) ** 2 # range error @@ -172,8 +173,9 @@ def plot_covariance_ellipse(x_est, p_est): # pragma: no cover t = np.arange(0, 2 * math.pi + 0.1, 0.1) - # eig_val[big_ind] or eiq_val[small_ind] were occasionally negative numbers extremely - # close to 0 (~10^-20), catch these cases and set the respective variable to 0 + # eig_val[big_ind] or eiq_val[small_ind] were occasionally negative + # numbers extremely close to 0 (~10^-20), catch these cases and set the + # respective variable to 0 try: a = math.sqrt(eig_val[big_ind]) except ValueError: @@ -187,9 +189,8 @@ def plot_covariance_ellipse(x_est, p_est): # pragma: no cover x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] angle = math.atan2(eig_vec[big_ind, 1], eig_vec[big_ind, 0]) - Rot = np.array([[math.cos(angle), -math.sin(angle)], - [math.sin(angle), math.cos(angle)]]) - fx = Rot.dot(np.array([[x, y]])) + rot = Rot.from_euler('z', angle).as_matrix()[0:2, 0:2] + fx = rot.dot(np.array([[x, y]])) px = np.array(fx[0, :] + x_est[0, 0]).flatten() py = np.array(fx[1, :] + x_est[1, 0]).flatten() plt.plot(px, py, "--r") @@ -235,8 +236,9 @@ def main(): if show_animation: plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) for i in range(len(z[:, 0])): plt.plot([x_true[0, 0], z[i, 1]], [x_true[1, 0], z[i, 2]], "-k") diff --git a/Mapping/lidar_to_grid_map/lidar_to_grid_map.py b/Mapping/lidar_to_grid_map/lidar_to_grid_map.py index 60bf4db69c..911a0bf0ea 100644 --- a/Mapping/lidar_to_grid_map/lidar_to_grid_map.py +++ b/Mapping/lidar_to_grid_map/lidar_to_grid_map.py @@ -2,15 +2,16 @@ LIDAR to 2D grid map example -author: Erno Horvath, Csaba Hajdu based on Atsushi Sakai's scripts (@Atsushi_twi) +author: Erno Horvath, Csaba Hajdu based on Atsushi Sakai's scripts """ import math -import numpy as np -import matplotlib.pyplot as plt from collections import deque +import matplotlib.pyplot as plt +import numpy as np + EXTEND_AREA = 1.0 @@ -44,47 +45,49 @@ def bresenham(start, end): x2, y2 = end dx = x2 - x1 dy = y2 - y1 - is_steep = abs(dy) > abs(dx) # determine how steep the line is - if is_steep: # rotate line + is_steep = abs(dy) > abs(dx) # determine how steep the line is + if is_steep: # rotate line x1, y1 = y1, x1 x2, y2 = y2, x2 - swapped = False # swap start and end points if necessary and store swap state + # swap start and end points if necessary and store swap state + swapped = False if x1 > x2: x1, x2 = x2, x1 y1, y2 = y2, y1 swapped = True - dx = x2 - x1 # recalculate differentials - dy = y2 - y1 # recalculate differentials - error = int(dx / 2.0) # calculate error - ystep = 1 if y1 < y2 else -1 + dx = x2 - x1 # recalculate differentials + dy = y2 - y1 # recalculate differentials + error = int(dx / 2.0) # calculate error + y_step = 1 if y1 < y2 else -1 # iterate over bounding box generating points between start and end y = y1 points = [] for x in range(x1, x2 + 1): coord = [y, x] if is_steep else (x, y) - points.append(coord) + points.append(coord) error -= abs(dy) if error < 0: - y += ystep + y += y_step error += dx - if swapped: # reverse the list if the coordinates were swapped + if swapped: # reverse the list if the coordinates were swapped points.reverse() points = np.array(points) return points -def calc_grid_map_config(ox, oy, xyreso): +def calc_grid_map_config(ox, oy, xy_resolution): """ - Calculates the size, and the maximum distances according to the the measurement center + Calculates the size, and the maximum distances according to the the + measurement center """ - minx = round(min(ox) - EXTEND_AREA / 2.0) - miny = round(min(oy) - EXTEND_AREA / 2.0) - maxx = round(max(ox) + EXTEND_AREA / 2.0) - maxy = round(max(oy) + EXTEND_AREA / 2.0) - xw = int(round((maxx - minx) / xyreso)) - yw = int(round((maxy - miny) / xyreso)) + min_x = round(min(ox) - EXTEND_AREA / 2.0) + min_y = round(min(oy) - EXTEND_AREA / 2.0) + max_x = round(max(ox) + EXTEND_AREA / 2.0) + max_y = round(max(oy) + EXTEND_AREA / 2.0) + xw = int(round((max_x - min_x) / xy_resolution)) + yw = int(round((max_y - min_y) / xy_resolution)) print("The grid map is ", xw, "x", yw, ".") - return minx, miny, maxx, maxy, xw, yw + return min_x, min_y, max_x, max_y, xw, yw def atan_zero_to_twopi(y, x): @@ -94,96 +97,110 @@ def atan_zero_to_twopi(y, x): return angle -def init_floodfill(cpoint, opoints, xypoints, mincoord, xyreso): +def init_flood_fill(center_point, obstacle_points, xy_points, min_coord, + xy_resolution): """ - cpoint: center point - opoints: detected obstacles points (x,y) - xypoints: (x,y) point pairs + center_point: center point + obstacle_points: detected obstacles points (x,y) + xy_points: (x,y) point pairs """ - centix, centiy = cpoint - prev_ix, prev_iy = centix - 1, centiy - ox, oy = opoints - xw, yw = xypoints - minx, miny = mincoord - pmap = (np.ones((xw, yw))) * 0.5 + center_x, center_y = center_point + prev_ix, prev_iy = center_x - 1, center_y + ox, oy = obstacle_points + xw, yw = xy_points + min_x, min_y = min_coord + occupancy_map = (np.ones((xw, yw))) * 0.5 for (x, y) in zip(ox, oy): - ix = int(round((x - minx) / xyreso)) # x coordinate of the the occupied area - iy = int(round((y - miny) / xyreso)) # y coordinate of the the occupied area + # x coordinate of the the occupied area + ix = int(round((x - min_x) / xy_resolution)) + # y coordinate of the the occupied area + iy = int(round((y - min_y) / xy_resolution)) free_area = bresenham((prev_ix, prev_iy), (ix, iy)) for fa in free_area: - pmap[fa[0]][fa[1]] = 0 # free area 0.0 + occupancy_map[fa[0]][fa[1]] = 0 # free area 0.0 prev_ix = ix prev_iy = iy - return pmap + return occupancy_map -def flood_fill(cpoint, pmap): +def flood_fill(center_point, occupancy_map): """ - cpoint: starting point (x,y) of fill - pmap: occupancy map generated from Bresenham ray-tracing + center_point: starting point (x,y) of fill + occupancy_map: occupancy map generated from Bresenham ray-tracing """ # Fill empty areas with queue method - sx, sy = pmap.shape + sx, sy = occupancy_map.shape fringe = deque() - fringe.appendleft(cpoint) + fringe.appendleft(center_point) while fringe: n = fringe.pop() nx, ny = n # West if nx > 0: - if pmap[nx - 1, ny] == 0.5: - pmap[nx - 1, ny] = 0.0 + if occupancy_map[nx - 1, ny] == 0.5: + occupancy_map[nx - 1, ny] = 0.0 fringe.appendleft((nx - 1, ny)) # East if nx < sx - 1: - if pmap[nx + 1, ny] == 0.5: - pmap[nx + 1, ny] = 0.0 + if occupancy_map[nx + 1, ny] == 0.5: + occupancy_map[nx + 1, ny] = 0.0 fringe.appendleft((nx + 1, ny)) # North if ny > 0: - if pmap[nx, ny - 1] == 0.5: - pmap[nx, ny - 1] = 0.0 + if occupancy_map[nx, ny - 1] == 0.5: + occupancy_map[nx, ny - 1] = 0.0 fringe.appendleft((nx, ny - 1)) # South if ny < sy - 1: - if pmap[nx, ny + 1] == 0.5: - pmap[nx, ny + 1] = 0.0 + if occupancy_map[nx, ny + 1] == 0.5: + occupancy_map[nx, ny + 1] = 0.0 fringe.appendleft((nx, ny + 1)) -def generate_ray_casting_grid_map(ox, oy, xyreso, breshen=True): +def generate_ray_casting_grid_map(ox, oy, xy_resolution, breshen=True): """ - The breshen boolean tells if it's computed with bresenham ray casting (True) or with flood fill (False) + The breshen boolean tells if it's computed with bresenham ray casting + (True) or with flood fill (False) """ - minx, miny, maxx, maxy, xw, yw = calc_grid_map_config(ox, oy, xyreso) - pmap = np.ones((xw, yw))/2 # default 0.5 -- [[0.5 for i in range(yw)] for i in range(xw)] - centix = int(round(-minx / xyreso)) # center x coordinate of the grid map - centiy = int(round(-miny / xyreso)) # center y coordinate of the grid map + min_x, min_y, max_x, max_y, x_w, y_w = calc_grid_map_config( + ox, oy, xy_resolution) + # default 0.5 -- [[0.5 for i in range(y_w)] for i in range(x_w)] + occupancy_map = np.ones((x_w, y_w)) / 2 + center_x = int( + round(-min_x / xy_resolution)) # center x coordinate of the grid map + center_y = int( + round(-min_y / xy_resolution)) # center y coordinate of the grid map # occupancy grid computed with bresenham ray casting if breshen: for (x, y) in zip(ox, oy): - ix = int(round((x - minx) / xyreso)) # x coordinate of the the occupied area - iy = int(round((y - miny) / xyreso)) # y coordinate of the the occupied area - laser_beams = bresenham((centix, centiy), (ix, iy)) # line form the lidar to the cooupied point + # x coordinate of the the occupied area + ix = int(round((x - min_x) / xy_resolution)) + # y coordinate of the the occupied area + iy = int(round((y - min_y) / xy_resolution)) + laser_beams = bresenham((center_x, center_y), ( + ix, iy)) # line form the lidar to the occupied point for laser_beam in laser_beams: - pmap[laser_beam[0]][laser_beam[1]] = 0.0 # free area 0.0 - pmap[ix][iy] = 1.0 # occupied area 1.0 - pmap[ix+1][iy] = 1.0 # extend the occupied area - pmap[ix][iy+1] = 1.0 # extend the occupied area - pmap[ix+1][iy+1] = 1.0 # extend the occupied area + occupancy_map[laser_beam[0]][ + laser_beam[1]] = 0.0 # free area 0.0 + occupancy_map[ix][iy] = 1.0 # occupied area 1.0 + occupancy_map[ix + 1][iy] = 1.0 # extend the occupied area + occupancy_map[ix][iy + 1] = 1.0 # extend the occupied area + occupancy_map[ix + 1][iy + 1] = 1.0 # extend the occupied area # occupancy grid computed with with flood fill else: - pmap = init_floodfill((centix, centiy), (ox, oy), (xw, yw), (minx, miny), xyreso) - flood_fill((centix, centiy), pmap) - pmap = np.array(pmap, dtype=np.float) + occupancy_map = init_flood_fill((center_x, center_y), (ox, oy), + (x_w, y_w), + (min_x, min_y), xy_resolution) + flood_fill((center_x, center_y), occupancy_map) + occupancy_map = np.array(occupancy_map, dtype=np.float) for (x, y) in zip(ox, oy): - ix = int(round((x - minx) / xyreso)) - iy = int(round((y - miny) / xyreso)) - pmap[ix][iy] = 1.0 # occupied area 1.0 - pmap[ix+1][iy] = 1.0 # extend the occupied area - pmap[ix][iy+1] = 1.0 # extend the occupied area - pmap[ix+1][iy+1] = 1.0 # extend the occupied area - return pmap, minx, maxx, miny, maxy, xyreso + ix = int(round((x - min_x) / xy_resolution)) + iy = int(round((y - min_y) / xy_resolution)) + occupancy_map[ix][iy] = 1.0 # occupied area 1.0 + occupancy_map[ix + 1][iy] = 1.0 # extend the occupied area + occupancy_map[ix][iy + 1] = 1.0 # extend the occupied area + occupancy_map[ix + 1][iy + 1] = 1.0 # extend the occupied area + return occupancy_map, min_x, max_x, min_y, max_y, xy_resolution def main(): @@ -191,18 +208,20 @@ def main(): Example usage """ print(__file__, "start") - xyreso = 0.02 # x-y grid resolution + xy_resolution = 0.02 # x-y grid resolution ang, dist = file_read("lidar01.csv") ox = np.sin(ang) * dist oy = np.cos(ang) * dist - pmap, minx, maxx, miny, maxy, xyreso = generate_ray_casting_grid_map(ox, oy, xyreso, True) - xyres = np.array(pmap).shape - plt.figure(1, figsize=(10,4)) + occupancy_map, min_x, max_x, min_y, max_y, xy_resolution = \ + generate_ray_casting_grid_map(ox, oy, xy_resolution, True) + xy_res = np.array(occupancy_map).shape + plt.figure(1, figsize=(10, 4)) plt.subplot(122) - plt.imshow(pmap, cmap="PiYG_r") # cmap = "binary" "PiYG_r" "PiYG_r" "bone" "bone_r" "RdYlGn_r" + plt.imshow(occupancy_map, cmap="PiYG_r") + # cmap = "binary" "PiYG_r" "PiYG_r" "bone" "bone_r" "RdYlGn_r" plt.clim(-0.4, 1.4) - plt.gca().set_xticks(np.arange(-.5, xyres[1], 1), minor=True) - plt.gca().set_yticks(np.arange(-.5, xyres[0], 1), minor=True) + plt.gca().set_xticks(np.arange(-.5, xy_res[1], 1), minor=True) + plt.gca().set_yticks(np.arange(-.5, xy_res[0], 1), minor=True) plt.grid(True, which="minor", color="w", linewidth=0.6, alpha=0.5) plt.colorbar() plt.subplot(121) @@ -210,11 +229,11 @@ def main(): plt.axis("equal") plt.plot(0.0, 0.0, "ob") plt.gca().set_aspect("equal", "box") - bottom, top = plt.ylim() # return the current ylim - plt.ylim((top, bottom)) # rescale y axis, to match the grid orientation + bottom, top = plt.ylim() # return the current y-lim + plt.ylim((top, bottom)) # rescale y axis, to match the grid orientation plt.grid(True) plt.show() - + if __name__ == '__main__': - main() + main() diff --git a/Mapping/rectangle_fitting/rectangle_fitting.py b/Mapping/rectangle_fitting/rectangle_fitting.py index 1a2a534093..ae41b3c53e 100644 --- a/Mapping/rectangle_fitting/rectangle_fitting.py +++ b/Mapping/rectangle_fitting/rectangle_fitting.py @@ -5,7 +5,10 @@ author: Atsushi Sakai (@Atsushi_twi) Ref: -- [Efficient L\-Shape Fitting for Vehicle Detection Using Laser Scanners \- The Robotics Institute Carnegie Mellon University](https://www.ri.cmu.edu/publications/efficient-l-shape-fitting-for-vehicle-detection-using-laser-scanners/) +- Efficient L-Shape Fitting for Vehicle Detection Using Laser Scanners - +The Robotics Institute Carnegie Mellon University +https://www.ri.cmu.edu/publications/ +efficient-l-shape-fitting-for-vehicle-detection-using-laser-scanners/ """ @@ -13,13 +16,14 @@ import numpy as np import itertools from enum import Enum +from scipy.spatial.transform import Rotation as Rot from simulator import VehicleSimulator, LidarSimulator show_animation = True -class LShapeFitting(): +class LShapeFitting: class Criteria(Enum): AREA = 1 @@ -29,26 +33,27 @@ class Criteria(Enum): def __init__(self): # Parameters self.criteria = self.Criteria.VARIANCE - self.min_dist_of_closeness_crit = 0.01 # [m] - self.dtheta_deg_for_serarch = 1.0 # [deg] + self.min_dist_of_closeness_criteria = 0.01 # [m] + self.d_theta_deg_for_search = 1.0 # [deg] self.R0 = 3.0 # [m] range segmentation param self.Rd = 0.001 # [m] range segmentation param def fitting(self, ox, oy): # step1: Adaptive Range Segmentation - idsets = self._adoptive_range_segmentation(ox, oy) + id_sets = self._adoptive_range_segmentation(ox, oy) # step2 Rectangle search rects = [] - for ids in idsets: # for each cluster + for ids in id_sets: # for each cluster cx = [ox[i] for i in range(len(ox)) if i in ids] cy = [oy[i] for i in range(len(oy)) if i in ids] rects.append(self._rectangle_search(cx, cy)) - return rects, idsets + return rects, id_sets - def _calc_area_criterion(self, c1, c2): + @staticmethod + def _calc_area_criterion(c1, c2): c1_max = max(c1) c2_max = max(c2) c1_min = min(c1) @@ -71,12 +76,13 @@ def _calc_closeness_criterion(self, c1, c2): beta = 0 for i, _ in enumerate(D1): - d = max(min([D1[i], D2[i]]), self.min_dist_of_closeness_crit) + d = max(min([D1[i], D2[i]]), self.min_dist_of_closeness_criteria) beta += (1.0 / d) return beta - def _calc_variance_criterion(self, c1, c2): + @staticmethod + def _calc_variance_criterion(c1, c2): c1_max = max(c1) c2_max = max(c2) c1_min = min(c1) @@ -110,17 +116,17 @@ def _rectangle_search(self, x, y): X = np.array([x, y]).T - dtheta = np.deg2rad(self.dtheta_deg_for_serarch) - minp = (-float('inf'), None) - for theta in np.arange(0.0, np.pi / 2.0 - dtheta, dtheta): + d_theta = np.deg2rad(self.d_theta_deg_for_search) + min_cost = (-float('inf'), None) + for theta in np.arange(0.0, np.pi / 2.0 - d_theta, d_theta): - e1 = np.array([np.cos(theta), np.sin(theta)]) - e2 = np.array([-np.sin(theta), np.cos(theta)]) - - c1 = X @ e1.T - c2 = X @ e2.T + rot = Rot.from_euler('z', theta).as_matrix()[0:2, 0:2] + c = X @ rot + c1 = c[:, 0] + c2 = c[:, 1] # Select criteria + cost = 0.0 if self.criteria == self.Criteria.AREA: cost = self._calc_area_criterion(c1, c2) elif self.criteria == self.Criteria.CLOSENESS: @@ -128,12 +134,12 @@ def _rectangle_search(self, x, y): elif self.criteria == self.Criteria.VARIANCE: cost = self._calc_variance_criterion(c1, c2) - if minp[0] < cost: - minp = (cost, theta) + if min_cost[0] < cost: + min_cost = (cost, theta) # calc best rectangle - sin_s = np.sin(minp[1]) - cos_s = np.cos(minp[1]) + sin_s = np.sin(min_cost[1]) + cos_s = np.cos(min_cost[1]) c1_s = X @ np.array([cos_s, sin_s]).T c2_s = X @ np.array([-sin_s, cos_s]).T @@ -181,7 +187,7 @@ def _adoptive_range_segmentation(self, ox, oy): return S -class RectangleData(): +class RectangleData: def __init__(self): self.a = [None] * 4 @@ -207,7 +213,8 @@ def calc_rect_contour(self): [self.a[3], self.a[0]], [self.b[3], self.b[0]], [self.c[3], self.c[0]]) self.rect_c_x[4], self.rect_c_y[4] = self.rect_c_x[0], self.rect_c_y[0] - def calc_cross_point(self, a, b, c): + @staticmethod + def calc_cross_point(a, b, c): x = (b[0] * -c[1] - b[1] * -c[0]) / (a[0] * b[1] - a[1] * b[0]) y = (a[1] * -c[0] - a[0] * -c[1]) / (a[0] * b[1] - a[1] * b[0]) return x, y @@ -216,42 +223,43 @@ def calc_cross_point(self, a, b, c): def main(): # simulation parameters - simtime = 30.0 # simulation time + sim_time = 30.0 # simulation time dt = 0.2 # time tick - angle_reso = np.deg2rad(3.0) # sensor angle resolution + angle_resolution = np.deg2rad(3.0) # sensor angle resolution v1 = VehicleSimulator(-10.0, 0.0, np.deg2rad(90.0), 0.0, 50.0 / 3.6, 3.0, 5.0) v2 = VehicleSimulator(20.0, 10.0, np.deg2rad(180.0), 0.0, 50.0 / 3.6, 4.0, 10.0) - lshapefitting = LShapeFitting() + l_shape_fitting = LShapeFitting() lidar_sim = LidarSimulator() time = 0.0 - while time <= simtime: + while time <= sim_time: time += dt v1.update(dt, 0.1, 0.0) v2.update(dt, 0.1, -0.05) - ox, oy = lidar_sim.get_observation_points([v1, v2], angle_reso) + ox, oy = lidar_sim.get_observation_points([v1, v2], angle_resolution) - rects, idsets = lshapefitting.fitting(ox, oy) + rects, id_sets = l_shape_fitting.fitting(ox, oy) if show_animation: # pragma: no cover plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.axis("equal") plt.plot(0.0, 0.0, "*r") v1.plot() v2.plot() # Plot range observation - for ids in idsets: + for ids in id_sets: x = [ox[i] for i in range(len(ox)) if i in ids] y = [oy[i] for i in range(len(ox)) if i in ids] diff --git a/Mapping/rectangle_fitting/simulator.py b/Mapping/rectangle_fitting/simulator.py index b21d4003a8..c7c3141fa9 100644 --- a/Mapping/rectangle_fitting/simulator.py +++ b/Mapping/rectangle_fitting/simulator.py @@ -10,15 +10,16 @@ import matplotlib.pyplot as plt import math import random +from scipy.spatial.transform import Rotation as Rot -class VehicleSimulator(): +class VehicleSimulator: - def __init__(self, ix, iy, iyaw, iv, max_v, w, L): - self.x = ix - self.y = iy - self.yaw = iyaw - self.v = iv + def __init__(self, i_x, i_y, i_yaw, i_v, max_v, w, L): + self.x = i_x + self.y = i_y + self.yaw = i_yaw + self.v = i_v self.max_v = max_v self.W = w self.L = L @@ -40,10 +41,10 @@ def plot(self): plt.plot(gx, gy, "--b") def calc_global_contour(self): - gx = [(ix * np.cos(self.yaw) + iy * np.sin(self.yaw)) + - self.x for (ix, iy) in zip(self.vc_x, self.vc_y)] - gy = [(ix * np.sin(self.yaw) - iy * np.cos(self.yaw)) + - self.y for (ix, iy) in zip(self.vc_x, self.vc_y)] + rot = Rot.from_euler('z', self.yaw).as_matrix()[0:2, 0:2] + gxy = np.stack([self.vc_x, self.vc_y]).T @ rot + gx = gxy[:, 0] + self.x + gy = gxy[:, 1] + self.y return gx, gy @@ -67,69 +68,71 @@ def _calc_vehicle_contour(self): self.vc_x.append(self.L / 2.0) self.vc_y.append(self.W / 2.0) - self.vc_x, self.vc_y = self._interporate(self.vc_x, self.vc_y) + self.vc_x, self.vc_y = self._interpolate(self.vc_x, self.vc_y) - def _interporate(self, x, y): + @staticmethod + def _interpolate(x, y): rx, ry = [], [] - dtheta = 0.05 + d_theta = 0.05 for i in range(len(x) - 1): - rx.extend([(1.0 - θ) * x[i] + θ * x[i + 1] - for θ in np.arange(0.0, 1.0, dtheta)]) - ry.extend([(1.0 - θ) * y[i] + θ * y[i + 1] - for θ in np.arange(0.0, 1.0, dtheta)]) + rx.extend([(1.0 - theta) * x[i] + theta * x[i + 1] + for theta in np.arange(0.0, 1.0, d_theta)]) + ry.extend([(1.0 - theta) * y[i] + theta * y[i + 1] + for theta in np.arange(0.0, 1.0, d_theta)]) - rx.extend([(1.0 - θ) * x[len(x) - 1] + θ * x[1] - for θ in np.arange(0.0, 1.0, dtheta)]) - ry.extend([(1.0 - θ) * y[len(y) - 1] + θ * y[1] - for θ in np.arange(0.0, 1.0, dtheta)]) + rx.extend([(1.0 - theta) * x[len(x) - 1] + theta * x[1] + for theta in np.arange(0.0, 1.0, d_theta)]) + ry.extend([(1.0 - theta) * y[len(y) - 1] + theta * y[1] + for theta in np.arange(0.0, 1.0, d_theta)]) return rx, ry -class LidarSimulator(): +class LidarSimulator: def __init__(self): self.range_noise = 0.01 - def get_observation_points(self, vlist, angle_reso): + def get_observation_points(self, v_list, angle_resolution): x, y, angle, r = [], [], [], [] # store all points - for v in vlist: + for v in v_list: gx, gy = v.calc_global_contour() for vx, vy in zip(gx, gy): - vangle = math.atan2(vy, vx) + v_angle = math.atan2(vy, vx) vr = np.hypot(vx, vy) * random.uniform(1.0 - self.range_noise, 1.0 + self.range_noise) x.append(vx) y.append(vy) - angle.append(vangle) + angle.append(v_angle) r.append(vr) # ray casting filter - rx, ry = self.ray_casting_filter(x, y, angle, r, angle_reso) + rx, ry = self.ray_casting_filter(angle, r, angle_resolution) return rx, ry - def ray_casting_filter(self, xl, yl, thetal, rangel, angle_reso): + @staticmethod + def ray_casting_filter(theta_l, range_l, angle_resolution): rx, ry = [], [] - rangedb = [float("inf") for _ in range( - int(np.floor((np.pi * 2.0) / angle_reso)) + 1)] + range_db = [float("inf") for _ in range( + int(np.floor((np.pi * 2.0) / angle_resolution)) + 1)] - for i in range(len(thetal)): - angleid = int(round(thetal[i] / angle_reso)) + for i in range(len(theta_l)): + angle_id = int(round(theta_l[i] / angle_resolution)) - if rangedb[angleid] > rangel[i]: - rangedb[angleid] = rangel[i] + if range_db[angle_id] > range_l[i]: + range_db[angle_id] = range_l[i] - for i in range(len(rangedb)): - t = i * angle_reso - if rangedb[i] != float("inf"): - rx.append(rangedb[i] * np.cos(t)) - ry.append(rangedb[i] * np.sin(t)) + for i in range(len(range_db)): + t = i * angle_resolution + if range_db[i] != float("inf"): + rx.append(range_db[i] * np.cos(t)) + ry.append(range_db[i] * np.sin(t)) return rx, ry diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py index 14c51ad9a1..eb2672a9ce 100644 --- a/PathPlanning/AStar/a_star.py +++ b/PathPlanning/AStar/a_star.py @@ -18,39 +18,43 @@ class AStarPlanner: - def __init__(self, ox, oy, reso, rr): + def __init__(self, ox, oy, resolution, rr): """ Initialize grid map for a star planning ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] - reso: grid resolution [m] + resolution: grid resolution [m] rr: robot radius[m] """ - self.reso = reso + self.resolution = resolution self.rr = rr - self.calc_obstacle_map(ox, oy) + self.min_x, self.min_y = 0, 0 + self.max_x, self.max_y = 0, 0 + self.obstacle_map = None + self.x_width, self.y_width = 0, 0 self.motion = self.get_motion_model() + self.calc_obstacle_map(ox, oy) class Node: - def __init__(self, x, y, cost, pind): + def __init__(self, x, y, cost, parent_index): self.x = x # index of grid self.y = y # index of grid self.cost = cost - self.pind = pind + self.parent_index = parent_index def __str__(self): return str(self.x) + "," + str(self.y) + "," + str( - self.cost) + "," + str(self.pind) + self.cost) + "," + str(self.parent_index) def planning(self, sx, sy, gx, gy): """ A star path search input: - sx: start x position [m] - sy: start y position [m] + s_x: start x position [m] + s_y: start y position [m] gx: goal x position [m] gy: goal y position [m] @@ -59,13 +63,13 @@ def planning(self, sx, sy, gx, gy): ry: y position list of the final path """ - nstart = self.Node(self.calc_xyindex(sx, self.minx), - self.calc_xyindex(sy, self.miny), 0.0, -1) - ngoal = self.Node(self.calc_xyindex(gx, self.minx), - self.calc_xyindex(gy, self.miny), 0.0, -1) + start_node = self.Node(self.calc_xy_index(sx, self.min_x), + self.calc_xy_index(sy, self.min_y), 0.0, -1) + goal_node = self.Node(self.calc_xy_index(gx, self.min_x), + self.calc_xy_index(gy, self.min_y), 0.0, -1) open_set, closed_set = dict(), dict() - open_set[self.calc_grid_index(nstart)] = nstart + open_set[self.calc_grid_index(start_node)] = start_node while 1: if len(open_set) == 0: @@ -74,15 +78,15 @@ def planning(self, sx, sy, gx, gy): c_id = min( open_set, - key=lambda o: open_set[o].cost + self.calc_heuristic(ngoal, + key=lambda o: open_set[o].cost + self.calc_heuristic(goal_node, open_set[ o])) current = open_set[c_id] # show graph if show_animation: # pragma: no cover - plt.plot(self.calc_grid_position(current.x, self.minx), - self.calc_grid_position(current.y, self.miny), "xc") + plt.plot(self.calc_grid_position(current.x, self.min_x), + self.calc_grid_position(current.y, self.min_y), "xc") # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect('key_release_event', lambda event: [exit( @@ -90,10 +94,10 @@ def planning(self, sx, sy, gx, gy): if len(closed_set.keys()) % 10 == 0: plt.pause(0.001) - if current.x == ngoal.x and current.y == ngoal.y: + if current.x == goal_node.x and current.y == goal_node.y: print("Find goal") - ngoal.pind = current.pind - ngoal.cost = current.cost + goal_node.parent_index = current.parent_index + goal_node.cost = current.cost break # Remove the item from the open set @@ -123,20 +127,20 @@ def planning(self, sx, sy, gx, gy): # This path is the best until now. record it open_set[n_id] = node - rx, ry = self.calc_final_path(ngoal, closed_set) + rx, ry = self.calc_final_path(goal_node, closed_set) return rx, ry - def calc_final_path(self, ngoal, closedset): + def calc_final_path(self, goal_node, closed_set): # generate final course - rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ - self.calc_grid_position(ngoal.y, self.miny)] - pind = ngoal.pind - while pind != -1: - n = closedset[pind] - rx.append(self.calc_grid_position(n.x, self.minx)) - ry.append(self.calc_grid_position(n.y, self.miny)) - pind = n.pind + rx, ry = [self.calc_grid_position(goal_node.x, self.min_x)], [ + self.calc_grid_position(goal_node.y, self.min_y)] + parent_index = goal_node.parent_index + while parent_index != -1: + n = closed_set[parent_index] + rx.append(self.calc_grid_position(n.x, self.min_x)) + ry.append(self.calc_grid_position(n.y, self.min_y)) + parent_index = n.parent_index return rx, ry @@ -146,69 +150,69 @@ def calc_heuristic(n1, n2): d = w * math.hypot(n1.x - n2.x, n1.y - n2.y) return d - def calc_grid_position(self, index, minp): + def calc_grid_position(self, index, min_position): """ calc grid position :param index: - :param minp: + :param min_position: :return: """ - pos = index * self.reso + minp + pos = index * self.resolution + min_position return pos - def calc_xyindex(self, position, min_pos): - return round((position - min_pos) / self.reso) + def calc_xy_index(self, position, min_pos): + return round((position - min_pos) / self.resolution) def calc_grid_index(self, node): - return (node.y - self.miny) * self.xwidth + (node.x - self.minx) + return (node.y - self.min_y) * self.x_width + (node.x - self.min_x) def verify_node(self, node): - px = self.calc_grid_position(node.x, self.minx) - py = self.calc_grid_position(node.y, self.miny) + px = self.calc_grid_position(node.x, self.min_x) + py = self.calc_grid_position(node.y, self.min_y) - if px < self.minx: + if px < self.min_x: return False - elif py < self.miny: + elif py < self.min_y: return False - elif px >= self.maxx: + elif px >= self.max_x: return False - elif py >= self.maxy: + elif py >= self.max_y: return False # collision check - if self.obmap[node.x][node.y]: + if self.obstacle_map[node.x][node.y]: return False return True def calc_obstacle_map(self, ox, oy): - self.minx = round(min(ox)) - self.miny = round(min(oy)) - self.maxx = round(max(ox)) - self.maxy = round(max(oy)) - print("minx:", self.minx) - print("miny:", self.miny) - print("maxx:", self.maxx) - print("maxy:", self.maxy) + self.min_x = round(min(ox)) + self.min_y = round(min(oy)) + self.max_x = round(max(ox)) + self.max_y = round(max(oy)) + print("min_x:", self.min_x) + print("min_y:", self.min_y) + print("max_x:", self.max_x) + print("max_y:", self.max_y) - self.xwidth = round((self.maxx - self.minx) / self.reso) - self.ywidth = round((self.maxy - self.miny) / self.reso) - print("xwidth:", self.xwidth) - print("ywidth:", self.ywidth) + self.x_width = round((self.max_x - self.min_x) / self.resolution) + self.y_width = round((self.max_y - self.min_y) / self.resolution) + print("x_width:", self.x_width) + print("y_width:", self.y_width) # obstacle map generation - self.obmap = [[False for i in range(self.ywidth)] - for i in range(self.xwidth)] - for ix in range(self.xwidth): - x = self.calc_grid_position(ix, self.minx) - for iy in range(self.ywidth): - y = self.calc_grid_position(iy, self.miny) + self.obstacle_map = [[False for _ in range(self.y_width)] + for _ in range(self.x_width)] + for ix in range(self.x_width): + x = self.calc_grid_position(ix, self.min_x) + for iy in range(self.y_width): + y = self.calc_grid_position(iy, self.min_y) for iox, ioy in zip(ox, oy): d = math.hypot(iox - x, ioy - y) if d <= self.rr: - self.obmap[ix][iy] = True + self.obstacle_map[ix][iy] = True break @staticmethod @@ -270,8 +274,8 @@ def main(): if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") - plt.show() plt.pause(0.001) + plt.show() if __name__ == '__main__': diff --git a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py index 65d1fc31a7..cf76ab67cd 100644 --- a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py +++ b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py @@ -23,7 +23,7 @@ def __init__(self, ox, oy, reso, rr): ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] - reso: grid resolution [m] + resolution: grid resolution [m] rr: robot radius[m] """ @@ -48,8 +48,8 @@ def planning(self, sx, sy, gx, gy): Bidirectional A star path search input: - sx: start x position [m] - sy: start y position [m] + s_x: start x position [m] + s_y: start y position [m] gx: goal x position [m] gy: goal y position [m] @@ -179,12 +179,12 @@ def calc_final_path(self, ngoal, closedset): # generate final course rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ self.calc_grid_position(ngoal.y, self.miny)] - pind = ngoal.pind + pind = ngoal.parent_index while pind != -1: n = closedset[pind] rx.append(self.calc_grid_position(n.x, self.minx)) ry.append(self.calc_grid_position(n.y, self.miny)) - pind = n.pind + pind = n.parent_index return rx, ry @@ -252,15 +252,15 @@ def calc_obstacle_map(self, ox, oy): self.miny = round(min(oy)) self.maxx = round(max(ox)) self.maxy = round(max(oy)) - print("minx:", self.minx) - print("miny:", self.miny) - print("maxx:", self.maxx) - print("maxy:", self.maxy) + print("min_x:", self.minx) + print("min_y:", self.miny) + print("max_x:", self.maxx) + print("max_y:", self.maxy) self.xwidth = round((self.maxx - self.minx) / self.reso) self.ywidth = round((self.maxy - self.miny) / self.reso) - print("xwidth:", self.xwidth) - print("ywidth:", self.ywidth) + print("x_width:", self.xwidth) + print("y_width:", self.ywidth) # obstacle map generation self.obmap = [[False for _ in range(self.ywidth)] diff --git a/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py b/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py index d29112eb65..328898db85 100644 --- a/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py +++ b/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py @@ -23,7 +23,7 @@ def __init__(self, ox, oy, reso, rr): ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] - reso: grid resolution [m] + resolution: grid resolution [m] rr: robot radius[m] """ @@ -49,8 +49,8 @@ def planning(self, sx, sy, gx, gy): Bidirectional Breadth First search based planning input: - sx: start x position [m] - sy: start y position [m] + s_x: start x position [m] + s_y: start y position [m] gx: goal x position [m] gy: goal y position [m] @@ -170,7 +170,7 @@ def calc_final_path(self, ngoal, closedset): # generate final course rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ self.calc_grid_position(ngoal.y, self.miny)] - n = closedset[ngoal.pind] + n = closedset[ngoal.parent_index] while n is not None: rx.append(self.calc_grid_position(n.x, self.minx)) ry.append(self.calc_grid_position(n.y, self.miny)) @@ -220,15 +220,15 @@ def calc_obstacle_map(self, ox, oy): self.miny = round(min(oy)) self.maxx = round(max(ox)) self.maxy = round(max(oy)) - print("minx:", self.minx) - print("miny:", self.miny) - print("maxx:", self.maxx) - print("maxy:", self.maxy) + print("min_x:", self.minx) + print("min_y:", self.miny) + print("max_x:", self.maxx) + print("max_y:", self.maxy) self.xwidth = round((self.maxx - self.minx) / self.reso) self.ywidth = round((self.maxy - self.miny) / self.reso) - print("xwidth:", self.xwidth) - print("ywidth:", self.ywidth) + print("x_width:", self.xwidth) + print("y_width:", self.ywidth) # obstacle map generation self.obmap = [[False for _ in range(self.ywidth)] diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index 198ddd2e3d..01f1a31d64 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -23,7 +23,7 @@ def __init__(self, ox, oy, reso, rr): ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] - reso: grid resolution [m] + resolution: grid resolution [m] rr: robot radius[m] """ @@ -49,8 +49,8 @@ def planning(self, sx, sy, gx, gy): Breadth First search based planning input: - sx: start x position [m] - sy: start y position [m] + s_x: start x position [m] + s_y: start y position [m] gx: goal x position [m] gy: goal y position [m] @@ -118,7 +118,7 @@ def calc_final_path(self, ngoal, closedset): # generate final course rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ self.calc_grid_position(ngoal.y, self.miny)] - n = closedset[ngoal.pind] + n = closedset[ngoal.parent_index] while n is not None: rx.append(self.calc_grid_position(n.x, self.minx)) ry.append(self.calc_grid_position(n.y, self.miny)) @@ -168,15 +168,15 @@ def calc_obstacle_map(self, ox, oy): self.miny = round(min(oy)) self.maxx = round(max(ox)) self.maxy = round(max(oy)) - print("minx:", self.minx) - print("miny:", self.miny) - print("maxx:", self.maxx) - print("maxy:", self.maxy) + print("min_x:", self.minx) + print("min_y:", self.miny) + print("max_x:", self.maxx) + print("max_y:", self.maxy) self.xwidth = round((self.maxx - self.minx) / self.reso) self.ywidth = round((self.maxy - self.miny) / self.reso) - print("xwidth:", self.xwidth) - print("ywidth:", self.ywidth) + print("x_width:", self.xwidth) + print("y_width:", self.ywidth) # obstacle map generation self.obmap = [[False for _ in range(self.ywidth)] diff --git a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py index a413a05d7f..f3984f87b0 100644 --- a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py +++ b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py @@ -40,7 +40,7 @@ def pure_pursuit_control(state, cx, cy, pind): if pind >= ind: ind = pind - # print(pind, ind) + # print(parent_index, ind) if ind < len(cx): tx = cx[ind] ty = cy[ind] @@ -181,12 +181,12 @@ def set_stop_point(target_speed, cx, cy, cyaw): speed_profile[i] = 0.0 forward = False # plt.plot(cx[i], cy[i], "xb") - # print(iyaw, move_direction, dx, dy) + # print(i_yaw, move_direction, dx, dy) elif not is_back and not forward: speed_profile[i] = 0.0 forward = True # plt.plot(cx[i], cy[i], "xb") - # print(iyaw, move_direction, dx, dy) + # print(i_yaw, move_direction, dx, dy) speed_profile[0] = 0.0 if is_back: speed_profile[-1] = -stop_speed diff --git a/PathPlanning/DepthFirstSearch/depth_first_search.py b/PathPlanning/DepthFirstSearch/depth_first_search.py index 229eb70c2d..c8d2d5eaba 100644 --- a/PathPlanning/DepthFirstSearch/depth_first_search.py +++ b/PathPlanning/DepthFirstSearch/depth_first_search.py @@ -23,7 +23,7 @@ def __init__(self, ox, oy, reso, rr): ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] - reso: grid resolution [m] + resolution: grid resolution [m] rr: robot radius[m] """ @@ -49,8 +49,8 @@ def planning(self, sx, sy, gx, gy): Depth First search input: - sx: start x position [m] - sy: start y position [m] + s_x: start x position [m] + s_y: start y position [m] gx: goal x position [m] gy: goal y position [m] @@ -115,7 +115,7 @@ def calc_final_path(self, ngoal, closedset): # generate final course rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ self.calc_grid_position(ngoal.y, self.miny)] - n = closedset[ngoal.pind] + n = closedset[ngoal.parent_index] while n is not None: rx.append(self.calc_grid_position(n.x, self.minx)) ry.append(self.calc_grid_position(n.y, self.miny)) @@ -165,15 +165,15 @@ def calc_obstacle_map(self, ox, oy): self.miny = round(min(oy)) self.maxx = round(max(ox)) self.maxy = round(max(oy)) - print("minx:", self.minx) - print("miny:", self.miny) - print("maxx:", self.maxx) - print("maxy:", self.maxy) + print("min_x:", self.minx) + print("min_y:", self.miny) + print("max_x:", self.maxx) + print("max_y:", self.maxy) self.xwidth = round((self.maxx - self.minx) / self.reso) self.ywidth = round((self.maxy - self.miny) / self.reso) - print("xwidth:", self.xwidth) - print("ywidth:", self.ywidth) + print("x_width:", self.xwidth) + print("y_width:", self.ywidth) # obstacle map generation self.obmap = [[False for _ in range(self.ywidth)] diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index 0ece712ae7..b744bc6fc7 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -53,8 +53,8 @@ def planning(self, sx, sy, gx, gy): dijkstra path search input: - sx: start x position [m] - sy: start y position [m] + s_x: start x position [m] + s_y: start y position [m] gx: goal x position [m] gx: goal x position [m] diff --git a/PathPlanning/DubinsPath/dubins_path_planning.py b/PathPlanning/DubinsPath/dubins_path_planning.py index b72801a6b3..9c13198aff 100644 --- a/PathPlanning/DubinsPath/dubins_path_planning.py +++ b/PathPlanning/DubinsPath/dubins_path_planning.py @@ -9,6 +9,7 @@ import matplotlib.pyplot as plt import numpy as np +from scipy.spatial.transform import Rotation as Rot show_animation = True @@ -136,7 +137,8 @@ def left_right_left(alpha, beta, d): return t, p, q, mode -def dubins_path_planning_from_origin(end_x, end_y, end_yaw, curvature, step_size): +def dubins_path_planning_from_origin(end_x, end_y, end_yaw, curvature, + step_size): dx = end_x dy = end_y D = math.hypot(dx, dy) @@ -146,7 +148,8 @@ def dubins_path_planning_from_origin(end_x, end_y, end_yaw, curvature, step_size alpha = mod2pi(- theta) beta = mod2pi(end_yaw - theta) - planners = [left_straight_left, right_straight_right, left_straight_right, right_straight_left, right_left_right, + planners = [left_straight_left, right_straight_right, left_straight_right, + right_straight_left, right_left_right, left_right_left] best_cost = float("inf") @@ -163,13 +166,14 @@ def dubins_path_planning_from_origin(end_x, end_y, end_yaw, curvature, step_size best_cost = cost lengths = [bt, bp, bq] - px, py, pyaw, directions = generate_local_course( + x_list, y_list, yaw_list, directions = generate_local_course( sum(lengths), lengths, best_mode, curvature, step_size) - return px, py, pyaw, best_mode, best_cost + return x_list, y_list, yaw_list, best_mode, best_cost -def interpolate(ind, length, mode, max_curvature, origin_x, origin_y, origin_yaw, path_x, path_y, path_yaw, directions): +def interpolate(ind, length, mode, max_curvature, origin_x, origin_y, + origin_yaw, path_x, path_y, path_yaw, directions): if mode == "S": path_x[ind] = origin_x + length / max_curvature * math.cos(origin_yaw) path_y[ind] = origin_y + length / max_curvature * math.sin(origin_yaw) @@ -199,54 +203,49 @@ def interpolate(ind, length, mode, max_curvature, origin_x, origin_y, origin_yaw return path_x, path_y, path_yaw, directions -def dubins_path_planning(sx, sy, syaw, ex, ey, eyaw, c, step_size=0.1): +def dubins_path_planning(s_x, s_y, s_yaw, g_x, g_y, g_yaw, c, step_size=0.1): """ - Dubins path plannner + Dubins path planner input: - sx x position of start point [m] - sy y position of start point [m] - syaw yaw angle of start point [rad] - ex x position of end point [m] - ey y position of end point [m] - eyaw yaw angle of end point [rad] + s_x x position of start point [m] + s_y y position of start point [m] + s_yaw yaw angle of start point [rad] + g_x x position of end point [m] + g_y y position of end point [m] + g_yaw yaw angle of end point [rad] c curvature [1/m] - output: - px - py - pyaw - mode - """ - ex = ex - sx - ey = ey - sy + g_x = g_x - s_x + g_y = g_y - s_y - lex = math.cos(syaw) * ex + math.sin(syaw) * ey - ley = - math.sin(syaw) * ex + math.cos(syaw) * ey - leyaw = eyaw - syaw + l_rot = Rot.from_euler('z', s_yaw).as_matrix()[0:2, 0:2] + le_xy = np.stack([g_x, g_y]).T @ l_rot + le_yaw = g_yaw - s_yaw - lpx, lpy, lpyaw, mode, clen = dubins_path_planning_from_origin( - lex, ley, leyaw, c, step_size) + lp_x, lp_y, lp_yaw, mode, lengths = dubins_path_planning_from_origin( + le_xy[0], le_xy[1], le_yaw, c, step_size) - px = [math.cos(-syaw) * x + math.sin(-syaw) - * y + sx for x, y in zip(lpx, lpy)] - py = [- math.sin(-syaw) * x + math.cos(-syaw) - * y + sy for x, y in zip(lpx, lpy)] - pyaw = [pi_2_pi(iyaw + syaw) for iyaw in lpyaw] + rot = Rot.from_euler('z', -s_yaw).as_matrix()[0:2, 0:2] + converted_xy = np.stack([lp_x, lp_y]).T @ rot + x_list = converted_xy[:, 0] + s_x + y_list = converted_xy[:, 1] + s_y + yaw_list = [pi_2_pi(i_yaw + s_yaw) for i_yaw in lp_yaw] - return px, py, pyaw, mode, clen + return x_list, y_list, yaw_list, mode, lengths -def generate_local_course(total_length, lengths, mode, max_curvature, step_size): +def generate_local_course(total_length, lengths, mode, max_curvature, + step_size): n_point = math.trunc(total_length / step_size) + len(lengths) + 4 path_x = [0.0 for _ in range(n_point)] path_y = [0.0 for _ in range(n_point)] path_yaw = [0.0 for _ in range(n_point)] directions = [0.0 for _ in range(n_point)] - ind = 1 + index = 1 if lengths[0] > 0.0: directions[0] = 1 @@ -262,25 +261,28 @@ def generate_local_course(total_length, lengths, mode, max_curvature, step_size) d = -step_size # set origin state - origin_x, origin_y, origin_yaw = path_x[ind], path_y[ind], path_yaw[ind] + origin_x, origin_y, origin_yaw = \ + path_x[index], path_y[index], path_yaw[index] - ind -= 1 + index -= 1 if i >= 1 and (lengths[i - 1] * lengths[i]) > 0: pd = - d - ll else: pd = d - ll while abs(pd) <= abs(l): - ind += 1 + index += 1 path_x, path_y, path_yaw, directions = interpolate( - ind, pd, m, max_curvature, origin_x, origin_y, origin_yaw, path_x, path_y, path_yaw, directions) + index, pd, m, max_curvature, origin_x, origin_y, origin_yaw, + path_x, path_y, path_yaw, directions) pd += d ll = l - pd - d # calc remain length - ind += 1 + index += 1 path_x, path_y, path_yaw, directions = interpolate( - ind, l, m, max_curvature, origin_x, origin_y, origin_yaw, path_x, path_y, path_yaw, directions) + index, l, m, max_curvature, origin_x, origin_y, origin_yaw, + path_x, path_y, path_yaw, directions) if len(path_x) <= 1: return [], [], [], [] @@ -295,14 +297,15 @@ def generate_local_course(total_length, lengths, mode, max_curvature, step_size) return path_x, path_y, path_yaw, directions -def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): # pragma: no cover +def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", + ec="k"): # pragma: no cover """ Plot arrow """ if not isinstance(x, float): - for (ix, iy, iyaw) in zip(x, y, yaw): - plot_arrow(ix, iy, iyaw) + for (i_x, i_y, i_yaw) in zip(x, y, yaw): + plot_arrow(i_x, i_y, i_yaw) else: plt.arrow(x, y, length * math.cos(yaw), length * math.sin(yaw), fc=fc, ec=ec, head_width=width, head_length=width) @@ -322,11 +325,12 @@ def main(): curvature = 1.0 - px, py, pyaw, mode, clen = dubins_path_planning(start_x, start_y, start_yaw, - end_x, end_y, end_yaw, curvature) + path_x, path_y, path_yaw, mode, path_length = dubins_path_planning( + start_x, start_y, start_yaw, + end_x, end_y, end_yaw, curvature) if show_animation: - plt.plot(px, py, label="final course " + "".join(mode)) + plt.plot(path_x, path_y, label="final course " + "".join(mode)) # plotting plot_arrow(start_x, start_y, start_yaw) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index b8395e5ff8..0df40410ab 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -41,11 +41,11 @@ def __init__(self): # robot parameter self.max_speed = 1.0 # [m/s] self.min_speed = -0.5 # [m/s] - self.max_yawrate = 40.0 * math.pi / 180.0 # [rad/s] + self.max_yaw_rate = 40.0 * math.pi / 180.0 # [rad/s] self.max_accel = 0.2 # [m/ss] - self.max_dyawrate = 40.0 * math.pi / 180.0 # [rad/ss] - self.v_reso = 0.01 # [m/s] - self.yawrate_reso = 0.1 * math.pi / 180.0 # [rad/s] + self.max_delta_yaw_rate = 40.0 * math.pi / 180.0 # [rad/ss] + self.v_resolution = 0.01 # [m/s] + self.yaw_rate_resolution = 0.1 * math.pi / 180.0 # [rad/s] self.dt = 0.1 # [s] Time tick for motion prediction self.predict_time = 3.0 # [s] self.to_goal_cost_gain = 0.15 @@ -93,15 +93,15 @@ def calc_dynamic_window(x, config): # Dynamic window from robot specification Vs = [config.min_speed, config.max_speed, - -config.max_yawrate, config.max_yawrate] + -config.max_yaw_rate, config.max_yaw_rate] # Dynamic window from motion model Vd = [x[3] - config.max_accel * config.dt, x[3] + config.max_accel * config.dt, - x[4] - config.max_dyawrate * config.dt, - x[4] + config.max_dyawrate * config.dt] + x[4] - config.max_delta_yaw_rate * config.dt, + x[4] + config.max_delta_yaw_rate * config.dt] - # [vmin, vmax, yaw_rate min, yaw_rate max] + # [v_min, v_max, yaw_rate_min, yaw_rate_max] dw = [max(Vs[0], Vd[0]), min(Vs[1], Vd[1]), max(Vs[2], Vd[2]), min(Vs[3], Vd[3])] @@ -114,14 +114,14 @@ def predict_trajectory(x_init, v, y, config): """ x = np.array(x_init) - traj = np.array(x) + trajectory = np.array(x) time = 0 while time <= config.predict_time: x = motion(x, [v, y], config.dt) - traj = np.vstack((traj, x)) + trajectory = np.vstack((trajectory, x)) time += config.dt - return traj + return trajectory def calc_control_and_trajectory(x, dw, config, goal, ob): @@ -135,8 +135,8 @@ def calc_control_and_trajectory(x, dw, config, goal, ob): best_trajectory = np.array([x]) # evaluate all trajectory with sampled input in dynamic window - for v in np.arange(dw[0], dw[1], config.v_reso): - for y in np.arange(dw[2], dw[3], config.yawrate_reso): + for v in np.arange(dw[0], dw[1], config.v_resolution): + for y in np.arange(dw[2], dw[3], config.yaw_rate_resolution): trajectory = predict_trajectory(x_init, v, y, config) @@ -182,7 +182,7 @@ def calc_obstacle_cost(trajectory, ob, config): np.logical_and(bottom_check, left_check))).any(): return float("Inf") elif config.robot_type == RobotType.circle: - if (r <= config.robot_radius).any(): + if np.array(r <= config.robot_radius).any(): return float("Inf") min_r = np.min(r) @@ -269,8 +269,9 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): if show_animation: plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(predicted_trajectory[:, 0], predicted_trajectory[:, 1], "-g") plt.plot(x[0], x[1], "xr") plt.plot(goal[0], goal[1], "xb") @@ -296,4 +297,5 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): if __name__ == '__main__': - main(robot_type=RobotType.circle) + main(robot_type=RobotType.rectangle) + # main(robot_type=RobotType.circle) diff --git a/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py b/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py index c29e37e896..7100b0e604 100644 --- a/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py +++ b/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py @@ -23,7 +23,7 @@ def __init__(self, ox, oy, reso, rr): ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] - reso: grid resolution [m] + resolution: grid resolution [m] rr: robot radius[m] """ @@ -49,8 +49,8 @@ def planning(self, sx, sy, gx, gy): Greedy Best-First search input: - sx: start x position [m] - sy: start y position [m] + s_x: start x position [m] + s_y: start y position [m] gx: goal x position [m] gy: goal y position [m] @@ -132,7 +132,7 @@ def calc_final_path(self, ngoal, closedset): # generate final course rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ self.calc_grid_position(ngoal.y, self.miny)] - n = closedset[ngoal.pind] + n = closedset[ngoal.parent_index] while n is not None: rx.append(self.calc_grid_position(n.x, self.minx)) ry.append(self.calc_grid_position(n.y, self.miny)) @@ -188,15 +188,15 @@ def calc_obstacle_map(self, ox, oy): self.miny = round(min(oy)) self.maxx = round(max(ox)) self.maxy = round(max(oy)) - print("minx:", self.minx) - print("miny:", self.miny) - print("maxx:", self.maxx) - print("maxy:", self.maxy) + print("min_x:", self.minx) + print("min_y:", self.miny) + print("max_x:", self.maxx) + print("max_y:", self.maxy) self.xwidth = round((self.maxx - self.minx) / self.reso) self.ywidth = round((self.maxy - self.miny) / self.reso) - print("xwidth:", self.xwidth) - print("ywidth:", self.ywidth) + print("x_width:", self.xwidth) + print("y_width:", self.ywidth) # obstacle map generation self.obmap = [[False for _ in range(self.ywidth)] diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py index 8d9ccd2e2f..09df21c4c8 100644 --- a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py +++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py @@ -11,6 +11,7 @@ import matplotlib.pyplot as plt import numpy as np +from scipy.spatial.transform import Rotation as Rot sys.path.append(os.path.relpath("../../Mapping/grid_map_lib/")) try: @@ -36,52 +37,55 @@ def __init__(self, self.sweep_direction = sweep_direction self.turing_window = [] self.update_turning_window() - self.xinds_goaly = x_inds_goal_y - self.goaly = goal_y + self.x_indexes_goal_y = x_inds_goal_y + self.goal_y = goal_y - def move_target_grid(self, cxind, cyind, gmap): - nxind = self.moving_direction + cxind - nyind = cyind + def move_target_grid(self, c_x_index, c_y_index, grid_map): + n_x_index = self.moving_direction + c_x_index + n_y_index = c_y_index # found safe grid - if not gmap.check_occupied_from_xy_index(nxind, nyind, - occupied_val=0.5): - return nxind, nyind + if not grid_map.check_occupied_from_xy_index(n_x_index, n_y_index, + occupied_val=0.5): + return n_x_index, n_y_index else: # occupied - ncxind, ncyind = self.find_safe_turning_grid(cxind, cyind, gmap) - if (ncxind is None) and (ncyind is None): + next_c_x_index, next_c_y_index = self.find_safe_turning_grid( + c_x_index, c_y_index, grid_map) + if (next_c_x_index is None) and (next_c_y_index is None): # moving backward - ncxind = -self.moving_direction + cxind - ncyind = cyind - if gmap.check_occupied_from_xy_index(ncxind, ncyind): + next_c_x_index = -self.moving_direction + c_x_index + next_c_y_index = c_y_index + if grid_map.check_occupied_from_xy_index(next_c_x_index, + next_c_y_index): # moved backward, but the grid is occupied by obstacle return None, None else: # keep moving until end - while not gmap.check_occupied_from_xy_index( - ncxind + self.moving_direction, ncyind, - occupied_val=0.5): - ncxind += self.moving_direction + while not grid_map.check_occupied_from_xy_index( + next_c_x_index + self.moving_direction, + next_c_y_index, occupied_val=0.5): + next_c_x_index += self.moving_direction self.swap_moving_direction() - return ncxind, ncyind + return next_c_x_index, next_c_y_index - def find_safe_turning_grid(self, cxind, cyind, gmap): + def find_safe_turning_grid(self, c_x_index, c_y_index, grid_map): for (d_x_ind, d_y_ind) in self.turing_window: - next_x_ind = d_x_ind + cxind - next_y_ind = d_y_ind + cyind + next_x_ind = d_x_ind + c_x_index + next_y_ind = d_y_ind + c_y_index # found safe grid - if not gmap.check_occupied_from_xy_index(next_x_ind, next_y_ind, - occupied_val=0.5): + if not grid_map.check_occupied_from_xy_index(next_x_ind, + next_y_ind, + occupied_val=0.5): return next_x_ind, next_y_ind return None, None def is_search_done(self, grid_map): - for ix in self.xinds_goaly: - if not grid_map.check_occupied_from_xy_index(ix, self.goaly, + for ix in self.x_indexes_goal_y: + if not grid_map.check_occupied_from_xy_index(ix, self.goal_y, occupied_val=0.5): return False @@ -138,64 +142,54 @@ def find_sweep_direction_and_start_position(ox, oy): return vec, sweep_start_pos -def convert_grid_coordinate(ox, oy, sweep_vec, sweep_start_posi): - tx = [ix - sweep_start_posi[0] for ix in ox] - ty = [iy - sweep_start_posi[1] for iy in oy] - +def convert_grid_coordinate(ox, oy, sweep_vec, sweep_start_position): + tx = [ix - sweep_start_position[0] for ix in ox] + ty = [iy - sweep_start_position[1] for iy in oy] th = math.atan2(sweep_vec[1], sweep_vec[0]) + rot = Rot.from_euler('z', th).as_matrix()[0:2, 0:2] + converted_xy = np.stack([tx, ty]).T @ rot - c = np.cos(-th) - s = np.sin(-th) - - rx = [ix * c - iy * s for (ix, iy) in zip(tx, ty)] - ry = [ix * s + iy * c for (ix, iy) in zip(tx, ty)] - - return rx, ry + return converted_xy[:, 0], converted_xy[:, 1] -def convert_global_coordinate(x, y, sweep_vec, sweep_start_posi): +def convert_global_coordinate(x, y, sweep_vec, sweep_start_position): th = math.atan2(sweep_vec[1], sweep_vec[0]) - c = np.cos(th) - s = np.sin(th) - - tx = [ix * c - iy * s for (ix, iy) in zip(x, y)] - ty = [ix * s + iy * c for (ix, iy) in zip(x, y)] - - rx = [ix + sweep_start_posi[0] for ix in tx] - ry = [iy + sweep_start_posi[1] for iy in ty] - + rot = Rot.from_euler('z', -th).as_matrix()[0:2, 0:2] + converted_xy = np.stack([x, y]).T @ rot + rx = [ix + sweep_start_position[0] for ix in converted_xy[:, 0]] + ry = [iy + sweep_start_position[1] for iy in converted_xy[:, 1]] return rx, ry def search_free_grid_index_at_edge_y(grid_map, from_upper=False): - yind = None - xinds = [] + y_index = None + x_indexes = [] if from_upper: - xrange = range(grid_map.height)[::-1] - yrange = range(grid_map.width)[::-1] + x_range = range(grid_map.height)[::-1] + y_range = range(grid_map.width)[::-1] else: - xrange = range(grid_map.height) - yrange = range(grid_map.width) + x_range = range(grid_map.height) + y_range = range(grid_map.width) - for iy in xrange: - for ix in yrange: + for iy in x_range: + for ix in y_range: if not grid_map.check_occupied_from_xy_index(ix, iy): - yind = iy - xinds.append(ix) - if yind: + y_index = iy + x_indexes.append(ix) + if y_index: break - return xinds, yind + return x_indexes, y_index -def setup_grid_map(ox, oy, reso, sweep_direction, offset_grid=10): - width = math.ceil((max(ox) - min(ox)) / reso) + offset_grid - height = math.ceil((max(oy) - min(oy)) / reso) + offset_grid - center_x = (np.max(ox)+np.min(ox))/2.0 - center_y = (np.max(oy)+np.min(oy))/2.0 +def setup_grid_map(ox, oy, resolution, sweep_direction, offset_grid=10): + width = math.ceil((max(ox) - min(ox)) / resolution) + offset_grid + height = math.ceil((max(oy) - min(oy)) / resolution) + offset_grid + center_x = (np.max(ox) + np.min(ox)) / 2.0 + center_y = (np.max(oy) + np.min(oy)) / 2.0 - grid_map = GridMap(width, height, reso, center_x, center_y) + grid_map = GridMap(width, height, resolution, center_x, center_y) grid_map.print_grid_map_info() grid_map.set_value_from_polygon(ox, oy, 1.0, inside=False) grid_map.expand_grid() @@ -203,48 +197,51 @@ def setup_grid_map(ox, oy, reso, sweep_direction, offset_grid=10): x_inds_goal_y = [] goal_y = 0 if sweep_direction == SweepSearcher.SweepDirection.UP: - x_inds_goal_y, goal_y = search_free_grid_index_at_edge_y(grid_map, - from_upper=True) + x_inds_goal_y, goal_y = search_free_grid_index_at_edge_y( + grid_map, from_upper=True) elif sweep_direction == SweepSearcher.SweepDirection.DOWN: - x_inds_goal_y, goal_y = search_free_grid_index_at_edge_y(grid_map, - from_upper=False) + x_inds_goal_y, goal_y = search_free_grid_index_at_edge_y( + grid_map, from_upper=False) return grid_map, x_inds_goal_y, goal_y def sweep_path_search(sweep_searcher, grid_map, grid_search_animation=False): # search start grid - cxind, cyind = sweep_searcher.search_start_grid(grid_map) - if not grid_map.set_value_from_xy_index(cxind, cyind, 0.5): + c_x_index, c_y_index = sweep_searcher.search_start_grid(grid_map) + if not grid_map.set_value_from_xy_index(c_x_index, c_y_index, 0.5): print("Cannot find start grid") return [], [] - x, y = grid_map.calc_grid_central_xy_position_from_xy_index(cxind, cyind) + x, y = grid_map.calc_grid_central_xy_position_from_xy_index(c_x_index, + c_y_index) px, py = [x], [y] fig, ax = None, None if grid_search_animation: fig, ax = plt.subplots() # for stopping simulation with the esc key. - fig.canvas.mpl_connect('key_release_event', - lambda event: [ - exit(0) if event.key == 'escape' else None]) + fig.canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) while True: - cxind, cyind = sweep_searcher.move_target_grid(cxind, cyind, grid_map) + c_x_index, c_y_index = sweep_searcher.move_target_grid(c_x_index, + c_y_index, + grid_map) if sweep_searcher.is_search_done(grid_map) or ( - cxind is None or cyind is None): + c_x_index is None or c_y_index is None): print("Done") break x, y = grid_map.calc_grid_central_xy_position_from_xy_index( - cxind, cyind) + c_x_index, c_y_index) px.append(x) py.append(y) - grid_map.set_value_from_xy_index(cxind, cyind, 0.5) + grid_map.set_value_from_xy_index(c_x_index, c_y_index, 0.5) if grid_search_animation: grid_map.plot_grid_map(ax=ax) @@ -255,32 +252,34 @@ def sweep_path_search(sweep_searcher, grid_map, grid_search_animation=False): return px, py -def planning(ox, oy, reso, +def planning(ox, oy, resolution, moving_direction=SweepSearcher.MovingDirection.RIGHT, sweeping_direction=SweepSearcher.SweepDirection.UP, ): - sweep_vec, sweep_start_posi = find_sweep_direction_and_start_position( + sweep_vec, sweep_start_position = find_sweep_direction_and_start_position( ox, oy) - rox, roy = convert_grid_coordinate(ox, oy, sweep_vec, sweep_start_posi) + rox, roy = convert_grid_coordinate(ox, oy, sweep_vec, + sweep_start_position) - gmap, xinds_goaly, goaly = setup_grid_map(rox, roy, reso, - sweeping_direction) + grid_map, x_inds_goal_y, goal_y = setup_grid_map(rox, roy, resolution, + sweeping_direction) sweep_searcher = SweepSearcher(moving_direction, sweeping_direction, - xinds_goaly, goaly) + x_inds_goal_y, goal_y) - px, py = sweep_path_search(sweep_searcher, gmap) + px, py = sweep_path_search(sweep_searcher, grid_map) - rx, ry = convert_global_coordinate(px, py, sweep_vec, sweep_start_posi) + rx, ry = convert_global_coordinate(px, py, sweep_vec, + sweep_start_position) print("Path length:", len(rx)) return rx, ry -def planning_animation(ox, oy, reso): # pragma: no cover - px, py = planning(ox, oy, reso) +def planning_animation(ox, oy, resolution): # pragma: no cover + px, py = planning(ox, oy, resolution) # animation if do_animation: @@ -311,18 +310,18 @@ def main(): # pragma: no cover ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0, 0.0] oy = [0.0, -20.0, 0.0, 30.0, 60.0, 80.0, 0.0] - reso = 5.0 - planning_animation(ox, oy, reso) + resolution = 5.0 + planning_animation(ox, oy, resolution) ox = [0.0, 50.0, 50.0, 0.0, 0.0] oy = [0.0, 0.0, 30.0, 30.0, 0.0] - reso = 1.3 - planning_animation(ox, oy, reso) + resolution = 1.3 + planning_animation(ox, oy, resolution) ox = [0.0, 20.0, 50.0, 200.0, 130.0, 40.0, 0.0] oy = [0.0, -80.0, 0.0, 30.0, 60.0, 80.0, 0.0] - reso = 5.0 - planning_animation(ox, oy, reso) + resolution = 5.0 + planning_animation(ox, oy, resolution) plt.show() print("done!!") diff --git a/PathPlanning/HybridAStar/a_star_heuristic.py b/PathPlanning/HybridAStar/a_star_heuristic.py index a27293288c..36c3342462 100644 --- a/PathPlanning/HybridAStar/a_star_heuristic.py +++ b/PathPlanning/HybridAStar/a_star_heuristic.py @@ -8,8 +8,9 @@ """ -import math import heapq +import math + import matplotlib.pyplot as plt show_animation = False @@ -17,71 +18,73 @@ class Node: - def __init__(self, x, y, cost, pind): + def __init__(self, x, y, cost, parent_index): self.x = x self.y = y self.cost = cost - self.pind = pind + self.parent_index = parent_index def __str__(self): - return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind) + return str(self.x) + "," + str(self.y) + "," + str( + self.cost) + "," + str(self.parent_index) -def calc_final_path(ngoal, closedset, reso): +def calc_final_path(goal_node, closed_node_set, resolution): # generate final course - rx, ry = [ngoal.x * reso], [ngoal.y * reso] - pind = ngoal.pind - while pind != -1: - n = closedset[pind] - rx.append(n.x * reso) - ry.append(n.y * reso) - pind = n.pind + rx, ry = [goal_node.x * resolution], [goal_node.y * resolution] + parent_index = goal_node.parent_index + while parent_index != -1: + n = closed_node_set[parent_index] + rx.append(n.x * resolution) + ry.append(n.y * resolution) + parent_index = n.parent_index return rx, ry -def dp_planning(sx, sy, gx, gy, ox, oy, reso, rr): +def dp_planning(sx, sy, gx, gy, ox, oy, resolution, rr): """ gx: goal x position [m] gx: goal x position [m] ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] - reso: grid resolution [m] + resolution: grid resolution [m] rr: robot radius[m] """ - nstart = Node(round(sx / reso), round(sy / reso), 0.0, -1) - ngoal = Node(round(gx / reso), round(gy / reso), 0.0, -1) - ox = [iox / reso for iox in ox] - oy = [ioy / reso for ioy in oy] + start_node = Node(round(sx / resolution), round(sy / resolution), 0.0, -1) + goal_node = Node(round(gx / resolution), round(gy / resolution), 0.0, -1) + ox = [iox / resolution for iox in ox] + oy = [ioy / resolution for ioy in oy] - obmap, minx, miny, maxx, maxy, xw, yw = calc_obstacle_map(ox, oy, reso, rr) + obstacle_map, min_x, min_y, max_x, max_y, x_w, y_w = calc_obstacle_map( + ox, oy, resolution, rr) motion = get_motion_model() - openset, closedset = dict(), dict() - openset[calc_index(ngoal, xw, minx, miny)] = ngoal - pq = [] - pq.append((0, calc_index(ngoal, xw, minx, miny))) + open_set, closed_set = dict(), dict() + open_set[calc_index(goal_node, x_w, min_x, min_y)] = goal_node + priority_queue = [(0, calc_index(goal_node, x_w, min_x, min_y))] while 1: - if not pq: + if not priority_queue: break - cost, c_id = heapq.heappop(pq) - if c_id in openset: - current = openset[c_id] - closedset[c_id] = current - openset.pop(c_id) + cost, c_id = heapq.heappop(priority_queue) + if c_id in open_set: + current = open_set[c_id] + closed_set[c_id] = current + open_set.pop(c_id) else: continue # show graph if show_animation: # pragma: no cover - plt.plot(current.x * reso, current.y * reso, "xc") + plt.plot(current.x * resolution, current.y * resolution, "xc") # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) - if len(closedset.keys()) % 10 == 0: + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + if len(closed_set.keys()) % 10 == 0: plt.pause(0.001) # Remove the item from the open set @@ -91,82 +94,82 @@ def dp_planning(sx, sy, gx, gy, ox, oy, reso, rr): node = Node(current.x + motion[i][0], current.y + motion[i][1], current.cost + motion[i][2], c_id) - n_id = calc_index(node, xw, minx, miny) + n_id = calc_index(node, x_w, min_x, min_y) - if n_id in closedset: + if n_id in closed_set: continue - if not verify_node(node, obmap, minx, miny, maxx, maxy): + if not verify_node(node, obstacle_map, min_x, min_y, max_x, max_y): continue - if n_id not in openset: - openset[n_id] = node # Discover a new node + if n_id not in open_set: + open_set[n_id] = node # Discover a new node heapq.heappush( - pq, (node.cost, calc_index(node, xw, minx, miny))) + priority_queue, + (node.cost, calc_index(node, x_w, min_x, min_y))) else: - if openset[n_id].cost >= node.cost: + if open_set[n_id].cost >= node.cost: # This path is the best until now. record it! - openset[n_id] = node + open_set[n_id] = node heapq.heappush( - pq, (node.cost, calc_index(node, xw, minx, miny))) + priority_queue, + (node.cost, calc_index(node, x_w, min_x, min_y))) - rx, ry = calc_final_path(closedset[calc_index( - nstart, xw, minx, miny)], closedset, reso) + rx, ry = calc_final_path(closed_set[calc_index( + start_node, x_w, min_x, min_y)], closed_set, resolution) - return rx, ry, closedset + return rx, ry, closed_set def calc_heuristic(n1, n2): w = 1.0 # weight of heuristic - d = w * math.sqrt((n1.x - n2.x)**2 + (n1.y - n2.y)**2) + d = w * math.sqrt((n1.x - n2.x) ** 2 + (n1.y - n2.y) ** 2) return d -def verify_node(node, obmap, minx, miny, maxx, maxy): - - if node.x < minx: +def verify_node(node, obstacle_map, min_x, min_y, max_x, max_y): + if node.x < min_x: return False - elif node.y < miny: + elif node.y < min_y: return False - elif node.x >= maxx: + elif node.x >= max_x: return False - elif node.y >= maxy: + elif node.y >= max_y: return False - if obmap[node.x][node.y]: + if obstacle_map[node.x][node.y]: return False return True -def calc_obstacle_map(ox, oy, reso, vr): - - minx = round(min(ox)) - miny = round(min(oy)) - maxx = round(max(ox)) - maxy = round(max(oy)) +def calc_obstacle_map(ox, oy, resolution, vr): + min_x = round(min(ox)) + min_y = round(min(oy)) + max_x = round(max(ox)) + max_y = round(max(oy)) - xwidth = round(maxx - minx) - ywidth = round(maxy - miny) + x_width = round(max_x - min_x) + y_width = round(max_y - min_y) # obstacle map generation - obmap = [[False for i in range(ywidth)] for i in range(xwidth)] - for ix in range(xwidth): - x = ix + minx - for iy in range(ywidth): - y = iy + miny + obstacle_map = [[False for _ in range(y_width)] for _ in range(x_width)] + for ix in range(x_width): + x = ix + min_x + for iy in range(y_width): + y = iy + min_y # print(x, y) for iox, ioy in zip(ox, oy): - d = math.sqrt((iox - x)**2 + (ioy - y)**2) - if d <= vr / reso: - obmap[ix][iy] = True + d = math.sqrt((iox - x) ** 2 + (ioy - y) ** 2) + if d <= vr / resolution: + obstacle_map[ix][iy] = True break - return obmap, minx, miny, maxx, maxy, xwidth, ywidth + return obstacle_map, min_x, min_y, max_x, max_y, x_width, y_width -def calc_index(node, xwidth, xmin, ymin): - return (node.y - ymin) * xwidth + (node.x - xmin) +def calc_index(node, x_width, x_min, y_min): + return (node.y - y_min) * x_width + (node.x - x_min) def get_motion_model(): diff --git a/PathPlanning/HybridAStar/car.py b/PathPlanning/HybridAStar/car.py index 13e50b2995..9b956a0877 100644 --- a/PathPlanning/HybridAStar/car.py +++ b/PathPlanning/HybridAStar/car.py @@ -6,9 +6,11 @@ """ +from math import sqrt, cos, sin, tan, pi import matplotlib.pyplot as plt -from math import sqrt, cos, sin, tan, pi +import numpy as np +from scipy.spatial.transform import Rotation as Rot WB = 3. # rear to front wheel W = 2. # width of car @@ -16,25 +18,25 @@ LB = 1.0 # distance from rear to vehicle back end MAX_STEER = 0.6 # [rad] maximum steering angle -WBUBBLE_DIST = (LF - LB) / 2.0 -WBUBBLE_R = sqrt(((LF + LB) / 2.0)**2 + 1) +W_BUBBLE_DIST = (LF - LB) / 2.0 +W_BUBBLE_R = sqrt(((LF + LB) / 2.0) ** 2 + 1) -# vehicle rectangle verticles +# vehicle rectangle vertices VRX = [LF, LF, -LB, -LB, LF] VRY = [W / 2, -W / 2, -W / 2, W / 2, W / 2] -def check_car_collision(xlist, ylist, yawlist, ox, oy, kdtree): - for x, y, yaw in zip(xlist, ylist, yawlist): - cx = x + WBUBBLE_DIST * cos(yaw) - cy = y + WBUBBLE_DIST * sin(yaw) +def check_car_collision(x_list, y_list, yaw_list, ox, oy, kd_tree): + for i_x, i_y, i_yaw in zip(x_list, y_list, yaw_list): + cx = i_x + W_BUBBLE_DIST * cos(i_yaw) + cy = i_y + W_BUBBLE_DIST * sin(i_yaw) - ids = kdtree.search_in_distance([cx, cy], WBUBBLE_R) + ids = kd_tree.search_in_distance([cx, cy], W_BUBBLE_R) if not ids: continue - if not rectangle_check(x, y, yaw, + if not rectangle_check(i_x, i_y, i_yaw, [ox[i] for i in ids], [oy[i] for i in ids]): return False # collision @@ -43,12 +45,12 @@ def check_car_collision(xlist, ylist, yawlist, ox, oy, kdtree): def rectangle_check(x, y, yaw, ox, oy): # transform obstacles to base link frame - c, s = cos(-yaw), sin(-yaw) + rot = Rot.from_euler('z', yaw).as_matrix()[0:2, 0:2] for iox, ioy in zip(ox, oy): tx = iox - x ty = ioy - y - rx = c * tx - s * ty - ry = s * tx + c * ty + converted_xy = np.stack([tx, ty]).T @ rot + rx, ry = converted_xy[0], converted_xy[1] if not (rx > LF or rx < -LB or ry > W / 2.0 or ry < -W / 2.0): return False # no collision @@ -59,24 +61,22 @@ def rectangle_check(x, y, yaw, ox, oy): def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): """Plot arrow.""" if not isinstance(x, float): - for (ix, iy, iyaw) in zip(x, y, yaw): - plot_arrow(ix, iy, iyaw) + for (i_x, i_y, i_yaw) in zip(x, y, yaw): + plot_arrow(i_x, i_y, i_yaw) else: plt.arrow(x, y, length * cos(yaw), length * sin(yaw), fc=fc, ec=ec, head_width=width, head_length=width, alpha=0.4) - # plt.plot(x, y) def plot_car(x, y, yaw): car_color = '-k' c, s = cos(yaw), sin(yaw) - + rot = Rot.from_euler('z', yaw).as_matrix()[0:2, 0:2] car_outline_x, car_outline_y = [], [] for rx, ry in zip(VRX, VRY): - tx = c * rx - s * ry + x - ty = s * rx + c * ry + y - car_outline_x.append(tx) - car_outline_y.append(ty) + converted_xy = np.stack([rx, ry]).T @ rot + car_outline_x.append(converted_xy[0]+x) + car_outline_y.append(converted_xy[1]+y) arrow_x, arrow_y, arrow_yaw = c * 1.5 + x, s * 1.5 + y, yaw plot_arrow(arrow_x, arrow_y, arrow_yaw) @@ -96,8 +96,12 @@ def move(x, y, yaw, distance, steer, L=WB): return x, y, yaw -if __name__ == '__main__': +def main(): x, y, yaw = 0., 0., 1. plt.axis('equal') plot_car(x, y, yaw) - plt.show() \ No newline at end of file + plt.show() + + +if __name__ == '__main__': + main() diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index 14e4ac5aec..ff9b3fe43b 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -7,28 +7,27 @@ """ import heapq -import scipy.spatial -import numpy as np import math -import matplotlib.pyplot as plt -import sys import os +import sys + +import matplotlib.pyplot as plt +import numpy as np +import scipy.spatial sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../ReedsSheppPath") try: - from a_star_heuristic import dp_planning # , calc_obstacle_map + from a_star_heuristic import dp_planning import reeds_shepp_path_planning as rs from car import move, check_car_collision, MAX_STEER, WB, plot_car except Exception: raise - XY_GRID_RESOLUTION = 2.0 # [m] YAW_GRID_RESOLUTION = np.deg2rad(15.0) # [rad] -MOTION_RESOLUTION = 0.1 # [m] path interporate resolution +MOTION_RESOLUTION = 0.1 # [m] path interpolate resolution N_STEER = 20 # number of steer command -H_COST = 1.0 VR = 1.0 # robot radius SB_COST = 100.0 # switch back penalty cost @@ -42,29 +41,29 @@ class Node: - def __init__(self, xind, yind, yawind, direction, - xlist, ylist, yawlist, directions, - steer=0.0, pind=None, cost=None): - self.xind = xind - self.yind = yind - self.yawind = yawind + def __init__(self, x_ind, y_ind, yaw_ind, direction, + x_list, y_list, yaw_list, directions, + steer=0.0, parent_index=None, cost=None): + self.x_index = x_ind + self.y_index = y_ind + self.yaw_index = yaw_ind self.direction = direction - self.xlist = xlist - self.ylist = ylist - self.yawlist = yawlist + self.x_list = x_list + self.y_list = y_list + self.yaw_list = yaw_list self.directions = directions self.steer = steer - self.pind = pind + self.parent_index = parent_index self.cost = cost class Path: - def __init__(self, xlist, ylist, yawlist, directionlist, cost): - self.xlist = xlist - self.ylist = ylist - self.yawlist = yawlist - self.directionlist = directionlist + def __init__(self, x_list, y_list, yaw_list, direction_list, cost): + self.x_list = x_list + self.y_list = y_list + self.yaw_list = yaw_list + self.direction_list = direction_list self.cost = cost @@ -88,9 +87,9 @@ def search(self, inp, k=1): dist = [] for i in inp.T: - idist, iindex = self.tree.query(i, k=k) - index.append(iindex) - dist.append(idist) + i_dist, i_index = self.tree.query(i, k=k) + index.append(i_index) + dist.append(i_dist) return index, dist @@ -108,7 +107,7 @@ def search_in_distance(self, inp, r): class Config: - def __init__(self, ox, oy, xyreso, yawreso): + def __init__(self, ox, oy, xy_resolution, yaw_resolution): min_x_m = min(ox) min_y_m = min(oy) max_x_m = max(ox) @@ -119,94 +118,93 @@ def __init__(self, ox, oy, xyreso, yawreso): ox.append(max_x_m) oy.append(max_y_m) - self.minx = round(min_x_m / xyreso) - self.miny = round(min_y_m / xyreso) - self.maxx = round(max_x_m / xyreso) - self.maxy = round(max_y_m / xyreso) + self.min_x = round(min_x_m / xy_resolution) + self.min_y = round(min_y_m / xy_resolution) + self.max_x = round(max_x_m / xy_resolution) + self.max_y = round(max_y_m / xy_resolution) - self.xw = round(self.maxx - self.minx) - self.yw = round(self.maxy - self.miny) + self.x_w = round(self.max_x - self.min_x) + self.y_w = round(self.max_y - self.min_y) - self.minyaw = round(- math.pi / yawreso) - 1 - self.maxyaw = round(math.pi / yawreso) - self.yaww = round(self.maxyaw - self.minyaw) + self.min_yaw = round(- math.pi / yaw_resolution) - 1 + self.max_yaw = round(math.pi / yaw_resolution) + self.yaw_w = round(self.max_yaw - self.min_yaw) def calc_motion_inputs(): - for steer in np.concatenate((np.linspace(-MAX_STEER, MAX_STEER, N_STEER), [0.0])): for d in [1, -1]: yield [steer, d] -def get_neighbors(current, config, ox, oy, kdtree): - +def get_neighbors(current, config, ox, oy, kd_tree): for steer, d in calc_motion_inputs(): - node = calc_next_node(current, steer, d, config, ox, oy, kdtree) + node = calc_next_node(current, steer, d, config, ox, oy, kd_tree) if node and verify_index(node, config): yield node -def calc_next_node(current, steer, direction, config, ox, oy, kdtree): - - x, y, yaw = current.xlist[-1], current.ylist[-1], current.yawlist[-1] +def calc_next_node(current, steer, direction, config, ox, oy, kd_tree): + x, y, yaw = current.x_list[-1], current.y_list[-1], current.yaw_list[-1] arc_l = XY_GRID_RESOLUTION * 1.5 - xlist, ylist, yawlist = [], [], [] + x_list, y_list, yaw_list = [], [], [] for _ in np.arange(0, arc_l, MOTION_RESOLUTION): x, y, yaw = move(x, y, yaw, MOTION_RESOLUTION * direction, steer) - xlist.append(x) - ylist.append(y) - yawlist.append(yaw) + x_list.append(x) + y_list.append(y) + yaw_list.append(yaw) - if not check_car_collision(xlist, ylist, yawlist, ox, oy, kdtree): + if not check_car_collision(x_list, y_list, yaw_list, ox, oy, kd_tree): return None d = direction == 1 - xind = round(x / XY_GRID_RESOLUTION) - yind = round(y / XY_GRID_RESOLUTION) - yawind = round(yaw / YAW_GRID_RESOLUTION) + x_ind = round(x / XY_GRID_RESOLUTION) + y_ind = round(y / XY_GRID_RESOLUTION) + yaw_ind = round(yaw / YAW_GRID_RESOLUTION) - addedcost = 0.0 + added_cost = 0.0 if d != current.direction: - addedcost += SB_COST + added_cost += SB_COST # steer penalty - addedcost += STEER_COST * abs(steer) + added_cost += STEER_COST * abs(steer) # steer change penalty - addedcost += STEER_CHANGE_COST * abs(current.steer - steer) + added_cost += STEER_CHANGE_COST * abs(current.steer - steer) - cost = current.cost + addedcost + arc_l + cost = current.cost + added_cost + arc_l - node = Node(xind, yind, yawind, d, xlist, - ylist, yawlist, [d], - pind=calc_index(current, config), + node = Node(x_ind, y_ind, yaw_ind, d, x_list, + y_list, yaw_list, [d], + parent_index=calc_index(current, config), cost=cost, steer=steer) return node def is_same_grid(n1, n2): - if n1.xind == n2.xind and n1.yind == n2.yind and n1.yawind == n2.yawind: + if n1.x_index == n2.x_index \ + and n1.y_index == n2.y_index \ + and n1.yaw_index == n2.yaw_index: return True return False -def analytic_expantion(current, goal, c, ox, oy, kdtree): - - sx = current.xlist[-1] - sy = current.ylist[-1] - syaw = current.yawlist[-1] +def analytic_expansion(current, goal, ox, oy, kd_tree): + start_x = current.x_list[-1] + start_y = current.y_list[-1] + start_yaw = current.yaw_list[-1] - gx = goal.xlist[-1] - gy = goal.ylist[-1] - gyaw = goal.yawlist[-1] + goal_x = goal.x_list[-1] + goal_y = goal.y_list[-1] + goal_yaw = goal.yaw_list[-1] max_curvature = math.tan(MAX_STEER) / WB - paths = rs.calc_paths(sx, sy, syaw, gx, gy, gyaw, + paths = rs.calc_paths(start_x, start_y, start_yaw, + goal_x, goal_y, goal_yaw, max_curvature, step_size=MOTION_RESOLUTION) if not paths: @@ -215,7 +213,7 @@ def analytic_expantion(current, goal, c, ox, oy, kdtree): best_path, best = None, None for path in paths: - if check_car_collision(path.x, path.y, path.yaw, ox, oy, kdtree): + if check_car_collision(path.x, path.y, path.yaw, ox, oy, kd_tree): cost = calc_rs_path_cost(path) if not best or best > cost: best = cost @@ -224,99 +222,105 @@ def analytic_expantion(current, goal, c, ox, oy, kdtree): return best_path -def update_node_with_analystic_expantion(current, goal, - c, ox, oy, kdtree): - apath = analytic_expantion(current, goal, c, ox, oy, kdtree) +def update_node_with_analytic_expansion(current, goal, + c, ox, oy, kd_tree): + path = analytic_expansion(current, goal, ox, oy, kd_tree) - if apath: + if path: if show_animation: - plt.plot(apath.x, apath.y) - fx = apath.x[1:] - fy = apath.y[1:] - fyaw = apath.yaw[1:] + plt.plot(path.x, path.y) + f_x = path.x[1:] + f_y = path.y[1:] + f_yaw = path.yaw[1:] - fcost = current.cost + calc_rs_path_cost(apath) - fpind = calc_index(current, c) + f_cost = current.cost + calc_rs_path_cost(path) + f_parent_index = calc_index(current, c) fd = [] - for d in apath.directions[1:]: + for d in path.directions[1:]: fd.append(d >= 0) - fsteer = 0.0 - fpath = Node(current.xind, current.yind, current.yawind, - current.direction, fx, fy, fyaw, fd, - cost=fcost, pind=fpind, steer=fsteer) - return True, fpath + f_steer = 0.0 + f_path = Node(current.x_index, current.y_index, current.yaw_index, + current.direction, f_x, f_y, f_yaw, fd, + cost=f_cost, parent_index=f_parent_index, steer=f_steer) + return True, f_path return False, None -def calc_rs_path_cost(rspath): - +def calc_rs_path_cost(reed_shepp_path): cost = 0.0 - for l in rspath.lengths: - if l >= 0: # forward - cost += l + for length in reed_shepp_path.lengths: + if length >= 0: # forward + cost += length else: # back - cost += abs(l) * BACK_COST + cost += abs(length) * BACK_COST - # swich back penalty - for i in range(len(rspath.lengths) - 1): - if rspath.lengths[i] * rspath.lengths[i + 1] < 0.0: # switch back + # switch back penalty + for i in range(len(reed_shepp_path.lengths) - 1): + # switch back + if reed_shepp_path.lengths[i] * reed_shepp_path.lengths[i + 1] < 0.0: cost += SB_COST - # steer penalyty - for ctype in rspath.ctypes: - if ctype != "S": # curve + # steer penalty + for course_type in reed_shepp_path.ctypes: + if course_type != "S": # curve cost += STEER_COST * abs(MAX_STEER) # ==steer change penalty # calc steer profile - nctypes = len(rspath.ctypes) - ulist = [0.0] * nctypes - for i in range(nctypes): - if rspath.ctypes[i] == "R": - ulist[i] = - MAX_STEER - elif rspath.ctypes[i] == "L": - ulist[i] = MAX_STEER + n_ctypes = len(reed_shepp_path.ctypes) + u_list = [0.0] * n_ctypes + for i in range(n_ctypes): + if reed_shepp_path.ctypes[i] == "R": + u_list[i] = - MAX_STEER + elif reed_shepp_path.ctypes[i] == "L": + u_list[i] = MAX_STEER - for i in range(len(rspath.ctypes) - 1): - cost += STEER_CHANGE_COST * abs(ulist[i + 1] - ulist[i]) + for i in range(len(reed_shepp_path.ctypes) - 1): + cost += STEER_CHANGE_COST * abs(u_list[i + 1] - u_list[i]) return cost -def hybrid_a_star_planning(start, goal, ox, oy, xyreso, yawreso): +def hybrid_a_star_planning(start, goal, ox, oy, xy_resolution, yaw_resolution): """ - start - goal + start: start node + goal: goal node ox: x position list of Obstacles [m] oy: y position list of Obstacles [m] - xyreso: grid resolution [m] - yawreso: yaw angle resolution [rad] + xy_resolution: grid resolution [m] + yaw_resolution: yaw angle resolution [rad] """ start[2], goal[2] = rs.pi_2_pi(start[2]), rs.pi_2_pi(goal[2]) tox, toy = ox[:], oy[:] - obkdtree = KDTree(np.vstack((tox, toy)).T) + obstacle_kd_tree = KDTree(np.vstack((tox, toy)).T) - config = Config(tox, toy, xyreso, yawreso) + config = Config(tox, toy, xy_resolution, yaw_resolution) - nstart = Node(round(start[0] / xyreso), round(start[1] / xyreso), round(start[2] / yawreso), - True, [start[0]], [start[1]], [start[2]], [True], cost=0) - ngoal = Node(round(goal[0] / xyreso), round(goal[1] / xyreso), round(goal[2] / yawreso), - True, [goal[0]], [goal[1]], [goal[2]], [True]) + start_node = Node(round(start[0] / xy_resolution), + round(start[1] / xy_resolution), + round(start[2] / yaw_resolution), True, + [start[0]], [start[1]], [start[2]], [True], cost=0) + goal_node = Node(round(goal[0] / xy_resolution), + round(goal[1] / xy_resolution), + round(goal[2] / yaw_resolution), True, + [goal[0]], [goal[1]], [goal[2]], [True]) openList, closedList = {}, {} - _, _, h_dp = dp_planning(nstart.xlist[-1], nstart.ylist[-1], - ngoal.xlist[-1], ngoal.ylist[-1], ox, oy, xyreso, VR) + _, _, h_dp = dp_planning(start_node.x_list[-1], start_node.y_list[-1], + goal_node.x_list[-1], goal_node.y_list[-1], + ox, oy, xy_resolution, VR) pq = [] - openList[calc_index(nstart, config)] = nstart - heapq.heappush(pq, (calc_cost(nstart, h_dp, ngoal, config), - calc_index(nstart, config))) + openList[calc_index(start_node, config)] = start_node + heapq.heappush(pq, (calc_cost(start_node, h_dp, config), + calc_index(start_node, config))) + final_path = None while True: if not openList: @@ -331,83 +335,85 @@ def hybrid_a_star_planning(start, goal, ox, oy, xyreso, yawreso): continue if show_animation: # pragma: no cover - plt.plot(current.xlist[-1], current.ylist[-1], "xc") + plt.plot(current.x_list[-1], current.y_list[-1], "xc") # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if len(closedList.keys()) % 10 == 0: plt.pause(0.001) - isupdated, fpath = update_node_with_analystic_expantion( - current, ngoal, config, ox, oy, obkdtree) + is_updated, final_path = update_node_with_analytic_expansion( + current, goal_node, config, ox, oy, obstacle_kd_tree) - if isupdated: + if is_updated: print("path found") break - for neighbor in get_neighbors(current, config, ox, oy, obkdtree): + for neighbor in get_neighbors(current, config, ox, oy, + obstacle_kd_tree): neighbor_index = calc_index(neighbor, config) if neighbor_index in closedList: continue if neighbor not in openList \ or openList[neighbor_index].cost > neighbor.cost: heapq.heappush( - pq, (calc_cost(neighbor, h_dp, ngoal, config), + pq, (calc_cost(neighbor, h_dp, config), neighbor_index)) openList[neighbor_index] = neighbor - path = get_final_path(closedList, fpath, nstart, config) + path = get_final_path(closedList, final_path) return path -def calc_cost(n, h_dp, goal, c): - ind = (n.yind - c.miny) * c.xw + (n.xind - c.minx) +def calc_cost(n, h_dp, c): + ind = (n.y_index - c.min_y) * c.x_w + (n.x_index - c.min_x) if ind not in h_dp: return n.cost + 999999999 # collision cost return n.cost + H_COST * h_dp[ind].cost -def get_final_path(closed, ngoal, nstart, config): - rx, ry, ryaw = list(reversed(ngoal.xlist)), list( - reversed(ngoal.ylist)), list(reversed(ngoal.yawlist)) - direction = list(reversed(ngoal.directions)) - nid = ngoal.pind - finalcost = ngoal.cost +def get_final_path(closed, goal_node): + reversed_x, reversed_y, reversed_yaw = \ + list(reversed(goal_node.x_list)), list(reversed(goal_node.y_list)), \ + list(reversed(goal_node.yaw_list)) + direction = list(reversed(goal_node.directions)) + nid = goal_node.parent_index + final_cost = goal_node.cost while nid: n = closed[nid] - rx.extend(list(reversed(n.xlist))) - ry.extend(list(reversed(n.ylist))) - ryaw.extend(list(reversed(n.yawlist))) + reversed_x.extend(list(reversed(n.x_list))) + reversed_y.extend(list(reversed(n.y_list))) + reversed_yaw.extend(list(reversed(n.yaw_list))) direction.extend(list(reversed(n.directions))) - nid = n.pind + nid = n.parent_index - rx = list(reversed(rx)) - ry = list(reversed(ry)) - ryaw = list(reversed(ryaw)) + reversed_x = list(reversed(reversed_x)) + reversed_y = list(reversed(reversed_y)) + reversed_yaw = list(reversed(reversed_yaw)) direction = list(reversed(direction)) # adjust first direction direction[0] = direction[1] - path = Path(rx, ry, ryaw, direction, finalcost) + path = Path(reversed_x, reversed_y, reversed_yaw, direction, final_cost) return path def verify_index(node, c): - xind, yind = node.xind, node.yind - if xind >= c.minx and xind <= c.maxx and yind >= c.miny \ - and yind <= c.maxy: + x_ind, y_ind = node.x_index, node.y_index + if c.min_x <= x_ind <= c.max_x and c.min_y <= y_ind <= c.max_y: return True return False def calc_index(node, c): - ind = (node.yawind - c.minyaw) * c.xw * c.yw + \ - (node.yind - c.miny) * c.xw + (node.xind - c.minx) + ind = (node.yaw_index - c.min_yaw) * c.x_w * c.y_w + \ + (node.y_index - c.min_y) * c.x_w + (node.x_index - c.min_x) if ind <= 0: print("Error(calc_index):", ind) @@ -457,18 +463,18 @@ def main(): path = hybrid_a_star_planning( start, goal, ox, oy, XY_GRID_RESOLUTION, YAW_GRID_RESOLUTION) - x = path.xlist - y = path.ylist - yaw = path.yawlist + x = path.x_list + y = path.y_list + yaw = path.yaw_list if show_animation: - for ix, iy, iyaw in zip(x, y, yaw): + for i_x, i_y, i_yaw in zip(x, y, yaw): plt.cla() plt.plot(ox, oy, ".k") plt.plot(x, y, "-r", label="Hybrid A* path") plt.grid(True) plt.axis("equal") - plot_car(ix, iy, iyaw) + plot_car(i_x, i_y, i_yaw) plt.pause(0.0001) print(__file__ + " done!!") diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 912e56fa4b..baf7dcce91 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -5,7 +5,8 @@ Atsushi Sakai(@Atsushi_twi) Reference: Informed RRT*: Optimal Sampling-based Path planning Focused via -Direct Sampling of an Admissible Ellipsoidal Heuristichttps://arxiv.org/pdf/1404.2334.pdf +Direct Sampling of an Admissible Ellipsoidal Heuristic +https://arxiv.org/pdf/1404.2334.pdf """ @@ -14,6 +15,7 @@ import random import matplotlib.pyplot as plt +from scipy.spatial.transform import Rotation as Rot import numpy as np show_animation = True @@ -38,7 +40,8 @@ def __init__(self, start, goal, def informed_rrt_star_search(self, animation=True): self.node_list = [self.start] - # max length we expect to find in our 'informed' sample space, starts as infinite + # max length we expect to find in our 'informed' sample space, + # starts as infinite cBest = float('inf') solutionSet = set() path = None @@ -51,13 +54,14 @@ def informed_rrt_star_search(self, animation=True): a1 = np.array([[(self.goal.x - self.start.x) / cMin], [(self.goal.y - self.start.y) / cMin], [0]]) - etheta = math.atan2(a1[1], a1[0]) - # first column of idenity matrix transposed + e_theta = math.atan2(a1[1], a1[0]) + # first column of identity matrix transposed id1_t = np.array([1.0, 0.0, 0.0]).reshape(1, 3) M = a1 @ id1_t U, S, Vh = np.linalg.svd(M, True, True) C = np.dot(np.dot(U, np.diag( - [1.0, 1.0, np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])), Vh) + [1.0, 1.0, np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])), + Vh) for i in range(self.max_iter): # Sample space is defined by cBest @@ -66,11 +70,11 @@ def informed_rrt_star_search(self, animation=True): # cBest changes when a new path is found rnd = self.informed_sample(cBest, cMin, xCenter, C) - nind = self.get_nearest_list_index(self.node_list, rnd) - nearestNode = self.node_list[nind] + n_ind = self.get_nearest_list_index(self.node_list, rnd) + nearestNode = self.node_list[n_ind] # steer theta = math.atan2(rnd[1] - nearestNode.y, rnd[0] - nearestNode.x) - newNode = self.get_new_node(theta, nind, nearestNode) + newNode = self.get_new_node(theta, n_ind, nearestNode) d = self.line_cost(nearestNode, newNode) noCollision = self.check_collision(nearestNode, theta, d) @@ -83,7 +87,8 @@ def informed_rrt_star_search(self, animation=True): self.rewire(newNode, nearInds) if self.is_near_goal(newNode): - if self.check_segment_collision(newNode.x, newNode.y, self.goal.x , self.goal.y): + if self.check_segment_collision(newNode.x, newNode.y, + self.goal.x, self.goal.y): solutionSet.add(newNode) lastIndex = len(self.node_list) - 1 tempPath = self.get_final_course(lastIndex) @@ -94,7 +99,7 @@ def informed_rrt_star_search(self, animation=True): if animation: self.draw_graph(xCenter=xCenter, cBest=cBest, cMin=cMin, - etheta=etheta, rnd=rnd) + e_theta=e_theta, rnd=rnd) return path @@ -117,7 +122,7 @@ def choose_parent(self, newNode, nearInds): minInd = nearInds[dList.index(minCost)] if minCost == float('inf'): - print("mincost is inf") + print("min cost is inf") return newNode newNode.cost = minCost @@ -126,12 +131,12 @@ def choose_parent(self, newNode, nearInds): return newNode def find_near_nodes(self, newNode): - nnode = len(self.node_list) - r = 50.0 * math.sqrt((math.log(nnode) / nnode)) - dlist = [(node.x - newNode.x) ** 2 - + (node.y - newNode.y) ** 2 for node in self.node_list] - nearinds = [dlist.index(i) for i in dlist if i <= r ** 2] - return nearinds + n_node = len(self.node_list) + r = 50.0 * math.sqrt((math.log(n_node) / n_node)) + d_list = [(node.x - newNode.x) ** 2 + (node.y - newNode.y) ** 2 + for node in self.node_list] + near_inds = [d_list.index(i) for i in d_list if i <= r ** 2] + return near_inds def informed_sample(self, cMax, cMin, xCenter, C): if cMax < float('inf'): @@ -192,14 +197,14 @@ def get_nearest_list_index(nodes, rnd): minIndex = dList.index(min(dList)) return minIndex - def get_new_node(self, theta, nind, nearestNode): + def get_new_node(self, theta, n_ind, nearestNode): newNode = copy.deepcopy(nearestNode) newNode.x += self.expand_dis * math.cos(theta) newNode.y += self.expand_dis * math.sin(theta) newNode.cost += self.expand_dis - newNode.parent = nind + newNode.parent = n_ind return newNode def is_near_goal(self, node): @@ -216,28 +221,29 @@ def rewire(self, newNode, nearInds): d = math.sqrt((nearNode.x - newNode.x) ** 2 + (nearNode.y - newNode.y) ** 2) - scost = newNode.cost + d + s_cost = newNode.cost + d - if nearNode.cost > scost: + if nearNode.cost > s_cost: theta = math.atan2(newNode.y - nearNode.y, newNode.x - nearNode.x) if self.check_collision(nearNode, theta, d): nearNode.parent = n_node - 1 - nearNode.cost = scost + nearNode.cost = s_cost @staticmethod def distance_squared_point_to_segment(v, w, p): # Return minimum distance between line segment vw and point p - if (np.array_equal(v, w)): - return (p-v).dot(p-v) # v == w case - l2 = (w-v).dot(w-v) # i.e. |w-v|^2 - avoid a sqrt - # Consider the line extending the segment, parameterized as v + t (w - v). + if np.array_equal(v, w): + return (p - v).dot(p - v) # v == w case + l2 = (w - v).dot(w - v) # i.e. |w-v|^2 - avoid a sqrt + # Consider the line extending the segment, + # parameterized as v + t (w - v). # We find projection of point p onto the line. # It falls where t = [(p-v) . (w-v)] / |w-v|^2 # We clamp t from [0,1] to handle points outside the segment vw. t = max(0, min(1, (p - v).dot(w - v) / l2)) - projection = v + t * (w - v) # Projection falls on the segment - return (p-projection).dot(p-projection) + projection = v + t * (w - v) # Projection falls on the segment + return (p - projection).dot(p - projection) def check_segment_collision(self, x1, y1, x2, y2): for (ox, oy, size) in self.obstacle_list: @@ -245,16 +251,15 @@ def check_segment_collision(self, x1, y1, x2, y2): np.array([x1, y1]), np.array([x2, y2]), np.array([ox, oy])) - if dd <= size**2: + if dd <= size ** 2: return False # collision return True - def check_collision(self, nearNode, theta, d): tmpNode = copy.deepcopy(nearNode) - endx = tmpNode.x + math.cos(theta)*d - endy = tmpNode.y + math.sin(theta)*d - return self.check_segment_collision(tmpNode.x, tmpNode.y, endx, endy) + end_x = tmpNode.x + math.cos(theta) * d + end_y = tmpNode.y + math.sin(theta) * d + return self.check_segment_collision(tmpNode.x, tmpNode.y, end_x, end_y) def get_final_course(self, lastIndex): path = [[self.goal.x, self.goal.y]] @@ -265,15 +270,17 @@ def get_final_course(self, lastIndex): path.append([self.start.x, self.start.y]) return path - def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, rnd=None): + def draw_graph(self, xCenter=None, cBest=None, cMin=None, e_theta=None, + rnd=None): plt.clf() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd[0], rnd[1], "^k") if cBest != float('inf'): - self.plot_ellipse(xCenter, cBest, cMin, etheta) + self.plot_ellipse(xCenter, cBest, cMin, e_theta) for node in self.node_list: if node.parent is not None: @@ -291,20 +298,18 @@ def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, rnd=None) plt.pause(0.01) @staticmethod - def plot_ellipse(xCenter, cBest, cMin, etheta): # pragma: no cover + def plot_ellipse(xCenter, cBest, cMin, e_theta): # pragma: no cover a = math.sqrt(cBest ** 2 - cMin ** 2) / 2.0 b = cBest / 2.0 - angle = math.pi / 2.0 - etheta + angle = math.pi / 2.0 - e_theta cx = xCenter[0] cy = xCenter[1] - t = np.arange(0, 2 * math.pi + 0.1, 0.1) x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] - R = np.array([[math.cos(angle), math.sin(angle)], - [-math.sin(angle), math.cos(angle)]]) - fx = R @ np.array([x, y]) + rot = Rot.from_euler('z', -angle).as_matrix()[0:2, 0:2] + fx = rot @ np.array([x, y]) px = np.array(fx[0, :] + cx).flatten() py = np.array(fx[1, :] + cy).flatten() plt.plot(cx, cy, "xc") diff --git a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py index 7715174e16..790db074c0 100644 --- a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py +++ b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py @@ -1,6 +1,6 @@ """ -Probablistic Road Map (PRM) Planner +Probabilistic Road Map (PRM) Planner author: Atsushi Sakai (@Atsushi_twi) @@ -25,14 +25,15 @@ class Node: Node class for dijkstra search """ - def __init__(self, x, y, cost, pind): + def __init__(self, x, y, cost, parent_index): self.x = x self.y = y self.cost = cost - self.pind = pind + self.parent_index = parent_index def __str__(self): - return str(self.x) + "," + str(self.y) + "," + str(self.cost) + "," + str(self.pind) + return str(self.x) + "," + str(self.y) + "," +\ + str(self.cost) + "," + str(self.parent_index) class KDTree: @@ -57,9 +58,9 @@ def search(self, inp, k=1): dist = [] for i in inp.T: - idist, iindex = self.tree.query(i, k=k) - index.append(iindex) - dist.append(idist) + i_dist, i_index = self.tree.query(i, k=k) + index.append(i_index) + dist.append(i_dist) return index, dist @@ -75,23 +76,24 @@ def search_in_distance(self, inp, r): return index -def PRM_planning(sx, sy, gx, gy, ox, oy, rr): +def prm_planning(sx, sy, gx, gy, ox, oy, rr): - obkdtree = KDTree(np.vstack((ox, oy)).T) + obstacle_kd_tree = KDTree(np.vstack((ox, oy)).T) - sample_x, sample_y = sample_points(sx, sy, gx, gy, rr, ox, oy, obkdtree) + sample_x, sample_y = sample_points(sx, sy, gx, gy, + rr, ox, oy, obstacle_kd_tree) if show_animation: plt.plot(sample_x, sample_y, ".b") - road_map = generate_roadmap(sample_x, sample_y, rr, obkdtree) + road_map = generate_road_map(sample_x, sample_y, rr, obstacle_kd_tree) rx, ry = dijkstra_planning( - sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y) + sx, sy, gx, gy, road_map, sample_x, sample_y) return rx, ry -def is_collision(sx, sy, gx, gy, rr, okdtree): +def is_collision(sx, sy, gx, gy, rr, obstacle_kd_tree): x = sx y = sy dx = gx - sx @@ -103,41 +105,41 @@ def is_collision(sx, sy, gx, gy, rr, okdtree): return True D = rr - nstep = round(d / D) + n_step = round(d / D) - for i in range(nstep): - idxs, dist = okdtree.search(np.array([x, y]).reshape(2, 1)) + for i in range(n_step): + _, dist = obstacle_kd_tree.search(np.array([x, y]).reshape(2, 1)) if dist[0] <= rr: return True # collision x += D * math.cos(yaw) y += D * math.sin(yaw) # goal point check - idxs, dist = okdtree.search(np.array([gx, gy]).reshape(2, 1)) + _, dist = obstacle_kd_tree.search(np.array([gx, gy]).reshape(2, 1)) if dist[0] <= rr: return True # collision return False # OK -def generate_roadmap(sample_x, sample_y, rr, obkdtree): +def generate_road_map(sample_x, sample_y, rr, obstacle_kd_tree): """ Road map generation sample_x: [m] x positions of sampled points sample_y: [m] y positions of sampled points rr: Robot Radius[m] - obkdtree: KDTree object of obstacles + obstacle_kd_tree: KDTree object of obstacles """ road_map = [] - nsample = len(sample_x) - skdtree = KDTree(np.vstack((sample_x, sample_y)).T) + n_sample = len(sample_x) + sample_kd_tree = KDTree(np.vstack((sample_x, sample_y)).T) - for (i, ix, iy) in zip(range(nsample), sample_x, sample_y): + for (i, ix, iy) in zip(range(n_sample), sample_x, sample_y): - index, dists = skdtree.search( - np.array([ix, iy]).reshape(2, 1), k=nsample) + index, dists = sample_kd_tree.search( + np.array([ix, iy]).reshape(2, 1), k=n_sample) inds = index[0] edge_id = [] # print(index) @@ -146,7 +148,7 @@ def generate_roadmap(sample_x, sample_y, rr, obkdtree): nx = sample_x[inds[ii]] ny = sample_y[inds[ii]] - if not is_collision(ix, iy, nx, ny, rr, obkdtree): + if not is_collision(ix, iy, nx, ny, rr, obstacle_kd_tree): edge_id.append(inds[ii]) if len(edge_id) >= N_KNN: @@ -159,10 +161,10 @@ def generate_roadmap(sample_x, sample_y, rr, obkdtree): return road_map -def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): +def dijkstra_planning(sx, sy, gx, gy, road_map, sample_x, sample_y): """ - sx: start x position [m] - sy: start y position [m] + s_x: start x position [m] + s_y: start y position [m] gx: goal x position [m] gy: goal y position [m] ox: x position list of Obstacles [m] @@ -175,41 +177,42 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): @return: Two lists of path coordinates ([x1, x2, ...], [y1, y2, ...]), empty list when no path was found """ - nstart = Node(sx, sy, 0.0, -1) - ngoal = Node(gx, gy, 0.0, -1) + start_node = Node(sx, sy, 0.0, -1) + goal_node = Node(gx, gy, 0.0, -1) - openset, closedset = dict(), dict() - openset[len(road_map) - 2] = nstart + open_set, closed_set = dict(), dict() + open_set[len(road_map) - 2] = start_node path_found = True while True: - if not openset: + if not open_set: print("Cannot find path") path_found = False break - c_id = min(openset, key=lambda o: openset[o].cost) - current = openset[c_id] + c_id = min(open_set, key=lambda o: open_set[o].cost) + current = open_set[c_id] # show graph - if show_animation and len(closedset.keys()) % 2 == 0: + if show_animation and len(closed_set.keys()) % 2 == 0: # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(current.x, current.y, "xg") plt.pause(0.001) if c_id == (len(road_map) - 1): print("goal is found!") - ngoal.pind = current.pind - ngoal.cost = current.cost + goal_node.parent_index = current.parent_index + goal_node.cost = current.cost break # Remove the item from the open set - del openset[c_id] + del open_set[c_id] # Add it to the closed set - closedset[c_id] = current + closed_set[c_id] = current # expand search grid based on motion model for i in range(len(road_map[c_id])): @@ -220,27 +223,27 @@ def dijkstra_planning(sx, sy, gx, gy, ox, oy, rr, road_map, sample_x, sample_y): node = Node(sample_x[n_id], sample_y[n_id], current.cost + d, c_id) - if n_id in closedset: + if n_id in closed_set: continue # Otherwise if it is already in the open set - if n_id in openset: - if openset[n_id].cost > node.cost: - openset[n_id].cost = node.cost - openset[n_id].pind = c_id + if n_id in open_set: + if open_set[n_id].cost > node.cost: + open_set[n_id].cost = node.cost + open_set[n_id].parent_index = c_id else: - openset[n_id] = node + open_set[n_id] = node if path_found is False: return [], [] # generate final course - rx, ry = [ngoal.x], [ngoal.y] - pind = ngoal.pind - while pind != -1: - n = closedset[pind] + rx, ry = [goal_node.x], [goal_node.y] + parent_index = goal_node.parent_index + while parent_index != -1: + n = closed_set[parent_index] rx.append(n.x) ry.append(n.y) - pind = n.pind + parent_index = n.parent_index return rx, ry @@ -255,19 +258,19 @@ def plot_road_map(road_map, sample_x, sample_y): # pragma: no cover [sample_y[i], sample_y[ind]], "-k") -def sample_points(sx, sy, gx, gy, rr, ox, oy, obkdtree): - maxx = max(ox) - maxy = max(oy) - minx = min(ox) - miny = min(oy) +def sample_points(sx, sy, gx, gy, rr, ox, oy, obstacle_kd_tree): + max_x = max(ox) + max_y = max(oy) + min_x = min(ox) + min_y = min(oy) sample_x, sample_y = [], [] while len(sample_x) <= N_SAMPLE: - tx = (random.random() * (maxx - minx)) + minx - ty = (random.random() * (maxy - miny)) + miny + tx = (random.random() * (max_x - min_x)) + min_x + ty = (random.random() * (max_y - min_y)) + min_y - index, dist = obkdtree.search(np.array([tx, ty]).reshape(2, 1)) + index, dist = obstacle_kd_tree.search(np.array([tx, ty]).reshape(2, 1)) if dist[0] >= rr: sample_x.append(tx) @@ -320,12 +323,13 @@ def main(): plt.grid(True) plt.axis("equal") - rx, ry = PRM_planning(sx, sy, gx, gy, ox, oy, robot_size) + rx, ry = prm_planning(sx, sy, gx, gy, ox, oy, robot_size) assert rx, 'Cannot found path' if show_animation: plt.plot(rx, ry, "-r") + plt.pause(0.001) plt.show() diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py index 5538731dcd..8ba11a23d2 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py @@ -71,9 +71,9 @@ def quintic_polynomials_planner(sx, sy, syaw, sv, sa, gx, gy, gyaw, gv, ga, max_ quintic polynomial planner input - sx: start x position [m] - sy: start y position [m] - syaw: start yaw angle [rad] + s_x: start x position [m] + s_y: start y position [m] + s_yaw: start yaw angle [rad] sa: start accel [m/ss] gx: goal x position [m] gy: goal y position [m] diff --git a/PathPlanning/VoronoiRoadMap/dijkstra_search.py b/PathPlanning/VoronoiRoadMap/dijkstra_search.py index 7bf5425ebf..54d15ea9fb 100644 --- a/PathPlanning/VoronoiRoadMap/dijkstra_search.py +++ b/PathPlanning/VoronoiRoadMap/dijkstra_search.py @@ -35,8 +35,8 @@ def search(self, sx, sy, gx, gy, node_x, node_y, edge_ids_list): """ Search shortest path - sx: start x positions [m] - sy: start y positions [m] + s_x: start x positions [m] + s_y: start y positions [m] gx: goal x position [m] gx: goal x position [m] node_x: node x position diff --git a/SLAM/GraphBasedSLAM/graph_based_slam.py b/SLAM/GraphBasedSLAM/graph_based_slam.py index 9bb68c2821..9335dbe6a1 100644 --- a/SLAM/GraphBasedSLAM/graph_based_slam.py +++ b/SLAM/GraphBasedSLAM/graph_based_slam.py @@ -6,20 +6,22 @@ Ref -[A Tutorial on Graph-Based SLAM](http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf) +[A Tutorial on Graph-Based SLAM] +(http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf) """ -import numpy as np -import math import copy import itertools -import matplotlib.pyplot as plt +import math +import matplotlib.pyplot as plt +import numpy as np +from scipy.spatial.transform import Rotation as Rot # Simulation parameter -Qsim = np.diag([0.2, np.deg2rad(1.0)])**2 -Rsim = np.diag([0.1, np.deg2rad(10.0)])**2 +Q_sim = np.diag([0.2, np.deg2rad(1.0)]) ** 2 +R_sim = np.diag([0.1, np.deg2rad(10.0)]) ** 2 DT = 2.0 # time tick [s] SIM_TIME = 100.0 # simulation time [s] @@ -33,11 +35,11 @@ MAX_ITR = 20 # Maximum iteration -show_graph_dtime = 20.0 # [s] +show_graph_d_time = 20.0 # [s] show_animation = True -class Edge(): +class Edge: def __init__(self): self.e = np.zeros((3, 1)) @@ -52,26 +54,21 @@ def __init__(self): self.id2 = 0 -def cal_observation_sigma(d): - +def cal_observation_sigma(): sigma = np.zeros((3, 3)) - sigma[0, 0] = C_SIGMA1**2 - sigma[1, 1] = C_SIGMA2**2 - sigma[2, 2] = C_SIGMA3**2 + sigma[0, 0] = C_SIGMA1 ** 2 + sigma[1, 1] = C_SIGMA2 ** 2 + sigma[2, 2] = C_SIGMA3 ** 2 return sigma def calc_rotational_matrix(angle): - - Rt = np.array([[math.cos(angle), -math.sin(angle), 0], - [math.sin(angle), math.cos(angle), 0], - [0, 0, 1.0]]) - return Rt + return Rot.from_euler('z', angle).as_matrix() def calc_edge(x1, y1, yaw1, x2, y2, yaw2, d1, - angle1, phi1, d2, angle2, phi2, t1, t2): + angle1, d2, angle2, t1, t2): edge = Edge() tangle1 = pi_2_pi(yaw1 + angle1) @@ -88,8 +85,8 @@ def calc_edge(x1, y1, yaw1, x2, y2, yaw2, d1, Rt1 = calc_rotational_matrix(tangle1) Rt2 = calc_rotational_matrix(tangle2) - sig1 = cal_observation_sigma(d1) - sig2 = cal_observation_sigma(d2) + sig1 = cal_observation_sigma() + sig2 = cal_observation_sigma() edge.omega = np.linalg.inv(Rt1 @ sig1 @ Rt1.T + Rt2 @ sig2 @ Rt2.T) @@ -101,34 +98,33 @@ def calc_edge(x1, y1, yaw1, x2, y2, yaw2, d1, return edge -def calc_edges(xlist, zlist): - +def calc_edges(x_list, z_list): edges = [] cost = 0.0 - zids = list(itertools.combinations(range(len(zlist)), 2)) + z_ids = list(itertools.combinations(range(len(z_list)), 2)) - for (t1, t2) in zids: - x1, y1, yaw1 = xlist[0, t1], xlist[1, t1], xlist[2, t1] - x2, y2, yaw2 = xlist[0, t2], xlist[1, t2], xlist[2, t2] + for (t1, t2) in z_ids: + x1, y1, yaw1 = x_list[0, t1], x_list[1, t1], x_list[2, t1] + x2, y2, yaw2 = x_list[0, t2], x_list[1, t2], x_list[2, t2] - if zlist[t1] is None or zlist[t2] is None: + if z_list[t1] is None or z_list[t2] is None: continue # No observation - for iz1 in range(len(zlist[t1][:, 0])): - for iz2 in range(len(zlist[t2][:, 0])): - if zlist[t1][iz1, 3] == zlist[t2][iz2, 3]: - d1 = zlist[t1][iz1, 0] - angle1, phi1 = zlist[t1][iz1, 1], zlist[t1][iz1, 2] - d2 = zlist[t2][iz2, 0] - angle2, phi2 = zlist[t2][iz2, 1], zlist[t2][iz2, 2] + for iz1 in range(len(z_list[t1][:, 0])): + for iz2 in range(len(z_list[t2][:, 0])): + if z_list[t1][iz1, 3] == z_list[t2][iz2, 3]: + d1 = z_list[t1][iz1, 0] + angle1, phi1 = z_list[t1][iz1, 1], z_list[t1][iz1, 2] + d2 = z_list[t2][iz2, 0] + angle2, phi2 = z_list[t2][iz2, 1], z_list[t2][iz2, 2] edge = calc_edge(x1, y1, yaw1, x2, y2, yaw2, d1, - angle1, phi1, d2, angle2, phi2, t1, t2) + angle1, d2, angle2, t1, t2) edges.append(edge) - cost += (edge.e.T @ (edge.omega) @ edge.e)[0, 0] + cost += (edge.e.T @ edge.omega @ edge.e)[0, 0] - print("cost:", cost, ",nedge:", len(edges)) + print("cost:", cost, ",n_edge:", len(edges)) return edges @@ -147,7 +143,6 @@ def calc_jacobian(edge): def fill_H_and_b(H, b, edge): - A, B = calc_jacobian(edge) id1 = edge.id1 * STATE_SIZE @@ -167,14 +162,14 @@ def fill_H_and_b(H, b, edge): def graph_based_slam(x_init, hz): print("start graph based slam") - zlist = copy.deepcopy(hz) + z_list = copy.deepcopy(hz) x_opt = copy.deepcopy(x_init) nt = x_opt.shape[1] n = nt * STATE_SIZE for itr in range(MAX_ITR): - edges = calc_edges(x_opt, zlist) + edges = calc_edges(x_opt, z_list) H = np.zeros((n, n)) b = np.zeros((n, 1)) @@ -200,13 +195,12 @@ def graph_based_slam(x_init, hz): def calc_input(): v = 1.0 # [m/s] - yawrate = 0.1 # [rad/s] - u = np.array([[v, yawrate]]).T + yaw_rate = 0.1 # [rad/s] + u = np.array([[v, yaw_rate]]).T return u def observation(xTrue, xd, u, RFID): - xTrue = motion_model(xTrue, u) # add noise to gps x-y @@ -220,16 +214,16 @@ def observation(xTrue, xd, u, RFID): angle = pi_2_pi(math.atan2(dy, dx)) - xTrue[2, 0] phi = pi_2_pi(math.atan2(dy, dx)) if d <= MAX_RANGE: - dn = d + np.random.randn() * Qsim[0, 0] # add noise - angle_noise = np.random.randn() * Qsim[1, 1] + dn = d + np.random.randn() * Q_sim[0, 0] # add noise + angle_noise = np.random.randn() * Q_sim[1, 1] angle += angle_noise phi += angle_noise zi = np.array([dn, angle, phi, i]) z = np.vstack((z, zi)) # add noise to input - ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0] - ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] + ud2 = u[1, 0] + np.random.randn() * R_sim[1, 1] ud = np.array([[ud1, ud2]]).T xd = motion_model(xd, ud) @@ -238,7 +232,6 @@ def observation(xTrue, xd, u, RFID): def motion_model(x, u): - F = np.array([[1.0, 0, 0], [0, 1.0, 0], [0, 0, 1.0]]) @@ -277,7 +270,7 @@ def main(): hxTrue = [] hxDR = [] hz = [] - dtime = 0.0 + d_time = 0.0 init = False while SIM_TIME >= time: @@ -290,22 +283,23 @@ def main(): hxTrue = np.hstack((hxTrue, xTrue)) time += DT - dtime += DT + d_time += DT u = calc_input() xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID) hz.append(z) - if dtime >= show_graph_dtime: + if d_time >= show_graph_d_time: x_opt = graph_based_slam(hxDR, hz) - dtime = 0.0 + d_time = 0.0 if show_animation: # pragma: no cover plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") plt.plot(hxTrue[0, :].flatten(), From a36ddb4cfff4f1f7677175c93e8d7935bf5fbbd4 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 8 Jun 2020 17:16:56 +0900 Subject: [PATCH 274/940] use scipy kd-tree directly (#337) --- PathPlanning/HybridAStar/car.py | 4 +- PathPlanning/HybridAStar/hybrid_a_star.py | 42 +---------- .../probabilistic_road_map.py | 71 ++++--------------- PathPlanning/VoronoiRoadMap/kdtree.py | 49 ------------- .../VoronoiRoadMap/voronoi_road_map.py | 29 ++++---- 5 files changed, 31 insertions(+), 164 deletions(-) delete mode 100644 PathPlanning/VoronoiRoadMap/kdtree.py diff --git a/PathPlanning/HybridAStar/car.py b/PathPlanning/HybridAStar/car.py index 9b956a0877..cc7529b9c7 100644 --- a/PathPlanning/HybridAStar/car.py +++ b/PathPlanning/HybridAStar/car.py @@ -31,7 +31,7 @@ def check_car_collision(x_list, y_list, yaw_list, ox, oy, kd_tree): cx = i_x + W_BUBBLE_DIST * cos(i_yaw) cy = i_y + W_BUBBLE_DIST * sin(i_yaw) - ids = kd_tree.search_in_distance([cx, cy], W_BUBBLE_R) + ids = kd_tree.query_ball_point([cx, cy], W_BUBBLE_R) if not ids: continue @@ -71,7 +71,7 @@ def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): def plot_car(x, y, yaw): car_color = '-k' c, s = cos(yaw), sin(yaw) - rot = Rot.from_euler('z', yaw).as_matrix()[0:2, 0:2] + rot = Rot.from_euler('z', -yaw).as_matrix()[0:2, 0:2] car_outline_x, car_outline_y = [], [] for rx, ry in zip(VRX, VRY): converted_xy = np.stack([rx, ry]).T @ rot diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index ff9b3fe43b..45d6e11b18 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -13,7 +13,7 @@ import matplotlib.pyplot as plt import numpy as np -import scipy.spatial +from scipy.spatial import cKDTree sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../ReedsSheppPath") @@ -67,44 +67,6 @@ def __init__(self, x_list, y_list, yaw_list, direction_list, cost): self.cost = cost -class KDTree: - """ - Nearest neighbor search class with KDTree - """ - - def __init__(self, data): - # store kd-tree - self.tree = scipy.spatial.cKDTree(data) - - def search(self, inp, k=1): - """ - Search NN - inp: input data, single frame or multi frame - """ - - if len(inp.shape) >= 2: # multi input - index = [] - dist = [] - - for i in inp.T: - i_dist, i_index = self.tree.query(i, k=k) - index.append(i_index) - dist.append(i_dist) - - return index, dist - - dist, index = self.tree.query(inp, k=k) - return index, dist - - def search_in_distance(self, inp, r): - """ - find points with in a distance r - """ - - index = self.tree.query_ball_point(inp, r) - return index - - class Config: def __init__(self, ox, oy, xy_resolution, yaw_resolution): @@ -297,7 +259,7 @@ def hybrid_a_star_planning(start, goal, ox, oy, xy_resolution, yaw_resolution): start[2], goal[2] = rs.pi_2_pi(start[2]), rs.pi_2_pi(goal[2]) tox, toy = ox[:], oy[:] - obstacle_kd_tree = KDTree(np.vstack((tox, toy)).T) + obstacle_kd_tree = cKDTree(np.vstack((tox, toy)).T) config = Config(tox, toy, xy_resolution, yaw_resolution) diff --git a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py index 790db074c0..8681420e2d 100644 --- a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py +++ b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py @@ -9,8 +9,8 @@ import random import math import numpy as np -import scipy.spatial import matplotlib.pyplot as plt +from scipy.spatial import cKDTree # parameter N_SAMPLE = 500 # number of sample_points @@ -36,49 +36,9 @@ def __str__(self): str(self.cost) + "," + str(self.parent_index) -class KDTree: - """ - Nearest neighbor search class with KDTree - """ - - def __init__(self, data): - # store kd-tree - self.tree = scipy.spatial.cKDTree(data) - - def search(self, inp, k=1): - """ - Search NN - - inp: input data, single frame or multi frame - - """ - - if len(inp.shape) >= 2: # multi input - index = [] - dist = [] - - for i in inp.T: - i_dist, i_index = self.tree.query(i, k=k) - index.append(i_index) - dist.append(i_dist) - - return index, dist - - dist, index = self.tree.query(inp, k=k) - return index, dist - - def search_in_distance(self, inp, r): - """ - find points with in a distance r - """ - - index = self.tree.query_ball_point(inp, r) - return index - - def prm_planning(sx, sy, gx, gy, ox, oy, rr): - obstacle_kd_tree = KDTree(np.vstack((ox, oy)).T) + obstacle_kd_tree = cKDTree(np.vstack((ox, oy)).T) sample_x, sample_y = sample_points(sx, sy, gx, gy, rr, ox, oy, obstacle_kd_tree) @@ -108,15 +68,15 @@ def is_collision(sx, sy, gx, gy, rr, obstacle_kd_tree): n_step = round(d / D) for i in range(n_step): - _, dist = obstacle_kd_tree.search(np.array([x, y]).reshape(2, 1)) - if dist[0] <= rr: + dist, _ = obstacle_kd_tree.query([x, y]) + if dist <= rr: return True # collision x += D * math.cos(yaw) y += D * math.sin(yaw) # goal point check - _, dist = obstacle_kd_tree.search(np.array([gx, gy]).reshape(2, 1)) - if dist[0] <= rr: + dist, _ = obstacle_kd_tree.query([gx, gy]) + if dist <= rr: return True # collision return False # OK @@ -134,22 +94,19 @@ def generate_road_map(sample_x, sample_y, rr, obstacle_kd_tree): road_map = [] n_sample = len(sample_x) - sample_kd_tree = KDTree(np.vstack((sample_x, sample_y)).T) + sample_kd_tree = cKDTree(np.vstack((sample_x, sample_y)).T) for (i, ix, iy) in zip(range(n_sample), sample_x, sample_y): - index, dists = sample_kd_tree.search( - np.array([ix, iy]).reshape(2, 1), k=n_sample) - inds = index[0] + dists, indexes = sample_kd_tree.query([ix, iy], k=n_sample) edge_id = [] - # print(index) - for ii in range(1, len(inds)): - nx = sample_x[inds[ii]] - ny = sample_y[inds[ii]] + for ii in range(1, len(indexes)): + nx = sample_x[indexes[ii]] + ny = sample_y[indexes[ii]] if not is_collision(ix, iy, nx, ny, rr, obstacle_kd_tree): - edge_id.append(inds[ii]) + edge_id.append(indexes[ii]) if len(edge_id) >= N_KNN: break @@ -270,9 +227,9 @@ def sample_points(sx, sy, gx, gy, rr, ox, oy, obstacle_kd_tree): tx = (random.random() * (max_x - min_x)) + min_x ty = (random.random() * (max_y - min_y)) + min_y - index, dist = obstacle_kd_tree.search(np.array([tx, ty]).reshape(2, 1)) + dist, index = obstacle_kd_tree.query([tx, ty]) - if dist[0] >= rr: + if dist >= rr: sample_x.append(tx) sample_y.append(ty) diff --git a/PathPlanning/VoronoiRoadMap/kdtree.py b/PathPlanning/VoronoiRoadMap/kdtree.py deleted file mode 100644 index d3dc01b1f6..0000000000 --- a/PathPlanning/VoronoiRoadMap/kdtree.py +++ /dev/null @@ -1,49 +0,0 @@ -""" - -Kd tree Search library - -author: Atsushi Sakai (@Atsushi_twi) - -""" - -import scipy.spatial - - -class KDTree: - """ - Nearest neighbor search class with KDTree - """ - - def __init__(self, data): - # store kd-tree - self.tree = scipy.spatial.cKDTree(data) - - def search(self, inp, k=1): - """ - Search NN - - inp: input data, single frame or multi frame - - """ - - if len(inp.shape) >= 2: # multi input - index = [] - dist = [] - - for i in inp.T: - idist, iindex = self.tree.query(i, k=k) - index.append(iindex) - dist.append(idist) - - return index, dist - - dist, index = self.tree.query(inp, k=k) - return index, dist - - def search_in_distance(self, inp, r): - """ - find points with in a distance r - """ - - index = self.tree.query_ball_point(inp, r) - return index diff --git a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py index d060c8e46c..d184230fd5 100644 --- a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py +++ b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py @@ -8,10 +8,9 @@ import math import numpy as np -import scipy.spatial import matplotlib.pyplot as plt from dijkstra_search import DijkstraSearch -from kdtree import KDTree +from scipy.spatial import cKDTree, Voronoi show_animation = True @@ -24,7 +23,7 @@ def __init__(self): self.MAX_EDGE_LEN = 30.0 # [m] Maximum edge length def planning(self, sx, sy, gx, gy, ox, oy, robot_radius): - obstacle_tree = KDTree(np.vstack((ox, oy)).T) + obstacle_tree = cKDTree(np.vstack((ox, oy)).T) sample_x, sample_y = self.voronoi_sampling(sx, sy, gx, gy, ox, oy) if show_animation: # pragma: no cover @@ -53,15 +52,15 @@ def is_collision(self, sx, sy, gx, gy, rr, obstacle_kd_tree): n_step = round(d / D) for i in range(n_step): - ids, dist = obstacle_kd_tree.search(np.array([x, y]).reshape(2, 1)) - if dist[0] <= rr: + dist, _ = obstacle_kd_tree.query([x, y]) + if dist <= rr: return True # collision x += D * math.cos(yaw) y += D * math.sin(yaw) # goal point check - ids, dist = obstacle_kd_tree.search(np.array([gx, gy]).reshape(2, 1)) - if dist[0] <= rr: + dist, _ = obstacle_kd_tree.query([gx, gy]) + if dist <= rr: return True # collision return False # OK @@ -78,22 +77,20 @@ def generate_road_map_info(self, node_x, node_y, rr, obstacle_tree): road_map = [] n_sample = len(node_x) - node_tree = KDTree(np.vstack((node_x, node_y)).T) + node_tree = cKDTree(np.vstack((node_x, node_y)).T) for (i, ix, iy) in zip(range(n_sample), node_x, node_y): - index, dists = node_tree.search( - np.array([ix, iy]).reshape(2, 1), k=n_sample) + dists, indexes = node_tree.query([ix, iy], k=n_sample) - inds = index[0] edge_id = [] - for ii in range(1, len(inds)): - nx = node_x[inds[ii]] - ny = node_y[inds[ii]] + for ii in range(1, len(indexes)): + nx = node_x[indexes[ii]] + ny = node_y[indexes[ii]] if not self.is_collision(ix, iy, nx, ny, rr, obstacle_tree): - edge_id.append(inds[ii]) + edge_id.append(indexes[ii]) if len(edge_id) >= self.N_KNN: break @@ -119,7 +116,7 @@ def voronoi_sampling(sx, sy, gx, gy, ox, oy): oxy = np.vstack((ox, oy)).T # generate voronoi point - vor = scipy.spatial.Voronoi(oxy) + vor = Voronoi(oxy) sample_x = [ix for [ix, _] in vor.vertices] sample_y = [iy for [_, iy] in vor.vertices] From fa1585d880ea771abd4215077eb699d194486eb4 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 8 Jun 2020 21:43:37 +0900 Subject: [PATCH 275/940] fix scanning error (#339) --- .../random_forward_kinematics.py | 16 +- .../random_inverse_kinematics.py | 12 +- Bipedal/bipedal_planner/bipedal_planner.py | 3 +- .../inverted_pendulum_mpc_control.py | 28 ++- .../lidar_to_grid_map/lidar_to_grid_map.py | 3 +- .../batch_informed_rrtstar.py | 158 ++++++++------ .../bidirectional_a_star.py | 135 ++++++------ .../bidirectional_breadth_first_search.py | 142 ++++++------ .../VoronoiRoadMap/dijkstra_search.py | 1 + PathTracking/cgmres_nmpc/cgmres_nmpc.py | 206 ++++++++++-------- ..._grid_based_sweep_coverage_path_planner.py | 175 ++++++++------- 11 files changed, 487 insertions(+), 392 deletions(-) diff --git a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py index b3426e53e8..f9caace300 100644 --- a/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py +++ b/ArmNavigation/n_joint_arm_3d/random_forward_kinematics.py @@ -11,10 +11,9 @@ def random_val(min_val, max_val): return min_val + random.random() * (max_val - min_val) -if __name__ == "__main__": +def main(): print("Start solving Forward Kinematics 10 times") - - # init NLinkArm with Denavit-Hartenberg parameters of PR2 + # init NLinkArm with Denavit-Hartenberg parameters of PR2 n_link_arm = NLinkArm([[0., -math.pi / 2, .1, 0.], [math.pi / 2, math.pi / 2, 0., 0.], [0., -math.pi / 2, 0., .4], @@ -22,10 +21,13 @@ def random_val(min_val, max_val): [0., -math.pi / 2, 0., .321], [0., math.pi / 2, 0., 0.], [0., 0., 0., 0.]]) - # execute FK 10 times - for i in range(10): + for _ in range(10): n_link_arm.set_joint_angles( - [random_val(-1, 1) for j in range(len(n_link_arm.link_list))]) + [random_val(-1, 1) for _ in range(len(n_link_arm.link_list))]) - ee_pose = n_link_arm.forward_kinematics(plot=True) + n_link_arm.forward_kinematics(plot=True) + + +if __name__ == "__main__": + main() diff --git a/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py index a3838a6a38..91f6f1bba0 100644 --- a/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py +++ b/ArmNavigation/n_joint_arm_3d/random_inverse_kinematics.py @@ -11,10 +11,9 @@ def random_val(min_val, max_val): return min_val + random.random() * (max_val - min_val) -if __name__ == "__main__": +def main(): print("Start solving Inverse Kinematics 10 times") - - # init NLinkArm with Denavit-Hartenberg parameters of PR2 + # init NLinkArm with Denavit-Hartenberg parameters of PR2 n_link_arm = NLinkArm([[0., -math.pi / 2, .1, 0.], [math.pi / 2, math.pi / 2, 0., 0.], [0., -math.pi / 2, 0., .4], @@ -22,12 +21,15 @@ def random_val(min_val, max_val): [0., -math.pi / 2, 0., .321], [0., math.pi / 2, 0., 0.], [0., 0., 0., 0.]]) - # execute IK 10 times - for i in range(10): + for _ in range(10): n_link_arm.inverse_kinematics([random_val(-0.5, 0.5), random_val(-0.5, 0.5), random_val(-0.5, 0.5), random_val(-0.5, 0.5), random_val(-0.5, 0.5), random_val(-0.5, 0.5)], plot=True) + + +if __name__ == "__main__": + main() diff --git a/Bipedal/bipedal_planner/bipedal_planner.py b/Bipedal/bipedal_planner/bipedal_planner.py index 60c03024bf..01df63034f 100644 --- a/Bipedal/bipedal_planner/bipedal_planner.py +++ b/Bipedal/bipedal_planner/bipedal_planner.py @@ -46,9 +46,8 @@ def walk(self, t_sup=0.8, z_c=0.8, a=10, b=1, plot=False): print("No footsteps") return - com_trajectory_for_plot, ax = None, None - # set up plotter + com_trajectory_for_plot, ax = None, None if plot: fig = plt.figure() ax = Axes3D(fig) diff --git a/InvertedPendulumCart/inverted_pendulum_mpc_control.py b/InvertedPendulumCart/inverted_pendulum_mpc_control.py index caf0c23e77..e7b3077740 100644 --- a/InvertedPendulumCart/inverted_pendulum_mpc_control.py +++ b/InvertedPendulumCart/inverted_pendulum_mpc_control.py @@ -3,11 +3,12 @@ author: Atsushi Sakai """ -import matplotlib.pyplot as plt -import numpy as np import math import time + import cvxpy +import matplotlib.pyplot as plt +import numpy as np # Model parameters @@ -39,10 +40,11 @@ def main(): for i in range(50): # calc control input - optimized_x, optimized_delta_x, optimized_theta, optimized_delta_theta, optimized_input = mpc_control(x) + opt_x, opt_delta_x, opt_theta, opt_delta_theta, opt_input = \ + mpc_control(x) # get input - u = optimized_input[0] + u = opt_input[0] # simulate inverted pendulum cart x = simulation(x, u) @@ -86,17 +88,19 @@ def mpc_control(x0): print("calc time:{0} [sec]".format(elapsed_time)) if prob.status == cvxpy.OPTIMAL: - ox = get_nparray_from_matrix(x.value[0, :]) - dx = get_nparray_from_matrix(x.value[1, :]) - theta = get_nparray_from_matrix(x.value[2, :]) - dtheta = get_nparray_from_matrix(x.value[3, :]) + ox = get_numpy_array_from_matrix(x.value[0, :]) + dx = get_numpy_array_from_matrix(x.value[1, :]) + theta = get_numpy_array_from_matrix(x.value[2, :]) + d_theta = get_numpy_array_from_matrix(x.value[3, :]) - ou = get_nparray_from_matrix(u.value[0, :]) + ou = get_numpy_array_from_matrix(u.value[0, :]) + else: + ox, dx, theta, d_theta, ou = None, None, None, None, None - return ox, dx, theta, dtheta, ou + return ox, dx, theta, d_theta, ou -def get_nparray_from_matrix(x): +def get_numpy_array_from_matrix(x): """ get build-in list from matrix """ @@ -133,7 +137,7 @@ def plot_cart(xt, theta): radius = 0.1 cx = np.array([-cart_w / 2.0, cart_w / 2.0, cart_w / - 2.0, -cart_w / 2.0, -cart_w / 2.0]) + 2.0, -cart_w / 2.0, -cart_w / 2.0]) cy = np.array([0.0, 0.0, cart_h, cart_h, 0.0]) cy += radius * 2.0 diff --git a/Mapping/lidar_to_grid_map/lidar_to_grid_map.py b/Mapping/lidar_to_grid_map/lidar_to_grid_map.py index 911a0bf0ea..57278d4a47 100644 --- a/Mapping/lidar_to_grid_map/lidar_to_grid_map.py +++ b/Mapping/lidar_to_grid_map/lidar_to_grid_map.py @@ -19,7 +19,8 @@ def file_read(f): """ Reading LIDAR laser beams (angles and corresponding distance data) """ - measures = [line.split(",") for line in open(f)] + with open(f) as data: + measures = [line.split(",") for line in data] angles = [] distances = [] for measure in measures: diff --git a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py index 227b3f9d25..b5eabbb39b 100644 --- a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py +++ b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py @@ -27,7 +27,8 @@ class RTree(object): # Class to represent the explicit tree created # while sampling through the state space - def __init__(self, start=None, lowerLimit=None, upperLimit=None, resolution=1.0): + def __init__(self, start=None, lowerLimit=None, upperLimit=None, + resolution=1.0): if upperLimit is None: upperLimit = [10, 10] @@ -96,10 +97,11 @@ def grid_coordinate_to_node_id(self, coord): def real_world_to_node_id(self, real_coord): # first convert the given coordinates to grid space and then # convert the grid space coordinates to a unique node id - return self.grid_coordinate_to_node_id(self.real_coords_to_grid_coord(real_coord)) + return self.grid_coordinate_to_node_id( + self.real_coords_to_grid_coord(real_coord)) def grid_coord_to_real_world_coord(self, coord): - # This function smaps a grid coordinate in discrete space + # This function maps a grid coordinate in discrete space # to a configuration in the full configuration space config = [0] * self.dimension for i in range(0, len(coord)): @@ -126,7 +128,8 @@ def node_id_to_grid_coord(self, node_id): def node_id_to_real_world_coord(self, nid): # This function maps a node in discrete space to a configuration # in the full configuration space - return self.grid_coord_to_real_world_coord(self.node_id_to_grid_coord(nid)) + return self.grid_coord_to_real_world_coord( + self.node_id_to_grid_coord(nid)) class BITStar(object): @@ -137,9 +140,9 @@ def __init__(self, start, goal, self.start = start self.goal = goal - self.minrand = randArea[0] - self.maxrand = randArea[1] - self.maxIter = maxIter + self.min_rand = randArea[0] + self.max_rand = randArea[1] + self.max_iIter = maxIter self.obstacleList = obstacleList self.startId = None self.goalId = None @@ -186,18 +189,19 @@ def setup_planning(self): [(self.start[1] + self.goal[1]) / 2.0], [0]]) a1 = np.array([[(self.goal[0] - self.start[0]) / cMin], [(self.goal[1] - self.start[1]) / cMin], [0]]) - etheta = math.atan2(a1[1], a1[0]) - # first column of idenity matrix transposed + eTheta = math.atan2(a1[1], a1[0]) + # first column of identity matrix transposed id1_t = np.array([1.0, 0.0, 0.0]).reshape(1, 3) M = np.dot(a1, id1_t) U, S, Vh = np.linalg.svd(M, True, True) C = np.dot(np.dot(U, np.diag( - [1.0, 1.0, np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])), Vh) + [1.0, 1.0, np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])), + Vh) self.samples.update(self.informed_sample( 200, cBest, cMin, xCenter, C)) - return etheta, cMin, xCenter, C, cBest + return eTheta, cMin, xCenter, C, cBest def setup_sample(self, iterations, foundGoal, cMin, xCenter, C, cBest): @@ -228,18 +232,19 @@ def setup_sample(self, iterations, foundGoal, cMin, xCenter, C, cBest): def plan(self, animation=True): - etheta, cMin, xCenter, C, cBest = self.setup_planning() + eTheta, cMin, xCenter, C, cBest = self.setup_planning() iterations = 0 foundGoal = False # run until done - while iterations < self.maxIter: + while iterations < self.max_iIter: cBest = self.setup_sample(iterations, foundGoal, cMin, xCenter, C, cBest) # expand the best vertices until an edge is better than the vertex # this is done because the vertex cost represents the lower bound # on the edge cost - while self.best_vertex_queue_value() <= self.best_edge_queue_value(): + while self.best_vertex_queue_value() <= \ + self.best_edge_queue_value(): self.expand_vertex(self.best_in_vertex_queue()) # add the best edge to the tree @@ -247,11 +252,17 @@ def plan(self, animation=True): self.edge_queue.remove(bestEdge) # Check if this can improve the current solution - estimatedCostOfVertex = self.g_scores[bestEdge[0]] + self.compute_distance_cost( - bestEdge[0], bestEdge[1]) + self.compute_heuristic_cost(bestEdge[1], self.goalId) - estimatedCostOfEdge = self.compute_distance_cost(self.startId, bestEdge[0]) + self.compute_heuristic_cost( - bestEdge[0], bestEdge[1]) + self.compute_heuristic_cost(bestEdge[1], self.goalId) - actualCostOfEdge = self.g_scores[bestEdge[0]] + self.compute_distance_cost(bestEdge[0], bestEdge[1]) + estimatedCostOfVertex = self.g_scores[bestEdge[ + 0]] + self.compute_distance_cost( + bestEdge[0], bestEdge[1]) + self.compute_heuristic_cost( + bestEdge[1], self.goalId) + estimatedCostOfEdge = self.compute_distance_cost( + self.startId, bestEdge[0]) + self.compute_heuristic_cost( + bestEdge[0], bestEdge[1]) + self.compute_heuristic_cost( + bestEdge[1], self.goalId) + actualCostOfEdge = self.g_scores[ + bestEdge[0]] + self.compute_distance_cost( + bestEdge[0], bestEdge[1]) f1 = estimatedCostOfVertex < self.g_scores[self.goalId] f2 = estimatedCostOfEdge < self.g_scores[self.goalId] @@ -277,10 +288,12 @@ def plan(self, animation=True): try: del self.samples[bestEdge[1]] except KeyError: + # invalid sample key pass eid = self.tree.add_vertex(nextCoord) self.vertex_queue.append(eid) - if eid == self.goalId or bestEdge[0] == self.goalId or bestEdge[1] == self.goalId: + if eid == self.goalId or bestEdge[0] == self.goalId or \ + bestEdge[1] == self.goalId: print("Goal found") foundGoal = True @@ -288,14 +301,18 @@ def plan(self, animation=True): g_score = self.compute_distance_cost( bestEdge[0], bestEdge[1]) - self.g_scores[bestEdge[1]] = g_score + self.g_scores[bestEdge[0]] - self.f_scores[bestEdge[1]] = g_score + self.compute_heuristic_cost(bestEdge[1], self.goalId) + self.g_scores[bestEdge[1]] = g_score + self.g_scores[ + bestEdge[0]] + self.f_scores[ + bestEdge[1]] = g_score + self.compute_heuristic_cost( + bestEdge[1], self.goalId) self.update_graph() # visualize new edge if animation: self.draw_graph(xCenter=xCenter, cBest=cBest, - cMin=cMin, etheta=etheta, samples=self.samples.values(), + cMin=cMin, eTheta=eTheta, + samples=self.samples.values(), start=firstCoord, end=secondCoord) self.remove_queue(lastEdge, bestEdge) @@ -330,7 +347,8 @@ def remove_queue(self, lastEdge, bestEdge): for edge in self.edge_queue: if edge[1] == bestEdge[1]: dist_cost = self.compute_distance_cost(edge[1], bestEdge[1]) - if self.g_scores[edge[1]] + dist_cost >= self.g_scores[self.goalId]: + if self.g_scores[edge[1]] + dist_cost >= \ + self.g_scores[self.goalId]: if (lastEdge, bestEdge[1]) in self.edge_queue: self.edge_queue.remove( (lastEdge, bestEdge[1])) @@ -338,8 +356,9 @@ def remove_queue(self, lastEdge, bestEdge): def connect(self, start, end): # A function which attempts to extend from a start coordinates # to goal coordinates - steps = int(self.compute_distance_cost(self.tree.real_world_to_node_id( - start), self.tree.real_world_to_node_id(end)) * 10) + steps = int(self.compute_distance_cost( + self.tree.real_world_to_node_id(start), + self.tree.real_world_to_node_id(end)) * 10) x = np.linspace(start[0], end[0], num=steps) y = np.linspace(start[1], end[1], num=steps) for i in range(len(x)): @@ -409,8 +428,8 @@ def sample_unit_ball(): return np.array([[sample[0]], [sample[1]], [0]]) def sample_free_space(self): - rnd = [random.uniform(self.minrand, self.maxrand), - random.uniform(self.minrand, self.maxrand)] + rnd = [random.uniform(self.min_rand, self.max_rand), + random.uniform(self.min_rand, self.max_rand)] return rnd @@ -418,7 +437,8 @@ def best_vertex_queue_value(self): if len(self.vertex_queue) == 0: return float('inf') values = [self.g_scores[v] - + self.compute_heuristic_cost(v, self.goalId) for v in self.vertex_queue] + + self.compute_heuristic_cost(v, self.goalId) for v in + self.vertex_queue] values.sort() return values[0] @@ -427,21 +447,25 @@ def best_edge_queue_value(self): return float('inf') # return the best value in the queue by score g_tau[v] + c(v,x) + h(x) values = [self.g_scores[e[0]] + self.compute_distance_cost(e[0], e[1]) - + self.compute_heuristic_cost(e[1], self.goalId) for e in self.edge_queue] + + self.compute_heuristic_cost(e[1], self.goalId) for e in + self.edge_queue] values.sort(reverse=True) return values[0] def best_in_vertex_queue(self): # return the best value in the vertex queue - v_plus_vals = [(v, self.g_scores[v] + self.compute_heuristic_cost(v, self.goalId)) - for v in self.vertex_queue] - v_plus_vals = sorted(v_plus_vals, key=lambda x: x[1]) - # print(v_plus_vals) - return v_plus_vals[0][0] + v_plus_values = [(v, self.g_scores[v] + + self.compute_heuristic_cost(v, self.goalId)) + for v in self.vertex_queue] + v_plus_values = sorted(v_plus_values, key=lambda x: x[1]) + # print(v_plus_values) + return v_plus_values[0][0] def best_in_edge_queue(self): - e_and_values = [(e[0], e[1], self.g_scores[e[0]] + self.compute_distance_cost( - e[0], e[1]) + self.compute_heuristic_cost(e[1], self.goalId)) for e in self.edge_queue] + e_and_values = [ + (e[0], e[1], self.g_scores[e[0]] + self.compute_distance_cost( + e[0], e[1]) + self.compute_heuristic_cost(e[1], self.goalId)) + for e in self.edge_queue] e_and_values = sorted(e_and_values, key=lambda x: x[2]) return e_and_values[0][0], e_and_values[0][1] @@ -454,18 +478,19 @@ def expand_vertex(self, vid): # get the nearest value in vertex for every one in samples where difference is # less than the radius - neigbors = [] - for sid, scoord in self.samples.items(): - scoord = np.array(scoord) - if np.linalg.norm(scoord - currCoord, 2) <= self.r and sid != vid: - neigbors.append((sid, scoord)) + neighbors = [] + for sid, s_coord in self.samples.items(): + s_coord = np.array(s_coord) + if np.linalg.norm(s_coord - currCoord, 2) <= self.r and sid != vid: + neighbors.append((sid, s_coord)) # add an edge to the edge queue is the path might improve the solution - for neighbor in neigbors: + for neighbor in neighbors: sid = neighbor[0] h_cost = self.compute_heuristic_cost(sid, self.goalId) estimated_f_score = self.compute_distance_cost( - self.startId, vid) + h_cost + self.compute_distance_cost(vid, sid) + self.startId, vid) + h_cost + self.compute_distance_cost(vid, + sid) if estimated_f_score < self.g_scores[self.goalId]: self.edge_queue.append((vid, sid)) @@ -476,17 +501,21 @@ def add_vertex_to_edge_queue(self, vid, currCoord): if vid not in self.old_vertices: neighbors = [] for v, edges in self.tree.vertices.items(): - if v != vid and (v, vid) not in self.edge_queue and (vid, v) not in self.edge_queue: + if v != vid and (v, vid) not in self.edge_queue and \ + (vid, v) not in self.edge_queue: v_coord = self.tree.node_id_to_real_world_coord(v) if np.linalg.norm(currCoord - v_coord, 2) <= self.r: neighbors.append((vid, v_coord)) for neighbor in neighbors: sid = neighbor[0] - estimated_f_score = self.compute_distance_cost(self.startId, vid) + self.compute_distance_cost( + estimated_f_score = self.compute_distance_cost( + self.startId, vid) + self.compute_distance_cost( vid, sid) + self.compute_heuristic_cost(sid, self.goalId) if estimated_f_score < self.g_scores[self.goalId] and ( - self.g_scores[vid] + self.compute_distance_cost(vid, sid)) < self.g_scores[sid]: + self.g_scores[vid] + + self.compute_distance_cost(vid, sid)) < \ + self.g_scores[sid]: self.edge_queue.append((vid, sid)) def update_graph(self): @@ -511,37 +540,40 @@ def update_graph(self): # find a non visited successor to the current node successors = self.tree.vertices[currId] - for succesor in successors: - if succesor in closedSet: + for successor in successors: + if successor in closedSet: continue else: - # claculate tentative g score + # calculate tentative g score g_score = self.g_scores[currId] + \ - self.compute_distance_cost(currId, succesor) - if succesor not in openSet: + self.compute_distance_cost(currId, successor) + if successor not in openSet: # add the successor to open set - openSet.append(succesor) - elif g_score >= self.g_scores[succesor]: + openSet.append(successor) + elif g_score >= self.g_scores[successor]: continue # update g and f scores - self.g_scores[succesor] = g_score - self.f_scores[succesor] = g_score + self.compute_heuristic_cost(succesor, self.goalId) + self.g_scores[successor] = g_score + self.f_scores[ + successor] = g_score + self.compute_heuristic_cost( + successor, self.goalId) # store the parent and child - self.nodes[succesor] = currId + self.nodes[successor] = currId - def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, + def draw_graph(self, xCenter=None, cBest=None, cMin=None, eTheta=None, samples=None, start=None, end=None): plt.clf() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) for rnd in samples: if rnd is not None: plt.plot(rnd[0], rnd[1], "^k") if cBest != float('inf'): - self.plot_ellipse(xCenter, cBest, cMin, etheta) + self.plot_ellipse(xCenter, cBest, cMin, eTheta) if start is not None and end is not None: plt.plot([start[0], start[1]], [end[0], end[1]], "-g") @@ -556,11 +588,11 @@ def draw_graph(self, xCenter=None, cBest=None, cMin=None, etheta=None, plt.pause(0.01) @staticmethod - def plot_ellipse(xCenter, cBest, cMin, etheta): # pragma: no cover + def plot_ellipse(xCenter, cBest, cMin, eTheta): # pragma: no cover a = math.sqrt(cBest ** 2 - cMin ** 2) / 2.0 b = cBest / 2.0 - angle = math.pi / 2.0 - etheta + angle = math.pi / 2.0 - eTheta cx = xCenter[0] cy = xCenter[1] diff --git a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py index cf76ab67cd..ecb875f410 100644 --- a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py +++ b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py @@ -17,7 +17,7 @@ class BidirectionalAStarPlanner: - def __init__(self, ox, oy, reso, rr): + def __init__(self, ox, oy, resolution, rr): """ Initialize grid map for a star planning @@ -27,21 +27,24 @@ def __init__(self, ox, oy, reso, rr): rr: robot radius[m] """ - self.reso = reso + self.min_x, self.min_y = None, None + self.max_x, self.max_y = None, None + self.x_width, self.y_width, self.obstacle_map = None, None, None + self.resolution = resolution self.rr = rr self.calc_obstacle_map(ox, oy) self.motion = self.get_motion_model() class Node: - def __init__(self, x, y, cost, pind): + def __init__(self, x, y, cost, parent_index): self.x = x # index of grid self.y = y # index of grid self.cost = cost - self.pind = pind + self.parent_index = parent_index def __str__(self): return str(self.x) + "," + str(self.y) + "," + str( - self.cost) + "," + str(self.pind) + self.cost) + "," + str(self.parent_index) def planning(self, sx, sy, gx, gy): """ @@ -58,18 +61,19 @@ def planning(self, sx, sy, gx, gy): ry: y position list of the final path """ - nstart = self.Node(self.calc_xyindex(sx, self.minx), - self.calc_xyindex(sy, self.miny), 0.0, -1) - ngoal = self.Node(self.calc_xyindex(gx, self.minx), - self.calc_xyindex(gy, self.miny), 0.0, -1) + start_node = self.Node(self.calc_xy_index(sx, self.min_x), + self.calc_xy_index(sy, self.min_y), 0.0, -1) + goal_node = self.Node(self.calc_xy_index(gx, self.min_x), + self.calc_xy_index(gy, self.min_y), 0.0, -1) open_set_A, closed_set_A = dict(), dict() open_set_B, closed_set_B = dict(), dict() - open_set_A[self.calc_grid_index(nstart)] = nstart - open_set_B[self.calc_grid_index(ngoal)] = ngoal + open_set_A[self.calc_grid_index(start_node)] = start_node + open_set_B[self.calc_grid_index(goal_node)] = goal_node - current_A = nstart - current_B = ngoal + current_A = start_node + current_B = goal_node + meet_point_A, meet_point_B = None, None while 1: if len(open_set_A) == 0: @@ -94,22 +98,23 @@ def planning(self, sx, sy, gx, gy): # show graph if show_animation: # pragma: no cover - plt.plot(self.calc_grid_position(current_A.x, self.minx), - self.calc_grid_position(current_A.y, self.miny), "xc") - plt.plot(self.calc_grid_position(current_B.x, self.minx), - self.calc_grid_position(current_B.y, self.miny), "xc") + plt.plot(self.calc_grid_position(current_A.x, self.min_x), + self.calc_grid_position(current_A.y, self.min_y), + "xc") + plt.plot(self.calc_grid_position(current_B.x, self.min_x), + self.calc_grid_position(current_B.y, self.min_y), + "xc") # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: - [exit(0) if event.key == 'escape' - else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if len(closed_set_A.keys()) % 10 == 0: plt.pause(0.001) if current_A.x == current_B.x and current_A.y == current_B.y: print("Found goal") - meetpointA = current_A - meetpointB = current_B + meet_point_A = current_A + meet_point_B = current_B break # Remove the item from the open set @@ -158,7 +163,7 @@ def planning(self, sx, sy, gx, gy): open_set_B[n_ids[1]] = c_nodes[1] rx, ry = self.calc_final_bidirectional_path( - meetpointA, meetpointB, closed_set_A, closed_set_B) + meet_point_A, meet_point_B, closed_set_A, closed_set_B) return rx, ry @@ -175,16 +180,16 @@ def calc_final_bidirectional_path(self, n1, n2, setA, setB): return rx, ry - def calc_final_path(self, ngoal, closedset): + def calc_final_path(self, goal_node, closed_set): # generate final course - rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ - self.calc_grid_position(ngoal.y, self.miny)] - pind = ngoal.parent_index - while pind != -1: - n = closedset[pind] - rx.append(self.calc_grid_position(n.x, self.minx)) - ry.append(self.calc_grid_position(n.y, self.miny)) - pind = n.parent_index + rx, ry = [self.calc_grid_position(goal_node.x, self.min_x)], \ + [self.calc_grid_position(goal_node.y, self.min_y)] + parent_index = goal_node.parent_index + while parent_index != -1: + n = closed_set[parent_index] + rx.append(self.calc_grid_position(n.x, self.min_x)) + ry.append(self.calc_grid_position(n.y, self.min_y)) + parent_index = n.parent_index return rx, ry @@ -210,69 +215,69 @@ def find_total_cost(self, open_set, lambda_, n1): f_cost = g_cost + h_cost return f_cost - def calc_grid_position(self, index, minp): + def calc_grid_position(self, index, min_position): """ calc grid position :param index: - :param minp: + :param min_position: :return: """ - pos = index * self.reso + minp + pos = index * self.resolution + min_position return pos - def calc_xyindex(self, position, min_pos): - return round((position - min_pos) / self.reso) + def calc_xy_index(self, position, min_pos): + return round((position - min_pos) / self.resolution) def calc_grid_index(self, node): - return (node.y - self.miny) * self.xwidth + (node.x - self.minx) + return (node.y - self.min_y) * self.x_width + (node.x - self.min_x) def verify_node(self, node): - px = self.calc_grid_position(node.x, self.minx) - py = self.calc_grid_position(node.y, self.miny) + px = self.calc_grid_position(node.x, self.min_x) + py = self.calc_grid_position(node.y, self.min_y) - if px < self.minx: + if px < self.min_x: return False - elif py < self.miny: + elif py < self.min_y: return False - elif px >= self.maxx: + elif px >= self.max_x: return False - elif py >= self.maxy: + elif py >= self.max_y: return False # collision check - if self.obmap[node.x][node.y]: + if self.obstacle_map[node.x][node.y]: return False return True def calc_obstacle_map(self, ox, oy): - self.minx = round(min(ox)) - self.miny = round(min(oy)) - self.maxx = round(max(ox)) - self.maxy = round(max(oy)) - print("min_x:", self.minx) - print("min_y:", self.miny) - print("max_x:", self.maxx) - print("max_y:", self.maxy) + self.min_x = round(min(ox)) + self.min_y = round(min(oy)) + self.max_x = round(max(ox)) + self.max_y = round(max(oy)) + print("min_x:", self.min_x) + print("min_y:", self.min_y) + print("max_x:", self.max_x) + print("max_y:", self.max_y) - self.xwidth = round((self.maxx - self.minx) / self.reso) - self.ywidth = round((self.maxy - self.miny) / self.reso) - print("x_width:", self.xwidth) - print("y_width:", self.ywidth) + self.x_width = round((self.max_x - self.min_x) / self.resolution) + self.y_width = round((self.max_y - self.min_y) / self.resolution) + print("x_width:", self.x_width) + print("y_width:", self.y_width) # obstacle map generation - self.obmap = [[False for _ in range(self.ywidth)] - for _ in range(self.xwidth)] - for ix in range(self.xwidth): - x = self.calc_grid_position(ix, self.minx) - for iy in range(self.ywidth): - y = self.calc_grid_position(iy, self.miny) + self.obstacle_map = [[False for _ in range(self.y_width)] + for _ in range(self.x_width)] + for ix in range(self.x_width): + x = self.calc_grid_position(ix, self.min_x) + for iy in range(self.y_width): + y = self.calc_grid_position(iy, self.min_y) for iox, ioy in zip(ox, oy): d = math.hypot(iox - x, ioy - y) if d <= self.rr: - self.obmap[ix][iy] = True + self.obstacle_map[ix][iy] = True break @staticmethod diff --git a/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py b/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py index 328898db85..dd4282573e 100644 --- a/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py +++ b/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py @@ -17,7 +17,7 @@ class BidirectionalBreadthFirstSearchPlanner: - def __init__(self, ox, oy, reso, rr): + def __init__(self, ox, oy, resolution, rr): """ Initialize grid map for bfs planning @@ -27,22 +27,25 @@ def __init__(self, ox, oy, reso, rr): rr: robot radius[m] """ - self.reso = reso + self.min_x, self.min_y = None, None + self.max_x, self.max_y = None, None + self.x_width, self.y_width, self.obstacle_map = None, None, None + self.resolution = resolution self.rr = rr self.calc_obstacle_map(ox, oy) self.motion = self.get_motion_model() class Node: - def __init__(self, x, y, cost, pind, parent): + def __init__(self, x, y, cost, parent_index, parent): self.x = x # index of grid self.y = y # index of grid self.cost = cost - self.pind = pind + self.parent_index = parent_index self.parent = parent def __str__(self): return str(self.x) + "," + str(self.y) + "," + str( - self.cost) + "," + str(self.pind) + self.cost) + "," + str(self.parent_index) def planning(self, sx, sy, gx, gy): """ @@ -59,15 +62,19 @@ def planning(self, sx, sy, gx, gy): ry: y position list of the final path """ - nstart = self.Node(self.calc_xyindex(sx, self.minx), - self.calc_xyindex(sy, self.miny), 0.0, -1, None) - ngoal = self.Node(self.calc_xyindex(gx, self.minx), - self.calc_xyindex(gy, self.miny), 0.0, -1, None) + start_node = self.Node(self.calc_xy_index(sx, self.min_x), + self.calc_xy_index(sy, self.min_y), 0.0, -1, + None) + goal_node = self.Node(self.calc_xy_index(gx, self.min_x), + self.calc_xy_index(gy, self.min_y), 0.0, -1, + None) open_set_A, closed_set_A = dict(), dict() open_set_B, closed_set_B = dict(), dict() - open_set_B[self.calc_grid_index(ngoal)] = ngoal - open_set_A[self.calc_grid_index(nstart)] = nstart + open_set_B[self.calc_grid_index(goal_node)] = goal_node + open_set_A[self.calc_grid_index(start_node)] = start_node + + meet_point_A, meet_point_B = None, None while 1: if len(open_set_A) == 0: @@ -89,28 +96,29 @@ def planning(self, sx, sy, gx, gy): # show graph if show_animation: # pragma: no cover - plt.plot(self.calc_grid_position(current_A.x, self.minx), - self.calc_grid_position(current_A.y, self.miny), "xc") - plt.plot(self.calc_grid_position(current_B.x, self.minx), - self.calc_grid_position(current_B.y, self.miny), "xc") + plt.plot(self.calc_grid_position(current_A.x, self.min_x), + self.calc_grid_position(current_A.y, self.min_y), + "xc") + plt.plot(self.calc_grid_position(current_B.x, self.min_x), + self.calc_grid_position(current_B.y, self.min_y), + "xc") # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: - [exit(0) if - event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if len(closed_set_A.keys()) % 10 == 0: plt.pause(0.001) if c_id_A in closed_set_B: print("Find goal") - meetpointA = closed_set_A[c_id_A] - meetpointB = closed_set_B[c_id_A] + meet_point_A = closed_set_A[c_id_A] + meet_point_B = closed_set_B[c_id_A] break elif c_id_B in closed_set_A: print("Find goal") - meetpointA = closed_set_A[c_id_B] - meetpointB = closed_set_B[c_id_B] + meet_point_A = closed_set_A[c_id_B] + meet_point_B = closed_set_B[c_id_B] break # expand_grid search grid based on motion model @@ -137,20 +145,18 @@ def planning(self, sx, sy, gx, gy): if not self.verify_node(node_B): breakB = True - if (n_id_A not in closed_set_A) and (n_id_A not in - open_set_A) and (not - breakA): + if (n_id_A not in closed_set_A) and \ + (n_id_A not in open_set_A) and (not breakA): node_A.parent = current_A open_set_A[n_id_A] = node_A - if (n_id_B not in closed_set_B) and (n_id_B not in - open_set_B) and (not - breakB): + if (n_id_B not in closed_set_B) and \ + (n_id_B not in open_set_B) and (not breakB): node_B.parent = current_B open_set_B[n_id_B] = node_B rx, ry = self.calc_final_path_bidir( - meetpointA, meetpointB, closed_set_A, closed_set_B) + meet_point_A, meet_point_B, closed_set_A, closed_set_B) return rx, ry # takes both set and meeting nodes and calculate optimal path @@ -166,81 +172,81 @@ def calc_final_path_bidir(self, n1, n2, setA, setB): return rx, ry - def calc_final_path(self, ngoal, closedset): + def calc_final_path(self, goal_node, closed_set): # generate final course - rx, ry = [self.calc_grid_position(ngoal.x, self.minx)], [ - self.calc_grid_position(ngoal.y, self.miny)] - n = closedset[ngoal.parent_index] + rx, ry = [self.calc_grid_position(goal_node.x, self.min_x)], [ + self.calc_grid_position(goal_node.y, self.min_y)] + n = closed_set[goal_node.parent_index] while n is not None: - rx.append(self.calc_grid_position(n.x, self.minx)) - ry.append(self.calc_grid_position(n.y, self.miny)) + rx.append(self.calc_grid_position(n.x, self.min_x)) + ry.append(self.calc_grid_position(n.y, self.min_y)) n = n.parent return rx, ry - def calc_grid_position(self, index, minp): + def calc_grid_position(self, index, min_position): """ calc grid position :param index: - :param minp: + :param min_position: :return: """ - pos = index * self.reso + minp + pos = index * self.resolution + min_position return pos - def calc_xyindex(self, position, min_pos): - return round((position - min_pos) / self.reso) + def calc_xy_index(self, position, min_pos): + return round((position - min_pos) / self.resolution) def calc_grid_index(self, node): - return (node.y - self.miny) * self.xwidth + (node.x - self.minx) + return (node.y - self.min_y) * self.x_width + (node.x - self.min_x) def verify_node(self, node): - px = self.calc_grid_position(node.x, self.minx) - py = self.calc_grid_position(node.y, self.miny) + px = self.calc_grid_position(node.x, self.min_x) + py = self.calc_grid_position(node.y, self.min_y) - if px < self.minx: + if px < self.min_x: return False - elif py < self.miny: + elif py < self.min_y: return False - elif px >= self.maxx: + elif px >= self.max_x: return False - elif py >= self.maxy: + elif py >= self.max_y: return False # collision check - if self.obmap[node.x][node.y]: + if self.obstacle_map[node.x][node.y]: return False return True def calc_obstacle_map(self, ox, oy): - self.minx = round(min(ox)) - self.miny = round(min(oy)) - self.maxx = round(max(ox)) - self.maxy = round(max(oy)) - print("min_x:", self.minx) - print("min_y:", self.miny) - print("max_x:", self.maxx) - print("max_y:", self.maxy) + self.min_x = round(min(ox)) + self.min_y = round(min(oy)) + self.max_x = round(max(ox)) + self.max_y = round(max(oy)) + print("min_x:", self.min_x) + print("min_y:", self.min_y) + print("max_x:", self.max_x) + print("max_y:", self.max_y) - self.xwidth = round((self.maxx - self.minx) / self.reso) - self.ywidth = round((self.maxy - self.miny) / self.reso) - print("x_width:", self.xwidth) - print("y_width:", self.ywidth) + self.x_width = round((self.max_x - self.min_x) / self.resolution) + self.y_width = round((self.max_y - self.min_y) / self.resolution) + print("x_width:", self.x_width) + print("y_width:", self.y_width) # obstacle map generation - self.obmap = [[False for _ in range(self.ywidth)] - for _ in range(self.xwidth)] - for ix in range(self.xwidth): - x = self.calc_grid_position(ix, self.minx) - for iy in range(self.ywidth): - y = self.calc_grid_position(iy, self.miny) + self.obstacle_map = [[False for _ in range(self.y_width)] + for _ in range(self.x_width)] + for ix in range(self.x_width): + x = self.calc_grid_position(ix, self.min_x) + for iy in range(self.y_width): + y = self.calc_grid_position(iy, self.min_y) for iox, ioy in zip(ox, oy): d = math.hypot(iox - x, ioy - y) if d <= self.rr: - self.obmap[ix][iy] = True + self.obstacle_map[ix][iy] = True break @staticmethod diff --git a/PathPlanning/VoronoiRoadMap/dijkstra_search.py b/PathPlanning/VoronoiRoadMap/dijkstra_search.py index 54d15ea9fb..aef07ebbaf 100644 --- a/PathPlanning/VoronoiRoadMap/dijkstra_search.py +++ b/PathPlanning/VoronoiRoadMap/dijkstra_search.py @@ -125,6 +125,7 @@ def find_id(self, node_x_list, node_y_list, target_node): if self.is_same_node_with_xy(node_x_list[i], node_y_list[i], target_node): return i + return None @staticmethod def is_same_node_with_xy(node_x, node_y, node_b): diff --git a/PathTracking/cgmres_nmpc/cgmres_nmpc.py b/PathTracking/cgmres_nmpc/cgmres_nmpc.py index 98a12ab10c..bb5699b888 100644 --- a/PathTracking/cgmres_nmpc/cgmres_nmpc.py +++ b/PathTracking/cgmres_nmpc/cgmres_nmpc.py @@ -5,17 +5,18 @@ author Atsushi Sakai (@Atsushi_twi) Ref: - -- Shunichi09/nonlinear_control: Implementing the nonlinear model predictive control, sliding mode control https://github.com/Shunichi09/nonlinear_control +Shunichi09/nonlinear_control: Implementing the nonlinear model predictive +control, sliding mode control https://github.com/Shunichi09/nonlinear_control """ -import numpy as np +from math import cos, sin, radians, atan2 + import matplotlib.pyplot as plt -import math +import numpy as np U_A_MAX = 1.0 -U_OMEGA_MAX = math.radians(45.0) +U_OMEGA_MAX = radians(45.0) PHI_V = 0.01 PHI_OMEGA = 0.01 WB = 0.25 # [m] wheel base @@ -24,19 +25,18 @@ def differential_model(v, yaw, u_1, u_2): - - dx = math.cos(yaw) * v - dy = math.sin(yaw) * v + dx = cos(yaw) * v + dy = sin(yaw) * v dv = u_1 - dyaw = v / WB * math.sin(u_2) # tan is not good for nonlinear optimization + # tangent is not good for nonlinear optimization + d_yaw = v / WB * sin(u_2) - return dx, dy, dyaw, dv + return dx, dy, d_yaw, dv -class TwoWheeledSystem(): +class TwoWheeledSystem: def __init__(self, init_x, init_y, init_yaw, init_v): - self.x = init_x self.y = init_y self.yaw = init_yaw @@ -47,12 +47,11 @@ def __init__(self, init_x, init_y, init_yaw, init_v): self.history_v = [init_v] def update_state(self, u_1, u_2, dt=0.01): - - dx, dy, dyaw, dv = differential_model(self.v, self.yaw, u_1, u_2) + dx, dy, d_yaw, dv = differential_model(self.v, self.yaw, u_1, u_2) self.x += dt * dx self.y += dt * dy - self.yaw += dt * dyaw + self.yaw += dt * d_yaw self.v += dt * dv # save @@ -62,13 +61,15 @@ def update_state(self, u_1, u_2, dt=0.01): self.history_v.append(self.v) -class NMPCSimulatorSystem(): +class NMPCSimulatorSystem: def calc_predict_and_adjoint_state(self, x, y, yaw, v, u_1s, u_2s, N, dt): + # by using state equation x_s, y_s, yaw_s, v_s = self._calc_predict_states( - x, y, yaw, v, u_1s, u_2s, N, dt) # by using state equation + x, y, yaw, v, u_1s, u_2s, N, dt) + # by using adjoint equation lam_1s, lam_2s, lam_3s, lam_4s = self._calc_adjoint_states( - x_s, y_s, yaw_s, v_s, u_1s, u_2s, N, dt) # by using adjoint equation + x_s, y_s, yaw_s, v_s, u_2s, N, dt) return x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s @@ -88,7 +89,7 @@ def _calc_predict_states(self, x, y, yaw, v, u_1s, u_2s, N, dt): return x_s, y_s, yaw_s, v_s - def _calc_adjoint_states(self, x_s, y_s, yaw_s, v_s, u_1s, u_2s, N, dt): + def _calc_adjoint_states(self, x_s, y_s, yaw_s, v_s, u_2s, N, dt): lam_1s = [x_s[-1]] lam_2s = [y_s[-1]] lam_3s = [yaw_s[-1]] @@ -97,8 +98,8 @@ def _calc_adjoint_states(self, x_s, y_s, yaw_s, v_s, u_1s, u_2s, N, dt): # backward adjoint state calc for i in range(N - 1, 0, -1): temp_lam_1, temp_lam_2, temp_lam_3, temp_lam_4 = self._adjoint_state_with_oylar( - x_s[i], y_s[i], yaw_s[i], v_s[i], lam_1s[0], lam_2s[0], lam_3s[0], lam_4s[0], - u_1s[i], u_2s[i], dt) + yaw_s[i], v_s[i], lam_1s[0], lam_2s[0], lam_3s[0], lam_4s[0], + u_2s[i], dt) lam_1s.insert(0, temp_lam_1) lam_2s.insert(0, temp_lam_2) lam_3s.insert(0, temp_lam_3) @@ -106,7 +107,8 @@ def _calc_adjoint_states(self, x_s, y_s, yaw_s, v_s, u_1s, u_2s, N, dt): return lam_1s, lam_2s, lam_3s, lam_4s - def _predict_state_with_oylar(self, x, y, yaw, v, u_1, u_2, dt): + @staticmethod + def _predict_state_with_oylar(x, y, yaw, v, u_1, u_2, dt): dx, dy, dyaw, dv = differential_model( v, yaw, u_1, u_2) @@ -118,21 +120,21 @@ def _predict_state_with_oylar(self, x, y, yaw, v, u_1, u_2, dt): return next_x_1, next_x_2, next_x_3, next_x_4 - def _adjoint_state_with_oylar(self, x, y, yaw, v, lam_1, lam_2, lam_3, lam_4, u_1, u_2, dt): + @staticmethod + def _adjoint_state_with_oylar(yaw, v, lam_1, lam_2, lam_3, lam_4, u_2, dt): # ∂H/∂x pre_lam_1 = lam_1 + dt * 0.0 pre_lam_2 = lam_2 + dt * 0.0 - pre_lam_3 = lam_3 + dt * \ - (- lam_1 * math.sin(yaw) * v + lam_2 * math.cos(yaw) * v) - pre_lam_4 = lam_4 + dt * \ - (lam_1 * math.cos(yaw) + lam_2 * - math.sin(yaw) + lam_3 * math.sin(u_2) / WB) + tmp1 = - lam_1 * sin(yaw) * v + lam_2 * cos(yaw) * v + pre_lam_3 = lam_3 + dt * tmp1 + tmp2 = lam_1 * cos(yaw) + lam_2 * sin(yaw) + lam_3 * sin(u_2) / WB + pre_lam_4 = lam_4 + dt * tmp2 return pre_lam_1, pre_lam_2, pre_lam_3, pre_lam_4 -class NMPCController_with_CGMRES(): +class NMPCControllerCGMRES: """ Attributes ------------ @@ -145,7 +147,7 @@ class NMPCController_with_CGMRES(): alpha : float gain of predict time N : int - predicte step, discritize value + predict step, discrete value threshold : float cgmres's threshold value input_num : int @@ -226,20 +228,22 @@ def calc_input(self, x, y, yaw, v, time): dx_4 = x_4_dot * self.ht x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s = self.simulator.calc_predict_and_adjoint_state( - x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s, self.u_2s, self.N, dt) + x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s, self.u_2s, + self.N, dt) # Fxt:F(U,x+hx˙,t+h) - Fxt = self._calc_f(x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s, - self.u_1s, self.u_2s, self.dummy_u_1s, self.dummy_u_2s, - self.raw_1s, self.raw_2s, self.N, dt) + Fxt = self._calc_f(v_s, lam_3s, lam_4s, + self.u_1s, self.u_2s, self.dummy_u_1s, + self.dummy_u_2s, + self.raw_1s, self.raw_2s, self.N) # F:F(U,x,t) x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s = self.simulator.calc_predict_and_adjoint_state( x, y, yaw, v, self.u_1s, self.u_2s, self.N, dt) - F = self._calc_f(x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s, + F = self._calc_f(v_s, lam_3s, lam_4s, self.u_1s, self.u_2s, self.dummy_u_1s, self.dummy_u_2s, - self.raw_1s, self.raw_2s, self.N, dt) + self.raw_1s, self.raw_2s, self.N) right = -self.zeta * F - ((Fxt - F) / self.ht) @@ -251,17 +255,19 @@ def calc_input(self, x, y, yaw, v, time): draw_2 = self.raw_2s * self.ht x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s = self.simulator.calc_predict_and_adjoint_state( - x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s + du_1, self.u_2s + du_2, self.N, dt) + x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s + du_1, + self.u_2s + du_2, self.N, dt) # Fuxt:F(U+hdU(0),x+hx˙,t+h) - Fuxt = self._calc_f(x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s, + Fuxt = self._calc_f(v_s, lam_3s, lam_4s, self.u_1s + du_1, self.u_2s + du_2, - self.dummy_u_1s + ddummy_u_1, self.dummy_u_2s + ddummy_u_2, - self.raw_1s + draw_1, self.raw_2s + draw_2, self.N, dt) + self.dummy_u_1s + ddummy_u_1, + self.dummy_u_2s + ddummy_u_2, + self.raw_1s + draw_1, self.raw_2s + draw_2, self.N) left = ((Fuxt - Fxt) / self.ht) - # calculationg cgmres + # calculating cgmres r0 = right - left r0_norm = np.linalg.norm(r0) @@ -276,6 +282,9 @@ def calc_input(self, x, y, yaw, v, time): ys_pre = None + du_1_new, du_2_new, draw_1_new, draw_2_new = None, None, None, None + ddummy_u_1_new, ddummy_u_2_new = None, None + for i in range(self.max_iteration): du_1 = vs[::self.input_num, i] * self.ht du_2 = vs[1::self.input_num, i] * self.ht @@ -285,12 +294,15 @@ def calc_input(self, x, y, yaw, v, time): draw_2 = vs[5::self.input_num, i] * self.ht x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s = self.simulator.calc_predict_and_adjoint_state( - x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s + du_1, self.u_2s + du_2, self.N, dt) + x + dx_1, y + dx_2, yaw + dx_3, v + dx_4, self.u_1s + du_1, + self.u_2s + du_2, self.N, dt) - Fuxt = self._calc_f(x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s, + Fuxt = self._calc_f(v_s, lam_3s, lam_4s, self.u_1s + du_1, self.u_2s + du_2, - self.dummy_u_1s + ddummy_u_1, self.dummy_u_2s + ddummy_u_2, - self.raw_1s + draw_1, self.raw_2s + draw_2, self.N, dt) + self.dummy_u_1s + ddummy_u_1, + self.dummy_u_2s + ddummy_u_2, + self.raw_1s + draw_1, self.raw_2s + draw_2, + self.N) Av = ((Fuxt - Fxt) / self.ht) @@ -312,14 +324,17 @@ def calc_input(self, x, y, yaw, v, time): judge_value = r0_norm * e[:i + 1] - np.dot(hs[:i + 1, :i], ys[:i]) - if np.linalg.norm(judge_value) < self.threshold or i == self.max_iteration - 1: - update_value = np.dot(vs[:, :i - 1], ys_pre[:i - 1]).flatten() - du_1_new = du_1 + update_value[::self.input_num] - du_2_new = du_2 + update_value[1::self.input_num] - ddummy_u_1_new = ddummy_u_1 + update_value[2::self.input_num] - ddummy_u_2_new = ddummy_u_2 + update_value[3::self.input_num] - draw_1_new = draw_1 + update_value[4::self.input_num] - draw_2_new = draw_2 + update_value[5::self.input_num] + flag1 = np.linalg.norm(judge_value) < self.threshold + + flag2 = i == self.max_iteration - 1 + if flag1 or flag2: + update_val = np.dot(vs[:, :i - 1], ys_pre[:i - 1]).flatten() + du_1_new = du_1 + update_val[::self.input_num] + du_2_new = du_2 + update_val[1::self.input_num] + ddummy_u_1_new = ddummy_u_1 + update_val[2::self.input_num] + ddummy_u_2_new = ddummy_u_2 + update_val[3::self.input_num] + draw_1_new = draw_1 + update_val[4::self.input_num] + draw_2_new = draw_2 + update_val[5::self.input_num] break ys_pre = ys @@ -335,9 +350,9 @@ def calc_input(self, x, y, yaw, v, time): x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s = self.simulator.calc_predict_and_adjoint_state( x, y, yaw, v, self.u_1s, self.u_2s, self.N, dt) - F = self._calc_f(x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s, + F = self._calc_f(v_s, lam_3s, lam_4s, self.u_1s, self.u_2s, self.dummy_u_1s, self.dummy_u_2s, - self.raw_1s, self.raw_2s, self.N, dt) + self.raw_1s, self.raw_2s, self.N) print("norm(F) = {0}".format(np.linalg.norm(F))) @@ -352,36 +367,38 @@ def calc_input(self, x, y, yaw, v, time): return self.u_1s, self.u_2s - def _calc_f(self, x_s, y_s, yaw_s, v_s, lam_1s, lam_2s, lam_3s, lam_4s, - u_1s, u_2s, dummy_u_1s, dummy_u_2s, raw_1s, raw_2s, N, dt): + @staticmethod + def _calc_f(v_s, lam_3s, lam_4s, u_1s, u_2s, dummy_u_1s, dummy_u_2s, + raw_1s, raw_2s, N): F = [] for i in range(N): # ∂H/∂u(xi, ui, λi) F.append(u_1s[i] + lam_4s[i] + 2.0 * raw_1s[i] * u_1s[i]) F.append(u_2s[i] + lam_3s[i] * v_s[i] / - WB * math.cos(u_2s[i])**2 + 2.0 * raw_2s[i] * u_2s[i]) + WB * cos(u_2s[i]) ** 2 + 2.0 * raw_2s[i] * u_2s[i]) F.append(-PHI_V + 2.0 * raw_1s[i] * dummy_u_1s[i]) F.append(-PHI_OMEGA + 2.0 * raw_2s[i] * dummy_u_2s[i]) # C(xi, ui, λi) - F.append(u_1s[i]**2 + dummy_u_1s[i]**2 - U_A_MAX**2) - F.append(u_2s[i]**2 + dummy_u_2s[i]**2 - U_OMEGA_MAX**2) + F.append(u_1s[i] ** 2 + dummy_u_1s[i] ** 2 - U_A_MAX ** 2) + F.append(u_2s[i] ** 2 + dummy_u_2s[i] ** 2 - U_OMEGA_MAX ** 2) return np.array(F) -def plot_figures(plant_system, controller, iteration_num, dt): # pragma: no cover +def plot_figures(plant_system, controller, iteration_num, + dt): # pragma: no cover # figure # time history fig_p = plt.figure() fig_u = plt.figure() fig_f = plt.figure() - # traj + # trajectory fig_t = plt.figure() - fig_traj = fig_t.add_subplot(111) - fig_traj.set_aspect('equal') + fig_trajectory = fig_t.add_subplot(111) + fig_trajectory.set_aspect('equal') x_1_fig = fig_p.add_subplot(411) x_2_fig = fig_p.add_subplot(412) @@ -443,11 +460,11 @@ def plot_figures(plant_system, controller, iteration_num, dt): # pragma: no cov f_fig.set_xlabel("time [s]") f_fig.set_ylabel("optimal error") - fig_traj.plot(plant_system.history_x, - plant_system.history_y, "-r") - fig_traj.set_xlabel("x [m]") - fig_traj.set_ylabel("y [m]") - fig_traj.axis("equal") + fig_trajectory.plot(plant_system.history_x, + plant_system.history_y, "-r") + fig_trajectory.set_xlabel("x [m]") + fig_trajectory.set_ylabel("y [m]") + fig_trajectory.axis("equal") # start state plot_car(plant_system.history_x[0], @@ -462,23 +479,25 @@ def plot_figures(plant_system, controller, iteration_num, dt): # pragma: no cov plt.show() -def plot_car(x, y, yaw, steer=0.0, cabcolor="-r", truckcolor="-k"): # pragma: no cover +def plot_car(x, y, yaw, steer=0.0, truck_color="-k"): # pragma: no cover # Vehicle parameters LENGTH = 0.4 # [m] WIDTH = 0.2 # [m] - BACKTOWHEEL = 0.1 # [m] + BACK_TO_WHEEL = 0.1 # [m] WHEEL_LEN = 0.03 # [m] WHEEL_WIDTH = 0.02 # [m] TREAD = 0.07 # [m] - outline = np.array([[-BACKTOWHEEL, (LENGTH - BACKTOWHEEL), (LENGTH - BACKTOWHEEL), - -BACKTOWHEEL, -BACKTOWHEEL], - [WIDTH / 2, WIDTH / 2, - WIDTH / 2, -WIDTH / 2, WIDTH / 2]]) + outline = np.array( + [[-BACK_TO_WHEEL, (LENGTH - BACK_TO_WHEEL), (LENGTH - BACK_TO_WHEEL), + -BACK_TO_WHEEL, -BACK_TO_WHEEL], + [WIDTH / 2, WIDTH / 2, - WIDTH / 2, -WIDTH / 2, WIDTH / 2]]) - fr_wheel = np.array([[WHEEL_LEN, -WHEEL_LEN, -WHEEL_LEN, WHEEL_LEN, WHEEL_LEN], - [-WHEEL_WIDTH - TREAD, -WHEEL_WIDTH - TREAD, WHEEL_WIDTH - - TREAD, WHEEL_WIDTH - TREAD, -WHEEL_WIDTH - TREAD]]) + fr_wheel = np.array( + [[WHEEL_LEN, -WHEEL_LEN, -WHEEL_LEN, WHEEL_LEN, WHEEL_LEN], + [-WHEEL_WIDTH - TREAD, -WHEEL_WIDTH - TREAD, WHEEL_WIDTH - + TREAD, WHEEL_WIDTH - TREAD, -WHEEL_WIDTH - TREAD]]) rr_wheel = np.copy(fr_wheel) @@ -487,10 +506,10 @@ def plot_car(x, y, yaw, steer=0.0, cabcolor="-r", truckcolor="-k"): # pragma: n rl_wheel = np.copy(rr_wheel) rl_wheel[1, :] *= -1 - Rot1 = np.array([[math.cos(yaw), math.sin(yaw)], - [-math.sin(yaw), math.cos(yaw)]]) - Rot2 = np.array([[math.cos(steer), math.sin(steer)], - [-math.sin(steer), math.cos(steer)]]) + Rot1 = np.array([[cos(yaw), sin(yaw)], + [-sin(yaw), cos(yaw)]]) + Rot2 = np.array([[cos(steer), sin(steer)], + [-sin(steer), cos(steer)]]) fr_wheel = (fr_wheel.T.dot(Rot2)).T fl_wheel = (fl_wheel.T.dot(Rot2)).T @@ -516,20 +535,19 @@ def plot_car(x, y, yaw, steer=0.0, cabcolor="-r", truckcolor="-k"): # pragma: n rl_wheel[1, :] += y plt.plot(np.array(outline[0, :]).flatten(), - np.array(outline[1, :]).flatten(), truckcolor) + np.array(outline[1, :]).flatten(), truck_color) plt.plot(np.array(fr_wheel[0, :]).flatten(), - np.array(fr_wheel[1, :]).flatten(), truckcolor) + np.array(fr_wheel[1, :]).flatten(), truck_color) plt.plot(np.array(rr_wheel[0, :]).flatten(), - np.array(rr_wheel[1, :]).flatten(), truckcolor) + np.array(rr_wheel[1, :]).flatten(), truck_color) plt.plot(np.array(fl_wheel[0, :]).flatten(), - np.array(fl_wheel[1, :]).flatten(), truckcolor) + np.array(fl_wheel[1, :]).flatten(), truck_color) plt.plot(np.array(rl_wheel[0, :]).flatten(), - np.array(rl_wheel[1, :]).flatten(), truckcolor) + np.array(rl_wheel[1, :]).flatten(), truck_color) plt.plot(x, y, "*") def animation(plant, controller, dt): - skip = 2 # skip index for animation for t in range(1, len(controller.history_u_1), skip): @@ -543,12 +561,13 @@ def animation(plant, controller, dt): if abs(v) <= 0.01: steer = 0.0 else: - steer = math.atan2(controller.history_u_2[t] * WB / v, 1.0) + steer = atan2(controller.history_u_2[t] * WB / v, 1.0) plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(plant.history_x, plant.history_y, "-r", label="trajectory") plot_car(x, y, yaw, steer=steer) plt.axis("equal") @@ -568,7 +587,7 @@ def main(): init_x = -4.5 init_y = -2.5 - init_yaw = math.radians(45.0) + init_yaw = radians(45.0) init_v = -1.0 # plant @@ -576,14 +595,15 @@ def main(): init_x, init_y, init_yaw, init_v) # controller - controller = NMPCController_with_CGMRES() + controller = NMPCControllerCGMRES() iteration_num = int(iteration_time / dt) for i in range(1, iteration_num): time = float(i) * dt # make input u_1s, u_2s = controller.calc_input( - plant_system.x, plant_system.y, plant_system.yaw, plant_system.v, time) + plant_system.x, plant_system.y, plant_system.yaw, plant_system.v, + time) # update state plant_system.update_state(u_1s[0], u_2s[0]) diff --git a/tests/test_grid_based_sweep_coverage_path_planner.py b/tests/test_grid_based_sweep_coverage_path_planner.py index fa2d0a7a64..12ef98df39 100644 --- a/tests/test_grid_based_sweep_coverage_path_planner.py +++ b/tests/test_grid_based_sweep_coverage_path_planner.py @@ -2,8 +2,10 @@ import sys from unittest import TestCase -sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../PathPlanning/GridBasedSweepCPP") -sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../Mapping/grid_map_lib") +sys.path.append(os.path.dirname( + os.path.abspath(__file__)) + "/../PathPlanning/GridBasedSweepCPP") +sys.path.append( + os.path.dirname(os.path.abspath(__file__)) + "/../Mapping/grid_map_lib") try: import grid_based_sweep_coverage_path_planner except ImportError: @@ -14,88 +16,109 @@ class TestPlanning(TestCase): + RIGHT = grid_based_sweep_coverage_path_planner.\ + SweepSearcher.MovingDirection.RIGHT + LEFT = grid_based_sweep_coverage_path_planner. \ + SweepSearcher.MovingDirection.LEFT + UP = grid_based_sweep_coverage_path_planner. \ + SweepSearcher.SweepDirection.UP + DOWN = grid_based_sweep_coverage_path_planner. \ + SweepSearcher.SweepDirection.DOWN + def test_planning1(self): ox = [0.0, 20.0, 50.0, 100.0, 130.0, 40.0, 0.0] oy = [0.0, -20.0, 0.0, 30.0, 60.0, 80.0, 0.0] - reso = 5.0 - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.RIGHT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.DOWN, - ) - self.assertTrue(len(px) >= 5) - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.LEFT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.DOWN, - ) - self.assertTrue(len(px) >= 5) - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.RIGHT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.UP, - ) - self.assertTrue(len(px) >= 5) - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.RIGHT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.DOWN, - ) - self.assertTrue(len(px) >= 5) + resolution = 5.0 + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.RIGHT, + sweeping_direction=self.DOWN, + ) + self.assertGreater(len(px), 5) + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.LEFT, + sweeping_direction=self.DOWN, + ) + self.assertGreater(len(px), 5) + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.RIGHT, + sweeping_direction=self.UP, + ) + self.assertGreater(len(px), 5) + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.RIGHT, + sweeping_direction=self.UP, + ) + self.assertGreater(len(px), 5) def test_planning2(self): ox = [0.0, 50.0, 50.0, 0.0, 0.0] oy = [0.0, 0.0, 30.0, 30.0, 0.0] - reso = 1.3 - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.RIGHT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.DOWN, - ) - self.assertTrue(len(px) >= 5) - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.LEFT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.DOWN, - ) - self.assertTrue(len(px) >= 5) - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.RIGHT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.UP, - ) - self.assertTrue(len(px) >= 5) - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.RIGHT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.DOWN, - ) - self.assertTrue(len(px) >= 5) + resolution = 1.3 + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.RIGHT, + sweeping_direction=self.DOWN, + ) + self.assertGreater(len(px), 5) + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.LEFT, + sweeping_direction=self.DOWN, + ) + self.assertGreater(len(px), 5) + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.RIGHT, + sweeping_direction=self.UP, + ) + self.assertGreater(len(px), 5) + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.RIGHT, + sweeping_direction=self.DOWN, + ) + self.assertGreater(len(px), 5) def test_planning3(self): ox = [0.0, 20.0, 50.0, 200.0, 130.0, 40.0, 0.0] oy = [0.0, -80.0, 0.0, 30.0, 60.0, 80.0, 0.0] - reso = 5.1 - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.RIGHT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.DOWN, - ) - self.assertTrue(len(px) >= 5) - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.LEFT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.DOWN, - ) - self.assertTrue(len(px) >= 5) - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.RIGHT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.UP, - ) - self.assertTrue(len(px) >= 5) - - px, py = grid_based_sweep_coverage_path_planner.planning(ox, oy, reso, - moving_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.MovingDirection.RIGHT, - sweeping_direction=grid_based_sweep_coverage_path_planner.SweepSearcher.SweepDirection.DOWN, - ) - self.assertTrue(len(px) >= 5) + resolution = 5.1 + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.RIGHT, + sweeping_direction=self.DOWN, + ) + self.assertGreater(len(px), 5) + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.LEFT, + sweeping_direction=self.DOWN, + ) + self.assertGreater(len(px), 5) + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.RIGHT, + sweeping_direction=self.UP, + ) + self.assertGreater(len(px), 5) + + px, py = grid_based_sweep_coverage_path_planner.planning( + ox, oy, resolution, + moving_direction=self.RIGHT, + sweeping_direction=self.DOWN, + ) + self.assertGreater(len(px), 5) From effddd2f6bdba33f75ca9df3367b4c6fe0fb00df Mon Sep 17 00:00:00 2001 From: adi-vardi-enway <57910756+adi-vardi-enway@users.noreply.github.com> Date: Sat, 4 Jul 2020 11:44:35 +0800 Subject: [PATCH 276/940] Potential field - potential range and ocillations (#345) * Potential cover start and goal as well * Oscillation detection and fix potential look if outside range * Formatting * cleaner and flexible oscillation detection Co-authored-by: Adi Vardi --- .../potential_field_planning.py | 40 +++++++++++++++---- 1 file changed, 33 insertions(+), 7 deletions(-) diff --git a/PathPlanning/PotentialFieldPlanning/potential_field_planning.py b/PathPlanning/PotentialFieldPlanning/potential_field_planning.py index 31904fa45d..8f136b5ee3 100644 --- a/PathPlanning/PotentialFieldPlanning/potential_field_planning.py +++ b/PathPlanning/PotentialFieldPlanning/potential_field_planning.py @@ -9,6 +9,7 @@ """ +from collections import deque import numpy as np import matplotlib.pyplot as plt @@ -16,15 +17,17 @@ KP = 5.0 # attractive potential gain ETA = 100.0 # repulsive potential gain AREA_WIDTH = 30.0 # potential area width [m] +# the number of previous positions used to check oscillations +OSCILLATIONS_DETECTION_LENGTH = 3 show_animation = True -def calc_potential_field(gx, gy, ox, oy, reso, rr): - minx = min(ox) - AREA_WIDTH / 2.0 - miny = min(oy) - AREA_WIDTH / 2.0 - maxx = max(ox) + AREA_WIDTH / 2.0 - maxy = max(oy) + AREA_WIDTH / 2.0 +def calc_potential_field(gx, gy, ox, oy, reso, rr, sx, sy): + minx = min(min(ox), sx, gx) - AREA_WIDTH / 2.0 + miny = min(min(oy), sy, gy) - AREA_WIDTH / 2.0 + maxx = max(max(ox), sx, gx) + AREA_WIDTH / 2.0 + maxy = max(max(oy), sy, gy) + AREA_WIDTH / 2.0 xw = int(round((maxx - minx) / reso)) yw = int(round((maxy - miny) / reso)) @@ -84,10 +87,26 @@ def get_motion_model(): return motion +def oscillations_detection(previous_ids, ix, iy): + previous_ids.append((ix, iy)) + + if (len(previous_ids) > OSCILLATIONS_DETECTION_LENGTH): + previous_ids.popleft() + + # check if contains any duplicates by copying into a set + previous_ids_set = set() + for index in previous_ids: + if index in previous_ids_set: + return True + else: + previous_ids_set.add(index) + return False + + def potential_field_planning(sx, sy, gx, gy, ox, oy, reso, rr): # calc potential field - pmap, minx, miny = calc_potential_field(gx, gy, ox, oy, reso, rr) + pmap, minx, miny = calc_potential_field(gx, gy, ox, oy, reso, rr, sx, sy) # search path d = np.hypot(sx - gx, sy - gy) @@ -106,14 +125,17 @@ def potential_field_planning(sx, sy, gx, gy, ox, oy, reso, rr): rx, ry = [sx], [sy] motion = get_motion_model() + previous_ids = deque() + while d >= reso: minp = float("inf") minix, miniy = -1, -1 for i, _ in enumerate(motion): inx = int(ix + motion[i][0]) iny = int(iy + motion[i][1]) - if inx >= len(pmap) or iny >= len(pmap[0]): + if inx >= len(pmap) or iny >= len(pmap[0]) or inx < 0 or iny < 0: p = float("inf") # outside area + print("outside potential!") else: p = pmap[inx][iny] if minp > p: @@ -128,6 +150,10 @@ def potential_field_planning(sx, sy, gx, gy, ox, oy, reso, rr): rx.append(xp) ry.append(yp) + if (oscillations_detection(previous_ids, ix, iy)): + print("Oscillation detected at ({},{})!".format(ix, iy)) + break + if show_animation: plt.plot(ix, iy, ".r") plt.pause(0.01) From eb42d3937e7de41f8157457d384b52757a30a07a Mon Sep 17 00:00:00 2001 From: "dependabot-preview[bot]" <27856297+dependabot-preview[bot]@users.noreply.github.com> Date: Sun, 5 Jul 2020 20:01:03 +0900 Subject: [PATCH 277/940] Create Dependabot config file (#347) Co-authored-by: dependabot-preview[bot] <27856297+dependabot-preview[bot]@users.noreply.github.com> --- .github/dependabot.yml | 8 ++++++++ 1 file changed, 8 insertions(+) create mode 100644 .github/dependabot.yml diff --git a/.github/dependabot.yml b/.github/dependabot.yml new file mode 100644 index 0000000000..9117f1216c --- /dev/null +++ b/.github/dependabot.yml @@ -0,0 +1,8 @@ +version: 2 +updates: +- package-ecosystem: pip + directory: "/" + schedule: + interval: weekly + time: "20:00" + open-pull-requests-limit: 10 From 5f6e4f855551aac9ece93533ceeacca8e97e1ad1 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 5 Jul 2020 21:15:18 +0900 Subject: [PATCH 278/940] Dependency setting clean up (#348) * requiirements.txt use specific version * use appveyor * fix appveyor * fix appveyor * fix appveyor --- .travis.yml | 35 ----------------------------------- CONTRIBUTING.md | 2 +- appveyor.yml | 1 + environment.yml | 5 ++--- requirements.txt | 10 +++++----- 5 files changed, 9 insertions(+), 44 deletions(-) delete mode 100644 .travis.yml diff --git a/.travis.yml b/.travis.yml deleted file mode 100644 index 99d239217b..0000000000 --- a/.travis.yml +++ /dev/null @@ -1,35 +0,0 @@ -language: python - -matrix: - include: - - os: linux - -python: - - 3.8 - -before_install: - - sudo apt-get update - - wget https://repo.continuum.io/miniconda/Miniconda3-latest-Linux-x86_64.sh -O miniconda.sh - - chmod +x miniconda.sh - - bash miniconda.sh -b -p $HOME/miniconda - - export PATH="$HOME/miniconda/bin:$PATH" - - hash -r - - conda config --set always_yes yes --set changeps1 no - - conda update -q conda - # Useful for debugging any issues with conda - - conda info -a - -install: - - conda install numpy - - conda install scipy - - conda install matplotlib - - conda install pandas - - pip install cvxpy - - conda install coveralls - -script: - - python --version - - ./runtests.sh - -after_success: - - coveralls diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index fd41946b65..91f6dfa822 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -18,6 +18,6 @@ Please check this paper to understand the philosophy of this project. ## Check your Python version. -We only accept a PR for Python 3.6.x or higher. +We only accept a PR for Python 3.8.x or higher. We will not accept a PR for Python 2.x. diff --git a/appveyor.yml b/appveyor.yml index f34bcb2b28..b883397d71 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -34,6 +34,7 @@ install: - SET PATH=%PYTHON%;%PYTHON%\Scripts;%PYTHON%\Library\bin;%PATH% - SET PATH=%PATH%;C:\Program Files (x86)\Microsoft Visual Studio 14.0\VC\bin - conda config --set always_yes yes --set changeps1 no + - conda config --append channels conda-forge - conda update -q conda - conda info -a - conda env create -f C:\\projects\pythonrobotics\environment.yml diff --git a/environment.yml b/environment.yml index da1c3c0a6f..fdfd25ca0a 100644 --- a/environment.yml +++ b/environment.yml @@ -2,10 +2,9 @@ name: python_robotics dependencies: - python - pip -- matplotlib - scipy - numpy - pandas +- cvxpy +- matplotlib - coverage -- pip: - - cvxpy diff --git a/requirements.txt b/requirements.txt index 1398664be8..775486efa3 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ -numpy -pandas -scipy -matplotlib -cvxpy +numpy == 1.19.0 +scipy == 1.5.1 +pandas == 1.0.5 +matplotlib == 3.2.2 +cvxpy == 1.1.1 From 77f6277e9c86e3b20a74eabfe9be6da3ba339308 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 7 Jul 2020 22:22:53 +0900 Subject: [PATCH 279/940] improve test coverage (#352) * improve test coverage * improve test coverage * add coveralls CI * add coveralls CI * remove cover alls --- Bipedal/bipedal_planner/bipedal_planner.py | 153 +++++++++--------- .../CubicSpline/cubic_spline_planner.py | 2 +- 2 files changed, 80 insertions(+), 75 deletions(-) diff --git a/Bipedal/bipedal_planner/bipedal_planner.py b/Bipedal/bipedal_planner/bipedal_planner.py index 01df63034f..9757fc42d6 100644 --- a/Bipedal/bipedal_planner/bipedal_planner.py +++ b/Bipedal/bipedal_planner/bipedal_planner.py @@ -110,83 +110,88 @@ def walk(self, t_sup=0.8, z_c=0.8, a=10, b=1, plot=False): # plot if plot: - # for plot trajectory, plot in for loop - for c in range(len(self.com_trajectory)): - if c > len(com_trajectory_for_plot): - # set up plotter - plt.cla() - # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect( - 'key_release_event', - lambda event: - [exit(0) if event.key == 'escape' else None]) - ax.set_zlim(0, z_c * 2) - ax.set_xlim(0, 1) - ax.set_ylim(-0.5, 0.5) - - # update com_trajectory_for_plot - com_trajectory_for_plot.append(self.com_trajectory[c]) - - # plot com - ax.plot([p[0] for p in com_trajectory_for_plot], - [p[1] for p in com_trajectory_for_plot], [ - 0 for _ in com_trajectory_for_plot], - color="red") - - # plot inverted pendulum - ax.plot([px_star, com_trajectory_for_plot[-1][0]], - [py_star, com_trajectory_for_plot[-1][1]], - [0, z_c], color="green", linewidth=3) - ax.scatter([com_trajectory_for_plot[-1][0]], - [com_trajectory_for_plot[-1][1]], - [z_c], color="green", s=300) - - # foot rectangle for self.ref_p - foot_width = 0.06 - foot_height = 0.04 - for j in range(len(self.ref_p)): - angle = self.ref_p[j][2] + \ - math.atan2(foot_height, - foot_width) - math.pi - r = math.sqrt( - math.pow(foot_width / 3., 2) + math.pow( - foot_height / 2., 2)) - rec = pat.Rectangle(xy=( - self.ref_p[j][0] + r * math.cos(angle), - self.ref_p[j][1] + r * math.sin(angle)), - width=foot_width, - height=foot_height, - angle=self.ref_p[j][ - 2] * 180 / math.pi, - color="blue", fill=False, - ls=":") - ax.add_patch(rec) - art3d.pathpatch_2d_to_3d(rec, z=0, zdir="z") - - # foot rectangle for self.act_p - for j in range(len(self.act_p)): - angle = self.act_p[j][2] + \ - math.atan2(foot_height, - foot_width) - math.pi - r = math.sqrt( - math.pow(foot_width / 3., 2) + math.pow( - foot_height / 2., 2)) - rec = pat.Rectangle(xy=( - self.act_p[j][0] + r * math.cos(angle), - self.act_p[j][1] + r * math.sin(angle)), - width=foot_width, - height=foot_height, - angle=self.act_p[j][ - 2] * 180 / math.pi, - color="blue", fill=False) - ax.add_patch(rec) - art3d.pathpatch_2d_to_3d(rec, z=0, zdir="z") - - plt.draw() - plt.pause(0.001) + self.plot_animation(ax, com_trajectory_for_plot, px_star, + py_star, z_c) if plot: plt.show() + def plot_animation(self, ax, com_trajectory_for_plot, px_star, py_star, + z_c): # pragma: no cover + # for plot trajectory, plot in for loop + for c in range(len(self.com_trajectory)): + if c > len(com_trajectory_for_plot): + # set up plotter + plt.cla() + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: + [exit(0) if event.key == 'escape' else None]) + ax.set_zlim(0, z_c * 2) + ax.set_xlim(0, 1) + ax.set_ylim(-0.5, 0.5) + + # update com_trajectory_for_plot + com_trajectory_for_plot.append(self.com_trajectory[c]) + + # plot com + ax.plot([p[0] for p in com_trajectory_for_plot], + [p[1] for p in com_trajectory_for_plot], [ + 0 for _ in com_trajectory_for_plot], + color="red") + + # plot inverted pendulum + ax.plot([px_star, com_trajectory_for_plot[-1][0]], + [py_star, com_trajectory_for_plot[-1][1]], + [0, z_c], color="green", linewidth=3) + ax.scatter([com_trajectory_for_plot[-1][0]], + [com_trajectory_for_plot[-1][1]], + [z_c], color="green", s=300) + + # foot rectangle for self.ref_p + foot_width = 0.06 + foot_height = 0.04 + for j in range(len(self.ref_p)): + angle = self.ref_p[j][2] + \ + math.atan2(foot_height, + foot_width) - math.pi + r = math.sqrt( + math.pow(foot_width / 3., 2) + math.pow( + foot_height / 2., 2)) + rec = pat.Rectangle(xy=( + self.ref_p[j][0] + r * math.cos(angle), + self.ref_p[j][1] + r * math.sin(angle)), + width=foot_width, + height=foot_height, + angle=self.ref_p[j][ + 2] * 180 / math.pi, + color="blue", fill=False, + ls=":") + ax.add_patch(rec) + art3d.pathpatch_2d_to_3d(rec, z=0, zdir="z") + + # foot rectangle for self.act_p + for j in range(len(self.act_p)): + angle = self.act_p[j][2] + \ + math.atan2(foot_height, + foot_width) - math.pi + r = math.sqrt( + math.pow(foot_width / 3., 2) + math.pow( + foot_height / 2., 2)) + rec = pat.Rectangle(xy=( + self.act_p[j][0] + r * math.cos(angle), + self.act_p[j][1] + r * math.sin(angle)), + width=foot_width, + height=foot_height, + angle=self.act_p[j][ + 2] * 180 / math.pi, + color="blue", fill=False) + ax.add_patch(rec) + art3d.pathpatch_2d_to_3d(rec, z=0, zdir="z") + + plt.draw() + plt.pause(0.001) + if __name__ == "__main__": bipedal_planner = BipedalPlanner() diff --git a/PathPlanning/CubicSpline/cubic_spline_planner.py b/PathPlanning/CubicSpline/cubic_spline_planner.py index 239ce16738..7ec01d1f4e 100644 --- a/PathPlanning/CubicSpline/cubic_spline_planner.py +++ b/PathPlanning/CubicSpline/cubic_spline_planner.py @@ -190,7 +190,7 @@ def calc_spline_course(x, y, ds=0.1): return rx, ry, ryaw, rk, s -def main(): +def main(): # pragma: no cover print("Spline 2D test") import matplotlib.pyplot as plt x = [-2.5, 0.0, 2.5, 5.0, 7.5, 3.0, -1.0] From b19476f175f7b7730068e5bb7883051e6521ae9d Mon Sep 17 00:00:00 2001 From: Todd Tang Date: Wed, 8 Jul 2020 21:02:27 +0800 Subject: [PATCH 280/940] Wavefront Coverage Path Planning (#351) * First Commit of Wavefront Coverage Planner * Update wavefront_coverage_path_planner.py * fix CI / CodeFactor problem * Fix mypy error * update * Fix PyCodeStyle * Fix Code Scanning Warning and code styling problem * add simple unittest * followed second code review suggestions --- PathPlanning/WavefrontCPP/map/test.png | Bin 0 -> 156 bytes PathPlanning/WavefrontCPP/map/test_2.png | Bin 0 -> 150 bytes PathPlanning/WavefrontCPP/map/test_3.png | Bin 0 -> 132 bytes .../wavefront_coverage_path_planner.py | 219 ++++++++++++++++++ tests/test_wavefront_coverage_path_planner.py | 64 +++++ 5 files changed, 283 insertions(+) create mode 100644 PathPlanning/WavefrontCPP/map/test.png create mode 100644 PathPlanning/WavefrontCPP/map/test_2.png create mode 100644 PathPlanning/WavefrontCPP/map/test_3.png create mode 100644 PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py create mode 100644 tests/test_wavefront_coverage_path_planner.py diff --git a/PathPlanning/WavefrontCPP/map/test.png b/PathPlanning/WavefrontCPP/map/test.png new file mode 100644 index 0000000000000000000000000000000000000000..4abca0bf3090e5b22cb5d6a48ed9c55a4024e787 GIT binary patch literal 156 zcmeAS@N?(olHy`uVBq!ia0vp^Iv~seBp9sUv)%<#>?NMQuIx|P8M&EELc9#81BC)S zT^vI!dXxX0cd$uNa(ufYN#sD2|D=hHjSuaGsttBZ-poD05Ss&JNE+~U7<-f(Z~R#> zVMk@i#}!F2466K(PSYECptdJh!x z@^oA^-pY literal 0 HcmV?d00001 diff --git a/PathPlanning/WavefrontCPP/map/test_3.png b/PathPlanning/WavefrontCPP/map/test_3.png new file mode 100644 index 0000000000000000000000000000000000000000..1a50b87ccff5a966f5e078282cefec2f14ba9112 GIT binary patch literal 132 zcmeAS@N?(olHy`uVBq!ia0vp^20*O90VEg-_b)jBq}WS5eO=j~u(R_RiwlJC@d1S_ zJY5_^EP9jwoNtgfSoCow$BN?&i>2I5d1QGtPRUU#f;|BY-CV2^o55JQI eekEFDFfjD$u~_NcJpT`927{-opUXO@geCxLEGFFm literal 0 HcmV?d00001 diff --git a/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py b/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py new file mode 100644 index 0000000000..20d640f24a --- /dev/null +++ b/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py @@ -0,0 +1,219 @@ +""" +Distance/Path Transform Wavefront Coverage Path Planner + +author: Todd Tang +paper: Planning paths of complete coverage of an unstructured environment + by a mobile robot - Zelinsky et.al. +link: http://pinkwink.kr/attachment/cfile3.uf@1354654A4E8945BD13FE77.pdf +""" + +import os +import sys + +import matplotlib.pyplot as plt +import numpy as np + +from scipy import ndimage + + +do_animation = True + + +def transform( + gridmap, src, distance_type='chessboard', + transform_type='path', alpha=0.01 +): + """transform + + calculating transform of transform_type from src + in given distance_type + + :param gridmap: 2d binary map + :param src: distance transform source + :param distance_type: type of distance used + :param transform_type: type of transform used + :param alpha: weight of Obstacle Transform usedwhen using path_transform + """ + + nrows, ncols = gridmap.shape + + if nrows == 0 or ncols == 0: + sys.exit('Empty gridmap.') + + inc_order = [[0, 1], [1, 1], [1, 0], [1, -1], + [0, -1], [-1, -1], [-1, 0], [-1, 1]] + if distance_type == 'chessboard': + cost = [1, 1, 1, 1, 1, 1, 1, 1] + elif distance_type == 'eculidean': + cost = [1, np.sqrt(2), 1, np.sqrt(2), 1, np.sqrt(2), 1, np.sqrt(2)] + else: + sys.exit('Unsupported distance type.') + + transform_matrix = float('inf') * np.ones_like(gridmap, dtype=np.float) + transform_matrix[src[0], src[1]] = 0 + if transform_type == 'distance': + eT = np.zeros_like(gridmap) + elif transform_type == 'path': + eT = ndimage.distance_transform_cdt(1-gridmap, distance_type) + else: + sys.exit('Unsupported transform type.') + + # set obstacle transform_matrix value to infinity + for i in range(nrows): + for j in range(ncols): + if gridmap[i][j] == 1.0: + transform_matrix[i][j] = float('inf') + is_visited = np.zeros_like(transform_matrix, dtype=bool) + is_visited[src[0], src[1]] = True + traversal_queue = [src] + calculated = [(src[0]-1)*ncols + src[1]] + + def is_valid_neighbor(i, j): + return ni >= 0 and ni < nrows and nj >= 0 and nj < ncols \ + and not gridmap[ni][nj] + + while traversal_queue != []: + i, j = traversal_queue.pop(0) + for k, inc in enumerate(inc_order): + ni = i + inc[0] + nj = j + inc[1] + if is_valid_neighbor(ni, nj): + is_visited[i][j] = True + + # update transform_matrix + transform_matrix[i][j] = min( + transform_matrix[i][j], + transform_matrix[ni][nj] + cost[k] + alpha*eT[ni][nj]) + + if not is_visited[ni][nj] \ + and ((ni-1)*ncols + nj) not in calculated: + traversal_queue.append((ni, nj)) + calculated.append((ni-1)*ncols + nj) + + return transform_matrix + + +def wavefront(transform_matrix, start, goal): + """wavefront + + performing wavefront coverage path planning + + :param transform_matrix: the transform matrix + :param start: start point of planning + :param goal: goal point of planning + """ + + path = [] + nrows, ncols = transform_matrix.shape + + def get_search_order_increment(start, goal): + if start[0] >= goal[0] and start[1] >= goal[1]: + order = [[1, 0], [0, 1], [-1, 0], [0, -1], + [1, 1], [1, -1], [-1, 1], [-1, -1]] + elif start[0] <= goal[0] and start[1] >= goal[1]: + order = [[-1, 0], [0, 1], [1, 0], [0, -1], + [-1, 1], [-1, -1], [1, 1], [1, -1]] + elif start[0] >= goal[0] and start[1] <= goal[1]: + order = [[1, 0], [0, -1], [-1, 0], [0, 1], + [1, -1], [-1, -1], [1, 1], [-1, 1]] + elif start[0] <= goal[0] and start[1] <= goal[1]: + order = [[-1, 0], [0, -1], [0, 1], [1, 0], + [-1, -1], [-1, 1], [1, -1], [1, 1]] + else: + sys.exit('get_search_order_increment: cannot determine \ + start=>goal increment order') + return order + + def is_valid_neighbor(i, j): + is_i_valid_bounded = i >= 0 and i < nrows + is_j_valid_bounded = j >= 0 and j < ncols + if is_i_valid_bounded and is_j_valid_bounded: + return not is_visited[i][j] and \ + transform_matrix[i][j] != float('inf') + return False + + inc_order = get_search_order_increment(start, goal) + + current_node = start + is_visited = np.zeros_like(transform_matrix, dtype=bool) + + while current_node != goal: + i, j = current_node + path.append((i, j)) + is_visited[i][j] = True + + max_T = float('-inf') + i_max = (-1, -1) + i_last = 0 + for i_last in range(len(path)): + current_node = path[-1 - i_last] # get lastest node in path + for ci, cj in inc_order: + ni, nj = current_node[0] + ci, current_node[1] + cj + if is_valid_neighbor(ni, nj) and \ + transform_matrix[ni][nj] > max_T: + i_max = (ni, nj) + max_T = transform_matrix[ni][nj] + + if i_max != (-1, -1): + break + + if i_max == (-1, -1): + break + else: + current_node = i_max + if i_last != 0: + print('backtracing to', current_node) + path.append(goal) + + return path + + +def visualize_path(grid_map, start, goal, path, resolution): + oy, ox = start + gy, gx = goal + px, py = np.transpose(np.flipud(np.fliplr((path)))) + + if not do_animation: + plt.imshow(grid_map, cmap='Greys') + plt.plot(ox, oy, "-xy") + plt.plot(px, py, "-r") + plt.plot(gx, gy, "-pg") + plt.show() + else: + for ipx, ipy in zip(px, py): + plt.cla() + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + plt.imshow(grid_map, cmap='Greys') + plt.plot(ox, oy, "-xb") + plt.plot(px, py, "-r") + plt.plot(gx, gy, "-pg") + plt.plot(ipx, ipy, "or") + plt.axis("equal") + plt.grid(True) + plt.pause(0.1) + + +def main(): + dir_path = os.path.dirname(os.path.realpath(__file__)) + img = plt.imread(os.path.join(dir_path, 'map', 'test.png')) + img = 1 - img # revert pixel values + + start = (43, 0) + goal = (0, 0) + + # distance transform wavefront + DT = transform(img, goal, transform_type='distance') + DT_path = wavefront(DT, start, goal) + visualize_path(img, start, goal, DT_path, 1) + + # path transform wavefront + PT = transform(img, goal, transform_type='path', alpha=0.01) + PT_path = wavefront(PT, start, goal) + visualize_path(img, start, goal, PT_path, 1) + + +if __name__ == "__main__": + main() diff --git a/tests/test_wavefront_coverage_path_planner.py b/tests/test_wavefront_coverage_path_planner.py new file mode 100644 index 0000000000..a72818c259 --- /dev/null +++ b/tests/test_wavefront_coverage_path_planner.py @@ -0,0 +1,64 @@ +import os +import sys +import matplotlib.pyplot as plt +from unittest import TestCase + +sys.path.append(os.path.dirname( + os.path.abspath(__file__)) + "/../PathPlanning/WavefrontCPP") +try: + import wavefront_coverage_path_planner +except ImportError: + raise + +wavefront_coverage_path_planner.do_animation = False + + +class TestPlanning(TestCase): + def wavefront_cpp(self, img, start, goal): + num_free = 0 + for i in range(img.shape[0]): + for j in range(img.shape[1]): + num_free += 1 - img[i][j] + + DT = wavefront_coverage_path_planner.transform( + img, goal, transform_type='distance') + DT_path = wavefront_coverage_path_planner.wavefront(DT, start, goal) + self.assertEqual(len(DT_path), num_free) # assert complete coverage + + PT = wavefront_coverage_path_planner.transform( + img, goal, transform_type='path', alpha=0.01) + PT_path = wavefront_coverage_path_planner.wavefront(PT, start, goal) + self.assertEqual(len(PT_path), num_free) # assert complete coverage + + def test_wavefront_CPP_1(self): + img_dir = os.path.dirname( + os.path.abspath(__file__)) + "/../PathPlanning/WavefrontCPP" + img = plt.imread(os.path.join(img_dir, 'map', 'test.png')) + img = 1 - img + + start = (43, 0) + goal = (0, 0) + + self.wavefront_cpp(img, start, goal) + + def test_wavefront_CPP_2(self): + img_dir = os.path.dirname( + os.path.abspath(__file__)) + "/../PathPlanning/WavefrontCPP" + img = plt.imread(os.path.join(img_dir, 'map', 'test_2.png')) + img = 1 - img + + start = (10, 0) + goal = (10, 40) + + self.wavefront_cpp(img, start, goal) + + def test_wavefront_CPP_3(self): + img_dir = os.path.dirname( + os.path.abspath(__file__)) + "/../PathPlanning/WavefrontCPP" + img = plt.imread(os.path.join(img_dir, 'map', 'test_3.png')) + img = 1 - img + + start = (0, 0) + goal = (30, 30) + + self.wavefront_cpp(img, start, goal) From 7dd6b6793a5e1e55303103709d151bfa378cba38 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 8 Jul 2020 22:53:20 +0900 Subject: [PATCH 281/940] remove cover alls (#353) --- .travis.yml | 35 +++++++++++++++++++++++++++++++++++ 1 file changed, 35 insertions(+) create mode 100644 .travis.yml diff --git a/.travis.yml b/.travis.yml new file mode 100644 index 0000000000..9fcc2dbdc2 --- /dev/null +++ b/.travis.yml @@ -0,0 +1,35 @@ +language: python + +matrix: + include: + - os: linux + +python: + - 3.8 + +before_install: + - sudo apt-get update + - wget https://repo.continuum.io/miniconda/Miniconda3-latest-Linux-x86_64.sh -O miniconda.sh + - chmod +x miniconda.sh + - bash miniconda.sh -b -p $HOME/miniconda + - export PATH="$HOME/miniconda/bin:$PATH" + - hash -r + - conda config --set always_yes yes --set changeps1 no + - conda config --append channels conda-forge + - conda update -q conda + # Useful for debugging any issues with conda + - conda info -a + +install: + - conda install numpy + - conda install scipy + - conda install matplotlib + - conda install pandas + - conda install cvxpy + - conda install coveralls + +script: + - python --version + +after_success: + - coveralls \ No newline at end of file From 72c4a891b33d2075df77f97d0bd88f0540fd455b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 10 Jul 2020 21:34:47 +0900 Subject: [PATCH 282/940] remove cover alls (#357) * remove cover alls * add codecov * try coverage * try coverage * try coverage --- .github/workflows/Linux_CI.yml | 2 + .travis.yml | 35 ------ .../wavefront_coverage_path_planner.py | 103 +++++++++--------- README.md | 2 +- 4 files changed, 54 insertions(+), 88 deletions(-) delete mode 100644 .travis.yml diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index 293c5621e2..de99bd446f 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -45,6 +45,8 @@ jobs: run: bash rundiffstylecheck.sh - name: do all unit tests run: bash runtests.sh + - name: Codecov + uses: codecov/codecov-action@v1.0.10 diff --git a/.travis.yml b/.travis.yml deleted file mode 100644 index 9fcc2dbdc2..0000000000 --- a/.travis.yml +++ /dev/null @@ -1,35 +0,0 @@ -language: python - -matrix: - include: - - os: linux - -python: - - 3.8 - -before_install: - - sudo apt-get update - - wget https://repo.continuum.io/miniconda/Miniconda3-latest-Linux-x86_64.sh -O miniconda.sh - - chmod +x miniconda.sh - - bash miniconda.sh -b -p $HOME/miniconda - - export PATH="$HOME/miniconda/bin:$PATH" - - hash -r - - conda config --set always_yes yes --set changeps1 no - - conda config --append channels conda-forge - - conda update -q conda - # Useful for debugging any issues with conda - - conda info -a - -install: - - conda install numpy - - conda install scipy - - conda install matplotlib - - conda install pandas - - conda install cvxpy - - conda install coveralls - -script: - - python --version - -after_success: - - coveralls \ No newline at end of file diff --git a/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py b/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py index 20d640f24a..aaf77e02fc 100644 --- a/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py +++ b/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py @@ -12,33 +12,31 @@ import matplotlib.pyplot as plt import numpy as np - from scipy import ndimage - do_animation = True def transform( - gridmap, src, distance_type='chessboard', - transform_type='path', alpha=0.01 + grid_map, src, distance_type='chessboard', + transform_type='path', alpha=0.01 ): """transform calculating transform of transform_type from src in given distance_type - :param gridmap: 2d binary map + :param grid_map: 2d binary map :param src: distance transform source :param distance_type: type of distance used :param transform_type: type of transform used - :param alpha: weight of Obstacle Transform usedwhen using path_transform + :param alpha: weight of Obstacle Transform used when using path_transform """ - nrows, ncols = gridmap.shape + n_rows, n_cols = grid_map.shape - if nrows == 0 or ncols == 0: - sys.exit('Empty gridmap.') + if n_rows == 0 or n_cols == 0: + sys.exit('Empty grid_map.') inc_order = [[0, 1], [1, 1], [1, 0], [1, -1], [0, -1], [-1, -1], [-1, 0], [-1, 1]] @@ -49,30 +47,30 @@ def transform( else: sys.exit('Unsupported distance type.') - transform_matrix = float('inf') * np.ones_like(gridmap, dtype=np.float) + transform_matrix = float('inf') * np.ones_like(grid_map, dtype=np.float) transform_matrix[src[0], src[1]] = 0 if transform_type == 'distance': - eT = np.zeros_like(gridmap) + eT = np.zeros_like(grid_map) elif transform_type == 'path': - eT = ndimage.distance_transform_cdt(1-gridmap, distance_type) + eT = ndimage.distance_transform_cdt(1 - grid_map, distance_type) else: sys.exit('Unsupported transform type.') # set obstacle transform_matrix value to infinity - for i in range(nrows): - for j in range(ncols): - if gridmap[i][j] == 1.0: + for i in range(n_rows): + for j in range(n_cols): + if grid_map[i][j] == 1.0: transform_matrix[i][j] = float('inf') is_visited = np.zeros_like(transform_matrix, dtype=bool) is_visited[src[0], src[1]] = True traversal_queue = [src] - calculated = [(src[0]-1)*ncols + src[1]] + calculated = [(src[0] - 1) * n_cols + src[1]] - def is_valid_neighbor(i, j): - return ni >= 0 and ni < nrows and nj >= 0 and nj < ncols \ - and not gridmap[ni][nj] + def is_valid_neighbor(g_i, g_j): + return 0 <= g_i < n_rows and 0 <= g_j < n_cols \ + and not grid_map[g_i][g_j] - while traversal_queue != []: + while traversal_queue: i, j = traversal_queue.pop(0) for k, inc in enumerate(inc_order): ni = i + inc[0] @@ -83,16 +81,35 @@ def is_valid_neighbor(i, j): # update transform_matrix transform_matrix[i][j] = min( transform_matrix[i][j], - transform_matrix[ni][nj] + cost[k] + alpha*eT[ni][nj]) + transform_matrix[ni][nj] + cost[k] + alpha * eT[ni][nj]) if not is_visited[ni][nj] \ - and ((ni-1)*ncols + nj) not in calculated: + and ((ni - 1) * n_cols + nj) not in calculated: traversal_queue.append((ni, nj)) - calculated.append((ni-1)*ncols + nj) + calculated.append((ni - 1) * n_cols + nj) return transform_matrix +def get_search_order_increment(start, goal): + if start[0] >= goal[0] and start[1] >= goal[1]: + order = [[1, 0], [0, 1], [-1, 0], [0, -1], + [1, 1], [1, -1], [-1, 1], [-1, -1]] + elif start[0] <= goal[0] and start[1] >= goal[1]: + order = [[-1, 0], [0, 1], [1, 0], [0, -1], + [-1, 1], [-1, -1], [1, 1], [1, -1]] + elif start[0] >= goal[0] and start[1] <= goal[1]: + order = [[1, 0], [0, -1], [-1, 0], [0, 1], + [1, -1], [-1, -1], [1, 1], [-1, 1]] + elif start[0] <= goal[0] and start[1] <= goal[1]: + order = [[-1, 0], [0, -1], [0, 1], [1, 0], + [-1, -1], [-1, 1], [1, -1], [1, 1]] + else: + sys.exit('get_search_order_increment: cannot determine \ + start=>goal increment order') + return order + + def wavefront(transform_matrix, start, goal): """wavefront @@ -104,32 +121,14 @@ def wavefront(transform_matrix, start, goal): """ path = [] - nrows, ncols = transform_matrix.shape - - def get_search_order_increment(start, goal): - if start[0] >= goal[0] and start[1] >= goal[1]: - order = [[1, 0], [0, 1], [-1, 0], [0, -1], - [1, 1], [1, -1], [-1, 1], [-1, -1]] - elif start[0] <= goal[0] and start[1] >= goal[1]: - order = [[-1, 0], [0, 1], [1, 0], [0, -1], - [-1, 1], [-1, -1], [1, 1], [1, -1]] - elif start[0] >= goal[0] and start[1] <= goal[1]: - order = [[1, 0], [0, -1], [-1, 0], [0, 1], - [1, -1], [-1, -1], [1, 1], [-1, 1]] - elif start[0] <= goal[0] and start[1] <= goal[1]: - order = [[-1, 0], [0, -1], [0, 1], [1, 0], - [-1, -1], [-1, 1], [1, -1], [1, 1]] - else: - sys.exit('get_search_order_increment: cannot determine \ - start=>goal increment order') - return order + n_rows, n_cols = transform_matrix.shape - def is_valid_neighbor(i, j): - is_i_valid_bounded = i >= 0 and i < nrows - is_j_valid_bounded = j >= 0 and j < ncols + def is_valid_neighbor(g_i, g_j): + is_i_valid_bounded = 0 <= g_i < n_rows + is_j_valid_bounded = 0 <= g_j < n_cols if is_i_valid_bounded and is_j_valid_bounded: - return not is_visited[i][j] and \ - transform_matrix[i][j] != float('inf') + return not is_visited[g_i][g_j] and \ + transform_matrix[g_i][g_j] != float('inf') return False inc_order = get_search_order_increment(start, goal) @@ -146,7 +145,7 @@ def is_valid_neighbor(i, j): i_max = (-1, -1) i_last = 0 for i_last in range(len(path)): - current_node = path[-1 - i_last] # get lastest node in path + current_node = path[-1 - i_last] # get latest node in path for ci, cj in inc_order: ni, nj = current_node[0] + ci, current_node[1] + cj if is_valid_neighbor(ni, nj) and \ @@ -168,10 +167,10 @@ def is_valid_neighbor(i, j): return path -def visualize_path(grid_map, start, goal, path, resolution): +def visualize_path(grid_map, start, goal, path): # pragma: no cover oy, ox = start gy, gx = goal - px, py = np.transpose(np.flipud(np.fliplr((path)))) + px, py = np.transpose(np.flipud(np.fliplr(path))) if not do_animation: plt.imshow(grid_map, cmap='Greys') @@ -207,12 +206,12 @@ def main(): # distance transform wavefront DT = transform(img, goal, transform_type='distance') DT_path = wavefront(DT, start, goal) - visualize_path(img, start, goal, DT_path, 1) + visualize_path(img, start, goal, DT_path) # path transform wavefront PT = transform(img, goal, transform_type='path', alpha=0.01) PT_path = wavefront(PT, start, goal) - visualize_path(img, start, goal, PT_path, 1) + visualize_path(img, start, goal, PT_path) if __name__ == "__main__": diff --git a/README.md b/README.md index 4a64f53642..49a99959f1 100644 --- a/README.md +++ b/README.md @@ -6,7 +6,7 @@ [![Build Status](https://travis-ci.org/AtsushiSakai/PythonRobotics.svg?branch=master)](https://travis-ci.org/AtsushiSakai/PythonRobotics) [![Documentation Status](https://readthedocs.org/projects/pythonrobotics/badge/?version=latest)](https://pythonrobotics.readthedocs.io/en/latest/?badge=latest) [![Build status](https://ci.appveyor.com/api/projects/status/sb279kxuv1be391g?svg=true)](https://ci.appveyor.com/project/AtsushiSakai/pythonrobotics) -[![Coverage Status](https://coveralls.io/repos/github/AtsushiSakai/PythonRobotics/badge.svg?branch=master)](https://coveralls.io/github/AtsushiSakai/PythonRobotics?branch=master) +[![codecov](https://codecov.io/gh/AtsushiSakai/PythonRobotics/branch/master/graph/badge.svg)](https://codecov.io/gh/AtsushiSakai/PythonRobotics) [![Language grade: Python](https://img.shields.io/lgtm/grade/python/g/AtsushiSakai/PythonRobotics.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/AtsushiSakai/PythonRobotics/context:python) [![CodeFactor](https://www.codefactor.io/repository/github/atsushisakai/pythonrobotics/badge/master)](https://www.codefactor.io/repository/github/atsushisakai/pythonrobotics/overview/master) [![tokei](https://tokei.rs/b1/github/AtsushiSakai/PythonRobotics)](https://github.com/AtsushiSakai/PythonRobotics) From 4c5e3ccc9eba866f743feb3ade462fb104f0f4b0 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 10 Jul 2020 23:46:19 +0900 Subject: [PATCH 283/940] fix VisibleDeprecation Warning (#358) * try coverage * add python warning setting * add random seed for test coverage --- SLAM/EKFSLAM/ekf_slam.py | 7 ++++--- runtests.sh | 1 + tests/test_batch_informed_rrt_star.py | 5 ++++- tests/test_closed_loop_rrt_star_car.py | 4 +++- tests/test_dubins_path_planning.py | 1 + tests/test_lqr_rrt_star.py | 5 ++++- tests/test_n_joint_arm_to_point_control.py | 3 +++ tests/test_rrt.py | 3 +++ 8 files changed, 23 insertions(+), 6 deletions(-) diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index 6b349d858b..8fa1a771c2 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -117,7 +117,7 @@ def jacob_motion(x, u): jF = np.array([[0.0, 0.0, -DT * u[0] * math.sin(x[2, 0])], [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])], - [0.0, 0.0, 0.0]]) + [0.0, 0.0, 0.0]], dtype=np.float64) G = np.eye(STATE_SIZE) + Fx.T @ jF @ Fx @@ -236,8 +236,9 @@ def main(): if show_animation: # pragma: no cover plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(RFID[:, 0], RFID[:, 1], "*k") plt.plot(xEst[0], xEst[1], ".r") diff --git a/runtests.sh b/runtests.sh index 52ef50f001..d7df3cff04 100755 --- a/runtests.sh +++ b/runtests.sh @@ -1,5 +1,6 @@ #!/usr/bin/env bash echo "Run test suites! " +export PYTHONWARNINGS=default # show warning #python -m unittest discover tests #python -Wignore -m unittest discover tests #ignore warning coverage run -m unittest discover tests # generate coverage file diff --git a/tests/test_batch_informed_rrt_star.py b/tests/test_batch_informed_rrt_star.py index e83684d92c..bac8941460 100644 --- a/tests/test_batch_informed_rrt_star.py +++ b/tests/test_batch_informed_rrt_star.py @@ -1,14 +1,17 @@ from unittest import TestCase import sys import os +import random sys.path.append(os.path.dirname(__file__) + "/../") try: from PathPlanning.BatchInformedRRTStar import batch_informed_rrtstar as m -except: +except ImportError: raise print(__file__) +random.seed(12345) + class Test(TestCase): diff --git a/tests/test_closed_loop_rrt_star_car.py b/tests/test_closed_loop_rrt_star_car.py index 18513ce665..060389d6a2 100644 --- a/tests/test_closed_loop_rrt_star_car.py +++ b/tests/test_closed_loop_rrt_star_car.py @@ -1,5 +1,6 @@ import os import sys +import random from unittest import TestCase sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../") @@ -7,9 +8,10 @@ "/../PathPlanning/ClosedLoopRRTStar/") try: from PathPlanning.ClosedLoopRRTStar import closed_loop_rrt_star_car as m -except: +except ImportError: raise +random.seed(12345) print(__file__) diff --git a/tests/test_dubins_path_planning.py b/tests/test_dubins_path_planning.py index f9349217a1..1be70e390e 100644 --- a/tests/test_dubins_path_planning.py +++ b/tests/test_dubins_path_planning.py @@ -1,6 +1,7 @@ from unittest import TestCase import numpy as np +np.random.seed(12345) from PathPlanning.DubinsPath import dubins_path_planning diff --git a/tests/test_lqr_rrt_star.py b/tests/test_lqr_rrt_star.py index a9c2f5eece..0b59475b3d 100644 --- a/tests/test_lqr_rrt_star.py +++ b/tests/test_lqr_rrt_star.py @@ -1,16 +1,19 @@ from unittest import TestCase import sys import os +import random sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../") sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../PathPlanning/LQRRRTStar/") try: from PathPlanning.LQRRRTStar import lqr_rrt_star as m -except: +except ImportError: raise print(__file__) +random.seed(12345) + class Test(TestCase): diff --git a/tests/test_n_joint_arm_to_point_control.py b/tests/test_n_joint_arm_to_point_control.py index a935216475..deb30f83be 100644 --- a/tests/test_n_joint_arm_to_point_control.py +++ b/tests/test_n_joint_arm_to_point_control.py @@ -1,5 +1,6 @@ import os import sys +import random from unittest import TestCase sys.path.append(os.path.dirname(__file__) + "/../ArmNavigation/n_joint_arm_to_point_control/") @@ -8,6 +9,8 @@ print(__file__) +random.seed(12345) + class Test(TestCase): diff --git a/tests/test_rrt.py b/tests/test_rrt.py index 6e8f3f300a..b7c03d25cf 100644 --- a/tests/test_rrt.py +++ b/tests/test_rrt.py @@ -1,5 +1,6 @@ import os import sys +import random from unittest import TestCase sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../") @@ -12,6 +13,8 @@ print(__file__) +random.seed(12345) + class Test(TestCase): From cb796ddeffc83750672846db4353332a1a2243dd Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 11 Jul 2020 14:12:37 +0900 Subject: [PATCH 284/940] Add .circleci/config.yml (#359) * Add .circleci/config.yml * try doc build * try doc build * try doc build * try doc build * try doc build * try doc build * try doc build --- .circleci/artifact_path | 1 + .circleci/config.yml | 25 +++++++++++++++++++++++++ .github/workflows/Linux_CI.yml | 7 +++++++ 3 files changed, 33 insertions(+) create mode 100644 .circleci/artifact_path create mode 100644 .circleci/config.yml diff --git a/.circleci/artifact_path b/.circleci/artifact_path new file mode 100644 index 0000000000..59e6bd06ee --- /dev/null +++ b/.circleci/artifact_path @@ -0,0 +1 @@ +0/html/index.html \ No newline at end of file diff --git a/.circleci/config.yml b/.circleci/config.yml new file mode 100644 index 0000000000..f63f094a3f --- /dev/null +++ b/.circleci/config.yml @@ -0,0 +1,25 @@ +version: 2.1 + +orbs: + python: circleci/python@0.2.1 + +jobs: + build_doc: + executor: python/default + steps: + - checkout + - python/load-cache + - python/install-deps + - python/save-cache + - run: pip install sphinx sphinx-autobuild sphinx-rtd-theme + - run: + command: cd docs;make html + name: doc_build + - store_artifacts: + path: docs/_build/html/ + destination: html + +workflows: + main: + jobs: + - build_doc diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index de99bd446f..8338a5f4ce 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -43,6 +43,12 @@ jobs: find SLAM -name "*.py" | xargs mypy - name: do diff style check run: bash rundiffstylecheck.sh + - name: run-circleci-artifacts-redirector + uses: larsoner/circleci-artifacts-redirector-action@0.2.0 + with: + repo-token: ${{ secrets.GITHUB_TOKEN }} + artifact-path: 0/html/index.html + circleci-jobs: build_doc - name: do all unit tests run: bash runtests.sh - name: Codecov @@ -50,3 +56,4 @@ jobs: + From e8a805ef67b8c7ef8f623d1f594c539ffa288d1f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 11 Jul 2020 16:18:13 +0900 Subject: [PATCH 285/940] doc build test (#360) * try doc build * try doc build * try doc build * try doc build * try doc build * try doc build --- .circleci/artifact_path | 2 +- .github/workflows/Linux_CI.yml | 6 ------ .github/workflows/main.yml | 16 ++++++++++++++++ 3 files changed, 17 insertions(+), 7 deletions(-) create mode 100644 .github/workflows/main.yml diff --git a/.circleci/artifact_path b/.circleci/artifact_path index 59e6bd06ee..d2c64880b1 100644 --- a/.circleci/artifact_path +++ b/.circleci/artifact_path @@ -1 +1 @@ -0/html/index.html \ No newline at end of file +0/html/index.html diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index 8338a5f4ce..a751c75d4d 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -43,12 +43,6 @@ jobs: find SLAM -name "*.py" | xargs mypy - name: do diff style check run: bash rundiffstylecheck.sh - - name: run-circleci-artifacts-redirector - uses: larsoner/circleci-artifacts-redirector-action@0.2.0 - with: - repo-token: ${{ secrets.GITHUB_TOKEN }} - artifact-path: 0/html/index.html - circleci-jobs: build_doc - name: do all unit tests run: bash runtests.sh - name: Codecov diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml new file mode 100644 index 0000000000..55d33eb324 --- /dev/null +++ b/.github/workflows/main.yml @@ -0,0 +1,16 @@ +name: circleci-artifacts-redirector-action +on: [status] +jobs: + circleci_artifacts_redirector_job: + runs-on: ubuntu-latest + name: Run CircleCI artifacts redirector + steps: + - name: run-circleci-artifacts-redirector + uses: larsoner/circleci-artifacts-redirector-action@master + with: + repo-token: ${{ secrets.GITHUB_TOKEN }} + artifact-path: 0/html/index.html + circleci-jobs: build_doc + - name: Check the URL + run: | + curl --fail ${{ steps.step1.outputs.url }} | grep $GITHUB_SHA From 9fe14e657ba6a6c2aa7ee8bc586312e1c2154b72 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 11 Jul 2020 17:12:47 +0900 Subject: [PATCH 286/940] doc build test again (#361) * try doc build * try doc build --- .../workflows/{main.yml => circleci-artifacts-redirector.yml} | 2 +- docs/index.rst | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) rename .github/workflows/{main.yml => circleci-artifacts-redirector.yml} (87%) diff --git a/.github/workflows/main.yml b/.github/workflows/circleci-artifacts-redirector.yml similarity index 87% rename from .github/workflows/main.yml rename to .github/workflows/circleci-artifacts-redirector.yml index 55d33eb324..849a97f1a7 100644 --- a/.github/workflows/main.yml +++ b/.github/workflows/circleci-artifacts-redirector.yml @@ -6,7 +6,7 @@ jobs: name: Run CircleCI artifacts redirector steps: - name: run-circleci-artifacts-redirector - uses: larsoner/circleci-artifacts-redirector-action@master + uses: larsoner/circleci-artifacts-redirector-action@0.2.0 with: repo-token: ${{ secrets.GITHUB_TOKEN }} artifact-path: 0/html/index.html diff --git a/docs/index.rst b/docs/index.rst index e8e6052879..3798a1a1a6 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -8,7 +8,7 @@ Welcome to PythonRobotics's documentation! Python codes for robotics algorithm. The project is on `GitHub`_. -This is a Python code collection of robotics algorithms, especially for autonomous navigation. +This is a Python code collection of robotics algorithms. Features: From 0c23ebe62be248000151f6fe543bcd551d964177 Mon Sep 17 00:00:00 2001 From: Todd Tang Date: Sun, 12 Jul 2020 12:09:43 +0800 Subject: [PATCH 287/940] Spiral Spanning Tree Coverage Path Planning (#355) * First commit of Spiral Spanning Tree Coverage * Modify followed by first code review * fix pycodestyle error * modifies following 2nd code review --- .../SpiralSpanningTreeCPP/map/test.png | Bin 0 -> 156 bytes .../SpiralSpanningTreeCPP/map/test_2.png | Bin 0 -> 150 bytes .../SpiralSpanningTreeCPP/map/test_3.png | Bin 0 -> 132 bytes ...ral_spanning_tree_coverage_path_planner.py | 313 ++++++++++++++++++ ...ral_spanning_tree_coverage_path_planner.py | 58 ++++ 5 files changed, 371 insertions(+) create mode 100644 PathPlanning/SpiralSpanningTreeCPP/map/test.png create mode 100644 PathPlanning/SpiralSpanningTreeCPP/map/test_2.png create mode 100644 PathPlanning/SpiralSpanningTreeCPP/map/test_3.png create mode 100644 PathPlanning/SpiralSpanningTreeCPP/spiral_spanning_tree_coverage_path_planner.py create mode 100644 tests/test_spiral_spanning_tree_coverage_path_planner.py diff --git a/PathPlanning/SpiralSpanningTreeCPP/map/test.png b/PathPlanning/SpiralSpanningTreeCPP/map/test.png new file mode 100644 index 0000000000000000000000000000000000000000..4abca0bf3090e5b22cb5d6a48ed9c55a4024e787 GIT binary patch literal 156 zcmeAS@N?(olHy`uVBq!ia0vp^Iv~seBp9sUv)%<#>?NMQuIx|P8M&EELc9#81BC)S zT^vI!dXxX0cd$uNa(ufYN#sD2|D=hHjSuaGsttBZ-poD05Ss&JNE+~U7<-f(Z~R#> zVMk@i#}!F2466K(PSYECptdJh!x z@^oA^-pY literal 0 HcmV?d00001 diff --git a/PathPlanning/SpiralSpanningTreeCPP/map/test_3.png b/PathPlanning/SpiralSpanningTreeCPP/map/test_3.png new file mode 100644 index 0000000000000000000000000000000000000000..1a50b87ccff5a966f5e078282cefec2f14ba9112 GIT binary patch literal 132 zcmeAS@N?(olHy`uVBq!ia0vp^20*O90VEg-_b)jBq}WS5eO=j~u(R_RiwlJC@d1S_ zJY5_^EP9jwoNtgfSoCow$BN?&i>2I5d1QGtPRUU#f;|BY-CV2^o55JQI eekEFDFfjD$u~_NcJpT`927{-opUXO@geCxLEGFFm literal 0 HcmV?d00001 diff --git a/PathPlanning/SpiralSpanningTreeCPP/spiral_spanning_tree_coverage_path_planner.py b/PathPlanning/SpiralSpanningTreeCPP/spiral_spanning_tree_coverage_path_planner.py new file mode 100644 index 0000000000..4a6b42db0b --- /dev/null +++ b/PathPlanning/SpiralSpanningTreeCPP/spiral_spanning_tree_coverage_path_planner.py @@ -0,0 +1,313 @@ +""" +Spiral Spanning Tree Coverage Path Planner + +author: Todd Tang +paper: Spiral-STC: An On-Line Coverage Algorithm of Grid Environments + by a Mobile Robot - Gabriely et.al. +link: https://ieeexplore.ieee.org/abstract/document/1013479 +""" + +import os +import sys +import math + +import numpy as np +import matplotlib.pyplot as plt + +do_animation = True + + +class SpiralSpanningTreeCoveragePlanner: + def __init__(self, occ_map): + self.origin_map_height = occ_map.shape[0] + self.origin_map_width = occ_map.shape[1] + + # original map resolution must be even + if self.origin_map_height % 2 == 1 or self.origin_map_width % 2 == 1: + sys.exit('original map width/height must be even \ + in grayscale .png format') + + self.occ_map = occ_map + self.merged_map_height = self.origin_map_height // 2 + self.merged_map_width = self.origin_map_width // 2 + + self.edge = [] + + def plan(self, start): + """plan + + performing Spiral Spanning Tree Coverage path planning + + :param start: the start node of Spiral Spanning Tree Coverage + """ + + visit_times = np.zeros( + (self.merged_map_height, self.merged_map_width), dtype=np.int) + visit_times[start[0]][start[1]] = 1 + + # generate route by + # recusively call perform_spanning_tree_coverage() from start node + route = [] + self.perform_spanning_tree_coverage(start, visit_times, route) + + path = [] + # generate path from route + for idx in range(len(route)-1): + dp = abs(route[idx][0] - route[idx+1][0]) + \ + abs(route[idx][1] - route[idx+1][1]) + if dp == 0: + # special handle for round-trip path + path.append(self.get_round_trip_path(route[idx-1], route[idx])) + elif dp == 1: + path.append(self.move(route[idx], route[idx+1])) + elif dp == 2: + # special handle for non-adjacent route nodes + mid_node = self.get_intermediate_node(route[idx], route[idx+1]) + path.append(self.move(route[idx], mid_node)) + path.append(self.move(mid_node, route[idx+1])) + else: + sys.exit('adjacent path node distance larger than 2') + + return self.edge, route, path + + def perform_spanning_tree_coverage(self, current_node, visit_times, route): + """perform_spanning_tree_coverage + + recursive function for function + + :param current_node: current node + """ + + def is_valid_node(i, j): + is_i_valid_bounded = 0 <= i < self.merged_map_height + is_j_valid_bounded = 0 <= j < self.merged_map_width + if is_i_valid_bounded and is_j_valid_bounded: + # free only when the 4 sub-cells are all free + return bool( + self.occ_map[2*i][2*j] + and self.occ_map[2*i+1][2*j] + and self.occ_map[2*i][2*j+1] + and self.occ_map[2*i+1][2*j+1]) + + return False + + # counter-clockwise neighbor finding order + order = [[1, 0], [0, 1], [-1, 0], [0, -1]] + + found = False + route.append(current_node) + for inc in order: + ni, nj = current_node[0] + inc[0], current_node[1] + inc[1] + if is_valid_node(ni, nj) and visit_times[ni][nj] == 0: + neighbor_node = (ni, nj) + self.edge.append((current_node, neighbor_node)) + found = True + visit_times[ni][nj] += 1 + self.perform_spanning_tree_coverage( + neighbor_node, visit_times, route) + + # backtrace route from node with neighbors all visited + # to first node with unvisited neighbor + if not found: + has_node_with_unvisited_ngb = False + for node in reversed(route): + # drop nodes that have been visited twice + if visit_times[node[0]][node[1]] == 2: + continue + + visit_times[node[0]][node[1]] += 1 + route.append(node) + + for inc in order: + ni, nj = node[0] + inc[0], node[1] + inc[1] + if is_valid_node(ni, nj) and visit_times[ni][nj] == 0: + has_node_with_unvisited_ngb = True + break + + if has_node_with_unvisited_ngb: + break + + return route + + def move(self, p, q): + direction = self.get_vector_direction(p, q) + # move east + if direction == 'E': + p = self.get_sub_node(p, 'SE') + q = self.get_sub_node(q, 'SW') + # move west + elif direction == 'W': + p = self.get_sub_node(p, 'NW') + q = self.get_sub_node(q, 'NE') + # move south + elif direction == 'S': + p = self.get_sub_node(p, 'SW') + q = self.get_sub_node(q, 'NW') + # move north + elif direction == 'N': + p = self.get_sub_node(p, 'NE') + q = self.get_sub_node(q, 'SE') + else: + sys.exit('move direction error...') + return [p, q] + + def get_round_trip_path(self, last, pivot): + direction = self.get_vector_direction(last, pivot) + if direction == 'E': + return [self.get_sub_node(pivot, 'SE'), + self.get_sub_node(pivot, 'NE')] + elif direction == 'S': + return [self.get_sub_node(pivot, 'SW'), + self.get_sub_node(pivot, 'SE')] + elif direction == 'W': + return [self.get_sub_node(pivot, 'NW'), + self.get_sub_node(pivot, 'SW')] + elif direction == 'N': + return [self.get_sub_node(pivot, 'NE'), + self.get_sub_node(pivot, 'NW')] + else: + sys.exit('get_round_trip_path: last->pivot direction error.') + + def get_vector_direction(self, p, q): + # east + if p[0] == q[0] and p[1] < q[1]: + return 'E' + # west + elif p[0] == q[0] and p[1] > q[1]: + return 'W' + # south + elif p[0] < q[0] and p[1] == q[1]: + return 'S' + # north + elif p[0] > q[0] and p[1] == q[1]: + return 'N' + else: + sys.exit('get_vector_direction: Only E/W/S/N direction supported.') + + def get_sub_node(self, node, direction): + if direction == 'SE': + return [2*node[0]+1, 2*node[1]+1] + elif direction == 'SW': + return [2*node[0]+1, 2*node[1]] + elif direction == 'NE': + return [2*node[0], 2*node[1]+1] + elif direction == 'NW': + return [2*node[0], 2*node[1]] + else: + sys.exit('get_sub_node: sub-node direction error.') + + def get_interpolated_path(self, p, q): + # direction p->q: southwest / northeast + if (p[0] < q[0]) ^ (p[1] < q[1]): + ipx = [p[0], p[0], q[0]] + ipy = [p[1], q[1], q[1]] + # direction p->q: southeast / northwest + else: + ipx = [p[0], q[0], q[0]] + ipy = [p[1], p[1], q[1]] + return ipx, ipy + + def get_intermediate_node(self, p, q): + p_ngb, q_ngb = set(), set() + + for m, n in self.edge: + if m == p: + p_ngb.add(n) + if n == p: + p_ngb.add(m) + if m == q: + q_ngb.add(n) + if n == q: + q_ngb.add(m) + + itsc = p_ngb.intersection(q_ngb) + if len(itsc) == 0: + sys.exit('get_intermediate_node: \ + no intermediate node between', p, q) + elif len(itsc) == 1: + return list(itsc)[0] + else: + sys.exit('get_intermediate_node: \ + more than 1 intermediate node between', p, q) + + def visualize_path(self, edge, path, start): + def coord_transform(p): + return [2*p[1] + 0.5, 2*p[0] + 0.5] + + if do_animation: + last = path[0][0] + trajectory = [[last[1]], [last[0]]] + for p, q in path: + distance = math.hypot(p[0]-last[0], p[1]-last[1]) + if distance <= 1.0: + trajectory[0].append(p[1]) + trajectory[1].append(p[0]) + else: + ipx, ipy = self.get_interpolated_path(last, p) + trajectory[0].extend(ipy) + trajectory[1].extend(ipx) + + last = q + + trajectory[0].append(last[1]) + trajectory[1].append(last[0]) + + for idx, state in enumerate(np.transpose(trajectory)): + plt.cla() + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + + # draw spanning tree + plt.imshow(self.occ_map, 'gray') + for p, q in edge: + p = coord_transform(p) + q = coord_transform(q) + plt.plot([p[0], q[0]], [p[1], q[1]], '-oc') + sx, sy = coord_transform(start) + plt.plot([sx], [sy], 'pr', markersize=10) + + # draw move path + plt.plot(trajectory[0][:idx+1], trajectory[1][:idx+1], '-k') + plt.plot(state[0], state[1], 'or') + plt.axis('equal') + plt.grid(True) + plt.pause(0.01) + + else: + # draw spanning tree + plt.imshow(self.occ_map, 'gray') + for p, q in edge: + p = coord_transform(p) + q = coord_transform(q) + plt.plot([p[0], q[0]], [p[1], q[1]], '-oc') + sx, sy = coord_transform(start) + plt.plot([sx], [sy], 'pr', markersize=10) + + # draw move path + last = path[0][0] + for p, q in path: + distance = math.hypot(p[0]-last[0], p[1]-last[1]) + if distance == 1.0: + plt.plot([last[1], p[1]], [last[0], p[0]], '-k') + else: + ipx, ipy = self.get_interpolated_path(last, p) + plt.plot(ipy, ipx, '-k') + plt.arrow(p[1], p[0], q[1]-p[1], q[0]-p[0], head_width=0.2) + last = q + + plt.show() + + +def main(): + dir_path = os.path.dirname(os.path.realpath(__file__)) + img = plt.imread(os.path.join(dir_path, 'map', 'test_2.png')) + STC_planner = SpiralSpanningTreeCoveragePlanner(img) + start = (10, 0) + edge, route, path = STC_planner.plan(start) + STC_planner.visualize_path(edge, path, start) + + +if __name__ == "__main__": + main() diff --git a/tests/test_spiral_spanning_tree_coverage_path_planner.py b/tests/test_spiral_spanning_tree_coverage_path_planner.py new file mode 100644 index 0000000000..622b6ba18c --- /dev/null +++ b/tests/test_spiral_spanning_tree_coverage_path_planner.py @@ -0,0 +1,58 @@ +import os +import sys +import matplotlib.pyplot as plt +from unittest import TestCase + +sys.path.append(os.path.dirname( + os.path.abspath(__file__)) + "/../PathPlanning/SpiralSpanningTreeCPP") +try: + import spiral_spanning_tree_coverage_path_planner +except ImportError: + raise + +spiral_spanning_tree_coverage_path_planner.do_animation = True + + +class TestPlanning(TestCase): + def spiral_stc_cpp(self, img, start): + num_free = 0 + for i in range(img.shape[0]): + for j in range(img.shape[1]): + num_free += img[i][j] + + STC_planner = spiral_spanning_tree_coverage_path_planner.\ + SpiralSpanningTreeCoveragePlanner(img) + + edge, route, path = STC_planner.plan(start) + + covered_nodes = set() + for p, q in edge: + covered_nodes.add(p) + covered_nodes.add(q) + + # assert complete coverage + self.assertEqual(len(covered_nodes), num_free / 4) + + def test_spiral_stc_cpp_1(self): + img_dir = os.path.dirname( + os.path.abspath(__file__)) + \ + "/../PathPlanning/SpiralSpanningTreeCPP" + img = plt.imread(os.path.join(img_dir, 'map', 'test.png')) + start = (0, 0) + self.spiral_stc_cpp(img, start) + + def test_spiral_stc_cpp_2(self): + img_dir = os.path.dirname( + os.path.abspath(__file__)) + \ + "/../PathPlanning/SpiralSpanningTreeCPP" + img = plt.imread(os.path.join(img_dir, 'map', 'test_2.png')) + start = (10, 0) + self.spiral_stc_cpp(img, start) + + def test_spiral_stc_cpp_3(self): + img_dir = os.path.dirname( + os.path.abspath(__file__)) + \ + "/../PathPlanning/SpiralSpanningTreeCPP" + img = plt.imread(os.path.join(img_dir, 'map', 'test_3.png')) + start = (0, 0) + self.spiral_stc_cpp(img, start) From 808aa0fc4032500982ba2e4111d533ccfc1bc65f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 28 Jul 2020 07:16:33 +0900 Subject: [PATCH 288/940] Bump matplotlib from 3.2.2 to 3.3.0 (#366) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.2.2 to 3.3.0. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.2.2...v3.3.0) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 775486efa3..217a23e50f 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.0 scipy == 1.5.1 pandas == 1.0.5 -matplotlib == 3.2.2 +matplotlib == 3.3.0 cvxpy == 1.1.1 From a87c5ab88026b909564b0787f8ef19961ba90d60 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 28 Jul 2020 07:48:21 +0900 Subject: [PATCH 289/940] Bump cvxpy from 1.1.1 to 1.1.3 (#367) Bumps [cvxpy](https://github.com/cvxgrp/cvxpy) from 1.1.1 to 1.1.3. - [Release notes](https://github.com/cvxgrp/cvxpy/releases) - [Changelog](https://github.com/cvxgrp/cvxpy/blob/master/CHANGELOG.md) - [Commits](https://github.com/cvxgrp/cvxpy/compare/v1.1.1...v1.1.3) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 217a23e50f..2b884c032f 100644 --- a/requirements.txt +++ b/requirements.txt @@ -2,4 +2,4 @@ numpy == 1.19.0 scipy == 1.5.1 pandas == 1.0.5 matplotlib == 3.3.0 -cvxpy == 1.1.1 +cvxpy == 1.1.3 From d861cda9d4448f792be655bdfaedc6e8e8a0ed7d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 28 Jul 2020 07:49:42 +0900 Subject: [PATCH 290/940] Bump scipy from 1.5.1 to 1.5.2 (#368) Bumps [scipy](https://github.com/scipy/scipy) from 1.5.1 to 1.5.2. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.5.1...v1.5.2) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 2b884c032f..ea6578e457 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.0 -scipy == 1.5.1 +scipy == 1.5.2 pandas == 1.0.5 matplotlib == 3.3.0 cvxpy == 1.1.3 From a3808bca79e22a7fc7a131d6f357fca2f30c6d75 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 28 Jul 2020 08:54:56 +0900 Subject: [PATCH 291/940] Bump numpy from 1.19.0 to 1.19.1 (#369) Bumps [numpy](https://github.com/numpy/numpy) from 1.19.0 to 1.19.1. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/master/doc/HOWTO_RELEASE.rst.txt) - [Commits](https://github.com/numpy/numpy/compare/v1.19.0...v1.19.1) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index ea6578e457..a256740bbd 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.19.0 +numpy == 1.19.1 scipy == 1.5.2 pandas == 1.0.5 matplotlib == 3.3.0 From c90ef2ccb3961620581b55fbac4555f1d5aec14b Mon Sep 17 00:00:00 2001 From: "Gaushik M.R" Date: Sun, 2 Aug 2020 16:40:28 +0530 Subject: [PATCH 292/940] Create CODE_OF_CONDUCT.md (#370) --- CODE_OF_CONDUCT.md | 76 ++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 76 insertions(+) create mode 100644 CODE_OF_CONDUCT.md diff --git a/CODE_OF_CONDUCT.md b/CODE_OF_CONDUCT.md new file mode 100644 index 0000000000..e8c4702596 --- /dev/null +++ b/CODE_OF_CONDUCT.md @@ -0,0 +1,76 @@ +# Contributor Covenant Code of Conduct + +## Our Pledge + +In the interest of fostering an open and welcoming environment, we as +contributors and maintainers pledge to making participation in our project and +our community a harassment-free experience for everyone, regardless of age, body +size, disability, ethnicity, sex characteristics, gender identity and expression, +level of experience, education, socio-economic status, nationality, personal +appearance, race, religion, or sexual identity and orientation. + +## Our Standards + +Examples of behavior that contributes to creating a positive environment +include: + +* Using welcoming and inclusive language +* Being respectful of differing viewpoints and experiences +* Gracefully accepting constructive criticism +* Focusing on what is best for the community +* Showing empathy towards other community members + +Examples of unacceptable behavior by participants include: + +* The use of sexualized language or imagery and unwelcome sexual attention or + advances +* Trolling, insulting/derogatory comments, and personal or political attacks +* Public or private harassment +* Publishing others' private information, such as a physical or electronic + address, without explicit permission +* Other conduct which could reasonably be considered inappropriate in a + professional setting + +## Our Responsibilities + +Project maintainers are responsible for clarifying the standards of acceptable +behavior and are expected to take appropriate and fair corrective action in +response to any instances of unacceptable behavior. + +Project maintainers have the right and responsibility to remove, edit, or +reject comments, commits, code, wiki edits, issues, and other contributions +that are not aligned to this Code of Conduct, or to ban temporarily or +permanently any contributor for other behaviors that they deem inappropriate, +threatening, offensive, or harmful. + +## Scope + +This Code of Conduct applies both within project spaces and in public spaces +when an individual is representing the project or its community. Examples of +representing a project or community include using an official project e-mail +address, posting via an official social media account, or acting as an appointed +representative at an online or offline event. Representation of a project may be +further defined and clarified by project maintainers. + +## Enforcement + +Instances of abusive, harassing, or otherwise unacceptable behavior may be +reported by contacting the project team at asakaig@gmail.com. All +complaints will be reviewed and investigated and will result in a response that +is deemed necessary and appropriate to the circumstances. The project team is +obligated to maintain confidentiality with regard to the reporter of an incident. +Further details of specific enforcement policies may be posted separately. + +Project maintainers who do not follow or enforce the Code of Conduct in good +faith may face temporary or permanent repercussions as determined by other +members of the project's leadership. + +## Attribution + +This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4, +available at https://www.contributor-covenant.org/version/1/4/code-of-conduct.html + +[homepage]: https://www.contributor-covenant.org + +For answers to common questions about this code of conduct, see +https://www.contributor-covenant.org/faq From 88cc03dd217e10f2672bde06b11b5d892c975f15 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 2 Aug 2020 21:50:27 +0900 Subject: [PATCH 293/940] refactor hybrid_a_star codes and clean up heuristic function names (#371) * refactor hybrid_a_star code heuristic function names and codes * removed empty line --- .../circleci-artifacts-redirector.yml | 3 - ...ic.py => dynamic_programming_heuristic.py} | 65 +------------------ PathPlanning/HybridAStar/hybrid_a_star.py | 8 +-- 3 files changed, 6 insertions(+), 70 deletions(-) rename PathPlanning/HybridAStar/{a_star_heuristic.py => dynamic_programming_heuristic.py} (76%) diff --git a/.github/workflows/circleci-artifacts-redirector.yml b/.github/workflows/circleci-artifacts-redirector.yml index 849a97f1a7..951e3a5947 100644 --- a/.github/workflows/circleci-artifacts-redirector.yml +++ b/.github/workflows/circleci-artifacts-redirector.yml @@ -11,6 +11,3 @@ jobs: repo-token: ${{ secrets.GITHUB_TOKEN }} artifact-path: 0/html/index.html circleci-jobs: build_doc - - name: Check the URL - run: | - curl --fail ${{ steps.step1.outputs.url }} | grep $GITHUB_SHA diff --git a/PathPlanning/HybridAStar/a_star_heuristic.py b/PathPlanning/HybridAStar/dynamic_programming_heuristic.py similarity index 76% rename from PathPlanning/HybridAStar/a_star_heuristic.py rename to PathPlanning/HybridAStar/dynamic_programming_heuristic.py index 36c3342462..cc635260d6 100644 --- a/PathPlanning/HybridAStar/a_star_heuristic.py +++ b/PathPlanning/HybridAStar/dynamic_programming_heuristic.py @@ -42,7 +42,7 @@ def calc_final_path(goal_node, closed_node_set, resolution): return rx, ry -def dp_planning(sx, sy, gx, gy, ox, oy, resolution, rr): +def calc_distance_heuristic(gx, gy, ox, oy, resolution, rr): """ gx: goal x position [m] gx: goal x position [m] @@ -52,7 +52,6 @@ def dp_planning(sx, sy, gx, gy, ox, oy, resolution, rr): rr: robot radius[m] """ - start_node = Node(round(sx / resolution), round(sy / resolution), 0.0, -1) goal_node = Node(round(gx / resolution), round(gy / resolution), 0.0, -1) ox = [iox / resolution for iox in ox] oy = [ioy / resolution for ioy in oy] @@ -115,16 +114,7 @@ def dp_planning(sx, sy, gx, gy, ox, oy, resolution, rr): priority_queue, (node.cost, calc_index(node, x_w, min_x, min_y))) - rx, ry = calc_final_path(closed_set[calc_index( - start_node, x_w, min_x, min_y)], closed_set, resolution) - - return rx, ry, closed_set - - -def calc_heuristic(n1, n2): - w = 1.0 # weight of heuristic - d = w * math.sqrt((n1.x - n2.x) ** 2 + (n1.y - n2.y) ** 2) - return d + return closed_set def verify_node(node, obstacle_map, min_x, min_y, max_x, max_y): @@ -184,54 +174,3 @@ def get_motion_model(): [1, 1, math.sqrt(2)]] return motion - - -def main(): - print(__file__ + " start!!") - - # start and goal position - sx = 10.0 # [m] - sy = 10.0 # [m] - gx = 50.0 # [m] - gy = 50.0 # [m] - grid_size = 2.0 # [m] - robot_size = 1.0 # [m] - - ox, oy = [], [] - - for i in range(60): - ox.append(i) - oy.append(0.0) - for i in range(60): - ox.append(60.0) - oy.append(i) - for i in range(61): - ox.append(i) - oy.append(60.0) - for i in range(61): - ox.append(0.0) - oy.append(i) - for i in range(40): - ox.append(20.0) - oy.append(i) - for i in range(40): - ox.append(40.0) - oy.append(60.0 - i) - - if show_animation: # pragma: no cover - plt.plot(ox, oy, ".k") - plt.plot(sx, sy, "xr") - plt.plot(gx, gy, "xb") - plt.grid(True) - plt.axis("equal") - - rx, ry, _ = dp_planning(sx, sy, gx, gy, ox, oy, grid_size, robot_size) - - if show_animation: # pragma: no cover - plt.plot(rx, ry, "-r") - plt.show() - - -if __name__ == '__main__': - show_animation = True - main() diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index 45d6e11b18..9679e3979b 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -18,7 +18,7 @@ sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../ReedsSheppPath") try: - from a_star_heuristic import dp_planning + from dynamic_programming_heuristic import calc_distance_heuristic import reeds_shepp_path_planning as rs from car import move, check_car_collision, MAX_STEER, WB, plot_car except Exception: @@ -274,9 +274,9 @@ def hybrid_a_star_planning(start, goal, ox, oy, xy_resolution, yaw_resolution): openList, closedList = {}, {} - _, _, h_dp = dp_planning(start_node.x_list[-1], start_node.y_list[-1], - goal_node.x_list[-1], goal_node.y_list[-1], - ox, oy, xy_resolution, VR) + h_dp = calc_distance_heuristic( + goal_node.x_list[-1], goal_node.y_list[-1], + ox, oy, xy_resolution, VR) pq = [] openList[calc_index(start_node, config)] = start_node From 765f752165d157b3342e9175380befc3b92e3d89 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 4 Aug 2020 07:53:43 +0900 Subject: [PATCH 294/940] Bump pandas from 1.0.5 to 1.1.0 (#372) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.0.5 to 1.1.0. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/master/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.0.5...v1.1.0) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index a256740bbd..1dd8dfe984 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.1 scipy == 1.5.2 -pandas == 1.0.5 +pandas == 1.1.0 matplotlib == 3.3.0 cvxpy == 1.1.3 From 6d29bcd97d531b762b7c7cae39e5676930157d5f Mon Sep 17 00:00:00 2001 From: Mahyar Abdeetedal Date: Tue, 11 Aug 2020 03:31:45 -0400 Subject: [PATCH 295/940] support no obstacle in RRT* (#375) --- PathPlanning/RRTStar/rrt_star.py | 4 ++-- tests/test_rrt_star.py | 11 +++++++++++ 2 files changed, 13 insertions(+), 2 deletions(-) diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index 7b46029791..10ad93a6ba 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -81,13 +81,13 @@ def planning(self, animation=True, search_until_max_iter=True): if (not search_until_max_iter) and new_node: # check reaching the goal last_index = self.search_best_goal_node() - if last_index: + if last_index is not None: return self.generate_final_course(last_index) print("reached max iteration") last_index = self.search_best_goal_node() - if last_index: + if last_index is not None: return self.generate_final_course(last_index) return None diff --git a/tests/test_rrt_star.py b/tests/test_rrt_star.py index 514ed34829..d3661610ff 100644 --- a/tests/test_rrt_star.py +++ b/tests/test_rrt_star.py @@ -20,7 +20,18 @@ def test1(self): m.show_animation = False m.main() + def test_no_obstacle(self): + obstacle_list = [] + + # Set Initial parameters + rrt_star = m.RRTStar(start=[0, 0], + goal=[6, 10], + rand_area=[-2, 15], + obstacle_list=obstacle_list) + path = rrt_star.planning(animation=False) + assert path is not None if __name__ == '__main__': # pragma: no cover test = Test() test.test1() + test.test_no_obstacle() From 750e8a185e20b7f28424f258f503e9ee4870515e Mon Sep 17 00:00:00 2001 From: yashvarshney003 <59112785+yashvarshney003@users.noreply.github.com> Date: Sat, 15 Aug 2020 08:24:36 +0530 Subject: [PATCH 296/940] Update breadth_first_search.py (#374) --- .../breadth_first_search.py | 8 +++--- .../DepthFirstSearch/depth_first_search.py | 8 +++--- PathPlanning/Dijkstra/dijkstra.py | 16 ++++++------ README.md | 2 ++ tests/test_breadth_first_search.py | 26 +++++++++++++++++++ tests/test_depth_first_search.py | 26 +++++++++++++++++++ tests/test_dijkstra.py | 16 +++++++++++- 7 files changed, 85 insertions(+), 17 deletions(-) create mode 100644 tests/test_breadth_first_search.py create mode 100644 tests/test_depth_first_search.py diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index 01f1a31d64..406e5eb51f 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -33,16 +33,16 @@ def __init__(self, ox, oy, reso, rr): self.motion = self.get_motion_model() class Node: - def __init__(self, x, y, cost, pind, parent): + def __init__(self, x, y, cost, parent_index, parent): self.x = x # index of grid self.y = y # index of grid self.cost = cost - self.pind = pind + self.parent_index = parent_index self.parent = parent def __str__(self): return str(self.x) + "," + str(self.y) + "," + str( - self.cost) + "," + str(self.pind) + self.cost) + "," + str(self.parent_index) def planning(self, sx, sy, gx, gy): """ @@ -92,7 +92,7 @@ def planning(self, sx, sy, gx, gy): if current.x == ngoal.x and current.y == ngoal.y: print("Find goal") - ngoal.pind = current.pind + ngoal.parent_index = current.parent_index ngoal.cost = current.cost break diff --git a/PathPlanning/DepthFirstSearch/depth_first_search.py b/PathPlanning/DepthFirstSearch/depth_first_search.py index c8d2d5eaba..523225ee42 100644 --- a/PathPlanning/DepthFirstSearch/depth_first_search.py +++ b/PathPlanning/DepthFirstSearch/depth_first_search.py @@ -33,16 +33,16 @@ def __init__(self, ox, oy, reso, rr): self.motion = self.get_motion_model() class Node: - def __init__(self, x, y, cost, pind, parent): + def __init__(self, x, y, cost, parent_index, parent): self.x = x # index of grid self.y = y # index of grid self.cost = cost - self.pind = pind + self.parent_index = parent_index self.parent = parent def __str__(self): return str(self.x) + "," + str(self.y) + "," + str( - self.cost) + "," + str(self.pind) + self.cost) + "," + str(self.parent_index) def planning(self, sx, sy, gx, gy): """ @@ -88,7 +88,7 @@ def planning(self, sx, sy, gx, gy): if current.x == ngoal.x and current.y == ngoal.y: print("Find goal") - ngoal.pind = current.pind + ngoal.parent_index = current.parent_index ngoal.cost = current.cost break diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index b744bc6fc7..9956dff326 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -38,15 +38,15 @@ def __init__(self, ox, oy, resolution, robot_radius): self.motion = self.get_motion_model() class Node: - def __init__(self, x, y, cost, parent): + def __init__(self, x, y, cost, parent_index): self.x = x # index of grid self.y = y # index of grid self.cost = cost - self.parent = parent # index of previous Node + self.parent_index = parent_index # index of previous Node def __str__(self): return str(self.x) + "," + str(self.y) + "," + str( - self.cost) + "," + str(self.parent) + self.cost) + "," + str(self.parent_index) def planning(self, sx, sy, gx, gy): """ @@ -88,7 +88,7 @@ def planning(self, sx, sy, gx, gy): if current.x == goal_node.x and current.y == goal_node.y: print("Find goal") - goal_node.parent = current.parent + goal_node.parent_index = current.parent_index goal_node.cost = current.cost break @@ -126,12 +126,12 @@ def calc_final_path(self, goal_node, closed_set): # generate final course rx, ry = [self.calc_position(goal_node.x, self.min_x)], [ self.calc_position(goal_node.y, self.min_y)] - parent = goal_node.parent - while parent != -1: - n = closed_set[parent] + parent_index = goal_node.parent_index + while parent_index != -1: + n = closed_set[parent_index] rx.append(self.calc_position(n.x, self.min_x)) ry.append(self.calc_position(n.y, self.min_y)) - parent = n.parent + parent_index = n.parent_index return rx, ry diff --git a/README.md b/README.md index 49a99959f1..07dbf7ae5a 100644 --- a/README.md +++ b/README.md @@ -124,6 +124,8 @@ All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation 2. Install the required libraries. You can use environment.yml with conda command. > conda env create -f environment.yml +> using pip :- + pip install -r requirements.txt 3. Execute python script in each directory. diff --git a/tests/test_breadth_first_search.py b/tests/test_breadth_first_search.py new file mode 100644 index 0000000000..7dc36b2860 --- /dev/null +++ b/tests/test_breadth_first_search.py @@ -0,0 +1,26 @@ +from unittest import TestCase +import sys +import os +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../PathPlanning/BreadthFirstSearch/") + + +try: + import breadth_first_search as m +except ImportError: + raise + + +print(__file__) + + +class Test(TestCase): + + def test1(self): + m.show_animation = False + m.main() + + +if __name__ == '__main__': # pragma: no cover + test = Test() + test.test1() diff --git a/tests/test_depth_first_search.py b/tests/test_depth_first_search.py new file mode 100644 index 0000000000..15aa7a0a53 --- /dev/null +++ b/tests/test_depth_first_search.py @@ -0,0 +1,26 @@ +from unittest import TestCase +import sys +import os +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../PathPlanning/DepthFirstSearch/") + + +try: + import depth_first_search as m +except ImportError: + raise + + +print(__file__) + + +class Test(TestCase): + + def test1(self): + m.show_animation = False + m.main() + + +if __name__ == '__main__': # pragma: no cover + test = Test() + test.test1() diff --git a/tests/test_dijkstra.py b/tests/test_dijkstra.py index b86f2e6ce6..7650eee802 100644 --- a/tests/test_dijkstra.py +++ b/tests/test_dijkstra.py @@ -1,6 +1,15 @@ from unittest import TestCase +import sys +import os +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../PathPlanning/Dijkstra/") + + +try: + import dijkstra as m +except ImportError: + raise -from PathPlanning.Dijkstra import dijkstra as m print(__file__) @@ -10,3 +19,8 @@ class Test(TestCase): def test1(self): m.show_animation = False m.main() + + +if __name__ == '__main__': # pragma: no cover + test = Test() + test.test1() From 007db0c844589a4677eb28a646833c86c549b988 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Aug 2020 07:23:27 +0900 Subject: [PATCH 297/940] Bump cvxpy from 1.1.3 to 1.1.4 (#377) Bumps [cvxpy](https://github.com/cvxgrp/cvxpy) from 1.1.3 to 1.1.4. - [Release notes](https://github.com/cvxgrp/cvxpy/releases) - [Changelog](https://github.com/cvxgrp/cvxpy/blob/master/CHANGELOG.md) - [Commits](https://github.com/cvxgrp/cvxpy/compare/v1.1.3...v1.1.4) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 1dd8dfe984..78ba2686c2 100644 --- a/requirements.txt +++ b/requirements.txt @@ -2,4 +2,4 @@ numpy == 1.19.1 scipy == 1.5.2 pandas == 1.1.0 matplotlib == 3.3.0 -cvxpy == 1.1.3 +cvxpy == 1.1.4 From 7442bdceb18b6157b733311ffcc2d544eeab901a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Aug 2020 07:52:23 +0900 Subject: [PATCH 298/940] Bump matplotlib from 3.3.0 to 3.3.1 (#376) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.3.0 to 3.3.1. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.3.0...v3.3.1) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 78ba2686c2..2a7d5b3a91 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.1 scipy == 1.5.2 pandas == 1.1.0 -matplotlib == 3.3.0 +matplotlib == 3.3.1 cvxpy == 1.1.4 From fa227083372445f0f440b5d5ad878d9201ed7476 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 25 Aug 2020 20:32:47 +0900 Subject: [PATCH 299/940] Bump pandas from 1.1.0 to 1.1.1 (#384) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.1.0 to 1.1.1. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/master/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.1.0...v1.1.1) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 2a7d5b3a91..3bcb2de332 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.1 scipy == 1.5.2 -pandas == 1.1.0 +pandas == 1.1.1 matplotlib == 3.3.1 cvxpy == 1.1.4 From 409be20b472b5ec88077495aeb980b02d8edeb68 Mon Sep 17 00:00:00 2001 From: Sarim Mehdi Date: Sun, 30 Aug 2020 06:04:08 +0200 Subject: [PATCH 300/940] Implemented bug algorithms (#378) * Create bug.py * Update bug.py * Update bug.py * Update bug.py * Update bug.py * Update bug.py * Add files via upload * Update test_bug.py * Update test_bug.py * Update bug.py * Update test_bug.py * Delete bug.py * Create BugPlanning * Delete BugPlanning * Create bug.py * Update bug.py * Update test_bug.py * Update bug.py * Update bug.py --- PathPlanning/BugPlanning/bug.py | 327 ++++++++++++++++++++++++++++++++ tests/test_bug.py | 17 ++ 2 files changed, 344 insertions(+) create mode 100644 PathPlanning/BugPlanning/bug.py create mode 100644 tests/test_bug.py diff --git a/PathPlanning/BugPlanning/bug.py b/PathPlanning/BugPlanning/bug.py new file mode 100644 index 0000000000..21bbbbb1cb --- /dev/null +++ b/PathPlanning/BugPlanning/bug.py @@ -0,0 +1,327 @@ +""" +Bug Planning +author: Sarim Mehdi(muhammadsarim.mehdi@studio.unibo.it) +Source: https://sites.google.com/site/ece452bugalgorithms/ +""" + +import numpy as np +import matplotlib.pyplot as plt + +show_animation = True + + +class BugPlanner: + def __init__(self, start_x, start_y, goal_x, goal_y, obs_x, obs_y): + self.goal_x = goal_x + self.goal_y = goal_y + self.obs_x = obs_x + self.obs_y = obs_y + self.r_x = [start_x] + self.r_y = [start_y] + self.out_x = [] + self.out_y = [] + for o_x, o_y in zip(obs_x, obs_y): + for add_x, add_y in zip([1, 0, -1, -1, -1, 0, 1, 1], + [1, 1, 1, 0, -1, -1, -1, 0]): + cand_x, cand_y = o_x+add_x, o_y+add_y + valid_point = True + for _x, _y in zip(obs_x, obs_y): + if cand_x == _x and cand_y == _y: + valid_point = False + break + if valid_point: + self.out_x.append(cand_x), self.out_y.append(cand_y) + + def mov_normal(self): + return self.r_x[-1] + np.sign(self.goal_x - self.r_x[-1]), \ + self.r_y[-1] + np.sign(self.goal_y - self.r_y[-1]) + + def mov_to_next_obs(self, visited_x, visited_y): + for add_x, add_y in zip([1, 0, -1, 0], [0, 1, 0, -1]): + c_x, c_y = self.r_x[-1] + add_x, self.r_y[-1] + add_y + for _x, _y in zip(self.out_x, self.out_y): + use_pt = True + if c_x == _x and c_y == _y: + for v_x, v_y in zip(visited_x, visited_y): + if c_x == v_x and c_y == v_y: + use_pt = False + break + if use_pt: + return c_x, c_y, False + if not use_pt: + break + return self.r_x[-1], self.r_y[-1], True + + def bug0(self): + '''Greedy algorithm where you move towards goal + until you hit an obstacle. Then you go around it + (pick an arbitrary direction), until it is possible + for you to start moving towards goal in a greedy manner again''' + mov_dir = 'normal' + cand_x, cand_y = -np.inf, -np.inf + if show_animation: + plt.plot(self.obs_x, self.obs_y, ".k") + plt.plot(self.r_x[-1], self.r_y[-1], "og") + plt.plot(self.goal_x, self.goal_y, "xb") + plt.plot(self.out_x, self.out_y, ".") + plt.grid(True) + plt.title('BUG 0') + + for x_ob, y_ob in zip(self.out_x, self.out_y): + if self.r_x[-1] == x_ob and self.r_y[-1] == y_ob: + mov_dir = 'obs' + break + + visited_x, visited_y = [], [] + while True: + if self.r_x[-1] == self.goal_x and \ + self.r_y[-1] == self.goal_y: + break + if mov_dir == 'normal': + cand_x, cand_y = self.mov_normal() + if mov_dir == 'obs': + cand_x, cand_y, _ = self.mov_to_next_obs(visited_x, visited_y) + if mov_dir == 'normal': + found_boundary = False + for x_ob, y_ob in zip(self.out_x, self.out_y): + if cand_x == x_ob and cand_y == y_ob: + self.r_x.append(cand_x), self.r_y.append(cand_y) + visited_x[:], visited_y[:] = [], [] + visited_x.append(cand_x), visited_y.append(cand_y) + mov_dir = 'obs' + found_boundary = True + break + if not found_boundary: + self.r_x.append(cand_x), self.r_y.append(cand_y) + elif mov_dir == 'obs': + can_go_normal = True + for x_ob, y_ob in zip(self.obs_x, self.obs_y): + if self.mov_normal()[0] == x_ob and \ + self.mov_normal()[1] == y_ob: + can_go_normal = False + break + if can_go_normal: + mov_dir = 'normal' + else: + self.r_x.append(cand_x), self.r_y.append(cand_y) + visited_x.append(cand_x), visited_y.append(cand_y) + if show_animation: + plt.plot(self.r_x, self.r_y, "-r") + plt.pause(0.001) + if show_animation: + plt.show() + + def bug1(self): + '''Move towards goal in a greedy manner. + When you hit an obstacle, you go around it and + back to where you hit the obstacle initially. + Then, you go to the point on the obstacle that is + closest to your goal and you start moving towards + goal in a greedy manner from that new point.''' + mov_dir = 'normal' + cand_x, cand_y = -np.inf, -np.inf + exit_x, exit_y = -np.inf, -np.inf + dist = np.inf + back_to_start = False + second_round = False + if show_animation: + plt.plot(self.obs_x, self.obs_y, ".k") + plt.plot(self.r_x[-1], self.r_y[-1], "og") + plt.plot(self.goal_x, self.goal_y, "xb") + plt.plot(self.out_x, self.out_y, ".") + plt.grid(True) + plt.title('BUG 1') + + for xob, yob in zip(self.out_x, self.out_y): + if self.r_x[-1] == xob and self.r_y[-1] == yob: + mov_dir = 'obs' + break + + visited_x, visited_y = [], [] + while True: + if self.r_x[-1] == self.goal_x and \ + self.r_y[-1] == self.goal_y: + break + if mov_dir == 'normal': + cand_x, cand_y = self.mov_normal() + if mov_dir == 'obs': + cand_x, cand_y, back_to_start = \ + self.mov_to_next_obs(visited_x, visited_y) + if mov_dir == 'normal': + found_boundary = False + for x_ob, y_ob in zip(self.out_x, self.out_y): + if cand_x == x_ob and cand_y == y_ob: + self.r_x.append(cand_x), self.r_y.append(cand_y) + visited_x[:], visited_y[:] = [], [] + visited_x.append(cand_x), visited_y.append(cand_y) + mov_dir = 'obs' + dist = np.inf + back_to_start = False + second_round = False + found_boundary = True + break + if not found_boundary: + self.r_x.append(cand_x), self.r_y.append(cand_y) + elif mov_dir == 'obs': + d = np.linalg.norm(np.array([cand_x, cand_y] - + np.array([self.goal_x, + self.goal_y]))) + if d < dist and not second_round: + exit_x, exit_y = cand_x, cand_y + dist = d + if back_to_start and not second_round: + second_round = True + del self.r_x[-len(visited_x):] + del self.r_y[-len(visited_y):] + visited_x[:], visited_y[:] = [], [] + self.r_x.append(cand_x), self.r_y.append(cand_y) + visited_x.append(cand_x), visited_y.append(cand_y) + if cand_x == exit_x and \ + cand_y == exit_y and \ + second_round: + mov_dir = 'normal' + if show_animation: + plt.plot(self.r_x, self.r_y, "-r") + plt.pause(0.001) + if show_animation: + plt.show() + + def bug2(self): + '''Move towards goal in a greedy manner. + When you hit an obstacle, you go around it and + keep track of your distance from the goal. + If the distance from your goal was decreasing before + and now it starts increasing, that means the current + point is probably the closest point to the + goal (this may or may not be true because the algorithm + doesn't explore the entire boundary around the obstacle). + So, you depart from this point and continue towards the + goal in a greedy manner''' + mov_dir = 'normal' + cand_x, cand_y = -np.inf, -np.inf + if show_animation: + plt.plot(self.obs_x, self.obs_y, ".k") + plt.plot(self.r_x[-1], self.r_y[-1], "og") + plt.plot(self.goal_x, self.goal_y, "xb") + plt.plot(self.out_x, self.out_y, ".") + + straight_x, straight_y = [self.r_x[-1]], [self.r_y[-1]] + hit_x, hit_y = [], [] + while True: + if straight_x[-1] == self.goal_x and \ + straight_y[-1] == self.goal_y: + break + c_x = straight_x[-1] + np.sign(self.goal_x - straight_x[-1]) + c_y = straight_y[-1] + np.sign(self.goal_y - straight_y[-1]) + for x_ob, y_ob in zip(self.out_x, self.out_y): + if c_x == x_ob and c_y == y_ob: + hit_x.append(c_x), hit_y.append(c_y) + break + straight_x.append(c_x), straight_y.append(c_y) + if show_animation: + plt.plot(straight_x, straight_y, ",") + plt.plot(hit_x, hit_y, "d") + plt.grid(True) + plt.title('BUG 2') + + for x_ob, y_ob in zip(self.out_x, self.out_y): + if self.r_x[-1] == x_ob and self.r_y[-1] == y_ob: + mov_dir = 'obs' + break + + visited_x, visited_y = [], [] + while True: + if self.r_x[-1] == self.goal_x \ + and self.r_y[-1] == self.goal_y: + break + if mov_dir == 'normal': + cand_x, cand_y = self.mov_normal() + if mov_dir == 'obs': + cand_x, cand_y, _ = self.mov_to_next_obs(visited_x, visited_y) + if mov_dir == 'normal': + found_boundary = False + for x_ob, y_ob in zip(self.out_x, self.out_y): + if cand_x == x_ob and cand_y == y_ob: + self.r_x.append(cand_x), self.r_y.append(cand_y) + visited_x[:], visited_y[:] = [], [] + visited_x.append(cand_x), visited_y.append(cand_y) + del hit_x[0] + del hit_y[0] + mov_dir = 'obs' + found_boundary = True + break + if not found_boundary: + self.r_x.append(cand_x), self.r_y.append(cand_y) + elif mov_dir == 'obs': + self.r_x.append(cand_x), self.r_y.append(cand_y) + visited_x.append(cand_x), visited_y.append(cand_y) + for i_x, i_y in zip(range(len(hit_x)), range(len(hit_y))): + if cand_x == hit_x[i_x] and cand_y == hit_y[i_y]: + del hit_x[i_x] + del hit_y[i_y] + mov_dir = 'normal' + break + if show_animation: + plt.plot(self.r_x, self.r_y, "-r") + plt.pause(0.001) + if show_animation: + plt.show() + + +def main(bug_0, bug_1, bug_2): + # set obstacle positions + o_x, o_y = [], [] + + s_x = 0.0 + s_y = 0.0 + g_x = 167.0 + g_y = 50.0 + + for i in range(20, 40): + for j in range(20, 40): + o_x.append(i) + o_y.append(j) + + for i in range(60, 100): + for j in range(40, 80): + o_x.append(i) + o_y.append(j) + + for i in range(120, 140): + for j in range(80, 100): + o_x.append(i) + o_y.append(j) + + for i in range(80, 140): + for j in range(0, 20): + o_x.append(i) + o_y.append(j) + + for i in range(0, 20): + for j in range(60, 100): + o_x.append(i) + o_y.append(j) + + for i in range(20, 40): + for j in range(80, 100): + o_x.append(i) + o_y.append(j) + + for i in range(120, 160): + for j in range(40, 60): + o_x.append(i) + o_y.append(j) + + if bug_0: + my_Bug = BugPlanner(s_x, s_y, g_x, g_y, o_x, o_y) + my_Bug.bug0() + if bug_1: + my_Bug = BugPlanner(s_x, s_y, g_x, g_y, o_x, o_y) + my_Bug.bug1() + if bug_2: + my_Bug = BugPlanner(s_x, s_y, g_x, g_y, o_x, o_y) + my_Bug.bug2() + + +if __name__ == '__main__': + main(bug_0=True, bug_1=False, bug_2=False) diff --git a/tests/test_bug.py b/tests/test_bug.py new file mode 100644 index 0000000000..31d8b2c297 --- /dev/null +++ b/tests/test_bug.py @@ -0,0 +1,17 @@ +from PathPlanning.BugPlanning import bug as b +from unittest import TestCase +import sys +import os +sys.path.append(os.path.dirname(__file__) + "/../") + + +class Test(TestCase): + + def test(self): + b.show_animation = False + b.main(bug_0=True, bug_1=True, bug_2=True) + + +if __name__ == '__main__': # pragma: no cover + test = Test() + test.test() From f969069df9a5182dd006b17fdccf52a7c4e64b36 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 30 Aug 2020 13:07:08 +0900 Subject: [PATCH 301/940] fix docstring error --- PathPlanning/BugPlanning/bug.py | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/PathPlanning/BugPlanning/bug.py b/PathPlanning/BugPlanning/bug.py index 21bbbbb1cb..62fec7c109 100644 --- a/PathPlanning/BugPlanning/bug.py +++ b/PathPlanning/BugPlanning/bug.py @@ -53,10 +53,12 @@ def mov_to_next_obs(self, visited_x, visited_y): return self.r_x[-1], self.r_y[-1], True def bug0(self): - '''Greedy algorithm where you move towards goal + """ + Greedy algorithm where you move towards goal until you hit an obstacle. Then you go around it (pick an arbitrary direction), until it is possible - for you to start moving towards goal in a greedy manner again''' + for you to start moving towards goal in a greedy manner again + """ mov_dir = 'normal' cand_x, cand_y = -np.inf, -np.inf if show_animation: @@ -112,12 +114,14 @@ def bug0(self): plt.show() def bug1(self): - '''Move towards goal in a greedy manner. + """ + Move towards goal in a greedy manner. When you hit an obstacle, you go around it and back to where you hit the obstacle initially. Then, you go to the point on the obstacle that is closest to your goal and you start moving towards - goal in a greedy manner from that new point.''' + goal in a greedy manner from that new point. + """ mov_dir = 'normal' cand_x, cand_y = -np.inf, -np.inf exit_x, exit_y = -np.inf, -np.inf @@ -187,7 +191,8 @@ def bug1(self): plt.show() def bug2(self): - '''Move towards goal in a greedy manner. + """ + Move towards goal in a greedy manner. When you hit an obstacle, you go around it and keep track of your distance from the goal. If the distance from your goal was decreasing before @@ -196,7 +201,8 @@ def bug2(self): goal (this may or may not be true because the algorithm doesn't explore the entire boundary around the obstacle). So, you depart from this point and continue towards the - goal in a greedy manner''' + goal in a greedy manner + """ mov_dir = 'normal' cand_x, cand_y = -np.inf, -np.inf if show_animation: From 46bdd2afd950046d3f57c181efb0b867c63a2536 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 1 Sep 2020 08:26:44 +0900 Subject: [PATCH 302/940] Bump cvxpy from 1.1.4 to 1.1.5 (#389) Bumps [cvxpy](https://github.com/cvxgrp/cvxpy) from 1.1.4 to 1.1.5. - [Release notes](https://github.com/cvxgrp/cvxpy/releases) - [Changelog](https://github.com/cvxgrp/cvxpy/blob/master/CHANGELOG.md) - [Commits](https://github.com/cvxgrp/cvxpy/compare/v1.1.4...v1.1.5) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 3bcb2de332..bc087081b4 100644 --- a/requirements.txt +++ b/requirements.txt @@ -2,4 +2,4 @@ numpy == 1.19.1 scipy == 1.5.2 pandas == 1.1.1 matplotlib == 3.3.1 -cvxpy == 1.1.4 +cvxpy == 1.1.5 From 2a2374ee90c5c101e4f23c7171fc2e7610e32562 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 9 Sep 2020 22:35:56 +0900 Subject: [PATCH 303/940] Create pull_request_template.md (#397) --- .github/pull_request_template.md | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) create mode 100644 .github/pull_request_template.md diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md new file mode 100644 index 0000000000..9fbb893c1c --- /dev/null +++ b/.github/pull_request_template.md @@ -0,0 +1,23 @@ + + +#### Reference issue + + +#### What does this implement/fix? + + +#### Additional information + From 3b92ae8c84f86b02d8c5eab40628319f86c7e40f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 12 Sep 2020 21:36:47 +0900 Subject: [PATCH 304/940] remove code cov check (#400) --- .github/workflows/Linux_CI.yml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index a751c75d4d..1174438dd5 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -45,8 +45,6 @@ jobs: run: bash rundiffstylecheck.sh - name: do all unit tests run: bash runtests.sh - - name: Codecov - uses: codecov/codecov-action@v1.0.10 From ff3ad5bb9cf1810363191f41c5ed39e5fb923876 Mon Sep 17 00:00:00 2001 From: weicent Date: Sun, 13 Sep 2020 10:17:42 +0800 Subject: [PATCH 305/940] dwa pr (#390) * dwa pr * dwa_pr * dwa_pr * dwa_pr * dwa_pr * make changes rerun CI * rerun CI...again.. * rerun CI..... * rerun CI..... * rerun CI final time! * modified const to class variable * put back missing comment * add test for dwa stuck case * add test dwa stuck case * add test dwa stuck case * add test dwa stuck case * add stuck test in original test file --- .../dynamic_window_approach.py | 54 +++++++++++-------- tests/test_dynamic_window_approach.py | 31 +++++++++++ 2 files changed, 62 insertions(+), 23 deletions(-) diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 0df40410ab..74ff064e86 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -19,7 +19,6 @@ def dwa_control(x, config, goal, ob): """ Dynamic Window Approach control """ - dw = calc_dynamic_window(x, config) u, trajectory = calc_control_and_trajectory(x, dw, config, goal, ob) @@ -51,6 +50,7 @@ def __init__(self): self.to_goal_cost_gain = 0.15 self.speed_cost_gain = 1.0 self.obstacle_cost_gain = 1.0 + self.robot_stuck_flag_cons = 0.001 # constant to prevent robot stucked self.robot_type = RobotType.circle # if robot_type == RobotType.circle @@ -60,6 +60,23 @@ def __init__(self): # if robot_type == RobotType.rectangle self.robot_width = 0.5 # [m] for collision check self.robot_length = 1.2 # [m] for collision check + # obstacles [x(m) y(m), ....] + self.ob = np.array([[-1, -1], + [0, 2], + [4.0, 2.0], + [5.0, 4.0], + [5.0, 5.0], + [5.0, 6.0], + [5.0, 9.0], + [8.0, 9.0], + [7.0, 9.0], + [8.0, 10.0], + [9.0, 11.0], + [12.0, 13.0], + [12.0, 12.0], + [15.0, 15.0], + [13.0, 13.0] + ]) @property def robot_type(self): @@ -72,6 +89,9 @@ def robot_type(self, value): self._robot_type = value +config = Config() + + def motion(x, u, dt): """ motion model @@ -139,7 +159,6 @@ def calc_control_and_trajectory(x, dw, config, goal, ob): for y in np.arange(dw[2], dw[3], config.yaw_rate_resolution): trajectory = predict_trajectory(x_init, v, y, config) - # calc cost to_goal_cost = config.to_goal_cost_gain * calc_to_goal_cost(trajectory, goal) speed_cost = config.speed_cost_gain * (config.max_speed - trajectory[-1, 3]) @@ -152,13 +171,19 @@ def calc_control_and_trajectory(x, dw, config, goal, ob): min_cost = final_cost best_u = [v, y] best_trajectory = trajectory - + if abs(best_u[0]) < config.robot_stuck_flag_cons \ + and abs(x[3]) < config.robot_stuck_flag_cons: + # to ensure the robot do not get stuck in + # best v=0 m/s (in front of an obstacle) and + # best omega=0 rad/s (heading to the goal with + # angle difference of 0) + best_u[1] = -config.max_delta_yaw_rate return best_u, best_trajectory def calc_obstacle_cost(trajectory, ob, config): """ - calc obstacle cost inf: collision + calc obstacle cost inf: collision """ ox = ob[:, 0] oy = ob[:, 1] @@ -238,29 +263,12 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): x = np.array([0.0, 0.0, math.pi / 8.0, 0.0, 0.0]) # goal position [x(m), y(m)] goal = np.array([gx, gy]) - # obstacles [x(m) y(m), ....] - ob = np.array([[-1, -1], - [0, 2], - [4.0, 2.0], - [5.0, 4.0], - [5.0, 5.0], - [5.0, 6.0], - [5.0, 9.0], - [8.0, 9.0], - [7.0, 9.0], - [8.0, 10.0], - [9.0, 11.0], - [12.0, 13.0], - [12.0, 12.0], - [15.0, 15.0], - [13.0, 13.0] - ]) # input [forward speed, yaw_rate] - config = Config() + config.robot_type = robot_type trajectory = np.array(x) - + ob = config.ob while True: u, predicted_trajectory = dwa_control(x, config, goal, ob) x = motion(x, u, config.dt) # simulate robot diff --git a/tests/test_dynamic_window_approach.py b/tests/test_dynamic_window_approach.py index 197dda2158..93deb6846d 100644 --- a/tests/test_dynamic_window_approach.py +++ b/tests/test_dynamic_window_approach.py @@ -1,5 +1,6 @@ import os import sys +import numpy as np from unittest import TestCase sys.path.append(os.path.dirname(__file__) + "/../") @@ -20,8 +21,38 @@ def test_main2(self): m.show_animation = False m.main(gx=1.0, gy=1.0, robot_type=m.RobotType.rectangle) + def test_stuck_main(self): + m.show_animation = False + # adjust cost + m.config.to_goal_cost_gain = 0.2 + m.config.obstacle_cost_gain = 2.0 + # obstacles and goals for stuck condition + m.config.ob = -1 * np.array([[-1.0, -1.0], + [0.0, 2.0], + [2.0, 6.0], + [2.0, 8.0], + [3.0, 9.27], + [3.79, 9.39], + [7.25, 8.97], + [7.0, 2.0], + [3.0, 4.0], + [6.0, 5.0], + [3.5, 5.8], + [6.0, 9.0], + [8.8, 9.0], + [5.0, 9.0], + [7.5, 3.0], + [9.0, 8.0], + [5.8, 4.4], + [12.0, 12.0], + [3.0, 2.0], + [13.0, 13.0] + ]) + m.main(gx=-5.0, gy=-7.0) + if __name__ == '__main__': # pragma: no cover test = TestDynamicWindowApproach() test.test_main1() test.test_main2() + test.test_stuck_main() From 298f1090749d2789433255c0ea997bc18da53818 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Sep 2020 07:52:00 +0900 Subject: [PATCH 306/940] Bump numpy from 1.19.1 to 1.19.2 (#403) Bumps [numpy](https://github.com/numpy/numpy) from 1.19.1 to 1.19.2. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/master/doc/HOWTO_RELEASE.rst.txt) - [Commits](https://github.com/numpy/numpy/compare/v1.19.1...v1.19.2) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index bc087081b4..67ceca7dc1 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.19.1 +numpy == 1.19.2 scipy == 1.5.2 pandas == 1.1.1 matplotlib == 3.3.1 From 6f1642076498d9483ab002ff45abe94b854e1459 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Sep 2020 20:12:00 +0900 Subject: [PATCH 307/940] Bump pandas from 1.1.1 to 1.1.2 (#404) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.1.1 to 1.1.2. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/master/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.1.1...v1.1.2) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 67ceca7dc1..094def17af 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.2 scipy == 1.5.2 -pandas == 1.1.1 +pandas == 1.1.2 matplotlib == 3.3.1 cvxpy == 1.1.5 From 43ab313762d6688b0f27f963bfe2400cfb985137 Mon Sep 17 00:00:00 2001 From: weicent Date: Sun, 20 Sep 2020 11:40:32 +0800 Subject: [PATCH 308/940] New A star algorithm pr (#391) * a star pr * a star pr * a star pr * fix line excede 79 error * fix pycodestyle errors, missing a whitespace * add test file * add test file * rerun CI * rerun CI * rerun CI * rerun CI * rerun CI * modified test file and rerun CI * rerun CI * fix CI error * modified code resubmit pr * fixed some minor error * modified pr as suggested --- .../AStar/A_Star_searching_from_two_side.py | 369 ++++++++++++++++++ tests/test_a_star_searching_two_side.py | 27 ++ 2 files changed, 396 insertions(+) create mode 100644 PathPlanning/AStar/A_Star_searching_from_two_side.py create mode 100644 tests/test_a_star_searching_two_side.py diff --git a/PathPlanning/AStar/A_Star_searching_from_two_side.py b/PathPlanning/AStar/A_Star_searching_from_two_side.py new file mode 100644 index 0000000000..0318970cc8 --- /dev/null +++ b/PathPlanning/AStar/A_Star_searching_from_two_side.py @@ -0,0 +1,369 @@ +""" +A* algorithm +Author: Weicent +randomly generate obstacles, start and goal point +searching path from start and end simultaneously +""" + +import numpy as np +import matplotlib.pyplot as plt +import math + +show_animation = True + + +class Node: + """node with properties of g, h, coordinate and parent node""" + + def __init__(self, G=0, H=0, coordinate=None, parent=None): + self.G = G + self.H = H + self.F = G + H + self.parent = parent + self.coordinate = coordinate + + def reset_f(self): + self.F = self.G + self.H + + +def hcost(node_coordinate, goal): + dx = abs(node_coordinate[0] - goal[0]) + dy = abs(node_coordinate[1] - goal[1]) + hcost = dx + dy + return hcost + + +def gcost(fixed_node, update_node_coordinate): + dx = abs(fixed_node.coordinate[0] - update_node_coordinate[0]) + dy = abs(fixed_node.coordinate[1] - update_node_coordinate[1]) + gc = math.hypot(dx, dy) # gc = move from fixed_node to update_node + gcost = fixed_node.G + gc # gcost = move from start point to update_node + return gcost + + +def boundary_and_obstacles(start, goal, top_vertex, bottom_vertex, obs_number): + """ + :param start: start coordinate + :param goal: goal coordinate + :param top_vertex: top right vertex coordinate of boundary + :param bottom_vertex: bottom left vertex coordinate of boundary + :param obs_number: number of obstacles generated in the map + :return: boundary_obstacle array, obstacle list + """ + # below can be merged into a rectangle boundary + ay = list(range(bottom_vertex[1], top_vertex[1])) + ax = [bottom_vertex[0]] * len(ay) + cy = ay + cx = [top_vertex[0]] * len(cy) + bx = list(range(bottom_vertex[0] + 1, top_vertex[0])) + by = [bottom_vertex[1]] * len(bx) + dx = [bottom_vertex[0]] + bx + [top_vertex[0]] + dy = [top_vertex[1]] * len(dx) + + # generate random obstacles + ob_x = np.random.randint(bottom_vertex[0] + 1, + top_vertex[0], obs_number).tolist() + ob_y = np.random.randint(bottom_vertex[1] + 1, + top_vertex[1], obs_number).tolist() + # x y coordinate in certain order for boundary + x = ax + bx + cx + dx + y = ay + by + cy + dy + obstacle = np.vstack((ob_x, ob_y)).T.tolist() + # remove start and goal coordinate in obstacle list + obstacle = [coor for coor in obstacle if coor != start and coor != goal] + obs_array = np.array(obstacle) + bound = np.vstack((x, y)).T + bound_obs = np.vstack((bound, obs_array)) + return bound_obs, obstacle + + +def find_neighbor(node, ob, closed): + # generate neighbors in certain condition + ob_list = ob.tolist() + neighbor: list = [] + for x in range(node.coordinate[0] - 1, node.coordinate[0] + 2): + for y in range(node.coordinate[1] - 1, node.coordinate[1] + 2): + if [x, y] not in ob_list: + # find all possible neighbor nodes + neighbor.append([x, y]) + # remove node violate the motion rule + # 1. remove node.coordinate itself + neighbor.remove(node.coordinate) + # 2. remove neighbor nodes who cross through two diagonal + # positioned obstacles since there is no enough space for + # robot to go through two diagonal positioned obstacles + + # top bottom left right neighbors of node + top_nei = [node.coordinate[0], node.coordinate[1] + 1] + bottom_nei = [node.coordinate[0], node.coordinate[1] - 1] + left_nei = [node.coordinate[0] - 1, node.coordinate[1]] + right_nei = [node.coordinate[0] + 1, node.coordinate[1]] + # neighbors in four vertex + lt_nei = [node.coordinate[0] - 1, node.coordinate[1] + 1] + rt_nei = [node.coordinate[0] + 1, node.coordinate[1] + 1] + lb_nei = [node.coordinate[0] - 1, node.coordinate[1] - 1] + rb_nei = [node.coordinate[0] + 1, node.coordinate[1] - 1] + + # remove the unnecessary neighbors + if top_nei and left_nei in ob_list and lt_nei in neighbor: + neighbor.remove(lt_nei) + if top_nei and right_nei in ob_list and rt_nei in neighbor: + neighbor.remove(rt_nei) + if bottom_nei and left_nei in ob_list and lb_nei in neighbor: + neighbor.remove(lb_nei) + if bottom_nei and right_nei in ob_list and rb_nei in neighbor: + neighbor.remove(rb_nei) + neighbor = [x for x in neighbor if x not in closed] + return neighbor + + +def find_node_index(coordinate, node_list): + # find node index in the node list via its coordinate + ind = 0 + for node in node_list: + if node.coordinate == coordinate: + target_node = node + ind = node_list.index(target_node) + break + return ind + + +def find_path(open_list, closed_list, goal, obstacle): + # searching for the path, update open and closed list + # obstacle = obstacle and boundary + flag = len(open_list) + for i in range(flag): + node = open_list[0] + open_coordinate_list = [node.coordinate for node in open_list] + closed_coordinate_list = [node.coordinate for node in closed_list] + temp = find_neighbor(node, obstacle, closed_coordinate_list) + for element in temp: + if element in closed_list: + continue + elif element in open_coordinate_list: + # if node in open list, update g value + ind = open_coordinate_list.index(element) + new_g = gcost(node, element) + if new_g <= open_list[ind].G: + open_list[ind].G = new_g + open_list[ind].reset_f() + open_list[ind].parent = node + else: # new coordinate, create corresponding node + ele_node = Node(coordinate=element, parent=node, + G=gcost(node, element), H=hcost(element, goal)) + open_list.append(ele_node) + open_list.remove(node) + closed_list.append(node) + open_list.sort(key=lambda x: x.F) + return open_list, closed_list + + +def node_to_coordinate(node_list): + # convert node list into coordinate list and array + coordinate_list = [node.coordinate for node in node_list] + return coordinate_list + + +def check_node_coincide(close_ls1, closed_ls2): + """ + :param close_ls1: node closed list for searching from start + :param closed_ls2: node closed list for searching from end + :return: intersect node list for above two + """ + # check if node in close_ls1 intersect with node in closed_ls2 + cl1 = node_to_coordinate(close_ls1) + cl2 = node_to_coordinate(closed_ls2) + intersect_ls = [node for node in cl1 if node in cl2] + return intersect_ls + + +def find_surrounding(coordinate, obstacle): + # find obstacles around node, help to draw the borderline + boundary: list = [] + for x in range(coordinate[0] - 1, coordinate[0] + 2): + for y in range(coordinate[1] - 1, coordinate[1] + 2): + if [x, y] in obstacle: + boundary.append([x, y]) + return boundary + + +def get_border_line(node_closed_ls, obstacle): + # if no path, find border line which confine goal or robot + border: list = [] + coordinate_closed_ls = node_to_coordinate(node_closed_ls) + for coordinate in coordinate_closed_ls: + temp = find_surrounding(coordinate, obstacle) + border = border + temp + border_ary = np.array(border) + return border_ary + + +def get_path(org_list, goal_list, coordinate): + # get path from start to end + path_org: list = [] + path_goal: list = [] + ind = find_node_index(coordinate, org_list) + node = org_list[ind] + while node != org_list[0]: + path_org.append(node.coordinate) + node = node.parent + path_org.append(org_list[0].coordinate) + ind = find_node_index(coordinate, goal_list) + node = goal_list[ind] + while node != goal_list[0]: + path_goal.append(node.coordinate) + node = node.parent + path_goal.append(goal_list[0].coordinate) + path_org.reverse() + path = path_org + path_goal + path = np.array(path) + return path + + +def random_coordinate(bottom_vertex, top_vertex): + # generate random coordinates inside maze + coordinate = [np.random.randint(bottom_vertex[0] + 1, top_vertex[0]), + np.random.randint(bottom_vertex[1] + 1, top_vertex[1])] + return coordinate + + +def draw(close_origin, close_goal, start, end, bound): + # plot the map + if not close_goal.tolist(): # ensure the close_goal not empty + # in case of the obstacle number is really large (>4500), the + # origin is very likely blocked at the first search, and then + # the program is over and the searching from goal to origin + # will not start, which remain the closed_list for goal == [] + # in order to plot the map, add the end coordinate to array + close_goal = np.array([end]) + plt.cla() + plt.gcf().set_size_inches(11, 9, forward=True) + plt.axis('equal') + plt.plot(close_origin[:, 0], close_origin[:, 1], 'oy') + plt.plot(close_goal[:, 0], close_goal[:, 1], 'og') + plt.plot(bound[:, 0], bound[:, 1], 'sk') + plt.plot(end[0], end[1], '*b', label='Goal') + plt.plot(start[0], start[1], '^b', label='Origin') + plt.legend() + plt.pause(0.0001) + + +def draw_control(org_closed, goal_closed, flag, start, end, bound, obstacle): + """ + control the plot process, evaluate if the searching finished + flag == 0 : draw the searching process and plot path + flag == 1 or 2 : start or end is blocked, draw the border line + """ + stop_loop = 0 # stop sign for the searching + org_closed_ls = node_to_coordinate(org_closed) + org_array = np.array(org_closed_ls) + goal_closed_ls = node_to_coordinate(goal_closed) + goal_array = np.array(goal_closed_ls) + path = None + if show_animation: # draw the searching process + draw(org_array, goal_array, start, end, bound) + if flag == 0: + node_intersect = check_node_coincide(org_closed, goal_closed) + if node_intersect: # a path is find + path = get_path(org_closed, goal_closed, node_intersect[0]) + stop_loop = 1 + print('Path is find!') + if show_animation: # draw the path + plt.plot(path[:, 0], path[:, 1], '-r') + plt.title('Robot Arrived', size=20, loc='center') + plt.pause(0.01) + plt.show() + elif flag == 1: # start point blocked first + stop_loop = 1 + print('There is no path to the goal! Start point is blocked!') + elif flag == 2: # end point blocked first + stop_loop = 1 + print('There is no path to the goal! End point is blocked!') + if show_animation: # blocked case, draw the border line + info = 'There is no path to the goal!' \ + ' Robot&Goal are split by border' \ + ' shown in red \'x\'!' + if flag == 1: + border = get_border_line(org_closed, obstacle) + plt.plot(border[:, 0], border[:, 1], 'xr') + plt.title(info, size=14, loc='center') + plt.pause(0.01) + plt.show() + elif flag == 2: + border = get_border_line(goal_closed, obstacle) + plt.plot(border[:, 0], border[:, 1], 'xr') + plt.title(info, size=14, loc='center') + plt.pause(0.01) + plt.show() + return stop_loop, path + + +def searching_control(start, end, bound, obstacle): + """manage the searching process, start searching from two side""" + # initial origin node and end node + origin = Node(coordinate=start, H=hcost(start, end)) + goal = Node(coordinate=end, H=hcost(end, start)) + # list for searching from origin to goal + origin_open: list = [origin] + origin_close: list = [] + # list for searching from goal to origin + goal_open = [goal] + goal_close: list = [] + # initial target + target_goal = end + # flag = 0 (not blocked) 1 (start point blocked) 2 (end point blocked) + flag = 0 # init flag + path = None + while True: + # searching from start to end + origin_open, origin_close = \ + find_path(origin_open, origin_close, target_goal, bound) + if not origin_open: # no path condition + flag = 1 # origin node is blocked + draw_control(origin_close, goal_close, flag, start, end, bound, + obstacle) + break + # update target for searching from end to start + target_origin = min(origin_open, key=lambda x: x.F).coordinate + + # searching from end to start + goal_open, goal_close = \ + find_path(goal_open, goal_close, target_origin, bound) + if not goal_open: # no path condition + flag = 2 # goal is blocked + draw_control(origin_close, goal_close, flag, start, end, bound, + obstacle) + break + # update target for searching from start to end + target_goal = min(goal_open, key=lambda x: x.F).coordinate + + # continue searching, draw the process + stop_sign, path = draw_control(origin_close, goal_close, flag, start, + end, bound, obstacle) + if stop_sign: + break + return path + + +def main(obstacle_number=1500): + print(__file__ + ' start!') + + top_vertex = [60, 60] # top right vertex of boundary + bottom_vertex = [0, 0] # bottom left vertex of boundary + + # generate start and goal point randomly + start = random_coordinate(bottom_vertex, top_vertex) + end = random_coordinate(bottom_vertex, top_vertex) + + # generate boundary and obstacles + bound, obstacle = boundary_and_obstacles(start, end, top_vertex, + bottom_vertex, + obstacle_number) + + path = searching_control(start, end, bound, obstacle) + if not show_animation: + print(path) + + +if __name__ == '__main__': + main(obstacle_number=1500) diff --git a/tests/test_a_star_searching_two_side.py b/tests/test_a_star_searching_two_side.py new file mode 100644 index 0000000000..6116c9bbe7 --- /dev/null +++ b/tests/test_a_star_searching_two_side.py @@ -0,0 +1,27 @@ +from unittest import TestCase +import os +import sys + +sys.path.append(os.path.dirname(__file__) + '/../') + +try: + from PathPlanning.AStar import A_Star_searching_from_two_side as m +except ImportError: + raise + + +class Test(TestCase): + + def test1(self): + m.show_animation = False + m.main(800) + + def test2(self): + m.show_animation = False + m.main(5000) # increase obstacle number, block path + + +if __name__ == '__main__': + test = Test() + test.test1() + test.test2() From 5462ed7e6644341446c1efe394b01401f5f4a739 Mon Sep 17 00:00:00 2001 From: Sarim Mehdi Date: Mon, 21 Sep 2020 06:32:38 +0200 Subject: [PATCH 309/940] Added variants of A* (#395) * Add files via upload * Add files via upload * Update test_a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update test_a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update test_a_star_variants.py * Add files via upload * Delete test_a_star_variants.py * Update test_a_star_variants_iterative_deepening.py * Update test_a_star_variants_beam_search.py * Update test_a_star_variants_dynamic_weighting.py * Update test_a_star_variants_jump_point.py * Update test_a_star_variants_theta_star.py * Update test_a_star_variants_beam_search.py * Update test_a_star_variants_beam_search.py * Update test_a_star_variants_dynamic_weighting.py * Update test_a_star_variants_iterative_deepening.py * Update test_a_star_variants_jump_point.py * Update test_a_star_variants_theta_star.py * Update test_a_star_variants_beam_search.py * Update test_a_star_variants_dynamic_weighting.py * Update test_a_star_variants_iterative_deepening.py * Update test_a_star_variants_jump_point.py * Update test_a_star_variants_theta_star.py * Update a_star_variants.py * Add files via upload * Add files via upload * Delete test_a_star_variants_beam_search.py * Delete test_a_star_variants_dynamic_weighting.py * Delete test_a_star_variants_iterative_deepening.py * Delete test_a_star_variants_jump_point.py * Delete test_a_star_variants_theta_star.py * Added requested changes * Added requested changes --- PathPlanning/AStar/a_star_variants.py | 462 ++++++++++++++++++++++++++ tests/test_a_star_variants.py | 47 +++ 2 files changed, 509 insertions(+) create mode 100644 PathPlanning/AStar/a_star_variants.py create mode 100644 tests/test_a_star_variants.py diff --git a/PathPlanning/AStar/a_star_variants.py b/PathPlanning/AStar/a_star_variants.py new file mode 100644 index 0000000000..cbf5395fd2 --- /dev/null +++ b/PathPlanning/AStar/a_star_variants.py @@ -0,0 +1,462 @@ +""" +astar variants +author: Sarim Mehdi(muhammadsarim.mehdi@studio.unibo.it) +Source: http://theory.stanford.edu/~amitp/GameProgramming/Variations.html +""" + +import numpy as np +import matplotlib.pyplot as plt + +show_animation = False +use_beam_search = False +use_iterative_deepening = False +use_dynamic_weighting = False +use_theta_star = False +use_jump_point = False + +beam_capacity = 30 +max_theta = 5 +only_corners = False +max_corner = 5 +w, epsilon, upper_bound_depth = 1, 4, 500 + + +def draw_horizontal_line(start_x, start_y, length, o_x, o_y, o_dict): + for i in range(start_x, start_x + length): + for j in range(start_y, start_y + 2): + o_x.append(i) + o_y.append(j) + o_dict[(i, j)] = True + + +def draw_vertical_line(start_x, start_y, length, o_x, o_y, o_dict): + for i in range(start_x, start_x + 2): + for j in range(start_y, start_y + length): + o_x.append(i) + o_y.append(j) + o_dict[(i, j)] = True + + +def in_line_of_sight(obs_grid, x1, y1, x2, y2): + t = 0 + while t <= 0.5: + xt = (1 - t) * x1 + t * x2 + yt = (1 - t) * y1 + t * y2 + if obs_grid[(int(xt), int(yt))]: + return False, None + xt = (1 - t) * x2 + t * x1 + yt = (1 - t) * y2 + t * y1 + if obs_grid[(int(xt), int(yt))]: + return False, None + t += 0.001 + dist = np.linalg.norm(np.array([x1, y1] - np.array([x2, y2]))) + return True, dist + + +def key_points(o_dict): + offsets1 = [(1, 0), (0, 1), (-1, 0), (1, 0)] + offsets2 = [(1, 1), (-1, 1), (-1, -1), (1, -1)] + offsets3 = [(0, 1), (-1, 0), (0, -1), (0, -1)] + c_list = [] + for grid_point, obs_status in o_dict.items(): + if obs_status: + continue + empty_space = True + x, y = grid_point + for i in [-1, 0, 1]: + for j in [-1, 0, 1]: + if (x + i, y + j) not in o_dict.keys(): + continue + if o_dict[(x + i, y + j)]: + empty_space = False + break + if empty_space: + continue + for offset1, offset2, offset3 in zip(offsets1, offsets2, offsets3): + i1, j1 = offset1 + i2, j2 = offset2 + i3, j3 = offset3 + if ((x + i1, y + j1) not in o_dict.keys()) or \ + ((x + i2, y + j2) not in o_dict.keys()) or \ + ((x + i3, y + j3) not in o_dict.keys()): + continue + obs_count = 0 + if o_dict[(x + i1, y + j1)]: + obs_count += 1 + if o_dict[(x + i2, y + j2)]: + obs_count += 1 + if o_dict[(x + i3, y + j3)]: + obs_count += 1 + if obs_count == 3 or obs_count == 1: + c_list.append((x, y)) + plt.plot(x, y, ".y") + break + if only_corners: + return c_list + + e_list = [] + for corner in c_list: + x1, y1 = corner + for other_corner in c_list: + x2, y2 = other_corner + if x1 == x2 and y1 == y2: + continue + reachable, _ = in_line_of_sight(o_dict, x1, y1, x2, y2) + if not reachable: + continue + x_m, y_m = int((x1 + x2) / 2), int((y1 + y2) / 2) + e_list.append((x_m, y_m)) + if show_animation: + plt.plot(x_m, y_m, ".y") + return c_list + e_list + + +class SearchAlgo: + def __init__(self, obs_grid, goal_x, goal_y, start_x, start_y, + limit_x, limit_y, corner_list=None): + self.start_pt = [start_x, start_y] + self.goal_pt = [goal_x, goal_y] + self.obs_grid = obs_grid + g_cost, h_cost = 0, self.get_hval(start_x, start_y, goal_x, goal_y) + f_cost = g_cost + h_cost + self.all_nodes, self.open_set = {}, [] + + if use_jump_point: + for corner in corner_list: + i, j = corner + h_c = self.get_hval(i, j, goal_x, goal_y) + self.all_nodes[(i, j)] = {'pos': [i, j], 'pred': None, + 'gcost': np.inf, 'hcost': h_c, + 'fcost': np.inf, + 'open': True, 'in_open_list': False} + self.all_nodes[tuple(self.goal_pt)] = \ + {'pos': self.goal_pt, 'pred': None, + 'gcost': np.inf, 'hcost': 0, 'fcost': np.inf, + 'open': True, 'in_open_list': True} + else: + for i in range(limit_x): + for j in range(limit_y): + h_c = self.get_hval(i, j, goal_x, goal_y) + self.all_nodes[(i, j)] = {'pos': [i, j], 'pred': None, + 'gcost': np.inf, 'hcost': h_c, + 'fcost': np.inf, + 'open': True, + 'in_open_list': False} + self.all_nodes[tuple(self.start_pt)] = \ + {'pos': self.start_pt, 'pred': None, + 'gcost': g_cost, 'hcost': h_cost, 'fcost': f_cost, + 'open': True, 'in_open_list': True} + self.open_set.append(self.all_nodes[tuple(self.start_pt)]) + + def get_hval(self, x1, y1, x2, y2): + x, y = x1, y1 + val = 0 + while x != x2 or y != y2: + if x != x2 and y != y2: + val += 14 + else: + val += 10 + x, y = x + np.sign(x2 - x), y + np.sign(y2 - y) + return val + + def get_farthest_point(self, x, y, i, j): + i_temp, j_temp = i, j + counter = 1 + got_goal = False + while not self.obs_grid[(x + i_temp, y + j_temp)] and \ + counter < max_theta: + i_temp += i + j_temp += j + counter += 1 + if [x + i_temp, y + j_temp] == self.goal_pt: + got_goal = True + break + if (x + i_temp, y + j_temp) not in self.obs_grid.keys(): + break + return i_temp - 2*i, j_temp - 2*j, counter, got_goal + + def jump_point(self): + """Jump point: Instead of exploring all empty spaces of the + map, just explore the corners.""" + plt.title('Jump Point') + + goal_found = False + while len(self.open_set) > 0: + self.open_set = sorted(self.open_set, key=lambda x: x['fcost']) + lowest_f = self.open_set[0]['fcost'] + lowest_h = self.open_set[0]['hcost'] + lowest_g = self.open_set[0]['gcost'] + p = 0 + for p_n in self.open_set[1:]: + if p_n['fcost'] == lowest_f and \ + p_n['gcost'] < lowest_g: + lowest_g = p_n['gcost'] + p += 1 + elif p_n['fcost'] == lowest_f and \ + p_n['gcost'] == lowest_g and \ + p_n['hcost'] < lowest_h: + lowest_h = p_n['hcost'] + p += 1 + else: + break + current_node = self.all_nodes[tuple(self.open_set[p]['pos'])] + x1, y1 = current_node['pos'] + + for cand_pt, cand_node in self.all_nodes.items(): + x2, y2 = cand_pt + if x1 == x2 and y1 == y2: + continue + if np.linalg.norm(np.array([x1, y1] - + np.array([x2, y2]))) > max_corner: + continue + reachable, offset = in_line_of_sight(self.obs_grid, x1, + y1, x2, y2) + if not reachable: + continue + + if list(cand_pt) == self.goal_pt: + current_node['open'] = False + self.all_nodes[tuple(cand_pt)]['pred'] = \ + current_node['pos'] + goal_found = True + break + + g_cost = offset + current_node['gcost'] + h_cost = self.all_nodes[cand_pt]['hcost'] + f_cost = g_cost + h_cost + cand_pt = tuple(cand_pt) + if f_cost < self.all_nodes[cand_pt]['fcost']: + self.all_nodes[cand_pt]['pred'] = current_node['pos'] + self.all_nodes[cand_pt]['gcost'] = g_cost + self.all_nodes[cand_pt]['fcost'] = f_cost + if not self.all_nodes[cand_pt]['in_open_list']: + self.open_set.append(self.all_nodes[cand_pt]) + self.all_nodes[cand_pt]['in_open_list'] = True + plt.plot(cand_pt[0], cand_pt[1], "r*") + + if goal_found: + break + plt.pause(0.001) + if goal_found: + current_node = self.all_nodes[tuple(self.goal_pt)] + while goal_found: + if current_node['pred'] is None: + break + x = [current_node['pos'][0], current_node['pred'][0]] + y = [current_node['pos'][1], current_node['pred'][1]] + plt.plot(x, y, "b") + current_node = self.all_nodes[tuple(current_node['pred'])] + plt.pause(0.001) + if goal_found: + break + + current_node['open'] = False + current_node['in_open_list'] = False + plt.plot(current_node['pos'][0], current_node['pos'][1], "g*") + del self.open_set[p] + current_node['fcost'], current_node['hcost'] = np.inf, np.inf + if show_animation: + plt.show() + + def astar(self): + """Beam search: Maintain an open list of just 30 nodes. + If more than 30 nodes, then get rid of ndoes with high + f values. + Iterative deepening: At every iteration, get a cut-off + value for the f cost. This cut-off is minimum of the f + value of all nodes whose f value is higher than the + current cut-off value. Nodes with f value higher than + the current cut off value are not put in the open set. + Dynamic weighting: Multiply heuristic with the following: + (1 + epsilon - (epsilon*d)/N) where d is the current + iteration of loop and N is upper bound on number of + iterations. + Theta star: Same as A star but you don't need to move + one neighbor at a time. In fact, you can look for the + next node as far out as you can as long as there is a + clear line of sight from your current node to that node.""" + if use_beam_search: + plt.title('A* with beam search') + elif use_iterative_deepening: + plt.title('A* with iterative deepening') + elif use_dynamic_weighting: + plt.title('A* with dynamic weighting') + elif use_theta_star: + plt.title('Theta*') + else: + plt.title('A*') + + goal_found = False + curr_f_thresh = np.inf + depth = 0 + no_valid_f = False + while len(self.open_set) > 0: + self.open_set = sorted(self.open_set, key=lambda x: x['fcost']) + lowest_f = self.open_set[0]['fcost'] + lowest_h = self.open_set[0]['hcost'] + lowest_g = self.open_set[0]['gcost'] + p = 0 + for p_n in self.open_set[1:]: + if p_n['fcost'] == lowest_f and \ + p_n['gcost'] < lowest_g: + lowest_g = p_n['gcost'] + p += 1 + elif p_n['fcost'] == lowest_f and \ + p_n['gcost'] == lowest_g and \ + p_n['hcost'] < lowest_h: + lowest_h = p_n['hcost'] + p += 1 + else: + break + current_node = self.all_nodes[tuple(self.open_set[p]['pos'])] + + while len(self.open_set) > beam_capacity and use_beam_search: + del self.open_set[-1] + + f_cost_list = [] + if use_dynamic_weighting: + w = (1 + epsilon - epsilon*depth/upper_bound_depth) + for i in range(-1, 2): + for j in range(-1, 2): + x, y = current_node['pos'] + if (i == 0 and j == 0) or \ + ((x + i, y + j) not in self.obs_grid.keys()): + continue + if (i, j) in [(1, 0), (0, 1), (-1, 0), (0, -1)]: + offset = 10 + else: + offset = 14 + if use_theta_star: + new_i, new_j, counter, goal_found = \ + self.get_farthest_point(x, y, i, j) + offset = offset * counter + cand_pt = [current_node['pos'][0] + new_i, + current_node['pos'][1] + new_j] + else: + cand_pt = [current_node['pos'][0] + i, + current_node['pos'][1] + j] + + if use_theta_star and goal_found: + current_node['open'] = False + cand_pt = self.goal_pt + self.all_nodes[tuple(cand_pt)]['pred'] = \ + current_node['pos'] + break + + if cand_pt == self.goal_pt: + current_node['open'] = False + self.all_nodes[tuple(cand_pt)]['pred'] = \ + current_node['pos'] + goal_found = True + break + + cand_pt = tuple(cand_pt) + if not self.obs_grid[tuple(cand_pt)] and \ + self.all_nodes[cand_pt]['open']: + g_cost = offset + current_node['gcost'] + h_cost = self.all_nodes[cand_pt]['hcost'] + if use_dynamic_weighting: + h_cost = h_cost * w + f_cost = g_cost + h_cost + if f_cost < self.all_nodes[cand_pt]['fcost'] and \ + f_cost <= curr_f_thresh: + f_cost_list.append(f_cost) + self.all_nodes[cand_pt]['pred'] = \ + current_node['pos'] + self.all_nodes[cand_pt]['gcost'] = g_cost + self.all_nodes[cand_pt]['fcost'] = f_cost + if not self.all_nodes[cand_pt]['in_open_list']: + self.open_set.append(self.all_nodes[cand_pt]) + self.all_nodes[cand_pt]['in_open_list'] = True + plt.plot(cand_pt[0], cand_pt[1], "r*") + if curr_f_thresh < f_cost < \ + self.all_nodes[cand_pt]['fcost']: + no_valid_f = True + if goal_found: + break + plt.pause(0.001) + if goal_found: + current_node = self.all_nodes[tuple(self.goal_pt)] + while goal_found: + if current_node['pred'] is None: + break + if use_theta_star or use_jump_point: + x, y = [current_node['pos'][0], current_node['pred'][0]], \ + [current_node['pos'][1], current_node['pred'][1]] + plt.plot(x, y, "b") + else: + plt.plot(current_node['pred'][0], + current_node['pred'][1], "b*") + current_node = self.all_nodes[tuple(current_node['pred'])] + plt.pause(0.001) + if goal_found: + break + + if use_iterative_deepening and f_cost_list: + curr_f_thresh = min(f_cost_list) + if use_iterative_deepening and not f_cost_list: + curr_f_thresh = np.inf + if use_iterative_deepening and not f_cost_list and no_valid_f: + current_node['fcost'], current_node['hcost'] = np.inf, np.inf + continue + + current_node['open'] = False + current_node['in_open_list'] = False + plt.plot(current_node['pos'][0], current_node['pos'][1], "g*") + del self.open_set[p] + current_node['fcost'], current_node['hcost'] = np.inf, np.inf + depth += 1 + if show_animation: + plt.show() + + +def main(): + # set obstacle positions + obs_dict = {} + for i in range(51): + for j in range(51): + obs_dict[(i, j)] = False + o_x, o_y = [], [] + + s_x = 5.0 + s_y = 5.0 + g_x = 35.0 + g_y = 45.0 + + # draw outer border of maze + draw_vertical_line(0, 0, 50, o_x, o_y, obs_dict) + draw_vertical_line(48, 0, 50, o_x, o_y, obs_dict) + draw_horizontal_line(0, 0, 50, o_x, o_y, obs_dict) + draw_horizontal_line(0, 48, 50, o_x, o_y, obs_dict) + + # draw inner walls + all_x = [10, 10, 10, 15, 20, 20, 30, 30, 35, 30, 40, 45] + all_y = [10, 30, 45, 20, 5, 40, 10, 40, 5, 40, 10, 25] + all_len = [10, 10, 5, 10, 10, 5, 20, 10, 25, 10, 35, 15] + for x, y, l in zip(all_x, all_y, all_len): + draw_vertical_line(x, y, l, o_x, o_y, obs_dict) + + all_x[:], all_y[:], all_len[:] = [], [], [] + all_x = [35, 40, 15, 10, 45, 20, 10, 15, 25, 45, 10, 30, 10, 40] + all_y = [5, 10, 15, 20, 20, 25, 30, 35, 35, 35, 40, 40, 45, 45] + all_len = [10, 5, 10, 10, 5, 5, 10, 5, 10, 5, 10, 5, 5, 5] + for x, y, l in zip(all_x, all_y, all_len): + draw_horizontal_line(x, y, l, o_x, o_y, obs_dict) + + plt.plot(o_x, o_y, ".k") + plt.plot(s_x, s_y, "og") + plt.plot(g_x, g_y, "xb") + plt.grid(True) + + if use_jump_point: + keypoint_list = key_points(obs_dict) + search_obj = SearchAlgo(obs_dict, g_x, g_y, s_x, s_y, 101, 101, + keypoint_list) + search_obj.jump_point() + else: + search_obj = SearchAlgo(obs_dict, g_x, g_y, s_x, s_y, 101, 101) + search_obj.astar() + + +if __name__ == '__main__': + main() diff --git a/tests/test_a_star_variants.py b/tests/test_a_star_variants.py new file mode 100644 index 0000000000..53efeddd20 --- /dev/null +++ b/tests/test_a_star_variants.py @@ -0,0 +1,47 @@ +import PathPlanning.AStar.a_star_variants as astar +from unittest import TestCase +import sys +import os +sys.path.append(os.path.dirname(__file__) + "/../") + + +class Test(TestCase): + + def test(self): + # A* with beam search + astar.show_animation = False + astar.use_beam_search = True + astar.main() + self.reset_all() + + # A* with iterative deepening + astar.use_iterative_deepening = True + astar.main() + self.reset_all() + + # A* with dynamic weighting + astar.use_dynamic_weighting = True + astar.main() + self.reset_all() + + # theta* + astar.use_theta_star = True + astar.main() + self.reset_all() + + # A* with jump point + astar.use_jump_point = True + astar.main() + self.reset_all() + + def reset_all(self): + astar.use_beam_search = False + astar.use_iterative_deepening = False + astar.use_dynamic_weighting = False + astar.use_theta_star = False + astar.use_jump_point = False + + +if __name__ == '__main__': # pragma: no cover + test = Test() + test.test() From d7cc364b2f8d83f614a316cb5916e9f0b17dc10e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 22 Sep 2020 07:13:16 +0900 Subject: [PATCH 310/940] Bump matplotlib from 3.3.1 to 3.3.2 (#406) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.3.1 to 3.3.2. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.3.1...v3.3.2) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 094def17af..58511e90f4 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.2 scipy == 1.5.2 pandas == 1.1.2 -matplotlib == 3.3.1 +matplotlib == 3.3.2 cvxpy == 1.1.5 From 468be047aa5975265cbdc5b89740bc6b61079a9e Mon Sep 17 00:00:00 2001 From: ajwahab <1449672+ajwahab@users.noreply.github.com> Date: Sun, 27 Sep 2020 00:10:46 -0400 Subject: [PATCH 311/940] robustified 2 joint arm example (#402) two joint arm point control example will no longer fail if target point is out of reach --- .../two_joint_arm_to_point_control.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py index 75e7cf301f..85ed612360 100644 --- a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py +++ b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py @@ -37,8 +37,11 @@ def two_joint_arm(GOAL_TH=0.0, theta1=0.0, theta2=0.0): """ while True: try: - theta2_goal = np.arccos( - (x**2 + y**2 - l1**2 - l2**2) / (2 * l1 * l2)) + if np.sqrt(x**2 + y**2) > (l1 + l2): + theta2_goal = 0 + else: + theta2_goal = np.arccos( + (x**2 + y**2 - l1**2 - l2**2) / (2 * l1 * l2)) theta1_goal = np.math.atan2(y, x) - np.math.atan2(l2 * np.sin(theta2_goal), (l1 + l2 * np.cos(theta2_goal))) From 60e9e8f39b528d664a3d641f916549a2545555d4 Mon Sep 17 00:00:00 2001 From: Sarim Mehdi Date: Tue, 29 Sep 2020 08:32:21 +0200 Subject: [PATCH 312/940] Implemented Flowfield Pathfinding (#408) * Add files via upload * Add files via upload * Update test_a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update test_a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update a_star_variants.py * Update test_a_star_variants.py * Add files via upload * Delete test_a_star_variants.py * Update test_a_star_variants_iterative_deepening.py * Update test_a_star_variants_beam_search.py * Update test_a_star_variants_dynamic_weighting.py * Update test_a_star_variants_jump_point.py * Update test_a_star_variants_theta_star.py * Update test_a_star_variants_beam_search.py * Update test_a_star_variants_beam_search.py * Update test_a_star_variants_dynamic_weighting.py * Update test_a_star_variants_iterative_deepening.py * Update test_a_star_variants_jump_point.py * Update test_a_star_variants_theta_star.py * Update test_a_star_variants_beam_search.py * Update test_a_star_variants_dynamic_weighting.py * Update test_a_star_variants_iterative_deepening.py * Update test_a_star_variants_jump_point.py * Update test_a_star_variants_theta_star.py * Update a_star_variants.py * Add files via upload * Add files via upload * Delete test_a_star_variants_beam_search.py * Delete test_a_star_variants_dynamic_weighting.py * Delete test_a_star_variants_iterative_deepening.py * Delete test_a_star_variants_jump_point.py * Delete test_a_star_variants_theta_star.py * Added requested changes * Added requested changes * Added flowfield * Added requested changes * Update flowfield.py --- PathPlanning/FlowField/flowfield.py | 223 ++++++++++++++++++++++++++++ tests/test_flow_field.py | 17 +++ 2 files changed, 240 insertions(+) create mode 100644 PathPlanning/FlowField/flowfield.py create mode 100644 tests/test_flow_field.py diff --git a/PathPlanning/FlowField/flowfield.py b/PathPlanning/FlowField/flowfield.py new file mode 100644 index 0000000000..f222e8ecf2 --- /dev/null +++ b/PathPlanning/FlowField/flowfield.py @@ -0,0 +1,223 @@ +""" +flowfield pathfinding +author: Sarim Mehdi (muhammadsarim.mehdi@studio.unibo.it) +Source: https://leifnode.com/2013/12/flow-field-pathfinding/ +""" + +import numpy as np +import matplotlib.pyplot as plt + +show_animation = True + + +def draw_horizontal_line(start_x, start_y, length, o_x, o_y, o_dict, path): + for i in range(start_x, start_x + length): + for j in range(start_y, start_y + 2): + o_x.append(i) + o_y.append(j) + o_dict[(i, j)] = path + + +def draw_vertical_line(start_x, start_y, length, o_x, o_y, o_dict, path): + for i in range(start_x, start_x + 2): + for j in range(start_y, start_y + length): + o_x.append(i) + o_y.append(j) + o_dict[(i, j)] = path + + +class FlowField: + def __init__(self, obs_grid, goal_x, goal_y, start_x, start_y, + limit_x, limit_y): + self.start_pt = [start_x, start_y] + self.goal_pt = [goal_x, goal_y] + self.obs_grid = obs_grid + self.limit_x, self.limit_y = limit_x, limit_y + self.cost_field = {} + self.integration_field = {} + self.vector_field = {} + + def find_path(self): + self.create_cost_field() + self.create_integration_field() + self.assign_vectors() + self.follow_vectors() + + def create_cost_field(self): + """Assign cost to each grid which defines the energy + it would take to get there.""" + for i in range(self.limit_x): + for j in range(self.limit_y): + if self.obs_grid[(i, j)] == 'free': + self.cost_field[(i, j)] = 1 + elif self.obs_grid[(i, j)] == 'medium': + self.cost_field[(i, j)] = 7 + elif self.obs_grid[(i, j)] == 'hard': + self.cost_field[(i, j)] = 20 + elif self.obs_grid[(i, j)] == 'obs': + continue + + if [i, j] == self.goal_pt: + self.cost_field[(i, j)] = 0 + + def create_integration_field(self): + """Start from the goal node and calculate the value + of the integration field at each node. Start by + assigning a value of infinity to every node except + the goal node which is assigned a value of 0. Put the + goal node in the open list and then get its neighbors + (must not be obstacles). For each neighbor, the new + cost is equal to the cost of the current node in the + integration field (in the beginning, this will simply + be the goal node) + the cost of the neighbor in the + cost field + the extra cost (optional). The new cost + is only assigned if it is less than the previously + assigned cost of the node in the integration field and, + when that happens, the neighbor is put on the open list. + This process continues until the open list is empty.""" + for i in range(self.limit_x): + for j in range(self.limit_y): + if self.obs_grid[(i, j)] == 'obs': + continue + self.integration_field[(i, j)] = np.inf + if [i, j] == self.goal_pt: + self.integration_field[(i, j)] = 0 + + open_list = [(self.goal_pt, 0)] + while open_list: + curr_pos, curr_cost = open_list[0] + curr_x, curr_y = curr_pos + for i in range(-1, 2): + for j in range(-1, 2): + x, y = curr_x + i, curr_y + j + if self.obs_grid[(x, y)] == 'obs': + continue + if (i, j) in [(1, 0), (0, 1), (-1, 0), (0, -1)]: + e_cost = 10 + else: + e_cost = 14 + neighbor_energy = self.cost_field[(x, y)] + neighbor_old_cost = self.integration_field[(x, y)] + neighbor_new_cost = curr_cost + neighbor_energy + e_cost + if neighbor_new_cost < neighbor_old_cost: + self.integration_field[(x, y)] = neighbor_new_cost + open_list.append(([x, y], neighbor_new_cost)) + del open_list[0] + + def assign_vectors(self): + """For each node, assign a vector from itself to the node with + the lowest cost in the integration field. An agent will simply + follow this vector field to the goal""" + for i in range(self.limit_x): + for j in range(self.limit_y): + if self.obs_grid[(i, j)] == 'obs': + continue + if [i, j] == self.goal_pt: + self.vector_field[(i, j)] = (None, None) + continue + offset_list = [(i + a, j + b) + for a in range(-1, 2) + for b in range(-1, 2)] + neighbor_list = [{'loc': pt, + 'cost': self.integration_field[pt]} + for pt in offset_list + if self.obs_grid[pt] != 'obs'] + neighbor_list = sorted(neighbor_list, key=lambda x: x['cost']) + best_neighbor = neighbor_list[0]['loc'] + self.vector_field[(i, j)] = best_neighbor + + def follow_vectors(self): + curr_x, curr_y = self.start_pt + while curr_x is not None and curr_y is not None: + plt.plot(curr_x, curr_y, "b*") + curr_x, curr_y = self.vector_field[(curr_x, curr_y)] + plt.pause(0.001) + if show_animation: + plt.show() + + +def main(): + # set obstacle positions + obs_dict = {} + for i in range(51): + for j in range(51): + obs_dict[(i, j)] = 'free' + o_x, o_y, m_x, m_y, h_x, h_y = [], [], [], [], [], [] + + s_x = 5.0 + s_y = 5.0 + g_x = 35.0 + g_y = 45.0 + + # draw outer border of maze + draw_vertical_line(0, 0, 50, o_x, o_y, obs_dict, 'obs') + draw_vertical_line(48, 0, 50, o_x, o_y, obs_dict, 'obs') + draw_horizontal_line(0, 0, 50, o_x, o_y, obs_dict, 'obs') + draw_horizontal_line(0, 48, 50, o_x, o_y, obs_dict, 'obs') + + # draw inner walls + all_x = [10, 10, 10, 15, 20, 20, 30, 30, 35, 30, 40, 45] + all_y = [10, 30, 45, 20, 5, 40, 10, 40, 5, 40, 10, 25] + all_len = [10, 10, 5, 10, 10, 5, 20, 10, 25, 10, 35, 15] + for x, y, l in zip(all_x, all_y, all_len): + draw_vertical_line(x, y, l, o_x, o_y, obs_dict, 'obs') + + all_x[:], all_y[:], all_len[:] = [], [], [] + all_x = [35, 40, 15, 10, 45, 20, 10, 15, 25, 45, 10, 30, 10, 40] + all_y = [5, 10, 15, 20, 20, 25, 30, 35, 35, 35, 40, 40, 45, 45] + all_len = [10, 5, 10, 10, 5, 5, 10, 5, 10, 5, 10, 5, 5, 5] + for x, y, l in zip(all_x, all_y, all_len): + draw_horizontal_line(x, y, l, o_x, o_y, obs_dict, 'obs') + + # Some points are assigned a slightly higher energy value in the cost + # field. For example, if an agent wishes to go to a point, it might + # encounter different kind of terrain like grass and dirt. Grass is + # assigned medium difficulty of passage (color coded as green on the + # map here). Dirt is assigned hard difficulty of passage (color coded + # as brown here). Hence, this algorithm will take into account how + # difficult it is to go through certain areas of a map when deciding + # the shortest path. + + # draw paths that have medium difficulty (in terms of going through them) + all_x[:], all_y[:], all_len[:] = [], [], [] + all_x = [10, 45] + all_y = [22, 20] + all_len = [8, 5] + for x, y, l in zip(all_x, all_y, all_len): + draw_vertical_line(x, y, l, m_x, m_y, obs_dict, 'medium') + + all_x[:], all_y[:], all_len[:] = [], [], [] + all_x = [20, 30, 42] + [47] * 5 + all_y = [35, 30, 38] + [37 + i for i in range(2)] + all_len = [5, 7, 3] + [1] * 3 + for x, y, l in zip(all_x, all_y, all_len): + draw_horizontal_line(x, y, l, m_x, m_y, obs_dict, 'medium') + + # draw paths that have hard difficulty (in terms of going through them) + all_x[:], all_y[:], all_len[:] = [], [], [] + all_x = [15, 20, 35] + all_y = [45, 20, 35] + all_len = [3, 5, 7] + for x, y, l in zip(all_x, all_y, all_len): + draw_vertical_line(x, y, l, h_x, h_y, obs_dict, 'hard') + + all_x[:], all_y[:], all_len[:] = [], [], [] + all_x = [30] + [47] * 5 + all_y = [10] + [37 + i for i in range(2)] + all_len = [5] + [1] * 3 + for x, y, l in zip(all_x, all_y, all_len): + draw_horizontal_line(x, y, l, h_x, h_y, obs_dict, 'hard') + + plt.plot(o_x, o_y, "sr") + plt.plot(m_x, m_y, "sg") + plt.plot(h_x, h_y, "sy") + plt.plot(s_x, s_y, "og") + plt.plot(g_x, g_y, "o") + plt.grid(True) + + flow_obj = FlowField(obs_dict, g_x, g_y, s_x, s_y, 50, 50) + flow_obj.find_path() + + +if __name__ == '__main__': + main() diff --git a/tests/test_flow_field.py b/tests/test_flow_field.py new file mode 100644 index 0000000000..bf8fe6b802 --- /dev/null +++ b/tests/test_flow_field.py @@ -0,0 +1,17 @@ +import PathPlanning.FlowField.flowfield as flowfield +from unittest import TestCase +import sys +import os +sys.path.append(os.path.dirname(__file__) + "/../") + + +class Test(TestCase): + + def test(self): + flowfield.show_animation = False + flowfield.main() + + +if __name__ == '__main__': # pragma: no cover + test = Test() + test.test() From 2b316502e336de102888cb62cd0ae39769b191b3 Mon Sep 17 00:00:00 2001 From: Rafael Rojas Date: Thu, 1 Oct 2020 13:15:52 +0200 Subject: [PATCH 313/940] Bug RRT* fix, issues #382 and #383 (#401) --- PathPlanning/RRT/rrt.py | 55 +++++++------ PathPlanning/RRTStar/rrt_star.py | 132 +++++++++++++++++++++++-------- 2 files changed, 131 insertions(+), 56 deletions(-) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 4acea0c10e..834fb24e39 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -32,8 +32,15 @@ def __init__(self, x, y): self.path_y = [] self.parent = None - def __init__(self, start, goal, obstacle_list, rand_area, - expand_dis=3.0, path_resolution=0.5, goal_sample_rate=5, max_iter=500): + def __init__(self, + start, + goal, + obstacle_list, + rand_area, + expand_dis=3.0, + path_resolution=0.5, + goal_sample_rate=5, + max_iter=500): """ Setting Parameter @@ -75,8 +82,10 @@ def planning(self, animation=True): if animation and i % 5 == 0: self.draw_graph(rnd_node) - if self.calc_dist_to_goal(self.node_list[-1].x, self.node_list[-1].y) <= self.expand_dis: - final_node = self.steer(self.node_list[-1], self.end, self.expand_dis) + if self.calc_dist_to_goal(self.node_list[-1].x, + self.node_list[-1].y) <= self.expand_dis: + final_node = self.steer(self.node_list[-1], self.end, + self.expand_dis) if self.check_collision(final_node, self.obstacle_list): return self.generate_final_course(len(self.node_list) - 1) @@ -108,6 +117,8 @@ def steer(self, from_node, to_node, extend_length=float("inf")): if d <= self.path_resolution: new_node.path_x.append(to_node.x) new_node.path_y.append(to_node.y) + new_node.x = to_node.x + new_node.y = to_node.y new_node.parent = from_node @@ -130,8 +141,9 @@ def calc_dist_to_goal(self, x, y): def get_random_node(self): if random.randint(0, 100) > self.goal_sample_rate: - rnd = self.Node(random.uniform(self.min_rand, self.max_rand), - random.uniform(self.min_rand, self.max_rand)) + rnd = self.Node( + random.uniform(self.min_rand, self.max_rand), + random.uniform(self.min_rand, self.max_rand)) else: # goal point sampling rnd = self.Node(self.end.x, self.end.y) return rnd @@ -139,8 +151,9 @@ def get_random_node(self): def draw_graph(self, rnd=None): plt.clf() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") for node in self.node_list: @@ -167,8 +180,8 @@ def plot_circle(x, y, size, color="-b"): # pragma: no cover @staticmethod def get_nearest_node_index(node_list, rnd_node): - dlist = [(node.x - rnd_node.x) ** 2 + (node.y - rnd_node.y) - ** 2 for node in node_list] + dlist = [(node.x - rnd_node.x)**2 + (node.y - rnd_node.y)**2 + for node in node_list] minind = dlist.index(min(dlist)) return minind @@ -184,7 +197,7 @@ def check_collision(node, obstacleList): dy_list = [oy - y for y in node.path_y] d_list = [dx * dx + dy * dy for (dx, dy) in zip(dx_list, dy_list)] - if min(d_list) <= size ** 2: + if min(d_list) <= size**2: return False # collision return True # safe @@ -202,20 +215,14 @@ def main(gx=6.0, gy=10.0): print("start " + __file__) # ====Search Path with RRT==== - obstacleList = [ - (5, 5, 1), - (3, 6, 2), - (3, 8, 2), - (3, 10, 2), - (7, 5, 2), - (9, 5, 2), - (8, 10, 1) - ] # [x, y, radius] + obstacleList = [(5, 5, 1), (3, 6, 2), (3, 8, 2), (3, 10, 2), (7, 5, 2), + (9, 5, 2), (8, 10, 1)] # [x, y, radius] # Set Initial parameters - rrt = RRT(start=[0, 0], - goal=[gx, gy], - rand_area=[-2, 15], - obstacle_list=obstacleList) + rrt = RRT( + start=[0, 0], + goal=[gx, gy], + rand_area=[-2, 15], + obstacle_list=obstacleList) path = rrt.planning(animation=show_animation) if path is None: diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index 10ad93a6ba..bef0086095 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -12,8 +12,7 @@ import matplotlib.pyplot as plt -sys.path.append(os.path.dirname(os.path.abspath(__file__)) + - "/../RRT/") +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../RRT/") try: from rrt import RRT @@ -33,15 +32,17 @@ def __init__(self, x, y): super().__init__(x, y) self.cost = 0.0 - def __init__(self, start, goal, obstacle_list, rand_area, + def __init__(self, + start, + goal, + obstacle_list, + rand_area, expand_dis=30.0, path_resolution=1.0, goal_sample_rate=20, max_iter=300, - connect_circle_dist=50.0 - ): - super().__init__(start, goal, obstacle_list, - rand_area, expand_dis, path_resolution, goal_sample_rate, max_iter) + connect_circle_dist=50.0, + search_until_max_iter=False): """ Setting Parameter @@ -51,15 +52,17 @@ def __init__(self, start, goal, obstacle_list, rand_area, randArea:Random Sampling Area [min,max] """ + super().__init__(start, goal, obstacle_list, rand_area, expand_dis, + path_resolution, goal_sample_rate, max_iter) self.connect_circle_dist = connect_circle_dist self.goal_node = self.Node(goal[0], goal[1]) + self.search_until_max_iter = search_until_max_iter - def planning(self, animation=True, search_until_max_iter=True): + def planning(self, animation=True): """ rrt star path planning - animation: flag for animation on or off - search_until_max_iter: search until max iteration for path improving or not + animation: flag for animation on or off . """ self.node_list = [self.start] @@ -67,19 +70,28 @@ def planning(self, animation=True, search_until_max_iter=True): print("Iter:", i, ", number of nodes:", len(self.node_list)) rnd = self.get_random_node() nearest_ind = self.get_nearest_node_index(self.node_list, rnd) - new_node = self.steer(self.node_list[nearest_ind], rnd, self.expand_dis) + new_node = self.steer(self.node_list[nearest_ind], rnd, + self.expand_dis) + near_node = self.node_list[nearest_ind] + new_node.cost = near_node.cost + \ + math.hypot(new_node.x-near_node.x, + new_node.y-near_node.y) if self.check_collision(new_node, self.obstacle_list): near_inds = self.find_near_nodes(new_node) - new_node = self.choose_parent(new_node, near_inds) - if new_node: + node_with_updated_parent = self.choose_parent( + new_node, near_inds) + if node_with_updated_parent: + self.rewire(node_with_updated_parent, near_inds) + self.node_list.append(node_with_updated_parent) + else: self.node_list.append(new_node) - self.rewire(new_node, near_inds) - if animation and i % 5 == 0: + if animation: self.draw_graph(rnd) - if (not search_until_max_iter) and new_node: # check reaching the goal + if ((not self.search_until_max_iter) + and new_node): # if reaches goal last_index = self.search_best_goal_node() if last_index is not None: return self.generate_final_course(last_index) @@ -93,6 +105,21 @@ def planning(self, animation=True, search_until_max_iter=True): return None def choose_parent(self, new_node, near_inds): + """ + Computes the cheapest point to new_node contained in the list + near_inds and set such a node as the parent of new_node. + Arguments: + -------- + new_node, Node + randomly generated node with a path from its neared point + There are not coalitions between this node and th tree. + near_inds: list + Indices of indices of the nodes what are near to new_node + + Returns. + ------ + Node, a copy of new_node + """ if not near_inds: return None @@ -113,14 +140,18 @@ def choose_parent(self, new_node, near_inds): min_ind = near_inds[costs.index(min_cost)] new_node = self.steer(self.node_list[min_ind], new_node) - new_node.parent = self.node_list[min_ind] new_node.cost = min_cost return new_node def search_best_goal_node(self): - dist_to_goal_list = [self.calc_dist_to_goal(n.x, n.y) for n in self.node_list] - goal_inds = [dist_to_goal_list.index(i) for i in dist_to_goal_list if i <= self.expand_dis] + dist_to_goal_list = [ + self.calc_dist_to_goal(n.x, n.y) for n in self.node_list + ] + goal_inds = [ + dist_to_goal_list.index(i) for i in dist_to_goal_list + if i <= self.expand_dis + ] safe_goal_inds = [] for goal_ind in goal_inds: @@ -139,17 +170,48 @@ def search_best_goal_node(self): return None def find_near_nodes(self, new_node): + """ + 1) defines a ball centered on new_node + 2) Returns all nodes of the three that are inside this ball + Arguments: + --------- + new_node: Node + new randomly generated node, without collisions between + its nearest node + Returns: + ------- + list + List with the indices of the nodes inside the ball of + radius r + """ nnode = len(self.node_list) + 1 r = self.connect_circle_dist * math.sqrt((math.log(nnode) / nnode)) - # if expand_dist exists, search vertices in a range no more than expand_dist - if hasattr(self, 'expand_dis'): + # if expand_dist exists, search vertices in a range no more than + # expand_dist + if hasattr(self, 'expand_dis'): r = min(r, self.expand_dis) - dist_list = [(node.x - new_node.x) ** 2 + - (node.y - new_node.y) ** 2 for node in self.node_list] - near_inds = [dist_list.index(i) for i in dist_list if i <= r ** 2] + dist_list = [(node.x - new_node.x)**2 + (node.y - new_node.y)**2 + for node in self.node_list] + near_inds = [dist_list.index(i) for i in dist_list if i <= r**2] return near_inds def rewire(self, new_node, near_inds): + """ + For each node in near_inds, this will check if it is cheaper to + arrive to them from new_node. + In such a case, this will re-assign the parent of the nodes in + near_inds to new_node. + Parameters: + ---------- + new_node, Node + Node randomly added which can be joined to the tree + + near_inds, list of uints + A list of indices of the self.new_node which contains + nodes within a circle of a given radius. + Remark: parent is designated in choose_parent. + + """ for i in near_inds: near_node = self.node_list[i] edge_node = self.steer(new_node, near_node) @@ -161,7 +223,12 @@ def rewire(self, new_node, near_inds): improved_cost = near_node.cost > edge_node.cost if no_collision and improved_cost: - self.node_list[i] = edge_node + near_node.x = edge_node.x + near_node.y = edge_node.y + near_node.cost = edge_node.cost + near_node.path_x = edge_node.path_x + near_node.path_y = edge_node.path_y + near_node.parent = edge_node.parent self.propagate_cost_to_leaves(new_node) def calc_new_cost(self, from_node, to_node): @@ -192,10 +259,12 @@ def main(): ] # [x,y,size(radius)] # Set Initial parameters - rrt_star = RRTStar(start=[0, 0], - goal=[6, 10], - rand_area=[-2, 15], - obstacle_list=obstacle_list) + rrt_star = RRTStar( + start=[0, 0], + goal=[6, 10], + rand_area=[-2, 15], + obstacle_list=obstacle_list, + expand_dis=1) path = rrt_star.planning(animation=show_animation) if path is None: @@ -206,10 +275,9 @@ def main(): # Draw final path if show_animation: rrt_star.draw_graph() - plt.plot([x for (x, y) in path], [y for (x, y) in path], '-r') + plt.plot([x for (x, y) in path], [y for (x, y) in path], 'r--') plt.grid(True) - plt.pause(0.01) # Need for Mac - plt.show() + plt.show() if __name__ == '__main__': From 2a5bbdc0be30a9adfa1b074727548f5d0160a873 Mon Sep 17 00:00:00 2001 From: hotsuyuki Date: Thu, 1 Oct 2020 20:21:51 +0900 Subject: [PATCH 314/940] More intuitive way of plot_covariance_ellipse() (#407) * More intuitive way of plot_covariance_ellipse() in EKF and UKF * Add the same changes in UKF as well * Modified rotation matrix to scipy.spatial.transform.Rotation * Modified angle of covariance matrix * Fixed typos --- .../ensemble_kalman_filter/ensemble_kalman_filter.py | 2 +- .../extended_kalman_filter/extended_kalman_filter.py | 6 +++--- Localization/particle_filter/particle_filter.py | 2 +- .../unscented_kalman_filter/unscented_kalman_filter.py | 6 +++--- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py index 1307b1ebd1..8ef2089b01 100644 --- a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py +++ b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py @@ -167,7 +167,7 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] - angle = math.atan2(eig_vec[big_ind, 1], eig_vec[big_ind, 0]) + angle = math.atan2(eig_vec[1, big_ind], eig_vec[0, big_ind]) rot = Rot.from_euler('z', angle).as_matrix()[0:2, 0:2] fx = np.stack([x, y]).T @ rot diff --git a/Localization/extended_kalman_filter/extended_kalman_filter.py b/Localization/extended_kalman_filter/extended_kalman_filter.py index 2d0d86bf77..51e8f22f4d 100644 --- a/Localization/extended_kalman_filter/extended_kalman_filter.py +++ b/Localization/extended_kalman_filter/extended_kalman_filter.py @@ -10,6 +10,7 @@ import matplotlib.pyplot as plt import numpy as np +from scipy.spatial.transform import Rotation as Rot # Covariance for EKF simulation Q = np.diag([ @@ -147,9 +148,8 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover b = math.sqrt(eigval[smallind]) x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] - angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0]) - rot = np.array([[math.cos(angle), math.sin(angle)], - [-math.sin(angle), math.cos(angle)]]) + angle = math.atan2(eigvec[1, bigind], eigvec[0, bigind]) + rot = Rot.from_euler('z', angle).as_matrix()[0:2, 0:2] fx = rot @ (np.array([x, y])) px = np.array(fx[0, :] + xEst[0, 0]).flatten() py = np.array(fx[1, :] + xEst[1, 0]).flatten() diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 89a43ea600..002718f028 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -188,7 +188,7 @@ def plot_covariance_ellipse(x_est, p_est): # pragma: no cover x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] - angle = math.atan2(eig_vec[big_ind, 1], eig_vec[big_ind, 0]) + angle = math.atan2(eig_vec[1, big_ind], eig_vec[0, big_ind]) rot = Rot.from_euler('z', angle).as_matrix()[0:2, 0:2] fx = rot.dot(np.array([[x, y]])) px = np.array(fx[0, :] + x_est[0, 0]).flatten() diff --git a/Localization/unscented_kalman_filter/unscented_kalman_filter.py b/Localization/unscented_kalman_filter/unscented_kalman_filter.py index 7bf279ced0..7f80bccf51 100644 --- a/Localization/unscented_kalman_filter/unscented_kalman_filter.py +++ b/Localization/unscented_kalman_filter/unscented_kalman_filter.py @@ -10,6 +10,7 @@ import matplotlib.pyplot as plt import numpy as np +from scipy.spatial.transform import Rotation as Rot import scipy.linalg # Covariance for UKF simulation @@ -180,9 +181,8 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover b = math.sqrt(eigval[smallind]) x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] - angle = math.atan2(eigvec[bigind, 1], eigvec[bigind, 0]) - rot = np.array([[math.cos(angle), math.sin(angle)], - [-math.sin(angle), math.cos(angle)]]) + angle = math.atan2(eigvec[1, bigind], eigvec[0, bigind]) + rot = Rot.from_euler('z', angle).as_matrix()[0:2, 0:2] fx = rot @ np.array([x, y]) px = np.array(fx[0, :] + xEst[0, 0]).flatten() py = np.array(fx[1, :] + xEst[1, 0]).flatten() From b10bfbbc40988c8d475427d88188b7d261cf9342 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 7 Oct 2020 19:57:58 +0900 Subject: [PATCH 315/940] Bump pandas from 1.1.2 to 1.1.3 (#416) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.1.2 to 1.1.3. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/master/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.1.2...v1.1.3) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 58511e90f4..da40bbae8f 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.2 scipy == 1.5.2 -pandas == 1.1.2 +pandas == 1.1.3 matplotlib == 3.3.2 cvxpy == 1.1.5 From b3ab809890d0d27c6242266ddc05e4fcae7226e8 Mon Sep 17 00:00:00 2001 From: Raghuram Shankar Date: Fri, 9 Oct 2020 16:43:21 +0200 Subject: [PATCH 316/940] Add Cubature Kalman Filter (#410) * cubature kalman filter * Revert "cubature kalman filter" This reverts commit 172772897c3f8407390fb9d57476c15b4f21fa75. * add ckf test * update flags for CI * update flags for CI * update flags for CI * remove comments * remove comments * change postpross * changes requested * remove comments * Changes to comments, remove linear_update * changes to comments * removed comments * change comments * update comments * update comments * update comments * update comments * fix comment --- .../cubature_kalman_filter.py | 246 ++++++++++++++++++ tests/test_cubature_kalman_filter.py | 14 + 2 files changed, 260 insertions(+) create mode 100644 Localization/cubature_kalman_filter/cubature_kalman_filter.py create mode 100644 tests/test_cubature_kalman_filter.py diff --git a/Localization/cubature_kalman_filter/cubature_kalman_filter.py b/Localization/cubature_kalman_filter/cubature_kalman_filter.py new file mode 100644 index 0000000000..0fc4c93760 --- /dev/null +++ b/Localization/cubature_kalman_filter/cubature_kalman_filter.py @@ -0,0 +1,246 @@ +""" +Cubature Kalman filter using Constant Turn Rate and Velocity (CTRV) model +Fuse sensor data from IMU and GPS to obtain accurate position + +https://ieeexplore.ieee.org/document/4982682 + +Author: Raghuram Shankar + +state matrix: 2D x-y position, yaw, velocity and yaw rate +measurement matrix: 2D x-y position, velocity and yaw rate + +dt: Duration of time step +N: Number of time steps +show_final: Flag for showing final result +show_animation: Flag for showing each animation frame +show_ellipse: Flag for showing covariance ellipse +z_noise: Measurement noise +x_0: Prior state estimate matrix +P_0: Prior state estimate covariance matrix +q: Process noise covariance +hx: Measurement model matrix +r: Sensor noise covariance +SP: Sigma Points +W: Weights + +x_est: State estimate +P_est: State estimate covariance +x_true: Ground truth value of state +x_true_cat: Concatenate all ground truth states +x_est_cat: Concatenate all state estimates +z_cat: Concatenate all measurements + +""" + +import math +import matplotlib.pyplot as plt +import numpy as np +from scipy.linalg import sqrtm + + +dt = 0.1 +N = 100 + +show_final = 1 +show_animation = 0 +show_ellipse = 0 + + +z_noise = np.array([[0.1, 0.0, 0.0, 0.0], # x position [m] + [0.0, 0.1, 0.0, 0.0], # y position [m] + [0.0, 0.0, 0.1, 0.0], # velocity [m/s] + [0.0, 0.0, 0.0, 0.1]]) # yaw rate [rad/s] + + +x_0 = np.array([[0.0], # x position [m] + [0.0], # y position [m] + [0.0], # yaw [rad] + [1.0], # velocity [m/s] + [0.1]]) # yaw rate [rad/s] + + +p_0 = np.array([[1e-3, 0.0, 0.0, 0.0, 0.0], + [0.0, 1e-3, 0.0, 0.0, 0.0], + [0.0, 0.0, 1.0, 0.0, 0.0], + [0.0, 0.0, 0.0, 1.0, 0.0], + [0.0, 0.0, 0.0, 0.0, 1.0]]) + + +q = np.array([[1e-11, 0.0, 0.0, 0.0, 0.0], + [0.0, 1e-11, 0.0, 0.0, 0.0], + [0.0, 0.0, np.deg2rad(1e-4), 0.0, 0.0], + [0.0, 0.0, 0.0, 1e-4, 0.0], + [0.0, 0.0, 0.0, 0.0, np.deg2rad(1e-4)]]) + + +hx = np.array([[1.0, 0.0, 0.0, 0.0, 0.0], + [0.0, 1.0, 0.0, 0.0, 0.0], + [0.0, 0.0, 0.0, 1.0, 0.0], + [0.0, 0.0, 0.0, 0.0, 1.0]]) + + +r = np.array([[0.015, 0.0, 0.0, 0.0], + [0.0, 0.010, 0.0, 0.0], + [0.0, 0.0, 0.1, 0.0], + [0.0, 0.0, 0.0, 0.01]])**2 + + +def cubature_kalman_filter(x_est, p_est, z): + x_pred, p_pred = cubature_prediction(x_est, p_est) + x_upd, p_upd = cubature_update(x_pred, p_pred, z) + return x_upd, p_upd + + +def f(x): + """ + Motion Model + References: + http://fusion.isif.org/proceedings/fusion08CD/papers/1569107835.pdf + https://github.com/balzer82/Kalman + """ + x[0] = x[0] + (x[3]/x[4]) * (np.sin(x[4] * dt + x[2]) - np.sin(x[2])) + x[1] = x[1] + (x[3]/x[4]) * (- np.cos(x[4] * dt + x[2]) + np.cos(x[2])) + x[2] = x[2] + x[4] * dt + x[3] = x[3] + x[4] = x[4] + return x + + +def h(x): + """Measurement Model""" + x = hx @ x + return x + + +def sigma(x, p): + """ + Unscented Transform with Cubature Rule + Generate 2n Sigma Points to represent the nonlinear motion + Assign Weights to each Sigma Point, Wi = 1/2n + Cubature Rule - Special Case of Unscented Transform + W0 = 0, no extra tuning parameters, no negative weights + """ + n = np.shape(x)[0] + SP = np.zeros((n, 2*n)) + W = np.zeros((1, 2*n)) + for i in range(n): + SD = sqrtm(p) + SP[:, i] = (x + (math.sqrt(n) * SD[:, i]).reshape((n, 1))).flatten() + SP[:, i+n] = (x - (math.sqrt(n) * SD[:, i]).reshape((n, 1))).flatten() + W[:, i] = 1/(2*n) + W[:, i+n] = W[:, i] + return SP, W + + +def cubature_prediction(x_pred, p_pred): + n = np.shape(x_pred)[0] + [SP, W] = sigma(x_pred, p_pred) + x_pred = np.zeros((n, 1)) + p_pred = q + for i in range(2*n): + x_pred = x_pred + (f(SP[:, i]).reshape((n, 1)) * W[0, i]) + for i in range(2*n): + p_step = (f(SP[:, i]).reshape((n, 1)) - x_pred) + p_pred = p_pred + (p_step @ p_step.T * W[0, i]) + return x_pred, p_pred + + +def cubature_update(x_pred, p_pred, z): + n = np.shape(x_pred)[0] + m = np.shape(z)[0] + [SP, W] = sigma(x_pred, p_pred) + y_k = np.zeros((m, 1)) + P_xy = np.zeros((n, m)) + s = r + for i in range(2*n): + y_k = y_k + (h(SP[:, i]).reshape((m, 1)) * W[0, i]) + for i in range(2*n): + p_step = (h(SP[:, i]).reshape((m, 1)) - y_k) + P_xy = P_xy + ((SP[:, i]).reshape((n, 1)) - + x_pred) @ p_step.T * W[0, i] + s = s + p_step @ p_step.T * W[0, i] + x_pred = x_pred + P_xy @ np.linalg.pinv(s) @ (z - y_k) + p_pred = p_pred - P_xy @ np.linalg.pinv(s) @ P_xy.T + return x_pred, p_pred + + +def generate_measurement(x_true): + gz = hx @ x_true + z = gz + z_noise @ np.random.randn(4, 1) + return z + + +def plot_animation(i, x_true_cat, x_est_cat, z): + if i == 0: + plt.plot(x_true_cat[0], x_true_cat[1], '.r') + plt.plot(x_est_cat[0], x_est_cat[1], '.b') + else: + plt.plot(x_true_cat[0:, 0], x_true_cat[0:, 1], 'r') + plt.plot(x_est_cat[0:, 0], x_est_cat[0:, 1], 'b') + plt.plot(z[0], z[1], '+g') + plt.grid(True) + plt.pause(0.001) + + +def plot_ellipse(x_est, p_est): + phi = np.linspace(0, 2 * math.pi, 100) + p_ellipse = np.array( + [[p_est[0, 0], p_est[0, 1]], [p_est[1, 0], p_est[1, 1]]]) + x0 = 3 * sqrtm(p_ellipse) + xy_1 = np.array([]) + xy_2 = np.array([]) + for i in range(100): + arr = np.array([[math.sin(phi[i])], [math.cos(phi[i])]]) + arr = x0 @ arr + xy_1 = np.hstack([xy_1, arr[0]]) + xy_2 = np.hstack([xy_2, arr[1]]) + plt.plot(xy_1 + x_est[0], xy_2 + x_est[1], 'r') + plt.pause(0.00001) + + +def plot_final(x_true_cat, x_est_cat, z_cat): + fig = plt.figure() + subplot = fig.add_subplot(111) + subplot.plot(x_true_cat[0:, 0], x_true_cat[0:, 1], + 'r', label='True Position') + subplot.plot(x_est_cat[0:, 0], x_est_cat[0:, 1], + 'b', label='Estimated Position') + subplot.plot(z_cat[0:, 0], z_cat[0:, 1], '+g', label='Noisy Measurements') + subplot.set_xlabel('x [m]') + subplot.set_ylabel('y [m]') + subplot.set_title('Cubature Kalman Filter - CTRV Model') + subplot.legend(loc='upper left', shadow=True, fontsize='large') + plt.grid(True) + plt.show() + + +def main(): + print(__file__ + " start!!") + x_est = x_0 + p_est = p_0 + x_true = x_0 + x_true_cat = np.array([x_0[0, 0], x_0[1, 0]]) + x_est_cat = np.array([x_0[0, 0], x_0[1, 0]]) + z_cat = np.array([x_0[0, 0], x_0[1, 0]]) + for i in range(N): + x_true = f(x_true) + z = generate_measurement(x_true) + if i == (N - 1) and show_final == 1: + show_final_flag = 1 + else: + show_final_flag = 0 + if show_animation == 1: + plot_animation(i, x_true_cat, x_est_cat, z) + if show_ellipse == 1: + plot_ellipse(x_est[0:2], p_est) + if show_final_flag == 1: + plot_final(x_true_cat, x_est_cat, z_cat) + x_est, p_est = cubature_kalman_filter(x_est, p_est, z) + x_true_cat = np.vstack((x_true_cat, x_true[0:2].T)) + x_est_cat = np.vstack((x_est_cat, x_est[0:2].T)) + z_cat = np.vstack((z_cat, z[0:2].T)) + print('CKF Over') + + +if __name__ == '__main__': + main() diff --git a/tests/test_cubature_kalman_filter.py b/tests/test_cubature_kalman_filter.py new file mode 100644 index 0000000000..e6ac71a8ee --- /dev/null +++ b/tests/test_cubature_kalman_filter.py @@ -0,0 +1,14 @@ +from unittest import TestCase + +from Localization.cubature_kalman_filter import cubature_kalman_filter as m + +print(__file__) + + +class Test(TestCase): + + def test1(self): + m.show_final = False + m.show_animation = False + m.show_ellipse = False + m.main() From 1b1e649b7d74dc3eda20ac3d63d43f60a3681dcd Mon Sep 17 00:00:00 2001 From: Raghuram Shankar Date: Sat, 10 Oct 2020 03:51:16 +0200 Subject: [PATCH 317/940] fixed TypeError (#414) * fixed TypeError * updated global variables * updated global variables * fix comment * Change try-except to if --- .../two_joint_arm_to_point_control.py | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py index 85ed612360..90fcea1df9 100644 --- a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py +++ b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py @@ -34,9 +34,14 @@ def two_joint_arm(GOAL_TH=0.0, theta1=0.0, theta2=0.0): """ Computes the inverse kinematics for a planar 2DOF arm + When out of bounds, rewrite x and y with last correct values """ + global x, y while True: try: + if x is not None and y is not None: + x_prev = x + y_prev = y if np.sqrt(x**2 + y**2) > (l1 + l2): theta2_goal = 0 else: @@ -54,11 +59,15 @@ def two_joint_arm(GOAL_TH=0.0, theta1=0.0, theta2=0.0): theta2 = theta2 + Kp * ang_diff(theta2_goal, theta2) * dt except ValueError as e: print("Unreachable goal") + except TypeError: + x = x_prev + y = y_prev wrist = plot_arm(theta1, theta2, x, y) # check goal - d2goal = np.hypot(wrist[0] - x, wrist[1] - y) + if x is not None and y is not None: + d2goal = np.hypot(wrist[0] - x, wrist[1] - y) if abs(d2goal) < GOAL_TH and x is not None: return theta1, theta2 @@ -118,8 +127,8 @@ def main(): # pragma: no cover fig = plt.figure() fig.canvas.mpl_connect("button_press_event", click) # for stopping simulation with the esc key. - fig.canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + fig.canvas.mpl_connect('key_release_event', lambda event: [ + exit(0) if event.key == 'escape' else None]) two_joint_arm() From d90fba3717c556229a2cac8778324b915438b65e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 10 Oct 2020 16:29:57 +0900 Subject: [PATCH 318/940] fix circle ci (#419) * fix circle ci * fix circle ci * fix circle ci --- .circleci/config.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index f63f094a3f..d65f0fdf3c 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -5,7 +5,8 @@ orbs: jobs: build_doc: - executor: python/default + docker: + - image: circleci/python:3.8 steps: - checkout - python/load-cache From fa636b26406baad31e8c2840657ff0dcbb6fc4b2 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 13 Oct 2020 06:46:11 +0900 Subject: [PATCH 319/940] Bump cvxpy from 1.1.5 to 1.1.6 (#421) Bumps [cvxpy](https://github.com/cvxgrp/cvxpy) from 1.1.5 to 1.1.6. - [Release notes](https://github.com/cvxgrp/cvxpy/releases) - [Changelog](https://github.com/cvxgrp/cvxpy/blob/master/CHANGELOG.md) - [Commits](https://github.com/cvxgrp/cvxpy/compare/v1.1.5...v1.1.6) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index da40bbae8f..932089a068 100644 --- a/requirements.txt +++ b/requirements.txt @@ -2,4 +2,4 @@ numpy == 1.19.2 scipy == 1.5.2 pandas == 1.1.3 matplotlib == 3.3.2 -cvxpy == 1.1.5 +cvxpy == 1.1.6 From 840d6afb6d8bb4835fdb1682a535cea034ea4ca9 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 20 Oct 2020 07:22:35 +0900 Subject: [PATCH 320/940] Bump scipy from 1.5.2 to 1.5.3 (#424) Bumps [scipy](https://github.com/scipy/scipy) from 1.5.2 to 1.5.3. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.5.2...v1.5.3) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 932089a068..e175ed2d00 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.2 -scipy == 1.5.2 +scipy == 1.5.3 pandas == 1.1.3 matplotlib == 3.3.2 cvxpy == 1.1.6 From 48b6ee3cf9ee65fec86124948c277f43b8cf06ff Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 27 Oct 2020 07:23:42 +0900 Subject: [PATCH 321/940] Bump cvxpy from 1.1.6 to 1.1.7 (#426) Bumps [cvxpy](https://github.com/cvxgrp/cvxpy) from 1.1.6 to 1.1.7. - [Release notes](https://github.com/cvxgrp/cvxpy/releases) - [Changelog](https://github.com/cvxgrp/cvxpy/blob/master/CHANGELOG.md) - [Commits](https://github.com/cvxgrp/cvxpy/compare/v1.1.6...v1.1.7) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index e175ed2d00..92f1b04fb6 100644 --- a/requirements.txt +++ b/requirements.txt @@ -2,4 +2,4 @@ numpy == 1.19.2 scipy == 1.5.3 pandas == 1.1.3 matplotlib == 3.3.2 -cvxpy == 1.1.6 +cvxpy == 1.1.7 From 2bf0dcedc906332e1b4d1b5b4a307fb32de4afc5 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 1 Nov 2020 14:05:46 +0900 Subject: [PATCH 322/940] fix unittest animation bugs (#429) * fix unittest animation bugs * exstract a function --- ...e.py => a_star_searching_from_two_side.py} | 0 PathPlanning/AStar/a_star_variants.py | 129 ++++++++++-------- PathPlanning/FlowField/flowfield.py | 20 +-- tests/test_a_star_searching_two_side.py | 2 +- tests/test_a_star_variants.py | 5 +- 5 files changed, 92 insertions(+), 64 deletions(-) rename PathPlanning/AStar/{A_Star_searching_from_two_side.py => a_star_searching_from_two_side.py} (100%) diff --git a/PathPlanning/AStar/A_Star_searching_from_two_side.py b/PathPlanning/AStar/a_star_searching_from_two_side.py similarity index 100% rename from PathPlanning/AStar/A_Star_searching_from_two_side.py rename to PathPlanning/AStar/a_star_searching_from_two_side.py diff --git a/PathPlanning/AStar/a_star_variants.py b/PathPlanning/AStar/a_star_variants.py index cbf5395fd2..e0053ee224 100644 --- a/PathPlanning/AStar/a_star_variants.py +++ b/PathPlanning/AStar/a_star_variants.py @@ -1,5 +1,5 @@ """ -astar variants +a star variants author: Sarim Mehdi(muhammadsarim.mehdi@studio.unibo.it) Source: http://theory.stanford.edu/~amitp/GameProgramming/Variations.html """ @@ -7,7 +7,7 @@ import numpy as np import matplotlib.pyplot as plt -show_animation = False +show_animation = True use_beam_search = False use_iterative_deepening = False use_dynamic_weighting = False @@ -89,7 +89,8 @@ def key_points(o_dict): obs_count += 1 if obs_count == 3 or obs_count == 1: c_list.append((x, y)) - plt.plot(x, y, ".y") + if show_animation: + plt.plot(x, y, ".y") break if only_corners: return c_list @@ -148,7 +149,8 @@ def __init__(self, obs_grid, goal_x, goal_y, start_x, start_y, 'open': True, 'in_open_list': True} self.open_set.append(self.all_nodes[tuple(self.start_pt)]) - def get_hval(self, x1, y1, x2, y2): + @staticmethod + def get_hval(x1, y1, x2, y2): x, y = x1, y1 val = 0 while x != x2 or y != y2: @@ -178,7 +180,6 @@ def get_farthest_point(self, x, y, i, j): def jump_point(self): """Jump point: Instead of exploring all empty spaces of the map, just explore the corners.""" - plt.title('Jump Point') goal_found = False while len(self.open_set) > 0: @@ -232,11 +233,13 @@ def jump_point(self): if not self.all_nodes[cand_pt]['in_open_list']: self.open_set.append(self.all_nodes[cand_pt]) self.all_nodes[cand_pt]['in_open_list'] = True - plt.plot(cand_pt[0], cand_pt[1], "r*") + if show_animation: + plt.plot(cand_pt[0], cand_pt[1], "r*") if goal_found: break - plt.pause(0.001) + if show_animation: + plt.pause(0.001) if goal_found: current_node = self.all_nodes[tuple(self.goal_pt)] while goal_found: @@ -244,23 +247,26 @@ def jump_point(self): break x = [current_node['pos'][0], current_node['pred'][0]] y = [current_node['pos'][1], current_node['pred'][1]] - plt.plot(x, y, "b") current_node = self.all_nodes[tuple(current_node['pred'])] - plt.pause(0.001) + if show_animation: + plt.plot(x, y, "b") + plt.pause(0.001) if goal_found: break current_node['open'] = False current_node['in_open_list'] = False - plt.plot(current_node['pos'][0], current_node['pos'][1], "g*") + if show_animation: + plt.plot(current_node['pos'][0], current_node['pos'][1], "g*") del self.open_set[p] current_node['fcost'], current_node['hcost'] = np.inf, np.inf if show_animation: + plt.title('Jump Point') plt.show() - def astar(self): + def a_star(self): """Beam search: Maintain an open list of just 30 nodes. - If more than 30 nodes, then get rid of ndoes with high + If more than 30 nodes, then get rid of nodes with high f values. Iterative deepening: At every iteration, get a cut-off value for the f cost. This cut-off is minimum of the f @@ -275,21 +281,23 @@ def astar(self): one neighbor at a time. In fact, you can look for the next node as far out as you can as long as there is a clear line of sight from your current node to that node.""" - if use_beam_search: - plt.title('A* with beam search') - elif use_iterative_deepening: - plt.title('A* with iterative deepening') - elif use_dynamic_weighting: - plt.title('A* with dynamic weighting') - elif use_theta_star: - plt.title('Theta*') - else: - plt.title('A*') + if show_animation: + if use_beam_search: + plt.title('A* with beam search') + elif use_iterative_deepening: + plt.title('A* with iterative deepening') + elif use_dynamic_weighting: + plt.title('A* with dynamic weighting') + elif use_theta_star: + plt.title('Theta*') + else: + plt.title('A*') goal_found = False curr_f_thresh = np.inf depth = 0 no_valid_f = False + w = None while len(self.open_set) > 0: self.open_set = sorted(self.open_set, key=lambda x: x['fcost']) lowest_f = self.open_set[0]['fcost'] @@ -351,30 +359,14 @@ def astar(self): break cand_pt = tuple(cand_pt) - if not self.obs_grid[tuple(cand_pt)] and \ - self.all_nodes[cand_pt]['open']: - g_cost = offset + current_node['gcost'] - h_cost = self.all_nodes[cand_pt]['hcost'] - if use_dynamic_weighting: - h_cost = h_cost * w - f_cost = g_cost + h_cost - if f_cost < self.all_nodes[cand_pt]['fcost'] and \ - f_cost <= curr_f_thresh: - f_cost_list.append(f_cost) - self.all_nodes[cand_pt]['pred'] = \ - current_node['pos'] - self.all_nodes[cand_pt]['gcost'] = g_cost - self.all_nodes[cand_pt]['fcost'] = f_cost - if not self.all_nodes[cand_pt]['in_open_list']: - self.open_set.append(self.all_nodes[cand_pt]) - self.all_nodes[cand_pt]['in_open_list'] = True - plt.plot(cand_pt[0], cand_pt[1], "r*") - if curr_f_thresh < f_cost < \ - self.all_nodes[cand_pt]['fcost']: - no_valid_f = True + no_valid_f = self.update_node_cost(cand_pt, curr_f_thresh, + current_node, + f_cost_list, no_valid_f, + offset, w) if goal_found: break - plt.pause(0.001) + if show_animation: + plt.pause(0.001) if goal_found: current_node = self.all_nodes[tuple(self.goal_pt)] while goal_found: @@ -383,12 +375,13 @@ def astar(self): if use_theta_star or use_jump_point: x, y = [current_node['pos'][0], current_node['pred'][0]], \ [current_node['pos'][1], current_node['pred'][1]] - plt.plot(x, y, "b") + if show_animation: + plt.plot(x, y, "b") else: - plt.plot(current_node['pred'][0], - current_node['pred'][1], "b*") + if show_animation: + plt.plot(current_node['pred'][0], + current_node['pred'][1], "b*") current_node = self.all_nodes[tuple(current_node['pred'])] - plt.pause(0.001) if goal_found: break @@ -402,13 +395,40 @@ def astar(self): current_node['open'] = False current_node['in_open_list'] = False - plt.plot(current_node['pos'][0], current_node['pos'][1], "g*") + if show_animation: + plt.plot(current_node['pos'][0], current_node['pos'][1], "g*") del self.open_set[p] current_node['fcost'], current_node['hcost'] = np.inf, np.inf depth += 1 if show_animation: plt.show() + def update_node_cost(self, cand_pt, curr_f_thresh, current_node, + f_cost_list, no_valid_f, offset, w): + if not self.obs_grid[tuple(cand_pt)] and \ + self.all_nodes[cand_pt]['open']: + g_cost = offset + current_node['gcost'] + h_cost = self.all_nodes[cand_pt]['hcost'] + if use_dynamic_weighting: + h_cost = h_cost * w + f_cost = g_cost + h_cost + if f_cost < self.all_nodes[cand_pt]['fcost'] and \ + f_cost <= curr_f_thresh: + f_cost_list.append(f_cost) + self.all_nodes[cand_pt]['pred'] = \ + current_node['pos'] + self.all_nodes[cand_pt]['gcost'] = g_cost + self.all_nodes[cand_pt]['fcost'] = f_cost + if not self.all_nodes[cand_pt]['in_open_list']: + self.open_set.append(self.all_nodes[cand_pt]) + self.all_nodes[cand_pt]['in_open_list'] = True + if show_animation: + plt.plot(cand_pt[0], cand_pt[1], "r*") + if curr_f_thresh < f_cost < \ + self.all_nodes[cand_pt]['fcost']: + no_valid_f = True + return no_valid_f + def main(): # set obstacle positions @@ -443,10 +463,11 @@ def main(): for x, y, l in zip(all_x, all_y, all_len): draw_horizontal_line(x, y, l, o_x, o_y, obs_dict) - plt.plot(o_x, o_y, ".k") - plt.plot(s_x, s_y, "og") - plt.plot(g_x, g_y, "xb") - plt.grid(True) + if show_animation: + plt.plot(o_x, o_y, ".k") + plt.plot(s_x, s_y, "og") + plt.plot(g_x, g_y, "xb") + plt.grid(True) if use_jump_point: keypoint_list = key_points(obs_dict) @@ -455,7 +476,7 @@ def main(): search_obj.jump_point() else: search_obj = SearchAlgo(obs_dict, g_x, g_y, s_x, s_y, 101, 101) - search_obj.astar() + search_obj.a_star() if __name__ == '__main__': diff --git a/PathPlanning/FlowField/flowfield.py b/PathPlanning/FlowField/flowfield.py index f222e8ecf2..e50430de3c 100644 --- a/PathPlanning/FlowField/flowfield.py +++ b/PathPlanning/FlowField/flowfield.py @@ -129,9 +129,12 @@ def assign_vectors(self): def follow_vectors(self): curr_x, curr_y = self.start_pt while curr_x is not None and curr_y is not None: - plt.plot(curr_x, curr_y, "b*") curr_x, curr_y = self.vector_field[(curr_x, curr_y)] - plt.pause(0.001) + + if show_animation: + plt.plot(curr_x, curr_y, "b*") + plt.pause(0.001) + if show_animation: plt.show() @@ -208,12 +211,13 @@ def main(): for x, y, l in zip(all_x, all_y, all_len): draw_horizontal_line(x, y, l, h_x, h_y, obs_dict, 'hard') - plt.plot(o_x, o_y, "sr") - plt.plot(m_x, m_y, "sg") - plt.plot(h_x, h_y, "sy") - plt.plot(s_x, s_y, "og") - plt.plot(g_x, g_y, "o") - plt.grid(True) + if show_animation: + plt.plot(o_x, o_y, "sr") + plt.plot(m_x, m_y, "sg") + plt.plot(h_x, h_y, "sy") + plt.plot(s_x, s_y, "og") + plt.plot(g_x, g_y, "o") + plt.grid(True) flow_obj = FlowField(obs_dict, g_x, g_y, s_x, s_y, 50, 50) flow_obj.find_path() diff --git a/tests/test_a_star_searching_two_side.py b/tests/test_a_star_searching_two_side.py index 6116c9bbe7..013e9253b8 100644 --- a/tests/test_a_star_searching_two_side.py +++ b/tests/test_a_star_searching_two_side.py @@ -5,7 +5,7 @@ sys.path.append(os.path.dirname(__file__) + '/../') try: - from PathPlanning.AStar import A_Star_searching_from_two_side as m + from PathPlanning.AStar import a_star_searching_from_two_side as m except ImportError: raise diff --git a/tests/test_a_star_variants.py b/tests/test_a_star_variants.py index 53efeddd20..13009c1365 100644 --- a/tests/test_a_star_variants.py +++ b/tests/test_a_star_variants.py @@ -10,6 +10,7 @@ class Test(TestCase): def test(self): # A* with beam search astar.show_animation = False + astar.use_beam_search = True astar.main() self.reset_all() @@ -34,7 +35,9 @@ def test(self): astar.main() self.reset_all() - def reset_all(self): + @staticmethod + def reset_all(): + astar.show_animation = False astar.use_beam_search = False astar.use_iterative_deepening = False astar.use_dynamic_weighting = False From 0c76141b8057630865880fd57368be3312f58c6f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 3 Nov 2020 07:30:43 +0900 Subject: [PATCH 323/940] Bump numpy from 1.19.2 to 1.19.4 (#430) Bumps [numpy](https://github.com/numpy/numpy) from 1.19.2 to 1.19.4. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/master/doc/HOWTO_RELEASE.rst.txt) - [Commits](https://github.com/numpy/numpy/compare/v1.19.2...v1.19.4) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 92f1b04fb6..526d314410 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.19.2 +numpy == 1.19.4 scipy == 1.5.3 pandas == 1.1.3 matplotlib == 3.3.2 From 35e23c89cdd789e09a4849eb87b345790ac2efcc Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 3 Nov 2020 07:30:59 +0900 Subject: [PATCH 324/940] Bump pandas from 1.1.3 to 1.1.4 (#431) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.1.3 to 1.1.4. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/master/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.1.3...v1.1.4) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 526d314410..600dbc480e 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.4 scipy == 1.5.3 -pandas == 1.1.3 +pandas == 1.1.4 matplotlib == 3.3.2 cvxpy == 1.1.7 From 31b75f135865bcd9e92376088b1064b84d155068 Mon Sep 17 00:00:00 2001 From: Nguyen Mau Dung Date: Sun, 8 Nov 2020 14:09:59 +0900 Subject: [PATCH 325/940] Using vectorization to speed up computation (#427) --- .../rectangle_fitting/rectangle_fitting.py | 41 ++++++------------- 1 file changed, 12 insertions(+), 29 deletions(-) diff --git a/Mapping/rectangle_fitting/rectangle_fitting.py b/Mapping/rectangle_fitting/rectangle_fitting.py index ae41b3c53e..a60a6fbfd1 100644 --- a/Mapping/rectangle_fitting/rectangle_fitting.py +++ b/Mapping/rectangle_fitting/rectangle_fitting.py @@ -69,15 +69,11 @@ def _calc_closeness_criterion(self, c1, c2): c1_min = min(c1) c2_min = min(c2) - D1 = [min([np.linalg.norm(c1_max - ic1), - np.linalg.norm(ic1 - c1_min)]) for ic1 in c1] - D2 = [min([np.linalg.norm(c2_max - ic2), - np.linalg.norm(ic2 - c2_min)]) for ic2 in c2] - - beta = 0 - for i, _ in enumerate(D1): - d = max(min([D1[i], D2[i]]), self.min_dist_of_closeness_criteria) - beta += (1.0 / d) + # Vectorization + D1 = np.minimum(c1_max - c1, c1 - c1_min) + D2 = np.minimum(c2_max - c2, c2 - c2_min) + d = np.maximum(np.minimum(D1, D2), self.min_dist_of_closeness_criteria) + beta = (1.0 / d).sum() return beta @@ -88,26 +84,13 @@ def _calc_variance_criterion(c1, c2): c1_min = min(c1) c2_min = min(c2) - D1 = [min([np.linalg.norm(c1_max - ic1), - np.linalg.norm(ic1 - c1_min)]) for ic1 in c1] - D2 = [min([np.linalg.norm(c2_max - ic2), - np.linalg.norm(ic2 - c2_min)]) for ic2 in c2] - - E1, E2 = [], [] - for (d1, d2) in zip(D1, D2): - if d1 < d2: - E1.append(d1) - else: - E2.append(d2) - - V1 = 0.0 - if E1: - V1 = - np.var(E1) - - V2 = 0.0 - if E2: - V2 = - np.var(E2) - + # Vectorization + D1 = np.minimum(c1_max - c1, c1 - c1_min) + D2 = np.minimum(c2_max - c2, c2 - c2_min) + E1 = D1[D1 < D2] + E2 = D2[D1 >= D2] + V1 = - np.var(E1) if len(E1) > 0 else 0. + V2 = - np.var(E2) if len(E2) > 0 else 0. gamma = V1 + V2 return gamma From 7e312daa705e4b9939719fca3719e5956614116f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 10 Nov 2020 06:55:51 +0900 Subject: [PATCH 326/940] Bump scipy from 1.5.3 to 1.5.4 (#438) Bumps [scipy](https://github.com/scipy/scipy) from 1.5.3 to 1.5.4. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.5.3...v1.5.4) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 600dbc480e..5035bbbc69 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.4 -scipy == 1.5.3 +scipy == 1.5.4 pandas == 1.1.4 matplotlib == 3.3.2 cvxpy == 1.1.7 From 40df009180e7541e6bc85e7f455d7d973a064aed Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 17 Nov 2020 20:18:04 +0900 Subject: [PATCH 327/940] Bump matplotlib from 3.3.2 to 3.3.3 (#441) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.3.2 to 3.3.3. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.3.2...v3.3.3) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 5035bbbc69..5cc619a841 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.4 scipy == 1.5.4 pandas == 1.1.4 -matplotlib == 3.3.2 +matplotlib == 3.3.3 cvxpy == 1.1.7 From f9e2293a8d0478c51752809efb878c9f3cea4a4d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 8 Dec 2020 07:49:13 +0900 Subject: [PATCH 328/940] Bump pandas from 1.1.4 to 1.1.5 (#443) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.1.4 to 1.1.5. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/master/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.1.4...v1.1.5) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 5cc619a841..b66011e4a4 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.4 scipy == 1.5.4 -pandas == 1.1.4 +pandas == 1.1.5 matplotlib == 3.3.3 cvxpy == 1.1.7 From 2d5024dc386b1d84ade7cdbdda7d5aaab58cf57b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 20 Dec 2020 16:16:35 +0900 Subject: [PATCH 329/940] add test_rectangle_fitting.py (#444) * add test_rectangle_fitting.py * add test_rectangle_fitting.py --- tests/test_rectangle_fitting.py | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) create mode 100644 tests/test_rectangle_fitting.py diff --git a/tests/test_rectangle_fitting.py b/tests/test_rectangle_fitting.py new file mode 100644 index 0000000000..2a28320626 --- /dev/null +++ b/tests/test_rectangle_fitting.py @@ -0,0 +1,22 @@ +from unittest import TestCase + +import sys +import os + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../Mapping/rectangle_fitting/") + +try: + from Mapping.rectangle_fitting import rectangle_fitting as m +except ImportError: + raise + + +print(__file__) + + +class Test(TestCase): + + def test1(self): + m.show_animation = False + m.main() From 4264cb8b1010e5eaa448b3ef6d0a1c096bba65e8 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 20 Dec 2020 20:29:36 +0900 Subject: [PATCH 330/940] fix pure_pursuit sample (#445) --- .../ClosedLoopRRTStar/pure_pursuit.py | 41 +------------------ 1 file changed, 2 insertions(+), 39 deletions(-) diff --git a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py index f3984f87b0..ca763f0d4f 100644 --- a/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py +++ b/PathPlanning/ClosedLoopRRTStar/pure_pursuit.py @@ -250,7 +250,7 @@ def main(): # pragma: no cover yaw = [state.yaw] v = [state.v] t = [0.0] - target_ind = calc_target_index(state, cx, cy) + target_ind, dis = calc_target_index(state, cx, cy) while T >= time and lastIndex > target_ind: ai = PIDControl(target_speed, state.v) @@ -291,43 +291,6 @@ def main(): # pragma: no cover plt.show() -def main2(): # pragma: no cover - import pandas as pd - data = pd.read_csv("rrt_course.csv") - cx = np.array(data["x"]) - cy = np.array(data["y"]) - cyaw = np.array(data["yaw"]) - - target_speed = 10.0 / 3.6 - - goal = [cx[-1], cy[-1]] - - cx, cy, cyaw = extend_path(cx, cy, cyaw) - - speed_profile = calc_speed_profile(cx, cy, cyaw, target_speed) - - t, x, y, yaw, v, a, d, flag = closed_loop_prediction( - cx, cy, cyaw, speed_profile, goal) - - plt.subplots(1) - plt.plot(cx, cy, ".r", label="course") - plt.plot(x, y, "-b", label="trajectory") - plt.plot(goal[0], goal[1], "xg", label="goal") - plt.legend() - plt.xlabel("x[m]") - plt.ylabel("y[m]") - plt.axis("equal") - plt.grid(True) - - plt.subplots(1) - plt.plot(t, [iv * 3.6 for iv in v], "-r") - plt.xlabel("Time[s]") - plt.ylabel("Speed[km/h]") - plt.grid(True) - plt.show() - - if __name__ == '__main__': # pragma: no cover print("Pure pursuit path tracking simulation start") - # main() - main2() + main() From e0a8ab2368d83797d2246af1f9b4fa80788d74dd Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 29 Dec 2020 07:28:19 +0900 Subject: [PATCH 331/940] Bump pandas from 1.1.5 to 1.2.0 (#449) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.1.5 to 1.2.0. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/master/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.1.5...v1.2.0) Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index b66011e4a4..c8aa78aeb7 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.19.4 scipy == 1.5.4 -pandas == 1.1.5 +pandas == 1.2.0 matplotlib == 3.3.3 cvxpy == 1.1.7 From 65debdc332b23083a434c24fa5b73e917ee71aa2 Mon Sep 17 00:00:00 2001 From: Mahyar Abdeetedal Date: Tue, 29 Dec 2020 06:32:13 -0500 Subject: [PATCH 332/940] RRT* for seven joint arm control (#439) --- .../rrt_star_seven_joint_arm.py | 403 ++++++++++++++++++ tests/test_rrt_star_seven_joint_arm.py | 26 ++ 2 files changed, 429 insertions(+) create mode 100755 ArmNavigation/seven_joint_arm_to_point_control/rrt_star_seven_joint_arm.py create mode 100644 tests/test_rrt_star_seven_joint_arm.py diff --git a/ArmNavigation/seven_joint_arm_to_point_control/rrt_star_seven_joint_arm.py b/ArmNavigation/seven_joint_arm_to_point_control/rrt_star_seven_joint_arm.py new file mode 100755 index 0000000000..d10733b41e --- /dev/null +++ b/ArmNavigation/seven_joint_arm_to_point_control/rrt_star_seven_joint_arm.py @@ -0,0 +1,403 @@ +""" +RRT* path planner for a seven joint arm +Author: Mahyar Abdeetedal (mahyaret) +""" +import math +import os +import sys +import random +import numpy as np +from mpl_toolkits import mplot3d +import matplotlib.pyplot as plt +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../n_joint_arm_3d/") +try: + from NLinkArm3d import NLinkArm +except ImportError: + raise + +show_animation = True +verbose = False + + +class RobotArm(NLinkArm): + def get_points(self, joint_angle_list): + self.set_joint_angles(joint_angle_list) + + x_list = [] + y_list = [] + z_list = [] + + trans = np.identity(4) + + x_list.append(trans[0, 3]) + y_list.append(trans[1, 3]) + z_list.append(trans[2, 3]) + for i in range(len(self.link_list)): + trans = np.dot(trans, self.link_list[i].transformation_matrix()) + x_list.append(trans[0, 3]) + y_list.append(trans[1, 3]) + z_list.append(trans[2, 3]) + + return x_list, y_list, z_list + + +class RRTStar: + """ + Class for RRT Star planning + """ + + class Node: + def __init__(self, x): + self.x = x + self.parent = None + self.cost = 0.0 + + def __init__(self, start, goal, robot, obstacle_list, rand_area, + expand_dis=.30, + path_resolution=.1, + goal_sample_rate=20, + max_iter=300, + connect_circle_dist=50.0 + ): + """ + Setting Parameter + + start:Start Position [q1,...,qn] + goal:Goal Position [q1,...,qn] + obstacleList:obstacle Positions [[x,y,z,size],...] + randArea:Random Sampling Area [min,max] + + """ + self.start = self.Node(start) + self.end = self.Node(goal) + self.dimension = len(start) + self.min_rand = rand_area[0] + self.max_rand = rand_area[1] + self.expand_dis = expand_dis + self.path_resolution = path_resolution + self.goal_sample_rate = goal_sample_rate + self.max_iter = max_iter + self.robot = robot + self.obstacle_list = obstacle_list + self.connect_circle_dist = connect_circle_dist + self.goal_node = self.Node(goal) + self.ax = plt.axes(projection='3d') + self.node_list = [] + + def planning(self, animation=False, search_until_max_iter=False): + """ + rrt star path planning + + animation: flag for animation on or off + search_until_max_iter: search until max iteration for path + improving or not + """ + + self.node_list = [self.start] + for i in range(self.max_iter): + if verbose: + print("Iter:", i, ", number of nodes:", len(self.node_list)) + rnd = self.get_random_node() + nearest_ind = self.get_nearest_node_index(self.node_list, rnd) + new_node = self.steer(self.node_list[nearest_ind], + rnd, + self.expand_dis) + + if self.check_collision(new_node, self.robot, self.obstacle_list): + near_inds = self.find_near_nodes(new_node) + new_node = self.choose_parent(new_node, near_inds) + if new_node: + self.node_list.append(new_node) + self.rewire(new_node, near_inds) + + if animation and i % 5 == 0 and self.dimension <= 3: + self.draw_graph(rnd) + + if (not search_until_max_iter) and new_node: + last_index = self.search_best_goal_node() + if last_index is not None: + return self.generate_final_course(last_index) + if verbose: + print("reached max iteration") + + last_index = self.search_best_goal_node() + if last_index is not None: + return self.generate_final_course(last_index) + + return None + + def choose_parent(self, new_node, near_inds): + if not near_inds: + return None + + # search nearest cost in near_inds + costs = [] + for i in near_inds: + near_node = self.node_list[i] + t_node = self.steer(near_node, new_node) + if t_node and self.check_collision(t_node, + self.robot, + self.obstacle_list): + costs.append(self.calc_new_cost(near_node, new_node)) + else: + costs.append(float("inf")) # the cost of collision node + min_cost = min(costs) + + if min_cost == float("inf"): + print("There is no good path.(min_cost is inf)") + return None + + min_ind = near_inds[costs.index(min_cost)] + new_node = self.steer(self.node_list[min_ind], new_node) + new_node.parent = self.node_list[min_ind] + new_node.cost = min_cost + + return new_node + + def search_best_goal_node(self): + dist_to_goal_list = [self.calc_dist_to_goal(n.x) + for n in self.node_list] + goal_inds = [dist_to_goal_list.index(i) + for i in dist_to_goal_list if i <= self.expand_dis] + + safe_goal_inds = [] + for goal_ind in goal_inds: + t_node = self.steer(self.node_list[goal_ind], self.goal_node) + if self.check_collision(t_node, self.robot, self.obstacle_list): + safe_goal_inds.append(goal_ind) + + if not safe_goal_inds: + return None + + min_cost = min([self.node_list[i].cost for i in safe_goal_inds]) + for i in safe_goal_inds: + if self.node_list[i].cost == min_cost: + return i + + return None + + def find_near_nodes(self, new_node): + nnode = len(self.node_list) + 1 + r = self.connect_circle_dist * math.sqrt((math.log(nnode) / nnode)) + # if expand_dist exists, search vertices in + # a range no more than expand_dist + if hasattr(self, 'expand_dis'): + r = min(r, self.expand_dis) + dist_list = [np.sum((np.array(node.x) - np.array(new_node.x)) ** 2) + for node in self.node_list] + near_inds = [dist_list.index(i) for i in dist_list if i <= r ** 2] + return near_inds + + def rewire(self, new_node, near_inds): + for i in near_inds: + near_node = self.node_list[i] + edge_node = self.steer(new_node, near_node) + if not edge_node: + continue + edge_node.cost = self.calc_new_cost(new_node, near_node) + + no_collision = self.check_collision(edge_node, + self.robot, + self.obstacle_list) + improved_cost = near_node.cost > edge_node.cost + + if no_collision and improved_cost: + self.node_list[i] = edge_node + self.propagate_cost_to_leaves(new_node) + + def calc_new_cost(self, from_node, to_node): + d, _, _ = self.calc_distance_and_angle(from_node, to_node) + return from_node.cost + d + + def propagate_cost_to_leaves(self, parent_node): + + for node in self.node_list: + if node.parent == parent_node: + node.cost = self.calc_new_cost(parent_node, node) + self.propagate_cost_to_leaves(node) + + def generate_final_course(self, goal_ind): + path = [self.end.x] + node = self.node_list[goal_ind] + while node.parent is not None: + path.append(node.x) + node = node.parent + path.append(node.x) + + return path + + def calc_dist_to_goal(self, x): + distance = np.linalg.norm(np.array(x) - np.array(self.end.x)) + return distance + + def get_random_node(self): + if random.randint(0, 100) > self.goal_sample_rate: + rnd = self.Node(np.random.uniform(self.min_rand, + self.max_rand, + self.dimension)) + else: # goal point sampling + rnd = self.Node(self.end.x) + return rnd + + def steer(self, from_node, to_node, extend_length=float("inf")): + new_node = self.Node(list(from_node.x)) + d, phi, theta = self.calc_distance_and_angle(new_node, to_node) + + new_node.path_x = [list(new_node.x)] + + if extend_length > d: + extend_length = d + + n_expand = math.floor(extend_length / self.path_resolution) + + start, end = np.array(from_node.x), np.array(to_node.x) + v = end - start + u = v / (np.sqrt(np.sum(v ** 2))) + for _ in range(n_expand): + new_node.x += u * self.path_resolution + new_node.path_x.append(list(new_node.x)) + + d, _, _ = self.calc_distance_and_angle(new_node, to_node) + if d <= self.path_resolution: + new_node.path_x.append(list(to_node.x)) + + new_node.parent = from_node + + return new_node + + def draw_graph(self, rnd=None): + plt.cla() + self.ax.axis([-1, 1, -1, 1]) + self.ax.set_zlim(0, 1) + self.ax.grid(True) + for (ox, oy, oz, size) in self.obstacle_list: + self.plot_sphere(self.ax, ox, oy, oz, size=size) + if self.dimension > 3: + return self.ax + if rnd is not None: + self.ax.plot([rnd.x[0]], [rnd.x[1]], [rnd.x[2]], "^k") + for node in self.node_list: + if node.parent: + path = np.array(node.path_x) + plt.plot(path[:, 0], path[:, 1], path[:, 2], "-g") + self.ax.plot([self.start.x[0]], [self.start.x[1]], + [self.start.x[2]], "xr") + self.ax.plot([self.end.x[0]], [self.end.x[1]], [self.end.x[2]], "xr") + plt.pause(0.01) + return self.ax + + @staticmethod + def get_nearest_node_index(node_list, rnd_node): + dlist = [np.sum((np.array(node.x) - np.array(rnd_node.x))**2) + for node in node_list] + minind = dlist.index(min(dlist)) + + return minind + + @staticmethod + def plot_sphere(ax, x, y, z, size=1, color="k"): + u, v = np.mgrid[0:2*np.pi:20j, 0:np.pi:10j] + xl = x+size*np.cos(u)*np.sin(v) + yl = y+size*np.sin(u)*np.sin(v) + zl = z+size*np.cos(v) + ax.plot_wireframe(xl, yl, zl, color=color) + + @staticmethod + def calc_distance_and_angle(from_node, to_node): + dx = to_node.x[0] - from_node.x[0] + dy = to_node.x[1] - from_node.x[1] + dz = to_node.x[2] - from_node.x[2] + d = np.sqrt(np.sum((np.array(to_node.x) - np.array(from_node.x))**2)) + phi = math.atan2(dy, dx) + theta = math.atan2(math.hypot(dx, dy), dz) + return d, phi, theta + + @staticmethod + def calc_distance_and_angle2(from_node, to_node): + dx = to_node.x[0] - from_node.x[0] + dy = to_node.x[1] - from_node.x[1] + dz = to_node.x[2] - from_node.x[2] + d = math.sqrt(dx**2 + dy**2 + dz**2) + phi = math.atan2(dy, dx) + theta = math.atan2(math.hypot(dx, dy), dz) + return d, phi, theta + + @staticmethod + def check_collision(node, robot, obstacleList): + + if node is None: + return False + + for (ox, oy, oz, size) in obstacleList: + for x in node.path_x: + x_list, y_list, z_list = robot.get_points(x) + dx_list = [ox - x_point for x_point in x_list] + dy_list = [oy - y_point for y_point in y_list] + dz_list = [oz - z_point for z_point in z_list] + d_list = [dx * dx + dy * dy + dz * dz + for (dx, dy, dz) in zip(dx_list, + dy_list, + dz_list)] + + if min(d_list) <= size ** 2: + return False # collision + + return True # safe + + +def main(): + print("Start " + __file__) + + # init NLinkArm with Denavit-Hartenberg parameters of panda + # https://frankaemika.github.io/docs/control_parameters.html + # [theta, alpha, a, d] + seven_joint_arm = RobotArm([[0., math.pi/2., 0., .333], + [0., -math.pi/2., 0., 0.], + [0., math.pi/2., 0.0825, 0.3160], + [0., -math.pi/2., -0.0825, 0.], + [0., math.pi/2., 0., 0.3840], + [0., math.pi/2., 0.088, 0.], + [0., 0., 0., 0.107]]) + # ====Search Path with RRT==== + obstacle_list = [ + (-.3, -.3, .7, .1), + (.0, -.3, .7, .1), + (.2, -.1, .3, .15), + ] # [x,y,size(radius)] + start = [0 for _ in range(len(seven_joint_arm.link_list))] + end = [1.5 for _ in range(len(seven_joint_arm.link_list))] + # Set Initial parameters + rrt_star = RRTStar(start=start, + goal=end, + rand_area=[0, 2], + max_iter=200, + robot=seven_joint_arm, + obstacle_list=obstacle_list) + path = rrt_star.planning(animation=show_animation, + search_until_max_iter=False) + + if path is None: + print("Cannot find path") + else: + print("found path!!") + + # Draw final path + if show_animation: + ax = rrt_star.draw_graph() + for i, q in enumerate(reversed(path)): + x_points, y_points, z_points = seven_joint_arm.get_points(q) + if i == 0 or i == len(path) - 1: + color = None + else: + color = "grey" + ax.plot([x for x in x_points], + [y for y in y_points], + [z for z in z_points], + "o-", color=color, ms=4, mew=0.5) + plt.pause(0.01) + plt.show() + + +if __name__ == '__main__': + main() diff --git a/tests/test_rrt_star_seven_joint_arm.py b/tests/test_rrt_star_seven_joint_arm.py new file mode 100644 index 0000000000..fe90801b3b --- /dev/null +++ b/tests/test_rrt_star_seven_joint_arm.py @@ -0,0 +1,26 @@ +import os +import sys +from unittest import TestCase + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../ArmNavigation/seven_joint_arm_to_point_control/") + +try: + import rrt_star_seven_joint_arm as m +except ImportError: + raise + + +print(__file__) + + +class Test(TestCase): + + def test1(self): + m.show_animation = False + m.main() + + +if __name__ == '__main__': # pragma: no cover + test = Test() + test.test1() From d29dacbf9e89db2e06be3fcb799a5cf78f22e4d9 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 29 Dec 2020 21:41:14 +0900 Subject: [PATCH 333/940] clean up seven joint arm script --- .../rrt_star_seven_joint_arm_control.py} | 19 ++++++++++++------- tests/test_rrt_star_seven_joint_arm.py | 4 ++-- 2 files changed, 14 insertions(+), 9 deletions(-) rename ArmNavigation/{seven_joint_arm_to_point_control/rrt_star_seven_joint_arm.py => rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py} (96%) diff --git a/ArmNavigation/seven_joint_arm_to_point_control/rrt_star_seven_joint_arm.py b/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py similarity index 96% rename from ArmNavigation/seven_joint_arm_to_point_control/rrt_star_seven_joint_arm.py rename to ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py index d10733b41e..0de4c7edb8 100755 --- a/ArmNavigation/seven_joint_arm_to_point_control/rrt_star_seven_joint_arm.py +++ b/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py @@ -224,7 +224,7 @@ def generate_final_course(self, goal_ind): path.append(node.x) node = node.parent path.append(node.x) - + reversed(path) return path def calc_dist_to_goal(self, x): @@ -385,17 +385,22 @@ def main(): # Draw final path if show_animation: ax = rrt_star.draw_graph() - for i, q in enumerate(reversed(path)): + + # Plot final configuration + x_points, y_points, z_points = seven_joint_arm.get_points(path[-1]) + ax.plot([x for x in x_points], + [y for y in y_points], + [z for z in z_points], + "o-", color="red", ms=5, mew=0.5) + + for i, q in enumerate(path): x_points, y_points, z_points = seven_joint_arm.get_points(q) - if i == 0 or i == len(path) - 1: - color = None - else: - color = "grey" ax.plot([x for x in x_points], [y for y in y_points], [z for z in z_points], - "o-", color=color, ms=4, mew=0.5) + "o-", color="grey", ms=4, mew=0.5) plt.pause(0.01) + plt.show() diff --git a/tests/test_rrt_star_seven_joint_arm.py b/tests/test_rrt_star_seven_joint_arm.py index fe90801b3b..0788b3675a 100644 --- a/tests/test_rrt_star_seven_joint_arm.py +++ b/tests/test_rrt_star_seven_joint_arm.py @@ -3,10 +3,10 @@ from unittest import TestCase sys.path.append(os.path.dirname(os.path.abspath(__file__)) + - "/../ArmNavigation/seven_joint_arm_to_point_control/") + "/../ArmNavigation/rrt_star_seven_joint_arm_control/") try: - import rrt_star_seven_joint_arm as m + import rrt_star_seven_joint_arm_control as m except ImportError: raise From 581b3cf27ab188a319162dc13dc926503b52cda9 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 30 Dec 2020 13:52:00 +0900 Subject: [PATCH 334/940] bump python version to 3.9. (#433) --- .circleci/config.yml | 4 +++- .github/workflows/Linux_CI.yml | 6 ++++-- .github/workflows/MacOS_CI.yml | 4 +++- README.md | 2 +- appveyor.yml | 16 ++++++---------- docs/getting_started.rst | 2 +- 6 files changed, 18 insertions(+), 16 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index d65f0fdf3c..0ec05a3a20 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -6,10 +6,12 @@ orbs: jobs: build_doc: docker: - - image: circleci/python:3.8 + - image: circleci/python:3.9 steps: + - run: sudo apt-get update && sudo apt-get install -y cmake # TODO: remove after osqp wheels released - checkout - python/load-cache + - run: pip install numpy # TODO: remove after osqp wheels released - python/install-deps - python/save-cache - run: pip install sphinx sphinx-autobuild sphinx-rtd-theme diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index 1174438dd5..61be099152 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest strategy: matrix: - python-version: ['3.8'] + python-version: ['3.9'] name: Python ${{ matrix.python-version }} CI @@ -21,9 +21,11 @@ jobs: with: python-version: ${{ matrix.python-version }} - name: Install dependencies + # TODO: remove numpy installation after fix cvxpy install issue run: | python -m pip install --upgrade pip - pip install -r requirements.txt + pip install numpy + python -m pip install -r requirements.txt - name: install coverage run: pip install coverage - name: install mypy diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index 3a28347b18..84ef75157f 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -11,7 +11,7 @@ jobs: runs-on: ubuntu-latest strategy: matrix: - python-version: [ '3.8' ] + python-version: [ '3.9' ] name: Python ${{ matrix.python-version }} CI steps: - uses: actions/checkout@v2 @@ -23,8 +23,10 @@ jobs: python-version: ${{ matrix.python-version }} - name: Install dependencies + # TODO: remove numpy installation after fix cvxpy install issue run: | python -m pip install --upgrade pip + pip install numpy pip install -r requirements.txt - name: install coverage run: pip install coverage diff --git a/README.md b/README.md index 07dbf7ae5a..2dcb4bab7e 100644 --- a/README.md +++ b/README.md @@ -92,7 +92,7 @@ See this paper for more details: # Requirements -- Python 3.8.x +- Python 3.9.x - numpy diff --git a/appveyor.yml b/appveyor.yml index b883397d71..9fd7430223 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -8,11 +8,10 @@ environment: CMD_IN_ENV: "cmd /E:ON /V:ON /C .\\appveyor\\run_with_env.cmd" matrix: - - MINICONDA: C:\Miniconda38-x64 - PYTHON_VERSION: "3.8" + - PYTHON_DIR: C:\Python39-x64 init: - - "ECHO %MINICONDA% %PYTHON_VERSION% %PYTHON_ARCH%" + - "ECHO %PYTHON_DIR%" install: # If there is a newer build queued for the same PR, cancel this one. @@ -30,15 +29,12 @@ install: # Prepend newly installed Python to the PATH of this build (this cannot be # done from inside the powershell script as it would require to restart # the parent CMD process). - - SET PATH=%MINICONDA%;%MINICONDA%\\Scripts;%PATH% + - SET PATH=%PYTHON_DIR%;%PYTHON_DIR%\\Scripts;%PATH% - SET PATH=%PYTHON%;%PYTHON%\Scripts;%PYTHON%\Library\bin;%PATH% - SET PATH=%PATH%;C:\Program Files (x86)\Microsoft Visual Studio 14.0\VC\bin - - conda config --set always_yes yes --set changeps1 no - - conda config --append channels conda-forge - - conda update -q conda - - conda info -a - - conda env create -f C:\\projects\pythonrobotics\environment.yml - - activate python_robotics + - "python -m pip install --upgrade pip" + - "pip install numpy" # TODO: remove this line after osqp wheel released + - "python -m pip install -r requirements.txt" # Check that we have the expected version and architecture for Python - "python --version" diff --git a/docs/getting_started.rst b/docs/getting_started.rst index 93ab70503a..83565eb872 100644 --- a/docs/getting_started.rst +++ b/docs/getting_started.rst @@ -25,7 +25,7 @@ See this paper for more details: Requirements ------------- -- Python 3.6.x +- Python 3.9.x - numpy - scipy - matplotlib From c2debe3b05b095046f63f72bb9b9c3b0c52c2635 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 31 Dec 2020 22:54:40 +0900 Subject: [PATCH 335/940] use pytest for test runner (#452) --- .github/pull_request_template.md | 2 +- .../two_joint_arm_to_point_control.py | 26 ++- .../Eta3SplinePath/eta3_spline_path.py | 178 ++++++++++-------- .../eta3_spline_trajectory.py | 48 ++--- README.md | 2 + requirements.txt | 1 + runtests.sh | 8 +- tests/__init__.py | 0 8 files changed, 152 insertions(+), 113 deletions(-) create mode 100644 tests/__init__.py diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index 9fbb893c1c..fb412d571c 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -1,7 +1,7 @@ 2\u001b[0;31m \u001b[0mImage\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mfilename\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0;34m\"hoge.png\"\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0mwidth\u001b[0m\u001b[0;34m=\u001b[0m\u001b[0;36m600\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m", - "\u001b[0;32m~/.pyenv/versions/anaconda3-4.4.0/lib/python3.6/site-packages/IPython/core/display.py\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, data, url, filename, format, embed, width, height, retina, unconfined, metadata)\u001b[0m\n\u001b[1;32m 1149\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0munconfined\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0munconfined\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 1150\u001b[0m super(Image, self).__init__(data=data, url=url, filename=filename, \n\u001b[0;32m-> 1151\u001b[0;31m metadata=metadata)\n\u001b[0m\u001b[1;32m 1152\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 1153\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mwidth\u001b[0m \u001b[0;32mis\u001b[0m \u001b[0;32mNone\u001b[0m \u001b[0;32mand\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mmetadata\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mget\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m'width'\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0;34m{\u001b[0m\u001b[0;34m}\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;32m~/.pyenv/versions/anaconda3-4.4.0/lib/python3.6/site-packages/IPython/core/display.py\u001b[0m in \u001b[0;36m__init__\u001b[0;34m(self, data, url, filename, metadata)\u001b[0m\n\u001b[1;32m 607\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mmetadata\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0;34m{\u001b[0m\u001b[0;34m}\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 608\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 609\u001b[0;31m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mreload\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 610\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0m_check_data\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 611\u001b[0m \u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;32m~/.pyenv/versions/anaconda3-4.4.0/lib/python3.6/site-packages/IPython/core/display.py\u001b[0m in \u001b[0;36mreload\u001b[0;34m(self)\u001b[0m\n\u001b[1;32m 1180\u001b[0m \u001b[0;34m\"\"\"Reload the raw data from file or URL.\"\"\"\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 1181\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0membed\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m-> 1182\u001b[0;31m \u001b[0msuper\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mImage\u001b[0m\u001b[0;34m,\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mreload\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 1183\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mretina\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 1184\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0m_retina_shape\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;32m~/.pyenv/versions/anaconda3-4.4.0/lib/python3.6/site-packages/IPython/core/display.py\u001b[0m in \u001b[0;36mreload\u001b[0;34m(self)\u001b[0m\n\u001b[1;32m 632\u001b[0m \u001b[0;34m\"\"\"Reload the raw data from file or URL.\"\"\"\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 633\u001b[0m \u001b[0;32mif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mfilename\u001b[0m \u001b[0;32mis\u001b[0m \u001b[0;32mnot\u001b[0m \u001b[0;32mNone\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0;32m--> 634\u001b[0;31m \u001b[0;32mwith\u001b[0m \u001b[0mopen\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mfilename\u001b[0m\u001b[0;34m,\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0m_read_flags\u001b[0m\u001b[0;34m)\u001b[0m \u001b[0;32mas\u001b[0m \u001b[0mf\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[0m\u001b[1;32m 635\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mdata\u001b[0m \u001b[0;34m=\u001b[0m \u001b[0mf\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0mread\u001b[0m\u001b[0;34m(\u001b[0m\u001b[0;34m)\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n\u001b[1;32m 636\u001b[0m \u001b[0;32melif\u001b[0m \u001b[0mself\u001b[0m\u001b[0;34m.\u001b[0m\u001b[0murl\u001b[0m \u001b[0;32mis\u001b[0m \u001b[0;32mnot\u001b[0m \u001b[0;32mNone\u001b[0m\u001b[0;34m:\u001b[0m\u001b[0;34m\u001b[0m\u001b[0m\n", - "\u001b[0;31mFileNotFoundError\u001b[0m: [Errno 2] No such file or directory: 'hoge.png'" - ] - } - ], - "source": [ - "from IPython.display import Image\n", - "Image(filename=\"hoge.png\",width=600)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![gif](https://github.com/AtsushiSakai/PythonRobotics/raw/master/Localization/extended_kalman_filter/animation.gif)\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Section1" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Section2\n", - "\n", - "$\\begin{equation*}\n", - "F=\n", - "\\begin{bmatrix}\n", - "1 & 0 & 0 & 0\\\\\n", - "0 & 1 & 0 & 0\\\\\n", - "0 & 0 & 1 & 0 \\\\\n", - "0 & 0 & 0 & 0 \\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Ref" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.6" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} From 2fef7bc476929a62f304b8aeaebb2452659fb5c0 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 16 Nov 2021 23:06:25 +0900 Subject: [PATCH 412/940] clean up doc dir (#565) * clean up doc dir * clean up doc dir * clean up doc dir --- .circleci/config.yml | 2 +- docs/conf.py | 3 ++- docs/modules/path_planning/path_planning.rst | 2 +- .../cgmres_nmpc_files/cgmres_nmpc_1_0.png | Bin .../cgmres_nmpc_files/cgmres_nmpc_2_0.png | Bin .../cgmres_nmpc_files/cgmres_nmpc_3_0.png | Bin .../cgmres_nmpc_files/cgmres_nmpc_4_0.png | Bin 7 files changed, 4 insertions(+), 3 deletions(-) rename docs/modules/{ => path_tracking}/cgmres_nmpc_files/cgmres_nmpc_1_0.png (100%) rename docs/modules/{ => path_tracking}/cgmres_nmpc_files/cgmres_nmpc_2_0.png (100%) rename docs/modules/{ => path_tracking}/cgmres_nmpc_files/cgmres_nmpc_3_0.png (100%) rename docs/modules/{ => path_tracking}/cgmres_nmpc_files/cgmres_nmpc_4_0.png (100%) diff --git a/.circleci/config.yml b/.circleci/config.yml index 4cb628ecd8..4ced9fb90b 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -12,7 +12,7 @@ jobs: - python/load-cache - python/install-deps - python/save-cache - - run: pip install sphinx sphinx-autobuild sphinx-rtd-theme pytest + - run: pip install sphinx sphinx-autobuild sphinx-rtd-theme pytest IPython - run: command: cd docs;make html name: doc_build diff --git a/docs/conf.py b/docs/conf.py index 7422e2b106..64b32d5047 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -20,7 +20,7 @@ # -- Project information ----------------------------------------------------- project = 'PythonRobotics' -copyright = '2018, Atsushi Sakai' +copyright = '2018-2021, Atsushi Sakai' author = 'Atsushi Sakai' # The short X.Y version @@ -43,6 +43,7 @@ 'sphinx.ext.mathjax', 'sphinx.ext.viewcode', 'sphinx.ext.viewcode', + 'IPython.sphinxext.ipython_console_highlighting', ] # Add any paths that contain templates here, relative to this directory. diff --git a/docs/modules/path_planning/path_planning.rst b/docs/modules/path_planning/path_planning.rst index cfe7b6ad40..60651dd5ff 100644 --- a/docs/modules/path_planning/path_planning.rst +++ b/docs/modules/path_planning/path_planning.rst @@ -39,7 +39,7 @@ In the animation, cyan points are searched nodes. Its heuristic is 2D Euclid distance. -.. _a*-algorithm: +.. _D*-algorithm: D\* algorithm ~~~~~~~~~~~~~ diff --git a/docs/modules/cgmres_nmpc_files/cgmres_nmpc_1_0.png b/docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_1_0.png similarity index 100% rename from docs/modules/cgmres_nmpc_files/cgmres_nmpc_1_0.png rename to docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_1_0.png diff --git a/docs/modules/cgmres_nmpc_files/cgmres_nmpc_2_0.png b/docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_2_0.png similarity index 100% rename from docs/modules/cgmres_nmpc_files/cgmres_nmpc_2_0.png rename to docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_2_0.png diff --git a/docs/modules/cgmres_nmpc_files/cgmres_nmpc_3_0.png b/docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_3_0.png similarity index 100% rename from docs/modules/cgmres_nmpc_files/cgmres_nmpc_3_0.png rename to docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_3_0.png diff --git a/docs/modules/cgmres_nmpc_files/cgmres_nmpc_4_0.png b/docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_4_0.png similarity index 100% rename from docs/modules/cgmres_nmpc_files/cgmres_nmpc_4_0.png rename to docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_4_0.png From 7b0522b588301109cb0936e3412c36220ce70aff Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 16 Nov 2021 23:14:26 +0900 Subject: [PATCH 413/940] clean up doc system (#566) * clean up doc dir * clean up doc dir --- README.md | 1 - requirements.txt | 1 + 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index c9e45d9363..74c19d7a5e 100644 --- a/README.md +++ b/README.md @@ -8,7 +8,6 @@ [![Build status](https://ci.appveyor.com/api/projects/status/sb279kxuv1be391g?svg=true)](https://ci.appveyor.com/project/AtsushiSakai/pythonrobotics) [![codecov](https://codecov.io/gh/AtsushiSakai/PythonRobotics/branch/master/graph/badge.svg)](https://codecov.io/gh/AtsushiSakai/PythonRobotics) [![Language grade: Python](https://img.shields.io/lgtm/grade/python/g/AtsushiSakai/PythonRobotics.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/AtsushiSakai/PythonRobotics/context:python) -[![CodeFactor](https://www.codefactor.io/repository/github/atsushisakai/pythonrobotics/badge/master)](https://www.codefactor.io/repository/github/atsushisakai/pythonrobotics/overview/master) [![tokei](https://tokei.rs/b1/github/AtsushiSakai/PythonRobotics)](https://github.com/AtsushiSakai/PythonRobotics) Python codes for robotics algorithm. diff --git a/requirements.txt b/requirements.txt index 77a0bea427..7c60c4a24c 100644 --- a/requirements.txt +++ b/requirements.txt @@ -3,3 +3,4 @@ scipy == 1.7.2 pandas == 1.3.4 matplotlib == 3.4.3 cvxpy == 1.1.17 +IPython == 7.29.0 # For sphinx documentation From b812cb1fc9baf2197e7ff8d834d1187d012c7021 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 17 Nov 2021 19:42:14 +0900 Subject: [PATCH 414/940] clean up doc dir (#567) --- README.md | 2 +- requirements.txt | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 74c19d7a5e..5a06f09ca8 100644 --- a/README.md +++ b/README.md @@ -117,7 +117,7 @@ For development: - mypy (for type check) -- Sphinx (for document generation) +- sphinx (for document generation) - pycodestyle (for code style check) diff --git a/requirements.txt b/requirements.txt index 7c60c4a24c..dbe243878d 100644 --- a/requirements.txt +++ b/requirements.txt @@ -3,4 +3,7 @@ scipy == 1.7.2 pandas == 1.3.4 matplotlib == 3.4.3 cvxpy == 1.1.17 +pytest == 6.2.5 # For unit test +pytest-xdist == 2.4.0 # For unit test +sphinx == 4.3.0 # For sphinx documentation IPython == 7.29.0 # For sphinx documentation From 6f309828ba0e204833574b9f72f1c6ee6e74369f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 17 Nov 2021 20:04:09 +0900 Subject: [PATCH 415/940] clean up doc dir (#568) * clean up doc dir * clean up doc dir * clean up doc dir * clean up doc dir --- .circleci/config.yml | 2 +- requirements.txt | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index 4ced9fb90b..539c0eeac0 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -12,7 +12,7 @@ jobs: - python/load-cache - python/install-deps - python/save-cache - - run: pip install sphinx sphinx-autobuild sphinx-rtd-theme pytest IPython + - run: pip install -r requirements.txt - run: command: cd docs;make html name: doc_build diff --git a/requirements.txt b/requirements.txt index dbe243878d..e11ba13b8d 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,5 +5,6 @@ matplotlib == 3.4.3 cvxpy == 1.1.17 pytest == 6.2.5 # For unit test pytest-xdist == 2.4.0 # For unit test -sphinx == 4.3.0 # For sphinx documentation +sphinx < 4.0 # For sphinx documentation +sphinx_rtd_theme == 1.0.0 IPython == 7.29.0 # For sphinx documentation From 137e372db1fb6455cfe6fdce263d63e7dd8e259c Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 17 Nov 2021 22:58:23 +0900 Subject: [PATCH 416/940] fix CI (#569) * fix CI * fix CI * fix CI * fix CI * fix CI * fix CI * fix CI * fix CI --- .circleci/config.yml | 12 ++++++------ .github/workflows/Linux_CI.yml | 6 +++++- .github/workflows/MacOS_CI.yml | 7 ++++++- .github/workflows/codeql.yml | 4 ++-- appveyor.yml | 4 ++++ 5 files changed, 23 insertions(+), 10 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index 539c0eeac0..4866240bd4 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -1,7 +1,7 @@ version: 2.1 orbs: - python: circleci/python@0.2.1 + python: circleci/python@1.4.0 jobs: build_doc: @@ -9,13 +9,13 @@ jobs: - image: circleci/python:3.9 steps: - checkout - - python/load-cache - - python/install-deps - - python/save-cache - - run: pip install -r requirements.txt - run: - command: cd docs;make html name: doc_build + command: | + python -m venv venv + . venv/bin/activate + pip install -r requirements.txt + cd docs;make html - store_artifacts: path: docs/_build/html/ destination: html diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index 2962028d6f..4e2e57f8e4 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -1,6 +1,10 @@ name: Linux_CI -on: [push, pull_request] +on: + push: + branches: + - master + pull_request: jobs: build: diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index 6b3ffa2588..9bfb4b6fd3 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -4,7 +4,12 @@ name: MacOS_CI # Controls when the action will run. Triggers the workflow on push or pull request # events but only for the master branch -on: [push, pull_request] +on: + push: + branches: + - master + pull_request: + jobs: build: diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml index 5e6c03aa16..148260a835 100644 --- a/.github/workflows/codeql.yml +++ b/.github/workflows/codeql.yml @@ -2,8 +2,8 @@ name: "Code scanning - action" on: push: - branches-ignore: - - 'dependabot/**' + branches: + - master pull_request: schedule: - cron: '0 19 * * 0' diff --git a/appveyor.yml b/appveyor.yml index efbb96131c..16a5d7751d 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -10,6 +10,10 @@ environment: matrix: - PYTHON_DIR: C:\Python39-x64 +branches: + only: + - master + init: - "ECHO %PYTHON_DIR%" From 35984e8978cff3f71bcdff26aea235d3ea433ef0 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 18 Nov 2021 22:35:10 +0900 Subject: [PATCH 417/940] clean up localization docs (#570) * clean up localization docs * clean up localization docs * clean up localization docs --- Localization/Kalmanfilter_basics.ipynb | 769 ------------------ Localization/Kalmanfilter_basics_2.ipynb | 381 --------- Localization/bayes_filter.png | Bin 1088102 -> 0 bytes Localization/extended_kalman_filter/ekf.png | Bin 113010 -> 0 bytes .../extended_kalman_filter_localization.ipynb | 264 ------ .../particle_filter/particle_filter.ipynb | 72 -- docs/modules/appendix/Kalmanfilter_basics.rst | 8 +- .../extended_kalman_filter_localization.rst | 12 +- docs/modules/localization/localization.rst | 26 +- 9 files changed, 28 insertions(+), 1504 deletions(-) delete mode 100644 Localization/Kalmanfilter_basics.ipynb delete mode 100644 Localization/Kalmanfilter_basics_2.ipynb delete mode 100644 Localization/bayes_filter.png delete mode 100644 Localization/extended_kalman_filter/ekf.png delete mode 100644 Localization/extended_kalman_filter/extended_kalman_filter_localization.ipynb delete mode 100644 Localization/particle_filter/particle_filter.ipynb diff --git a/Localization/Kalmanfilter_basics.ipynb b/Localization/Kalmanfilter_basics.ipynb deleted file mode 100644 index c501b117de..0000000000 --- a/Localization/Kalmanfilter_basics.ipynb +++ /dev/null @@ -1,769 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## KF Basics - Part I\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Introduction\n", - "#### What is the need to describe belief in terms of PDF's?\n", - "This is because robot environments are stochastic. A robot environment may have cows with Tesla by side. That is a robot and it's environment cannot be deterministically modelled(e.g as a function of something like time t). In the real world sensors are also error prone, and hence there'll be a set of values with a mean and variance that it can take. Hence, we always have to model around some mean and variances associated." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### What is Expectation of a Random Variables?\n", - " Expectation is nothing but an average of the probabilites\n", - " \n", - "$$\\mathbb E[X] = \\sum_{i=1}^n p_ix_i$$\n", - "\n", - "In the continous form,\n", - "\n", - "$$\\mathbb E[X] = \\int_{-\\infty}^\\infty x\\, f(x) \\,dx$$\n" - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "1.4000000000000001\n" - ] - } - ], - "source": [ - "import numpy as np\n", - "import random\n", - "x=[3,1,2]\n", - "p=[0.1,0.3,0.4]\n", - "E_x=np.sum(np.multiply(x,p))\n", - "print(E_x)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### What is the advantage of representing the belief as a unimodal as opposed to multimodal?\n", - "Obviously, it makes sense because we can't multiple probabilities to a car moving for two locations. This would be too confusing and the information will not be useful." - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Variance, Covariance and Correlation\n", - "\n", - "#### Variance\n", - "Variance is the spread of the data. The mean does'nt tell much **about** the data. Therefore the variance tells us about the **story** about the data meaning the spread of the data.\n", - "\n", - "$$\\mathit{VAR}(X) = \\frac{1}{n}\\sum_{i=1}^n (x_i - \\mu)^2$$" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "1.0224618077401504" - ] - }, - "execution_count": 3, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "x=np.random.randn(10)\n", - "np.var(x)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### Covariance\n", - "\n", - "This is for a multivariate distribution. For example, a robot in 2-D space can take values in both x and y. To describe them, a normal distribution with mean in both x and y is needed.\n", - "\n", - "For a multivariate distribution, mean $\\mu$ can be represented as a matrix, \n", - "\n", - "$$\n", - "\\mu = \\begin{bmatrix}\\mu_1\\\\\\mu_2\\\\ \\vdots \\\\\\mu_n\\end{bmatrix}\n", - "$$\n", - "\n", - "\n", - "Similarly, variance can also be represented.\n", - "\n", - "But an important concept is that in the same way as every variable or dimension has a variation in its values, it is also possible that there will be values on how they **together vary**. This is also a measure of how two datasets are related to each other or **correlation**.\n", - "\n", - "For example, as height increases weight also generally increases. These variables are correlated. They are positively correlated because as one variable gets larger so does the other.\n", - "\n", - "We use a **covariance matrix** to denote covariances of a multivariate normal distribution:\n", - "$$\n", - "\\Sigma = \\begin{bmatrix}\n", - " \\sigma_1^2 & \\sigma_{12} & \\cdots & \\sigma_{1n} \\\\\n", - " \\sigma_{21} &\\sigma_2^2 & \\cdots & \\sigma_{2n} \\\\\n", - " \\vdots & \\vdots & \\ddots & \\vdots \\\\\n", - " \\sigma_{n1} & \\sigma_{n2} & \\cdots & \\sigma_n^2\n", - " \\end{bmatrix}\n", - "$$\n", - "\n", - "**Diagonal** - Variance of each variable associated. \n", - "\n", - "**Off-Diagonal** - covariance between ith and jth variables.\n", - "\n", - "$$\\begin{aligned}VAR(X) = \\sigma_x^2 &= \\frac{1}{n}\\sum_{i=1}^n(X - \\mu)^2\\\\\n", - "COV(X, Y) = \\sigma_{xy} &= \\frac{1}{n}\\sum_{i=1}^n[(X-\\mu_x)(Y-\\mu_y)\\big]\\end{aligned}$$" - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([[0.08868895, 0.05064471, 0.08855629],\n", - " [0.05064471, 0.06219243, 0.11555291],\n", - " [0.08855629, 0.11555291, 0.21534324]])" - ] - }, - "execution_count": 4, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "x=np.random.random((3,3))\n", - "np.cov(x)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Covariance taking the data as **sample** with $\\frac{1}{N-1}$" - ] - }, - { - "cell_type": "code", - "execution_count": 17, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([[ 0.1571437 , -0.00766623],\n", - " [-0.00766623, 0.13957621]])" - ] - }, - "execution_count": 17, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "x_cor=np.random.rand(1,10)\n", - "y_cor=np.random.rand(1,10)\n", - "np.cov(x_cor,y_cor)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Covariance taking the data as **population** with $\\frac{1}{N}$" - ] - }, - { - "cell_type": "code", - "execution_count": 18, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([[ 0.14142933, -0.0068996 ],\n", - " [-0.0068996 , 0.12561859]])" - ] - }, - "execution_count": 18, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "np.cov(x_cor,y_cor,bias=1)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Gaussians \n", - "\n", - "#### Central Limit Theorem\n", - "\n", - "According to this theorem, the average of n samples of random and independent variables tends to follow a normal distribution as we increase the sample size.(Generally, for n>=30)" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "(array([ 1., 4., 9., 12., 12., 20., 16., 16., 4., 6.]),\n", - " array([5.30943011, 5.34638597, 5.38334183, 5.42029769, 5.45725355,\n", - " 5.49420941, 5.53116527, 5.56812114, 5.605077 , 5.64203286,\n", - " 5.67898872]),\n", - "
)" - ] - }, - "execution_count": 5, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "

" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "import matplotlib.pyplot as plt\n", - "import random\n", - "a=np.zeros((100,))\n", - "for i in range(100):\n", - " x=[random.uniform(1,10) for _ in range(1000)]\n", - " a[i]=np.sum(x,axis=0)/1000\n", - "plt.hist(a)" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### Gaussian Distribution\n", - "A Gaussian is a *continuous probability distribution* that is completely described with two parameters, the mean ($\\mu$) and the variance ($\\sigma^2$). It is defined as:\n", - "\n", - "$$ \n", - "f(x, \\mu, \\sigma) = \\frac{1}{\\sigma\\sqrt{2\\pi}} \\exp\\big [{-\\frac{(x-\\mu)^2}{2\\sigma^2} }\\big ]\n", - "$$\n", - "Range is $$[-\\inf,\\inf] $$\n", - "\n", - "\n", - "This is just a function of mean($\\mu$) and standard deviation ($\\sigma$) and what gives the normal distribution the charecteristic **bell curve**. " - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "import matplotlib.mlab as mlab\n", - "import math\n", - "import scipy.stats\n", - "\n", - "mu = 0\n", - "variance = 5\n", - "sigma = math.sqrt(variance)\n", - "x = np.linspace(mu - 5*sigma, mu + 5*sigma, 100)\n", - "plt.plot(x,scipy.stats.norm.pdf(x, mu, sigma))\n", - "plt.show()\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### Why do we need Gaussian distributions?\n", - "Since it becomes really difficult in the real world to deal with multimodal distribution as we cannot put the belief in two seperate location of the robots. This becomes really confusing and in practice impossible to comprehend. \n", - "Gaussian probability distribution allows us to drive the robots using only one mode with peak at the mean with some variance." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Gaussian Properties\n", - "\n", - "**Multiplication**\n", - "\n", - "\n", - "For the measurement update in a Bayes Filter, the algorithm tells us to multiply the Prior P(X_t) and measurement P(Z_t|X_t) to calculate the posterior:\n", - "\n", - "$$P(X \\mid Z) = \\frac{P(Z \\mid X)P(X)}{P(Z)}$$\n", - "\n", - "Here for the numerator, $P(Z \\mid X),P(X)$ both are gaussian.\n", - "\n", - "$N(\\mu_1, \\sigma_1^2)$ and $N(\\mu_2, \\sigma_2^2)$ are their mean and variances.\n", - "\n", - "New mean is \n", - "\n", - "$$\\mu_\\mathtt{new} = \\frac{\\mu_1 \\sigma_2^2 + \\mu_2 \\sigma_1^2}{\\sigma_1^2+\\sigma_2^2}$$\n", - "New variance is\n", - "$$\\sigma_\\mathtt{new} = \\frac{\\sigma_1^2\\sigma_2^2}{\\sigma_1^2+\\sigma_2^2}$$" - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "New mean is at: 5.0\n", - "New variance is: 1.0\n" - ] - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "import matplotlib.mlab as mlab\n", - "import math\n", - "mu1 = 0\n", - "variance1 = 2\n", - "sigma = math.sqrt(variance1)\n", - "x1 = np.linspace(mu1 - 3*sigma, mu1 + 3*sigma, 100)\n", - "plt.plot(x1,scipy.stats.norm.pdf(x1, mu1, sigma),label='prior')\n", - "\n", - "mu2 = 10\n", - "variance2 = 2\n", - "sigma = math.sqrt(variance2)\n", - "x2 = np.linspace(mu2 - 3*sigma, mu2 + 3*sigma, 100)\n", - "plt.plot(x2,scipy.stats.norm.pdf(x2, mu2, sigma),\"g-\",label='measurement')\n", - "\n", - "\n", - "mu_new=(mu1*variance2+mu2*variance1)/(variance1+variance2)\n", - "print(\"New mean is at: \",mu_new)\n", - "var_new=(variance1*variance2)/(variance1+variance2)\n", - "print(\"New variance is: \",var_new)\n", - "sigma = math.sqrt(var_new)\n", - "x3 = np.linspace(mu_new - 3*sigma, mu_new + 3*sigma, 100)\n", - "plt.plot(x3,scipy.stats.norm.pdf(x3, mu_new, var_new),label=\"posterior\")\n", - "plt.legend(loc='upper left')\n", - "plt.xlim(-10,20)\n", - "plt.show()\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "**Addition**\n", - "\n", - "The motion step involves a case of adding up probability (Since it has to abide the Law of Total Probability). This means their beliefs are to be added and hence two gaussians. They are simply arithmetic additions of the two.\n", - "\n", - "$$\\begin{gathered}\\mu_x = \\mu_p + \\mu_z \\\\\n", - "\\sigma_x^2 = \\sigma_z^2+\\sigma_p^2\\, \\square\\end{gathered}$$" - ] - }, - { - "cell_type": "code", - "execution_count": 10, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "New mean is at: 15\n", - "New variance is: 2\n" - ] - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "import matplotlib.mlab as mlab\n", - "import math\n", - "mu1 = 5\n", - "variance1 = 1\n", - "sigma = math.sqrt(variance1)\n", - "x1 = np.linspace(mu1 - 3*sigma, mu1 + 3*sigma, 100)\n", - "plt.plot(x1,scipy.stats.norm.pdf(x1, mu1, sigma),label='prior')\n", - "\n", - "mu2 = 10\n", - "variance2 = 1\n", - "sigma = math.sqrt(variance2)\n", - "x2 = np.linspace(mu2 - 3*sigma, mu2 + 3*sigma, 100)\n", - "plt.plot(x2,scipy.stats.norm.pdf(x2, mu2, sigma),\"g-\",label='measurement')\n", - "\n", - "\n", - "mu_new=mu1+mu2\n", - "print(\"New mean is at: \",mu_new)\n", - "var_new=(variance1+variance2)\n", - "print(\"New variance is: \",var_new)\n", - "sigma = math.sqrt(var_new)\n", - "x3 = np.linspace(mu_new - 3*sigma, mu_new + 3*sigma, 100)\n", - "plt.plot(x3,scipy.stats.norm.pdf(x3, mu_new, var_new),label=\"posterior\")\n", - "plt.legend(loc='upper left')\n", - "plt.xlim(-10,20)\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": 188, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "#Example from:\n", - "#https://scipython.com/blog/visualizing-the-bivariate-gaussian-distribution/\n", - "import numpy as np\n", - "import matplotlib.pyplot as plt\n", - "from matplotlib import cm\n", - "from mpl_toolkits.mplot3d import Axes3D\n", - "\n", - "# Our 2-dimensional distribution will be over variables X and Y\n", - "N = 60\n", - "X = np.linspace(-3, 3, N)\n", - "Y = np.linspace(-3, 4, N)\n", - "X, Y = np.meshgrid(X, Y)\n", - "\n", - "# Mean vector and covariance matrix\n", - "mu = np.array([0., 1.])\n", - "Sigma = np.array([[ 1. , -0.5], [-0.5, 1.5]])\n", - "\n", - "# Pack X and Y into a single 3-dimensional array\n", - "pos = np.empty(X.shape + (2,))\n", - "pos[:, :, 0] = X\n", - "pos[:, :, 1] = Y\n", - "\n", - "def multivariate_gaussian(pos, mu, Sigma):\n", - " \"\"\"Return the multivariate Gaussian distribution on array pos.\n", - "\n", - " pos is an array constructed by packing the meshed arrays of variables\n", - " x_1, x_2, x_3, ..., x_k into its _last_ dimension.\n", - "\n", - " \"\"\"\n", - "\n", - " n = mu.shape[0]\n", - " Sigma_det = np.linalg.det(Sigma)\n", - " Sigma_inv = np.linalg.inv(Sigma)\n", - " N = np.sqrt((2*np.pi)**n * Sigma_det)\n", - " # This einsum call calculates (x-mu)T.Sigma-1.(x-mu) in a vectorized\n", - " # way across all the input variables.\n", - " fac = np.einsum('...k,kl,...l->...', pos-mu, Sigma_inv, pos-mu)\n", - "\n", - " return np.exp(-fac / 2) / N\n", - "\n", - "# The distribution on the variables X, Y packed into pos.\n", - "Z = multivariate_gaussian(pos, mu, Sigma)\n", - "\n", - "# Create a surface plot and projected filled contour plot under it.\n", - "fig = plt.figure()\n", - "ax = fig.gca(projection='3d')\n", - "ax.plot_surface(X, Y, Z, rstride=3, cstride=3, linewidth=1, antialiased=True,\n", - " cmap=cm.viridis)\n", - "\n", - "cset = ax.contourf(X, Y, Z, zdir='z', offset=-0.15, cmap=cm.viridis)\n", - "\n", - "# Adjust the limits, ticks and view angle\n", - "ax.set_zlim(-0.15,0.2)\n", - "ax.set_zticks(np.linspace(0,0.2,5))\n", - "ax.view_init(27, -21)\n", - "\n", - "plt.show()\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "This is a 3D projection of the gaussians involved with the lower surface showing the 2D projection of the 3D projection above. The innermost ellipse represents the highest peak, that is the maximum probability for a given (X,Y) value.\n", - "\n", - "\n", - "\n", - "\n", - "** numpy einsum examples **" - ] - }, - { - "cell_type": "code", - "execution_count": 175, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "[[ 0 1 2 3 4]\n", - " [ 5 6 7 8 9]\n", - " [10 11 12 13 14]\n", - " [15 16 17 18 19]\n", - " [20 21 22 23 24]]\n", - "[0 1 2 3 4]\n", - "[[0 1 2]\n", - " [3 4 5]]\n" - ] - } - ], - "source": [ - "a = np.arange(25).reshape(5,5)\n", - "b = np.arange(5)\n", - "c = np.arange(6).reshape(2,3)\n", - "print(a)\n", - "print(b)\n", - "print(c)\n" - ] - }, - { - "cell_type": "code", - "execution_count": 204, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([ 30, 80, 130, 180, 230])" - ] - }, - "execution_count": 204, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "#this is the diagonal sum, i repeated means the diagonal\n", - "np.einsum('ij', a)\n", - "#this takes the output ii which is the diagonal and outputs to a\n", - "np.einsum('ii->i',a)\n", - "#this takes in the array A represented by their axes 'ij' and B by its only axes'j' \n", - "#and multiples them element wise\n", - "np.einsum('ij,j',a, b)" - ] - }, - { - "cell_type": "code", - "execution_count": 199, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([ 0, 22, 76])" - ] - }, - "execution_count": 199, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "A = np.arange(3).reshape(3,1)\n", - "B = np.array([[ 0, 1, 2, 3],\n", - " [ 4, 5, 6, 7],\n", - " [ 8, 9, 10, 11]])\n", - "C=np.multiply(A,B)\n", - "np.sum(C,axis=1)" - ] - }, - { - "cell_type": "code", - "execution_count": 197, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "array([ 0, 22, 76])" - ] - }, - "execution_count": 197, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "D = np.array([0,1,2])\n", - "E = np.array([[ 0, 1, 2, 3],\n", - " [ 4, 5, 6, 7],\n", - " [ 8, 9, 10, 11]])\n", - "\n", - "np.einsum('i,ij->i',D,E)" - ] - }, - { - "cell_type": "code", - "execution_count": 238, - "metadata": {}, - "outputs": [ - { - "data": { - "text/plain": [ - "" - ] - }, - "execution_count": 238, - "metadata": {}, - "output_type": "execute_result" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "from scipy.stats import multivariate_normal\n", - "x, y = np.mgrid[-5:5:.1, -5:5:.1]\n", - "pos = np.empty(x.shape + (2,))\n", - "pos[:, :, 0] = x; pos[:, :, 1] = y\n", - "rv = multivariate_normal([0.5, -0.2], [[2.0, 0.9], [0.9, 0.5]])\n", - "plt.contourf(x, y, rv.pdf(pos))\n", - "\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### References:\n", - "\n", - "1. Roger Labbe's [repo](https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python) on Kalman Filters. (Majority of the examples in the notes are from this)\n", - "\n", - "\n", - "\n", - "2. Probabilistic Robotics by Sebastian Thrun, Wolfram Burgard and Dieter Fox, MIT Press.\n", - "\n", - "\n", - "\n", - "3. Scipy [Documentation](https://scipython.com/blog/visualizing-the-bivariate-gaussian-distribution/)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.6" - }, - "pycharm": { - "stem_cell": { - "cell_type": "raw", - "source": [], - "metadata": { - "collapsed": false - } - } - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} \ No newline at end of file diff --git a/Localization/Kalmanfilter_basics_2.ipynb b/Localization/Kalmanfilter_basics_2.ipynb deleted file mode 100644 index 43f34ec6f2..0000000000 --- a/Localization/Kalmanfilter_basics_2.ipynb +++ /dev/null @@ -1,381 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## KF Basics - Part 2\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Probabilistic Generative Laws\n", - " \n", - "#### 1st Law:\n", - "The belief representing the state $x_{t}$, is conditioned on all past states, measurements and controls. This can be shown mathematically by the conditional probability shown below:\n", - "\n", - "$$p(x_{t} | x_{0:t-1},z_{1:t-1},u_{1:t})$$\n", - "\n", - "1) $z_{t}$ represents the **measurement**\n", - "\n", - "2) $u_{t}$ the **motion command**\n", - "\n", - "3) $x_{t}$ the **state** (can be the position, velocity, etc) of the robot or its environment at time t.\n", - "\n", - "\n", - "'If we know the state $x_{t-1}$ and $u_{t}$, then knowing the states $x_{0:t-2}$, $z_{1:t-1}$ becomes immaterial through the property of **conditional independence**'. The state $x_{t-1}$ introduces a conditional independence between $x_{t}$ and $z_{1:t-1}$, $u_{1:t-1}$\n", - "\n", - "Therefore the law now holds as:\n", - "\n", - "$$p(x_{t} | x_{0:t-1},z_{1:t-1},u_{1:t})=p(x_{t} | x_{t-1},u_{t})$$\n", - "\n", - "#### 2nd Law:\n", - "\n", - "If $x_{t}$ is complete, then:\n", - "\n", - "$$p(z_{t} | x_{0:t},z_{1:t-1},u_{1:t})=p(z_{t} | x_{t})$$\n", - "\n", - "$x_{t}$ is **complete** means that the past states, controls or measurements carry no additional information to predict future.\n", - "\n", - "$x_{0:t-1}$, $z_{1:t-1}$ and $u_{1:t}$ are **conditionally independent** of $z_{t}$ given $x_{t}$ of complete.\n", - "\n", - "The filter works in two parts:\n", - "\n", - "$p(x_{t} | x_{t-1},u_{t})$ -> **State Transition Probability**\n", - "\n", - "$p(z_{t} | x_{t})$ -> **Measurement Probability**\n", - "\n", - "\n", - "### Conditional dependence and independence example:\n", - "\n", - "\n", - "$\\bullet$**Independent but conditionally dependent**\n", - "\n", - "Let's say you flip two fair coins\n", - "\n", - "A - Your first coin flip is heads\n", - "\n", - "B - Your second coin flip is heads\n", - "\n", - "C - Your first two flips were the same\n", - "\n", - "\n", - "A and B here are independent. However, A and B are conditionally dependent given C, since if you know C then your first coin flip will inform the other one.\n", - "\n", - "$\\bullet$**Dependent but conditionally independent**\n", - "\n", - "A box contains two coins: a regular coin and one fake two-headed coin ((P(H)=1). I choose a coin at random and toss it twice. Define the following events.\n", - "\n", - "A= First coin toss results in an H.\n", - "\n", - "B= Second coin toss results in an H.\n", - "\n", - "C= Coin 1 (regular) has been selected. \n", - "\n", - "If we know A has occurred (i.e., the first coin toss has resulted in heads), we would guess that it is more likely that we have chosen Coin 2 than Coin 1. This in turn increases the conditional probability that B occurs. This suggests that A and B are not independent. On the other hand, given C (Coin 1 is selected), A and B are independent.\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Bayes Rule:\n", - "\n", - "\n", - "Posterior = $$\\frac{Likelihood*Prior}{Marginal} $$\n", - "\n", - "Here,\n", - "\n", - "**Posterior** = Probability of an event occurring based on certain evidence.\n", - "\n", - "**Likelihood** = How probable is the evidence given the event.\n", - "\n", - "**Prior** = Probability of the just the event occurring without having any evidence.\n", - "\n", - "**Marginal** = Probability of the evidence given all the instances of events possible.\n", - "\n", - "\n", - "\n", - "Example:\n", - "\n", - "1% of women have breast cancer (and therefore 99% do not).\n", - "80% of mammograms detect breast cancer when it is there (and therefore 20% miss it).\n", - "9.6% of mammograms detect breast cancer when its not there (and therefore 90.4% correctly return a negative result).\n", - "\n", - "We can turn the process above into an equation, which is Bayes Theorem. Here is the equation:\n", - "\n", - "$\\displaystyle{\\Pr(\\mathrm{A}|\\mathrm{X}) = \\frac{\\Pr(\\mathrm{X}|\\mathrm{A})\\Pr(\\mathrm{A})}{\\Pr(\\mathrm{X|A})\\Pr(\\mathrm{A})+ \\Pr(\\mathrm{X | not \\ A})\\Pr(\\mathrm{not \\ A})}}$\n", - "\n", - "\n", - "$\\bullet$Pr(A|X) = Chance of having cancer (A) given a positive test (X). This is what we want to know: How likely is it to have cancer with a positive result? In our case it was 7.8%.\n", - "\n", - "$\\bullet$Pr(X|A) = Chance of a positive test (X) given that you had cancer (A). This is the chance of a true positive, 80% in our case.\n", - "\n", - "$\\bullet$Pr(A) = Chance of having cancer (1%).\n", - "\n", - "$\\bullet$Pr(not A) = Chance of not having cancer (99%).\n", - "\n", - "$\\bullet$Pr(X|not A) = Chance of a positive test (X) given that you didn't have cancer (~A). This is a false positive, 9.6% in our case.\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Bayes Filter Algorithm\n", - "\n", - "The basic filter algorithm is:\n", - "\n", - "for all $x_{t}$:\n", - "\n", - "1. $\\overline{bel}(x_t) = \\int p(x_t | u_t, x_{t-1}) bel(x_{t-1})dx$\n", - "\n", - "2. $bel(x_t) = \\eta p(z_t | x_t) \\overline{bel}(x_t)$\n", - "\n", - "end.\n", - "\n", - "\n", - "$\\rightarrow$The first step in filter is to calculate the prior for the next step that uses the bayes theorem. This is the **Prediction** step. The belief, $\\overline{bel}(x_t)$, is **before** incorporating measurement($z_{t}$) at time t=t. This is the step where the motion occurs and information is lost because the means and covariances of the gaussians are added. The RHS of the equation incorporates the law of total probability for prior calculation.\n", - "\n", - "$\\rightarrow$ This is the **Correction** or update step that calculates the belief of the robot **after** taking into account the measurement($z_{t}$) at time t=t. This is where we incorporate the sensor information for the whereabouts of the robot. We gain information here as the gaussians get multiplied here. (Multiplication of gaussian values allows the resultant to lie in between these numbers and the resultant covariance is smaller.\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Bayes filter localization example:" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "" - ] - }, - "execution_count": 3, - "metadata": { - "image/png": { - "width": 400 - } - }, - "output_type": "execute_result" - } - ], - "source": [ - "from IPython.display import Image\n", - "Image(filename=\"bayes_filter.png\",width=400)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "\n", - "Given - A robot with a sensor to detect doorways along a hallway. Also, the robot knows how the hallway looks like but doesn't know where it is in the map. \n", - "\n", - "\n", - "1. Initially(first scenario), it doesn't know where it is with respect to the map and hence the belief assigns equal probability to each location in the map.\n", - "\n", - "\n", - "2. The first sensor reading is incorporated and it shows the presence of a door. Now the robot knows how the map looks like but cannot localize yet as map has 3 doors present. Therefore it assigns equal probability to each door present. \n", - "\n", - "\n", - "3. The robot now moves forward. This is the prediction step and the motion causes the robot to lose some of the information and hence the variance of the gaussians increase (diagram 4.). The final belief is **convolution** of posterior from previous step and the current state after motion. Also, the means shift on the right due to the motion.\n", - "\n", - "\n", - "4. Again, incorporating the measurement, the sensor senses a door and this time too the possibility of door is equal for the three door. This is where the filter's magic kicks in. For the final belief (diagram 5.), the posterior calculated after sensing is mixed or **convolution** of previous posterior and measurement. It improves the robot's belief at location near to the second door. The variance **decreases** and **peaks**.\n", - "\n", - "\n", - "5. Finally after series of iterations of motion and correction, the robot is able to localize itself with respect to the environment.(diagram 6.)\n", - "\n", - "Do note that the robot knows the map but doesn't know where exactly it is on the map." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Bayes and Kalman filter structure\n", - "\n", - "The basic structure and the concept remains the same as bayes filter for Kalman. The only key difference is the mathematical representation of Kalman filter. The Kalman filter is nothing but a bayesian filter that uses Gaussians.\n", - "\n", - "For a bayes filter to be a Kalman filter, **each term of belief is now a gaussian**, unlike histograms. The basic formulation for the **bayes filter** algorithm is:\n", - "\n", - "$$\\begin{aligned} \n", - "\\bar {\\mathbf x} &= \\mathbf x \\ast f_{\\mathbf x}(\\bullet)\\, \\, &\\text{Prediction} \\\\\n", - "\\mathbf x &= \\mathcal L \\cdot \\bar{\\mathbf x}\\, \\, &\\text{Correction}\n", - "\\end{aligned}$$\n", - "\n", - "\n", - "$\\bar{\\mathbf x}$ is the *prior* \n", - "\n", - "$\\mathcal L$ is the *likelihood* of a measurement given the prior $\\bar{\\mathbf x}$\n", - "\n", - "$f_{\\mathbf x}(\\bullet)$ is the *process model* or the gaussian term that helps predict the next state like velocity\n", - "to track position or acceleration.\n", - "\n", - "$\\ast$ denotes *convolution*.\n", - "\n", - "\n", - "\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Kalman Gain\n", - "\n", - "\n", - "$$ x = (\\mathcal L \\bar x)$$\n", - "\n", - "Where x is posterior and $\\mathcal L$ and $\\bar x$ are gaussians.\n", - "\n", - "Therefore the mean of the posterior is given by:\n", - "\n", - "$$\n", - "\\mu=\\frac{\\bar\\sigma^2\\, \\mu_z + \\sigma_z^2 \\, \\bar\\mu} {\\bar\\sigma^2 + \\sigma_z^2}\n", - "$$\n", - "\n", - "\n", - "$$\\mu = \\left( \\frac{\\bar\\sigma^2}{\\bar\\sigma^2 + \\sigma_z^2}\\right) \\mu_z + \\left(\\frac{\\sigma_z^2}{\\bar\\sigma^2 + \\sigma_z^2}\\right)\\bar\\mu$$\n", - "\n", - "In this form it is easy to see that we are scaling the measurement and the prior by weights: \n", - "\n", - "$$\\mu = W_1 \\mu_z + W_2 \\bar\\mu$$\n", - "\n", - "\n", - "The weights sum to one because the denominator is a normalization term. We introduce a new term, $K=W_1$, giving us:\n", - "\n", - "$$\\begin{aligned}\n", - "\\mu &= K \\mu_z + (1-K) \\bar\\mu\\\\\n", - "&= \\bar\\mu + K(\\mu_z - \\bar\\mu)\n", - "\\end{aligned}$$\n", - "\n", - "where\n", - "\n", - "$$K = \\frac {\\bar\\sigma^2}{\\bar\\sigma^2 + \\sigma_z^2}$$\n", - "\n", - "The variance in terms of the Kalman gain:\n", - "\n", - "$$\\begin{aligned}\n", - "\\sigma^2 &= \\frac{\\bar\\sigma^2 \\sigma_z^2 } {\\bar\\sigma^2 + \\sigma_z^2} \\\\\n", - "&= K\\sigma_z^2 \\\\\n", - "&= (1-K)\\bar\\sigma^2 \n", - "\\end{aligned}$$\n", - "\n", - "\n", - "$K$ is the *Kalman gain*. It's the crux of the Kalman filter. It is a scaling term that chooses a value partway between $\\mu_z$ and $\\bar\\mu$." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Kalman Filter - Univariate and Multivariate\n", - "\n", - "\n", - "**Prediction**\n", - "\n", - "$\\begin{array}{|l|l|l|}\n", - "\\hline\n", - "\\text{Univariate} & \\text{Univariate} & \\text{Multivariate}\\\\\n", - "& \\text{(Kalman form)} & \\\\\n", - "\\hline\n", - "\\bar \\mu = \\mu + \\mu_{f_x} & \\bar x = x + dx & \\bar{\\mathbf x} = \\mathbf{Fx} + \\mathbf{Bu}\\\\\n", - "\\bar\\sigma^2 = \\sigma_x^2 + \\sigma_{f_x}^2 & \\bar P = P + Q & \\bar{\\mathbf P} = \\mathbf{FPF}^\\mathsf T + \\mathbf Q \\\\\n", - "\\hline\n", - "\\end{array}$\n", - "\n", - "$\\mathbf x,\\, \\mathbf P$ are the state mean and covariance. They correspond to $x$ and $\\sigma^2$.\n", - "\n", - "$\\mathbf F$ is the *state transition function*. When multiplied by $\\bf x$ it computes the prior. \n", - "\n", - "$\\mathbf Q$ is the process covariance. It corresponds to $\\sigma^2_{f_x}$.\n", - "\n", - "$\\mathbf B$ and $\\mathbf u$ are model control inputs to the system.\n", - "\n", - "**Correction**\n", - "\n", - "$\\begin{array}{|l|l|l|}\n", - "\\hline\n", - "\\text{Univariate} & \\text{Univariate} & \\text{Multivariate}\\\\\n", - "& \\text{(Kalman form)} & \\\\\n", - "\\hline\n", - "& y = z - \\bar x & \\mathbf y = \\mathbf z - \\mathbf{H\\bar x} \\\\\n", - "& K = \\frac{\\bar P}{\\bar P+R}&\n", - "\\mathbf K = \\mathbf{\\bar{P}H}^\\mathsf T (\\mathbf{H\\bar{P}H}^\\mathsf T + \\mathbf R)^{-1} \\\\\n", - "\\mu=\\frac{\\bar\\sigma^2\\, \\mu_z + \\sigma_z^2 \\, \\bar\\mu} {\\bar\\sigma^2 + \\sigma_z^2} & x = \\bar x + Ky & \\mathbf x = \\bar{\\mathbf x} + \\mathbf{Ky} \\\\\n", - "\\sigma^2 = \\frac{\\sigma_1^2\\sigma_2^2}{\\sigma_1^2+\\sigma_2^2} & P = (1-K)\\bar P &\n", - "\\mathbf P = (\\mathbf I - \\mathbf{KH})\\mathbf{\\bar{P}} \\\\\n", - "\\hline\n", - "\\end{array}$\n", - "\n", - "$\\mathbf H$ is the measurement function.\n", - "\n", - "$\\mathbf z,\\, \\mathbf R$ are the measurement mean and noise covariance. They correspond to $z$ and $\\sigma_z^2$ in the univariate filter. \n", - "$\\mathbf y$ and $\\mathbf K$ are the residual and Kalman gain. \n", - "\n", - "The details will be different than the univariate filter because these are vectors and matrices, but the concepts are exactly the same: \n", - "\n", - "- Use a Gaussian to represent our estimate of the state and error\n", - "- Use a Gaussian to represent the measurement and its error\n", - "- Use a Gaussian to represent the process model\n", - "- Use the process model to predict the next state (the prior)\n", - "- Form an estimate part way between the measurement and the prior" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### References:\n", - "\n", - "1. Roger Labbe's [repo](https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python) on Kalman Filters. (Majority of text in the notes are from this)\n", - "\n", - "\n", - "\n", - "2. Probabilistic Robotics by Sebastian Thrun, Wolfram Burgard and Dieter Fox, MIT Press.\n" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.6" - }, - "pycharm": { - "stem_cell": { - "cell_type": "raw", - "source": [], - "metadata": { - "collapsed": false - } - } - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} \ No newline at end of file diff --git a/Localization/bayes_filter.png b/Localization/bayes_filter.png deleted file mode 100644 index 50e509bdac47d79a9db7429fe4d770dc80c53378..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 1088102 zcmZU(1yCH(vp2ffq6;A;xCIF=!QI^hAwY0h+;?&J1SiM_hXBFd9YSz|yW8Tfi@*Hu zz3=<(t2b3M-P7H_?&&ktb|mZsKlb+WXv2Lk{K-;!bIpR^Q-`gfD*=;-Ps7&WDweqJ&2)&Y<;(a7Fm z(j^h2NcP6EGB*)^lBxb#N)uUu7B4HyI!}n^W5`;>cxcugKE%(IbLbEEz0L4C^*CvT z>;~+%^IHJ{*SfK~86mcSc$Oj9pD?r!{e}5lig-xKoDyiLCSw~r-%!lW^8j_Z4{OIO zZp5JD$Pm^!@$46!sqOR2CIEGH{FIm1vcW(EplhYsOi>IFYP83noy8HZ63QIZfQl7r z|87eK&1Xo!u>0f1k5B=^Z63gzBPI4Ii3uQ3(<@_LVIVyI zZ~nr!Af=lvg>64mku>HJD+WeAx>VA_kvPI{u0QjVygp+ij^3^Q9mD=c6*>4Syyjhx z$Jd58Sg*go6`B}E`<-t+U>kqB1MZh+eh}k$Q}r{#jBZjO)e@3&`Z6vusAaP8O-_{o*b;dv^Hb8blL>DlGjyC=Ro-b_@ z3dFgaLiUQYKSOn8cMN>k5c7P~2JG62_SrO&e)@4Bo%dS$Yxf^#GsX#bU38+7(I8di z(3d_U%u`?8OqD3>qHw1>40Q~O(1=jGQ1;(!@u-x;wTyYcFrw(h8Lfh=bFeM3wLin2 z{oI<~emV|E-{{Z~pN{2rMp+MR{jG%T5}=z-cI98GAyjs}WWWqbpcrJ-gON)#+(jVk zQLO0{U6n2rH#4~v;B~UhI#0*x>8|}H#apEfi2g%pj$X}ogzAoK*GCE<5RT!erRv*Z?1v4ki4W|K4ZxmQ%ZfKsUz`4-&L+Xo zu@g&V+l(b0gt|k6ON;D}by(S)h%b04Ofz0~^!EUPr)}Nc-8)Vlj7=$&Ss*~cOZpgT z1sM-Az-rgI;5%{{9?TFU5P5nd`zK!X#v&Mn#T9tcg^n8d>J^fi1hN8B;zkCx1p6mZ ziV+~T1STU2OBZPsr9E(|i@l17901B8$pBb&p*fQnpm?k|PJ)aA#m;bXs4=9ZtT8Ai zq((W%1IYZhT`-q zNm=b)nO;5mPxRWd`I`Bfxi$LmA4-KoTFFQ?z=iKesm7D4d98fVPHF*S0i^)t%`4=R`|xAPNT1T6stkXL{~G))NNeRCvk{x3vC*>$ zvp%njtZ%T%oc5OK-`jx_W-1#itf`5sp3c6v)wipyudN%dyR~h!yWO|mZ#tmc9~m#6 z6fBwQ?IQk+!$%uYo#7Jbl6kH;r@*fPt8A5NRBP0_ZC}M`2Z(kU6|ai5+j(bSrQW~0 zU$|$vCc8Q%SqHiUw{U)u*>edvj0;QogpOgHe4WHcms{qO0UhIP;aHJ4a<^H}J6YJj zv83bsVg;Qnn)_i&Zju3RTSWYDiNjp^GbUqQv$)+f2>FG}9iQ4$W|3uflS-Nvp01?Y znAVVv`$I3CKJ9JlF?Xw#+J{@7F-~KLRohi7Q?n1VW(~6Cy$;GX1%(A&uI1o#xDSh6 zsYR*mXVB-dvg@*i*|6FASq}$mzGuEE`x1wW#n%p^4z&*ai$)F7$IJf;T-zOX^wGz| zC-+J2AvPg2!H8Ctwp4!AIY$Up=#9X%kO*-v@mt;!>rXvJusk-o!dN507KbYxdH#O# z{^MAWjJgb(jL3|%3?tzsK}cq4MrF&mft2A+GfzvKYrO}&)zP(mU(SQJG#F)DLAs+(Wy z!|(5nEhW9B8)b5IH_#Um^;dd4L3m(FVh$6W&@Iv_5$GpQC%%6_L)Wg3tH!Q=LMrb4 zm~l>|iK7|H6jPi(oj*-c{6rx2zASZIbi%=G@Xujl8N=TnP{*3??TkVB!Xotz6~P~J z3d(9rnK!8fJ;gg$g|$=s`L`~5%k|4dZGcr1m$AmX zy|*=?hhdd9ziaud+Q(uCS5rlQBxcld=+N`C-F{V2PGS?{o$)+~E~YT^arxF{mv&pn zJ9ST&@SVa-VKu+4&)1=8u!FHa;hD})V_io>`^?mP@+yRz$Lg!4L52-KWN@S~EH|uk zx(d}c^T`Qpmp#=w`eW1FiZSVN^c9?3f zT<>KR)zh0BEr)MkzU6QC(PYb}6KzF>MJ>UaSoIpW?U*XBd{fQ!WEXY|mJ4|v^M($*4xUWnWNL8INTGC`e*d>Q2zF3!U~q7H=)HucQ2>R9+Vr!dqc;KkFwKvqTAQ4OYq8 z8mmWh9S_C&I%=LwI-xI@##8?7{?r!|hmvC zC+PNmt(DYRhCQ~uu>b6>{iWb3M1IsK%c*JIKll0PQg2UZ>yv-eN_+eB_x^&uVIx?& zP#={1@aj~=g&r}KT6$DUR3U48*p%h@v=j4;g|PfxvM|dSpHP~bh`%cAoDc7 zmwf4|h|8i{5~C0B7UF#3-iN@6mN-<6X**XbMkvVNKQrI4nK-2cG;-HFmzL!r(>92_1V9_$|6>`ty$93KP)1vxmmIJmgj z{#md=yd0sXo@|Z~+W&U)|N4;uL(E-moS`;Oj@1A0Yij1?1{I~D`A?w#bNu&nf<0~i zZzM;^|D^RVL5}}uI6km*a{M3P|DYoOkqT+pc!KS9Wo#V4j*x#b#6EEHa*F&H;Qy!k zzajq@RPTR5dAR;R(Ep|SAE*e&e^U5gDgF0&{g?FLfQey=aQvUa7sCokt3dwuKFDok z)Ia^B|Ka~b`u<%Q|C|2fG0oz+B3!os011GijN~Uzr0Mp#+N}Qi!npwe5)Fz>-|9dR zCY?ecNe~^e>^I5%jEPS%$1H1ilW-=Tm{NnAuoslM>84mKx!3d`-*79$Q)9fQ#sF?- zKt=`cy!@Zq(_i5g!AnJ&Cuh; zdg!r%l2z>Fw=G*HACD7OySXyu`kiP;( zHs_S|xRr4xjVMb3Vca)x|d) z&v#-{`o@K$hDx`NhJr20cH=w0!?59`&JJW>gI_>1+*e6nD?(Pz%lW(~CHk?dVz)J}Ns4s7t$okX7|YPo28n#j0pd0OgfcfD5H zpKT}e^oU@;LZJ?|A!AmpL}`TVPaeqItTh*-8}!b3AL}d~7IwBOVOu+`8Mi^34cdVO zdTn^iY`Ll(+5)rt%~_(}zv7Omoa(6x2;z2piOw2TCwn)Y_E%$s;8EB_97)RK!$J;P zx0DSa|DO(%e`&)SrXk~5&sFWKbLF`%QA7nL5sx}H{`8*i$Hj3 z?^FUjei|CKB9n=Ph@a)p@me4I-PB+7{O!goUXLZ)P+yv6dzvbkH{Jv!Nb7I>0xjE} zH(tSDk4F=k4VPYTzbF}R>~_>q2$tY|44CUmM%> z-g7GTU42fRgLEQL)cs-oDA`uMWA1LRQ!dP3&K^N8+qDIyZF6e|$4x215dE-j?gZ_F zR~#F1#^(#PzH=mtEQRB;wkYGa`8I{V5o*4C*Yi}f46Bp6M*AzR9*b^w7X`SK1+=+n z7f5mPJER!v8t~dM;lQxom+8eb`2u_%IZN+cf@H1pPq^DiaM8L@yy@)NWvr1BUy`Z>-Iz?T#_#9aSt4pu z)-2P>g(tj#d9Fd+w-0jgcX%&bgzV{8Ieur#awy-m;JFT^Lnrk6%eLL{0%TXZ$KTKC zub0~h_zW*4x7?V8Y619w*x7VqFQhPf)8WfOA3Xau`)8}Xv@$;<4&70^}niSi!cPI{>X zBobFH>TzPQ_T$H_c zHlRu?&)+Cn!gJwGq3d6ngta%|bM)g(V3Mf(bTQ*!>4m}IrQsEu2c|0rqHd9G_{K6M z8-jP;9a`=ss!6H>q&pwcJ<9d>6xD>-n(L z6@fphaxFmI3ulk*={%MuXmG@){JDw_n27ko+kz0`-!~hqKb9rh-R{#qT94awHLSfz zl45sm7?SU)Z!ax&DF1cUU}`rpMb!I7L4RA`O@rg0*0??q`Q@`Kv%@2szfoglOGxK# zJ{)Y#zWRIO<|erD;cA~^CE(yHb&tnO)2sSv@ei&XpdZ)>+`Vs|!Em&%kng<6V}Mpa zUlMU7*CIUH$IaV)u2IF;L)5R5>Z&;y4<--CN78=qx=T-ZL$5TyVcV{dewG%B-=)YssS9eEE&9;vEc*E>cCy;UOPZxD)Gblk>C z-2KJe!`#{@>ev|LJVzaL58(4##3!6F9p_EIQzs03dh-KQW%n$sdOswf*+k zn4cATF804fgDwV zlSZ;2YYB>Qh#Lj)pVkCSIvx|>qKfI{_k*GNo%K|~37sWu==`Mi6qJOO0gYcfLkAg* zA=vyof}UN^e?3DXH)}J9+!^t!iE)aI$B`d#=wuWG)*@E=`PI(bXxD{x9RR1{t(Ciq z)AH;*`vHAQFEzt{$nQ8OEZl1JbxR+qfYF87aARqd06S%Y7VFz?ZK{hFZxn;+m<`BP zezu@J$}J{07baVC`3)_!sk>cs`X=brOLvgEOUGeF>+q2tUQziCM!(l{gVbX_V2mBU0=ocai z%pxY{8Lu)%S+5ltIPT}2jG;=hAvN@?QgAk`aki3utLP*aosu=LFP81;0k4Pxl`&PB z?_<0LUn&OhbNC!@{71;z-*w}*{mcyruwcs%?hyWPKz{~95xWMmVd(vrL;*G@^ zVF#l;>TY;+zi5EnH|OrhR`(Oem;IHn0zACu$A!Y-_1wl@-C>JQue#p^_$VTX-PD81jI4WTy!p>XA1gj3TC}d5m9QI+8Ip4>a9zl+?=2XfL z%+52;dta$UeVdL9I;(w~%#}%Sx^(<+F1hRx&N#1?jCK>oM!Qbb#NCj0hXwv%dE?>0 zf=f3hi+aCa`Z6q;uQ29uTdBbeg&Sa%;)b7ZoE>iF6X3c1L`fZuH*7)^b02Xxcc|wB z=iN*U(E|3fyK8u=46nM~4m7>S0fjB1{cWB$@1GL{rrM}`k#bZK}VlVG?@5~aP|z)o;h z)mYIkQ#__avYlAQL^;o{fk39LwE2`(r0(b`3_N(^2RB+*&3w>p2K9Qd)Zu?yKY^@c znQrbW5uh)-2!x?$3g@A-&M18DVL-w=Su^&3DdZnEs(3o+Mjtx+m}kd{P7eKffy4iK zq4HXhC_raXnP61eW6?cthNwYWY^ejR?DbX@f)_~nyfEfW`S7X#7rg2EXn|!k=60BS z0_{pVgK3=!#`(Hwo}b^@(WmcRaBO`SL!|krer{OEL_FZ39e(m)mExG${eXpVsXQ1} zS9Z(LCyjD9-j#8??!m^!|Y zuRNAm{j`dDUK{Rsb;yq?(5{y{nU&^?ic}p$y@elF>LhP0^Iv9>fRFxs8@JRr!#*0Y zJJz||$I(M3G(B(yh$E@kqdN9*v#cl6Bf-S8?stJ zrTBrm4O;^VJ>a>N7-ErSgEsu82TxU(MVOeY-^V5AlF18lA`EAjdKlcE^3iA4%*W#OO z6ho%x1hge&r<0||N?+7YClodH*j=Je4;z3@WRyy>E8#}%M|}rtAm>XN+cLwx1FWuE zRiDp+xzp=~b~NQ;KB*df-(EXZWlH9(InZ-2chSg2az{kya5>-x1r*W@w|bm1 zzw94-Y(d)2@~raE^L<35@BX?so_*5)we|&prrz0D7036MGvfY%2IXgrvA_0nlb_Gs zdA=fiRIm0YZ3o4)DI{J``TjC+9>ILLd4Ft*XqO@4F48sD>iKUl zgYrWtX7b#TdL)+*x1lgp?G?Jd7@6q8xDtuTn2FcgswjBsf@3JMmSLF3!5@h7?7nwf6ThLY12m2UGIIh7;~duZ zPm9+|M{T-ySLJRkqyi5k@FZK@Gl z(d@v4EA)gYqET4lUhrF|Hj>3h`%!baJMbXZtB%c#)o6C>DNCKo)o9_{7}m)w(^y|z zFjaYf_0Wg+e>}_{R@bWVbqgLh7Ydbpd|I)p?mO7BT%t{Uj;xm0J28xf4#%W0{ile| zysY+A(cm~j?sKseV3eAcurBD#*Mi50fS1mc?5D?Fu!uQtmQ>|upRPG7-@8^+(%*r} zR4gw%79UM=Hg{%9haa3ewfHLZqL5AuPWmOY`D|Q&R;+I3(8m^LGFAbStp z9w3wgxXfd@ZLolIS-p$F?>Jxj)QOGdHta!^0*t?rLpf6!XTDOX0L=H>WT;JWspZa@ zesI-CTT(Q>wia;T^z?cOk;O6LgFRS{u^(?Ol1zh`8($$2se3gu$3@<*4H4j$fe#%1 z&A4;VXXxwK>~W$u)+Fvr4g&M-W^`{YQyV|XeA0~(+5MvqHrwV80w(2gOHL}#Z@7h7 zKZS$fwe-qE?d$%hE8NaWwn?jpgr{#~BiA%-ew*OmM`qJQ(JQjW3MZx{#oZre^r~IK z3!xHX=hIr?gCr(4(mDS`vB$Xa;|Kk>} zvxaxzlVvZNdpViv{vW1St$kdjNfR2DQbYw_ zjQy)?$p4s5cc;0Wih{8oPom{OJfFVwX$00^IU$39$h6D~RT3K)}v?4%P`a*>!ts+OG16Q_yRF&YAt>aj4!;;+?T_BgoOufgd# z199=%3~h6nKBAIe;k*0{qsoig80(soKtagbgp{7Wb2}&v3TM{I6z1jr#Xq$A^f2^* z6TMw42-!{fNGtzdiVc?^oix81p-dY>TVn;{8K)XTdTUs4Vn>d7KW=nqHauGn&%+aA zJYE+ilONUFRuXsN*UFIxD$iDC@Ow*at=k*ZVh3Rw3+g7hTa9J~G2kUvc09L~J=tn| zZG^#w{J2jB?R)EolW~PuaFL$yTHbUZbXv|&g(5eB{Dxb%^}dtxsATL$?FP7%Lb?s7 z%Ry}wy9;XIQFF);qTyzbPzcj|>s3(g6O%o-V}Xa*x3q+NbvmPt0AVdE)4Uh3m`9_`7e3&U zGqP+DnJTZfZrlndFkKh=(Uh0A>9inLdRn%9#M?JLY*uhALkl3)ZcDQ@SBdIF`-uz$ z$2xJUq1@rE|l>xic8&V7tUlOtMqBsO7ZdVaVFvxU=JF58W~) zh$DcX1b5avp^p+**WMWTp-x$lz~%5(%_@tphkH2ZZ<5W_kSMpMjQmi@-#-$7XZ}b0 z2A=64F_}PH-j43kj75k zwtbUDy*cR!JX3M^WYFO(xQmO(pGsLmLhk~je?kG=klXsVYDL>fKignh`pkgAvsyT) ze~Up)4!zR2u_GftpinaX!D^K#yXS~QK**K()EL$2L01s^TCQb@fhd)_y21icl-*o` z+mK~=wSO@N>*u?+(%holwjq^#%o^wcKT=#vBwrCem-9XLHqMG0%@$I(33e6eSExXEl>We*9*Wy0hBzzscH zM>X&s=U)Nj_&Ws;Zjc|8WK+z$%4?N$oWtBQWCF?!J3D+qewJcq8mW?;vp6G4i76en z6Y}EwI}$x_JwM;u>A;isRIgxuIV-&LrJZ%S0fQu~UU6d_iR0jjka6l~a{utUVvO1Q z3(-0vJ9<1)m$+L+7W7Q3Dk}Z>2@q=0&B;n)*Mu~l81Z6yP@&N`2ViL1%AT(&HiIOZ z$+@&<-Kh3*@5?L6Zl{jBU-n-*-|>0%J>4chSdPlXU8_3F8J+fBP8^JP^A%u>?RYxV zSe4Vb&EgO~9hEONB*zhPSY8}xkf>FC^m1@=iW4c;y1>9ImF|^KH`5q6RjpDoWD}j{ zcaifP=*nx^A%o6u#t|kJE zyo<}C(|E$ae^TDIxsk?$eIsC4zXd71633xnbTiw=TJTVnP!*SJ#u)9Yi`(XQ^X2+< z=lFoTImH^zw|YC?gV#G3wF1|>u4^+{yI+_uR@z(qy4b0`(go13=$2PVYa`OgFe=Z zKf9#5%ozs9mSIlu@pe=?Oi(T^WI5G1o0ByYA_h`i-7tkH>75(x#!lu7qo(;ip4+%` z{W9VT#g7HA%b$vk5`V>H&FR#1Xnb{NuEoTaIvw2`N<_@x7Y|K+d~a7DvZPba^s?3Y zVmvg=(XJU@A0xH!<>TQx?b_30P)etA&bv1t?cCsOO6HLhC<^LQi>;g9)k!P3Kc&1t zJoY7z^Xizm@#K}*1mqMR|6zkwkYgK%U^qG{W1}sYn0}yEl!Pan-n)Lgc5Enu%KuYe zT}(_)V|{({I}E=>+x&~f^R#Fny16OpVFAze0M2Tm>Et`Nb+2ti^+jRh>YtCx8kFx| zapJ>8JqOlNN#EGI@Rk%TBihZ#ssgUnQL&I#>%hu)*G~RD_V?xRbFa%`49nw8S#60w zy(xCAT7Zh0qVPeXQffg?Z4(|#te?MW*nhSAhf(`iIh%SxM>8&{Q8=`YL&*kwnV}z8 zeU;FYLu2ce257H+#PJXrEANikIhCDJO&_6mu8URmBDZ-|VCP(dFXxVfn0Q}1M}Jn4 z!3#fJbi{h2s(eIBwe>w)52^ue-GES9C3_rM#zdZ=Bq2R!kqHy(feDL>IY^}L!S7*% z!Bup5NaUZ2NUgL6+@xaOdt2vczFnvTLl)X>APZw%9(|&>De~)sNFxd)Al@@L;LGzw z*WFSyFj>ig3OM7xzUXFES3ow`;=!L;s=N?XTa%&J_2hGtr2ir1R{C}+wH)F;AXYQK zcttN_i~_REDbh_33Q&c_1}7ojP|$kau|!|=Q?Un&KcoyMzUT6MM+}HL>O>{A=dNPr z_+(z3mmq;MM=DRR78D-uKEN$hL)y?w%tz6?k3(3v&KOHBSb{?x$xe{()P3H^8=fZM zlzF%MH`VKaPgPHa+wNQUxaXqg#sgF3@nS9iMSjS|Hi3G+Iz`o;O3&P;A-HBzfpma! zl1~I{p44PrC_Y&zx$SmerZdPiJv34Hc0zubn%v-!(8)`!nagwCX^F~zw^d*$DuIGI zF(4GCXGac2mqW*;WMy%F-TAy(dNHXi&VskhUwXACs|AB|h>#b7x=eB^Crw)v7~<_yTW#%0>;@Y|pBM>){;yQp*Ts-F!pLxUt&xxya%Tmc1ic%$|x%acQAO-Z@(!{o0Lj{ID|^>_B@J-E?g zk7v@*ZBh8U;2GeD>51R*lmT|vr%g0N2mhfpL&VfN1 z()fBV0SpP`Yk}3$z1pY8S7h&=Sd)`=x?1bgJn)2$;qS22!4_*xWnKP6yf#Z2(9+05&*}LMyWty#YM)B|AHD(!>(ec~c0=cR{X-NU%X*YFiLQ(UuPlv-u|@!B zq@>gz`HQ!XY27NHOouA{R!5*rJ*kS@5Mh))dem9>bDNwE|Ly$>;S=igkcJHtyVIW^ z$sV8VJNQ8xQ+!`rvm+ro$LMWskrLMt1Bra5n{<}5-D}j*&=2G5IAwlI1ex~2j}_6f zyFfdZ(t883p%Jng);0p1U)TL998aNu=VOxT7+^yX5dKG^r66R7t?gy9*&C9qcV|k4 zv=BBh<>DLHPw7_{-OI4oZDP2_&ZcT!YMgtLSa=Dg> z8a6;}yxtg}BE9D~5TeFS*(3E;x?5Akbh+}e$ImXJS=T0`H(2^9LgLJg(cy=#mu4K$ zv%Pe8u?!ibcV?gw%XW`qf3XD@fACw9;?rqc&802siRR_@D(qeZWa=7ck3mR_2Sane~zGJ#uGb}cudFM z@VE*ZlRyCvia7*hPl~M-tB_p#EMjrkM%8ho^Eok{CKhrSde$5>Ytera3z z$nJ{*`qyq|Ta25Db}{mWzkLi&&4JQh*r&6^ZBQXi`JV|U)QL72l9Wge91tDo-$g6O z;B*O`U-B;W%vrBZ&BrMcFwi+CDe@guqX83b#mTHCP6J!Hw&?;LUS;tOJ@aZD%M=BL zyN!c+k-pQ`bt}%G2z$V?pKf0az0P}ylwUs3I#)@Vu*9oeuWv&IJ?{=(mk?95`Ritn{ttW`+C^bK4sL()xz zOB+w5&q2g@d8nk%XZMF-0*4>Bh%FZ>RYCVYMm6^E?gFYzN!<*VUoTw7bmIW_bWZ!q z@0Q|UTX1-Ar1ik6qSwPsn*}*M5j;i8OhwVBf_Sx2jlV4(Xo?=)oxZ&__S0KMY*7s- zj*02-h#+1C0cRJGb+*>IaqZc1QQT~(&7irJRjjkA0XLYP+E}~za$(!GZ?j<(t+y#u zomZO8iAd46C1*#RrdZPbJSZk6ht7(&A!w_1)2n>e_F5djD?Y~NoX%&B1P1klr|f3= zRYa5UGAsSLhF4I{AUx2s)vmh18D>!;h0cec1-2X{)`7vRsH8`8J?ri6$1OEM3tM^l zr>p4VVzzZ}S4Cn_?9YZ%JWzDz{Cm5)<+HRDXS#t1TLa$Dbu)o-mWqgW6!Z^4;VZ3} zJXcY9MM#rhn}K@7q?Rb!lQqChTVMz@g_2p4wo%Vqg-UUFl@%qY8AYZloLn79dyH_buISXRQ9Jz5XCOXRA3)E z%0Atl;)gL!hGSM?Fj8n&+PiRA^?5NbJy-IQKSt4qcf?0m=$tetklP|zBvxdf@#eSJ z+{UZMUoxY2xn+Hv-P{-7+h|9>J?0&3c`9-|lkn)OW57d;eNaAO<2!Y4uR4@KWDg!#G&~ANQI5*RInPe8h^}sIcI?f`J6K74s|fY zN>NG(7D<*bm@NF~ND(rE23F9#EvLYZNzgrI_`yPdNPIrxKkfGyldQZ=-aJM`QbBgK~5@#Ldra*FMhhfP2J|y(!{k7Ovx! z)oTyq)@+@Gped|Q9Ihuz_r@^yGZ zhA z9w&^AuX$RWX8qvo2YZs8#$Cq9680ZM9{y$r?lV##e8Tyzq~_-P*UAhDye4r~rHGa# zUzxL_aKdnmq>O~mbDn>YfL6CmxO^f3J-hX}L+Z2;E-hNTQU8F){mGhWlj}?iO4VK} zGBGpH{ir966p=4`+uUpPuB95XZ2Z?zFt=HFCd%HrIM=y(!+J177VFm1Qmx1+(mM=U zBHak*tGvhQSiX*=F8Hm**@XO14GQ+DmWRV)L;d4TV<#JJm9n~Nb~u6c9#))N->PBf zh~L4ob69|1q;#`wW-?(`rRwIFz0mt`hOwLoo$r<}6Ax5LXsEN4rkuxOuP&N0-W%QX z`F}P>Uiw{6${1)~EZ@YIJkn@O0P>~mj&li?_7_*q*c%s?yvk3i}CTigzev`dRa$jCG1acOG)^A(u)gVZh_K%x_XFrNkn_>7yWQf?4ko_%L zboL3j=Gf(|Gg*w+T%xT9{VJ%9c1#!MS-|G29{>I zi)d4$QJ(eYo(238Ywl)x+93NiA6#&+`ERe_$-J}}Oy{rfhuU0@`$txiCE)QaC-8%H zd7Sg(S;EB#3kPiX{NX;968yyv#1&r+8XuD2+d==YWr4lSyk-hB7lnUJu1$D~193y# zn(-&xlNEiSl(p4tp~??phFczGf|lIr8YcYAx$mJVQf0sq$iAEycvLQ7`8S}qfFPTb z@yq?h=A@XZ6wTh2v(#Vfvv-;0Q6uicRmlllv>>%JUE(jEOrN`SQVn~{q{kz=UzjE# zMo(K*Lvl4-J9!2S>S;-D^z(8@{f({oYD$0ObFMRFbmsDe{8e3QOwkE=VD{n0VZz=K zH*%!)Yb5dQA4IPR-o-cQ=8p{NWAb1Q^37G#{xQaEfmIy4$%T5(%k@6%ohIMuhWu;H zzejju&0^)u^kIEMUr-1u_Qxa5(`cW{%e3Eou|mS-PQPSg$`ZakV&SN!d}aqu34LT{ zqe`mVq&Y(65r72(J%!@WC}UEOBc-+)xqkpjGZGeC9PE+?))Q!*-xw>@%_#g@KqC!x z>^cpfbTJp3OVe)|=g55J2nrrG-I*`Wa}3p{O+o)4u*TWb?!=f^vz`;{V|p7BLS#I(Cnggh~3Ju)aC-g64f$pAklkrcNJyUSIN_#<)! zBAJ^YyQAThA0>qF*H;;JN-!VK1P~14U2Zl`FXiqmNEdHd`oJc*$ZJ~lAn^hAXVt4WH zXOY)ZwjOaz==HfszyU+&mcbS|DfvgIfkfbJ3a$DujGbky9ifG@^h8XWp^XCKsVf!v zT^JNTK-Uy8NQ;x9CHTsMGjC%Pgo7VFQ|gp$AxPe}z%^cl93eH~dB?z!Vl&cWFlSGUSs0|Ep_UP*>X7%R)N#LxfShSLP4J!gN4Z2`XGreZ|HfGqSlbs z_^Lz*H$U$&9tnEKRr1iY@yJDQkW843DiNJ#sTDR-Up?Zri{ zs#d{#gs&0-qMGLQWTem2V|Q2Fon`$`!gY8+Wuof3u{WptQ-v_aJ za7^VZ463Es&+OduiMw!@CPCSf`GR+o2#f^TVSkAG;SDMEM3->qX+dyA!MlV>GY&#yH^CB*&|3sCxwqA zYJQd5D4};`RDt+mv340S^-RX5ul&xs*ozVFu^JH*seSpKVsEv_`hWw+ zC=uGx^Mo$~;Wx{)Yo05TQLe8kLvBGlk7*Luj5X%jUam+aAj`g=`~#Lv?y1z#4Mkzr zHqh^s2WXUAZah860O$jT08svNv5bKvZ^Y<&#YUi5Xx^D8kFF^V7{VkJm} zh>JlO!YJ?d3-(a_N0Hu(sd!bz-dD0OlLUhUX^mA$i0Q(FViCgyz5PsKDi(0zTj8Dg zY(G&-c7KcG*Mc%n#^<0o+kJM^kY+0MT>_RpvbC5@kQL(BvJZNa~AMg}!@sqYf2tmcTfM&VrrDdd(1)Jy-gPcgC2S!-8X zbAK<8e?0rbLq;0}v@DhufQ_OGS=-fyLZ!3{}&rHt)L@A~$O{cSeJ@8t-815OX4 z_f#W0HKAi&OJX$&LFp)j-AfM$n9$v!?r(2+>sB-ctoxKj?5V8n0`EnG(qccyLx`_9 zh-=-o(j2cppn7;*JA2|rF)nSwnLd?e=H}nDVBu}Q@P&KRJIB}vajt$Q*k`2}Gi)dds__&v`i`SD}3R+Y;2xm9)wJ+>Z9bV8!%s!X4MeEo^p zF?CYi%8T?@MPwaVp?kuI%=DuK`Pt2TM%Uo(-czF&bG?_DIq+(tx<&cZs~X(peVr!9 zPY_6sB(v|Fbpzw26%}rp#bk_rV>NVhPM`sm^aq$nd(1k0j*LNL`Oyl$UqE-f`{!1H z%XOQQVNV{u+nGtrEf>vlB|&b$eQ$P>7v2Zju#1%Qw?bi(2cLr~L)6g}kkmz|yUUYL zidD%E0P{uJsYuExexDmo=CzIPdO3zxrcT$5K>Xny*9H;3XZlHGrl0V2e-bw@bcMT> z0G6AVphthx`I5(AY%HV=FpQ+=zHgu3k$xQMq7osn&cWl-t-*V%vS$naJ5t)|77wj? zRLMcgGU&I@EUv80ETCJcdAfV#pw(5UM`LQUN8D$G@Hn^Z~W46e4*D z*nA{Khxz)pdAcmLgYEVs%)EZY*q*$fbO<1O91K)51FUsu<1fxJO=1YmGkm-<*h(4i z<2_xizc{QMYISOh-C78%pVIpJGyUE+2WdA>>@TFNmcwuMGUbYm;gP;vJKkm5CF>~8 zsH+p;e~K?@JmgA-0>W+U`w<({Q)<2+tqj!0;Vq{0{+e(-kc)fs)^th6Z!)r{4CSq( zhb4x4;>4N0=Du3CfUMA>RzVC25UxwlaXR0HrO1rFzYc0yXE}za61F$#ptCAVmXS3Z zs^%j)A3I+@op6pztdB}alPhISoeig7w0n1{gpKR@3L{pLq8I3Jp%s1erTu9VJzSO? zV)_?)UeAS{7W=3qAVWp@KBj%85K$a1Vtas1?5vgb9}kjmrox%7cX5wH z2T$r~I_u(0+M@U0FJ~E?j=@o!d9N7_6S$W_J~}vkC%wgzbE%6uB)_~UU)hvY%tsUC zRG#eTWHh|{4l`1t%Czazn30-PZbJ`iGo0O0Zt^&Mkzk(ifM1ufv@(T&6NiHvZHw~M zmt}${n2~#f)YNrft}JuW?*0^Oo3>Emr=3I6^M zzmHyek{Q_1q%)i8=XC=h(n4PMw{(|AkyYxJ&VKj2?P_E~dCH6t4v>L{x3GV6;Frgl zX*8q30gLR=pc9<_#XsV%^GtAt3SBy}ci-Of85=5Y-Lkp-vI#VRlg@eg89GXu3|O3T zq8-hQT?RI^$({{W?00^j+dIJ$Q&c6lRurq%{v2K%l|E8Zzth1_!<# z;_b3DOET2BCefW0HPE2^n~l+>2TK*WZ^z!UhodV{q@h= zp8CPaTg(8k$nUnx zc0^9-i%na%k(AI|6r4x16e0e5z4xd-wAqP)bY@_<@I6>Gw z`}SmMpUWSA^3u!Y4l*63hjll)L#_|4c{XM#Q0kwYhaS=*12r0M;O-0=4Li^?>se~L zjsenef-u?-_k+;~wvO&(@Zvr zevoBmeUY^@2G*cQ4{&jLB7oBtgA54<@|h)xAg>%nPSpkUtxFG_(Al_!r4#rw$H{UU z)7G9q!!$Aj^ySW-K9h_FO|zo`^@_nk^-Pv@;^*781TyLS_%`+^_+(>4Q2La~fj^Oz zJZ5ZLf_5%t)$cG^Yf#fn33b5t(LPOT^-kIYyaa^7qb{8|S>7RNw~~EH<}z_|JApel znlz(9{VqS(2^jE(wvlzw*g5f|?fw!S|I=UnoAMC;m^d29h|ZD+r90=UJ;BcfhHbBW z$r99-Kj_49GRe_zj%{k7dRtk^_^A`Yrk^nW$mBS%ow$x}2M^F{^((#G`d%BvdFnDF zQz~hbs8;7(QuNil~ZJEo-EJ&?3MD|GtZU2W5qB=K4h7O3r{@yU){haw#Wm!dlhFVK2MbY#;L&Wx zBrtK!j6L5IMds6ipp0oPGGb4hXm`eb?TtSXELoj>4qPMUW?s(BIB>bnfT8k%lmKVo zG^OI-{QC1xol+UzXzPC^(BM*!r*K4FI-!tG4r*{(Q> zIHIE_j4Lmb3OJlW>1D26az6%e$o>Ez-vyWnScoSu9emXkH|m2-uBp>O${r0kM2C+a zLC{w-yNjbp|K7*?S~D6361lv9lPfL6ElO#YC==x=BwoeVVi>A-i_o_z^4 zoW)^w-E`ZSu^AXSpp0<{f3rG`F+$*CQ4c6np3_j6o@$`sQ{Gnc z{42j;jqNOCwH0Up?*tlv)fF6JbO2~##M6WCQEq&vEmz2=^vw<3da=$E8Q+f+WT0UM z@H^e;LPo<&Szd;RQ?9iF4L5kZPq30Fy3ucJQerSI5qo4#`pGBifEZMCr0Ji|q$SWm z5JsM#0BxSZQS>b?4!WZMcvdv?Jah$2`k*ol)pAi9)0ylryB; zn_c6ZA+#R=E!W~yv>Yt?oO-kmHo*Q9mi!|}wpx_Byk;7wdeuJt2!2y!tGI?4)FaRyYIQe{$KJrW) zLMlk#h%wjH!5#)0eB;uW1g73&2KM1ObIaUE9xi=ZI?(W0I<`UdU-+~g;vkL0-$9pI zYo9Tb>C%ax{qmRP9x_$vcx+2uGw*#KKBs*$qalTJ)}54C_+DL~SvWGhlxz2G+RY5? z#!VZ`N&;YmSa1Id1FtddGy`-I{nS>4A%VtUAklUkKhy}HRj1!Odg&l|?1uf9-xCFE8- zl~4I!s#LvbAiM@;tyX`>YvHq2&pRmn12eE=+S{4fd+W44hCCX@3UgvLEHwU1g~&IFYxco zpz|Do2KCGa0u3A1Zz#i<)M%DY=)c*o>N1P;mLK(7skHV1pENBxCp^_UFYfvTZie?I zlP6o);oofH8TZXBvzX-Qhpsu#fU+~NlhI%Wv8k0W;^S%mK)MDQZVoiK#{sWDg$EL7 zKnEWubHYHwO#B)*=hnwFFxX@>geLH__5x%RY+vQLZ!d()oCZNd2cheS&5%*p!#;kH*Qp{ z{ZLlr_Z0AzwYqoo6GfNhVnapHoPxw+<5j?_+6d&9R8R~aFzAO7Z;~S-=}Y( znRUdbS|6p#7P^aiZAI)F*BpB}@$#cC(y zk4C05UP8}^v-o5)VRV5n0$2s_yv#)Bg9aLu2k4^RR+eHnc&^F5QVzsZ*y1fN+Clly z!!|lz)Ti0DeMbUd*SPm5WSCB2;>Y{*rY>+0k48s^Hqx4N!fkweeHuugK$XESvxZ%s z?EVbjXg|p8Jwn#}DaKOI{FFcg!Ja{FZJ|w^YrjdV7QO0)AKu@;OQ7L03}tGa#C6Sb zM2F~K*G>c)PyrjsHOQ`sQqfk`-=ZxPmd2dsfPwu& zX#x$MF#6XR0DMgJ|D#2Vl2+U7(J++MB|Beckm+QFcju7+06+jqL_t(0nagugB*2mh zGRS}-bz00~kTLC38M-U@9fjfEc>66jgIr%8c<`ZY#^Nsgy-AyDjIq%>g;^705$Erg zoU4~}N%&L}C(F$seVy6@B9`t}tB`9{y>7;Y%G@@nRFZ;Dq}Fy=WON1FK!fd*ShiIM z`oe|t<;!mf^1Q#WJoMOO+04s#MF&F~8Ja>LaZeBifs6u);5W2askGWfBdk}2rZ65p zLPmor(_6Q)8Ou-03})6VeYu}|h1CeMib5LL1|d5;;kh`K)MuKSDZvu|EY8#(9Ept^ zH?c>WaOUv%%T$z1Y~ZLf4Y#-aqaAx zvTzX@4IeHlci{NDW_@gXTVClZS#+L#E6DZhR|vM*hdNO>*T8e&3E@zxIvLOe8g=#@ z4pQikZ0+2=hZ)#EWdD$7SQFUB47D?`&JJq`t8BIc4QU3*!AEv+cnee31DRc1nejWORnvRIQ(y8*)a)`m_5i^OL? z0~R-fG=gq)?8P6Es)sYgh#mrCmxIo|cxpiz%HA99V&BZNimt(@8h{EYVCpsl*NYuRhXUMNK_1t`uVvu1 zgF4hz?(K0ehl5go+xHsx3~n971XmzLiHl4wlz773& z?~J?Il(z;N9M}jqcmhwD>h%OkK{<|0t3GLCN%j!m&7^T7Po0&IasCbVPMI;uVLFVFr+TqW}kRne5t**nKt#tsq#%3?-ImVPq2M90Zo_Q4P}{J z_FF;kHMEGV-c(P6E2mN#>NkNC>yxJ)0KA5ysFU=>{P}r%fB_oms;+e~WuU=&>Km#au3_nsSI> z$vrdfO`u^A`+9&BSxC%eGB}gBv?abJqb?&QK<82%XdfP>eF-en9>;uH@(2EI2Ducw zx@*^t(ud&pL(B%cFNu5MTx77S-BE>zUQoOV=@!ad`L->&%!O_^xe$-nBeNWatN{Da zw~3e$ryd5GtcS0IThqtufZZjkZdz--@|5txKk<92uM{WUKn6a?2Q0gLpM4aj16SDN z$B!?!;@{kWF3Qt)%gs1{w>`NxC*fQC0|T;ek`Ztiy3d=(PVnQ#W$8o)?BHh5FN0hj z)W3)xr=1r0R^IbaZj}+Q`(1rw0D9w=&E?HE-%J|(Z9zV-2ZhE4>c zu#p9i*6*B4oyr#XKrol{7+m|3K*J|wd@Nw%=MiS^?Nc)})1Qn!uOWBIq=VO-S++g) zgA8JjApFnYpUq%bJZ)(FT7Wc@P2%}yeIW01&ft{im2=;?^ff%` zt8`r^qTgXKU?4#@2kM#l;W@_&A!bM}z0;7`KlL%zG5-J>xzdiC#kv`|W;C2&f@w4p z8~2dG<7SZBB$q#DiL8Dax)pTNnykt0Wy+wZtN zfri`E1zb~J5cqtLu5A%Gfd*i33pjiDmy$L?cWB=Q{7;j`XQ1KB&zF@sWCYwkZF+2= zdpq5LFO;W@0px4s(_WOe;eBAGPU>-t(8!+SoQ$Dp|IR&o%Io+`w(%*J3XLMrV7s+t z!V$mpC6MEriX-PbnaPtEupbZH&(aC?6ufu|J(O$``rr22uhF~K zgDiyqpilLE92?eU^~$UE=Lo#AlMNcbSosA@R6CU)yL5sH2nGX;`=oQVpI4DrX{#QG z%#l}V9^M01`Uj#&J74>5pZaDu-#Fnu4ZcOkY}P|$`aVM&o_qc|GKSiKM4_!AsDK0A z&mU&_`ve+@_8Dw2%b**<1=TL>#s)4m(BQh@4-xc3d-vje_Q|U)$CG|_D;Wvy>hBDI z@3)q#AuZ1zjZ)s5TzEitk_Ky&STaKf+4I|`RCycgAQ*jP$Teyg)yNK)9xDkxkU3y}FBxu0zq^a@SVn#zY z^V-H5DP~GT8lY{lM)wEUAblz9^22e%A7_^orOaj4wLxC|WJY|B^9 zxs$z1GmfHAZYK(D1btxt0gU5u4uuOn%@lDxmJx5Adihg&#TjQ1?OQD_FgUdy161xP z>nwz6hM$pTvloZ4FDaw57+~B%W`Oi{S&0284dgEmoe&M4a8<6A-@nax@VAFFa-i(% z_?CRQi0qVG7*J1OKsqt6n(~^v{3{=EaO^w&X;7Y@;~XPXFnQ_}w?3xPj>6 zPnMQ1mVH{LL6=FBCzas@F-(2c8TPrPj-hZ(`=l!HH&u-p0NO&u;DGT1ZUPOo*>fJY zZ|}bSHVt5LZDT!4l5WYGk6aPY*>b|oc`ei83#OlzAIDxcrH zWoverZW}kQwM)JOBjZ10%)sN)-8NW^Fbh{@qr)WaKCrlS!Zm?kGBa)Z z>-^__RPJFgtvqJNiT1lkL$euVN5Fw|l>_MsltTWAvTZ>JbS2Pm8GH^Mb~CSCI9y*d z!0l9?efrsKcxV>GwM*b@z#;Mu1fM0y;PdGK;My+vGla7q>!oQ18eG2MMqyjFZpomo zZ4z(fm^U{Li)n%ydY_k0p)(KKc4zVe6Z%8=+80(pUpg~jpuv7nM>?q6O&!w79j5PQ z2G(U-25*F=eyX&mk5iZURVTFJZ*_}~g!)Ej#KDXAxaY}N3>ZzLH5hOg89d|L+avcn z1>T>gi!-#5_kGUxSZ5Q6@VBMXrf$}#BjBDVOVN=7Nx^m({>hUjC*Z4`G|LZ!XQ`TA zZEsIjSi;kJ3Ew~ub(-g#z0s*y#K3DK1NNC@did%y+fXwa92C{Q0#e|mmR4PWO8FLV z>!W6#kyh#&XQbYE^DXp7x7d#n!-w&`2Fi30leVkFhKwt>GKh4wNE_)TtT=S)KKdy$ zsmPK6#dXXwE?LZeEi8p`mwW@&)?euhW({&JTm#s1H~-Gb`bWOesWq_b%&V`9-G*&_ z`nl)n*XeO;FX0Pxr0;^G&Zo|ueXI;C_x@1dRo!zvGexEv%a7_XozNXSw&(R^27I0- zsM$_Rs+k7%`CmZqCQR#Bo1)%Jlh6%rfa)F%8{v1~;&O-p;dC;D9%gph{guSifuYMk zoQRMwbdn9;2t{2RXyMfwU{Ho5PqeKQ!N*;D_a+5?&z@armv1fdtrI=yxAX9mdVohV z7^+zQ^}ph7iS6gX)%XM-F!|s{#|C6|ptY^iRo$q3h98hEZMS|_Uabk;VmHt`@dI+7 z)(?K9joOb3JhNo!rv&caFH@&YPll;`WBAqyH{;E|Aw1ErxOk<2+48?L7xff=kM zI!FHbwQ0=v(7xUS4dD^xX*WE%b^CVq`q@^7GSM~%Uv(6p%>NEe>!k(wMC%zxb`AFZx>Og zeVZ&N=;Pi;A20rxeW8w)k)uZCEineDlui9EgO}<&J4$}H4(*`*R(YlsoNBd29B9uq$+hd(lfS`DI1Pc zhj`eB)fcF5!!yvJUa(K~X*R>}Elw->qQG^=RFt;c(zI7$6h>%me}vNf1xDjo`iz3>J*JZDDEg`_ zqjK|~c!KxLwx@0tMS71af*-=$WH6XY-6#_4tB!W<3-PfI6@<}$okiCK_9ZJ|&ZCcJ zIgAEX;ZC3e#h@Vqp_by1jjB=LR2)PA);4iMXXF-wTc^&P=9NdA^IEmjz?+0|(2?td z@^+VeDWl;L_uvYi@`AKA!Y*v-kR<`MO~q*@fdL@zJ3xeTHA`)d@Oew`K4m(v$B%2b zc?40;MWNL}R5b<(BtbKu^=M{S8uQcey}TjM_-^9mpDtx*^KPZBt&IpeONE#v)rr&b z_8uKS`NeMZxBRA|uo&sp0A{8N=h6)}rD^}Z%pmZo;oP`>ZC+32>jZDb;G2e+O+*8; zWn7@GGV5SWMeUk;<>nkTysU9@KmdK@1+yIt#2B3Vkb#SvZqCMmc3`9ftfJ1|E-_N_ zw0QfZ9jO6@=G3PVvp&woF>V}~^fNlbO{)y7wT~Mg!_%8=3HwL>R%WHC&VHq-Mz^NS zIVh8UjbVx$an530(o2WSHz0h?Oy;b)>;O$_s*afQme*TSf8IC&zRjnBlC&XEfJ8gg zVrG3ffN>{yY2=#qeK?AyWM95`EpMP{A2lYM5njEhvqgKMN&+9yK~r~4rNVbH)Y!qW z{1)5#Tiv0&E32-D-@ao<*-h|k1hkpOvJZosX5=)11|E$38MupMEzS*Gcwe~wm*$-f zGSI&U27GPXPJ(Ou81xz>oWcOZP2hT|pE3AVZ`2^Bw2}rs=XtT0*7AJd(&^DboQuBZ z_ny7`*!_8RIfvZ3m__6T@~fsr%1kCI|P z7`($H+*55+ee;NTR;Q=Yl@+%4svG11ugm{Uu+#SYy1%7MK1rbAUNR1>(|iB_7U`s3 z6*n^`q`jL#KCxf{%SzbQn>yuJ+hdSSEW;njOSRkT0y5&zM>^C7${fTg$I7BboqZZ! zF=JvqPN)vv!(?OlI#+{7%5s=6cmE52K%jCC_bC_DaTCf4O(*UoNGVYe|TdyqQDec8uI;v~sHRUR=s)di# z^V&LP)&Q;iZfbIWW}vmdD|yADGq96chBU6dJ)376ShLSVd)oTl^4HoT|I4R&T`V*A zX0RT`H+X<78wb1Dv`>8LTX{u(j&5n{sm*WE99^US2d4KppwiD$2DQUGcI_q`ad8=m z-Fsjb>H7?fY+LYasX)K0)d9dawR`=Z&+q&WzjK#7p?tZq?Pp6rDUUz#IInZPGyd-d z0(u4+V&AUS8S3sV12PlFiLB^Mb$?4|TBmdtXL(-wsCUg|aFaPFQl8Ks!{^Y}IrwSr z7oX^|U@rbbYnAX4fB0|HTZ80I0(*Z12oQHx>cujS*d() z(SB%i+<@8)(_v%?nz3f4he2y)Nxw>Zw$SCHg*Tt}Tm3KI0ol3?>TAJaS`I@fEguU0kK3x;qEIrG@>XJlH;UuDaC{-ATVv1-|NG0vU@#M>n(` zf*z1p0u$O*9c2)y>N4?4e{zqq9C`y&-n4EhWL=*3x|5KLKl-ptXX)_lnfJziII(7t zcA){^l|ch5Ueh0y)&@lM3uB+qL-MhBS(okBSKqLCQ(22Yc0c^+8#&aU=|^y|?e%`W zN!h2;SsZhoI+QK@IQ$4-T5kdk$4_KwpA(Xuq4nH3bC?tx6&dz=?NsC%zO&tqM|{@t zjXZ0xKd=by*iLmOUlNElP<@EW8OKf9l9Ojomu(xrDgVR&^govuUw#SSri~rYs{MeI z`6tF6Kiu+n3pA*Mn*xhPIrQvopy4`$#nr6ye2b09*nIEEQGyMfv+-VLqoJRhvd9Y6 zDTl#ea0f*hyelvm?>GoBj>V2s!5Z;$HgGe8>90RqLCVQ6b_*WI`)qknIZ8kwjxkhO z0Y|~rIdS0JFp3?h@I)|B3@Qfwq0{4|c2e<4jGah}QxNO2*j%A`#r%uKg>zFCb z!ZAuJ6Gwr_*a$=u`D+xsZSWoiNQV3D?f1*j39Roz7D9nnt^=GgK?mB`IdY;+o!0V%>tb41k-SIw^x%hk7Zc8)ZQi*s@!zk^7yY%2* z+a_F9=gRf0%zG7`@|8nnrv+4{X15}laZ(tA?mtN?oWj!9S8mBZ0gnkwem1P_#`m+yw z;ocS7Fqqrdt}N$HmNI!(-6>eZZhwnVf;`|TeH|eCE_UnD3626sIY~2@KWJn%SSmU9 zX^<|y8~)_s{iSE`zNL*cz2O)*aj?(C)%*M%CxANS!&?}1_9E?BMRs%MLv=Jt(#~`| zchRR`e((V)f2EAMo!7bIg!(F09RiQnM zr0dg`E?I(8v7|JhLH`mQp&qIZUno>=Mk()$X9iR@kV=(T zzq$nBllK>w33p5`cQDiFOs@`eXux+KOFi2DgQ{SH(%l;Tx{=q1;| zni;U>OZFl-a-%%{!t-SWdhF5#0s$P#o=ef}SKIBg4tCWefyrR&8cu46!Bx*WOAzBt zU56MDN%P%Xc9#*;CYC$UHTK5^0#oYHss{)N0Z->l9c;isc)nTZ8taIo7tuMU&6=C-O|kXxOd zMyDQT7IX9ZHRa5q{bj)LQDxjj_Q@ew?eofFb)umNxT`OdJr%uKwsGaK6SD{{M0Qqs3E_!a25^D%LD3J1L0=F9oV(03>!T;nK15uqz+50kLR>c+GJ%> z8=*g=9ojehzE}xy<%h{plBF>dZUiFS$%e*|5zXASvTTcU6B0;8qaap|SVfB&)Vby=R@i zQNfL84{qL7Wj@?_=5fTvIFAKN9(?OOGaOO5O_XMCOb zdF|bg${iEg3kILV$%ka2$O`(6{^v-bm3ktp=!RSl-j(X!!~Yzfk=LwyD}lR(pMP3@ z#O9&XSoWyTd+|Gg27N{Ydg^XzQSB~$D?I+lpVhy?PC^&kAx|3cUB8;86Nk=~1wVe4 zeVayLFKecTKD70#GaG)9PCN?CDqHq#gK+33-q6*_3xgL2*olALn$0Xh8o?{OAIP#q zgM89G`WxIjeBsnn{YCrS>jv|sgRs>XIlw_#+C>0--}d#{+;{vP_m}o@{hx?pB83a=gHU)pYc9vtQ^)i&QyG?%kf$bG8z=CzC+WlhM(kH>F4Ch zXG@lqJ7?a-=A_dCQy*A9HUmEG1wZwE~to12qWaqO}>VCx5;I(G)z5-_=R zfeGP#<^TM@{`d0pfB0n?bK6*!Yv{|-2MIF-yAITUh+qCyfd(6_uo!)DbFesi5C+wl z$Y8Ioq`vTLeaOevD}42L@iv<(|r1`Hk=L34)S2oCJJ zQ$)?VX6V8f&aikOpS~#NAjfx$3k1AJ{7$qk4&rn0(EjZFIS>Z+stTIdH15Iy$Ilg8 z*c9v$UJh1ZmBSq0Eyn(Pz{3}?E{s!Cd~V!;Zp^+9$64r=dL4A1I=ZiHJ!$JIJn{FJ z`1Pie?cb83;OE9*Ne2r_Ot4y|3t^MeZ&-hJSRRs8MqwX6a)23?Q{}kVI0galGVqS^ zz2%aYb9`?KFZ@jLeiJ!uFT?88ITmsZ#EEytUj?JHcjC})2IcIS%00HvXFQ~-?XKYh zzO;&Tu{qZ1r}tTG^Bogd=kGukp?2_b7ANo|(bRJg+xx}0ImGGviu4c{`$w44#{M7T zF@ALEg|bp4FCn-m4l&zw@@hH7wWf&s=)v8}$)i_7v*!HwecIlJ7sd_jUWSew7X_!` zK7H~S%OVbj2KI~ih?g8CO{MR5i}wkS#Mj_1{yw9FGH$>vWzcOS;$+&Y6GZs8@7kBX z;c`b2zDL7z%?0~)*zkU=TRqjmuYEZuUHu$8&ew|#s5}Yn5AE1qb}{Dgn(&klc~Uw$ z6cNX!$fsVb9Ne7!_Hz_phqt$d_P8tTuW_<$+`a#w@rF-~hOZ9L|I+K`qO6IB_}*N^ zXZUS{*ym!fwu9vsr^~tH2jI=hd-9j~`kc>;>k*EdOG5``zYjz|hnyecyXS`v>{SL0 z9TA>)InME;hZ*D(bfHt^E%9n-!`Jj1k9U-=C8$60P05Gd>u*5g) zoIiD(Jzvh2eXV=t0r^5%`EH+ji~TBp+rCDY_?j}c>wq#~{KyzN_qW-%X>Hlry7sqz z*got2ZW#ijj$}5hH%_**Y-i7$ENiyz4G*XjrS;9vNu%!;^|<{ZFExE*JN(_=w_6!L zW_%rdFnBzEj2Ya$hq*$3qXb+fq7G9w{!$spgqdKfvwYY;^5wL1Ywpo z>M(1PEv!S_l=GX5_w?rwrfpP@syBST|F8k2?*Lw@hpaddKXGh-*>+qkDzA8-_xr5$ ztyJSns|eTP6ODcr4{au~z|wE1LHK@g$Q`7gIdO=ry>IoQILMRo-FN#{yp<#SUO8y= zmwIg&%+zn#5CXCW&Is;-`{`3h3AUbzOnQ$vNK2oUw%^qQ+Moke+{l=1@qYPdz-|3- z)&_)U^is7U+Scu7bopwro#NfJyLGzb!}`76&`x_G9s@Zsblg}1`?Q|#I*Ld4Z!d^y zbb$8=v#E!#-&=-omc3nB>Qv>~x|H$ZI17VDk1aiLq;+G{Z=e19#jvwLeK1VxbuaP5V(mp)O@qI;HJ;cNNgfBmg zXd6jDlx#N!0q4)N8MDXfvkWjR4>b5H8$Eb<-**TljUioI1L{s0zeG z{_4fU-TT0==dYAQRM^z#{eP`k=h!|yfIk|$eM<&H`l)AWgU$awJiiZ~v~FZWIyKKt z=KGKd@C<&cgXdGHPn07}=tx8Rv*}ZxvCStrzFS7niNnV=r8EG?SNPH&%>gQ{Jx@&mp&~*j-V!>hr#yPo5vO6uo9Qpk>Lcmh=nSuWeh9=G zjP2`>{V>4nq|>PrNANjLMdpaj<>)7Lun~E|lzUo}>S00XVNS{$d`e0XwBv9eR z;HeYG%E<%A!+YZ7J@%L67C+0)eJj4!d&~<1k{r=3^NpbIXXX7Z5h^04=- z!^OSn559I3`?TRj@otJdF>&G;>}ubPZ``c@)QO`6xXyOS z{zLh<|L)(G(L=`2K5LSm1WEE&%KmW6-zCuC=2*T5+6a$CiFPCK;5+8+nvHAMmJi;0 zmmQ#2uwmHFtOp!PW`Hvdu4Qxv%4nRCHwAnBW;SnGzA{v8=kJ5hEl6bC=uu|7VZ<8g ztTO?wXLB|>T>%q?!Ej(Tj7IW|3>ySdp&FT8$$F;^2Na)D9-cZeJJh>|(CbNy0)Wch zNS9G6BkAH+XRulkRy7PYCiRZMf-`j|N$c}%2_LNZBCzjZhJPBbr81SusJp^bqi0YB z*hbTg*y+$4wLXIb;;gu{^*YGT$cTq^`0O!uCv{!u`uzu@WFC3=Azo28JgHO)kLyqE z1D({2%)p|qwPGD0v@q)JH620QX{0{0h7j&Fn@k;GR&x3B&m$bOi9SxAz=oaR<~`!^ z?Tn_BHlpW@sVS>QSD8hE2DV9>C+I|7bw>G0*|l?LS^4qO4#oEP%o)5&XH;gv%`~Zz zMOAZ+NQ-cNYe>f9}8M&b-gKFMQF7 zc4w0!XFDw1FI?#?zlIl~we?s>bB~`IVf)>6)~_%Aq+a9i|3}?>KwDK^4Y*T~DvE+& zL4^xaq=*d_6{QGbM@4L4#}<39(Ih4@CK{8di5d$wY=EMo^bSf92~9duL3-aZSC z@7(1X=|<;F`G19GIDqzg&-19m|(5k7=LNgo?_Ux|GNs23#yXuR=!8fSB?_ z{`4greYq~TV^|`$X3dYe4#!K(3OnvKKm83f^TnK*F?sr;eEwkvvlp5ye+?X9D`edE zWOmX@kj&m9AF|?#^?-z2o9oML3ghNFS(^sRrj47kQR=&W2BWA~#-3Gdc6T~u#QQ*d zE|$4dfgtr+ZY-S%8)@2kI;Qm#%5(G1HvXhgmd zkIF9TBzY7*6HdZ6D~O=^VqY+Z2RJP~UpZ%U+K<^M?&Y)3?$j~2EGUaI%fLNW#dtYq z`Aa#UGC&wXi_(owo4?D?&dJP#)lie6na}3V&F>%8tO?ETs3<~zc$G3a{x1L7BY|b* zbNt&GNn7&0IPr3weouO{!tK3b!%`MCV_T68_3UQu`po>P_p%`(aLMc>GC;61%|d4J zixqpqGG)*X_?sD9z52)O12Tr~IbIzpWwmU6cY4#L43|cr3o|`t#xk3PZZ?CZ?z7TL zIWJ5cKXD6OluM3nzk<&{`6M*bnp2(N_8Il6^zJ1dg=1DzB*PT4&9R)HxU;%R=gM`O z?f3qK3qk35v%iR`ltFv7JMxIAUysuan7hWK&WtChNMpI~yo>({7%#>VP{K?aDEOgh zI%XBy47ON|=lEBzeVA{1_RzbXKpJok_A@Z(#v(Ec&A|Db3ecW?fl|K`tn{auy2{81 z@hbA&hx-Xx?0HKH6Z=>){fE==t}1qedVLGDXs2{(CFKo#nL1ZGK}HlARruDqGlk;V z;DV-H%a==*Mn5XtN>}IOj%7dbfl1e{6Nu+WDFeZkv@XrNF5x1Cq?rQ0*d)kLWtu$T zi8b!C9?NzJuT~8YjIsvw8L6o=18qZx$}Jxu?~1dcB7$QZoj;L0f0p1SZj>A1*DV9z zQa(I>^w?OA%&5s-%3zPMwQ97mqw80y$NinC!L3Z4fUz?Y$b`OIw=pUU_VIP@`5kn|C62#z^_2^%=OBPOM&~$ zX|rPTqN#CsgO+g!TZ`N-rM>C+!bJJv%nSPl-i0<&R^_6oOkfVe%<4c_r0(;huhC6& z{xv;D%$}CcYRAKlh=vX7CvKdZ>-A-TMp;?Pt};ljM;R^LvwD{SwXxHl;&%g#UsBRO z4jEYrP@GG1;C(rDM>!8 zc5ErIKbWUfID#kUs)s3d08<-_1uDm3*%Gz_PE;4j9rUf6jq*C zb&z@in7HnOcck~C@?5Z6(W0yoN7^FULx|7ap7T9pTV*_E`V2meXat`&1E< z%qzEc11I^=m;CB_vhsxai&y1R+A@qS{Im(I0v`TZp;ry4oY1CqZq+L#ZngLPt~6-l zcu${@2G^rAz6NLS^#3p(CeU#4Wds^(AMkUaLFrNYmlOOi{oj8i&>-M{{wHw)nq)i5 zYaywaNyDcB97!~f{b}wCSIO2dtCxnsS`3uR0N&Cik*ebTSl!%jg=v3IWTkRE!d)d#7FFci(@P&r=B+bZ}p& z$Hnw{r%#;Fz8%N891#ubl~EE(91;PdvE@89a8yQKY19FibR_b5?gOPvOs3%(3K8Mv zF^>xsB9!?K8!;-by5jOUjHYYFelSb;P`1K@afPMEsK8G~PiABaz{fSYHU*T-sMDvA zaqkWs>q6`7+x$l(}g3R5_uid~k=xpR8trYvMcqY%| z(OH?3iic;p2VPO`abpAN{QK_kk%BaCz4ppD2BW1W+c(DH6& z3xMLk3|>gHtR5n!d%!+%=DFSSXe#02oC-x&1bZ}$6ynmp z@bR)-OMa+MUlPl*h4*@*stV6_7!~6tPKrPNoZQ=557-#S5vSW&gFlN) zhf0MG{~)|Q9#o^*CTIXG;grXCvPb`?&D&!chTOXYK8P3IdM&Ow`{L}o;7Jua7}BG- zlmArCmW>H>KT|*(`PI-8%77<7tHj<^*R9fA>0aeoGvn?4?{T8Tw&>K(=8^klsjtd) z6W?`Phx{R2R5UtFmi;P^RM_%qDk;~=OT)>)q5VY`&?IW|)T#0I`ya;Hr=J=}A9h$C zpXeTXc|(It-t;@`p&NU$SQ1%{U_(a42{cImItSS>jOKj{9U>cI@uf z?SeR@Mf2=TZRdWCa<@gOL@gVvjN`6z2eB|;6gBhSwv9C~XB`aJWu?^aWTD(<@yWPP zqu*Qa#(Sebh;vRlEiOLq!aT{RJi#E21_6HS8EQLpZXiM9azn}}@yf7?--^g$%b+#< z?ImEzzrnc0i@%IfbVh&v_17}vaOWi##i=K@%X7^=;?pf86`6|$0>qq#jtX5QDg%VG zFX5iFFJbY_RO;L}Xa0hCt52U8FyXVT+Pd}jTXO%VJmIz@Wv;y?49;q3*;6EOu>)4h zO4nmBL!J_!84QM>e18%+{rw*v%}h||!&=6fXP;B>6LjMI5*E;2>J8`3Je_OKm#Jzz zDx-A(q@i@E*WkmdlFG|)L*XkA*kM&em7lFS*-b&Nbz4Ldz$_HuD zd8c070T21vzuh0c2m{?9%=^s0J9|xAu{}q}&azUbm*4e%<=@Zn7HE8^9QGOBD=x*c z?|HxSOn#d7FHWx-go8n_?)-Dkj+RZEp>YlkH4i_W69Jku$!2=ej9<*z^Ru8u zoKN`Pu@fian{manG~lz;?f(4(`>gFT@*ex=<)4$@K@9Yyypi+{-+3vws}XEg z-Ya|j+zT-b%%G($MX;fAMICQW9$B%nIDUK5gm~|bzH!Ed=Wu*@8ybSrdo0(F{lc8( zKi8hy3$Q7j_KQC~al#UJ^`mGl_IgL2;4|^lPhupt$ z+go~$j$wYnM7r~S$ML($0e(%n>}Li6w5xyeKJdo}iC>Q$v;po%BggWEhzEc1i)e!l zZ+`)|Et$~x0sU?hN%8Jj1$^>$f)>z>u-`@n4dZX&*>E-6T&rdR<8xs1_@Dnwg~ysW z>6lh=#;K=AGicJvMENumlJJr;SRCfXbA`EANk+Psw1d5e-^G`(8AIUfuf1N0=2doz z&fU7l@$?@v=~jZf0RiQXd@7G>(`m;`-`c;@sP?hrrT##MiD#>j4LS~HYwAFP4d-<1 zkjG3nX>w5FQ9Duo(1C`1l2_FY;#Xbh7|LMp@ui$h`wAJSGi@T$q}6-)a*Z3&P?|u4 z^Dgy_kSC=XUzvDBfBw7wl(qn$Ip_Qw8Jcv-S_~e|AULHRKLnb*;LJ0k6@k0`_pOs# z5S^PgVbTou3lGOD`8fup5@w7o9)!ER=lH^DK5}5) z9pY8eBN=Fbue3=FviV%?ROw|KQAd3!X-J!96?pNqumSJ97UPz!iBpe00$a6h_N>!h z)DD-QvPn8{-Hq%M zfrfuyw;kit$bkT$fZ~O)m^tOM_y`1l_2r`23!~;Zn)ozocwio_X4#XScQu|WfixR@ zj9`n!y?5UqUorSqr*?{S&+C@^dnBqN$YAEhY6FxO@9m`JtO3A#P{R%(%N)2Qx5{0ni)etXBM=UotO+qTW7LK-wG1Q|w7wxw|2W;1Hn6%8HtiHr$pE3 zEdmV~sR-V}h$!|&>oltPmo8nJ9lD3nIC3OP|K{6nk7F@%4PtnYc-6Sd2sx8a22_da z*yxb+xyr)(1fN1cC8E+7u6ENO#IaPp-yaZ%5FqJ!;RSK}f!zfy=lGCY?nw!zwa!1c8M|j(vfUdaG}rc(zYpK8<+dHxEVU_U)qv z5%etxcZf2#3OSyFxiGLa=n@b=3qEN!_bDdt7F|v$_em>)e`M)nRmOjU)qS9?Sa^d-Jzp?4{AJ zeE~i|YQjddW!{1X9NjlDh7w%+V&S5=;?m3FC;}P#shEL{&gh2q$eSH>FR4h^Di*Mt zJS(ilLB0=O+{0acHyaG%Oix6y^&c4Tj_4mWa!<ILOW$}Yx{4u!w?R=1cLQy;iCzbkL7#5sB&`FP)7o`|!^ik#Tt#5j_m<9>DO zBreTPi&N>`jJ0dA;>e6hHeY2dWq_G-VWQm8p;vaUp|{EG`SapU47mv(e;nssa!DL_ z+;QpHN#ka#EbEs?%&HosRu%{wiNv6cU{8MHxtXcqUVoZp{0iMS8E5_FH{Qr*YbT@k z3}V=KNPd*YoxAfAHp0~L)kR*)9O3TYK1<%vAoFtH|Mcn8Vk7~Q4>;QJx?fx$Z8+CF zE0E9u(uUu43}NZZ-yL7$R{bQMXqXjyb=6Ne-{KTJ*o1Y=n9=e6Yp+HXjQ*=HzL-Ep z%cxBzP@0l1t&Vi9jw?@*PnNO zTu5-Lj7k#W!Ocm}x}KGow|0hea$L7Vu$XjO?8jjx8G0M@z_hR zC9EEQ;O;o>q)zZ!bsC(q1p((px~ZsB0nDvf!7yVB1~A|=VPzIf?YITL^TTyyI!83;FkrQ@&8PMslfc%59* z9U}v4H~;qGIFjd`dhsQ30&>{XQ@n(;v?#sj{$%iI@J4uh`CRGApM@SPDk`M~6E6!1 zYJNxs&vS3~j_w^g#tG1*!8HR^^0zYU=kFt*e4af6q<8sL{uK{q$>nQ*m(RS%py;$& zv!eIA@4|1Jqf6(LIsJ)#7vNR7sH{+y$$MD=z)$tRW5Bp6cL8srAFwcn0V@O5RjK5o zx^&KL9E?fvK1r)H&pR7u_t><>LO&7w8W*JbM6^vU=9Wv-0QBaFfiZpQ)!|;bj0v%c6aZ+_oh9zJC48dR(_H1<-^QyW2cB+*DW4}OVT@Vk@wW;X-mQ@ zI*pSE9(~mRy?B8@#@WF9+Dk5tW{n%?{FHeHCWWb|1bDhs@)Ndz_MN{AGi7DkWqd1T z9x$s$(A=u5LCDCL9)BXH@Y(%6uZZ){JTvyCiqb~h;?p%cKWW18#5EHwXvEKWU!A^Q zxd6P%Glz1C>vF(-ZuIW`X7qZmf0qA0@!&(z>4dhiC)G`EwYFhuR!_2K``AdEse_z1 zu#k5$vBU>k@L4uN=LQ?9?nb2xpM8SU_`t7z6*HGCiwjRWF)qYMI2>7n#EK0BF@%qE zwpv#C=Xz2mGH2zvf0t-hxR;J?7e?QZJQ<7}yYJ6W#0howjnlfG8|?^y)h{c9MzqHY z-BeUk75+==C}5L88tzHm2#iu+p@Y?{&PSZhTevX#U}q0{w_kL>sC%@=|7cF)$6$bs z&z+b2;iWC@rB2nJ_cL*zOej@mn9wr-r~XK1ouqMZY~f~2n#L*Ez@BWf7mmAuGkqHw z^N2(e002M$NklTNvKj?AUng z#pmL~`CrB5r=FaF_9ob4&PUlNuWm7+$2dDfHwGHyAOj8a7EwX-(SWGeqIq0^U$lSS zdbt+in7v@2y#My=KNDyGkiahyf+XS>Fd=utbU--1fH*z=d+?UqV;1ka5gHn>yJNE8ZV z4LF%d#gEiNIB(3Oqx#XM``3SeI?im^Fi!2(Eg9VsQjNG$c@d9J<(ou;u=9Dj-x}gp zz)IZfH8wB`JnP!*s!hwL&YT&&-|H7E7cGe{oQc}{C;|-_b2f@9%5u#3qX?Lv+Y-EV z0*tPwF%1lKgd}P+ZyG|oV0_t}L`K&!`ujhgiBr3r5vR3lPZqObp2nc#vWjgX3Z+s6 zRD)bbRA^`b>DX09$T+4#Pi3V5l40hPWgL$|F=*J(m_WtHt#{oSCmeZHHZj~4=gj%I z)kR_A?>d7rV{V&aJ(lh(_)@_E6Q6BhW*3|)9Wo<+AARsaJp0Z&aSYoUZoBHLI25>u zQ^!-V`cor_w^HF4omK%!AC`biV@7SIu&ThQ5_2zKeb@LJ=fsMG7oL44Mxli6>3MZr z0$$7N?3YH|POQJY86u1}4Lbu5W|f_vFwY7B9%80Q$7wsklj7(>j8mRFbKczOMRxab zj9jmmaWc+4`IK<$#0ItwYy(f*p*zPj!=MsY*}I-J%Fs!?Yov?_Fi#Ei)k zC&aHFdMMsU7+!$zyXM9lqcsk@j=x5TwCCar$7;v-ceVVf;C38P$g&2`b`j4qV%H%O&v;6+1J{?n*W!$C#CBYmx9+?A`ok7eI1 zkEJMsZ*jDWEFM`E;QB2F*F?4=jrwG49N+3#_NpD2PM3yUQDNh;nfA^o3{ed(g?h=* zuz{fgHjN=^%I6Co4SAcbE?%;fs(??(PHc)p4?QBzIQ`5x8pm#rT?q0p_sZqT0+L~p z_RPvlJkqmpmvEZ4?a^XJbCgPKo1`4{%a^^B7-R?6zti#^DUh&vUV zb5S|UFB%w%{0iW?8u&9nw+%yH*c*^4$9omwt+>mY{C0Q(8{rO z7KFXo+Fjr~gGc{(?zwn!z<_AY41bM0JF$H`7Rc!v1Ua0qPErOgkh7)Iac<=^@nN~8 zI3Z&#Kk>W#W!b&P=?ILK`>wq%mi)9it~mF6IyrYu2Sfas&C`IESEW&(qXUqJ0H5=O z>~^jJDSj+@lvWEmC>P)2c=a7LFmC_zALHT^+U2o{$05)5+qVw;%hx3>XSSO)XwYe# z+T6-#__v0&b1umSb)F4DHQ=Sm%uZt@j_KbwF1qY0oVw$o`@@jwRq4m`O=iChf;c~& z6))$`W77C?+ze)ecb}ybB0m`9TTJ%&Q-c1_zx)b~?v9Al+jq$FRCTiOQ`R_^Mw{z( z-Ki&p0etCP)qBbzgLOF*&g;wy}$PszXz#xWW^5JT~<`=aept+VvidvjiVSBA{2 zE_0G@3>5hcg9_ebS-Zw(8r;B1$3>axk-h`TOuzNk>ruOD^SJ)zW_;TXwuMgZC zT~6+t8Q2Z$2tsMIFkdYTgA7nxu@2tfrv8KGHLABT?@c`0xH@-dE1(yy|ER!DEVndFT8v%GtP)(k2xl+xYK6a#$3&sJLeS~edxAV9Uf(bl_{w|c#bw6907i* z41kBVq0D^BPjlwZj&YO5N5>Q3C7PwWb;1Ckbf_Hgr)yT;q%#K($X~)tXUX3S$F_YFkx>hJ7q9Y1X?vvOxNgzv_ms8Ty#`=~m+&d^ zv`wSch2znw{oZ^to*p(hdUQMqe!7whp{5B>d0eMdd(n!!3Kekr`OZ%S8e9t?Ng3)d zK37~geg=G*|5|ieKY|#4{>^VP(C`Qq2i?y(hm+=N<<@2ST<18y%cT9TvQ~I2tAvft zqWZ<-!?!|Im(X678w4gt_Zfhf9zCRPGxr{+MdPdmnuyIy7vY3BxvQD``+xmT=5O z9dj?}MqX9j7Wgwjow`*V@Dg6~u6j&eX_e&Mg$v{L{_n=Hx89CRuemmkMGko6rZ&9C zbL+4xQo|JndE(*=^BKI_%%Rn;KxSF1~sh!$|Nm8@L|ZBXW#A}58ZxObf#hI zzP0J$!sq&R`cIB$Ah1N=>LUB>C0==~_P6{XJiM%s6K2!cE;xwbeczX!j|ycC;nH+*Me@K(2IZr{sM7Oy20r#wGtv3_-=B(i<}Z$0NR0pD z(n}Mko4|?mkv;|h$v^{iS=D(l{*TC+IpC}xGOG50_2Z)MR5U;fu19;XJoYUHPR{SY z`G5cWK!el-(c~+wVKBjeP+9>Xl*C*JXgH4Gw;0uC-;X)wXpXXKm`GfQP|r*-#G@cq z$PZ`F_iyjKD;r&1+O2CI`C(MfaTS6Rsbp*hPNj^fi*j4Zrm=Tfp)E6MeC|plt{g<| z+_ouXP$)~7L*K!J;z0rp=QL;-r(bY>w8!A8Ri{pDN7!lbD4e}i%x0n_6fX@eg-K@V zAV@P9+qtI_0!PR42aLJtvuDT4ecy>MCr^v6-Oiz+p>>`my(=+NoJIJIqi%72<Zbv1#8rYT%=+5XQp^PLj> z{aXV=hS&I%q}O-xhjXpt+T(Nxyzyr&j?e{(Oe;)p#r6LqVC{@mYhPoB96j!@r65p`FXvYIF4s zH|81Ju6I52m)=wa=?no&Y0xOFPMr5>D9IQ0El_bf2Nj!JAnb7a5ypSdUp^3rG53qE zxjwp(U8oQ3Z(U2rc4$#&NFz?8&G`rmg#saH`wK-qmStxo%@rEk{oVU?JTYuv3|(Gm0#6{TfED zsc>d6oX8kehUQnTr1W*p91OYf@%Lw*ic2oNG8J1{J@$QLENMImZ|P5^mBu)8vnpmA z&)EeyYYbssb00z33~!RhAwA+{cYTI-E{;Sj)Nbq4$Zwi>)ZP+(%00CGi3b%xZ3;ly?nI%IvxGW52y>aKc72 z_NZ3PW@=kEa%v4UW7Wlm)hiX71pI6wi&CvbkdZ*ckE=KtWSs`PG{lyLB`e~>>n@Gc zI-d;xZHpm;K92s+y%Ymid>OyH`l{%5$|>w=+%I;5_N2MZRAX#K=4$Yi%ApH`k!&M3 zNbgDa(4yH(GpmIx+b!l2Xn5)$e~-UV`E@*Z-~Z&((Xn0I47#l+yDZ-;$I|G6#+2pK zQ#z&6Idt!FsY(AyufPWUXZC{ohZ|_P?i!j{{S=p+dqJEJ7Kv@X!oGYDjDbx4tj#r73CR>y;~_53srA@kir=qmGT!FhtGp)~T~!${MrkIe*}y zp)2gwA3h^>2jeJ{H4@c#X1m;mq9JUl_l!AT#Ov?B7ZZTZd6!(4LHUCzA$5z3K~}ea z2^VFU{K}7{3+E<`JLSG0u5FN`CVnW zI?eI?Sp*e}vex7?p5f(~!bw{4`EEh*J5$gf9}oB_`t*J&_H21r+<0Y?kuqaxRa5p) zfG$0rPNUTCdpVYT%1{{uke3Q)8n^=&^~fq{Za9@kZ@<_pde58^cXYobdS1{yvXoq% z0dCBamIt;~ci0n~kb7Do26kb#3^L>?FwnhyZQL_l9!JJ(phvvDhEw#b=U&J;J^jo3 zi$KF3HL?l=fCOBarQS?3f7eD4dqQOdLOV*_jwgse_mj`!S9jc5*kkCXU7$g2H+7^yRnH}j0~O`0pUFqQ09f*o zJf@7;gYRnxk0q(}_N%YOGb4w@dF@V&t9x7=hcs=Lc9ytv9Ce>n#==^?tzJle;(6jT zZC2o)7dKg1RGvV_2H?@>y?5hJ*fdl5@K4v@5IvB=wW(-WjXoEyi7Rj>k2|-lROR>N ze`UMR@H1#jf`KmuEyfSEE*I%LcokM&utxe;Ayq6VSL)`kgj|AP<2#DxpvO7z|pmtIaa;^7L~ zSWA_0u{F+0P5a4UOC#UqBjvGr&ov1ZX-oX%dpuK{aQTXF;^UDc;x+;eCpTyuC!cvn zv>~u|U|Id7Zx)>urb+Y8pTE@?j-wn`ru!^uUi~Kx8Q4-c8vL}P;dL7B4}a(FxcJJe zqYZ(z<}En7odEx89Ablx!rt#n2lA$uNj(v*PSWr3PoHZgRV8G++nltQKAAKz-ssma z8q_O`(>k0ON8qg2uU{XzL2wTpz#4(@l={42R!*jIHW#i-Rd9%PRc*+I_*AbCG{OJl17#D20iov#mBVi z_6ZyqeV%_NcB zvsa@A(c|JCu~%6=fRCPX9^9+!|8KwkBY}qP5V;E8fB{%5U?P%01{jKkAbB*Iz2!@n zW_I&%_JlQT&>)eh08=PfPG;29GRBc)86W%2!#U2`=XZb|Ig^Q@BVRmkBhRG!ajBO;}|&u z4MnuFkP$_;U51ocWgv-C0`n>yvSQ5|UsfQ@nuk-`=be~3_@g-Q!b>xP-mGbJ959_1 zoJHngc1fq*u~eSERP+j21z~30AV?Lz)eUA{EMfd&_7^c0A!v5wu)`0FP6(*OTC~iw zb?s516RtqgNEcSlPopyxF>r8v8N|!?eHoEeC@fsGhycT+7)rEt%EZa>i<@tX;|@O} zOH(Z`5_T#c6@nQBgJ_8|&Q0&&6axM~og7Z}fUO#xGqQ z_gryR^f;$0$HeTNO@Ve|-j=0S;+2im7*m?{a_wfJ6nbeWA_TYa_eSPmw6Y5DpS^H? zy#Cf(@rPG?<#!&t_r5r(ZM)cq>_P?BRzXtFxfU5A;gnfRd4Ta1tkR*+a_(Nm|MgQh z#(1)fPyX$%F%TSFNw)sdo>$Xw@-SdPW`S~Q;pzG_puoJcWE6Pmz?j)k!P#)gsv5KD zmh8F@(aVg~5QO)mzx!?M&);WWbzNp*8`p0@&;_9_9g1JQGLVt3rj+mLG#x25W3Shr-|+-_m{9>w!COi_SD^+rMV*sD!hPX~Qv+jEEvq zHmJ;nQ;DZk@(TGZ1!OGwOn83%&DTWeXHsVWNxVju^uqJIM+ZvvJg2&5%{>bv9{w>? zp-ix0p6lMUW^Jq?1G+P?s_0`;Lat{QGGu72#J44kU(6?PM*wNSfDdCCFufIH%N`JB zudO1`NYUW5G3^Ka`{%J|?n4(~W)aF^;5x9%-e7~Kiw=@X2VaCafhYJ-L%a&guV#%s z>GJ?iwo+ZO4JSt>wVm&7UX%K=JQXnIc7~73TPa|fw9Yx>5olPma#ei2ZGGH*?Tz%R zI5QoSVM7MT$IrhUV^%MZUtQHR&g|3?rN39oY?ZMked8)OwtjD#~nvmDITOvGhG@i zX4B1v7$ETUhr9d#k?j`3XdsOg! z17I1nfR5BN8GvIf*H!3`!ExIY7`OEr#pzwojuXhdxK}kxTj588XlZQm9mh6E=(7?L zj=CvGay8}*YC2a9uY?iv72l2{e3e_u%G4|T zEUK!?#ry>e2vmA4r;F;&L1NxsHxQ{*SohbF*J;yO`sb1O+ zPr8jl-J~v5r)Pki&p}NZp6*xQCVs$g$zY#E5co*~ckgk8U-!dX$9X-vM=KnoitwO1 z!l1P9cHY|w4kqk@t=mm(FsDwYXXLjnG zbnn&)`%p;3$|?C{A=L>32M>xN1ham`>0A!4xINQ={dRCJ%(qH5&Vy&E-!~9Qw^z^R zO=gK{>RqjR&Ncaz^_valYrsLrtB?W0MLFr;zArzC+k^*yyN((Jqni*owi)Rp=zjjE zpT&JQ+!SrFoAyOF?S`Cm&FM4)%hEsj-f*eqmDQw5TGPA@ZuchQ}LDK^GShc;l&@oC>wsWhV9_V-?srQ`^>z- z_OE9NW*ot7w?F)7xOKt+%$gs5%qr(y7+)SW`DW$8uB_YnXZBkdDFdK;Uxu6H*`0WX zl}QG79(nW+F@@k$4`gJ|%c-7%pX~WylSyTx!MiNEhaUA0l$Bo6U(TJiCB5_0CFNCkKO*sZmY9LD>K2DYSJ}XzW z!Arh~a#en|pP2e%`+b9Pz20?VKf`tia(u z;e(pbJ~qqXi7C_m6>s%_7hLWWr?hJyhaTKA>S8k)oLGe%{R!j5;FLPg%ef~lGLCeZ zNjRS8HU}^Dw*fZovFS5r;QNh>SKfU)ZtQtobUc==taXYW4bCmU3#}MPbDpkUeeTP} z_#CUqqw6M_WBMRdmMIT|K6`h?^$!=S}MM-rq{wj1R4zN2+xYxUlNA) z^;YJiAGVo!ZvqYrmoCY^dvy*N_uYAnOHayB z%t$qDf?|V7G_F+)GK!4lc8RL|T^U5GNF|QspdC1o$P~Q(lrg`-VSfu{a`%&ei|#EC zW(&eu*^I^VQH7lZ$Ibqim*_2_Smowb7-J|<=56Lz!+#4zqcE9+!S&BKddCE!iajWO zJ+^i0Xok|*14kswJ0akoBZ)i4lWEcz!yu4}EZdWLG$cGS#ccxL@JEOtX zZTH-rrFxd88jMJV#X1c#$aLaM0|nK_GYV#x(JlMaSkY+KX%OE&Yx<1oF>1ufc=M%~ zq7M7UZoc9Q0u4=4Ac;$z39CF5*ePH!R)l+&(MeMxg#Vaou1O{}&`<&A@2l@t#^7N? zD%bbOmI8gayi5u(Lgpe{zZHd!t zveU1E(?7iY5;KbUEBp6OA(~qY+-zUZo@w6OnTeUbP;fg&3T&Ra9ZNWI!2ErV!qLA~ zAR0M3VdK~@`KLcV8birwUrM0i%ImI+qp56Ap;@w)w1F^oY=ao71Q0+*)@|fiG~^_z z4K6f5%}O~3`Ok`mK?IL(`}MDLKm55@UmK^Ma%wcLe_#d~wqls8cr*aTt-%VFfF*=A z_Sri#Hv@+cji>(l*O)eU=Ktk5y#&br$N#HQjgv*zf_$!fZo8SR`$2@~RlUN6RFmtI~dHjGedR(h9T z4F*W>yQ8Shu5N}m*8)?UQ&!>`O1s1>_Z!v6`oK8fk~A}Z;-vWCgAZacw07_9x2LgU zDW}=^-FJ7p)#eySQ1#^(pXWrDk+Hxv{Qr2}LOEe~94w8f59z7%^5c)jT;}uWEjMP* zlf4O+u3x)`Ms-EDUJ);BG)k4p%7Nmv37tHYJ~V5_NB-9kQr2i#*wFT=XP${?*}`@t z@Kz2;_jziD%9cyHWgt=-2k1rlB67ny=yYT-j(bL+^zXXmrudTY z+HNZGK&Uns*8lFm*1BWQdZ}jH5hd^2qqC|SWXWi0}ano z(a^HR!EySDCsJA1C~6Zxs?3^&FC<;a0>&x=%5=!au~GJjL!B(;ySyaa6L$Qq{`j2C z`XH*O`VSo#zkT3W(cze5vozKDq(RKwg}=`!1?@|+Fc-l8gtJ#MZ=6TgX2$AYI9$Vq z4vTkt{WJEYg#0F)m&2O303O^7jI|v!orQnVbEXKINE7mBJ{O#){AGDCG4jP$PaFVFpiEcaQiDd9sfuT-fa4|&>z zfd+#bzN+9@%VQJ3>F?=t@*&kKU0WO)J#V}rw@wI`A2EWZXZMp^S*Xsa0fdZ=< zM0ybnFEVv*Rng&cd;{)-ag1)b^_D#Pt@~wH?$|ofBz2gH2kAokFzBR>Rnk-Pm^xcr zYGbJLy!_kC_r79#!&?JBhzI`hWc;GjDbb;QhwSrXH+z#6@`f~^+%|wD-?#7~rcZV?6NtKSt-a?b8qVk*ctY z<=I9Dj8cDN|0$0Ro}{b=PH7uay=wm>0}R<5lFYRH>vm|9dB6JY!!hlvui^?S8hTtr z;Et^m<)JgT2WU6STSX-{Hk}LMv!r{*6wbxm3)@orTb)&o%BSz4=?{kwiyPQhassm9 zT!I)U(MRaOvNCk*`mA7eY@|%;Rbio=6(7~XowC;;n))JnmiII81%Bm+`DDl68t`EZ z>f0wSx~NASf823#h+E8%HTG~*uR50YyLj_TzT}x+sT)~?V;X1_{wCf`ey&)#GCs$S z??rXi{v`1X+*wJv-+udLu-C1B!a`VUPpYSweu6_er9PKm-QFWEw9Bk=lxCL!>nT(d zxpksf|9)`~fwhjuw#nest^|raSho-#Pirf_vzB0JRZ^D89C60YxUUDH7pcC!uE!&W#d~RUb zO7<~S2=#fjSG+mxi@4^jF7b!sSz#XIF^D@qLxWz!gNd_N^?sxr+cLS{&KJQtltN5*-h6M%^;b(&bpiRrrI(cnQmn;+o<$^g6pqPLPd*u4F>p`q&>?OklKfI!etGGu|Wn^6TIJF50#xBL$-xxz&Iu zkKtps(a54O$TC{Slj(9i1c&Q%JcWt)*%O072Sgz<@S~68pD(-=hqOID?qc6w%Y)2{ z6x9nwprKfUrLO`%VUOaH`3(XIkIc*fqcsK)cvcPQ$p&rxp|8j8z9VMx)w|f1adEeE z6E^OD-HGopnKb4KW3({Tou8K_SneC+frSyrd{qqYw>Qw>)`1t;6ZprMUd;Pndg6)b zawZB z7qmJouD|s*nt8QKSpP_=p5K$Ugh`fK3V)QH*{&kv1^BtgtsX|tJr>auBW!qNkA@G2 z4vlN>y+8J4_Sau~ZJc#x7n+DR%yQsOl)!6T2xIBrY_SHiCD9deEH{%W9z0@LI^*++ zmQP){AYmY-CY$G9|L6ZH5)Hnn8ob9^7a{F;e6f-gqrMN+^K5GGTf?iUTi_Qia)r=! z>hz!Af9Re&2{d$$y6oMn1X|0P1>9lmsJNsOGY%brd&~G*#n_6@U94NLF~E6t+^Cm4?K_+bq8z(7@l|9M^odYXK#D_9Yr%zcjb>@tC`k80r zg@J=J`1J>}u_t$EpIcA1V$kUP=)B15j;mZN93sI@KnM7_s8ZRn&lRUdkA|OUUN<&w z>DeQfo^XPLjv(NY%y~-eEeHvr@{09B; zE}75U2n=>?+%V2&iz9?KgR7&Mx`O#@cVJNymhsqW|h`-?Af^3$PlMyHNxDAuV{Cv|}hK?~y$fI$Szp6T^sJo@nOq7&IP18T}aap>Bei$U1@$4~XOf0rB% z*CUVmzP}qJQI|}eR#Y_fdhL}s5SZKnzuF8^1JqzpI_b)KelI01N|hwamh7FtoYmO| z0&J42UfjE0y$l|HFknFZ<+8xz6;b0-M;Mo^mj7Oe-iJ3$^Nxy@0XjWVs`Rd6tj^)V{(p?6_ z)wiq*>=nrq-cMS0T#N&Q432N+yBxA=+Gn4|-4FhfQ(QicPW9`@1Aq8K_Bq%N4!>dx zfZ0F;4cbX2W(+E+r@f>baiZa$0SqMq>rqbWgzI<>962JoLyKPb(+u)-DjJ$MIVknK zysq&t-Dpo_&>EU^T-PODtv1mn@IIeqxwL%jmNd7r8d&@FQ-6yGF1sR*Kla#Yaqz)p zZ);=#NV<`pwU1V#3;EK|fnb}g>R_i4&)no?e-|fiUGPMY>9fCxXJ30Q1Ed#{J@&}e z+LU8ErU4akv@1CBq@6x}`$g~Po{Cl5%g5aBR%P{xw4-HdAi>{Dm%7Q9@42Po-#-U> zDXW#QzLeX3?l`;hs=^za0W+%s!-YQdb1!B4f%OlFlRBT4wz4PajQ!xF_{}}{#PRgZ zs?A(?0iME9{u6HobhPW7i#CO}ht*ZeH!B@=zDiXT^5f5ehSy$?e`4=lh%d8p zaVk>B*aezig^exWNaM~`I$`Q0uFU-~XwtxfTd0^=+LF>_=~>EjVd6{N6p0@A7X+ts$^2~^?{S9x2M&tM z*$Q)X_40A)&G*JxUAjc=y7gi;ys+ZyZ>UhDZ;y0|TzA`tM+ZAE^`|^0TwIIK@oy`6 ze8cL-x${Yi;otOo_0_oMI(js?bsL(OF60O2r%uz}^D=O!Zt_y6lwQhg`N*vkR=1h} zwt@B(0=`cJd;6btJH3zto?7I1CKtt{K83JRhdZ7@BYh~xGa;ZZ63_m<8*ncVPM1^l z^~oon#6WD-XFhm8o}eemNhBZkWQ(l&&cg!qZL}|>Az|ueFw|hTGCk!G&lNt}AL@_Y z39vY~ssEbB*1HecUj1C`*|>51?*9API&pZ)asyH&zs0SO$}Q!HdgLd91g=F!&FvD} zd<2Z#ej^RpK-9p`aD3KRo_#v{Or0IqpMPH5-1Ew4fGoC;m^QZZP#MnDu**rnh%>&Q zfrceZ;*Gc7jB0iEjvh26-@ie9k;?;>90i{K=VvbazwUqk`#^(BR&am|sONtGAfQxO z2#nb~dNeFW;d++t(MKJb6%9}zQ8=24agX1ujX|anIcW6gIQym>bF3T5zFySbK*K?4 zNO`Wa#!e}NmSwh#BQd04;+gIhQy6L-8FkfIGHRw0)KGj2gAv8j)P{&Y$sbzc}BO}%-jVc&(9{aX%;lda{c~U(6)Kk&r z+-}jCy}|W~de^}4lO#0`HTrd&{jO_Q2?#GAs8Y5hQs-U)r4x{!@m0>h%Zk_Eh<2aav13$cF6&Wj9&hRFHEtB-!qhTx$8b#dbE^2I7xCdFR29;t zfgq0$d-&ns#<+!F#_25%imT|@eiRiA3f7`gViH$=zchdGP=UaYl@uBT-eKc0_wH^0 z?*r)lUO@Gm2Jal?iMxJju~3qQY)QUy zY@S&T-Ymx=-7cf^;WmP`;CDUGvlmM_6p0zK37<`YE(gZUZ@;Dz~Y_Y z-`svvoOjk4Q5)lbHFC%;H-x_UB6GrskarE{q>O|X4e}^!q<25_lGlX0_?SjtihsWN zQoPAAx{dhkS9$70o0O4mJCTR7Y!TS{9eLIFG#tc(43xYIjVm*icRpV{YixL2-px2h zUvua6XPp^mV<@(0+BC<|8J9++`3y8LwnmuS?8LWK2RhgqN0y!||CK+^U*l^90bjf1 z-}jfl#_paw3wTSD5j=@Q9qdI* zm&QwEH~N#2y6!6a5VSfX8a8T_&c5@N?<+EQ1C4GwbWX}dWxyKN=3JFO!p(I$zW6Y} z;_;YMrcaN5zRJ;R1iw#h-=1cWo;pFGfpL^kr9guYqB7nl#ySxO?F}@TQL{YS`8uvJ z_gQ{6A313w=O+o2JVHfcd-ey{pd!xi6b`9eY$>h54}N3a2AF-e#-r6R&e@l^=GF|# zXyi_(3TEWU5y;`UqF&1uaU-xfym|9H*&}5y-!(vOAjay0bX@o;-V7S&KOSf{suXB2 zC|hU0I>2pxd`xxCU+=j$_mtm&z0s3^+X4IR%jp92kAW^Mzm^`vvARTf%V4hEvDF)H z%}~yW13wcl)qtISZC>g9M*R7e-mIShia>S03ZXl1W9!6;xh*ki4!vzQQhw4os)S%H z_Qpf!JV#szYlj6e`3#>^9V6PFGZWFR5B~o5F`OXMG5hWn_n=GKuno+yza_Zjwu}rk z03)|%XtbyEFO0dgH4HFY#bB0By|okN!3JX1LUTjMjEU9 z3ukFexJ$#zUr#iWMzW6ppF5AVm*89ZTE|Oz)Bc+|XHN8jpH|V(xZ4?LQeE0K14!Cc zZo@K|BL6Rj?>?m5|2-PfeYc*S;9QqCq_rk}tXkf)%ICF3~h zxbX!p9uKb@{E)|a@tu6}IR#-7DRvXduytGG+wakHyrsK`c#kH?mE+rWjD4WL$7^9>($V6tEi5Q)SlfdZhs`$4>{IpVe{Pq&s2fOGGG_2aq8vwv@vynB(J7h(i!Kh4B0TqJ{R@pd~)oLX>Py4{2S|;5^?0j*bvd3f6U5C$*p9Tya z7B@Zk>uAPzFTLXy8eE^w2{&~!5WJGaRb^n|Ho~mrVNNCnb=nOq`Dg>X8N6lg;#QbQ z1Xk%T_>yf}R3pBEoV@Yk?wROp){Op51k-hht!OeRlDZnXVjwq9=3pH4o;)f)3nLpn zTkWCDTnDdwPoTk`CvLr~x9@&&_9-V9r%sUckvdp`c5u zQCWw9KIM$37JWA5vlx#5@gly{uW!5|^+zrGl~h3{S^)zorX19t&|i``UAywcK(hXh zIMpUlm-KlCxyZojPGCU$fjL#T$?zT<{BQoqhPfhUxt#P zQg|ZR%w)-Yepext0RV_g!V|e^41gz}^Yw}qF_5|ZtV7#lZglm?r^ z!gYGd)EagQDWl9XgP9xWF5{E}4HCCcS4em?PM&IkA=ipXp3X| z?O3}RC!fjYI&}b43@VIL^xUYr|GdHdQz~JzUTF;RQ@9yCdLJXC_n;x7F7Bojunobf zS_DzbvtGN98_;l`(uT18_dtUN%{mmFmqxeFmU#B^d7n?85xuCEn6&JhXxrd`=yqZE zJdV$`3TGp(CAzM_cT))Zedsj%l0Zw&GnE3uPg=CxO$EA+@kfmNBp&?p-?F0Nyz|bD z_HEk|psJU9fwQp@Fc9_z(OkQI1l(`D0RjBg$`#DdCOsoLdE)DsHUG<;cP*@EtP~1O$Hhiv7#HFa zqf*(R><}+1{1q!!a%uyO7}<~c%147a>-(%Y=I}#l#6=f-;9hFpr9zfGcKmNgR+D3{ z;8h!qN~iKLmIQ{Ryh}EX`7T7^e})6#v3YaYhurhZE8|f4i2#G0>NU>RZCD3iaGv?7 zVf1L287cC!Z*Q^?Q?opji_b7ao957wObF-{j95IGle6|yTs6^=p+zB1x zq;IwPAVvt|*ptDC1Zo)rm+GL31jjaSV{i1zn70^t$@{*%uDI;d?BAg*@%;9;o_Qv| z;r;7-oKM98JxOZq$++AttuThcnDRs}Ap)j5R&&|Jk zB=7A?F!@X}MrJa7zT^4I(tmhE{GcaU zdO!Jee8FuOQZc0wZJ;58_l)CFrRofgTq#-^?p2KcKlCoVrF++>tk4z4H^pfN-B{C9ybzzx zn;%E*TRSeIBE#eOw8sq4n;~@`R%2~J_T~vg@{@GROQT(U3YVf$9+HG{HK^B+B^`%N z@TN*}WsCaYD*`g3na8LRLu17%j`AZ4D~9(0VKorOHLH@f zN0e43l7&@}dQJY&j@yVFuZ+IbIdofr{NVegZuq7*wxi=<)C>%70m$Vm(a4%8`%0XY zdGlAt*L+FZ@H(LGesSoLoY+ER$j@iaipf+IK5*M@c^u!a=%%dllmA$^bSQ5r50xQR z2@F<3Uu*&|CeDP3eCj1VS{bEooJ1AO`!t|?@AK)=9=&%70p`Z_%aYzwK5~!anw^$* z)Fpl>U#iC)Lz1^7fsVUdbbduj)#loK7914qGSEo-fqT^{YONI^3$mf~S#Xz;@%!p8xCGI4+&jnP>JQW<8LS~77%C{i{UhjY|2VXgKD!kXo<67&dWA9LV^sPU#pe>71%Tq~a<94FoIr%zca!pN5XK zZT8al)0tv@3MIROnn^aB;hsPvHAuEIXQgPbB zxY~|DgU*Zd)yb7{9A9Cj0jVKoY1EfXmc+#2Lo<`#v{{QZ6b&>ur?oua6DNd+3Rvcl zpv|HRlRTbM#lt+jPr+-}$_8%Vf44HrEa%Ri6<^I-5Uo13&wXRgTSuzIh=mYBaRCnn zko_af{42bT8Vi3vlhGCMKFiF)mtQW5nNz34jG6OeFFe#^+qTbh%B}8DStZ_>n~a~1 z1@9r^Qh}usV_ZK|aR?iG3FtiK@iL6>8ScYA7!V72@6@AP(J=5toU}bM%4z_>{tp@_ z{Kr~Q3bM$`iq@=@U~MW8t2e~yyafws-qSax5{oz#nc4Q-uF((yUQGcF z4NEJ+*ZJCyK_^V*29habM`5$RG!~ifHrAQ{%Zl{j;Lsv^K5Dk{*T9 z-!~l=do&22ZFtAdRpYfXI0Z;-1=v8gg-j*c`Ke#b;P>xvgjO&*#t=dDy0ywjS?$_5 z{gj@2KT1*q%iw~>kZM=wM!fbPOH~s-pGsXD64ghv3T(!cw#Es zIKGVe3s+|4MqPaDy=w)HziLw|yIWMp$gKbzVTO#1tE}CtomodRWB3Ei4}**slT0O9 z2|D2$SsJzo^js0&Ag8g8fg@gZc;&~!>Bry@7T{Fl&CfEc!-{o=vtpw6+kq(= z9UJZ!t=kq`8QXUmi3x4kq1s zXqyhvh>A5Ew> zTSU`C4k5!~K$fi?1RCkMyttLvhi9`7s+g zycF6xx_vwPKS1yBskm{hqzMc~VE||npN{Vu+&W;uP{Ut5i6d{azlHZMM1M>rC^+TQ zNo?t=8tpru9u4Z&BhWxbi}^ta*^4KCa(_M#np1a}c~$nXFegk?Id2DM%td)@pkdam znel1=k77Evb!vVPCu1EO`ykuYIm%iCH`1TRxZ^l)<(j%#*&zH3oG34fppn|ic~AvI zRfPOBZOkXRed(wUCve%s63jEy1zu^dI9r}2&-i@tC*IY;@|#H2HgFA_2<9rE zM+_Vg3s$a<77gmep`38xcZ1xX1$JVe*U zK!ZJ1UV8V#*oS-D9CviIqJ+N={g2Fks+V%@j3qyL8Eh5)%4PXXdRO0Z3$PKbMMm83 zu2{Ju{zbOY2GskqwC3$PMN{_`10PmFCN zK##2abj-+Xc-xY>Hv#T-%gPd;Kkzw}nDWDhZf+f&Hf>5acU!uqSj$0s@4^v#wPU~C zD@QH%JXD~;?oXU1QI4`PpQCOPh7xJY68J%$kbZ60%anjCvKqZ0Y&TN6x1RTRuEO?N zaJl^ZAK4bPFqRPGgTk_+VedV6kLHK8BEV5IX3d=!6Q@jy>$;vB&5)5*p~IbYw&WrH z=?uy11{$=(t?bhI@pIv$J)8CuV;6x2P62}-W`WZ&AHNq+KWAx23^yoqd_2 z_BeD6{Is8~_E5g^$mAoF5ryn50!#*V@bnh`@s#uA=;HgIoEV#dIl z@Q_Z5pk@(7%AlanWgO?K6Q5gAfnio^fK>Ima>2DOUG`O;VmAnT%!fnm=9k)M1|GzlJh5QWmofbPeldCV#%ReHCtu!!Q$-pk ze;e?#DWsKCdOGrF{sUI(MtPx-b44)I=G^LgZRHJ{IH?5xV;aGu{sV^xVa90H_NX}I zki*j-ay)>X$w(7d@{jna4jqU)PdBh9ia}@Pk+@Z^XV3>&=~S=62beHdB*qGN-+w zMax5@tX>&`>e@w6leuM;2QZX|^er5_3jT;XRR2qyhzn^~dNmoW47Jiwzi#e)j_e*k zF%EChgl&B-Vt?dJR%|n-bC-T{5ag_K*h&`zQ5kS&aB=HgGohq@c-|@3IYi{vk@R%A+(kV(Heli4Z`*4$ld9mup8Oq!f@K2TM&#`x<|1J4)ZF6 zguNSV)Fh#p`BTwVr)<;x<|=9Mr4`7|i~rl0YDsbyy8dRD#n-MlnhF>dt4eA4qD8UpyKkfN z9<`zd9d|A5)WEfxAsv0-?^+B7cwEwY{*3uWPzvRke>G@c!$Kvm43N$%Lq~2|(a>21ZLDQYo8hS{)uZ)%N08GO9mz0tQB5a@zxy2j3CMS+;C`{IK$SGHlQXYph3%YyVp12;l5P z#mKI)M-}i1zITS!3~J?^bP6Gc-FBrR9B`IKwr<8a7ca#i*~)QCbz+}=4Ga?i zg&tIx*@P5BS>tXKFt<;Nje4c&YCLOK3>(#BQB{V^0^KTam2Vn>-!5Ac8(04TjqaNK zWV0%HN8{L2OEdz_#@gIVIU}#@;7Y5zG4^ga-a0Hg)urH-%J|Tub90Zge5xL*OyEfz{J6W8eH}v zGW)uI_4ib3RcHQt5uB=--^t)K_x!|51IBV#kAGY4_ATaFlYKUZ8LfJc41b?XN4!9VwJTMf1m z`m$uzAguanD-NR-XYPZx57H)ZQki4&YS!XdHRMDFF_^Deu~J|nk3WXaHt^mWa4Ws+ zfo)I?8Z+RioX|dz9$c^G)*k)#e^B?H(RE!{g63fY699q)NRR|bA~6Svq$r6=Vh}0O zl59zK$=PmKRZqLCR`tyEOiizusqR`m)jd@+%e_{wUj3u%*Q_<=Dp|H{OR^FbNQz0! zIU|%brt2;<5chIfOB=jgp`Ivlv7*15@6*#VggnQ)) z{UN}?w1ev`qLXf^6R&Mk*`zMv^ExlZsT=Sn9Sv^5>pF8PojTl1D`Z(!mZh5Mv#Daw z=>^cI^VGSbzNC)e+R7hqvj(xI%qtvr{I0AMzvLgTiB7zL6|zm8=2Ay1`;;f8nrR$A z3GAJhyf@??eMfB)ahR+Oac4OA;&)!^GV+bw$XECA6fWCUui=MOREq2-z!gV4GDoAR zj>$S$Mr?ITw6!#nS(iDsZFhcE8EN9>sfO&bafQGSxZDEPFkA3b$B!9pIG3Rl<$!RI z{|X0n3-R8{^g4R^C!7pdar6#=@9Fey>%N$FkyX%&a8obQjbFlR!Q!P+0M^XA_QS_h z4bFhEW7vWPuDNwjxXD{wH=Sh~o6@E7&#eX}(CRP(Od4nYrtEVpqe{zyUZtn*_Euoa z))e%y;*rQFf-7!ea3n^jr9qwYMq!1|RgEp+Do%}r2OB8ViK332ZB1}%#>kMhCt8}) znfk-207u1$(c{xdGZ5h+@&NHpBU*!89Y_7oS_$$$=~jJaRG)4b+uQg~J{jAHS>vnV zMSD|YI@i#`Sdo(Rm$kesYqfcI-FzlUcJ*o1shf|qZ!@xzF*2y4OGn2~C7g_g9=s3f{!D3{e+12(H z+my*H93Y&)RsX(9_RH049xcrl4|vf)98g2Rg+lmn(J)T@03JGZ`y-fH>VU2EbX|GR z{RPmBc7vH2+!nC5J#j&uRk}LI+FnC`37>2QJs>2C>^%C3n(JzFL z?M85yv3qR%HO6IDgC`Wdw`XViKmPr{OW*ze_rT>zv5r}fnJlL3FZK0>91Xx8fPk=l zFF(5&UZ@fnHXsv%{P01d&7^}KJ$xvH?v&cvG>J%xMw*^_3CouV8s1EVlSYq1)&|X9 z(4!<%HIg6^cv&z-gz)_1%|HEVnz4Fys+~MJ5Z_}VRjlIW%`C2ssg%Yi5M5@VpowbW z7>5c(2|!`!Z#qI`Q0q5*oSJs+PLDmcB96ZsiIHhqj>0ZH$BbJ7_Zf*xVdIqxRp%93 zCg@AVS22qy2~5N2-dh}KXX(>bUxt3b#&yu4rM zhs@j)5q9A`I=*dd`pQ53aYW%miDdj4EKqxCJiY^_0$yTMfs|<|EM;(B!pIv;pSErH z#+MZ0%wR6yp)d-F7@fB-MU&2L(?U==(FwkgM;o|}8-NRDdjG1Zb)TybQe)OJ)V$FD@5HoRnm+7j|YM{D*F%x9Y!52g6o2$`_ z8wd-}l;8TBH`23z^y3i39=~(2;aEC>@p-JZgBDYoj-z49*nT(~DpE~3Mg@+Vi$rJK zs-gl?05g^j!Wg7aop4^BxS;dTwZ27k=MILsdsTaZLobS0&j2DM{V6VY`8pBz<7xYe zTZvr+sgsv;`O(*&OOJxb?p1|Q;4sWV*a2HBC-?B@fA4y6shdLym*!+%2Meva2;+zR1dizNWZ zhy*hSw-of_EP_aA?|`Ip8}{czz4`fy=_s^|4(QG3mtbLOF*H<7;Pd!o#%W@pon@7_G|qS*F9i&yq>t&{q{7i>{e8G$)t95VO zv?(=wygn^_;iW9Q4cQb1Dff6~^1@6DaU)CTm6yri>{Ew}d_b7Vzr5emCjb)0Q9H+K z{Y@&Xs!dO=TE*!`C1JSxys&nBD$>GMgVr`w>V$8=i+AZqI7>qs7a6`ICxPFw`i4k> ze)8F8(n2EHZc~YI2B!I_icls$lpz_s;9rc}zMX^XZhy`}+Hx$ehs84YlBIBT!^ZT| zzxb0hW9k&XM;S-n$6PhOB_3$p%t156gjgoAvc6->1Y=fasmzUlFW8So5Z$WTOr)uh zQ#BSYT^cFAD$hD!m95U%!Fyz$hL~eh{t91Hn3b;@62d`#p~G?@hKdoaUP1x#hkjuQP8w;ortCK-Z8q(0n87a6sFEc*($_@fd)MvvNht%Vc@=UyrHo%ZC}4W z=x5TDsZngS9LI-aaf_e&M%0R8uJX;mabPBHE3G5F7?_KT8k))!*WIF_>K3NWZ~XZ$ z(hAb?C)Z|tKwOk2yd10YQsDU6wRX&I0}JDsdtDdXikeA0=X{3|_&ATF<~_Eib~n_g zr`b|lSy2(Rq;W(CF=yqgSSfE7*L`{Uy_qB8X7B)DWxz$8wszOf-Fwo`ZCh~8o=@#J z98pS-Od6T0aWvG98k)xAXc*i>h5*5m{y2F;PJolHtvo=zg^wXu)Dff;odEW)6TOGX z=54++d+#1acJ3nQ+HlVAIZ&V4sh4AqO4kbJ{=Fanahl1RMy>RLC4a(GB8Hbw?5LY zI*Gb>TYEe7)RdYI>`#-x_a~?iHX0*c2c7ay=aw|31J}9hG;nQ&EyE4E7AFH|91DH= zyZxU#cRn3EdNj47FUgZ;&3}Z9AENL$n~Z{M9Lop9Y@Z3Z)1TPnng*`B_VMyosR9{` zL91MmM{eD`k*t=kR8duvrc9d=nOtTdC^v(L#aMKTL6`I=&gXNokK0DF`OdbL3-X#_ zz)u=GNJh@buf38c&Uh%*p^J@ymWq*sAT9SBx#u}YM1SIgaP?)sUfMhYL>?x+N@tEu zCybH)ty@1y``&stJ@$-@3Rf@S6-kU!54wY_LK7z=f(s>7KK&ief;fugrk9b8=9Nb z8-M-R>7g}i(vn4skjprF;PJL^Mu3A17(tiPkWPp^C=i*dz?+!_e3bLv?>sf`wLh%A zu>Yfv(lbB$5yecW2VBKR$I1WTe5PA7pr8fqF2@%7HTUK44q9N2W-{uayoTe*xcqIS;NueN3rxrGa)0@CG7-Y?@m>&HVId=l6mbP31ZRq=3aJDT${gQG zDDE{fdb57h#`N(AAEY^?na-LuD-gnzO}(rd-Fo-K2zAjwGMRdWP6(w;sz9!g^L!4!8nFgA-#&h;J8=eC9&9c5E$e03c=b3m=JKxS3@My zvl)woa|~tZwbx$b$ffb==~YjqQleu~WCtddD`~!q$SMLVb1L|@?N*T}e8XqqB2$%# z2$Nh<-HqV+4d)H7e(t%b=qwB+(roM!p@uRBK7z;j$FXU^LuM)reCOwIHh3Qogh16` z7B(BVY>6X1zxkc-hT)YtB2>JcxWp}_GlgGFi$XT6UF=^(K?%i|eq@NkPA{~=@DzJD z8-dMkiuH{KHZM?2XaY*bB|NG!3Fm72wqu{dCEJ$;3{V=+;E|SC^;qki5f7Mc;MF-4 ziTe6_gxisHqNO=4dU8ctwQ>df*hY}PbvXoU;0*Qp3$I}=C4oH?X}PM8n^A&QcPV9d78sB$UvGNTX0&1jGU4FeyRi{b*V zG6$U*g+wDf4)k^Q%Wl|$@(Fn5hy1J^`YX95K04EJl?3;T~ZtWQsW?Q3i^SP;ru7-tAi z(~?yV24m3oBW0nNdE7%vE389V2OcUM{irBbIKphETNFUro!)u(4V0CGX~W+7nBx?d zq;4YHQ%c9Ca_V1(bSbCP%8^Kf%3nvYA72hnI zYAD8TeH=|?G^LW-J~L55O$|315sDULcfB;oRrcM}Y9vnlb4?ZOzFU|t-&SUnUmosU zKH0uKee~XY@Zhm&I!fr|x;lyjTi}ZIqg~~aG$ZZ^;lVs-I%kZm@;m3h z|L~#oYvj|Tix#Kl80*ErRo3UFu_Jv5BXPkDK<5&XN!oGDuB{5Y@ROGbA1^ZtyC{6N z8Kd+l%Hj`x^dq*4%#AfP_1bZ|zF`3IoP5=GY(x32OqcIUdn$+GjIzotkn-lHrlxfG z(4lk;xm^NGo~G_X6}Y1#)pZLJVa>wn0xYjyMP@SRQso8x7}32&v`o5E*^B@ zM919Ye)!;la7fI-$*_p}0v5jXIRPX;3dNGSIv$NXJC$ZN-j!FvCu$qP=f%T(8>q$f zw(Z!S8gVo@z9*Njh|@;~)8=LB)|f%(`h+}Y4mvMg^WZJEFU+~uK3yOC6;_dv#8~zp zGVt?${5@^@^f=|Ava&Lq;41Ij9OKLDFNuTFl}4D{#_TD-6CXoo;5X+olKL~Q{k!O5 z@4xwGdYVGs9)D-%jTt!NyU(jv$igz*$uj(OzC=KU!G;mW?_ospjB91z!^t!`ja+~2 z_1Dwc&d&5zbb{LIsu+i`mL8%_`(e#=hWe7G>|0vUq2$Z{LMA}VLx_a7qWHf9On&p5 zH>pc>HXT1hg+{Kq;|8WlWYkud3{K;SgyJ6Hq$BE1@VrKI&z#wCpDCIA)kcNnrFWfr$~qgJaQi&+)kpQCvT0dSE1MFP=|(i ziATaF=ReY!{Ij{aB^^Ij&vwA$scOoU^el#>1=P>t+)#g({&U(69u7?^kIifq_cERH z?*jr3%J0Qvbv2L1Z8&y3*65-6^V6fqR`oG?sWhl_O?$vR1$^atmjQtrp^Ie>HOH+! zDEw?=JI3hy9AiBJ9c=mxij6``@)7k4<%Kd(e9*8Cegj4aEzpjAXAWv~SsXgS$NJij zY;E+>_c5gRzz?2Sz8r_+vGtDg*0#obA@apS*~%w*sV#b}u>7Krfd(wya(tHc z+`V^iI*9Y@If}nq56^kWb{ocL|Blb+g75NM=zFv$Oxy;e{iN*9PS+bmw&hi_Th3#1 zUQK6k`0m)TlM_$+Q&9RF6!o7PJl4#iiN$8?mOx1sZREWvmXpcgGCH=G?>C<`lCcHQ<34RWGDngZjm-J8W3)g zdV=y43`$~z&~IZjtlRi8CmOt$W}w{8LJ6&!R28Z1BAJXpg!AQVd@%ssc1TWnU~*tulJaWts>CY))uE= z?84D7rlKOffMGWdCU_fs$rxuJ@d111FHt*I3*?!SrUB!MdsLzDbj}J;oiy$>JBYGn zrcFD0w-!CQ9HVq)8mwSr3yJ&B17CyzwTo;+Vwu?vYQ4yaZ(jEb%-3* z)`lS(?J{D2mG0 zkS*NDEg}Ep*TObrgibyBxW}A~f`-gu&7y7ESHbanl^fSyWnl*>o1xpB`WXDxz{D}L3 zf36?IJc6-Ej_zRsZ9izx|EHVrv+@7GC%^jm8m+|b2=9vq#fa7fI}P#qYjzmJ;FqM^s{)TV`Mj(P4)13 zwWP|VgWNTW9 zKBKYgNp1mG=IL0}&Bd>9$~bT2j{30rhVn6-58M+x)3xYZn*#9Oqey?s=_A5f9eWab zWH?nBBSVXI%50d7r#OCJu3u(SoN_y>&dmt+fjyQ zJVsqL3z%w?>AY!3i^2)MflGvQuz~DHlP&s4;R5TshI!p0*K$xX1l3fAgEEmTX5FB3Q>Ze1o;% zNoutz8$+QS|&=>V~g<_50sRU!`#M z$cpi%7-hVVbzl;G(EakheQ`$v02Qd&iw`a^L=x{XUa|EUO4j>CNxSjXTVQG7+()Qz zTN6s4dpZ?(7AuN<{4mpDM9G>JB+ zOqq&ju`-U1QZR{R8qHxig9sv(&qRxmi;criZ-OhZGs?ZV^tF5cFs zo>`NYE?O8-r(BU&7TV_lQjV}xuuVi6 z(qW)5lBp^<3rVNcP?pf017F32GGUahtKz{n6+%We&1l$Cds>u-l9J$iY**xwiTRgM`6@xcoZf(d*+N_ zLJImweTC`hWI*KbA46u~xyRn^q?4C>FJ+NUb>dH*Egq4r!)MFb)}7e_domz84b&E zG*GAw^kp>ycCMLtWg*#L65*XWb9P#_VtE=psx^NPFZ4@99DLz6;E|aWot_c{+XAL@`?KIp>{UN#!c z0zGLj&cOz6q!anD5gyyn01`iPhoj?nPSTlk@ZK(zAtSs8;FF8tF*+K`iCE}_(NPeK zL_dyQ-XM=G2e%=J*w?Qz%sYUNWzq$-gUy5@{r zWk&+%3bf$XfvucVo*ET$%W$d$gfgqM9OcT~2_TH6LaH8eD&uagGvNeRwN*%sL&+!w|I ze987Ska}@c0`-tdZa=Y3fpnxKljm4`%q#(mmK`Iz$s)nlz*zJ2GpVMkDtNkl(%^=8 z8QW5zDIMVAvV6$#>6j8P^JDLH2IxLD_@VOe);qH%nizXs-IVkMj)t-5HnuG}eBk#xt&ykcF!KXF`q)leFWlMP{+_8vGumGgIaW>A_sZCaW(ZF*!2h71Ds9t)^p z>IoGVF>@|n@=fX0ZK-ZKuu!C1Ep)oM?L*mm4c+9U4I9#WjHAaXh~}}f;&btE%xDZ= z$DSFz^8K69wlW`tihz=G&i&8+ZG8xN%^-MmIQrpVIvUI{y^MnX%<9z?lqLeJ1BkW1 z$Fl&KxzntUUQXNrQv(({A#O9)A!LV@j9_~V_uslrp;_7<1irSlam3s^Ytt*gcq5&^ za-QQYGe^U`G8_$KMo^=nD2*?o3cWxgqe0`BUIH#IhFhv!6~`;yWGn19{0GleN0FXP z!@fcF<9i0W?w!Ti_XEtkVl>8QaK>6;mxRC)1jw&zJr-w+- zjPEkfyLRHcbl^J3e8&Qbd(l&mBfB*&=W-;xr;n)bTE9v;Z|wlvmu97*JVU^s zq&!P{)%h*Y_uVVf;lX3GhTkV+?Fuyps;X<^_|)pE>TrHJM)^t8EI+y^l5BA92br|v!Zf(Rfftp4W`L&45;ZK@g;vB zfjwZGmvQW9*A(OQ^pvUhKKwB4W_$8-`1|DA+E_Q+2s?rG(IyC;hIW*%X3{y#%Va~? zhdfsqAa7N7^<6pToLa#d9e1wJa}?coOQJP|bUL_plQ?9qTqTJKY(Ba^BAvat^7lL~uhzOoL z7pYFY!fhWq8g?T?UjEK^(&LXTU|e^RUmSzWf6gzrIkYW3`9UX*aML!DHq>W?jXc!* zeb>I|Ab3)bKC=r4Sby&Ki0rB81~-s%cW6hORXHTySnJF{gfP#y{D&i6JP|Go_zpT` zKiVF~nqEM@?!y7Tmy9@T<(x-W>B38d5=kh#{H>!Qy!G^_ zkj@cWA)taN6V%v{k(d_KjicdLW;7f-5+23Llj~9m4hX&IDnyQFFl{;}+w*xDox~Ow zNFp(YSDrbkK;?T-Er!_C+M0g$>d%6BSFK!$Bc?pY7b!C|;MiprG6;!AMaIZOC~Yum zm0XprfD?U5EY3wIgo@_QJ$usIZ@!UMt@#Q^YAuRLnqv%R&Dyw9!YRhhCzWHFK*j)W z^(iqZV0gjWHlC+;Dl7YeV4F0w9R1kk2q*O?Gr$pDHS<{wxi=AhuP zZPQ1iN^D14sz*TVW&EWTI2vGrdRxU0mE_pJ1?-1Xa1Cq$CYi@F<|9J|4z7d3K|@g{ zsnS&hp_|UUA7$&vAx=R-p;)kJaWFwspWT-wZ<84*AZ2`NE&(Ing`3RW_C zpe6uWbl#3)N&wEJ_ND%V$-j;{uPO zpbwLQX%AO%Fe%u!@7*0Yr09g9TtX8WapehLDYdA$$`hvHj|; zwClu~w2o6Ja92hR0XzQl|L&jTXjqmi$Bf0eLczu{VWBhENLo2~%pl_h!=ZhT58ZQMUwV7(yJ`Q?BWXQO z2d`>|J9W|kG8#swaX4|zXy^~k$My-vVxdcwz>MbqUJiklL08U6c>8kR5SCMjlPd1w z{OH2bulVty=L7%Wj2 z1sI;jAUcSnp$Vlz1>i9ZjK@(HHA>y1~wUgUG;T@b_s`rf_UsStx@l?raNH_p$|w1dyeFJIz%J*#xjekf z`VRmnRHQXZU;X*d(*W@Q=~b&!6+F_Y5l!BY)`cvw6X2fnaQT9~%{GO%e8E?w38Osu zyUOJL!-vybq?0dQwmhv^x`aY)!*M(zqs404RCY@%Dsj?|b5`-pj9z(TEN_O3-0$x` zcLAlpy`6{=^wiK$pT7QkI2y=8QjrXYAY&6p!uY2TWu9A;1|Vk#_CpqGc+l^4=<)`J zpOUOUF!2N@ok%Bui?wWa6Ya8~&2iW4|8+}fveZ5CT6RxVpc^m$ZdtjUL@w`d-x$2{3@IP%q!r+O@TlB z<@Y)rVolrH(xy!tQyUKJ67-n4IC;!m^MsA4UM^13hjL2X7cX50GX`8!*Urlt4z90N z(w)PwVvI^;%I^L9)0^l7I`WLby8UiKMP)b?Z(hAl(MWL1OaR92OI&o##7{@=NmCj` z($w|a7*g~tZF!>4RcP%)91R~LpB}@3@3DZD<0{ff_?=E7Gu|AtV^>zm3)E`_m<}RO zP!YFb&RO9#`n7#)bm+7-)%$h!lv_;J;6oi-sD`th#bVCAWQAnTP+&p*gM0mlz$aNd zjQhxBKvoZiw_3chhgu8QuU!d#P>4R)a_V$?;9v_!d)!4E$ zsbqK>GmIb-5J0g3F5m-WXDUHI!dmVQD#e`m7no%{Pu$Af5E!q(^L8(IHhfg-rCv@; z_qnuj%gJW2O448bamRpgjwziZi*6 z-PGI?C$k(rcqmm?Ri&@sxSI&h81yn5C~Ggn^W1@_oR4f1)-H4c`i$%v`ty>uqCQ4< zciMr$s6OTviv>#-M|~v&KbOhi5pUG-9J_cPMzw3eXB`c$L)Z<_u5_ksR7cgxpRfgZ`C=%7nx4;I%jg zXR>v88C&nlpf!1(V-jz)5#(9&^9b(o+3nlPR&g;hw4rPHZs?Enue`nQXh44K0_VT= z{qM8Y2uB0Yn=L1N!{LuS_0pN)ddh2p-_U>9hTNaofY2)U8f0}%%ns5)rK4d0>+p?l zd?QV%t-&Ej9Wv<2!oNe2^YTaadF6PDFQ67b(fjOD=b@AHO$Y$`^_)7%4 zEu?+w#L4u+cfXrn;7IGzNmZ;T?LvQX`Nmp(nXfPAXmIA>aZrf}onHYM{t!?Q&HjkM zzMIbBB^r-`uy~#s4YfEL*hdbaRn}b~YcA+bQ*pQRXiD6eCZATmco#8m@1OcA>d^Hm_LG=wn&7$gq8hAJ_7 zxGi+1(sdjo?iKcwS5#EMyq`{`j9caw9%7J7#a5+GrX)f5+4;D?c#uvpL3aQEKmbWZ zK~xb63`i^4ipX9v50TRQ_1d|0;!POIYM98f#f#&l2W|)^B;mm zBOd-PY<$MHWnwas%a^aj-s}w+)U6%u>G%KO57IoCiORE4BG=02Ea)TL^%`gWp-9k= zseAU}TA2D8;|4DNc9rM#D7v?9Ck(csy z!5wi$Cx*Rfa49s6#28&Loq65*bresk4@J>Ew)0S;jj~#SRz*FObzrNrAu9p|KH3*T z1TGo4WW9|moQM#Dhxv^xr(!hppkR9oMX``EPA8qqbh=6en@lf+GB}e(8d+FiAsqaV zi3Dyqzk4u8vl%oZ#VHN;p=4j&!pMG$)Yp$ubf05jf5`n8IDYb2qe(1{E=JC!(v+V1K^2=T<+8DBffJvKj*z zYd9KusFvJyvo{?$eJyP}MN||)d`TwG^=JR$pQSY`m&N(YgE^tXio_~T;)7WSrlVP- z;h{MXveQm}-9%lbv?I=FBT!`Ne^R3;+h2%3<76*ejp(y)S695p>v5Blbh z)~AXhTCLss9brP!4POnJ_opCpZ_(+tE1r^ zl%V}MGS^YB!K;d8GNWN4DYT=9bN2ZlJo$`=SPeL8#090CajFceXGp;D#z&ivwT^dN z%jg?4U`V~2mw)*C>G#NDnFubqeMsl2%I#2`4n^=<*T_sK z70@AtWD;o*(02z83%hF=9c-+r#ilPdIJWb_C2bienIz-AlbC8yV zbC!K0Kgb-XB^14~=EEWA^w(?^GQD%^jOpnS;9gf#6FlYO`3sSGVX;b;B9$Sl;mey< z8dNqF_9~x_TlyS;0^{i)$`>OFpTJ|*kufoT{CEsHimTR5N#ltmD`#LNyfaPtAfKfj z9hZE?GRteS%r&FNanVOajNlm>a>|c4iRc``vFW~P6~^*-!t5dM)39?x=YJkCKPk77a0OxCiY!evL*A4;{s3 zO$6=GhyAZlPBBQinJ{p4c}lZ(gL>Ic(3!MxwwLlOSgQdu{0PbgK5;# zwD(;>_Ic8dJjSDrM{_!gTa#K(a-11>vvunhWL`=7=I>FMu(~FqyPmWYsnM*jcw<}g zb`6$rZ1DVj2Q_%>dP~>xd84q(kE1xhj`QklZ%>btsq*wwrUe(K(;c0Ge;RPg4UJ4c zTW`Wk#W`dupOvHHy6r<6;gq(fPdoB-J;wU+BZnj6{wSFw$`3PyG>SaMLOL_UAspgR zzwpsn<+{lGU0(}dUb{sG1b-X3AI1qbX2k78AN$oWUyGAB=FEABZG8`?iIvo7K&D^7 z@a+%X4`Iy1F=mEC`_4n!jZ|#<(WziCNY{%Rjl5l>Ps7NQkKSLmF1-W2>R_Kc`=QwP zJqp><13vbUy{7IZU5T60ltzm1?uWAg1c+=Q9U}H~Pu!tThzh(e;`rCD^vY|$NKGi| zFTV65+q`OVVsNq-^xVT-X#w2BaRHy}>1V-R10!a#Vl?CU?$0SYo-%afx^=%ec?`G| zxF@wgPside7t!xTiH6(4}b8(*tQ}+yoEm3 zBToU=W)a3|367Azm6_6*dbaS_aMsB6q$IZqjV$GuQNDBQgxgJbl1e_Qwk~~xtr-(5 zDmaPYVr1({t{Up{T-Pl4TmqaE&e0`{<+C9#c+s z>=REeBPcdol1rBuzkE`t}gY1eEC0@ypZY56ThgRp;GMWT1{Qb%HnFd_6MN zW}^dJxOF@k4e}UqUVg>M0{)R9$6ENCP7>Qz?y0}$?RxTy(Qjqfd7SHOkxd6McvoQ` z%$znYwjwDT;)D&`=ia;~jIdYtmS)X75H30=V|zHTiL38jeYgeZ)X$(N>(+ct9orxS z4tn{AGFzNc4jL@9P4#u_*$5BeEALmo4p|PaiJRIru|~+@gGY~~-@N`tdVJ}U^z`x- z*>*~CPT25ry_9d^jN`Mqs4~E<>FUB}BAKlsPq$syK<9*WKYR9EII4GnlR6sAFjcl` z!$jsDb9WtmDGx&q@vQoo+cLFzyf<(a9^+i{Izt^eG#ezaY)1oeTowi3I2tHB@PdBd1_YrsHW~x$qir8UPZc%D`O|V2`s>5DvtM z?cv^!Hf~Jsz4vyioia5&MEa#^h86+5O6riFuiR6qcU6IDimFJi(j$>dB=D?IA{?_G zMz5hTsk0!#FDa&2fBYC#y;tLCFd{WNoFb+}%d87je)@<-rP}e!1jErl`!pF!k%qQ} z7)OG^6h-`__4Vm*e)`kc?(y83uTW5`B#2q!QxOcq492VjLjzu=RD#nhr&Gp$Zlh$$ ztQ6RGCLhU^zMFj+4R59uctfA;b2O+NI{)w{0(Ws)Z=%EzDXygVd~yAN=s2q=#X$*4=Oqyv*8hNX#;kSUX^&=TfJU3_*p{SqDej2G}mdM0Sw^B&36v0rlIs`<- z`Hq25v!W?#G_8!-6|#UQP6J`=~9QBoZZ8r&+J!afWNaRP)9=Trn4cql^RsK*m(Jb{JaF7)I& z6&9x+l+Cx-u8lenYxJ(-Xs{UMW{MFVYN$`^sm$#)2Q-*gS&(Y*P>&_0)U6Y_0_N|% zEN3ris(0w$Y>X%<1Z@0I95tiC|8&tsjR@Bg+;LOIU6k9?*L%|5j>~C%E5!o&HmkUi z(!c*#|8071^~zL%ARl-SV@5{<^d}u^GW9 z_drwD^U!F^_AsL`0z(CVC}8lP;63oDJfmUj`j68~FMT5|;Rsdv6PgO^Nnu4^3YUJ2 zsfTO^;zRHf)NvH|Le|xz4XqzyyTgb&>rCCXe_wiQ?K^2NxcK4jT`|6Dnw(xeAWbSQ z1Ga;4;;??;`2g0efX%_;x(bixuDI^}GN}4E-+`Fortf~@XJEv7z*Fupw(gtkooqjs z-a1b7k~_%XitAtf(LYPye(8lYX?$fE?DyzT+%&qWqrpC6UnA&gW`KBay85m_cW8g!CD*P26t2RK+Y#B`KK^nx|fkda3UGmRvOJJwF8=2jFH z9Ss)5lb)v3O^%EP=|i~|M;uC9^yiqJv+FExam*@T8Gm7J(yn+8t?7)`(eV1)Z>1v# z52iI_WzE1T=$1UkC9I-78j;^CpQK&0G`}Eg ziv05qQE%J!C5{DO-c^$vb%M%+Aj zq`0i2CQdl+c#daPbVJ5M!UK4DAOAvQDCxeSSK;E8B$fZx6RkL?4yRAHZiR=9PT$6n zQBzaH*g1iO@tYx`0&RM>4j!HI^30Igz(BeZ7d6(UwZKsnf6s*Xw2VE#WgkxbQ|)aO z`&|}60v)xN*l(_au9F%x;4`w5k;+57qSzkq;)k+ZUJ%A9--U9GW33Y>$;TgWh(eYH z!0?F`E28kMy2@oz$#Vx%q)wv);Q@$RSCQpFXY#Rr$n$&P>y_*1IxLbnUkGe8-ow%G zt6#>t%_7ro{=E5Y7pe-HzXAX6h3?Ie$&FHVGv!}Qi1uwyI#MPnt6~nIy+)lzo{on1 z!TALgGt{7)g!8Kuy~a$EUSyv%Ds9ORgpF{w?a*gv$7~X1ULIZds7x~&Jbu`^P(Nd9 zTnlxBtkE#7j;*XZ8sJ4eW>>IQ)@2|+gor=iky7|i2Hgd#Cs2?!vOHM zpsL#Kkym|GuLE*r<0% zc&;$r#w_nC$9eUmM$SDlGwu!~NX8gXoV}EGA0&E85h7hto;y@WZJz)1lfOz&z~=_g z-!1eZot+x2;(+ufzH7X=2D%50d>fq6(cre8?|<+6IC*A=KA@o)*^9JcK*1m#g9+R; zbJfdjnf;N8(uKT0qgR|M!dR6Co0@Snkj=0QJzx_2@nurU$G|Udf{zCC*OJen+bTPu^Dc}!9gc@_#;Wr?x@1XOv}jS(*SZP4ni-&hu7gCL zV!LJ?heMLKhb+hKA)m(Kkeb6bR!8b`agsskssurPLq@>%%^TBdGI*pXw`KV3HP&3az^zD` zoq&v@eRX(o()v^=unOAf&%j^cCcp7Na2ps!P|avi4(q7S91ZY9=5E_MFQrxWEXN~n zvtXHvC7{D zQT@(9lg`(?R)aJko;r5r&ndDr8(Nyt4Ys8o*5X^#fS8V+ZAS7fh+Gzxw$^p9gFeH6XX+&e+d0v#&L4Ap&^_Noj6WAPIsn`_O|rWx4unA!;5J&bfvDL z&JuQ!?SILyFYagn01}Oel6fit3JWHymAF*xjuEZf1_SH_m?MS`kBo+ylc&Hq5mEw_ z=MguVp$4LQM4pZY1+WH^Mu3Yck}IT!;t4j&2DVsLFnx%(^7UW-B2B@;U_mKQo+u&p zRU<;hSmq(aP>?w=3sCCG)oT}fjv*x9!wbdYiij?8pdHLswl>(6Tngf zS7R1T3r5rffq4GB%v$4JreT`)00gZ2Bl$X*6~hiD6Z2$_d(0+zZ*5uvp+}Ta=0MLr zt1!s-Rhb=P%9Mt%2Ae6z&M{L=VZ&>J&VzDKCf`?w_QOJB3pfJnY62q|o z-l+WO1hXIa`g=K#Sa8}AcT^0mbWVq8qToDZ+m2!M_M5*ZT0e>{0<$8WP9euc118?1 zu@(vgun_OVAO^mmdd7TF`aqaaUWSoD;7JL1^wJ$t71w_7K@>Y%gNJ(*FtP5zW*DyN z{qJnu9OIlzSF+?m#%A~MZSxiS2cfAgp5`8BK4xH9%bbCkj$+7X7m z%tgHQsHwNu>NI`&%(QaZGU#b!j2BfW@J9IhQecUj5v5~HI?#+DnD%b{1L;h9b#1-e zN2!6KQn78*790&Pr^O2w0yE&&gQN5o3jIyAMZn-uW*%L}3WLv>6QGSLupUom5g~<7 z5!q6=7{ji8dr%~FG#pGH?94J6YG`r>j)q#Yzbv$Awn*=FoEaSOu7_XRH?u{dE}yl} zY?S`d=V*u@vcFk&(eeRDLvK3Lc_nRaMoGMRFA+?O>wo^^AE$5OXsDf31@8t1z(u3i z2&W39hMvv3bs`L2w;uo>`G7SVnj0HKiFyPB!>Zv!ai;Vlc->+q-b>%oXvTN5OaOVM z%1Y2bgS35N?f33^9Yh;V@JP2#Tmt@+s;kpN;I2~{L?*TNVywTkWi1Tpvlslg&rn#v zt(ZLX*V&aTiSl=krP44meShPI4dG~*PQ<9Tx+b>VDAVLE(g%&<)Xr)Jg*;*&j$5NE z90shZbI2W={w9xbAL*Nn{Rr?`g`zcMI#t8NQB5rY+SA!9t|>dLG7i-Q56%_$P;&X* zdjcnckj_KrWM5`9cxsW^P+#F>g$lNRgwn})ZNv8D!@}O@sAJBXy2A++YX=TQ__LDLjYH8>!Qm6IVmQMfQ}@%Hc#@&mc(6*5;j2Q1`q z(wg7dpZjP}gEv+UKhfICsSqg9vu82Jj6VrG=O-Um;mzwf$veXkX51PV8q}nI&>Ig* zXg-5nX~BVf1P9eFvQ@@#*88`}XsD>IwY+%*Hv%7d#LP7o5}0dnAzO3V42+EA%0sy= z`qIfjI!fvV59Ptz;qh&Z{n5osqF%rVf*ZF8ZUk&~0Ko4|vsFikOdi@%(f4<8GgBfn z%9W-=K0!~yWAheHacO7>$Hr4+Qa+3faeSAlQ6OFFuvcjX@XU!?3CJ|p!?joD5IR)I zXF8D1dD<^Vj^c%iQ^0iGsZUv>A+{m`8*B7{94r8M51d0-fG@(v^;4EAkHX<@U*ZpR zpbV7jTXIF>%@li+It@Xe;f@bTX-O)#gkI1K{uOFG&GeJpc5kB z`ZM=Dqk*nKpFT$e_k)2!XMU2KIklia5u3m7DXWlKH^_Fogm7%>K9A$)T&ic-tXLF1 zo;H4B`pdug^R$#TFM_7}gNtrC>19&tvcY#~Uk4bI3BG1<>omcc&0DraeUfj!{7v++ zSwZjaA9uTv4t<|@UHvZf4&KE@4RUcqoVf?iE2Er?GVvNT*xcL_^kjCj84WMt7#v+u zneO8J)p!g2pUE053Eiv@4)P$Up6S^*1jQ}jrGA^?4~_<$b34)V4Cd)Pn2YRqjDnC+ z3=-VdsEhH-OVn`~W5`k7BT)4KJt>bexz1Ko=L9XBZfHpFy!|!~hsIQno@7y8PoI0dxfjI$2oiIN92^kG4*TP6YM#8CR>33ZJ^WCb zP&t9Z;K)|iMH<#N(n;cATvr3B@_C)_$|SEa?3si7Cv;)(Ksk1zy`5tBZ$Q(x)6>YO zNu10hy-1hp?D8(@RrzWyE8(LfS-GKOR9sY^WR8POH#W=0MOUZYyPu4>SN<+NwrFvB z7WpJ^(jfN|?m@S}S*NHDg7}WM9gjMIx|j~fJp047)tJ}z(pkM{@4nb_v*x+y(gJKh zpZ9k&8gzDhzdC#bIGL|9S4XCfU;~3Xe*8UfmT@RQlwqCFl1FoHAzS_yW3U+H46-TZ zk7frsHw!hJ85}%^H;bUVw!+Rrp5nJML>)mo)$ve(oV=xS1*Xm++psU634@cfO88L1Ww2fKU-Vh%>+fDo;}Jd^}ZsJ)X?H zXDU?Uf*xa;x58Y-%{34X!bYYVo=n;n?!wBxJ-fEC5oMyjK6R31Gn+ko3lZw2C}NIR zW+9VP8I@7ppTB(o7v~YMp?&*OaOxC@C>;3PMx<^(47Quf*ea(+jV9OCMQWZ(v+2;JwH32}5y8L(Tg% z9uO@sJRJ?Ba?uw*$Na=wIACNHs2mhPPZ~RyNekOTVZ6qsX7*(-3tTs2MbGq6V7768 zW(+@!PBLwLNvbX#k;+G~bz(^7R)q5gZS|m#F~Km3BH|^T@t=Yq6f?$g2PQ3^>5*sk zV|xILL^cF_ad9+!(%6>X>+FeY+_GJ-KmG9!)3POt(rETWyY<3s4A)e6O79I#WRt90 zpQ>wX(&HGsreBIz5}fI1&rAz|f`7ip1(f;H zSN^xtr~3yS4L#{#$A$Fa@vCuPW)`OO2QPm;tzNz?RaI8v{2^n3HcZn-`$5qI=WU2f zLpMD13Qxvhh31C(hTxI%sp%LO)(tUQ?Dik&NuDc><_bXY2IwG+Roe7#X~=gCQk4Ps z2Pde~47?+Un|{%W#B5yEu};14bGAR~WgTu5~tM*AsdL=HYDM zOBFqN;69uHJ9li0NRd%*i=2%l0;?h}UTMV3-(%|@_v_#ZBawbxZxu56mh`9cCY+py zyhmQMZo|hM-F7sNN3N@_iKEZtw<<*PN*6)?$D&ePc#aTITK_;$cA7cus! zlj}krX}E@?fqMf+^rO-&pK?8-4hQgYedUcRbiyODeCX2xYMn%hT3TA-2;-5ZqtohD z6v{+F7e9^g2LA)D@;u?Qw zPE8eH=WIkvn1<31jMP2+-b+5{lG?5~Pq*>60})3(-f|zAPN&-1;v}QTiS9l`q}2P) zlP)Z7i)(H_)BsQ~u(pots$6va%!E)j$>VaP(QQcL?$P?=Y177yp&z(secH6?u`N*; zOFv4~LF$lw_duBZ<} z>&PBu^zYxUT~l&Ts3q~c*|3^Hyw^NfrJ=Hf~Q@-Pqa4~~=RtS&CUsrk8POe;QnucuDj zrN0~fD7a0=MN9YDv~}0H)WQ?FqoJB2!2kTe`F-TeoHPo28_fJ8+mGU$8RCE^v@I2z zc_Tl#$vU4$r`nA^*3r?Po*^)!KBj)B6To$qKMHR-qWCXDpPy z!_=`)f{TsF)<$rra#B@Vv7Ca;I5l-Lso9uLtSLe*E1zxP?pys7^=m{Y-m1 zr)ZU@`8YDBPMIPjjIDsSDLu)f9AD^Vz#?=;_@M0x7kOJILzozF7vBLMh5Zhs4eQr| z=jCC0RN&0;=tyn}_zUA)M|B-sLwU6AD@S6?%tE>{Yt3MX+Y;r)W)G}q>=uK33_f5@ zF8eVeAN-dwi(}H0m+Kum0%MkLa{gg;S!Km4aZ=6K7O$fo2pms?cMVojB)X6%01 zuP^Lq=)><|NT@B%|V7#VQzk~wJynW%OK6x=hA(4d%mhrWv+iJgdmb z7%FfcS!hzhX8*qYK8I1J)S>8NtlO51PMi`Bw(Glny7u1d{^M3o6S<7X)d=APwtSdM zCltjQi!iBN*}mh}AoHbCD_op=9Ki?`1w*6{-&IU+!`M3TfVMQ&LkD+B3ogUMU4dhb zG;_u$+Z6Be0z)cm7Ss#j1&p(8Gt3Pfu-KgfN}qs#gPLTMTuaBB8lk7tX$p+n8XFgl zK9bqfj^n4{bX%;~ECOjYWmMxXADJpJhDQ!ZII@Yl7e&tT8*vbhast=DJ+f8?FF?5% zgb+0y_Tm-x%HGh}htYHAVBQM~@Zgg5bov^{4mPx$musrv@*c;nAQs-@ znu@P$=Q^KkZ|4}t26(|t4429wI@=X+IgT-Pd%IUQ()n#Z4Rye8&t(Rin$O(*W*)8w2Hg;F-pjRD;SZ zDLJ7~9(`7L3wB@GC0%67Zfu>vfzWmRPTG4StI;6k3wzspY!=acc!ULeO}o^nj5J#u z4OUi`w&Of>`WS$6FJ2iLloqUQa)D#vR6@p8RDzSh27a5RNzyvwaUG;V-{mzyXRKMC zRAHJ-Vtt#-aQnoheTu@=r=yFSgeK}5fthm9zqJ42fer5a8zAyWi zcbmOoVNnYzo@{K4j5{5IM(VszScwanGQ_00-YDC($aMSn}C&f`0+%cUa zb$Rc;eemreY3B6lM0Y9H$T(eepd9#NTk;QKBQLfs$85Gh-nMXv%Xj_{p3Uczq?B*N z@i+#Ym{M08$6Lw=UAvgKu*$f!i)Zq09pA38?Q5(k5B*+T@^T(J!YvwXB-Z0C%PT4)U0T=+6NyjR?p%a} zwWr)KtLnibZ!cBg`s?xuXhVIK((@}Wh;gCuf*{?x-`{L400UB zeuw)k~eok=bH zT*Q4>crP7ZoF17wJ5^U!q_JhA(g^U%!s&P6N121bzPXwIT~qrLXU)!PY;FNJyVHCE zOJ+9-Z)Kahp#7VfCjIgl<3gtdKg6R;=yLLL@l(2sm-N88iKk|*=@7g`Dt{RnLer*B z31ix6iI2(#`w2aW=hbIyKja1SN}j{5!KtQnHf4GFc(&S@y(%s0$O!t3 z$pUfaAb$;B%kT0)`Jp<8IFnz_BX|vci8Ia3&1^y8R2&=t6TwT3b#c&VZ9{#`u|_bD zvC4n4=hf}hm%$fsB{DM@g9|I|sIxYq>+RdUD|9iP3?ZeKT>PX~$o&hgl0I9ho|dFC2MU=Y~I=j36w>33ePy>k#e z!b>^S34gT6=Y*P?G_AHac!~Fj4C1Zp=^xro;)2doGu6yoHmYx%j@j{KFVQ%YJ=ehv zvz|}26D(vai~$mV6CPg9JL8Eu&9m&}*j5PsD4X1VAq-s)<%{?#|M53Z7!z-F#0)?N znE91C@#)`rKJYR~Cyz7hPJKiNkn1Mwv)M5i#ve6Yn2QCdPXU)UvKcOu-Qeju$KgBw z@jv~C^fFsC#^GoH17a>_@?@^Tn9`T_pD*laaON^xX~}mPUv|N;zz|eG_D%0g?@}pv z)5ecEW@bbDJe7Yzw@`46v1@)d^D>S1$;so>xT?DFX5XN|PshoIw6E!08pm(N+U~J3715Ua_U`w>sX3my)U{W9mX#;BVQR>D|TS%F+nZUJ6kv zf_bBOpKm&z&h=SIqo8-3?CBWy`keDQ&8x5ZMB;uj(Obn|*5LQ};N$qYYTn0BtxKa2 z+%h;B;#r8`^63-l=6MVle)rN?8$1$dg4nk%-%0!VA^&XwU(0il!vTBmN4+5`>_0p= zsw9;I_u&Zki|5X!_B{vh!x=Uf?MT9o-M`QC%CAX$s2D}67h`b^ZBq8*x{}$LiYL)7 z#HgWeW{L%ht|7E8x1UbBGe{zfaS#MH=)nHU3^r%^-fIpGj;t(CS31w2fc*Wq3#bG= zbW}ODl}aLtBXiN1yK=5OT{?L>#^U_N36>S(lw*GY>~TIncnNp!5%!MR@#n9yN#jyk z1x40?yNtBN`wpo!GQ>%q(R$MAA3#l>^HT${1HM)AY2 z(g_@61?*AMbtrf=*wwS`WVdjHAIAFij;?f(^Z@6O!<&!yFL8U+@UnD~h|skjM?l0K z9E)n)I2p=08KGz}&@!6=dc6i+-MMiQMNMOE5B;^Ak7XQJ`ly=Zs4sj^1ITysx%zqLZ!oW)QcS_$V{_t zPDayi!vP#=d?|)&F{i4ukh;j1^70L9UrylX>$V=PK>zV{$y+HFjKSnlN=nD5Pgj zwWrQwjUgk%S2+Y^#Azkj^Ft9R=g#-u=VfzgWM~On2QC0R?zInJwmq0h3>h_+lWWGn zvx-sVFxpNwrz@u}{8zHTF$kYxUWMg2{LWlU4Sdco*H&I*o8oYeX7(q|OnP``8b#Xh zRTQ;T$M)ikW)1k>Im<_ck(bZ=eRiNL&+)l(B-Qj8yYj$$u|L5*=0L;6IG2h?m5~lT z68?dMo~VB-89=U^^d`=VV;#JFULNb3$qT*wZ8R_24gL$?R%tnZ4aXhdjTtjC6^`b_ zCzM^+wDnk1wClJEMv^sf0mYZk;-D~6R)`xpPEO~u?aF`s-FxMw-b0dhs(o}myr?92 zpWA&}x9tpl$9sjfc8L-PHg{d(+mxz!jRAhc$5HI@LT5U6iNFir<^5#bJX;^z7e3OlFfHd*1DGo2FNi{w z5kbver6=_il3T&aBC4#{ zM8@6~+P>O-CiPOJkzHcx2={saTwW}B+Qa?MH@~Lv!SOm)VLy(JD2#mKUMgoiKj+qoR&0 zNJ0$RhUiKYX3vPDH*eyUyMaD%qnjeB=t<&3FuC0Q=LeP3c%`XN*%^a9lJUa1_4hczya(=dn#?m@nt( zJjQ`+6X!gFGr5E|2=p=buC~^6wz(tjw_O`&Cs)k3)xSUE`m6u*e^1~2-gl|DHj(){ z1N$>zV6R{9>v!U4(5Utm2n9?c;sbzmH1G=^GYX!uCvXcXKx;qvI3PBXe=mFv?2KR* z7eW$v&~CCf`Lr1Msmq0y5G9;WUfHtn;ejhBDv>$A>~|PrEWjdEK-@&RK9&FY1>Z&3 z5UQlu$z|@K5z6S`)1P@cehKJ7IEYdruv6~iPkhQQ;i6G65GRPKbhog^WzIPh>AOvw zzE9lwcfZZM%(<8W3}(;$U6l9hEU07q^f+wGaY~#riBH4c@k^9mDqH#Gd(lEnhVOK4 z-Gvam$5p#cq(?^TB^+Gy2iNHHafe@6H#DpmROOgKsQ`mOe7~9s@8u(hrxKh!gZN&f z?)sH;)Ze(0`ayI>46eMeUmA@uH$pEwknRtk(9_!wuR#I(UJ04wI5Hy5cQ_jeR{-## zsS`)TwubifL0iv#r9pajeBz$-$>zj|f8@&7`oY_5N2laaB-bDW+ijv{D#Ft1=Uu`o z=OsD((P=+-jpPNU8%E>-;bXQ|*Jm{DyyTsr7Lg2;M2M#b$vFuneB6lPY@NVK<2Dy? z+GEbtW{qeCzvVstb3$Gi*M9$LM}vxboI0VSf#WUrp6E>PHWE?fULO_5eHY*SEN%=Y z^TbHQJ)DB_Bl+0>7kcIP&%ERfqj65T);IC!-@^MUFUVp0nGgMzUyAe6M1S~<)u27m z=pyv=c|6#8ewu&U)o0<1-wPx8*wDgkE0Sm1Uxz74f4|M;TFdhvyp&1ell1HFgNd9f zO|K(A9;8iv`ofoe6%7S34Cd%%WeCEs;gzZd|>c{@-X%c)GU2`t#P_u?uhC#TjfCP!id9^KQDpgv1Ny z{g1&%IOQMwBh7>s>+C_fIgERV#ukQb2TaHCMlfQjl-~4p{lAZuLPB&AV z`%y{%+Gi@t_aEScBXQndpEqWI6Xv#GKv7z=d!$w2;xn%Ir!U9;8S2`nZ@b^W>*SG> z9!+{1xXZWv&bjAuDt}m6EPQ@joU$D&QWbFOh}%Cd;>`UlTF=}6uijaBdFITq7;n@e znlh?5O`srT=4i0i1G9Iq+;iX2z#r0W9;KB-+lFEj?{MhIJsPh#Gjudu!_m;%eJOpi zzbzdHNs9r*bv*C}1N7U2>KH|2jnV3jD|dct9+S^QSbf$SiSxqJ;+O?P3H%^`uK^eX z4PN4durThyg~n@gOLmQnTK@ou@nnS1VH@S0CQFC66$5AwrL-}B(#j;V~7&SLc+3){mc zKUbzock;c{ygu);{~WZUS?~fTT`)|%LASbcJDjhs=NG*kziT^`ld!CnLmcxy&U{we zW|G*RG}V_5mV$ zH`BE08q!=Q@Vg3+mDJsTWjZ~T-SKLhYWmk4iQ=_*YE4?U@+s2(t0KxHb9e8sML0ZB z!t@@uS;U@1Q;!e;@_(6q?nO3D$mo-4m}g0c*~T90_qS{d1bOaR_FB)IPmP4KECmUH zq|?N-AKNy4(6ksM@kW8%_FzQb$woRVT*LkIrYV_DX?5NY)_<5f&R$c|B=Wr|XsMwRt3h!or_6bw0o_q0B}zHVchIdLq- zPaa9Nq$G_ct<}`S*zX&Vw+;o-QO0lTd+dwC$T7Vv_JQ%e>57pS3hce_G*R>h+TO8~ z(*-)trk7SenPyL)o<_4(#8h9$Cp?|E=}g&nlw1D~b#ED{b(QshFS<<-l{#=J!9qbr zL=jO`K)}ZCF~=Ic^){v)C!KU0JFyTIQ9)8#1(cNTR6@Gz`Fz&J<=p?*&%Bunk0-DF z+k5Sm-@Vq_dF7TVm!kN)pqVLEh4jio&8u~68s9~vC!5kfaNPJfg5dO`?meTFJr%t) zo$SZ7JJv3eY%t~LOf!QfS!Tg=Wiffn{k4aIr6i{Ie?wETkNWmYgL5j#=&2{Q$@FdK z?jE|A?x|}iq&+b!#&A5>mg{3=_aJ}HGu;dSVEM|G*_>+x86Li_?9ny*U6?AH>3Rl! zyf4#N32qo5odrJ^$4_(|zOkOwANo8Np0$Q^=FN+@-+Ci6Um6@%nI=~kQ4dzi2|hud z!6k3-BkR}rYy+Ep>}N4G)6mlKtpCaeTF`Sh@AFoaHLKTf<>R;U&d_1$>~=Wyj5vv_ z2W>toFBiJ1^M3fC5J5i@r^*9LST9xCe zGW)h<%JOEk@&+u!foSO3SdJ!jDnA=i zJgjOrSr98QkP{cIh~djf_vE)a3%Wgl0I^fJW@>RvCxgRRedtzt1V97*FODQ2KZK@bf(+%+d3J+WHke+1xUT#sPw`&Y zTab?&N~-!N>F^dxCknStOk2JohR)lFLC4tcw}$7P*&ew$DaV;QWomr&*^oSuxPaRH zlTU0-4+GM-p@;M{t=Su3Oc6BoGgA`b9Z#XuC(^%=_GtQcAvMu?s2@x<{dB;mF>PUC zy+7%7Da}$_?x(X?Bibmmke=@tDYtxf@078EZbrZGuc#lDB~#ru0bG1LYj(W&Zr>!p zQ4MNG=gwR!*`!I9gE+Q*9k!D8DIHU$kQc#EWjH}|iOct<=qkb4uLYS<*C;PvPW&d` z?*B=S-@Rk|tS3I4Ofvx`=VuzOW0}71xTdA+u>L^522X|U{bQMkFH_LvGt=?asn+L@ z96dT_f44fio_0z$HZEz{Fw44+RmLWbNiGGrQu3tGQyYIj5?2=!d7FpEQRV3QB{|IWB9G*6t+>EM%kd z@a+A(V0{HmFMp%|QTG>gOLK~@24PV$kRariST)IMOUX=_hZIeATejp=r*6i8w`S4F-&hjl} zCLR(!x^zvS++H-n-_pPU06+jqL_t)k!}jaMr^h}b@$reyZ7q3 zF*Hj3V94l$^a%=eW1( zNP8}f7%?Ko&zO_rU)%G7Y$R*Bp9evX@B8(!^@-I1`ntY+ru?luDf`adXQmzFdCHTe zKmU5QcLuGc2UUn3mtI3phbEL2;jc+&-vp1T1Jsk%t5$=bfL7RJ%ZlW8`QEiEtCl|% zW$8P7s7dI^L8HG&AmrTh&yLo_A6|!9=(#{93;V|+vUJK4Y4=ngCVTVn>;ld8w=He3 zd{-Zypqw63meqbSVPZ^xHf>7lMC+5hNfXOViuzIdSU#xS8y`v+pABLB zFF#8k_u1y}mWbE`>&xl0qvI(j=B+9AOR{gBV`@*;2kMrbF#pqz*!0nI6W8Zh(kJaW zw9%eu8!gS5@$GbO^BI@G#Wmf#B2SI8%*AUuwF%D6zs=Z5ICBGwdOC8yJwiT`?gg7r=xqbA%Co$>egzqw!#?;Z zdfahy^t$qjC_(?Z*JUW1&<><6VBG)a*M9_PV24uaCL!Qh%O?ti!T>|anbg0IBb#B_ zqD4`iT;aB@PUL#a#+-t}ZEV25frcH~vtSe*o&WgjCo+ZTrmmgiLax#|hI;WdIy&1t z&Tg*W!XSgGL=BP*&V8=0Of81d{H!3R@`2F}8V8LS8Be|RYMfNFVqAFbZE@CFXJwsx z)+WMW1?RS4*bFRm6m@tCg2?qH8f?}m_@MIkIvN8q1#ub{=|tT*+TpMq zO=C2#bx}|hILFfA%sc7%-e5bG2Xjs31k)FR1_i}*PL=l}==U|jdcXc3Q!~^oPDgnk zOXHmS)U;JV*c>yZfw>t(suT~vSRH@@R>Aswjk`ZrxD2S$`0)K=l=tMxlVb!9(dZFl z<0p6C8mG2CG3wN{F`DVB2(R}T}o zQSot~x8jInPK@h%U7i7>b<)x!>!F#WHKIui6)0cpNb5*u2V8#7((>h)2G!N5(OgZ5 ziVdRPdG)y%yLe69(6f7-+o>a0Ur}n}RdVcM(UH~p)Nz#t@`UTj0ERgv-?D~+GDN(Y zziY7W@e>-_Jk#fcOecNt(TC#9)7x{sB+45)vq0WcXb9t7%*uncl#b(k zMW@MF-e%&x;5IYV;Awc40St`%;>&pM>1U#ZxpcYymTcUqGw0QQo8em>Bu|v=h%0!r zjj=Idd3}>LWM9!+)UxMR)yzRQt$J5;Wb|0noiP7ok@WDC5yo_blYz^q17%L+J-22Z9LZfCVNgPgo%b&LdP5HN))PXXaY@DSNyWpuc z+xN!IRa{-Tl)L1~7$Yk@Uw06oT-dcsI(%bBjfoLB=u_t|j9ae1fvZA0LUT%RpoQ|O z(_qkT0ISZDM(PrOrvsEdQjjJ0MVb`>3XQl8248;dwdgluOr}#l@Z_)KboSIT4Rwl+ zp>nS-%K!s@)L~Rl=v*7nCUn0nxD0tZvDNX} zdqMf!vT;*vqBd2zRk!Fs>g1}|b(p1{vadrR@dS~TQyspI@WFtg!{XuJ|0!B>^ws0) z8|hDT8bEl1Atmzc$2mjqabc%DPY-IqiYBNI3qIh4Z5m zcBw6(pv`0tM9(F#4lSIw`b8Q@_k#$Wq?68?dQGQX2TZ-=dJO99XW)FM&72jlzw=Ji z#|b*;%nk`?3X<4EKwwiY5Y&o`X-dyBq;@2^1 z$k4d#nrotMo7T~=q=eM(nz>KT*SR>h>-QsdJ#`(CH(z>TTyXw*+`ht|vY!S*+9e%6^@4QJmI^v3@6t#*$SVaI;M|Ih_iOon z(GqSn;3k}Zyzok%^xpfxeQ`FluT7s3Uj~c%9y+6GzhyxG%g-n{`NvEALv`u;A1-jfm z7uo=RiJjV)@-$-1xOnvOUq>sH(mCgK!>2hlN*gxJfXngaN9m$mDo+VCFs{63VC$Z1 z^E?m|V0EAMm!zRRItFuH@N2!_i3>ZQNmJ%i@+PIaN6_RET_xSq`IrCD#~D~LUxN$5 z2JJ=#!0Iw&)Ols4WAA1@n|E-d02x6u(8F)P_dd7ZY>po2wwBGB(D1G{8H6ZV>_IjW z#gZ-r7#=zPn;1H7B7W*TuDxEAdvhFsZ~em#iBf=uBgr}h+NMVXwimj)Nh~Y(-*Mo; z{BYkAXyEs-Tz&{T_{RzMvZjsP|GXAaUh>1Hn7(jL%tjqK7Szn19PJ6T4m+$Sz5%!S zOq&#sJ@iPN3^-K<`Op`z9$YyQ=uxf;hfJKVqFdw@>FY=ON$`r-S88+QAHkgofIFY| z?-w7AoDk=?KQ*qo>=M8YgK7K-c^(?Omp_*2F)#UBUU#hp+r!$>ovbW;+^Zf>+-e{9D1Fe+#!ga8P!$x(1GVg($yi}RJ(#Mw9 z?RoPpw(^4y`^D=Y4~(N3|CY!87yChjX!NX9RG##O)1PM?{XhNPqP{K4QwEpJUXVfm zGBZkf?*wi#`0HQ(g8#81IvsaZ+;ZFPd80wM(S$^w2N#ptKObR8MnsAHH*Ssc9Vm&Vu=(ZPNDeMFzE(&&s1JDS7DI)DKlx;bZcn7pW+v%FiN z!3Olw-aQp?k%#0J=_8ooXMtp6gfGUAkB>k61b^(xXn)E{(F8xW)}b|%$Gy%|e$yr> zEb3$5pYg-~J@of}B+vl8lm&Id+_~7MFTadoLkGu3YPN2`KDFTn51a4{)T;vv`W2uE zpJp2wuHKGe>8~H!0eu4ffL)YzI%oBxvfzaQ-kS2+M<2$3>2u@83%YW9SI=nHuwnK= zlP)QrY?{5&ypB~JyPbJ$L`E0D6N3j2jz-5H8<$*uX*2*p=Pl3)g`BHYGyHeI{{I6F zay(3w9}p$AD$G=HaCKV9XaJ=eO=r{Zm(%r?G`4n}j&`Vm9dV-T)v1%GN+PWai-y?0*U2!L)+i?mi=!+P%K$nsB7T|C zfb-$KuG3J0z2E;JR>Ig9_3X*1(aAI|YLNkp*W<}D8JI&dm0O~RC{&qPCE_bdniM36 zGq6F)cw(fmjH9FT8*jfAr_rVR9ByLphx!k~9FUUEy*aRZ#pYL6O>2zC2S0 zPQ{gJ-7vfgf9cYt+>^`|dm~52paFy8p~oKK9_N$NNjA8U&H@Z6*a)SxPKoCp?a6W5b=Su6oMLJK^0bD((Lm(Ez$pkghsN?RRTd$7e%^#A{DK6(d)yk9)4ZGA`-XHI<=`xCT?jCp~od zd3P#B$M8eGQCa!QjF{X3lo*OuMKxlZQSo* zVF1_zKhik!tQ?znsKorRE4p21H9CSCl`x=t*>|1uKm6&B@%iL$qg%Vy@snF`&pUx_ z#Ah#yve1JwwQS61plRbCQ$cO6Xf}W+M2_h_y=5_~*@d0I-@TJmeFAEMwFjU0P1d?z z@{_xwTel0M6rj(hH=7B_4NSa}NN3PH=(kzK%HGwid1%Vx*e}M#2OoXF%?NYjn`yI> z2F3rGHddPte6T1_Eyq4jWk^4uVuFarhV#3GvUF+MZO*KhB+GrDvXp}m=|F2UJgM+Q0t(zE(7@Bu`BDe5 zwgS+ALj&P-8odQcJ@^C8;zxr9$GuNH8SQDLanTjmrTu8wpd{y{4og5BXWBcrb%qWB zs8#-T1l7T*L*c=6BzzYC8=0LkM=48rNSDsS64zE!JqHg!C`Q@#?8N*UIz z{*~XoR#1I!6I$1x&B(pr8R z8uT{HP^VCP>%4W;-3Rr5>Mm%KI?X*|e|=`2cEQ6V$9=(7)BWPMpWYE20K)47PT3qy zC%FI?GXi62SCvbhPJicG9LJv(?1}aOM^RbEX65ZHx&78?ecZ88 z4f|k;rd`1E1Pa<1h}n5v`(2QCz$yNz-wJ^xJO%H%&s7P2*I<{2b3*#&^Z!KOd>?mX zKd!pu;%LmCx}W@6@}zw4-tGqUQ#a%~pucubd*?G?95>XjQa1>s&*OmLEx?^$KKlYc zjrcpZwOi-TbQiCcJnS&`)V+!EzE$OG1y3SKl5NOw5vM8WszHf=D{OI z#SQm85G|R@<#+rf&gpb^-e{m4dgWqHjL8)<8r-uY$R%G2=&-s38CVQF1P}yID!(>F z`-p>?KRx$S+}5*ObZCD%vf7G9hDT(uF8Exq{e_#R)HU)6yXlmfzYPuH0Dy*F*e!Xf zEY7@rOxE+iX>%6DD{s9So7Swt`M;1;QkwYIGccm}3>jJ0ZI|WnYr)bLF?jTs@yX|7 z0r}=|YQ7+8f8yc6iGQsq0r0I&$~Y~X3qS+3a-Y;u>IyVn?m6Zw_s;JO!TFU__J@4O zzq0sSJaaRKaxJ7=x^7F%Sj<&=Bv61mK%0n0jhn`Koz5VDI~@BkCB6XU|Mla)jMLiC zD+6Dy67P3!Q_o<7(hr87>JhW0&BuasZ?Y+qxc z%`blS%b2)mX;|&yuILefqr8J#7=u zGAQ*XuoYwu4?>wK2>)hixdyQKDW zG0;u`kG)V2xDNdtuVn1|>A?7;Pv5xWs>`^UrF|Svqr{p7>j^ZV7gK(eA@>Y@YdoSX ztJ4HJRM^9u3DvGft@ac<{m*4Q2*HPc2Un8|#kgStTd?S2(~ zYoA;2TaXL)68cDU_s6F7lcr3L&&Q08H_1$X;GUmGr}o||Lq-EYi-4NF57MWA5N5&& zL`e(%x#9t*Hr4EI|4ueF(?T6I3!WJ>dNd{cAI4_<#-H7JXPg3Xr|mRrM%i?JzAyE$ zdJW&QBC%#gWL6!lt=fSf0N1LNlP?AD)?#-@jvfL0b5G>l$X^vcGWP%veV|H+cPik}PL{kQ%9 zKLa#Cz}!_=pPH4=Nf-aOH>SftLqGd0)^O@^IL>q1<4*+bX=Kh)Y~^%GbW@b=5IU;* z{$V&2_ug}FEactyUeYtJyZ-u2!`#3r)cQ3)fVOh`0uH~9r$UjZ^azj*P-N3PD9QKAyH7Q&o_jX$Ts{BHGYO^(cfK1;>%`_96*A|^ zBppM?&9D8Pr&W%xfEMUQ0L*$?w2_8N6i=W3>8ozaE zb9~(Yz=P2afQpTZ&FePgDO7nFLWjB>)6MI~;2Ez#(g>NtzKwm|#l!cx-^u~}?iGa_ zkgoy5hR4m1JQA&W{uQ^}nLtD1($Y+a+XiT1;Oi|2dCG*b(FymI$QxEH7ZParsNehX z?cBLBcIE5KgCv@6{{*PPtP@2>LCiiJ$WH^xyvx*P>(2CD<)RFL~>LJm}SQ zo~n7eZXjf!q=A&Sd;yR6ET#=WvUw9ty0)&*+hZya{4B(AoiJr)d@^iU%%3+u9=-S8 zIQ2vt!XZDdUwR8POaOrUcp#YrGr0nov|V2fIm~a-uq;5sVNsj9?gIg1XiXetnL}o^ z@U7kUm2j8lBv@YICGYYNHc38C4}!1#{a)t23!Yd-7K3FeLl*9T&;Cz8fAGGz_R7ms zuKVDqJp9`~R;BUj#2hKu`>{JA9U!{0m^cA z31?4G&@=)qoZ2Z@!wGipx%uYIh`Sfycn$0px%tE=^VNh>P7=P zK@(4w)n$3|=vrJKFVpM|3gk)oRQ{T?a6!EK{`&;$edFep@ufYI^PWtFiHI!UIvXYkA3X!laCazCg8hTlyeoj_3f!mF=D`_s>eZe&cf*bg*F z>#gv6F<6w}GxGpm*I83$)L)kSY~D@^D|0sp&=xocfrf9{*I_twZ^And-hXeL)%Mi9 zZATmCSZ2BS9QnZUw6Dpl?4`6fNYviyKuSMfo@nYIPX+`Z#A%dc*Qd1M-rE2gjy*Q2 z3q&)qZJW3y0@_r?UQ`B56D)Bbia~~soxHIP`?3vy(}2l9`XG54@MtJH^3{L*IfgA; z9rr@_8*%s=*RP+amIAhpCog7NGvgYtIQL?Pl)Ua9I<7qATBJ`6GDQ{uG`!OLjd z-?W+FU7+FWd+y75JPZiay=%8<*}Qq$r9C*%UO$*0$}FR%y<^_m(t@7ClnDf|rrk^` zZ6W$VoncV=-Y1{NZ~ysh+e{FxPuZ0u8mJ{=rqFCbbP!SO*XKu}1@{n5~C+eB>VSKV{I2 z1}(mN*AKh!Cyyg5d)SMubU58W>BJIBY`*Q=8!$OGSg zGk*EV&!av5*r8;nx{p}fq`5$h-dge|LXSJ;?f>HGL^h=xK`j3b-ciWw9?0xUw!#Ab(^y5f!KEDyMFUV z_O)u>C^u*Rg0vrhf3I))G!LMQ&%qbgCauSQBzS=yDT0}fsjr|vV9+VQ%X`Xc(N2}a z-|@yAb^e&~6XId~r3p)y#hn*)CHT8CP9#{D&St_1j0oBpMEYSMs(-Jnx&&o2X~bB@ z2E{!PFj>p{KOH_ieoDr6w^m0}CR+g4Jm}Py+>VW^dGMimh?O>kv9xo$l}py7kK;j7 z2EFWs&+{b2MUHu7i!nCN3;hr(X$ zk9+)Hp5<>?82yg)Rkm_l&G!J+)8cuu5nHu9CN4hze6k!1x3wwvW_Y-dm6569twBty zz@PhNqzLS!AH_Nf<+=h5%d-4=DDlU?KKv-2dibH}OxAF1nmVg9xQA^g{`E|JdRJ(769LD8ue7#JI2sok>A}* z`CorKKeH}%pnuFaG$y`1PLw8e~ZR z`}fOj)}SC{e4fs!-5^rW1saaTfLJ=wtRcjN;kV=5pczsb%M=>BVdKWd&&X(4%)9Tt zs7GAKrdcA8j-rN>XBpTfs*8Hf02@VO+LjKCfPv|#d2$3JsaVv){%$3w-|rIeKJ?eW z#uaT^N0$q_$7!H`M{>26r4fa(Je4BIM{%kAJQYx(%ake^T>{sa4u$(~(1cRgftFm(nVO|@rQ-KgQDv_3PUFD-YaD##X&Uo& z9R?f%6C%0xP#835VDx^sPaF-vbH{bp$8kp;l?q?uSOv#Mx(Wz*I+YG7^wC&I@#2Y( z3axO0z?Q10YE+ArYgZ%a!{e>z{uzVm;QI&&^!1lsl2@p@pM?_~5OUU>dx`*S$b4x? zRl14tvX|1td8-gj5!U$3W=~)5-8-Iqvyjp7%9BsV1)a|+WHfBphz5jTH2liJeuJO$ z*Z^kfHAo#Ax zy!;*umd|nA3?vu_7lsBiIG}9CPJhAQdMirxs+Q|)i%$u5Z+z&X0J@0F$Y?n4yz`@R zX(R6H<D}YWUEYxo}|&Ua%}14k5i!k9hll zsw#GZ5Ss7p^V`9Il$}$!xaGuh1aVsSS?uz)!z4t|rPMs34G@F5CCr=xk=saj}GMyjZ zH^afbHH$b-aH+W1g@TL?JN7Y3{bj#FpMjDNlGLc9d{d@8@c z@2RKaEKV}3Lz4u0S*PG-8hdFBz121L@lj{`T=zx&n;(3$m;I@Z(bsqn$9~*;%Pp~l zvG2X~qAZ=ze%P~Q6ZWGLw!?HtK^t`o6U;SB2iN0T^7K2`0e`b!ds&V=^c{R7(C`3r zKBuHkTzu7aao)M-M%}t~v&*+SUK^1CGh?e03cx8rD*88r0OU%2qYl=YHY>(;2?|fyuuJ>(yK^quh?Fh#g@LYt zho^!9(dutcyCyOAQ0zxP03`cnR1r=lz%M? zv8UJ%ZP+(cr_!I{v*?RMcF1wZ#2q)?5N(b+d?Ft* zwtJcxWjd97r*o?Ksw3a z(q3C@fMg1_@}w_deZ0YUiz# zK4q05ElVoTIPPa5fMc=9rGB9H&MY>mRV>ZWsV@QzPdxoh+}7p1=-lb-IQ5jaq)XT0 zRw{a$5cFn1#M})ad`aKEfYODz7r+Lj3|=xrfq7T0mKhCeXu3HSoBCRxcjJfU%i_}R zJ>rx$Cr0z8jiEOu`;=UkLzZfw*A}n%o&a!k^dAh+uy}6FTd`2KiM9d_+!9b1py5!E zb37k5{ol4jk zb4VL&_8|Ooa4mX~!8>1K_dfifZ#?(ukhql0ru%RGNgN00XvUP_k-dPptvX-o2KUi# z^D1J-R~H({xrg$Od~XnJKbG%SuL3+D7|-G-Sq%8A+i#C6F1j%4Ku1e%C6ZZE2^cef z?YRE6^meZ$WXb^Js%Licylv22V9hJ+XJNOWeeuP3n#|$jdC&g>G@N^8NA{G{IChOOKnFPY=<-xa3}((@@Em`VL^p}5`i}3?gw=2rv#;U{p#1zxp`@H?{QId?9ee9 z0%}^)w}V(C4^fdN=_DPTuYN}IKWh-gl+SWK=p1#t&-9>k!IH)C76*j`0by=HN19Q6 zRErkb52l#WpnS?Jd04PGEe1po~BRQ6N9ENjGN*0Td$>0PH8E!1bBnbF36w&rLN^m`D_n+Sr!|ygtfo(?z>UF{*ehZ z)NfqMB6vYF^-AHxAN=>e{xd*>>vzZfpZ_5U20uC=Qgbh>M=8G8rmU;s+wm{Z#(&~Pk$Cj4X9 zC~eE>7?Gm29TZR_lny)lDvflCbiN82me0(A2WPg&%C)Ov#Hi8nUhh|9!2HGW=*bSY5{#-s4JW8bAedjqkaw;al9_cU5<}6$oZ{w`|?(Mg8na^T` z&O57P9Lk<*e4JYbE6~TUlP{r(%1Vbrx=C;MQC``HlG>{W!q;1&(U&;rfBD8+y^mmXFHV2~k_I`i07SmZNb`!M@3Y8ltVxH?^RNSJ z9GIu1pAH=sHv=@B!t5`;jg&M3_0rNt=)Xeaq71EA^FEzd=2#Qw7>GBP%$*mr351tn zyynfC5z7g5RxJIFkpU41hU;<~SRML#y0mQ%HMb;x+E|cF4WbHJ4u>AZDbS(b(N42g z_RFl8y{y-CS5FY!cY%&|T(`LwN1{g68k|g1SBxW-w@%Dk9-|hy>HmKH;jW)X*E2iD zku_@-XsrXvoRxb6+%53kMoy|c>C-9Eh-rY+DTVI#SMa&tQ9?Ci27N=wXy}9C>~-}u zan`A)lETPc)!rq|xSp(MN;iC7?A2gkLy8$Jjx#C*|prukJcARhQKQS9V95-=l zd^~7K2B-f^`9a%OCom3;(x6#Y-ydY?z%ND zyQpXK>}Qluz5a*4!*fI~Z0SsO;z~a5~x6X;OWMCnUC5#TJ zvZT{uj{{F7r*XRQkAM9uUL8Cn+VS37Ir%!B)9*vsuap?ZHn`Kw8hobw^R@etK|5VHfT?M!1vP2m+R2^vX6p5!`s-(PX>GvR}&a@I_I2d!>N>6aGTKM0u2U^ zI=Sjd9U$N9p6k3Nz~Ejpu6v;lGo5-pb6Bu&LF$^<&|@u{HKzorW7^ev_3A^<{Xhd_ ztIwscb}ml^`QAO;3J{{RrSmL9$?Ik-=vXdXxG=u@>dP2PsgONk{^!95ql5ECM+!(t zi*z*ELuDv|2Hu|lHoPGpsnh(OSxTnHYJ*K}mA5A2;0_!zC_a9pca%S-McjPN)o~Jz zV(mjHMIx)gTVr-(H!`S(Hn|4IhXnb4v%YrmO<82g=4Jv(uA?F++m=pz!Q4OPB=9Yo zMBjSx#n_KavuU+7R@k+z+HUQ(Hsb)&o2B_C{1HpnlxcZUx)i}qo#+~rQY~D%G~WB* zgZL#tLrot0YfekMvabi?pIA*VkD;MZ7(ERPFlRLAaCDT#wNxgn!N4FvQvC&90^r&t zgHdHk(81fSwm`R`qesV$4?Y}?`MYawx-l-Gao|x+NV8|(c5FtcJ6{}fb)+Snf+C)t z>cbdZNr!#N&kn}jMMi)?gSOCM)l~AnpALxMJpHe@=8X2y1rYr7)7r=301aysSlgLA zr0q7q@YGUWFMkvq0yR7zfW3S6P<#O0>{GM}2miYtHpk>ybK@OO*S7*H^f>=K{INEf zjZqnUDRAf94upr6tXvhJ&}3VnVd;{2F@NQvz{EvsfQAP6taT2-mH{+WGNS>S*cD$8 zv7n=z3+r(~G8`X;-?2yhDD4xoASLyY2Ye{tJwaW&Z_N8n2e1UR1Myy_PHGWEI{s}7&1 z*XSPp2;GJbh7aXQeLZhgF=O`IIkV%R&%clj<1OcT{I|cSUjP{m=vFi093ulv_)=ah zfV$de4(|9H{p+ppQi6@hl81TzT+qaftuY+t{Q{dbne6AEoO5PEn| zb7*YaC~tD`FlMiQ9&BPy$9hVso#x%av=S(&EP`)e+!wYW+G$ieya~br8 zG;vSWX_fJ5EGrqq;YOdg-iS{oejC?b&^4~_by@ZyEXM+K3^_#sQhmVh_Cedj94pbE zY&kx~JH(9D>K(y>*HuwcTB=4%KMK!w|BRgBfA8!6KhWUX-5pxnMl}6%=-9FGv!6W>%NX*mOADnF#~pKY z3VH#dXKXe=W2v*Nu*l##06IrHY&u`oU+Ms)qljhv>H#!}MkbKK*b1`fs`Ri{Z!7e0?S)ba%n0ktlO%-H6Qi>H?Gn;ECrq3W zpA8=#!-fqfqv5eQ12pu|Lk|I@pld99t5EaS{qtp((A<49pw{7K+6nBauyr8)d-uS! zy-7GhgE*0T4xr(5QlhL0G^0V*ac&~eI=dQ5jgBXmdEzKv?0<&BFWsDrRMJr_PkQGH zl+^H%Bcji1FLPzz;&>dxcEe?tL6;+b?4jU(s;JUA$LUgWXvnNlbq+<`PQifM-e4YOy@j!`&VufFmc zeKBs0bK190!0`Y9N_eGUG~qPXTgYl~^6(yeuvbBVFZGnlvgsArm~w6oG(@<#`Cxtw zA2UAQ@Bc}x$2k7tfd{j6!n8sIlByU$%UvdBM#E=x7pEyCbMbX#rHImcRia_7Lve6x zWHU%MYJcg3x=-0t=j}fU=KK8|;cuK`(wI+$7gH_EJog||yP?4-n{vM#AkkwQC zvxo1!ll0gbapA3jsp8$A3hrj$&%;J~7z5o6M8tRZawVi;D4d>bL0>8_wEXL21 zBM0(pJ~jw<1iVWIe&uyb&P?)F67TKv>DDf<-vX6BLjGNPOy3DvZZ9%Oo|tKze%9jBzrVSmy(i( z85sRQr+p}zK#4(r(w~8Ij?7crWX6c&`XTM@vEw1Zf&~j{w)I5}9y%-rjT#d_|KEq> z%(iX0#ieF~5w2NBG{Go&hy8P&I*Hn?BG6#7GHs;a8;Dd!P7rKLC#FyyH#pvZ@#UyQ z>BLWOy(Lb@`9GMlECc6VfDC()5kXn&YUR&@t>8=MtxiwpP`!)ZNjfoafriy&3yv8# zHu`_?e!Mm6i@1}L#~T5snv|6Mcv`RRQLx-kmo5dKvvW2x(0Thj*Do&>Pb+qw9d9<@iq zU;gor7%+ZfT+sTsxaIacq8-^J0u7l4FR$<+z~dS1|jri#t;RNWpz_G!@WRYh;B;CCVG+E@8e8kjz= z%`@2DE!iC3hqK6Klx)8D@h9=b-=2oxlB&LF*~<9vvtiNa<00|=%0;no<>J(DCmku!a5#Fn8W{}${s0a81RCH` z_seNy<_tP1=T(>%OXGLa7M^EA)9)}V&H!{fPQdQ{K*J*D_|-IS9^w)lEC)2IO5d$g zG8$VY&|s<4)Gx=z6OaFr(up?kJIx-|SNH(hC4*9d(!4D~9^$1&DFQi}K?#kl2RB$h z5P!~tw=saR@4WS9yfk1~T-dP#rDiups}?O1v@l)Vj0rO+Gs}oE_2u|+LC44&@_p_B zU-R=q&|WTWuI0%C2M>xDe*HuUo&Vy_+W{Ibp~uhR3Czjg^0sN6}UrBd@LbwkH14cXU~}vBe5YbyzyrIj2;bV zpGHYL2TC<){_9-*+ui5`<2&iBjZnAi$7@%OALYyRMfmLB=x6am`p*GW6ZiFb`IRW& zkc@`=?#t2%fvdDl``_pOOKkl=0X(ybA$o$G9xPYjhOvU*PJF|!Y8-rEf-oL*_I~}P z81UuvxSqp}o36StT4H0%^M3vH)B}=)*BhS#o(`VAYw zhxi`wmNHQQ8w&6JZ~gy&258v7`rKs2K+b|Zx+-38Ihl-xA)st)zFQF`Fz8wBPLHFT zHqFzSO(2j4Ix>TSoy<3E%-Fc^p8FDLxbyN0llW#d7=&)7!@TK#mQ7fLZZPUegF@tE zokQ`2C(8~Hl;Y`>DEJD{R%-$u{p;W2a<1U&)}v>f*`Y&T-R7x}sk=H^0tzyl2H&*F zLe>ON;CsK;(&Y&f%3B5Q$*fMpw+PFt2>I+`!{hQBZvbdGEw6(z_0?L#V$hOvML_b! zH;L*Zpv7@jd|4vEb7X!q6V`yr>nQ&Hx##H44A5{EHMX2A*f>cv*Lm5QIZqQ55|pa+ z5Ybi0RZuE;!50mOKlhYThh;I&&;*d&fhfV@Lx;!DfAi}E8tiuNI0~<6bB>{dC<>U) z5lhg4)L~2mA{fK?{=Ixq1xL%;e`^8<05&~^ap>0J^tk7iTjQxhH7z#l0=8Mn7=QLJ&?6zCunoBQ$Fi`SHqYuf=a(el@r2MVb$F>wHce zY_Le+<(?Km27+hS!k}y@AAIJ!G)62W`A`aKI0YKY;pCdCYB|gklump(b6#}sa7x^H z*WHEE3C7s6j%Jhax5mFJ2)b!|Dn8RzGr05tJZC41+zu-WHf&dkG5#T()R-pu=^%iH zJAWGXWWMXJJEAL%{hBmsjGU0^L%sDL91qL{85##0@x*uEOo}P+z?`{r;`^^A;t*G) zKEHMx%3fB37s^1Ja_oUPaNdA`Qrv?B=DK$9c^ki9w{uH;zh!N#H7;fDRY*WMm=le> z9frTLiKPyj3fMcD%fLV7dEY+PxEs)EITuWiV=q5nfDGX`enBr~H5(7{_wvu`)vMUo1u=?l^Z$JQ#kl|OpHdTeIt|(m%ab`z zTphQ-cjz%_lm?n{1Ti!MI&*x2e^@)E6KIM;U<9Adpx?q^8jHRA{)fFI3X2 zC%7!bKI?)M+>rf5lI{FbHe`M&uYL=E{9mA9GC;$?x&JTF@W}l?jVms_IQi*g0FoD; z{9|6%^duP#mv---*=U);qZ0uQlh1jW+vxvXSDvuIn>w>*lNo54IU|59n5e$7VeYff zJs&Ud3{zhp|K~sAY;>^o_1+}p0+f5{@7Kz!`o!-wyy|E5gC}V2rRmtFGg^; z!nfZ1lUT{vH}&iq*Inz0)N$#M3zSsCez3clrfQn7{SPXTMS~K~(*|`wj>~6HzjY?8 z$JFs!w2T`B02==HPk)Y1%}e64E3c)__WU@qUcJ~%pe|^pE_0sR4cH?AYx&63RUI&U zbf{C+q3+L4^qqj8LH69mi{cGVzlZX14XLj-{XOQ`W5{R#XuviZ02Hn`bq@+Uj7LC$ z0xeKBh2W0o`E`*8bilnH+0@q;Uw&lRn?*X`LLZERTxEs<&(t2J z-9TUIK&!{x^E^3aEsLlPo-qEa7>pk7H+Xpb^5Or%sYf*R002M$Nkl zoA%B1t8>-&f+YUa2D!J=N2fiX$Ik>I1&0MG1)ru&r$@uEq4Dl>FUA3FTE)+PdMEYv z$7dS3_?|#R88QOwzfq1rOy^&{lFSJmcvJ?`@`q{s0!LYTM~2a=AJ)XE(PQHMci)cp zxpm+!oJ4yxlydTATCskNPPjgStgfxI%#tM}f2W?|XYPUgFU{fD1lcS#oV#El4V>SO zCtrNot%|3A{#f*+^szQhw5O2Dlv#Z0Lo@E&gS4OUih-CQnD)u>4K#e7!FvH{*qzS* z-^ghA^o#M)xmAm}oYl1!x!(xBbr}+_*p~>rL0igQ5Rr@Efp^bGt(kSQ2J|;cT_W~Dt z_$;U)7$fg52WaR^VD#kQ{u$Sw*D1Q5-!&UT9s-cO^N01+IOC5QSo0nO3hlmn$A2gU z_=J;cKm(hOuV24L#SsV7+hzw3S+SODufLrguM-%pTe%`Gy|8DrMh`S@RFcggcaot~ z34WK*9`Ahu^ z-)4Xb4<{e{PWDOqSQ4PE76_<_E-|ZSJ9FDrk&@DKq)n4`F=_UanEiu#%zdavVAwd? z0W=&@yHMHR?>WPk9jgLW(&$*gjV3 zu%b_JP)&h`o%CJ$BHn%Xt$5|*p>g5a9pgSqClY923=OsbkG!G`x;C2|7Qh5#0RGD* zvKMA~sfXPlPuTUB)(|xI!`J)c&wm+n_`}EVxGj2-PTrty-L#?Ue?hza%=_gT4-Fkv zzSp0(r;D;=MwS4WeN_Y+YT%E~oINL=dG7i6=ezG^kA{1H|GTswW(b+};=b^flvjgM zpW`XAx+jH}UuKMwath7SXL6$%klL(KUw##L-g6HPlUK&gUC)hcuDd>Oosh?E*qAqg zF_ed#g4C%M_?>gsceGT@J|~u#+4CfUO?_2#fdPB}Aw%NUhaQRJ$ojngt_LzhsA0p> z*v{D7Hg3++FZ~*Ah%b5FIi`QZ8Zwgsxhndp%9r4Yy3>q?w>i1*|JFNk<4)2ds>#4KMiE)tL9DSiE$}{$`NxL}?v>hV#xP zqZ*(A9dAQPd0pRKpg~%v4Ntw!Sm*@z#%9^o$g0^5sBV_FG%-dnv&pRI&&Q69*WP+J z9=QLWIH!GkvS1DaXh25gd+4oR(VtTfqy>TRin1rrr*4oRrHzy`t6lneeerPYN8jh4 zja~H{#^Vn@kfp4a%g77b<)oqSV{bDf5#BG4th(Q3<7)RR)&TH8H`=FY7k-$fNS2ih zr{Vf5FaC?H)R}SpB|YPoYp(`qXqtX|89>iGT;>@G8pwBi2)>r%`HMKbc)j-7c1}bS5-z5^VZ(7-%SWvJwxxzXb%#NDJr`MT`vGvcz#FDKotSt8m7cG(yYrZZ!r7>p{C zE=6II$z-lVDrvz$E2t_NZz%Y5*zowvYj4DApIcN}nBr zrE3ZR^ijZdzEp_PO(o!*)7kQ`_`Qv4T$lIb4kJbU<5O~RRabB-(lk-Y0&334 zjITiAKV%x3h@v$2`%GblwM_lWpu=@w6e=H3jTA|oq0c{$fBfa|v4ZE`!l~>fUAtyR zgTbLB2 zlfQN9ar>2*Q&ZlV9t{nd4+eb)0W37F1YHisXzl^Xn+0k;ALp;)+Er0)#}-a>DUqOz zNM&Cc-Z4A^?jYbTDE1wUW4f&lyr))XQ*6dDShH;tV8eRKp#VPsmaCFCT!o$uHW?Fr z_KMm}L6z3fiWU!S6eq{5bLp0yF?#WLF>Emk*PpvNydJpersxRY*Tnz{G~h-hkK~nn z@V{x=rgQ6%TRx>cxR;)+6*GF|;nf6H3y{?>Cr+e$^@ni}fyEgZ(`&Ml86WIxjR~uzOTHA z%vZ!PZ-MU9XU!ro9uqU>%!%<|7fL7S|Hug%4L1*}615J%xxz`=L;s9Q%;(@L2cSbq z%g4x76tH2h1$&CGAJzGOo+}bgpdqhT1ISsmeNRl|MvqTs*+E<9w(z>+M(VG-oR_*` z$l#&z!gDXjdVX~u83EnSrU56kF~w5n#OA#kXX_)Ca~--Oz~kxsCUl{Jkb$U%U;UV; z8OWJyeT87R|ClfG#*)V$f0WV*uD4`emNX?Bz}w2Lv`>eWF%o=CV#D7!)~*$mkbw(* z)v|$|nPp!9YTo(i&(l=*IOEi~9Q$z`r#i}{4zzM*@a6SYo(2k7n-S)C>NwMNQ>Ne@ zPXxUh&gPx+(=tvU28|pQe|qVaDB;;x-*$7H-KkSL(b**&XUh32`|302?7Gx(X3Oae zW>y31$lwvVRR`IpL>^nXd|7-*Hr!bB*(K<))||jLZQeXPs;greAcH!yourF^g~6rM z1{@TX{-zR!UU z>PPjwKz7#KsyqD~erKtTYnwh3M{(qcc&~52IG}M!+;-#jaeT`b+0@e$UQ5dO!#wRZ z0Fd_XL1wBjmiwvh71$Nzwb`LM*blEq9!I%H-?v_iF9A2Nq%QmN9^Ip1-FlhAEFZd$ z363zPe6JmH-P#E0te$b6(%bL(;|yAKWIbj4;G>V?>391wQpB(BzAMh{cqUEXXv~MK zc&mcGfdHB(chcW|Ncmz+$Mae0H21))ECV9fVbG{g@Z5_p#TT63x2kh+{N%3t=#qb8 zUWI6iy#Z2wAiHJv^Q5-bJy5=M+JB@E^Dh7m1WIH~tzJ*I$5*71KlQhq`yH2F80U9B zH=31}CXi#ZGshN;kzWcQte-hUiKIt@JN!tXK`>fS(C4WazT@C$z|i6GeD8OnXSyvI~B!K)_y=62rxuUfT@v14<`0tXaXlR;2!EMit@V=;B%g zg$H7wYG{MY@*eDPCG>J}Zb=*>7PnqnsFTaeYw#o+3Fw2)#|C-z@#b9wcjdV&o0&9_d@U=1p{r~vb!({Lrm*A0nosB*59rc$IP-9&A zQ+ZTw492!Y6E-;m8UZBfUk&@D9-Hv>H_`9IzVY$6NpaRm+;nx#RUG~`Ne~JqO8`kw zQ@~x&FZ-=AerE76Px(<^S9j_6rwxE7^*Ovg^E3SY$DaOIlI1qi$S>;3twl#1&fjwg z!ajO9BZIiJ@_hnd{Iz;rA6tDOF@3Il?!ig&J@#YveEM$mek=M685Z?;&)xUm%hl9v z^SbfEd-wa1ykA;4zMs`WW^p=KeN^Y~+?88DJ9jhizQX@`;Ai*8id}o73#CZ*XgJ}x zV-qYggH@i?b`%dhy#+*B%DrGL`${PPJNbGinVy-!3hkBI4cNsYqejQ$PyIETbD(g^ zwfHkqXSo>HYNVxpc61au*(?4=V+VM>-yP(7Xqr5V(5dVU&{BJ$d;glES7r0lx?a7^zNmvUHjpRyNZZez$%h%6@x0Uz{7%{@kFgdr z7TjMC&Bk(o-5+pj_rV8{F>z0vc+AlSU{@J|!0N#~OyzS0{80DR>^Ms&vcCniFJG0u zU+nLeom|g~Al5jTl14xXfx91x7%pMI~zulg_&cvL{k2NcWyO zcW#XMe0Vg)K|BFLX!p4~y@8W-+YhqguG_U{!+6}qpgm8&Lg9K-!niK(C*SkS>hLo|Fo zW7`8_tAf%s&kB3;v{P8YJ-Ybl+MiEYy){i=b;*bNp(0{(O7QeI9gtJl()#he?*8FD+0@9^hTLA zlO|3}V*0enxyEw*+S5a?2(5&Ts>0W0n9AX#q|`f%&j;3y1L?L|t%44%Km&iY{{ z`_`?~`7Z<~1^L(MQQsKMNfUttX)K>_MAxW?^JnNV_ePswAZcgp{$#j)Icshl$@sml zzJj2!Wd`H|qS6}{OWm#`p^;X81Z0(6Yh}%D^QC;Me|1LLjFhiw$kVGYy&9|d{prUv zi*wHD98F3aWdM-bGuRL1%I0|Lm`rizneMLvjMNkq+=63geY0SrCxiZMH5qv00R~^) z4?12-)3$c>moRvdZpGA5*Pz3uF7s<`lWQ+#WU2qv@df9`vODw>I?#-}aR4Pt=FN)M zfYi-MQLopae)bE}{-lEr%`aSk*QL%T3`YL+}Av-#6(%Ks{Y@lmanm1QqRRHaPYH*z0PuHL=u(|3I zczDLFSuq=D^o(=PrL3=MUXd&Pq(RyS{#M(WPA=o<2nx1qJM5aCP8DNnr`+>{kVRhx z7hjN8`_&f{q5=m5XPwz0?)f^kyzRMKP5Z&zoO{}iv`?}dfsr)eGrvk(q0J~}Po;fj z-+hKxNUtP&YUJqA(Pz-G(9-wnbxE9j!im&KS7Y7mJ8RcIIcC~D#x3%^Je4Pr=sEY+ zwU`x_H;o|oo1xjvdGq7Lk3WtXOIJoS?iB8Raj$53RCAj8nxzBZF>gPli>I%q^5($~ zysvyIr$rFlfV6N5j$L8=b(=TFWKIKLeCLA%1(MPg8xAPXoX#BCm@DuENRNA0k z99HvCz(q?j$X0>Jy`^F$P5#DBnjRx3P9vjX1-gArmNFc~epO>TYQX9wG*B}R=m1OB zI^g%xN9xt<;y ztKwVK0a!+WH$?qI4&xfm<^WL##T@o_&h&5T6L3|gVmpSsku+C-A*Tg!$B-QwL2LI@ zduK3{H(t_EKa^u7x($?t@6#XBd_kwwJ3KdUnxety3w=I_6H96XB%ch}+cJIl4AixM>N5D= zy>vbHsnL!a9|+=SaLriiAMIbEJdv9@(C^;`Cd&TQMd`P~JC2WFXJGBTZ45qV!NM%NIsDMWqRnx~M#BaTkf&PM zZsITI>>31N{o0rM-7FjTya<%=sMHPGJ~J8w@jdvNJ$DW_Qcb6i(6s1`pW2Fy=Xyuf z$;@H*(`=F)kG=Hen8mon_(s}DFTrB{7vU)rrI(^h4&AvGMuRt%0&G>2vKQr&_3JmxxVZo`!n zU<0+_3l=YmsiVKh*rMKX&7w(*mehLIO2N<(!b-7uIJoJn@h}+0I`!N|#$*q3V>I~w zQ+ddEGL&fUyoC$6+kPejd`KLAWSuwyhe89Nib(~ibBGY?TqtxJE}fx5&7CJNg&HJA zO=T{EsS;FhbjIe=tY*{dm2r5T22rnm3F9A`C*7WSWttL-NTY@(tizOFI_?{;+K=4MMQ`0-SSFN$M8Mwy=bWP);X^NfZ=O1 zG}B3{jzV&cqP~u2SxjYaGpGVWZx+mqnKNR>{W;0h-Fteifb=RYv)i#em`h=84zn5ue0@wGqcRJv@#*wski66xq(~ z1syJU-aF&XT+zX^_O@6`k(n&eFo6b|)$GM!>SVAniBd0Ev@oWR8kvAg=_#$F1prm8 zTJ&$gIorKsYgBZu01cZk;M>2Pn210f_NYap22mHKUI{>gsyZA3*b=(r-t$@4M%wyM znNP#bns*{YJNS$lh|L6NYjU`9Y&lq(B zgDu*)Ek-T+E=I24K~*puc9`VV;lvZ7d1+}J4E?edlTL!hIpqas4#QTCJ=3^s-Lx?c zhrzGBs3W8-$@ix5t*1772|PLb>*>*;dBZ3zZOWCNr0Q`3>uI7!*FAKN$q=lk91e=7 zX7c2244at(mQL)ZRAkSd?TOHr0Tf%aaSKQ_S7j?=S~J}oU1#PH7MtV?7cx1qz9 z6NJox?luHkzIcI(3r`i=vL$><9au1{5iN-unlvKY;h-ZqU8DYxJu0Ux^HF>;-NMT$ zJMY58p(^{qx&<2S(J+N;{07X%F!LAtF`PK_#XPmB@4?FJj(#fz*oJgp0S)LwL5#N{>=}A2cErnnO9|viw!F`MLqQ7F~_#b ztS@y;u}6a-m6;40e^37eIMh3tk;I%`m%+6Tqc? zqtethuC1VFs6B-!se2qBni*VM=I1`>Oe;g`)!ZWJr?ad5vFYEO*|TE9>LmcOM`J_k z#-TN9;usUSrH(`nw0(@PPN@jLtK-#M8z}*B+^PU=$)h|oZ6H6B-#5~0#XdhPmM
PMr}CV4netzwmQ^ou+xU2@RZE5omC~cI^iRw0&#}b9QWKgV1G-IYwIg zc(vd{n!tVi<*?X=eQI=cL%P`0gp=SxAVAPt8PYcIWnB5bJUr;y>U8E7sQ^gX1xeGb(3W)yg}@Yc;V zTir_!ElwNt3n~CSZRI5K`*mB$YFG>JEF&l^8zps*jM|3^5O_jLzZRaY|5b&IhIQD} zncT!Pec{qrxB5FuxHiOrYIb%_F1=dR!uP5OjpPXrc6IH>=0m=C-rBvb=mtx*#d}7fQ_H)Z+SXB4 zf<8?%XYk6JyERP=0PHgtzhds?wRMwaWMDjcHGEi6M^r@CC zT}qbhB4ld|{c9RtFk;x0NiGR9%|+ZJbWZ?rX7K= zvdn^Kcmu+WZ>OdWt5v%WC(QMt7CP9>G*6`k8O+4C)K7oUTd4eS-s!Vx2jF*YR`#@E z-!qGf=Wb_ibLP*B$z#Vx-KGuUqXyZiv3k|&8DA);soQxDQ%Rn8{qnsf=4n&qEA~a> zp`Ou4bx$@^-r#}ZJV5FVYnDZWCdb07%pF}I=$h&OJYRptXQ+qmTU7~J6A-i9W-t0n z{hKfLw+wSG%X`g^@$kSaE*CABOLN8pqNG7d!F~{5*vQ=*%MvVsZ}fQ`+e0UN5flNp z%otXtT?4)hKHvQp}&WMfIP$!j4dCn`v0hV6W}b*Ji+e)gwTb!FG+w-Zetq^zHqm}x7&8N z?RH<&J>8qkW~U~*JG)6G+0-PJo!w+>k7Os6V^UL7$!t$w)7@^j?KVES%w;fO446Yg zNJ0__A&El>2}vCJ{r<0Bckk9#Pjxq`ieLNV`}7^p`#k^We_s#tZf|Qz7qH6;u|FFY zEe-i04CQ@(*N0cgAlBes$l0`G8PQJ&-~lIihgn+gsZQTv)^p}eXKHCgXKFl?YHQ}C zwGVubrs_0a1y7h@*fW+&%6qRft}waI{p7bclYF1!tiSWm|1^D#{y@>MgS!DC?&z~u z_HVrW4E}Rl91Suiy@-+07Mq+I-Eq7LsY6FF(mdYs;{*FsA5qgeZ1h|R*UsM}h+bJE z4?duvKxze?j4MxTz8Xkc6&69V$M^k~3NF znMKYsWzr6~9@{C?Gh!3RWP$jmgia?a+lS(02Vj-wB}uuQ|0OXsB!7A;lmP7{qkyzfJp@hY+(7RK-VeJC4@B_ZnF4OnqM zKl4&ZDZqrC%spVwcrs%NSs3Y^ZpBDChZl9l$~(g`p@%hKAVC2iPaX+Fk2yIXo07>O zH0YfF0E)Yr9?sh_!>h=CC=f1lBwGhcP6+~J*%G|6z)WM^Ik|5ti7G=fEfrwLP`UU1 z(QTMH2oux8^t3B=|_crr~V5;Jo;U3r0vM`exzhY{qD&Ac@D#2p2%dnev_ z9HNoPNf_=Ecpl-jh*2^Q#)FsFfps?yzJinIQymeT+G(@X9B^PZW0djT$;{0R25yl> zNm#cLD+Np`u!u4jl{fgn09hL&;CtZ&Qs!9e6~1?7xIZ=Z_ogmTyJRYJC?~2^g5k)x z>|iPZIAuI;;IX@mM$>j>DD7(RNjtj$S~*Ujt9XW?&2=jgKs7bM0;?N*3Wd&jv9~Jt zUFUn!NBj4udDRQj;`;i4r942Ka8EN62mEGTKBQHRF!3aVJq8NnNgo;)D*yg%+WHj) zLMxu}PWE=q1M5;PHQYd(D2oon0e(aJvw|4|c9dw<$SuaX&K+SAuG8q3NTBgkfb(*M z*PSSmpENh8PVn(!_Zi0H;%f!`MwqDJ>H^c8sVBU)XyHUoqL@nxFYm($f1RU2;pBSR zf_RnnXyABD93LOGok{PUV$ff?9$LLJ-L+ylN(ALj1K>m$S2+1_3Qae%%$z(GMt&gu zNmCk|{RmSHwH^!}wmr?St3^2@V-46Dsh5w1@x}V(A4VB64#n*FzH}22Cg|SCwmdEP zFv#YA7sw(w)7cS6A(!F=s;RAwUK)-mKVb91I8x~nL3QTE2?xsso^_lRc>BuHCv7EOLdAsAvgEibWGUboKgM)YW}H z9U~I7XvH0*bk~GDwJgSHy>d!rD$l`(czqS6`x1E5MM*~y z&geMejfkgug$73$7_85A$ahVd75)KVCLhK#^A;8wcFONimYKUHAZ8f$(XHK+3uX|g zr~@|Qj5wlv)8VfJ-u-j#$~|#a*=!FCvoOQ3;k&{ka7OvfoXnJJYi$krp<-PDEzJQh z)nP*ZgA3xL_$P5&mgGaDO~<}O6*>*~)d{UZXW5(2;*Rp;6j?uJ%Gn%HeaS2?WobAA z8}~q|q#$I<|&%$W_MmzUq=C7&JPCjvPCNL+DIuSiG3tCFo1Yrvl{YcuUC` zdmQV$g%LkWiNh!cn>|o;5{<*Lj*A#LI5sdt?&(CEgdFXMCpL35b~Bl1eHbJ1xfw9u z0vN9WEe(xHJU9#pgP*K}1x4X(an2Dz2L{)!aSy&DZR*%iHe~@AjTQ#sp^@RK69_^2 zG!)}#xSV$FZ%s}3v~?(V^O##$lAeC@(NtSi!P@ElMOKNyEqSH-lz6Z6MdzLJNh}qH zm%tkhe4PO+a2VTf2+kYMS9^#V(6UBe+LF%1%h21|Lj!HfCxaN*ufaE%hx;t9stgBWYSVsmo{pn{9Qb zvorOa?Fw3-UsKEJPxE7*>PtFKbi{`94tWF82c0^;_!tg4aL+O26~fAOl^|o~QN3g@ z9zT98^&+F}$FYF9&x6-Qv>V*;hdRU~stqipUv)n5Q~v0E99LSBkD0k6FR&+spIaJr z_=69S8?%B|#d#Z1%dg}!xqJ%e8{_N17WQWS`1_zA#+C=jzrdPsT&f?dyP3s&`cxAJ zXgvWU=?TX-crNVKY4R-1m^bs223?zbXO@LLL%SpA)45LLy)VJX%;vK3r@@eE*dOvE z$Can(oYI*sd>r4g_g4N>Oj*r5Zk zUL6rO>ds^zPD5mnYu5Q~zz2W_e|P-g&ET-Sz;(&94JtGd$i8FsJ!xTOW#Crmx?}gq znib=y0OpaQ4s8mraDp&~FjVIVTmpZ@0WbGt2;1Ns^64f)u0@L$g}r83Wt0hn+3u^3 z67f>l7|4iBOK@CU#r_?`W2I%{qKGzxBV75}&%?%`SGoTco_C*aP5=6z{b~C0SHF^K zz)$%*fQh+e|A^h6-RpOEG(hO#XaE7jvx-0&lgt1Mh6qDHcJ!09ean{Aj_@&(w4BIc zEl~+mS8quKY_zqC;81LusWe7=1-2U~G6YenOaSYN<7DI*KnP(K**!Qgwr!(gNWzmL%DhzoL}V2w8Mwxt4OA{-G`{ls>*)xM zuAYAGi>bDnMnV{$GHb{59x8!h$naX_K_$pBG9j}W8Z0?LBpg*O-E)X?!hGJG8r5Hmsz;J12B;v{>7iC zXTI^R^w9nHg@Z$cS6R~Yod3@Id4&?p-0bHd0V*_9ctdE6-N)CiK}E|Hxz5I?5 z5XVNTSP4Vt?%uEvl&vg#<5M{Bo(7)6&asSa$^2sOFdv0x_c=VL7)2&bt?lLG96CDZSj0EmyDsb+B%v?q8B+UC%Q&T94%U7*RYp7|R zLbvKrboqUTkIV~P45gR-c7DQ3<3YvIwaIJ)?-^GG$vxsDDR=RY>3R3>nL4?82SZjQQ*;Kg!}>0{JVbkR$4W; zEY;1cN|T8e5!(ot^8SnmYt2Cf6sGtr}gW3pOsqM6aaDHL9R{O#{h z7IQy_FUQ`2KOT*%!3B8Ovr&2;98W*^tG`P3KKyWcY{U9U3lzpdKg>&|$2IWvzz3CJ ze=i;BfO21ic_=G<*T{!LQz6yM{P%ryFztT#-Son@z8%fzOl1|8<2i9-91ppHnU8Qo zq8Z@MB$NUasuAcxKIdx{jzSc>L2&ta^T}uidIH|~(ZPMOM!*`523#q=Oo}L>-N1{6 zg($kyDDNmj@zzh}TE^DHS47F|a)Gf*-r%(^hv?A&4?IuPh{K(|>5ayraAXh*i0f<5 zJ)PFCBRYfwWiraQJXV2g8f`q>SN4d-hN2+sROGD5{fKh3M(|Slx%Z)m(mmk3ijEFC zVQYj({Feu~SMEd1i$5%x3O>f(*fMgl^^{au3644(>Ql z@kDs>VJMB>SN^GdRhIg>imQfEYinyd#rW+Q)r;>~!Ew{~MRZSRwDM0}4BT=3!kqmM z`N0?}q*rmUO9R4CgIL0al5Uo*7;!*uY;HIhG}g-b=pa9s;P4 zO**{{^h|=sXU@S^M0P+++uq!mR>7xL&}U#AS>mIC5l&x`*m*O5WnN^{h@ae3 znh?)*?uh4pM_tA>7IH6n&0Fx_Gp)^O!(&-V?KBz?TD~@7-LyD?0diwJ&bvt*nGOHd zv1U)15l*F;fT1vnY>f%r!1r|envKID09! zOf}d(6?1sZEoZ-{U`(iIfs4Vzq<`1LeuGn%7=i?mO{$|oE)=o>{q<%Mu)-PA+H(m< z!|Bur6Shc5N5g{BDd~^?@IQ^x*ePUfs#EBE6W>D@0bj&N@!r2h2%QY}NjY@nFe&tx z<5*lB?HY*6WDRGZz2swF@<@4saMlp@9y(Wm zx8#fBqxd5%!l4#C3OWVu!Xb2d?(f`lx>LWFUQL^S|NU*Lx2r47sj5mVX(C%+R~PpV z+?Ai8PrDBJpubTc^Kwn@skA3~?N$_jv@DW!ZYK0c zh7&;-*DIZ>hj=MBv_k@B+%Mn2LVAM8kvJoQXk+|ZDwk?A5o zkxoPA026tc8OJsnR_Aoi?u~k^7%WWuuJd(I!=cA_JJI`oOn(4RGx`$pV}3j}BXyo7=GgNOp=!rd3jjkw%z)}WL93@2G!iBglKDo8SQqEzivOT9(cA(Z?UB-SkX)fm4EP^y)e-kMS9>$5`T7 zR8EKTTN`lDffNttD829_ z4>AaSg>iHOno*-e%6$k&81l@0Fra9;SSRwS6}`rzV0*}z?mu@vz4QxnXLLpKB3Ktm)Mg*9iP8>fLf~~jfT$&CM+;`V1>XjRm zmh37V7Ds?eRYU>UsENfG<|-uo+*&>(F>XGbCWNN7>61uloB%_(0WodcwKHwmvN=`P z)}-YK{Y8rwCnHnVv--O@?h*!}ur;+y=Bxk{(NtWlqm;3V_&!9^P;_7xBfWj;`+xH{ z=?IGMvvgk9V6+3cX^|p)cxhRxzf%yXFqpz66H%EE44*0)fF%?u<}Bf87<+W$4}bVW zJe9N3lTSPzkw887&dYf_jzZr1sK8jSRmlB?>i`HEj3x*K#*I+Plmdu`^||)lG*|i2 z_r90D@TD)M$JRegV?V_iOpni0Mq~~Wn#!q@)p(FFRHkH9626SxD>KkC2h9KmL>G~f zohU4)VdP)^+Sf_HTNyYY^A8Uqd+L}n4%h0#w07USijph*6?WdwJ#p@OD+hsFM@J_m zC{3h<9!#@n2;&iQmDDODQ9>C}FentPyJNUek{rJX`~oOA5PJA(<{5STyzIk$ww_pH z{Wym921O@I4h8KksO1 zO}oL#GwmJGCHY<&-Q9rz8pj&1gUccG!55WY*I-Y9GL$s9l8A)eKM+wqaYRKRkFL27 z3L#JMc<+skX)^ONQg;VY{t9a4ytj;7MJpm&81MSWrxJl+qPl6h=O7++qVG3HC_7=V zAwfdDsh2(6zHMjv%2w299rW5Z2bP)Q_kD!;kKInI|jK9iJa_Ohg8S}J0` zHZ0uHc7Y=pF9h9(rOj0T*FT|SJI%=E-~_ZcgMw8B+e_v5qr->O_rCjGG7cU{&pq{2 z2xWzn_?;^wA>e_t&nm!$(kli{KQ)TdG0OBXcz1{9^vQ_wGqMx4xgA|MFMT zgYe# zj)qS!z8jZ|h?VdLuTiH_zA2r+80)!qGaaL>U}x)PXplPZvETfI|K#_9*%R~!Sxmhv zO*>W45tbfdr+43oj`R~k8C;bn#(`ItP~didusa<+d?aXY-TL)u-2)HC(WWEptBRsL zRr+?XgljbAVq(&}bQ+DQm~mvb!SCdw#qdGiKmlz6H{U1iv4=F!*=aS=3l%Px7|v4p zAM=qHivL+A0E(RdvBx<`L{5LB@K<3~7PvN@rMtFm!?`dk9MuhsJr_rqm-CK?zvag& zyGGblyn-+Cp7iSc{aoc*Lp?JH3L+Bt=G$+F6K4H}4Ph|q!1lMwg1|R^D1Isf<&{%0 zE;agedCq#iVHfAASh@N9?#r$w8Uq?LkFCAA9TfBS}8Bxy?Ym>RPC{zwfEnb?p%2%pL5(~ z>{*r)EHb;-uHE$rTMc*Tni)_=UNc2neAjSMF4&m){mq-9)3B##+PDUI`PE=_r?_dP9lsy?pH=l|{MEs;r7=I(nq^>3xH5!H>eB!Tg+qSu2I= zRlGj9Yj^tT4}K8Ny1Q@+8tj~f{0RGl@r1STmmdo!bqe=Q9_{#!>lbuzxF_l{u1A{n zq`8gnypulKw>Le-X<;jtb5tdKCQj(n$;uc3U&hywA+NDPp?EzA|COHHM=$RsO&c7O zt|8uZ79R86?|(lWOke%-mnnx>2w&j)?2q^rPAVoR&X}E{>~!w#rZf+*1LnRjeglq> z@A4S~yk>*Hj1xv3`$^=-Oq}_SEiZ6BHYC@sF>BCq&B)S5xDHNP3gUg_Tlv`Tv16 zCSsXIc782L0dkCjFz+Lj-)H>ly4tjy@`gxrK_PWsVK|OOMZ#kU!|)2G%iKiBV0dE) zDZx7z1zSN`X{5aV9HH6T)RZ2;lFher<%};gF9Zm46q!}%iiqTi+~JYqUZFfo zya*w2L8Vc*`y3a?h{JStr6hQE%ab}@0&!Ghbd*c&g15I3^JnP zAW|Z!ROb2&lwyX2YXx63HawE zm(u-f*5GWxNe6riG5kr<0`A~F#`zG%nWL0W*o#6zbzP?>xGTQf=V4+=SsLW;{f7>x zH{N?U9c12{KHL@ao5N5vk598F7jU#C>8?01#xZ6YO5f~hb8s?P9>iL1xi5T{1IJ&B zC|)9e{3DUDWeE>wT|GtaV+_aIH;@$oRB8LL0_xX zNXI%ayl3n!^RV}hhS3Kfewf~W?>)+!=5iF+(vTmsNUar-BU_L8IdAbo9uxeNas68! zV6;RYq{1Q}^IpQ-y5@@*02`V6Cn(Yn!DBpuXf8GAp2njhB9Bq7$qO{zoSzwUEGU#< z=PG~jJ6_%|i~-;_9@wt<;07*naR3B?)-mXFXWRav%52pP@j9w+;b?>@$=@I5{b4GtJ9Gr(dTtm~p z{jKuJy55_tO$UUq5KaLb$K`MDYhz*!jNPQwHnP7jkTSaFuDfHtp@1?!Wtf~*r-r{b z>c#S7?(#^D19@c5JH;LQ11KAnO-)TF(}!dt7J`RgB1ljTUVD_UYgaLL@$RKC_MToU z;IYrbn|sAx#*1vfC&1&cVC)||b}Su5iSEF-yL;{0IC-QPLwgV&;rJ@|{?^yRS2-#V z_L2{Hx=M~SIbHZ0mEg{fje7M{a-*?`_?ZHluT_h6mh%K2}jt8O}4|5wrtejc6$2xDNTFIOTZmxwMe4 zOL_{!W&*Hd&$`&xS6+KH^-)Lv%(Kr>$6bT-3s-;*dEvbXZfF)6ikum`!5&W}NB|Gk z89PdO+XQ5vy&Y6dVQBmgeFR>7uDvt;?Cs4Q4fqZY<@VG}pAke+ss&_ou#IN$M>((U zjWc=D6l(K5sYag0EuA;;5Mttv4jkrTDReVtEC*f6jN^ELE5P4NJPJHxzoofx;CyTI$+QXn-ba>f6~QW- z>@HclBy_dwV?4@r8%5WkHZw~{u90c^f;?CLDSz?5Yz@dl$}nKe96!1zz4nuz(vNLH z1bwQjtD`j7b>}*;W0*bXZ=IJ}jb@K{Pw(ws6rhIysIZx|9h6u0cX^AsA3pd|7@;iO zSNZ8>;7HjaEQD{!ZPx9)9oI{}#y%J^fA@*`%j0d5xbYXSr+e7X$2V-CHxP=AJVSbf z-^dT#FX0%pgRF8KamoxkovZT2uveh%xHof9?&z#mcJIXodGTvsOZUTvrG*>F26eYQ zxage2am*SF8j5#1$c3@|Uj10!>TiXc!RroqaARW=S-$&lR8LMXedQ}@{-Q;CA#em` zncm`^Cn+&?Kfl){}~zB38C*MJ#}HNjf$3~`g&@a zh)xA^g3NjhB}R>G8?hP9H;U#YMHUg>O9b>@8AH?eJTA_6-Lh?KI#2ZeK8U5ZrY3}@ z#Oiug0HdBzrUY^13aRrArU!5&CbJS$mK<9J&}R|wWXq}aI!2>j|3}uZPqSyt3QTDHsTSk99Ex_A8_=Ek|iFqNArV-~z0( zeT6YV{N7g&x34kh zFgogvF~S&!dkYuG(*V&ipztUqLNExYz`(-~kkTPC8aBT18u&CZEndDX91Zh@4T9_{we>bE0+UlAip&J~ zm3S$Rd;BECgE9`SVHA(jad315V_={^UFhf}inb>m`OEL8rF^Yn>B3Y2r;E{4djsk31e-nr-YB85}6? zA+We_HLk$42xSiEM;v__js|#uyb6cQc=peScoKVy@EQbP_o4Lv;;pyh zPywU|<@(xXxr^JUKBi?!x~bKaBxyq67L zrBAb0#4Y8G%^g(~kKl+|%jpzLQ4}jHDNDkDbRIf1!)RoFp~$gW;aub%(yiM!5gz9H zcp3M!v7VRrwDfM{n{P%f_(PPeETkmS=)cBgIB%Gryf_TQfN=&36+?Mdtc81vlkR2C zi#7OEq7I?_zXxpYAlqOa>8~?Ta>FoWGPzc0P(EEk zKJ7)3)8YFJj)2v7-jylP%tuGIS#_oG93A)Bo+9sXTsmiACt{c5$h86NE#_0&NTkc~trh{JH0~L08b?hPc6z7Cp+)JgJxho&tcX9G8 zj=K+WXm%h!tN~t)0(~b(;~K?`$SuDYw&K4ypTjxi5KzfvYE~!jJ~(&f2saRcB1`bC zH-15qTWR#2T7ffQPGu!W=u$rnk28X(t|Ctfy(7;kI)GW1zUTfrcV+jM z9oy6Pci)2#(DZWIavI*zIUWN;xcd<9&Re+pEdKBmjtq5@99NZD;*&M$I(x^%OV0qC zSDE|ezMiCER7)+tJsLFnL5;u(31x(4ko{z9jbhZtZ+(-VMB~Xmvupx$f_u|o8Cn@P zb9U+>Q{tx^-%UUG@kSc?o=Z&^&xWJnZk!AY=1jxsTO3XX%he|GdmR<>{+K_L=M_$P z^eN_>Ib-C>7*VlicqgA(W)Y4C_~_8BiK!of+}?LN9U*J)G;B;txx}M_lF0w<&;B*X z`>o-0CuYjN*w1VNGQ}X9<41W5IAr#b_-Z+*4O8v+bq<62B^-AvfxWn>ZsGpePa}6I z_*y+N=zw|3>%=2*RXz~?(R^l~Ezvd0<|ur4&-NXuX61_Xbt1g8a5UTi2fRl(gZQoM zjj5e1iATH_<%qw+BXiy(4!f47=H|3@%jR_Pd=Cvr7o=6lr^OhJ^1zTs%*80ae9|lM zl4s%J{M8%8Mdg{aWB^dUU}*^XtU%1U9LWm7Ac(Q~;+@EX7_4mxl5 zR@tbH66=jM!1v&1^6*b^$Zp;AURs4NwgDR?dY%Ex(61QJxo0?-@iEsg5abEoOZ`B; zE5DB{D%LG;He1~0_-6MWM~LHR89rmdZ0=*g zR(>?D^-?Q%^mers51^vVmKH5W<8xf0nP`&C%e><*+b8 zC_j7cdmvprbTk0)6Vx!h4I!SxdsYb|KYag#WHdCSQ5t3R17yFWvK5LT8{*L+p5bhb zN;D1{BPN-Qop4otZJOf4G)AK$dv@(i3u|hlp<+!rx%gjHxgY>t1zyDD3rG`z&#LDRxwF zjV#F!Wo8nVNG*f)QaEH84X4tND9v!bPdxG%ggz^XI}o37j2LGMii}%tKX7I&2`HQ| z+$Yk8xsPkgod*)8gno!@l0Bq$JqQ!I7r`H0as%EOgA$R&VVPDCyz2?YF=GI}Co@q% zNc@pj#d}77&-e7E_knv;)5-LWZ+$C{sFT^LpgNvLxlF+!JfmGDNo6YP)4Y#@Sh(?d ztcAT1ZYnQkNi;%?I!R{EuT0NztYHmGw6%K9#XV90$;35$0_tO9x+cf*J1U>T#q>Bm zz2%g{Tt)fcOG(LLqKwuyu6bx3^~dW%QMv-mgt2%bu821pK-P~sUcAR=p9)TuBC+jvvP}g2W9o!N&Zp z*Oeaj;kbKq<1dKFPE3oIFHLt+b68bb6=Pq$LMLsMt0Kx8rdp#)Q^FhE)AFO6Xh*k* z{EV9fLoI~)A}4O#APeUzM>TeIrVn;~kdFQN|C5#>KWl5~_=}UloP$v^7;Lmv2BTDw z>Ib(5nU6{dm1YtHTne6mJ@_QOsXR+-lCikyzKfjFvj&5_ zW)FtZ-W|Ksm%ska^uX#h5tX>Yx{4@cC?xwp1I@G2Z%!a0LTaqquX|d^IH>;7fJ{SU z$_#2anS+jo*WcVoM#Hi6ZsR90uf_bVVgBS)J(JUUrh>DD2*0aDjltuRB8_tdISviW zU!1FiAT7j|Kl^@s$Q!)=4;>93wRNVqS~7TNkWJ|y|H0phV>svI^whvE98V+`#Y#Tw zkz4X!oqA?ANVB1A0Ix0_4La`HPBsT^t|nq+j|MxF8`Y2(gs}*0j8b@ou?kMae?Bvy zaFJF+iR3$$G8LdmH=*FZ`m(*A z%C>-!f61d%L@&Zm-a*N2!YF-!tN=6Orj13UVdHoFuJiYIULhxVUpNJu+L2dyc8 z-q)m{Ks3f)N?8y+R&5?c#T{t(DX!-to z?{7<+fAK~*NX+D`#sJf4XfGc3Nla0WN>9RG`V>!fhS+>kqe!~U8oEMvMj_FqipjFF zruk=NG@R==O_t*q!qE^t5s+;YkWu1>5z!mSz2Teac03$gRaCJz4oAcF5wZcuup8ys zQqrQi^U`@T8()6&z4W7(-%5Q~y3_H#Gts~1!FdU%Z$+9{UQACU@Qr&o#yI6Z6 zL}1LZdC!MDIoA!nS6(8}bgDUR*|Z7g)P=~1vqwWiT^%FBtFZ-?`Jsz}H_p@hNni40 zVH-S+`>EflyIMNu{cSD}RB<$rVG0kfBG{w+sH&=>>F>-;-{*6iCF+1-v`l6)rdP;1 z#&Pb_TId|WPI;o7Qs1*#`Wx@QllE-emL8*gZAnAJFC7j1Mmh?t119ccI0Lw!YtsJE zN$omagFMFl4Mzj_*P&sbfOl|&3(E};(<6@TVdo;xl^z|(USD3>{$_fU{8IeUb{ZPX zf(kf}$rbOXqxi`2W9dzJ!QD8`9zk!LZdnJL6MMyP{f)Z1SH{1>4@BVYxi7!Sk@GkjSaWVCWq2LzJMQDXa+>wEa0!P7JkBeZ;o1s1 zG{u{b;FaSim(YXm`H&yl3!chke?S{b2khbR+GHV5#Q&gyjGhz%>Zs}r<8d&R5iIOS zkFlZcA#?(pWuEWrbrwzgLwGR9>;^HpnB!;lpWEYT0AZ}<1;Vje z;}9Ma zdTbWsgg2ji72#;m*-!*h8$I9o;hyxt&Yj8B$i+(*$FVEZaRz7{s%(jP!CduER6mvB@pWL7HP63q#a`LDkF-8ee#3zRohAoOI~elLe-?xA#cuEi*W zgrYJe!?xT+f>BYISbRvB)((G!LbQeYw9h^ANYs=|AaMn4WCZ3|G7T9?u8``X)Q~ju zLuE>DqM8h=}9+T|NIY4sH?N zf4gjZtl3Bo3Nr<>5q0;#{kG)A z_fNLA;Aq$$iefpq@*s|eyNO7-uPRzPz;3Yym7+KnjWu{QQ0~NF^1)nTT^R2+y+P3f zrzV@x08Nc9HVAEYNS*cRY)Dnj}9C^m(@ zbfE$9$?+3uBN;-Llx!eNW%i62&=QMfuN3U=pFBk+LO81=*}%=HmkPOvB2Jnvm>H9q zaMDp@)M(dUc+K`*>F@mAKT7M!%rb@bB4@4_0Q3TmiipTOcd-fCc)Ew1*`Z-p4D3;n z;w)$d{0vg_EfL!feg5L@x6(%#bQ^IxcrC$RT{OQa)#7wqK*P)_I2uOS*Bb~p9R^OF zWEGTFMX>M(-+79QdGkj6pZ(+KteNlG4DveVF5Prd&NCWH7;7+N1L?o|dw-B#Bpq2E zeFMHJewx+b@lF$1N0c}KFJUQtsKiLOXGvqW`Dycs6TzFT&0b4+Tp0$7%7!r4)2}ik ze+XgEyV6MeA}B5is#5l2HK%F64nz7~##2Kf8Rm3O9^>gpKRF6k
Lxf4R&Z>WmLW*FIO2R$4Ye}+>Gyo3-*u_Yn~uN04)+gj64DQ&RP-;<9&o)%VBWwMFA zlXr_38DD2y=vG-GJt#ZmS&px~${fU&KxFXI;MPHY5M}7i*I!EyGxmmc55l$z*Gszhjt_RHgYe<6e&hGjy{lJcDXi?L zr&5@`7QK=j2bjn=#l>)ZDWHWHV|i?)Q6e1;?yC*hR1}+=n`}QU<%oNSckBcPCa%_@=#Y$KhY7Q{II6nbmm^tzSlnVP-HX|VYCji zCdYQ~g{{hc9`TDvJ+KxI!a$r4ya$%Q%7fZFary!mamFkeOYiQ+IC7o?{a2#Vm@rj# z7-cQt*yBk3W#0Mmbjl_TM2&Sz`s@)=T23z-*1M1B=&PhlyY{6kmeWUJB_%giK_~WN znSy~=j>AKF6o?GmP4jj?q)ksQh&~+fJ{yC&51uMf!um}s*0J{X&tHvN_`8Evvj(Vx zmzg{KK)uPeC=bOO9URWrqd=oK7w{HWJ^FH(`&u$n$Qmcpe6PEwH~r-2ucS8W`Jchj zP+zkUK7%f$Y#Yr^e3@8?!(tNfFD!#j?fsBtF_geZ`4aWt;1+#~hLBUmtfg%BTzFVF z{TVi=pS=EF>b-O>9jA1{Ys37M>VZvVIVbPnXdpJM$C^EckA>{xOBzGtkXz8Hd_g*Z z+Xl~#UIc#5_dV$XAsQ!QjNpjAf)k|k!qs&2R2L-_@L`71(NK+n`9J^5{|QIK>No=a zI(*;k#Jo3|nFzw&fSfYRJ++o!r{i8S1Ej0xF^pDX^vXLthSbtGBd?mJp0=YiNy7&w z5%QC_V;tp)vM+OLLL1U;GkBaL_Ssdvl64p+4Abzni_tZIU3}VI_i`cM$qL=$`yH-{3_Pt zt+oA+gw&s&eBz04IOZ8jv1d$7zH25~uD6FHfH~{XQ-3lG%4}M3 zN4b_eGURE8F{ocbKHWivaJZ=Hq6DLjfEJ-U$4?moQN-i8IPu z=}tY}jE23y-VEO;ouHIeJwqpU?&uQV99dZ;j%Lo7Ea+<>*>Vzjv;iV7GZn<2^S!;P z1$z1rC-?|nO8fIQu&-twXz!I`zv*Z&O9@FFayFdrz%l5bF~U&?{@4OQ9sUO2E#(BH zOW0**3VPZ{cONIQf&b^xzhC^$x6^a%aYaoHpkUTxG!ql^@6YgcdmIfRv|+#iHvOAb4*a^ zSucR$Uj^ZQjQ9W8k;73x)6mcmJsKopxx)mO9UX-=D43^=MQ^i;ih@%R*cn~LO(F>+ zhtGVLaE@b4|9~3XnRq~-meBE@>x57kt6XJ~7kcKQ9b)HuzNZq~ zd*Nc*wsS{1)_8*RUw<#Hx^ra^TqxRnN4N&_V_cmKjw|z4AgQo~=i9wu&U%Y;!qU-T zkA{<{nxmJ(OiCwgKD3bfY>mobM!<%N5dqhL%b2Y9^K*s1j4E@&xGV){ma$U6o?K>6 zC2~`C^`_sAQS>>CS0kt@RN{=V&jk>Z4F)9^3a<6R?{1-5f4*m#zpdLyy0F8ZikJ&&b3@)-3ZpK1z3~*!19tsKl+i~6W z{dYIL1w$_+`no6@1TCzZkK&0z?HSz|lH({+Eu;<k4$BW-nEqT`LLrW?Kq8c#uCD7!PB4p<3CQ%KJrMMDQ>?Ej~aBJbsTC?9y;<#dgZ4- zNvl?`Nl(#JWx6T5;vx@)jA-osiN`)G$aI>8;?H;r{@gL8QW3{hGQKInDsVO*`e4_d z^p&rCGaL=#+|b|vN{WUka79R(MT0fS1GSV)0KZer7@&q)K-_ZzN)$*&Gswf~EqK=f z47#81+{+hIszD#FA(B=%cUG#IGc`@au)IO`*G>4P$EAf@!k&od*@EP6zUIoG<1_!^ zGyc_46g?W)I~#2t>7>zSBV}uRcxCK2|IHu%XX&LcJ{ty^WihHPDyVL9Mq{i2n4sc? z(Qg(*zr(2?t9=t6h#_kVzAsoVN;2b_Jwz*a58srTsoFsrB&%)I+dQB zj{LC@MG?TJQz$EMzPXW3(0yq^b#>MZ5?-(JkT)U@#~r`nhlX+^il?(wMe7E*tMWXa zv2;wyFPTxK2YVFUK9q@FyLN@lSlqBEEvj#bqZUJLW9^PDuL;L8<7j|7$07_*7#fX4 zGiQ~2QkiAiv2YTnte1Y5)YO)fC)0!Qm_^8s={UbEC5h->?B^Ihx>NERV4^Z5zC>il z_xa!b_TdqPI^o65lc!qJ_rCu!l0{-p_nh zPQ`J@)YOfM$Iwj0|J=^VG0k z_gdiT1V4wOxMTM&j=w&fzW&W`QrfqQuYq$aiu}(1V*UIs{sSh2s7Zfk4U8S~g0Vf* z+*5FFLK7N}>JHW(AHx{+^aj)RU-%-;Agil!#Nu#bzjW*9|pD>QV7kQ4yL++;TxTC!-m0?`3rDok84I1Z0V8s#VZW(FjFm*o}kv-Iy3^}AR zp&o@UqO;n21inHO2buTVL`kKOMT-{G402_Z+!*;DBBP-g9$|kLVSNi+47ntH+{@S% zc82k!rCZEb6pKD z__VaN($xI~!JiXk1=OUc&{Zup6JO*V;-N;bI$hwue~U9-Jo}$lo`n$lulvkBZPK_O zou&yrQm5@o_`q6>#;F8WqDe6GHDgPB_sCf3RGQQ{l&^;o3hhW$Xf^H%wQ~bhY>kE`OK?=L^T**3CI%-P?0l8x^xtE4$~67Lc6ihGLpW>XfF z5=dYlKES#2#v8B4QLZbNufSQoG)_p0OMX^R1+vO zV?y1poS>L}7G5PAeEXJ7>1m?fcP!%w$_R9FG97TyKJY%$ls1u2j-VJaE7x(nhdjse zg`edGL1V1fQ*(awlOKmni#|5!*k)Gg%u)^kV8&#QV-I<<`jmW1_{i&pi}dTI>{G`V z4|Gf(#-RQ=^tu9=KfYl@noUW&-*Mg<>@yzkSmIF3Q`%zA{2#WU_Mi?m0|V+2Iws9_ zGw`Eh?I7~|D_{Rcy3ZaBz~LI7 zmPf&LoiJVJyTj4Y+uM_#d-0|8>~qhi*;NZzM+VOr%T0Cc&+zrTI~rWPl$~F|LuB+V zK|g{4@d=8=Hd2>*y3VF~7}O8lb8lK&-w=Xl1VJ30K9FA~q|h=Y%m}V3r;1e|3kajY zlVGh=D@2&s_-W|s08#ZF)WN;AVTM#BOk9-zMRVm6wudTf;I?y^pOoPsEQa{q?Hgge06|GD4`swATf@_U}Vix z0BCTZ34RbcCn||Z!%9cPPk;P3QQx(m$ct&a615Q#(;R&*41`lKZ^m`~-cM!|3Nznv zJijZU>lu}a^rCRtqoL(=TY8>|(VZ*r_|!oXeGQm9fd1t^0B1dp3=K0>&?}I^6Nu5h z5LOapKdJntW1ISVoM`4W_F)6Cu@8YvCm23+pu``i6Yv05&dV{~LkV1Fs#55)FfmFU zjGfoLD2Gian-FY`(Ok;ol-51)APs!L8Kx_vwx@%z_wUTvqjHA=3LIR3Fj5d}#3*l7%kS>pp$AM_#7;X`>>5%2sDI^4BR7L zZ4MTK2nEb0YgbVm4^TR>ZQFa{XjlZUFIl`ORpV%wTuizy(6~YLd!!$u0ez?dFNHkI zw9e~fB#h#n9l^OU0`Nwe0PjX;?ZNZCI2yL4UH|gmrn{KM;^hr#HtU*!5S+}jJwVP} z=}Y}1{b@?^R2mZ!MFQ_Fm*@vhT||sqNn<#BP36ae3)1R1SA4>_Nkl<0IKkO|QdNhD zC`k{coH#LK4!FpC2CkxI(QlvxX<2}fyGc6q*{j28TXS1_zm*%vV|nuWH~;m2k)C_} z(Kw}L1p3oJHMLg!wJhZ@&ZC!q@{@Eg5s{}Je>|ch;<}$puYr%*P%*5yA%6kkV_y|I zfkV8fabaDZ(ONSzd>Zud>0>BNU*(fRCq3N+V$4P?- zYVJLW&9&av2v^*WG5b;AOfB5Hb4U6Jf&ALmJu$Ni^pPq~=BS%j%wuMnQG)VERBjyb z)G!K1LpI&9m2i(S_d!LAS!##*`|dLnzoDXK0C;a~C!TbTr^-_h`;XA6^e$kX6Ol@-X++ zag_`5*Kja1w(sRewDKc=h+~<;ek02Iy4cST_RtKn@dP#HUrVbvo=o0u1l6p+ECMCn zW{wLTvp3+M02%`Tz79OxOX7v`dLoY4Qj8Ow4j#vM6xuq3L%9t8^9;w6nGtu5z=YYC zMx*RSU;x5sqdedFySEy=MxNy7It_i#2jmbiSHZOzWYdYpbP*Y7L&XQ!ThpZ-M}BTl z!^{p9Vr9AdgnKFcIzySl)O7bMdL1lZ7HigVq4DGV zkX6t_x%gX2X{40`MgVK@pOVfG31q$6DZR$Et>R-!ZM4A4j)x?+P^ z_7vK&v{ge%N0ph0!iC+4PV2+m&kPA0=?*f!I@=V|qOWoPt?yGhfg|Hi$~~4ZU6v}* zZDx{Ts=RP)@yCaHjeF}Qz9~<20t$BknCXAezme1I_&bh0ro`cOqPu5t!aVxuBPjnI z?M!LjMC8cer3=x()FH=_$v3HV8e>A^?D;5j9FJqc61P&C=@!!GW<1Q)25mMBZ0hJt zzu3Gz{S;@z`Lpd&hTy#Ju1u*KIaLQf%p)rgNtVU~r}1$UfW-WQZ}Fro)aX~fsR8GX zh6xz%nQRBwpyg4b!^0D321!OkThE2`;i2Ai9Cn0RoNyzhI~LAQ|LE`kVS3=6RdKpf zDSNF`Zxm*&t~P-=oAEn>OcqY!doQIE9cMbz5#)%`-u2MxQuG3Oh%hf9%R^m5UT#D- z3{-F@c#ky8IO;G_ilMwi&(M)!Ag&+h)``ZZbR3+wcUE;x4X1Q{J~A32fTU6DzA}z@ zD87rM(tQ}i0S`Y0D&8yS3Gg%x-)@Y$!#KYT&?pa<5G=gw?z=(;scRPU9UWgbww6D{ zgSqFrpzsfeDQgHF8~(#qL{^dV+Y@3mcCXOyUj*Q=xGVD};3+oR#_ciswGwRFP1Bykiwa2|$+oO_Wt%%p5o>ZuaJ zC)f|^UdLb<-^^R5=^*#8|5O?D)z4nO`Sv^M09o6Q5iFDs7?dcEa`PduM9`5|Nh z8NkYUzjIf%yAQcOr94pf+oR#ljT_T4_SDiod8B+to;wVDoU8LvPRZ}JJH(lAV1VE9 zUFoR=J;N*<@xddrJw8&{>_0$e85zDWQYv&WrAE&23Rz!X%1qa--RM1Z?CVID_X?BD zA(E{p;KBWU_8vL_l&$*?9>CFXD?ROrA7l@^mjx_dUO9pTQ+XnfG@~#aRlrTW7az3+ zbUsR}%Bh>o$38w+n7die$4@q;E}U%V2u57M&U_Xd%8Z7YvxqW=GY*Dj4&c2fy@YekXg1R zAxn6H%HoTJ$o+f{LzT6*cXXy5I7&RSW(_q)9(^VO_;r=%NTGF3Tq-ImSf(>OR~er| zMmUMo;n`(;pH*~>)E;kaOq(}tqJi2Pj-TXgVh~+IP{GwH5=6mwC2r^BeSN6#hfn}^ zekb$nW@Ac-K1?gsV=1wG9!1pDA}FCjbaUb0SohT|Z-tRI^ z1BYSR@bII9 z`$+Se7`R?ZWMK}T;<92CKaAV!Lqv23FziOaPc%2{nw{eaV7dmP!fM0Wa6@g9*JZ3{ z^uncdU)RpxH*6=7F4r<~J7bb67#h+}E|jccilsFco>Q3P*0 z&XR4-t(-c+K-i#pM#JCx>I>;X1d27k_Cm-SDPiTa4;q*%D_gc~p}YU`bRRgcaMIw4 zJ#-(rT#fiBzGe9DI^5ID0B~RZf|(N1xe*QfPFQkv9OL5XC&!_u`%!Y21n+`)*jx4z z=B6MMM{nV1z`D)u#Mm~1^bGf`2^Z^Rtpnh>>8>7a+0@#Sb{{(Ftf^&FY-`OP>x}jqT{?Ri8Pv%6AZ6^j| zpE9wW(ufp3=Upfd#oei63X;+6qUs|8Egz| znxouAqu0F`8J)8{Ct$%?v3|#chQetF9;%=#_*F`cG&G((8P1F;7-ya%Ud3YuQSjhh zL@gqMJ~plchAaXWD&fx46i~Aq#2b09kr$O5?`_v`oxP_qeD5&2yO8KE4h`pS30Np^ z(7XKC-E=+STyWcB^4Y#R*KowLuy8bZAMSsKl;*clM0L8Dl{J%SSIm*QsLaZ!yRb@SxP!hm1`O=;)&yg(?p!-cfl*& z;~-Dg!;mWa*MW(SBn<$wzHC&h>}bPaKXs~^ULhrM3Q7g#Fr(-j@?T}BJWQNnvcN2p zf8L)-htVZ0yodZsc*!G_DQ4WYb1YnEM@KZYG}CSc28Jhc2!q%|@Ix7^gHpVg4=R(D zslngJ#tZ(#I+gi+F<|4KYB2U8KRgz)fk;{n_fQcx+Uj$pU^{izBBpsyoq5vVBr+nE zI|TE?QQ|&&B(d<34osImbofxLv$C=>%0YEdX|$+3+qh7@Mn{7u&KL-C{$U_6|0_74 zq#KoHQ|m2NF$!BuhL4T_b3ly04YLIgLa#P#^|-v5(`HZ_IvGa;xWP&?uQ2HM6w!ssk7g{b64tPf7h;AovP&&Jal2K<98w8To>lE-AS`xdb8?Cwds4jxI{kbxJ@p9S_bP2gHNpJtFVr=@y~ zzDgVolY#XF@P0hJJb0}OVBd7)i!1RiFv>m?Z&{j4@OxZ3BXCn>$6F$++j{yq-m*6} zGQHfOL+?`0;}Z9C{x05!Gm`l$KP+$1Q6f*QA(*##F}(t|j$hKtsm3u)$2>jC_RLK?4h4n6He1LMC^40loJH7car+L z_JMk;^Oe^}sSa~h2hU0ZEa?Pi_)MI1E&eUv_o43o4)($I8>4Z=dz^X)zWH5sV8;zd z19O+R35VeC{4Gy(ys%e-#|y3u(cK&6i@`$6lxyqi(rU`TqJd_BI~y;8c#NgY6SsYK zgvjn-eBsLqqdd<{3-{kr9mh7~?)ZtOaN<9_VMAIDy@+o*cSBwP+dRWt+zVME?_pcx zKHN(fdbuX~s=BRvY*4A4Kw;y_CYq*?BP;p7;K9lb)#eCpKo=wMNFBZ6r~KW)mE^)D zWCyfqqjWQo@&wQUID`r&hSCd(r5>Vg-4}a^W=swuv=Nh0 ze;fNLe2PmaBg||Pf=3wdwMVR|e96R2Efi^GID$e1@oe8v?3kZSRt9L4#ZLBm5>-IF zOj(l9!ETI293PCSf}|i29(rd*WC1MUNF*{B9S{?5y|7;pTU`yNDvN-3?1?(^MjS9*K61y^?7- zUJ!67jhTTV*{H;-gb9=I{4sA+R86}ya-mWooD_ELDCi23dYn^6<}^xOXGtmDmJw(+ zn9`eAHklgQm?KS~*v}q3k^=*mVNf)+0w(@O{FD#MNMyoSQ5c74vNshc&rF1-Mxgi* zLV&RqQc=bt1Cf#QENq2We2;l4DBJ^a)LK{>iRsv9&UR3{PlGRv#)_(iG{Kn`84^P% z*hS!?&6va+qiZUSmQ~2)WG5=S&QT^if&dsYVuX@3iD;rnAYHt4nMOFCv0ef`Vz3Nf zU>wekCZnN*vm?h-XEEVA0)_XACeSS#MNiNE0PyVRgoJBE;791qaFd$TaXe!|r;-aj zsi0>#t-x8amgrVBMq0m|k`j*tZi|+u4c} z?hHyARR&BsoDGXAN@>(LFNA_#`%o&`SCt0w?FvekN6wX^FwG$oM&Y3m=Ot{#;V`^J z1b@fh3QFHcm;zM5Nj)vYrP5|lXPH#6+ zuEP6vzmSjC&X~+;9&@5!jHMGQcmOyAtGwD;+5XEHaTYNT;OkL;mQPrpsZn$pB^1&~ zv**nYhiPP9fyX&7kY|km=OPqHqps4VQ4eA4rIRL7z2TeA*<%THY{(ZhVn1nUji1Faejz1p|}O_&v>t&+q*ym>=epY zCwy{Aou^H}kK8aXp5(2O`pTd3WU~p%kY6f7&Ru?L4xI8GvW?L$5~u@bXcngLf1DaRnWspA0FL zVC(yh?iMlUIb^6zhBw>e!Ex*rFv{a5I8$6&o~Gfza{UTOv-O<&5Lr9L;E_fJK+Na} zV1=^FdMv?IM!IK489mle8j;>75kU@T4SVN$HT**%XB>ZTHlcFVeNbm`&%#m7=SGk_ zJ5Q4Wd@Yqz7BF@Cj8qP;X7U=?z+8pBr<;tR1I(I>^NIk4a%&K{I|pe=M}wzqS$b!= zO#yVHQPYdQ)Y#Y>M?lV=cv;Y+xLfmrM@%G|JxJ0KYszL;0`#Qy;qoFS`iO zvR{Q+gIVMbWtw{q0GI_-*~<tdvWipBR5j_mBG{nA0A}>d?l_G^Ktynn3fimm!?V_`{jJU z0K76wP2Dyw?kx-qZYU1bVfi;`JA@?f& z^CWy1Gi5Jy!*ev7W1GCZfa3lj;omxAOQDX`8rX3?5gfR_V!a!&4zF&k>bsG2gJq>R6-!XJX$P>K6 zMuD!BJ!Y+WEUH1Q1=wUoWVE?YVarLYj2|Vr{7!k|oXoP4zxENNGlNr}?r+rJLzaW@ zI+S$=^@BGZr_ZH|h4Uy!oE&w*L!BVX z8+dI7YfoPot+lD!WIr1a1K#XqHq>r3I3QGOdj%~*$j{R$Hq`~GL?={7hTWUAQ}Dc>Np z3?_^+Jhn32#^Xn$A)!b9{qSe6=3oD{&rA4pLOF^<|E<*iYrpxMe@M)S^XSJDA-kEn zfAgRJt-qMfH;l1%{;l8q?Y>ZtAOerm>EG_>zxG!(C?_Q|3Q{A-3XaLzU;F*v5ShY=07HMQ`#omU-$&73%m z;}rYTCz)#XA07TN-hF^fhLvO>EI{C3j-*MqRH_terY~n6Vug@G0a3yeN)PmY8DZK* ze}*plG?=+Ch%$fkx(X2n55j8b7Dg(IyM|mD2XS~3#nc%(his^aVa|9(2)5y21Q<%{ zX^e;?-2>^vUIe4oFnpFa2q+Ez(W(E|Z_eeH^wf-V%zx`ae$5YSKzQU&Y9_nmZ@Vya z!sxHZ(XfCjp7}U3DyEgt?Hr{W1-k$Ns=}pK&c4Bv#j|hc=qW+c(QfAK z?Hx8otLNWIlPBVo8@=uLu3VZAJJCpP<@N1Gn`MkSWx>4E)!vobczwICg_QYOOW%=u z4}OCitf)dZ*E68?YCPQ<30^M%IBdMoWGck-|kIiY;gwl zJsMo{=WV^%mNa=z8Al!uq_*5ryN!2fz;B7L#rgEh(!$#{JZvWT80t)t7u;r*CMiFr z&cqSkdn3l@&)ar6_r-I|!|8SE{{z7-*r)U8xNS53_Xny*$-)PbS};H|x68l(`EUEz zJbpNfpyDXiChjTZ{2O2Y!$12Inj(KKGR#Ci^S|T<`G3Fhfd4=G!EJOjWNA}+M~!6Z zSwzK#2j57|$Bw1#)Tw%8lPOFE7!*}_qr*!B!;Z+D$}$hVZrwzq8_#rw0=j@97A{^) zdK_u({1<7>0+8=o8X!|Hnv|tCXEj^lqh^2b2=UPG?3^@?jK~@(ZtrYQP3JBo@PgF4 zxzQiNb7_sTN9rWZG17eT`k4-6bjeF^o%ht^6|!Z_i!G0Kd=-7uDm|eBT|OT^XY^mdd3_aKlfT1jq-bX^@i~7cAsfarw4DOr4_U3b1^%- z!g_n1pOd!?h5vzRHc!i5>;~+30Uw`vgol#(>oGU#+~0pG^-z<0y01T?s7sbn2R^o^ z!o*8>1X1~7>~#kD3}yj0r@?3O6W4}^SdaBN#%}638%ogp@}g8z+Yp|{QDEv`+8x$k z>819{;qLzG1&#DdJdJvp-5v49*M9Dvwzf2<&MTQjTROiYnh{RI3v6^ryv;8o8iCIO ziAU^f%sGR9EOPAYStRgQq*ot1(H!1WZR)$1&>sPhJ>~rol{2DYL|HGgUef6H4=x*N zH!CD+LYag6G>(WJOAbTAk{&Z|x=6)6+}RP%uLb28uhsLT{_i>l{&k|G*YUcS5eb_{ zw7vl&e+i!9g+xlG5Fsoj_tG>`RHS@^VyWVR86`RzuCd>P?C~H=?q`1XY`Dr?{cMmZ z=7phtjHc_U8zy`Swm{Ma&aClq)Q^!mqc)xgQ$Ul#L129D;^ov%H|};M!BK>n(J!h% z0(3R==MXiRMP!xKSZ1QLBR8~#ci?;MVTLn$lEwGHU%sDb0vNd+z?so=zAJTH9!^!@ z%p9WGmKK?r6nG%5jN!5<8EXdD{Y;$B`AUq=Uicl;a{Zns&3OFM+4C1-UzgO@(8P(T zBYScSxJ7iDd0isosJpu>UAfc?Zz5fhG3wFm7tR@Q#nomEUpZ`@j3%;z{9`&-Zi3Boo72!)A>H7TWYA9m*!Vd zPDfP3>;g+cIL_1ih`-{u*<%4WzH3I#S^7tv>^vLMrK-|Nsj9j* zvKMvciCd2Aeupl=@9i(*?}d%`9e|$*w2pr^Jp3P2c9rD_sHL< zqg-dsWt6Y@o@1JI=DY()uETMev-1(ZJlUkZttFkN)NejpJ(tw>88c=EPF~~Q&L1%Z z-xGJ>fy{Zby(Sn(dh;IAzv~)XWxRH7>T{PV{c44tY_hlze4I&E=VW9~=q&IK>BP&7 zwo7EETqL97@@1Uj$eaI{z4s3LsyG_{hu%TKu91!?Hte7%q6T}#h8=r}XkubZqS0tf z@@w$Eo&V9b; zoISgcy6E%7sqf^VPY3S1ZPYzF;Pe;k=2!7d;bq_^Ps^}6Ne_6h z*!u7T&&|}Ud~9TwYty_jkLVHJbXt3jTzkw2Kjoh|O{6yM zNi$(sOw`8gS?{pM)p8;fTSo_?KiUw9W)!F2=kx&pHDBvqH>!Fma0Q%J=Fe>!#eQXke5`?(~8F zScr`O;P3Nd&gWl6*R|TmIN1^hla&V}C78p&8jB7idG&S6s<|Wx!l)Sv{s56G>r2g0j>|X`_9z&x*}4 zbH;mV>#g0aA=9yY5EGo1^+%B4b2Aplk$5Hk2BQa@yN($BQq#5YykDnjz~wdu$Y4 zI&~^cNbyb=kjRGld_*IEjm0DHz2%nlY7N?@U+lie9xU+KHHj{y~9Gz=1(#Gt}P&#+<*kkZ`^kvu4NWr&;{#rB`CtefG?SmO6LtoU7kwUNjgT z3Noj2xKs>IRZyVoBI}aLdDWt_{2qX-kLg%Mf*laXXcr0-Me>e)SVU55wa>y z6|0@kilpLHT6mg|*_o$8FqH}ShBxX2nKO4zOnm)y7Uy~~UZ)dq+%fDT!Qzf?`PLev z!fy;%uK zw4J(P7-izvw+VECUm;R~Uam<|o|Q^iz8|=!?rpc+91~~Hi(YHCjT25e1Ke+(u#0!+ z-Mad+SKF90bJcoxg7}J#yrF{{=8fn?8j{wG@HtoBHazUZ4;RFER_49t=9?1sWB1%Q z_S}0YLSSpxi@60SP$%MW4(Ar0?hYpZ)LX61bza?Fuzow!Y`O{bk*o(YBKE#-@8 z&Ae1RJWJdIqkJOFV%&G~n{7?Ul#2|?^OI<+{rBFRmEAYXMVxei+3}L6J#DWlB7duR zsZ#6{kbsE>7tXlUPpb_OjP(T-d_Jq-fdoCbjP5-xw0yUN(* zu@Hfa=I{DfKD%lC+qs2^fnax6*)1d*MSEIMb4nC4aE(e+;^YX{VjknyAzlWgw z_Wtf3x#*gPl3}#m{jIH2~rN(W(_;HJ!{0+adFL_tN-hotk+)K zZ5@XkGKfX#dS<)Nd9%nT9Rg&Qa06cL>MsxBF0fmH@*6#c!{Afo@YwNxjq6x|vFDm? zVz2!UX8!*UvHp7NCYFkHoviR^s2h%6bAkNPHXWEAGY1$AlrjHFbIn zd*qSmz%+$^JMNh4BCN}t>o)SF{6zlZM%b12E|@6%9_rD=S+*lPHMS-AiuCh<`_0L3 zCNEEzIwMXQa(ryP#pXBzR!e!R9Ftb!(jyHxa3am5sZ%NJG^Q?BCX=T+-T?r0?wmPu z;>|awpu5M%0u0i_4ml(??or$7jWp_3X{9VzPp3gg-a3|r(R{qR-Krg2r>ErB%hdUU z1IDQk%g# z3Wtk3{`rnO;-$Bz#m0p94;lJ>=0o=`;orQs6RrO68}Xp+p>suiWXFqg%@441wn7V?a#3l4)E>Sx^_#}dNOoA;T0Zn0xqnxv{J7nZ2T6!v`O+e@&cXe zGz`mjy5YR{=f^WIjE_4W86N$*ca9x*=^tA%mwTOc)>ddF4s>D}Hmyw1sg<}PKSS=_ zK3E#K^GO5rkyD}kPJ8Kn@^+1?C!ZdZA(v~S5Ujgr&1)s+2Z~Z-H(4uPm?(+o#f4eVRIvXWm<`3+cV|@+vOTTMV%wHo4Tz;lL7jCl zK2Vc!%t%1bKGK6zIbqvRePJ4YODEf%ICF8uzq4z~OV|Z} zxclDNf>L*S z|IQ9`6LS}d(J#FkCmud1wnYxCh11dLSGIj|Q=sAkzzH>1pL$epDK>e>G}W3AZ@)b? z#v%vq9{qH5TdPAHf6Otl#U`6DRlGQ1>^ljY_)eWce##lAIqQ^`m&$q(l!NV|UVtdH z>*cxQi;E^d_Q?GVkbe^U4cI028HkOI{>a^3u#=>v)7_MnX$PUpp#)Q&7`R|S>dBEK zV!MI6#o(g{V@q_x>F8T{EC1=%kwV|z<3HqRScTL{ZP*Cp>dA58j<->SFJU-+fWp-i z?xKfoBj(71BMhm$!K22ci}O7@etcYW(M9nlcs=LvL*wux4yVJuX$nj`x&BZHX$+wu_hg( z6if;vzRxum5DqE;7di2rN?Aj(zzwwEBozwpK4DJJ+lu;A~f!WPlA){A;+lWu&7@FTV0}Jp9l@@!R``#XkM}#hE7# ziOqZUD#kEr1uT`eu=-p01=g!)?O7!Rg+~WZYZmOBj{|1-<0Ingi+>W+Nc#iwKAc5W zHtO0Hk0=Yqk*8bYNL%?$L0-)T)0?W&bR<#yt2iA!6n32s8j)|pzqj7;=eYLHy9Fn1 z`OU9mpYMJ*R?`d395jelU<6P*b{?xb8GLC~Jf%!li)U&4^6am#yc)l{>X-4<>yu)S zO*V=j{OJ7HiN$9W-Wr?2E&MLl<)N3iIXnZ#5$Mco2fuoZ8z2xH<7mir0Thl*Lr}3j zG4|;=<0lvAx0jrFS{#1l;jwYAo-7PWy@@t}apU7z@5T$yJQve{dwukwQ`4o>2GPW= zESWmNQVwa{NG1jAmw2{S`c3J$+Ua(&8@pGI*4v?VHwZ@{G*D1CtggL0<}s~e+QNA; zo#AuG^}eEq>-rUdnW3Srm}b?sVM~0te#6cnUoMJiA1#RqI2&|l;BUy|XBV9xd+fGb zY`E6ibiNHQ1(6yO{1)c`l)PT>UlhN*;&W-Ku_erN=gwt|y4T|cI{D9opZyOyH2Q&a z7hQ9{wVk?bN7O|cRK}6KqcLkcUB)}xL5}Dpv*LW=UPr?e48(EIjfwjrc(O{Vv-cp3BG7tvvSogG9*vtsq+$&+I2OXIVSUHIF10~`(PqrE<(6788| z&}2F5B0y^mKHGQ$WFD4N@={hC10jvw%%K<({xy;z!*zM9qhTeAvp5=9eDa+VuKQtr z6LHab=f&V7j>x;=!yk*^{_N*WEn5~pyWmH0#G!}8hIFP~Pe(_Ci^hR~l;Pqt@hd5S zs4}?fcpbc_JfK}U0x*#d>7Q=8Ic|IO@#w?uBWL~S$FU0w8MY%jt7@O(SsCo1@-ORg zARB#vd`~40U8IA?jHAOEk#;1_WX#4W1m9@vnA$^Yz?*t_eXxSKyxtE{+Yy9Z4OQS!X zQrEuG5hSj&W5*SsQ%7f8q7LF#ylI?@6Wf$9SQnj7;%w@)X)zvWz{pXfh?rU)rwthr z+hB;cWj6rjsPki`Q<)!I3_A1oTa9TKh7;$xwKZ+Ux!dxM>ms-x`xB!_$MqLo7%u_c zImaFwgXwr})U6xsl)3(ZyqMjsTmY;oJZ4i@Cde-ujpA1$xQuX>NHb|5Z%P-}=y(iA z^`CCIDW`i}cJT#ly}LVeme_`Zsd@lU*jCO&YYh}K;7KhHuFOCMC;m#+f0|*?i z&~drux4(^t>0s=#{(AAFpIx4|K?~}rW6<@88~{j11No@$bRr0wIFT;mT00~SXr4<` zY2qB{r^h`PS6y;xY}K1B>Tt;RXZ855UAm-Uo;!pAfB65Ud$5y*@GCpFSflKmSLu)3)12 zTX?;xIDl^Aw~{BySD$%G*Btayc9BLIBQ9-QEg1M&4nCiL_L;cp55JH5aP}U~HlagL zJvp|(9@BQ#xwQ~^VH>oQs7`YcNgWN+HhBiRD2wYl?#g7ur*O={P96Q!Q*rabaVuyFNy$%nbFnShBu{uu$dYKJ$0hSzOV@}+j3Yf)&y%Wp0qd-px}#ElO; zm|JlVz2b`44W6`9ssy*)D+{!-vvW-z);~|)se_b@UTwR!RXgeaPFwZWSL3?tu8n6V zO^Ks$_6|8=NNi7^Mcz$bg!jx}yb5>Xmy%OY@I37euHK6)<&#%+lQ#V5XP%AAe)a3< z)3syleej^z4SS|rS4OdIE7lizU>=qw4eYGeIU1;kaEs@pKX?*HxlRTAJc~%gM_3Q< zF>KZSjyNQC*`z3Z;H zQ`?wlo{5JaeJsxX{<$$=rybd`W}RqD)Lr)PkRx)mu;l?RJksv-ns=oh;zWA8z_Znw zfUWn~qmRa&xBfZS?%5-Lc=p-s>aulieXOHW8K}+^zRCu1@Y?ldTz@Ye4ajrXy8#&1 zW22#RHR8km$2bN$@4Efg82iTCaT@mZ@q>?wO?q_4c7;yZ0%dT3z6Z2bZ@NyGt^{rA znRDKy&X2~rJ-WnE4Dhb8c1PYA$tHgp)$sp28j`$8dZ;O3^GJq;x-OQeL9291Do>YoYjT^`IK4-;zGCSw6L2>+$A+g1#z0weKR|ic#*A!7`lGT&Yg!c+e27tN(253Rqyz&>)!ft#_u!tq8$MqsPV(Cmt7l8SUD* z=f=6sp803K2o9B{uqsSbz#uS0TR!w1d26_&F^4f@=#Qg1fBoC57>c*&DB7O8vV~Fi z?s)&#N&G34^xm3Z=4E!~Rd@1$!*`W4LXWk~KO1AnE$T+$AbDoYm^l9@82{UCpDU!h zD!F->uVGqdpzu`be6<9@p#VeiSR-*Q%zTh_Xo5m_aY(lX98P2U-LPS?SN~mN=*cKH zJcu&BraE3b^vli!R(=@6ZD z?zyoeD-7F_&=^DFB)=$ZRSXJr7v8a(sgde)L(trX!4rZ~0E@-Zsr(E_$cV9HV(5>5 z6ul^S&>82(z6b0}IAFI}w2}oeSxBojbzL<7AMxZ)@z_j zL^QNyp((JRd&9d!Mw)}@=Jwdc~2~h=eo`=&y)-9WS~*JV1c1-GvaxsbKP;)4!;G{Vmr^=OBurxEyT0L?YH z6Ald3vgmA*1X+j-1U|^aQLg?i5e*u;IvVISF=X~J^Sa#5ZPIiW*(LRy{3hbUv(Jgc z4>>gN9v?9x?)E@f`kB<&dL-F$8|2`v-4AWmkd$N;m9c?4ZN#%UXOMdeMe#6NF z-g7h!*{I>9+;br(4TWdvkY0A)58_oEIp?xv*O5mZMa0DBnQv}4NIu!g&6*auV%B1^ z;IF_h3|SAZ9xg8C3egYZX!zbQu80HJzV84=)^{5)AUj5mSh;v(I;G@G_(CI5S(zPj zV6y`!yvjZ0q@!wbsxn8JG<`PPRStU~9=-SOIPSO;VyAvP#b$Jl+S5UBWO^k$@1ky+ z9?Aj_ai0IEgq>SEAIbxrrQ+Q>xO>t+(0#Aaak&Yn>6X1VjeT*DxMkORL^LS>DkEB% zs}6JoMt&Es;!9c@I_mTjBPDd!R=VL`J9V$VlF@u4*=-ZcY?6yg#T<8|$ zib`QEc&@cm9u}Qd@S;o<7ao4^Ai?WIIgT1ND(=4Z)>wb5t>e5i&Wvrri^i(B%+3XP zDaN#&QVc}uE-zVs^{H}FI6SfrJZr;9-y(GDlVhHWJO2Cnc=+Avan4c4#PNq89$h11-c=BQ_%jiY{WZfruv`ycanhbjAoGIOXRE$H9H>S9-2}=Bg}LVBoDEj)rzPX`B*S;a0m#{o^6df@a+3R7u*H z@+Emc%P4Kj_NAk$IfGIk5z+7n&eE%KPB~b3=~-vQV4})4tQ-yMQu6T-U&iwYcd?22 zZN8qQk!S7PEvF7{r7F+Ah12oo+is0(X;Yi?{YAg}O$;2cTP{|s46f{SzZVI%B~K%3 z)#>6VM&BHEc^%`P;aO8J^nNUKUe%b4(!@J_Qj#OEBd2Lr%vfaaWK#H(l?z*l`b?( z^92TRE#fMtud*SdGWd2T4zs&)1U!D{opB6pb;rJaV$)4GO`As9Xqyv1;=j_V>Q}N$ zd>7ePpts1z*#6Do8K)r4m^p)JjK9TS?z^AS`i^nHcL(NR;RYLg2Y87hA~M$RUEExK zqWrLbqs~(XDB~0NcGP*VlUJvS(_3?E)=6)$)%Wvp*Zud!x!6m4F!-ROp$!hx646j( zxoFVV%L9A}ys&zdtNMgrJa^|3dG$?fj;Eg*6Zik|kI|Su(@%bIUi961t8}7EzvMOf z03K2Q>0DPP>tI`sW7~YwzJ#7DkQpxiN`l;J=VNSwXX&%viEerXN6hIA)|_$tkmyA@ zE#vX92<_Yt;o1#6I`2@yq&G2z6M3b;187A^<}19l zGZ8DfI4VQY5#C8}usaC2A2n)3T=e5hQn9(3szN%wz|hlt&Cdp`AaRxJF9=gK^hl${ z2nk0I6vPS;8Uz3eW;2JBUhp%C?e0iAznW5q4!+!89&Nzp)NPB zsI8~ld5lh-cmx6Xz~l*W@sLyE7!=zEj6}HVc;%rqy21Kbhs793i*+p33^qf{9Gy}j ze}PbN1kfoX?O7>z)~s1LcW#R-?zqju^U?DjW?@O`jG=Z?j#T_Py^#A3CMt^i!sVXb`$magGG>doinq zFXXwS`R=FQ9DHM8#R~Xn5j^a=6h;)ZZrhHnbiRs_&yI=nE;&DXM~B$wjN@YWz4nMs z-8!*=BeYw(DB45MFBg2wCc6*#;1-h@s((~>-S-;}0orxFrpy{wLkO0qe! zuYsg7Yl!F)aH#Xawxe<7Vvrxx5uf$NLe^ba#J6+>7lW*I-u-wrsPm8c~#2IdQ~${aI)t z?;{M7A2l*;PxI!@i|1Z`Ij*_p>KHQQq}Yp55l463=G3DyvXliXW;xRiRx$dC4geWB zI*5XI{-S)_o|VFlaF{-QdPWEhAO1+pT(~4ICQ4;{I!FzXSu63Bw_R=ZoF}TI;ql>* zrlVop8-L4kdm_@hbz-ZnBm1wYbAs9m$Z zb9Y?tp{hV4RMdZ_+E<`WLi&JE7)RKrd}k+7_;{I^}orlnh=w?1UM%|Im}8 z;_P2v6^CrTb?kfK0Xf3E;rbioh?OH38s-`+wp)!ZBamz>!su3*(nh_MGLMI1myQOfHhjF`Betgdip5KD$e|lFd_AmlexLai$Co@> zIoLI#Kf@Su&5&2K@JJSz(ZUY8sk>L(wRO>H;Z6>V z;q|I5DI+x)-=8}tCcH*;&NE}C^@odwK3 zQzzExC!&eeU(PkQ+;!3W?h^DgaNm2&ZE@GzugBR$sSF{~u`{FUhH8rgM|SP#8qp(; zgiWKgtf4@s9Nx&zHZ-ul($-b=8{=r7J#%K_{O7mclJvUq(x1g4`|KO5gFB}tSYLVE ze1%oIRt^z$OAbZ=t2;c{*>cM}N9#mFYULGI&uiq`sz2wKSGq{%z zKZ0k{u;n}Dna(Qn)(K^Ml7*CE>OEoBagzrxTGPSMq4C7HXJgRNGxPCz2OJ#7pKwC- z>eVZEz4(mz^0poM!|&~=+L@8Ib_#uN=gy9XG_IpF?`_}n;K}<&j)=?t^v5`7uYF@T zI$dtXol{wn1Jcua@CUpA0{r29=}0JXeP~D8QC+qYY~GT6=-12vhWV^9Ghy=NxZ|Pw zb4tn~d+&#%Vaw>!rAzXn+vU1`N_%$pu%k0##N#pI{(Is*bn8UyQWwG8Z1v)3*l=|n z4cL-IG&Cf-tPya?%yc`l9;ik1T{dO@%H_fZ*qrJ{qYYt7BL2`BJR}F!FC@8?Lv0j=Wcn z*g`qMl!KHrMG7lBQ}$9Rvd-;%jpS*?=(M}5Or7yg-0-JA#c!b%7G(VFmsg`dcF*>( zkaebCa8<8v$9)W&WI-Rl~=V-wY%+zs=u^d<^ShjeL2p*@WPnDK*u@z9vFum zei+lhw#as=W3V`P1d=n+oqv)BsrP^>Yrh+L^zwDl7S<jGdNAS6AWd@Fhzu-I?fus7AGtbH`zI$x6 zQQ9==Xh8o|k=f>-c;}jj)sdEY!(aY4!DepG^acm4X44^d+Q)78+|9J-u5l0pKD{>T zS<@dY*r|t|XsD~x5prz>cu#)$oIXN!;H3xc%|1=;yhU1hNSXBh{P{VcH}1t3tzqR+K2QvcbOXj3}Av_D8dgldP>AJ0DjT-?oI z&~piBsqotS!nt z4GOx-$&f-r=H{8gMM0RIb{N3zqMXMh<1I!=yg6-Z+;Zj<%^J+~Q^eLd1xMCq|Eq3orUfMl^K5iD8&&DlBMh zqt!!c2SB*1CXl!xYa5X`H=Tmqg_m5kDIE=rNZonQov}&Z9pigLhUBPPF?cWtg;o4= zh~LDsH~c2s+DSdUrw%4@zvreXH`lH(^!4UTejd*;Mti}KljFESheelM*iOR)g$P~6 zwF1zObuh>e=A#f%uq&Lhei)GcHms`|Q!{4MX}s~4o8uRMxsB8jw_fqfIDm+T)!Veq zZPHYnLS$a$tp6?GJ_G1FXM?|eo{NFO3*(tqa@l2<#dEV}#-Po%h;z@sfJm6_^Fw)F zx>|%0*A_%pGGqs6ijP+e(duxw%u)g*H{d zFTBK!WP`hK5~v&<^#tFXl2pfoYd0*Qb25F=f_Rt3ii~h*xYiocdMy@nLs);#ngNYg zur*#IrcN|KIg!^tK3^OY-kTNAfB0n@d?k<-qvZ!bB;`VxLshM7sqNv;~W>I$<|K5Aguavd>FdBbxf8gzUrYo7V* z__*NgvtlZ+52bT)G@?P_#M}zWTStA~Vpo)mGv!^lU=*I2C?vKYG zejrXfW=Qn!&z$wGdNW$rE=Q+V!ZS_Dw+UxD8YstTI`c^xL$0<*9o25DXr<&)M{hsG ziDSp*hTCr=tg}ZPu*Y{9k=iup*xKndx=_Q*QSv`x8S>?f#eT!kOuOCxK}^fjy)>9=yT~RzRkaN`}R1CKaEjO zj*goyx++Gl_#n<1d`z5lrVYtZ1H6+LP%KsCtjt4&NfT3 zla=(aZs5jtDlb{4^YItc2^fVO8+_h5q>i}k*b{Puw=07LE8rKWi&nHsW1Rf$)QWFu zZoSm0;?TA#e+f&r73$!A@(xcsIYdwV-!4wA?brw>ZY%J*l(zQXdvh|{^}Pl2iD>vd=8@L&Tra1~T5anb4KKs@FF*4_T=|nrVrTHu zE*)M~L<9Ljx0IKBSB~Vq0ssIdUs|2_b}6qYuVbZ%}mCfAHOv5k;cdbFgye?UaT!#K}>a^)5A0iRxS z`WYEv+Hrjx4anzo9D%dSmP=lTZ@hX`I3-EZC*qEF+*JDqo|-cC?YRC=H^zStyD!!v z{nc0eD)qLkqalghFm z{ddP^Ix%)&;73`r1jnQBr`{JY9P)p4$lH0y3)YEmY-=9M{(m5Y9~(O+&bsQ#*ms=` z<6bm^Sa8njDAgLa4T0uavX5*;AVn}4=h=$_6t#GA55-C?B4^x3oH?nfVq zhwr}^o94t^hsVCt8tprz?n@^i@SDF-m$UFJnI}zTfUFbz<62UU!ON%U52rW0!l3c( zw2@BhZ9qf=YtYs7hw{+!?HA}=w=Za4%ERf&+4hsSfFEATl2ddS9-c?P>}}S6cxL?g zxb^Tq}3L>u}C3%^*z z)QRWgo;&V{`(OTRoXB9!8AKy)(zSbub_Sr5m--FZ1(3R{x0f;ir*r7Od+&?&SRns| z6ONCzojR$=NW=jQ%D1dzdGf9NOPkJW|3`qANH&ffv4`;zIS_dYAu&%sIfngIXXl7= zZ@hy&x_8fzH3?vdrXfSnEk~fA#q)IL#TO?`C+xpp3^|ec{F`l>4aJe>;^C*`Ye< zBTnh~04*iA8fpsnX2TcGY={aHgn$jv)yO}=6RxA-9*p$K&paK69C1wS)R#H7hAuHm zD#JTR%8p~j&?sc6DpbMfn+}MeZ(b~*~Z-XKh zKJ!#jxCgkn6c4T=kRx`|k#aT6oP(7HJ?~e?QK2GyV=|%PPd^JyJ~}qX zSh4Pv0jf|ftq|CRPvANHomc);%E(9VW9)o)=SYnlJt}_v%PSdyjW`QK@yPuTOheJm zyl^{`DgG5IDo=Sx-ZP3Jg*pve}=CbWaZJtpV^N;b>R=;;Q)Dyty&3TaP&Bhd+wGjOvJU zjUngu8EvBg*V)jF=g$3VU`Us3AaldO1JACJ&;sMO5%4c1@A)XUQO`XS=ltrjO!cE9 zk7i!^py<)F8!JvPjfIOpiIo`IpJJ3v8vkm{|Kpv}gKa`PZ@}K{bXMBJdv@lLnB)&% z65+t3Bu>_i2Bvb>``ePyaqDky&{{E*6W5UeoG4`XSx!qB<9qPHKp22*~{?VCm@3!EtnY5&y z5HUN|2@~*nmF}uEDPkLPZH3}!U@=JMWlu%~?9~EiyX21e3IYOo^n>uxByzu<J~)fzK}r4eTX zXe__2Sc&pc(}7!!T#fNG#QhDtDW7$Uog*g##`}*VL*>7Yl!;`RksZLRaqd(!Bk$}a*+Db(_5Kl$#rUV_030@$sT2KjK}e%)bX2bZ{zl-T z5sWQQ+A%i|@t<;q!h}}57iYiia0M&Df1c4%6Q;ZwHxpL79#fC@#!>CsM;%$TN|j^)$LRPxUylWF(|MQ=QuD;U_JtB@f^ze)p z6c6fRI~Ya`Hk5wUqgwMpeIZ^nq%FgampYuEITbK+;X$o#WfdP82jMl z(I#*zkM%b6IJuDD$@kPlN0Kr}ew2nf?u`J;1*j=c+>5WjVH5oBzpsraCcYNi6M%og z?|u`z^w}{x`gXiL)!E{|a`=d|w3DEN9T&@>=sb1QI1NE3jXP$H#c}t&pI;h1d4J>y zC&d9o@$~H8Bd4-zm)HR^KTmToazY%qFTHX!X-)pAd!dCTNmEB)=e|ELhJ*X7|MKTJ zx^KVezia>4ih-#0)>${}Y<}wNZ0*#Q3TGL144lf8&IWKKygC_eZLUq>ln>WvaAENW zX-|eN@5{7|%{SXTI(6!VP18F0+bI-wM&5-+qenjxPdxYly64lF^yz1~16ZA&{UtZV zzFL2^=CMW#@;0JDhwr~Q8cOq1G*yTAR97g2bxZIiZ3lX)BO5c#3qdxQQQ$Ww&5QXi z5kMOC+;`eFi+~M;ca)9QLb;xrmj9h1&t(%bH;qtdmd zs8XKqeD1)6Hi3uVzE1?tli>bhaI?A+j&N}F4MziTRya@m z*I-wNz(5M8oO<^@PQeLpPLBH?eux2(HDb?Q2gGJL8aCXJUCde%DGW@Bdl2yjQ4BgE zmCr_{+0W3{cAA!sF7cdpqw<+DTnzH9x86c`zZf?Ue<;pB`Lv9P+km#$4(C|PaPX3P zNZ!bQiB=Jvr1P|$hFpRyaRKO&tgF#=tIcBY;K8w4$BytXHm%sSQgzo_eZPg5|EQzEMyyh? zL8j6HNh=U6lP67%F{~0hkr9uN7A%OaUAq!0)G;F%(pUod8a0My>lJg+r~5GGJZz#D zF*?;;O}pU*UGH&ID&?_ z?T$OP9yc%=<=BsSp$(IvP@tSw7EXHtYS-#~;N6R%9LV=7jWqpK#zI(TRnP z+9O~MSrYd$vIeaAXBh%gE62K&GV2?p#=pnki8gtA;u~@6bI;`cfm>`HJM7dq6_bj^ z?~=YWKo@7?-Y>GT%+2~MF+wd?U_!WHZ7jL^$sEqil^=@=D=>;bE7n* z%-j6G!z7X68WX^TPg6$)5oAY6%a zuK;V_9(mYg$=xrVL;@Hf){{|gnkHZdPd)Wq71&q;F-@Bn@yg4DSB?$J~}fh)E?erK!<1{O(fftqh3XDN`tQuhVDSI%+Yot z5n42M{wSSEahhh6bI@2w4VdOo#>9{2#8d{v8@Ht`5+}O61xg-WFGsXMpRLwp-B`Jp zMO9e|`yG0}qY~n8{^{Liqu7(tz;#iajsP_#Zy2+Nd+;u5DP0PP`-&#gx5$DbBR=`~ zlX!Rbta#@B`{NDLZNd57!AE5%wOht2!?G=Dgwtjz3=|!%S8GhgK8Y zg8TJ1W1f0zu(_1_u?(U!?&ghEN5qvN1v-8O{ZG|-QD35nKPPk-R zzq7MyXMV7m*OSsXO?|B%0Wa3gkvjEX){Wot zdvhEOPSLvmzpsnJF%biMY#e(Yd|<4O0iJr2`U;OSHSsR2HJKxRq+c$k2wcjXY*X-* z{O;k-3cvdEE&1C&=L|YBw%Tf|bVTHIQ1pi#d-J!>$|yUXwgc@A58oy4aFGs{sk}?a z9S)ucUwS^%?GkNbpP?s3r_P;mVBiF&L*cj9Klu;brlAgAs?J=}gE|#DSp!Y+}ah`%%jK?r+=8AxTlW5VFad52YGTb z3oPF?eoVr?U$52*ny@yX`P0$tZs2^7jL(X>Ev{-xol#aG}=?=nvMh8MuCB78D!*# z*!a(4?>|PAp2rUBtjEIWM=)r$W;%FNHu7A(CD`&$p0#IO@?E97<#`yaE`rTnzXB#Haa(TkDjORmd?9JNfRa_auuTkC`(wpY7kR zXKcUw0JfF>PNrAZ7C6-*$QJTc8fQM>AoBrMbp{W!E;<^NIrb6MA6GNA!9$y7mqCX{ zH|*@ykTuFC+fy}=D&)dmT@y)Gi3-@J)FJY&U0xR|b|7^MeYppjqUCWkcrW^6t(;os z_sTKr@49Wu2KlKuJe$)ckXQ1Sx=0>W5~qy~&*84@+xJM1>}E$O++U=;@g9#na*1stICGiGiSw1BSyuj`R`?#V+ZUWy?ggA1D)h= zedWt4D&IunT&JGb;%J~a2H$kDyH1pYOwEXlT7-k=wU=LwKjYA>j-N0f))AV1g|ny; z3L>MCX-COx;6R78_McPk-Sz0HTW*X!&;MZ@Mmw>;=*~heY+DZNRq9sd|82YeM;r|j z)+3c61W4j295|LCh-S^0$!N!fn8Nl{)2B~M&!~tm2AK-2C@K}3Y_bF*I48?PPk(Nq zNMo{bsQ^u5$K3fhGJ$jLRV*q|J-rGIQ`w33ncrl?gfVQyOIXiA$AAsP^eRLZdI~o4 z=PabH2@&#ADCWVnm~Z7T0HhGqv0=G3_zbjVQAp~E)_5*tj;-3121?=038?tJBq7fme zD?8;Wtf-54wG>B<^fsnp&I931<4%4fT?LXI0i!jH;Ao4YwR7iUG19jje8-QH-kkYe z!+#C<0;n%|?x>plVU&nULQ^?AP0&Jq%tds_U)p%u;T7kpHf{?G$;!g|8Mt_jiHewfXPH zJ2)9uTd#Ap==hyzy55?xg1Ks6>O{f%YSR$DqF20R>GJr5@cw^%&Rk@8kczJB*3BA4ht|!AWM~>~_}#n_(BjN#fKw-V4P2-g3kUE!84g1}bEM|pdt_Z`C(y#s z-Q|?&`VgOk-}#>`iVxYZdO5Um&anH6H)kGh`?jlRy+6mW(6K8Pn=(1NrR{^?jzpNd zPCgPAJl4vwyu>T-YZ%Y_>bW5KTVrP#&S8xXb$~kyv|%2o9XUHT*~ubrv-NLwM!~)J zNmKAAJ1BEA43k1_+u4Dlo?l=Tn@^755^3T)zf(SFblC3fVB}FlmA}ou09^a+eeKBl zkdI|LD)Uw9nBp|Z5fR&Kt&^Fu&)i5`_(h zVKS1TK0@JZF9awfUx35B z@;Tq8y$1Y#BadbKfTr3^o|a*HY2zrkyymxVNvtjrUp}jFTqkS!#@~LQIv2P+vJO1Y z{K+Tt=X>R^Ws46NjCI`!@ogKnbELzG)Rd*21N^o6TSV$&e__--%x1e*ZJuK?PZ`zU~fkU2__dING;=`*v=%K6?SMsegLjIEeb#x+K>P}$G zP9~qpN8(z3R}Rbnwj=SEd62(+k+>zYHKRi*Lw>jYStc)&2aO~Yua;LJBL4z<-jjR6 zS#(!*$0HsanYkDoIE}dU8_LMD{3H&XuBb!AI=LPIg``Xoc0kX1WRBhdkhZ_@3Ag+# z-fSo0+pD~w95Z!BJ~b(F(0nb=e;yTnvJmdYOX4%%Qg6!lP!3BA?PmGYZ64Dul|B?A zO;Vmzw4z?N8`oelLbR+UX8X27Tx6RN1>&)3Z5g22pL80&B>fq=vR{t*uz*3j>~YF}8EH-1+Z zkcDT!tujm=N(T&Z%J<4&`P3D&QSq5~{$>3Br`C3~O7y-d_Ta0Epufj8N~|8k{O+csX;F}4L5X=LcfnAXS9IpNVjDX`UGtXfzMj%E6%ZvTgq;^E9KN%BjYJK4^D(UknqF;TRLOscx6aW2)rh)iM;M+)sSSSt zA=saTf1@S*CfQKHc$X(X>*`bkxT1x$@{y)p`bD|7W0*>n?=uVVrVvbniF9^iigHDu z@Gk`+xU_5qwBA?w#(aI3v>+pCA+N}j8kMeQoe>@IS!2p|Rr#V$3Qzcbh2iWQ=RJQa zns}{MOq_WpEZ|E;BFwfY`9$MOT38_!oaG9jdjo5X*;&)WZaNKcK2G6hl#RdTo3H7- zss!jOqS&D&hShSO>1b%$iuSP*#RQE$nmH>bzcMiv-90L{S-VAaVHBb@ZAeE$E9nl8 zHZ~Ig_?qbxmC>T!TEgxWwtpvdxW+^0(mM8M)4=&$Uz=4O&Sb*=je=vww;;9bgs*YMRC0OJQV|VE6yHso_=SeGd{yX*(V`J7jj5}VC)U@aax|=HfKtS8S%Urd8IGK< zxo^Q*5i7y>Viw>00^U~9%Y%j->Nt^imJ*G!h_!K6z&9D)MEkeHUBh}&y3(OmUWM&% zTmdI(z*RYt?UlUqkUsEl)gFAO{FLH;WqpOCDCy#$u>2Mnn8Ks8){$XHQtcerHXPNg z97S#o>_S_H@f)q89B>qltW(Yx7z!vgh|0}B{gszAlpLkDGhkS`Vd;L8kdmLcQ(mOu z$n)%=QDU;0%p7xY?}%H`t0hcUc%9lHR$9~?4QWJCU)#SO zP|H;|D|dXhsys{C$hR7K8i2}Xr)A}6B(Nz{#knxrKJqvB;vL}9Skz!_&IpcEv%aKr zrv9{zSs&YqI!sw+UgE{}#7(~UdA2*!7dp#5&=C6hy>iv?{=^Y5S`X>3PPMJsMwG#( z*8o;t>)@-}v1z1%Y0S?uJS^8d#jnrQo61w|1@o6@>L%re_3=A(gyqqtb~(5am&$e9 zz0Yko(m>d3N7CD?_vVvuiI~J+bL!0{F9TI;wCIL0e%|2Louf8EG%i zn49u9aReQuwfIRHL_Wf28&pn;mx3GdUFxiCkjG4;e5j{yJ$zQgc51uH?}d|mvs0T; zm-kjwxRm9lH(wV^lrO(PeyKx*-#lEm$NFh6>-^HLH@!BuGK8#Ze2EPT5BkhDAg|hv zZRg4vx0LstGQc+LAuY=facdv9*g;tbpYUG3@GAHfPC#Db$x(ct*_O>)K3Gco$UYd) z&C|cysP=p0DHkv=d{73{Y~S)%Yk1Do>L=TzG*j={|43U1+KHEi^cmGdItZ1$$+wAH zL9Ep$D@Ex7kbesN)%&ayZ^UEDN6NR(;zm4|bsua$>bz1nvvNwCyruk9)>@qQzjEGa z26<=&K&7k%9~Io<&nb4PTWk7SI_hLlmYa`wly3ked0O69f3Mb|eXPwE;zk`AA?!a= z>8X8VzuTMx})2Wiq4hWdzfE$jmlE8>0@4HJG2;lr{l>f;f&LMMDN#@nd*WShCV6KE4L1p7JSL>~E*U^x$ zlfO791^~t>jX{B+7h6aa+%}XPN#co2og-YN(}AJK-;PBwYAr$FxR$E$`(F>`NCIDb zrC{^Wz_Qb&fUryrq3qC+XHM%NQ_I(@so<{G4N#cah^?2fr$I#;g^~DnJ0FFH#zec- z+cAp9oGJe4fY4A)rxK0dBZZ;hkWW>Gq(uSIn$6ci=&$FGM zTs#!`bL$+^I|8i`%~1*H3gCc>S)-$&wFU)gKKL;HK9#90PdyitesyE?VY%(Dg!eXM z0ms&)Z3}!YX-lrU?(~Vzmtt)4yj8Q7$>)~g=$7pSE~z`|9$qkv?hU7Ihj!ddwTsK2+9A9A(F#%>CZsnZ@a7Z~-bh zZopvr;%I=5bm-}haK(u7#0qCpig(+u^3bZ=CWXiLYrC|g zs^Qa`Xd`!*@f(eWPjNJ)vy(7P_tiGN^!BKM{V%`sLG`{=BjLA=X%KleWKzT0YMPIy z^3#!ajam=ogfMtbS(rHPS9!Y@Cozl2vDN<1Tfl#k8ead#Dx z|E+&IP@tDGvN#)xv!gQP93`?$`P(wGJyB2V>S4!D_-xl2*J-%b;1IFWRhk=qoAhR6 zNV%}+i-qYtG7s~t3|`w(>LdAy=ay}qJj9jq+|H`H&boQ8p=(;xRnB&w+wmy0DvJl( z796b-KYWmNDEQaVU&Ya28|9E~N**qTNe8xpj!N|wBd>HEl@lJ)!tyjo)2Jr@#4A_v zkvs$r)Td%Cos-xxmMwlvYhA>@@cK-?)Fx8DRvjko55G07I$oSuB??;?EIRic&tXm)3%WRYWaIFJ`#5|T3C+j2Iy#T{Vi=H z;WHm`YTm7IZn+rTSMZ0r(0a%-!kzde%hJ)(fmk{L!l1(^9m&*LTF74+aZ~4La5-UV zTbw-UXpm0GNODPs%}V7vu(SjZ6iRAx0(NC#p|Cku2f3MH`SZwJ1~QydMY^IFM;lv~o64E#>MvpVvJza5daZA!Nsh#`OZP~PET z(k#D8-cW-Ah&k}zUmkfiQ`6*qdE+Bxt)s`{L*7%Cq`eO=wSA2AG<7=8sCUXQWQfnR zT>?Wo8fcf|NW91|=Iw`-6IL5a{xompaJC!TgfQjwRFRussgL+B@oLGQCM&jD!d!dr zbL(EwO1x+bH)M+G5~i&#VmAl#l0L#{9+kt*TupCZDIJ8hyp+AtS7)?1mk!obePRE= zojDx*vprSq*}Me5>LZAw%7O1YUuJvdn)kdnZvacXLky=ZgJ*S&8bqGl>;jq8rGpF5{x3se^>J{smjt1)LZ((=GHFZ)eo(WU(v!E8r33c7Cgf*X7 zm0Aj~oFZ5mq>QnR%L5KPXz%GX^IL82%DFDzYcJSeXoVdiKbT|Une_Jcl2Qo*#ZIq34FpQ_L9#ZZ&P9RQ$l>Pl5rkciLbhS) z9rHWAqowiI%7fS`NRu5cwmh#o94QcM!bRcNidEkw=91+_X=X<{VUVchsK4^8WLMtR z>S(Hb43jDd9XVFW%ETGkO==sEP6ivWiqb~rN7hA!=^>M6gRj-WJX0w7PK82wtKM6G zM~e~hX`ob$E4&3};HiM;*{Vkc`l|1%u6F!8dmvLASCD@p{l|+aBrfj68;oU655IPx8De_f+7tl zo+xn3v!WCgkfu~ISH_CZGBlL>>YPfY%~fS2obrqYixn%LdHL23P)!gdBjlejoVTaZ-9&i!USqL18iXC*Q2B^s ziZDdb=mqm=0xcR^KfWh3K!CRP=k3TMa2L*cH=YudeW$esCS?)T~a48<>ufL2| z;GzXMaIsaWOdr+JH5@JQLUu-gP@GZ%|E!z*P@XISRf{<1QpUuYbE4^i-;J$y*d}`P z+devM*()6lKuW%R>Eu;9y<)Wp4SB^*y^cCY8=D~T!MldJtvpc%gCq|Z;wP;Ip~8D{ zG{|uU?eap>5!%XscFvmN*wFc!3l7V^nyR;$kWm%;0qQ*is4h{N&37xGWP;n^(e2aR?P>QMA*q+NOgEvrY|zBa9aaz+>$qIO*yt@ zk2+aLJy$KxJHV#;cI@CId4@v=Ue-77#2e(#cEy!v8Z6dZBU8ReSqDzcuZo87Bg?IH zp?LM5{GKvg*u=Z(Y*4}h%*ogM_L=Qm+6ha3pZCRB7qp}g?=3530(@T?{l2r~n$A+v zmvaWoqtdz$2-Za*Y=ZR0! zD&tMBjQ5%43#XlR%g=PY&(0E84eIQ8@!Rj@Q;$MB=~r-Qrz`QnYxSP`&-^r2#f`NV zH^Of^4RP_GbtlhE1Kg>nc%Qi7d430fhzt2oquKAIy>JOh))iTk9VE&XXW1!0Hkf~f z3-O}f$Zu=75Fh!RbOnBJn6^uCwupQAO}d#*e2CA21u?;qH??Q{u6U?81i(j)Ce~40 zn}=nkZsqfIe33@Dh1Gibk0i(KmX?ell1gF3Uqm*xnT0mhd zppYZ9H}j_L`l-pC&W6tf{@|=-v=S$_tvg|p26gx;d?K%Sh#TvwJtlsu)6DDW$NR)R ze5ngzDN%`Or->`l*&a+Qt#p8;UQf`0m2%Br+L+chBLDc?Jba#f%e^QmWlFEoM#PRs zUd_TAEA5}^o;x`y#i;o}fUn?n9iGz2t;&7Bs{BoUvCjOfc-1mJ%~zP}+A|Nz;{ucU zSNPNhY=pB({AD{#SjZwjAS3UAsXFrke@a=tD^GmyQNfUHoM*xgv9T?Q3dWHkT;i|D zq~avDeNv6Ox@6}x>07fwfhFlperb1euPl?-l{MmEF$-{uAMNg{lWV0DZr+<`4b;Ss z@9OaH3*L+Ww6l3!k+519>Y6yK^|`puh$U=;$}v-Nkd_74=4Tlx@42c| ztw;7bxv%iSFQr5Br7b}|F%t(~Z7oI$>gaMX()-eWYU%h)npjtzXD+U+oJz+-RutOs zuYAY5q^5;^dyoIMqao=}{k?vJ?1j#762#7TNy(DP2Y#S{RoTc$2rF7e3SJw1-b;Om z3l+0tqsLFrW_?Muj1+n`!DrJcX%xB^;!)B$8k@ow<};nYO`)M8X-(x(UCZ77gsOFq1E=Ns7XZrH0{8z7dei;$ z`%;z-PY<3ANa0`uYv|}_9)9N=X=(a@&cj3{pXH9|LdP^rRHU_|G)xs#@gx`JrQucb zuF{$RzstRPUr*EWM2HH9m3zMxKe=!rSzC^nDhF?}L&g)HS1@aAq(Y(I@>unJ8T=w% za&!b9wegpu!ooLU|Mz&QeZr-}V*Qi)x|VlRS0RT8gP#>}D!d9FoeT;<`PM~b0jIvQ#~SV9fmRc-4Y&T9@J#%}>t&w0&ep<<8cs!``<-V!%}Y+@Z+Tv1=l>M;0^h&>Ew%Ca zH%q9>C`K=-)L$GLdcy7DbV8qI2Q2AQZJMxgxbh)l^t*-~VUhNb0|`b!6%tH1L(scSm6 zdauK?uCu#}Oe^>*sj9zq0P@3pHT=xa_o=5SN7%)m9U)D!auhrYzecU_%NuD3n=Wzf zm!_+5ZocXzJ65z1(iNPPbXBVI4E(4+NSFp}=2uFthrRlO&LV577>@2?=UG^?g9cot z%1AaG21xl#Q~fboD-Bl?CGF*#8lT7)mQ@+{rQE{rLhOA-3%@On>hdOEXIkK!Cq?)ja^3LGGXzI-cvfk`KO(dng)mAvc!mQu>Szr~2BEwKy+$-Bjp zNS;x4gY$~+&$GGYrf6yJN)L+jl)Q~TtfQ{>{)bZ&K0H)~R+KFNF5uGF#0an-zdW}B(C zxg$+iAX_2i%7tFJ=^hjpkwB0 zsnEOzqis1Mu9JfWYxQ`k@>}IO-=uR$zD%34P|p;WQ^|K_Qd6dMRuI&FtaATN82|Y_ z+)swcq|{MF1QDI9(^?s#leXxB>Z=MqKY>?lH;HFqt3d|-<@ln9bkrAIi$(S9V(esf zW=7P}Vuh}pe(%8@dFNK_d|Rf_mS^T`AH#gy?$R%s;E1eRUZIzHe0z`owWGnRXTM0I zCgUWXY}XL8AluOuR~Xh4>Hgk%6#C`INnFsI#PuUSP9dp+O@c#Ip2>thPY+!xqQVq~ zh!_iLz?IR8G{PmU`PLeO-&Y;oqD<1r#wh2cYCMD zxzycjIV>aR^pakWaL(}aVH(POM+9W)R7iZ`4ivZu;&aNKv+(oy+l*<^>VSQsZ{I$# z5z{8t+@wdaym;n81-X(bpyZAqCfViXLYPKgtAvY>Naf@I(;=Qb3U}0} z@_DZRf&y}6(YcVOv5qCXDpRiDNZFw*vBOvv_A2~m?y8=8$3W=_m9Kf539O%~xb;32 zU};a><>6yta-lID4Vnh&KuDucdU0>2+17lkv%&|7rCRys;<@T!8c)9wN|l-l(%keJt(#|#ETmk7_mxj7c{>{}o>h)jODurdfs>aqzg1;I?Ti1HOM)Vt{HqMFs!og07_Yy;4)|tbdol<~^{1uTswfL)H=a0g02cYn63v2-}G=OMP!{=59KV zlyRB3JXcN^{Zb-(s`Mpw`J1v(x+7eY_GFeFAlre5d6(=cr|{J`%c)OP48<}P#I(+p zE_$uTkHA)NQ{+H33RgxODKB+41^zStR0y!B+96#knUTOWazY()z3n zCwyA!MM@Lbg2UQTc|eAe4I0<`bS$7palk}wzfTmz!+QpzZ|Ro%T4u2OcvRe@04N)2VBPN*XH>m6&tn_t(irB1b) z<(ukHNmr#uC-XpOQ$}Oe5|xsxFVq3$^jm8tMm@_;GyL$#3IQ$G#8W{WFA7bnc98s0 z!()Dz?+fy6?>fbkcF;82RKB--O0VTzQkTD(hh@WW!dK@!wcT-Vd0va1Egp;GZk4b7 zihrj1e>;R%+*#j@>V+;2=H;lj5kA5$&jVlbhix?FC$D(s2(z}Ge4{?mR<$!;7m<y(L1m^88- zKs)kwO%3f5DWYwyJoUHjMcfolu3)LLm34v*Z6`?>*oytE%(=&GexR zFvHNnp%(#BK?K1-RBW*z8b!qjwpbFQiAgLmi476|AG=9RVv7ihN>QpP@KcH?O;A8k zq{<8oLm8%*|N5?T)_M2c@45Fa^R^kDJ#+5fd+pWsbMAZZ+3W5CU*lzkrBSNSM|-=P zEo@=~tSW4)Syp@p5q$6;8F?R@zwnW&AF$0w-+(5qQ3=-a4 zd{`SotefKljbF*9Osn5)&I8W%ABNwwYQ_Q|0M)}s^?~3>+f88F6u|<19pH=KKTPdL z`aq0(Y9AWtK z1+0Q7#@o$D?D!3#UrVghc~}r#={bLSAJW6&9CYgFZ&~+KYU1J zKDs^Xc2C*diF?KdR;*92QvAAMACk?(0xcPKWq-=LE8+vt{+U?y!N3<7f7{gq9%b(b zeGB=#|KI{0M(A}LAK?6w%alxXeP>itQMWD9dk~ZsAs`A;Lk-fK0!mdxdY2|WbV5f! zrS}r52q?XG2#5;OdzC7^1_&hyftT;Saev(R?)!N%GRE0utvTmed#|-FP~@>HB$tbb z{vr1jIZ3vpF@uuuEek&6YWQyN{g9SVWD;DVa`nLOelp{=_D0Tsy}^GW73k=Y)mP=` zVB33KIt5{3K{&Zz*w2bY`!_BuAA%N3iZB1dN8~QAy%rRLgxM@9eU?1Ii?)mDcjiID zeI|8o-IQ=#cb|2mWVj%W_4`VikMqT|ImlwxgNl(1DlG3%&im4DHRA8+M86n=wnMJoD+L*5s7YM|tnp<*c|hs3f|*Ql5x2oTdxA&3XLl8hNuA zGrt)W$x(0h1w4kXib%le?||WBYlM21M#d`Z$87STZ(q_837GnDnaRLBL!fUXz^ zk7EVq4A)z`5f%sSnJf}VjE6~kus@eHIA8VQc!Y(fy@cPl<+G2-uCPy|vNmN6Nc8)V zcGSv=IQz)*@V&g>E1yn;>#2hdtWsCXw_pPYSFm3_B=o3Yi9W_6}kn8=Lo7-d; zQJL(nx~@mWWS6g>8{CAyjF?F*PF(YxCZgG?hmKi2SD8`)O3gm%9ZaYziJJ7bkS#sR z5Q$>MK7dm1njnk*mfhf9xJvt%Y#o2Lx5~dypKme~D@h!PW`(i|nT`Xojb_UxkK{92 zN~x!kE=L`Ttg1xg>!fXearm20@UOk>IO%b3xa6uQWd2Dn>;)Q5*b5rjmR$ixiOMGr z@!W9BURkZ&7ogav|2!&mb5myj={=HVg-6!DeXV=(zPG;z;_&eS2~b`M65^hZkZ?bj z+bBqiEet5B@(^d62562SX^ybsP`haE?ZH%ZMZM@sxxV{US5c+T^qFISxC)JHu0AEU zU#qhy^h{MazdId4R(8X(f6TPc027<5m%oJZX{-pI1odr;9IIIH?XIk$`cU}Zz3Fuj zccu8p_x0C1HGB`wST!E!Nf^uyMeffm9IHmJ9Sxw{YaWiGS2tlP!tx$QM|TdVJ;`Hl zaKGy_#?c4seFQi0^Kh$|a%bU}ogo&+D`UfFko?N7jnrevk;Fyk-9GgxK{U32Rn2B$ zrF{nW+C9KlF34zGQH2J+0)ou15BH+lz8@I67Pzkjsz%%y0eYU^i=f$v?fOmnm|FRh zG#YrfrZY}5TVxJcfqpG~H{@!AX!gn)xeZwD+L~i2!={I{u(tZANVt8;W(-7*B{faO zEh9-)HmetZXs7Hoe?s(>1MY_C^{fXq$lfHHR{bVJJCLQWigaA{5)j>fiOhq?KwX-O zXmXPVE=pV}Srx`y>oXo6MOVxUd=~`=HPwVezI>(9kSoO5Tcw%;W;efJ2qxJOXFH^ACIctmPfbEtnd+mLJA?eM`sHjoKpNB&;(Fza=jh z*=e?OeU&h`@>kW4ZZ>fH*|(5|Tt^^Pr75xiAd7}=t?!45^~~$g0h`t8T+NQo13C2m+a8o zCIA}vyWz3)&YZ~+TU|!Sq>Jd1!!nq`6*b+~5&ydUpJ&#!*yO@~bp1frbYXA&@y@DJ zq%RF;Q{R$Ck9szvM7B>=AJ^{RHt6Y_^E4BGcZ~Ga&!YIBSrd>3>AKgP6 zTUlJKkQxW>D!rC(=xCNkeJRjxl(}P+CLj4-m<5-aBMIzk}x{%eWB(OOTJu%RaDv#SLgw+W$5S2_MDU<%7?CwT@nVG!ReydH+Yxcm{UG z=ur3Ua_Z@v1_{Z5OQc0i6!7&}g#7<_3J5{(=LFepZvIV8`t0oEh0*_6wX=VC5H5n1r&#u-`aTTc>ZQ zYslhS3HoTXqNDjbh@B=&p=#9p%l88nvL)6fHZJ8pH}VrXx;A8V%+wXzXFg~je|~+< zKbtdOd*Yf=?3?m~#JHE$O{*RjmEruzzD_b%V8?&e0vN_^Gcn!%l`PpZpUS5a0_2X4 z8o#h~OC2yM`sbO)xh3h_1IFb(*iksa#9L-1#% zj;wOMo{q9EI7@v;IqQ<9*o6YtcvHi6z4UBhO4D-TBQYy}Ju()-@z2yheI2gxj4nLO zdlb<3Ycb2-z_EkxsqRNVw}lUb6N0?oTl3=Uq+ zP87Xm5|P{Jda9r+O?pKb@aFkb97d$;BTN&wT%`yjZojAX`LYTYG;O@c`&(! zu$w9qQ*n~U;Ty5hU8{^y22w6$OqMl5H2QrK5VM3d+l#SLqg}Ta6ZHT;!W0!_XH<+p+H~dEcZsw!tfHbnYFz2G?U+NL< zA|w{t`!%`1!7E_im(D^HPPc(wmrZ0u6GUnuVmU_A%~PgPS6;q<*BnwfrX@EJ_G#9M z%rwL-s`rCXW9E||J86`5VZStK+ zTda_> z&a7W!evMYECk%x=V)H}xIF@M+ct~q9&$|f8y~h>} zfX5(pwK>+3$)N6@RpugFKETZBXKt%Js(Me77 zGu3|+YHMb-Eltu~;;tKOSD8*4h#y>L27?q8l|C7qJko$vur%Z^; zird-_&rxMD>N;>~Vw)uIbT%@fJacj3Qlgqwo^_Z9R^^&jF`Ob>!o{uv&?{P9I+Js$ zKV~P4!7Cceg;N@^-depqhkAtvoh|{S8oi}Sbu0l7!QR`r1n5TRHBC^Dikw4|+G0R@ zwP!)tO*p54<(gQ|VPs?IkZP?*ED7tJAcB%l_&i@)jUD=x?)#y9!#H%g1#lv_`k53< zKazgE6q_DsD>o}?%2qt$dS2TwJsj;_xP7x75EWq}X;$d_R9eM{V+l#479!cHGHxrK z`NA>f`WjS)RGhqosYxWUOH%|idi^N>?TmeAm}%Y0=H|%nH2DL4HrZ-_E4<{j{A>4W zwhQ87tHC{TJr0;O^Ib_=4*WskIJ)GcrE$3P8_P7LBl-7gAEmbFX0>?OtTic_m&XV; zNoH?ubd7OInaJHfOsAFK;lRQzQbrVRf1vu{w~2Y^Ar+UX$sw<8xy#}-i24$=yp_?x zFF<;=yR6^PD|Uxa58>}|;AS~yww}o{{^Qs* z&!v%34RTd>O0s+z`N)dIfkrcaMmv_bD%k+Z*M^?kp4nw`@W>&&t9!)z6z z_v|Ha3NZ?AZd`q4BiZGt@29K+&^?&Mv*`GqfgiKnDfS0p=} zR6B;>xcWTVd~MJodylQhWG`I)HD>0y&Xr_lj(ludWzUtEVIJfliOtml8q_;2Vz{yf zbb>{k2ww7TgLkFm{iQPg>=p+iN#sros-w|((hgLuzr&>A^EA22_)?Rj@bi(V>PI80 zgH6Snu*Zy(PZ52u<6$OCS$i2dl1EA#QY(r9FPF{FT`?*p!=(=VXXb5Cx#9=sO&8{v z1+UoqmBX`Zb4N1>(-3nZ^dQDEsNefx%B+h0M)62avvZ8J?9xU=bVnSSkuvq#ec5T- z>P8RkB66TS`EY(ptV`T;_VhV+8vX-;ZP;;_3~uMZbK>#sc^s+@5$u_56BbpExQ!6E zIbz&(yFFTRObEKDr3pzd#U9=2wH;+UO?o3Rk%v5gjF61F4aGX}k-S_8TukP$_Hxpor_|f#eNl9>tCVQ#odKW5@9&Ge^%i6D;Dh+!Faq9XdTBXW3?SM) znl|4X2#H1Tmk~-Llv6E=-jF= zOm*NOm%~m}<1RD5F}%9BcBwq1IL^Fd?mwgE3u61$xseb6hWF@gEjcTJV!K>Vt$1dW zGVnLqIqM6zxELI2)QQ@yu%hHDiMiWBy~^;B?pNw}EeT9rX<=gSwRaZpQHiG(0KAC) z*=+>+XI<2>ixM@Cn`2T2Re_iy1%H?k?M*WKxx?|M8elO*0JE!z!JUeY$r|ut0bxtwiE4^<#On~?mX_}Y=?ub(#=dH! zV&NIOKCz1B&r5SC9nLdLU)cJh;mrM`^YU+s5O(+RZk;Dslk7oF$U*H!!D-< z$8DZ@>gdP2$r?gh3W#ecd|LdMHpnO`UBEos&P`s%1+hfC>)7PA9!f;3S#PK1W=eJW z!wh;H?xEQ<&&2NR?kc;6BG$I(_q`LntPsh5>PjKgGaE-H9r$&ix~t>MO!aVt1DQnm zhxFK~*9V(!HJ6j(%!PF9PuwQ;eRJl;#rq^4=of1ux~8a=z)QUQNTtEEiQks{R$|+u z-rJ~-zudDk=9s)QU7Th3;!j6>Sb~LR{gIcSgTKv6^ zB!j6vi36HvgNus;#Yc7Vny&od=3Rbt`$@w*#d2L`g>StG^Ge%%sC;6sD<-K(aCDsM zT1w8LA-dC)5u?bv0queqFXv@=f(kOc9d`bi{08v&M6K2_f`8m)q9=NkQR^m?aHCgS zP66RCne0d3T!c!m1W!AvjDLPUki;dG^C8}qV#%MSbrE^UjEW+wP!0 zl+9MkD;-t0JgogkGW~qwvd$bMstXFRVr+{j&8S-CJ={KD-7O}&F+W^dQ1+eU-&b-Q zT=Z%hCoQVi5^`?(1Bhaj-FQWtyKf_37e1X(w55X-lC=kN9f(xR=) z9h!@V#WgaC2wRxst+GYKw)eo!T3MG++>c(T-g|E!0tC|~WmzgM?v}JT#6mYzp=3jC zawd!GHrS!_{Ck${Ngs;MzZctg&XLU?YWC`$+ke4*?wyvPBgIi`>Hg5gikNmRv?-XH z5uyKmI?PcGNhs!U-0&AUhRf&H9;+%u8q0URGGt8t41S#-*S>(4?FX=I3jfQYaUdsB_(~Eyt!@c@f`5mkGP3 zEG~S>NzK8GD)j{UD_vttxJ;EF$^)KOW0YNg__tx2)&$%7WAGr!;ZIqy@4RQZvN6dQKS5ZjJs`=|<$v`RP zkFGxXZ~9-rw&D1^(b)ynqQ+MH#WeAPc9A( z!B68~k=4R2G6jQJ_5@u#JEtfB0fXgQJ`Ij*CL8`C?P({xZbj^;sV_SB8X^O;+L6p1 zA42e+X(61SK~@$m8~D}y+<^+0WRPrg$?C%e#?dOk#x>kL&0fXJZad&OH8a~&|=0bN^R6Sm7#Mq=*@{M(HNMCsZTJTr?H{Y|kiw?nRH7T!W`QeDK zYFNLGwMoN8TIz@3!;Ij~^Nt75*1Qf)m=S;l)v){dLe_0^Ty^mLd8+}tOKatMrR>8n zQnHi`*1M2!n|d{!K=p+HafRjNVtViHJ8z!_{)wcZFJONE8LrO0S-8i{dt=q2@UWz> zeT8e{lhu>Lm4A``yGMTLA2w><(}t_+H&Mc&eu^GB1qSVEc1Md*i5J2QYJ)-+9Rihx z)>edAteMT-(6|yEt(1~QrL-o;{d+N#HE>FRNz=l^N~0#e%G%Ig)h5l)h+STvoWqT{ z(yK0get~y2KOkAAF1Jsot$$G#F@y3n^JN8x@vVz4?6Q`3sG6x}mvll}>a|6DIcwEa zyvBmpzJDVcb#Q-PgnTV`an8Htn)n5jbm{S?*l$JEylML!!q)$b1iYC82CK>Vf2{$I z)+)ITJ8g}<$jdOXRZaSMhz$8U{0z~yJAAmc>3UtH)K_IeBqhW8Tg$#;gq7#4^0EtM zTM$626%0BPm9=GKZPUPw^*uxfxrwA=Q!=as_gnqu5gmA*$TG)3yOIQ=hxs_YwA$r14_b zCCZd&I^$vzV{VzN4s)tIobAq|d3JwhL4f?ii#*G>D7U4Tro%o{OM7nTrPXtNvkTf4f+m+ zgLjU$bdYMd8s-aR$~c+$q74d*GG%g2r;zCMYio?Q$i?ve#V$NNnCu1$OZvOQq4u3R3_h6m_YJ00gievX z3o^DvjRP`=-pv-fdsIamZ88!*Gf-Tvpnk~0g6ERU;m#lbmz`6dQhsLvz>pU}^^lSL z{gFW_9V7PGo1Q&rmoBrvqr3QCRzzUcvmcQatQ)TeWiS@N5v%^er>|xfAMoQ60ya1! zs>Yb4Tpn8>Q+)qL#G7s))4!)iB5L)iwq*TT%xn;S z&z9bZcuMFmDWg(ru=iw%^@UmSQBqa&x$To1z_0w;1_@@w!nKmCIA&$|?KO$zWZy-P z!-qyyOT&0IdCSt*cXNLGX9SBzo;++H=YuH)*WH!1zglL3poElRRg{PuG z8U$6`UyTq@;TwbdQ1=9s1Rj>L95p(Hqk1NjSu-?+B@aNStCf?^ag(O=5{#fc=Y|NZ1G z*eo@#YGNR>v_ZD#bg1#??aboT_EP^Ko8fGDP|u>g7Mp0$hPTjWmrd{C#?KmE8C^)) zx#j5D#AS(mqI++q6EGLrqReh95J{CJ*^ooAZkfVMIo_|*P_YfUyZ0@6jP6u5r1IN$ zd+Dh6Hs7wZzQzrD zi7~+}MInGmQIQtumMeAVf@a0Ewu&>Q%Ui6&k~3K!$F!H%mkezb9)cFz(t4}YJK*I@ zLsFsQTTNpoGgKx-i@U#HJz=eVKivx{m&3;6c0y8nOWB$65}kGLFE=sOp1&wzJym9s zVi_Z=A?KE*^mzCkAqQ}OWrLA=liPr5ir|%f59x&)x&ItDa8Om%kRgSNP9@{n~&y&mlPJ)7>-{ zf!8}v`qOgjL?p8_#MX9f63f<_Ux`(mJg`_5tWJ!1z_cD7_3n~W4)bHTKk55JRb9SY zWsP5Y<73NN$|~+@{&Qug1LZq94$9mJXh14<^U3#EZ^&kRQ^WRft0k4w^aG!VfI`z( zoH>#tu;#zdfng-9&?SGV zpJVq8#z+Tb4vOw6Z?w9PJuDRj&rX|ufJWccB?at!?1(FkB!%Vujb|84&*A3>>|~zM zzSdU*Yjo~Bam)g0-Fg}u(Xy@S#B@0fJU5xcWP9eyv0$Hld9wgLiJH3?-YEy_-{P1i za9vzctLoy-kRFuIgA6q;ddt}l4~k1Bz|r=ug3I8+a}z1AG%0A$9)zPoM5@SxSnT{< zJWjnJER+x?iXvg)d&eH^_sY0oXRQIfRX=esUr+PpbC+{gC5c7rLoGODX~t=>>CA;U z)XmAM$h)0IWqPs%Xsm>(Bqs zAc1vGmyzx5bHRVtyl;^wT?`e&zpse7WLe@Ae;QK>RGGF8LHtcqN``aZYdKBS6>C&j zRg&CyQTg*{4B3)*qsS7pL|^g9&LUH?#__X1M#03H6ZJ%74!86s2Vc6 zyQpvNZ{(Sa9!@2}q)`6V-##dxt~PziC^A2jkgT7WVS2DbWx`=pvikdNv4}INy~Ws< zrVW~&Nb1f?)CbLUG8#Q-z=k*PJ4m>1uM8ShtRXjszPW&}A@}q77X&$Fa ze()CX5|d8$30N>xQ`uqv{CU+ozfGzsK9lxs2ON#`s0j!-Id7Px!4GnLP8q%**E z&%w~espSyKW+y&ZP@Mg(b0)s2T@H6Nvr=s4GcR#i+s8gEN&$(sLH|tsuIHlnl$2eN zSJBOJ@5Oo-wLw$qdPQwMjo93rGv&n=`ESf{@^|LIyFrbCC2cD5!H&Be@hXqoWJ*ff z!zOw^xi;G{mu15yd;flfod00HZC$N(YBZY;CVw+8UCX*`Vi)K%0VVvvNN$OqxaZUe zAj%(K4I>3Ut**ViuY#R!QtEv~C9c_ML_XY`CWo#NjSLE-o^+9QGMM8|6 zm``JLH*DPSaHie*lyhHZK(2z8|THyCL^}vBut@CPb*y6X258(LP zPC5sqCDDw-SC9{h#m2a1UTGOng2b$W8w7k`mla;zC$;Q3n!0QZA>lWE@aJ^-zxE-fe3~vhCb>*Ty z-@V+_=4KOY{c^WvK@W`i=Q2BxDI>3{A>!|8(?Aq|gct&OZ$+i^)I&^-9h@API(w@D)uPT}M z{;stENvzJSPrs)`(B@yd%`)?#x4qM7#|MY{8v6Sw;qO0nZN86C?dsyeO#hYP7q^v8 z*H_(OX(t`L?Sl5Qv@mS4wEK9!secgO-4-TG`FpCHNbm#eI)_<>?P3i;KPt%ZxnrWt zM?7%gBiMU-+2tNGSNDGg=OYB8)`RG^jh8<%9n`#m>_v@%lG37jC`SyR7$%hAIrrPe zyP9a*`KVyJIQgk%nG*qI9jt+=5kMrHRtm&(c?>a#wi~O5p@w(ee?=`H@^{WuZVPS zmOdS?pv>?9yR?Y9tCh)V9C5AIBUvcM8PyL|H#GOI333s6gczdq* zRrDnPk$I5vJZZ)r?d5*+T~*9{bFC8R5yP*Fj-Iu}a+N5Rh!;JQ$%#lgvfr*TO#IO| ztk`U0skOi?1zS0%J!5KI58YPfvN+n)e0UWi-O<$ZdX&ZxW!B{&koj7dp-@n^+VOFP3nZ4PNK3#1Gzgd8mqO`K)CCMC7;D&Ey<;+ ztF`)sY55-QlskbujkmzAUi}ZTbmFsCU~O9KO1jb)#keSQ34^+kITbe-u1t|lh!a~< zA)E?cytL|g%1E*X)OvJG-gpSWnA{Z2Ihx2Q~FGDC7p zRdNnGWA!H=`E58V{dyny7;8sEQHsj45JwQ z3|57Jw?P8>6AYsl+sAX?Yd4}J75|xVF2&KBz^fp}g>~oX#~T6jRC4%WKKN?z!F-KD z)AOK$i&dvVjg@Q9^keoes#ddJoy{DXCZt78iif#!xDsLvUyLk^DvmoE^`lXP6;7{YH_prtOSp{y z&qVnGJLX({g1%s4qvnQ^!a|(q41K-`(uJ9h89{23Zp$(zhyViW&C3B!Z3lIO6SG|x z68Xc(oNZZ2xqYM2)5rIA%w2)X*8JMJ~CNk4}q!GwH6w+f8awwxz-W)+x48{ zntsn@=;RGW1h3@Uu8?PT>L^JLu+&@dhJm5^f<+8bQs&Q!SL_ZFB48GkIz8A z8xP{uzRTP8@}pz^6u=3FRPEf#a+}sz550DdzM)#jhpXk|FJ9}Iw0>mSu`P-*X^pxw=z{UQZJQTv z?Na;lnL_`X-mJLmeyP$4M`$f(C9<>HRQ`ssvWP7rK<_PyD4!z=s&8X)Fu$om#kY9h z;Ca>Z%5~hd!Q|ZQZ&;ngi~6>5h6ZhGnWJ~Iuvgc&rjcHY!holBD z58A4}^sTBN)?U_b?R8Zv-Z(G^$n@UZ4r2V0l<`|w$t06+5jNev`-~eUaZ+jiS+%k< zBRX>2y@jLsEm>vL+w6T>BZpV65~AeRRg!ZuUOsQai$a!5N)-&AvwR)+?EmC*JIe#^ zPVu;vv8at(Vdr+U*k=Xp*Vhj!M(T+4<$Mu*8G&9YA%YZPO;M(fF>{G8Tp+si7qipm zk~k|HGdEF8^q~!S+uc1??+A7@pl+3b#RsWn;^%9^_9xqE`LacHkC-;S$Bp*(7H)r# zPp=Nc!_)VN9i*IU#D`ttM&5Xe$8xsbY!Z>OT3Z6m&U!-3tdK*$y1%j}x^3L~VB*>; zWd{9I%oKWC{Fb&d)+Df6hFDe>OjPQx^~v z&eaX)rFW}-BI&0@Z2ET3@!j23(tDxJ zODRbb3ssfwMY)dR-rdGR8?->-3Njw(c{R<;Sq-gswJ+p%TvU#s^v%1RGBMi zqx|v0x%_GcTLQiJ=Dx&jT}(4(jp8Up%a)dC(`}GmexWy-YptSGOVX!fXp6@-PkJOZ`Mq%osj(*$gcDGNDhqzlx}Qv<&4S0m(eeQ*4C*FhFJ zM;&J);+|VWUVlCMiX}UDwX_O2!|&}_cC$x#p^}w-cZr%>$QcDJYX638ZhzGDs;Dud zFLzcPopK{Rdvs8PepG*_=8lCU_&OQ{dsUi){S-K7|51;|Kd}q}&%TqoW`s3rd>f$B zyf2wPEyD0HB}V3s4nOyKXE+#@7HFl{O1By$x{z-$3~Rc7@eqmKAGhtTA70y@rb2uK@oiZC?P@d4U+RTuppm| zj$ELIIAW8T_}+jbk=Fs8C6etTP7*Kl&3jjugbtd~bQ+8fR2C;7X@ky_(6XNrK2PKuNnOB2ZlRgBZ@@-T(C?;c7)V7 z2zJyK(b8Z4E0+HH2kUFmAngo`V1LYI2=>xz|Jc=Kj#d`gjp_je3$uCryz4lUBQ?BC zO+AyulO{&PYQ-;1KI(51s(nOsDWFSthXPe~5yVy&N`PrS4enOq2+!eoMohCxu{;I} z3;omduE)bVIw*o%e&KDE>25%`OY$L8Sl7hc&B^zr+ZQ`d_lv#}-q-I0ul9D`-HH9c zUWF9f8HoIUW`LhgEDs@DSX7{*R+f@;@R|d46K@|!HUYsP13T=Xw!yL|-0RnUgRg+V zRU*f=ACdCz_KKR)o2hye`1$2+4Z}0=B({?01) z+$zMB&`zYXn!+cDkOP`NmicNjeczW8MzJVlFFUmsr$}`3iYHPIMNA_tipsb^f&%8g zKA^#p%{=b*}KkFa%DO3@ms6t)h5#QrtI%VSyBr;uic;a+p=DU;@jN7*; zEw5_h3py{i&;rPzbQk>o#WBDnYwQWJ;Z*q?ZooG zLvk$?Znll9gj|6zYdxel$%&5#17bh&xj^3`uiOi3c#t*e!cY3x(r&NEPi zD@5a`-P|8fKO4GuSzglh)Lxx;)}a8Jp#H*;I<|yQm5Dsj`S<+$i3NA2iUb1%?4LYS zBr*@|$Av~!jVWpW09C24fe*){O#8QPKEy)*N8A1v8A`^={PVXWlbSV>)&FTZ_mcc+J@< zYJcXq(=m41O%!oO&PdG0PDo+;H4sd;kod_`yKV}gcbxb?gA>jp7uVpiPK3*(0NxkLfn@s#GAFs&{Z_+J zXZg3XxJ3lc1haG;ysbo>{*q3%f07&SoGgEf9>vB+9X2fqxzz1)Yl%UaKc*;OT9S?5 zeWECIO>49wFrod?^7}Jls@2}ND1JYnecQd&zPAFMPv#wX22-rzxPr5C!aPI2$9PmQq%M|)wtpRn``Nt1<8|B##LJ1}V5V;-*yWdXc-=qfLVpmER-4IJbmaQt(Ei9on8T=DX zi>`2d2i0S7x8;t8&2$rKH$1l6DCS>+Ne}KicW~##4iag2PEkePup|dC zk>%a3h$RADDYl*b2FhT1t5Ha?79oZ{)8Gv*(2HnLuwORB+t|4EeK8qXAOXVJKfrx0 zVs{Jfrfp#A5eev*8V@(3H*sl917&@34F`N}$9EaBSABpdw%u+b0IHiH@X>)Y~XcRHSDqVa`FKNkFKoHd8vY=_+R zMLgii^Rr%Xs_v9!RQj$Ygk?Ij>@~8N-NCOHxI9*Eaczw7J6X5u&K2vp z-URF1A}?a(Nv%r&IReRO9nCeOV ztM?;p-qrTR5)l%%AGMXA;YsR_LKvx?0G(gUepUO#;|$Z}W%P)zGziPlfsa(2XHgBY zXUe+-v|WE5oK#c5yt07y97Hf7c7E+ho8s~bBa3- zS+RHMKC7^o8`SB4ikE*&7U{lp@9?V>oOJU~;fBl1ds=_j287K#ma5&(gO%X>skPZu zNB*S^dSn$cKVd8H^bfONty7v8P&S!&d%X=qbQ4o|Q!Yae3M0Ii(-&VG{T~hb-&W*9 zw;#t?tr`(+Dv<%{s!Id8^3Ma(;LU9&AJRzy&nvuUOYA~Mg8lNl@HmID%q^xx76O*% zh?DLFU%wnBU|re?%UArZ6MUM2y17IsEI|ha<@MGi{*yX^|1y$I45cN-&9z|m%7avi ziEc8wP{p6-$?-SI2MgTef|v1-i8sXA_T^0|*sq6*{!Xa9{8^UcE$%``BVFi)0%klR z(2)cexPo2I(0;o1p`q^x_BD>%8{ZO?x%a^Bjej6Bz}KQ%9cui$ygxcMk6p3*4-OZ+=9uI-~kU@@~&9ZqvF> z)2jVsG^CeL)0?kIQ&C}Y0yY%nP3q&|h1v+YbbOZTRi8qMp0?EEAoQTc1qQZ!#tulv zEBs;*k|A^LGXZtLw|@$){~yH|-u(?fr-OW-1;^noN+xqZD{0J5QRk?LCkGjUG4)LZ zdtmw7s+UZ-tA`5oDL4jl@ea&%^#u)U)^rUXAWLsAZ*TGeQ}a)gStzKx6;Oo$v}Obz zhnF){OnsNUgO!QZJm`N~7AV+{JXraeWCLklbd{0RDp*5J>gXK%^~rRMnA3w{^Mey9 zKEcT#_#a2+gEd8tNYp2tz=xeDac*Adr&{5*T+SEFVf0tzP`Xe{J7Oj=L2_u#n}7BB zIA_fDwgLct8OK4{7gG245h2HF*a|VD^^BV3GqV@}qeVYcw0uKIb0DKwu%?%fNxeJ? zrxHRc5=CrWNpu}%_${3Jkd6)cSl0i#?7Hlf_p^^8tf!t^35(;T5O?1r5u+x5Dy*)s zm1&c$_i*f_+yXa{A#;5ha@$NMzG_u)i-$LiYQleDTyC{Hn3jr3NOMIBC$no7q9>T^ zx2s{EZGJkD@pZo5UPeL9wJtSc_`$qivf|JDTXa55cdZ2O{BMB28pU#V&el`iPOPSs zsE0AW{@tXeog&?{Icxl#)@$?`4n<)XR8vaQlWKrBk1hZSQ1>@G1Mz)ApjXEEC!}36 z;D5w7?l%QtIN;T0J_j-EDKZ9+QlzU7@?Q`{7?D#WDV{pFA2y8)65N=qVA8=!mPP%S zw`bVNJlNqb{IzI%cqcG3tecl{sKPRe5dM;0*fNR;CQR2d=Z3(UlJOXJ;1S@$m&^qm zxJD&c5XN>9VM)}FxE@4kf&<25Oyjk9vnayi5ZHEvr&N4jAYQ|723;Mxg}{Sv&hkq` z@bso#4O`lu_{5X5b0bn79(sqzcTDoa(ejpzUhF~5FqFpqBR&@5aL>U#6ZPjQg*voQI&x>p+tc-$=U zKiewC)9DP^5%qEwZ}$OFeA%M{MQMBpXTku1(FZWrT(8-JgN(AJUCKadETyLZ(Z}pL z-JpYOJRf<@HzRO|@@Jtm54TyYgT?(63M07liGW0mEmNr{kD8cyP9Z#q@yR5h>Q4%HsqJ8f|H{*#a2%&P zF&nw~n2w#8pK#AQRr%~2psn(xT_SCo`G2RC|NX&jNysV8Nl4=~J6DamNa*o=6i!QB z#WkkL5o&?+UG}$EAPK)C-$QICCyR%qF5+-4W+S^3d^ET3Qo*w5SN;vEv?^JVsL$-E zVN$zm_6}C8CZBNdk@_tXaJ!0CtjXa7h!?~>rY8PhbX{dsRNvQzVHk4g?hd6J1RPo# zL^?zoX{1XAkdTz_P*RYPM!+GYk#6ZO=|+7ozqQ_P^Z&qFELaTp>~qeJ=Xv(NR4dyQ z>O@%z0{)<?wunv)cWYh>xGHvb#qF z^!v?-)XZl3VzB9D0mIF~J1Zqan-as<{b6#S$dT1TFif>bm>iglLhVd7aPka>CWz+@ zoWXAGWXJ11T=Yw$Ss=#KYKSCSjiB35o~r=)?>BmX<%AHpgorYYi}EOnlx?<~BC(x$ z_1mGr_>)iEh93#x;f?JVUxGe^|MD55nhqs4o&9_g*bf;Lnces>%rS>4K%~kfrW;}@ zidAeLpMf`Ix3Upqka+@-KgC!=`P5tpHhi9LGpIQC0S7q>p$2msg`pSbTVTP*my5Q`b#oQNnVa~I_kCj-j*k5`sbGS1 z`;)^&@hv3Aj?kfLJvCDuQ-Pm53s;%YQlW>L&Pa-rrqd zUKa!ezWe>H3V(xgBQNlBuJY)j>TTQ655y97G`(>)-OJM^4C-`#L@quMrp{r&-`<&R zv*&lvK@Ylu|13Cv8@_V&Im=qgHhc5SVI1|2ex*c%FAGjd`u27r@0aMMMdT(W0Od80 z=)o9!U%CsiWj*fs^4;l8htygD31l=C{vuZ+C=^Vek zvUaP`;10$Jnl&eU$z#~C+GKKEWt=LrvyAU>UGTnU$pqh@zMNZR-&)++`>F z6R%;a4E=2Hs=A9`($Qx1ZgEx%{ZN8=hQg3DN1C=+5;7kL;D~}C;zy$iycsJqem3OQ z_ra8?j@5lI|D{&n_76<8_!QT*=PNzbF6W!1LlWi?kPPOf#w>6t1I>djru0kBMxHL) zGFSgYL&Z*2HUV<{_6_(7+C7)8IZRUv#UIR!X+=OFcD)iRwGxaEU^z2^TOGzrr)0|| z@L}3H*F=XQ|gE_WiAu8ImmvgJC=@3_%0}p@LDLaVas3x*pcg6z2g@ zS366{Fumn5^eG%rr-8v@h9UU~=Wp|Lm|2boXyau^u&TG z#4g<*>Uwp`qqZxvr{W<}#H0PVpz|*8>(z)mb0B4@C4ctvevLfvjWXmPnBzEUf*ljL zJBlJZNQNMkSg=oAImDWn#pXq|+FDZHec{a0V>teGF2T2>hHpoI5K9CsAYQP=v9Sy! zLLOQ5$A?Oot_2UDP3H$;aXmI?LxiB?1XMvFe`jkNL?fS%T17M3me&g$8CC^_v$hpRU`^7rcdLI#XZkK%oR!E z0XYWKH8IuiMu}{s3lr3WF}>syf-^|#1mA=NB&my>0PdX3pz;LZt|qP=d;p~QP?f`= zp~LYV>7ah0Zn=K*@@#)#Cs_-o0m1Cb^&nt~VOvX@!1FQbePDLO11c350pOtqE6fsd z`gNSho$(T;S_Q02tblNkh)IkPH6|c9?^};~9xK_9US~ks?G6VzH@8|~jaV$gH8#hvsAn=l?gj)F>kl#Z@b|9R7$W6lmTmsFP2Xeu3 z{S5cko}B}tK#%W)73>ZYpm6QKd01Jd$Ycu>h1cT5H zCheh+k1EA7pNu4T0>Us0IQJM1`A#{vL_mn!XA31T$T#~L080%(F8n$yYOm zV1P+O6j2yM&xJ;>6=F zav9WfEkzf5K_4mCR{=YhFGi{{X;&?$4BA9m#kH-Gq&ozl^ZzCO5$UFdm*)Zk9Ou_yxw^rH?6q5Uo??;!$MsUhj(Vkw*qxB84~^iL$6moxA1YHat!k~% z@1j(hQz3cTIJBz~g8RsFoG=6!$b%r%bxJ6VAduTj3uSrSYs!@*F&pD^Zlt zKDUB2lGD);UKj6T9^T_^atS#Xa>5VD2}<#YW7L(-%oB>l91LI)b1;eBY_LmZ3mcMZ zS=PJ)a8|D>2-BpHo_lIO5VnvbLR8d54cukE>BzxcBz_PR4y6E2ipWYAKJ!d>8b3>$3w=v-D5_ zkJdxwHivXw)u_z*ur5fzn<-(WX0eO~9?deg=>X}vW`iGWiq_t|mxPNRm|4&1WcBY$t27HRFe~C4 z3q6vfvVsLi>`j$VJcNZ(KFgjMA^Y({aICy|2vB<)9T#ZGMBn;s117zqO$bD?YM)MK z*h+9TCDa6rpFRd-8b#qILXB97a2ZJE91~)62O0>vof3$VSo>IBF&KfW%7#g!mMht8 zxdoC52iQ@6Fe|1+H&Jv{NFE4Eys6QLkMy51!T1=Lvrrj6YM8@G1Zgc4Q^VT<^?#ItNl7XR(ri$uq4M1ZQP&wizip6cSzm_1CakWVkmC zHt->6I|7_YKSYTkRTdVV4-zEHugwNgk=M;~x!<1eLb-kVdY^EP@-2D8E|FLohUp>0 zaB0gBj8KapeXLjbBc59$sYFd9%ekd&#A=60!r2Nqdr&`0GNgCP1DwkH@^>wb!K02C zj1YV<6Wc&>0=5wDpIjALBqt&aQOW>YVW<>AtC44#*ZX3Ul3Hc(Tb09tQ=u+azY^Bv z!^ry$$*wSfvB9&UaCHWNfIK+|V4)%acMvL3=d*luHY}=HYddl|hjUDr%uw?-R3j%H zh57}_m5wfwJp!U*2x4B?VPa3XTncgA#~fdXLFdCToc9!HTdpe=-vXK`pZspJ%oKGo zn+Kpv$tIN8Hfpv`wgl8{8zC^!{}5gfgJ`syJ$A=Et`@yZ0I4tkpH=*~$1A9{WOl}_ zJ~bG$4NHFebpW?g{6Iz81NDMNmQ%x=nD4K}3J`R$Mmrkm<>QwLWE2;uKJaF{GvEJuww#ZvPJI8n|Gk*Jbp?I*dOcnfsKQ+`1#LAf#D56Sm?Qp-(PMzKB&;bu zPgC-w`#iZsl2r=Oy&P|nWI29~!Vv77Hg^=lR%+%08iOTzNNY(d+b-ul=Iu+0Gy%Zl zcaZca8C7=0n>dv=BEeG;Z<|0C_02Q#~SmR|wpi9yBPi{S+b{gUZ0>L+H~oGr4g;=9XnpJ#wiIA12>V z>sD0@FPTP4$gq!?jnHH*Eue_v&+A7l;YO2js{rmp!~d{e-$MCEtmsmDWy{`YkIOmR z65!emhT>esi#>80)cZMvv-3eD;C6>{IJPDbb zmi@{z9d?Ve_c*+*qoSeR%E3c`xlqGaL)gWU`a?L%`YWRKU+xuI@$W3v)aYvI=?sox zEqmnptUV(y0ioVFAZZBzy37M9et-Y>*W=H{Oo>a-SysCeK(`-DwR+${*|TPnWpf!7yaP zCPh&am>I4A%@;$kC|4Y+VRPsaJL7C+uY zP;6vSB*&VswSNV4w0#?XZvxj1={~^FXi-{GqG4SRWDkkIP&VLJfkQJbi`M!jWyKDE5B1Uq z#JGSo)P_f+ST0ap3yQ>@)a;ix64)(>pfoqF6sftw^Se$r2Til5P<2Yw)PXdi;e&^8 zs^Zh9vt9I$F-pB>J$Gx~Qr5uaeoLsb1InQ~wo%s(bnMA#WDNpv@Y~9CkNXcwbSJwk$(AnRC{6(k3CMGc z{cw~H5D1N>r^6c1xeFYgFiWk!vSH|Uk4Sua1)*q5eat%VSfsbSEVl!b z=JhUrlGSg?<;uO$Y4$X5r$VPIY35B1)Y258XTyFQ^6b-N2Yk2F?8bsF)q(Ty+&<$& zYXP`r*Ae!9n%Y~3CyqU#c!}$Vq^;5`I2IX4wD%cKB^bOZt-lyw=wr|IT=BT8KlyxE z+ql2&7#;BVZNKQG-+BKAmE$2!QqbKW_t6-vgZCSM4dlAg&L)FAu5pK-N94R8{k)v9 zVD@^^S0^HePU7ywlcPpuDZ)f^1y#g);O;%>Zh6-Jgw)aakYcU|m)a@dRhG!}ritjr zwF4ig`~7^ql;STD8rxXwPSWX)->-f!1klAC2JuAXao?h8o+oCGtQxU3lDA4-qy<73 z{)9mo&J$}Jj*Cusb+(17c?01XZ7lP^z$$hJms&K{!eXhUlLpiSVfO;N1Yb`5Y3cg>TQ~PGdvUzb}E<874|*ahDSKZ6BUA zZ}9FHe4>_`?_cmyq4InVw=d@kU|d$m%a!mve;nyc*WzxZt%wmd5&^jj=`CN?{9*E8 z?@D1^Y4-6MSzv5T{pO}hO&i3lxO}Rrdh8?h^QSqc*CD?;UhaDti9Np~4p29~-c>wg z-79))Ewv5w&?I5|pR{A%k?LH`kIHK1$Za#7wEiHi>$A7SZGF&57-kKtWH~pKxg0;s zF-L`ipZDpoiFKGkTWyQg^HSL~GY|fDJ{h~TLA)Fan_=N$YQZS5w*v54qEj*~$iHB_OO@eLh!OIO~Sq#4eD{3=}@UWWFdBU zP`h~Zpfj+qYP(dqTJm>kxj!A8ki(an9I|1^Bu41->>|%ZZ=+z+!L|WI=2E~s1@J85 zMWs8@o~+wqUE2UzF)!d19Pvy z$yE6<{rJj1P2$r_o?{r^Chh0v2)%|wG;*4DK1ToQd!W8n7K82%cd3`J!zYkx17ugC z-XkKU&kN3fdbbNY0YV2n89EjU9=2w@0Wf|DnGD1OgF6H~iA7go*v6)wDcNtUk03|I zvT9x#M1$6R2e)z^u6$36tuc~+KBcsgA_Z&_q9!%|>E9-Lr{;%JWclCUt6fzf#7E91 z5Fz)7UO*-+rCiSs5o}0G z=)-_O=s|!1B6eL>_t+A?$tO<&Y{Sv)yKRN?lLILpR6`!Wo41RBa4kd&hz0HAr7n+Q zU7RJ^plD6<4oZn47G%Y(d7xr2Tola*a&W&l;v=eQ{b!y2pO3^zH!*-<-rwNDO}z32 z8nDQ!?O9r;=LysAL+K*;v~2Fx`4DM}>CZzjkKd?gNV2Nuh)k)kKE5|O-dOj#?In$B z7=7{@9u8m@4Qvl)ey1 zA$pmqAEYOHur8$T;P?;>D{s??S7R7}wHd_6iKKHM@+yoZ@XUcUvM%DvORYJOxNBMXzJR^S`KSn6FOiXsYMk{n`#V9syq7 zd)i6fKH9tPC?W2Dc~A#PKKxuQ%fB?Jfa%1HlFa3DEyTe=6A?S)x0sRF_9R2^(kDfu z8Pn*2jHsszHF+86AlQ8%jawcv?T-q;i1pmF>~5O`?_X|8x4=gyEa)Rw6++-J+`b!B zX?kWQsiTd%<$poTBd%$tUT$CU*Y;~Xe~M~lu;R_OJyfVbMSXF;$@{jsq;FyQ@8y4G z+i;dBuM;4drE^S|4)j~IfOPc;ifT;Qs$B(lzE63a8Dt(B9W+LNKa9pX$qWohV4QXx z$`+rvSaSUX-CZaNe3J9_?~SzSIxxHMxU?S-R7qVE^rRpyt$di6juX>bS!lgxU)ckG z;|%plsFw{9Ujn^~Y#e}zrJ1-Zw;XrkNHJ*r%!h4P7}gT4p8*0mY5q@e34hTCeNKC! z1;DK--yJsQ(Qg4rS}^ENm~V?6vttOuMySH9w&jHKZSzXJdDjk@%DIU#5Gb54@XX!} z3(IvpYekw=<`Q7?@!4Mf1IX~*4mdzj|H8QBH>bzN}VP!FX68MgF)eUOxR$HaD#!+@TR00Hpi2M`;b7^8gDA7XKgM5^o$Ef+7PWekyu z=Yk0+0>QIyUiBxkI!BtLMe+OR`WJ0(QjYj2S}6AdXs{b49j z19+Yr#bif3@dvhzOeP^@lLnxlzaK3Iha7XB8mP#;#S{TciHcaj!%^O4b5ci>^Ip=h z7i-ki(@d0`a@k{O6&rUKlZrw9hnO%t7{Lfmm6P24>umKJOj(E#GgE| z_7Di)e%~$=FZ2-}o?Zr1TKGuy>P0gW&;h8?`P?yo1zs)whw|Lc_DW9|Br|m8`v2aA zgL)1Qx)93bj+p&r#6U%!M(<52%a4Wfz`~KCqPsr_KW7?U?Y_0{20?eCIZ5OtEGDpa z=z^{W=Hc!^RERw8B(b{HlXESg_Z9FER&-L#`R zmq!Q{3S*2(g+oxFN?pn*BQhmu$SJgGQLv-O{vh-?3ssUc=ugRzSUSI86#pBgtUr8D ze_4|hYy+5{=7Z4azgz`qg-e)qc?EP9sQUk|vCV88lw59vyWKqWW7Jaq`jDFDEJ&LF zMj^kTV*9hA&?t(li7yJOfEa8G*P{Jt|#xdy8jB_Wb{P-sd3UnwG zv8lb6J-u)HHQy#a;3CUAZh+TN1)2^|GH{2)g5yyzm0tWz=l_)F@~UN~Nt*u1dtGiM z5<=C7yx|2zRx)^HUvj=FLPID2)lRxHa)>xg zHh6-boZDzaRbVzAZirLk4H~3LABMpg8-yY=2-Po({w89zr)^svhM=k?{vpVagNO_1VgfO8+W^b-8{>%0_kp;8-EBcKHw# zG*!kXCYi@NV8)Q#GYluOW)QSXMqL1@MFFu9m}mjYDlV3jT3H8WKB959G1TK$DQc0KuP97|;OPY#OM17Zca$m=I;B{*PIL zii{NLnk7*Q%xyY9>y~G>ku%K_$b_e_5@g9G*4neU*K}I|3=nh3WaN-tY4|<=G5+^( za+Doj-96|Z8D7=_zhiu1rMJAMV{}2dy5Fza!5}wk_AtTyHTl10!^=s)q~E96Ket;{ z0gQ$BF5`-O;6p8r3(EqyH@YaGZpJrKfYu3RTK4%A2>ve*&;%uyH%$k!V>7@uVlc5c zVwBm$*t2WB#r%&jnlxRHaDF`3!9_pgb*c@%B%}63>4e-$(q3)0L4o{-u`BbWkJadhZYmaGnF-0b$CRj2wo$qCPIipSc6-l+G5aC5}A%;{B zzfN@!=vA5e4-VtA{7IG@>|cZ{6=f`99LFdhQb&aD?LE17Go5oPSIK0ndKNr)lR3mD zn@6{wm3uA*oU)LSDN+66QvFpRu-7xFWPr2%H10z);ScRc)_zrM$N*i?wM$Wth}wV*9tTHW_By+d1z(A=Pe0>lNMpw z_5&TIPm>RSjyCvbUzJMf`f>;9{$j^SC@#PazAC)D><+mQfTCJMIo=QrpzQeP|K@zo zaGkst6qLbsAy38pCFVJ^?8Izb{+4EaUGGkddxcfDx$e|B<4fHupEmX zLO)PUMrTUrrzz*xe}s(oEZ(CWb9p$_EvC>p4uUf9>z%TlQ_z|QcoL>S9T6!?rsV{JO^-7Jae7SBa1XZC1I~0Ld!~mKceKxBQ-Rpy^TyK|si7Q(c zqIhJe#=LjV75iCvYS+-!n|(-jq5iQoj#N>DN-GR?IVUs~JU%FoBW8}`p@dJB-w6l3 z+CgF5XPcsS`_N8ynE%Q|fpf7`&dz!3tH^qTl3J#ro(62Qyj!fo!?wKnJSW!HS0V%6p50L-Kl&}Kisk@dsIjJdh;XQpbFY29Nn%9;i)uhsfg$fpUDuuhqpqXI;u)8b`^-tIE0OOZZ(?dgDN-y6UjUH zk;-8gP58Xxbr+#R&F1U52H$AuXd0-+S9IYCti%&8t1FT8Np!a_5fY1y;_y2VtC9R3 z)dtlUbQhSzz&9~dw}xO=%@;T^Bv|v<01f33Ra+5fS`|{Le;Qo(3b*i!2`os!$*oUi ztspd2C6dY`GBCu(F64Y5b&|QLmgxWrJ@KJK?R_ zHOVoR3+CEoNx}HkE-7a$fQ_B!lf#UX#1MOYdD-OLG+xI1UU_CJy5N0o5X<#X61QQV z3CgPjw1Sa1R;m^7FvYBd>AFa18<*2f1^Bge1{>X2G`HTyMGlN425s8nw@*v)vS6r* z-htSz6j`nFZK>t2?23W(P6^Y-X2qOjI=M>tYuRu7Qf1uVw86Dhl6L8uVtdrITgg(g z!@ZuLh$uo*nX4FOF6cUr2}A?^oj?xJHy5>fB&z?RjThtSh~1mF-TXZ~n;x$6)&`xFgb2LEV#A zV`OH-sNlIA)U0Go3u;u-n-KoOFxc2nF8^D(quSpbD~ZWUahx17JAIrLk*Knpx*_kc z9XK%hHOZ1)Zmq1mPzKb`U&&}rZubfX_)!FyztMw^?6E2}MqXdp9K&xu3m2XTU@ua( zspSvTh<>IjGEW(|{#8qlu^*jd7fdX)4t73E7A*~I=dJ>4xPNLw)sUu~2@Zz%$h?MA z88QDtFE(n)&+;(|bca>3#Z&lYE|*v#D+|0XhDJQ#knG4U6JZ;3aq zNwszFymZLEFERoX-yN`_sjLy1XYF#=u+2kbll+#F)Wj5JpB<`z%q!hB3Y$j z6fBbW{&mXShH+i7MA<=)0a2aoAfyceMY-%Uqk?B300ofVy&ae6UIgpeJdjnx^U*AdJ||00!Rii?^6 z)!ii9;wryWZ&!HZY5J_Cr)=W$XPKl;Ey-|^Fd_Ur#!P?P3?bpdyp|fvfr`gl%9@{y z?c(S~z-?A(ZX?!IZQ$1lM6B!JEHd_}82?$rNTFv@iEiVdisgg46fF5)qix;yi zjf=z@q7c90jgH7P+pVvxoH(;*RJL-wRtEP3Z+&VNohe}=(Hx%&7^at3x1f|`@wu>c zk#0F!zf};oqp)vXa@D65=tYA%u<-XdXa@w9_Qx@3;0EQ%?Al{M^Lf1Z?h;D=hO4XC zq;k3szb$pdvrx60yk!yYVaHi^acl5QtezavPvfK1cTzhw6pDBO)hZ!oTqmpPZ!A^! z)Iu%&QaUJ*)BSq3CGK>nB*3x;MeP$CAEeqruz5@*&2gyGTKr?KlfJUlma*=G(GLKl z*R%>?i4{kD2=jM(t%kqzGH+5rq@}-+152+Ls#0@E^-&ox{@&Gq=RPwcmVJSrr)vTaxaPeTN9t;jf z*7Msrtaobihf$&uIgz7?wzsv>L8E-HUq6cQ$I76anl9U|FAG?c$RR;&b(IqvHe{_a z`2@Ctw#5%A6CEB*Zm*=f^ify$TiMvrQ;~X&t({Mm@*bxs^_y=9Q1wa&Y!$G&P4Asv zJzDkR|0cfSKmA2-3-&uR3jhHTl|Y1vH`Yqn~E zSjuc?-GLWc*3k3|DOpp)ab438_7}RO3Rt6hS{jC?dG>t7?e7L#!oJvRU71BBfBV4v z!|A>EqbEI|ZL~^ygS$0uTKx1-)ru7y&xETa76nk_Z$%(H_H02=xxh8+%=84GLgVy8 z8BtI5U~<`~+TLt*Ni~dhvtQNLt*4`h ztL;aI=Jd2SUJoYD7PdIz_+aUzk=}EuxOZDtgrkHH^d!7~%^bp=sXgCGRsT^OTA|qQ z5#K`4O~+ZL7FB=~(1T^Po#fq#s&iJlUp6SYi<{(Hn=9ta7BtMf`jzLbTllagK)*QJ zF>>Pli)ho5Z4`~9D%pzNnO)@_(mexFZjpZ*NhcvYnnXd2n|!&22^FfVM9v(Vrl!)I zrh}<`o`&Q7O_k*no`E^eul52?(Sq8w%pFE0q@YrBR*tiV3B;%drNoU7TO ze8H(Y%`A7?m);UaoyfmB-!!T=ndmv0MESV_)mEK6L~g^+O!@KVkfd8GD{8`?M`wd; zGJ9ynC$0(Q(63iag^us8DoJc(bO$*u#`a*(xb1KRI9-C|`s7-B!W=l*0(v|>$2IS% ziZy1$GIGP70JTolgfj1XK}$=_d0m1N;ZQ(+Qr|gCF(JWd-JWtC`KQ*jDyD|V)|6`) z4*!Y_A1&i-&3XA~67jv-^Pviuwl-N$5z=+qnZws@K-6ydhpd101YX#T?n2ckbSbr9 zh;@!RQ7Ym&nj4lDP(~k8zRzgfHRM$nCUndW)lSZAFz=YD{zvg8T-Dl3g! z=d`t_U;AyL_Bw9A;f!rdh^lr(AFB_w{?7WNim0h)!m&}sJhh17AiUYo>#@$>u2i3gG__&>H%kR-lKqaS6lVpu)&WIb#4K{u*m4`*@bRs*a zSAph9)M1uDyIO6#rl$L&aDdk7^Z7!e-= zIvdV&^1#{8aAFlai276i$toYk9)GEvzb_PNY;inGI`;CusW_Y?bvI<60CT9QCWvTc zyk4~NJ66wU8D(O7o_Yj7S)&oUCb1#o=GL+Vxs)~BFy?4(fCN(BN0>wG@lo(PNyooP zD&~caf;0!B`+g>-%loy1Z)Y?34~WLSIViE@BpNl(`WKzT8s6s zSZXFFjOr*^kL2FbxiSfq#88p`#{5$@w7i|tMmHahzw;42qsU(B59rr+lEDx5Xq$p> z27GOj#F#wAY7;(F0gzRc{ErYW1x`O5;f}suW!zJhkRvz8xh;T^mW}EYB6{P4i_q-K zV~O3>OL=o`wTSY);+CPi-q|=Ow*EVaCgjb9mV!bdlXeOo`!=I+jF6T@x8NY#N%{+E zSkPICr>LoAD$bB|b+Z9Qha@ znrT*!XmMs5Cfh|zuDX~I@i$rwXvsFhUxk=cRq0hK--K_lRO1g)Ll5v4c_HzN2N|_; zUi^8INqZ4?Qz5uh?A&V&?ZY#5HtOtu?2n^6Y^na(d)5a`Z0zh4G2%c-(ipgxxilvm z+JCY;nl_A{a|Mv8ym1N6(`<|`Xk?_5vo0G+wawCOGF)Snma|rNh@8kYyH7cjfynA$d6p_YhQCz zdS=?MN#{HhD%40C8AY@0$fe|6lR?Agn0FT{Ea1xeSOI#zFEv4_*+ExMwI=dHB>aUy zl8^eMJVkG#MS`OSN1_q3-(B}6(16mrW(mWXM8-C}xm~R}uKS1`{FJG>a35&Ol$hME zeZXD|ZGlv`i{|5U&xEh|yB4KftL#7I>h`~8+T`TQyVMNoq{bu#Jyr!4akG}nbL>g! z!9G^GnmD3mIBhK%wN!X&XvcPV#k53u!&cwytfcz=hy9uG??Mk%;--SHz-LEo=jusM zUNX|Ek1uNZN7&(|Kv$=&lQv3U*(e_Y0+Xp9TE-CrqYD*6wqqwtn1aeKXZ4<%WBYLp zF720^pOtuT_|>qrNKy^g3OoR=#-vy3kg8d6z#}%<+TXmj4+9zt(X#lP|Bf`%$YEvA z5!L=8?*{C2W~lMY-Tq9DPdG@`|9N|{afySGlOI`A>Pyx2uKPIq6}iQu^d+`e^|y|P zUhM&@jYXm_+lyXKWa;U5sjD{LmvjUfh*rXLrv3%AEF0dgkN?b7Z5DvkrdYQJ41OtA zSS$<}cUo6I?l1W=;=WcW{G}pX*@$w+=cxCb%YFLLI7Z|Ex6N?F6qoW!h^lNN=EL`? zseqdTk(qP0BI2r|Jb;tb&vQ*$%lyZZuDtmz)BCY8;G$+u)gNIL7m0G`c?eYc2Bhbf z55C*8^4=wtc6vI(v>&%JBHRy~ z4Yb`ovinzPLdl+Elq;bgn5CH=V{GKvuEEZ|Q!ixP1pH}|E$vL*p2unVt0cW1&&4}_ zsl03_fAVtZ6BTc1UvkxUsaTCY!S&?tQ~Eho6IjbV!fndC-5K#q0T;@)&rQzgL*Rc| z(oKi`BVC4THA)WTtPN+z%g;Qit_zdg#;^JCpmn$Ngl)jR23~Yz<>cm-{8RQk@s{DI z$6ASGx19aTS4p>swOlWdZFUS%R6x$pTPY5+!cYjwopYnpU4!#NgVW+Tt7;1%3sDv= z$nn0g{1AZ2^B8;4Hfryz2QB4Mga!+`VX`qob-0umDt4T5oKH>^o|&vc6xnB+$7)E# zf1YSFeQqslz$8Olv^BQI^1HC92fesQllC{W*HP|Sfkzc?I8h4G*wOrc z$%F!mJkkrMrO)T(jNnb-Z(iMe9u!p99j6ZYGAPg%_~b2#uFu!DjVw>fnR8C+@j$5D zyhP;z!Y6q@Nx(Vni{oM?A?GLZ;3~!|=GFko4Dhj5D%*-z8%n=W45WVD;3!)R;TgCIz>-3b3~oK5xUL{85UxbBU$JgZ4~o0U3B zC60z^)!k8=YJqE;^sgYrP%Ks7@u75qi7?)OD(FV@;bWiJQ?!4Lm)XPE->FjZJbt-i z(G^zVopCzG%sjWXY5C|x_n98+hi;7Vnd_%p>LEAUm2Y>+(KMW9jF`6dx-ySTc|oF9 znx-ge5-?rYzV>LEn(SIAG>8e%T zmcEHGsPewFe#5t9-Y3NYGgO531 zq{(j=btu`edfAfq=!UrLeJ#{*a;r9=fL|S!cYb0({esSmB)dWN+MAV6V#F<}RZT95 z+{3`X@dB%nnZHhOa<@i6mx1-qQF@*9j`zM^@{;FZ>W}+A8dcWn(S>%XRV=YE9nHWz zOq_AOkNbey#NfLzo3BUmeKquaUmC`@@*?~x(}sa(@eK$RQ#uqRklmhxX-5lRW?kNqv~_Q)r7kqS>*`>T zd|$+o+&(g1q+rcK#mqFG28zb*dQ8hoXgd!>dr2W&caU7$&d~hk<~hfQiTvu|(5vT% z1_KnrFQ0H6KbHJzEbO{c8`Ht8nIXnD8-Tjp7%hQTF7!9cqoH0=UGlt_%`?ho%6d?& zoB#9X{_cC5MYbKsBs6q#3Vg->_h$16=NwfN!Y1R2#Uhi|SQs&zGopC89%31Rh5H}W z`ZnYDqzWGWL@!CiQ+{e)TdU3JRCdEEi5HdNp{xv!VTowTSe%AFqKI(jFv%jcO_ z7g>O6n#~bG-moj1OjawFPs3T021v0>j9VP-8w2J}Wtwq5Gt-a_moD&`Jsp77ht+hm zWuIW=Sg(D1@pZH^pZXeMPOoZpWuQ1sET_-GquOLJ1cqYXAhcX}`o(rqq;(A;17G5w zC)8sl@lVxd1^?VTm7pbv>G1y6SfpdM?0qA!&d7fM;fWi^seFkWpc_vn zyPiION4FW48HclV^Vz!eWWjy!D=yvnzSlV{l*EGn!$ev1y~3A232Sxs1IOA64Lw1t z?koR43m|+zB$8LS=URVFhe{o+QgrgYL_AJ-06i$idINz`$a`?{=w~w~Ix$TEX%4!h zY1&2HE;$aZNS4pJ?saK1Hwc2KP3$8~;)T9kM`*Ft(74&91^bCM%g^W}Vo!kcOBx|G zkoisk1Jz3E+}$XDeqG`Ia6)#@tkjrpD$7iZ@?L|iPIDBU?Vh)tWNz$f$6sQ4*5Yf9 zfPd3Y#)ogZY~OJk@&v@JSj43s>1MWfi8AZZ`uR-xFKM@JejGzQ@-ln25@$J+EUTzu zMAzWUXi+nJ0t}9Hx~X2b_M81mLjAb#mqskHkB)RKJqL{uFw=1Q*vY#6nJrQ**|LOQNT7 zbYzEr2JhG=Fx1KT-|OD#FGoI-Tr)I{CSD3Ccyp1{G3RY2ThF(o4*LXs?xFVz8x~-@A!tqg;6yNf1O%zxEiAgn8tVT(TPyda+N937 zHOx3zGIj?LiG*NgV8pdyJ9RW}nq<~}l^>Z;J`Hcd zbW(@DyAOGszxCAY(9eAQNEz18`Ly(FqY&P137|V_oWQlksuS1)I`X)wiW-g#Rkc(-_O5M-ENO?5x(`$1$ssX%@v z-_>K@TgYj|ufl3>{t2~0LQ)^=_$wid8HZG`2~nfNHew-YLg2j=90WmG?5AcUMbxF;l6Ju@$m`~ zv2W|O)`GiRJTR$8ev)kA-NvB8`@z~TpB31{D6Zd}RSxm)^EK6KY53-MghNiMwS7i= ziMm_H$p3{#ED*LR9qpdm(RcWKv|QjgRL!8pfqYgbrt^CLe)s9MEuTq$VMQN&X~oh> zWtxF4^0RtAmQ^>7&mO$Q#MeWG2B(YS$x3?R$u16uwvF?L6H!ua2sGplu@;$Do)gu@ z%wPY10JT6$zYT~ERp8JDVm4ydjq1v10mA=60F?u$QYfM)ARSch3Npx8idlRz@emld z3Ga3Q12H1{P#QUMuL*l)p*UKk0BIkm1h5|0 zLC#{=_1++<6x)Ok6BbB5oMp_aoVGBrQfF;h6n_=kMF-#mS8SB#XGr?+Ab3$Lx{*sL z;w-7L>-tDXFOd$}(SwBT``%DAUS-Jdb|JmV^A&om@eN0xgQt4iKR!=+&jUiv@!&oZ zRFDg4qHiY4?S2%E>>KQWzR5*AI_8u0VF%F{**BIg8qv#%6qciBjb1hGBs+2RN0b2< zRvLL_)zbLz-IH)z%X~yVcA;@i`?rd&3QQMzseAe~{G+RbmH@DAWK8O`#X1!;s%#VJ zxG*Dm6ed7acmFGhV+quV0NRaJxL)E^>j~beCx;!)ntMOpIf;4`NLE3?yQVtN1g@tg+ zN1f|c7wt1t=+t90v@0@3hZ4qo4FIAPlyEFYyuL$i77hpF;c4zbK^* zDCK@8PQ9Ze@^PpbeS^&*BQV$n^xt8zt;PRxEw&j?Y+z^$w_Ia0umF(@D6+9WgT8$M z`Qmc`;XuRVS!qm!AaNX6YxXkQ?r3v7D8gRc_xK$?1t&1o2hs{{p`3%{raHmKVq~2g z=9bdy%w6acJ>|m(Afu0z@_)t$3H*B;NB~1+&Mk2;7j&?>sHeB|Dg9=Y=4;mWpi*ci zJhJD3PFQ5&W%`ta{q}2SkLzN$s!Us9lTY8EVEdIKyX~H`if8gRiy6LvM`m<68hyUtondlw;Bj8*S;9gt*Ek&lI@{y1O1H2FM{dlDUS_V zu!5%P(#ZJlrm#Sd2`n@S3{IT>W&HKy4LgQD<4t`QD z6{1)NvKw^hLmbsHwvd4j0dV>t_0L#APUooPNo(SYryY<$6ptq*f(|^?0`c+T z4sw+czK!uIBtAm{u?k=NLotc5$zq)+SfNk%CkwUokx8q^kMTu2y;vQC69bj!_@_UR zi3x9?G6s^IntT zta>~Oit*ah3ydD$c$0JuY~d61^$o0Sd&`!$%x6E{!o%m0Eo$D*W>~tT9v@`iCVhD9rYr@Xw(|6jK3K70h3Re4x`{kbGM8yS58_4ciccvS zi~z$PiRptBk-2RvH`-LTpZi)q*g%DhkPo}WCnvNi0;+yWpBKIoG$d6e(2~pLN~awG4{aEG zJh?q1ot17i{=_fH7eJD!du)J!J;MWg@rIT{0n!$10Qp$Uq%N^Bf)5wd{tJElA`d9( z8xE%k=mm+xS0V~h>{y7+sBQ*Hc5Z~E4In3Di@@0Q+AC!nV;33po3Kd(vErbb`C_?m zt74Dnhq-uZxn*g@Nnemf7a8|(tfAtT6n=hR*&l77Jt;T(wf@s)1y|QWYAlcaM>EV5 z9Wc)lJoXjm8X+IXxpD`;um=tr(JeQeuubyxt!+c%jC^J>h~y4|lc zb*-_(7AcF*nfg}WBpoKeRq+{Bnh6W#-Qu+DiV zH}2_sCJnz`F?YNDd`TeYQq3cC^|25=3D$BpjbQB1-kdMU!;f{?V(4ERa}FH#Sr&&d zVKd@^Jr3IBq&87LU=JSqs_N%y(Kg%wEMN-_reEodwGHdELD?q}pP>6OUnyMi!uRik z?iWOV5?{(|y`dXI)gI@8;gjW=M~AH*sgn*E_XPW`IKcCq*pCHt1VD>V*`5^^<)Fb& zE!Dwn&_+*W)!}6Vh!ambpjKE>vO6c0rm`%i$eV^5C*fRKXNJ=lcy=bdZQPUSiG*P# z038n)&VpbE70Kz}weZs+=hhavwrhc;cLyzNy{4oRkX)xS~F) z#sYlJTcz;s^#N42xgg`vwJ74$QAgiZzbD)n{3sO+%^tgXcKuR zW$Pi^Tlm_Jg=4#D=dPb$y4)G;yiX-7JF zejG;!4T!MB8@b|8!5s@lN0f~nMhO$TZ2Yhl>auNYCeTTa&tAt9^n(x+s>Vdg41C3d z&F(UuOiVoZD>Bx$XgyD2RtbX4@NwS)&qsND59NLemwm20ZKj+AQL#1u2!=M@j$qOZt~Qu=K?a`JgdjDj}vMX%ey!YFl>c)?MjfiLKFE+VNz>#yZg@;t2K_iB*6e;|FC#r;J>6rej>CG+2HjEh)D0V?SPOAxpsfI+xP{OP86Bh;U#6e_yQ>ZQ8`YxFR^Z zqULh7*;l4j&$YT}YcUCAf^Z3SI?E)2gJstj*N%~!t43V?fkIq$7hiNB7_J?W^mVz! zHzZ#pE`|q?Vh!rJ_9z)OiLr2JGim_^lh@>d9#Jsr3}0v`^vJa+!kcgE2SK%2_f(?=iC7C&Vu?T#z8K$NDHm?taQ zE@;=+4Aa)2#XD78x8<5AlDpl#F_`xg!R%RB^&d{NI2 zJH_UeC$+Sj{-6xI^Ho8ZB)quM20pG64tmLJ*a!j*Xme%N*T&?C;~J)9lN|YRQ_2_c zI}^b6$Mor^q6N|Q_=CRwb3H7tMeeI7TJWW<*d%FRsiRH8_ss$6(@(GwPGtg&NcO;3 zM!&qu#2Dm9@wg7lO$pdphNAPJJ<>TusJAg#w2;p_D1E4?53~jz$cnD{5g)GN(GM|x zG!_M&{pxGD@Kzb+@XxERJyBI4g1-=0(C$YS(ue2`+P+e!T4=|sCR`kqJdz`HCwS@1 z*H8rqC5Mu5Go@eb**}yiI{WiuT(&hf?;(32_Si{f-k1?Z|Cx`{$c;SY!{4e8RaQF1 zI=Ajc*?NJ)n5;oBbfz0|BE$z>&U{EJOgMe`mLssK5 zUdJ=MVuMp70RI@I^a2qMzmNyH9Sp1M#;U`vww6QFeZ4T#SY-U@A9jNbphZ7Q*UFd< zGSE)R4V>Ghv1dF4?By*ygL9N;Is`5joj> z8&W>(1h&YJ?r09p&o&~5Uq!>F72q-Yg#KwG_G9|sGVT-?5qeonpx|fP{G5Sm*c@ZX zJS+$)?fLNI(h>9a+i$%sJBrr@kk2wQ4#Y6l63m$~E|7tqi1{gA^P(TzM-a|nVf7`R z!7(aa+!x?uD51bLejV6pW$9CX7Y2Uz3$_PU2ppY5+jA8<)rWrZxKKT9qs&1Oe6X9h zc~wFIAI7|d&tYCkpP%gq(^|96QaYpRYb0-$jF(X_9O(=hJa@~NK_z^?k^)Iy_`;kU zy$1kU!SYKG_7l8j5U&Vp!)u*lBlKak8y=R5wz}_>FkH}@{2j6)TOHD0IEHcoL#7y) zK|jkqF0oSuuNUbn{X;I+VbsSul5rU}M*Hbw_68E#_3-m}QaQZ%H){aWIsn1AVMEA3 z9dc7nu)V6>aHTBu1qA(oeEg8)Tl%n0=Z_8a{bwqLj+k0j`oelrD~i4VOS#%~Au%3V zywDG_VVB5?EX8FAKIUeRkFsau6^MMj4EQ>bbBSn&&7lVs7CWI1KXC9Nhjhmse|)#! ziUSh^Abs}SuqX!&y#k9KLM1ZL(zQ=N`9$~dgAaBaH*Dx0edLkutvBB2CkK8;dy@ol|-i##Dq7@`jb zinZVj;13--+5A=KLChjiJTY=&FYILKc8YSa@2Fft`&WLKA(VoLq>|9%D;z|`6uB{_ zZSa8Sn>u{qw+Iegd7x$Gmw5Alq?b?py~q}B4pcb8$AcBp3JgFyR?$YJH{N)&d;Rs- z{l4UZ2V%IfII=^RuAznFOeKp=A4-$@Jc+0W2T6yorOfciU?+xCD70yd7wBS`Z2&K2-@?XUeD)Xp zmC`-DX)}EJq>d;92fM-+9n|KWOj2hY9zY+vreDzmd1T*z{{v)4Z@8Q?bcswTBlR3~ zXeRQaH*6$YNW_E*JPRJbw{!;YCnIqhSOg!2Gs}- zGU-Fw!(YDPyEYa{;DN0B?#m%e*S-AmEA|Hm9I(F+2cjRb8xEt&?_G!w zHfUW)Z^YS;@Wt$R*EOZf^A!z$lJ@!vq=m#%)@TTHnyO*r=?Higq z$kVsT)a!gqSiGkPLcWdFD zrLwt07Jh_zf7vN?x5!68jd$1STMi$fZ99aA2=mugw(HiB|KgGv$*vev{5rP!5xHM~ z{SCE4bTpQjr!Ak+X>I5rFd~#<&Ojc5#XvvhL)n{eZRzLkgAY2$^1Q>Z^oyUsb|3^& z>YlNL{+a*yU^AW*@p<@3fn)FJo_6rwe6$PJY5^b;1bS=$+;-96opo;vG>;Hgu3Tx` z0T;gn-C4!AULb;>6OVVr58J@6ZP7yw{Qe>GZN%iaq93#w;)ne7ix@KAc!0tD&wRsr zj&bF7DCSU*4K=c3H~a-PuMG}9MC(WWqP*xc_Iue&qL(o^SB=A8MlJ8VqeJBO{3>4q z<3mK7bsw_7`sypzJ2v4lBHg1`Y&qWh*Xt+BY`W?I%HS+|)wx@9b4e+t;oV%I(uqVp#H{s(^WV8W%%mVR>c@zawqf#nJAq+U`Lv;6= z)_wSH)-@~C2LCRH=%Y)7#&1HAxfZ>`Kh~PeuYgES!C_-wQ%go-)={z|_rr3n0qKwP z&cC3$Ntd#6&(V`qQ&}dW<3tUdfH8|8k86J7~q3-4zZ|v6Jd1v?V z{r7eIN|{F-ez-U2{G~Y-SvV0d;M73`I@%v~0@VZ-fn+H6Vo06(jyh`d=FQ#Xk3G`u zF9Sa6m}9$Rk2}sAI~JxKG;pwhnfb>b)$7=j%}(^77K+Z8%*VQ*pA;6d6t?Y?vYKKy62vLvODX-k95Z#du*Kg zYVxBVC+q2M@d;hT>8XD}M}6pZ;lcNrr=RYgeex-%4>|1c?zj_AuwAl1VgtxR zhaZG9(K24?4>nk#EismEXfS0sYIt$bfWv;^zWcgo9^2R*a?~;1ajQ=Bc->D<_H9ih z^exVtam9v^bSySROJ&eR?<_c3HbI|0W}&h|G@ezTuD|)_ZkrY|t7Pv-9es=ssn9o* zQEDW|PuN7-f7DuM65sNdcJTwSjI}2of4qC(&O5Ymk5lJE4ms3|QCbd70=h*;0+S%+ zp48Q!)>F~HnjknWDkU3>0w!a0^Vsb-cc)+R37u*m=XPONiDz4utpu;Iea4wsns3JD zFTKFuiy)7^jjE!|PapV*yt#+ls#TFk*ejE}a;?@3lK3}kcgWnv}vm_QfGvp~%W8T}w5 zi@c|ve6riT;h}ELsb_R2o_L~t9JZSiy2R>bqz~vnWVcn?^yyjmuHo?En z^iy6itUc}Y?x-V=w2rg?(1jPKqUggD^lIvbJ~`T=He&D0ANwD8fYZ-C_iXp{Q%`j- zz4&~0knCm6x>J1c!yzO#PTvxkrLcEoW=?dwXp}zao8_5r?n%sK+&)Hr{uybhWZO@|a_~ z!=-l?qWFRIOHlOq5nby`x@Ufa4*dgt`%ck=6E?$P4u5KF)5eYRWsi5qtUAGSH+=D5 zj30Di*@}E<-g+S%uJt5&V@-1NE*X`z~% zbx6_A*ttkJ(EjlKbcss!!Ct(%60c`uGmk&|sO;~p?jYIY2`8Q09ioRc_!@ku=?KSb z?m{zZkC&+hY80M=d2c^G$k?Ls^oVTcS;>ztIP%D&?GM=8alqrvp8Og1iJ!N9zzg}A zqZH5w{+u@0>xntOWaMqq>vUt?Lfb98MkDWxmM{MZWOKAv5p`tdb9kTZA!g%4-YJ1M|ub05tIp^eqQp_sZ8i|HNb6d6!)w z-D`f5-J;LXtl*`e@G;n&#-sF>dKLOxRkxq!bHca2_fOr`U;JWs(_}P|IX|$ixQXNp0%>{`bFY;4SUWKKpDhaCyRuV`I~Y9-s>W9AFUQ z>1;eTVZpPnoF##i;B+(?I1}i@a(*}8ctdxJWIs~_oYP7+bu1WgB!nE`9>^4+Z1F@R zSw}I!FsjFi@xd+zD()93Q5uIkpUUhM^#Cm89FRoO93ZPFQukZGuA-1fmVO0Z6%^L5M>ho)X3rIB;k;H-T_|o3xmC zL<@A}I9fVC?X*)pp3ocmSW%vmc)XS|3r%$3zs0T?d#63MZfNsM()-xD!7Iz$E(dQ3q({=kTx7dHJ zUA;z!Ux)d&1Ea;ZBHChM9*S(IOtx_d6^Cfh2gvp>A4p8#iNYN^2zW?`4HsQ@L)V%wh%pXas!wVf80tn zxP2;%Fy1AScga0v+W7@$n}f z?;g>ZdRji=Xw7>UTyQ~mq-;NZqiLHynvz`vCzKz?p1j3FLU->ncc_2)3mME$4`{>n z=my5?+ui9}Gfm~0?e?9oXgF4)N z&NnDdlip9(K?a9^dB|hCFKVX!4n!z{2wo+&E|un~9Iy{=*wEd2(~UkfVY9nt&6@7W zBjS*UzQI06^R;vyV%tB1k1qzs?NA=OWPas9f!FwMyX(&GA^G?-&OEa_;e=H_T%%v0 zX<4L?6cmxsQ)z*6%BwmcWDTnDq7k1VJw5xv^W6~a!z~Hs?tAXNw|n)q zSGy}U|D7Pa$LD9_xDzMj*Zy-{-rho0%3{+1Uj7U`>AJejVH~S0AN=JM8{w9S$;SN!Eq6?FYARa^@5}C zeS1pd^)($D-L?L1(Z8oVTn`}DtXb2oU9-;XCVuUohkCRj`XK(iATpzF)}pp~(Zsgn zkSErx^ewjc%=6E8x7>Pb_Ydt6R*UutC!Ao}IW&ET+cDBf%1Rq%4W0|-&mMX7vF>kw z`))h8wzb zHTRvecCFV1Ub7XrS>;VQcZZb6Uz=dVdy{m-f%R2aUFo%Of6yQpua7Va{YOf4p5s0J zFLXoqtT)0}vNoX&PwC+6Z`y|(bm$@7<(FNi!{kG~p0uGAx+Y%PNXqFLe)AR}!d!6iCEbPRooipgtz5>Rc@!MaqoM&D>;=1F4HkA@UR{;0b4|qjhfW^V z;Tr3w3-rKq?dp@opM&sv-w`@V`P>Y(3*DrCkU2lhuiPwuQhLD;Kl#KHTCX0_U8;52 zamO6(+k)8qGTD`8eYb(}>h*})WZx*e_92^M_%e5RZKL_ahmJb9e0bx=?m<0>r+?W` zJu9F5|NhVa*?sHV-|mh%{v@=Z4*{+2xnZXd8tSIM!{%4cjLng+cS*nR%K6-V*InH; zfB3y`GjO%!(u*(FKtIJNLGQ>R;y`R{WzzS_DmII9(XVuETjxuGL4~7Q!4nY*?ZdLt@m0F<}JHpueJf?u8e+-(Pc0 z_rSe(cb8oD(e4yEsAF`qfrXMMO(ro7hIq1W@%)wML7Zu~r5LlFnigvtAAO|z#V>y8 zC&ZU)!aPxnibH*MX_-%@Sr{Ux(8l7Nw3&Rp*%coghIy%N&_}*IbqMgApa0AQ{L+gq z@<}L9d)PGblnTPJiAKjEDc`7_ui)(*C7yVgNSNes6xZGG_wI)4uj{__wXbVJKGU1R z9AwbL(IAH%90RTn;ted+-8Z5O9L|SD?9~x zO}Jm-368HZ%9*d!wJ>8wi;2H$GTtQTdJKmcx=C{CDW`M?>5zv$#kLs#oDlOA2AyKB z95_(N!pDo@Wh^|GdvV3BBVKJdR8NaHN#DQt`OmvIbc#}`)T!F~h6risq7OEc z&|_lcV?DVIELgRO*iYBdi%qlP{quF#cX!-!Q}=~0eyKY{o4Pz`0FPih6dp8b1I&UW z-4GiUY!F?0Q=>9$4EQIsxc$xVerLF^e&s9OD(S`chs?6QqywLnGq{?K<%OTPdNYmR zp>MDWZU{Z_&_mrHME}gQ&gnk&iH~=ONiSjFXe9hLeB8JA1o7pd0qW*wjRkM`Kp#K+ znkM9DpM6%kU*FxS#n#nd{z`Z0M?T`kiWjzOW5^2^Bvwm;B?WT={sJ9&v#iC)b9$=4 zLgn_`ZtGstX6372|GEz{&{@(q5s`+hCe3~WYBtuN796q}7<1T(6zB$D^RPD4_i6FZ z;oZrnoZ5Zz6QAgg*BtVe=0^LgGLAg271=!pLPWd>$!ELt$AX2YyKI;_Ji0>%;ScB# zpAFtcmt5LiqVdXga_D38%z?C-1u=B+uf6??9y&&D?A3}ZW!U|rn;$d%C$;%H@W7Qi z_&r^lqO;CA zTe^{5N{7gg48YUB=mhy~H&BryKe)a3$=uq?Z?o*%olnzW!Fl~HRKDqaT zSmd!K0^^sEyqU3C6z9PXeFF^s=YBmv`SFi_q=y8jbsxX-%D73QcKS6_WFC{yWT$>1 zI(o$KvthmY*4w&2{qDEjm%j0h?&1qC@M||dB$GV?=e{gB&O==~x4sn7HtY(&Nc*sN z`h?dVpVk8XdTr{M@4g}W%uo0N?A-x64wKqJIU(S@Hj};ZV2M}b9+O>O`=>v3t4=tn z`8PI*uK;#|y%Qdpc1JI4;)a(ELx9(Q0nYcB~SUp>ZFx+tR?P1B!cw~I? za3JTOw4K~I(g*l`XtTk`|8TQlvvl)Et+k)m;pW+8?&g8y{+c8GS|#i3qVJJ}q5rfK z`XYkL-7a(=f0p##2Oj8tskOoJqIr?#4{qSD)VhOp1-=X&^I?reJK%+E!GUp#Z}Tyq zS>zbT?y(^b@qhP=Uv!`R>}R|4bU?+;EaqX_PhaT4Bgm6l5e1;#MMJHFb#ok&iB8j8}qQ)`Pcuv|hdT_rL2tqq+N& zdML^32lxpeG*mKzhkd{Z+h-rZVFNnm^)wz1@nFnzncDcg=D*GI1^3;1pVH5DpZe_Q zybnPR`V?WK-;k0taRl0(pMXhN&6U#mo3iH(TF2ijU$9Bz^%&XB=hU~WwMTnh2dEr8 zvM%LzZ@l`i{fBU{C;FXsAOk+0wG4+BzA>n=x=jA&MIDl?*Sg@YyVt9KU(rVoJT~6d z{XhTT|F1s&PIu&SCrHq=k4o@tz#bGY>OsS{tuhWR5O6RyG^RDh%EzUP@ z+UP5EpZ)Zwx^v~AxE{@QG#s4=hhjSiMW{867Jb?vFnR?#kcos_1+S^IuhU7~pRV~s zcZ3GVSz6?tt0%n2$%(LWVWH)TM-IXhjwhX<@4=b0-Jx)0(qLn>)bGx5wdH5O`jsY! z_1zU$eN2ZKr~8LGSgf!aqzx<`yp0R-lne8KQeR{{(U+V8?c&`#p0Ymp@Wb8rfA9kv zD+|yyYj{d}xZ4+3i(+B}he;jXlFkW~k;5V-d8W=->@d09q)F$;qJPOpKiYjvPcDw; zsf#wJ)UhxHJ{Lde*zH#o;^x3pT-xLbPy>m{jjPx!v54A-9 zLyv)m-eWS1MHWgiFA=353CM#p=0uqoN6)1EtKa;_@78_qyWj0jJ7t~w9tX-H2^*Fe zbjN5jod-MM`Q`!>r&`a6 zJNS0qgez z?tI$?zPIY+`BqJuypy`_^wYX4wAf-}!~zdkzdI>&Xt zXi%R#_4G5{pJg)-=@qKuR;|)4o^v#2&-9Z<#w&+ANXAVh^4R+UD|7`B`6Vmwk~29% zm%n1cbx!P%g9@Hdu&Mk0_rKq5(Z=_}k6hH9u7k%DPdLGPj8{M8_C<%_&9#(4zp{WJ zu)(Qst1yWpKQLU`<*CB&e)%i=fsg2lAy4WK)9F7pfWCnv;9I~$U-U73$;Os4k0HT= zlLralu_*uTAOG0hEPwWmZ+*)?lEYNS4z#gJzq2b@IkdvAEjtY1r#!p}K4?JqYAfx5 zCpQj$`m>)I?mId$KUsRAj*xx@`3TU;4|(&UY2p)otg)vBoF{+T9KTy}_r3S}kmr2q zBZEV0?6sE@naw4>?6smhs?v~!I&_3BJ@@Q$8dDp)8})RWC$Qi9r+<>}&(@-b z_d>ZLqyQZe$4cm1e1d&Ja%4^_2MsLHkc3w!_9=P8(?lwI1aJN?T$JL+zf^2e? z-^-4J2HB%zPrArvvC*0S_f0_e;?L+p_q>Y4{B+ArH+T2yF#iqBwU>VM^6sk3ujmfd zwO|(i9M<7W>0b`DY?q?T0?+m;`=$>V5%d8YCFWN)y6AGFHd{AJ=TB%cxALHan?yuUsd{RF0932cEqo=(1 zitvqUFFKZ7Ry2_UeEL3cNfe?Zj!;=FGQT{!`SI>YKmKv|hWz3eufDolqZ=9cb>?2| z5*qkQ^kKOadtD?N9s}6Acp|s^!2P22gvL90ZVUeBfBvVRN`FD}A9=(PUf9x?=yFE_ z?FFBMhU;|T`x|Y%z9oCVQk!Xf6#9&@7@IoVp5$%=B`lt48~wxvpLGSc!|zr+uIu&J z{OMZHcmMi7{zrGV4yT~aXTd?tJS#{~JoV$1m5sX5_j~p2Nvqd%|NNcr>Iv^LdcE}@ zzQT{r(Vxet+KaEG-L^}~=Lak5n>c8Q+k?C|u~Ig}O^kcBDO#_^{|3$BAN$m&yHD%T z^k5yb@oI()$8@p{*$a8V;JoC`@`OXT*aHW5tcN$~Fa!Rd(Z=XP**xQtSDok^+k)(v zejtG7!)U?S-Zh??Pu)h^Nm@3;YgFrX;CSmTH+$@_(rv+uxf!Pzd(XKcXqxnxf5A_W z)hT1Wi8cofY>fW&XC2(>u;F;k-RGWrUU#0>+W2{Hli+I@ORVYGNTP4bpn=^JTLzVn z4jSZ}{0`e~~NLn98XuGQ_Mpa1wr-RHmb`J4sV4_q_A)Ph5can zv9>`Dq!1Vq+5V7=c5Qm>(e8&j)I35@>%a5OZ|SN1G13XYNdmB7CWvp1RC>ug{S94y z(~8%_Z`b_vTlMXiwXXT1HtW1r`Krc~$7WFs@QFte@}pP!gLMXn4IJRI4zphs4{r57 zqKCD2i9WAxe(@_`?LKnB`83dQ)rN$KOi4)$KCgI z4{5J(?D4C*ujv8JDQnjF!OE7`Ue^OR%|+#~0sFLnlV8XF;l^za=Gx`TbGX3mpe3^R zPse4U&hv3u)HoZmLf&bg{c}5j_b_?V^+!F4;@#%swV^og zyz{$rbozg&p1^YOm9HRi(7<65PkNYOuzAKWycnNqgjTw7m6nNzA3Hoy3!X=%_wUQz zIcWIEMY=iVgN75`Hykuz_lzmV3AR8$FUZX|^?Z<>&0Odz#w&+dH{EipHb(!aJ55)O zFVbRyLktcE3E(+k56GuLe^Bm&2H6mcOSeHX5ZJIG2mDwl|K<>jx|2w|M?O3*#`-q-z1y176HJYV_3)qbr6UW_Ln zj3BdUT4u>+-HJARutEE>s$DEDSg6H8!&APw#v#ntzomn_{-7Zivc8sEWTyoYiqFlg zM=yQM#v^`{gtqcjgc}Vv=?Xua)9-%odwx>K+<{G6KV`Avc|$fy@1k4l7d6S=*_;#n zBuMZpwK#uW`1fh!a+j{~;}h2E2G7-Bs1F+AJy`UNcX3}T7CA(-{+*^oH2JZ*Ez&)U z7BxZ`yd#uJOWOZ2||Rr2!(s_rcaN4fdEDF#H4kZhIA3erLvqyXpg2`ZoxQ zFMD{?M!(wk)Z?3V3*oTtqnCfQJ5L7!`>EbH4$y&giK!qkk~0UOGqLH*J;vx~>7ELH z+?O$Y^DVb@zy8@zyMuLzai->OKC9$wcyfg=B0v*cvGR~!uT#0y*Z+#??N z(G~IsZ|Di^FLYbtzkmPxIA}OWH;|4!&W8}bk}Dk`7eW&8z$5qtPvo~kh-iyqG_;TU z8K1<#-4Aro@VYi&SC@kZek%Z7^V$aJdEiGn6_P%n9}AKfA5ESy;5l4n+(!J*|MkCg zL+I@8>d$_rJL>QwOdI;1qoBFK01tG>{PI_grC-S(d|PwtRoZw_&X2A!Z-ifv$l}FX z0{w$)pCF#J$8t(Z_#EKT34z}^!q@yk2RzTn-~ao6{D)s1+$!4eU1(tK@$B)@scE`!3@(1N@mSCfJp}jUHB!Xkss{JMinQ7Y-~3 z4ZQNfcx7|(DUH?7ee#n&Kzc(@9bjAKgmQctYXuHr?v~Bmdh0EoJ6GvO!$lWg zR1O;0w2fY!Kr-7T3GpGFo5{YMD(YnK`>#Au8>5%IKkK0quR5(-b;6t*4gC2*Y!f@e z*I=VQEL7WK!yT`M+J?*!-_I*%`h6vB$~Vi${8R^D&*)J3!izX)&_eU3(E zdt%;za`IrEO5nFv@SQ#YSB#9zS5URxC`LAHY|~?pbwB*!5A_uN*zS8;8*o#TxsQ3f zbQNfG1LKHN#g0lE-;8d!wZH=uHq^hb%AmU4B#L4f&D>wbsTDb36HH-QxL%4gl7zUemoMAH+j)_HE0hKRk`+5Amh#^gHxC zKZ(BQCc$~trt!oB!sp9D!yU}s@@xNi^%WhKJk@>a+u!ZJs#^ezKy$y)haZ2Eq@uq< zeq`KJgLG50yb~?hzLlpVQm_<)qmhO~H>|sK%VEGToSzoqEaa}2_z_|ZM>e>k74~v*MT2;@c!;HJuO>;711Z&!W;BeBtn3(Vw*`y7lIpx^K#XoTo*i>FU(cr>fF31D^hj z1y}y%f*d@dBVcffw2zGoflcOSUDy5fZ-3`W;GeblU$=U-7x8Rtas$I(`>;Kzz0iq` zc3fL#k;FoRaux#UgarjR8lKb>m;3I2pu17mJI~jt{}*-8z=koLYdAN4SgJp0P#@!v z(F1h6`O_kotDH2Dr#pGjz>S6t8y@cN)(JY-FTbo4Vh(vwAWjzt3Jvnu2Q-nDGI+2# z;3OBFF-eAgwtLel(C#5^SZ>n+(uM~f==RqF{foLf%0UA-JXwGi_TsiPQ53n^%+ZG| z9O+l!Q|~xNHtReUxm7m9yM}M+-S|_^IHS8#w=s@C?s#uxtRMPRgmAKGgj-AmbOJBN z4~_ETSuuGw?FVY?Kdplnu1DT;=j}RZIMMH@@>JvyE%IL1#)yR+PySi#a_tWKOti#t za3VWpl92pdBj@Ql^!ZhGexPcD#?y~}_#+=Q@Kl6@!4p?;qd^-ZA2e{4Tt8^({?a>t z!nZAz@z3jD*f1y0y!%Rj(7!CA;lquFUubi&cI_H15HIv1j(0v;RK+4%3Ko3o7<+VI ziXS$@Vjw4c`rdv(dW1fk+~4U&!wq^e!i33q;<`Eql8gu2B7KQWC8X`Z4|;hZVY!uu z7kv$Vbk9=}o^&%|=0OAXwr$1Guw6D97Fu3w&@ zrz0%F*?d8VHeloCp*a4D82X2}7^0K6HHP`C6H6sK2ZQ{G*B!Ur(LE?095nFi#1(qQ z?_g~VUe!h$9|kgX)7Rr?&^xw*&T`D!A85Bh-ZyDvuN&mQuGeAgv)VWwe&i8)b>b3V z^=7`pw$nG|G6EU>5mzPjg&olh;`pFT#w*RbSvvo{ZmsdU;A!$Tr<`(%9}@@9h5i_kZZF({0MjKlU;I1`@Aj;OA_2!u69z z`cJ~xQk1an(RY;463dFNIB4)Y>$*zMRqvntpP%|ic|Y@+&-z9K?V^47VUX}M_%r)^ z(P5qBLpAY6JseDX(r%WJtN1SK+H#|uq8-KFfSIoRn{>$>@stko zuhE*1ar}1izLj9*iT;Ba+n*J=8DQQLY_n6o;DlRW|FSxuSlDZn2^Ve#H4BI`lnB zF>3*6L%d*Vb)fYs4<%@j z?OhKQ&@aA`xduC89YcF82lk~ogMOtCR%jj1YbzYw{Y>`Ak7b_!kqdp8&tbp;n!9)? zslj0y(FO}QE^J>>65>l>?n7rhnf~z)f8blamubz%%_$BVkTqVF5U^xSpJv-p+uh%k zqeFc>_Dov7K)4+EVn@98_{*RCxciI_r`YWF2MwyTpFx;fx#XdfWp$dm68H;1&&w`< z_Um7F8+8-rU;pJ_eWSs+z=%HcrVkoKL!vs+4tyqKm%y0E_b@K#SK0wf{LLfM{ZD@K z6aC=*aoxAS@%8SQBlW7Rd>DPm=t&Vxh_51RmeaR{h&Aryi)omD7+q^#UVFS&4^h7G z^>21x`1GfIqak0Nus##F$mBMe;D{#D#vv%LCNQ3s=(Yr}PHfivx;_pXGg}n49`q)>$`NcuQ!}^`IyLHIG!vcPs^lQ2?vF_y6-K!c4 zTSR|f*$1m&8HXRb;afdsMGZQviBT1Q&h;&Sv<8w4*!&Cn-6?)U=q^3P=EopkmA;>P z;<4^a-~FfVD>`U6T0i6(dXD)33HQ{n^9K#mqWa5*Zg-A-p;-!-NkMYV{HpZdbX}Ui zKC!}Ml_af_cbr?@Z*|d0>D}{$Ch(=EF^|7<-471`q*0pQ-CHtd&Eeb34RZe0xx2L2;4&sbmiIHn?aJq%#!zdrv5C;tyEU!**&5eTw zHqUt)Y&p?0d?cs`0|P=IWVQ1v<(yuEODBMTi{7>W%`bl0U38fipqF0et71$B$b%yy zpbN_>`o#L8(E72wO6$Li*_gtQR~%l`K?tX~x9Fhfd;jt;-38J;lOEUinLv;)HWxfW zW)m8xs_+0m7E~bzaLBpDz-24~P~Ee-{=|m&UOgFkTu$)wItaK@PmDP5;<{LDn2YYA?*F18 z$Hc_IlLy+!CW}QLZD5jM;zFkni#7)h8+D`Mz=IF~uUPb!(&wtkcMgza4z=DE5hv-eAY?qk+MNjA%-NFdn z(&ubk{Ns(P=U9W+HK30TaYKlMhIQ-K>AmI)yVa{#`${wR%R92@6T3s7(DOlq=(8!N zjHl`FWFp3HX%D>F*l}?8yKDc{-Jt8KpVt#o4jTBya29DCYSMomH=+xoH`vlIa$%E< zRoW)9hNBaZ3z--X{NU4%bxoZG#J4pepLD`1k7e+%Jz~=pJ^z<3@}L2oW9PuIn5LXE zHl^@jVSE2W4|c!()vvo#Ws9Hx)TecOia*aJV8POEd&e%lfJsl@ zl{#o(@ynHd#*ybf#Vn?=N$e1v^K?iBwjJlykNgIK4;r+Q#!o!7aZ~pfJ;i)Ri+}!t z3su#Q8)HEY*; z?gkG1GUnNo1T}F`**-Er+5{i$#=J2zRl|jOg=@<%tNnlc^R?ZLI=DMeWA#kQ%@b07 z%jN%4_uc_pRac_-qIVFf0xDfVKFQn|DFQ1{)#Mz8Fv*U&5U%;8}6#dDFYXLpgs)1YqwsOqkaOijb zU0%g}2#~UZ?62UVh_K;_P3bV z_MN-LWjO1tId#eE^U{lH%Z@SO17?xw-zo2rL2ic6DJ!CY_6Maim%5Zh=;w4M+^tCzI2Fk>X z2$~uY-w!XCJu6(+H^@GGmRGisAMMZPpefq&U0X~z+HAVk9M(j{2Jo7TTEdR;Jj8I#hgQkQF@JQ+4!11A^TK8r~uM zNFQx4w6z(YUA|;tT>Obo#>L3wW^IoK58#LA`A2kqY_Gpdpdm-^OnLb(?SNEMu8^iw zQJ)zTQ9AQcoas=XaYpoF>x6EK#UQJJOdSa?RiQYQXv@n9D_?$}QGJCU!e3$?Nd zM;T~1JS*@U#kJ7OHXIjM7CiROD6xX13^qs<{#P(ZmGFSb>{jA)a&`35F~ayay4?du zx?`t~xpl&Q*;()gAU)m+F8(vbwBcxMrs&1L__8#>U_zCiuOg%2Y0__M{6$8CzgcNl zEF{wc??J^`^mF@z^33!Q@ zgjWZ|TmQ_Qw(Y8NDY-j5ml`!*gxY)8WQK=%2`(N zufp)GsHlk9(9851-r0|pQJuu=l{g9^B`^OxU2Bf3FR&gV}k_J#3p!V z%CxC5b<%qoXz0imfzxnY+#+B@Ix9L~W-%BXR14+&GWsIWz<2fx9ne|!;g~I6cNm89 z>UHa5B*yTIAK$>$T>^iSr252(S0Q_FA0?N7ckoc%kHC~N0 zw<5iQ@w^@9)a)i#NDVZ2l1m~&T%cIQy_W`(c#u|AUS9H(^WaL3^WZCua2_(y@B)E` zZpUNnIcch{j0lmLH z_RSbDpr~Wxk*?xH#Z~Z~N){zfKhD9y3|&P>;v8t zM^)nxe+CwGxReL-tFm5t*P;7>cBi~QnLxvW=s>2#x#t>aXp@0p=SR6>d-kHS<$r~l z2Brksxu_b0I<>lnGw;fJSB|F|Xuy!OIF*40tA-!e$QljXvrTDD9@Y8vQZ^_nrR(az zEIyoPx5G&L8E8OOnT0eDm`B5}E0LEi*$40W-p6+9p2mA_oq(1zfF#~&JA*Rf!~giA z0AC$r%f(S}$~5QR3?608L{Bkk=mytCdRcIZX?zHc|Zyi{V7gV-nAJPj~fs?{HbUwt7`_rX+VfL<47yI0-d2{3S z;jdGNpnVo3v{-R2ns9&0*KGBF{*SnGB+{^Y?rrcg8rxv-&>?XenJQ*uD8uC+`&Z6O zpYpFSapINm@<-vM6uLegNN}YrkSABKT@&NTgjqwN;SzLrnd+UiUNrNO{}$NhC)zJR zI|UgCAP}-0gMQhvf!B)rRN~(Vw zj1nh00n)tmzMieT6_pj4)nJ->-~Rn#Aho#~Lr>OdC;|-yYzE~HB!gzR2l3-y!d|`{ zOrAypA6m%SjDy)9&VVQP#>F^|$D>E~1B2N~@`gciX(QzibfOKSZmwC~lU@parF@YF z?W4@#k$@^C3ctKs>eG}hKFCEk2d}EHiodJyFYc8!W+NJC z7(0GkOeH{NG05&@+VsGVZ`rJQ!n$uyQNY=wE}ds#b}zoYs2d%WHjtM=dB@=PxGa*# z=LI;7FS1S9trN!)2=K%V^{W{TE*K&-65fL_f5aHF@k9RcmeSUpF?&vKw`oeIne`KTW^tYiN__S^<)<~f)b;9fzq9D?c(UzAvQ_JJ3Vfcxs=Ara z>TczubM584{*NziR!%D4ETTPf%$Qis2@6ATcDoX2kXA~&w7gHMOXL`pb*zr(qYE-K#xjz)u<%wo=9>VCR-Jo5tprV4J!c%iQ z^o5sD*p_S(=Olypw$DrH^=I8w3`f7C#G8wm$_#ai^lnCjiv+XLf73pgL2ZnA(Xv(R zER@-~LxJ(*)_L;tybdz>C?J6tPvDLu8wqCu%n&!!O6W)D0 zCQhOr8vL?p+ZF;1i{kQ|Zpp05!&D}i;oy%d@6E?W1|~W@&`^tW4(RyU+Pb9Mg8m`2H{r3+bK=TzSd?kho8#gg zBIxcZx2RD@@OZ{_YTGRgl)`Yy{v1Dsl4Exc%YMa=ed!>{pc)N}h;V!AgsG|q8Z5Sz zfdH9UiZt7I7G!W&EwVoZhce^i-5Av6s)e0&RamrVdEHzp>-@u ze=mliG*iF|Fgzm;{M)NA_CXJD_+{dTI}Gk5JmAbg!!(SQY1C=hPFr0tp8H{FwP{PB z0ebT6V2hOQ+h^8__;lP*ys*|RoJ0*g0|WJ-N8dGaAo{4^q;af*pT>?GpDVB}D86Z0 zu!Sshm2r>!3Csz%ZK{BHRCt-^Oatd#8BhbGt2!?R!cPR62nza|jf^oeZ`$0kY{}5U z@VG^d35|ku=A<;|lztL5B8hpn#k{)W;{JGz^XHy0GKLGdK#|_E#N30s4d`3o9x(>tf^*92tp`_&)M%P`?4u3%nf8 zIq}kk^*{>#!ypE>4AC(j4LBXf8t_eZ=7S+6&l%KkjC*mW9hb7oqjaAhHY_%6-x`;b zZfy1xqfQ)p#4uRNAVtdJL--0n)48IVq#=2_hAXQ&Nc?B!l-Xle$v5EJ1=&7`>@2rw z$@8VG6aLb{^4UV}5O7O*ptB`i0<&}m+!{n~bu#F3Kd zZfTIWk~f`Ckx>kf=`7|^I(2R&tUb`M!P2!DaZ7QeXUzBzeC?yKAAttw#&+G>P|h8Q zN}9=L`A3tcB&?$GKR%aADSH7|ecq19$R?V-*jj9Fsom zuLwBsheOD**g2o!g$yz<24$LohWDV!1sKte@i>mlvvx>R0+7}uvAvv6+EA`~d0*1E zztNs6M9M9LEWWE1bd02V19v0X&a(piwl;3R^L?@n7Kk>Ydm19s2I5uWB zc}}>UTX7^mnr{5oJ8x4XYC2f~ojK`>jEN%&46;a|EYRW3OC-^XFcx|XJxBY_16)+# zk2`cM_apE2i9Xu**fRqSn+cv;gQqKfm`SOl>motwI}joNmBAQ$QU_&9Ex0ZXQ0GIO z2){OuG~{u4FTea!bn4P2iwQSpF1nlJLR%{v84gN zanr_lhx!;grGo~a8=gpIK~8y9J!c?8T`RvzX9laB2j{fxOB^e|ghATT9&;RK)mfuq zEN#0=f7MmgJVB3$b7A&*i9wq}{?VrJIrWpe&hZ0g)jTtoT#iE++)kIpmKQ9D@z6~h zoM;QQS^Rq|GT(+>WDxf*GTEo?J1zs(^0$Eo@#rZ_${g`w|H|uitQ>oc?ra>R1qoviTx(yOn;s+G(0 zh{$8mBL*6DN}VHvJV`UO&Fz4u9RSRHZ@(-1_X2`ZDx=G`tVBG%)8P{{jPj85ahNy<*BqUf2ad3t~!c9yG7$O&_G~N zyrmxD-hv-xA#EHQWe|=-eiPN%7e5q#%e#J8z+|AojD{r(E8}8p;clI~WT3&hu`Qo1 z<$J-yj$aukkJ(2tkK)L73s_tT+zp@X$YT~?Le{i^kIZOjga0J2`n&;C@tl5$vXx7^ zckDLi_?2mXPB{22Wd=5f^_7+*3v&A)S*)jln|^1U&Z&J3^Z9Hao-AdIyroWr>~el} z-o3})rIXa%z@X&bwa3gUGa44<$qm*sk}#rzgoJoV5)7SMic(mOHny-5TbSX{-HTeW&cTts&GMV#W-ymecl zAK!~PsG5QQzhe*&&N{DsINK76hCq$l5Tv-_`o7KM_`=6`AMLGU_ge%8>`P&EBy{Dkq*2;w*fL!}SVM60H{ zXVsJ|vl&XK&Uq883|K%QGF?W?=v$^$kQi;%kT9)k9m4gs5wFKwBIurNZz`92!5bhz zH0EvBZ4!>a-|qHEfq zLQuobcKzM9oo`o6{7pDCdYvnoQX@g*-#~*TcFDyTXGTLh$Mh{;Qqh2aaW3rAiVh4v zWP642?5dr|ClyAJ_n8HwBRU^rMI*Wg4(U*e*R>=F<39de<+eQqM`8zb0fh6W;#6`M zf`y4snw6*u#ji2ClC;rzWF5>~FfWyJe;f;soO7I}k=3tLFOQ$I0ICj>1yMIM*E-wQ ziBQ0+xb`TV925MMm1^nV?>rLKeV!Hb=7Zk`8R5=ikUod7Qn3kpx$2ek2yVr(#)I@J z-I(p+XB|47bXSnw*Ztv#GvdRk(=%06W#9j-{&5sSR$kIrv5&nNTs3Q>ylQJ4gLB%~ z0C&Hu$BfmW-DdE*8BF4IKmFFk*jkBE?lDlNkvD60I9m`pL-U$sda4GiZ5XPk zHyj;#q)@mZFC)m@kTRuq4d}hL*)MJpqTp-2IwF~ zF2_U@jA0#%s?b-`qd|tcYGUSj2SEc3pqh-o8cvFax}cX1w~AUvOuDs3gQ=+-c;58;}yZylN=~SOQQqy=oUFoD^VWE ztEn?+N13XeQMVQHjXCD;LrF=eFtrdzjd$LU37#hApofyvqgNR&mMMq|L&qpz*h-l1cs=*sJ8#^8w@%6RcEY|^+oLcFN6 z)Iai1t!k`n(Y|Aphozmp+%N4&LyMO!jp45i&uv-;8VrOh!==I0(V#-7#W_ePoA&Kf zyt)leS~sIcdEw>B2jX3RH0{@P8le5RA(ywY$sC(g7vv}ZO@ zIuZ+TZ(+6G_TMCs(Y)Oe;ZeP<$+j^|Lw#xHqHVeT(r3k$K?ZT56Qh$W3=J5s z{OorSYT6&`&`%W=6*v}iVTmgi@9LuS%^q5?pn??gw`1vo%Cy7I8GLRWN6=a+vT^HXp26;Lu>9?K zrE$YU)ekVgFu(dS`HD6(;0Q0|3M_V+^`boaM|rRrnRe9C?K4Z(qY!g3V`~v;kS0@3 zf>!H*sk78y+8EkQzLYa`p8VzbR*w6U?dZ0Zoyhfr!8OJ%ohm1j z{+vE(hc=~A<(`=-$}nyA%tqz63g+~67WF)J!lJO9kiiCIT_u)pl$9B9NS!8cp*OUF zk=fe3+Q`a47rVr{ysWJ!>=vRnaQ7!N`pjtZnBGpEI%T~E;nwLBFZBo_*rqbL$SlPs z=5J-Yet|Z;h2XWB$?v&XQ(w_7z|EC=$e?lLQCuO5J zLSBg+?~(UY&j5d3{O!2bvOx1Pvc@gkSFoseOy@4xM%Z4$#=X*cX43JHStH6dVKZP4 zDJ5;Ej^(opMSka2A>lCKy`Yk85`r)pXy6FSBU%wWf-kgl%_tLwgEc3ZD`kj*J>|On z6@jWk_X&q{V6fT+Lo<-FATs*b|Lq{Vfw4mK5d%? zw+sG0j73MsHh2Dfboca_L!AceDqVKb#nF+hxDCw5cJ6fxi1wLuE{(gepzO)O2srb5 z`%3zye__%`X@q`W&(?`|r?4HA0L)Hx!R{R_Y_ExnuDu5P>>?Jijs$Sv=J}8N_4f%h zhznlGr(_g~9OVp1bMWTHGPdlt^oK8UtgHzJi(#N7v@YD^?i!E6$M|0(dCe3`Cr z77HURSHhV%r_N_IbXCZnk2{UYk`Rw>-+?pkJLkSJ8BHTpW#Tge<8vAgNdUCvC2>n6 z3PIl$PzoxEVKdA$5oNrnvLbr0V&AGY$3sH&3L4=lEAMOU6a<`2rjVsGkU-D$sS#)N z*h__1Uh~9ox6hIZm_V45CQf=f}xsote(A{mWD7Gy<>lXdyV~7UEC*8f@cJ;!fTK^bC6K=O$NUohywY z>oinUR%Tnu0=JcDfcg@b8ZN0veCJhkfdR>!s-ql>az>e-@`?94z^-vxNxQ=C`S5Mq zw~s!3jwh(uJo&INe0bh=c&U+;f$Asw^LGvNC723V#VSm;0yf+ zy<5x108PqVo=+S*2HH&>0=$kPojBSO59wS$kNc?U;@<|Xbv_LCPMY*?tRARL(-jaiw8z_5chtThU`mSt#DF5O~crd500cb>@o1Hg~-g7 z*nwkI1{##fN$2pGjuj6JLiPvp6GzTT?fL|iq3NB_&^l7lXTeKLmo8@e)R9?bzIAiz zDSLqj!4K*>gqOT0{Fwioi!PT_43AFDb&~`j~%5`=d;=Jkr z8N~NF`9n?W+}fX%=(a(#({goPJqZnJ`YJ~a9yt!>=z_|M+=^tK92W_M+aFCOcU4s$ z(UG!UY0s54=TyDtIJ~rD3h4i=8*O_tMy}4ZLCq8To|=XCTttxO#0e-(-f|9g(v=Ho z5kMo-qL=VWk7mIcu(O_wvQU09(`GV3S?lhcPpWqZvdV->IVdklE9zq9Yz6_uKXjpU zt^*;hC^wX;I_}9|pikLgpuh_A9>ILr5iR4)v(Cx@z0RxcDXVi~hm~4s%nXx4Rw2hQ z^gR(oJ>d2n$18tGwep5zu~77)g^S7JSr)wrC?AK@*pPYI3oq|uUJV9RuY(-tyWKb? zW|dhSwIS`eQ)Ij(6)$oOSg!Jm^F- z4T&rD1=<@O$ee(`z0gwr2+ow9@`GCwm1UJUjGmBYu{!H09FMGN)A|T>_fE1J95-#! zUb%3kd=^*Y+IB4RE03nEL?_9Y_Tlda7G0U1gUu&Rb?MfflaYF5=9-HTI)q8%%mGl* zR}p9suc=QZDz2OxMnDMEb&CaSIa5R!YMq@I~df<$@rP82-_DKd!eIDKv zH|oHYU*JL-1PRy~MWDex48F;K@~*t0P4yvofB&tC(Thc;E}c7PfJA-}?hNjNheG~3 zTJ(4ouNC+~uF!^kIu3DHUIukG!LQ?Kdl7o%9I|gM@aY)k`;_D0N1IlDEPNBQ6$+c) z;G03mLg$)IQfx_;FT5Q8a-8)sBPpm)&}abLg{-@g{0eU6Ic1vqSl$v|aVyxhI@Cu{mSy%Z0f2?ze(vnqStvSB(?VAj@}LN2c)vJx{6#QQyAS_{zNIV2q%B}A z0~dU>HRTlp18bm{MI6s*fYX!4I(6uf_|q;(8WbtYEZUZi#BAai{J8+eO=;sPb6mJK zNZlA&<~SEGU7Gb^7FAT{(Z~bN?3de0Hq)02EcK)<;4bDs-w~Mx&7?g|`{F16;e))9 zfd=Nnqp7zb`}JMjBDaTe?Ld|+o;@YL@ckdh-+F(_n%-b4&Ogo4@(D#zNvRBVH(@=Z_q;jND#)5#K_eqUZbBOE^8f>$dA1d4G3D-)aeyTq?>dzE+>J}<{CKIRJ?sY!w-}`FA414w*NP4qR+q54q z=i1d3G!0HX1_6JU&-%M<_!1Z8%fB6aIp4x6UOmt!$HTi<`K-U!;Q>fLw$ZWUln4D@ z`m{g!MYzg7`1lv?3zxr@xN&|$DIM)pTD(|WK(QyigzxkCg`tCi#Uw$u4;;=FQ zy6(A_r|eU>n(;&9hOG9X;I?cZ5I z$N3WvB`m_~I2?~K``I>?Rb~`tfdi1Bx>_&0-$yDY#=(@vRz;HA&!LCwlZXhLfpcA(tAml(v)zC zQ{O#+Q-f(M^1$zG%Q2RC6EEeW;FXM`?MXO*YLJ2;#E1%e%H7bjseEzt{tpcc~8}gw``;QPCaD+ za4W{S_$ucmvrYJW8?+*=XFt4q*}s1~ZpZAq^JpL9L7WP|!CBLQJz{emG%rm{Pvx^Y z|KLccZz~3s__vK5J5GVtQ0)^Ii@)Ny)W35WOAp>d7YUAtL%rg7mEF6T`=3Xji7FTQ-n zmwQ|dsO^F_#FsD%m!EB;93Sz?43KSSVr{1$KbW0hCXx3$9`E<%@4_hT&6_sP;G%{9 zw(s)SqJ7)-8T%2w1~^F?*4u#p(0=_*oJkK}&aE=l=M6a+G~ESHNRPtdczqWJ$Lw={ z*N`u@k9Snz#(T=kw!}qw36p)c0G@_8Q96|ya3&m+m-8wN_EEwwoQ}ume7C(4PH9#+ z#D}=I9iMCF-_Yb13~~8Vn34{8_j#X_4$Cw|wJV`?vS|yYk9FmX56} z+N;5la=_zONq!sTK@4iaj^4(YYo%h(cFbGR|KOYZ{ zy)M~lwGB)nGuE+vV>!PGlP~WV&*gJ|=Own!LP3Wsg^thg4= z68DbZ?|rtUZ+|awY5U&my!xH|a}+jq3sU@b>^81l7h9Pl@#4$N`{h5|^D5gC2EVgS z;ZSCJpZz;$KJPuvdDTajZb$xZ;Ir-d@*d}){F{$CwsMYr)=OG&4B|rk*}mU7Msd@C z;D-+C793W`<9FUy;zF2w);7wQe>bcO`faGv3nf1Zx3HDG+nn}wcn#G1n{9guho9}w zc73LV%l3VFd7rft9C2-tu;@OSZHJHqc}JAP--+C?*M51*}v+;>~I zV-_yk_vQWNXJIS;w#Pr)K+d6f7A}ABvoF8*YJ~1K5M&L7tpMX3J67Qp7BBl~zygk0 z2OGChLxR7>wXoTaFP|yfw=c)%@5;nl$k|=+N{Lf{cg(iyT+|{6nVFeY_P#XcZ}x9L zi4(pNZq9|u`4Vr!>g)cW{3x!!;S*#E9l>9YRcRzNAK&Y54>T}#Y#pLCyu<}B-$lL* zB?4#7oeHx*G! zUadN?oq@=tO3JkE${Dj`QPoZMqX7hOY8S*NsAE~xZ->4)r7L)GOLVOIVFB;i8%K8QO+aC9 zEUO^8wSHR?H9tkq#>MuLHF!wkQ9@to4~JZi?=XH?2_WmMzE5K3v-fue_T~s=LoW@0!+H6=44Am&U1!CywC~Y13lgp;h;dSUG&Kp4_3_U8UerUzJeR^+mI_S)H6{`lXqDacZh0Ah|s&4)Nd=u^xC*q?i9RrwgwQWI_-F7J~mr?L#&LI=$z0HwMwaNb2xQgPD{C((U+lN6cyLra3ZSZei z;<8CA_SGNWoT4xFGw88q1r_a=6r-13#lN`zKV1r0`;do9no(HcGe?6~6d7tn%6@%{ zS@GR!(wnESXYA0cGxyaw+`WT)W5Hkkl(%)JaU-#Nai-=T0?aWGYr7tO$l7U;TaUJ| zrDNOLHL-_CZ*5j#>rrH`4l6fiQkZJHZQG6*HTCU7yNtglzz9I90`Ov?+gRnNF?z=*1R?Vgjt7Gj7f@b`7=;br=<)TBs|aC}d4z_FitmAX_!JGI_l^#I+3oR9NzfmviQP3Flv5?fJsKonzm< zcQdc(&@S4tHLFoQ(sVa&iQTI=#{MnrWhF>bqaj8E+ao;I5F4D;-d(YF$*P!skisL5 zuH7=4v}wv}Hdzox(^<9MxrHNgx9*7Q1Zx`~**sd1YP=6;X9-&c){%MA_%Omc7_bU) zSM0WL*u+tWOaB|M3Z7Rx#=4)eifb?N@0>W6_FXwKpiR5XsH%8(QY;5fzhBF%yt?o~ zSyu9U`Mq;0E|iPXeFK#GA_NF&Mv`|wgmHRIvNZOBrCu3h;uvtZq_idejktxNoF+m4}pm(S(j zzrK#ff?zR>Ob}!%dTJdvl>MA^bem|(O1di~rWmhTFeet%h;pO6l$Fh4W`kjWEhoK4 z{A}bU?!3HT_?u$2G-}&E&*fIZ?ULpfE{gTsSmIq-<|RBIAqqk{tN|qL`VvpxYhUeo zHSgLf^`9%<>p188{iUn2?^aCy7Obd}79fp-`jC$YFL_NI+8!iva31&=z1kighqt6A z1OM$pcdwbdAm($Ew4hEcFNT>qs~l7Lz3-iP*|+UGKi=cB%@N4W+H^u*c|6{(*s*ba zY+2691pKC~mhUvm#dq=_?;mxEXXUWCQB>NtV`>J!Hervq*$T?|jVsqPisByOIP@yv zKlD34_ihFM)v6nt+2*kX#P6)S!S=g!?}8(BL~a$BF?njzwfe)kv3=VVHsO-qKI)QA ztNENf)a$OTYFZcSy9&}TQKdNn6X8y7xU!Y%1^>1K8s)YP<4sJcD(#udXZ23 zPP|K}e&4KXmuO9vgqe&}#*T}HRlnJm^y_t8=ays?ZH>80A<{#x<2$v@jF1g07jrZz z8KC?oZoH1>b?g~uK<{pCVUdUx(+w+DMs z_BMNQcdTAo8TFdAibhSFXNJz!wX33KJGKduu~WM`0W*SB+tJ&bDVVus)4JGEomKh9 z4WkZQTixDj=Etn}K8%V(>=I$@3NztjChnwz@@J-k)!a7J5Nnkyz^?u;nEqbOuNuB` z)v=0uX+YdA zVt<67w7qWaTEyC=Yhp2<9c#;`HDlF=BGB9SL<>N2`U&a$3unGh&7}f|(!01*270MK zK8jyk^S$?!ICHG>lJ~aZ)#bz!GMic%ycjuI$#-7<*8FfBXY7XUo7cr`mB|0*5_jqn zVUnlHIp{{mCkz^#tL`)38XMEL?M?jIeW2QCE8ykL0?XTk+vDj@{>^iyCItkm9v<`=(gRO6+|<`axWG{dH_1JQ_Ox_y-vn zq6;5{X8wlDhYd8i8m#l6vEwq4lPc3Fq~^?<730T3ycWcoH$U3qgdIu6*Xlk)M9kC} zE2x`lBl71~R>tF;f9>bvJ0G2uuG^57XzH_-wM`?d<>~~lEJQ_rDzu^yAyGWHQ+aZ$2ltslunxy;()&|l3WDGy43X{tsz6o0-H#>BiDGnEp{5a;K4ZG6 zs50thx{xVJ8Y{wV2LC|7*MulFTh`Mi{r#L;6%=W$Cty7!27tubOrJ2#yyt0MD2 zrg|~0rdA2NX*zBPF{ROdoE*~>oq5x#9HV>8wh+m&AkW*A-j9=x;aGPS-3!nI~ z5AQbx*T}l5OGYb=n)+G%nGR*Dm`17TRz?>kG0&=Bfx@0Ki(}Zp>*=TVjkZU$&fn7j zH}%f;z=vsGru6x|M}69->5}g6F4HYDH3|Hf?ze-nS#)X%sgCbWo=$b~&YY#&JNGFo zz(lqwRJLcDn*$eC`!#J-e3+6bj?ADjRZwTT9GiO+=P#HaGp2E*=G5Q>H{a57MG-3AZV0@}PX=oC&XPNfrwhHIjZ5855J17bl*aV_gF&(qo&plR~^=#fq3haI$W*M$rqrwD*|8+~5Df`MWw^E2V<$$<%4orVkmM8};++-^2yU_fg(@%@;T{{qlN4G_mos!$SlqRzCL&i*ij^}I0FN|Kg zkQZH<5zk(ZFXgav&ws+7V`O}O_7tV}Ntd6@9&w$yGtLN4a!}oBhK9T-UllsE z;B!wWG8?KI!8g9iK84xrvt491s>j#ie8^9eX3dLJjyndLIV$8=3s~p&oGRR;oCg;M zYNZKv%odz3$K!Y6-4#2>>AkMFilbG?!}pPu2Y|y9FtiIy4VP}TSqj^r*g{~Yiu9g^ z@Mz1rHS&=2t$YzDww=64d-BwxrORT%TW_cS>)Nqno`$3Dcix4~_92~o&iQojyTP@s z=q9%eOqS}8}v1OU0#!BghRP4t-7~*$r4Uum^3w79o07avVY#KdU<&x_bXwXW8WQ%y4e(X zqbx^fjgzV2PI`;h!65N|EJfA}6U32a?Fm8`^&XjLx z#O-NrGjcmnt*p5~OVE^Cf_5E1hqGm3Kl>x(NuHS} z);Ooi#rF*z?uE8tZ- zG>HKSl#>=#w#`k{ZgXtf9$wCk{m2*Ex9Y+btJh>rqq!^A#Hn37MAvQo2c#Cy?erKQEA&0rhGA9^0`}8 z^%L40VaVb@tO2j~;kHrd(jwooq5Tz$HydLq+m0tso52y>-J|C*U84zsG3BZFmJXa( z^}aTiGE17{>!kIhTjtU>wbu@A7lS|6tY4c)z|NgJE0(R^5*H2ZADxeGUj#4EsoG)U zJjDVuX!f%6XWt+r?MmlI8nQq2wzQ%RD*d>1$>PB8RV%-x2(mDryX~Ebm`E6dJSxgKp0D!u5K!1RQTiBdw1u*-ji)y zI;dY9st!vkGG`HalJ6Y~^Ha%1(ln8`Df>pst$nKS~euK(hWvfz?7}lUPhmRf; zKYQp8aV+_17hiuX6{F9{O4kZr4IN(!Cyg8hriF73?%9Ibvd9)Bpun@j^*$&s_iaLi ziX+UUX%NVJAghN3L zvx;AZxqEtk`|u+~#rDPEL1)Ja6wm5-RQoj26LxT65J0BV;7KPB;bQv|wlA4b0bpO^ z%S&OS@jvms$?@xl{}{JkcTJp1W!}~>VH1jH`AivTNCVA&cmaGei_Dl#1$fhGSI}q} z)JJ%W*QHCBaGw0E7&C4h47oF|y7ZE)MD3jGe8}7ynrY<2bP6dIrv{4wf^_B?zXDj{ zs-aOH^JWpHMbs;p_Q8ko#M6&ZZ04M}?82d`kmXeOgStYk5H#Q;-ZgL(oYIf&i3g2S z@y+eUchICo0NtlNVd7iy%8O6M%;nqSAMdy=2KGA>0n+r~Ui&mec{cl!E_pf6Wsqbm zhL%c5BS!qVpHzV<{yd%H_1A~TLbIrSCn-GK&HWj$F51eP| zQ5@{$dj+9;&85E$7~7Z4LM7@~ ziQ4wzRGxq};K9p>+k`M$SJoW?bBT>n+ir8ZQQWotyHKcYOJsia&YT zAH4?{*t)I_L^r=EE>o_&2}w*S3Q`Y+Ba-j!%Q?yUbsUKwg2UW51;^r75Bxf2E?pUePUwZfbS?Y1djcm0 z6}m5J1dJOrmcKNfeL1J%Cg+lgw%&wBvCc;Bd!<_)w>RH@8-DtA!hYK)uZ}_Nne9YP z3Tanb6b5mSJPxcH;eeaR)cAF9G-bIin>y{{WB|rL-HVxDXv$9cnVzABmRSsmwyt#!^hu0H4o}ujn=(lqQ z4$LER+p_9!P;xuJd4&2H7W1elH$-^rId8Q(k^gOM4GG5RyuL4R zW6TG0wst{>bRzpEN(K03k~VS0iS))LH1jXEjaR=M!$WST4-&Z1q%t{ zj~*3IzxZzeWV>D52cKx&vLHie{rPzbezt; z_N5Cr(#?o5W8+`$yFX$7)TI~2wO3u43ry1M4zd+#_~0B!_XcH38$lf?jMyp&m7tbcPMm>MT3w<#FuF zNoh3q|ASkDN^=%e!~=i$LyUcQa$G*Rf1GnJ1<9$WVR61Jk_ujg+4^bHk$O!W`8n-w z;1@R*(G=(MvM+ZmT7T>v77Tyzz5C*{6Z=H}GtWf7QrCe%hG>?j#j*3J?V${?UuoX9 zDV!As3>cNMOyUovocm56MiRB zedHLkb_V0KegHRQUmK813oATMa$5ZMndjr?%P)<=)O4^QXld`3zETEwlnped|D|pg zb_*mc%jA))cZcqg-~7I!l2cjUo5V?fFU7pYo8q1?{R4K>iEJ}r?H|6;PfULRT0UsQ zSG8{tLR=VxF+gRX@}IV_V^cSLh}|*#)mP%#(c_~JiyL=+<}=Z&d$-ha21#vOU6sB8 zIFNUxbN^O9WvwRh#^0%9U1;LvLYjfs!GqGiZJRk|Etic1wiYg3%;||^;^aXC?Uws!wh-B~h>;A?km7I>{qQlP zo0z4PuMH7;HdWrPJ>|RvAWzRf9^VQy@ujI_wG$Bg;mg zR$$~l^}>ts_3z&oC$*{-H{JR57&2r?XhiD}OKcXr(~*{q}2c?=nJY21WC(Yby5Y{S)ZaifsX z@OM5lZ~>gcYWulrUlqBPhE;49SaObCc^&@7>+$%bzl}-rSI2$#elso}I)v3OR-pH*EqkU-{f+FTu0|^{~doydy`x18P#$t*aDMmSpY@#20;~!!M>04J1 z8600kO?B5Mv%={XAVCGE0=CMy^J}0%Ltqn` zDAKJ8Kb1anX}`(@m4q~GVC|kC{98<#IXk{|K z?{h}!<(+gYz?1SugIeBAPniXvjxJOSBN#Xp|sYl-xTu}E{V}^j%9UvZd^QM zC`AU3qf$2p1>?8KZZ&Y*m{oF}FaxyCt&SJKv(jG#H8j|yrHvRr?yWaN%K8dB2xQD6 zi{w`rxwY%nj2o`JIvt~?&6;MVW#u4Dp8T%SCJm<1u1w%J@$RJ&D(*92$UOPItE2C| z_g;(`H98(7DEp&td@U|G=j@aP3M`E`=}}mH)@PC~fnUCr2jpdqrBa?5U~Arz?Fs0S zSszS~KXGL6BR~6j>?VKy```IaoXKek4RKyeXGosP!lG5M`h5|M_LLNiIp-2Ql=9d> zfY}^o#EpAvLj3WuN8-tsN5!Q>&y6qKaeEwh?6E0pbhs=Mm8W26>=0bZqOZ`u?P{!~ zv4kAWz$|0)du2`I=FM15LO(tGr?~T5_ay$l{k6N}Q#V|nt1hncL1@$p!9jsOqFQ%qfAjUp@9zw*T@-dg&;a!19IHE&?~cWwtn$(Mwp{}PYcO(OCJ6I|Z+t6Z|K^wPjLU~!7~Q*c zB|EZkaK(YNBK0X-a|MsjJL%g()L=awJXa%y8-Oy%uya3K%rO2RB?xo>gTIYWf9lFO zZ_qiJo#pDfg((g4m`RyI9`K^R^JEmW`8;{Sl_^(6b*R%>XRMAzN7zDTQwfAW@cV~j zKZRsqzP&D5JaqBvo?V*REZ&s=m0@sZ?ee)KKPXqw(WeY zyDStpYwnzQg)GzY@4pxS{MD~U-;+;@Cdd}+1{^?sXp7YYr!}ZIV=?M9r0Gk&RGwhq z!hrMW`Si+Pi%04hOy`Kxv17)>fBpOyaqhVn#GSX@!ihUwX%ig`wPb(`yfciHEjnC2 zFMaEvihutW=klyaE++x-&(fvKVj^31U*jaAr`~)gzKOGYJ0bR|z{@~GJ>;!8mQFq1cz-QcMX?LEQxvipix@77yibwyM}GHEyfX3KIOmiT z;>&k`iKDVlPUlk@qdYOoN#0542b_7?rZQO>TH2H1Nxt>(rr2GsxqVlI?7+N$!gnUs${{cQZ~ zH@}M$NFV>~*S;6$6AbV~IO$Pb2)nc+ZltAj2%$Nhap&EPT5WpqXur-&4eS~nI~NJQ z|L;GI=ie9^pSkWbj#$5vliNMfSNKp^%S@%byLnIbM4<=!XfO+ zcX`f5HSbvieHjRNaro=;{By(N3wPcbr!%LXXeUp2zx*l9XxqsDE~>hal8dK|N!Sl# zrChr82ubfZkYN^QW(R%nK|JxNVd$0Ganm)|WJY4MW^B1-jNU69$Rq}0q)%;EX-Qcj zPbn+ZeJ=RyVlG_(F;L*qvNMrm;|Y@7_v?q^Yq#GPmtQb6j%wQudM)&w^rF5fZEWem zF&I?PPIB=}ezn+eU2H+KI9){XoiTL!5 zH;^&dDPcuHu)u^I0QKpQ)U2JEB>GV62~x~iFh5?wKRTKPqiZ;MqG_ul!z3G%=sw2R z-zCtHUWpUorHp3+sy;HgJ7eaDAI1cno#hyq%~%~Dc-rX%8jeW?wG#!a(I`VnD6aIr zG49Ry@?Cf3{^+}|yew`a=x{tMQW`uOaXNQt{6owNsRIa5g`f&jWs_>< zM(9-#th`z=)K%-52#`NM`E)$@>sVLD&~jeYWojCr39{NgJ`cATC^eQcyV? z3PMw<%y3Xh$c!>fnHJ>lX^7F!dg^2>#GxKVMDBP0_4Bylwp&@PJDsz^yQHzAU=shO zQIb(>+ER$<94W9>47Q&}D1ty?W1j{ZmJ($806KU9V`UMM?%RpXpVYfIM;tcGj0xcr zXwx{2%4!JOm$QY2f9VXP%B9KJs`R z#q9f_(_!&d zw=VT7SoxmFS@nNTAf@oylYT(!$Hp4YC4;j9>a={w(zn=iN^&K-0%*-fV)YubZnlqHI7 z4Gzi@aJy*zs#vmVZQ|a!sAcq?7db>n90hOAu8DkeuhE?*M;IA*L% z=T4m9(T0^#6gqNJdN-5G_R`S;ejR3&=U#X=ol*GA3>$+o&8hp*<>>a&l%QyJ=Ap8( zA|8C?VI26TaqXp-$FbeIMGH>ws10A(p4;8zqzuS1fAXp;RYh=t?Hfs(#qo6-8fhQ^ z!;+;-l3&ekdg$3<@%4ZFVhkC`DHu3(W<8XvxK6mVtud=ZZ4lK}aGgC34tZBula360 zTOUJ9KJbXQ*WVZ(&p-1-tlzyqzV=UFB_MlBR?>DQ8)D33v*an|iSoruUM*JS=-0lP zS7lr35PqxQh)U5IpyS`37*9O)csxd+;R^WaE{v_--Ma%157D+;0wIQ~6Su<%D`$2gyKy@T<>t?AAh~FOL`zpZ~_U7-7UcU%4x;ypS{H zk@E&Iv<=ih(p^b2(wsO?r$gLT$-2}d^rJkI7u4VL7B7s)hdm!Ze&}~`)72M&m-9Hj z@6=rVw${l3l}DG$P|qK2mbI#>_MJh zammG`)t;0``1=58=#+Vuyg{A^fBB2J z1pPM{8QHmW=UgS#*3dZ@FT$mftlU*EtE=+(KjeV6f&l_`x$R~Em*r=4(o1{!phm66tjaZ7-K2Di6rgUCzLhBRV;!IjaJJA9`s*2!?Y=Cr9( zV+?_Y-~RHqF_=Z4+gXI@*|lrdF-Tfrypo!Hn5>nuRti*x6?5&_q!ne4bMD-Tx8=)M z#CYV)D+H?_o%mjS>yFRH)f^qyj;*`O7Uhir2HRHWFJU!!8m9-WVny9;6giKK=>T(X zAYRSuxKIk|ge~QSib<0ukr^;LY4Wq5xFPk2wyZXreR$;xI!{Z7+6sAes&WBXg}E9s zbw9d$8$ky7wIwUWjR@paR942@IK0oi{#u-O%8BtMWTinKb&~wAepBYC`!e%L2x&6| zUA!y5kUCI{vWySX0R6a4Ya?~LUV3$S-1g;*Ffwc>lv0@zY=ZDxM$nW_04x$jGg#)dtZOSm)mtXDEw&hzd7w5D;%!o1@uM9LiK5Q5^U|nR{)da$O zL~|C#w2g8h5||QBp{~AkqagZDF$oJz>HV z1kDio%}c{$5ZfC5<;!0t(9kD?$Ei=9Q*>Vmx1$i>#rD3U#!?3Og`Jl)Qw@1v7k_Lu za`&kQ`TE-f4dS7Y{z@IVnHPc+jgtamKf-o4hTq#0#>Y~GW&@Pb znJ1o{5$l>vsE&xYi%I(vP#?P1UKy0!7atXc6aX>`+HeIqWo;!>j9XGI^1 z)3sp#R*^P`kxTnJrJ16`SQIL*s2gWNzC}afBmezpGz3Uj_(rd10aF51@!q)qYRL-9_Ki6!K2(%ns&hN!k`nNgQ4JY#U-P- z2-i9EbK56xh!cDE%0PpWUJWUqQ)mjGLfQ6QrB-;$=w_tQdd~4~?lFC_9@VJUf|qwy z_M=9`15dvgw_FCzT*OKj0hq(gmOwyhh$={2#di)>1R5ju;TY2BqH&}B1{!oiYq|=E zF|-(CV%+%goMZe_y!7sL4BRi0etAwh(^*>pBcw1Ma7v*Yqv+B|L7(D8Rw$H`#BSTZ z>N39y-|4eBFC9bZhmSsyg?;|xSHFmXr}xdYRL{RQIA!}PN_i&J=}^E1UL-^vXAMx5 zqz1WdD_rXmgxQABeei%iIQ$_(sti5R>0D zsFfqjG3Gs2djhiNsb`*vPu_e>oO|Y(>=A992Cyq1I{nH;gHEn;b*wgUBxVYlHbK;I$Zc4`}L_~r&88@_xs<8^9Bw~ z{b5Ffj$Iw-Tj#|9XC5z!?DZ&WS2#29L!UZk(!BLPG`7SU=5$P${9b(bd*6+TWZPUn z;EcHSGq=Yn9L=cC_NYT)Hc)iv_Qz6Z<(4}qM1cujn2Zb@>7**#*5eGk%C^V5zI|_K zV*m4(J|9m*Ar>K%F4><-70iy1f_1{z@642UWBU5VNc{M*sr z^Oh`*r(S*~{vG{y-H-t>7jZ#iZ_hx-fC*yVO=+W``AD@mv=bRHaUVT;c>e4kD;XLRl zx^gKT0G9YxuDD{ZLm{oyGhokm>hRpM3H;K4$AOx`I+jJQSDt+~9-aPSeDkK8<8mCM zwjB8g8gn((!p8=0%qEzQT>9gaPsSsxEdEcg+I0`h(~Wjh_lA-GPapd~-govujxcO@ zB!tBx)0R!~&Zr3-C)p;xNJfTRTE(+EPW%{b*bB}LG-%VP!<|EEM0vOi8d63o(^5`? zE7RiFkxl#t{Pd%L{cbu&-}uxGqp&_O z{M%YKkCL5rKiibg?$A1}zUj6YKz)xR$UJk=Ds5nBTl>ZZ6*FU$ajuMetg~`CGarCo zS*d(<^;^BYfo+qMXM7kB!mBf?tF6ur1(sMEXgNpdi zZ+$b)IpcKd@K9VG86(ZxzOYtpNo@O@XW3F;90sqXcy3j@K$FWZg~bNv30}x)Pv4%4HlTCclCz_ zPF?VPoq*$i{P*&ojR%@pl<@{*vAKUsgnwO)nKtY)c}!!xo4k# zI=ZmE`6d=(>mSuF$Cm>Xk00af?-yub!d2+*+jXT(1(U`ClRO)uAIAhNTCgA*W3==? zg<^VLk4dM=O6R&u5@s1_7|jalzuoh#u)NNlLx)g-^Aov;NgG6^!|bP0mLO7C!7%ig zjHmISpfjyYV$=A~bV>+9N8VMDr(b?KzWl=<$B8`iiLd-)oKHrBd#^NvO!HQ#YHT%v z0sXuk11t?j2u=+w4TE$QPJ@c-83GNHUMH;<1M%zugV-X_Cj$+( zA?zA(w(E+4t6c8g&8QhdK_*n;$rSZ5Y<*YEZekT=CGEdM^#9inKTI*EHgW!dfpK!L z<1*0TzEg#@cvOJMbOr+y)Z1y#_LDjI&dcbiirExZQ+bV4&Y3eO#<)8D#1ol@){oVk zV~;&Hi^OQCXo!^2Sse%4lo2z~P$f{(fOZZ*kiyVCXO7V*>+}ylh!;kTU@sCG4Fnoa zVn3bfT*6@5wNce_9pW{fQQDY9A8)Q&`ELz5v zlF?)|Jo`k9n7t^zM>_LG=MIjRq#r6g4lu8!($7^L+Lt!v2O3Y|E3TwXm4hog_S1lh z|I+9b6y{?Xh(CMo#jJY!n_v7VhGO5OHCLuJ(hV};KBS_Q+NB=__yLIB;8ZF|jSGa{ z9!lS9>^7o(x7&;vKR$l?&AVeFnb9{6J}17&s!ksi&)%v)gK!q=EAc%IisU9~tr&LWOGH^ZO*53frvzK{%|Q{t3fJ)(aWfC8l79_1^GlMEGAB!7We-6N3pnaQQZ2;Yhx%5wP%A{ z*I?^LYCxb63{2%a?YcUh?U|9lZw4Ero2-pNo3-m>U@#8`3zw`|79-x85MTf4zsHas zJvmSQg6Q9WV07--3HmU5XM3!rO7gs=i^<{|8$bK~Z~pHwhv2J5=KKM+1OKhpxhI{9 z(}~f*>O^y@(Hm&^En9k;Hfa!7UT|S_>(ZI3+RbwOW_ySiWlE8mRRrsd_Pd(rikT!T zKc|xeK68~6<-ZDJWhTMraq#S8&pwm;j?X*utjsF2m}M4jLf)8iu2E!r?%B7J`)-^) z4UT#kcp61Ir^@&=q>*FNyXR7mB`a@XZsyA|_2-)Q-eFoN`#|%e(ch zNACMU48^%?h*Pn`-I*(w;G3e|nBMaOEI{|kMQ;qX)-Fr{G zw`@gR)%T>_I&tcWCl-MQPBbydQ-fzcS*1RGYV>Eu6Y^L6pTT=@qT?rj%1Z`$Y7i*d zfDU{G$LI_9e3zMvxaS`~7uQ^TSsJn$!UeY+>w zIndsb&QsRYPX>07W!g9f0$lN34WGJo&}@SfWjkW4l+rwlZVoAzGZdh;!D8qRLJmaWmRO;RuE%n7f0 zN?vjJ;XMPu{pp0(|_vJB3Q9Uni6Aw`_-c-MatW^XB!)HjtqL^ zwb!UK(>1>OrGLz95_Q}jWT63eKNmV&^b~U|eoCiKdOU!PROe-&0e&)Iuojwoo$YI1 zyZ8H9HUFz@@4M#m%cDDVqkeL$PzD-!2lMGPN*CJq$}Db4+e1DzuqLnia%+h}frZ#j zkC4&u!{0mCT7h{B7x#`Q#ZW(c<7eSes2`*HnQ%{>2 zxI@-$*k+(%M*RAZeMazkWg(e3k{*M1};ONYpIcI#?<+K(+l^7SV8a#)Ty=)LBi(b$ITzO!wqLPbltusjU9wC$h5Id7`A_9Daze@};<}EvfIL|FHp_ec`$1qT|4R8EB~8;ZmT1uWG-3 zoF9LhK!Zf|iK5CqP%MBM6(j(Q|9tM5oiSxfY^qonjVQ|oQ$Fn$$Z@xV(?i)LblB;o!VZWn7c2v_{NfBCgvgVSIPV()h&_Pq3G|dE7kehPdX+e$lPGQ#wLN z0Y9Uj8s>tUfd&mB4LKE0Mnt)0W(yG(8&lRJ5a4Gs&_GsX2KyPGA<%FS05bfVYqC3b zOQNi1o!qbKtBYL)ht4QvW>)}cBesH}VC827Ma%0O*%_MOH>}?fi{4+%)`=;xhceLz zKYb68#J&lB3bBTtbnsy`Rb}BA3AEgUuRe^xdN0SxES3Td2Z(N4(J*!T)Ocjl0p*@^>$J#L+F@6;b2`_Gua zFXDUO{CZ5Jx!+~%qjWvbQ3Z2`D62uJddyox-Qbz~8x1OD`7z_2;rf=;=Qan{p+1g_ zfuuzkagROrXgoS~dLH5R_|JdJ_M&TWYKg2X9|9?}Hfvv*UYT{7NihPM^79WPI%}|1$daqCyB|d+xZ~f{+yH;yA9Ma)i9p zDQk#vcsAB=-V}>hEK4Wi>B*BN8ks?4@Y2)YxpipfPp~)fG)omrpOLqHNN%5stE)*R z8MEfIylHu(fAe=%Df2=`($5ydrl({|+iHMxfM7frcGq*B^QM8Tjx#4&8+4 z+NopiA=MC+w#A-Wj2>v9!J{MN!>n>iPQ_%mJh&ysjEKh2Zk)p9%h;Dq)xqyxdWpS^ zpNny1x;l02Nb@>2^YYMWJ4rym@0$5E_>hhg*R74gsMDU#uMQM^YbB4R*qCIo0t}u) zldV^uc{282tQKGW>fgk$fde>crB#-9Dyydm@+eEiHUa1fzGP4n9;pxCTY7nnGUnrA zKURXw;~yc zwxU4;2n#FAnl-3vQyO2YVzc~M%ybcT8mqvMX6pG1Uj?~gkPoOWo_ zCiPu4_<|@aO_kXaL@-<|cMPj9oUbcjz(W0}ps7pTawpE)7;x=|4e{u2o`_$(P;7Pj z!;k(WCX5-APX9srt(aZZSj;E94)7+O<$IkNt5aNXofnNqD-8?+WZ5c$KL;HC)<1tc z-ruo1?ihGwJp3if><19ihZe`sPw5=NbY<{CU4lmjXAD}IZI>RYyU|;2A2fK9^x^)z z#sLBiS<&#%|C+S}b4qI9nX zT?{mw#0j>d;SaCVGlW3Qox=xFNis3Ff$11!paHrYXpr_Ax$>jI9p|X7@U@sXI1GJs z$lQl~5=YT4^PXt&OR-i`5JWbI;Cw->PRaZD%MjKMWErgPyRM0;w+9HJS4hz>qax@R;l;X#(?L{WN*C#U2P@mwC zvVIC|lIQqy3@2UHgvFiq3msO26x5@5dH?ll}%@{B|Kv zUx)7Zu%EwIm#*pbiv=c73;@U_^J{|*Vo%!4euishr53oR<9H0c z`9AXWGi>3>3m3&hw~vdPZW$l_-8w;#&hN>K2EKG2tpKYB{u;n5RZwWZs;iVKF@Qx* z9zD+3ZfTs2Jbm|{{xz=Z*dcB~|BW7bLv-oJ(WU4nd$J_fz>6-nvXnZI>uFEx_-YIL zEL9@Z2A2(n>1R}c!*9-+6O*2MHa`7{yJ8qNO)qRRZEdS{tT@Q6Wbm@s=tXjz3@W$< znv*%eHrHAE*`T0UCVp(#us#;!C%o|HWOP^6`1HgH(KiDPmu0m=;>jglt(-Gh;(_zl zAF-Ok0G{+dhau!?C{}(o!rnD-w~#F*)2B_3|9*9He4UDhTStwGE+l=*z$_i~tTJyl@Rml7&hKgeF^)oB@IHDRAFv^|!2uGUujAi*x|IYPUZnD>-Bo?!-g`b1b;{f2T%=zbb~%fW=Rbd% zKtt)?0Vah_X0j0-+K|6opn1rLF`Wh20ux=vUYjw)hQ}2!zKfbo%U~9dNvnaOc!BRv zK>)u(6PC4n`>!V668C@p^Kp6K%L{-&kkXKIr3DebTa@RBO9cqp-JTUB8cXI1LsX@# zV_{auy?4*jfb1*Z{rBj?`2Xiy--tVIzb#s{YlpJmpGQO*1W4yla8<~?&ZTRa;j!z! zi*EpkKzF~%)j91sqJ1_@v8jwb8h-cO3o+@%*W!T*H^r?JXxNC-uZE#>7GuIJmjMe) zX)WzZCK60w<`jAXPv(PeGP#le>I55%r0u{VaZmZr9{Wv{)v1BAI}XQSC?^QGKN#nm zjE;bmQF?)yaWrTJmQu7|VD;&HDrBRt8h8f)zskx=I;qc#-#qeYJjA}Sk(BRuET<$2 z1C=inpve`KGL49w^CclLNaDji)H)XeZANy<4)R8*W4s#uvO?dNW6s_t!3~pOM55*-|ol?%ep< zFCLG(a7I7-33@bi?36~Eprk@}EpaiERz=pO(ERc%=~hNZX)@Pz)R}(`N;0cJ|1B6= zZ_x1R=|_JM^L9u4;2-`L+K-Ml&0A!^NX2EdF!|D`tNf!;T zd4aZSb&fVA$YUwlJ2Pj-_rLOR%q8o6-{_H)ixFs`QUxm+rOEirH!UK^cCzq=d-Lpn zag^^@ZrhS&ie{jHJE?F`G?dC9Svus1-3fk|1DIi!k@~8$s{zKJ^KbQ-CcnlJ9AZE3 z!|&8&NosNFT3nNuO>E*lo!=IG-a-64Cq3rlfluER*Ta|nsD|m(wk?ruj%q}%492*% zNxAYpG$jraYt9AbZv#mx&!juFl165$=OIu3^1~m-g0<^Wns>zQ>~9{({$r2&JOxi? zpn-MN5Xx;ODhq=TO0mi)X=l*EDi!FCA+1AT$@=bnd*jVnGvnd!{#!hF)41%>FkrwS zj~EdO@0eLY{m`27gW?m>)czURu>- zEm(4wE@@g9x}pD|1x6>t-oxiCdT8PIA-Zv!6WU#eUSba zb8HMU*43M@OU51#GuEzL8Lz+bdQAHLui{YkhVl2`_-0&3pMa)~Y_LXFiS@gHQ6ZM+ z_9NykzPWWy=h-bs?j3cnv^b;DV(DmI=5~hlGI00UW50|^bC=?@+{h_3f1X>B%shz& z8s>=wIE>EIUL^)aN|iNUOL$N(DQ^bA3^Y^&EB6!Jne^JL@%8V1FOD#+f2K#n-JiG< z$Ea0q8$qE(4Ga}R;K}RU0AslB_VM95(g+%4<`OJTV-8I7Skt;VUhCJci~st?FXLyN z$l>FKpZ^3byOA^4(J{zTDWGm}R{i8&ZP&uUQFV>~lr84ZdP*zlRF!H5aZK81od4^; zeK%&&4D#L)L*fe${sn=C0cn7Wky9UuvEaZb*WvbHT>=`E zdXq7F&Bkxv{Kv$ZZ~gVdaRL zD_~qx4O{uwV1(V;KUlFce)ESv#$oXEHnNyjG+a(agU(r=(BoLl&22$7rL~I*59UK` zhR^MpqtU6HsbeMFVFIGtwr@+?|NJLEiQ8}%Z@m6`nzwe3W;ia=(rsieopLGfsZ-Uh zJ_^T!wG=yU(qI%MX7suBY13Ei3hrDfQ90OKYn^ z?HZ&$l?MLDe0Ai`aXB-jAIU3tV7d7U#-1~KPCW6{uQ_dLR6P8dd*kwM-LmPa#&`zg zn6vkOk@=g|bqO-5!FxK4+JJ?vfX?N9tro4$_=k4w%B>TxQIhV%OYD6K#(c zm1lh@=jtdO&XpAe8lHJNevJ*Mjsw*)_^&GBu5w90glNcp)NjJJJ^1+`g6b;ynZ^uR zACpI)Sd+&`-UAiJCgg>wi48SJZ!lN?I8FZq_EBlEV{F8>#Tie&F6)PFE z1?5jOv`;=upy83nV;J${FZ}Jl#!XZYH@l4Hss`1#hM1{t%?cjY*a|RhvjX9BS`Z0h z%l|4E?+;!ws9~Vt`(WA2@XlX->ed*KObsLeRu9=RVQ3ID1HUkfN0S<~^3*1PivSVF!$cbaIgUtO5?A7o5!*^oD)dNTvj^*Tu>!MxfE+|c$X0{_MfAYG4 zfRa7!m>Fnboa}1@-F;8FlV;M;trP1vRK{!5r^hSs+5-faxPp~K1_ur5nDA`Wq)GY-OBcT%GwD6`U%!1i{_6hE#ho|Z zh%MHRV0E$GS&Y~I&7idF#@r!BCK9#3>>DA5i33&y7yxtopH(tzD%NF1!=y=1(dTD> zJoer1#MtYGMT@5NZ&F`qOQ16{xhw{|mfV9psJ)RZ%GmOye4YU|E^if;RRix)arfLG zpNXHpO3xF5Qs4Q;-^L&kOOA66dCIL5&fS5;6!=9Lb_=I`X_XXF%=Br_V{4cC2h}Ff zaEw61t8cv(U;pYiVh7*(B0U=JzxQscV7g?`OIz~7DfAyY#6Yztt!aN4EIQ7$H*DS* zud&^wO`l$zwD_rLSYDp|F0Gu)$NBLm3N$3w!n7EDC|@171REe0m78add+NmI_3NVv zN8(x0(6?LnG&<~VE_m1lwhv7v{bRkCZ96@0#WR8`L zhL9^TI#Z?JW$=uovG8VGGJ{-$poWn-l-|0^jq!WH^+lRNesrzz8~;~@e) zRy4FB^6wEt8v3PuT`F|vYnCB{IE;~*D6VI)Km)+*2!5VrEg-I2yEeBsya^v1XD*+i zJW>H~+qP|X?sorg5opkXD}oDV5ClMf_xchl4GPv);kO*H8cNhi;#vYc?~+Y>^fz>_ z9(^18JnzI1>W~Uqhe$qQB!t_a;YxT_L)3dOO5kk7seu5P%TL^sd$5e^ZUDI7CPO;u zsb9t1?Wf{9U;8V%8mko@42{V#C7q|=RY4;V1$}oJcmVOhT7HmKreM+K`l6g8#ioFrJ@vay`n&YJjt+m2V8Ky7Ib433Nt3 zWCaADg=Hy`#ZhFh^7#vA_D@rDAXm&Y$rYlf%5`K#;;Fkz$e(4TMJL%8Rr}yR2 zh7&meIxIF&+Lad*rQ z{)E`4QC5T6Hz}DMRNT_G1WJ$!B=d$M_M0IZDb3 zsSbHM(C)qa;#ZIVF4~m0q*FT%T~`7PI2JXl)g;h`F~J(DEX5WZ1^Up~P5Fh^%9e5~ zR%kGpRj-ZVyJOq7m_Oeh3e)1n=`-W6zxZ(6h|{I*b>|gPz~{>X$Rn(3;*D zhs1Z~6+ElOQ+{WebB>Oo!6KeGU-7Hp#e(na5yY3atJbcIpZ|)W=Cd!lT=Ddeeh@d0 zVe166$?>5nnj-@;%7A+R^Y{Lwxz4%Oc0P3`tumXpXmR}Xr$32zR#(Jl zM_(UzZ+8IByv0s|tH`!rAfUP} zo_dL1IZr$pU%CgJ89Iz6)K^4vjND8R@IAM$*(WEfzvN5s)@mt(JMxXThMDpVG_V$8 zy^Vi8)yb_BPyF$@IJ9kZOe8~kEj=1~_UMt#>vW978TnJ(mv0atXj9yiv~f(k?yIL< zV`-+0Swg*U-(G^I@5j&o>!)!uj`UdMsaw~sSuv>m+55LL&ia~)wec3t#gut7;>&;eB`Smlv7M)V?#p(|$H}A2pSfm9Gh>wID}PsE z?yjH5fSZj@nsE>H39MP_t!?lgCCyL0@J#gR*f$=!@80OsxohH_RYygDj;bAa9LUMB zVWGSS^@+IPoTV54z*R15vHyHGbAOKj`8#jE8NZtMZhZR-Ux>RWjE{1##=wx{Xk}>nq|Jvha^SKPiJ*264sP4)_*L8XOvpA(=~Cdv?EU7m~yyUeoh@%w+^Qs z@y21~{tOpDH0U?MmXVtEv4xHzPx3!lOoW})r9uK-aqN6xT4b=H1$y1j0=`SfyzNfbwG_QL$0k)K1R8FEnUKaMVgKX|8=x*lg9X z=^E02?sy(Qc|XnTeEi*gpN{)T0NF&_@^@`jG0mWjJ#wV4O@kd@8{4WcecasUl3@RMevJ2!#FCF2lOA1Co5>jn^`weW01k>nAC^d zkJv9J6gF&u@dlY})NP>i2&Y+DSvCuv{QkduKgJ9n7Gp+?$mXpb%gYnLv*|HBrwoec zAL%)0qzq|GmEQ9@@~67Yhey|XyyffDXT)3d=6V30wC_f%R;}|SiDFEXUQ|QypV+Nl zHQAVzNjVB6)|Qm-dH5=wl=B_ix5qND=2-&PHK5;Tus!;MGoCb(+o4iUib0h9+%673 zsh<&_yp9BSeY1K5TsK(dk*EetJ#}K<`~~sLN1lk!f9|sxXlPI6lvQNvR4WV|N1PXn z^+%+E{!O7vi$I}#quwYz)wgSrzgYzGUwQfISh(>>Jo?@5#OPrhiHhBkTl$#0!SEsx zj31)Dg=aD-&EFCM7*ib9#xDBW6hRYx!KEL57?Vjt{P_7-;zn$pfB4#0={Ivl25~&X zSldE>FMR`ODh<>@`bT1>4XbMrkU7U#r$|)kr*YHKut{0=5Sl!7D#43?jE#Kfp?mM5 zx$38)Tc=Kip2JqV2p||}NIORR3>_|}+YGXD^Cp^DlWgpNRs0#%MNK-Cr_5!b?b13I ztM>8x_kSN~;GW$s;UY+jG;;JbTri%e&!3950Kx*8XZ4B|ahzk>`gG|Qo!YmjgaiW> zC9Hx~aW_QqxTp)r@P6x&N0OS?wQm)7ede>Ae$Y9ix1Q}QGZYL_C>0~#X2Np<%ALXw z%cVk14h?@}dCy1D>*|a;ZYttykPWZF95@W@Ptqs&HMf3YAeH|h}Je4x^ zvmuCviOpWDW=LfLEiE-vQ5-=-EnBlDe){`obME(y9>y8JS4Zdaj%0;lSd@bT&D2u6 zm6}KiT)r<*3rJqW^$`u6M`5fS%d#l5*3Zsc5cd#8^!!@8AKPa^(9FGZjO7>!uF?mA zcFkQ0t0$zn^ec=Q9WgS)2<1-bVpGu9Uw<>V#QgQ0w_%+3AcD)0J18+rSyeivhtbId zPn3{rtKer7H3`r41uyqu*{%8TB_VyE^3E5h&5x@(wI$GSSF{8CbhL8670SiC7NA(J zVvYITwaARgC7w|c^Jd`#(b`T=$I?#)M+d z7mlaQc`}4XoCdCrMP@CCvg&MjPd3T&D6vJz)At^GGRN-4zkmLJzD%`8#|$#KU$G`7 z*z#b(H^`Dd!*>^XHJZHx=V#rfjjI#O?FT&2S1vTbuR^DG`2JzEUCBav^<#mjd{=YPz8B^I&|Kj z0a1IQdPQG zO1v8AocZp;c#N%DL)x^95d^2YckPa{;uuDh%_;8DCUm;uw#!0d9 zy0xkwJz1wF4U`YEhU@`W(yDQ-s>reiaE+{>uxANDBd%{rtU+6&KF<9t$}NMhR_CzJ z)EZGCayE8h=xyD~;2*6ihMLFNURYf5=$9dSuQoN^Z2;sAAS(C$QsULQSQ2K zXa+T#6DV-ctU(F4OeiZFFFHFq(YaLvBaVTyDnY!^z))s26dPbXdz_d1UuVsl9?#5L zkoWbq`#v50DU-|qaY-)o73Wqg5!3jjb9F2$Uqn$>Ik85AMZ-mdU1xg92Oq}Mzj!op z%$+NL_q8ua*N)`{U$CzB_t4!OTuCN?Vj@|<(m8Fl^{a1h&J1^K=>b*N4@oOZlJeaR24e z$8+ofO{>Li_dFQA2*PAPBE}JWONPGsRQi`3MR`PQS64fp_vGBgN{zWg;QUOojE}ug z$jQX(2N7r=5go~%fiGps>lsJifurE>YUhP@D=*Fo(5lYOAkLg*Q5{kU>4d8qk76U z^_XLg?5$h2a0<-_@$}>wd9VNerH7-NNdjpA=1N0psw1o8Ab!hxxyGzBKfy|35H#m! z^`;mo{q~VqTE^JZ2#_!2uXkK~P29>Bu@+#>S-zwEDKn0Hf$w-C);l!1du#3ji|Mjb zftMK8sZNxWiEmODy~dKL15U}$++PN^8N(o>`an8r4`!VN_ndYZf>;fqj&Uu^2Ibm( z;(^IKv0Xb`T58**Jn$WpAZeqz##~qa=R;}xt*Weyum5LptoG=uy2bEO1RZ;HPoDPs z;+9o!+7?CgS@;5e5{nHi7ybcj@8k?1p*yWCGdZ*O;C}j{eHc%^JUO(PZoFe+^y$?n z6L0D_ZSzv)kGPdG<2caB`6{1YBkgfM?`Nc;>vIAeGk7;;#>{wQ+4A_@$l>(gpkX|E zH-ou+*3bEUAD)b&3~<4;TawoNtgYkw^1ifjff5Vo2eV;gWjyixi^v;Cj^A^4I=dd7 zsSZvX9lEPKoQmu~hD9w%QH?UQCVZ8G0k{EmC+6WVDb$&)5L`D%`vwmNfju}j#VTUq@Ka}YQ6NyNBKTemXyyV+>jdw=*7@XWvg zx%Dk^kuk-Y5=L?Z&_(*@<+zt3;j7M;N7aKS4)d5%_{xOj^eJz~)YTguKE97F?6yaP z7gmfI;8jBFVesW2k`uFJ)_kQ9N z(V=ad42T$HU;$JAi1MzTSgGyg7EQOR&Ss1D==<)aFX5-6N!t$G6!#}nd4nJ0$Dbt7 zAoyq)s-*ImLI|VyY9^e*`KVxV7qK7r1Im}&lBq5g1N8u7Gd3C?E~rsHm(?Bvf=ZSWF&BkYfz(hGNCl4kJWh-J z?_7=(sMx_?*OR=K;W#y5+`7<3!^ZLQ`^>#$fD5Vuy2i9%VV1?~_^RQqfo)T?6nuo> z7@u|iRz)~|J!#JSmd;84kFty0hu~%u^f-H4jm!xY3D#Vzn!wKI{fwZdVPqNL0fH3= z`A!39(F8-FAqq)4mjFq6_<5P%IZ4-IyG&t-<}ouGTbBULvMi(iMr6&D?_{s4&Tl*R z>FHQnZtIwJ>D^HPaRGb^y2py1!Wnc;Eh%%pohN zW=(1Sg@R=q9hWp_bJqOB?|IKgLyeHLrUkt<*ts*UNa&Kri%OLB_DDf_<}eDZj54yz zaB8G`;XtTpFw&rzN=Cy?W#aLF39^i@GhkQXY{tW!%-H%j4bzj*=rC(~h_N+(oO^S! zn@%I05_r!bPdd}`NM48RI`3lr$Fiy$2s}J&ox9=YXjspXact9*r`}t zu{q{1--Q7{rUyG#f4Ff1Co>3Wl?`C?$B`ZBF2~_UVxq}|c zfa~n@AavgiZ46kH!S8h$vleTj!J}*xA1wGqKFab%oQ@h~^$m(RuDqfW#ns^&s%A2u z&WZOOdj}b*I(*J!BO7sqWYOfzDg}ZO@b_LawOjV?ibXrNG9$L6@YKld*Qt42)q{p^ zWn}r;|4;-Pz)5)023K-xZHda|kFr1iEY%>j$vkLe7mAZCH|tsz0@~oPD)T)JlN`V) z*s}j{tlzbT2D9`}p<={G_f}O=ie2;Ax(r-`v%ATnU!ZiMNf~F1QxPVQ*Pbgkx?DP#yHQl|A28&zSG?GprPd?2kTE^a*vc{(94&t2( z-x_s^Ypx|@DX$s=;=Bf>_-LS089Bi{AA`S6aKFx{DO;fGqeH|ov#%N>&eg#3DU1)d zkTFu;gJagm(AEfYu40+kBft36dD($;vyI;-q8nG*cu!#TtV>9$9#dtqbzI zGU{>7W;s1h%xt~ausio5KDQUATHLC`{WJw@8WN~>Yorfx(x21|j-QS@?`iZpSLdn0 zSk-JkvheE!E&2-dCVjO<~oXn>LT@QRo>1L zY65PhsziHOoWhV+YLD}o-Qc!(*O0(m1J*nfi-xUZ_X?GpOB^f%zZD6wps2oX?q&b?s`xCkE=29qDX&z4B$SSG)0)@(Ly$ z!7fyuTEH)5e8-9!xh0bjT)zs}KwYH0A@4Z8<>-wGICE!Y{`V(sO<1{J2F;YQLtwo6 z)pc!3(5MX=b$P-nkSfr#jNjdEt3$FEUS7U>O|09o2M5?71UJBA{N>G}d+TP=96eVT zxbYs3qp#KXwUJF_Qp^=!)Gk(USmN&qMCpVw&_$XO8Kf1vs-hpyW4s)tlzJa?+q7?c zd{}ul_&@Q#F(TZUh;yUHt@3n)Q(_cjyRK#EaOdw@+9X%nOC$BH%^Urj6|_42VyASj ziR~%Bh#~4h>1=RpueQMvj-7=E8=yPHVRfK9<|FmnC7R2J8E}BwuA6e|I%Yr^I{I1d zSmju|TP)iSmK}oUYw@|ptV>gPz9ux0U&R9b1+OKa$^WjK^5ML_FOyK}4Yx6BLy9@l z*X*=*>KJOm+lSVDf>cbXIuScMML@uj4cKzTh2+@^67mW_}LBZ z4{%?N8B+|l`nP1uNNev`{E{~Eo0zB^TcPMWG?bQ?*0|WRjJ&Z{Vubp2J9dXbi56gt zwoUqG{9XBXn|U7X3QrhRc0CUhpl}V#2u?~D?Wf$TBtJky@73|NDYS(TF|P*jRSTT# zdfbEK$m_0`yy-oNDaxwzP8%DH)Lzg*msd;-NGmI?yoSNAgYe5?Xs?cHO>m?+e8YsZ zg2!>P$~h&zz;^kEw_&>i^SKG;4|4D-j~aLv2Mux@q4MegGJYHydaq5v57$;+lUEG9 zdJXwcKSdpU2?AI{F2V2OT=JEe$vvbzftTWk6~Nl@&fjacZq_7i1CPeF-&Sq~W4`jI zL6MvzQ#T-V3i;u#x2|Nu2;{S%-0WLm+&#Vv#bzJNfI z=kz&B_XMa%BZQORZsW0YrtcW9QCTJa29SM-Tc?T$U9C7%R|2=TgHavlz~e?|HVfV5@L> zy`;^h`TJfPXaK0-?={w~Umw$-{$upGen|A{-8(^08mR0ADV3M^Auu?;PMIL)k(kE; zO$E;&i9(s+!8MA{yZ`lgEMLAn)-PWaLvOhwI(O`t*OwpszQ&UVsm4G84!>(?2)+h( zG#1UY_&343FfJ|Sq|_S#-a~|M*}?@hC2SHyM~omibr}GlfFhR6R}e|X#+nIYDpLb0 z{w@1+Ft&iUlxaF-7CSxaf95iOt? z_{qu(co5>HF_=69eG&k9HM_KZ+g468*bw`-Z;ZazkBM&GyE8szSb(r|(g0Gq3vi;O z^QxCYo!Yto&wZJW>)!=nLEF#h@Yqbqx$k2iVHNJVd!N41nk_D_k&cI%4qsK;8mg|V zw6$DV!|mAN!U6JR0QoidS3=XeC?pl&`pOMav1V0PG}OfiYu=`926UFKS{>8oyvuAN zIwOW{(dj)qHHvQSS`cwA0(_P>nngF2>Rx^w*6LWy1{%(vGgMGG5mrl_Gc%5{<$7~t zIMB)nP9_e-ews2Y-Lx~7&=BYZ@q;ap+sCl39db)dr}B=`l0B>{brqmSgEDKTU3r)}p-H#86|xYph*Y z5wl-PXSpvOp0aw4@_Ktw z?whu6jg^}!esNTf z16<@j(y3F~^HiAuMg&|iPFd^otj7Ty&2&O9PesZZswy;Q$yZW}%HPneZX?O64@THd<dYdA;Z|l(KdOcaGDC4 zcP!^-hC^pQ_uMi80}7`xFysT})w!f@;9iyUeN=Gl+O{=zZCoGCJ9dpL`wxgFR4AO_ zz6|my*9@IloU+O~$(OE*vTU$bN4&1<0cIH7l`dZY5P_@;nqO{Ny*&B0=b)i^B(a9C z24(7H<{|xc9HqVVG3c%Ah;s%IoUimyhLSE~9iQL3XD>KbNgtHG$;<6Kbt$&Hp@Vd? z#CXRjVO0&r_51lg>me5F1bUxdqtLAeRf-Pmm6esTYT>(JU&Ckx-!*U9D!1pz*V+%6 z9YZE1kXb4OH62dxU*`^iV>?Mv4X6G_ATlfI{$c~4D^{+IP3u-ghtA!iHF!}*u&*8g zP>n_BY;e|U7zmu-v*~AM&$)NEOE`8FXy>{+cQc-8mvB$}aBP=REp}}GzUWN0vjtU= z+8xr?xvN{{AFm^hsG~AC&im?a*Vp^}NC)#y${X)XtF7?l2lMAd>&{)#-F?#Dk)Bzp zq>;{d9 zk~g$npn=ygV4IZ$>S=8-PD~DEpbecd#o51D0y6aGa}49QAWmM7?!9}&fB}Qq=FuU)BUTykJFTM#56LS!^sbM*DV;WL z+!U3oSLN1*CfJhAcs4|~|jO#rP>@FDKGrecmxR!z5afYH^^^9-MK*BSRZ>Qd+L!=RSDv(J-R zmb@SPcWj|&TE}Qt-Z3i(fee|+8bp)Hn>$?`Ed(7YqYpqOb z$8Dl=X8KDnu$`o7^tk*AXmeQx#GQk9B~8-~md6>#N@C?U<&(ebgJ@Uf1o)1h_hH2^ zs~juA;dfu-RYRw7Y(^_{^=w;$4hpPzJd$kS~|9RS6P*AHfUZr z?agS~p-WsncnCqzMjz3`^%Rf%oVJpI0k?Onzx~^3f}-Ao4`-hI?t=5bcGN-Ebq_Lo z0DHAf$4=3qW5>i7=bYHWeEhz4u^1y(c@2a1=XuZIP|}_`JFI-^{psI`Gds6$iyd1x z=l6T{9~kYayi_+yZy(;PLo_g8ah`*<;slURys>iLSX@Gy_+zhna2v`4a2R*Bf zvc88;aFWXU&GG%8{4nm~Sj?u)+j3k7Ro5TfreUS6WlLl7DM1xxd<8xpk+{YQ@51d z=%uB1@1g8x&z%v?Q1o58c8xBbJ7-z7OrRjR&r1d7$p$_YA{}Uzo}Y2H>9oRN&b`F^ zbzqu3D80AYYO!qbd(m&u)oI|i!3a$w+V3L7mg?E`Poed@0-K6dC)koiucMRd-(>DI zECFvH8#Zl@S1B(uQaX$h*0!zNz|ajYF{9;K25e9a3K^dlbnMpc`x>#{pEOc96s8i` zcr61IOIECi=l}4B7=$vm`?oZ+lv+n9gF?(p5K##WYJ#Q;{wR*Pl_K7UidzFWXUw${ zkh%V0J~L~^Y8A%gKK&g$*Sn5;QU+;fHnlE%>5sINPCo5r!f@2U)3Ie(RoYn6cp=H$)0#${YfT1of)@SR4ChD4$( z7fItBx~ni(u3D8xhSugggNF=_u52yRc+Ro8h9D?V*J6Ce1OSg74q9gmqt!S`> z(yY}PWc&gR0jg6TS{oYH;~uJzWjsl?`@(rLU>XZ3tWyLdbbM{RXal|T?vdm31{w}f zX0~$Y!C1a+U)bYxEA#Vl$FOVT%3eJw@$Z=qu>k^=nQLSaZUYAB>yzJ%gH#CgBmmR1 zSFh+m8LkG3>!!n{F^vTUlAv_Cf9WJX_{jA|9t@%#H_*U*G`u}_QCclrN{KK1H2U_s zA_lOpvIX?9>PIW?9QWqdk#htZG_>SLe->W8a-q7#ae<4 z3s)?QN8Wff=g=CKXuuRZx2_dk+q90BWy&N~15_5cH?YdNGnr+v7Xt)E74aX_x4H+G z$@MljK(HD!A-85dnd$HHQ`~JpFo1$Xv+Ni8p7aiCxHWJ#jMptP(mhedo5QB9* z4WLLPF;ShO-qNx5cxJCx>fUW2NN0Bm`fnw3*GU*Md{hh}Xlf;(7%ol45%onHitxE~ z)sT}vm3@P&(og=DKJvWRGs9QO+~1?Y<3YAh83gD{FuY6WPSCiJr(F9ImN_o#sXQ52 zP;VvwrK*Tr$kWMrVh_xy}o^$bjy2-t>^IQi`cuL@2oaK zUc~mKIrNr3@`kpKdRvL@71UK)2Zp^!L$;TuOy{@%c}(mX1R7dL;~MB>a1e-QN`+12nuxb9 zpZ6jkdSa4|!o_6Y2Uy@E?i1U}wK&7i$7!g0k`Ek#AFODYyEbAMA8o>STBBPBUOg;s z8hvy0=7ct@gVgCJX4095=E<|rOCCsBM&4Fn7c6G`t9rgINiiFOwrt)azbl5hey&w+ zk>a~nS^8bqO*)H{u8TY)eUwqJV=(3j6{8E^UmPnwSW2K&dF`1!Mw;<++C;3ScqInA zj^3y1DrUkYi3hH${GT`~S-=DnIoesus9GuZzA{UKKsDCp(sxr+;vqstftv z5NK891;iPC2$!3)P;y=D#m$dMR1dQ5Kr)DKZNIR~*oUT_St%zk7A24P!Zcj%vK zXUp^cZpCFo_(D0>o>ZnbtmhyDf_67tKO(pND?e7(OMB^?0eWQA0Jq5=*U-SAwy^et z*Uvx$)w<5X1dxHXwa&d_9d_7Js>u(>&dndjgWvigP08;h5Y~nnI1BDMpS*lbAAh1i zgLkiDh4>KtBLJje6qOXKR~u-U5gRKiC?T#ML;DYk-WYP2Gj!zES%+l+G#L-JF7{EQ z&|P?qx{N-{$N-pGj2bYHdubF@jjq{bFsDp=i)w~;(W_^#Jl3f>f|8)ef(q{LGc$q* ziez+HVaNy~g5=L)jHP%g{eo$TgafX-_wS3hroI!a*+bnAaO&Ef%m@x|U5!W>R71q# zEQ24;Ps3OPRzX(~+>e-!9M@4H$bh~t(A3}_D=Ig}b1%G*4xwGB+Zkv86jhK4x>0Cl zOL5Ui5Ihu~5_tJX>0K)O61X%X{jAr0|HBXCb&hHpNMpxq$uc$|x}9Z3{5^qzxd=Ya zNp@BUExFGUDFn&)3i|K~XyeZ+R{uB9Fmvua8pF(uiMQPrSN5S|f_qm13!W+imA(dg z0yE$L=#{^fuE{0%Y~i#EG~Sz$#qAh!?@UACGoB}dl(%i028eu;V48CgcQpKeH) zmP+|BqAL(``RRoZ3X5Xg!pamU4Pa{RzOK)l5Q`&g! zW|o9O8}HB0cuo06L)c8D`}^F}x{C2P0#w%n+*c1AnA=v4O^SIi1c=SE}|FURw^3Y)`Mdp=$@bp)z@{;I;`dr2l~E)2&;yp>oL+2y`SJ!^~C1CQb;U z@z=5AM=(@+MOQx84qPy>X1SVl_bFX8S`2c^pDF?kWY<*8@jm2GBkUQxBlu|`wbJ0HL-&48)$$n`Ky5jFoVp}MfmqH*WE&dp@P#ccI}H;ZJ`&BF;^2jA=5Jm`u6Td z^Qa6IU|J`sj>x88h;_=+ zNwQ?pLH>gYlD=YO@;C2DcV(!A56(wJirYz<-v938s8rzampnlFO4YX zFD>Os4JJyLn;D!5sp002M$NklEmLE3FQ zcf`xDycS0Z_KX}cGCC2^bSs3q+p#r9{a(tWYsEgW0lJwDjlJDU& zPq2EKW^vjZ!=QT`0zEbu#f?hiHD!hGr85Bk8T>N9nfluCl6T-0#?$stXZjuW%ONtr zi@>slBnoaMh(7?wPI)P|S`{?#vra7Kl=-C5?)TM?;2aZ8jLWs*8Z35RQ{BCrN|>1h z8n$oUitfIhld-z-XDtVGF=P2EW~2iEPk0Rjy4ofN;B;W5O(rf_Tdf0a3;(u@EMrB* z`j|U+PPFgTktD<|^w?^iRf^(>4z76M99;u>N!qKsCAyA;m9TCdKvN|aT;TdlEY?(3 z#vfjo6wkc+2D%ITO(x}WD}jdIR5UcnKm!gD@2THhTe;EeNh?3@Yz;CPY{)(7yq5th za93PP2Mwk>MZozuRbhwVhsu3hV-|ThHzwNmg|l~J)YuVm*BzhYX!pz6VhrDdbv9fV zFS6o^;D|ggp6RTMI|h#yKo@zUGnFv?(NR{YNe8>$Cy+2t|L(k{yZojMXg6h(S6<~w z{+M`a0>%C`2S~!qnKv&M5$tWsc9mYpQ(qiv8{}!fm@FtN1*MH&h3}ZRY$T3JqP(8h zlvh}HaoOOefq>21x5X>;Gupm=OI+2jKjZhxBaclKdg_aKpzikmbDhEYOd#;P!87m4 zB$hnnwbRb!-o#|><7GIEuVD*&g36B{m7B@W$TN*Wp!}j_$wPJr;L?y1uaq@c)xgvF(3Vue^WO~ zPyLde1jDCHo0fK~@??WSKhC$HMe#-ThY#<;vE}*H&sFv&y-c>SMZH%2yK}A1?&r*c6%o9rdhM10Wm-BA^^St-Mwn{ z>P!-jy5WYnoMeeose`XRRX1q^%QvO#rCx&1)6d~=1_+$DiEibo5y2>+KUS|>n?26f zu3ZDhw2E6eqP$y2Xb-R3n?_!7++1hA&rDO6QULsiDa*6ct|~%S3;QYYk2&o-cp#Rq zS;KP`Ta%B|mkhsT|E{>>{s&?r$&O}CTQdU&$OmJ6j358|KtqWRGCa!Fte3##@s_Xy zq&W|ht%x}@rW2{$zh|X_0F5omdtA(N?Ur6HL}cJBdBP0r%?`Q%BVbL47fIzO@_<> zfO8SVVeFhg0O7f`M%O1#of7L{xPAi(G@vkBwrQOpWLMjZfOkzMYp}tru>zhXLEr>c z!CNrZ>6MXn3sj;qrsX>om6h?wXP-@nX*g#{XGH@}n+~UQEh#buBn5`=YIr(NuajU3 z%~ENiJk6eF7M#BczMg3C_T)EWASYi8=B!>bF5a);Dex%F&MP0x(fRwHuRf%^^b)89 z$jtuod5sd!@ik*Kf8LxJOP2A z=Di6*mKDAA_S=kcfg>ybEHg%C`<=H=zx(PxGHjWyMs)&(^F;A_Ur8l_k@XN91zH0Q zyD?T)uUQ-O=FW*8efn~~^9>orRl&F&Mih3u1Xo^F67_J9&9?ivs8ho#l@W5$k6Jg|5l`H7HLrzum{r z#Ol3AWBIN_WGfiDw15bYCRRTM` z=%(K<+O=tuPEs|>3p_F70>K8AVxeOSMW!QOi%J4ZNi|O0%vYVNfHNGIr!!Q!ZF5W` zSo-ZpewFvwihreTcN%T>Y~LoDHz06`qkoZYXezfVtXVC1Edvekp8wgD_99k6$}Znc z2Mn6Qme3Ro<$f>FSHg;h3^W`(78^M2V*Bn3v6_CoK5n{pARU;m#HksQ#;t({`SmPY zUXa){9t^Nry_H?&2@uQE%7zNp$o%Bj--wP~y2K45i>*$|oY-OHU!v#;Nn*muTz+f#lQxCm(Lx| zr$IH1TgVTAz-$ajInL~>0l}qK1spq(Cj#_Fhp0Qmcnw@Jp%#156T`rt68<`Wja%j3 zpT&8NQf1bP2KSt<->{yn$V$3(FOPBp7~{c8w`RDdE{$5Qqt+J%Bwu&Ss!h8JIqHS5;J6aoQzcI}9E?aO1x(4l!Wt~hm+a^~zD&-@M8*(WIV z1=rL_*3fkfY47;zLQiVa<*)#$%|eXq!>26dpPPiQ+NzcG*04Xz*b z@n?05{iCWIy@U47=M1vVH;4}47}0yeK*RGmrAPPf=cJ?2(Yd@l%gD7gTwA{<#yC%9 zL|mzcyjarj_606PmYymz^l@(203+=gVZho%gn@>aUVbS{yybTt#wKNr(w0dZ0NP}b zyTs?oD}_CyOqFyv45AkaYcp%yl7jij}7L1uE& ze28l+_ae?&Ai?bu85DE!V5X;?cw&!oago5YI?&^Z51?kSH%N&p^io zdSE1`uucq-^A#V9YMO%XX>&uPRNr7^I*!oO%7^`jIA(L^%y@V9EUHhM5oEYLt|U9{ zsVw4vV|y|{>LBQojx}qiO{G2OeR~p?!Fz+((%v~|pn+aAo3?F>m#B!_v2$A{^-LOe zEawPSoqg;hd$VN#ucSM;i`)VQeZ@y_C}oXTf6G7>!77+6yZU=X>lExs?e_uw`xU1= z5NI%1q3xdbDp+RoYI(-2xA&a^Ke(DW@0o>6 zY%EqZzpK6H!+@4!D+l6yNv{_3wyL=3*`YkI-&h&1V%M~8-!5+F)SBkan&x&DonueE zQu@Wflqq;ddsplcx8#vLIf74Bk!Qfa3^Z^*1~j)Z_hsllb@%X5H^j(c*JZ_>*HvFD zKVrB~F;lzS>v(^zivd!3)N87@^C)QalRWAX;+30eR8Am6U3deP$yfI6oBC7#FOzxd zXU58FF<*6R@?`31sKI+#CC9Z+Bir7Kfd=)I4bT^1^O-1U)x2fgdh_@^<;ZO)ZmqL| zN zN3PmHQTc^AUs_*&_*g#vbb$sX8{o+7DFK3Xx-giq*61+)VN9Fyb{=opysUAIxo&s{ z8nDRX1jb5cE?9gWWEu2~AOtv+qGL!>GM$Sm6V}1t%e`)wGDcQ3OrJA70}X;xk8YeF z-K1&m^V7L-sbx6##`&|#=ORY(M_pTC6ooqtF6IGeCy)!?mNrjj?rYYrivDE2t!QWk zP`L%cqjNyZ;#_kK63fIDX18;w8r_qr0v4!}nNbWHi|(aULAy=CqZ2h&Y6IriBY>^R z(&mvqC{>j@h?GL&{LO}BbPOgJTm&cC(4#d~)c$Nmg$h|$W($ZabyDqxK`Bkx(N&l)8lvK}SyD`g=qxt%qCe!RbUQQUa*&728N zXLs(oWZ+2C?EcF=8^IL#HFDDUNAT0wP;oNvj6icw>6kDt!Q8DAuMs5C7`*51yE#s) zUG8hr$VwVPlQg6uvb4#2CL*bAnER($N3$=|T>5Chc~52%_mUy4sHlhqWOTZ~FFHoe z$le>>75JpLuR0jgTqSBWvYLvEF;9^_lpqFnTw{$3$M?K&x7%#k4EV8iLI-BVjW=eH z$2sQlsj`@3Tgk)NX-M;<*YcWXUaG(k@~IUD@}&lJSrannyuWTeU4NmuC1Z8!H;l0a z8hYUvnWgi5YR7Z_b-7nxi|ieJ3{W~MKK`8ZEsht0kC3~f^bqXCx6Gc$?ouMj{fP|Iiho$R_uM|3}=Abwe?ZOMZlR>Q9+WZ#ywQ! zNLF%j@E^(=3LK-}{~Q=0zt)5gYe{SF{|tb==M7@#=uQJ|qdrD&D$@@uc+;2n!TlzDff3$+yu8n|ivLvv=9MxTnOKE^~X z0)8+`VW{#qjr>%c%t_u+zNC*oFUF9Y_SO_i>wDt3T%Ph;##Sc-3}?=|SDo>>;p#X$ z^0HYbdD$RC_3DDwG04LoxMsmyW@Ga+Xyc2lg(s9;po$^`4QI~B#=S?Pg0A59 zXjoI&B{3Q&^{QTdV#LtvV&E11(y6gOz*&?pv(9_;n*6}JY6Kup&`P68qd~{$RZ6`( zb?X{qFeqAF)+}kjN0SE1yM|OMUuct<3(sgs6h_bgl$eTdK7AOZa6h9*Q!RY&-MI1A ziDd1sPW&)9R0N(e&ygjKAxjhuKA6$;8p^zec{&yFVH*E9)Mf$2h1~=iDmPZf`;?Je zrgSlz|L7f(0Jm=lXA8Y%?yaR<7Wv z(2jA_jbo#ITROY*H;o}NN3v!^U-;B@^Ip_-8tppq((Z(NYF!Dks@0G;%bEA0pKP+c zj?*5*mj3+*#$fbRBlaX4gvp?z>%}sr#8t$;0X%W zONY-Bai-E~y9ohJOQm~JNn@pw9sE6h*Q3D1N^w!%L6B3I7TIbHJZNLkBaMIThVy== z7S)af0uF);Z%mmIbLPy9>xPerE3ggPl9g(R!)XA?3MXYoe$?(jcoV~zX0CNj#;qZ^ zQ+ee&8g4ra?W@bCD8B;)lCPt?TB&X#*yjjoZB+x5%>Oz!|GATv+s*Ir!y;$ zS_03KCtqqXOP{mM-*vE*U)n2AlU{m}08jh4e#nq?=uEH_$Gqj#8JfX;z#sCW`c=6R z>(%Z4mz4uxP$~E$4|p#8e73|)Ap<)e$7L|bRqEJiB%9Fj)!%)lL&MnKm+SCRgJ&>N z1Kk-E_J`FD+6$*McsHBC^nNNE?xX^#Cr+>Oq@!rKLw&D2m1NxOnO&3)%B#T_dC_sL zXf>ND{aj~*B%29fOrJhInp0(P8x=@xsJiog`66wJTz$<%+`10Ud5gMy6B z(}uD3<}mQMdc%hJ^^?Di$0xl+F9xtj+VYs#1D)5lC0i%J4Q$#Pj8_$0l{c*%<4P_; z!Q=dL20pi{!JwvpGhmgxlz8lVgBLuH@jL{+Y$TI8cO5v#RJl!k6IS<|P*QJfg%RhzQBLpi6d5LhFKDy}4^ zV7KTHUf}y?q?JwSo$JXs1~5F@P(7%9;4ztpNb(qHcyI2UXw|Y6S^F!aKX}j>oBqgw zgBffvKv&`u@7rN@8eKQ_s=-m;vYTc*(5e5U zD>GOEt^J;X1~JpVX6k79-_Kj!p&e)-#rL&`E3hRevF)Q>r%rL#?RR7~;!(EPio+Rj zg*rlaVtC37Si@Ku6veKUPn4(P$wKhE^zk0^w7eB7bBo+4Dgwrg7@5r@-J&ceXkV-Q zJc3wisZ+!;{gDFq!2#A!d~=IaDbV1_E~ScwWjO462|C;~?q-5Km*@8~_yxacXKN3X z_#`om^-MZIdu@X}29x=F1gscjzcODpZlxMy?OFmQ%Q)V)QQSVBW4=3fO8wz6^Uhzp z-7RZYU%6E$Z31ZG{p(}7CYQJi0v0|)O~yA7u<*mBoEG!}O|j|aL>2DNy*uN^yFM8= zj~`FPO?#*TE%|nVBD{P|AJ7OY{cj$A+b0B6NE2;gvh*$>G+HS>1pKCwW!$oUJsq?! zi?P=akG>cb=LiBEp);!A(-Cm7j2fO|u{FRm(11{ynU(=na9Bf`h0H($O8Y2_J(p%u zv)`Q)ZD<10vq#SiG`MHaQqog^YerfzKHa0PQ7VwY4e8Kj)?3FGWKTt{@EA1%6l>Fw zdlv%!#@laWD6WVB7`I(Cdo`YjG*uS%2jI+V1Xm`_s58u`K~V@K zijwPCs;VK;0A{PCN5iBSC*{7*>xT`?hE+ybRlC5-9st*jfFhgXDp?gO&Og>Q{6(T&lSCUr!gZ-CE%f~jtM5*v)e%&FEdDdw*;UHqVv@V z^6C46tWnu5+qU5}zLtjN=QxkubGzLS?cW6@quCy-r9mgCIzg*P1i9=3z^lKf(qs-A zF9sk~aP~kjEAk#es?G!&MhzdH$4Tjo3PdG^X+#zDL?M%<(RY*1sfO0Q>yK+;p5 zXM7FmT{w>GHms*qZ$(x#jKvTda_u!446)m{YpBU4h+7e3)=Pug>m+C~M{Wq?-~<&0 zN0A3Ac^JRZWlgEnsGZFkjk0cF{&jFD#sc0RA*XSBj5QHd>tIOKgGS1gk=Jx)Satt1 zn545+1Q;+R`Po25XC*Z7zK0I5M5oGAV z@s@3x;jj}#QE}R=5XG-+fM?77;NY;nHE_hMbF5`GGV>b1=c>{XyDCZ>N~o}`ZmP|z zQQXz>$S+o3SxQ%rh%V zWGYyYKV>z8&YxY51)qxqd<-;PtZJZvhNs}w1}a6?Zre>@DPj{M10u$#%Ll~eRBGIC z-H5oR-@s@>=2vCty*Zf8AWxh;u05L7F&ao3t>T8x#VYo|PMY*WbnDfNy~U$3R+=Th zNmC!8`8ms~kC&SY&`xyft`j1rHID0*`r5Jl>W2JS$@{GIfeRA$Q<-_3hC!gP6*WhKfy# zrv;%YO zy>OQKS5N#%G)di{BP5e&lTk2PeQuyZJ)&bI{$3=|P@j(Mhrxw6sA!lse|8KXF*1)+ zZqXR5VxDecGf178bFkL{y=!_F{L;vEt#u4*;RuS;>g?0V*m-cSMng{BXj~RssJQ$6 z)6c}d%FQtz!?1g2dPC7@&N*chM#gaM)Nk@|I@jrZz^dH4G)daSgVNt>4RwgspjMTv zz`%X}1)9r&?IW+hE*cY5Mo5YVyYNNf-ZE?Gq29EjK>LHs@i)lCdMlqgF5YiCUdVzD zhriDuX!kmf-9+{S4rEbZ&Gk@38wGfMRR?UWML+M<2 zgsuIRta|y>CqKzCpR<5IZcu@93Gtgkq9dX5z z<{VeNF-a)TxKCc)F7`-g?KJt_EjHTUR)Lx@lr}boeg64pY0}s@`VSaDu%u`judV08 ziM{f7ftl!9cwgsV`%9lhy`|l)gQ`rZ|IAJ+V@I*;X3m=%Z)30Cj4eD6+E~#h*7{j1 zuEgH|3HFiwMrZmrNK9y;MfXa|EEk0>COD}__n=32h4tq3!#p+WaB!%7YIS(Jo zus=IjX|LauTl=J$^38P(GG(6}WY@kKZhL$lKcPdnZt*Gbprz|=5|}EOYC7tyruu`+ zq+JBte}w1BNAO?{KPMonVWkYUk_ z2=_UhIs*+ZRAxXBYL%nswz}w!qf&rllgjSZ5oqdOVi>}J1QU+LOiGsCnfXq%CD70p zA|ZB_F@N7XLK<7?%|DQmErN}5?=|O4e zh4WkwQdVRBLOEe86ghIuwa@YQ)6mkaj@hc}e2(}!-y?6&_xGFvHx8VN<@;!obAV&v zh!OaB;GWOMaQOI24A%~1LF%D+>|0QSKmbe|>({M|KRid4@zB1^iu8piJ9X-mhKY`t z^w2rdVE5;Ybju_1Kkvzd%8|xas!QmuA!m~~G3njKi{n+YUA?GiaO*^Sf*qb9fFvRl z7zfa?3WT>bG#xqC8n%S)8YJ)s_ge+yvIap1#4b)?z-(m;!_;|m;u}Bu&%DPLjL{f+ z^enFyy~{a8hpiJAsFt{R);$i=h!@t)d1*itIKvlspSLgym@n7-{{jtg??o#bY8YrB zQorXgfrdSl!=8@{>{cH)4j2~w`&=1ghmVSD2Mmhp7-^@-NS?vCtxkYL^H@HDT*#~0 z7vzoKed8?zkV?2oc);2^V2C~~nOalN=~;zMG_C5(~(GrI#Z zm9t~Vj^-9Nv)}W{l1`)}^RU5#6FaPEs6(ZZTVQmC3=BZ{l;1>2;FI*+7t2gPQ+u zRe;$v4c@gC>oOya^h*ST}teA7))PL^7JEASPX$a~1Gc=LbRd+&HVt11C|C8YO| zUb*Q#1VT$7kU|NB5{d`}1#}bz#WE_6Gmc|L9osmHLsL^wE0t zbTp9BpaZ>s|5I}B8j~S#7}%E_)$%TlJFgOdW)<+O0%?$lfQ@&+D~)+G8mgi!ErOn2 zc=3gJe+{Qam382Bo-?9n_wES`jmYB2uEJ4jKNfkja@Vy8ca=FEn`Sts5hKoW%NiIj zrcJ*EJ-y8Mjc|Zl_IM)c*eAequ5M+ z)VW?Aj!D}ZFTM6!Oq@6_do-NL_#N7|$6&9YnJX%NIvAAO;$&%j`MbEJqoEF|?nzkO zZy$@@ONmsKIvf`ZFJ8WCRXq66!?AAZvKT?1gYKQWWF$~rlo#tvt^zJ6J^~l_It>os zqEYLdHHuZtoJ9-c?%$KqKxURSBffcE))SeB!@V)36FM4dFtm;aA7Cfr%MICT=gS-W zVZiBVV2{0bX6C>{_yXUMXV8?J^=#wyTKe6TuiqHs7HlBE#vq^!!Y4)yzb3x$$(wOB z^vBUa6UEK%bF482G_%U?_Q)h14LW-2W4Jhxcg<)R_d3m6*GE}LOW1}*yAB<3T%ZGB z9EsP;WcO8l2w)`LOOwhJokz+Q^$z8qdt41ZP@jwjGgx1v=gE}uGjT*gBO<^p&zo9wA%+QI;x!yIuyj)D>K#0WeETU!nZK=BoB@ zvUiiGAEiA2oYhfFSw>=k=$ZY#nD5c?xKH6&(=ow)nYa3sy_}w>$#pq+{}IZFdvxoT zdnj&;&*FWK53Jov=bd;i{28M}v%arPHdx_FFUoF@)dZXm(Og*Nj(!AaLfxY#zkZc>S*wY*p*+j}hQ29#35yq4VDfNQ%SY>(Y#AFQ8HKe;Wu3J9_ zoqBro?A)b@43nPY<}2_e2$_$jqG>VyUV&irMFJ7=WGb~#+B1>?0-BaH;ms*A=Jhd@ zG_;{Bb|0c5z436jDilu;`49}shEb`=aW99~fLHh`sMD|mp}n7sK!WjM3ZEXcmvNHV z(DKCoCzEDh^k}f@ljBr_2&-xAg3KxuX+XmuR5(kifXS>e>M~WA`xzb4(O|R5MN7-$ zfrlPU@A)um8oY;S0-pFMs);_4gl-RQjqYO zr4x@m@-RIb22eUNfXo7q&MZ93e#iC8kkWAGZ|83mK*BL1E7SIKnXrn14hk=w0h!J< zZXD6?sqyifZla-7za%arE2*q8-mzCk(YzP$Cj;k0_gsSXe!|2#IkpkBrR5dz%9vM@ zDUG`3+Bkt893JiD=L!PxMo*=31|-ZCl;R9(cj0L8wfoIneFzH~pNfm)>kLsrmr1RH`MpQk#B3DB)i@o7 z!!*vMY(>S*ObDZu8Z8QBjY4r+b;WyTI98b#@7AewLy zWh;Gp_DV%iTu~7PgVRWIJkxfK=vYT4jMK3s?3u5E!Zb!jU9%P~lF{1#;qAAl5vgcE z*+k1MJlU}>~K+Jld)UwrE=$&vdQ%b$>XKwrlQv1(| zJ{>vw3T9mwp>q)9Rl^rel;bBCW^>ien>Ucr&_DW?91Xxed#XsI;tsGE{u*NLw+g>F znT`hO0=T%B3c2Gn>KI>d_f%l>)T56_cQP7I!=NrB%cdC)4^RS>L_0)_JA@$KvzG`c zPJ}|hGoFelYpsT{U(Gt*Dk|_CZHA+?eAUVrJ9Tn=`_5mv#Awa~wJ~~ktQLJcl#$VZ zqk-`bpllvQ$+d?~Ro25mDb%?mxXogGA37EKmQH8{0#fb^u7VSXj>Cu{qhSkN1ag&9fN|SWGH#B!qLbc9O3Ogs~j1DFr%Toq9SIZ zr0+*rzVwny^8_97#H<(jfV^Fvqp>ATi7Tb?l@;7BX-C6InpFui%Vrz&ZbPYAL_}-` zS=O~%HiImqySF%}QItwKd=`{TKA=J*ZhAlI*w2R0U7@sPpJGc)TYy_3Yj= z%kSFjXn+@*tyc800pWnR`>0Ws@`G{YnaM+ekB%v6)guK>S=Tt)uyr#5i1B1JOycyJ zUYxAZCj%T!NcA@ROPQ*Z*h@SUHYqE3P6LK5uaA*a9eqPM9pGlW$tpT%Ge~6j3XJI| zD0|$nqB71!dG6BDj0Vn4hi=3d<&!v_PE25KR)dPSxNSCLW<0U~IvHG-{N3oQ^sOOg z{qDoaZgr0Hh75_;&01uZ8rYS%o{lPho3fiZ8!a|VKzfv(q_5H`6vcO3X`xGbwCbA# z2*!>X6T{9wKeNOdK(GErTJ|9?R1T>F=s?ox=30tKFZ8KgVm#?r`D#78?|Hnlr48dJ zPK-_KH^kLfUrmNkcRm7l`MqO_^XdrvjQilU1n1Ie>OO-Xg(IMF5UNjDHsNVo!f#dO zsw_pCM6ZCBC$x)8k$*bw3L_3Y29`Nz_EZL_tWJ5#{oQAIlH}!4tis%scue9n+HKBu z|09pY{m(wj{;`cbye{ii6-R@m6NRIpru2lDMfsio@tSES4W+@tkIib3rd(qcbkM5s zdr#`A3O?1u*;NH2R9;-U10DqNsfN$c-;L@9Mba#!nVK8pxJAxOE-TWrHka zKLKlT+(^5!xfXb1rhvhXsTjN-x!a*brx*;qcI?oR$$%%&lRBg_PrUS!kGY59xBM_4 ze5B)1hl5QgjriJIVdK^bpB}YNj*RtWxGG-Iwq( zC}>z z?4zO{nOR@x0A9*`6J=x<;UDP>ddC-yHxwpbu+2;MyAtH^j zCSS`7lpWs7->MHUV%(Q0`)G?^HIit0Yx?9E^)ETdgtt1Y`mX#+*lN$nx3p)(o0Qq^ zF|d}V46NEyZ54cS)~wkC3FzfUM#Fi7hj1KiefR*f8oF@q!d{tj5P2(qa1-Sh8FT;+ ze4Mf*j~CX_z9s(B!wLWJ**QG9`LIgf^7YfKd5VxPb+!n23OR zY!cH|XsI+x>=IrIDi`42+}|$8>o#tPaR|(EykKu*yu;+ zg+fyYg2d(#c^bSaG>>6;Mi>;FDx&si@CYl3Y~X-_S-Wd=N9HOhL{8U`1|zVtq``BM zWmZP!Rk}*V;yP63jhYA>H$!80%qy?t5n0yL)n(p!ZLmFtSXfA!&xKh~!v%J7Myaxch+z`2`LJK-!e4b?MM7I<;+1O}J%4&@v+`AP%8y z?B2tAXmnK#p8F*i&E3=b}|5=nj^^HNNafB#FS!0Bu{V(>DO`#LThL<&g zH|Wn=Ri3~jU?M%r(<~8~h!X0l6P}=BhkVOvq)Uw!ew4gMfef^=jLCFujUt^1(s50d zf8Z^z@sc;GtawU{O0;Eo!%>7h#YLLQqpA3=b?f50jzafTx^irlEXU7NFPMiVark=* z1Ax~??kuBPSy`D4pQOF>&OHxDQkUe38oZ7NQ_1-k_yR=vt>a5WMxf;L;*Ihv`LT0? zCwRJme8!`0SD+9XT|9?0c$@x;A1R~Y*W#eKnf!n`ma^7BrlWjPK41?5jcI$q=rFb} zbw1e)mCKgr_quoOPS@?;d18o;hIE=HOcZPIa2^`C5@BLIb9Oh12TNrBKICW0Kui1H zeEY4;XlRH7+*2)jvA@#LP9id(Tq<=X7^R$mH!{jmTJk;ksfHn-*9ouo0Ps%FkNJp*kHWgZ9-?9jgHkId#|H>?W!u`P|agJwo zpP94g#B`hu?x_vbG>TM^lLzu0=j^3JL;NiEHl<*`FPxl#vfVGIQ-j|aAzg(d|IN4G z&c=O@VNIFL1N~NLd z3G$!?7)G;^QI?n3N8x0Qb(@H4D5{?(PY_=cCkr}~mgFruMbszLIp~snNNenY_-^|C z+ta60p7CxveY&A*_wCa+dxxl_I;Q%0>Xh)oLHM&C2Ip)TzmEuEN73cL*ud-dwY>32Qy zI79<`(wjQD-*X;$`W=5aBpX${---jr{vyge#}#Id>kmq@(xBe!<0r&QvOX>#`_^WV zX88DB>8Y4|p-W5e-b)zxT+n|(r}>_ryRXoLd{0M*y7pwspqpYh4WTK$K{shgLtSS> z8tjawUhiJ1YiW#&a~><{xFuaxxJgsm65BAQ4eELPq#1q1sYs{eXrT05nD|3r;@%c~ zhCSf54hA0%>^yv^*QZkexg=gXkB!(Mm7IuV52STC9rDx(>=0=(9VI-c^k5wMX4;vo zNmvUPWs&ohk2L=`+7&lTsc^FF6+D zxGxL^pDyS^eA4Nl%_!V;3U7u_&RMu1X4C&~9qU-PgU09Ex5Skn`#6q<%c5oDmN_pV z#46m$5AXGVb~K15UdKM`1;)h5clSZSi(!5qqqJ!Lg4hdi`ylYUbm$Nb@W|PFAj<>T zRE3LMZas9KZ47LU;$+Gw0$b!!5i^w%UwaxC3e0&R@f_;mYY~NM0}^!V&@s=-Eg`QA zFdrb5!cGNPhl8gwWUVIeyMSa;BAP@fbA@@^hrmeMYEnl#cJ7?@>J3Si&SP~T6eFY6 zK_HP$51NAAdQ;)C4JBQLK_r%$9%UZf&+(m$srBQ=jb~+t<3v2fEpTGg$J>`_L=u)z zWd0hE8i);1WIW$q=S!ZzfZ`xVr;^JUK6@1kRM7FfJf_tuEeh?e*zdMkScP_t!YE`OxAei{fk|E?t3-1d+^ z!JsmvF==$i@%^rhQUhCIRELx*6&)GWn$<86QkGOiJXWoh5qDsq!1DXv%Tf-XRT@?L zjT8w3yWQ&PF9`$TU)o=zIh(d@ij^xX$y9kS&znAlRJSHZ0r{}V(ys9$Bka|;Z#ut(gWu-|#TdY+WLTIwrXnYvDs*K2 z?uCY``|BRbW#L{O`OOJo+*qJ+VEUArbPUQQ!I zO0({N;aR5;&3I_4olHf>Nu8QTTj(8%gwJTCKwrRbFEHB+9;Kqs>%(MH=xAV>g#(L? zRfx0wdjD#0_(zJJ@jMkxP6ea1Q%Cy-&I!Ct>^{p4f5r}HI^HRdIaB+uk;`K0Sl{tG;Wi|_fYvqWTC z!?+qR8*#YHKYC%1c1HP^2WrfuOm?gz>yUn>E$PSgB|mjDMNIzp1OW{h_gTZ+J)J#k zX4Z_iZPS*>^a(U_K0ep%(V{w#RMLb+;ZWyq0ujQ8n`FahGapp!ii|Su0pc5#vcJuH z=myJh@HB1GgyWIhXP=)&_2``eFA#TyhkIo@v50NSh*zFKgOXSWW6;1x&YgMh0rs9I zpdxJ}&gmFl*6Z5H(zE9+Ijoa16em7wRnCdm&d)h31H=!ngpu$E$A!BJZpqkIf!A?2 z>5Vs%e-+*Rn^4P)BZS{rCc{s_X`KkHm+|a_WYcA3jI!DHQo-e($^`dWTJ>3@Nj|@1 z@uGCJcfoM67F?Q;P90p?TzZJ}sT;6v_ci4s@K+w@jrfT=g?lPq2penSw{TLysnpv` zPvVB-JGO>b8h3nOd~|FdUK(xk&vZJATYN{^Xd1fk6em|mQxz4_h-|WxapE@tXVgiA zhb)d#t^fc)07*naRInB%IzhcGJ*olS3xC(1GMn`jPKLt4VRUpGd}0Y>P6Xypy)=fJ z?3&|;&qckPcA)T%Gtv;%pE&d7JGBT759?#fZa{ppu8ES;X!;Qt5q(R>w0gAV=N zC-BuZ`;f1R!y1gsD#}wIYTW4f=-9DCv>>vs%*$D_r}6^#)z?Lz0gNKyEX)p~UjZZe zOF9~OPX~nKZ^L=D5MHpXygd0|J9tf(PB`w=n;1`eOd#;L{6PMk(R9}8eu#4#rQX|P zBWtMVvsamcip<=YB(dp>;$p?gW?rV_|Cyz6F?>!TDnXk{u z%Xm+m@bB`9igW}th4*%+^q?v9YQWIaDP@^Bsl2hwSGgh02m{A*{_08cd1+YwpR~+p ze$TZnShOe>l4joqhhte;ku9N&^S8p3p$a&lN4Sor=nm4HK{cH?e3-bKFas{aNk^n> zRsKzz{!XmJ;60se44s;(Tf;N*3w+1ld%3T|Uf$+?q}Q~euutUe>Von-=OxZaYnI^6 zojWfZ822L^Lwb@+iMvHJWO`6Zc`oXZD&NF!v`e?~9D4p6vM1G*`vTs_-O4rA{Q#LUd@2Ml-Bc994D=6jO zfFpxGdR>YjfxIH^MRA{bCH#SDf%iD3p`T*?>U-)?z>e{&a(^>e3__G6w=GrH);gX{ zIGaSbhMt6rnU1bO2Zn>Ed}2&-THfXUnZc}GD9kOp&OUF<$Bakq!=*Ua78Ar?i~h5A z`{r1;Wo_K_na{__D=v@Ljd7kH+1z6GxxF9CfBr6x24G!)!=2=U<>W&|g?y9vCXOE$ z?@pT@Kx55Z$od&rZ?bsz`5FbqKGJ2A~g*ka{y2z{mDk+E(i%2N4sH84fxBy~V zjRM^vn!p_Ft)S3!d=XABuBkbWqnEJ(3c84wOn6w06sRVRdH8_rh+Hx&owk%YnzT%%Xsi*@KtoI7JWwTvfZ_iBk( z2APT(2=81HKFn7~NNp5Ai9+F}A|Ufsh$z^EeaX?_zS!t-A+T9YWZ}%=7jleXo4mJk zlOajm-bdv*Va4w?RAeOXr~B%@%S`=^V|&!0>(Q;^R&6`B)CJmx~ zEfi}EZ3VS^eGp}8-(I5D>~$l`DjL!~3l*5i4)EeTIvVy>qZCB5SU4kSs*wet@T`Hd zZ!^eu*KCjJluvBmMHa_ygcA2HYu*kT$GOp=9bKcF@qJSVO@RidS)KThp}-sAAnXBH!Y7-3g6AbzC2sJUxRL2^%u%5x-n*|L88m?+hhUgPOuY2OQYOqcP+3t?RPjwd%=f&c zH}O+`pmDKu-puHK_PMD*7ZFO7Zf4|v&P5tBw}4oeTfD2O1ljaFpsO*}QpU zMqxVPTvNWPz#fel`CZ0xuN>dhdikR?pqy~-&R0gJa_BwesXV2lec^(6nFibf+-n7G z>r9sp&1%pkWg9|zyrLOQn%KJ7l<5rfO_`-vB< zUq_cPaUCvHnJ52E=O*I|Z(*aHE$Iis+&KW2+?Q4C>sxP5Kt6Ry!>Az+5~HocR$W8g zz`1%!Q{ubwRh>o!-*J=H_$>F+dvZVb-Fa26s*IIOmqdrIob=JAZO;8D?TPZzx0}R6 z_~uDZz+OJ+?^6ylmS16e_)cL^it`#y`NLXU=87{xW2Q+1jho6RbIcnJqE zJ)I5Nqe160o8&%OYEcu5U3z5OsWHcO%zfp>YjBj6Q|dPzN5dL;F=QUc*KJ6nWikfH zFtZG}8qECQ0m~88nZPOc9iSVC6OVMX`)vC7D)!ZK$$H>RD>6OgH5zpC$ebh-JqlBB zQeG(@iIZuN0!OBsw8S#`yU=fJ*0}U(%9-V!c-de z9`gD3<`el|wSv;b({WTcPkKte=eX{Z`W}C$`~$buDZQtAYMI)89SwZvSVx2W$N9+T zmoWD_@ZPTUQ?ZoI*^0X&Z1Nh$Dy=tZ7QM&ctHX#pI$y;Voyp2p=jNX4Y+MWM*Ho?~ zqpuTA#}kq!owMK38Q|VIk3x3W$Uv_17p^*Z(hgDX33K2r{<~L}ZFv7x=uex`iTjW( zuN_kG-a!h(nWDR^~#j2I;&o;8vpvm@SS=z4M z$4wH?^M|}FbWofOz(L$G(@aN$*=O=b>AV)E71*fmaN&j3O(p>{N$HE ziH}})O|<2BOK;=mI`=eL$dH5u`-vzPGtDKzfU3@K;h`9JEzV8Yw*jG>67AjtlUz?{V8;;Fe)otB<*)y5 zm-lH&w_}fmT8|OB3L*Z#y^LWPL;B!+9J>+B&ST0{4ph4E`Tp7EdjA?+T<2d}qwkA1 z4KbqYa%80Sg-apy(s%uwYSY}WWA}l#{_JvJKlmN@!y3lg2w)lMwl&m%6N&JWCQAG1 z>*8Ji`t!?qc$MZ=yyCP6{-|HGUN$_F=yq&edlY9JPh9!mT;jOvt>objcBsP9tF1_# z15s7@Hlci#a9umsEOLL-jE!qnzYcv@P!yT$p@RqnYDQfu@-cOq=1p5fn`VuoX)T;g z2X{t|Ll~^|FtBuDAICjv080xZ1dC!sQ~H6M>(b^eW)BDKa1}I=Yu#J4&rFojF+Nf zsDJsRCoh>x1<7!Pohvzw(d!;2wM58g($@z-1MU zo$EG$Tl?c$UKISp19w)a6yWUp(@+JV`$Iw_MVU zuoX5nQGlxH?1I%)KTKEgdR*w_{*(EbR_H69>ebzvXgWe+g%WebXiw z|HvmDMtf;YxEWwvufS3U-%pU z7S77BWAWbiS`t)f(5z|dHCqT6h#SJDbom|eS4t@H=hA0?=~B4ceJ zycr`;`FgA@6W_i5C!BZ8COm{+NpES*-wkSV%2bnv7^_ucGm3f%XZYxEz8uqs_i%5V zhx7M-b-^1?8PXZJ6?zix$IjFBHDQA{f}jPb;Ef}fIITXpy7b18XW{Ai@~Y&;Ji9Mm zIvPr)6SXk(YcXzhyjj%{l7$2-|~w5@)TiqEd2fcvAD#`qnEm!V;_s} zeyD8F!H@XVtG!)67%=Gc3e#wzj4((7ZN z9Y;JlmR9{-oN0>AQIk`Q%-Grm&b$x5`Ag&b{r}BX+P6Bj>PO9nMen&i8_5nK`%>8d zHT?VFJ^mW+7pAy#qAmfgY>G#B5xq_sua}gv>6z znmp?r(+id3@*BOMdI^nu=20$;pS5hJX% zYC!w9$KdE_Fj7#802xg-+GH)OwNQGljl5Nmy)oh4**SjK2Gwa$d1kaB!Xykm_tx*5 zmX`BlJvQ;Fhr%K(cH?XiE~XHhT5g2bdFe&=EBJO;05p8qkA5QDSU;2 zWBBY`^`Lt%)2Hkmpx4q`Gb8XBF=Nd14uS*1bQ9SLtClT`H&<2`bLZbK*2&=nu{>ZG z`)aC_ztK~zC)j7+NZfF5^lmy={>d@y_HI)yoAj*!F0<&1ed$SL z&F-tUgc)ID9eOphCj?4>sj}WnSnH9@s22BhUDkfRU%5QqBfZh9Q|qQQU+kS{rh5i+ zMjemfr8r|*&Cv`9#?}k&QLEC03VY5UoUx~a#(X7={WWl=#C%Wg)-gJlb<8?8vmL~D z8=BgT%bIb$qIyU*%H2zGJL}hIQfBS;?tK`)82oxzGySWAqxN_m6h=tb>d!SJlgf>5=}9zj;CLR*)dQ@(w1r5Ix_3l;Y66) zqzqEpv75A4H}yDRUah*>J4S@XFH-SvrtI27HWYQCZ?0IEIC)0TUeU2jce0i=9xMr< zoPs%R*|{xNyk8l!m&|h-(Hsd^7d-CUv1XjqnbHp&4F^dlJ-B;2xF9bwx(klNN8Nif z4J@57g+V1%g#aBl6?BNaRL?iDRsw_}|(!DrJy<-LV*E^jbuC_PE=b){!t zzF;<(Wlc-w&yNX9mgd;KDb2BIrzL07yx%v9;Z=%W%a6r(>DjdLz0w<4X1bygc~2_x zUN$asd?Rm@=Pk@J&OEUf(ZRBWTQ))iCW&*kS|brglB9M_z4| zV?L3q$qN_f_}yAJic5=9B~hEf`7mzS&QSzs*(oCsJZC-yrv+O#A!SQ*&=JZQ&4#SUUyJ06zf^Ek@geD%vpUWGuxn3 zbrN}v{Ade0(OmisO*p>5*3x`4VtI+THd zG?09fdCN~M`731%lzKV1C;TKImMB;j_3okyml$n$oHcA{Hg^=}(u}&UYg5-t{TKMl zvy1}E!!lCO=XUOQKYgui^}CjkPM$C>DowxR8qkFvEIoT={}^>h=~bQ2<9*fb%sjF5 z)rhnDsrMIW3w;MiIp5EHmcLQLR7sS4%#3$)?6Rh{qjNWS0eXRQ;vo8xCt%np_#pJN z2gBT64`wr)6_kMp?ya1uf&Q%?sXnm9>;mAjmF9d4$&y~a(NjL?pGIj>r_SgGWY9=2 z(xmt%y_nq~zL||H%{b4Jew|Tzc(uBiNSnGM_cUAg-FK$PO5W`WEIOkLd&*ZmWPsUE znPI~EEoI3}OyHiG)aovb?|n?(S9Eg;KS38Dk!tbQkxmD)6IC7q&q zNk{Cl_#v+{f-kReT(c|O+sx*K#{7=@rnqHh#p=qHF@M^ObRM>5u+u2zXiQ*DxV!JE zql09Q@4S-#fJEY*^eUgv2k$7KQhsqCKldcN#f#?0oE7iqG|%YSElY>YKuuf($Hhnc z9ptg_z{3m;?akrTk|dN#%@@@((z{N%?m>iSVMVi&qzLdI2pc(4C+Mnl5D^$QCg?w5?_FdVRk zf`GRdEnE;&CQgjGD6Jbv%kJE^U34Tp*JCOrKT|$UaZ+%L95Ye09{K%!QO=JqIcq?i zGk8eW_^Igc-U;Dz9}{?GK&Dkn0B(asA`=in6hg`LKsx^xp}jVeqC1723x60rI=b+B z=;b5hG#ZOpGi#^ZO!Z~sMXDrV2-0==^CJC*KR|W`b~*!GYc?qUZ?nYzoIZyxh~0!j?)epUX5n37`&X9raR8WIW=zl z8*#=Nr^n!d12g?w#*t~0;0gof8ayV|O%+x$#!S6Ku(^&Rl@fdsf4~C`jWuL~*v##n zX>Z1?H5+2oWtVV-&WX{4G8b_~{53sFq3``$}po=@$gDvlVP zFmvgR^5V0P#nO#?g{LW{Dv8-61sLqW(O|Qk#TDh* zXmKLPrF!YXmUi``i_Lm}sh$voF!>_7p@;XZ4z)Qwff9x~?A3v7q>%2)-=SZ{4v5Ci zE5fNRziW_&GRi4JWYvz{F|Bfaj79kphDOW02A|rWhH+i!q|KNp6)FuXD>mkVndMQ3 z*)WZDcmjvGnkne)kvOBGr9vdV%4-&sFO8?3e=atI`vcAzm`=wsoL?&cX*3FZewRW$ z1(A)S$f!WC+bPwUg0Mt?oY zKxvlQ36>L#88-nwzAH~n=|Ih_idGGjx4ks$JPZ&uxWqyCNX10OLO83$%U4X1m**Vi zMerMyiA9SR(TRFijKj%u?Zp>!+Qo@Ewgy)I9$w<_linGdr6iunFVk75lFhxmr~Jh; zuWMn*NKdP64h6kVN0EDf-TJupn(Lw$I3uoz5AxuoRmPIOq$Mw5nf#I0$}su6JRpr- z6bT&-X83sA)$6Z~i8oQu2cFm`E;{#I%1v;<2n)wi2r`zheU@)3Gvq^wi|`@koiZd9 zF7BZsWKRhjM7=eATDMWNAQ|?3qN^` zW6Q_naX!TR<&`TrMPe+xW?FP*t`}c_ee~9`nQ<)}2ir;W^@{4|#l!o#Ph! zpxWp@crQyPc0lLTX3mV?Jos=l0JN7}bYToQ`IKnavUSc|ILlXEw@PzHp_s2J$U5R} zYE~0E5O%37vM1T|g1dMu^84WBM1mpDzwt&~Fz{61(w9Ckolv6bxpaj8I!^8{YZo__ zfvI0`Pw_DYC>!C(;qTNkB73mUl6Z z4gekP;=A|Dau@ESfn%x0c8sXC)NapRxG-LR<>ff*tU+-ydurNzL!8F`E@2=nShM>F zNR#JFKZ%R3&wcejp1o3U;7`l+mVq}j;bk-4o5h|EG;%IR!yY?`Ios^e&=&SI2<$!nb(tJc|I zHbaroAg=)*xkn9*Ut9p-4Y&b(_QM}G;c;KXF|La@tc!7ricCAU1is&wjFV;=p5Ei< zlq@!CUq41(ekq1m=e(y*JG2`38TSSEl~dBIcqvXMKjuFEopdVPfS3CsEbY1QF8bJ0 z4?mWf10&BmGlrghP986-fiKQ$APMU<82OF5rLT2l>R3x>Ajss2XWma(xgW{}`wxwy zf%H@8llW=k+>c%pC-hWP?$ANehk#*O*$K&K{e3!P*+X@M{gkKJxV;8*G0?SMW^YS{U{m{;1j2%Qw>>h-QNgTd7Ae~+~*#SDQyTpWu>sw zDN(tyl70~jX~xRQVZizv@LlJWP8|7#DgBO}<2WfE(re0I;Hoa~+~r|98T`B`3&1gk zPEfwIJo~RqWN!z9FK6H+X=aHF@>SRhi=#X}AtX)|c;Q${$K1BGpYnNmfx7o9>;(0K zsc%k-`D-@Et=C-}C-v%uj*5l}ER-Y4ZU^0K@~?iY4gj>)}vonfa9C6!3t-5Il9lqpJ=9 zV6jFpD%f_BiZ%YtsqwXc`9`LZ+;GuwygS!(WMxl`x&2u?DdWzF9ly#(JZ^*tA#s9W zi3a7)_ov*7Aj5FdEZ7bI-e_m%ex%4`4U2W6O8N=*ItY9MN=3&xE@>O ze1!W>7`zcc8K1(SG``G~f%1L#SC6_5p1P!DN#LH6Flq7|ao3|y#>XzbG_JbjV(O_* zIKuo8B*0ZA*LleV9be|0`wXld(~juET%s0NOu4N|gV7b0mGL^l^4TXJjj795$2Y$4 zxwv4+kYug^IwKm6BLj474PNoGCTpsJvSdbs>oVdhvp0&fg}tmp>ZfHVb1+<xhm|v2gpU|-@>@p*m6BiT6}ju51{a?SQ#-gy1SRx)$7)Z z9njNc_Vm8HeihS~tR|abaD0N}bNY6tb3Ef7#?hd_S9mfU^in7&IxI|)lpa@9(wBfa zzBOY;Jp95-ek*A}F>9)y?67G|(&U<2-^@AZn-0V#9MYQsWxtMfqF2YVXjU6zXZL0z zK{UApE@&lmaK||Y^HoW**L!33vpV-Z2qRuYX~K-v8)9mu(QWV(FnE3R;)^&|^5p1= z6Rd6P)1o~?MqnFsgwM2SLUFX+3-Xi)h89~q_OXh`7;oDcJx1K{Ezj_b2@ zVkxIh%wJ21!1hD2WNY3wE*>@%hr)p9h*EMq{6)v(eGfc@L#KXRjdQI-`*zvju_m4P zt5BbOfIb>F(^ZiY#(*XbD(PM4OI|$5&oqksTw~B$*~N<%#}rO8_|0?A#y3Cn**I^| zpltSP^HB{>onDTi5}^ZDL#?_39o$F-HD7~MjO{-9s8vt=tD4Q5CcQB!MnC&>Y$RIv z&tLy~oYB939vKYe($P>d95wEw-NGrNl2l{?B_D7NyatK#+4}t*M2x4Rs66r5qw&I< z)8o>iL*kPkyFPk$?V9{oTv35_e14VuAms(GQc;n&fJ=Uud&76+J{rU zMv{@K&G7lxCQXX3-|@qo%U3>iQ(QKD1Sd&!%4`E2j-GNNjq5B;nF22AR8Xcs_!)s_ z1E8kSM#`y^-8|Ar$auesW{|I0cS>884c->-2yeEq7Ee9 ziSxikeM?zw^iMs_zm@B$L-DzpdE#j0s#P&(KF&2@|K@wM(I(h%$pr<@%hyXvaw z30&mm8jDGz%tPGZ$x#_sI&vUj!o&BRt8!3SndzaEMT2hQM0mjykH?E-34QgZPs9}$ zUKnju{=vii4fv6c2IR(~@}=?H2mZ+Mmd~U!9anXhF%0WnH@dWL5{<}Qs}6s+=Ypq5 z=x9i}&-a{}G~h!g!$AOIX0Q5cO>q*`z~o^c2@dcee=~bDypIvQR43OGnn5xOTM$D} zKbzxBTY}frd6Q{4?Tzu#zIT_n<+C?)jQEMjBj_1C$x=F4fSDxXO~M|WlLmypILe!e z=ZAooju6)@PuNW6*Le2yr{Di!He3G8l~=|!JftVHC6d2@EArb?Hfi=ZnT1_(=kIyqcF(@O(7WfLZhX@;yusZNZ|=x390_aDJV4UJN9#*QrCtda&s7aDyM7w_Niy$mQmNo2;lBOw1T0QdY%G4i~vz~ZnHj(nxpxf)?$H(XwpNqE_RK$O5Rf4A z9+2Uci4)?c+dh|dHn&_cGCpJ+!KY??*F_uvZ98=+@f+Dj@M*{<<@tp5z zjDdI{@nH<3LkP`uG{A7@FIgOS|KX2u-@}i_7q7Z9E*gGOoI%&+`WW1YNO5#r!K1L3 zdCG(&l0x7W$SXsYS*M`j9^S_^UL6f8a{vCH{~0Yg`QkE+qW(B-Oba&aAb}2y_MvQv zm@@m40;geZI-Sl9l@0|>Dq|RvUh6R`7NQ7^!IOW_z4yfDZ@D#w4m>kEn0xAg0965% z0ZN1_uFgA^HRhTPRe+7kiw+H=_%glvcskwZWlNUOHFsJ(NhZlUgv^&d^=anbhinEM z4KU2=C^cTY5HNb9bH0r4eY{);x4~PDfIxWf<~x=N)WOkU%IgfA7~}8`|M=eD#m(1T z6E}S1BbhN_X@g8ehLj8fCZZ!Cy`YTe9K{tc6Vm$oE z-^bWR#(f-7%R}ss9cSxN z7iVqtOgy;1`~C0Ymw3-R@bg~)|Dk7|l}uY^nmCSvE8e7`#J-B-x!*A9{TQnXr`n8F z1z}*LzI`apHK<$Lwr_WgoiH(e@}uv@)PY@wd3%A^o%+-2PxE#!{h)k#e9@eNr zF;TG8s>cyOdx6nF>0)wR3#$835uyh}64 z%^1R~^+$4j@}nP#v*8~nA|%qmhN7z?ByR45nY-6Eg*^;@SQ;V?*a<$*UxsGg8w~>2 zs&O!dl-+;*;SZyH@uIlprkmn&l-v_B07Q!2tiy5@7)c7x6h`u?#6+Lv69^{8JWgfK z2X7xj3DRk3s`N_;p3i*ud+~7;l?%?hfUd{`qpYkWU!z`;`I^zNY)xg1oj5MO^~3MF zMAiU3!3xf4hf}tD$8Ss%*$VIpBZq%H9m?gvbh>_Lq}xfRc4hhmNo zGa7U>Y}|)KbnVudgCl1WL8C>1f7G!6eB9HdZ(t)nuOh3>@_-4GC&$kpd?3F6 z)vv`RI89rlD9MwQ2O8^MLb>4Uz?g9r&S`isZqab6h>)sGcn>2rW*odq#=)ca-4mNx z^S@)5o`a*u6nJS>9Pl)h(m3*YFT0JWvCh5a1%;Ac@M3vzE%<>B!--QS$Ac({556`o zt{E{RzJ&6BV$WVVZk9NKR~nm;WUV6iT^Klax{Ln$5uc@n@cno4@nz zoYTL4@wONRFDoNsLV01?L^TZbD$HM{S=gk}1#WAYEAv#g(wLJ+1ADXLESnHdbQs?I zyWhpH9)BYG@%rmO{b^hA5;__Z9w24TopDqgN#dV0`WAO#QDOQ2E|y9MxKVG>Fg@hTlwv>Wy^s5)cEDke;T81{6q{NT$}>cgsd+w z^{~8vuX50Hxl^-RUu1xf*0UwpWtXRH`qx;^C(XWn)$#ZAL*S_?nIQw+Ug(#gc zNRYj7m~W;9gM;F_mvc08L4_Z}P2+G6bfrUI`O*j;vkO@`ld)ePJ2vjU>o+lI*oAS+ zjWLsl7kDJ{w)Gop%|Sg>e8{PM25;x~^yobVS?7PbuQRXe)0X&Q}a23ei{ zEj7dkx`J9dk;XprDs&0v2mjsA=6O1ab9Ntf7a^VDo9rR?!(Ye=CRH-KY&`}@IkIBX z;-bbLbuunIXIQi)Q%A#O`{wO2@wL&>13J3>YhTSEgt#J3s}JbN5Ff>JjXYse%4!lf z-2*nakWc*W?#h$bgEub|bo-~<|0(3>nt6aeVS?{}di|YKg!O9BVr3z(4xPKOZptPpQAiz?IjIjzKgo;P3oq$ax;46=@9@5cstyTDos8T+i;TMWH@}Ws zK67iFGjL#@TvMNH!o$$2`ZFk=xSd8cFNA@7(m6}32Ck&fjT<(k+-ugl4X+PniSl&x zwTGU0CbOV#y87zqkNxC{d^O41kxx2b@iiUCjOkiRCuCUWD4k_vc3>@Rlr8SDr&Aa( z^cd1#KJZ}N{^^_3ao4_8aXN^Z2R2s~$q(mTb>oOFK!G(B^jgSNY1TERqd{Gmx!FMW zMY6IUd-}1MG;3kpOVI6tv(M(JZTb-L`^0Z)mfxjAUtYrasc*0s>KDqtlzZT*ay#`} zV7ZNQn0J`_^VomC!bvg|J@1=e`AQ5txqsR%Ntp6?@Xvs%uvQ1CBL8*n?uVOs1a2a& zbW{bL;TVnBN#@t{ICsANm9K`yeP8;-4e{w4Z@_WaF#|H<-(hqw?N{+nzAq2b(V%^| z6#4TU*|qKa_KH!XMn(NLt@B3Fw zr*^0%OlHUcQk1)P&oodQr^swXKvVcOP!m5E0{SM`-UTBpVQ{auJy)%1u{OX>2 zqY3n_*JqFpGdjC6RG% z+P*d3dvAVBc?&P=-S@_YmtPUrUvWhexKSBXl`@*fy!801Xr)7mfwKEKJCIDA_Z?dX zC@OoVxt_}9D_2sIF+QFrLi*h7xpBu=zY>>VIJPFzr3*utm^LcTsL*HXm3uATflEec z(^z7Cj$LB7cKFq~Hj~=ddw}_!FxXD~d3S5mwpZ&S_^M#7E0&TC3 z2Jot8RfGZio`MrxtVuJj?WFL(HgQsX_g}vlvq=lM7M%I=t)GkjJ$uJtvIY)v5`r)> z-E-Ui-LV_*!*SF=)TF^<{f71;*b~bZFNzt{r^oA4-i+Tp_ga=qoW(S-gK2unRK(lb zoCjTt$Q+z_H~W1MVU4(nrVScKi^dJ2MZH?lm{5InaC5JMjHpl*aR(q(0X|R=5h5^# z_3UTg*O8jPVAIZ+OXQuNi`02C7}rf#Tp5F?vF+cd4;d@%QEsc@P@p{zxM_4mdP<|n zvDD}iU@DWsUWY)DB_sV>ax?Ya8F2^E`{Cgh-*?bhwn#};n6bCa z%Trm*GCG6(g`yf4%7T}XS}zLV;yMk(s1qd7AZn1{4q!gpaW zZ?H~sHZoztM~qq8y=yf38Kj;;CFD6ys=_Md>YwzEr!b}$Ul!4 z%#1)~NYW~Nl6gtD@^)zz(4@>t8gfsdQU7)gd^y&m8;lcNK4*-k9=p2Q)#>7~2KA604*NCq@IdS* z1K|pyj5;y8KvN!vY5xlOmT(t;#3KU+!d|?w?||bAd-qd=PWdk1v4>Fk(xowpOq)l3 z_xrdMNBgid&t&Y*)cLkZIH%&w8pZXZ-uj3!DqI-Hy)bJ?`V#-Wr_GGLbTm&V!13bi zV`DP4-(S4-);N>7x6X`)dO1%s$~5qdO1qz>0Ec*}vqhdDZx_~{ULc+}Y0?zj-y5@M z&q;c{=dQcs9D*mGzwxH%1zen~hIu;Xn1_2Rok~Bxmq%90&zZl@W5*Tt>Ny&XwNd`< z8b1M}==o=!iifAY6aR)@b1n4Lnv%^uI7x+tdYE&Re&#M(NTBHVao00XW+S`J0)T5o zcTNRs*Cv`!0$5uQJ#*NPGu-3ZYXK|evqm}7Dr6YH@l+t!X(m%GzsGapsZK(^c!2%h zfroSxugf>QALHLE8p_q+H|Gzg_m)`~$cXKD+9!;kkVgjJj#Jj`EFGD2RYjHlhb~9`M zvv71?q^<}2>%o7-LGLLYXMlw{xR;=KuEqUHrz!L2%kl2~d2z?Deictm7$0A}^70sQ z>18+?`X`^?wqK7Cp;tHnOo(hmOFGb<5NFop_i!2e3(gBYuhpd{$%(32P(ZP%rOg$q92%wmt_v-FMG_ z#mzT;D$YjV>rU1|V}e(E(2sTlcXdf+lz8rV9s{kTLMK{2cwZjoT;zCW#F^ddQIazV zUOfgc^Mss_p%3@#)jL|^$UmCV04&t2)pMkEVd6cUqq0$$r|fVq6W;I|5X~bPSf`VXXTF_$ zM_W+GucrXczyb3T_TN1?VNOAZ{OadFAE%RXu55KL3!BfNGFhqMeU`n5JK{L=6>rjp zaC~0pU9i<^G^iI_aVEdap8g6)_#52&w(G8mPmH=QOEWBgVq$qzvbur1-usC`IvIAL z!!KE05zpZS>2z9uvRp<*y|!(0PZ$cmB1L|9ufMyaLEvlrB=-|G299&qoEhf45}gJ4$mN)m&PiQKphR^@XX(VGND)Kwkt@3C!*7*XAc;jk%_%oyQko{ z?n*~P&1wh=2u0&j!CMEVQ>JGaeXbKNt7D%8vlC{YzIN&Lm->X*Qm&E zA;3RA^>ln5#+RiNWF533vQQPKaRB9EGnSJ=)S4<8w*p>z= zQ|PJ@N!vuG$AX2_q)nd|58U_LIA_EqaouH?;ehFwjR9pI;)V_Yn~({6&-zv?F!j|r z3nLkm!o~=p3aXJ9_hk91%9x13_~Pj2;@P?H#T{SzViAGG(O?=>6<}dhUO}vKt`}Rz zkO~(tN<|JBoAsg7M=z+U=Cv`9*c6!GyK&#$cgLOM#s+cG_`%QrBL%- zXEomEK5#VJq?r$H6chHOGs3G-ioqB-l`nK5_l^z07Z zp6Rq}M!H=sI>s}vZQQ4l?1$B8h6i!bRAG(Pfk$1O78=LRVZ<%Sut4lm(trUE?p0&% z9-mkprwC9NsZbR0#j)?}_8f@Co5_aSu$5AbKRFsce#yu<>y*>tRD?tq9Sy*58_^M2 zwoWtguoRsW&hDvBq)cmOFZ@pKIdC-naVj3}AN}$_VmHe4mDgP#7hEtr`u6UfxMEaA zyi%Ua^V>ukgGd6W#D?g3VTw0A#Or9B+w%*|GsR%h6`X z9i#_}LJfS#*3#%RscGcQ_#1d9@5Sj*h(Htu2jp`x=n#D!3P%H33|scZe4IF|*KUrL zM_Q7P;MmAh=_Ap#Q%C5&Icdl1aGL%R2T(PP-I1AvW|KA>Mec{@j0x36p%)j;*iqr+ zHt;U#2BV(O6ZY^(_d&P||5Y@9dza|q1n_b+y!g{7|L31MD4L^WX$+fzBJWZW-2F1t~J70b!K7x_{g@5>m=z~1dDX4)c zo@g*SZ~xXHP-#&)N`BAxlJ@{R_bbc5c(w<`n)PerrB`2#`*DO%WMOg-> zLTDPWj)rUq$v(JdWt=pqvM)dJS%~YPmKVs+j0~z|+C$;@fBa+o9Qg!#k?nCuj9?A+ zX;Cim1NaWgAoo)Fa!sCNuIx~`73KB=ql{kiopfZg5Ari*!Q>h5#1Fpzy_g8k{47nJ zuhXG?Qa}BoWP{KUm*2|E(jemd@_X;$d-BQD1-O^Sr0J>YjF%?^pS6@CjmF`7%MZUF zeVbQ_QP+Mhh7TDQUCU7Z!M$|y@LPF+3c1Rmd{`K{E>%e#4Z^S#lyDuoY4*XtmNMtZ zUVI^b`p|Vi>8ZG{v z_yW!O{qhRxni>0LVE@*>n@@H>4Z?lNPgA37|@Sj4{Pc>Ds21 zW)pZ!b9H3UamepgYuCi2H{OUBo_i)9qlxynZvISMbMYmqhkAsm$78!zjS=^5-eMea zk31CjjD9xd+;;H9(ND66ts8pM|iPJw#7)_^vP zuR0%PB-V8y;|@b#yYMh>=8H?$ucBW~(ThmFI&AQ1I2xL#qhSX|^Bd#eqy!hk=*wRv zxO8&D-0}eFO8AK5N9l^SC;@Z?WH5|*>2%OgFB%Gx70Q2Wz?&CwG<@y{KgczH^SV)S z6-H_IPMvc+=}FquKvIWNFD{h`XxM3pW`HJn4D;Z=IvUg`-ShI5E760WjPK+8I-lQ; zA`|pnj8Zc}Ipeg?4Z|`BMy7!nle*kenj=z5V=)dla zr^v$nJa}`-6_>}UIKY%4IvSFefU|mE(kr+mpO7BJ8Fi`TkFK8m@gW~gdPTlXB)IaU zZ+|-mpl_TvbSPt=8Xe2Z5*KvcCfGZ^pgL|57P(+#@Z&*usXZ)Ng5Kr+cV}x_efn^n?qhBjODTN8Rf0;HdrMdc~72lt}u!$$7K>}i>zkev**o? zH*mr{`PdV21!Ybo!=IU|8#wp0bEFsMEv)il{_5KD_yrY9 zW9*~}l(0P=Z!KIIzx~#~#d!nH#L++?0X$5*1K8HZ32ND~&REN@t=9RosN5cyk^AF*K>E5$f{NpXRq%Ntgk-U+$iyIjzMd$Nxz?||z+)2k3@<@=U zt_hzrNMH~`UGCNK1RfSEZfP1s%@4V`6E$X4w;CdmV?Y-NSxZ*0FdQ zj)rHSjjm^%5!X}RT%RmPao9EGBY*MX{OAAfXmH)ajLi@^y`WiIwih(`|YueA#Npw@up9Ff+%C}^hWO5 z&iC0Q(->78vg0otukaKXN})(6Q0OM#Ip- zL$U#mHL%u@8&T6URwz{{IS2untBhY}P9K_T6Hum*swF^5p~!8SzY*m@a?qyZHN;j05sijc;n(Zo&Omj=ve_|}hp7}J(6 zjjvvId0c+wRfS;$%y%R3lb)d2LhwlA(k}Cb0ac|dp9Z}GbsrJtgQVD0ufd+;_}l|t ztlh8?N5dQO<)8l~u7?ktJ7j3|$8ae-p$xf=fI(SV4^1ywv5dYnljBEs7LJC-=q&ZH zJNk8L94B>YA1xbFx4IAK%$_Y098K*|HmZPAZZh|_S43VSwRFK8?b(q32?u$Bt{gKO zsC(YT*h@B18%_Ddy7k**l|DDF%Z3hzpPUh0I(4LBWfL4FYcslc+<|JOdS9N7hE_xZ z8z|6Ggj84Un{XI->vRR%6W-FMd*N%JB@F4x=&p{2)oXAx;J6xx^X?%8>*rDaFQlnd zo0hHM1(Z>N!wPj3K@C&aC=XCUQeifdZX;FyR-tgO-BT4idA^M%-r~gFvjsx2`zXTu+7`D4!)zpQpf%(tb5X1Q{$nB9*94@`Bq$w zWYZ7=oS1rq8r8ubbS2{jO+ zr~smyjsatA$95dY&M(FNee)!CoX5_SIK>24dhZ}4Aqn+{Q13J9y;s!rUe~(kU_W19 z=LXulnC>ubl*OSaKv6^wD{&qqBk|_v%}3#XpkKP{l{z|I*{s$GC-6 zb!s%AH_d2h0DY8qpP`;HSd#?=Nu_fFrTpzz{9FDnR>11SN?5E2EE0gk$%A$Am_!d4}06pIAU zkh=O~wz1tmYDC-&V13o_5zz)4b=)jOz~oY9!}-)P(!4qlk`_GA^kQ|sI!Ie?kv!{0 zIQAv01R9=?v&j6dH{O(6Cwg@6k=sfP8qN5S@1=ntv-2SBWe{yg@;f}Q{Z8tF|?Hllc-LEc#r?l0z_flh+F+Z#E^* zWDI6Ap5Wfa=z__UCK2F27gt?(eSC#g(mvfPa{iUa^qJ_d*$3(b15|lmKr91b#%24~ zXHfTeno|~l1BmyizUgemef8O=;@yqg;{W~H*D2(((szUgTDCI?Wy&9I zLs;(NJ|6~AEVgV$-*J|l4`7Ek?AaO9R-Db#U>ZQPYp)rKK5UcEIRV%-Z{mkh(YH^0 z`2zGm*{)U+V2BPw&V|CHZQz71h?vMTOhujhI zL+WzfPr=5Dvhv)zAf3%7L#w0@=lF_C`@&PQEyq|aHc3C*wgbwrK*R4}eKr2!x4(;_ z-1ykv{!NU%o=i}(Yz)*35MN3`L-4XdS{Xo_YWZ>%TRo#Je2hH(^M5}P zuVZ8XoGlr*u|?oYw)Ci9+%~DsNkEZ%)A!>U@{DsNt>kriQ9Yp#obtqH+Jl2Euza{+ z0hyrR!v^3RAp&@ccH<6?Nesf&6LRM{`|4R#88ItRX=K4$VLPvV*BQ}K6A7709=WB2~O zv3U8?m_BEA{3}I7|LRd{p5Rk~D`YOu_bjYvpW!hV4 zWFb~-WUSp-6_aL6jhEhjCFZT!8o&9$4`U2ExD_CVe5n1Fp2i3AnsHGs-l2E(Ewt77 zIlze72&H*)o0fbeVEPI=_-Di+WBd1yzx#`ClF=|A`Bh-lt>N}jS zr!9dt{GXtPfO3f?csgAI8EKg4b0X;|ZUGIqOz2{tBpbt{Xx3C##&2GDG2VFN zt@si(8b)73a6#cD_Xm4cwN8Wubu`Edg+iB(E{aG=&{0uQIvRx}`_FqGd$w=?zL*ap z_is=BD%!VdiIa5$XzLZMKvp0WtfC%c1r}kjUHj{$vNj7K9Xn{NbLGoVO}92{LI*Vq zKCN64Q)kbP7hiZO9(e@iH)Jr?{mav#pwU#?{*>hn_*JYrxd!R!yz^cL*L2`& zs)b^y2N+-xmW80tQxNheUw$n<2hecugqt&?!9AqXTHZ;A#rb5s>3q^pgH35;zti!j zZ}N(BYi3Mc6!SJ5(6`@tJD&Q)nQ4FN8{+~ z!dbT2s_UvszPwOa_l?+_P_YOn&eEc;SElBHA(L&dqC3tgmCVf;a1+jGF=|w8oLE&$CPs zJwhM$Fm_)j`1=Grahi1hGXNIp=l}?5Od3-6p?(9w9*rIQ5RrY&SuJ?6Hf>#C%x9p} z?oZCf%H2m|$<8A<=>!?oKF<9UZl_4;khqM%t}9M-OAQpm(D9d6Iv`AO{!Ax=_B8m? zOJyw$>0UbW&bJv2-)B{KE)M2jkKlO^iab3Sn< zp??-gy?`04A&BQuwSUNHm;&v;_49vEP=&v%eZ} z^(X)FZ}eQih}suCc3`)Qcy%BfqyQSuQcTlK5P^n9wb^2TT+o?(C6L1S_#bDRz6vz> za;ymsHrzpIckBwWe9ZUU-VbQg$GXP+-Oz(X1>E8n= z)XR*9em#0+1?8sbqYF4RwU|3yADyTon}I+ET4zB*c*FohUMvN>p8^dy|L)74HfvTq z`O2&DZB|IfU43P6`@Tg}pU`D;Q)xq;BIqjwAxUM4*Vxysn={XGtC%*Ab_i|wE%Pv zvvuNy*Itb;Q8&cvM_>K3xbKeJ^SD0?sJUIGF>|QS(fKhrRENI>ao^xn>(%6^0SbE9pI{r*y>Py@9Gv{gJCRRvU;FvgdYAmhV5Z`3$-7s{d zbg_>Hjmj%(D`g;qZRRZ(PH0yj!Ij)1DAK-|V$ado0MBNPEnK)L-kXi#L3ehwZ}ru9a8J1th{=TxXrdl$ zf-Zx3uy@C^2&eRyHu{$Wk4>3Vb+W*qHC0|_LDlcy$AYKDAU#>HDcf~3o? z0o>G!ENCMg)ECm-V?XO)pUmjngRi}q?Nd`{&x)V^{@M5*w)?K}zJxkPI;wwiv6R8hL)Sb9ko=!BXT`XI1LHe?`Im7e zKh>$;Yu}t(eT9s}@cSH#JnDS7Ma(&oKlLfGvT0`;wP+TH;hA>;F#i4rKZ@1R?^_Sv z#}@Giqg#1-oQ4;zA(pj?1Y)4S&ul=Zh6Qq!#dVvivPMI>TPN;+Aeytq79pV}I?gsuO#$Ov>{_>YNUZ#I4QkAa39U3&1tw4i9oB=3|?(Z4=(w@rBEfl3RF9XW0 ztfsy8-o*GTR*iem{+GV>7jX*#hCqX<)TY2Yr5ZAS%1}B2{;jhlvz1m|6376BtJSbL zQMs(K|T0cfsgaaZF^dp1pEgi3&kOmT0742DJ3jc!|_XEETFoyJXCy zzsk{7#|@PzKhVT?CQpeyI8|R@?~?oMTLPF^$kM*r=M4N6Xq79p*U+i(q>avCf(7(N zN6USf^++i_fa5loRIc|YO^T;pej{$bbpodo+!VdKRYbEU%|10Q(nbRZvt^qad_f00 zuVb3&R(wa%R*969V--NdBrmU@U@l?j3fuGxwNjOsN}knqYXxvBS(MtL6Xv!&tlJc-%XFY&`z(BL&dFR*TvI zb~R~($;GnZw4OK;o3?C3W|ze}R+{!tqS`fQPhQfYjB~}A4;=nFe77N9S`(Z(V(mm^ zKY<3vSz$lM>l6eyL0>xN>;(>slV2E@~MqaO}ZFpifcTB#kce z;~eOaB%kxUQ{+{0to>bsGH>z6@sEIxd)BUJKl!~eo-Gbm$#*qX0LDu?%ZvWhxlmuh zsj1`CDP|PZspDJ%G7vPK!H^t1#(CBhe3~+QX8hn^eiCB`Um0V^j^n7_QCVR1JbOfr z93eo!I8|=j8XwMOj(+j;d>&#MjTk_$HWVQ1&^B5(CLQqtTYoN)s>@ng1Lmm-b5WnU z@W>?jIe`X+kpBe`FR+jJJg>qT5@;aMB%{G%kOxTBUAy-fN44(9p*j~ks%tddN(%i* z`q{Ztd$uDqN}%C)p#Lo!w<4e$AD8y+ml;kCkoQmM_XP}d%B{3Tes$E;SEeqyHA^SO z{y_B9YX&)jZQEIWU5X<#9iZViF99^LGCl5^Q50xvpYpD5aZjT)4oX$Xl^Fw1?{^i$ z`Wnio0j`zL)elXZ0W|QPb?es0hd6O>lOnl(>(=-_&dMlOx=hv1)pTUs;7FUJ!O!59 z{%8N_zj`2bm;zlb)bfp$v3;%p$*=$WKjZaftK+`0H^i5z^E0qd@4R2zkWMVljXxcJ zuA*^&;e5$EICG4#q$gcHb}V(U3%lVNi$Q+UP^T zn9Gb3p5yp^gmlt|C`YbPdG5D#(s?usMfq@F@l2fazo#a~?5*44ZdP8u$~Lp1fIKvW zy~CbW%Tb}vDFVxUxurz?DhMnI`WXJD1uBw@nEuX!}d;$?w{4|2Bxx88%hiqoaRG+eeW1 zJ8r+7V@rpTb->YW%)RxYJg(5-EA2M6DYx1nuNW;HU{0NZ?%G@Zj+ATX0-6c12;$5F zX!r?f@Dt#d@dWJsu&)=lZ%<8$)0y=k(X==6yZ8IM^pS^hei@VF(uYdlhUX}EJK)JR z>p41;<0oe1t9*d4~)3N$nVIC7u@Q|T9ZuYdE?xrURn4Oi9~SkfZ_cl{E^VwR@$ zAEsct-+u9x=zlHSZEm}b6RCQUPLJ(|zwE04XaWL^L7vg?vpAgoqkft5t?%TEj$}qd zZR!SjG_%_t-{g49*XA#azk2M^_#8o_$E&*nD}M=OnhD|7*4#Sr3>ghCznpxZbI3D? zb4+uW){NJTHtbqc+HTUw6MDh{4#t_gXuR|_<8hizQZ>o{*IvNv4=_w6X7 zU!FSAvTX-ik&s@+IEvptd;k7PKtqWHuq5j64LH`MWP^<>j(pZ{k2vi=@Lt14$3!br+6)5*g&RwuD zroJ~h#@}``AjY5s8azf&XSq<&IGE5#2gFM!Hut>qyUvxX$|bZn+vjr?+BS^N%2lgk z3M-AKQF`Rs=gxGSXZp$d?L9`n$bA!|n3~2@EKeJ(Y?=YU=BO!#FEA zSyQJ?jc4EcAa1+<+L$ordWzb0E%tBIhRRIvLI+oe+Dm1mGVwV+Q}o~GlxX8T=oD?) zzAa`GtWPAJa(dOy_}@5w1@h+`A{{ zEsv8e+%K=vp_7`=}m1i(QYB>U@$J8+vNYg!8|vh!Pjpm0%UnIq^g^E^C{h(<9JZta^iHOhIyH^2M0am~o#88pg7=}bXyfd*wHR~waY`ksz? z&L~pLXSS#Q7Yve4))ra_fb@%>|2!5GIF0RD5s!X_6K=@p)6q8I_Ir*)TUwe^$E_ph zJR2Ao#3*y#sn< zm4U!3^pX3u{f=FF2)sbVPlG${fHqhD%=#G5zZm;Btc+Xlyf+3DxCoMDh6i>jgGKt1 zz6TC_p>wPUb21kt`Ae3@&;RuoG2y0haovcKnJv-wlD0`_ z^$}f8`yl^0586L%T+*1nJ0H%ocBed@G&YQsR+wvuDnTX>U!8?n8&f1Wt7FxL8*q zl~*spTLDHJHCS?AKjtUp$vQ6j9@<(#2HUNPp7bP?U3>S&JhE)2Or98T&07|a-a)np zx=f&ywTrk~9uxK#hEt!CvI&p?f9SR>;?mH55HXqAl zCR@~L9liUqr@mEdc!7C2bs|>J{5U%GYa5?`=zfk|?Ux`F6O}$$@(sVMi|gav4leI5f>L#a%wqGHUG^vJmST8?|~-;ZpK=5&i7m;1FN z&aqp3Y&U&9^nh(=#(=zztQn9h$Bs$+Wl%Z~UG}pd|1(=AhM*%y#sG>2cI?mr+W_!~ zyet2LW&V`+mCw?pjOpX6=e2nPFOET-<2Gf%fGOy*$>^E~KL225Y_}r@X$frvRqUs& zrLLqe{w_GA?ASNy>>SJMnNh(PT%fd0NmW%b+ZeS^C-9Pys;D$!e<8F>H=66pnwb{o^K7k6>C?=Y;54a{O-B<$~|{c7@ZTN*p^{k zBK3eivGj00(;guk@`Ksa>4Q6`H0okbN(yvKKNtCM>$%%V-<q8ZUVq@N z>Nh@9KmH`3!I4S^Q$KVnMc8B=-!lwn>iPE^6~>puL{^tpP)zO=g|WJ}@4(SLZ4(7I z9m`a~42ns0GbM8Y0{-j=(`lu+zW&f%QBhu=2Fumk8o3IKp-khZqXi=|@iJ5@R}?{k z;&MNNC=+L&=;uC+=A;j%#6tG#dEGT)a10!DMGCk~ssp4D6afZ732i5uiU1l+=8Lf^ zq$(sU(AUG^HC@=ir4m7T^3}pf4J0lZe)EK=sHjLp&AnOL8ih__&LeVA4vjI`vXReL zuvO$4v@0+e=KMa-GvmT@(4U|3VfKB@z@DT>4h(?+m8hth3fs2qf1&)C4}MQJrR{XU zs{8KyuB1tyef#!NxtbaclctAgTsg0+$6XtpyOc$13|`>~763px()3>|BNAx<;U$7A z7+?^lGH@<*-c>dSSrOV;RTYG@qeUM_UBA z^bi50&#ubQu5`!qBYOaVgV%nJMO;Xog~?OrRkt4TwFmEy3JRf`6?EYw6{Y#4F0aOH zg*eOV$*Scm<2a7r0Mhs>*eBW=gVq4XJ$VuXasCvm=>)#sRD*!(0t)|}X>b^sT5Q7s zY&eGlrITftc?_O72tVv(3&-}82jegcF%3wAtKWnbh6V(m$vUi-@NK2^H2iyv*LDKI zRr^lG$NO<6VYR(vHF#Y*fV1bzyGF;>tyt-A7>yXKRCY^)g);@9>f!uqSPF2h2<|ip zI=u-V@f{Vv`|VxfeW6;OMz(7agGP?#q?Jx7Kk|w^?7W#3q;YTtl+ly{#-=egkgsb- z1N9Fi|5==3W$_@u;_UeVcWW1A-*3HQcnrM!(yab0&~SpY=TC9NAyy$)SFYnI%*pw^ zx&UwW(Tk1Y8{KTk1V1r9{K0OR=+G*n3#US~#0jq-2Wz_z`FZ{<| zqqqQ&bBMRA4xfxQdk@6UJ*Q$*HEjn~bc!BbyG099nri_h?bx*=UY=g`eZr8-qAx&0 zJ6A5CgDKCRH?8cHKs9ax+>k>d0yL6ubAPsfSId*M+(%~D2K3mJ4`#$3zCDcRjvQf% zdW&>4rL8N@I-NQ{c|m98U0tl6J&s|vu7SEyr&0McC{gZqur*`p!uj#ma?1%*dt%7t zS$CtE>6eV(c@>nktJ!yWrId}KUQox&Pw7PHAaL1lL0Rp}x^-*ggIC|o^hiJZGPe3sAfr=-Dd%9lFv`w6_JPJTZo;|O{6ZQCqvzx{I* zP`fC{DbQdVHq%o$E9fW&k$Nhh4b9z7CE%OeuAoPPweY&t#mkwSYEynNK&*iK#K0SGAe&#=aMqt;g zXU~))<+I=oWg2}&8y-U`eWa7ZV_@Liy6U7c%gHA4~QQHI&@1KG*rRwv%-lnAoJh=GPKEHnZKP^!4caNNcMRahxMm6L^+UeDmQHc#F%K;V>DZ$E*(59 zI-!SM$Pi4>j!18*?oWAH`=mUaVeGzXe|?S_c>GA3X=p@U8klC)_!--x;8AU%?@0ADM~gNn_(0b##JbJXe6GlGWWg&}Aj}dVPM(=;+#o zzzFAG{wP+Ot=~ij75C)(&_NxZ+lLsx^5lHOI0-hn-@6__!vQiTK3YtX%nu9u*P}^| z7<==bfSPTK6rtVd0Fi zW9>YixsHo#5YhsXjy+GTk?+uj-cte^{Okg@`y34)r3&*tQUEtlE9b-Y`(h`bH3Z^s z$F{(R)Id72^x;ME6n&5<`OxvFKMMazV&z|7IQfRp4W9MM5;$dUmDvJ> zC>A`-x|=bZLYZ?59p8sX-1Vi$GPA5ChXs?tkI>ejNPX)c@|-d($xE01u)a+(M-AD2 zxj%l-329Y@T8Vo&N#hC@39J*~yz9&5l<}{+rT|UxBbZyqr%unsH+V-Kp>Ecu`|RVK z*0ip&GM=42D<5x2cKx{PqI-`X88rH){gY<|!sOM|?X;yYrLUBFj_;+PMn{y{%oKob z0(py(qe6Bzz0b;vnqYAwj=En4XcOU zrnQspLMvA+i-}7M`}ZJpDI?g`&o(>T&ZS7wSNmgcmB(5x+R|4+?A#`*eDR#r1?V-i z5)NlTTop5By&Efcoy|HwcRzSf7FW%9j5*>aTJ$06V)Oy8n$}B8j#z=o1qIl%|aeeeSo|>NAkKcg7^D8K_KnBziZQt3DtSN zv`?#6t&Cs4TliT%;1Tp>?;hQgujxi^Uz0BdaRlj|WBJ49W-7Ej z=xr|QKr24QONxDVFZdWv{u3^5)_}OeA+s9%6c>ySaReNeQ#|CoH{Oh;I0*+?&APa8 z)3~@*tK7?Tn#os~bXet4q%_Vl0cT|p7$pmppjjn&SmQ})NM#w4wsF$eeA7B+6(i6BUC&x9N8pkTm8910Uw9qbv3@u8PU ztibJuxn@rO09sLD9*4LQ@5#6dk1vgdj!L%2cP#F59vZ7~RX`f?tSJGdb0$-H;PCJ) z72cLj8(D$-IJ&oK5fub!DhrKq$#`2=!uveRsveHIX*{2>azj>pzO1j{z9J2}3M7pH zW7OFaDPOmEL9E()I4&pnZr`OW1t!jaQQAq_J*i{u^`upkbq&Q+VVNItf#@&veSJ35G&MHyr0G1 zN3Z&xsB3A`egm7cp2FX9tt+JH zQEEse(12VBG;BI@D%S2h5ZiaLr?VPp=+m+;MF%@^;zS#^G_`=97UyLJo;k^k7v#Ul zK%-Ce+k&YjK2{IzCcs~?cxjZiX&!xt49^uDoiZere);`$Ka%dIx6AVeJJO@5)nWhP z8@}s6)T>!r1^c4@*|c(LEZlP>uD`TjR8TKMNAehatDaP!sz>u_rqnA8jskDzO|Ecl4}A`t^91lR^XGdR?K6g;CNRyZv7*?{Rd4wL$#A;MtF zbUIP+i;kZTo0)6!&OWl}_N-e;+UW^am|92o%dTLXN3)bagJb*UxJ|9qMx3{Oo|;($ zv|p1pF0d+O00&`G&uD+t#oDKxr2Ow&w;DZ72F$>I(VL4KS6-lrj=kX8A%OWU%NEBup3|&Ld9)xvYepuQS$673_1Ou4UiC}T zm6bzl=VY)+zYBRPwnSL`R2r(oY+rfWxovA~oUUzJI zx|sf-QI6?%p(ojfXpqb2(!s482v#1Grk+pxgihPOd3SW{)s;DAYYxF%1Aa<`U3L0!MF?|znMj_E6$v5!0(qW&9v7e0{%&KV@D$rmsC!YyEo*;lVGj7AmRjI!QoBc-tK=+TQKA`{V zWA&r{lHjEBbQ;-l_>GX~I<`gs4HV5lQl>4&%2ZLO>rm|7wk_7KUKg$D^MGsF`U6iU z08HC1beP#vhpayJr*dlhjwSbm^IlCGf)0E=$8DyCi$)ff{+JAl6=b-j8bTFmV`?(( z(v=V^%w4uO;`-5NBd?ldMb$^mEe{j zk9uS~0qjN=^c;69j+E?t+2zp!U)#(Ec|8|Tplu0Is^J{#E5aXwa2N3D(r3kLq|Di0 z$4`Gv%dbQSZ``^&vmM*@=@IQa0k)7;>URZL^8^6eYKCp5(KrHsoWho=XY}_P;M?nm zq3^qtaYf*!_E>H)#rv&ft6J1>GS9?83P6WapTR>sxM>P5fd*JQS$ z{U|bmp(EqhsXWa+C%q4OckXJ^w*IL_Ce@oIJLMSFW!9%TL=3fa&C*~eYV;U-Ioo_Y zB>ggL1wH7(W%`HeDEf#HqztBQq3!ed%4TURnT;5?{+#iJG`G<1zCF8Q-^TS(zj3qZ z*6*@t!GeXd=3X7wFquxgmCL z*bw#GUySX!5R13&ji3MgpEx%3K7fYyazTzIiCO*IXYt3M3^X`svl(OnnMETjxZsNf zEapnX2%<EP;?e50awd_G71l3xUnwrt&+SqD2d zZ^PI$jzR1{FE1-gd9h%asJ7b{tnHCUebHy!2(}wBhbTJ;PHWYx8#+=v<0!z$q6G_M z#k0@lv3Fg%ca63<->oq$Bu3*%@qK>Q5){z7@)Prhu@_`SF4;O!za}eOJV_u)y42vij>QE_SSK2hGK6UQO8!gqp<5ST?Z`A?k8ox*AoI$VGMxiUpuupd1T?_A072Gh_%x&85J!jZ z*~cpG*{H-odyOQspjUZU(oZ?jqg#1q7!-VpJmIyRWsGhMIirK*1JU)4SCBzD-@Ii@ z%$qeUI->^$voBvAX<#A1kO+Rtle)N&DfOlNEZr@_xZyYA2UEQK?b)E#z40x3%^{{hmkv$!fk}k?Q*WqJ+-RG$;*u@;I zV{ZM<2zac#OP8E`^?|%n(mVc4n&^D-pK_@@ti+B2elzx zupuKxjwtpi^DOnRTPl2r`XRR>0PaZ#ZIyb!)oQ;d4Ru_ldFmyeVTRuNb?ag~v==1r z%4%n?p1raNqWr2p(rL;upkKUvPk9lbaTQ&fdD$*Q;`746^&aJE2`j<}S?O)g>Uj5F zJ)=t(f(vYgW0qcS@zbuU^9}d}QS6JK<#rMJQT$%WhYq*%<2`HX`w~v7kX9X7Ah2zZ zJXYQcy9|}-ue9LJ3@~!_i@$Z?>JSCF6~eZZYn{~#$egl$2)cQk*;=*)b}B22@=j%B zQc^&c48l_SaQX<0H|rmm9!${0z_8I2lf&mYP1X@{Wb(55-P0*txs`sq0X1jOo|OUL zr4+opgp)xmKB?`nzqz=;JUR~sU5MHpv)I6XR- zca6)~ev-#bJ4ajs3(lAQNL$F?u7=9<(!wn$wk_XiSNxv*CEq9~rUXe8~bfr$y?mxJjrja1WKnSZe^f-`9-<(*l&F@Q_~ILF$vf#R-vJr8Io(s789hn za`^B}IoIE?9sNZf0{>}G36gyd_d9NR?vDc-9eDvN9ze0X7TAI_v3=Y2sKPm4!`#X< zBWS;!8M3sQY47NhGXQhWW4>s+L@W7Se;~IR8ch2{?sNW?+D!nyliA++`t%vmoXU?! z(RUm!1aC?8;yYNW7}FV`p+kFs2DXmWq;3v6S1>+-2HS%t&+x3|Nyh8(mi4p+$;r8V<*d^+&TtL;V_!0e-r2%yO?7PMxewduN+mEi(rRiq1lJ zYjz0oxLwSxB+jjKz7BtHC3HCj2yt=84$+s)Ncl3ig+hDf!XZ1S{vtohGXigBTX~$d zAcpM~yhxY%zQMTr$UWU_9jn64k@GJ2OK$FWbcsutSAAK>15tAxa}kbv1oG^g^X?pGMlJl8 z{v>@UbTe}dUplspn>dYO-uzs!sp!@%V}zyzjXvM|3qTD(fIerIEn}8O>R@TBJgBFb z!qji-dG(xtuj5;~d_^ppJuCWBtg}aVw*Cmn0v?yZ8lK5W>q+}`5&us8|S_+7_w0sU%CI**nV%oVuzgbzU~Ydolv1sc4Z z7gy?C_*%b_BXXh50BXuz0eu?jhpU_TzPc}MDm;Dx+kXMQAV{bUJOk}d5|F$2qn=T> z`H~;?o%iFnZp9xqTiPs>%jtXfii)I*I#Sv=M?OQpqG7|vnK>x^wJ-V|7Fkvo+h6UP ze5=hgldB5gPMLB6%f*K)23^i#OuMw3W<5$j8y9$2SDs+Jo{(ZTm}5$Lr@#6jYMaIl z*!BgG;k;#!IqoX(=CmmaqR2ph3oU zVhk>HA{7)F-^tWX-he@yivrnNSrzqQj>~%YiJs+MSs5h*fcrA-ncz)_(?F?VvnK2Z zB6$%()HtaWMQ_b~u&Sv?RJmWLDQKsuPP1`Trhf22o;BU8U%$BQvO&?F)H4M`!&f+l zD*wV-Xmq`FG8I6Yg;fftF@JL`C;*FG?IqZqH06WXfPi~6T?L9&bl!rF8b-&dpvuT9 z3|FOG$?`K(d^M7VQ$Qfbcy-EkVpLi(wT%4Y%P*ynj=JiqA}Av8OlE{xRhEJXjzgwS z2O38-`_JFfN8_461J6{Eix?a1IPN7lxbITnY5*sF47nV18|2NDW4fCGqK-6S3g87N z0x%}$&@m~Xj?13q?xqf}jqyN3wdw0WVRz+}--T&u3e{2-&ukRViN`IZ^LnsOR z>73`Yp?3*f*+mNOdfHwM-|y!4YsZbFpwJa4qMAuFWyE_*S1Gu%e-2Kbv5(TiXKTb9 zua2f*N>$ZHjtBgh(=fKPb);zwLAiFT=myXrif#P>#?DU-kswBYmaD28%-|&5+TF&@giN3a8=Z{;j#n~GMr_8 zYXUUXV})M%l;7!gu6$u35~be92^5vbcEl!XEgZ!T)x0=Z-MyH=pGUAdrdJDZ_Gofr3xN;Nw0$y0h}$mib1xV}wm%bZ#r5%{%YD z6DKepz0ot>F!&zPY9Oj3qVX(@1L}pj6HL@FOJjpsc{k^#dd}q=Y46IBGPa1-qIcfp ztYbiiOW~XL?Qu47R@^Re+HENEB7M@Q^i`J?DE`FQp^E?-iVPp*t%0B(^$HFgjMacr zGZ%dnKYQw#9Ha9tj0qMKO|Vte9ZNf-*f%2^q+`oQ(WzBaj#@*;852r?`Ao4$x)(JX zNQgq^*Oo50We$&P&%MArim8Z&PACF(WkFf>{vudC zp5H4uPxeQBtsMKgfzihR$^sb^ZoeajvA zs>%HAj-^YNMdkW+`JMhaaf5idzdiK;vZ(&^vajkf=_*~67u(fNX=fadeJSZ{-`h}C z6|-i|%&d&o*u4P&JOawDcsW*Wta2l*yw`$b0-^~%;aruRJ)e^fA8i_dyGUTaJ|=Ma zaLSZ);46^T-o1OX6|gfl^(G;Jq4%rNX40V(%nlvcV zFFBjRT)~@WAqX@SePsO5OrXJHkb5WwS-E$A%-F!<3Iq_aFR$nxLkC|TH;)@bZJb`w z2-{v0kl`G(KMgOrSalAY(+nTd{pF?XCc&eR7AycHJ09)2bdD=Hg`pE$0ZT!&^k#C? zzfh03jX^yns370it^h{*czn29j0#Va|Mx zV-ReV_w}Xde2z&uQ=g{3qu=VU%!tN*xy57+@-$=Gv^?poFTQG9Kn&|S_%=uhp)$dA6FLkK&Z-9L>D4jTY3R@1>#?9EL?iJ-}$CB>!A$26}s9S8;mw=3O za#&xL@2DU2&-1(dEuDO(^R;Qq)-0y(BI?*1Ziu#ky~;OKCWD5c99~wRT&ROQ5mZ~7 z&i19ZK!bW9i%F`l9Rsv-ek|_4pW1b9QJo2Bdet?fsmC;uEui(2*HVW|7w3@g<76h# zko61r`>Z<5Af5K)Bl|0@GCKo4aDhNy+bt2+9Jzk%SOB`dNkhLY{p53j65Eg`^%c}P z>Vo6&t2Wy2N=rdIGa9_-Fh0lH$_=p`ncA^^2fkj17(Mc8wn=s_Vj}zEGiWD)5A2Rx z=v{@}-Rpk@Xka$~Z+bxN3}g@{I6c;_Sjq90Qxj-tgt5J%{{U9bDslx=k@Bow z1DK;!eLDuRJ?5k~!lmFFsLCuF1&>lPh2|{Bgjnt0Vnn8d&HL!1_;BWoMA&-ZC|^!c z*A7Qc=h9bB5na>>Y3x1PN8@vZqcRQX6i%58KFp!$)Tjsq0`~0Nm*<+V_-GLYXGUkC zxYEjnfw*nw@m%y#rt|NTBcyPr;ih33Tfy{i0hN+tx4x<}UVP~#Dl9jRYY{>n&^+pl zaenHoaIbCKS7~8ezB1zjMigvF#^yO0Oksc;>Xb4j>s>ta+u!A?!qp)EtxzNul+qBI zVwfNWeb({MAfDgl?d&(d*27?kC|46Eji}1Oz8x?)Wp#HhK*NI%Kb!?^ywAQSA?T0o zs-R8vENI~aG+-EDe(H4k(|)VWQgJe;7Mim<{Un@F75!}-+10JAJm*RpsPvLP&`DbQ zp3jl?wqv@b^Qz;glcA%ON*JSJWmz*0mI1`8!T}EKEW%H)Eg|n%z8a^yPJ3wVx10CC;+i6%d z!YcdhKYdm)Ngwy3`aO-mFZt2utlz*19*Y*o&h5Lh-oX`D4$V3s@_;~tG|d+>lO_v# zpq=woGmU^#jFKhzuSHJXC2ffM8J|JoYk&8>D5Iy{OwR*Zz8K}%kVfjTVk4iO26#Bl zYLS@?hA*bj>!euVhOjGnCo7E8e}M_NbC?Eq;2gC8jvt7PM^UDDQ}uh{sFiom`?u`a z#x@yFVBt9czJQD!;wWhk>qsYExBDO&BGhb1>P39<*4y*w&;EV;;DmHYN8&Js%))^> z@dmpuzVKoKCzk<8czj$J41<7z=)Mj|5%g3$fa(-prdbGS!ur84ZFB63EoK#ti`) zpw}+yIIP;ZIi}91!u6BCI7~#zXF=_er=E66lj1>1<=5ju-ykRY@7;IozXC1&}A{WZ@(DM zInMq2^~ND1y&t|{>X~C5E(&`dKAMI!S2U0%vzL_jV+0f{aQNX*Gq58!O}LelM~0*`Yj%-A zvmm2#lWEg9J6@&WN%)9Lcrf{q(Evc-)3mDYQ?|NaLkKHMkeJOMxY z?-=r;ZTqHfP2i95A7Q0W@K|Tb?-}^17hEm${-w*7$5OHa_ONZREBtuPs8Lz?QXQfr zC^+qX>N)%4G^Vb?R@rZlL3J!mv3CZ+I<-tm>H=2*7ZPx-MAzu_4JF_mPG($7>Rlwz zPG6lv9*|D6wD5a6Y8JQjJEn)KLtT~0{zHF(HJ`Z-c@o4wxOXqxvpT{T{c^>~RW|3$ zmkzOjjC!mTG&qi&L+C9n)LYWWAlL6JPd;HBf~i1FjcB@k{#qrr(| z)G^NB9bPL|Dhu14G^Rc0R=eo1oNw)~JfEwbytfPo_nD`kj`FTu2yK2~JA@SICSqenhW}(8tXPxS?MS+=CA6zivlr za{~bYz^7WyH!rtYz)UeR>u_oi%B_dVZ-ry2n=9YkMwRH#6PnZ1Gx6%`d(v@&@b z9#PlWwz6+fURp($#`-ww8)>4?WIybKy1`7Yja#-h36KTa4XgEc;%m2qMxMZj1hOR-Ugi7F z>pA*Wla-J2_;pDu=bE`;7N9eJFyoSswD;OqGck7V-4lzJE{XR!BL2>MABdZ-zdi%) zPw;(`kNLjrmSA7{i}+H|-+ty+Cv=ed#Y?bCK*=J|`sUjy;JX4Ke=#wj^^NYh=N=09 z4on#rY%OdLKo|Y=<%4WV|HCGwgY@%~?_B^+{mbu1&^48tHdEk#Ed{1G;ODiCao69F z#Zv9J+d7jc;1~OEhKg~kHbp-~`sC>_@Vk9E?pnJ(zQErm-V(80>*(UwY3Vb{Tuv5P>yP?Wy!xH2$$ z@kJc3rg;>mg&jqhy>zfOw&~O%5dN)$;WKo~Ra6S6fnV_q(@hZ^lt&{R65F47MD8=@b5l1{>7y9zuX9@jF$F*)t#rCfRWhHELfViw2;9 zK70sb{?6ZgH){cu_h6qP@^&#`gM}b<-99VQm-tUFy1bgG>vlWC2+iDTp+dYJOCy1Z$vJ)*$j;cc$`}UE@evk(>yBR?2hJ&IkP zIqlwBtLp=X@O*j^k<6#a6wgDxp2_C;ALf++%Kc+Q~3 zPOF1+1&N=^gmYorItqSIU9)iU;+XLPKm%DVR{^eRH+04X)zmd5hbvcjd6s`GN9q}6 zUqC|I>+tG0szY_m_5vmgG|T|3J_z4D^5~`H|CTL+49q;5j@==iii_Gpx& z;11;qcuChg6^_R=R0CS|%u@QkhtowW;K$LUM`zmZ5%wgjOI$^fCh9Epp1RVu)II)` zZw;aa9?c>#9aSNgUV@tPc>t)a!1+lePj4 z4o;^!>4;qTyR=`6JWT8vi6 z_XQ*jF08KZSmvY0UU~kxv{(IUdl2BD&k+#JZHN4{&(g=2TIj8JdHk;F7lYR&+L+O+}en3o357nY;|R0 zSD%=B$L9BPMXw$}F?L|nwr%kgy2cY&ZoB1{PYbTuH#2e4afL_IJ~56GP3*s8@zURr zxAYC9oAyJR$Zzm5umigDLnpM~gjuIXmd+xFyjZI1zD@_)6Rlh2(S`9I}= z@Apjj__Q`g5roMu{k$kE>)yL2$Q!?~_ z{ORJ0Ja0DQ)DNep4Zq{gyRv{`f(*7)YL9+svoh0&=VhNA8?=);@~C{{vz;4{zdK65 z1qL^)UmtU4&WiHRWpOJ&Mq9vM3&h&*I?&u_=oe|H((jUJ_L27mfbhmrFVcmy!}3fG z_{ZZd|NH5u;=f*gg&Y2GjqF;7<1JeQy3-y2ee=fk$tEE4$c{3%9&PChEt|Y4baIvf zOLJG%-6QWvvdErup`XLN9R+CE$5GCed)YRy=0dS`f;QYTcl!-j#}^;{LR`V>zV`d{ zks?^BMWs}mkJhf~P+k_pM~E>9h2hLJvdMqJ z%&G4wzo{S8Ej&}2r{1XkOps5SZP>Umo_X%MxC8*{{?FZ&K*K3c_%nOQt?CFWItL#H zpF^PGH1|m(+foFSr{qa>8P73buYv5UXLjw|!-D7Hc!LGihralw7|$XE#ErA8IAvjD zsB7<2zwoHDD3g=g6UJ^k&Yx{Mm(oQ0ZDD5%+3$o`R+7!I06StP@x7maD25CggnlBs zhG#p6Y4hoO>TupqzGuwxs=O(E9d}x#4r4Bfrbn`nnCsVA0oc`?AkT8&11!wKgtm$Z2uf*4o$)YtUKTc;3PVaRfQ= zbhhIZT)*Lt+vA3@V{%(qBD2!}Gk*Qg01Zr9GP>N7EW;0HjR|BXVgo?KOoEslphGQi zZiZcUdGxO62Fi;Qg=6JDADPE{oGgzf5@^uq>BMFbr$R+o+%{nvl_`@=nRsS1X3d`$ z6DLi~v_ZE{2sE@OVAtU3NNEJ^Ujhj9$vtT@lY4XhJSQH8^gF2xVICcjCZthX4C@t8 z)>Sx*qcQf~G5Vgzu9NF_4w1fk^i3nHz<;_*p>cuXe6&oc(^^QV1s)l7%j=jn_}3zcEXfw3L0qz!^!9|PpG-P5#X+g8q%eJ}63 z_wKt3BoP{9IwjBWo(yuKO^#dsp$+FC$40v%#41u1l(f$b0YHMCq`j^{K}~u0-5AN% zhC4A14OlTeM$jsa?W4}LykXy6rO{Yrnjt*uvrEXjBv0kU96IM#)i-cifnlqv+z{8_ zd~=K#dS%XwD5kul0aEd4yzH0rTypL;IzCThBkwz2$Iz0%r3T+yw{~sJoINLxNNPk1 zU(0U8>iG|eQ^VU{;8Aa7Lon-B47N7$(vfdaj}$z3ASuW7SKonz~cnPY5w;Th1eAv{r;*m9vq#&mWVgU9Jf^UP>~ z?*sxJi_f$@pW&*Ar&PEy?yI=;sL%=b=vnXycx8frgnMkhO+w?cb|UbYjJ>S;NLjEBhi3IKKjoW`os~ z28_k$S_HB&j-hp=)CFd7)gn`(9)(^l*y?K9)6YL2NA~TH3F!DPIOzsfl32jVp8}kP zBby{jn%KUx;Ln0i_y*7_f9GB2#qlm%y*i#oo_b+dZx~%{?b9}vY^E(rZv&H(oVabl z=Oynr5A2277c>;hc7_ul(Bg0y=&--2W%a9-YU%$dzdd-fXw5%jVboWJdF z$}w}Er`bRggB$CzY#{(Jpl(lb((%d@`uPyDD{!IzBrgjxl(xkvKen0R4=b+%@ilSa z4KM72AcH4WtN_4x;_0X2m#@CcXo{;2lQp(q^XT4|Z9(YrS_A~vT#)DTL=9++0mxup z8px-HUm1cyYoA%qEEw)l_o%O=qsKrW0rcI+_Kb}j2RnZwwTQUCC5;@Q$@|8Rh_5{U zxKr>z zW~1^LI(+|2VQn*ly@mhaIGQz%q>i` zD=pP4&a3~)lj2|w$5D6b`6 zSI0=3Pie-peU4+LQ~7;vkZiey`}r4Mh)eKi?zxjwS@0`AaY2`?hMFueTtLSvC$;M1 zBYF~z6WB$4P)>NsZWCKav>~b z5uNRO)_^#Vj9Ea^Mdp+z+OhrA4a|*mFF+&+w3jw2H*APSWHh)iS!6U^TJRPNiprZK z)GzlXEgZZy(e{#Nyq9wWKgvJ$-J<-b(Ix9QZj7a?RwdBTqIt`>@rJPg4J?o;!^occ z)waC902++Dsh?MnCbBmuR|>0944#5EaNeE-kuo^ z7qw|mU*$rtVxEfMKYRcF&jJkyo0FH^Ap=8HW+65#V;|7IyeS2l~q-tfNL~Hu`;cb)ffj= z!O~f=uRcqo>+c#B0Th*^MI8wzi;M;YRYCIk8q@?D`2PGwAI0yU{O{Zw)dOBJTw!!&i)Ojf1l#VvQ<0npGd`=GHm zuun%0Bc*f0aI#<0*7sFVf&$J*KAS$fiX+PFvvrs@v(h_p()-!3dq^iL!>FB;mI%4? zdI6;-&83Tux?}O#={WFvIx+n1iit)|+Uta<*!PkOyauKH;k0Qn0AT7SvQ=7jcrky&R#&90c;?T+Se2)x>eeBN%!Pv?; zyzaT_bASw2#NYvaQ1~55U8N}LkwYkN0z39ytgqY5Quk+L6=?%h(Q&804j?? zy0t()Oj(6@xQ$C*CqUsm!Wz&rooeRB43IPE4v)61+OaD>;26vwKJokPRvYG|5#;OB zwRQBPf_0l_q>i4!@jLBaNN7r5Jq3a$`I~n6Ss>ravaHFRnH#JlX8)NRp-^&<0UAgt z7ib`(Va2XPY)he7VX;#vZXI$}3>`R#LXKpd0W>rwo8}Pd=gOJjk_J*fJWn4^V-%fy zWmW;z;W5SV`DdSr!NZ2f?Kj?pv1U&-I-(>?pBiLnV>{|Z<=B;IK{n-8x*O~m80pZd zhjqC21JDUHm==8d9d~6$gHD5bLfKAzP_4hDzwPT}_>6Qs`EJ^PYCR_tq+a5g)>|=X zwCJzL;oW`jy^J5A0T9Dgk<>5RGVfIv@;vEY3LKyn(U7ETLx+u?Xt5~^eHFXr0 z#K!gOqkI4UaU;NHTX@o}m(=mx<5+wSEu{XFM|B=kKS~##DS&J6R4eTynK#Uj0iE?) z))8O`kXjgaI8La;+?W+&87t+a>SIOSxPygoGC0iw}lZm*R8@^b~f`jY+v^xCxq#(0k4kM`AP=v&D@z9-LXGu@6ehn49m)R@qI48;a& zhqRT_JA*Xzl=pj|0g!$4<@_f7ooB|VPhtj&0jp!ySCB71m_99QHQaaq{kh-X)0j@s zM}Y>NamVN-AM%(Sm%2ndX5gv}%Toz1F{WCM5&M4-U9cI@ZV|emLz{L04P)XWfGabE z?6)A9d%RV^&Zl&7OwNn{*>|_Q>h!yfjSmu}x`2&Zv3^|w4Nm}mNny39*PR0!N3V9A zbW{)80=#?LkGjS0xEOPRzs(v*pN2MtT{299CeBw~c+!(b%xK8d&72n+KXU3ECn~Y6 zkYbRFwnXfry^HD69`yf%V}``nzxwB-;a{3S!@)g=Xrmfv5Wu26_kJ71xT>z-q^@ym zgCM5GAcq1xmY0>Kd60GjOa{_sK*%%lj=Co^MDeRKyO@4?6uUg5zf>1L)s*l(&^Lhw z^svEtH^8HcuK2_F;ik{4udD-Ld+ME(d3dAH&H8tR@0;__+^FMo)fs)(k}XRD4R5pX zv!6u|Yc$yJJcg8j{H$4I@JIrRv@gVvGGlx|yV?p_Q=iNW&Mf$tF`24vmc|mm*cYFr z*me63WFuY~9Xg;3=sUNityd3Z_A7LBp{f+HCjbC1%9r|qj>AkyfnhHTa>~OW05rTo zFl`MX3m)n#+jhz~ZK}7tY|l1I@8_G<|CDs7pGh}$lE)sq4eX6~-i=L_8{$5IyYA)X z^w|}4co6Ko zd899Orvw_zC`lPIld%Z}XYn!Iila_*ocbWjUI}P$98Q8f=XNJga(SCGn3#_lCZy@+Mf$ZeV z$&B-R*4fD|X56n1Gmet>wj*uzt#dB;TODZ@+IjfLld3$8L|bCb7W=+--8$+XwTyAs za)fGGIenrZ+z+8sSGiD*o0UZ@@eUMCKp<&Ulf}wG-N>r7U(XA-3Fy54-=k zr2~$~xO+Yq<8QhtTC{Fc%@sBvM}Ky&|2d#RmX)vy6AG|+VMrkOI*P}9fCAYKLtFv_ zUw!4U=t*HFW;;$pY$rn_P@6PuBqJ;4TQxtk8~8gf+7?AJov{%PZw+2pP0l(xmKhDx zXHMt1nl@B|@5QTUrZa2wWYlEVY9Y6eGNA@11w^Jp;mH^ZtIVQ;$-t4+-y;~zH|hIY zQqruREYQ%JG5mk*oprpO)s?VUTp$o9#IMAa2oRFs!KD;htXQE&1u1Q(rAlRLQ>OwH zD3nrY8KgK#2oORNLWtYFxi@m-O5F23&wB3xzQ1Swnfc8NC+D7X-gnE|%h%d#>t&Rf z9FK~~`wBnL7erRTK;|OT^1FhtRi=x5X-1`%E?pXrk~*qEd&X&}r?O%}Ej?{1>=~Ox zpt7Q3>yd2?4i_1UC#mQXq+3lC+$y=w)#tJ>3w=(*FnWxr$jN7%LHhpaOpTLCOAH!L zIvqq~6^bMZJ~Q%URKkzDlE@`?nTa(nvVVwd3m)!CZ%&TsC@g29JP#i_Bw7<$Kzh0F z0}t>A5h)2>MxG7~*4uZl90%{IJkqyYEu4eV39|ymPneKG@#B|XMhak$Oz}4}MaGj# zjW_{w&Am~KPoe8vR5qN5%;Nxt5kIBk;`bJOGyQTgO2sskm7e7laXLqE9mBeM32WC& z1It3Ci9^7`HL`f2IG!hR0O!OTn3rCExE4=y>I5lVOJGd%VNfgUR%S8CF{4JIq>>$> zQ_VHy^}c|l?PQ>|YriE!$$Lu1v14k9;U?^tRk(x=i`22Kj-!RE}9aE)|#fVG_X%7hqy=UsW+XIcL;PMv5J zZBdY#^C;>O$0F)%KuLj4nxjm$#8}qhr`o>_N5CrfORvTYz8(1P-bvrcoyH{RG;57F z0R?0q%HO8_yEw{mQ|!cN(z%N#v`|#eKA2Za7OXLC9>yTvyz@X*t)oW6>TNJ&+I0cB zZoKNoIQgV8F|b#8bnV!Ntyl;-)>mPrfKVX(>*;6MUbQm@4;f7Kwb)sZI;D!L}!7$t2whS7u`MY~_jvXNH7Ldn)ZY^VQ zMOk#L&uGAN#5{qiBcea~P9ew&1)2#Z+jTz|oR7AobZDJ1H6nFHxaw%w!Z2&Ldg{dX zShIdhEUnLIxah=F4Oaps?d z=K>sH{~%&C7zd0gh8jkhnZvl`XO2}oFX6h5WqF|Ec3o6}RfdcrsR+9UUfYR?SX^#8 zQH$wh9b9_Z$Kw>D_KwFR_EMpOFUrSNAPPk=p+uKJz?c64HpxJ`%Rgva#ZhHNIl#+M~yNKA$g4LIw!}Nd=fmd9p#jlin*N3$h~qvCyeQ$7Tv2Nn?yx;1daxy zbuIDU?P1%Bmpt3{Rs5B4*65M9coK(>2aO43fktjBNB~NOTR1L-2T!3O?>ZbYZg&_n zdJLyJ4FvZ%`VB?Vu^NFFzCN3V7I>dO(02*;eik;q{9A)p9;&0^)$!vKS9q`ZKm;f>c`jpK$5k0Jdz zt)^Q~wntEAm3H$aC5fB4D?gQmrrT@4r1H*!da4CeOWXxIf%_bOfl_~DOPo`yvyk)F z^&8{tv(L(UE!M{HB!zU$1Eb_KJf3&~4yBA{4&tfuNn8=m@|iT8c*b{?|9OiR#d8EX zdX$yLSac7I?uiSop;rb{n6uAofC-yYKqLDT2YHn)|E9}?pGx=?4AM!!{w$m%7Aw|B z%zJ=?ZAlyANk&%VlMd`?O0Z!0TlOtNDp=>e8h4UB0+u&vIie7OE*@&%4 zgXhQkHKh^Ysk1?TuH#btHb@{HXq?L)-BT{^HehZ7W)EvWXYr!=GtN>S4M%}i+aP(b ziy8g^3XFF|-n4AMyx~|xXwp(u}Lw7{V(%oB`A4VU-ICYfFXkczSWsY?F0+U!w zP;c_2NgT(%KDt(x#~I_sMJIGt@qG{an7Ad(U1wk7jyP(K8F{%zv+y_s-&0OH1?6B< ziiq#n{$5NVFk@{DvjGMYSQ^YrzTim}(v$0`!%1g@fBT<2K)BO$e&>5S3h3AMG2qq| z!){&O%6I~}uc)m_88Q$)Q&~}-`pj;&jhI;^?h8NXpmFaJz|yYrHXWL*ftUU3_((c7 z$inA^6wQ5%txlcEf^plUTPj-#H`*|>&U*^EkAsUo+}0-Vu?^c2PR>OKm~fNU(y;|^ zl2&vyxE1N6AHO_~$I;-JoU6|}UTMlp8g>rK7Ht8YJ+`THQXZdU=Ccmj(mdCY8T9;=MU!V^&p}_f`haNwQ!&OTRRQ@f{|ez2n&_F2EtdoQhzXe(#yGsTf*Nh zm34Ki;@w&AW|7zn8T&}|57$R|SJE|{w=z6~%Ji4N(YEkWx6b>taab{VauYHRv<5q&)_g%o91dr3t*&)1>6_ zIvdt(+7PQZZzRyMIWD?}VvrYK#Bs^+w7kS3SNVVL^@40QHNiP%{zfD57gt zqII9!4i?LOE^ksNz^d4lw5yl3BZXKTflN4G5S}<7vnY81%_@)~$s|NHiBCmIhNbbN z*J=Hxjq%beujG+FA~yP)002M$Nkl#Z(D6I51&myNrg z!rONltc*382S0j`b1#x@S;pjb*)@O$M2YQBsgA~wP=#3Mlg|* z@@%@GFjp}WznrsPeT@sVNh~7M38ATn+kKw)FPvpcj>%|E8dLNEh9Elp|C7mupk{8r=ERQoJesa(+X93Ts!9>O!TtK?EUP#g-J%JSZ9?@GbR`S zbF5dC_}#)ibMS&LU9l`0;axrr4{_f2dsHlSEg-ZZA@K*LrPQ-pcj#`4u0qQSA8p1{#$M{-0X z8U%EW0?YV-Fk@>Pn|6^2wSH$TTJs+1;oIMLG+ck>4QxXh&9;K>(TQ`ykK(AMCK$d= z#AVihNmW(6{NhX0;n)^^`{8uNcx92Ya&N6*RH2PCpwnb*(1lsh=D`n#1luLMD~mJ zII#*IJAO~M@pJ`?LB2iZErjq#Vk`!=Q4#6Cl#wQ_NSDeI z6%9KS2Che;VDk-lE1e1_vr9aFQa)B!x00iDXJ@MCh3vQQ58jmMvSfUjNrk{nUM+u+ zFWYBEjqH#4$zMu*#xXedWf(?P;H5`!bw-gp?bK7*hR`kH>3CK2e3#Fr^3OUtZ~Id| z33Ik*YIc^nqY1_UvF6^_GvFm`b68w>@r`s}yq@#gs9Gt-^$Li@vzL@eOaj-Bnggrw@ z`6S%^J=g#9Q!qPjM=*tjw)W7IIce=EhuKqeafam(S;1z!eG3J+G$TicdQ9 z-QJ)Qd=!ODx1;1vcosgd5$|A(c*c=gWB0xDz&9!q%6Qa?IkQ zaPx1klwHt_Yd;;iJ>~V+Guv?lQFHgn7fysi=Q3g{j8YHd`Tg~DYTA97H%=@tdy>6o*=5^%Q&xRFJ-AgGg>#U{7h z4J^%Qc$ibb9^j;|qsd-)FTDj37a|k~c4;5Ska2qi8ES_P=xET%313&%+9zYS&%+;b zG#o-cN+T(M;Wrv$u6YL4_u78i8z2xGT&J9g!Ucn{c+ zfAAH4b1b%91SX4`Io4gOhNfO1yQu@b_x$tDjm~7sx|YqsyOv~{T1z4A4c4vkk!+6v zMu%9wbjH9VQlA3G%6j>e{mOf!*LB!X)^B&7BXu0t#;px|;0FtW@edZC~Z8dY8OR+*9{Ai^{pU9y-q54zm!wVD93Dv3etphD{qdd;oAjkH27DeC(zh z$%?szEUo`@G~|MR@DGryzf|nJd}oPsFXYlCo|Qc#mg2oJ$}*U2hCXHGX%IDLQ3|14 zqzOq_rp~BH$wXu(?;|mUq*7s&K@;D_Go5q>M})jJ{jE3>g{dd)_NuH*M*~gevp%25 z24Z<7v!X4LL*ny38G#6v3{av4`E*2V!ejOtjJ104qUehP-J=J`W5K92E|QUQua1V? z)?t5Ok#mrsWmrNZ1*=HUhm6)4Mdd%0Y9mH3zVuSgWt98INX0hoRi;)TDbFw#2|ze0 zOwt3#oHBxAZxE)4tpGFKR0Yl=O)B^E7A}mJ@g%Bf4TpKFOr*Dwai>zr_#9(t-O?bZ z?=*Vp&%J*-Ei|~T)8Gjd$EU=?7a61}X7(pse0ljU z+8EF9X&H0k19;%TbNzVQb~GkbjD)|Rb?(?> z!kjsHuL42iLc>PJ^bX_if^+92oG?XEBZUE@;lWf2V48kN!OQ$LRQ+9HAWq3-guTuN zg@t1<`dVFG%`ucq^Jt+_r<}}jM?-Sm6!tl0+7L&4*^b{O4!SP1>31ckhfGxk%C&c0 z)^1oID^{(H<*Vv~QU)=S;)oR}6=v5QB7>nwCuWSmNXXiruY^BzB@;Kjcsu*Sm_Zy% zG~p2Ne(Q}X@$S!l8Yz@D$+Z5vW4Ri{)84sb%_1UZ}W~V(Wp&}Xm?CoaGiSqaYLAV17OQv zYW=Z=KbKLTp_*C(D^_iYl|`TerSc*K2{i;N%c9#c?Xv2(k!Sgcj)N5|R>o9L57#?M3(gwAbBHmi$`ZyyZ0fxzF$y3eXm8LhMr6<>LZ{8_%0jtIu8(d>9tMs3rV zvc%}D`(9_`46s0(dyY>;K_7s@Zj@>Brp>g60f?Nmvz!CZ<{W5On5Tlv_+3}w!dH1Y z24TC9?KZBdGNyZvo>^c{8R#Xx*@o>Uj9E*w1#BnN>-oJohMskUY*%^adE`dLniKuD zYPhGw%$qkSGadT?`);J#AB}v~880t&t_Bs%ppj?oA_K|q+?TBa+z4l$ThYWNBvwZB zY~TM(^?nUQ{Qxre1RTlo8Fi90xEZ4`7dLe@@FCZ?!* zupP!ze3acjXIr*il1qjD0)DgBbPi4-Pv~D5X;h@Hz&v$QXy2=UxHZvz(>n3aAc9$5 zR#xyt#*>+1%-wdKr##rPiJygTQOG}O%qu}dzt#y*uUL^D)uRY#E&84Z$-|Bgd`W(a~TkJyH?c1V+e3?&5Fc3G)Dp`2;TIWaQDseLJYp zuxS^^3vS#L(-yO(lfEnk?##!XIwCG3jeSu6e!zwH_5c@nvAT#YGQ8vs{%v7S@vL@P zZ4uz0Aa&~w?KyQ~G{;+ZOGDZMbru45jfH*I?_umBh_F+Km8ZGQPy=0FXW&Me@3v$e zcT=IKIq%NQxTTEuWTNg=0D#5|@fO*_Z1rE=nhvDaKel z-f{wtfR61u)!}p8Q;#`jVL%8o6WYCNoq(k|tnYRW-Txe?)O@mf9pj(b+O?!0hTF5$J z;<&UIq!)2O-biz4oC|;9E+6*qhS00LU7U2zIyTHATmhe-Jo(LNNziG`=#!|?a7^NW znX64v{B+DIV-JEZhY4)z43OX2PHr6nSA>%iD|H0=a*jG0HV~z+f?gLQzb(!^99`Ix zM64s`+BPS6DL=9Piu`-OfhV&aft}6-`KvT6ZO>xy{ zJ`)#T@)7FJ{GX#Ci6;q&e-yf~Ki4on6)X@UXQ@ors;#b$*)!gWd895aud0f!?K(sm z%w8Z?MC_$?-8L;_zGXS5c3>?HWyC#@34@-zo2^?(_rZ3scRFU=^=0+8&TSu-*! z(V4wtWo6|k$wejHl9J}TNNPJ-(2oV*fgsW_m+%sC8NI~eE14Bc***2|U<9mKTAfPb zv3SlswZd8l-eY^F{kpY43>CQwrL*uHCP70yDoPsOdeAlYc`TX8ij{Q~Q^ZL^dmbIu z4rM~`o$bglRKQfyWgtle%tOYQOoMSMQ1=sMkx5FJ-eYQ@nF|)dsX+mKbJ8TzFUzxv zZyH?OC*v_<=h`_&*Uom+VFBSKQ{i`ov1vbgt4*a+2+1gA3GTJqg5r?lcV4cAX>jP@apJ02ODb5}6vS>D3_?ltSz5{20trW|+c(j}GdMlwuMH6IhN ztevn40keGdDvniK63^kl@G3bPhO>2ISg)QOW$Bh1Dyr|@#`1yJtbzXse&Gcg`9;!+ zxRn_VI))s*Khh7Y#F~8IXjn`(!@H|D<5k}qYwH~igDUzGDXEBx@}6;Q=T6avsIa_< zA*Z9kEfjK!2Grj0)tF7Q7QU4KNgF!uX5qN2?AsTo=5fg@Ji}W@gU(a&UwA8M<(=Zb z4uz7DrLiZiisMFiG9{MvkaxQGyt<}_qP(*>0&ye}(!LyT%qcA3la2_BF6v;AW^G%C zOJ+DATZD-;no#0B`8ISQ4|DCekUh1YjEUv7wHO8sFuX=(w9DV6J9&yU$kcNV$`KU? z`MCU2=cW8o#n~6rE7pTPtogEHB~C#MfXy2>ME8nH#y>0_0a*_Qx-*jNBHBh85sbm_ z2SD+-amS&x{T;K93k)0gqpY(JPPYs{HF|fwngJyw7fe&x!9IwU)*p?K_|3 z3G|zMl*x%ku7#LWa@MRv!K$iSLMrw;B1$dNVOr6%EVl+&C|N#cG&0*@eRYb;_fwA2 zPx52NY3ts@KLRI}J9+1F_~c?7Jg$y)D=I20$r9=SuLJh{?t039Gdm6)K_fC1(ByGs zv+!gQK`UTl#(_n=8nV4%2XyX{cFUI4L^<@@y-U~VNc7c=udFMO&$~qNW zX;NM;EHt`=xjb4KCfu2DuFvw7bur~lqQ^Ke2GM?Ncvw2Oc&;$cWmOm&JR^P!FX>D9 zBp(yrDa+{JcR%~GZ+T!9df6i6_aL%hdR0`Q%okZixlW8;ne13q?9~;Tl1(9g>nvAB zE1S$LRd>^I<2tBR3oB1DQTg8n{U1k$&9OL-lFpg0YiK)0080)eiAI*Y8?^Y>P3sAl{iTdr41(zDZ4EYcNE3>OsRK$#Jo1>g6?0}n2?@LS#ONt zu5Lr~$*&vW2v+Z`1JB39hhJbTTP~nP!S#^=Y@J{ZZE;34r5I#m7Z=$3R`6JFmv&ei zFya91@8@+;=Few93D2N0=fgJ&1x=lFH0(Y|Eu!~g`VtHcZUFcY>fGW)N#`(o zQXMmmMQ}uCnQbSJ;y#bJRF|2*a6uL%RFCXNfTjn!lSOfJYTW1ADGze2%vHW4-zw=} zI(5~zI}kB<96CSb5q`H0{`fX_!XCB+_v+m{of$1z6N6g~X-oazc9=P~f?2_ZE+al0 zIFg@v$urb_G9whcbPTS7e0b*cx3jQwCHUToIp}0{9MWM4HXg~SZmSc*lfQJT=24H( zne;GFIY&Bz%^%%UIlFx@8Y_Xkq%tDTn}*EjAo5r zdAlclI7Z>LfbDUcHmr;O{RdJLh^TMHk?MOfNC2pqr=# zL+#2HS%~vJbn$Hj{#Mk?iLd_TxA9SqwLP}p(U7t;N1V<6kNk(VW+na$mk+xz8oMH_ zp9OUBp9r}x6^Y5OPKvjuO^a!-PsYO88ePgO(im3pQ2~`WG{kM;2pE^uZWZVvi_Ff7 z+TLsGzL8rC!!(5%Dxhoe2+g3NnpY2AWklqTM$xj}bO87R)0B~la2^vV!%!fqi1{w# z1zYl^fhq&m%j!PXsZ*y1^-+Ut@90|Am9)%ug|h-em%-}EwSAd`&xvp{FEBXAXCJ0e zrxHN_rVHDb{jOPE7c**tfXE*qxvFR9Z{%)FZG=S<{Hv zuzGncq3XV=>c?@4fyR(I1Q!mHUS~$bGT^$5?Gu~v z%xY-2K9W7Zq?zvA#ae@C4O)U%i2Q9^_eGmN9jRE|8Q5|n1>-o(TIq728II6AjPbiS z7H`-ZbJyT>!KuHAk;=YXGS(wnw~NkgTSq(g3N`^a2Z%y4#8k#K=H6OZ#jL0S!K({V zsJ3|Lk37eqM?*9UAiarK%WId$g4G*?^KNi> zbZ7iT%Q(rQCF$5r`CEJ_qTuSGC<5S)Nj%w8wqp=mI>a>Lq9gU)NWIBQqZ^>xbLk$iy zGAw+CxdLwjFTi6z>)@=bUK9&(Ty&wWkwiu0hZZN5?%n<*UCC3#ccbINM`2ttICNqu zu+u3EA4s0WniYo8&ZwR}KUUFp8LvLWk4t*BZF%c%WJJ=@7&M@whM#dG{#@PvZ?N`|D0xc%6PP7sx!%q9V^vSa4q z{2be=WlLlJI@XWNDlkJvjm!)i9V#mJ;(-dfFqA*4+}gHtlaFewsc;#M6i0P32rJjt z-)iU0i4}-1uX2{Td@z}77^Sx5_;mh|M}}s^I+cI$Q5ixzuBqeI@$O7?97xCWhyvC@ zOY->gUTm9a%@Kv*i1i)h)y`jddVgbZMml#+!pA6{MdS^C?Se^ZC*J zDvK;i+7*B$*}>40$7on-Tqu{NA$fxB8WFTF<%V<9@va=%5AM}sSS$fHLpV;jM`fSH zE!WJ>lb_H|(N@9BngKWEmeE_YWOBBBio_j496iOr1ugzh+apr@j3 zWD>9zzS5+)CaenMurQ2N-lYZQtZU?Y@IVF*q)BOg^IDFzTel_YX&BiU>Qp)nb;KQM zzyMs?i1X0GsqNwa;*8j*Ua*}2hVoI}#P;Ra-sjPDMqsO!R>#tHXnck3mhkvUzoyZ@ zQ#%|D$UU6%=BgeB-ma5ZW-9m{-{@%2$zWE4*$v{CE26Qi^F};%t>vO_omjtPUr`LQ zdV8KWVVkT%bZyg^LZCy^=o4NV?+3_Ol%`$(4?AS!wc?P)%hy%cMh(wX8HsI9{h}>K zlXxcVN_1Vq2X!9x1J_1gW7@sAt}d0ln056xolH6!7S5a=b*N`veLJ>^Eb(8rroj z^;3^fG*Bi!i;w9K)Ll^4zTxW=<+o-5Mb;@@UX?%czI;ULgQSpi_43(KGQ-J=b;5c{536gt95OMl&{l z%U}ff?wY!WZmIKXNsvrFzX~2aeeu%#PI?+Npnu^|mabW=l%2wmw$$}nv?8#|IPFu% zr)wyGbe)8W&IW%|@3HpO$|dL>yXzx8*-OOFe(}?|iaHIQ+aH_Xh~LHP*5B|y@a@0R z(O_gsGlqp#ps|ps*!g+E;&~KMdoiX>d5dCRZ*dNM6Qao7(oAAbVt-VQYmM| zW}#bu4e8&DRMTSpI#gr`_AfI~an@O)ajU{05iG2(2@+x7zm7wQx1$h} z$m`e&W?XEcaQtrb&_k-S;hFZ%(Xq;C+`s655}C)uZCtZ5mhGt5Sm{B7p+mPWS%KB) zg~G=z4ZbwO^|WdT%Mh%E;7eoP@t26(dD!;`;4*)$iGjsMvMm+$%cC{XW*t-8STo1# z_LpMM8p;}kDRCCc0L-7?GsTZ_+owvmQBUEvY|h*$RKBA9iuP@&y+D*7W}ie2J~(fW zgj2!DXekU%@Ned8z;cLj~nF_j;cI4i*m zlQeYr&9OUw$1dKO31GV_l;W=IuxjPXm``D`($xcn$0N-Y8sdXWk@%ZJjc07T3F&L5 z<9otD?l%UfxLH>}^Mow{mqv_Z59_gD*1T9#YMl3O<;O(#&fQYbnHjVTn%Iw_wP*XG z7|ib@!PiQheQhv|+fv8jXxd`CYT;yHU%p!>WPMh^hS*V<$PVJGEePaIjA5%0UWx@C z!5Wcw9J@H0aXZe5ZQjEWS?V~lcaYNA8~jIja0-UTs><6wqKDg1rq)nvV#x-SRW_}v zAZqBiE){sp++*4Dh}J|cseXLGXaWWrg2yZ#4K!(0M}jmaje1n-E}RRy@m4GRRZ3ab z6k02mE{!S}e(CCqa?!Q2B5^W>4{)~~`AEVYSZE|2#^I8MLKW7Gd6&+VeeCO268dmU#6eC6soGRHvK*B3Iy1LJrlQS4TXNWueNW?OQC(aoex3(J`S?nTjg7q!OZ%q5&)~ zd+qIa64y)Zj~ax0g4gKGunm>UG*);Q->oH-&Mf*B20L)}sf?+->0m55E#%8aJ7<$c zP`aA&$57T)g*_1`5lES!(NMtF%qrKzL78pkX%;G>)(bE)wio^<4#-Dqmn?}I=2yCU zAR~JA>zB%%zsm#VWy(E^^C=(XbKojnEg(fRx#m#aEl-z!e6LU0kww=mEBJiMy_q#Yp8V(qI+{UQ;+dN_`v;Y&^bJToGps zJoqloh>zm8mvC{s&cokbC+DLc8Rd^)#bnHOpB?g@`)c}HHQb+Ll#C>qib@e+9 zG`TtrG6(-ij*|L|-hus<_sq<6EEGy-i{ z4KW=bz{WX>4@(!#i?!6`DP3J#wTK?&m5JBR&$+w4;=DSO^4sFSrfjFfh~MM`ZYOfv zn!1eJ1CL_=y-txSGiJsIoD9cDAEMYnTVYT+t+P=i&j) za5S`!ws^Kba5UILJ-dZg3TK0k28;|H4ZL(Tc!zobh>-X$AGDaO*$!KFABfc)-rGJK0l(9G5jG{v4s7Hm=6@BJN45{4zu6_)@tIOJVIwojDTo-6= zy?Br8(HS4&HRSQeD6(6meX~{NkLf7joY$7RQ+N5#U?NGw5GlkO9+rx>etvK7UcE zX>1wngsxpP(k;x@o5eZD>AFi#>i6m)sdGS6%3jCo-1y^t`J=A59zMK)?32>fl|OpG zCv`IDXcOO?BIjL49rV(>x~u&t_jJ(6bL>N>vH?i@bzVDhoG)9sDuXk&Uq(QnORrww z1B;y_;FL+Rxgpb`oJhB1rL5(I^%#sUP%#Ft)Z4VGx z)1Z>2@7coq0pFMwmjAtKrcX}9k#+g*7*K6D^ky9ol z@#;O+$PRXdn@$uE~HD z;PBskULl}zW6{c^8NY;4VoWk>=TN*5Qp`i|nuu=o*>|VTh{3~#P-v-w0*RfHP}0!= zyj4itnn4o@>x_U21B9ENS{agaNQVP|t8nPCHNDAH${ADM2t+vhpwEh4U{jEmpy1AY8@R8ii_ru6$B83`b5v;O zWZdGX6<$>|g=sP?p7#!1QUlhZq1oiH)h^4k^T#>Gf*rY&%F zjN+9HUIA2cGC2MeT>NJLUiM|mpJTQ^+ZSFITzg~EtMTfhCE=((bJdkGpm*;yPQ)|U zHOB?csF;gyO^9mC7m;#6QzU_b8*$!U@5N;-&520wV@_7me(dj0C6(5GoTl_&ecWmet zMr=Hi@-U8vz07AjO8fqU`#AXm`sS%!808!G?Tk9o|5sqtZpIGTjpf=L7jf$jEl}h; zW>jE52EYz*YYQ0>8>sWJ2|2V5{Zt=O$?=Q9A@> zN#QAF;^?Ioe)0p2V+}qX64I^o=J7?3{q2#c1C(cDj2=IBY*c`kDYU=^`Ize{&ZsmW zAev=$acme~h1Yr?#kuymcNWKL%OhK-qhTj&v7R*1d5adtQxl$zW16;&6Hh*o(;Noo z@qJK!ZgDA!C9RJ|)m8DrtK%63#lS%JX2AEv?v3I^j?p}ZIu=_uu8+Oj){v&EV$YT_ z@y=)i@II_#DKSwc(m#2)e(QuZ{(+-`O8;b1Y-X(0n@B5PhofQh-dJAmXBpbFjI9%F zJ8Rb(0|%PKzHU^twJ!sNwY|jM3I8lHA>}!M#430lP3df zjU}HG_mj`SfRgn@;Y*$`lAJVK!rs?Ol?`4{#2EVlL{o>Mxm2*!v zd5eOe(^jpGVLdpL{iKsf%kPo~qxbVb@)GgOK2i~Me89!;gq8iv55z-pQe#cS&Aqr& zC=B}Oi!bL`Exkb!;aVHCx)dZUE4!hlGFpRqH%lnp9eu9r>>4M{KS^ccO?fL8vxF5WL5=tNzN zlKA+;52w*PlA_6D&KwsNWo7kn$GHYQxt{WP9Uy*o%#Jf(^kcsXE8r!6mFKDKc_#Y| zqVRvA0Aqi)U5y-ZVy3co#F(}nY1J)Z8k{;qh%2*0t5Lwr%Di;wnS z%4~cOoT;m;%hOHfPM?8erw_85I#oC&%>p#gAYJ;rTbv9wl!5^aFu#{iDpNBv0vsq^ z_O}t8Y2_+vbbU?U;V!ozjS!qtw2&(iJt#&bQd5jNsY(llc*)qExysgFGUEWJjYbHWIUj-C+5 za(WxWEOFR&l`%SQ!dgGms`CCaBa<0mT^#o`vIQkOKL3z#C^Dp4&`N5e{ z>{bJHbsY;LxcDJnq=VBr@SFWgM|@;X@EF!fT9uC}PnLo6&r#oO{)#%XfqTY@)CH24 z$xn5jsqY!25gzhDaa%qhuQ2$a9B}LVvhG(PF7MEg3C3b}-iN?)!)!jSPw57LDv5n04{7CiWsDO2M3ii+q@V5ywaaq`LN!tfdC zl>Qy7V+Sl;I&cboT3)7co(^rsU|$y7ZPl_kI#rmgK@X{3u`K2-o*(n8mQ%B5Sk@4+ zkh%qZ-C9lKiSMcF%2P@XX=qH|ZkB}38A-^Z;__DKA%1SaIaO1~ah3CC$IK3ypSGfb$WpLEJ|O<&#XOXW;)Yv6r2kw4=HeV|TRtRQEdW3DwMp^D^1A55sah9P zxU*MTS>lZMCLO`AXgr;P4dFRD0(Qfjb%M7*f3onncB?^8aa}m-aNY?ob1V6C&pZ>W z8Q9q;93N+$ep+!zL7e*|x9sz=>P%m6KKVE&slN%O9BP@gChYZalLK=Z= zdcgJAiR>bzRiEEtpVqg2`0p9H|H!ygCb`k66|{e4#K_gF0%2)0WSn6S;U(vFPD zA}GSaaS9hN1%dE3>LXlhYinZ`0{k@?>o%DDCFh?<;kkYojGfaMF$LHZMvXxCW~m6t zuxt;K&$fh(a}-z#JQa^72r7$G&O!m5Jo$}y{Pj2Dva`>M^UpXVPpQZ#Cgbus1(^&; zW~DH)apA%+bAA0yymj0vAnx~+fxGwoHL90C`_O|i3#0NYH{KX$0(%uuFfWCfil!-R z=>Va9m3G%rI7lCg3*Y_A4uzGH(a0-G|hgCNar;INK;tu?zT3PhUddK?X#L6t@X16xv%;3$-R zFr6bQcYrI5iJA{PuogCY^w&-lKwQM@i>b%;<4%Bo435g){i%@LjsBWo7*gC3c$Ok- zj8t$Zo|I_H^;h{Q91TVxF%D3=XCmx>|L6N+F-E|(IKRf7drlV9b6s|Frm>!Fm8wEH zBLfBcvG`#V_HF@|6ioZzONeTC5D|^07#@Ve_VC>X1pd@_rpM3k`E88oHz-ay`II>R z_>p;pEoxwHN7{-ayn^jhZ_k<;_dW8kBM&3+v=S%uXc#B<=@p&WI(>aou{fQh6mbET`ODdY+moP2~bDa&s%p#D| ztMpLpA$Qy;xvY~Fv{n8sZsqZ~mvJ1}Xd+!%2p46{wxr9X9q_+IFU~Dr%u}A=8arJL zUX={TAsyDhYu*9pCy$?i;(jP@xZ#sAe9)jYTpW-0$r}q^EB+Sa*D2z{4w4t1eKwwbcUGK-li{+9FUmdc>2v}Ay`+8lo~vRz&Pkc#yzE!>^gG-3 zQi+sTugBRt9@+8pKi!jcO+J71RdK;tXJrgMT zrQOc_C%!c$zW2M|#fY-ban_mV#z`Yih;GVm+D_R3eYlTUXMhx7Mf+6HX(Lm*$v%Q< zWxpEiI)*iV&Bj}?W_7$cabi69TTe-W&!;$DMXs3?P%zf_LIwA)ks&2;u0J&IIt)OSox- z$$!L|%!1)J*VWTM+<*S=++3s<7R0rm_(UERYR!lvFkUp?q(_aqRMf!_7BOYH^j2~- z6oLw<@SAXvp4<;_5!Pu_r^PGJJ|9EJjOJ+EbE6MI4)qpsM7>44=Arj#QT@;34wC`$ zUdUb@_XKiK+8Z~+@r>irV!Lm?`DQ%-^nb=1HFa_G6_>|(@UqSrMjAXS{lZ}{?eAb+ zbUZ&d{*`!Q;&|%+5YI{iz|qjZN%Zg18K*nrMlK==n1*~6-XScZ_l9JrIRK^P!IGn) z#1GUxfN|11xZe=C9HL(x4J+WqH5-WjujFJW;NJ3xqvN=tgUBpsmkzNV=w@#MpJDy_ z0Q;*G_R@*8BYZT}=rr+9`V>zX0^lm(>=fK;AXcgSIA3{^0h&o~ycysB)o=JE;?tL2 z5@!=cDMRN=xcKrU=zXsj|^Ryl7 zuypIvHFa(Kw{3ZR+8eyP1w~%t^U|v@5Y{DnR-a@B$qQDZQ@(+7?O9I2IP1LgV+7;w z)w>sUr8*QmmiCk(32QNmvD#M7pT3jNqtAG$Gpi2^clpp}Y@Di^+IVil_{7Ca&N(}a z8@I+GA$=zgrVVjb-fLU(V|8`sm04S?qu;qz-P#!PdmXr|amLPCz{w^vk=^4b#YLBW zl%u9cv2~Y1xbgy?p^?OcbSMIM>*d(4aFLJdU@)@px~K=`k(kU)e!UVNJc}(TuTcl< z)#g<*#NP=_t$$C7v}?qZxG2nENs#gYV4TkS?s(^d7as z-atM*_^V%sxiHtE7kupEi?eX&9vuzJO?Xa0FZ?UM(VjJhb`ii@4o*D7*iJZaTwHU_ zwb2Qf{%^VdTO1APMPh+n9EBs|FuhY|G=LB3Xn147#H<%!@t(2A6Nx8cE92dbagoTQ zGQ`UW-y{UXmv6r#Q-5x};?lSrMRXv@pdd3E;n96ogmxQ6rUFWUEVhUz$8{VsbT9jN zK}90>M0s506VE*tU;F7#Vg$ck_2oNa9L!aNT7jss>7`O=u}E7mBA{^BTj=*P6C?Ph z@Hys0P@WaZ7gbfoLytcme|`Gt_~OSuM#W_eb`&m)(HW7F>Bul-AR>ODK-3d8TSHke|qpij`nNA5prh|)fqu#ghEa*5S23t<-^-iGL;SnXuFPG z#wY`Gf17Fkxi1|=H_BLxljJqFxBU5!_rx{VUl%76S?FC!L>1G2|7*7Ybx*Is^k3@0nV^O)TSSMs7-v`Ipg zS=fgLzc{6!NyZ2c6ovt~#=X{Nup<52@63n^D2cy+;)%Ekfp!(un#)k)7+|qpFb!dv z$~vnm!?n$HyZ{^FQ(6m|l;e=`8f7%&;3c;HJpPvlV{+Z9_|Y9-i3`A)V>xcj!Z#L$ z5#}^e2xCX6lOzRW;c&=xXCC5?aI>$YzzG@LETSh5KlD)C{h$Atbp`(8H@}TjMvW@g z6o#*Ina2pRezxP@SYKceYl#uee0(*;NN#~}6)T0m((f~hqI>)uUUV#=$p#XEQXFuEVrn&@@cqDBJ}0nvo#S;b1z)r=)X z0+TJAcqp*^t;(fPk``3j4zuk-L)>G=_VT`g?`rl@fNU4X_^@?iZwFF)J9nY(19cB@ za%{x~+?+Xd=+QVjcItt1qCr%x-xAg9$hN>ivbL~+;&bPYjT43rCgbJ=_7(Sq4yi7W zqr?m$X#pMM_@&3GL|lIIt6#;^rPcANE3S%*KYB?FLrJ%- zZQIC<(y##TepbLWWInzcqv}QEcmBT!T>)=2>zv`p-_C^&mj)*yZ`_|07*naRA|uA04%lu z%VpG3SVX$+>h-LNY>w;WXO4?gQ5q_#DblWeYkpfF_dfhroKXkk@{e3ZHRl0DyP#JL z0F@e*HM6Y5Nomxmg36VAKwc=`${&Qk{6^gOa^K_Z*|Xzy`22%U{%73ssZYmQr<{@* z6CO7v{uU|f@|VJpRz}F5livedKf5^se?0d0_y^;^?3{Dr zi=X~9k?+3A=j3(bmM<@5l5j}pA9JxIl@k?r$17fCS~=g#2iLN%{Kc1Ejz9hAM_J?L z>!15veC#6^XR%imWbfCo5T8p?biXUTRflL`@7ynbjS=_{7U z)u)^qH+NzIO}m^xv!t~^r&YGdU{-)Sq(?v#7tvXe8lgqC# z^~aFgzx~T!;`)zX9OF(oEsh^LEajgW5W-IvkqWf3RG5n&;=fT!CX#TpKjEEgLi;NJ z8#ips^VlEw``;-rc_=Q%m_82UqGwspbY^>x#*jLN?Fo0=5XOEM2I8S@`n{LyD}O6x zG`xx9?oW5$9Ty_|jAHg7y4w-QpnyzyN;~4E?RjOE2knbTW&@>8zbhsId7si)w`4WzdVMIEQD4Yze6Oc@K59@hf|B%+nbEKhT~djW^`U4_s4QGc6dU93 z!DpV#HknRd7Y#T%`gCd&ts$DG&{t#Rq0b`y;lhQZ!PA+ zO(F2~7=Xt*Y9(yU_yEr4R7EZN-Cy2+&dFSH2bHJOs@B4E+M-b?$v(Ai~>Uny!2%u**C~6`}$YzAm}p!*?l%A zzi_;LS$WRcdCKdRA#OqOZ~3`6FYT7-*SWba$|-4AJz6_rWnEpoKo;xY9=Jblyy??% z5~tQwLa#ao<%_PLZ7MsQZ^|IXpL~+Gyp#v7iI-z`J~|Dz;Ak*I@-c!09_9K8oV`PE zk{rYKL^Idqsmi6240rslrx_Q*-0}HtKtcE)#4#(rw4&hZ+Kn67iZnf5dHvP6_pvA9 zj?Z#J0>K#_4W9m^eNa+L(%BB2^2lNNyW^%^jKjoRv!Jlt(&?b1L_4B-d2LL7dm7HZ zm*UlFGvn^>eJ{=!GlqI!Y*S{Q;nUL!D%2UVd%Xx?b*5wnP(~(b) z{`KK_;Fa-l>X5;4>&>6f>}1!?D;=fWXI(CJ7j;{PoA6C%m;A>$FfZG7KJv0w1og}S zeE}!s5AM7(meJN{;bYfbbrtfdX9m;{5(G2@%i2GV-HZme@*ZYB9_v|Kw=({T{Zck; za9j(m977QHf6MjX;%L~l5glMMr=7&{FMax^ zfmZBoN6`S-?x}na<^L5J$1OMC9BX;@3)g=luDs$(j$ayBFf;ZgAKjuzk>0n1B9RD4 zjeYwrjOe0Y7hh%|F34Qdc!Uvb#?kOM47x9V_uDZln#J|s{zjY&p>)Ihe*hvC86_?i zE;AS;aHBoWNyhHh35`4%tVpk+u9HLMLngdn$>O*NqwxV4?7v-qL!5&mdOS>|1#N8O zI53%JNX6o}@xuNZTWZ4JXa6 zocnmzF%Zqt=!Ire@C*M`a{Yoih~SP@r6Tu~sUXs)j)tYROM(6C@snTvDsI2|b8*Jl zlcR6%-bB+nW=6#>;BA#@mC90d#iB5_>)bU2($T%h7BDKV<6VL2c*>04T zxcA1(7+v4}#vSoC1?euo_yU}Gw^BWRQ10J60Ap^~9B(g`_ubw!{*JHZ7|KXt?Sdz| zJ;kq@>NLQphQxps$_B=+?7OMOAo#k!REdKw%WV!brSR=o;-+`BC@^M}HIMuDeBrTyvw=Q`l~E z7f#1o46x5!e`9=9p-lTub`M6SSvKNk;+s5*HO-SBaPnaJ=ej%p7A+|@$(Dvad)dd$ zcoZV?G9#onfBlZQ_{`Jef^*N0v17+XMR_>}PXkVJ*qO@S(iO{aNW30*{ro?2t#vd| ziXw(|ZybYrc8e~psr$hufQE-m`BsSp{=oV$ifn>j37wp(n0p>YTA$J2IuykqSv(vK zhoRpsqyyK!w{Pr$P#ivbORI`M!MBXZe9@^owFV8FWv; zgKO5Ui=Y1Z-{aI#C#9o7+Hq{TB?)>`Ayl~lZITa(9~#8sipqx>P5uT-vEQ_1@{h?= z-i$~8_DDQLA6K$1x#o*#Q@xdtN$hccLhX>rU9`l;6q{PxKHjN8osoM+ci^CcD=Yv@UcRf)X*}ha z;iJw+BVaT1_{=LW#Z6!PYM#vUwXb|7F1zqzPO9jIAC9zr#%k5?L$vA12#zfs4d7j- zO2ZEt!>5`;H_Z|z(2wgOe+F-BR<4ML!I_`m^QZX2wO7a4r*e!c^0i~T_PJ$K13;O9 zxsz+?VhSgXf!#Rag}E7YiDS&ecTY;tp}29whIj|(+8@Dp5IM78Mv_6)tFkg-o5#R% zuMQs#fRbZCCyY2GU8(pM{TH-V!hcV8k)~e5SpWAQ{2;FR*A8izU!?1lZFd_D|42ix0x~cEC&13xpU$hU;PT1Bos77`4^5x z`ZVASYS_LwBOdACQU`Dyl!<6#sfTII$qVdX<$M8|u5Ut9kNowo(VJ}7&t88$TdDe` zo>7bk7>IX_MI282fWJ25c@)^}&+n7J(1#f(7VT`&zAZ(QiK>(3@!)-bidPp@#dn~m zt8v7b(Xfvwqiua%}0N`_u;?9@BjWt;-mji79q~<-y!-Ob9A(ZeH0lD8o|KR zIq}MqnHWPRqBACswX_CrKO#VTqvRIT3}Z&tB)pL=m1 z#ke!h$m3EQu)VIVI^9AS-e zunstRMX{&cZCX!}VRO^%Uv`@D9gMCk2mtl%1wBD4riY6M(yLrueWS$Rbd(kW58CFk zPuDothW-oy)zz&8mJi2WIMB~4?-if8`LkppjmuLX+~OuI%&aKnwN6yl6qu-6l-Anc zY_r5m)vFSqeE%+X#V>w;cRWSb#0?jmPXWDa^Jqr-wmP9aUc3bC*@ko_FY%o&vM=S9 z`nJWf%{VZ_LY2;wy(Uh6Bfj*xn=`ZNLi9cL_{#E%#1nN>aolm1#%jOn@%CH#PT05x zscX`%aFXAz1UApS{Bk_-r$59kw|+Us5?IpFU`;ihOCPig&jBtjL-KXrbw;XN+E0#w zwe|-4cYQXHbuf?2=STkYiL8Zj0|xJ~4C-}BerO7R$_>^v`8Q)q-i2d9K4VQ40i^6x zSJsIuA8iKB?B28i9{*N6KjG#0^#c#Zw{E*NK2FrWD~<+h54f#BmugSKgQu|9tl8m^@>4-2c;`!G}+c_SE4q^C9toHi~(J zkLc3QLA_eom+Haj^id`WGwHzkPfVJ^{!`_iMc1nBdx-+L^`ewEqXMqMr~tEV8Dq%sUCTJL^i%9vKRdc~?S?W@D3}UbFBy_VF7uOc6#goBGCpr{+6{4zXz(gTWey9f zmf&dkOFWLka@!|winB<2RiW?{jjililR2n3mjq`j<}wM0JPjg+HnOJS zZ6TJaqy+!^4}XXX6weFrvU;>rPn;xqjxys_F;KBpsdd~kHlHmi<|>I9p+#X5Zf;l6 z39|{f)YR7EseCPd{)=D6ZD0H%jt2I;RpMnu(Ne+RxqSym(O{^NQR28&fYQ+d6EXEP z9St&?ggwLvj4W;=Q>dw_i5cvfeilc=dW6iUue(0CW>`N$gT55S(y^oPRQd5ejegdy z2XuuORM)%fXs_r~Y0xh`(d(a^1X-s|x>_ThTE-_!BP_{9_9 zBGQ%|4Kgh+VWQwsaa?9b147}6zx^#?zt~chepJS9IG&8zOJpGWwstQsVDv* z2E4@y^(HrMfMSc3R0wMPHevgNMUiye{qW9j#8e{GS0IpYVQr7Y(cl)RLwJN+>x9A4 zFdiCx;f}9nA+fT`p3x2EzC8|&W;g?y;=%Bg0kawo;CK+lr^?A8j6y|G6>FkvoVph!> z4EBiSE(+HdFTEsAMd2DmN^{p9>{aDnaZksfv?*Tb4A3E%FxSb%J+6oJE9?~f!c!c3 zi%gjB|K!K9V&Q_g;kp~+BGTQC8+u&ghYEr47T3i?aitM3Fr(qnL93$6511iswQOk- zNDCpd-wp*AEaqd}Xv!8!dc=VNcvvWJe$1t91>sFxDOpd$$ z<5xLHYc#Y0rv17!AYJ!ZjvvK4kAxzopN@u9s-Z!TUjn5Q?rKL2qhP&yn|P&q2#qS( z8@s=$5k>*eZ6+VMYU2)0^w`Mx(0ik%K3nAKv(IHq&=|G>6d4V5q)h+r{s*YF(JVf} z_BDA;moDAVblB3v*b66&Gz$KyV1Wq2yfF?ci|`rIke5kIX)y5a*w?IC6N_*LypC~k z_n+^L+i$ro9SuFYbxUJk9+?qdCZtlOV@Q5x+ZH#I)|_lXzeT2l&$w6Bl;rBgi(=x0 ziSZ;3<*K@s@socq91Zd!$LgBOs{vfX+cAj`Dr&YVfAsf~!IgZD=Pb^r^Z8AVBYynx z$Ku{+{}oqWcu{=yOJ9n?{rV?9iBq=AY9tP^B-x+eiFaP!<2bBGg^mVbBaW+tS|`DUhbv?|Dv7!H-0zH3@QRu7f#2*avrWL?d8Db| zM-=UMMAp6j{u>+(IIOKzuzOok143iT`!)7eGR-a#F7EMFX_H6FKYb}rglA@x(9dKX z4c{b#&KICKAcDWd_NWs0vfZN`-u zT0l1U20#2y91Zv06Strso=HZ7(c=zn+Ci&0Nw`m^na}087@IgQOj2=o8R)z8S@~)J zz^I$s9^b`C|09m@of|gBWtUtMqcAS|_3fLEbPXe6q0`+7yC1pWJ;h3jpSJB~~)SJ-sqvd_4ZxqwyTIr@jNuTy^P3qdU<;75^qUY{hkef<*}Lz~TIRc+xK) zejwFXIB8y&3^*qG9osJ2a9iPMD2xpq4dxcQb;4H~PCOxXrlY}iW6U}XK=2%=_|^#7 z-jMliM`Ue4)-Bz%EvAuLwv1<6;b=Jhw9}#+5$MCr#X`m}u-$3!$dU1byS|^>aSx*h zS+G|9PS~sCsPD;lq!{^02`A+Z$|xr!XVOS@Px+Ru@5R$(_uh0zy`$lCpO4Ew_Hi5y zg<(_*atM6!T-fJjQ{p1);AKDZOS=%a)L9#&*BDs5=i!Iqd%yX0oZPZ?eCj)Q#yRM$ z?FlZaYo{}V`Dx55V_oY~fmpvw=T!cNo=IONx{{~a*{u2V;+KE;eLTtf-UJ`M;_9n2 zW6(g@R`eP1kO^nzi#$gCK;4+9lWy!!yFf>Sa>~G47GGt3+>WcG;SRQzjXV9!I4?6A zMnqZ9o=!P=xcaFO5kHl2!X#gO_Iv408ctrB@UrHIMMrToKvVLvhyL`(_|k1(jxi_V zXu#>{k=*G-=03-tbS2MW{u-yQt#oNXw~%A#IpDsut$pJ>R+C9$t$;_7fBWeFdNMtR z4jNQ!dt{CVXVaL5kEO8>Ky2U3{`}3gc3!TLPE_li9KrFfyRZ``zde-z%7pmkpYM-v zA)nkH&=rR!5Xej;w?(LPppqm_;_~7@mkgN*9L&heLawevJ@1ew7_?kiy(C_kI6fYI z>hXAIepNj1)1RlK!2q?-IcMdkv@VeIowk(^;-2$&J^fqfg?K3*wV|M|cs!NuDt~?O zFLC!XPvdA99$$kW=xETs5Wh;iOWaV0vn{_jP$|EW*XXEWG zIE)mcETW(NT_&;-WO#}+wD0}qS8?Le9pkc3-w>yt&YnG(dKQt?7=h?CR*c$c085M# zUJ^cpL36aNf`XLbzC7}Z?<9gHwKefD(V{0nxG!9Gd7MH@@X*0SG8$w>bQR)Ed#64B z7Woy%BDN848HvnDCM8T{gjS!`@u0FWbMD;ut0vEZSz|R;9%DB|6(pAq0`gTBzZ^dyHsTn#9-%M@<=iUu60uA{ zSSwg%bjj@Mg^b^;;E7Te%u0h&m|=jZAa6wpoQ)DU8Ds7D7y#E^d`Vn^BG;o!*IXwB zuttPTREJ5Cf-KWxZJE2m!SyXU8xn>HgPAuT6@lA9*z1-n1^h4Rbw@2yAWM#{%MRM z3aFwb9EGV&+IfpJg<)aW2qWOG0o)WL((Odtne)piJH=IZLL;wJ7vtw&|7t9t?ej=O z`^=|46$63&fkOx~gj8F`wU70m%+`rFfB2)U6H$g&wKE}@4j9%gks8f->15D=h06F( z<=np%Qmh+>tS3M~IqYLYiDWDQoRlz}JHTTdW7pBJR7V5p`UlA9?bfwp)^U+$(chv4 zaMUY)2-;rHaf)-7uZ(wAa8d=ok!YFMbr{2=N#gD+cE zhk-Udeslj{Y&Rso#mOiO{yi5(@F%cG?Y>CED)ORB06 z`qSeN|9mX&_~fUk9da@!3msE9TcLZEDwUGtW6+UCr|X+a29p*8Q@LYJ zQnt!Rr?D03t~JPUOF0( zGYLQXG{tn=t{w3beE7B>-sRBaR%F!2;q`sWE7KU0uPPH5I1$Ps^T)bPDOcz#3kNbi zX(88!`xtccF-?Z$Z0UKNbmMy-e>ARTyUJ;!$KsG3675iOcY*Kj%grb*Fn6xPS6MB5 zjqqwjD+4n_g8p1ZfUz(4r$qyV27MEKaQ^Ct${Qh@w)yFQ+bmQ{!@{Atazm7YR!|{s;8eY;< zI@D-e7^xe$Ch}5|K)Eb#t!Cf!!o`bX0@;oh68+Ncx8>G}4(&M6g84x(DgP4N8GB(k zDlZ&2uohOdC#=*7T$9Y6fKP10=vqwM)8K!P-G6`dJ?W&ljttg*y?Pan25?0ulyu{Z zW)dfI>jW@&35AjTU4tuY5%67Obf%VMJDTb}8HeV-Ff3kucTRlih8yCe7hDkCI(5b| zpb;v56plE9CJUjD`~Uh-{Q2pBiem3y=k{zC{knFcMguTBK;S0J@j@pI2zM{xa{vwnX}C97{;eUIaYjU*kt6LaIJ zP+;`L#43GE_#*tWXaj4j8xvL^GMgrk!ug5 z*ZhVcN?-2(^w<6^WuS!vOFX!g{o=Yx^WtXmH12m@rKi%mb4&i6{r^Aq&IInSqPqK& zeNV_j683~eKoD6J5EKw)FM>O$xV&PuqSo3?Y-_b@ZSAM}+SX57QA%GGWl=#E6%bHR z5doEb4GAPbAPa%)d6xJ0J#)|f&;RECBmo|Mo+M|U=l<`#GiT1s{O-(|Ip@yIRXOfd zz4^~`zn-qr8}_#z_3HF`8A%S&9!R9UOk-{8HgywR=tqz%v@6=awH=iMUert40%Kuh zGGlFCNZu%=^e;a9nRKe;*lS;Xv^KJQsrB9Di++xL*?2?wrr)9MP*-X9lz}qxtf{c1 z$?P6z*gt{|i;-pLoc|3OHQ#Id}qV#7&LtgevdgK}TiyUG} z60(DQF^1+>T6+{-d*jd2xfflWKK!ot$WVQpzK}2@FK1FYZI~#2s&O`Bj6HKO2+&7c zpRP19G~j9@rEo`Kzi-Zi>Bs6v_7^|#H=2!jxQxA1>^U-Ho7vseN9sKC zg=c8SEtQ97$t(x(p^pMb@Zlu{je-}F7s;Uc&Fik!2BI%YAN|mW(t&z`Lf-}*&x;q| zydZ?X=^OHA9}H#;VdU=-?$lQm)zSugUL-Hl3)HK`_isP@S=(#n-P*t69ePQ=`|R0f zXkZpAF9R8#<+g=wlNXU1BkKhQGa9at;cxH5Uao!A-kzrJs2L4ZdR&GpUvGxL{by(Z z5I+P8m((Q$i5VKMxH8=%C0Q*)7M|VHEGfqb0H1<{`hwMr4vAfV|K;4T8Jv4dD82p6 z|6`kNVQ5&b_1MGpz|{22Qc0u0nvJl_Rwx9A8n_xDjUAzilvf?MipP5X>wkV@`tDDz zHvaEA@#J*atF*D7_8~x^liw_eq%f&s(J)Z%Xn=05rja1L5oA58=vdF`UTFC9=Fd-; zT>1mOiG45~x!a!U5b@sgMSG@66DFF{f{>yk1|hQutHDsgts|AMH5~Crc{e}9GQSN# zh}`$kgX!Nj_-ApQ zk87}UtETZ^A;t8hR~)7RqTU+spw3lOk{LwUn{r`cGYx2EaxUy_?WOo2yt43?pj0_g z@EHU=w%{?n#k?o|NCVsjiuZvxy;)PVcefc2O#8EVO2eL|@F4%REtDC`L??u^%|m(C zYM|`Vz!XF_)Vt^Id(tm75cFK>@QjsG?!l?aRJ%QM&1gM~uhEB)k!RbdF#LLol#?V&`Bg z6*OQ*yT0qbd(#*61{3$H9cHIvPCYs8x#ylX5T|2jU;ys4Dda-88FyGe4Gy$p4hGX| zM>3EMQAa{2xK6xzTX(ZMwr^?K&2&+n_`2h4_v)S0rbZ7}2P31zBFQ7BY~T8u+tO7x z-72b<+eMd0D54p*RlRsqprTm2kiM(wv($@xSm!SK-1%`)@lp23<_OX0(WG9@aDQ6y z?te6;Yvo1m-Obj;k;k4W1JL$bhA>W>SuRTdcHXzl@bt!ayiFU|?V{xeOkq@=M%k57 zC=U!#vXBKDAn7@?F)TA2@H0hJ&jM%dLD)Yj1IFEV-JO2*vm4W`Pt2DbJ2oBivV&9~ z@}|2?k)+O3pRFK@kNox9JkX?_sZ9s~+8lBkdB?!$5p~$Vz2(;Qog1&WC?7ff3|phh zKnz;i9|!e-!$8d3tzE$f_~1poGI=LI_EbS;{!TOWzW24SX~U=Pw8xa`>21Phw^_3+ z4)J&vV6^=q^~_*nb$ z&vGdS_QeO$Bky^ONqLX~u1x5m7!LHK)LlzM;bv%%5d z9v^65wIFX+a^;`F7K2fo$$qr~lZ{G`=Sw;`j1IJOWEp<9>$!gJzrJE&v-Nw%SszX> z)*u%QQFf8D44iFHuKt01nV~`aQJy$Rmw_Tipqz^8j_MPe^)dKA=X)0!{}W^sJNbl@ zY_+FJwu zW3-g$rIN$Q`MmTZzdc44&>w*ZZ_rd}By%Lhl!hz3JZs8eZ%BnD#-s-yo|C?L?zxF2 zp~q{9z+p13vAlu$!Lm$K7*%5Mbi+0IhQB#5*EP=;nZ$U9x{49w2`v%es}L9JYbdXI z@k?wL$qte;46w~Wq-X2n4C*}fhEG4TOo)Dl=SQF7{S4{Rwz+4Ae7@>*!!_5X+m|g$ zuRr=VY5#rq)gA)dsm)F@0||L&MhP;L+|qwrI+C+^&`!aNywiS}y-Ht*(sSQ^_oZK| zf4%08-=#gL%t&uN?agVoS+i|90PPwBQZ_zG_{rruqPC@a%CbRgugW`p6VIMEqeD~= z*sp^x|Jx^7dK6b5U^2O@7n^B`215%J z?*T>ooep=~>td&Ecd(ahPe1cino|Xw{echaC4rU<3SaUKKBUJ>H#1<6Cyn)JSFYId zRvY7&jTLBDI>4Tn9XDtu$+?=vgFANrgVG5no}d>rnmtvuMQ|q_9Q>#g)EyK$ zH-CjwUrbJjeu3)b<$A$*-S2WQ{+>TN+4fN2%MH{KWPlltt1%wqGvX6w25j-A9^t4z z)KBV;jp;@7z}&g%ymQY>52#MQWcavr>ihqXz96@s#_brwwai(46nUrL<^>si#Yp#g z{KOc+@=7{tM;OTA&$6p0wbbc0y@WXbhgYOs747JgPD%T|WZ$%d#+2ZVF~agHrZ&S# zG<;1CT#nyv&_5ll83)s3>>a6i z)EDZlqS!N|E?E1QoXKNio+a~5PNA;6gB<}`%d9od+5gw|H zR5pYy7IX#_Ps%b!BV#GYj@xVPk}48Q3~1m80|XNT00#G1(NHF79QbqK;I~eEyF`S+ z!4!5i0*nnz(ceba{>d^hOd2;q8z;#kru_M5l4}*PRtr#w$NGn!b4e* z!-}tsH5HFfgFP)FOPtAi9=ttXrnl6l}g2q2Xoy2_PgXhK6UA-^Yc)JjsGN zYnP`*S}HMo-xurK&by{j<3`&q;luQd^u$%iq@e0;{nKkSWmg*(E?glajoSN4VN4qz zFU)CE)1;J59H(|7T=?W9b&QS-1(zv=U`&V28B9zGR^8zl)7j!^A8atUP@N}lim5l# zw5P~q9oF_$-_1CsxkGbrK{m+RJQCXw1L9W&2keHu@~v4se4RqG5SFUVE__;_^Hh6Wsyt99#wd@&WVo8C=d;_iNomR$ zP48Usv^u%vnyQ@N2CnVZ8xwuYk58#tA$6ud8mfG$cB{|~#4%E7pd}FUj0U}t)-s4^ z6mNm1>pr@CU0SwM1JoY9;j&p`QUXOgb|kaEWTaF%mneT2Rwq-}RW4f^qqO*=jgCW( z3ty(fBL{e+NE_h~nFZdge+LihK1(W|(VFA=dZWX}yllcXOA67Bdc%l;0Y#cNYqC<$ z2YHMPU?9zaiZ=(eF^bKmZ#;9J6$5LYF@q>%Jn{fJrfOyUXH3Dw#xrLSB6w6LutqM@ zmTcO-;*)JN0Md5En}hbI2)2X`iTc=63)8$O9htT&bgP1TSPT*s!#N8GR4Ue>BZ~e7^Mw7^Pmc+ioU*m$9x{I3shI#%b&0 zg*7-(b_UI6@KqZizqA)NIV4SF1#*_9IuFVa^Q`0*ebQw0P1{Ho^O-`H#DNEW2}Wx+ zTV~KaL45%-oBmO%oboH&B>PRi&<83{v?=5=pC_aLCQsw^yk-h_+7k{OZ8I~q7uewJ zEv(`(sHUx1pQSSSv(aPD?M~-aTI%)qGx~g~`tIeDA=AcBO#95*Elrj2YlVz3JbU_0 zmNVLN2&HF+C}BaL%^;X@!%(YN8Zasyn*pJE%7$gj)LtK7x>(D$H1k5V$O7^|UeDMn zlH@>_%EfgyG)OLK>_Hu8O*$B(Nb@ZC@&PXkz=g2~vgldiiHu(%996OGtvb(_w3saj z<|s#$nZdrjZPar{{?iB2o`z{KPW$ry1DsISpH{!UM25}f;xSRrbE@(V4~#XmQ=UC> ztS-opJo93OJ&UN1*$5|prA>OsI@%PDO#>G$T9lTnzOv^I;{p2b$-;f2+CTYZe6&o{ z)ft1Z9}8*viw)W+X)|81PsOSH$cG6UUw{`%*JC=!`*_v29kqcaV;eTOCO;Ty=&vaQ z^@P40d7uhz?aKOewJ+Mz5L?QsK16-iI`vt|fcdJAPwKfc^J|921v}{F)kMiV_B0Zh z)>hYO78=u}muT$xq~!HF$@X!Y5rLs`<%(r#*KNk8S=(-tCTN!5a2cEF0m&N&*ZK37 zdAx9PhzB)nOc}8P$ z*5!|vY-HB+ROunK4;0e;D6`=Memnz~#g5ZbO>0kT|Hv3j&3b_N8ET5zvQ(l{es55y5GwL=6eIflH_^T*}9pkjc>O*a;t!G7jpuRI( zf_&xr1!r2YoXUaRqJC0e8Ld-~n9)GK8H3Q@Vj!VE=m$AA|Y;-oPUK_(T)mCP%0+Ai@g0LfG(KYlQxI zRp2oaTb8fJC-9LGxGiMM1 z76=bIc!U%R2AvBEKRnogX7Qq@3>OAn(zqtyGqy~$jArJ9;Jjj#hVJAommcr13Y{tyrgdc04naU2{ z&`}1`26v{xGGl`djDaDY%2VoymTKTNe)4$vOLJ7o(hv*ZYlg3M#)u*mhrzUDfz?c!LH>0!zzU)npEYZM!*(zNVM{iJ+ zAL_sewHG}J&7n|T7p}chh$$;|8vJP|Yz4O@aR^rGvbOH}|$Di)176j6p84h3AN2lr%Bo(XL!65^HN; zX8ceZ#4}^22I(mJ^bN=y_I;piq-~@+UJP;vgVY0ngLzq zp-*+($vb<=(0_n6OA?T|>{r1IMDo5&iYWO5SJJosME7EC{RL&FUUMMJQP!!k;Dx-S zKH<3M*)#Y;dEy=>W`L%Qdh)|%tQ#Vu9foU`kW7-oD2ZonmOPKuaxt5w0B=P%rCIft zHat{HB}N9;$ugJ*lT~Z=@LdLulAC&A`4V4b zJI~H$>qs`3GOb{q2Z}ExGlP%n@<`P=mdnx4@i}M42IDkPr+;N^LtR8}BKt`%?<1i; zS@@xRFrcMuv@Lu2po}1Ek#Rg%R9~=1)?=un@8snL#v30pO=6Nxb z#m7PPHI$1N5GcDN#Fry0392_LhYD#50nZR)JN+#?+tXIb8-r-t9ODX>GEnaqYnA~@ z5?_TtRwGN9J!H>{HmGudjg7#RU#kbYr>;;I#!zIIzKnLo)Nf=0DY~ImhoK=#KODRNI6==iv+#BRsL9FFjUWZ zjf}j@v}ewIeR<;H#jDdw%`@jM=h#si(Lg=3 z>L256#@%MH6n?Y`=+=rS1_bhH?U6oQ@fb^hHL?|147Su)OV1!&? z9{^@LkXPt)n^j#=IC7WgvO?n#WHK}A=rfQjW@u0zFyfPU+9}T)DL|MKH2ir!&&rsA z4#F}n@|qjE3TCo5%SIdD==qUH(|?pNo;$c(-y(h})4duCcFPE7FAqe|@+0~qWUI*n zH39l28v`mo>_4zp{ZFsrfD!)SliPCE1E_!S9w8jM7$fP;h~0zf3K_SxN!M8QRVFJ{ zUNELy{J|5f;eqjsd-@=rn;K*lE?FQvai&)Z(=2mjyoF9-reo;wFvjLt&@R@=_{i9h zm#jRG9<@DYH1I4i;K84|$BcH)U3zJ^RP}L%3}3tiH91b*P#SB+Ylz~Hl1vz-*{{qB zC7dyZq_g$+-NHp9taRX^2dBd|OJwTQsg~z0;pYV#8hB1P&ce|;K^yGo;nS?}#{#uX z*2hI!o4Zt2JUwNrj0iFwAQhU1!NyD)Gh4@vL`HZa1gKcHc1Deb4uXM#9-j>!EIw(G zm<}o+2SZ-7P$|F$KC1MjVKgGeQ9;QcmC!39Y+4!tBisjZXCNNAMu1X*`tKgp=aaJm@Htur(Shn*1gF*P&H3I>a zO%22v3c_9YJY%M&Te%d*V1_|s777yH>Ky0@h=*e%IU2hQU{90hVAzSyaH;ADX^?Gu z7J3Hu>{K@JXHX6HHXWV;i|UE-)7b_kJVV7MKP^F*1rJ=oJlC6CXOt=Hl(G0Th)0NE zI6;`hm(H63HUb306G9w6>ah*jDh#2ug90mzJX2oEfeV3G&cRsF26H;m{s6al{3 zz$GE6PI|4%iGs@v2$n~1kOpm!0R-tVU<6O{$lLk}>U8M@mddL8>~gIM)_{Ga24rKX z!%{GRd-Jc;17G=XP1ziuW=)%(wo`tmt4d5#-D5_>I?ZOFWjT(@Jq1%)Fp{*6jHj?v zJ>?Bpm+IpI#|`E zHx?_p)6!LXYpB8O8r8iX337PbfKIa*)GOP%Sf=jl?j1DucCem6^IYLWjuh z7@@Vj%z{8!v>8&G{h{tu9g@<};9;GP9_58+C-pClR9l*${7uu0k8v6stX;iK^?HS# zIfFXYLp}Fiby~`@@Yhoi{+1Ixry-inpcW=SVWdu;wZYlYpg6-vCk?^UQ|mO~SCv_z zUC(=jI~zUv+Pv+R-_Qdy`2Hk$z;jgP$HS+z^*I%PyYh@6D-)NJ{iG10toOOS`fMIKNV zF9(lW+F1YqKmbWZK~y|2V3-3N)h8VF6rOINA^!}pP(m#c zD)I)ewaO357->*fz29=##~_V?yy2!8%+zB5$nyYq%1*vjJi~`}gMr7MpFF|IWW3U% zyd2858Fo-2hf9HBN<5e$+lK+A_+i)qa}<5jsh*Y?z(G9pd@*M7woSDm8&wpn$nBbn(X9C+RgCRfYQkPR{FZJQFqm@ z)xJ^QDUc~%Dg(I#Z^K081UHs=U~sUqTb;_!*JZmY8mh+-Ah*DteixZfe9|Ic`Lp9% zc0he5uN?3NvN2Lmm9m<2-L3Lf-fq(h#_AMKHTE034-yp$HtlX~GYoAwDU;~&aPet6!zab*lC zPwRK266jA(#K-_^_r%fov0H{~mf>RXWu^c);!LhXujhmU(WTi7Ygg+N&{F)TPmuB~ zvY|X{(h+0wVX>&gI`Ct(fsp}YgC2y@^mIvamjW_OLUx4uQ`sx6jdn}vSkpT^En2C) zYgS^IS6TJ^q+;nx0@{@EJboIYeCIXuEHRSu2HyGuqugeAw&W=HZD0vD$XXO)>LmtV z+K$yF`9lr1;K;St1=Chz3Q6l3}KsBb0T$VBRjz0fgov;;+5+!I0;+v<-k!U zD|6*XodX;4MEzyy7X~j(Lzzd|>$*+HVC-GUM0HmeiLn@H@rSzj*sh7pfhL!<+5bw2ijLJvlAOqd`y zL`=SsF&G-?tCg^|KQm65{Lk`=dSG}_8qo~Vi?5-2nL_&hS zuE|u%fc%11^h!~ak)*ropd31Iw5J}8Vf65AX_acZbXR1Mo`u@8wGGj+)Yjq&+vz)O zpLUr&%M7CMpe$gqIlF!_GynvLzS^M%pvtBPV}pPBnUYLJLkMBjq+=3nOnIj9P?K#i zDp~}U9*eYCJtQhQ4^K2!p+#zym&dOMhrxjknMMpNDzJT;L_8R5nBbs6>fQ)Y)J1ER zSrO!$E1&qAFc2>s4>UKnJZ+c$#1v}c>Kf&;e&|$45ui-D@=ji9s8muqVB@Md3_j^R z@kg-0!vv4YPaH4+H}YycAke{plY_TX2x`iOV5Je8qkIgYbYp^Aw?1&o0x**qUtQYz zF9}za74P`L!ZM_EvQr~e!=kZyCm^OU7McFIRJ!D!=gl)BPjuus1?RHKpTP_HpixsU z=n!_qE zQz#!`kENLSbi~|KhY+Ur)?U0x!-RR2XLwj$5Dyi^cx55SGt3wmM&e1q?0Hc@Ir0v+ z2u%cypHzmd0UwPJ_CT($t1XTZjfVELMuiAZCChW5 zGonT?02Dx~?|EQlgKVYItv5edX$5XtqVhfuPXEk zbCz5Um-4OFre~_RjZ(K)_v+Jd8icJ=IlHOvYQsEC@~qxB4Z#Q`N|YgzvE1nl{^ZFz z7X|R_cs2%?f{mD3%0JIXhha~7z?$|%JdwJQ5XFr8O}oIzGh7ySj=Tva?L_TK195Zk zBeD_zXE9VeAdQ?B=`sRl1I=FX?b5MYd0eZ5r7*)4f0!)bqlL>@lUopLs<4KkR++7g zYHP}`@iO5p@Oowvb}&O+0$VHzgbG0@}fjLc5!M)+FYvSkx^j6ow z8M%OxN?YY&qO=g5dr~x|ntD%$M4M%~;?rJKzr5bl)`;pd#@Z2y;RrC7pRd?j8u(is z(bC-3+h637vE=kPNvjMv59`%Pe(xk#05c;_+`)HTci(Eg+ z3e#W72YfAeR31Cj)|DRZ8pl9uIM^w!Dz_f3p0k|Ar_8#xL(#Kn$aNk+8{k!CbUY|J z^_e$xV9%f`_aU^g%nW4)xoHDbDGy8qM-r@79GgudjF=t5;Gfiqh679f@Zp)0Rz_SD zPK00M+8z@m!V@}chbkLImejIY4ffU=V~J!AGZdImRBkwJW* zH)Tc%(4X?Qjn4shs{v3pW+>PI6@Daahh%~-c?R4wu*EUZE5)UNnIR195?}f)9B*GS!sI0$xvoQG&s~_HoRJoN zDT)L6;jjeY2NNY`W!8P2t}x;GTfGsH<?}D@$SNbCjAWWE|+#>@^*F@2q>uKyIPc zi8A45XI)B>Fe9+IguQiG6yDZ0Ob#`44PAmr!yuiapdz8DG&2YcAl)F{h=hoMG)Sw2 z(mgOpGed}UcMsk04*t$}J?A|>=l%ZTnv3CL@4f0?Yu|gVA(J-M(+5NBS6@u? zE>OT|yULnAdzc#x2)^mEG<=z@!R75Hf58qv8zcvZDA5nXO^5)UTCo;-(Or^uK-ilDx}McnjK^2PN-+|!86-Cy$U zwtM%kl@$a^=T(@QE!dkyDj=Q#f~r(M%aiX{(96JnDlcc9zmL7Jy=&46*&^1*g`5$> z#NOk83#=S!(q0J>pgtUcdiu#~V6eA+ABR{V?>SiZlz82gk}D1WES0M zEVJ(Ra?Z?O>gx(iwqL2;9g+)0`tM?;e9Z{uj8nKu^Nf+hZJ+MMGv`>!krz?O)*LK| zC+JqKvYPCzsANcgO^;|X*=yf7qnB`}(!>d3V26e@H!_R)d_7OBGO(IU3u0L`|s(Tuq%x1xDe?8@rXmiK`nn(qP zgg&CBmmzcsX&PZ5qQDI0zC%h#Q0GK3ohx&1_~rR?REqc#@08D4-Wt<*gfo-ZPQwbT zHG!M?(5+6jNEn{$OE%9iAn`+7Y~wr_?iX8Z2!GUfbZfPGNQ0=+tx(sJ-=sn#Pu@B$ zbmStgPJGvvZnI>XH_;ZzSxE+FE2o&;=`MYd>D;~d#Ypp9`r{Cn!j4PM^p|)Y2OSrc zMG&wO!^maFpDxyxkYf7cIsXlwrOi2~l?)%;)y~G%p)vZ@8Ef*?S&B`7$!d;-n;?C? zGl(TE(s0VnvF~Uo&|IfMybXbDzLV<@N})f{X6kf$XQYfg_-d28FXxqGVkxbazCLSp zK8@Uf(pba7p`djx6OD;x`p(4P6q{aq02w2Hd8#9o?+SU1WHx$sqsz2S6}{h->ksc8O|o|Dku0D@V4}lzO^?dgj!%g!7ntrGC9LPWFza>ufyJNq zjbuE~zvV4KtG$5@i~I8FxlD*ssMSl0+)ldQC*OC^#j=hN)U2;wCFqUNqIyw8E}Y!Q zKlopVz7g>GQR>p^GjaLYuYXCqfJ4}Aldod0Ozx#?#!gBFZKgeSNpZuQtJm|FkM76o^xScW2@vmsWqPVtXkV`^`yo*~>M~0UPk?+( zgruh)XY3qytGsOha`U`U7>}G?d&An5eC{+gAAgzZDxG(c_EtBHT2Xdgg+JF~33WG@ zcH&unn*N&?mQx~7Xc^+;OF`?pN15*D;{?-5Rn+G!l`f|=q>j}CqN>1(pr;jH0KDCY z(KKbq*#4~G`eCYmo7|96YON+pBrDbUfJ){Uqr{BNmZK}fb$_LO?vl$PA`1vE_eC0m!Ezvg|P6~nWHt2&-SKh}^g%Hqh^Er)ih zx732l9Fd59Ri@ClGaF=4DZUbZ(zSdo%wM6KN!^dqbq7i;b2%wS=HquH50g$|d8J@#D_kl3p;B#!2rN5_2md;C+zz0h#awK)ukSPp}8dQyyPZ$IDe?^-<0W9h!<;>enZ=*CI$kP|%bfur~3SWX8(huE7(uO-!8vy5#KaN5f z6=M@hQ=Z@Ta^t`>NqA*ozJmAY9aBiH@0{+L?l<5$pL|C*O7%x}gH$sQ=~W)Y%>k9T z0rN~qI^4U>8i{+`yJvg%wZaRz?Wwza85X2>mR-|7$QmtYAf`}0KZmw2?H;9v`51=G zzjv6eS19GXtMv=TI)gk5lq5J#ypDtq(&(PXF|9zVvW!N)dSHg4|!U zD4|NKsRUNt6PT%U>-}nL8DzwhXlGi6YA}3S+dUci@NV4s3)Yu@JwZQrYqlmOn(OIp zt+G1r!s-B3dl`-%WJOcn4|bK1R}^l^{04@=9NT?so(dCaYWUBU0^w;3q)V@uU)(1M zUCY>4h906vmABmePid!%!|>!|;6cAHCJT~3552g*^fpT-{p?=GmQ#2Alcfrahh3wH zsnXnikz<=_@3a+f``vvS-rRFoN%4ChNQlAZP@}i<`iSae)H};}0W!ay^nI>0T|dw; z+184JwWd1nXvG+vKs3|k5}0eM=SVV`C8h`PaRC6i22r!DoJ$={pVmlMWcYMu`#an5 zDB}uM+xsbn64DtOwu$9;Pzz!3h=K7m`|glm#dlsc*qL1_eyeM9DVEsLFZaxrvVy#u z^3brkUk(jbXwFY>$TY4Kh@R1zamkPnY&jl->tFO<(OIm1|1UNU{2H$w!;@+M|;P1+5TW^;rV{O;)0WYV^Y zT~+&By79=TGDEpuv7&8({CH3-q8`5*6aSs> zWcVr}bB5_%P)SK}9waWt`#6r2Tl;gWBcyt7*)ODGCz>Eh9QmyNXj^lJ&< zo{FqpbbfQk%xLln>xdU+$K_e%&ThBViw3dRfq71^@m`-TktWh9U+JEn*k`+Y^hZDfltpNZcF z<@zncLI<(i1%itYkdSvJjW0a$KFMmVgwjhj+}g4M80!=(67G(|M(rzyx#{(3HA16dZrFaQi}wUwNn z*)Qo++9Y$i6Rwy@$8AT*E9P6qr}4WbgY-$&23CpJr-`F(8VkJouJ zSwG<|&HZtGG1l?b33jHiH;8cL<5KC}`+ZiU94mn_VZq!2Fh}hwS3^dIPKB5s z@CowmYP^-D9D$9bBA{I&-8yNgc7jpHR8%Hz0#}LxsG-YK;vtSLC{xobaAqcMuBGx|*d3s(x zM5RxgF$|OPm@a2$+5Ipz6c^se**9*XcAlG#r)rQR+$ndudf~cbe4H=qcRJA~Nqi*Z zI#aQ;Jw9T(l0JmzTfmHq2)fOx<+6-a-)BvUU!HWfG?0Co`eb|Wb49TN^@WaMPAJGr5%v8n>F0WX-R*2St@BH!6QwEefGrb{lfCG6WO1=QT($-%#Sms zKoRi+$Q>Wg%FR<{`Wb;vMAQK)e@x*#`cyILzn+N{pKdrO0a)k}QJ>zoDi z6!+5WY};!_%X>#sfyHt3tu>0iS!%0%M}3ghd%Nfnk;+ixvEqCC^FD{6QvbsZ*Qpmt z1?fklV2xz4Dfe2x9&5{7YVjP?ZgcmLvSO|c=2M#H@m3|wu-nAO$^HQ$9>_QJ(<>x+qsawA_&^zh%3$bT4KvG2E+Ni~WCubfb3VmpjmZIb^o_w57}g)HY39Y<6{Z^UrALDMvD8`)bcH?AJm~Q_J=&0{Qb`M zV=wemYNvW#4`cn(wi}OQT<3{83NFb#ty3y5HOGTZty0Qo=Uh8jJn|va2mHRZwohc% za^p8A`jQ}i){Kg(J)F~5WamHH(m$W}Iryh;kMxESncdC}CRex*IW$NTs^8mlMf(Y> zV;&wexITO$F|)=4UU~| zFSQS@4-&5Vaa&u~`bxcBWR42W1~F}%hsxr(2FFV(t;fJ9D+$EqS|poE^3{w5eJ+Ar z>Q>*lH9c6hVZL9b4=v&~pDV!>G^T#WrvzS570^;lnsZ|Lzr}$0gd28aFTk^hQWTzk zgdg8{dTpImowrO~%5gUfC-I=~cHQk6$q!$V`-tI`DH-hcmKUjmDZ(PGmV4K%OXZKt z@@TAc6V?k`d!+y|q$Y`U;~!Bmbd|O6(%< zZ_JB*AhrTGaOEwQO!dZ;Us%G%tVY!`gi5CPLOi(zCP@)Bt?;BBfRx``9R`M(1?*z#l`mQ{Yz6Hd+wq8Df)oDxz>>&?5g^}Fx7GU9&3gx^}& z1z%{B{txRW!~@V^;tP=XBF>W?eL>-vFoDt#DhVFB!sjrZe1%n(K;gOC8HR6c!-Mli zPFyuSTUqzpC*CF!j^@M-y1DU6AMtX@Xhv?8;F21yXjakohoY_X8%>cfH9ZS|K&x;| z1m`qY`0U?lv(mNT&NKh5)6q9NeMWTuED*l0goTSW?x`RfYzsikBAd)VA1pB9BI+s| zQ{MK+t41-ydKl1%(f+(OqVc_fBTJ?54ru>Wk8P+eCrHe-(3TQmYk}8*?o%a+qEuOb zL0dH*gtg1~MG7&tqFkcxXGAKgu>4|zbQ0E|=pdY%X~X&RaHE&U5BEQ10;OQ@#~>oP zMuW#;Cc(=^!?ot>NkSSuiGu3XJWn3#LC`G zF-%P39@zrG9<()FBJkR6xXvCdK|!qJkFYWIgDN(M{tEj|I2e{i5NYY%I3ZN5J zPMa@}CWiVXXVQ*l{I6Z%*aW$hTorGPXnz+QZ>hf_DfH9sG`^!&v}>cdutM5&Y$zf#@v{~1E2R-WS26v{>?FswO~0Z9MG$JgbF5XU z1!UM1r!u*&goT|MIUe$LCP$=y@tK4C(0z1wx^*T{RfIWnDk zzL{g5)5HkymyNQq24b${vXu6h2NQf~{9)ip&xPo<`FFyaw=+Cn$?SD<4OJ8kZN|Iv zE`u1ej-^g&gHV-sg!9BqP4tHxWoCnZlj5VD^H}^BxKcheQMWOD-WQp7n;*KvTsJsV zdTF$5T1eLfo{}?SFIyw*Cwt7LVo%?Oy89NwqWaRP-hG<$_T%~Uz~B@HFzl043n?iK^!{aFHV%Gcyx7d*&M{iaD?FSD zM2Lt*Ak=a1_ccGJK7-X^q|raSUUOP?G@$ar$qC7>! z2U-W+W;Y43?XNZw>zIB~sNb>P$8JbE{N0yzRRZ_kK0lNN7jgau0H#uPgH2g9CFG+v zG+bB_s8l-s!v7S7(kywPQZtCLuC9)%qce_6V=fbH86%invt73_sM~xt?ApDd`KW{0 zJBoqnXxyfByk801I9Y9O+gyZK*@|x|_tC}R``L?4Bf%Gr(`o9gy&>>~E4y71{BA4l z2pKDhyf|DxByKU0TYq|iUHpXU3tmG_YK&Gb5Na1lO?J*6KUn%UA~UOdYWTvHQ8C`Y zZOi0Pdc@=%51-;n9<}YN9*9ZcV}zSIsOQD;%aIjb~#x+R_b-+R$t z|He92cxONR%U%zEsc>HE7KinMz!H;QE9q-{J;GWbM*F%oo{7}CgCQ-g9WRvkU<(18 zQBpED9f-t{cLM~JGQvLQrVL5_3}GbBee3FWY-hzzMwU0jVlCxxAz^N16{dg2t5L!) zJw&!5rV%t%)*mR|fD^b9h~+j;E-4{Cs#jUc_mzodz1#5R{AW#Bua+qtQFk}0ln1xC z5Zb=6K`#8l$fW(V5wGQYM-Il-tK&n3)Hd~2Pc0pq9k?P>|K5)F&2|D>poiggofvF|I`G^lB^CTQulJg6U zixHw`gF382kMD5!9+v6(A{oauJdS)6B7W!u~3Q zU?8L5&?;c5)*U%D&%)n5d4tS$El|QA5glyBKJS3#Cx$C1T%46085>T!p`eOvGS&)8Lnsv z)n`8F0yY&hr~FkcSIDE8fENvSc0X-Vq$=AJ77-e<1r7qWP2LR(;8>{emCh|557)}n zeug-MU(%{KhvB|Gi2@{QRYUNuh#D0uCP>bYGD?k498O!)Uhe6-XfV;Eok7S?!KCHn zkb&?pO2^8~a<;ZvgD*7%3om4K2c{4^ZY4tU243#Cc;A0Cr;_Zkl8*KF6Bj2->!>3w z!Hzn)hM`V;L!vwL;jV9&EQ3;v&?Ns#yZ;SA1mgx`3i4U2!Uh$cK+;~TlUDks_pF%t z9(5mcRHGlWU7^E=Ov70c$>e6?6+PdK1)@Cj<{^y0?qnj0^2yfbTguEZ6(uuG142j% zycWCF{vh~XY~nl65P6H8?rz=)cvg^RQSZNJfqqvJP931Qy zFqb|T<<>lcYOngp7)vi>%3+gqOAuTv9?FQeU`nU@!Z0i<2h%K)Z|KVQf-IFNc-bnB zU^`L%jYDFTni&{*yKu?npglYy;zq6m53JV)^X%}=$J!`MWjNE%&UA*b37DZ_I6wm4 z^*kKSTNf!|0IR1b=fobYs;*l9Y8D zvgf9NOe!-~39sCMvWj97lT5;jbvrh?P^74!fxczW2J-3I(V^T)t#G$k^q#>%w4s#i z{O^N(E5B|2B{cc};OT!^g`ynJX!phPuPSXtczQVdyn&wB;#~9V7 z82!ZAlwA{&tT6MotNkLP2HQ-Dw&MGuq`XgK)R8xFYDQ8P@UNpI<-}MaAn{2VIl``b zDsePEP@dLkO|@tR{At3W+4pQPsmUD7nExdC!>GUy;cAXxY$w9wB^urX5RH^0@2EZ>aF z&i-nXzC;iVJQW%$`rL7cVw4>xkC@DKze!l}B6YoXrkVke0_^dAuzHyDc*5&j2W0mQ z7+jOXPt9M-|H`aWtE-kP2mQCW6h&|@Us+)?PT9dwdXrCn7Yl3!GZ)K}5;jn?B~O(1 zbUadSzt8B-7Z8e98{qtD&?=wX1rB>FOj7l=(^Ctdu2;CsR1X5>47BY%N=~ zygdT5vQl;Bq21+SVr=U;eIrvgUAEtr#aH@OuRS7DV@2<0l+J&aT?j8SZZJDy$M3k_ z_3Ct`0CKsmn-5n!U5q~}>cODh)*q-|{Eu&7RF0GW*OzP24nAfw8^M-&DiEha1{@z4 zPNcNBdZNIi{pCJ&a`^*ogDTtPK31p%F0p)%NS0xfPwnY~q}_N$#gzNR7?23|sHO!Q zffWXb0v=C!WbUeTg}Yy09#@0Gq_g4KxCWABj_v&z)yA|1K&Bm_5#)vp9%B|suALm= zw}60jW;w?+(dPj~r)VvIs_O^BZ{p@uY8^Lzmz0mum}pA+d74Ne$a`ztaibr^WEK+# zlJV6fGz(*TvufO(+LnD_fA*F_IEqxNB(*^x>wx|#L|k)1Mw0qg?knh9>D!9cui9Vy zbwEIY8>N7Q;8#EpK>Lc#_h8^)Hkh2J>0aOmzxASm{IPP&i6;aw{wyU_%3XdI@6GQ- zTzDno;vzaw%s`^G?fM;wrZiDlR_+c45w*W#0P>E3NFS1@F?O)|``nb)sEFmrOh8n0 z0($RD8uq#ml2JZ9Ta_awYg-Qf-fyNhOe{~)+#ryEk+sKz4Dczp;G~Y0d_qan+4@1T zgKy7?@7YkMre)J{Z^b3qgrU@d=DR>FT}HlTRHnnO9<23A6eimAD;z$W9xD&3>HWn{ zR?a=U5=PP5$wuI5dVg-{Q&rln13|G7 z++h~5=huA+es%+AK&zbp1qGfUI56ofAW;emLNDR<>cP?IsU5!&*lo-(t;`?XR0=&< zOAOp8$pk|MTGfMf+1PgGTXmHZxTd@FKP6nSf`9s7t@!^g$1>SZ8Ohacn5UKC!p@MK zbPVtyQ)%!%~MYGc!ZuDDB2rQb3E;B2g6mxPt-(@ zX#v^om0CWDxJJO9J&biWL9dMObg==5Bx63Vb-1zj-w!ajJlF2w*9qW0KA)WtP@DX_ z0yV38lXTGx&_Zb}k8Do{V*NfgT^*L*j>5k_Z@x}7IUgU%e-zJ?yoXHnBlDNtaeA6& zT-yNZNi3y7}U znQ10hdr1XJO$T}T5fH!Ar8TXqMXk+8KA3Ml+41a<#Z=Qb2X?#O3&V`xD}b4OByf&H zOs&`z6;E2o2l45R-YXn^kL5l}h4;gIarQR7A5)Ahq|PZFZ)5&Wbit+X?#Spg9Y{@6 zYA&Q=CByr753f)8qj?!2kmhXc(~yhW=KW}wzl`Ni1jN*u4pOtT1@OYc_)BUyeV6zl zqCc4*Tw@$7c&R4WC0M2CJ#~y?q&%@iIjJ8;dGoJNVz0{>hy>n3z1jxU*wSO9mqB3h zi?fkt&6%sCYH9!hjG^or(PMHXmO6|Tt1jI53wD3AYQi1{^1R%DICz6UdhOZ(xk1<> zj#<6s$2h6-Vz{^+d!&09k{bh)kMhFhj=%r7bwTRI&r4D>9BZhxYVz*&z`+xr)9RC_#{Bh+6pdg^k4R^ zM}cvrxWuCE*c1Fp-1QsC`az2%NaEEY(fc zh!y-H=3d_qLga{vx7}HR|Jm)-?*aEvgG4ZK$9BR1(_mlfn~V_5*RcMg^f8E*Fjx^x zp*M~#59TLRyg*|zUa4|CsZKVqh{(&biognw8D9@DPFXK*4u0zM55FawPy0f!L**G2 zFoGY)3~u!@Z;t4olS@o2)id$8k9Ynd7j(%jW#-7v($wEVMVxYB}@ zU$BO+!jJvYYOo~XyRy2;HBZ87XJd~_cmL=B9E(M~S zBw5j+gh#?k*6pTN&}7`lqM6C&`dH^AHDm&IQfkD{NSA}00$BYWy4S8IpK*5S?EMXOHO~n zq;5aX%Hz*B%VX~x_P)*%s8PJ$SF9F(K@por?bCt*ytCfjcM3)YaF0GiPw~_xPbPUF zZSYTUKib|Zsnx9DK{bWFxHs)MJzz`?MF=cb){EC6229jK-;LBCj}6-U-o-N-$kYxf zX<_0b9f_$IjmZ2fKmL>0K(Q!SB~@@Ol-7P;9#uD2%2SVKQHFnx&c+V?R4SAu;xen9 zD9Ur-dYp@yt5-mYP+LV%3nK7MF$o-I^r4}l3EVkCw`niI8guQ^r_S}}&CsD@$p+t7*QUG04g)yLl!zM2;v#Mmw@b4XwaCV{IOT#l6KS-o0~z3OZ-YKbDinnLG(tHxJ1~!205JOlYd!Iuy@uNt4#h^O`gBB=)M9GU||LbZ7DiNMC25xn6JwU57vBLMR zJ>VX)Kw94<5b>$Sk392ya%D4vn@3;=>O}}oo&UlysN78 zC4f&tOM+!0H}n3u*^m~vV@wzp9>M@?tGQkYctF5jtQqX*O(NV*B4KthecWVuWee?!!W+c&`17{? zjWgH#8d?O%>ZN!_zbxsq)yPtL@}y9hY9HAv&~l<&6<`OUin)y0UaNHst-mhHjDaRpU;#^#!X_X z7Ph4XiF&s6TUD@cHA{(xwnH5bJ_}4$w{W=#yp_t*=F}l)&(4MvFLl6AwEd3q(8-jE zg?@U(-*=kM$Da`%B|y9I!f=EY!7MjGW8_>P{Sycz6)1(mf*lOjE*_f!UJYuV9OhPp=2uzd_kqu^G5O@dwE)Y~|{9YJ%XY(=u8yC@L7Ap@sf9SLO z4)RSh?iN|*usPykqE4AV9+>GNxuhkM85~w-j;l77B|8^Fz1h1*k=AFvI=G^A8159P zcs^2zx+U6rLiE4tG9G~9X1gCxEy=?s?CbjyHGNKdAXV%V!E)Q93r|Fati5D+!T=vF z!FmyJQp*0%{pAd|yamt<>JowXoh&5~7y*a9H%r+3#w?s$>GT zi&=sVdB)KZ>?WT(L5-k@>LE?pJjJU8MNJ1!1XFK+nd4k*TY-%5WlP@LSIFg;U1EL-uCMg$! zjSP$xwWdRq9i*for(#&16zvLtw9?w;+bQyB>(p#`6xQ@nd0Rj-{^UXy7i(seIS)=) z*hXoyg720Mq}(x46M7%69k^ere6eY%SYG<7tQY6FOUqBJaZSTPj0;;`L{CQfYK(%) zf4=-85T*BHGboRyAmhy!2A-2Aw^gyC2th_7o@G&s6Ej!tDY70V1C0wTJ7r@aG&RJLs+I#v! zyAIb!4ppVCoazG5_Iu5rh=l!58wGd`pnYWAe5q2&ot zlaJHKqfeN!kGL&h?bQ4Z;9S3K_g0VS$vWPs#BQt7f@;dA0cfm{-(MFcH+TeqjdKaJ z$`U96&fHulV6vm{W7xc1AeIv&E@IK+?X>9~qJ76iA~ew>iGT*oeTm)Mpdlw%7!Jf6 zn)Be}?q2cL`tVmf3GB72vCPZl2Mh101-zlsIPKUl_4n=6T5@qGK%O36?UUpLbX=@Y zTcQBeoE_L9Mg+w7kq;UpN5dS#Zva`MlSn)cf*2Ahg@Gw{)M_yCGJypW$Vt%F)0Qa0 zM6EI{JTRNy%a%=Y1^n)B0A>une^?e3Ecfbui)Smtg@{m@E$-%QOYPen(a8ViuCZ>w zwhDNL7i9~;v?Z+R5pI^dNxt(zvc*g^kGYfcuusgym9kZzc38Dc19^`G)MojCm@)+z zfuAa|m#hwBfMW5os59xwIBnOijEj*a>Sw{ruUp({@ zuC3<8R`m&V37;L|v3-lVF4QyHd(?D?APj5%gXFwJ^VE^`phWy; zMl_HA;aA950a(<&Y;wNXL0$taek5wr3xyNT_i%OET0alCt+r-~|K9~ld4lmn85>am zm{?X?j$S<#snAJz8g`yPraVa3ens3%Gs|i*y^!siljQ;r56+|1h4{M7lYn|FX2Hpr z62Q4_DWO(=&%rbR%p5F@sjhO>=?YgM2wg^*;ENc_3~|Bo^$~F$8jNwZ>1J zP(U)2@aci8;O_s!Lk5b97s7eFOM10T7VTWr>xWDcoPDNJ61udPI@TKq9Wq z3ciW;(Urzk!K=%XZ>%g1jRE5P>F(p!Rm?aBWP?1$dpMA7r#279!H$|)uiNs8k7s?_ z@xySKE0|5_JfFQB^k2;m-~38v`=qNtKp&@dnp6sAqx}-%KDYbmolR>Ek5;;fD9na>D-)JcWH%T-#A6 zjfpTzsh%I<`v@J zES%tU0xGrd(*~tj^47fCArJOM#)>Es-WEdc|GawuB9W6PUzpz4@S6*63D76<`SQWh z%KIbzcGuUP2iTDLXE8Dv7qco}-D1j2LjQJq_iu?a$O;dTkd6H_19xeh){(}6OsAb6 zf%91MaTPy0WNrk*P%nc?U5t@n=cQ|KJ<4%C0aFKpFXYMlvrZP|j6G`yQI+B3Y&^K( zKnAJ3)+fZPA|ak{&>c$3S3d6eaw7N3OnF9_O#mfxOULbU|9gnU@Iiy%Sz_W@t}X{h zpCavuC8V-H=IG_XbIie9SllxSjvqaA57dq1nKNokRVq7_^G;mIg~@amryP|)NJN^V z7hIo}A2*;t8FaeHioh1PPeXfxo;pstcxL#v??qRSAmyT-Q> zYFai&_`B(BYo?>@JIr~3!6GX&y~3(^Gea%=L*n8TNZYq@IjXS?%$s-Npk)3;<0PIjfrRcFTM45idl?nh%E7B8Bc_n0psY zjzr9@h2uY0JeiAFIbCQHXLr<^o}}zJ^{$nQ*J_ojSM-_8wAs@#k~H`9lQ+?SsU`fM zl*oS-5#Sgy8ZVHv;ip=%s?(7LRf(r8uZ9IRihcb?EB(JD`LnN@nZ*Ay8v-TML<3xs{$ zUymsEw&(ki^%7cFG!V&a$g=%(7IRvo#FV3-90fw=_bCxERxRy~{}9{Y%aJz%#3Fq# z#`5@XIR6;$AhTcW9_kZ_J2kk*!e=Fz14}_c7RP_}T#N$F_6A0#)X^LG%Dw=X|P}RL^E#)sve~jjyT=?Jt@hdpO-}E z>n9`or8Tl_iq*FnJ^skSR++Gd{lKN*bAoe4F!UDRbh=(eoCjy&ynV5+@$DLfFve6Q zm~I?I3$2|b`-!|&9oxvsf)P=5>U;<7u^3s)b}ZEnnMuD>2`L~nh}<}tb%dKOmc$rx z$^l&QkxKG%x&9Eg0aH-VA(>muSqz5MD9s*6E7|*gs+)YV^|bo%Q&)rQ2=VcytVlPF@atfi~}#cZ?Gw!;1ViHi4pmpi(l=m@cCPHwAX24n6k`8c7|qM#5dKlDzUC;&sr|?7MBF3KKdds58VbOfUYIWWOXc8cgO(YGm_KAZXi@eYi6HvW~~LnY~7CTxH=OUn_`*y<_`n zxZ5pbYMd_(FFWqJaH)}Bot)b}%Z1~mTB>SVuF!~@qpyS;SLF=aVv!qv%n`tbV`>HR zLEUnuAq2k0GYAX&O^aYt+=Huo084xVUXXtj@;g3MTo2D@)YsRYdlr-Hrl1V*li`Q z8$99%nVame9x6PGV4nWRNC1RT&5r)rb~ij>%w#<7ug;}l)i4Q_;2=2=UkS%R7kNXi z`wv?q53aC#gx}H&zm>YI%diXmb85f-Q0NsiI*r&x9#R&PlJsH6tyD8ooYp)HzSXYL zhx_^>E$Vy_4*lN!kYX0(s((w-a;JEi{>fuq+)pjtEo96fkC<7+c$5s#^f`C~)N|*; z2*y?Nhvzx^jKZ-tSp&nqfmZ@a^`EU*ONdis_+FYT@7eW*clw&#i7OWfEoB;UVWcgH zw9MxW{m1*-3f(Nq#p_udN(m~$p>6-r>U7Uk=bXIak!&Hd9`*;0oKcJ|a zb%`h>bn38+e4=#Rig%GOR~}gcbtZ{-qB_6qdH#a!%JEq?BZDP>q96K6;9OQvN=n-& zA1i6Ie*8h2ST~x?XSPP;23_DpNpxlSrJK#`w!3#C`uhV!>@i0MeRm&=3s)%9aF7D5 zlK3IvTich}B-NP@!y34_Mrk^<51xvO*L=r*xpen=F^wDbKN{JGgJDVA(#75pV;}@_ z;`xL;k4fw_v1$7V{(8>yNI#ONmNE%1Lvw9qWaGh6fZ#ds7SQ05m*e%lK{1BKg4sFt zkEQBtK3*o*41e|B$f-G0LuDXyGFLHdcN7rT>a^dDM%u%9Dx`v7~1> zE1*yGKTIWoq=FUmd^diW9`nSctX8h5(~@08k7BexqKMId*O_1?_f+WmH}Mw&3Do<9 zg_>nwut50~pI_jYdYKEsWco=bH&26Opot-_-fDWjmoZsNdN-R^GV*L!PW&G@a1#Wu z1T1$rl#L_SH-CVhDJsEpWEfe0?o6OGr~K?086|pi(#@SeuY&ETBK+y{$zeqpyuqO_;Z-{_K*K1}PqtU4%1 znZrl5$?RE1notb0%q9WGMpa6s@M6|`Opmb9zr%c=9@N~hK#K9P@v_(~l8r~ZOVvg+ zpJk*jPS#Hzlnzpw8g>k z68}ha_sp8COzuf z$O*6W!LQD(L&fb4v7KmdKnk2LGT`{BtCG}qTztfBjYCe}HjWXnv zhR8+>r_BD#hxHNNXpE*7{~jYDkP6QL_wyks(0l;ltM{A<--o8XmboTjiSq+nWG6c^ zVdKM&NSySH*jb{_RvC6WLd}b%MAOn6M8@29=;j;fP;Y}24|ZBhIkwO<`g6Hm#?3y< z`NR6bD!Y|$JIhl!Moanx3z{rZ|J!ZBdYVQqoec(nuoU>KwtrqJ1+(0c{Eu$aoRZ)H z7;qFM=8ag*hY)f-3N@|la8tZKWkZH8F2|B@guSrULAxR&Gjm6k;N9WN-?NV!&V%eC z2*goXi+&q{4*~)J9v;5N)FxrlzW)%-M?X+Fdab3$&Tw5{WHk&|GBKf@2RWtQ^@(LQ zgp~=tq_z6-QqfPM?w>3dy03(Jf0Nqb5{aRA2LrI#n4Iic&8ZZbs9#u?@TV$^aeuPV zsr;V(`4&}-p<+aC@EFifia{CS;wS-KePiPUot1jNsy|?Zi|fH1N6j=0@Eia1!ZrOu z0?rxq$Jvg)qHrA3Kh}NF)sWfRQ_AnPHgK`|>KAf*&2m0zWJ@yS4VDMqGB z(0(ov%qShA7m#Q=Z*kz63>5p3qoRfg}i<3q6r~=d*SV#o>*MG%)5Vdvg{|vtn+V_30xD0 zqPe>{@l%}xS26DWjS;(*^{{xgMY)PPCq=K&8~h?jk9{OovHP2+!fWQ3LL884B9B=a z_FNWFLaAz!kBOTE?~EL~U1^l~;z2BV#QX3Nr&$r+qe$ZV771T}D?W+&}ho*Ckud8kPc5K_W zo2IeT*tV_4){fQKNn<;WowTv79ox3w-Rpkd-};tM+3TEj&irSNnejdLy}UnkJ@e1z zj)gbM0)P|lCM*v^VnBdPAc;a^WQME6JZjv3wmfJ*=CoHNLRCO019gEOmkp1=KJC&6 z;OW~G(5Dayd-4`rQCMuk+)Ny(;w{Y_dk#@ut;?wdo~ULJ#2#WpM2JHMdB0Oe%U?W6 zfctYl?8`0Q!UZ-M^7(nBrHVV|RbD7H8{Mz3HCqPo!`Ek^9fagF;^ai>;9W!wNIIS@v0cu4XYj1+FnS`U&VF9qBag8LUe3na4T zXwvZeFp;N#Q{Hr@9_g&2UC=%t_@XeMmbxrZ*Opn0xy9=0RCGn9b3mvt97lW@)@KxF zo_=Jm{IzPKqt%Ou{3x0RCvK>S!hGr5wgwZ?7DkAPL7j#si337DgHJu-Qh#E!O_}!Q z#fiGOKgw5FcF<#i2`h@?tcV_WOt+VR2%dQw3cyAIpa)9L8^Vw==p{cQNJmFy?dnNV zUT-L|%2~K)KxRN%V!}cwZRL!Ch1?1|o7r_5uYfJ1-5fUUDZ>yL$X*;ae}y%OBNC=Z z(4><((t_iDP}^ce`O9n$?F5EGFW0WRE1sg&ZeyjqTfyNcpb|^jZj)@MUOv{a)P|Gw z6wjfim4NrvVD76@cj1Z~4L$4PW0Xhi@%MzX11NI)E3DxCkfYA)eyj-=7c$Ueq~Q#< z5)QkBoHqN!JT?#?k2y!5ZDx^>Td%5q|3u{#S+FKdN#eybPBcuE-b5sv*4HLj?Wu=J zlg&MXyt7?bL_kb@{}vmIf=YSWgz$CxO2v9G7CYJd8mS~L*UEJ&1!4Fnvy2l zk(1b0c^A!LJ%AQdcRJb7H`aQ)I)OzTiU=pS{xrlHQG*Dz`owu^);1M)s(rS9uOZbL zV2-xH0NZgI($vfeiv))5=qr_JV+~~<79K9pQ`s;k^yZbnbVUn^TuXlIGM52aD~nR( zu~r2Cyjp4CFl3|h)0NzQSOkW%cZae4qwptnD3d`#c0Cx`tgNHT+z!{VF45AmOv-G# z4qFNx-vVNpvc}}-O2fAtK**Nmtd|jBaJVH2#gMgtxBpJzHHVR@Dx4a_hX5N`6@k{Yr4P*aKb)Coxh5$4~_)&Zj@grY~ zJQdk^9}Nd(8ftoaWhH}|z({XpFZlHApS@2yqU61AiD4FW=-oo{q5>5-wCz)`02 zrSi+J5qWIz1^p?-4L9_^V4{=vdjg@&gl`e*L}nWPQ0I|j>EQ*kGe%=rBAiL-{-DvI zj-~0Q;$6vpG9NgmC_PR{kb~Yvxb13HOBzWTzd!NfN&Mf%amo!4WnIyh6O)>Os;2Zo zPaR&uk=8VGktYiVK#yptg#KlmjFio+I=RJ1Vt}G|#xgX6WDf~PD6RHW|ES8kXuSvh z?~^hp$s$mAy-f}eblQQSm8j8@m4!JHf?HyISwUkW;fPm%SPlAe?PjhB*oC;Vd9K>` z!JL^!>f5{b9(NpC&FFT#v5dFXjn;OVA@DJ#0ir1=U2+j3FBG{dN^@&(9LWtIl)E30cA8f&U)R$cp+m%A6vr%-Hz9f~#$=P*>14SH&0~jNahL_T$D< zKyC?mav61Sb}V5r`4Mn-G|?bm7&ExKz|8u8r^?O84b}@tfgtY{VakGwhK0qZqT{xP zs0)1idJgFiLogZJv*4SS0Xa7Yen;C#=H*J|p=XN2psFl{{3nI37@S3Tm;|NYPdgNg zVPNi0TKcb-7E;Zs?^OE;bE@4PxCr7Bl@EVibcLGi%oXQ9*KV~v_nsI)55Xv%O~A)ku*{)+;OF4+XNZSwyv zqeW*h{0K{kL@^~CXV$$Ml{IjYtGMUrwlT|Z=f=sYGG$6y2VT(a4?Oj7-_oF`dm*@} z`0v>Vz}e06MC689T(+2Y!Gs~Q_;!G+MMLmPaGK5D0G3n@C_E8QnpPx^U+{|LkK`^} zZiC>TnY&WKSmgAw)mGmDNb37_fyiEN)G}Ul)@P_&!oeYiT9j53jAUZo_6k}MqlByj zy-3|?y(wSmO*x`w!?e?F4J|3B^L#u)HHjcw$x#&jM6Kl*uIhB`W_fDlhZ!>SptvFe zcM3bqc7>Bwaw=@}8kobW`oE#WL0Zv0Y$?h7=Ls?(8{#41gm?~!(prXlDJIN~M-_UC z7}1}H-%2S2X%k0?4vv+}T5F~fGGVDBGGO~ui6kSz2u|vOE;ot?!Uw%}2f|EgAOxTa zON&4RE)M|8Na$&CE0z5Fsf)?S z8pY^O7dNz{D%tvCev_9@i>4(E2ZVpR>n!ZIYo)1z6y%ZqsXdI{6Q;e4(D2^f7jjq4 z?+`{2Z1pbx7YUqlleHaccqg`m3~SJ2r>{nIP?O$bxMZ0ziMDv+UvV5p9_cM(>_oTC z?4Dib*~kd?vxvt71RdxW&h>YYWavH_~NEQ@71D)81;@quyPW z-)r)Xo!iQNFQOObx}{@G&XR^NINh_o9h$%HOS}w)EjTe0Qe!;qGQhc#08xR#V4f5{ z9uD7 zP9RaFnuIb9mJZgchvUEhN%h4(Eb85l@rIUmQ@FZHBI10L*!BLKcfRIbP z$#a4X2%ni^6$VzYMSyc5Blj(UI&5)-^rns2btc!4-H$kJR@UJH+aygA87&AxPcDhE z3f8>%zv}6)NlYsK{8WNt#J(PR&`=iN0TXp^fx(;~e>wR&1A5%1vQ1NJ6bKVT#g;m~ z7MpE~SKgjYC}e*7$}1u{g6IA5Vzzk2ZNtb>x?=Mr$cMyEx?cJdHNx(!1A0gQjC~6% zF-;$LmL?7bkxVfItTHiPPGj7Q^}Gq#Ok972i3UE*$iuHk*ffcKm|2~CiSyK}J;8*Z zOqz5?v~U)RZ3vtJuM?CHOq^a6?V`}Ma2DiZh*GLSJfL8O{bwi*v5@{nHDI#6LG=rN zPp>5mzvXQ&dUVN>F3-*ovb0hQ>l;{@-`_uZB)$5=IDzT!CA-F1{5?2TZKaKZLIaxy zbc?ToA?t%7Yq7<17v&m1cfH!Xo^twFzoML8E-iV)Jo4Ng025Qjs#P~|j?M89!&$sq z9EI0K;bqV30w58;J`K#^*pOz~Q(ul)?xA+txR>7j%0xT{lByeL7(v#f@T@sBzl-yA z9)DSVNMc_6)-$Ek-hNirUB#@|^mnr3CaP%bB@y8oE6FfGDGHL)NJJ(5L&akyElcrz zpI(Xog6_e?v)DuR2WU9$f6?nCKT1d=q?wcfS=^}am#cbORbH-95ufiCdE~SRjX(Ec=#{d=59%9JB zNx;bRj0=aiw~b*z1g3XYOUqJwM+fcMrelF%CxO=-1c-mx6@B-0os;O;ec(F-QRb#O zANxKR%^p0{O6d<#os&~EdE^Uw0}9WFt>JE?)QZ7%{*a~0LzU`{ZMFNS&Yf$y<+EcP zw9#p&5uPqm#0i|*ehEuN3KBjH*2;?0oQ6q)+B(xciFJC0{qRovLL1H`$4>Sps> zi`AQD3qB4GGRDv^$GX|>&sm#hxOy&4D+qze#45Fa+rg(rj-~%M!V@#L3@l)Tx;M^-3`jS z7gxWqr@&0d%X!3IveK7(0kZcnmH|Z$?a?ZR+4axubVBB6cOmAQYXLmvAN;gbIa>vK zk7oDTc}I=r;-oZ{S7u(x8C9Fgv1qXJJk@P-dpu6Zr955F?caF|XRNsXmJ?8t;yy0P z32FOhY#?&Ib1cmy3mls#TmL}a8IBHeA~xp9_FR)K!i2F8Q7ujx`^98Xb86N&@l4C; zQ~!4GqHvhmT;fb^z?qa%uW~F6M-j>9bwGqtQ+1->V_|RSIo>}6)%sbt61(ocbv^O0 zd&zG$gmtOgC>-V+%vq&^+jC6Nv4@vv~|@xfKECnGz!sXJ*gHqr0Zc?)A-MUaaAk$~9|1 z`XX`M(E){dyA1yd&o=(+7q>Pr8qKzS7!g`oPaM(1PtdG z^>kz0>2SkadJ0u2f?VMWmqH11QW<$SB)RKkNIP7q5 z-TKg29;^OaAnG!kQz87_jDX9b{7{!=U9edd9<}i9`eXn zp`3uR*Rvq5t`UvSTbc$&manInM~pK(HLQu0nSTH*1-Vl5y_gIe;QMuIu_*l;DE-&} z%V03Ua!lggx8fDrAm_!p{o7 zclMQ`BzdOfT6S22OCq`uCGU6Jw?9ea(Omg)!R4^3!I0wmIZFM?jicg)?aoI|=wB|D zr+$k&j8ck)7e~M=7zvz2ci2t&88$Ene0uF4uTE}vb&t5q%WTwfvfAl8cQ;MyT4}z& zO|5pee7e@#P5+($?M`o`@^?@d*mMYa^S#8_&bKT~=Z;zsEX8#;v?fa#otJZN5`S$T z4k_3c8ufRT_>3H;`iYwyLwsE#ICZ@~7(`ZF!?~zBf}QxI6hUi{5ELhNk{l?_j=;>a zH$Ql>&UrK8u!5NTN=vxbu^RSpUUwapytv4DxG=pI+T7D)gBx(Ad6t>$)3O3>8v<1> zdX1xwBOQ~^;)vXg@C3!lG3`R9Sb3WoO8<8$Q>_zL^^_ z;5zdW8-^Lm%B>r^?Am-7uBc-7oY#4{Y?iTXQI~|N);O-4t(waY0N#GM>Kpy4tsCIpAu&F#jmc#wDxe{478HsxZ+Uj-Vz z1FE&!{_f+0_0tMHOLu^{wR2F%Wuf0w-)DH&p}=J`k4qye5P!!4%&H8*YT3%Lw}2cF z)^V9A-p9NMB+vWv%}#(K#L9P46%VzLN6weRtspx57fE{ZJz1n9g;)0|QMv#T9Tjnq zTy5U{YegKiiYPFFxLZLx3d?N)n>mc8yIiXhN($;WfZ)S z6d-8yXH>wq>tc$KK;+T)c||N8p$>iWVaQVVpC`H*o{u|em%pn&PkUOP*2>m-T?%<&10?sw7&ymw?Or_{sfo!u-67x{oRG^O)6**5NPC)~c ze>Eycy%&uc3>hL^Z_wFQ7ZJ4}9s2#_KY<5|dXb#L+H@*5%+cZZzu%x6gdT1c-l13J zP&K)X+laa`j#hzjv=SBO=_MywnW{tOoQTafA;SIW%LH%pm1{PIeO%cJBV85C{gfp9 z`1{`cR&l>r{jzE$#?hB474B}gkQmwIJ`!+Gp7og8lAhfm>a11YD(^z(C&1jf!I~sD4YaelH5T-p@RX^zlw=h9SOBr{=ho zVST`H$B&MHnZ@pF0^6Psd5bjtstI!3w%LItFD3%K)m;XtX|@Ahr@3<|PP9ekgrhTC z?7vhY@$DQXYyg-X^hoo(KeTvK-=YJF^OBo~nZ8R9!8a;LW{x}S_Sd2)!4erxzZ9>L zEIT}$eQkbU-E4jjc*bpZobWxp&^M!00fd{WtE71Ke_3cb%)qVMO>J3y7HysKyH#Iw zTM-}d$4mUfe6v%1M!y$`d3D_86Y$PSHRVPs2!He4YV(ireJKh%mS17Of7b&jV+sWu z)dq);jiRiJtCJuF$81nQe;}FYl(10n+<(ZjfyA#4e*cBXI`VIN$Oc`vlmtw{ihEsm z466C?-*whZd#_P+hvoX)MeW>Ck1-QtHP`og2|j0|4&=w`I`d24-0JQZ zo72`ChK6sajr2u0T0hH^v@)bGDkUyix1XNMnks{ToRUok6_Zp8^3(++j7~58=dvwg zAw#XC*o$V62o&{g66JBM+e>JMZHeoDUx3xw4kiMFfni3 z_@MXfP}p=F^a&3_vToLd{0YL7vmTb4#6sA~>`Tr(NoO)pK#bIx;mQ+OJzwtowBhS^ z>bVzcSOAiI<}e#Hj`Etn2vI=CD6dhV8LJsu#2$~$YHhL;d$jeYc7Gn)ZOe0IRvS=L zSE?ob1)WgEK26E)OnYN;fheDyaI@i%_75-MgU}7-YJ*d7jQ=~QZu^xU ze&F~FIjK5vX^DK`{9ibu;3G+`K3Xu->xs+8TL<6hCPUBsl_2PPf&}wE?yh`V2qGw= z?~i{lrdzf-x~x-nkhZ3GWH)xgOhKzs2xupT{we7U$ghKe@q!#%H&G$*k!Dn+2tv8N z1hH|(M;9;D_#%X=2tiYUYU;iIa2Rpw!>vU>=VU7&IjoMMjV=SjyX{v=KWfhX4y;d? zyGK%)^vrLY&T2I^3=36WUL`Bt%Rck&8<4I#qwQz*HG#m#x1THOKq#+C{(JQpD}ySA ztMb^3Y2^3D5w*I%@)ZI#x_Jwo89$Un{>!+1odh2YSP9MH5UEOrkElf2DabD@Jtd1~ zfWID2Q_I6jln8rE5DP!IKK2uumxxF8JLG$4oAQg*dmS)*6ZaX@{ZS{&(zZM)@Tlik zsB5Or>xDF(uWm$326?>#&cQ9|wiJ>W3U@IZIQ>L+FRbN12EZPK!F!?N;p z0)gBaIXBXeJQ|5gRZQg%JH3?@h&gL?T_(dysZ0Y(SXolR?o2(X@oJVZ4@8C``h*R} ztJqP9#48{b0#szxX$de2V($hsYACboF#vRuW?#?rt>@D4RzEtso_gOO#)Uqr-HtrR zHVR?wb0)Db=Mh~d0wJ(dXZwGwQqHct*kbcFUY0R`RBzTt`@hiG_DHez$>PXrTn&^S z;X~kRHVVbomwuVbL3Yzlq?>h6uKMLFbB&o?X^H*^JuIAbTo_tN=?4#~fa@~*G+6D4 zWf3J}I5Y~JmDS9TJ!bvLnBFhyeu{l81@d0&Rh3r9XpMfuFre1s^W%lk;)mS|zcB5aq9`_XGYKC)$@+JC-DwU%*SV``oJT;W)?oRGP8qMmSnVkAgZ z%izKwmZK;_qe=ROQh6ISz2GT&ad&Lw%Z9>*?_xhU& zYud_Mo}TCSw(h0V`wU0JJMuNP>tUgkI(~~_|9Xy_%-NNz1Xb#0yOo_R5&x$?(pZ8s z;!DqPX5HrTM^m!NMEDv;2tFQ&TaYt$nCTURi=6a3CfCj8vaMIa=oN(?o zt>Oyix%* z+LeZGzA39N>#VX7qU!}W>!hf~ka{YO3MrO%yXfXPStMz_A+n^9-iVw3bO8lbJCm$W zQeV9hDHdIer@>)g;ve|=pCRY0fFT@wS1hg{)`sTvS2v2@&>#DbJU>rn*1WkU5f~F~i0l>+&GiP1DUES&% z8b5hHk2c-{h1<~ap2QRyDoa-rH{Y4UT`HHc)*W{NIr?X={|bIv3%g+K%i`*A)R{CQ zIYse32{C3CpZErQt5lTm#AZe;e^ldJ-qkAqMkIzyYK@`VH0<_C+No)D5DEo^6TiRN zFM2#fFH*-7pEmqBFPX>9G`gbP=*lGw?2F z)~?^P10%?x2ZRaDpU18EdHAWz(*6*fEC4_FdsH4`nZS(kTc|hG8_stB&H6}^mD0{s z!+-F9rX+}RWf`Xx)$`<(mfWBoVIQn6AZHAy0?^tp1y2ZmK4b`#3P3ha#J z2V2&lbsxieAT@8Si=&$65$%^r~4@+H3kPAA}x2eq7#tJ)ZZs5_Rx z?Zw2N;*}MI;ZgcaFf`Z;xnJamFsfV-!YV-n{3Bok;mc%`;Re%}Vz_ovh2j?DnF;i4B)(Fju_!{FEg#aYL99O&`2c1&BnqQmX@YH~wQq*t&>> z5nBC&@q`U+-9yvMXmNK6YN!&F6%a)=P2A9tvB>4~P%uhNtc}^ccei@K*iSTVq8#5v zg7!JVq7c;y_&h8t`rlx_#-^(H>b|;dZ#++W0M#}1i!o_8O#gLOUe0XcTlP-fX>mAG zI)>90Uj6=CuuVy-h=csNaSu?)_AG5W5$J0x?xHSY zRwe6eH83JTjr<9US1nj!@pxOo2zD4k>BBcUY%o$#vni_abY69(*X7BSt4wb7b35b6*+<%_K+OJPIER9`x@m7dt;kbL)RNHy0*8*%>ITocf zUG*e6y_eoJ{k*Y%ZMFlip9@er=|tYa`GjEx+PC`0Ak5H82@cvvuVV)2O1TjMx=nZa z@>%951^|LO+oO2Pg5Q+y?3g|xgt7MZmH}^Ks}Czvz+dWJoR%LLrz+1V^uyIVjD{z` zeQ<)<$kINWLUDeQMNHu5vW4!$rT^yQ=^bgu9!18*s7Vnn=2vfc!~Gd6Yc$1rB3&`E zTy1mkT4SLvu|0Ng>Ru)vBcM7ph(AC_A@gyx4wKn|M^}$1_dfbwoGZa&$iK}4Rxfq@ z`8}Z-bGrB0=(XwXo}Reyb+!gn9DN_t!uYd+2!;XxW%BHsYqwK&zko zqKlG6H0Jfp*ub~=+ag>h41<#GD+bb>T~qWyiew+GuXGztetY&Pl2MeDvsgK$W^9)_ zhDavtF@JvvsX^(wplFg(lfZCY|I2E7pF#WQ>BCOxk2!9B3w=shdl3g#30R$6-ZMj= z19#W9alwi-BWCRdo&y~`vMVED*8Xtw9Y?E6W8Hh(o*!wZI^LlQd0Jg^QOj!~%u;hU z9`>>xkxWXxOP?GEs+(hve5y{Kzn%&r#_H#B4F;7Z#b88mbJA|Y#KTm`cVe=C6sl_^ zPty>>_Bo)c5mTa>11XW67QCWqd>pb)Y$Lp%KYnN5%iM9&Mv0Wv7GMJoS&}o+n0eqh_QJ+& zT1E}Hg%AjJ!+$wiFAuwt)99X zhD<3pRWVLwSQI2Igh1m(8tu}|1~s+ExO?|iQImmFVYNZP?`qH2)$y8+LA&Ay8%Jnu zMYUnnW_tUA$EMLcWqm@^LJk1ZW;s*4LeI9q`R;73_rIdUHR52KV>o-@*v%WKBqg@%jR9LZI zO#hyUTTw;zUq=yq!ahw8h-IEX?cK@wp`G%jPnrV33ePlBf;?Ih>IFsi!^SvNmy>Au zql)!DWlmEVRuPA{6hP=kDKuq8u3kKh0{$IS8 zL_`^5wLf1qpEH<1#C7XQ6UIvF*?k~$O9TK01__ZKGLYjiUfCI$?*2+^_ zHag($3iXWfal_&B`tw8a;liV5)&G_&U`{cE+xxD}e!YDGG~dc$1vCn53#{KfP2U1E zc`#i-mNqDk4L;5>M46CubMMg4e}|HE0b96l9fAP#<~0lt(bih)lmM5|mjZqjxi6SF zPW}1CRq+P6H>xQU$Nyn9(&9UVqoQAsOK#$$wlQ{7;+2 zWiNGWFMFw0|r9>1%u&p(+DcwzJqP(Sa|s2HamTF({yBk)_5~Ig` zz!B2G#iD;sV2~c!{x63!5=iBv=Sc>=CcbRdA_7e>#&>l1dH_ag91}8z*Da zCWe!sIvB~3G;EjFx$s&?3}y~qq31f8^6oBqKO>#oGL6Sk!!hq?VF}@blXDPxyaC!A zTM$y5V>I_~j!gVO`V_Vp(HgI=+P0PoPFf=FswA}Lm2TuLyD72FhCs^}?fu`h_JOe% zC&|`Atbg%HU566`+r#gR;lP*6zgbiR$)cNi0!`o$VKY)Rk~tap-v9K8H9v`wHl}cG zTDkurXz+5O>T(OAJTyL`Zq+wjCmgJ)==YI&V&Gl|Fn&dW$+sTmN_@A*>O{;73^E^D zV)fI+oCat!%{Bym6T?1NK|Wt~C=>!(vHI?d5PBYX+0J-(Lc4fZOB(iTbpuSIJF79; zHSymqpP^*f6EVec8}z}ljqO_yaPnW+x(tVi`YGLgVSo zIZATNJ>g?O{2ly6>#jBChP!g#^C|@F zY#FUEJ{BdM^Zzc!EO3G@9Gp6MEI8O?Qb+^nqKK|fRe(24>$&6kPe*0!fn_>GBosl< z0l)iM7T}PyJAaWI+cT)D;>Q+1WfRtpm#Y$3=!1zLdU>^fyjcIy)w_XoHUnVM$BtMj zP8tFu1|_Qt=f;+F_}YQ^2MUN*TLx&aU!e2yD7qo7o|Yv))*K$YJ9^3{$Q;la81n*I zJ>4|nCXJd&nBo{nH2K#&`LS+Wb0k9UD>8GH1Slmzg5(RViDUBT#~5gk3M_NJFBmGh z9J##sb4)_I3SLT4-SVHN)9CEx#_1<J3V^+ z5?h~zLCg|g&u>G_OEVD$V*B_!R%;xD%(8@Tt#zr)T>_bSc>Cu#Q%naSr%(a;qwPlO z26O$8PrWrK0_pD+V!s5H)p^I%mWiBmQ(N!eW?7fpPdDtkmh`Nf{i{hEX!a!iOoou@ zhY|RoxR%QZlsf!D89y~ght?gES@DmF{|ONh6f%eSl$$qM7I^Y-N3ow2j;8F<@%&Q3 zFyp$p@IzSjtw@z&9GJ$v;|Cpyxru285yE_3tCPg;YKG`sn;y0I0UsnFB0@zsZ$Xp(tn$Q_M85`B83Wc_U|8Id@R)C9EFzG zlk8HKY?GT;SIDa1KUQ8cyQb6pLA$e;9Tn}LY+X3vEag9)Iyd&{QgBx$bToF49#=2I zr7L<-xdKfp%{tVE^5QI|N1_5{voaucr&k+I8Uc=qwb>#$G{$f8O8OEe@OWhEz9(zg zGJwm{AP5dof3?@u^fX(e%={8H$V=!_cu1`&g{;|+_Y6E!7Il>}jCwdxiIHVvlU`aga^wUo&aQ9&EOlJOD7=Wq;P)VF?E9E^7|$-|A28W`Ir2H>D1Z&9<9G z@?2BjGBV2e1(ZN6a!qABxRARjIbq?9#CurOYmBYF#lMIQl!H4bieFApN|an4#`Fm1 z|9eW|3xlosvPCm+qn{0ifcJ0A8KPX$VR22Z&N{eY}j1B$O1L<3DbHHns z#`6Vb^W6q}%9#yO+Dqc05J1 zQ=&e+lpTeCEX+5a0h?CR;Mul^#3c9#=BWqmZs8h&l>6qj%(aL+5?LG z(jduyw)P$LyxzEFu6|f9hxwQ0TVj>fM|!O z-v!jsU~0MDd^FH?41Tbg-hg7chh}fxdlav%GQxCK?$#{sv|#}<-^O`vD?)MP*~LbQ zo$o~FVPX^fcE27mJVG5&d)y{nY4*8jNz3sE!sPnTP6^Vo{^B-{x^0bXEU_8NDNLIpdEoweJb6Y8wV?Q%D0J%a`jc1K}HYbUz^1UtIt1{99D;;SF0R0 z=XCb#M&qy)77^;r=nmLhOoZ7g6@C5s6T!hC(g5zvD@q-GiSLkoVw~e&?0}e-7YmxJ z(4a9^z&y=7hfBS(Z|640t8`zjuT9YT^XmUs{!N9n#_Ndfb7t&^ugM{Tr%K)3cdGE@ zK~%x`74q{cBEp%7HzHnhoBFj5ZO{Zfyh#*-<9?FKZ;C5FrITENR|Dl}(K3opK02(Q zbbRXS93$%LbY{XjE==fsSLpt=^Kzq6Qp{Fdme$vUa3-3bSw%xR2ppH7Q^5$5h^EVv z>3Dm-wi9^AG@loYOf};P3OOwaVHNH?3{$^}^HPMvHG9ciN$h zR(($U+s8HyJor7XHs40){x%(gsa8LZZd%#;h2lP;5c?%NRl+J*jNZtlu?FcU#8x1# z#^Ub+!1Yv?dY}lsz2tr9QH0!Q+%ed@-b*A*DS1fAC`6v5xUK#zA5s`B{?8bFzG1!RrU>EE z^SvVf6M%S{9#dZcJIj!;E_7WW2*Ql{fSrgoPuWwSu_lW#bA8S<(_@Yv^@O$)rdwi*=@-(L3a$T>4B*Io zVL7h_#QHRyNsdv?!QD);WXRsN!M0||Cs^bxW}5v8>OY@N)*y8>ny_%#z{&EFIOg?O zRkK5pqT(wYlSN>EDkRrNLaMbQF;-EIK9`57g_q*m&z~;1t%zX8@;a3wbM#UsAE0;r zay{7x*l-E_Ug>rmB7V3QdO>Yx@3>@qd@0AY+Zy!fRQ3zqefqYT*l0b+-k$QEeLlk6 z#yVt@On>OSNY4s$lV3lj=xtD*Ch9GVhi#QR{$utXQqjqlzL>ny7mF^zk>QV|^5}Mg z`S3T*=Ees`zZK;utRin{f?7Jmp?}QeZ49iPsp39|_>69UnBhE+f=H)h*siy^41N zoYT#h>9#Z3iVo_CqZ_rmwl)qhTP3)J4|@=paI5-WFm}qA&wF`2-WcqrT%*q1ChD zeAky7Vl{_3^CEzbG}b`AA{Z!so(5tptMnblHeW1GJ5P`;Dm9LxGnJ5qi5PZa=!+~* z`86A9+5}kqTY}PURlKpaCguOjRyd|Q_kI(BLN*fC-(g@_;S57cRFki>`9tWYLNSz_{G71p(FWdo%J6Ym`Ebrg0y_1;0(Y zOo72t-Yi?+hXpGJ!ckrShO z=SigR5r&%qmuXF|JNnYvp~1d0Q1URv`<~wds3H>#@+R%M*Z1C!8SNo>aOFf>oh4*O z{<+v_$m>VN;U_ESoTA*}L^d9Oy?$=;WK`nVG=EMoS4`#;qVMhL z!=2%0%)~iy({naubDc-dy_B%De_JWnJb`)%4k#f0dEw}bCk#1CX{(2Bl?^niEQz0} ze>ge)nDpzYYPV{dSklZv-0+Id4rq!6*Ue`Y?5ejpn$si|)t1ilEzT-ZuV4&n>e;x zGR0Fz4+K%!7JNuZfWbsIFfQn0CN~-Y_kg0R;mv9NI*@CDd5ie)VNXO`$Do zX0o+iqc4lq(i+IT-V@A{jXb3mL^gAuqOG?JsQ$NSzb=zD-4y;$R^XuY_d`r?xxh8a zz_i7yMi4>RNhl;-7=SysoOM>60LHW7mVfDu;hAl0A@oeSNK(gvz~lT0#g$n3xRsp4 z+~(`-DXq=5AE(yxv?^d6A$r9;$+nBil+0o{x6Zwt!f|~x#vZvB$kIgrrc4Eh^^6I4Epvh6IKja z4@BPf!qk)Hb%y7}2Y_TQ7i<*yj%fi4lwU8$1s}_2lVc2{(*p$Ej~vLmU%eVO?603UYZ1cSNujxuO{)p+VK!}-Pwv9e z54069`mT#S6PTjHR>z1B-@Ch7HxLr9Qbvacv!k!p#Mq;hO{b@tGIj4Ezr1u$rvB;~ zJYdqbU_M>Utk%o#f`;O}Vkde$wjaMjaBAWrI0j<;(S@1PnQJoE>IN6A~dcxry!)25ZCW4C6 z62-muj5KT`GRqjXyH$$j=}M3k2I%KLQiJlQQs8N1tq~lVgL-_ytIeqo)BRQGE%<%K(C=@fW~bkUP{87b+phfG z_tW^MLf)Vpw=Lfp%Gj;`(oz|-f?NJiWpDKM8{PN?(s~k=c=;+&$fy>&Boe`=?I)63 zM*ERN=RmQ~*pXTBad3BV>TJ8;S-xZbl13QEo7Lwmu(wUKdmlMktTOZ|k>RY+sI1_l zKQzG9Q~Lk-ddr}?wryJ&Sg>$+cMWdACAb79NN@=dB)B^ScXtmSAh^3j@Zc`N-3jt0 z``r80S7+zFnzQ%;wOCWe=)JWrtq-LX)=D#X_laNpms)v9} zOF2UYii#XGdS{_~ym(ZlOB(`^7bS^5S9LGG?X9TShs*13Z>(1_GC%(~fjZP}8Xjx9 z!m!l!Xx9q@I#mhOSo2Xxn&%X?_7T7GbOwC_D-~xI!ok&#ezM+GSZdh8=ckC-DDL+2 zYWePbM}4?&K0WrEc(!PVf$yEJ!Dtl_OY&xi&53YO{-s3CY!DH*B@CM2^C)NX(h;IND)7l-4@><`Yk| zS#l)NvMDxXMdmSfLuU_0bW>E!4%(`KZh};OUPh5mvr+_RvcQ~Z+D(hf>wF~>KIaRQp3UW~o`GDYYd(`^gMt*QWy$(7?^Gsrjm6hLo#-k~|ACo3kd9gN zR%JqGVQhF?ivz|;y%a3W`-vlXU&(u7^b77U^!M$0&+X%+D`*=IzpXu7#RfkO8l_hG zhFrmy=rrM`U(osnKoA%WiD5yQcgC-FJzHp&;8a*8qFI<$`Eec~k8|ye$T8#;*}SIf z)Hy&YX0 zCn75l;u?W&Pj0%!puli;{mi~pIn*G%Z=vxC*Zhrw{_;RA??#s3!y>c3XjKH#!Vhmh zRG{|A#-r>bM~*A@=NN=<=<*@?Ot%=dzR2{}%Pz;CnqY8{rGoxk_vt}Jdy&*)x_Ep{ zHlOxJ7QQiK9&F61*L$aThWVcdIq`F5Bvxi7`i)?;U zCthmbCflh03`0GDdMc*tox3%qyX)d=fA6hk8E_k3`3IUif<(~Bcp&Ov`AXEX4CPNd zQro*~k8R#1F9S!V#_=jff_WuOH9n@Va6-vEy35`IZp_mfoLnU&7oN2P{+(guxx2w! zlT~Wp3gN$-o_HR{s0i*ZW6w4`5*?aUtNvkvB5zE#6GTL_P1tp&U;Q4pVDT>R_dh(A z9kwtVG|Ghi6H=y-Mk`h7zVP5922JewXn>vDzefZ)8^2z-uvi6o*MYpWyQQzO>5?MgFs@6C@G@ zSglT+(%0ACZK{XC@3Fd1j5tLp-b#G`lwdhU#}|)0eArFdY-ab0Lf|^f0~6DS?r4@I z%#r4-I}2^Xc6|4FsJ%dUdLZhgM))~ExQdXaV=C%s)%qjp{f`Ad&@8p#8nx)^_hjg? zQuFEf8OjOJFJy~p4j(4vv;jc$V5G+=E_cO!(3ok8=7w3{6lL@SO5ormsrLrKk1f^V zfDH2JPRrd!nXkr_i)eDQpe=+q!-wc`i{w=HIUc1L9Skgic`R@g@Qygdel0!lpdnBD7H;mJp zk6O|7Gq_}TPap^wR2T)jJ7%^Syrg6I1WxvFsk>3DNKA+(ND=f8<8Ad3}+bQbU&+dkG+e zH`im$d{GJ@dC-j5)^j&cIQ8q`G+l;hS86EMN_m4(^}b(hNue&xw_AURH|$CIz@WM7 zc^ta*MvKw+BZ8~?#j-wFtwg*Agv^LrAejWI;5Z7`xaU`qnqQR{V?1pvY_Cbq0foVt zSy*Bk2$dELi@G?d?Ds%oE!|of9;Ih${mF zncAf?m8AzpqiZs5EWhTN9hs<5luZ(Stfua6w))i5C~dtkt+i0d%D~rMpQL-$wJK0b zMP7=pT5R^6wWB=Gm%h~f0(u*drRuerK4Vl!%s8w$bnhS3HkEHfyX^%^7X&%IHwnl(7ixo=rRC=$f-|T$R zd|Ka0)^;ng(GbE)For#WJl0?>Ri)LYqOxQ_<$L@LLf$7K7%o>7=*!F#GQ#iv%;k>E z6|7!&O`911c%3x@3BIS;t-b*$J@QwqtS+M!QwNB8t1j?`X zghM#UV|)J~4b}i65pHr0NL#T@@|8HDlx@QEgxQ!Oot6-_!Dsl4sD9jjo1qE?`ZVV3 zL~fd<*ci%4sEYBP#77)1>Bn0`lxx&u+U1_PEE`yKQG~I4d|J4G8Nw zCLJt4^))ZpP>sKF`yV9|ktl_H6?<>*n!zjL^{GOh`InB)_CNYe+Pr8NG+NBmO#zJ3 zr@8Lbl>;*2c2QPFfk9HL3Pn{G%a#K9Y?pasC~SZt+;yFYhcjLh>lWhs>S>YpF zFp9&$Fn^uwKKbyz6FDZ#eB_{*cX^sDIwT8A-mx3tp;U@)x$eOTc}z?-twmtORT-~q_es@(kaiLldS_tb%A z5Vfl~O?}TMBKf0vy#J6lj{As)CEc()&8E!z-7@1zG$;2y6c>)n4HbpjbZ!R9;N}^# z^9EgkQ?NAJMCTgvZZ|3B)GEtJ5~N$yx=AR^<7rG0r~XdAsX|73X>JfuPw-FHr-sNj z_04^X$;Zzl)EVAW@+nkVKDw&TX{4$s7(YHt_nW1$KuGbMl&pII(Bs>E+z#6QV0~@5 zXvt^97^pVPrs6&vi`1ZlLR4w7s}=6azHo^t-9*jCJy5d6P~bx@{N%3IFF8R??wA43 zC4ZeFLANB;2sm3??VqroA%w{S{fTbt@c;M)1Hda3h>{w6w*1boI%h7mD`6Y?k%L32%ms!ujJD8q(#|+lg~rP{KIYA zoYhZvcsxI({ zBD*|I@0MSGYr8prx%a7Q&~rsyDv;qVnEAgXvX~UbFeF-UCfTNBYp^#OdMF{povq${MvD2qhh@6;~g9@{sfP^^P z$*6AE2+;F%Yr3suQiv}nc1_%QgT#{Ll$-0BzJEALZ0m9k~0eulT znx!kpOvabjVj-Y|5Dqqu3Ml#jQ_KW*wqvM;Ok>Sx z%+!MXlA8Hsf#rWgEFJ^{fiWUWdg+;r)qUsi& zCKWCbT?;d3qOm&PZa;Sqqpi0D8V+TnyR5wOxQJ3B9scK6iqO?7`}EC{FAZ(sp2`PT^9j$zAwq*)Ql(s4``g8k3Xfz)sKE|{WM6DKi$UN?x>?8WZ+Q(Qr zCqfKKGT&dGrBA@11QwpCEFW%p@3^{2P3|;_ln$(;;=tfRqKI&CSJ1w(47BsaH$U59 zydr}{z6yHd8t56crt{|+FYU|~$EZ082vZzG-8drf7AcQLWHt!s-#-Wrb^FT%QZu7) zP6$^fvi?uQ!u}4#)M#H!sf70i8vp2*K`C6(tf1#qI!`?{tfyG4Y=x`MF>KlDH{G&| zNv1=2BFWDbkc0dbyoVoZ83w(@nU&iPX3`p%9`?j^r1Z(YeWwb2@^3-&(qt(}4fMX# zP_EmZ`OMO3mi;E&4YEl;9#?rQ2>TzAM1u!jGZ@Az0Qyjua)F)(?# zNX@K~8kv~Y`-kDW4p5=9(sCc;cG2899%;YojjAVc` z->XO8H&x#^+p{P-Fro(~A!R>b6&-(h{{1ED4Z_4(eM8$%=H@*LkgMiTBFUpvYmm|&iDn_QrR-w)iYnvb{F^9518ty8*NjK`ZNW5 zly-f1yndp4vy4hoe*>sWRPZg+b1XZ7Y6yI8Tt|V@}Az`v~Vh&l%3b)59pH zlmd;l4*I4R{0=%eKc#u^%t<>DTHY6mfvKN_0UzjJ6QEc7y4#mN@m}USFCzbal6=Ho zIP$v;@4BI>5-}3A-d_TfwbDEdXe!d2ro1uQ)W)B5mjgg>pTnHpPzHsq>3_fML4Nq) zdNOgU1=F_n@QcYEzhO3R83aK#j&A#&hB4U|^1JwM%Qhth+Bn>^?HZHzyGf`CrJ2RO zPzHtv^tLW`itVCmBBi}gm9Tx5d;@JXj+sLN)EFy#dI|NA{N_uCDjCKbI$XuhZ$L$VW3~Of^qlU}ulL?jPi5HwU>% z;cxS-`}@?XfeGd6Kl>2el=wMEOw)@?r*7xJy~;(`aBdT#yB}B{5*WY`WrXtz1$PD? zeE+rM0h#^=Su6dMlzZWW1fi^l?D_V8&?ksUdW*1)d%rBg#sr=cE4qB0&ylQIBo(hA zfifzibnY7)ksK|!;1ETc2Fa4OMye+!Nk#4V)o1#{M%^2Z(}uF^i?!+l0j8q8>gOmM z!hVc*_6Iu<$c(}NnX2vLbL(=VyPNFU1xZxJyNyAd%dan$I-bctcl$*X7@lpo(aDb3 z2@4F3_w@gUeFs4jBc;i^9%HN%9C6V*HE!{dbHcPeX~P2J`tm%I@VFi51^n}}!~EyO zSaJS~uG?2#n%?dCcCVYMxsDC}2NNU}js7h|@nXgw?Hki#?=d0wbucd==%fj?egfSr5r_OL!h>jT zl4fpFxc@VcdAF+1(LRPX>YGUJ;$Wc(6vG)pFWTPNsPIEau9}XW=V|X{+FRdU?*QCE zYV+=Rl3NJfvrIHxfsL$uMz^z+X84h6mIKubXxvA-1_@q)sD}m16mMk~>vao#S{__` zPYV4KME3^?frIe+goOXEb|Qyy;N2?OpBRn7f|!O$+f<=#>e@j;oxw@RL~pUISls&= zRptRM>#x!6bVJ1Zjpo98GWiN7j9vz-lm#}6Oe1&2@dBQW6L$G0(&L7&( z=eRLy4bmY;f@Qi0v6IuhX)f1S4O*FW?2J6r-)nOn&Q1RQw3A(jSlQg~KBi^!^l-*O zC!7~8;vLumc*`kRilI~}a|4dS7C@^97;0KM6CMZa%9_}6|2rKSbpnFPsY17A_Ct2V zA|yg*5CqO(56CFNtLX#~7%E2U-!PmhF8FN>MR0Q8oq3bPNI364?_Xj-nx1gS=XPSVeP!>a^>hIc3g6NvZFog+r@ z=1ko$#30ic^%qX^lC;U*V+7wDq)7TE#8on+}Nd5DTbZ02A zexIL$P?1QZFqFqMcR(tGz4d6zA4P&QL3yeqK9s%?W|-T9x+(nmOn`pCsgX{M|BUMa zg2~Ib{!xA~n0r{Fm`Wommt{`T{hydDAaOb57sFxdhEpAfrtdrf zE zAwT5sjGF~eLgPs)7(W`7=L6y7AIMC0{rndoDYywVQZF33cGo^5%k%~%1M#wQ{MzMr zLJRVVAF(#zi9{e~hX$gEYmS#1Jm7dOd|@@UVCEr2(4ti7&xm|v;8uXa+eZPUk2!5X zU3{Gc--Cd{w;Xv0WE<*2%Y(dQ`^+L3PFG6K?MNB2vdV*a!I$!=AHY!Oqb9TLA8kO7 zq8IG#(!^fXwX@5@@+!%(Z8Y64Nj!F3{EbFVY!hOl=-$-*!xT0l<+NE!b+M9Iuf-(G~61-Y2Gj8X$x1eCH6 z`H?^LBl^=aDW9PiZP4+hCg0qWUQ#0eao^Q+37%mDzdgJ+h3dbH=kn6NMQ!WXyC_|_ zML^qxAJ&SHx*=MBG*Hsw8*u$y4k{>5uV!eHu!mGtkGjD4_K*VuuRX@rZ?i0gb$>M)o8}~mZ;>w}(Tgo;KJ0R|fs!N~G_JWzpcr>lYSwuCMdj#Z-#(~ zA`$%D;&NKA+u|%!bn423p2o5O|~p<^ZJ9b6b0l&vqgd^gHeY`t7A7r4^K|8-c6NpknB<~e`t4pxDH32KjXjS;Bp+1HIF;2PV)?(2q?!VGPs)9%79HoHP4HAHGYNA!fu2m+tz3=7^>ir74+ z8}3e~ZS~DLF7cH9Rg=t$aGsY)7}W=a?-+O1e4BALwIz8d=LH`l4hZlYP#}@FjM#^* z>g0wCeZe;t20#NaMuO>qvtF4$bS)qR|3nt=O;=nj2cLjemt_cnEN`VQI3^lZp3uFN zyIU@4?I@zzym)djv4GVaTpHDaRf9>lDI%twsI&a7A)l1@gg|Nuokd?UNkIt3{bIzX zlrPO9Z}m4?^KZWNk$$Iy$iv@N8KmbW-S%4Mw(%>7`^vEAwz1B6)$x-F(`ifjC-ww$ z%0Am%`mpa4!XGc3dUN|ENT+`FuBi_35X-G^dzo%wh0jXy0 zfsvgOTn*-ty5T)xd&wzg-OD%Z+bU2sx%ouw6F#~);CT^drj}W{g}2NTIWRepse|%V zFxjZO#t-XXt(r85KPS7G(vl$w<~t(1sG-d9CV#R;(+JsWEOSJ)qz{XV zJ)4l5rd>)SYE--(j(1@=XJ1jfGEKwm8|q0sOg(b1<{VxhzU_8us`$-wZ#t*LeF6C7 z??hR2!WVEO6;0nUClfE}G%CtGiJicL#}chgqa#Dc3ZQ z`jW?qZ|Oc@X8oL(3X=L394>i}9Yv7*te&{~Yt2XPK7V%dt4&2axx<0L6;0t|?%cC} zwZF?DF~9TtZTqdD$5|JwuFLiee8%D9UVgkU^3mkk^KHl4>RHfRo{7$9V zah?2zY=2e%jt$;XL;H!Bo`VKk(7;UR{GFe=SaVQn70FkEuI#`LjilGuBNwb^Od|v$ zXNT;^LwJhbBPZ*q@+C$N!!?Gn@86ZuxoIW9ytP9I(vsv+0MD{ zzka@BRDvY~3DTfTJ*wL-cch7;oRf?*J+$ppK+?<5@Ww(L=c%(ugcQ~KaH*~qvwzeX zGJR{fBS+sioUd!xf;Gi0p6@F5Wb-ozUdkDEtmeae6$3s!;a?PihZks70p4x_dGzMw z=NQ8p8D@|jmYe+PT2XHtEja||*&yH3oqJP+cC!g0mTsLwXW=Sp+Ex4`5C2bxEN6k{ zU>c`zBvXSpFWWdI83BneKR$=tk12Xw=#{=tOOmH95c7_x-ToqB zzxI|#O7c=AkMArErmgb&<5=vge&Yc~`!SJFMukWlz>BI9dUdZ~J^Z(8Rj$ z-w7vtt|+qKR$}iS+M{6U9x|5>e}tpW=T}}exng;1UHu@_^L~4x_fXvK@k>*?{iEx! zs$yzsmOY=HPSZI3&deQAEqc;nRBZ|HQChk5(#H`QmN_}1x4#67mL3uA2t!bL{o8VYdL*6f?t`m}YjyhX=V!c~wXt<^n9Zemk1T0FA;!XC8Bca*lp4(FM zI=7)yxse`ON8V|No9;lxanfU`PiACVysNP{1OHW*H(DdQl`5p8T_ha9=T4`5PjPjh^ zbU9<<6d&aH6GCjOp<;Kv-0`pCf2k|Hnd4Wl3@Frzx>MW#=}6m>Rhp$LlO0C0D6sNa zOxvxYt)CFidcd!&S;#a%`-Vg7*~DU}ns$U`8Y4R*i*wn;ho5#>?i5B zE74=!u<~i`@%P(fU}p4XB=LgfMrm0^bvR4={9Bi8V!BF`c1A*kyze033$~zK z0m)vwe1-pwR=t*U{QFP{2j%mLTDiK;-|Fpc-(7S=GRF*f@TUuN^G}VOUj4jh*>%_U z4ca0wagcseeY?_+q(tsH(f?k4E>gVh|M7Zx2ziyBJ4sI$A&`E3R+myMoF?OiuP!Pw z^LGMq;z4C7dvNxGBGSWHZ6Y2a2`VH6JXO z9&E6Z^upqu<&S@#M0l7IXVUR<`$Q!l&hqZ2=i2lj5JA#U4ILlNv4S-dbBry@xK9!F zg$)vu^Yis6sY1_g z=N<5Ts3x^Z#UsEAWBX#R*YxM4Wkm3HIsU7z*Y&SUOae8v#Jb#E(&Pzt`A+EnK6A)@ z(aDivr@_NlUHgc@XnRK1Fwr0wB=l>?aBo{3njkQOWLIV5W|;l{x8x+I`uRMonxEXJ zKo{>y9l;`YuKnUc7<#3(-+qt_BeyTr>Xo1G{5=uut`kXJ1RTN~(wi>QPWyt`uTq9b zhgV@APY)l#oBsXDqWw-zP5qIzA->HK1mx8rR4Cm4UKU;O#foLmRxQmV`7BNHNXTkO zs~)FJ9d~^!!;?~^x_W2+xCy{;`Hu3A=LgAi-1Qpw{BpBjRmgX>_Sp=} zEmyi*Nd5OB>lDY_3(xga;LSAR+inD6j%7L?$8|dq9Ak7}eEuwr?Ip z1aE`g++_QXlDD_yvM1YNTN=kZOff~rtGpWX!$`ca2eBOY?k02UYWm+U4IQ{NL)R3P zYg?C%5I`2RI>TvJYv-tDoS8P$QANw?m-o~_!p<7oTQO*Uq_%*JUt1VV&+RXwMS zkPHlw`}!2C6Y5bYGu}s4>FuaA-qILA{rAa=4|ml!AtJHIIUQ>@+)Mg$H((xQYb zq6FuPWjZ|8n*KfyzOv#OQh(HY#%FtuS#t&Z@|6>lE)1%ZIJs>P=&>gRZ&%T_u1d++ zBZukPapb-HZC62K?xpAYxu1Ov{rIJ=F2m)-ZD+oc=;N5c%e)T962j=%;rV8_^N$$b@frSG`^ z`DJ(`m{c$29rUiHjmGU*PP^)bs<;Nu}{B4Nk*BX-g18{w&1WGIG)?bwPW{SgaNxr#?> zF^_wXFaLUV22hwXIh8?R9KY6$Ai}AMS667__$7$P0VY-d> ztd?0OQhrS(Iy4>zo~}qynnDv2yu-EbXSYiBl$!fZLMC6V9vJD~jF%4_!ggT^iO8Gu!%t9*49u5(;mKN! z6Bilqm&dj)`p>HzJH4LM*9S6;!ifL?EAl)K*Jpfr+!e0bQV1p;2niCrna@9}omSW} zMD>_YnS?K> zSxPl-&YU0c2>sj2vHFElOuQ8XWtv1FF+$ys=s#Cy_&nb?u~KDzc4~dQY};c$AqopL z6mMcTeE{j_@9oUQexUuBPhvu+WcHERVMwEKiafnB5c4fEdS)z~Q-&TeMpSs4y$DVN|^zrO^uEtqlD|&8Xj+ATFR3Fu``9{@C(!?YwaOx)-i2L)c zI!UD)^LE<}c6Ou-MV+e#>twopjSsp**d=0!RA6s1-yY!>Zx*c~UDO{RMEo0#D{qJ*7M)UQEvi z{_df0LDM)pU!G$HemhqCZQ&^6o*zY{Rs}`gbw3~i5GrnpCTjwXov)^w! znuuP#3B01Ke`~XcB=lKdSjW@xmz_ewFT?a$c(|Ohez8!Fv!)?A#vKm_WywFem&ygM za#5Kqzt?^EEoYX+nMNTBX6LMu3gX)zY`&iTh$tBkSll8dFi}5f+qw#vywP?&dsy*C z6pz?z>K_MIZ3X=1D-6q=rg0>vO$@9g^iCJAsl?6Cw`)2Ttrx@9i=WGOaCv5RT~;b` z#lbL}HL=lBoFdErzE6YdSAen6jmX0Ia_jSwoL#5m@RMriG0>9as1W)XuM+8{8*IDIbZoeh#X#;AwjhyBJw@u?e8xv3|5#6>}xvMs$gVDb_ z7G>DW`pvC+9P4r~IL24^A6O=E&1rK)q9y>-%VYGwaNC0r%7pA^4S(G?RKULJiF~`7 zqDp&Lmo>)PF_Z1~J9X!7D|)=yYaK*N2Yj)y3l>yAwD*utFC|HAKHA>d*4bPwsE|^} z=jnQ3U--23a(Gwhwke_~1d{Iwj|HzwM0+;q4j3k)y|-sOVYddn;t=|Z!Aa*fs&x2?Pd{*KZ1zRx>h+U)#=TwzRy#IVc^}S ztea)9RmOpO@csN>%r1@p>k5CARW#EA2ZS>>(-kRuUc_gQ@_D`dSz~dW-}mG|@QY$2 z_H-ItFh(=zg(5!u^+A`Zqx!7U=c!D`XXSbax8qTQ_o%8z1t$oM1dm6U;@rgvgMdgUs`SuZuqeu$q7&h{x5#%;7-+LL$HR}}!jcTCxqJcKd2#C&@u{@icFhQL zOG1(0vBi#zqPt2|LgUlT(nue!zD_%^nUYz2?nid$72Rar7Dn`v{s3=_=TO9(AkjD1 z&*3hH#VHUp3Vijhh~40V_n%`#N_M)pQH{2uIQhIWV#M=He?!(Ll&|(O(~R#R;723H zfV`VQTM(+(o|u-tBq8gRum1MF!PX4=TnK1vKV~|#A1*iQO8EIanuz!ukXUQcab7TO z0)sNWapIS~ZUytUIut4pyY@oAcy1BW|M^wv?c}_8J8v9qhnqeck}14BB6)Aqw3B4t z4Nsf!@;Lr7s&wJDiJ7f=<2EG(h_bm1*=GVinD<~~kTRN)#eFi|o~oyQ$tL|!oE7^W zIGHc{hApG`4LF>|a|3ZF#W;$-((R|^6j={NYJ`=+B0Lc*cdc*@z1aJY731&!&AALH zUTyG11w>E~>GN6eS9;9GctxQmBHK>L`!WGyD_*`ycDli6F9K$YEJ=tAyMFu~AVF@x zdstp$@7@Jeh>lj@u6h(f`f_1<18bwm&i5;wBL8tM)^*U^)?6a@y<8X&gaRcTD_xa0 zR6gC_-djR_|CFpC@T}q;U?6l}1!8|+!Aas9P#Fe7ABwOJ0}`kAviI`?LP_?o`#$;Q zF8XC~60>~4R~h1d(6krodMl#@^D;0Ulj}VOe)ufb5(dRP>6eRixtIqkHeT;K`jv4-q7QaGU5@!Ak!GId6MgIC&3rBre%fyuq_jJ2+={xmuJjRAFCl-Ml6s8}*>eG0+Hfxqo!NWXSM0#>9mY=l`;gIMup8QRPQN`e_S8WiGBNXU*U zOHr{9j#K+49Pc2+K$NiF`1(2Pm~j#2^A6*J4wPd6xXDySO}XfV0~gA(Zu&){qiX2b zN!%ZQ@%e~{-^CeKH>cNf1jPJ!H`jT`-4qNx03q|NzD8h>7NR95>l0LP?gsw2tK@?H z2-7rA*BmR}d5#md&}HiQHbsKxGX^EtlG*drV{JqkwbJ|A(rCNaz?(gO9|r)NV$1~h zt-FFOBSXn-nrd;Cik%^S)RmDi6l~nBKzWV4F$j!=w=)Q1g`}58UK#!uP9?7ZH3BSd zOL0&?*ePd;lIU(HE3yQVF)$=|^-`}WapWPgDiOj4zkDmH=yf$xtdl~qy$+qR(0%pK~80o_VQEDev2mt4v@W*!9=n)M)$1o@d?FNXG zRT)w)M2T5HuzL9`x^*9g>pvP1$fI>?aI%^xp+;a{L&dX?qM>?obBc8T1&FYt0VLE< z)*=!tNxq(f(^>4tCK>pd03rw+X*+QhCXeT{7zFNiS+*NE>a2W?ztnA7>iyR?$j_He=ocFuna8nig-RuXP;Em`NkS%YnpAaMZ3u-eQoBbgUW|cealKx zg^SrPbRMecnODq=C&$VuaAb)31~8Hezq9dOo(Ja*#KhkB{RISLzBd4(WkAtso(@tR zi^RJ3O-;6`S(~-E(vGP)Sw>U?-y{)-6M$s#m{Ci2fMy~<&@Pgf zV?ynG$L@g|k9bv#`P1gZiUqs1&t>23n_={$d3G}#?3rMuTF)cD02?L7O` zxVMMyA~xEyz|!2n1X>bv>IWSSCFvq1u5`5JpQ56_?7x&wXfyyr=5iw`!Af#YXeH6ahTURF_>WJFsq(>$!)p1|Y&X>Z+r|C_hZXhc&U zBLEVNAxU553<|>LK2YQpx-L<4+Tl`X-8u2B}s0DcDw5Gg#b21uk#8935hXha1cDp<=Ta)7n4u0w{4jT z-Zmmz4@a>c7=+uAD|%WFKpmSzOTYy|QZleAoYlcTY9e9ufb%iV%8-%Q?)u-V2u!n{ ztr`9y9zKfvNFY(UC>e#%62JA- z>vV)K>#F9ib;l3Z(WgzL4_kkCar(UQQgN3cpf}YlLrdst19fMP77zXGRq@!ud>(*# zfFQVafr*8=fnWbu-dT0mV@v&yns{*nbfC;9t+JmChu=H&?gxaQV=ehu^L*)X8KK>P zP=jg4E6TlJP}r`)qss2<6%ob9D>-i4JkrBIfDFpF9Kb7T5S|5!7#7&iXKPqO!_K`8qO)9>i%GH5(*K?Ok%rhv{2K3xG!-1*rAoV)8*_yX5=ZHIe`{*qh+!+gw_E zc2=k~@B#_F4@KWhP*vEkNcG+DMMw6ehuZ2Tc3DT4 znzX>C?N_P58t2c`OO1*IFF(Dmnu>>W0ssdcO$;$er)E^QJ;14ytaUB*GBIO zzubS7pi0H@%k`~&wE`o!?Pp(!5=D6dU%77Z00&0j3?=PHM?y|>@BWebx0eWp^5Wn$ zu!`wg2WadlJ@^&k)au&gB0Py?8A^C=pd+e zwXPZPaJM_6{MVcaMw8H7zi~4mz-ErJXde9-Ao&`J4ueN9&#GxKvHk`Rz|CKxBn{YP zi6}{ciii$QMLstA-V4UTr@KdV1mPF_Re(5+1#uT|jdu)GM`P zO`9*CXtHSiH*-x%czw+|pB!g@!P`We8`z2SjXg+YMJp8K=3a^kNW#=VCJN!$^csi; zXR*lW0GXKu^p3mD@aZ#O;f|Ba`o+&p5R`VQCn9DUC2-}b0F&ZEyX&RCU-rEGX`ys? znf;QXN_tlfjnV_6#MV4R&xe_&#M|f`gew$f)%K4Pnx;qz>w*Ja2m`=j`phpPKU%1{ zbx(pt76j7|1=whDR_{tXK{p=mh$+JP9U>;=r%t!Ux)KW-ygs1&~ScFzpqBx?=G_{j&W?27A}s z8&3(mZ0tC|qYJU6{*^jVa&yYaX+7bbS`F0O<=7?>g&Ue>F)j$1~hJ8OhAq{V0U}dlk zB6f`+2sDH<2n2cKQEB2rfuMol4q37>u!3DXrTsSiCeb~kFpPVE9eJX|VN~|L{vaxE zy?Yq%-F?hB9a02}ykDoXa0GkACxdOUr6Q}KSh$P|&c(Ng1Q2fmdQ%l%1_>omtAJSb z73sf{jDAC+2JeuO$znEqw-#MH-IjjYEg2p=m`sunSg3VQwC1MNvH3V6NYSEa-fraL zDYF?@@lWMoa()W#f=tC@!>c<3)|9}U>3U7_7q7#QBZ&HU-5EGtgJFy0+0~X7RAU)!wus|kcCmj&$?{G0z9VBo-B_^Gj9Q}8KD_@)|8U*5-U`H?@ zD@I1?%~jQPnX)wKO(cri57{L^JBRi8MjN@!(7wGs&aFo>NR{E(YdCHWJsV^o-u((+ zgZyz@*I@wOHqG7KABhLqMF)qElt8O0ir3dk%YjecwV4#{Hfn6|{&lJz8H;uJ|Iqao zKvA}B-#8_`grIaI-7K&)vao@?RWOO)H)nH55vXn}5D{N`RH+8`$jZ zRsOaFNcH|SbiFxkFb5`a$c3@vXQ!72xt#k!R#fj(5?&bI zE1-{pE-s8S&QntB^S>zr?zVOq4^gwW*RP1ikPx?0|H4$l8;?p~?|<$w71WYFg~!%P zOkhmNR7=iLf7BYtgN}*Q{b_tGFO*DiEg`clM7zO7jQJH8AIX{xM|8H}@#v@oMjLf9 z6rkU!xpsDT_P5|Cg?kS&Wy81_6Gd1q{MlD4m*flyx!}Tzp{IkZwDW~?hM>ZM9MI<) z2^*|`45eJ(~;K)Q~K z`c=F9V@d)Y4F>qK%6E^gW1Ajx#uZgcNV`H_IGy-FZs*QDWbsM02sz|Xf(T0P%86r@ zf{qdTW;TTJBTR8cllJ3Gu#}U**5L3zV+v*no(Q<~M582AozBhk=WeBYrG|*B%bpQ; zKvt}a#C30xy9TYqUTaC9&gC>bmFQu9kKq zUPX7jr;Xn0Ktml>J?fv;7{D_xghmo8b;->@Me~$xEg>SNDQsA-lRh#bxQwJJnxcoc zxUU{0-d6(u@R&OK!N&U$U#{@Ue+L^CvzH*y2vgJ_&ypMqCy$!_kFo5w4LNHs>vIb< zY-nZsv>|rMIL975>AgL+S~L%$#Jolqd8&(5ZNuIWf(m;QI=bWYIEfMOA!-wyHF8FT zOrBERoMhPdEX(OH$Z}#X=qJ!fCI1mL6i_=bSZljALOv3%zPfiY=W4%>HUOc*CWo~c zwy%jyD1oTeLRUY+lKtBH$C3>(CEuH)1pj>DB zYXpNVjBsV|l-9z9aS0%n`g_fPVbi{cyey3WBxh9#qPQ@(>>P>@W0HOid%1wvu*GT`f89fFI+a};;z`A@n6_r*@#7cpX&B%^+w-DJ& zGk-Id>T_J2p#;ZC%Pfh_jelVIz+L&FGmM&gFV_EcONHsa14r0|xL%3jwFJ??UT59F z1QUDJO|mK7sH^lN`F=EH;kqUyuz}~2g*ZrbZHPq9e^lh<<6TZNyM}WB?4F#B^>F-P zJp71H=&V^4rctWVK*;dVDJM-!iii*;lsIzqDBu4`r45pr6QiLl*4 zXIJ zD7exkb^3wOzi2rYGiXomC$G`}26fnKx=CyD%)`GFR>l7-ucbw&p=OJ1bN?5G`ye(L z1ma$N(8vZe|&AF3osV_RlYKA%YO`&OsO*>;;qFY{9l)BIBG2T zUMj{+|8>sM$Dea}krbf05q=3maxqz&s2$~W?&67&%6e4BW7ESG&c?Z+#G5nrG%li zczAOx>*hgyG*>P4u`< z!3EkoK?Q`4D-yEa$Hc`iiyU-KQKBBQ^J6NYXw+B>4Yev>StQCA@;W%1eVcbe4Xd7^;< z1MzZ@z%W(57;&e;@)8}jXMw6OUL8}ox9NMx2=LB+87HtuqlT=J2iXm;o}!L# zjSz`k5K_Y;F)ze|aHqB6;kn7A-z%$?4T+3kywf-|r^YKKiH7$>=viUV4ie%3g$qlE zAM?N@4WTB9o)De0MS}MUakv*i9v3qkIW^3*#0W@q-(Z9ln6t5jC2_9mBvD_=0rzR7 zz-0UYVy_pIjkX7a?Tnz*8cM5Pz&MH+soGkzKphi(T8tgTWxF;H-m7GR#x8vV8<&2w zxl-=i%HOkV8=DZ+^D<)8`^{LJ079%UzgivV!VkLgQVS!;MJTD+66^BJg^WR|eOSdL z=;SnfG`b)2^1&_i-YX%57RqITznH3$*brJ-7D=2vI(FlEV7yFmmSTO6hXSm0=8z%- z1Idw>UGydW`~w2L9oECmYxi-KGLn-`p`Agf$YFMjdvs6+T2kB06a({vT6YZF4k5+D zj6GPBKBjgrS{G@DQ3oKSvB3lHmq{YmQpc``TQsKbKHck0z^gC8D2f9QR zhsZfcy{~R^t-Goz1e<|`uSCQ7dt3yqxg*EuJs4kDCGJ;$6;*ih%-PGqvkM@3PWGQQ zviK@wu@x;Sr4q`7p-02~{CPyxXH+oc;Y2^>fO)`vnk$%E#E4Ad9(UdnZ`fiJf_l3y za({pOu(f&tOdYovxjU-^lfJh-FUQj zRm+9A^K*AkLHE8rdu`66jHyUTc$C;NNt$yC2`A05*dSqhBmsL>tbcjei7DggVqTA1 zY5g@LnV-s-V331vAaV1ag2CS_&rFAGhqCz@Y)j3;F*jsvTF#?l);|7~`qKAHB=I4a z=-=cDSawf8btm&1i1m7!D1(NR`MEv8eVY)5{fF%9RwM%v5msn3%<5)VOj_JfPRW~^ z`pKj2V*+A);>i1j!fLd)<+1Wl7oy37a0l{~&xT22B;b`ziHdKn^Vn91qkAJ^{IRg= z*+#7dGa_Ml8u!S5w5B29WO9+UyT*!+r~KQF5(Aodty8DT_@{gY4F7p_72ML>e)>q0 zU6F8k^GTJwbT_aoTgD3NARgUwIcF1?!Ba*r?@|odL7N(s=bQ!cP@8-B&JQ=qNsP|K z7idT5E*cWKTJ>egko3QQ%kUt@DyvjhAn{Y)*9?K16^PXI<$?mwQ)`>QS4+(WR-uj0 zpPgHR74VCg^i4~KwKilqOIbTNa4o<>WY&y z#Z{Qf(CjGCD|Bd)ZS;iUClX&N>DqiRFuc}@Eh2dd?a}FU*CEqS$D0Om$3|}TDTiMu zZ9m5+g?9b;bNAbAfX>UKL$nJw(sR!EbLHn{U%RKlOz-NRf5@;8krj&9^U6@Es}tHr7-n(6~Ej_{L7%!o-a6*WE-Q@EmPU&^|gTBppb8CpPYOB8X@)`Sji7$ zavcJjo@Tx$_e29(TYfcuZ;@Th^P_Ce1-11=WOr%qL)5UdETBCfOoK{*2#ky2p+A2* zOf*1=tL1i6+rtq7yttfIvL^>12m1wpH<>T%oC6Xu`31u?YZ&rvfnf@$vfw->%osO<1bPXw;fv z+}s_4HU2MAhd@;>*eiZn6@0_raf5U_pSMXxY32x&9}^z}JHl!^%Zm>HP|h$`&r$04 z5EHEFSu1kP?;k%e8&vOxpL(Of?h_PQ2C&n* z)xPROK%nWxrOccQ772gD`OtnmMy2&bjsVx{8v;HK0PY^BtoeYIm>eFLyZf*;;Ch6LEyah8;!!|bR7U89U)e?g`VGo-#l35&&VPp5_zDU6d2 zCAz)iRsr6;&cCDWz_WTd!1q5WKMxx^3}Y$+)?qf@dUv%yTtI(TdgDqY-7~!bn9pRD zgaA;FXwzWK_jz8x*QoNLHDI7Tdfl4hgx0WS**6Pw_B?+8orZoFRqTCR{Y$6dS-vvg8n2eDUKAE>cdp*nD`uN$^M{VAT{3O1&L^v zzmY!eCzkyZTNW(+(pTFr!MyuH$82hYEXy!o>rpqY_IVM1K-r6cwSD79W7Pq_9K>tU zF>99H!#Ig!9oowMk1B58+5pkA21#;(;#*`nvR*IPZIb0&D9l^LNh4HEuO?}m1srB8 z;To<7&D&e2ybB2^Saujt`ladGu@gK3YLDS$7jZQ+@%y<E)2VKPd^q&PYBtfXZ$bhVh0n*KOSX(I|(WY4m5#VBWBg!4fH zg_SWWwW&bp1J4wc*2WTk*+`@V+^MFWU*?gZb5|2j-1N>@F!)7Usi3c{nt>yPXC8mb3 zCy}AOfaP6B_mQ=Er9)M7v1B2G1tyUNdX_zH)-#DJ2>BK|4sCqaDqw+N{#avA@_}Mg z2TB}-T%+Lde4{%^eha;|v<;3U#4DHeize)S!TX$d+wZ5EO7rQYs{5+oM?ZAUzMfo` zM#3BmL;Qy>5!2?5!8uh8RasRGmoAzsy>JV}gb29zUH>oBKT#Hcuhzt5H0@>U;@j}Vn4nnKo#$({?EI%f2aouD zR8aa&cT&p;>4G}fUaLgDS5naJ{-+8zuJ{(tsLkj`n)~(l^^ZR?CCouL>kMPNHDf_{ zCj`2d2B{&9^C$^kOGG%M0VQ07`oi3<7V>|$pbwB4ku88Ish`@TX&1h3qL$l>F3(di zdKhf^3$0jPpgQ^gownDL}eJ%U-S>F;K;d4@7(HfOCaAQQ7_94VaVvVxnx)XY$j<8GdzzqM=9S zET{z#eGbO~3g8J(Q3C=z>p9($_nzMg<(Gov%EV6q>X76J&A`H8iyOB*C47S zbvKGAXJR03Kgd9nT^3YKIctiQy}P(cc&j)q2p-99)1C(+CE_Q@CY6r<3)Jfuw#T!N z`)t(lK*1Vt58i>NhK-Sh9ZL;c(5-(R8YOVE7h6jGEZQ1!cRi5$=kmuNDqZe1dk~I9 z^I-1d{_Y6KELkpTzb^)gD-rG8v0OiOkk~F{xwX{EHyFgZj3kokFwtfZ-5Y?d-!IW7 zqWuB3`he?0bYQ#)tv|Qnr_ui;95(4 zMi~$U1|8p-tX4%>lpmOzc-_q8Cdo!Tq!f@kD9p)vdbjWNN2Iv?Ol0z`po_b)GN`K_ z?;+kAH$yZdQ#N(YuhX!hG9HQl0L8`3=(|#<^b*ygwR{JD_j(`&y%(OxI|Xs{b)uLp z_uGae+F{OfvA>gH;Gb=C%bVJ9flsLe0Q9?n5VD~qvuoAuVKj^~taZNA41T@X_Io+g zH8;ZL~odEeUls zAGqm`FR_TU zWg?vwGIurk1&{E9a)z_!*By!5!M&Ram+Wc@rP>afC!KChdaQ7d7We_Efoz2 zQctr`AF+Ro#_jF<)`=@4ffc71+69!gIKQF z+fb{Nemy$p@_mpA`ODlE?GBS0bJg{fq}-;3KyRH=VjsyVSAipEFbOWDw>T!lQ;)Gk)4a z|Dm|JDMG$Ge`zzi7$C^3e$v|=uNJff2%B~IkJrhZIYxOF$`47k34-qJH?ikU%OxRWlLV(e&vJL(%>^H<;1zq!f!&n;p<77*%yDy z95r-|9sU^GPLdb6~3a?XCSaTbkxjjk~|a z`a+jzgBcoQeB*);)BKOrv=|M27yQm}Um(^~gSIbGMiIv}aDH>M^<-?A)Cznv@f}hu zlj}S&*AVy=;>xPKszz){DkcGn^IKexnw)7!f*uPo-YM)}pfZe_52R)bz5Id4?;SCb z&E5+xsQwV{T^)beRU6#s5!1aG~fLfBMcGi6y594ik zzvdDn3*7X(0bc6r3l3;B2tsXOUpRqV&{N(|1`>u-TlYTF_|<+|#6OUFKRe4^|GW7h zQ;bB1XG@tIPfxJ-JK~X22D%_Z$Whx~c?B{tPmR0FoUjyxIY_de(d_*>9T21*4()R4 zcfO5dkv>kQmrcgJY>+koE6fx~#yy>ky!e#2Zb=#cs`wQWic=>;l=EuKSZSSp;EUQ} zweRtOVK&lsd#pMxdZi~f_HjBt2}sQuR><^)jv*cOCEOI~utK4i7l4QJMI(+u3A(WW zxYyU}q*i*c-ja~Sk>~uYE%t8Jklb)Y#E{DaBW$uX1*~a-$!d-^YKVv0<;-o1Lp66v zj;n9r*84tt%B^q~^)F-=y z7TXZT{>76f5g2=6>$KT`wCdGp#}`!2SmfTl0#vR&UgnIVLb!u2ayN|@U0+cGo#y8~ z3l7!N)*mAz_Y(;)1P`l?nbLpq)3JA~i;JeQ}I)l|xD1D@G zMzLZp<&5&nI37+piE8^1PU3UNt7lQ>W`u`h;+2_>8K!BBbhR#&?BA5@n42nJ_?y4% zAK4 zqHcb!8`KRT(Ap2~z|ZkAf2(U11+=zDOW`J!biPE98V&<_f@5#uc-pc*6S$0Vj-s4E#Ykyjs_2XiEG3aH|lfeD`2Z48%V8SKXKl;HthL zq=a^{svfI+$%lAr$x_#}stE`keS9rLVMycZA-(ccI1JOs(wh-(0pnR20~7MBK?n)` zeb#^!$&HV2$VD;&t*7I)zo9#a47A*#$7D`!vvmFXujPb|1%3I2uh-e6ahRv)3;%Py zoWs7fKmf0xn6;FnIKi`-EFf^W9TwN{af!|uo!HM1QkL+Lifx{)oH?4t%*lYA?S@)- z3b@XXe|5TrWBd)WeE?bG4ig@nD26)c;s|glGmK{!2PpYDe{7h2atn5T<=-s^LtkfK zVihO*^f}L*xl~e@ZHKC+_YqJ`J$1FzttT$BldUcO()SZ2G zeGt0YIsh)Av{{Nx-NThy^`&aUd)xEwuVFJ}=!sm5`eubEzxj^B&2%vPGN67m`0Ioj z1GK|sIVfkrE80nAo5WZzvhBex6`6rB6+TyROLWb))VBC0O79%&xI(KpyhVG1V%w~N_o|!7QA{_2c*v1JmwW9Yk_&%m2@Uclf&TPF!DILOeB&` zBEMb$S}tdvbi&bxN2zamOMj0UBi^E5Y=E$@`?t1Oif2kIABw{0yL{eIIj+(nozkk}P0;HoS2%ORq- zZ0x}{s(uW_-vw-R@+cR9`*albP*RCTiN#R*-c4U8fJ28QN1|P+N)ToBvn{9%_ip?rHAxOKkMn6>fTnBf~J znG8_dQxZhQ7I6vGsezZ{kuphlfHP#Q zwvO>$cJ`eG2AhB#-jUkAPjNh9!Jlp8KO>%0DEpOTa2DYHwR2>I_iKGQiDnSeiVj=R|7(Fv_*tcn$B2h4e-^d(=5N||90AOIt z$g<1p^yVi8&cYv1((XzUtZ6ofee9d>flr(C{BLYiNpl*_v#L^bH3J^eo0nzge;KXE zpHv}EplB(bwYnH8qy6w>wC;SnNk$0whb`!W}p7~sV|FP^;$^5=)Iu%oW&rUcH0Nzsj;VAz#N@CeOioH7+DIT)p3HzWGYvj+NwjU~-5&m_d))xSpQIuL5 zAy%Q6omRo{1;)KB-_ePlpRTE??9`tLf#Sq4T{4enKuU2r%VskQg&g znw!UU;E#%Dq7E~XrSl{*@g;O9mv!gjMCv{tCMLHtARk$K$2~dTX^TxuXGTuF>!Jhs zkd=L`uyU>&q!@x!$<+`n$YRn&~P^C`%D|`Ijxw$Vl>n8NHF^n!3-r`{L=I zde1q~5I_YJ(=^>|i2x=<8+3D=PVBh)}GKP?sJ)Je1=vXfI%oVbBEV z!;=!uDU3a|MN?!ix`?;9(ooWT1fYM;Og76Crfvr3mr*imoo0;jQlY9Yo);K8_c<`L z6$9H~6E(RkW32d?>)ohs9jGQ058J_Ab0kqpH-V5OvP<2E$Q~8(U0T_Pkw!LIp45sI z)JGjZE`Qjy7DCk`Z@VCz!#Ihr?WS@s>=v`VmM@Qo=a0qJC=4qwXa2ul08mWmYx9s; z1@?S~c^x0UCjoXR6c)%gm`DTv#J`!*_U9$REweC2cwdA|lIri_$&{|$zZ9(xiQL$3 zR`}hAJLu=*!w4E@4hkce$L3(Ze$$5`Nvk0u)OMU^8do*VbuSE^9)%I-=0wG{=e4QoSD&it_#x%_T0$)r zyneb4!m7)p-YL!Rk%AC$7oI*IRV^IZ3*{f)2LV1*&j|7qQV_}vNYFESL3E4)Z0aYG z6-y0*9htCm`--ZR=d^2>NncTQ`Xy=nq?~pxtpH9-*vi z(L>nAxTdsoiiEvto3oc`y{ax4HiYd$%p9CQJZ;c5V4@qP5w=l3{7g@tk*+1mS}_MD zE86`h3J<~1jKlf*^6K_LvVhNvY7{_2z{TtAO6&07q=)G^749mU+4f-terK_YspXD{ zMCrrNz!dT;9g(JbqbdU3NICuhrlo>LK3B`$4R1g=%^l~z!Qy`GZvW)Q#ONI>r#rbI^7QfZ;CP zc;Z%XOn1{vW1gj$LgU1@(kj8w9(#vZUtW4XLWy6-O)-GoDw{1C*ih^~JcuUR4N($Y zz1XC)nt83m?DVHkS~Gn5otlsBw**{i?-69 zeAYgU-IasIla0vyVuto%MZPpMQzDalWkc}P`&f%;JOC_sz14GypG=BL9)UB7;3z`I zkN%ZsveAT0d*&%k6zv#!(D~7}5G}obWt9bgZDS&l*7T(3_=5!U`JE>{GF56By>&{! zUQ5G+kH)7?n*w18RFwkFct@4BtKQZ=RWl}=^RvXBKYbd-zL|x>%l$7_BU5dF)wKeo z&`+{H)sIOQSnm1>KY25uQ(wKwk>f$o5`|pdbE}|F3jL@7HH4q0O_tc4l>j|RM3T}a zLh@Fpbv3`P&hogOL@7z-8~N@Q5#0FdCHF<5B0U@}Mu@Z65S`cVQ_Wy>}@FK!?<>-sdc6T`hsnt!XMI5brvRJ#H3{Cb9l4&X#0 z(rvQSWhtfCR^vD-sv7OzEdlNV0*6jBM@1aFdae*ki3zWr#~!4a3o&72rY&mQz3j2H z+mq>lV~bF# zjuKiGPnkMVk%|?0BloU^&U81$qk6kz^b0Q(1iY?V^M&N{2RQeSM=Dd*OJTrZ$L*tPxA%HOTZeg0LlyS9!I0yy7+S*05Ws=yTJ~i&Mkf%!bu*Tv2wDNq45bo3_*DWYm+1E8*z8zTt5HRrunW=6P=dAIqy8LJ;^ysU-qMG#b z;zNNrmnh=vV&l<0^hVlkuELvEpmT_RBUT}a79$5XXq8!Sw20(*PWU}?{KSxZ0_TMe zaw3Azat>5!SVjG!S9?*ypNqcYVEU~EryIFsjMhxL1-wed30Hs8mnG35cHatOYpRD( zY){hO?ED|J93Q<+Y&>Y;2>L^1J8!!%^cebsH>T=Arr}tkO_r>y$LJ@dm8L|uasiTT z02LzL$i{^=Irm?ajn!p4#M+tG4FT;4bDltZuJ)_>tBV%uYJQOitPpG_-M+_BY6tj)L_OYJ;q6>{` z{73g#!kPcz)G4Kq-}kdTFEIaYhNx|wDqU`MbonXbA0tAt!Y8A%0bjrBq8C?X*0f@x zllcBOS`<^GpHhOXMKY|^&*W?@p|`PiNP}-N7wZjv6RE0Ki6Dwe{;j&VDdF@M9p*B#M~zCXQYLT&7#x+HLYkn ziVa}?FPqPvZv!O;5LwdE4(D-B_@3EV3eA1BLZ#4PbSfH(VjL7gmRusW$!P_A^FeHw ze*MNhi+BpaG*VH`hZ0;|&VFuB)@4e2D3~n?fP)AW)Q^dIkxwJ*|4A_X%~*~_sa$b1 z8EqYB_3_5}*Ks)uatEB)K1M+fc;MCUhS`tuA}t)|9eq^N|Fyn>y6L7}Titu4K|qRWl=e zwXnbGIN!brH@d;wZaGpUp(N3`o!3I%a&%Pj`XHi07-}EDE}Q77f61qbPX29z*7=k% zSffwHYxa=%X8iL--r>Tw>I+#*)ztjqiE78BGUF-<{>g^*nN?J=oYsov-8k{6e%1TV zC;PadE{>it8q~%T&})m)PL#(VM0#gNiyRCM6eEy->5`ij83-+z_F*>N)H3mZnfQp9 z9>{^W`)$TJX*_f3%8|?jvNMXi`>6JNmbg+vJ)dBh1ytYo01#e6_Fw8}U~5}oL~E_+ zo>5Aju0N1v--EV;^+@vYtuPx$OOMBmUV)+sPejbyyW&B1%IOh1P;E zjhZUg(JwJ=r)A5MJI_wDmX&;ENe{dBjF7N)OP2Q_Sr6%gbFdq+Z1_pl=2E3c`G59! z4%*m9Q4i3VD9u%{4cvxax(84;e0ry$B{eBc8L4(k>C_CohrDPJfJ@R-Js5ps1U7VG z3)z!U``-Y9V~FZ@Gh7Wr1(7kk2hp{3V@w3iNjd)Uk^2>Sj~P+kXOucB2~e4cNeWW4 z<-bc>fenNp(0l%7hWA$t6hEm9?TAkcm)ZE-Df=^7*HG!adyKIeDJUNiS;X6b2%$yD z-9eBaJ+Z75eMn<5bX%jPX8wf9&{Ds8NRa=km3HM#b~L)@`fQacp_#PQB>2qf+NJB}U-MdGC(e2G0|6xnInHTofzhDqT+!UtkiGwg3mBw7o*^YzbM|I@a`M#!NjT zzIy))=&Z`c4tJ5i1Ug5gwh#w|j_!+Om;)nME9ids!ZBfrRTSW1c`)rD%RuiPU4B=- zOY-*;KprJCtte3sBrr+Vl9>39^J=CCeM56lNqX;nEgKVrnRZe0pLPMT0*(jJRM9xR zsT6!ms1%nw^6+!(?TDYju)K5a#5Xu@N$QWu)^BY2i+}b+BY z@Lb^VURtZI*oj7g5$*7J4RiZ;$^)fgk&rUA+>e=81{BtmK&ui{4kdb@4NA-&YKO{% zoKHqxOP=o2-9TY!AUbcEXr!5N`}(_+UgNts$O{4uJ4B#mbd34rfA6W`?W#q-x1PcPxz0l_}CSc}&OuHaZ()RAvJH*Rkmzz-1=R`!dUO zc9(Bu5d798;@+g4E5c-zI3fxJB96$ILdhEc*Qb+}75K;e^Jd_2J?6cajTCOZgN#sU zN4viT(DC3uT)_XkB*6a*DB_tZbQTE$+{z8mD$M+9gFgaS^hP-FjB};vV><|>syhC+ z4*g%S4@K^cw|KGWOi6y`R^sFx; zeVp@g+V&nHQ9}iw__@240FWqCR^ES^KiHyzX8|I*bAj-u$fJB?)*IJegNLZ4cswKY z&!xEE>7A=cmrmU!$U^I)meA>p-Xs5wCQTJ+q;0w6H_*W3dn?rQKZ83e}fG8%DgX0{*~81iQQ zl0^_{ey1$P)58)dn*{>h7TTeX$^ZTUJ#bFL-&VOYMdK`0KM|13ucHlJ(^gO~G5euu z1BJ@k8K(T#F9Hb@8hVV`;F!T{8TX<5_zU513=0fh4)QqWE!;@lIl=8)7g6wOXuj3| zepcY=J6RcXt2NE^)5I;T`S8WPmKVX`qxs=RLG&JITa=}2InX0RmcuaOU%!fhAw;W1 zUaYa>zt}*z$FJ$F(8JpFhVRWk{%%?)B?kS30CuD%N_+EPpOgr|9-|5!v-`&~bYk_B z0DcofqMUy`K5+4Z0INz$ME2A_)*=`$nhCJLP}0i$yR9%aV1eNQNtcKK1>JvrD4~G0 zMiBBJ{pSB(ry4NIl|${T;qYHeh&oKD;aIp_06Mq-8Y;>w0XSs9r|{W-{wX0aoc@)g zxBr~PNz_c(?TCN;=buudjP)Z7EREvnvpvp_t4%m5qG!&TX5JtvPN_0A%IXYboWPa%;^7^khD~I!gJz#2$MNo8y9Q zZS3GZuY@-WQ}WoC@h_h)zL_|t`f3SoO)l0;niwP)%Gdbz!Jx#{WPpx&nEOk%Ek*L> zMOup2F2%D+4R7PhEANmEthLg-*eQ#Npoj6?PYAF)tay2FiVk2^#Cu_$+5;+2m8$!q z$=Ya&G{jylO6Z7L?dK*pWfeYHeDZV3>T&SvJAJ36cCPgeLnWHu-6H6oPYYvc0^pU! zZ+`30P-CfF-{Yd=SK%W+9IjgLn-5S?>a5q;TkOk;e!))p%tn2rICHMo_7&#c=op0? zD?_4z*xW>@#_Iz5k1SYZB`o{|rVnf!WuD2Yj)Y1(ZG2AS&8tz668gYX3{s#fkQr1r zBsb_Yp(I#4#n)SSmA>YyV4^@59FQ5rPqkG4EA;tBY~`nsOz_7vi+i3JCnj17zaG?8 zF?2%4klgZZ&IiqxR$B}`QyD~Oc%Ur9-35vafWq)nZ3N^_g|32!20{;0&wVk0cb9kfngc#}?0mU)v= zu;uJqEW1hVIY=YzTo`w}kL89}=Ih=e*4qEv{;9Q|8A}zuEm1PVbyBKT$w+#a?G2Z- zCRLTni+j=i^t>AEq4!=E1>NKc5n#Oz*SkMJ|GM|})ZTNs*-}W~WP8d)uTIonVLkq4 z_C`}XLx^TeH1zVjhWzFamUnNcx8TnbgaSOP1{b(X6XWuSUrZqB-+mDNZNbSBqvXCE zTd6Q(GDFF4PnSKgHrX7>rLF28C52F323>2DN)JOZ8cjlYJ9zd>n+_5_e9rgkNd;O* z? zBt-f!Kkrj0qaY~>_BFL4J}D0WgoQNR%_NxPszVMpWnpnS!$%Jl*bB)ru1z)>epI_t zY&3)|*p6(uv55OmeZkW;A$JCg+O*NRwH%fx*A(vR+Gmv}t4|%^jd5(OC6$y&-T$D( zn~NUrmI($`w8llHY4tZ^3Yk1A=C0xk3Ro-(X;n@$KaR98cJR@=hNz`Z*!y^g^;DdX zo|F$r|#>ibf+(o_n;ySU77mSUcFP`{~|_N`^Zv{9K)RD~kvO z=kUnAh_Fm(xUYLie~jzArVx0l)bGx9BA*|h^z-Sc$>q%2+wU=nyBXtEIU80Ad$j3s zLqV*|4P9K5-S*Kk1RZ=$uZq2&L}0B(iftpI8#}HM13A$Kilzb)FEz4IrJqL|jH?kt zSc;ay*1Jh9M@GvU_|Fq7%O=8gSpluJvC<%u5t6Xrdwk07=uOSus~*m^QBou{e_-+l zHynefgANPejdIok10L^bPH#y@gpic8$(At00v45j<8jLT$I96v>48EG-gI#U zB{7R8M~!O_1jyk&Ns8DEKKRl^(JWR&RyeYo5V|KBedDvrFy~=CI5whWwa0O=AOx05 zI>s&mZ3WDQaiV*g_YCn9X`3|({ssqTK{#$=Cy6^hdZ!EB^`2!)idC;hH!;|Zz~|M+ z>cIEUpdp$JQP<#;x8$p1ZD0ZEJ%s>2h<+ELn3U{>f1?WljnfmFM6l_lz*1qUcRp3Gd(EnrjFR`+(Fb_?Y%{lMRUJEXXkD=VFG;6ruN`V)eGgWFRp8h z2Lt8@rrtf+{0PQE^mBN0vI3M>RV~k3 zAJuA83em(&B-wFP3Afk?OvW{vl$XBK2&dS*uSJ6AgBNu{dtzoKnMc~$Mq0!wFf9M} zBK6MI`2_AFJ5EGRE2pHWyi>y?za8j|#ATr0P;BliRejjTQbLzS+cFd9Ae?i}az6FJ zRgCqP!>e71`_PfbGh6SK{DD`M;9ogTID&6hJ`+cyB@Q=S& zq5!SWDr(_bQr$i>-Bys2F4oW9sW^#LQ+C_ns}eHdvCD#M&*-O!9GcqoG`Xzp6DoRF z(-9?xBeiEOEH6d1E2IN47xypuHOfcw-zFRqBi{aQjTa}MW6Ie+qKTGxHbJwBTPW2= zn^1ve@KZx7w$7QvYIP~$g(__MAS#{^9rNjMjKb=+f*;{$K!1k)KAvHY>Rf7|)%}df zaRWQFYUNXRRCNrb(CLfML}1D7lRp;8j$axrJVp!h2dNLKo|Wf~tNUg@)d-*QLu4cK zjmTwl-j}j$IySO3W-}nN$85KoRSxp{7}DH>&aL!bSk0_-ORM01`4-u_D3&flfrjm9 z^q#z%Mp6SA7#hc?qo;Er5_@gW;Z14*+gUDh;#NLTIJma9-7%{?>Vrb2fp;_rjdwmc z`iU0)W{5_p3uk`x-a17sd3VgXHsQ%S&b zG-&$fT2SPId_qBgu}j_&4RwVfUy_9(N3k`+CRT?0<*|JdiDS$VLfI94pVv2fzLWEW z?r2$%bmnM?_#rK;vCVb;3w3fQ)^ssEM|?`Rdqss28ruxb?%Q8uA`1nj;;Gy&BON5f znV9G^iqQu{<(J_D57U_$6cgsc>$_|Xsd?q?mV$zkB$4l12Ze_fsqcHv_u|cc);;a- z7|PLK#DpH#7OENiZgS3_G$jh8bb8=sfRylkJO z#2^r&bJ)6kAz}ux?@oMnl-F)NH!XA+a+FEKk4=8gb^J1o6uug1lyo1v&Hv$>7$kkH z1ZhN`9U4&rPPp<~!UK?7EGNF--hhmxyml;jvF}8Ip7hcD2OJxgpDe4mmCVuVj}9#p z?UZrkP4M06n`GxdHX3s5E6b8c5N7{uwN8kt-7D%8LF|+7s(fGkv1>j=mBVA>nYYf_G4WZs^STEvE`#t>F%4m!i@vib1$@8d1$Or4OBwB12_8z` z2hUaa@ZX+R?HHXz#sAj*$*GEn^@~`X(36@1{Pnh%Gd6F$35ANR|*ij(_P1_|m zbqMZ(H;YDM)M^#)t4suJjGeIr?Twwt8&gAl`|%62P7A}ICAJ)I%YZt-jGi}j@~TIX z`Pxi~LD*$;)z^C)3Ge*44wim0hRb?(7HP90M%rK>Ve%aVOWN3W^`p3147Cw!hF=Rn zB*>{;dReTnFh~!Hj96Io#fae zi9Pa$^Cu+I{avj4jm~Rt7gKHa?lLlLk^`IUYpQzFHF`CQ)g(#d!7R`2yXf zQ`?u?a5jcfNzW&qqysUpbb8rHWRffxnYC%swC64-0$H37(wlZ-nB!cQ2^QInBpais z0zVyBD$F-l?LUQx`MBUJf@lUL2mtYJ44fV_7 zP*xbVIH}y-NF>5(&oOn+=Zf}GJa2I=DJ%ICui1~X$Rzyf(#ez2KcvYs?IR}73-8o$ z+*{l;sVgIIek5ty-rQ#q9{)JtzMz;vDs^5Q;-f4n)+|D+q}7+>ba`;>O4-sPmjDBc(xkQp19;I!94 zKFkqLl*lLVHIjs5NA%1u*uWe=?xW^?94F!Gb{gm0TW}Z%wt5DdgwdXf_VE4DX2;E% zH7oBUj3l%H$p`&A*fEGpZucJQl#8^KCHrLDYm_U>&i%n2r)O;_`ZVN6*ea`Z+G7zv z<3yo4(Njj=Q}}TmGJtz9sCVS!mwGkwgf-VN0=sciW?Uzd<~us>2ik!!$a|}L4plzh z57~YUS@|4B-sI0c7I$O0|ABks+RiJhMcG$DH&b@*v-)1ckBzERrqm;iAG$t{q8;Ac z&m_wNMj<&QS!9^{7i~W@H?Cc{nelG3p&>vdq}T(ec6pn10(nQJ3%c_=o#^_-#e*Mr zeh5K{L?S(OTqy1qZn$u%d?Q>+0Y5q^g9EF^5pg0djpw*v@zlk|ijG#~mp5pH(&*)) zWut|(aWn8hVBO4YGoJ{LwD{+*C3&+%WcHmA4D*NPWG9{*lLvj(uyWvvz~F2QpbGAV9Oaif-4euXs8o6b5=;@p^hl;*itzK zGa5AcU`59%8=6_qkis=!%Z5eNnI|Inq@f|?Op7vQW}%d_a~r=-r;Co)5EjzNGt0z- z6~{D6DLcw8uOnq*<6dA-*{D;*Z(gpAF=24^)u~ZOc69LXe;^wgd0je6qfta5F3QWx znrlI$8)oz3+H)JtKq+uPM0ryl)N}&lo|qry;FrCuKt#*zW0$YXkfFxo zOhz0GbgpX%8b(f(KPcusHZ6XUnIGjyGeNMWApl}T#-kHFqMljT=GQsu%6&i~(?UDF zfj%KK_xygrXoG$>bRg^1#VPhYJ@-BFvta;7jbIKUOWjgtkP6g)7Ybu>d zNDv2EK@P$tk46Wj+z68)hhK6q=AvKG7pdo)RMENW{L&Q}DqiXw?hpQ<&w?viai37X zyrz+!bLz=?)|C!dq~kinE<44Ye0aunFJ@u8m8Tk=IuN(==QL{6Y2Y^T$cL@#f;Hvl z`A8)3HyggN%sPaOxLIh(XNNxSc^X#eX3EoS+$ZraiF)!J;*xRVlmK zFY16i>A0l9nsR6T;!mdzLk~Pq?!WK8yw3*V9A%bX<-Sh?1J@}2aowh^8hR?q%6ooJ z+|NVskMmV$tyW@ON){)sQao>AsE%|Po*P492qSN8#8icR&^jE-WVCUe=vl^O%|QB;1~af=Er*>$_^jo&E&_3*fLR+ zE8kslzi`dyRFOBj5gEwk2L>AS+($E4jpvE?U&qZ4T`?D+=*U z0oqgcPWj=8zL1S^j5;%z~)QGI%fZAcHaqP7KadI$K%QUEOPS_v>E$rr-7I zwfar3Ucc3UMRol;(;Un+9T8ALK>-z!87|Xhov!EKV zt+r{GrK55I_Fb?eo8X=PY00(v!gA`9=uPR4{2HL{7W<(NvqE4ApN|=4PB7_T^rD^7 zrL;?5tcXUAHg1Ul&1^6ayF5$B}+0z$Y;bceJm$s$QPyX<?*L#_%YDX zWFqMc#CE_>3Ghlz5s{|N0i5VH&XF}ChL0^vIceWIt~r4kuXpfE?AO$R3` z%aFarvQSw@liJcfios6HF9~kP86h*Br8~@0Vaeb!jY{@1!X{i5c2AgI!L*!*POsN3 zD?@ruX0g1C*b}4fSthrf#>hkE_Z@~`<1cgQ7zj%kU8tpG>*rtMloYK3;6TZUo9(&8 ztnatqejA+P09p>XjYBUT#8>9^dlR|$hdAosC}0YUzoXp2Ke$-~*E}3JY9yTPHo};; z10#Ka6H$#D0s$?e6sXTfE3P+#=cOpB-hF%Xe9tI>LI0i2zGqju=b& z-Lv@E5{;^Lc{tGR*S~)T`6@j#Gpx_3y(Dg&{ou^A4#reMDl84JX9sc`Bk|QBnJQKV zx%N{c&(O%UF>wgm|2S6+*pH*7a{%sViJa1n#iqpVHj59bppwQ^}oCYEE1SjEn$e*?| zfdk4nFe7+&W)vy-QAhZLYvLizk_n>&0R9(o{KMFhT!Pl3VV_yfewGJpPiSJBpilUn67rILsA1Cy`Odb3hke-4 z+I9;o22wnOQ=PqSf{rOe9oFMPk???Rm)EPYZAJD&4`+$$M;+oU$~Ac9D)iUr2u2t+ z^9p|EcN1i&*Q}-175u3q&H{X48lm!cT{o!*tAlCVl~MUC5C9>R^Z^yh-Tq4o;*ayr(no*}-WBBD6OdGtkvC@}&Li_h>ZXaH#jyW9ladr}l|- z>fN(<24^}^k!cb2k>FSH6pojrO`ITqaX$_OMZUZET^w~~+u5AV+)!VGyEJKLe3Y^3 zpwV_<$RimfL#&E7eZ@cPk-x&f!JQz60cgHUYtOg#zcn;am)WnuvLXt$^=P#|O=_++ zXNyMP&|g&tRy`lQ#Et$@&p31B8I*#v?QZOcq_F>V%7kTmVrQs0wBjM_@!HMEtU6s= zXCL>4UeVp)F7S$LgWX?u4$XL0{bK(rZ_-Q~B8|R1_ig$1{I|$&E3m;eWm$aW%q!m^ zchqn2QYXJVJn)tfm;tD!Pr(3>HCJDMsx@o7h9T(7*{_ce%ET7y+B>7mqXSvaf z5oA|xZMQsi5q>>?@j?b%J<)aXiCXl(u?_hSy3NtFC0PviuODujxo7WbQyO{Bpu~O! z$KC{fd+U>kJio)Q;23(t2cZk~d)R;SxBTQ_unz$q<R$64BD?Ol{eCeP=o{9kQTRxXxw1XZ7-(x$$+rIMN zE&ckH{{2dId~xYi2LFzZG~gm*i~?M zuqg~}YUEVew=O`W->j48U26F)V+OzXMJ8gOfg_&sdewXAWy@PR?YGS`xtL2k>y90v zE@>R!gu4Bnfho9{DI=``Sc3=Z8b0D|z@?zsi80zR`bI&w17c+1J5YJ`t}LuL#R~_K|(BT>FeZy*!}amGAZY8haP{;ThX( zUn;wPf+KLM?!jl}o^6vB@~7}^XY3L<)@#rPShk^OZv#oyUsdkn*K#&sL7^Jh0Y7oK zA8dc>v@faGK68mC&=TNH<_>l0uTgpWS07Os>f860GH~D^&Nax~0wo$h`{O?yXpjO| zmO7Qcl_#5TQUJ3|Xbu2E1L9MH+ zP2dv+0WcM0fC9^Q`CYmw92&zqm{U23D~2AY+~{WnS$rsK8x*?h0#^|ehWCS4tNt#b z=h?6Zp1Kp=$MK@TDFVo%l=pI@3i%K*N4AsH2kAsjv;= zRPm4tD&4{sx!#IWQbz`z08wzcRTT$@B5mTneI>2zKaT`vT1rkOn*h>fgD4Ets6T^r z6peKy-4&dzUp{I2);7yS)j6(o_kmE zv>G`PMh2ifBW#U9=tKR|F~LJ|0akD)1uU~&-b64^Pt%9-+JR5bFp!Plnrr-(@DD$sKUW>kZwPV zr4QOa$!6eLofSX!3TVfeNl3q&Lar{j1qaQuy6{J`j_fPp7-YD{EUZsgxIr!Oh2a4j z;j_2r@pFTKHT$5&zPb#-hrIoy?j#NG}h=S*JI>f>Lvaf4^k!Qgv zZEVrVx_b6nDmEe zQO}J>t0{S|UavR>JO5Y!+Q^Ucribz&js|e-n`Rc%c6r!8kwN&tOW`N*^bl8JSyJ4k znTO@&8}+XPXzAXUzIL#!GZ&r-GAaHa`XjH`V3Wbms-ya#@0Ho}42&Ec$s;Kvetc|$ zyso2{nRnW2`)}5n1fI_S_u2`0kL%hc+ZFzzUntJ=aD@S9`rdwNQZ^#KFwi2<+tss`aI90OXLH2Liua_H|gMj*TIW)$>5fP z@}x510LMXR9)_rYhNBg7p=$l>=kQ8JCgqhMgA3nL?*-(kH@{u)-Oxw7lOw=uzbn^) zE&tOe4pPLY;?E$G`|5Z7QlHmmIj~VTCD_ArP7)aCNng{>rjo8UgjQY+v0HSbjjaL= z?QeGPD)`mDwnt1Kw}`<2eFN+Cx8OXhkE)DRpW1#9KXs2hE&piy`Y=gnIq{DE;ViD& z3G4b6U7${~@1t{RbM0&Efv3SKT3tjb7o8Uzyudw>QI9Ee!ig`zwZM{=%9nKGtZh@L zNayB04<(~PnYTXSColn@h*J+_)j?x3W>8Q0G1w*T&BSfwsY0M`Q44mVdgv)%E3ZvZ zF!BQpyWs=WNxz1U@?+hrEBec}Kmpt75nV5@@LhjTdyoSZ+?`me9jm5@GQ}Boll2^3_l$SrkixP;Buxvwki?g(suk6=+q?ONDAJ@fu%H*kK z_Ut)j_?^QmTzFAA66DYQ_}c^;u4rtGYSw{VmhJ14`(a$O?dy$Y>DzCYb)S4%_O9Pp zMo%4AMzxKu#?3)69qvqnol~91%Di@X1R_*!SehSR=NZ!ozeCY&Sp8X9ws%*#lUp$M)0k+4;8mg|3O|8n;1x$@>e|5Mom zw1>xxEA3Mzms@YYJx*%yRY|FQRaE~0hG>MVbMKz=tB+R!y_A1^bV(UFct{;M!GK{_ z74QwpHOiRZ;#-9dWkE&6^5b%vQqRp_P$o>CoM$X2?0QyVpv+^e zTbmUDR~)R%S`|X+p~L1`!+7%e@v?W*mh#Er&LqJ8M(L@9Rg4-tXIbU=8yyh)*|u-~YC~DNaRZP`Su%cX84c_^1`d?qRS~K* z=|g!WM%zFfbTSJ-Cq?+u*+IEomEZ8b3j91g^x3;_mCsL}E7O2KX~BJE=!g+ynA{rp z8c=!Nlvp|u5wF=c0*VvDS;KDdOu9FGE-rqK9zI-Ne{X3y$-P%+&M3o1jf%mJBLL3n zE6e&1hSb=^3E+ncpUcn;RA>(sMQP_Z^|}OV_s*T=&9&>wRNz1O!t*#{{aQwiK_Iwm zp!zri1YDJSbb;-F9^x$zTCqk@{&faXy6ZHYJbtXKdHdb66WEWoPcAd=n?o8l4h*_a zqc1J|uN+zlF3 zJ>DXGU{!$1mbCDY_oR>gT#Y`1U1;MVYU8@KW!aW(WdP;wn>wZ3HGX`#U3uaVSK*73 zP=#3sC^*WrUA|Q}cGZ(oRHZKB{<(AK%7_2;*JTsWE^Z%H?wT~E^ke2!zLE#yOa(>$ zcoxn2r~a;&ax3~2{FP~o`s~32o#nS5t>hOxbN_-eY~;xBym-|BC=MFDV_jj7RyFE& zX=`ojXZ4P<;E{nd^$5RX$By#O7hjfn!v>XmA6l3JvIDzHVX^otk5=21CHq32JbmJL zS-aw+=*j11%`6k9(7OOu_FR5eX^Z0vUg~$9JA;y5_qY1ppaMb>XWu0OJ;)@`Q9c3e zeLJ_7RonIj!TdOgc>?F?P0#4#3*fi*gLliPM^BfD zJUQ*b%9H)Dtz82oYi{B1SC8QC*-BbRb1j$bTj+oK%;~c9jW^3a%DnW@f-+?2Fq+iz zAGjuOX;0-5c}*TRU>JWv+2JD%ystmtefvnBw|wXR{pG(dTM?h*mrp!e?zrO)d;s*c zArAdQ$~SlgYhdN@ETZ{YuSJ`BosWGc?`>PZuDo;TaCvgn=rVo&eX)J=g0d|xe*7+e z`YM79y}9OqHoB|jgZSM6xjw?_lP60jKF!-3z79ICE?QXH$BvB-P+wJyTIe-2240Sw zfbAJv)zKN?0N=hfu%l12W7Vf+0~Txy#U6R()iQYSpaf#o2h~>uS7b8nQD8U%3pnEH zp&pVi?X&a|_@6#?s%!xE>O-9=^DsJc7Ji4ppYL2ojD5`0KHH*?Fmi;xe3Qnxz+d_@ z@S&gmeV}t+`Qy9G$_4I^;4=@t8Qs<%9TS}=U3tv@*S|9hy6z`c`AER_OY}0Zt6Vj@ z=4#or;mh*=mzD01%$QQzCrmDb&W|sZ~Zi^qI-nI^TUjEYmvM;2$?Pvm_)CBZu!@RE#sLir(j~zQ& z{(0GQilu*wNaaSq?}eB>c@Lz1+o1_zXn?+M_XJ$$sJH+|B1FetwG$fDBL-Yz55 zYzA=9U($}ilywY9+hgCLopjD-)7*3H;j+o>&wws5c(#Av-m(pUtfNvOfB%pF?SC(? zzV>%zEOIN@=vDa5??3nBZxU#Lmf=I`(c-sC7X=32We0=Z58ipVY$f0z-R91jT_!O& z>WfpLfM<^cI!1=53|bjb<_!b$j921lr4FuR*i6;Cz*2+HP~Iy)URj2Z9+gfSIdW7P zh=E9ij9!XS=PVN_gc)44gs5>4Bb*4H^=J?^JpD0_CoycxmMtqC+jo??3+9*h_I8}m zJIXC6L9t4k#Yx6%1c%@M-k~uRzm7e7${WA?J*j)Ql!qRExC|RQv@2R?d#m79L*(xW zpGuE*C=|`+iw^uRoWBqnDPZ1Lh_-CoR#t!XQJFn|e!1tKdon8(I&$B`2x!Xt48JRU zBYQdyIB^`oLtJbl&soMu_NmjS%i8tp%l7Tt%cD;|Std`K)S88&f20QGC5iOUTPaX* z&Vt%@m67)wLu6gjT&Z$a+Q%-n002M$NklQmaP0(gGc*-y&J=Pu(PvFnLfSDn=`lE zK43tUjQj|4HBzb408XI6Res^@N3e< z2?=yLLz)2w@I8B|MC}9V;f^HALkB09Dk#c31 zW>!_WG`fpN#EUxQ2P3sARh4Wu*P>3Nwkmk>KYQ+M`Rw!0%Z9aU%Y;dj%eZml%AFXW z+ir6hX2WrYP|S63ilYx+3BGVw_#WL8*r0bn$a7xj*jx-2OpF%;5~2NJkr(s+m-20 z`PRXov+$OeClm38CYh~Wtn5c&!>Hv4PPjAx$Cv~E5W%A_)~zeMckImC zN%?)+w7V0yQ`bhP-~dD)KnEQp`&4SFXDaU1F_8WV5YX1l%E6br=+jR=Syj%VZ$^w5 zS!Ufcvy2}zCIbKm3D*M(;wkF<;V(6&&e{jSw{7+oQQoCx)1Nou`tN$K$$+oJ7|<_1E{YVpW&1obobwNDOW_G6Pi zM+YA`&{=N7*SHtHnL-fXS#SqHH6sIjKsMcV!#O}(f10*rV8k_bjTt0cu-B{UQ{O(- zK6Wgyr<9R*j)-$?puxeBslf&sdV!m|(Zku#40>sge50(UU6#>y)3>M3o+)e51?yI? zCU7*ROqe*4px~%-I}<-uj-+HgT4c_T>pHV_Pvo0Jo}q4QJp#|H2KKqLXUn|%=HV|5 z3l7p%c;YILnH{4&(|^)8l9$y9-nXnX(WYQ4&(4U7o9)>{Q1cxo#Rd);Tpqap{xXCC zqZ3rU>6`AzPeOc=Bcatcrx&^!Q@>R7)i;%PE)zU+=4{zaX788S);YkQ$-v0KxANzq zJZ136clEj%J;IUZZtknS6UXohGOW*FTMW1zgD!g+ylmdIDM7qN$kX_7Z&D8rrjLDs}OJ^)~(b8L@1 z!gc#XJmX{XJry?Bz}@GLGO6_Sh7DyKv{BaYoj144g69XIYck*mZVzB+Pb;nDJ`TYF zOaAuon%}Ln@yFD49lLjzk3amVoIoesIbvj)3}3dlwZ#_*Jn`gTGJ&Cy{9=EFPw0cj zehE|hL!8v(;PHEcI2#z>e6(UYlZ1oH#EFy2xUu8n$4f(X4aTDS2dM@8f_zZUAA8>x zMNWOj4|T|+XW;XXR<0~xtXW;|d+bRJ z_K|#V`}8|LW_)1V?tkC`e7)hZYu-~&+lK0Qwe&r-5>|6G{p;Dod$H{l(ME3Hv7@~G z$3K?w(ELGoUfbj$KQxEWm^I|2f%LT>tid+bx@uq`18?dPzLTma39fzp_19$^did!V zUMTlWpTScseWLGpu!{%eF`o%uJg*L@Sqh93w2jQ09cYXAHM#akH1NvAzUF9-R7>9p{Em=W!HQVt7`p zSV5LV8-hNuv~eDcfiUGrhEuR)*e0W)ndwnb{il+NGK9%2C!;BN3WbdD<~whfokZpy zc<`Yze*8ET%HRYVjD%%?5#|MsZ4UuF|J#Rx>}Na9|F3`jtE|a_*R>@kEy2V-N>`Me?IRmc;31Tc@;AMbB#pYpKlkNkYI1{wP zNSuy%0wEaJ1_#Ufk?$2u0}aPdoGhPywx(>O4bMFHT$z6N-D#8004mSgR|;Zvc56zz zcnd>#(!k#eWNp(;NuND@_(<8kr=x7Z01YDe@&thl9Ys@ljeG(ivktxCp>Cvv*FZxl zz07C;rjGMvK3A*<9K2SYx$fm8&i~GxJIf9RU56O>&bap;l;8v94*FXIlkAkx07DCI z{!W@d*J4n?^auLnD*Sm3xOF}L^^69cmCx3!DTgr1uKSz|-S5Uxx3A)ON=KS&zp9)< z19;Ex`AwVb)AY61C@(P`^lI3@geEILT#oZLpiCG)p25r5G8`I7>jWBXGq9~g8E66^ zIwaCXr7F$+tz**|P@Q`X+s7+cmG$)N)Twtzo<=fw(NPR9hzrlSvE((DJ%M#gxzx1Zq4o6Od!m>+xe(K4Do&48_C&?(qew$jMJ1~}4|n$e&P(Ea=& z3p%{4c*sjS_6FA8dh1Uy_zRKOJ8r+8*(A@|2h!2~@zy!6s*Wx1%E}c=-WE;XwTd zes^aLpef&njvOvK34DFMk(m+N^WucI^rLlE*$eYqUMp)huXDSQ*`JKQ4 z4qEm{p}jh|E0!-WXBpIuBB(Zx^uoy##@9dtI_}0mgS1H<*5g0m(hQrBezneAM060Ym$3H@api`rS7>IWTG) zO*S7hUdpn%pgR6FRn>ZgZM*V`y{r0M{M9qkN7+>`sN*-`{D1i2iZYY_)PCHCj!ba6 z)o1?#&wuBFy3YPT!+`VN?9VE+L3 ze94j`^#Wx;s18ISo127P!bTiMo*ZE4h&r486!v3mTU#=|vf(Ghl*-!d8>t-{bD`_Z zce&P&o7QPxPGCO_PHo!wO=gm(-94?`&%kTQ9fJ}8aX6=(nt`ERGPq&8Gbrb}eexXv z17Rw^26_!L7<5nub~9jH`N^sTN^WDqWG;L&W7;%Q?R%C>4EhW-(CRMSn>I9OZslm& zU_I)f?mRC&zh*GH;=|?X$MF*;lpMCmid2rF< zav#B|8uU&N1=q$elI{tVfWJ!w4K7+r+~pC^wndy1STj%!zw0ll)0C&FlP8H*^i0}q z+w(7%Q(usyjxO5s&B3J~>oAMt9D};;yLOdt&;@(;>?tGK?kY4OZEG=MC@3vb95HzX$-cvX{t3DP+ z9h3tQJga?`?tDZ7KCzBW5^#1vw+tP5{OFM~a^&bTb0*nSiF5c7~qF ztbUq2r5@E!Q*LaBy2d)KLtSH_;q&!hl=t3yrwk!beK$VS1Z2tqyL_A!d+ES;Y2U~# z)#V7ze2ZKGHuwj=6REw*DJDAKXQFd0_VvMs9%eFcVzMRr5j>R+Hah-3-z4kbS-iN*AM>7NYm@0)=}H;#y?&M-uk(sUq?Lng zD#&>={>B@>|9!ce$-E^C7iLVQtchPJ0$`sr0IFW}y81+XtlvX_%y!sL`@rjF-a0nZ zetd(Df8mu^$~=No9v9(%VOu`FF3&nv(;oVKXhR+HhyiQsRn{zP|C>>LgrHQ%p1tV# z4VhSR{GmUlt#8H$;+-Wm;Hr(%t_ee0#kb~qmDL(RcH@7u%FdAGxMl0MvJpLeoHiUe zdaN9xu3!F7|6_US#h1!$qsh&8&MqAZFe~!&Gd_@AsPUgX+>|S8pMWE6G9wH#bthWu zu?K>FjIbQsyRW!T^?qj8CnM-CIk*7PWjWIV;nFa%j4Vh0R6zxpj2XsbLna2z&VH|A zP`B#ik4xK_F>w^fa5m83Aydjso;5r&l8mk(*m<&foGan-Pa)C4vYcsiI*Px0^N(da zZCJeIktnEvz*Yh2L^!+a`Xe%lEAFW^pj+Sm@~J9kAmWgCZ5{Qd2H4ZpL;yZ7u)X29)aG(3yp9L<2&dn!t4-V?aJ z1V$fRzC?;D%-7RRwh(p|cV2f!oz8S68p?GYBk|tsj1)@n1Tz7%@4K%&Of*;CJV&;J zd}+(woxCUbxDH<@%xfwZX>=JH{0KZcE1M!3)X?G4LD<7gngg%H(4{}=v~%X&SEdnY zkQUCMHhr)1i*n_<3X1Lw4KnBjXXz|0r3*yFVZJ47`z3w4eCd0oAAz=s6DMT0YvhO# z=|kyUX)QgqhdLv)o3pT#(?`Wn$fFtGPro-%{R+=qPmYT>tdim zXUnztkxTIKuv_ID9SeB_@bqEj9eFmKNMC3ygs<${N8fDSQeOY{uVdIACvZ226nN>K zKEsKzT!IOlTV|6pbi#p1^q-3SZ9q$>M`uMNbODFQS)9uRwe8mN@ofs)T0p3ayMR$&+Sd?C#i|86#(n z#!i@69w*2%g2A*7Rg+pTfY3cp^NspoksLy#ViiTXYG2cy9_V*<@PWgJ%BKu0c5L1f z$8jEx;+)yDv#Fg9w)`ls$;W{MMEkbUyIvRn=C^}-`>QXyN}auB`?j+5{rAhar%so< zaB^ocvp#X`*w~Ed;1+Bt9-axtwRin1U2+e+Q*Y{KgE8=T?}s(aFn;*{Qf9kGlqtxm zPUukduy`q-@>TR?3$FM{4YF%gsFa`&$<0b}O zeaJ*PMKE?FnRaG0oIHM_7-)E4!Tn_rODexRe=&B#B_1kkGvN$0WEPEfYlrkPoXk)+ znkC_q59`ti?Zsyg*+(C*TFLDC9+qj|R_4r|OEBPWX4Siw?+6;gIH{w-{l;_C4$n`bk;CEbR1|ETJM3!!^gZ(g#iuXwy8pXfA5GQvY;)zu`Jx6Hqenco-f0M=}nM zFhF|j(Z|Zz_V(x*vlA3_^+s$e_^7u%{9Oa@6}mhxpNnt&J$xCFP-gVUUjNN+%ANQc zk7J*PGkEL)j~QUN#@foJ z-xKwKPiX5ZuG&-rA=p*#Imm_Csip=ky3_^r*beP_lhNS7OTX`h7hf#X;*UAWQwMR{ zQDrFTN>u9fzjX7+JUusk<1YSy4Uu3gl2%d0!kFDsTWE2rR{kt|u6J&TNL_};w}PBUw$JOUnSA&Y!Kph(+*zhipFyBuJbW`OdQw<5kfB9x z(YTVEUmoym{tBCxwb}#mu=Tx@A+(f9)UTk=g9{gy$>8mh$6L_DnIwWP^0~COf1~f= z8Ay`;^SXWEKl?Ydqpe&HkL^2np!^Qp<$lz@XMe6_=j@u+RX9G!ynNlz>1$|-|^ALDhm~U<)Oxg zD9dh|f11p)&)2Uj>#^T2z4ltU51+#_F3Xd@^m9GrIbkVFbz;?fbzGtz*48O+O}4dT zn}hf?2CB`t>q+*=)6YIzCX5~1#Tzfrj7w;f=BlCHTnWkC%xPCX@skV9f7`oVk9?AW1hBoLKVzui*(5vje9D8Zc~w z$dY)RK*mt^XmAF#5xzWNHY%0inl_h<7?D!4UX0yUjKD@62r5E z!L%t?=`Y%u$R=m0Yke_f1|NXu?+A^6Tl7x{@Kd36gG>kPpML&X*~={TORv6GW)RI) zS-8ecELCjcBJL^&aZNqkwVVyfpbrD8QnM+x-N8v_q&hmv+Rr{OgGLN5&p-Ez3`*T7 z%#G}%c~9W<@FA4Fuhz638pZ?~=mZCK&V0L`Kh8O{G0Mv(#es%mz{fa{_GlO!2s+F7>8e!;to4WA=d*Tt zI?kxHFy%`c7|qu}cPUfu$v1$?eL5reysx748M7n2zMeqC2XFtW^uZCCIC)ai)XnyA zpkM@D+WLue1=LD&2mZhUcO3|wO#9m!t;2fzVgxSW41Ms?hvoB+KE^oA&2pF#I25-s zyI^2MqXQ~Hg>SB6L`hjPfTCg4V#7+n9mTCVq=g?9dJHNsgENWy0<*_$YZ3yli6fH z0o#=K8ic9zOyB~zIXFkwY#fJWy8;d1<}3G(!|yKB`s|Z6<(U^>E%Rs3WflZy^)i75 z8l2Qx`9z+~r^|()Fi7xC zmbiL}S))1Y`)D<@nA)m1v92{bV4a^65gds~)HOc*mJI>6Lg z%O((zK1>b%0Ym@Ell5EGrL|qs$ere$c`#VIoWZmy-e&PkK*tYefRQCr*aG18((f?@Mv(Y2{eRP@?`xZo`31E zUiD>@#bQ70+Pf!?qBitV?8jXUkZhN_#u=^#@92QYyR0cypow(h6SzFDQy!-k9jSxt z60`Np=oqMe7~GdIgM15ktKa`JhJOj`dac1jp0J*?XU=4az-lH5cJ16ze)-@2W0q!s z5N~#A5@{kFAu5z4IUlBQQWz!qpYKEZ)N$xE6fz# z)z(%n6Lixbs5~ym)lV3OAC*Hnx4vf(Lm4Hx8?bv3j6TKW$T!%IE%5tEY{`u2GYM2b zSO(p8d$|aF5XtfmZHAkN>E1hlseMrSTU{({Gwp|4hqrpJKMFw6lP67?;1COW{&-r!zPwi!K=NtXoZ$SUpMpM1tX3rDt*+l%M84Qlv z2v9jlbo06l0Khk|0R^0!0cV+tJOXdnf6B1*RyM3zzU)QcUP4c<0QXOpFV9k;slXr3 z?5?&enJLKIjd*r_7sczSU;oZ^rPqLrfycw7+5eV-%fUT+n6-Zz=YL#gN!4=+N(0}4 zwR{vg0q2S%{RhtKNNKN($?M+B9tQljyfgQ|`qi(>$hNlf6g)qSB@_nMyIsS_xXer` zZLStVysAD_V`hK|)_Og*r1Fn8r3MEK`nk8qx-Y+C8Sy*i*;ii9#E)-sk+}#cB<;A=if->r;(3n5L zGPLD;WGr{;b^F;5JkSIh41R6hu`^i*!`q?F6Hk`WBSvQSS9+?;1EJMlD3$O?GVq{? zWg6QnFKT-eOhKO>h@hblM#2?Km!?Ha~bqboiqvlXXzZY`cWAL-|pVL7Q!skXNrKbJ`}-@FC(!Wl;w3CEGte+7naS}TDH@$EZ`0TEvvMG?=o{`g z{4Z#M>nD28J!d*Q50qd1_Vr{+Ik}-9X{Lt$n$PKbHF`L9NhCSKf8m>2Povws9-ozG zeQuM11_Bv#AGp6fwrFwbk4<+V?;*T8KKS!MLj2h9dG!fuy_G)Ace4&$y8YR@waNB) z`5*qFEWqdRa9k$uij#-!Fv!^i8mv>lQCJ2Vyw@y2SGPI-I7pVJ%W%IYbFCM_fnWUM z`7(j=#zC8WZ)1|+G25?G%!9WB4UU(v{`FZ~Nn*B7(^mFDp6q%yor?@jcfpn(B~9c?sTrc`m%K{)jYTPBwg`Jn=|tW4&ifH>g21tWj@TZLc$#pM61~ff?Q>UwW}DzW;&N+F%{~8s!tVv}goV zC8c0$I1(VRNe$s`9IaE4s4NULtR%>@YtO#&>Mws;W=@?(_tij6NWpVA(!%elOQS@c z9@Z7wLk|^$_#2TwK%{lYjvZw!j_5FEF<&B3G716wj)6;}#K7)OUEO*9CXE2bNLADg z8YrO75^0DuKtDof4UYi`&#s9wC2A9beu_5CCne25gBcCyaU!olJB>r$C_o=%hMM0R z3mtlpmrdCakAO}$0tWu3E$$DYaWE44G3(y;@9HQ62v$9?@L?Rq>FIBSKQuV)7hj!b z6_GUXpY)aPsl&c#-IF$^TkF6WXn2n-n?AH<;*`l{`iyBY5b{I@_cs_E9&hmqIASzv zUs{JUWIxDf_BRoF;C}~x?-KxYK#RXY|Ac)MTq`+s>eModD7S+nnMO9oQ_M&WA>gPi3)H}YgD;JM#>PP`kF{`? z58YG&e`dBp?hqLb8n(~Ze$KPq7#O`=rZV7lS;p0i1{$C_?G6o~gTacc zeB^T-plaN$r|LCznGT4~k`eTdUAtJXzNKttkTGt`)bixxPn7F{20|7seAT(~zW;LA z7Qy-hUJ<^*J2QBC(4X!tV~}Jm&el%S0qs5agPA*PHqH=B+X!;lFO9qhjG%xMS_3ly zw^kYXQe4ze$!MUDTsqmUU1nUn?hKsqSm)@=BE-ASxou8I*NnQq4f<5aol)Ly(ZUE~fhrTsVk1vxik!v?at8Ko26hYKmq!RR zn9W7LDzT zoVnQiZU!+o;m1iXLmy|c?=Xfv3s#Eah&SVLyx%c!T|>+a|%_gAnc zo!aoEztq3zaOK~nFgG)}bTdl>4KAH9qrpJKy!rQ)nJg>mL)$Kqads0hmC>$1gRol2 z{)@J7A+kY(Z-F0~ZAp6lAK@97U`)Py8p~qtDP!8&g0tBk^2ANBc-6K%Z#!DLF-ujb z+cNTb4T3Wu1#WKw^;e+%GBV;;Fqob>dsgg+OYa7-oJYPe{bj@_CA6T>7^f#r(`tvG;q05JsblI^5XSR9Yg+T;C9Oo=c361f!x4%?{yJjFnz^FSwi zX06Ne#}{9IIm?sfH+SZ5^hZz$F)&Dc7*|U6$KW3KZ7WOHV=ZCl7 z75ia^slK%{!d)<|z+do|^iCfDSsdd(&_^EX8Uqamh>jdTMu22}*~Z{Y8$AcQEWn01 zDE$^$y9pZfQs2qr>P!Bq&qH(iM)|BVTCanA26Zky&<+}CScX4y^2kv(fow~lVG4e{ zfrbm`%n-uvYq!B&AFsYyfQ@Ittvftto#_Y8%90qUdu}0kCNA2KKa!O^`mVMzgFu7( zTDixMd}yG-Afrp$kvCVqMIE%0!catGB2%pBx z@>I3~eF7v6ryZ!Am_OmwMvl*tpXCiejlX*`NC`m>G<36zoEo^JP1UrH8 zzkV#x*eUDIxDQ%d_XYNnal^(n1lC;U`znFz`{&FFj*d+l+ZH>)v-Y3(_}jKOy1_nD zkGZFjKBzX{K0C<1QwFNPAVa7d_S6g^C&#smW>aLZAKDsOk^0i1b@p3y7IjHWdDU?$ zm6rkNbLGik?^leA-2+e`;r!{d<;mAxF3&vmOu6;0(V@HJ7?_gh0$c+9Y>)qRph1R- z=<}r#y)vN&R)>WiE}J3fG6D_9h!PD&0PiF6G>J}gSbv#L>juMSP$vvKkL%5+ev{dS zYi-s8vtXcm;`Dq^rx|GY=!0dYZR{8V4O7WzaOs2@4OZ_v-55C zjn>P&8Q^ox`wChg45x2Dc;ioRCRp;&qD4tva))M}XqDnM0u4Zc7er8OD~_rBhCjBa z>!3&k9bC3C05F0+Xz-x&gnToXmR6 z9i(Ny@*05#W?gKjG`Efl3%u=LgvEd2rqXZ_WIwtgpGra8brMyMM*dZR+qQ2j>u^Lz zj2n{~so@NGFLTdX%&dC_FSkodS|d0KTcOO(_|#E@4IrYxLKkO641Q(vAq3rwhLb3( zx%2NY4?p-oHiLARV-SkbarW#geO#m6@EoATJwX|azV6ER(ua2FFvh{B9eZ}OAt8hH zeLL8bgfzE@7B4FI&LAzAXD-qw4%Sutjl$O%sOiF@39i)9rEFC)tv+&wS6Ufpc%O9X zzP(x*4R;$17#aFHh_<}6XaZG%#oc;vkGd_Bc1S0_%RkQ6eGh#NG^|?sJ~L9Y%iXNA zHC_F7oM?GQC(Yfnewky5jG^(Ec>I;F1ZQ08_JaK zbi#Ght|`yb3Hrr81v?oh*j9}B9oWhYm2vOt5Ab8!Q2W9Gh`gl}yK&3b@>^yXCWE&T z^dW-=@|<{p8$6=SI)ml4?5+%+(#bZ+x6J^ZT0<9SmZXj8cuk<;Q2lEyXJ@yu>~P z6Hrc+OGX3zdZjvPzV+cp2!D;u7@f^=;4kj-M&uSc$w%rCH@{S#I*`#VTWUtbxG8s+ zCkgTlXRm;|bfO6~$a+!|y0*AQ{L>G%r*+Tz+?-5D#WzE^p_I#c+ze9wn8n7bvso|M zk3g_NLt#XhND^owC=Ydl4y}A;U?B=W#kmj2Ka76GWQG zz9axBSK&p=>Hsz}V_*ASUJ{n@qZ_#9p<`i}^zYB>?2vJTM<3#d4kN>3GHc4+=f@c- zb*Mqj@T4>WuKFeQ0Y|=&CXr|A7guX=_EH+U+{iso-eT#*7G^RZTDUNQhC%S8@63)f zM4yRU@Z;HvB2X%-T&YJ$CjIC^n091-UgC&LiaOR zH_dw;fxCfhX8Y<(FPG8n?F8+3Rl;^2*>l!LQ;9$zl7Dm?oqI;VACpQIOojBC*L1A^=ykTEfx z0LCQhOGn|v?0To9C!lSXX%79!q8i~3NtzqQ2w?aX&f2=SAS4kt=a498D+!u@Y;_Z z1gh=3dl)dzBb)M8^s^a4-LMVr(V+hon<{*OhZLM$#;50Cz)o3GM=M`uR9lbs!=-np zsAqIrJGRL^ekO#bW;E0w1N4<9;)!ij$LJs241Ng!fwwYBk;t!o-w%HG_iF6NTj*f- zB5}WyvE#-iGugIiKkPgGa%t-EQ{EOvWHdJ^LpgcXj12c^c!wbSdi24fM;>K4%#=)Y zx^zN6M*i@S-)kS(f35oDePG28_daygZpbtGQu;vqIy=j6z}>x?o?&^leX1XB-}tOY zV_PFj!fW-VwpGl#d}3hxyUEm39ye~?QhxjE*E9L>1WUu+;In2&S&|Phf_IuNY_C^a zs?KR-+CZDj9qdoby9~+Y)t?b)*uWU)73{|X0}VW*4wL8QOUpY}6ertn8~jKE@izO( z@r;2zZJ+lHROr)m?B0_Mp{taA;e{8&GYxEU2wml8kXCm}F54sBq^D0_nWAv{fARmA7Nm8TkYHQ1mvSY>&Xds{=)5s7qoy?@OqQGnD8|F}mj3Ub* z3YQFG=SC6Y=$>Tl%$x7LmG#F9ST{C_lq=V)o1U88_i4Kf$DfK@#3x_FBl%X*Zr!i< z9MDinoUC8{>enpC7+9VlVrihknKBJG4T!OKFdo6d_$z!yY7-;@l)~eTgM!$ksX5@% zfi{K687ZT=58&iJKqiU1or_Ks5N(gZfV=I^j1g_|n)m&efk6~Xt4~mX3T;zk|s%&*!Y_FoC;*h{PUeY*gxT!CL3WVKzrtj-0x_RCDwd=}AW*1&& z4~Rho8h%7bjiS35p%Lz02y+03NopTxfNW!9jN(kto^JH7Yj{mF+(eK;qiNdSOa{~s z5plg8-n@n*7=r+hfqWdtIxB@D0jO=DgR*3T5lddLYM{Xs!=6Mw(N^U^$F2k#_U`H^ zZszsSqJ?FKPBisjH6tU+jVLNJ!aB&Nrb-8CE)VA5yYdu%q&0Dzpcx%o))8f0#^yu) ziE2+Gm2NUo?hyc~W1eA*asp zDp#f-dzen{>w|tI^}lal`Vcain(08%tOXq}dCymVN|SEt1Nd0OY+Lq{g8AFuzd^v| zVtMk(CrTSL)LA+qZGfR1$v4s&R;z}e-+niRRXNS97@dq883nJB_t437^PxA{1Hw(t z7UBF4WZksN-u1T{Zv%E3=*HMU^ymZS%NYU>M*hJPIIYkq?D zm_yKGm*G1dS>Xmn9**PCf+7DjZKw_seL(N{aWE_29A>8I8+800@OL0JbJo2C17>y2 zUI1;1K0}5L4ZR~zd5kCcZ%;b7 zmFCK;_1G@I8%Xm~Go$K^moswjqJOubhvzT2KTGe1kdAFyu+QZKj?y3p007ZdSG`#O zT0;Jhd{9na-Mx2Td4r{W^7o^UEXiA3%wn5Y!zIqQqOQJM5gK!$c{ zUxcNM=*(?kFunYPr37OaFavu(&OftwJS!X>!vE-@owC2qqi2p{TR&qq&_IJTu=nsv zRBmPlRz6T(ZEyOQI^`EPY|DTVSum)o+^X;Ul39~Ip(x{qiN3kPjD|12SYK{u(!q?l z5$)~f)mC2vDu>ShN&~uDMj@?=9|H|N@i|O){Te6n8)$Qs3@tMnmOQ+$+`+yc+Ke9= zR2r~$uOA174jQwJls2gALqBMqj0P1b-))0I2j#hA-`?^m{JwV|fd=+Aa5s4OC2keAJ9a8pI! zBH$}@A0-GglCuLZ`K8+K8r%_#cuT1SkKyUS;FP9-hNJK|?!AXV zHU2?&{07^m&l4u;0((-q}{R@^TFI>EYy}qWfY4Nbqi%BQ{!Y5f8J`$fmxk!)&T`Nuo=0Q7f zg_q_4PniA)uE4ThA5gxk-mXhofAjk5A z7ordld*Wh{Y4pA8CSI&}_FC1YK z?$rny*I@>Qp)Xkl7nnhCjqR#cAD0mfL|tEN1l{-8#;L(LG$}?hoXSH+6=oG0l{-pN zW&mb{1q3YTY@oB>?-POcjTvsrG=2gby)Z-44<}W@bg^ z*0qzF#y{XFx(+>_FXuq!|Y32a}KBIP`5+*}Lf zY~Y;x=9f9lGMaKFrct7t6%5<%^9qBGZxl!icWGV+e)bDWO!`sgJDjQGCrKq=yDl4& zJwt@v4G(n&8$}}AstD@_gg&1cLat~18~ma&5MI*MsNWv{mh{%ctg-Fr;H?uxD~GXe z%(SkNC~}vBXqX+yIq>wY5H4NuIaPHA7TnY5q(`Jv?x855ryEN7)(Hn)zIEdGvEytU zIHTOhG64sr@=6R3{Uh!wEP&#CS0yU%Nar3sc>@GW@S-zRz&8pkY?b5gJ$u+3@6&Ps zhtYQ)yGO&cyYJ3(*<+&BKlZU7`{^Px<_XmCymSjcQfK!?)ld)%+Lb$TI^NM4V?p{n5%*tb6;E*M3fm za@BwiU}jBvYIF>W80GKN2W1N3%^0!|UFSx{jEj{C97EcYKm)M7ZbpZ1DEQM`Z)ffP z5+dAg2B{nyBnvMB7vNwOou7X8xAoYLx{kHt9;d6NDeQfpclP3g_m`ITF=LW`c^jK? zinlW-8W-_Q)`#%nd1>V#-5ek)b1@Rs#m%Y@xNqv)DI(A7;m5UKd|4i0(;i>J<&2NU zs#!Ae=VzT3bwW51crCsJwAnVMgSbx82>;RJ$Kad2>DwQ9f8;YyKAo(uYgdrR%NRD! zKN55ZZ}8}k@*~enn7lTVc1foY&imHOZ3n;SFYwlhy?e_JXrnXNHgR%Uykv2Lnyww} z3N+A8=}`j>(xrvB{UL0Bav13KgEvQYH)SKTZ4B!6Q-{1U4S8~{YTfvWjrS<4(N#~W z!|a2KU)8h1%`9(=PnBVv6^+06C{Ly^p2xXRue$^Pxc2tQzp_&U$3cuXSC~F0y56(C zIENz7k-E9>@&#qVS;kM$k+&oN+7Dk*=Bq!&Rec~VKY13YXw1N?)M?2oZB+IxXL_Y| zn9<-q2M)ZpGbr`-lcv?$hJHATmEY_0Ra>PB30%LlPPJbCQlYw7T~L=3^dNB8i9Ed( z{$7mzaJTaW%Alq2)n(#k@XwS_`%Aid)B#uR8_P-yZIbu3Yi0&)LQk#)e;vgI_ss?G zy4!i^OB?^%!zNi=8P+jV-}!p7FQ9z~fuyGx7|lROTCb_z;#}pm%5`J2b&_q9^i>zd ze(>GEzi$DddBOV#Z=Kk^yS{b8!TM8AK2_QoWY{;hQ_|i*-ha`I8(UTfGn7~F6U1>d zNV6rjZQELo;vi0)I-R!`Ehxj-U&)|)0>`w^j0R=N2@VI29*wUdpF)h<*ZB_LLVF_! z&N6<^Ea`rNvbQj+JC6y184TKem9v{?({Wu|uR;7@YfIYU9|~kMNbuRXX)^<__mj?T zKz1UNC!Z%G)o{4`T&fcdT;_XM1Xu9%H3B!kgvW1S(20sA zI@q(n)jO?w-d9g@7!WgXXMk$Wr=OH147%=PVAKN~@(M?aniVVE9mx1vQ3qD?eF6=l z%s+$m+P&1xGx{RpZV=-TKGT<9Z6KxmM0uPbz8eQNaxFc&K0@Nz3K8sEec%-jZ&{ax zgzsjM`#TS?htTfq^)r;g=t2T(W>3`#u)4e>bOJx0x86q2MklxE;5GY2ntNTGjxyMC z;%5)=m5<5rjY|*=G?-~<#(`Np+R^|Ik`+IH>+9)rdQMY-Y2V7T`cGyGe*Dpg*^g_) z$dL)GjTg6NnTOR{dM>ROW%Emw+Ri;((U$k zUynQ_s7BtwEwtc@wDIuVklpi*`ak^yjm)NWkA~&EnsdXK>j^kMm_4)1)^=H8f`QPd zYa9SB;%9rLajmn_xlFj?-&l{nP?e1mf9&1&-WR3v$l}GkvXlS`?Nrw6d&|pz>OkR& z8-OGCk$t{fUY#7i1Wq&QAzlus-{kd{29LB)W;Dnf2?p_;-=&ei^?$8PUrZbg9_lkF z6Uwo5h_^P~CCCN?Tz=pN*N>5nVKCMSO#91>YqN-iX**~}=wUl;LVQPPrSE1tB3JN? z@YMq+PoB#1JLSox(N6(?!uWA1E507KGvgbcS5`d?yh)OpRmd_7aF8#}{Pe9wR(={C z?k3JVIy%S-KS8kJXgNTJ)(ije-<0Q`{{@*bZJ|3{9GE=B+0W1SKz1d||G&cr{Y237 ztqPLvG!n}j0hpD?E!)H^+ukSrvJ*w(JFrJFDDriDeQ+jFnK7Ks8mmYoC;iVEGRqMh zGFxLHtWRc_fn2k93E}yQ*|c>;6^Ee!+uGanE^(bk51B{HlII@zZ83&1O`9ACRwze#DP!Q^%u{viI4}(>Vh1Oz?0Q{G1;(9P0i~R=< zlx55y4;(lshDYaI!=d5KPRf+iArxoZVxU0<hi9q@sWwtT6aAQK> z;Xa)ddxIy^vT1wT%x{HJ82%PUC4{uEO49Z?U@!`883$hOsP2rHvkZ?s_E_F+pTRD| z7EXW|DjS_*X{n;n!BiL>05tVQ{G~r2up25ko>NG;BVzb=!8Fl~s|Sw)VEVCXiWD6|`?m zv5cR_AU6G`p^z9l+tMw;9-J26grUN9Q2srR;93TCTQ_}^z>mvpu$CLI~vTi(I0 zo1OYSu)){%hhD%Je|bP-t*q`p&{_8E*;DrI<@ID^$LCdx1Me6}Mh*in+S$mwa#)u% zXy(8hIM+Y6Lz3vg*O@hWOC7nFAj5&q&Nu)%ic?vF;7q6kLHkI$ijy-G9^zK}t|hbZ ze63p@WQwiE8+{FYb>uhD{KB{Avg5Y<e68apj(*gUw#5t#&n~l(&z!w6?RceG zUkNnK&08UEya0$?l4>ZF6r>b(2@($wv1qX(la zGhpR8`BI&(UXkZ@dVE&f*^(^!1$t3N8CDP3PY&{Jle%Qbu8#7_s+Hv)vc6{DGZVah z#cp-9g4}=bkMxl?*5}NQgI+Tl9(&^PG6}kyy{C;3XZznHIvrXyGiCOLcsPrsLn$n0 zz#LRaI(4ab!kJR{B{7)y5Kj6?-hN0-IR_K;_srMBemc1z`M!vG6*b>_}e~c0uPqe zPAMbGfv-OG%^wEt*0FcfBy_;ovF&6E4T-F&L$y19>G-$WBKpd!GUKa74TQTl#)A3x z)eIhVsB{)T>1E+kssykLwTbFpdC-1{KLy>rF7LTSUE%rpXC7ASStvjD7TuGHUNTbfU^Oh`#8kQ$2#Z z*Yd0NC+(}(q@Vq6@W_3541n#zXBxspo3C>nHk1typ}9Pe01_2MXVVb*#G@H}ifi+c z?scH2?&+4L9^1F?D4oz=-*r5J-YJtOB~Yzj;^cz*$Od%b>KE`6N84}vLK7(;ybZ7# zXu!wrWJw8`i07Cn@U^98fckbG`$d~Bf2+I2Po9=O@=#z}cj!ii{s*@Hncv+r%ikNY zA0Mz;v74SwoH!wSi5Z}>&ud^!qKa$&N|v;vl3Kb16|T0*K_B6&ht)M^+-=>wiSftm z(oSG)0CJ}8SC@&eJdr^-w3M#uaNCmm&_!Dz{nYOsW<)nZ1N(Iu{+ROO@?q_VvaDUu z$JMfCVg}rmvDkiKNE_Q{J=_Yttk>@uuW?`8b}@PKA>*5=WUI|5&~6~WiK$RRh6lbd z4367gH}W;xRUT0W#M8Ff7HMg}c+a}+JNIvLjNqHDrVudI-w8jo>_v0|G->LQ#0|db z%lJM97oVw&L&kwxPv~7BML{vgNB+Ito)AE`I7J;kjwJJZpRWZHA}k zzDz8@?0NOFfohj#xD4zZa_i>8dv<(N{)hkhev*8){|i?Q*#r> z&@u3n*>x_2c_^ddbjgOVui3cjlQLvndv=u_LLlQ-lz`Z z^k~xVyzh0H$Mwy=a_-ok?PbRNI%DL(%g%SOWO|_j5+{det{XU;gAf5r!Lx0tD>YSR zuab3R!p}ZhS_X}5&-yMSW2UB?lIJ-NE7Q{ zW-+678%Ezv#8hDJVr?7UI84Q&g3<9bIG_@;-yN{npvniV!$SBST%1Rdb#&}3dv|=z zF5VZ)xS3?Cj2jolW~9`<($V$M&>M|((>rM^?kYX|)nJLsA2hZqM*~3a)1Z>t-Lb2j zIdQD??%R*OL&n7jiMI}c&$v`Xcse(U7*nUp$c+)xw<;`*u4NkMOum!XoW=a|lMl$| zxK>7vomSd`KaiyjI^B7FCUj0F1kZZ--PAz)*S_`57e>QPIaMakGRQTuFMMgal_>Q7 zotw*~d*){MeVwtJ5LDl+A=4PJQ@LW1Dg(hp8ufn49QB!X;#*1N8h^|F&Hb||)zzd0 zAKkU5%wF_R*1{*yfLt1AsA*|9i`EnVfKPzoZ+TPRzM|s33)F(jOh{U{W2bjClA=cQPf^zo9vhT&8rDlwR?V+0!T|&`^VA_V*EH(+(f(WUb-h zGGY4M1izdmau7n{&_B8fy2_9Ci@MT!rK|LoPPQ%b3h&xy>Ktdhc5L0kTPKc|+XvrS z#tR@`!TT9FBclIys6OgC& zb_Pwi1$X5ldYigzhxoZ+pJ(56VEv7J+9umzpn=NRr0%v1de@Nwvw7WyGVj58HLynT zOSzM;V$(Q-YT&E?>;vmePo{6xW!jGx^4#!woi^8ZE?fE@dgc}acMH&wtdpmhI#jzS zza*#;UE^kUtw6&Kaw8AP>t;MiH+5bGA8<x@eJOSk*97vq^nm9&Y7v=W@JYX z?k__}kV!di0yz2V&#DWoKp9e3HhSK+XbTgd2EKf$Zql*0Yh7NUE^>1)?bDHi`{1)4 zWz2Xo4hRMqXlMp>mT!(`U{o7bdEPojwnaX^RG#q}v&uGqwT_J@@8H#wBg3c8kZK!j zyLPA<$mn#}z9nn{^Zj#an9_z%oKP|nlwQ< zzSsDtT9=JS?~3;{I! zW21rZcX5^l+qx&hXeA?gNMooZ@yo~Odp@+U$;=FeX39?rsC))e6E~^@0@($ za&T=GX??E^6S}^{6<%SyyS%mP!}7`_k7i(GrkKm}%w{mKehoeDz}n42)hCTVqb;Sf zRIe;FzJa>bTgr|5G;H0xF`FJPdG2}M3NeEA)=Uj`LF^QDDB~HJia&S-Z~C>;1jIS? z_nJPEF8VZw$==z%eq$LnX$;xD^U6RrwUr;$9ezB-S-uy7x;y?h73d>bKR^T5{_*2| z1CDzMR3F;c!65DX(mrW=88c=~0%6LC&q)V;E^%s}mG#|{qQ+#J%vK#u8^uFE+t(oOT>o{M zj{R_HwLXjE0^2M@_}w;0d-aQcvHIVo)B2X)w;luM_NzK3ldd#M`?2z)73qfs_dggP zTlo-~z_IUW2Mn5LGA@Jel{S^9#6gY9R&THJo$Y2$7SmLIa&50-}$O=ilk2A z`fPk(*^ut;9gQLsrFj>HG1_b%NzEWZ`Q0TljqK78Sd!xn{AXgEZgvK zb56x+ooF&XG|)g@&3(`6WG5iq17i2aFG|llhL-yXRJ*~aV>9XMk?{@XrMtY4w&BOQ znWX-OoujRkNBX(s5WLQ^Ps=G_yHCSeCLO=Whj8=ajazn?|Lgz$Kg-|!{oj?*!`j%x ztJMe9UcSL=u{!$v5=IM z$hB&!7l3*LfBR{KmERtB@)6I&{@@rxL%V?#0dH`*sr0`C1%`9rnsx>9)X8Jz)c(We z3;=oYA@AHKMfSVPm0fNHo!LxQLI;)(=t{mmsjYr!6()hkNoi%nj?c!xzY4^ChCnplC6R1P$fd1T> zljZxfEQPpXlEZrBgVQ$x=DU49dH@5mvluMC_W~Eoeh=~kV5C8JjVCo!j^Y{!oH==< zoH}%-;PMx7@ENxU9eNj85vNa-PCMj=Loqf<@+2So-h3F(qBe5mz%qFFs3<%KMcyY-gr5D7v-QqR;&Oxjr_Dv@64T|?H0i6BY zI)b;n(twkHda*2UKe3P-k5T*>I%aq|ao}*-OTWl{cYypQfcK@cJIA)e^S5!8^~*Sf z$2xbE{U?7Y&S9a)%UPH}I!PbZ+d)3fVV&Y29sKA{$TN`-&clH}bj$<{g>S?#h;gp$ z-nOe8;oeV=iGv2Re)MEH^^+UYU7FbE!uF6iNAelcJ_^2Jp9P3_@#1;<|3tZPbcn=j7|s zRi$Pnj+vy4@4G_r>`Yc&|OV?@qf??g~GC zzxJp6j`)#pYwkr)kzIEyf&mzME0=#0vlcFk(lmGBJBaY8SQY07qhi)-@AA(}T-VqY z$7Q{Nz+w*EE@=(>k*@1|L+{`o15Bf7^@_#u-Lefh`>-$T-T=VG)h@fyZ)O!Iiu`lv zd?o%;QZWZ*sW^7-JM!i(1X3z9cMTP@JKwEZ&hf!3Lzb__1A8*(#82rl5iz^8DE{`U zTRbJN`WyMmdnq@{a)ZjdRwq+fbW7J@TDNv}tX;Y?*1{9=H%nk`+=FqK@w&v1yiEB} z33>4Y6W$8QoVR3paP#vVMj zv1h`?Il1PYcPWz&h{mo4o%-q9Ws5o6d`;>Y=jvL8MM>W9^8dIRp#RF1+mRDuHZwPl z(&ZbCkGNZot4?K6_TILa}=P#64duvtyA#oWI6j{`adgYpV$Cx0Zwf zANwtTTf1(Js8VfrjO=3j*>|hHjj!h{Ou6Cxg}E2Kd)fYhjQqtI#V3WlP#y^r$Mo6p z)ekl5H%voWr%6NG=7n1}am@54_Cc@O8uR&{SABk1t}@#}SN-?-OYb{@%grFfTl-Kx zRjtCg@>T42g^^A`MF&S2zjnnE_NG&L!gn0W`8y|d*-8-cOL^w|>JO%w-xKHJNgY_Z z`cBwHH3*ekAVb&3s-^4y51U3lbIiOy&(fCjs?MY4 z?$tO|swO(0V?Cjnl}o?ICR~}{m;U~TiIKEWqCY-P7)!Ta@~QXwj)&iAijb;Sw`m4w zbcoih{f_Y$#HMYs#W@KV6LmlELY?xx7J=Ttx!42&aw6*2TQ{-!Y1u;=NjXRG~rdw>VzKT%5mG)tb9TRr!@* zltB&U%pwwX->lghh{T_5$keg?y$EEKXtWps-0-403~d1a2PVFmFZdnjSFKi+*saDM z(54g%oYAWbr_TP_Zt=If1K6@Vu)P3=nX^J@{r9UT_m##sFsO24M`XZ83~6ClyJ2nY zv6|_8D#unM!@gOxJn>V3AE~dM%T84}QkDOvFaM>KENHPd^7cpGrWi5l-McH(cB!@# zy<9jM2s!C*bxOaPJw0Z@6s}FUO3R2)=CnhsTd^q?@ptKxUc9$+_j^n|@hbi7T%}x8 zsm=*6_y`6w)J%kgtS6bfo}LR#N+`PqA7a#bujWy@cIQPo7N<@vUA`oi7`xT3&GEjwvPFhJ zpeg0d8tlD|&<>(3#}=+TJ1NGP$GZO~%{Ri{*aAX{c_hrWnH|3ti>=?HN$ORTJtjZb z5KvgTcxfzASa3C{LNXdf_U+QuvBDeui|Y@6x+~7R;Jm0?y&f`#z#88%l;*?#{*$kN zOQ7Kgy!i|?phPY8(7RVimET_S|B>_6zas1MULJuqV;UJXGIh1Ll`(DtDP~DB5=Vw# z#93W zqMS!|efCMrT_c%9w8oKXx=)Lu?2j=syTBM`GmNSkrPHyult{y}6gl;Ck?$UDGZ97( zZBVjs(W3Z(vsbm)y_GZ-7|XTRb-sVmZQndCdgb?PgnwKX4v}}+4DX{ zWOIG)5uY(-O3WeS;nlHKE25`0vq6{4qcfvNmeI6rbeYjvBARAU4XR{DjybzFA4bH5 zt8;h1>F5a)lfd^UqU^b`Dhs2Z;?sD1Z&R4}#l(7=fVje%DX;%TK z$?TV%fwSVJAnJ5vJC3HRPG*3JDD!X(j~%lYh?!FFn?eo2ATES+KKN~J5#akCnWW=y zDeJ&d@AF4-?YGa~*@3n)cxO^sHlOoi3@;_3I~GeADQ!z?HAW(H?qnC{O(AW&#DdKZ5G1yna!RuZF)?A z@4OoBx^o;zHp1v^R<1A}@qy$S;oz9^i*wtE6J{x_Cw17(*Qy5lEVyk*e)VsGT#xtI3oDNB;3_^qG&kY0`cTUoM{ zEdQ5e$Cj{e4aZi8waH#7R;84(r)J9>)6AYQb!(G6VHRpFrTkVUxjrW^T{^zXXBm5m zr_Y!ilV@oHM(oqH9;K|sQEUd3%r1CZMX?u=>@9TaYiY-8GxB7!(RN^CnZ5>_bl_

Yxmos6Y)4lx4nVFU6elL7a(GFYzGkg?B0I6~mhI_Sd> zbL>V$HJY>Uw07OP%&}YsXWbL(TuXB*#xANK#7n{|@2ws%b0$GxJi=>h%^WI+(XU?Z z=!vig`>Z{B(C<1Q>0X)QoUCjp>1FksI8~0hHgV+GJ_{?yUdmPl_q3{=_M#7kTZ?kr z)waO9V@rR9TuheXKE+y;VQzy|7rOn-xtLi}$4XDjk-@W&@zdEm>(z$-G4@=rYDDAF zN-l$i!Y0?9_wkz|CI9D!j0PUWsbh+7*O?`_l*oQQYqmc~qq^hKowBch887vnSwX9c zJQ7k_&s%vPw>v;FSs7$?&?e@b`@_|njLlEzW%O-){K@E8jMLzCAV%qdl+C+!O-IA+ zc{Ywz#=91AtxW_Xvhqxva?3*B@q15Ia@^8d7A#sEgU5`?vHhn#l>~b=Y?%DxI)$N^ zbf?VE3@GD^2kFs=_mD5duQJ1|q3^9jW>1|lGsXiSul=Yx*|Sk2f&@4-!kW3r`%XwW zdO!P*XxEr^*Der-!d%%V56Gw4GX$J1N7j7!;YaB(ILe{Wqz(J*Zz6BxCEj@9UmD%n zFTuZkgU{rJbWVV!^3rWJj&EhmVw!b+z_u%|c5FeZ`Lq6D4$yR-TEcJCn^qGlUkwfm z+rsA1?h$s(hP`U#$+W0Hw9S?P_o-h^i^)r;NAo?J((rj-=+VZM#kNlGnS9E#)p|ZW zDMopfuxDWT*@smOUc%C~E+?Bh^UKLGYQZ*MZQcSo(~zLXwz&aU=chi^R!TW5oWv>X zDPUi~-SebQ6_~Nb+-Pu3C2hB{imy`FPNiTJsxD;ppR$zEvX(jDPXut_e zTP3^C3WXU{C&z?Eh3>0YseH6+-!ZplYLh1&GPdJ6u5>S)e0Vv3X)o`Cj+fru{=^sZ zGt2!44;z)=^`AD-%s!OOtDCiD)UDrBWoN$y`CFL!%nfsnl8p~-n}ie3{^vF&d3QEh z@{wZ-8SMC7jy#;|kUB~0ZjH(;IQS~&U+}DQjA^HhW|fC@uiVf+@gaKEC4I5;2p<9;|ipZddwqjTrZjfr#T<@g=23G6AS zy_E8b?+X(j>I7k{ER!D`OPKH^8qzLH`r-c0=UalKb7swoakB~;Tn`)3M&xeqbgP!X zmrqjP@%9b}UHZ*AY@;XVr7W;#&sQY6=VNnuwZku~U$4-s$}!>K=)thwGpMW zOp5Y)J#*Gpd}qk;_`|)wC(v+y)U8o30}T$Qyes{ega3#A^KS_>s1Sbs4`eAWd~9d< z98qS+?Li#JXZfp+-vKDuhU_&m^SlnBWSLlnG-}EwqCfe3LfrAt!wJ$Jhqa2X-H*%j zk~L~1Rvjq~AB7P#n_Dm3FP@AI^3u^}Mly%ON`;=kg@C@M)Agv2KaSr0-;D$D6FYKD z-Jx`kcfXm&w!|R8rPIl89W(cTLbyfgpUjQ(2$Rbw8XA>QiW*7w6z~Y3A)`i7X|NzV z9DQ^gbl^cW5h3GCxzaj>pUfg7q)=f#Djl6(h09vXX=ExJLuzE%kVLr3sFr~)`FaVR zN~dxh&0F*=I3n5*XlPi!J|}rp%{gb;JoA(ZyobP10m&&Ei7BLDOqHs0*CnUU<9Q`6 zcs76`48@7?ah*nnzv5V@J}*2UpD$S+ht{sn8QZ5)ro4A5c*oGNQD7=;i(mueK>Nak zw=&BlPwYZp60>r`TSrU-#C{1Mj~gEkJlQ)MFjnW2PlVnNjXi+?fk1x0jfS)HDfSiX z9OYzlT!pED27@^jD(+ZxO^5$f_~Nt->HZ%{Gc2amwEv(1@$74TX5D81?5T!H*2=Rr^c5~mWIAcS4YMB%4<4J`5JoHz|pa`bkK9h=ggTCpVL3)<$;5v zXV+umkOL1SOGCvIO3vR3Lwh{PlV9L646UNu+*1+)of=(r}Be3$d4&4_M zzle`G<9XJcMREG+r_$_hAA*j|pFraG>u`)vK8|mLJ?AW*b>6feQoev=<(JSgC}1i1 zu4F6Rrt{H9pT=9S_K$bR4vZ6z?i%NudPZ?%u!5I8z8g2rLK_QTa zDswJ57bV)~!)-O@72f> z_s+F6zR$kDf&j^UX#R6x{}%f1ypv9hR_OVfz{Rps=Oirseg-L#g}#^iiDzLUfBIc< zDGYs287;2n(=5xqxTA&)CWT!!PV3Pl_G{LRfT@*W6*5qs+t-jE!q~A(Iu3|{3-}A& z=e?Doj-8Gl>oob`=@&0Q|6(iwemw~?9ODTdlt3$=-P)-REC(FDEO@j9~ z^S5$$9kiuv^60zrI)!}4K)^6?`uv*%6F)ayaZwyaqrsigLD~cxp=G=4>x8PWOq$5X zZg1Pf+MTmDhz(@TUfbKH;5&oQG+di8BVOwJQhYLVc4j0mz5cp5h&|EHS)DKKc}bhf zNuRyaN#&j;o#hr3zhAM01J-28yhmg|_{3AOe=SOg+Z{n?{r#x&tIh9Afrj!qp3b+t zD*mKV9ih}$+)p`>--n09kN2@W*{z))eDZ0$3C)~%=pmfoabPwe_5>K^N%23N#qUc& zEq^P1Gaw_rnTPbUhQP19mG%_0wh9?PbI$B|oBi|7sdM}Gxi{ZlEaJ#5Fw%&yR4>@f zQu(4h_jB)^YapP`jt0dlwknP{vQJ)|K7D$8I_|UR|H|ue!WpN;5p51ndbH0{VZR_7 zlirmjMIcvtE?>UrucFM%N;hK8g3)KR;#B+_?1eD+o}v$kSEi z8DSu8rfncy^PYMx13QeBd?vj}uZ$-?gp)dU&6>4^Jw`91cRm{*hqv4>&N}5}8noBX z?>n|U=Uff=XuI+fn4^z?Yq1SOoEE`jP?7NWUgFkMy~fe!X>h;SVjB1Eb>eZ+4W6o5 zt!m0`b((8b=J?Iw%`b20Ad8u+VYVZg9)shRyUS;yxyov~%pgGm${R0}tLG zOV@6SPKO>C#~s@}nm27qa)&-3*cfS7d2LS7Ze(takgkmDu!;P;d*g?)wZ0*!u6BGTrL z{m~yy_ih&L>5JfTn4UyrP}=!sf{`(Wf%?<+D|eF~e}RKSm!Mm>=`w>yQ>c9RRF)y* zK994ycSC<5XGqf8`$hh6`$WZ3ZjJlw(-{5E zz$i;Uv$M`Po#ao`v`r1>sPDv{K{EA71{zpX1~wSa`%3>QGoV3(1+GgT)+TV?gI;?+ zKKW)-9Mk&1=+yoQ8dldwpHYPe->Dnyf2RFW7G0#zD9x=#FVA00pT40(qFvWxaCoTSK3NjPk-bB3EN~^hY1ZEw|he-!S;aU5}2Qr=6PT$4WpFli5Cnl|+yY=}>5e zvsWn46z+VcLX{wsu^7vYhkNh_AiVE>rgt1$yGC?9?aXLTG}mKYB!+Zkm7F|eoD?0b zM@A_zi|=`Vqq90*cD3GsaF7udQm=FT(zgp1MK?PCw!xU&r+M>qC^RZ^AE8#hV>50^ z*eXC21TwwHEXp_<-5R$V*sFlkd;qfxbNs?xhv3Uy$hB5LP;Ie$TPZN-)(T za0COZG=ziqR3PwG z(fR1k2*HNg6b{cP_z`|Pu$L)*4RvpxbgDoSNh@(YT=vHe@4t0L>MHH!=Vu_J4%r2pIhmE;xV|uSVxm%oj+8NQLQ6r|oYO#tpQ+fzjVwCKZ^OJ9sn^L4S zzLkH8YW|)KmF`;@%-?SNt1W}^}guP?(pP$JEkk= z4ZJvR%6w?lY74iCSblEsXfv4!>0HNGd^@(rv~>Rgjlb@^?z%9)Z~?U5^Yqj5qzdUv znscwY@+KX2=tuf62vU&yOqVEnL9=HGfp*Zo7gTs?kTDLwp z^+#b`K^Oc+ET*FljHG3Ck(nRYq=Q>H>^k1X=}8)OI%+9vp!d(-doNBs_uM%A@U|Qg z*pjh!B3rdIjV*g$q~i;(C>w>1mt!Y>Sx4#?XvS(2*P;Qn1Q|b`?CuM%yi5g2(>SJm z`|M&~i>d~VEooe%OjrmTVd~|&a$puEe&r+aomDt|&rAI=c`_#)5rlbXz`Jodj!`>K zX)@5@i4Y~)ki^x=(uH%BHw|`{Dqu3u0DtM2iC@>L?wU4jdW;=ACf@1OCw6SwBrX9q zt$~Xj*yVo%DF$jXD8$&Qk4iY@J{j}@K8BBlb@CkVtJ^gGZ7|sPFZaiXTQ|k8PCG5m zAUI{9I*ob04|itSZ+YhKb{*%Nbjn=KxNd>xHZWfeQIDytfL<%lsXWSHkE?v+t^V=A zvo9sA?!Wz}=-#DsR6!1yd9}(;IjpYQiM42$S~c+lGQ!W)7oKt?b#CT;ogphJ#er-2 zoB+&YPdpI=#*d35YSoF$Z@4ZFLk?^Aq`u@k$&eBUzZVyYPyW#sOta>$g<9y^xr>;xWfYi+!4t;jNQ+_xs9MVQ3OST2zh;Uvaw)T>MsD0zSxU zRG=JRK2}amhbBKA|5?2K`de}0={@3zL;o3Q5I4$zv_+YduvFLio-k1NTS=wkYT(oP zt3nJ6`?<$^PnhsU3>!5n18le4dJFbgt8^IUbLmf6CVdr+P>X6Qc|{)f{X*6hx;+yc z(3Js8tNF&0P|_xUcI3!7kz=4QKkvNQ2btiNwkWt1);g%pRVT|i{)mk)zm}?#N&)7q zK4P6_$L)zQbU1;vzx_SFV7%Kdx*$#?Xj+TyL*IdO<%=>^8^C8PA=2&!;@TfsJp>HI zjTv7PN@bY0UHirFv>7v_U%yx4g}2|yO2@z7`P=AxWc#Q_a>Fg#2JXIJvo5PXU9Z1M zdBA$Kx3tl=M|O(wEg;u@@;>i`?(?&c39Q}u``=Twwj|Ez(lO2;h<^~(FzUw**yuS| zU?5!NG1sH5p?;8$@^9XgexxIvX(j<)HYaR`jrkyM|Jy_G>h95vq*8|t9Wr64{VQG# zFgl*ZBK>5Lkt2aXFlOwB@#?cr#lYE1qF2{r;>;c=#@>w@ zF&Cmq452Q|G@_5y2cC^Urpf) zL+X@{7&A70cijzPvEJ1u9Y>%6r)A7oI_juA16M=EXre;ZOXgEiDtKLvhL?t$ zf5=2Oyz|H__x>2IvTSK0Q8^Xc%K3}p1cCu=%%$XA(VDSq7XjX& zcAdO;8JsFgw#!>-GpU3rT$3SL0iOs*x_9b;i7><*o9K2I3CjHWfGb5)Z3T5Q8u# zF1_Q9*qbqWU3NvBaNG&$l)6`V{aPCHz_*U0(o}#etmQC+3g6>QuO!IjdB2O7eVwn% ztEhw>%_)}AbK&E0pT@|s??;D2kI3Tz?arH30L;rMzs8e#M%-x#D8$Q_D~wM0C>=3q zHE9aIa4s55rHt2Dl+SiQZ6P{Ob8x3^Vl>rF|Mkfmc~mtV6z4Om^GI`16iFRzTIU< zqYrq}?&b25IFJtgy?ddz0+;XC^BuUt@sxAUWv@n!DCyom4c}q!4T{(9e>g^NS{Zj= zc1fJh`OXb7&|Rn1L2KY6gB9t>f-?<96~2y!PDODq6ea7BW|eUn1ZgA1q|bnmaptOgcP;Co#d76QSY|e|Zyd2vAp>k1NlCas62WP1Nv10n$?@Ph^u;CK%jw>9ta9*2dF31fznAjw~XtvPN=w37V<~RUmXnP zoNzH)XhXD-ICL*R^-R1udusgVob%&?)6a;;$O36hyTW6RZT4D;wYYskheQ4}pkOfC z?5NI)TS%3g+wq=RuN??X&YCwbUg9kIKlgqi*Z=oBZjBSsA7)_1r^jF#?A0~Zo=MXZ z+V_3eB)mMeXAAe=B<(V;K}UlD%KFbHPKbXz@^HNT(U|DD-+^)Auday0ushs_Ax?Ep z)JaxmXlF^|rNEDJQ|C(jrVivY|4tpidW6l;F(1Tb1lRZCvvbb7FuHd?E{{$WKgl2J z3}CAa(XNngd^m3}ohI!WzQTJ2ucloEU75{$bI9QM$1_jHnH{=tEaR~p<9B#eWgFOL z9Acd-?~%3zbC++VNAD+{q%+Mt)rr0?@JbUs;JOTcnLy&_MUD?&$rg$p#~qhP9(yW| zm0ZqMdX~Oi=OXOWZ;(H0xv!N`!pJH$0}opP&K3}B6<7uMT3Nk-Aj$OU)2PT8L*n6R zl3^{V%Y)z{>H@AB@XPr6MqWx!ZPu$2)^1rg73c*|}+=>d;#aTTy{j<;G zcemXh?a+JGai-;cb&=VAf8(0Xt_on2Rq7)hIO*FpsLKp&iVsg?lea#mV(Lw3^3f4P zTiGeLk1fDbj1~M*2yQcHKTe~5{g54)_E%@{jJqB!YnH^c;9tdU25=dE8k(!^jxzl zseA?+UOqM&;! zZQ)6AY_dRLSwSIgq%)7PevjnC&42lG9NoBSbUFUGXh)S$qXrEUp86>zJ6Jo&tH7VZ zY2*ZB3mf@U+^Tmo5y)$k05j*zjlS>nkKy3<{L3y+IgtJbu+hel7q!QPySAl#=)99Q zc`bgG5k-Y44ma@Im8PE_vpHqT6cRI^M8DTxCqUgSj>G0SV8518zkYpSy+dw|6}OJ< z(iuF*5flSbfa z$CBQXzQL6^)%Nv$Z|V5bRpG-GO@oEgmy^EYWRUmb&1avEvJD!=_1Fh(4mj}VY7Bpz zdIR|QTj6SRR=3;B4_l!TX-65kJ+`ZI-9UrzaofkJ_ur3~9(y=mpS>`yJ+)_CLEvt$ z1`V@WS~L8D>CdZxI-(u~)-5>#Vb)ZUX`ht`j_Huc5$L*?;!+ zzYjEsT_FhL6&KLse?gi6La5CoQZ<5RkjoMFHMUhW?A>H9f&yE}#*&2xq4@x?W@imF z{P8z8#@CE;;i)HYGZe|k@;!-D!&^$07|LO=m*rO5ZGo8S&aM#9Y1PQmLElb6!}ovE z5P>KcFo!po%WofjI8JWdB)Xq|I$5a>G=r)gKcQTH4m2>P3@vjQ1aLV98cIwl^SfQ* zCy1Z|!gv$H(mhOHVMM?1=IgO=!sIyllpY+B)F#i?)!}CHsWde%6e1cqUf#1{l)^EU zz!WIn+YEI%O8V9#BxcN<8Sj7caXj(V)6uER(b4^=j+FoGoxuPdU5!bVt&A%(%FG3m z%jh!Vwqs;q5aFnT6GpB{r|YA!W7#4wJU;(yeEj;x8{$Z^B70Ci>UYGi-%qCDUYS8e zP%BsrG^o5(mKxV81C0Yet4NvRkKF4EBB4Xc(mnf9pV$|}{5O|g8V59Qo}`jONkH%- zqpI8sRExI6rGiU=?xlgp+nhuJT!0Prr<|=#pkdh1=>7QPF`9MUaoH7d0U6#saq2ce zPo$eNxPa!uF~n#_@oS_ZRrTa@-i0%VQEHSF2U177til9AIBhn81|p$8j?0}qPJuD&`BY27;S<@_~N#HVzkvJzi9>#1;%d>JieT<4xqf1bUs&fZD_R0bL@ zy7TrpfDzBW{K`0yj?@haQ2l@rw}FZbO$W!4p9%vL+T(r(6xLw?%$PF^gKbit{X1vj z{3r)pe&QY*!S5>gcOHiH93ts;>+KmeFeW_K&#Z)wm*<3A`evUDX~*EA&BR=T=by`~ zt5&T{Wm>5sO~HVlbR#_(K>3yu$ocb^1pR;*BjP^bWMxB5f_p#Fsd1+=R5Uxbe9(n8^aUM?Hu_(3%_3P)>B^9p*MDitc zDSYJFt<38O-mip0(@4R(&NXQSZ3nzSOv<1cb2vh7{5bZK4vT3^zKLrvw%qDewOVx) zePxW%qDo>K^5Qc}hu!CRqdSrqHXQ z9!<&i-nMo|0kb`_m(e+doH~sPV3e+8d4$T`cf8P&~0TLVV!|A4OD1Q z=RB1u2B*hJv2 z2%14Jd|!t{-ZFsgz2#ZqjMsiU2*8R|3;`App*UJW+v08U}{STbi$d^mPY27E`386G#^_B#TP zho$4CK2V0M)5M`;`&;S5vAwU)UcY?bwYY8_wl8p|2T>{bTHoiQM#}@@>WeOk))=|s zJhvJ!zHqH;v@iewKmbWZK~yo2>GyLymQc`Ok?oa#at|_J^?eWd3H3e-yp}++25qjX5Kq#Pe5av)I*H71Ns5M2~UDkaAM*CjgtLi zbTBGHOS6%WFZO#m?t1E(T;n6iVgn7;322&qg|VR%xRCj8mk-b?{*Y;|Ng4vVIJ@w^ z?=yF|4hmO;GoO;k`TN8F75zRL8|StynOPDoaMLJO`zrqHfjj$L5l$3Vj>0=hj2khE!YXf(s_*olAuM3OiZh6@RJ zc)Hk^6DH=-bIYiF^?h+$7CUVV_u9w;$`V*IxMUK@#L^Oi69zPzHEo*PNjxH3J*s1} z37O|yt)$u!d7?9>UEpt(yBQedb78Ghs(h$H*1rk?DD5kqvkyto%=~zK+;!v4Bz_K# z-K$iMihO1@tu___%|M#LAupXr@1cDo?~5AOA&-fR-KthgJJ{g;t9@RIM@9{evj~!0 zcJ6txe{+vNhraoZbR!?>tV0Ie3)u)Blb=|R>k=nE@+LfMcb1W+f&1$u+y3&0yJ8}9 z`sOcl13)S9V!y9J$eQ2WcW)d+py8O~kIz7Z6+*7raSb|Z&p3PGTau0PsCJ+U6YZvw z?iFV8n2F3;%=sk(4I@eDoqNfp(XP#5(E{C95jnc%+f|IUCFkwE)Or4H8o+9O(1|0D55$&4GO+HA_#cj!e7X(x>AdrvI$B(7 zql#bumcC7TmdBo4O5Y}r^c{|@dHj_=ap(0nVUM+E``YeN5x#aDtGi4rSkb8L79Q#% z18cr#4>9$W!3O8?}=MR zbxzwMAGEF2c;7SknFQ%yd+qh8!B)(3&N(}FZ_prRlL=41n|?Ik{ZGFBErAB3hbs7t zz-<%$G7N8+Zi%^*D5=ER`DWq5-1F7ypaaOBHB1F4gIWqIf{h%l!~w8}!UK2xA&u&j z+1uRxgcI^yT?M5PXw+FUno8Px@3vE=s7NbxjUqEs3RN#NE=FU`=38zj@qA50@vY&* z;*O`Eic@RVjpIOU$BrE^6zjwmgllGloI6(L%u; z(w#bURy_B{tMTQ~!ExGIz1SvlST;4Oj(}I#$t-4S9aEtsQTvcNR5X?^+Au~zt|HPn z_pyRL1k(WoU_aT+oclqJ{mzO1Yt~>!?|mW z%8V*BmH#{(#qpnwi{bQ9_+s4n_|>)7M7x7pWofEeCdap0L?$bMfKA1##;|m&7?I_l&xfU#?%XHnxLCEK4o6 zQQ(B)oGZAbQE4g-U<69ZP~3t6X`{iil)lJYo* z?3QJ&<(-dX@t^-2)DgZ4KXG0v_42bcUU*M>;wfqKBZ4sh`1?aKcrFoijEP7>g zlt9B)D}gXr3d7U#Qw?#m3m6s9NtNo=<9qfn8pVEh(7>4Y^`e+bprHZ|Z3a}hgBgd_ z->o7jum)p_V?fEqxYbAFDwQE?)Zk5nllf)SE8zt_Nt6D)(JctPR}LQbePJW~bgDKJ zlrXEmY!$&it~+nKA&%+TG3r*W9_4Yi$!QU6gr-?{9yiE({H^d1PTs?ygT|cimkh9P zXj~^vzK^VV@#Q{o=IO|R!|3b5whViuNN*XuKoKYtY?x;W;U;)acK{SpkO0#6>7RB1;H)attfe|TaGaN<~iY?#LHwrr*^GcYb& zo(i6FHnlYis<8r}F_0Ak9`QPF-O9N2SJ%c#-HwAye~J+V?gl^eVvJtBIR0?S#c@LC zqoXd3)WnlPT-_Exo`!`ulZSO8%}j~EpB*{isB>qa!73LWQ_rUU$K#L1BPjlMEa}>N z{uCV!Z<_{1DG=Zoj;qmLGCq~-nZ3}cKqe^PHExydcGy;ixIN^348=Qcye<|q_GQPN z6er*qwQR9($}8zWLtN)E1Ag2?uqtm266n+zST*CO9Fm4J04J`QlR?e5h7XPF{`S}C z+HmhU?&Om)&``H_o&3GD;ymOjWwDRqKW>tD!gygEucURJ&7hdMRWD4PJu6m`F3KeJuKhS4Vn8Nc&EE#pdL z{DJ$lNZ6{;bmWA&nOCbDG!BKA!4c=DL8`uXamsn0mCG8sE8*u4#*B$KUVJHDo;o3} zrf<`Qr=A{7>Nm(W%0J3U!xcNCvl+ag74YU!r!X5lNzhH5h|z3t(DTtXNOvWJJQtnR z@6}i1j>n(M(-0oGcJqVc*pp6(c5KbC=ZUf{=kI*c_1XdQqBfX3 zQ=+AGhn?QAC1FGm9 z9nKP;3)fPB$oJI0u1y;EUdlW#D}Z#i$5Ore>Wh8i&9S5CZ*W+g-QyH08k%L*nHln& zA8U8{I$H)!gt^-qmH*;YeX2buF125k#oDSKNBlN=@1Y0&8k4!_pDw?g@lTH01W{HK z@RS0)hw?9jyv!$qynG_f%CE{y`BYl}iFN!4{-u8%wJFo5N8i5v;)(umMk{`E!yoU9 z&PTS7O4uJd#5)jVsECd=!0UE_?1N-riQlT9lmjUPgbi@g-gAqni37KYenfER-uwO> zUo2V}=XU567hQNEy8EE4WHOME_+$MAAEEb<4JpHzOFEPyUDz>ylZM(#>Tlt0FM{_z z7)?do{n4d%z37T=vTChygN7;Z(xC>g$^m7gbRiFErz=Yggm|iq0XXeKVI@4J1rs}S z7R*O~435$7_K%)D&qO!1ivzGF#k*Tq4eFEv-cB>^B55OOMx6zZ@>*I<8wB`hcYMol z7cE-EHmxt?72sZH_gc~Qs183@G)VJSR7(rWnoN!*7^I;hfFW!QL>MgaS()ZGZh7Ww z0)dkW3XUd8@cf&v#MRiTo!cHBd)DUoU2LYTvVd=dv%Ke6$}QnzPc<1W?GWhGz=44Q z`P;;jv^r(#lo-X9`Tp26Kh&$4frdi~;2S9NQg1684YWyvIY0h3K_;BMuQ*hnlqpYO znX#p#vLuC8uGjOUdN?BgkpdYeHn}Yd(xTL#{++*&d z1@ZdpZ^WMaw}|togxJ-D4)mCp_~3WBz~Y_%$bbJWfreCIC>Ie8_6tD3yu6Xw-dRMG zMw2Q3X3@gTaI|jSDw;NKl!lV0PDrF?nI$Hj?BN(Jw@|vIGVMil=){w4=CyYcm_Y+e zR=k&r(kg~Z2$daSItfKWm$1AflNA)91{Ir~37cPY1jc=bV305ol<>PgFtB zDO9sm4xym1a-Jn7RA{L1BxplKN9ZF&WKMCZky`|I3TF5IVpK({a@fk8%3?4qUa=yZZT0@g z!|^#s<=uRdfre9}-X439c_QN?ETJz04Lfizt!15bGb-L+rTP=3D!rR=DlWe3t{`Yl3P5ikHX5wA= zt0ct5N1uNl58VIP7&doa^kQH0g(&7j4mv1l#DGmYZ3u7SC=JOc&f7qN&QKa*z}&K3 zA1XH2g0#~NgFqcy*Gq47| z?+PE-&%kotwFGaKmyA*g&&21xh*zA!v72B39~40~5d-|kiQbK&UkG@vwoM^W{4 z^Yy=u`HcPRlTMBk4K(0b>!kR(I-=mELIzve;5~Bd0Q2|nG(ffiR(g?VeOS@(7D1Tn zAN*@{#85nuJ(WkbKPrR0S(ygSWYCl;s!wDJOKj!Y{2cmpJYnWNg_$zX0E(Fz%k2BU z^LC6IJS2LacTOBkWmA(TO`;6%D&sj?CveCj!GvtUA#5d^oQ3QA}5-wBYm7yscP}cD|f6DMnyJ z^ndQDs6sII8swPG@sjVMhum_23^UpA&z>^`z%+V+cLtY`%^Ln1&Nh-YyJk>vH4g0v z=KbQskHy>bXT~*DGhAv#1F}FJmPr)Gwi%>78vHx6)vQN;mKLo#a%=++8lZL}w?~89 zu;x%n@Rud~iME9&8Jd=A}D8Z{Tl$Ss{n*Ydx%QE97_0S32GK&Y`EnL2hHTUqb9JHA@7Brc$G_1v?O!}}kQdeQBs zg>A~$nP1YjM9tX3szme31nuxl#Bnd3OEd0Pm<~kNTz&T+qdl_cIZRZpuuOi?I<^NsFjo2-G0Zl&W4WVr=igD8OX3B4?jHiXYOw4 zv4@*F!hl`c@61t{lzb+^l7E8}<$*!d48(wIduv!BWM%8~B;D%N+=IYfXSO7AN=%(P zkO0+BINXk*tVup(9A&<*r70ik3~4~UCv8eM1~fe#W&(0-#F!80z42z;_^YeqXaWtj zNfz#m|6?+mp;C^gjiH`kT<4hqyMz>I1s=j&c!-az#%30iu{lPfKVEzC@z}m$R|&StYO1UjQ)gt7f%wNL394hfRQ~K2+_uzMGL8Dcr9u*Z%Uxy+^9ljFa*GZ zOJe2!ZU6Y>qRAnkO^3zs_w3{>}`y5p|Wnw^Tr82^UP{ zHVg?urJ_N!Jw&o{`3g$u-imAQ{Zm}r;mA1Vm}BEmnp4(72x_=VpgN2)oWkRm*>r`i zf>GvAgN%C_adpqLETs@|zs+OMKNsWPd?$Kcb5*n@Bjp|`Ge+OB2Unr*zBdW4l)cyR z@_y;?0y1B#BxFVd4Hd|yt|QQ3>C$K-(GTNLpG-5w?j1T(&P)c@%sS(09G09}$5xT* zbQ)mLs1mjcUmw2K>B?#a=3=&M(pQsW@W>JI4rM&Qzx$qS#$q!djgpLlZezd_W9q0| zfng&og^7U?g^X)6tE=*>Mk&3**R2!p5ovw;>1U(mkw?T$>?1XTo&tf-y@!H3|7PCe zK&IE=mo_ru&3ii-ECJT*$Odl*K6itjRv^6J9xx#8zxBqL!a?dcQ8IS!si#Imnt8d; zwG87Ml`jKIbKe#3Wm&v5117VY1O=&3EuA>A6&#eukTcLQZPu*ljd6Y-O#{7p|Lwsz z5u;@naJm+H+Mac~ML^mxT3d3EG}<(+G?X=n6oLv@@hVL0=xk-iN1uKcx8HtSjF>q) z&S-s5TzQ?%yjnxkG*HCYl4hhWrj)<4v6ae5Lo^#*x(dFd5H#bmna?*u$5ytig1-g~ z9}$<`dVAF6dzTZ$IOzl%)$EmuZ4(U%i_&9`vxNR#zs9*$3+1a(LdhC%5+`08+D>A+W zcX?m9E8nF}S5g=f%$$3HqU491B!BDBtH?*tnCaJ-T%3W18_qg2PDY39he0GRb-2@z zW^RtDEVIhQCZAbKp22~_$Wxajy+~8sj9bJv;PNd3B-j7tzBroge?8cG*NGC+M)ey& zCxwHBX_9)W$ngA-M|5dedvE1V$>@@&OOBDWAfM01DK$_%sBa&(P+gOOhRkk4lgf8- zCeNEiv*(GlY#>^BqT?m9)ql$3%uYFJ=uBiO%dj z_P9S`=yzSaZ0wX=xB5<9;Tj6Zlt93?_k3S?I4=#;i6kqA4mp>TiS8>W>UG;H)LASwDbIJ(!tN)~AJ_jQ0q$N>nY(n>#Na@BM82 z>8aj)8u9S&@5pAwHLF!inzKShn$P3-42CPSaE@Gu2CuqM`coF9TtN2wx=OXGQ3m_q zE2^Sy{_SsLAVJeERI1&6@4eZ{{wLu5HCq6*4XpT(X0(@Vq+8mGnB(Vs8J{_;_goJP z&21q%UhXMB`Nxam*fBcrMA9tRAK{`gBYGJPe9V#6on=eX}?vGaqdZLl{aSKA)j?xhDFkt0< zwDq+6?2R%BntbA=m$Lfc%#%*eKtoLe=<o~4`AOCyM=_+P@`(3!P zRd`#o_OImd4!rM$HN~p_^(DXhDCsrZ@Uhv5Ly56rczCHNOP@PVqxyBCOV{I|zdBj1 z^3l74;;vh6i6aOe)x_DX2>zt6l(WD?+Ad&AMJc=~j|v-umnA+D5AuRdntlI6?8sMe z)}O-ZJ+o`qxEX%hw|Vol$#X2n1-Hsx<(houSeX!lK9uv~-f^`Tlo4f^m%42kw&VZ; z4Nv_35AiYU`7NhHoK3QDPvneFV%oZ3%%Gyb*S?b;q^FdJyr-;F#ux;!nnd`xWm8)4 zWVdIKVGmQ;%ckCV{64D7Ivt%`N>+2+wmj->WKAX!;W6)% z{vq==8JSxjc~9JY5A6F7c`q*f%}vo}mvV95wKu0dR-=CXSc|j00y$a%-p?uw=_Qb37~Zia;O~4sO-A(uums z0F?HV&2n82h)$a!PY^?fenX(zz9DYie(c@1<8RnYU8robCrMT#BU_{o6Ajwa>Uo*o zZA|jJfBRX&Ch3acHSo75i8S@)mtVzTWPI-@o`|YVo5nr2-_F*FgVNS9Xl|h0xoZQc zr@WW?GxZAd7hD-Qf*#${s$K81{(+~DjYLMi@Wi9>`ow8*CC#U=rJ;MHh6EZ2Olf16 zd`gB&8{K)k{dfz?YYuDg_wp-Ixz6r!&bjAAoraAPek=eC6?ppRbE54(?w|jCpur_8 zjUm+k1`PiO(NIN9r?hW4#@XU|^Rk4e%^?S8w^Egyd(bVr7o47+pu;qTQtuP5x{`My zuIbi2&SHCm1g)`Su%Q$jeC{KyA+C2qZz5E zU+NnZX>@ir`-BfA`_gRh;;2FmPv_^pA;(ieYmj>%4b2P;uznq1GZ-pMPghVG+PrQK zLgYiDt&dQRaT1xwW7*5tpl-eFUai1O20>VAWIC47L#sbrJ0B-Adc>V&Md<{;H@{_iaXh(){bo2&XtND4jBkw?!rY_r{Tt&Wo!+r49qZ4$FPkB6*`K zl_)ESC=Q?u`@uWz%&hRW=bum4*B(*7PMtIgZQiBxq_T9azD_00vzK#L5K6{IynR-v zWb+{mG&{k+i1Dvt^LqH+d$RP^K*RS$(6{3^DmMkR#)}F;oEgXwJ~j>g9>t%AGfGKg z%Qd(^%wWLB<35kOs5lrqXI>n?U-P*1N_sT3^0+_ta2es=Hg9Rhhwuk*>2O$DtFm@w z?iV&PFOJ=FXfrZPcn6Oh9oPK!u2jmuzVL!L4xVa)Ff-%2nWlik*$Jr_9LK&OJNUqH zTY(UL|HHA-_w`q@k?L2oW+x2TBoMn01=yJvl^`!F$kO0vxy(-(7terEH04^bSAY>P z-j@C;%kQ>l40JTXD%MJJ&wa=w%Tdk-lfW~N_0BEtO7`NqYokl24pFx{fd<~+4w!F( zHl!D6T?MHONri+`lg_1a=}dkQ*Ybxay0}$gEPD?B_V|;O>RlX1Q)XC;Dj3V{q!Y8R z1wC3>V`dlwMF=t0_R=i(H`pLv*D_g+h|0U{#+u5rFMED`MsRH)2G>-|gKr^%-kPlw z20qFV5x2pTdlWw#_bFv_udt0{QUHfQc)yIFJ}+0P@l*l0VgKZVofK)T3RiAHH4ii^ zOA9yP1bILUz>(hx|AalTmVN+9{+Pm*gl!pqvzc*Lqw80!Ekrjz$?FCJT&Gb%X4&r> z1RMW!|NZ&?-8cR^PN$@~MpXh07#mi>WN!z4sDmhs4d$ebgchYogN!PAKl4()DStI6 z?PK%gGrgl9blHT@{y-UNCxVYUb2{T`obY?`r0kVf)5!+T;!ioNyj8|1=Y*-wuD=)W zHu(JYRoBE~#=g48Nzvn!lhcUy`|1$CFP)eba{iWPnkDtV1~jvxiut;=E$;__mHB3l zmLtR89Wgv^MSmRGm}7b=IkqCsEjOtb_@1<*L#N@T%<`;p*I|ZL9y8#gyz|l^&1dM! zIn7q@k8T}1;CRu69|ypDn*|ou5|pw`-Bh_EMmYBtFUyy&Nax(Yr5W!j zZy7kT3;*odvuO%DHXiQtV%$qbqFa&7qzP}0aLaqW9b;IV)O+rGe!_)!)mkMJEY z0}XDc`D)7K7&U5C^dSJ&pyhs4G+Yt~QKe!QGXvC&U2JcF57-Xm@6u3&Aq;eRKdaWv zkml9~)}!pLO<++YdJy{Kp_^{b4D8kCoEw+0{h%J1Zxa(5=h>Z{@5^9mcK|2pTU`w) zCf!+0m3onP448P@j)?-Z<6pbHIq8>rgI&HfC+qvRw> z8p?X{SCaA4zQJGv54#{k+yd|^y7kVx?~W13o3)*IX<{MH)vGuFf9d^9+(fytj!`olqbjT|`!j5# zF%5OAGla>mBv!nK&X@Pkj3#SPUdy98Y06e<)}ue4r7_-j*iWaj<--%eY<{YZsMBLr zh(~NMShOhK<+PMH*+%#6hAlB``Kmx|Ww2o22Q>FRhm=EJ* zj-LF@6_;a=?Va)|6AmmO?F@gxGot@thO2fvAPc|dv+$IQ#`n4KOvVnjUm=fB1{ zetSc&^Wt<)ou~)gmDdIT7(grL@0ilPzg4iOyoXlgCEm<_Q9nTU+QJ5@rq5z~GCdle z!cO&i>W_cq1cZ*sqiZPfS7&Pv%SX;jxgtEI4TCV+2ij%YNhZpy+|fr+9vE1&YWP-~ zXU`zWc;WHg;v_QEEnBq6fSr}F&QV*^V46Wr19$S2&aV8d6DlsOV(>L9PGwvXUi}`M zYXHvlRd@U@_GP)}|K@s{b044jS`NzPXi3Gkuu`__oMfqLGj0HuZ@mv4=b9V@;igPg?)jI&HS_{Ttq3*koFyOFWCeox^ycy zXrQ8c68^`KchsiNF=*<%xR9frFFW__*t-FNhKp%l=$%d z4`S}Dnd$gRoDDI|%mN!RGD8dHq@a*_-iOgIzvu28=6tdu8o&GCtjowoY9*$OUO~h% zoS7^$Whye2vI0d`*OB)(8UrO^>mJ*|qu-}v?W=KAz1^cTjq%!0(Xa>QqZ)yw@>T_i z%F*?RVuJzxufkK1r9r_OGfR!|QV8f2&YU|pUL%V+^}~;8Le?W%AJi)LZrUUbwq!gF zR+vn})6mr^_2?O$Z4D|3(NZE6iN=?Lipghme<}OQW%TEtf02_L4yWRPqXhTbD{4_* zq()OQ8xWBB3{rSMoiBxJGU7JDs)CTYy|*RK&c&nC=FXX$j@PhZqvDE7FD7HOUs1M% z;LCmz%+33#C^EwboHeGrhkH5=)cBd4snH>`t3d4FJcW6W8S??rT#mHccb_;DW^9fD zt&r4ERUm1oD;3gdgwYMk2z%izZv4#5jPNjfY&YTx2$E$O^zV-y6VE;TXe{LW7xg?P zOTF#FUnmA>LL4%f&l;viaz&_0GcP_=2^!^29564lUj}@{X@79~(tAVltG8Zpc^nDN zR7Yu-0hVQ$w@TU4R1G%at&)&7#Ge@iajR3|T76%-l_rJT7n3H%(@#DX%qxLBJ_9M|4=|B z^ddMlIv&*_8tqv>dCw!%GTO@T4G1|myD#f3Z~SpRxD;2Bu#KyQKV%b_Ik zem5Z}H28nmP9a>0PSEsaAUm;a8O|YJFJ*tOxu_Qnj@m?RN^2`fW58hZF9Hqnx-gP= z(zpOt8XLmM?1e!}<;8LwqiNHo)39-TJTqW$TtUXZZL0&L>TWjTvU=g4jbEiZFKJOF zZBS_=ytWbNKQyU5Rg7SJFl-N9NndN(7i`7Kj?kWp&Jyq+ zf1+s@vNm^uQeE@|7H%5;jFZ_4V5$T06a5*=(5GPoQJp2ra10kRCg0I~@w)iJ3pmxI zYx3F15yRt!M;{}*hqHd(nbGxV`q)t6Vug?f)(=L8An44FK$pr9A(RT4_5bYL0h!WO zqW!5eXT}RJ^@{JN>31Ey9Cc;Aw|Q!XT5 zD<{B@ygr|7;OhjZM&MMRO^_tF8KV0PG-P0edD%2j!%(BnhXDokT#m=HawUT_@UYNN z+6S&?UM7(ZeDT%S*dkOnI-x_FHf~HtYWL)s%=$StzfV~MUhVj;5vI=7KvW(o*L_Zz z!~Mm)`?6=xo|W5$USjUIT+l0V}jx(1-u2Bhukz{`M;oKEg(xl71kt z;@%jL(`L*FtA7ULT6rv z9SXyiXRXldEudd#B}a@76x=ry3Oa-JLISQ?i$J>%hVCdgYC&?d8Hk|x}0x8 z`+i)kPkK@IECi^K?Jo~RV?OGBTF+=tV69Pu2E{y>S4lpWf(g@rUIZ>dj&g*JiwBISh@B)jzV4+%fNln8a$#N6%7X-+?Hz48kDL}iBCojkKYrhJ{Wtf zGEQMR)|fUJ>rVR=ShzJv8q{&q{!q4U0M{ns3Y)CZ1y&fT8$Uzu^(UCw|BFe{5xsW- zm03-Ji?U8wDqEH5!dm^7q{1AvQ-yOjB!su5abfOn^4l9ZmLoXV(5b!B&$}sr#8%QB6}+H)-$cJeQnZ=WB4mXL(oKN4^?QF!mv~iq4|Z zcehpt#3@$9wP>D!1|9xv*joH3?MY>O$tg`5XCYPxNx#}*WeM2j77*6te*RI|WA{G# zWbDa(PwRCy6>%MN>zzlhXY+69C9AZ+g>s-W0Sf14Rho0R2bOU2wKki`F(@o<7Jsue z-X1nQ`V1T#=XPwLC;aWdf6MeSRugPf1_%fJnIdyfU;ukWJ+976Jc1YD!F01%mooEv zWV741C!;_5Q4wzcvo0h$n>OAn`>FW*tgvHE>TY$R72xusG~^tm8v}p_N|lgFRNz*+ zUAA2PF((__zC2`D^g8*ZXiH+I?jE&bH}t1fd}(7ducQxPtn8Bq)pgp|(w4r4azXz_ z*=qtsdY>_4W;VNj_x1i!u}-bH>f(!Oe%dVcsN)sehfNk1Fi>}tr>}zgPaNnM7?{-d z`Vm%ko0(0!eRk`_r^v|u{hp7p3%`vXBu!4~-Zh#wXo%cJ76NN4CDJ!#9R_i&Jm$3A z*aY4dAbSQ57#MpUd_bJWR?G&C8nGU9RZ1Y%$$$Up*S{suV1EJ$R0X1-l}Vt6jQaRI zhqH`7WS`%(Nt4MCEMu>4wWy8IF%oE5A3shal37(uU!pkQ?E6y8Wti?56GvhEHg3=W zW<$9^G)x?I#}$ zk7~QuCOY3Dnlx?_wJ{WBLQ4f@F0<(hOe3KR2}?wsZ>d3w_j3Q0nJ)#DOt6xYV9!~f zK5beooH8vAMJYFF*f6v1Wz|uu+IuvSs<` zIA|zpUT7y1lzG_pn-nC4$KkhW}+BnOWr3V#4DmW&ufoSk1vzoyAM`%L>TRdiyFut$KS2qefu$4A40xw>f zyN0=jthA(zkdNdcGk}#V@0?0=#`I|%5&2b2q1>(Y5r?twxJjW{fU(2H7+H$c~^kf6!(lws%ucpTAY9r>@nhL>i>S07J^W$V_&ktZAzP4;RWyHq8R zK?d3es_WLTjrj}avSn!k5&iiXoJ+HEqaN9@-K$6JQME?Ys8Tt0W*=ZV6s(mq%EvTb zfp_vY0S0--qbxxpK>#WYfQ6M7(wl*%&EgfMxgB#XL&L1K8@I-+MI0wJlk5+_b<2v^ z@m<+Q#<|;C7!%1Zd_-ns0q>vEp&b=A2U2lXwUF10x0wJ{uAMCuB1l;%t@~QJ>qB^@ z;lddHUBHgUvkMl+kU;}u^vrp=$F{?%Ju)*Q&ub)@5iwAw(${&`a53xh%Q5A(%)W4s zQlP;#$WQ8zXI|)=+eNzU-5}Z?#ny&~4U%u1WAWQx@GIlXSL!a;Zg5gMcD~9D0~4-A z`dSMOdCvMX7;*=-<(INC1DUKBfaDkkL8L=v1Ow%Jepk7u+><^9 zora^$!p73KW9HQ9(fZ&6V;_!iY=|syi<=o@=cO#PoHQLS$7RffKk}qx%t@olcNLcg zuW+>@!i?82&OxufXWeK;wO!phb+b=_>y)-qM!}b^U42(F?v-oG8OQQrprQ0#KU=YU zIf3fgF>UhXm_KJ;wC&u9AUF-};M43Sz1p}kxS^0^z+4n%Xtb9yZatF6= zh_iX~=Ea0BK94WPd=%wsRgF%akHsdapH1KFFt04jQyO@d9}KX0KlNZ{zjzO3MmE6D zyl+5QXFz#ukA}%ObRWO{PJ9VN9D6{^IQ%e@4`%9^rnKR_r0vWq^6b2wmvB{fDkqdd z22@;|MkRkH9G3x`2?W0;j`|?W@DDwvQ}zt0LjMNg?7-5bm%n%3zNhT>l{!_2wk(dS zvLCRd!LDI#FCkC07(QfhO#ga$9MBlN9@Z`zHfWGpR_U!&Az`ygt3Ld__sID&zO&Sm;;{7S*bMw^TKhiR z_0GoJ=~H9HiYLf8AhQV_-h0*Ogtgft@?JrkIxo)_x?14`5+9|5+{Qwm8fI>J+07QM z4Qtk=4*$Is%QI6Y9c#={9%cJB>htOJf(O{IYp(r}TT!7a@kFD`ZIO;&n76SV$YRAG zp^tg}#UH&M50mX7Kh#;Nv%zc@*F+wed>k5f9?BSHgc*(UT{9V^VZYP95PzCmTVoyR z`#a8e#}aJh)qnKUm`PAf$BWVFlA}RBBZcNaV5Kc1A1(MC0VZ%zM}u2%mDT>;i9Y4l z!FN9RBoOiO;8V+E(W1rZ@DmE>0`QfWC9lmj7{Ey(l^Ikpqd*>RMwzfsUZ}6CU&`bB z&SINx+1&BP_Lx6wYAk#Zy#{*nNK3bFD^sOUVXO_}d@W9`e*X_yzlGyS9oq~XgHC2N z=xAsqQ*+1GjchNij0MW3+PXYVMBA;DbzHI&)Je1Ob@Fg{RbPLup|~p#PT9mfu3YKK ztnJ3;W3grPm%wBJ!GXD1f6icw{H0`D0C2|5z~r@j?@OJYw+!fs1JZN``?$vds7E^= z+`A`sZP|`)gkAai>l{B>m-A*QiHkPtdfJ!xu8v+-=BX5{9c_x^Zb`m_P_S^WPAd7e zC-X>8o8NgS4!|~^o^&L;#q~qMF4*urKOiNs4|%R_!%=}G|q{Fsd1zpUcqY^kQQ1J zp*$kQ2!(y8(FgI#G)yDYvsH@jOOQP%{TIj#a6i{^DDM1p%DE=NQvtyhu-sDF`~LAMvkc>eUd%Ecp+tS zG7vqNMxZ%{Tgj+EL_K8+44JyoaEVd|mg7Hnn*Q&Qwo{SS=0_t8gx@s~ z-g8|&Zd0M4u)PN3y1^VQWHnSp0>oDMnYN_2QO~7}_A*T5!l@JNKW7i~5YqF8lTKVd zDvdG~f5#>D6~etp0rF_iUdH5+TaKq6ecGOkL}!NzqvJOn$s@!ro$ZJ#?Ojnep&}+v zXWtn6r%HxgZdqZhGHbun37|oBg>_Xy8VR!-2En^sMfywcAn+MR^xdOHPj$3M3n|mv zncE{{hQ`BBK9`KOGLkiMBCi(ZU#q;3@5+O(uun6z7Bs17iv}OMv@e+8quYgqx0m9@cyyYwNZT z1)Rr2H8*iu$=;^mT!ff0xhkg5TS$@5Fk?_CR}pGNL5EdEf%5|iFOx$fd)pjXJ~YGUyHp*562hBZ={37j0OvIEuB4sqm^oj zF2U%5JBWbt%-(gzE56-i4SI4dsQZC5P30u1>P~ zR~r?TV}UX22As!KR%NXQ$1nUfCWMh~-{4*2e>hPrf4j~eykWyUsh~`~9-#uwvge~4 zMWwsr67#zoqi5H|C=^JuPWpii=;jy+B?n(KIM#)*EpVq6A6E^qom4qK#u-hcuOY1U z0M{QnlTTg8&{xowlT9L=-8*`lY!P{&bxcOEpG7+Fx=3Yo#-lT|KjRxPlxOW-q&$ApTuME2z_e^TIu|;@Bnl zu|ilH^YjaA9*FQ6X=B`lGJw+)8a9o&?a039IolJ%#te$;`Z?6B7?;ngOsF8}Jka=* zZxqKt6~)_ZZ@3B~FBKVKA+PtiOQRdE-RX|DX!>eTV3I}EEDY)KlW;JNOrD{0Lb}dO z0LH3vdzEPTP1af7K2+L*hnX6iJdYWt6OVR{La6v2KXxRJpEwH-7#h{JI2qW+W7I#L z)ch{sbvC%yUa8o_ck(iehYq2A4fv8{ScV}V)L2kyH0pG^wJEyKTtI$|jLNAEQ3)>) zkJE62A9}2ya??x+x6yQoIE;6c1_3ZpUbs+3Hhs76G{}I}#jbPFez2LWC2(vO$7aIk z2184(t31q1H81~mEw4kH*O>bV`0ptC)OgW(5>)#Y`f>ip1AuCu{Rr;E_vMdZ`9 zj&m_$TqU&|rstL#+xOC_zH<*52d2)q4G z$E0#YT}BwW^$y5k6yJ!BlgHyoQ+wh>eMP^R^}q@o0aZz#>S5_vOS%yaaU$^2Z33r5 z2ZS&C8-2Up(x*m|_laN9b2m7DiHw8GXU>y8JSnEnzYqS!b{(C$;IgZE>Zq?A7UM@C)8N@R$wIgX+?By*GRSYmkE=a8wxN5z6X!Az#oRTL z`{NLR2!J~{gQIs~ne~~5MtkR_*s%xa9Ky}@wqG;a7Ck~n0|w@)4jk6Iw{sLYMpq3w z0qv)wL3soW#GR6(;W~ID?8VO!tmP1#YU*F|EQ1x|dnI~w(i8ep`_Ucfd+3o>)f9f7 zLJa|U0dy`e>A~=mM_B+_xoURAHQG-e&-mmA&bvQ!mo(I;W68_Zvzr@_#L0tA1rMHC z8`YDhu%>KD6c1=ur=na&Cz$irs5K>CexAGy8Q?gSui}f@rI~4nTrjfVvVV7+KGl^t zIb#tguQfE}dKg%8u4&`~8|8@3oh#6({K``^q{pi`8miFYDyt}POdl7~@#L}cGq+!y z1?Rg?bfkVh?STa`0f(&Pk;f|=(3CRDu3>rw*jxoRWx!%M?Prh-yw?$+BhX-&85z=& z&gDy&y1>g5sY?$n8%37m1TqfT1~rURl)w{DFk^A^U5D;X;R8>zHWVgm+A3y_xc;uM z+X1Dka&%$w`b_&t_)Rm%c#lQ)O^&gB@}mbkM!sq=QvU8%Ds^YKrpg=38KZ$S=~d^t zPJRPc1L2hhJB86@=;>C^WgaGr5*)6cQXkc1H~5T>gp?sXE4|9^wGFN_2QytQpq*I; ztckj>HjTE2{m56v<1RC+p@-2ED`Fx%c+`lIsb}YQXXct0&%!*?5!wUYU1JWTMwG#W zi|lC~0>j{eMOJY^1LvXj(@p5`=g?bdWXeKxj&b9QwPOAT7wkhE)h)V`+Vdy{eYHcX$LS?t%Kqh5k$aKLn^>G+a9uQ8YF z@L996EwuUGms{fR{+GYWtrL@`)b??;V!G0a>-9~(elJG@;7`UcqwwY50>pP#4aEwC z<^2%R=5=e=#G!rr(?Q_*)RQq#Bq)spJ%kdm3+=mvDj`Yuww38nFaw!@(JdLc-Q|pz^Jf zYlYr5zj`xPeD}pzhzBx_$0S(bO_MqvyozWn(pY%qn0e<0g?rA6ad??Fot|>qFtcPA zDR@V}+8)pT^Pj{tn7z-G;FnGW{!ZhKc7?5T@_Usq;i9tPC1dj%%G_Mj3uK3LQd2?ODn&(VZ}NM@C7lRmEDrP6J-g=tkjBNoWa^mexs={V8S zgs|Nc3m$(y7UNac@pTP>Bn$^T_5)-?%cjD zIu0F*5oGS%|H#8JecH4fuc=)MK`+~P%@St7$2GUFG@uxRWA?M(sjTGoAig`wnr_46 zUI9~Vm`hg6j2Y>;Q>j)#RXB+6M&HE#!5D)^J`^%{iMAW1llGj40*#M34kP_C{m(aU zj4#%H94}BuV+@MP@%FYjc&sr_GOxyyr*iDGaWu>r-#=zf)X`9Z6R1Ceh}1rqyhi2_ zjsVj6kq$YPbk^GS*MXK1Tt45x(a?+1=>E&Q@QS+_40p+BxJTiJvwe<+uTF5{13jMO zWsK>E&pi`M*jqOmI=RPu@>tOvziU4rT8Qqw|DXS#n6ctf(r_O^(Qw~B(dmR=VVsIz z3OeaM>n@0oCZh8ywAYqN3TMQbp4^^oo@36!OqLLrxkWhI4{$qZ=pB4c8oc0TJ@$9^`|^IqLAp z`4o)8Rs-k-s*ih&mq*JPvF(SW#?uW3@?M4lEjQnMZkbCm-5i^AQpC$C_B@=e!F!?V4;J@)U|5tng5 zk73{P%sI1S%A`sB4*kRb3Z8=^MqlzCozITV_LLPGeeUOWPWI#d2|E-Xf8TfDKx}&B zmr+Be%rvqSYEUXGabl-<=U(}^bI!;hjSfUn)9Ik>@Ou>yFJ)62PvDVwulz7Qd-LW^ zarCndv6QV4R+86ZTYVQEu7P|;hlKbptqQ**IGld<%U{P+ zPdyP2a~i-6H&>Dim zy!hdzF?;6BG;FS8EEG;KO%Cu+NC;!vlW!^aZ8voW-eo@Npk^G_vv3s6Eu<)a_F3|& zskB=^V|wnhmcQwAF}T8_;jG4pWlc*uj?Mz{PMAxd$}Z|OB%@b#XP*vBMUF!&|1q@h;w`Q#i}3w zD7P#nUW+R{t3H!7DYO$N@_2ruJHOXxb?oAz@KZm~LD5N|Wfz%$JGXzCM?!bV5V@Ar zj)^)P4byNmOc+6y&>b8w7+U>UH|HbE57}y+0)u7Jw|Hzj!Z-1*k9KpdnZI+&ng}%P+R}XXt z6M>vFF{y4^G|Yg<*G$4ekNluN@ykoO?RO=9pM01(3F}_AfhO(^rPWeq3lxRYH0YQ_trBQj2+sbqzcy!{P zwd>-cZ>^5H`ucQCYp|yd?bvgz3htsFDi4reTmZ*s7MxsD9ne0tcjWi-x^w8+AHMfq zTt9y4HdypzZ_Y`ZM;LKG&zT+aF2y4k zJn=+4vUF*PAB z9j)%?m@4xRcQb~BGB9Fr#b{7t@oFGqtDchLoi@4mcb2wsJna5wfNG(SZ+ zoZ^hvD)vAxCp~x8^l7=M*AUv7636{A3m3{oQ8;Lji14P>XaH(xsVMrLNG!3rZ}fAV z0H2deHUIwmV;;()2;p8d_kCvJLl}sPm(PiC$yj)|50Ox$RWXtf(?Dk&BAtZjUT!Ps z9)p=YvUFJ*jAmn)%4$2w@F5Bj(6$|y{RoWghxWa!MImxKH<_=D%K08a8G7r@w>WZX zVyt@V$t;$c0?IkcnEJ*nA*u+7)JD%Fx*`hzC6{(o-WAX?bhlVIH<`{(VE_KRzl*0S z0QlIlrRl_Rzma20roi|dw|kUT2J|pm48`vpYchBKpRjWxOviaBe9i%zOwc=?M$_bWIi5r!Z=dq2%t`u|3AJPwPc0 z+?uZ0jdR2Hz0V#rAdDW!D28B=mG&o|BL!I}S0zya`_Q}W8V$lYk+2(^nh<3wvq zJo5Mx@zfJ5iC~Q^jt&xUDB|Lrg>^C^*NeHAj2Q)=^AYxGwDzs5>(hL^H8x_bpKNJ~ za*A3lee}^-fbpe}&2z_v1<$#@G9TAM=Ir{}SEgOE4tkMgxTgH+omI&f2i#w|hJA7) zp$AViSulToOqo0x2LlY4w$oFLBBawmmxiY(_`HUl%ClK104J4bnXK!i0b=y<3fVUA zeE4B(+_EWNdHuCKR&W1Nk5&CD4j&_}ZTCKxGv;8k&YaLMrlGt~A?0-hjs+w8GH;R_ zXpsx}s7MSUyTQM25ji$Pgs!0*6*0a9PlcK9IvZ}?!!yoA&UIgp!=&l$Z!e6vV#7wn z|N3wLt9W+h6S@7$ROu9Q*^kD3|2TlM^6NL=h&jM})ykDgr_#50A>D~PZlM6#=ojUP zex-H47x(>JI&e)Ccwy8i2&kr(k3`-qrg-n9V>Zl%778T_B z4UkrN>ALXc_>80? z)Dj;~rztR0u~1=@o>U@)nfN9Tv2K9Q9#cF0T{>_be8#OSuG!J1#ypzpDj8cf6u+H2 zZ%)*aVWC4>!`MsX&i2G{t9#qG0$#dTS(7iS6qL4=xu&)+J$dTOI*vS^K;&ok?AaJc z)GaV=p7BWEj!F5TF)GShBvs>~Nc%)VXI;b(WrD_WI(^{xIvOqzIa~9|C(($(`zVfZ z9ge0io6RQwP$^CWh(7$Rv&{M(rIcv*;JQsvrAEb5K5vZ{*IGVlVYJ`;<~KyG#>b1) z70?+gK1x&GE4>-z6JLb8{6*M{@4`zwcb?+CV|Q((7kRSs!?gLg-+D71Bo%Z8d~77n zNXHF^CC`+qN(HZ#o{t8~PA8uaf!HNwGDzi5$j3^~0b17zg70 zIG)6bZpP|3i{qYM<1~tB$GJ&IIz@zew#%BQk;mUv)P#`lG&eWLA(YS~hYm*tCm*fi zNZhID1-Z`_gH|eG;yE5=xHuv&R$gc<39~%Hl66sDW&g+*GsVtflJL(1uE^)&--ceA-l-f@pC~)Gen-U%;D*oqT<_~3RDX+_;OBfi3#@yZW!D;l_)>yKyXyonkX=z=~;Jk|(56C&-D<6@ksBb0?(WjTNQudx< z+p*gio8SeX zeflX`1m|OFZCxy;?U~F${4--td=!^;GN=owBZ=?wGhYU5%tmlt$)lN%PEG5>_}#W0 zJL3~-cuhtJQ+`aGRFizf3=-ktoYd*1d%qK>3l7R!(x=WOd6~}5teZglj>#a2!MwFN z1$V;_9$m2_=IF>E`_FL+8~c|x2}|)>7zrQS6({9I(x<tPC!*p0(wa+oL#XLfz{cx`%-z*Cj7Ld#`Jt{ODpmcj6p8uzz1X z|I&+DY}lB79T?e1XH+~&Z&^~y2|3KfM@`eh%(dlWC9@P zx{aU5ryQL)7lAo%-u$Sot<8v(g2fk@mhJdIi9sd6#mmSsfZusadf(zXnNWI|8Mgu;+lFB{zT$gY<~L!OURGzM;)240h8%6J)LhuGA)Oc_Vdl#o ze~fIB`(Ump7vQpEW@yQX6j(N9yW)g>DVQ?l+)ilM^keI63`RNN;rI%eeE8e9q8vp^ z&;LRkY}I7MWTVVo1-6$pl;OI4VMBVZ8%&Zv@^%yo2E2yrHqd|cq?2%46C&wfHm`Wzx3s%+xKtYFIz zu-d+BN4)#~@7SkI!OfkA>^Nr9|C|QW`$m(}S~fUFQlVTY!(i}cP@j^clBH5kmpM*= zknfIPK`adm*W^XKr^3Lv?h-}obn8UNnb^@vF)5lj&dclH{pp{^D>(El5SYi_(ucy{ zEgQq2D*%zoknmvQ$xE!KVOsl_Uwlcr?9p7ug-aIa@rf!8Do%wGTWqV)cuWTm>!mX4 z7M4_Ez)xvNI!OGW&m04?;3zeI*5K^z!3dgCTO0RL+-lmi`ZNf=m#IsPsdy>uRicwt zm^Y2ZHJlk18Z|}Q!f)vqLU~MO4SaA-*MG7$#*=+C2g7UnwCSltYn*X&@oRxyb~@uQd4#bC;!0=Yx(vtY9gX#f{FZG36q;;FUA)iScD4OIi6>z=*#;#kg zgZ=ZJaJOsm-D?-YhmSFgbUe(NJ156K5eJ^Qrh`RTr?J7iG^xzcC=jE{^lH{ z1Ch;araQ`yHEZKz_A5XA?6Yw{fuAu1mvj;+7o=6&_rbfYwQWgH04!^dXgsHZM!Thq zJmscqFogOtr_mwb{O#LpdpjF1z4+~{-IWDJ8B4FmVB!a@lR=PmX?RxWoz5zMxA1ro z6^Bd9|Iy!b6`&#tcynKE<&9V{#~J+g-A(K@|^iMV6rT^-W3GAqkMeTS*t)rd2oZu;~r8eGk( zELXut=}*U?P6X#HJ(YAc*IgK>(+QJoo4>upQ)R(f91T0EVRH2Fp?q%9gAb97_)u;w zx`9!gTU+JDJZ}b@c&8!k7{xo~stzvsj^9fX_GN%(5PaeYa%s&+ALCT$in{uSSiG15 z?K5U1KhdBxL&(6NsXz45rEQ8U&Ru*EUiN954%~6epZs2@qfS@pY5NyjGGk3ggBjI2iR7t1 zmpqmBGqaL+x7^x(Nr$(8`_RcR5B=IPhCK8r(w`weuEFnKA_J)wXRHnYb!o@Ia1y_y zS8*fx8snF*B`7*by~ zyT*DHwrQ}+aVOmQEWYcM=!ABJ{cd#ASHAy)c;vwc5+4jcI`$khIN`sN+z=nL5F>ob z+H^Vvq~kJz4oo`rUtxY8Cx%%E9=UlJ8u>o$*8_V7N|q?}O9cw@QAUa8Bw7}9M2+f%gyh>az$mE_Z_Xu7gVrAOo zFqA<(&9)-Zsc6Z#JVGW7RggnLt0HT3ej`MtlgJ1{`7If>SyRuYWDLBjGrBibIZ_c5taPp)2_M_%c9mgpo_?1fcA(Q@KAOmJ1ElB+$=gBLT7;svL!wqT(mC%YUp+uOjz384a&crTdWw zme2;qGRAlXH4#RXQ52PD&6v1HW=4OCFIu-j3Y+5j5P)w;98>7%@%RzLV48p-00xAu?;vR5xtuwU|;x$`B0h|9sdM;^} zuW^C^A7FKNAchj2oV{c;Y;Gme!Ef!}$n~%Ph@ciM?~r}bUPV`+CplWOrJI_BOMxpCHm3HVCtih3HSa=iwfy0L=Y|`TP(tv z^=lY^Rs+W{kVo!-$800AJ`UMryA8Ec8V zv97E9{~pTLWeTR^pn{&78XHj*zn@#8yw9;oqmIovD)UomR_3uD;jfqa#J-QeN)6vemV9t!#IK{qmZp;VmNl&R&~zea5U{n2_SUB{00t}q+8PB z%=AD*Nhet0Y#2!P)EOM%A4T`Y^YJWMD)m!{zye2WP~C$Ur~IMKyJT-s5GQ$_sNpF{ zx2}6C*8ujzm$Uw6sBtP6@^v5qhPL+h`0WQD$1mS}CoWvM5KZVdUJFT(nNnR54P@<2 zET>2`gw?OtlLy3(0xsT{j$g(g+>@^JH}2(MK_}85wRAXk;yUSN{f1EhoXoct`uS`N zTM}tw5-)l2v=J5YSAX@Fv6RSr6*}S&X@+%hkG_Ek>G(SH(NR4V{M6}r{?dia%GieC z<#ylie)qdEk9E~pyFneMA@FhodRYt#JMYMN%3R>b#HZ5tLqzuFRgP+ zODln&M)3Vu)WCzET*(pB6Ke_si~E!dw&_1{P-9kfR*y=fm$9borTpAlX8;Xgy4ZkXt7_BG@g7;=XjRqd~n@I2(X*dhg}?vAf-(IFcN@1o)Ym=kerg$Pn7`<X~_~J`WVZ9(4k22)GTkm#bd+gc2FD@e^FF>zn(Xn6P#EBPi_KcZ2 z1%_4Fb~Kdq>3qJ)*B{2wP~y2FhOa~g-XU@Uc1TA99`r8K;U`jne*4hqmvML%&?uBr8Mq3CNH1cKf|2NGc;i>UO5%MQ=ItJ- zLZQX*;d$FkW&r_c^s5}{k+yvqZK3pI+$A?t@hg~#%veRzRPPU|9{*IIqd_K=@C5NQ z62Sna2bB~r2~*`!A`}i98zo{*<&%3=0-eJtyl^UtGOHKJnDDG&$LOSUEm2gQgF+~c zbeVN>>OvTo6lmX7jvR=_olI82-`La`yD_RO@$fzO-0Dny)o9j8l)(F8rIxXl8tf9f z%*m^OP2U>8q@1S)xK4+1nB;i`&R!f1hYlQIA66&c)}=7PTG!7ivne>FC0fo&7=>qCBSo0(qH?UDC`VtO~H; zCzY{nV$?rzG&r|(G_dgLXrP~57x2wUlK5c%GEjw?%FK-$jF}(Gh}c3HI28uQsqP!G zv$ZYOwG|l+7A*Aopa1KB6{}aSh#KgmKg#4FV4yG*=cE<)OTI}e;JkUo)`@ZO0oTet z{k^29=xz3U1*KO;bb+lnZv;o!yI)W`6)#nsOe_8ZeBZQwLpmCkvX|5hj_cRDId;rF zoA8vItQCR?Qw9ax=MhLov4H=*UX>(zg!h;&bseF)2e0;86!Sg8mi>TU(;4pE`hHP6 zW?WR44~`1*Wd~wp4WbQC8xc=T#Vs5S2r_^t2=3yLkc^#E&Z_T!1Nf0yfDbr!`Z5}J zpF9<7j$?fAeQ8_Dzxm_WXWUQOL*|6E=^lG4>kG5~IJeAnkVk&8 zbxR)eXiDw0y83iv>Bw}=+!CXaB<-k#Dx)+yHLi3vq@o8ONIYjQ_M>7Xzt_?5!N+T2 z|L&c!V&#*0)UnxXDm&hv${euOnd#nH6&)R(!bvBCaw`>I{?0XKWpBglg}o8GRvZn# zX6uAU>^_5hG9qOfsNz6lS%i@8$O|KR<1 zWBFq%Vg)?19A!}Fi|v(^Ri8H)V0MZQcxz+`6O~u{%=OKs1`mM^kEV08y@QAm^mMGL zDZaxIa!bfUQaRMon$A|*NaG(Er(+!&=nvk@?{!>jd|C|gI>srG%z|sfN0p}&$h?S48K<5|(K7#LzpGQ-siu*d4T?4;!&4rC}TLm~BFMRIhd+|j><2YmA zw0RSCgxa#=yqO+48Z0)cQkxN1`(SOAtt!gJcACP`VEeACwR*TA$8DAKvXMsZitUu| zqSNTen}Z`@?i>pZB0qrdtv;i42yMcg6aUk=W%TKsrDYurIs>GsYw$Y_UFDMB_kahV zZrBj(*namQTV$0@lZftg9bXx>qld@1GI$az z2QsD%H+w`QNIB~`)jpU`f%Cx08aHZz(y~k8)eB5-az0-F;bVxD4vW^#^KAX4B0kSm z^SivbZg@rf?ce-+j$7s=1z=%q9O+xVR~nVxbTr&x4muh%dOayaym3FjTSH&N@LIsy zrXF{NRC(IhFv^-+yvrX9a-@TbK6Nt4*W5DWdg{awXLJI&E-kICRMtPtHm8H>XjqMt zXG+baG!hGEn#0g&Lx%>JHRPmy`9aEAah|{Zt|XtNEuEWZyGT(-_8r10sGMEG7T=}F zkaC=wIvValqmJ8bKJ|8agLpz|nrq#4N2Gz+2;>WO92l=Zd@`gNm=e2kNQ4}l-;4^Jc0 zdE?mAX-qqgRURhX)v$Di%in~P@>()C9oGRlObhc-pK)p=6 z!R>d-44n_QAwQHK^n&MwJk@Cct$|BAv8|z?KDLA4*AM>ahXj5e$hJ~{$KMrC+JH&R2S6#QwB4fgpIJ3*Lx)KQRLEg91R2Eo3Fg`-PAd*5R|)xPBVhB4po;< z9%&|TAx9F{^qmfP@KZg3U$Zt#KkSd;IFl|Rm-k|Om@Rmj^*s;mo;ukUFTGAi1CEBu z+FBS1V=6I?Y}EgKbFV*~qd^W^x)Lz19Mp*Nv@bInK8*9H*gAoMuyhf7r0VPO48xEB zbP6CA#MDstzUs-AiIy0L0?~!jcva92U=567tE_2+ZGyRezWMX0#R)KbwyCev*e^Lc zjo}+0MG^-{p|?pyO$PyEHGNFQA-7I2eicWCkx@;tQxD@gQfPj|p1>mq_s1#(+sv6W zD3CW6Lg%bzh(yn}Rj(oUBzBz_8X7{QM6fa_6=)Gyf|NK_JS5nr7E)hHEt*(ULu%2g zsASv{fJRw*i5Wh?t^%7a~?sZ!RwF7P-tJ`QSsYGO4_?byjD@nWW};& zsf2o;Oe9mZXqVd=53mO|B?p7>mSH)O6sSC8+xG2Tx{2y^u$~(>ZQ|_r_W1En|9LDT zg;c^-L6%uK1`T$FnTnze#qVUY?mv^62rrde2Vwg%6qWxDjN7JT5IP2L<)n%6Ez*K( zr%X*@m<$vcN#vgTpz>+E!prAvOE{;x#b?{kJ>tR*!Rfx~g9yyShe%z*bNR?)kH-_F zrw+%-VH%%`oEav$?-)VpoNZr$R79%_<-H_$RD@KHTyIls8(WUWXBdwyO^uvnP)R1t zN>a)1&x*npsZ^m$WgXaS1Zspb;1nQ(=r`%cC>ONTLq%IpRq-gC(c`EX4UHIq{gBku zk))E&nlUT)?bV>n>0ENI3KQ{KTor>z{uYc@lc=>xj2ptXRx8OSImv^o+ej^Gr4xI0y7~dwV!J{r!0)|0fo@$`BV$Fm> zWh3G$f_pzv*Yy~=yTHeHH*d~4*3xDj3hqo!XPGu(G}|ZOODHU8e1*e+`GWeX*lP6O zfz75<)^{eyPszt@OvPK?G?-!a!!c82H1x)<6GZS%6cx^k-N+ID_D_Bs-+l3gJi9uT z2G&MnW;kOXMP|l5IyL2817--YOM`&^ZhKOKim0?NE=c<> zWuat|h6r4f7pn9DbK&oIDqdDF_n6rO(COQ6zn!vTCj5N~3V1_(L-O%%oQ6h7jd(fN zEan9NQBG*UxTY$eI<)SwSZNfgOskCHXfR@AjfVB>K8cAFJu-L>O6ZK3NbQmStX0+l z>4SqjKpfI>DGnx6B@V5OWX0Y zSB~E~FdrTJB`2D^(zZ+T$@RI7;+feVd-moY+wYLUvwG!9s@X#$;GsB8gWweNb$m>~ zc8e^wB8ukx)5$?!&eirkr9@i0#JZh?uWbG5tITNl9_=q#cz@!D_a#j;j&!>A(XD)b zFgQFI9FnG82ajL8f(~HDm(|_JQutB5L8I#+JZmeoHF9J{d>==Kjt2FCThNj`SMD?v z{vl5kR>DC;#pmVi;*7?Z25%A71m^rMzc_OAD5>6u<8)hFJVd1KnWvsg2hka5!K|h% z+$k>b@^i`2Ag&a~mO4Sfua&0;3Ur8!98-~n_tuj&Wh%MG%mdKUBI-aWpVEO3jTxO2 z=dA-GEJ}uk@9H}`Of*JIjsOcgmJ!&{ac!34Z-4t{W{oaba9`XHuQa2<3h9^5b!DdD zP-tp6vQJ0;Ab1%dLRLeY;6*ypz(L`IL{C^rS7jJRIv>`oTNfYw?(KMF+45M(2@+E$ zaq+I7MpSaCd-bNuVM_~l!_iDrz_ zmtX!4v`XLyLtq&6d?ubPk4=qeAka}$J~TKWhpaM;Ie8gtSB%@CGiF{{)L3{p zAKu~gtPL!|-*JN6#wljT9%cLq^>bnj^6Ny`<=D38crPXZ6HmEiG(AIuJWBc&9W>i&tKvuq`^PnMpU{ zw_frp4PccCw`gei$^+E%zNTmT5-8%R{8QcV6q!3_@a)A-P&a?%i6>(D@@2X0(X9;z zBdy$TMuvKsdQM5l*72gvkopcdC_gqU(bRe)C>sq@XA58&A9NB&{oCtGK>yO_H{>C3K=&A4Es>4rIs=e)z-G$K)pl zShZc8ySk-wFWFO$kwy|XfXlSzosX;5;n z_c$Ltibm@`c!vtmI58eywk$IzWS|nD5ef;+bu)F=J-lv-@RSedr}xj_OH9h~mOS8Q zG?-qrVdKVVCe`ytKlw2=8tzLYS_emZLm7w)wMTKt^(2H&{mWt}J@vRqRf>SarHkpDCfp>R3=1+$MeJK!JLt&rw320x2>EEfmLin!9 zd6>l^lsLWfZA7MYG?-1IP`ZLp*C>+d=@Cs2H}H{xl|0{$Qz4-;>iCT=+V3DE@(je{ zLmNK-JdVStMj@z|v$t8;xJAe|?l5L?zF^?21&WYD$-X=XTY)b#RKS}`ssLhgL|#Uv zk@pqe|MzfyjVT|M9(1!BCgMRan0}uk%k$Edm&RRsvYC_ZDnML+F~#*zAX}u$=+bHS zzUpY$g<hELfN;x!i^*Yt_QqP8!ip}cSF1P$lfyB@;cK2!|s zm)`So?NbdCR~eJzmVev@AFa%Nhm_K@*Vy0JaV562S}YdFR^PLK`xk#6FFgHZ)_NJx zPsKn(p-{BNcMF}p`Rm^x@aM-fE1%4*6Dh#xO9djw!RLfCyyg!4L1js!%Pmg@t{^zU zdks`+A`AbqUg>B+sBQjybG-cB*J9a&4=0ZF-bCQvq+nk!^=8aI;2CQn+$QXC9pzf( zVmNE>(N~$#Aly-!uOTpZG2S&BK8sx_aUX8klCzuw3e=K4KYjdYifvYKemeq_NU6?- zJbnr~yp7SNlSW5_(RrN>DnED7;$8Jzc_yQ>JCOGwygUWNadlmH>qJ+qKL-EeI-mcK z`0xMhU&IeyelezEa3@a$NA5DlVHh112vlLG6Vd(#lA_)Zn5npU%F1r|Ow-{b$#a%s zcr9bw%`hAdc=(cc70%rv+9CaTWo8m^754Hou|kE#{kFc3!AUe29^44ty#u~m408I+ znHee7nXJNQF)s~rD}bk>#k!@V6GKdzl-DXpl2#eN@R45A;UK?*S8MEgE_=?midq#4By=lnNkq~WFX`)8YfJp%mv5v2@hyt) zsr=ioTN_f569*hGkBNIaf~9?xFnO5cRe_dY8pXFwzn8ChkHsr?!f*S|($h*Q z*8S5kTFf@5x~a7ZldEi-F^k6t_%L*=#C^snUdprm&nTUaKygr6rS2hpd0eM~AB)$m zCF|e;_S)YEAFkzSL-iWvTpGN7Ati9TK=ZPN1a4IBfe|o%FBem+j-gv&R7_|4gC2b5#EIh=4TXLog)i~>Zk)Y zSr>{mP!CXMsw;XlqDL=Fqw)gVv~3GXn}vG}8r_eq(x{sXe|+_oSE9Ox0;1rf$3?0; z$iw7Wnu}&8i0f%Ys(-Mq_9Jb();fbSkOf|zrB=%qM5Pbx+nc|eNx5w4(hT%n2d{6_ zmcbb_LZz#c5vxuuzYw?O^#gFes!vF>>iFfz4kO5|jD78zHPP16664U5o>fGR;wC{SFIdYpdbvuulO$J!q=KKD~ zAIG*Wn={ZUJ&h+=>&aeMpjB-Jx1DG7zK`cCKjb;CT|a4xH5KmagDk<+)GZ|1|A3j15ojm}r(wM>w^@>C#y$7`TTIXH8=V@bScjKid!5=UFU45+CBV;T3}U8Dog@6_{_pp9G%$A+mlUWh zln9vE;=;*bA;lwy55<>THX%UUqk?@`IvVCejC%PjKxA5*6kr+~Scd|Mqk+Xw(Iz6Y zKr#RkQKNDg#)V25mZ2L_DbBVoeutNP#_ZX#2%+i86QkTO2{MZ8J}Z)?AcJUbq6q25 zOeVr_BD~B*W+mg2a1{kAeA=S zX6o6VLcvQWRS+Ts1e2ii{Jt5_*5CjA-)AA2Z$aplIATf$xoN+p`|bh{qlq+B82d79 zkXYuLo`3!}LgKicgYcBu??kEaI4GlxkCKjNl+nSdaLPzZ(IbsbD{5z<6Z+CCDU2Pn zFBzB2ryqo9AH5LUDF{RldK0jD<<;+}QlSFmI%)L#jCkSS_Qj}j>jDj>mtIezgzd|W z3eX`LqUUGJL`;9(fl*zKV*cE7#nuTk6FkyV2F1dq(JoGu)>sBDLzQ{J*OOVh&ML$9 zD}Hs8rE(aYJcx1E+R{>ZTZu>wuB^&pFmTgUh-6SQOqrlKB6C!D$iy78hLNdr;=IOE zDn`s%4|-9fp)HGxWeVxM`TyW(03HS2fOEjfz2&(b1_;UQ5>T|0#suT_I6cA{Xntfn zFt%+7druOn8dDYX!Sxw4XG9G`&bbK_g@Mj8;qJH#rVF*vrb5(tsSNwOYg$1T%>dhG zZs&*?ee&75IB@i6JoEhXSv}e6xL<7FMq!^rv3|?e#M{}}oiis6jykq;RF51Ig`)xd z1FwWrNnnVJ;*a>~cV2u<#ni~Yj<`IJo8QcA>cu#}Nz|vK`(|uwIUVcUj6Bk8K1ngi z|M9g2gra)SJBj;K6tg$KaefbK}VsPe4zj0jK}yler6DU&2K? zOCynYX^VAv`?!b(L*IIHabmyU)D*YCvPQ&(a~(%$cqrH*(eKn2N)S0)oU*w*pFk%G;$q^ zOE54VCK@*c1-|5H5YDbbMjBWz;hJfZeD8V)_gojoE3Cy|Ga3eJ1i&Ld{NRJE(NJ4o zACIurseb0nRG>^{l!i>DFOBaWyha+(5s;2v+NbMWPZdRtBAq1~)JDHdzx;gt`j|9% zQWk@3sH2z{yg<5F8CAiOciaQNjOf^=FXte?S6P>jItS@VME5t_H@)*+#(t3fn5$Mj zlhLlR$Pb;k;;Z9yom3Pv8VJ4UK#`B8d{W6xf&*Qmoy%^7} zdRm5xryfI{dkg+p&{P(dlTW#J@O9yxkwAG8ePmibyeo|h#^V0oGZ+{ z)z8KKDA9#6VnJve)XYyluIzAqRd#jKikHq$V+E#aY8Imfh`!*(9#7VK{CH+G>|kxj zjh_%dAR;xfp&`fK%lI|cHA*#HSghRtZr_7YvQy>)Bl$x*tZ6s-gK*(AtGgF2##iuQ z>w2`&&x6aB<7jv$%5jX{QVFNMf!-^RLDx{pH-p4W`5|s(wpZdxft$I;{>^=D$4}(e ziRPxpbZk6DCgpwXS$BFpz)ZZZP6p(*>v8S;g;b!Gi)G4q6lt{oxJ$-|H7k%{ zc>)rEj01c2#_!&F8&=($r%o(cyd?L2vpA_RBh*-Y9bgPtd;!0e6Je>i`Dji`4=gtr$u(;|80zVe7 zOL~HjNT&wEbTFjR3=S%5Q}2+UK{G>HJ8^@Xfg^G_*A(y|6Ac`-w6rEYc^qvmLBf|U z6g_ED+~HIN_2AV1SMWgPk-Bxl8V%~SiynL+ z9 zWUaM13+~Hyub>OEL=1y=8Lv75SV@~W2b5F1_%ihi=kj%S9Qb7YEgv=`&h2FrYHAYS z>+9;s1f_-)^LEYTGj79^7u$z$_g&|D;veI;k6Xwh=WlH;9bh1CT%$1Q@2C;CVeQ8_ z8dg*Io9rVpga#uQl}ENEpG-bZ`>w0mB#1I?J)%66Co6BwI<>agE&^cc z@z0Ts@gTOJm%oc!uAexf{;4hFeCCu~Nfb3|O!X{TmWpxPz{XfI5DcK5c((+nHB{S$T*A$$n^bAgpla+mA|Wa70Ry2oQn*>cVX~a+{nUy z8jN*ywVApkBC7-$t<+=b9$}4Tx=F>t`AaYf3yGVH-V&knK7O-rQ_|k0hQe5~Buw8Q zP5PvSk!f5o<5XOERxh4W7ZpU649BnMRwGxX%(itjs8A-;p=}k%gNF{s*3Fw@5qqW= zSStr@3Ks`jIxt2jNeVg*tA@hCEQ z`j}@50p^&Bi|Z%jgh@C)=OkXp_+(JRTR4^kk>@ryB7B-Kpii}T#Dc|(GS#~hhlcYP zF5*Z!Vi(sKoX9`nud-E|XXA zDj-z&N?U>y{^G0s0g_ygVvZVl6vv_+jcg<2T_~(uzx*4H&~3M_G$NJmfCdL;TPA(y_GRCH^@-{6h$G=uY9peJXEv zh}ztSwmYuej4zvr?6vcp_xm8%U;f#j#FLLLqZ)T53bzg?6b$B|p!4*HMvUF{pM4e$ z4b!MX{9wY!b+cFRkv4ploD8;^xWW2KuSUbf6EE?npex!2CoER0;M}!+Z#=!~+p+k* zMM0v^6kx z>^qSCPDFoc7(XzkjvbAoVR%#wMd4AQ;5CS6<)M1i6OcUNRt9v|d>Oq=M}yze(U1p^{;;LYOH>8Wz=GDyUol#Ok3?wgwr}S;*ZxI`s<~? zd#TtB$YNeijg5JNi*z#wr`iHurgiHykp9It*I1lz&4jhIrZVAGWCO@^bo3TRuLTn= z3fv5j+)SkIGCZT2h}8Ym_?cE;pZKOyCGD3YI`*LC>jA^G=?p6I|FR2Q&~hHhWKgN-4 z%IAtlAEVe7wTbvG4GNxN7|FMCOnh%&sr=hsA1(Ns3a(0-G9aTdJgEF|E7JSOr$=b} z@nxQaUZn3QPiO4XlylXXQ-;W!{Y|*oS0P6VdXwg)H61->8d}-g?F}8wVHvz;7Ch3i zISygry(*15V{`~8_wIs=u5Y$2%y8PLV^7+mKVhSz+AN!vRx0J=cyz0yg#&9jS;6RT zX*&;%Bu{q!_TjrYAuj4*P)SUg3Y^4SBYkGQ8PVGZ&bTGCy{#?g-M=V{L3%=fvP*tc zO2I8s$cxnU(wexI;$!k6=zxy%o5D1`m-1t`ZJ#`u>B)~g`e%L(0=iXd|6>z+EFuS}nK2M!E*LglZS?5uOow0(`oTg49gNKyrAs7Sw*w!K4SgiH> zEsXD*;3nG>$_Yr}m&0LVBoaOf$Sn%#X-GOt?$UNk$LaWV>$doK)0gOat#R_qDVHf8 zni5e@LC&co%VO+MBADP;W;8IDTt%0TdHmyy265BhTrZclph1Djx8TNY91Yjm*3nHG zTI;#Jf#AqBwLukOrxLG*D&31&hTtQk&9)#?>!1jsl zI0oCHr{@S-sgFsYX-L5%Gb>0~@|=3B-wQ8kG&6ZvTY0j)ARV&Yr~Y&eK4s9y^s0vdhdkFvj0J^-B_Z*5I_ zb3ebwfxGQidJ+e9Cfjz(dU(t&#xJiaAYA}OJ|wQlL!5^hLS{*~;<)>K!v>sFCu1zx z01u!S%$hkf=Punif9Wab&O8z)?TeQ*T58XC;V!&gRO@~Du1@e7!Orn)ozV8EshOAo zL*e{2zUL$2J5b?ybrRvEfh+E-6J+)j<1TbPj8b^9yvE|(+qZ7YtwkUUUFgtA#Y@fmF= zGr+xU-^=w&+~@a_?&^HhH4XNuKWj{XK%n+MoB*DBXC^^9n`{7BXwUfaI~|y=MZx!r zqTIs9%#O6pSP$pmxWqX#Iu0H_3|=AXs?7dOSz z)Q`E}b#WcUNwYn6QLMWc-tsKj<};=>B>kn+9NwuT#Vjpht^Jp}2jfdQA}{4Tv*PF? z9mxHFjm`}-8mz6PUTs1B(_QD-!hI_K*-!r@zVph<1konKyKp)3+%PgG2B=hi!>>Px zqd_ z+AkG6F1$!9LT0sVB5Y_B`L{-umABhSl{5lY4I`<-XdekeyWkR{%*qI^%BTvSN`MSR zWc7KG*L(G{ik!&^7?TE?#aOJ;+=Yj0*6djvKUs~k!5&!d)A%Dm-l5q%=tun8!4EFGUd3TuI_7w>hF%xc?%0K-&Gc!hstxN6angF;Qa2|dcVR; zLslkeW!8&CrWyo$Nk=Y7c*H4^s?808<*863KGAy@dv?4SuWTcZ|YHe*yKsdOD z;!Lh3KcnreHbsVUmJg7ThUfUn4!e!H z$k>_VaWt@}czn4T4d5J1m4<-}aOa+)%>rM9qx1H1j4FfHFUY-XeB=Ed-PL~x+c?O2 zI&<|_Y~|F64Q-?|^IM^wM11S9hhsJjzk)Pnm5$P>6Wo$?tKjrZ?rOZkvoTye#l(Jv zMLH0bc%Kdle)ICP0^-<_=9stOAu68Nnyq}Jv%`Mqa74m%Q z_&~uO8&j&vW9$fwKgKhF{%>3X@2;|i0=yf0JOlytK> ztQByDsFUfh7tVL(?~^7?jwv3K#oWbX@r(uNqs4*-g|BNO4GDAkn7mV->-Q>i;!+)jN2rJLMyd>^rUb%La%b=OE`PKj!f6sc?s*JW!_b=xQR7DL38cpwT#28fFlPF zKtp4bPOB=bk|s68G@30QEDfokI4+~C;zmiy7bf=OJtc)jzTn>}Kgd=&!T4vR2&tT# zRpxyO%RWVpp(ZWLe@!p-(nuA4!bn`VC~uBmI%DDGOFF`Lk`-e%#Qb@4QvvmU@gi|J zTLO20Nzx03p)gXh%eH}oe}8=e58>o@e1z^hVhcv2HH0)=9GkpE8JTbd?o2)Va{Z(w z=b&7bo?J_nR@*9QiZ$RnpY@336DQlqqB=`K#rZJ_`C;_m-%62DKRX}gwnnvmyRf;p zR%fyUXDtd|gA&XdSl zt5B=iIDXgF?IDi&G|mj8u@i7$D7(vnjYhfS6Nci8Fm^6hYIprg3cP#Botq0KuI3uh zzH_~R+-qxZ<75T0b$E7iZ7ru!O-x6NyxVpix3C4%6SiqYVzjx&;?*_!73QvqZD`oh zQR*Y61-G`gByMXgjYWo-NhuEbyje*)WW--HN!%{uXUC>Kqp|2Z33q8A@t;Y{Gc?59 z4tf*^)#NEtb4#C&Y}?2&15?K;ER$v#llUSGi1XA&;hu{TtfU(p$m@{WK&i*mrAZsNrf!+&;lyZ=wnK--T$A0e^ zN<7AFD)k(JqN7yjp*n}okxq;*9kw;#jRoEPEi+T4Pe+_^1>De}-R zCubKK8I_fl&?!!8*33FNUh)_KoS)T0q%V0`;yZmic0Y@ZiTBLk?@IDd__-Cg6aBz( zTQf^~(Fx%=g^6n`UvR9_Y1%jR<+I{Tw$BKZm3*CRAq-uU3-FlTI8Bvvb6L|d1lvk; zPu}SG0cIgP3O&-_?Nk1qa*w}7?#!_4Tcg6^e4A|n1Pf`uwt@P2$PdTnJcWqkb^KoP zZ{Z@pH87}sAWo)^3T%|Oh5qQ8Xj>IJxDK$6w)R-CaADM;bJ(71>gBwJhjVo^R*K{ebseWNS6B_cEZS11Ympc~=g5lA$$ooSQJ0 zm&qfYqfSTxFC_2M#}(S|fCsB%U&e;JM)2@pV{81!|MY*xtFL`OCR9yC-_>!aPK>_9 zzi;~W2XZuMFabo+N5+>_&i{$+0Ioai?b;I`;nmu_X(JU#*9YoS%%if-y-O+)cx`|q z0l+woqwE5|Etx}vc1mq3bVhK`bexD2huVm)vM)-HSSMQ_(2PYfiZ`0rt=9*saCv?5M=JFa}TN78$cChUwze0>M9wuH^ zGcHC{!XRP3ItXOGD)HADN6*>zxN(_dbB5zcLBJZhkbrNZ6r8_$FPe*{;^FF12#G4T zTy(`v&Ws)~2qrSL977(b6h_-%7?=_NWEL=*p34{GO2=`8r+8W5#9-ELAgM^*XNgSr zwd%evs9vn`E z>MKMkjsc(oYe8#PN7r>8yF8|C{Vg0XY| z!65T9FW-E*1}>ZJp5s-zYWPqMQ4JaeGlLKTQFuzj7+w`qD#!?_Bw|7FP#C!De2vKb zwacy?44i*D%kDwA1A(JT#i91IU)Mya;x7BVsSXFzyGJw_9vX9zqq8Oq%#4N!>1beG zZAV1{Myxd?wdej{w_Vls4qf(5k3 z4jUUIs9ACKJg~b&&4=;hV%WF|q;GOeqzV%_(~Xn$;%N*Bo;5Zwc+9xCO~%Si;Bo~8 z=X?*p0RKv8vTnkNm@>8^CRPlKF%*LwrmzL@S1xd*)YU6|H=OMZDvYYT2zlnDyZAuTCn@$g4#!lXpk0p(=dNUCgjhA5*Myp}M4~9xcN&=Ux99_D z#{lM1Hg-aux?%Q+_}D{w==qkmyl42NYSyuEHh7}PZR%fK?P4nxjhvtjFV~@t*C=@I zkP3JL_$p1fX0Z3DP@y3sL7cmZ(b?T~E-r%?!a|zXsp2)Rb^>!45iJMFZsKoYF_Txt z#Hyr~o|C8II)G$3=m!%6`1c3y!^j%2XsgZ<(_MSI&cux_PqknS@ZUl3q=CRqC*xI= z+l?nq(?WqmQ+Q{335(l(yvZ@SUh>tkwG(6Vw3*4r&SA)&J#aW>gmbGJiNVNtZy=M% zypEw2i+|^NNuLZce|Np*W6D<7n5B!ds`1HlE_Iws{2V=b ze4akw*1Mae<+dLxhY>JEL@O!hsyY=)+YGo8NNl&;#CPPmQ{?wNqH$QoCLmnC$34yuA8_gT!h(B z263J*I`}NE)>My)@zZDJ9)6wVJ&gSZIDLclRZib#JHj>S(|J_ZPeLvaj>AV=5-!fE zp4W)~pSt%Bw6Z$-a0jG=bU_4^j({R6Dp(N&6crnGQL$?@iZ#(_j3xOrG1bK0dl!`6 zl%@hI0!kA&bd=t!a-U~5+kE}reDRN)H`yM}K6|fsy|bqNX4Whenn{*T-_ZYv-%;C9 z4&A$B(}pO=ylN1*YP%hK~z79L`y^OuEZ+9(nvrICI03*=_uv}M>){;h2*01d(ptRMe@T_JM827bpc0u9^C zRf$aq=)C2tW6Z?GF^7p%ElV{Qg020u(PLGL)d>^V)0Q}HT-|}$sRRdnNnl->Ds7^wU9tQZ5R`! z@1O&+O2WpdTL5jg@!F34{cej%jsnfqX_e8nj=vQDX+FREJk5ADz?U=uxnU{(A&VoQ z`qVya?Hc8ycH@0>>w-RwI`$iQehs$9&uN<~?m?Weazm_Rz$N^y9D41+s}?VxuPj1U z2HCDqmEam*f76V2KXxr+Z(Y42cHjf=R-OI;n<(3d zHy1I^KD?BDdERAh%*$t!Pn}EM8azWq`ob(hZg#y_r*4&~-(o*(OnDj?@;rcM+xV%i zk#^ePa#Tr{#ZD-zYw^E7R#9=OD{9mt5a%=$ukYBxu8gbfcS9kU;XBo#OLbx#6M+ly zfj7`&1WXAZ0e!*^)G6u~Szdj-eAmnQI)09fOu#ZJd&-?MSeIwtqgiWw{2B=i%Qwa# z8=%dWRZD|j+iCO4as>Krhgv4%hsk1S;KhRk>UlZ(+Bi-pUs!gg%te8}H~Cu$6W@Am=7*gKO*f|M`00!QaGr7o10<^S$A9 zNA^B?=n1p^=a2tO{r;l>4Wc+jluFGi`lK2(%-}DSUrvtqY34O{^oKEY*y#UP0--Z0 z52^`&gFJ0q8}rx5y8r#9;Qie!{P&;v_wUO54Jm=Eh=DV>S%>k`sQy@2Lk6l$gFKDT zCNe6-Nk7`9K-2+MuSoFX9@(|4*2c0QZFJ_%SRSWW5odPO3IGx2{y$UxAHQ*ZB(t&^ z2(0l20wxW>k9E~#pc*&>qO?0P4m${%T-P6C{wkU3I2jdazNqn7yOahlKi0$@o7bLo zIUNBjupNcC7TSFKBaPpfaY(FZl|b_3YJev#&j0Z$D%Um`(^h-!2GCG5>bZ4dS2M`J z0}UEAr41c`oE3ov4UCSMl_%~8*9)^sBN2I=H@6(@1PofbVH-fhVjN~Fk#^0MPp7eT zO*Kyc>;)%MEx^eH1TUM{t%=1O$Y}fngF3JOZ61zajY<9u1E z$A#_|P4=o4^>7Gkaim%mK(#W`5C_-hRplwGYY5<2lZK3?abTrNv7$j^>Rk%(1LTF? zu9-Pmfrjs3hHp1-kIxBy`_H8un!ow^^4xmUztdHw6;gJlDQzLTfKVye=zF*%nft^_Tp8kCZH-A68j7+Ko|VGNBd`n&+qQZf2-9o zn@5%u+AQ4$SoTkjT9A}Nuveot8UeXj%l_@9|Kzy;`RnOu*RBdUzCBj11t9v*ANW81 zuEj?s#2%IG5r8~V#=T?iL{ z0P|VXAM@Iq1+K!rZLjs%kA*+t;L7(tRy|>#^l6rUv*N#XWdEjJ~dTv;` zCVdXI&W~|v`)aZ^tQ0B)ZFjA@^|3+UQ5m%?1G4{5jFeMN(MK@BVj>=^u+Ukep<2{d5i3P3}7fQB_O z{)>e%i%78=$0Kh7Db^NRg$7Pel`hp!*o8IUtoqSt;`3+VR1KaX2>T9yX$e93E{wuI z|I^pr%)N4*J@WZCSP}UnDqzXE4_Su_fF;s-6}sSm@|TkI|KQW4UjSNAQM46#TCi;S z4?x8~IMjdnxcawRCAPA{?;dBob}h#={+Cbv{SEEeKO$@D;CfZ4+^$SY1|7d{701y3 zeYk)6U-cQGDiuC9R9(7;B*6bNqBiXxS$64O8@ij2+<_mwk-0DWU&jAO|D^V<)dbRxd4-WPJ zyN~}UKtq;*Bal!ewW?>#s%pWPY3{a-Zn9Hi*xbrnx6U+JX~+4lAgh!$7aCl-#}_1$0LXG4%N`A2 zts?lL+@IO`p8ItzO|;a<<5p}!HFU&avWDNs@g3UJ9A>}lvZl^Knz`@EZ5ReYma}=R<6n2`f5q2 zrJ!j*8Qc;n_t;vZWZAzZt(MK z>_La`X@l0PfbaE``?z8YuXP@`+7ind=qg5Tw%dDmQpgl(C%@4<9hNKIPmJX(@(ta1N zqwD1;KC51KJXc{XC)oJ=HFgzvB53rBhZL4!R*oSA5NXHjQzg> z8vG*fr+o4(EOyc%OB^A(l@&V(hPM$6F9B$nICmLaCul6n*NO(K$59=VFD+wp&!Agf zJS9b1WO+4n_orop>j)TpF6rV2ysvU1?LBE?$>PNvo%mIZB_nan!R_L}{q~DJc2x|i zJEV=gZ3(BcZ&_ub^pxxy`vW(w-;mp=s?vR$Ggfg3;7@pR8?;}z?3j1yU$#;CR>Hqhi#mLI%wSWGKAS z-_bOXlPxv?vy*g)eH+$_I+kuyVFE?7lEEz$Iwi?@J~&SgS#pb-Km#|W|3x{D4&_9T zC2L|NtSq81H^?S-|t{LkkAFCIX zS(}-8FCB5$#|ZbeJ}<@?h9mHvaG87G zw;fm-7fQw1x|2Ey8wp?fT>i9L?CZJn;+0pQk7esQNsI5EfBxCIl|$Yr@QJ<*^V4QH zCf{M;w6D_I%xx-cZ^?a4@Hh!|$p&QQi)mlRYyAeK9`14Mk?GUaV~eWu%Q-WaW2UX* z*}bpNt}Mxq#fF;N6=hZ0+lN7(w5(l!?Bma-#(q>79k749XbivCCTps!y0*%7$~<)U zrpj6Bapqf^<_o*ofPvZCTPi=x`fsLL?&j_EyIA^7y!l>#{Lb}p`pGBKr=xyu!K_4C zq5Ptpf5(5mS;djpU(bsvGw09;V=0-`HH;atKj>Bi5=Siv_!|J`2sD%i@UB5)?5@8=DM9_INp*|CuS^(8KkKzW9T+AtW6AC zHf>Bfc4dw|oqBl$e{=laZ%UA5ThoI_bD$;vjks*~i4O9nX_q9LtJp?~%H>JSSwy zuSs*~Z6#=7n~}2ScBT#ZK{jUocoHWuK$`>isS^ht(lHy@8^dU`Nl znk527WLun$)QgM|M1d*k&J&5U28yb$4#+1LG#= zE&c7mVgDZEgY@xp{wWkGJZZb3yM5D27L>#nY%~0vZ3IUh+%}JAtxw;iY5=JE@2}p1-T}uYLU}Km#k3#7t61 zS6(iLN?6oxIt|apj~*Qh=gs3x_VUr8-9a30iPD6SmRs9JT?Vnqi06)v`D8*o^y}Zm z*9>^ciQVF~(@x9%Ln=Veau;Z@DU_!$C>WIpW^L4zK!Z%cCDW+HBm?}X9UnNz8l1&{R9YGbOLMs1gq|=E; zNxG+V>Cz?Hng6{ZLu2Klh0(ohw>Z3G$LvIFu&$s;EBDH4WNk#_Jd44$|5iveqRv}` ztV626YaHg!FNsgTm=gWpdp}PaIEt>s`=em@ZrCuJ<>-hOFX`g*x^J>7hRf%1Ppn{r z3P<5mf#rTHgt&x;j+5EjK6>1EDo@7871vx59S%N-J!kc^_eIVL!F5puCi3V|N?!#r z1RK1hoA=eJlTKRMS^yP3myX=nabsh^8?VHk`yCV)(s*wFR;>~Uv8>WPq3M7^(-eBv zOQ69(&n9#>c<~t^dtTB<1zwqBnQYuL@`DfJ_2(at@$*;4#iyPe-8y$dkr>!{lpN=2 zGbg_~WlS;>6nrrU3&@!FAj&U1o0 zjH7avM~X(G*hI(qI=)V!{YPAr+_R-ZL&&yG9Y<4D zzyN25b>u``AkEA&Bsz#qr@MAIB4qJWip1#0h;a zitgRI;iNZ72VUi$jxpmJkSINNkk_~vFn>$g-89zjBOHgBbLYf(c*N^KeB@?(Q~+q$ z{lA<#ArQjUQmLw-b^hdg-*dM7D~-Fy=anY#tpd7VRvBe|wxK*W^R!kMd^UeYjHawc zv!a^z>f5JxbUM64G-As`HOd}!ZtY<2eJUV_Hh)_dbu~#16}T7dF|{aZcR=Z)-%AUG+^iy@Q|DtzJtBG+P+x8&b0- z=+JHiXY5BRT^=Wr=a?~fevJF{ix@s;Y^+)ePo8&f97=FepYye=W8BJ8qPvco-_MZe z0YiqxmosL>#2KIGGg_r(b&*m<@l^t%;t7UCF$FX)~S~Lc%}Wk+l_DzK<^{JDjj^eXOJJ!neDK+vlf8E>w1PdUSNvU&@z`qI4_h_-z1R0Ljn4 z5dBAw%QD%U?z!6(JQ0N#H9c#yy*VT{m>kgcM_f~#H zFQDJvcTX(X7IDfk9pg++#5wrD12TBAZ-gL`r&UO!>}JlKb#l}Bf}Xscvab^))A}qn zD0WY-`-umR7#Y9#?eC)%3v^2FK5+!6U^HsfDCJ)rV1Ok52t>*6?%g#|bq}(8j%{+O zT~W_SD`jv!<-ax?{TkqDFyk+rKNn}Eb96w*w*de%Sl@*HPPvD!%8CKF4s>;RP~Eu_ zS@k{XEuX8?45kHd{O)?d>My6yj2B*eJsRS`b?tO?o;Hxp`WRn8O*wK-1xLNmz*GH| zdYy3u^gTaaXI=ZM9#uA$0+7tc3H6kUG0gwW3oeL`?GKK|&_%G?G5oA{!LfXPUquH` z$JA%YJ~+;sfBVut`T4me^I|d$X@}73X)6^^S6p&&I->GSS-{B*p3wz_&8ZWz;Um8n z^`VZa@}Zv~K&`G5UwzS71w{kP2}-ADZ1`vc;UC!fvI;h)}gLv-nM4E>(WZz8iev7qJP+a#EzBdxAk4Osi(_>bc5yYG(!nm359-A}});nWw_ zmB+>pBUscgfG*09wpv+t&gy;bo6qL90();2gI#sM{>TFC({TK;7hZlnPVL$$I-rC1 z1GsAd046_b^9){;|1J0c>hOZS)@EZD%TnIYdOF+hzANz1cILBT>yB9K={odWc=fHf z=rOY~PC2nhv~J1KwRP#?RR!UNo<1){)-jK5ZKEelju9V!8jDNlnM2PnueSBbo>N8B zv__TKt1>_X_bClO+B3m5;_JK$bdz4bTsQSD?@H2q2|7ry?|GhWyw-nTCRU-J<^w2B zowp)pf%fv}v~%?uG~npugV+;ZJCB*3H|>kK$VN-wnTO3%tKcVDLFjte^JWq{(vuSUkDe6AAJHK$IICB*Zr-fG@9={lh9Hk? z>li+l6HHLb=jFZp9o^}rEcrL>?=q5B?+qFp_x|_E{$XNZyA?gb#)v9 z&@N5fKIBr$?|Dom{9jcc7++f1Qg>$mF`iApPJS=P+_5V3G+UDm2FHB-N&Mld=b~e? z`qAU0Q#1Z(vQMJ~?v+#5R=Teuap~y_Hc&K1$iyknXMYOGFM#K>Dr^4Ro;3CwGQJt~ z{^01|<;duCZ09)SkVCRbu(n#7tHaWU@?B+25W;6NnW-P{;L4bQvb^K5r>huyE@OZC z1t5FB{?WW~)98i{Yl9D;2|b=ac?Df2Jw2(!Cbil^c|zJJ&;T7=BWazDz_s1nOMv97 zuQ;7>;-q*VQ1h(b=j8FO`l$jLJ9s|rsrJI>^>Q3-h<2_RbNF{(>Iq-2y<2l<k*_VPhrJlu&%C|4Wr#Ms*bf8_&Vq`5Bo4|=&)$k zzFnMo_F1t{lO`#1DQhV)YKDL9>z@Z26gnyBPwC-mxB&c5M%d2Y=&zX7kAupYwnxBNC;H7Q8q>1q&=cac=v38?V zw^auXII>4aNX6%PQZs{57}-+~RDv4)LSRrZ#s&sDj5@{|pM^B#nlhEjlMhG7(1AnZ zwqN`_j>hQkfs<&}fb=kMP{^IHb6270gsDsvYCq$ed;k15!dQchx9INY1gJxY4vp8J zc|IBwC|-5Zg*b|B5)Bq;(DCs*KkyRIA|4xrg02?uz*QL=VC8dSqEm71w8BBc{)rA7dwd5d%kl z5R2z8iR-VtJURm0)u~wr3U;F~_WB6>0 zDK}cppS=3sd@aW~^~!$_7%(vY`ox2=YEi_UH(np7!!r#*=u1Iwc`yMl_)ED=gRfHp z->DOI*5oTQFzFcJOsFFTE3KlL%yCqYKlN0+IAmDt&scZ;Dy0X8`EK7z~gsz>2zyf>1?`|zWW6_u|vBBjb!S&xxba@$C*gFq=)S#-VY`oEa7!UG1MdFOY0dZWBRiq70}D z)H~WjgKSUn(LQ|!?Vou5`Doj^b)0xy7aDZ6%r54F#X7RGNg=S);ipj=V;Bf%JH3Yi zqfVCg*71D?-(SKJUDL6BqX|m;z11(Sy6&3j1bDPJ4efk>sTKt%lT56sUgr$-l)1^S+7ed!HZY^*SS(HENVTfNLm! z6kdEEd#OHfOam7Ej?}@BCVdcOmOtg%2u{tR%JJpbUW;D=_ImyK&O74d?%lGvm^@Pq zq@AyN%r8qLY39G3f9iC;s|{9<$(OD(0u~dotq=bG_c8dBNpakM&Ewj>H^q@ut9Wd% z{t}ZzA3$^DKWPPRTwCen*vhQ)-i`z9$sH+6_%$|qU5jqjC%ELsTca({b=EakMb|FJ zODmmwb*!>(0IGi>%?()6USVxgrdacZWE%So8WImZ{#0Cb+DUnG z%7F(Q2+&Y3b(lcAfv5aXZ0@HW<%az3{LOkJON_Z=J2syAmqK?~&9DZbVe0HT@ytsv zQ--}f&OZG#s@B@XJ`L-W#jVKa0StV0l3#NdEs3FHK8XPzjEexi>*jCf{vokTm7nE5Yz+i(qesJrox8=# z?WJPDYAUeie;Z%3he;d9sL`ZZbArU9@$2@?p!eh9L*l+We+Bq(NK{2mm46c&>J;^0 z0ZbBTD3w8-GNeE1s|XwkfNN_7sRWNEOq>|~-+d>Zqi0&Lu3h3f?BD+Tw#)>cx=VjU z{&4D!%R?gjChr6u^cH;E_Y0p;4=Zcc@yC{a^KHDzR_W`1^FV&=E_miFj>FsspdkZ5 z_(K2GHT8D`_ze8HkNTkia#|@zHXJ|Igp8*trED>xr>4BXnm+R8J8=-d-|%n0PWw>< zJ!nEI!57BKgdl4qk4qC}O+6zGY^LaABzX` z@+=D2-gK6}D_Z5WE ze!N9B`1`NFh21+dj@e~D4Au+rO97maMl!29*oN5Z2X&hE#TB&)t8`LkTg9o}yGP6B&9jGyw9_Y5CLGuCrMJmKX|HVfyL_TvQ|_`di}h7k*x=l% z=ehjn`ir#~pQKG-}WwD-jcnB{t0OGG^*x$CkeEi9UjfYI#KaE06kFZMHl$ z1D+W>W=tLnzaHS=rl0&I{V^NW3Kr`ps#l6}jP?Vfk_<=IkXP-Xf^3zq>9{-|7aJ(x zy8^pAhIzmG+*2{|%eiq4pxx!fASToElqBe~9e+ceu1`?_8UWDYxsA+w4nRXcs;>5E z)|fRrHySo+0=1wRGM9_afB*h7fBBdD&yNE%K)_@$A78DSoa!(BeDAnYt5psq3f{D zLsB(#qRmZ&@7^kfXr+_EsCk5yM(~&)&BkC)`uR7^E)0EC-&^gu`Wkt zcVsg&8IZ!5GKE4?3?B1In4^rSASpP47aGoDW?Dfu7<(G0V!;2GP7kyQ^9mhg~9nsD-m4BFFF${sssacaLKyNoHdhbk5A(9#~zE5PCq?*9NURw zLYpR9X_ir^zfk&*pywQSIVsRd#`QiTc8*`@v}%bXhL88mNX5cK!sB|wr^ zWa)l#F&U{gt<%5=G!(|eG2tExr-s^~y;#wpQZHs<^0WNCG(ujv+U~Iw+6);sES~-S z{qZ6FJZ`(BPh0?fn$Qj0Iq8sFjgr6-e4t@70P@lq(pEZG*Hi^1-}t5gOGVIRk9Bg)Dupil7lkAgG*<=S!|9U&1>I4mkx z2T4Uyj>E9sb@$ydZpQ35@z8d0<4w235r8~8h#Sb9m-d7e#xe9N4f{z4*HDm4FhDfh zmuu{O66MvHLRYsw3>Y;kF1horuqgh#E3Uw}^#o{WhTIjl1IT+C!c?^Uv>~SkrV`aK zYcY1?;5ilH40!vKnbY|MjeW4IE$Ra_u%BF@p-MTPoOv<1q_e!O>`B{#!N)=KO)kls zRUObP4Gwd5?kaZj7_pVo(xm_mUo2V|!{=?F0TN}f`OSz2Zo4UZ;-uHFT_;NKfdAl? z?eK;?k<|*UqjH%JF8ZaomMN>!2D#Jm@Oae)^B2UJ37^EnfBsAAnBxg{n>KEo+Z%L* z+>#;UZ^v|bU-?qb%400bVXROnFb)%ATf-LiG_2dSh9*$#Dd9V_7c7pCzW6F>KX3ND zxb3=Y(R&BR?#OaQnl06=Rs(YFB<-o`U8s3^THlGqLnAHsQC!zx}rG1PiD6x?~ z5-TaOtq0K1wneR|i;*mqK!X6EtH=czOCy&C0RmKlxMlgtY+cycLD0C2hEo&fEsnPr z7v7h1ync53O@O-RWPtVtj>^6FJecp_ck3-6^rvM9^mQv~iUmJbBEa=nVuOIZCu>~{ zSTZPuKMja{PoC5P&=J)^_=3#EQ_nmdPYxWMJbBk&|C$vO^6P3!DCKV*A9bal*Ew`O z)CC@|s9si<1(OWWd4nde=mIhm1~j7xNN>3OiUg`}IQxt^i;9N*TenG|Xe}kuRT!rV z0jfZQx?I^ZKvF-de~W>fz=c_tg3JnNko^XD>jz+Z(*qC22`!t%X=k4o-MV(giEc>6 z3!U51Gp>X4(^-){toqVXQAcX0+-~4{r2`C28y%lsIF138Gs6e8R%NEAioPvJ6H9Na^`z$n72nh>L@<>>@(QBW8!3i zhL!*gl)+2WqK%i7B9W_Ml__+Twegw z_H8)=k9CyKH?Q9ac(fH+Ap?qRs(*bB@1-NFEmg;D!WrGdakQ4es(Y&ggs;M{7(Q}D zJWJQ_k&9PE-`>6BQXIafG!e|KC3G%k>(vL&S$)8dbo$j{E~sm$4s|W0xz!V%>LAeY z?29kPeNR8bHzNM>i#y^p?8hEd+hwwW?>JX&g+KXn%AhxpUU~5&*OE64+y#%U5HMRh z2?t%EVc^71hSfB5KFP%=B_ESi_k+aZC5y3w!($6L}br=sVpv-UQF^m&tptdY;d zugr*-@ADF9(B}ElFO!FM!Yeyii%q3Dx{waO3jrFwELj$_*}|}e?_xotWvkZFvq#t1 zyFvZ-SNvf3V*B?l}DABv;Ic%3A#k^6eX2&F{o4D3Z%*7slT|to$aN4 zb$o1t;EDJg?_<*+?LRoqIlg<`_LFO(ZOay%%&;kw8>N`5$voGxpu-EGrJ3Vm^@2Cd z=jEsTufJ5446)6u1sd+S_ulL)anChZ$5|xZ8j=uG$4MXct@5tUO2ss;81&JPa)ErtD)_4Y9193@`yF@0#D$CECnT)SJ^y@;hCh&TchImDo)H7&WnWWjBZ*jOqI_(l-1pPu(igr7}Dta5n-U`^i85E{0PP zcQsWB*Iv>GprL7O-$ZP>8JiEUqPE+Q2gkmR zn`8!J3(k>&n#wr$p~5U9#*dGiV1)U6`}$s|MxQ>Hum`JkI&y1pL|yoDELeFQ3K?6& zqrhioR3%P1iiTK$G_#Y8#|;$HrON>t*n04@KmH-k2O;hO&~VgI01bQA%ZyS6>&!=H zGr;hXwwS%(JssgRqWM%PFBGL2X}ri(>Xv2An1d30_0{-#+{ba=MZM!NsyA9RZ=MeF zy0vtS=Q|3bl?2|yE5QqHBr_`%28~6>JkJT|89Xv^&fGaM4kh>~KtuPFPl_I$Iwfkh zCrzeQ7CH~|K zT@iO&c6nTU)|r|0w$x1}B2eKtuBn+2!4aQ98u`<;bg`v-21@*{0{86kS###Zb1%IZ zzs6bgdiFQJ$zZoCpv$^7M1DN0d{}h0O7R@Bh5AVTNfD9C+<&L{<_{{FavBI6C4q)} z@4qj`;S`;8NV~Y<#+xw^hh+9xpdtC)@d->z?V7jq*vXpu{T({E>E!;X`Zq#;leA#_sGPUdMWjK_1_H z`|ULFljh9w*3lX)sdklVstEWF;bdO_cI%DNv+HrOS1nF8*hXL?3zB7b9ew63 zePg|KCJb!T$>shANg6lNYx!*j*~)^nqk;@f7bj(Y%`gL<2o`H&nb!9Z}@2(3D8iJY(+(7 z9|m5F(=vslXFvFGY)qRyJH||(oSo|T;+}QOy0@RIBLWG7)E(?Owz1)wRa>HFU3xS$ z*)#U2<^~HxYv>D2z0$$up8`^zHes+K&`{PjO$tF3Qj?mEXqUNLwc)km3#G?I?fVC-&eMD zQgvK(V|Eg}Q~~7qj(d)TU$4IW^0Xg)&pLxDjdOAj?-rbB1Fs73SS5gJ9Y&prq@4o5 zJe{k&l1>))(Mil8mB;b@Wh+)hzv08`AgwXEQg#|6>UIqGEjMLCxCW_qQOK);LR+PXj9H7HLtl?_z|8h-o7 zKgJ-ot(?N?6IYO}Gr*9)HvlxN3(E3u>0(ubL1eD4JkNp@dBqHyFKvppr98T96BVgL zanLX9dvk)7w*h{gg3r{Z#lE?%&x%xpyP#)WQ|{w>Dx2Cn=PVFovsyt6sFjJCQrtru zpg;D;djsOWhyNDWP;%V;xUSLhunyTPXA`z>t5rdalXQoVy$mS6Q|~$!iogVtP=+T9 z31XB7*xG`DU9o;kOu?o;_xfwGa^b?vs&{CQ@7bamen44H1zQC@<$+pJ!l^m~MvjU8 zLjf8V%#N=Y&&zuqF3UTWL zc6f9vM;>^*WeLdfq#2818e1oPI_nblZPg}@KkgVR8tTQT@cjpGzZJi{{mwXw-b!_- z4)WMxD?JJz4|;@q>MQ*~d-x-R8P-tiV5Q1te9G^bOwHQ0@@43DD3oeJ?BZ1gqs6rVovgCU}%z)4r;6{X@#D^2Hhp#_IP~#bOFWB=d7=%f13U~H_PCiVA`P9 z_r^?|5O>^pXMDP3Xy18PWNeW23P^HTqXz%_=Ro&89tKo{pz|C<6BROgy)@ zcU{y8&Ral2UGoZw!hz_?OE15aV^RegIJOeH=?e>x>Pt%-tA+Jt1Unf3eS=;@m#UAn z*IRuqfQGUFj_dIQmjEVDnmQ$(dg-OukCSLlM~5|U)F>0D`a@R8rmXVZX{Q;-xu!mI zo~&i+M(*#Nt#ULzvr=X;W4m=?RF1`)|1!py4R^onv>^gV0XvpiibQbj{=; zhELigP5dPnS=K4&mn!g#w3!MB?)HSY0NG11=i6`WOB{M&Cgt>7j9=7Q(pX>8{~4W? z!4Xgn96x<**3uKc^f$C0mGC*N_85izc=qv!W5|~!ae1%P<7z6lTQ_Z%GP-jcQV4z1 zUZ+-I497!mN<)MB%a+8eB&VzFy;odF%-FDLQ|`>gJo0&brhoD4#{n87f@|!5{69kB z|11%Kx-pe<>%nBRzoopgK4{Y6Al6niXz;cZ2vuOg47~l`DiA*%#h+u07xL|EPdhm- zy!c|aPVAS#?#6Wh69{!F5L`>kRjxXv3Wu2^jn`Vnux!jN4>GeQMml!}7&?k?67b&j zx4%WN{XrDz|8Vrt$Iuk305lXbbcH}-cY*>LWF_CR@tMw^Wz#aT#>9QQ24yM}6^jmm zj^fj=zaG;E4~cULcn`;DwnETrfJBQ<`r2lhC!bf?Qy^q0#+085ff9y{=df{=bLNBD zBy$nXwmt^+djf~WtrI6O@BQ{=>je85&Hh_b- zjpJT6YqUqhu+gJqB#Q7x9L1w?aNWbCGwHZ~PY26DU4^w{8~f*VUU=pDGk+C;&mp=h z%>^2C6m2dyYUGG`83ov;W5>9*&&AP}x%*+CQQGR9do0=(9L5YPa5Vj?)0jdkt@(dm z%z+zoL{UXLCNGZvJ4Y=lQ{)$UQG=thcAh$Tsc0RL zdlbQ)biCk|M7VSQWD#+iKK|^p_`{$67-MN3c=BNf##L9d#}6Xs)PO?Ye zC(Q|bSu=i116JBHSDgyxpfjHV2lK23NV1vvy~lc94A5{S@AbOssyObruF9E z;+Rp^%92Py6_0rmDYuJuHL`so*`rbZufO?5qUE2@nV^t5$&#z}S<_f;8B)?As`rJts^0CVf0H=F<#v z@yccCh*yDTd)BHFyWgJ6U7E9c*!)pzi>r%p^-ur%JF6*#Rne&|qtQ2{DzPG8;Hk|1S1V(1*DcT--`z3#Jhn~nBE{i}^~FKjVz z)Tt>1W2iB7rh4D46Eo(bYu zQ~gx1BQ^ncTZ~&YbkgBZk;X7YR)1x+9dk2L;JNA2+;U~d&uSfPqjubkuTHR;<)YYkO5QK{GgJ@agSh5yi&23J*15*oC@T+KkBI;ce|Q)t zmu*<59o#N1zWj>li0!VxJf#Z+PIAkd(VL%!rNdDY1X zFQ|j{tE?o$(z|2@S>oSb+A%f-#J2JzU^r@c?us=r=F%0!O_jJdFykBeNS&uWvJtF+V?~1LweZ#a1@lwaynrv*tie9f^SI-vY-$hT3FE_?+BXOBy%p+7-J?(h$jFt`ch%j^@t>bRpJbHie@^1hdUXRLq*Nfg4UJ&~<#W!a@ z0<<}o)G|56f7$>1^FV`-&bsF10`p6%eioukDGUm#buz*65P*giH2m0`>`AA?I;Nr8 z39${NG^%9~NCkZz6%Hc^Y;GotwusTLJM+}I_!6?;`|Y2lIqqXBl#){hjj-6vD@(_? zw+@ZY(fW-vH8IGA33LG54``Ku8P8?Qm&Y3e2gWb{@|QTf{Xuc^X{Sf0PMvb=giYnF zXwZpOS=rTIW4x9um;!3quFUT978$yr1Tmt!oC~*3JOk5wiKA|r`ca1;QD_E9Q0nvQ zL>Ty{Q1W~lDPJv@7UO0gR!5EG0e1v=wnf1Y=M#hK{Bjffve-X!khT2R~ z<*q}L3Y&FO6w^WBJ;8wldr&N1qS`7I!5tkggA0}S=WL%DHe^UV4$yEUNagjHUlwfv zV5FlCrnJ_;SgvjwPZaZxRg%iDG#kVmMMDg|KpN>Ia&yTyV zzA7#``<&cU?w)UHon>^aotY7z!*x~>N&v7xPrnZ@X`z16c)A7}&SL4SO%Pu|`Q88g z3;Ef{@4Y8ZBnyy0g9eh%>x}B87aWY@ocXwOcD}xN0Qp5n@q1n>t zdG6UP0iHU)gi*-4(4(P6gFQH7ylT|ubcD)e-~|gx5frC$#SC=4ymW^Ax3q!i1-b(g z>6BRVwhH+Yq}UzjXtxUV10mb&@s^)Zh9=NZaKLh?c;J>B;-s!!qCxGtl<=dd*=C`< zru?vm@|{72j)R@HT}wen9Z&-o`BNk0DJwH(P)>)#_55?s$K_XE8C{P&GC?~VsM_7T zkZmytC7TY9`tlJBre$|&rmovba&u)#w z+wLFbp!Irm(ENENF>~sdv66j{Yf9!(S;Brxc%uyLQIY>tEstZxvU)Cb;Vf%|BlifB zbu5F7S0WHDk1nyJ1%XPHiZz&X0VMO8ox79OSu78)RfgVHG;F1$SlUir^lkJjL8n1h zl4*I}cH?z%E)Jng`~G_a0U92RCH(epRM?!;^OUHM!>w~`1K$Er$}>X~KQB;~|6~5# zG7Yx8q(h;Rw)vZYrKRNdvH8m*kHk|17#;X*U$!E3KJuvCi>YpuUzAyf;^qGwkbB?^ z2?z)*xfW(JT~|Q{v(y3&{v1I=+dk-Cj}5!#^q!O>UKj`ARIqTdbpydDV{1d~H&Jxd zhfGS;m@lB)3_Y35)LuO09G>dvB&rn)^S2Bf$zmD0Qz{I)4f{lmqNs&U25$QSATD z+wt<~@$nNXU@pZ`Yyn;5LuIHS?2N|TrHM|gmv+OXO4{*V^jH3Lp8bs53^U6JP<_u+ zPv>_8s(T)PeAEIw$`f;VH^F+or~NMQKK=}P&`Lj@etAQnT6xN?2hg(svV9j5ND%xH zf5xp7J=-5ZGsvH?b>gthirV8xz*_KeCm^+8gH<0^OUUoaL_QvCZIzusLlJN=$gpJH zhPId8^0U~Rd0u+OrEw~{U_bm0LGNw!fXECfgP4hB;aCf{pkiNj-~|6FW*jt_HX zFy?(1;}d2@!=E0Gi@LC#=fs|IEY(dlsnXntJQ+|MG|CU!Y<(MfM{!kxtc)nb>$~sm zn}Mz8Zd9n=Pgvo$t^3(gsuDm*)9A<+%027U&aF;U zKOP_V-g!4$Ck}}kRjA-mhq#{VL->X0E%_(y6ZdsR^&e@nWvHS*<=uVDltMq$1twqRd`VJ3?ETv8W>px zx)d;W(9ogr^nLfo$9(K=g2vuwo*513@uMHB-<7)1MP!`x>AV*MswaxNKK}^Kw2MB6 zO(6~JrUNuQ{ODuxw>JwF4L^U7iiTr5XRy1TGIq1_*-V)G6#QZ4&N?WM3F`7J#slgG z>7*QKtLz71AZ(T6tv~-ceTAUc^83R_#MO8HG7hO0(fjIK;-nLLMB}E-VkfdHaOZleHya=;}Y&A-Sy?u*XCaSG$E=k@S0*p998wNKl@yiZQLk+e!~sX@t}jUV${mH z{2udjo?gn5)nEGEu7`1y@k|-OR}?7Q@32$+sY;D%Nt+MHjER?sKL&gK-+z~V}Y(e80n8tEb853W%jY#2tV5W1M?Lhv-Q~L#IxiXoyvhGI%N>U?@>}4ZqG0175yo6bm}vk;xnWm7Mv^v(n|os_fu&> z6HANGz_9?JVIoNGAhLBMnETzoz7Ig?Fphtz3gF?E3!EU0t5Zg~rK1n+^EnV49YjAP z&Ao?)$GMBF8)Qr*lQw`%-9xXx6+P)zd&8BN#{sQd=U6IJ13SmEyvy@{i$H@QMxir2 z0>|H7hg2@mL?vjc`Vy4X@KJ1?c=C}LS+XqdBAC92iiQRp;V3ZW_p+%Z^L6c919`Pj z_U#l{OX%gJeP__ZXPkc}K$40$gY)Km9Zx;?T-^WEGmbJ5?%G;Ymtb`8-UP z{4UQI0woj+_mC$GrH3dO?x3@)VzoSVH#7R&Z`?$-PW&39{1re$rw;Mc>rjG+9hw1= zTPJi71sE#fP@9Ey{^{WAV6g;_t22!%FRT+v%o~eh3z+mHbA0Yk`$j9~(&w5hGcan| zyhYMNCzh}BT`uXv4}k~w<<)G^fQ%A*bVm%2#~yz?Jbhz2fw5OhQsFHc?u7$ZC2Cfp zQp9qBFNdkTe)4wTYeKG z02*|_fC}<@=x6q5=o$^`)Jp|k7BJJxY=9tx>zVI2qU{`nT3nKOs2 z6EqI|>tj#EO;j9or$>X^kVLtafB7bzNX9o<)X`8D$}q@1Dp;N_l7 z%T#C0DWS>d1 z6h}Z$oH42um~83^ImtQ^G(@bU%3<-QrLhE`gk2C(fi&r!d)B0)i|j9SG(fgeL>^`+ zoCo%zSMo?gDu%YPO==w_#fz550Dy+_{GDRfyzadDhB%+TGT!r@clyO2e)C|SPyRsP zo8qjKdPW0Eh%Jxw@0qD!P5ob9$dEy>%-CY*iLzLrhN_yjyWdQp;=GY>j&Tj8mN2J`>wT)q0j7I$0E>R`Q??D zT@g$9`sFm3yZGWhnUPXI>d5IRmPI)kgjpu+dY35&m%*=Q*L2)6^CJD=o856HN} z)5Tp!uHTTM@pGDa9k*|zIOl?kqeqV(QID#CjcmtJ-v~zQAY@}L?&HY_>M=7)K8yO- zS3&1sU*u79m_|OE3u<8jMtcU%p57?9nh}_^^2Ou_vSIAqT}R*I%1JgJtA8b7le|WcFICnlzGXQwSh0*eOIBG|!6UaOda}-F9L2ZD@V+^2V*IrC`SfTw?}r`@0u6#M zsS}v9w$7}*gJ!=XXkN(ZqI=*?o&R*I8QVUPd?3eBK~^!U2)opCq~`c z9I4Gb)h!-HERUEKm3O3xa+dncHDz3WOTJ7wL(jOqO#BV!gIy9ZrIstcWqZMh(PQGuTW=2_9})z8 z;*3*H%PludCUy{DnLLpvv)Yrn?lACzM$XgVvuN+W7hu3J=obj&$+?RN=HBT4Ui|t` ze~msTbj@msPDdRbH3;r^;2UnmzA8^}OhFI$J$T58yFE9XK@z}yPc_5p)hqIz)d^0v zf`lc|@a4>So(i5-OP6Fb$o2=eW7}XOzzg>N1KyM;c~pTUP|1SD@fO<%UU+*DJq8xV zf~5<%2SCGKg^Gr~+&aPelL8Ga7=d6xH)mo&`-VQ!XGs9fFS>s6HvB9wt50cZ`gZ2N zg}H4nSEy)MK-IQ$K6&Z{51c@WzN!F zkPQaN3KIkN{`g~8{_OTRfK#zA`RT3M^Q2MZCb12WdJ`4ff~EQb(!*&gC(>CkL9kbv z=;IWC2l$K+`F#54Ry4fwE~kmS{7PJU&lYI#^I1KD&T(wzRa(hE%CP!g zoon@`gQh>lyvq|K2#|Psjz`fxL!Y&#^&95)ueJaU_36D~GhumM|6D)GarK>)2knHm z&#i$b9xJkq<9mKzO_iNhH?FIvPE19|j~Y8Jo_YDzxb^0~(GA*I6y<5NCy23 z{`FU-vzN4S`-)p!t)RCuMqOKecTzLx#tmCHC0|zGqgHM!v6=AG#2-UHnI4y%d3s#I z76@arObi0_euodgQ@|Hm@Lx15Bx26H@%$xJ`al1|3sJe@o^c5=V}k~b@M+N1JfG{t zlR2e-=?mU+X?~nbAxNhXh35ZM9TIHXv?(zXgmb~Xxlz4h6&AQXdyJd1fS}MgW~wb0 zKxf9Fbo7LYaqWG-&Pknjd}m5u&&ksj3_|VtS_UUy0oU2I%%>=j-rJYVqHtz+PlQ}2 zOvjO1;0_EY@8VTp8@mElNNwgx+ zU_es@8r;us*YH_m#>Z(K;pl$D)@1HQm1~~aL_S|MG6on{lw>d=J^0;!J70~EYb;&t zhFhU(mH1}miWoL(R6O#~AEShEY{qhC&y%yFLFHfA`?u@+Iz^D*l3?ek;__K6>N5hJw3#wUumRm63 zZ|9ridSBOx-@QEQ$^d5Q=rPgv{(obzd6?#PH}$?CI!f)sv~XTJ|ISw4HVCSK(JNPxedF}Y*n~qSrD-6J)6etq(y_CG%HZPTiId~6 zBR`0y3+KoEH{BR*n>31V=gf_{V?KyA(3K{duJhcj!5ZlPB- z<0c=mF3iO}zU!ICvdwE^$;LIYhInTyB3z*c8AbLQTPmnyxdG5e=ghS&2fd3G4VLYG z%VF))maLAkv&oS2cZ#y}x}L!Hbb7z=;4#on@Q*!_=I*u&`>>zCD|)6b3x+&0sytSB zsjrY9^q4eO=a?<>7)XB?XwdMx7G^Ts()AUN;?vJPAMcDF8}+&Koxh?V4EoIN26=)A zla?0Br4QgbsEggdThs&UV%JgKUdR~X%i(}+WnSZ{5W4Q?zesTEjAM_?trG{dX_FZR zohs$Z;M9Of2i=n_)RW$)=)5UU89efARnh^a_YX8(L`B2k4@bv?PdpVZnEUzH(uJRZ z-K`VOT`)j?QT7D{eGY*JpT$7Cn5~yizMQ|hS#VhXnzv|Sb`2j#Wx$zdpUKf=?W5(s z`vUk@OTgRtT9M&8IKH~wN;P$WK(~&w+Y~aZ#y!>8>M~3GJ$1rHoKL^_0;dMFi0(M& z9*^9RxvPUcL5B&Yy-WK4d)q3V8Anhjc|MgJ6-7F|$jYKci^v*H$!%8s$9^2QU3GaJ z$=vOIRE6?T>FVo zj@~^_Vo&*L9Ov2~D@e3&39LgS*VbndATVPlcqacV^XYfw;`1NgvwF(E&jXx&^PP9& zFR#ANw5hotsBU(14B942zH6tq~_-j@lGH%f=mKW8-Sy2MN7;srF z!Rn^Hk~f!9X)s{u@Obq3m*b41I>d3EkE2@iP_|C&5t{%VcQF5)C-RhbpYIAvNppqF z9u1`#a|gO^(?b^eQ1_2uO;~$tpL>b1jwzkJ76sca23G*3T$Jmpx=h?VkNFiE**Wz zAx@E%OHq3?Z`zm)`hHP| z{w8jn82`~H@xU+dh{Ny+Of(qe3N%=mVvX>V7;kQX_0<)VM{aR`S=<7rwJ~=D+!>fkbP2qcm4FA z?m6{Bz?B?20Fe_<8kg0%^)8V+jTn{U-He!N+#H19XID z0#)jGd0yQ%<7@hEy!c|gGI&@t=KDXr<>ok=Edp*&)(B^^L%RlM?<Tu`G zO%t4PyHElR@(S}`2jH$hcE^JcMJq6&vo5|Ox*Xe?9u0eEpBaJhjBOY%^%q1ai!4fY zw<9}$Y2X?=XKkRdLIJGa!tt4lsLUA}uMQX#SDtYS$Hg8>{Lz{wnl+O4`i}ZCs&8#+ zg7(}?9#s!{Bde$&QtBE$kO{H1%-gNolc!CKSKfL%8rN^g_Tgirb&D3M<2`vJs~LEH zfd$c-?JKl52QU&_MnaWSGzS6pJUwEvC$6@V@K_pamx+YNBjLbLLPaM zAEb5KH|Xp4j1S5oUr;*rr@bKr*vpczF~Mn*-0k>iRcjV}WGjSTc=nN)GExM|JW*ms{MX~ZoF7a4XBj?AdDW!C;v z(5Hu9el1DbrCsaj&Y9ND8aHO43^YM{RNj=vsR(u8?9E`Ql#G_nFJr1eTpj*fFm%p~ zYbE7!V{t@Z7%({ZC!Y>tc{u35`{6uBOGT%0Ww5MnFp#MZifXB$0$R*$rUM{@BIF9A z{TfsR3vjqbg32wLJT*EVdvqLtf@;>ZX?DcT@*5OX0u_ue`?$TshKo*ALA1=Mu=N?xBPSH>s z@%VSaf^>9wPK8oO*KC&=-p?q*oH3^)di6SuZ5b_cZYhj>PFi{;=m4F3!z~XAWf9=W z`}1r%87gx#KBD1YGxn#SPK+UAKZ&MI8^tNCY4b*nQW2yPU=Aul1>Ve&rBW)wJOzaJ zv$}-!H4EW78?@N0%99&bfQ*hrdH?C9S95+nk3NE`nIqD$nIRHra9_P$)NR=5TH0jH z%QcY(1;C|%46ATdTxMg;x|b|k90LJK22Gfh-?{$6^Ye`O>d-aOclc%tYp3B6d3E0M zYN`kMkjww7T+Mcu1z;%8^O-f$xtlg~CV|(pSw`7(k4gj>7tk^t488yWKmbWZK~#IA zWr7MSD*0VyWfM3nd3+Xu9RV&YYAmNO7*OuWv+)1qe`P~}>XR>~&|v57oX17S9ur+U zcaFX5*Uu8P4OA1P1IL_g7Mcz?Kb008l@(O^%wM>W;BaOdu`gLiq$8>mT$krVyYsV( zfi6Go*a!d(3SE)z*mMg9fG8)*04-t4M7)Kdbhun+kGGUY6;QV2c@95o)_x;i#e%h) zvPZ+{rHB_pi|=|}ctRJt&F@D^T^#~Mocvr{3>)K#YKxd_$dsd%WaA7Lb(9RevUC!D zkoOI`=FXd&%@~J{8BaCCQE~8oZPI8~C#Z8?uB~$~7ziC)1LrCjOPUr^&afUwL`NT2 zi!~)1Nmuf+WCL|v=Fp>I0u>D-rc8@U^XA0)>_2Y0N9|aPW4&$8%xF-)OzcJWsXDZ% z4DF?dItMQ)wPsn2SQ&1deB^@i?oJGpV8doUyN=JT+`ctdZrvEmw{RK{j%t~D5e*wP z$qd0-IIV1Qdd~W+x%1-v0sYCE?1K(#PfwD)v+Loi6QXS0>d~Wn_t=*;t;KQKRd8|*c5`nteQXS@%}A;H zy^n#eYiWkpz*n8=(ZWe1p1~dsp8@vvd-?TP$i0p~{4n&v(Xls~I-N}eJ9Vy(v~nt+ z6f08rc!9>yJ;8j|A?+*AWVM7{&n+c)Yu}55hiCKE%g;MIOZcm@rurP7{$mnFUa5k; zwDddm0r!$mlBeJq*VbpTuS5mbMc&y!V&<#av*`ix4l?~sGz9=Yv-f43veF8l!={1Q zV&K5C9*O$Oo9Qo|*u695*oVhHd(}@+ zZ436pAW_>V-z#HQxd?t0#}$OhfD4`}l))R^>7#uQ?N`P4i3GiDTj<<&Un-9diq>q) zs72P({tVi_BG8~uqdv&J_VBm-w}VQC&G5EAA$e|vuoA-L4KSZ`0l%9eH zdhAdsh`Uz1dQJLt;I~3U10ItwJD|1PD-9@eOS>g63bK1Yfr%|-N7ru!bla_BYyz;D zzj94XnDT9WsV(KZ8+q+rYtLwh-l`42Ii0or^2_OQUDc< zsoM*|E?IlV(GaMw<;&Cs$^|}a>PU3hOUhFnvg*a-Ck;g9KYcNM*Zd&w zIe%@hx;eowbfVyWdE`Q$Qa|?VlKC-k$S{rr{~~F22|?Y#R(+8ev2nARb>%8`2((g% z=@$D&&8oHe3m4JMa#D<#_*oo(@cz-hJv~WU zx6b}RX60QkeVPP(nXG_SH4O}{7 zPBm%Nn98g@5=&<4pn>IC(92KCHC;KA)n-(o)m1MI~!>a!_v zS~s=~;*Yu2-pXNZl0dkzi2B9LvC>{Jp!QSVDC%Z;(@Rj&3f+?VC0SWNe)Ra*ty<;i zb@~}>A8eZA8DkY}zw%SyLFaEWLZ92p6#+7n4}wO5UMW}jXyvgZCgUbgnHmG%eK}^6 zwdo2tbuwG4Jq}!;7bh%ryS%ABM_}%gBC;y7yH|E~cCXCt>gukp)zwuQRgtT+vRAEM)%C5q*6N(1A|o7OM>xV07>qGy z6!WYZ4M-p%CNW4t(7)flx`gvnR#uQ7eDU*>p6)yMoPGBG@8RsT&oTB3Pfl})B$k(z zM~Y1ri8CD!P^N7SS|_*&=R!x<&rE}hh%4X}#NL+kg8C%wC%4TuOL`=;sS!+(%O<54joISi|3_z z)tq5Fm10;3p2kBSzzE|K1!I5g`&eH7&8qb}+5&72Qj*I1tWVKHB)YS+1EaJr)ht{R z1u`wT;=MsbX^VhJ^O$c4Fao+LK+;A7I*ds`McVj1>m2x9SCCuJHm4(d4iX?p>6w>a zi>k^XT71tyg$hD?OKWN4&wV(`29z|K9HTU}J&ib1x~%$Y!NOxFj;Eu0KV^^q#8g&M zlPb&0qo|)ova1Y(fRKi|bkJeUBb^2s1es#`Dbr}M=U`}{$LMi4PU+zzhtrY6C*bLn z*1W)J9}5;n%C*LoX|F0DjnZQJZ96J2I?7M7N2Y`XLmgmKQ;V20Gct4pEf)6qXTL~w z-6^f8nVps|Ulse_RQgt|)kvhls5Wgnmwnb)P%+xaP?R`95oAya=>#ybK3i~aYHCU+ zzt|n}HgDC#=|T2oPn$L^3Szo#!TEO{M#GB*@Y)b<^z&IieZ9utEq2pI)<_3wu66D0 zVSvH4;rvSvN9+qbHqB?>Vf9>2O_(~DG3wi^JIi`*ZK)G5VUJ2ph3G?j!sG&RxRbEl`7ICC-NPh&O0M>h6e!|#%6Xy_pNKGqvuMx4(+Ft zem90amAA;QxXIQFSNO%?Fg!T> zM-v!46+>uQ91rR0Q#f?PvLlZBvi?H^7nwUVoy6eS!Xe6tN4AXtpdshpN4GcB9{4g{ zBA8OOv^p(YzB0C#$tP}?Fvy_$A6xI}x2wt;YNqc7&NCnOT^So-rPQFHwGK2&U6E?< z>`ZMPt>99Bnp0YlYUbC(icxH7vTyK&G!%Qp#sM%wY}9y`-e$F_Gd1SCoO%s0jT!aF z8T7}MiyfS&y%-%*mZlNC6Nf`T(H0;U{NgH_eRF$({l9#%JM@S(B@Do5JZHE~QCY@v z)$J2Fy{)ayWJpX&bJ2ZMr%a6?hCv)#!GYQ zZ(6W{1_Pe8`}U+Q$La#hUVZ8@>NYKnAiXw*?W#v2ZJF^%0(n86_u2B2Tq5nnSTlEQ z+xbNxMA1*G;r6wZYwplC?P$|$smARhfILN@a6v;K|Ae_D&dQaZKcdxs>J-#r}$|Xe)FasrvNs4)WR8 z$M!;MG>k>BN|#a4@CJIbv-etR?YfA~)JD*LBzmcgeosl0$bwYg$j=5E#^Px8Ub~r2 zG_|FpjnvHP?ji%|a+(P7J+Vh~AGbPmTqQpcW5ISApQaHEF?gU;Vn$s*`oQ^8&I{oO zGs&VZ5pyt_MwF?3#&ZM5<8~p7KT)IMGJ(sEbP9F{zN3Kc?6DI#t!x=ObaJ{tO8L2# zQ)%I{RXnpaYzg_nwxqiO2XRwvFOOU6M_PMYk*D0axZ!?s9VF*e`eBM8ag{M^8&<1xe8ep{PCr(JyN0>ji#Z6_Pp z?l3YfUHKFaZ)MVtP&UPR7pTPJ$Z7!F#4sIEi-1S%7xc99Wx(9vofD^>AXbR)$BrE) zfOR#^oL!MBE30B5(nTcc>`}V6$hNWgqy?h=x^1~Y7B~QX9E%=;wIzb*;a7E_i#Mkm z8q&d?U!<~{YO-r8IG&z51jQxy)b79|jsSTZvIPWadDOEJD`&eGqxbF-|!XpIrei?s)ZUsJ z8&0Q&`i}JQW6N0_m>&T>gE`vQ*9erm6}trcMtjdO4=Q`onmNDATx!clAe{a?2K(TB z21(AskKN}x*#0n?EWrmNd(}WWL(gc+{m#F-*?@@wH@D_$hezEK{uXu7kc7yLgZ_o^ zk%83q_V!eN>R76;JI5)5W$E$9*91P?WGjsR>Npmsv<2K&Y5?sH&o$8CcBWo@uN^=B z>-60p{HyfaWbap2R|n2ByYwtbb?^W2!PoGAV3uO?n_W(dPNG6?>YA74t%U-anskhm z{7)#vaj15G>TW-mrXy6drgA(T3}*#!Bbugw>fjrs@SJXsvoU?!h?gns{!N3>D7V|> zj51k>N&#LG1qO@2R993CS3pMiU=kfX`)g1@=GO4i@OEV;1R80wHh|BSd5yfgs_ru^iZ+Gn z_LpI@1JFky5iGOfj2OOeYbCFX8U*U zLN}|cEvaH|Ijaz}17r<~XlMwsu41c@e3p)%N`ybh3V&?rU_4*VR*2vSv=Qu#j+#o` z(|wVwjp{HyR5sFGTB?9_gcW`T*l2by(K|mcEh~#ir-1|k&@Kz&;aJ3&vJ8w)KwpEs zX5PHyagvdK%-=(?!87i&wW6|-UN2X%?0+~cjK_Y;UmCO0N6Oq_elB7BU8V?*2KW?K zn&*(#m#?e|gbIaGd<|uPcQw#xxO8$p;L7gU$t~VH7MV76sBiiewl}p%mRTXK$w{GYtGtOatbQBjbw$C&+#(CS7 z94`BvuLnF<3YZ#qO;i_rutqu-;>H`lwp|7 z2s*k~xPORM$-C}}1;>#2QDZnk10{7A-X5e+S1}kzG#^jpU`jcL?KBk36y`nx4f1Em zEghqygcHC{AwWkFrN;bVHxnd?*#&c$UtXHE{oLO>h_i9+TgN`1d&Ef!!RSw zr0+J)8(Ol2ls~VlH^78mPB&<~kajj@bBDyowVo`g<*a@b!+Td)-SET~G1rW%nbfXO zemt3A0E0(?y=Pd0rya=YC1l&rXCOXoVy4b-gnJX_-NLQXjJp==h8ZfTbh2g?n1*SPS$h7?9IK;NV94HtS z-{B`w#`!V8sQz%v(KU)OR(YZctCV6wmKl22~h9 zv@J$l!Ql01RB1I2{bbD@b(~{YXNUuSUtJ*1dgafz@8W>`E*1o~@*N198EnjVHx7z*3JngSFusXrs*?h#2#zs zE9wd=!WL41P=_@ji)b@ahS*Bd}||l z8U!#CGG#Da=g3ohE~5jqT^zsiY8?;toeqW1&;~RJXm(2*Hi7c$iB*%}cWpQWI~GE; zzXk-|)~an_Ki$?NZ%gyB)Z9>3b)pS4*mmX|xfoC!Y5!)oTp{D2f))4)WHmyD@MV0r zzsl#(NF3^dLY!<@I}PLz&o@AEiv^Vt@c&o}ie9}nn3~9dXgGHv^%7{f z-gh-kMeIg_sh-rK-V#B}QCq+p&n^mkM@Qc=8*uKY4KD+hW56VX4H0Nyj&{qF7Q4qDD8pi)MLnDXs*VzUEWka2E(MqnHKBF}kgW6O`yA#7N9Mm)3c)_v>6 zb~B^47u{_DtdzdbAcHyYr%bKWYoOt)SfK2RL(zAhl{?Ye222R2#*{=K+s}2TGbc}R z3RFq7>k*t5P?rWC>8g#F`!aMgbVXUXtCct zrc%E}dW%C^G}6SegyYTq22}iA`_Lei{m3)1CEvTxDlW^2U z&XxK@yd6V56B-O1qD^EFM;^2Qq&9)alNzAVR=geoQ zqvWIO*wOk=ekRZ9Q|kMfMITwyJjY9YrJXGH^s_Cj2cEw}(5;f7yxDaI7<|c(;+TO3 z+myz(qb;d_It87eePQMcMnnXa4UV|**Joeg>uZej24iv&`HP0S^l$#v_sM2{D^)QT z`2@m5pR)gnykFnzHxD$Re{+Qp#uJkonwg1U1^~o?h(3P4bt}iYHIRXMwP*3JX80=3G?r?qu|KI8Y(LNLJWA7oGbYP=H7z`(sl}cl;MCZShO%z zR#wGn2^zSrQ0LC6MvlM{E1Wz_<}d@o-|2LKlh2SzHR3F$XNJXl6t+1|HPn}1{|3Q; ziZB#xE25S%C_In@sWi|rwp|@sV`N4XWio+EL(G+8ncw4OOiTYU(X5FG)%tboDC#yV z0Lb=aO4&<;-LVLw3Xb1%Wzd3Dd4yQLRKOKN-;LxN2sn83X!;>Xv2A2e>l*4sSRBO; z3m5{tQBl96fO-jhjv)YrdlYEfGwN#)MI%w5cO}N7g!Uh(O-;<}CQ^|eShz6jDwV+MuBi_ewT_S?37UBWnQXy6E|`uaHHY6%6=R<2kP>1EPWfR%5& zSAG%51!sXt1JC}c)TNnoE$BMGK|6T9y@NC54<1VAdDoCzM*Av$=TW0DR*vLNz*Xg7 z)`t$1eCWKpJ;Y~3M4spQPlHYaOr><<)Ty*<`}R2U$6$cKG!w^8CFvZ=!@i`GV~}42 zeU-0rWL8Zc2ovm`U%}q!_7#BgvoF4&uF8qD;q}+jR2;fyRws^~JQ;=R_MJW%b84C= zWY=VhcU=NQJxf{8pASyXo`w-v!m0`eSFG4E7iKh!#)BTm%2T!i2nFE<22J0fh5Rzw zKto9!!ML|E3p8lp0*0+|tE4RxWjZG>XI_9S&)z^WYpiA0A&=d+1==M@s0M|II&Q&+Lkj zC#Hr}-99R`6SyK+V&(IaDHJgxpgICt_hH~1Jai}>{tvkpKFD_p=1fb)q-72f zXz1?4h^HX$q!Kbckb{9cd`3pYsg~}v^%%!Q(MA@cOX<5Wz7QwPRN+*XV0aohj#Ut7 zWADT-mAk)))6&j>n`w`Z?+mgk9Upy)Z7A@(fm*ljgagO-l<&Yo1{QR-A;v9VivRh% z$g@WOz1N@55>z`3#`hxAlThGpN2{)^q(_V&914R4ItE5TKY2N1fxp{k9$?fkb6z#h zb&A9VaqJkpUQ2N_gVa@3RcS75TRclHaXw@hW!<)%j~GAC(_r@(4Gj4soK(gZ+sSC# zF?yn+rW)uQwDv8d}!O!$$m>y@kIPImDBXk=!>-XerRUj<;}D0 z?di|{;xEz!jG)&yZj7x8^0@OPhKo63i#TupvN@nO3^<^J=UCKr8fO}K8ld)Hb`(F4 zvK8V-|L)(Vm;NDpW>-Intl${%c^IqGkDqm<9fMf};;nopJq#iT{pr8F6!#!&KGY+q z&*6|B1SiinHl)|zB0YKWqM(8LTA8yQb!EsQx?V?G3OF`pI&>-bh5-r+Ij3TsywyqI zs}YPpjD8vmFTeECOJpvR?oWSRfpR_r`_wtZ^p)2PDoX5M>s4qU*nyEN1~WbbN-Y@w zP4v5!0M&vAmr_^26Ph@yo;kF?>bQ(|;6K{TgFCricF`fybNw4M_qje_dbt<+ApCxw zxt)N){UEZmu%?E7j*L08?_skzN&ZK_97Akhf(GjSkXz(Rd^Lb!`|`aDLTAv|`@Z}# zaC>fbby|SlHtW*%)k*T5;|NEKZGP&#kV*NJ_H0{uwE&ztFS0V=AL}_uw=XHC_xXn( zq=(sJQL|t{nmTQ2q^_&?!r7FG?Kl0BC!A;TFYE!@k=_u3{)uJZHuX>@@A`noC`80=8HKnr&7E>fvCtW*m zU_b|t6;;L*_=4Uu$POb!KqswDNZu)B7X7Nd@er9mu{Cn3C=Vlua0Z!Ll1%R%aCQZ77g>F<990L z7xj*gY^J9TM7dx>unVjVjHVC1yJ+WvV+)Sxj?X_&-QdkEf(#GR{yg|zEEEs4rIlHq z;anO3aM9AsHl>r#vTxz1z?b&hV^`(N+QWy_`#=71oIJFI?CUDpHe*zba^Xf^=f=P- zf0iE&R7;C^E@SjL;;>kdEnH<8P6pXO`(j5ruycD_|H>xp$oX*sk@F%>>cdDA`zY-V ztXp_qogoG*j}p$mIX3C;ceQy8EVYA^KjBmsvu0o0NWo`<8PY{sOAmEw1g?1(cO9>P zm$k)$+<&wXc>RMOV&-c9oYNjL1i+=!uMj4jj>BR z{j1OejLGMFzc2M(Wao99OGghLB!FFzUfl3P48_(Bai<^zk3IA->CY%m?}fqdVBo8)RLm+n zQ_I~;X10L)ViXt+8g7V*8-rqSuli^VD34OwzU#~M*|x2zqPi;1j9svB0U$Udz%8Qv zFrG}Sat_B4Mq>t}U7x9870x_PoQyA{Xy_CHq_As7IW0OWo!Kg6h^Qu#LsXwgH;gWG3m_UB3Tfu}X2FDA?3Mcwg8s_uuZQDR!uK7!tAj>W z1qZ*EgLG~vsz5ZT1SOS*mtdtJ3b>A~i)iA`UAxlRv#seZj+0!0pvwc&#qTT3_Fqu7 zU0*uw(#BO14HoYg4DtYn2C0$9c8sk0y83kV@S!w~VwbOM*pSLu!LR_8?T2&1d#vzC zBgSp}rVYDNbK(4jptXS&+ZULmll0MHvoxz-hbdAd%8Z1wBbeU#a;R!spn*@IKD8z z8NVwPuJ&qZxMDRDp5nteYhK4lN5i?4{*mp0JULE5@Po~ta2zT7DgEGo{QdOe+NU`xixm%2Pm3wc zsIi2Kh&eN`_LqPD=jlH!@kum37S#{0x76i~h9R>D{B-k*D z&ov(V;Ggb+8>yW%&yK+>WH^Aib0`Wqm*cDoN2GREqOMWHVKQuYdfV@1%{-JxfJ-s#LR84XvMUBj=H2AWqX?c`R0`;Tx6fNcjIE*&4fd z?M^3;9gQH}nzidVzx&BF3S;di0Xbz#qe9tJ{xwR)5a-PH#6)qLp2t1mm~n47$h|jNzn{5O$;ST5#>Jvuh|vtVJGPusIt9kGA*J2RsBA`f(q3`E+ht9RbhM=;0C1+NGIV5sJJc7Y(%ho5|s z>M*3&tzVxOqMO{Vp#BKDFyG38&k--h67`GYaTP`bT6!p}fnoGP-67VDg#N8fO%w1>~zJKOO-+jaHbdO)LC!FKPy!Gyqn?sZ(glvO`7*xN>seHTt?1IFmL z;JsBi)Z&|MihCN}jzPU+;A_ zKP|)Y^7)te9#a0l8>Fjp>-W9PbaGo+=yN{Pc5_vK0(`5(>Jg`({PO+u2zqZR zdT-Wj3c4{4Wiir*k$?N`KQX~}oD193$j|zn&8fDJ_t+QTT|NF8#T`4_TH>@9kE)!? z7K1`E$!>EhjQzIu50)53+uTN1Li_LyPWAxXdn}7Mmhl+y7Fo>>yF=S`Z0Y^*vz_VP z&D&FFdox+GWH>Qamu1`*$S(G%(@-{xZGq^xX_KdsO~Gm=G*ho+*`Qz?{Wa)ekip$* z26n>XV64uA%PQjdZL$__l5x@8eJSlaa4wyJWmvzBQ+}!`>iaMM`9FBSdcOfv~idE~CLsElgMgk3>E>`^`2~hbZ@f zlkyfX0~OXXX{7I4C{EeKbIfK~MX}Mvix%C(!EhL%OZXYIqfMZkODFYI_zch@3p5yT zME>ZvrzhwH9za&#`QZ;aeW5fhf0&eiWXkOdeqUQsc~x&{kLgrvQ@EWh7JlfzbIYF@ zll5w{8e9f_)U!S4?+@ww!To#FOW42`@0~^luJq0DFI!BKwm#2bql=bIDq9WEy~vaN z;${EkL3NK~GMlFzoc!~@`eE4BZ+-KdQM1SUrK5chd8KpVSo3}5(13`usmzOW&ZY8e z+e($RcTDod5wPZ`6jERL7dbc|JAmitQ)vS` z_u{l|J68E}_ujqfOKgL;f9H4DuJCyD=LS3}pZN@VEXFd7E6%MlWRP9|Mi~&}9J4yX zOTXlN=XnCjjcNbheaQ6a^jqjw7qK0$I!BC`K4PV~=A0VTiY;U4BeR(Y$i6rDt^a3j ztQY`T(M@2@?PvyJ+OQ2fdoDzV-1^rxMm<7Z8$fY zf6+GYI&G$dd%ykBP~CUnK>GNXzf8|k?8k_r#q7`~0TN;CLvN#IGPVYr5mA-9t6S2? z6k;pGIv$AT%_z^oaLPJ}5PyL~-QM1jzV+>Ir==J}Jecp9p^|}t^w5D;nFSr7n{D(1 z1{x^#RUvl_-Y1O)=(mA}y1Ke_5XCta+H87tW13B%0j&}Modbz@jT=(z`V9oL`ylRr$aJhwiT&qPi}Uol93O#Hhp&!uW-Bk(L`| zvK60;d>UxT_zDLaQ0!wVte?E*kr8M>dGdXY01%9=6aA@`Y>Kv990$kuZcoA4n~9M& zx*%O-|8igd6=+3J4EC8cxr%h+QDijqrhSJm23_+&!~gQ#@21zmpv4OofN>ZEjQcLU z7#S(dolbi0plK|`-ck6o7iGC0y40OK8Cd-|IP(NbzW}-p5NME&%DHkczk4~}EMVb2 zYcp*!tjrxh$6hGTAp@-#xSMg-uMpfTgU=s%aazFmrx9q7r{vk37vziJ9p=XwxBm_& zoMB{2JkPM$p+X<<;1UkN2OocwPLT2O)H7@21R}H6G=NP9RUQL>>9_%1UnrK$53&Ip7sn4qjU23G;? zx4(z%Lm&-x$6&wJ5f-?urEuB17>Z9k{d9V6?b_IW;Ot3bX()!PU!}J=X7I^5^XO`w zm*^{VAAu1t$jj7Y_Y<47wu?Z(X)?6FNub)Z>g}6OgEZFw^%A!ogK4}HL7It?;RNuR z^l^fn+fmS!Kg8BG^@m4pS~KAF*IrAN*asH5Q&(sd2S36K5%`533@c>ad6i#$mY3u7 zB@eqTst;%X1iT*m#KHLGI4)vM5eEJ(oIHa(&Vk?2b`jr-baw4Od;!t2MF??%&*T;F z4c&{(wYRmUJ!IIlx3t8mM~@&&%LxW}#HxCen`2&i<40&@H)$i6P328|^W7^9b@-~l zd8I#|F16*OkAr7C`p!VZ^oqHmy9d#0_TTS@T-jeP=R0f*WI%l@uS9kN&v%}*fr`*| zcNyDef*7Cv>Vve3qxB51&%psRc;*;&c5U0A?SJqM^s#;C)o0sYjEm=Li)gnMfP4Is zI$34Z9_#5kmo{#Eg?-%B1nLP1s8fc(cl*xRZ!(?zclm6z3mjzVfVG2Uow#ajYU_6QlD$gL=;_K4uP0LEv~qQMyk5T6!+0+G8BGOxM*UE?-oXOiKUP zpZx3eG|u*9)8C=3g&FS*8knL(%%#Tzs?Wp`vEnkispV`-I9{Gk_QsoUhAk|SBVfjN zymH&jxed93r{o=j47O*Vv!E0>AipBBg9MfgG#p2_9y@v@RpF$+@!IQYVp$ofd=wbx zd)ipetHBTFR!qq;g68Az%=kT-R{jDjq5oy}{qNsj%l3m4^kERbd7OfyPlWwFMEhca z{3XBnjF3ZkhUVgL{$1PEE0d*+H_iBhc~VP5L;4hF{i1;e^#^);A!Cq^Lt<>m5V8tx z7%3%xlccFvb~Z_}~}6NGqAo7uP?VCbBJ&27~4y>*4|J%PY!G zj`KtCx4}~RB(RiucPycUdA9bkL03;i+k+4C&9~nsIE6jN{py|^LvlMnzLH)B(qoG- zy3ID!cX4u(yv`UL-w=OmYs>tP+I{PE3WJk^3A63QSlLBtlo<^w&iS-GgQ%a(7SSjA;CEdii@ky{ zfS}?faLMpqGPI1GDMXcLO6LHltp-V8h$mR3tEwdJ8DWWF0s>>Zen+NL&{e|uYL84S zJ@Np6DN}-)3?8d6jIF+@F};t|IE#&c&#qe+g<&+da`5oom6psf#Biid`x@SBBCSOf_5uK-;sQDt6nHre5KY^6ofwcDMr*K01IOgp3=qVaX_N$`GSKk!GiekC{v8$PFh4k_(lr2)&z$El26^`~2%qraicHtOSI_(3jmpRo1se@vWhubfuZEXX8qejCI{--}k zuNr9J*rU-n-WK+=hDFc~+PQyMqr&W$Coxz&u2Pz$_fMPVC*eBR%{4v+0rL82{|~y+s{_(c^J4se{0XBhWC&76l<}EMpvC zWnmA-$c`WUNm>l;7O$XqAVitKy>M@&=VrzTkjR%bT1}UgPOi9-fRHW?Soo3Y*Wl)} zJEZTyDX~wmkMFcxyO_@2yi7VS5qS*aeu`5LjDb%v$OiA=*jx&mi-0EC8+RvA)RS!> z^%|DcG;l(>{^xJK9f5{#JA*qc})6rp6^OWab8*)8iQub zA6doLi4}2dr2E*Vsm8uMsBDXAd78I>3%rF7HOgYeLcU?XCXfwec1!)Klj;5U-b**Y zvl?VDI8K8Z1^J9)%@`tn)sY1b&YMW56!Zte4wqmM8Yk7BSqhW=Q* zXfY=~l*X!=hG+1Y@<4yZFX=1Z`mS;0pu{nqNY$(T&`~xZ@8>OTt(+q9LCBa{S?--S zP@$Y>Mt?SMwjTjVX~EB#gGZ2#cI;X88Tc-o9pYWn^fyVp&aqpD3^+!h0Zi;{YfCH0o_YZzdMvADW^EcMaplZ$ z=Q_#n+n%&G2w=O?S)P)Hu1>md*zb9!{66$v8$l!;o|P17HI-a_kS&g6j+K}vQ^*tc zJ$JU8!IW?5NeTJ#YBlCL6r!M;Ktb+`2K zlK-s(q8_|T=ABuW(#32z`);j>ZKQhd*t{hz$KF`_z>?ti$t*AhPcTRJTRLdL-Y&a6-g8g)tRb3d!-|wQUijkFqsnaP;+nL_^;FI*jpL~$IuXIs8{#*namJ@F+ zCulpPWGu%xv+o_7);bS5|2{74rl2!F`x$erP2`(G8&3#ZwUI2U_91}aLcgvoeqv$fIK=@$H|&g z?o~HKs0%#)CR>q~VGFC{EL;f7HPQMsL@St=TN5iIMPGbR%wzVnTI$;** z9u`olAAB%<3&(4ES$P`54)ht?6bwFsJUKs#pJJ8mJCDw}ydJ+J$LfGF%xzEi1+vQa zr_;!jxa`7@Cz}{Vxq_qZl*U#Geu`ieZ7Rd|*9p)28}h{`KF7Z)bB@u)ywA37qd?+? z2sErfKP_6YFlgZRW@+Ik(h79PdTi_oY$c9uvdTDZNza=zIIiGqSnNXknZ3 zi1hN=(!@R+1ct_6 z;+SN{rv+a;^3Rv6R4R5sDwq)k&8$&n8o@N!z;|?bcd=@*2glAp!y+P;RaNYfVkJ{h z3t{G6<2Fubpe>nH13&>(kOUE#K?SSw&w)y&JO^ki=v^Hh1R7SSdDYbsQ8Z1)KG`3Y zi3WK_jO_p6=mK;yoM5I9$!xY6jEC@8gweuvKPDPFZR)i2!n4m&bZvSDoEVB;-fvo{ zz-iD#q4t?RI*h~7(8e)9uP|QtgWpl1XyhAF+)HZLlYoeU1`9dm3PlG?F19T}OQG~{ z@pu2i?>@u3a^V$_{fE|}Q9Q)Sm8OH%uGCYQJ+mQp&{!#)B6|<(N@@XY$`b3OOR?o5G z;}}KLQW1*G$cCRrliHx6#iWPvSLYP(ig21Ipc{} zksq(`|Ka}-frhy=X7f37f#_K*$W<)o&Fl-)Br7Yc(i)=Zvq-hiw*H{#p|Ldhs)95N zLYz=uT`h86rF|Y~@MkZ1S9!7?%-%0PXD{8xINs?FD`eNn8k1q64T;{gQV9Q%*kZuF!p*l}0vuR4>(g9%eHhDO{Z8vyJ;A5P>v z$$`6*Qd8IEbgGR(+jQ1BK8 ztz)I@=d8NbOv1nb06+jqL_t&-lwJtNEXV1c2gV~vk#Z;=ie;nG3wco1ITdG|Yb&oS zLzzAyh!pZl;2DF>tygBL|w7I}bJcKm*I)?T4~sTCYZ! z0Rw-(7ib^|WJew6%C?+wvk0$GOik1uQsgu}J%F`oCLNnh7)< z*uOs&v(o-L+aBjvRe=?xoYR)i2#1$(NYY#vI=7A`g7@4L#yP+1(1|0SaCM15gINK` z;ra8dus{0D)1kY^ur2fwj<91kh$Y?48j;4%am=Cm+XwQu%t2zF;6Z5}&N|Pr!17-7 z-r1(c2sAtbjy+5eMqO%AUxQx}l%f@Nh;6H@3^YjpxR@k)UU@QDt#dKTKp4+Hg#LK{ z-FG9S;Q{oL+Z)V;aRu=@DZg&>@OWu?0j7&>mf90xU+^4PB}YJuo5;3>ORXAj-;1dR zub$cR`S!H!S0AJm1V}u(uL1|mVuR6lPN@i?>sp>rD_&|W=|NGCJ|^T zqS9Nz5J4jJoAb*5Vm8HOPXvm=IVe8mlhAi=Lo(>#I}D1Bpy+Y|MWYEcv~e=V$wrQb zCBndZb6|Jrxbf-V6KGh2Lp+M_3=q&6&5;X)y0Sn6^I|Z~Blg5F<;>G+T3XLWpg{-h zn*;)u5#$NX&TR|%0}PNNc|8FCF3*T(fs1zC2^z)$al-9sZP>r3ag28D_=1()n)KVG zlFuqFOE-9~{HTK`&Px;JD%uPgW9+o2{5yO;Q|c@!5{ zK9%n%z8Jb93*v}}+GOH@aur)H!7S6_4HBp`_6Mt@^r65Mh;Vz4-`u5#Oyg#z8mx_8Hp^gLO~iwJ^Cmspvn zod`70mSY!pay!V+?W_9FaY%O;+q}$*_VW4akIe)EoRf9Wtc|UAbTVis{hX&EY#1+b z*ZZ=-g7QmkE9jt3&z$&dA8bcgI_XVEBelu#9#wdV&w=jre1sF8=*fgW6OD3&3I(gqUJ!(-_RwBP9_5`Ksr+X z%*%N-+rjNXo|1PQy6BsAk$q&{nadPie&t(lrB}eT>F{V=^f@jYrLSM->;429V5++q z0Z=$54@ruZv_N;5=M)k2&8)igFnQ(dtzQ4+n#el1i;(xCIE;QdImH+a3c&y%Zbm~G zhAp3vqN8H_ zwynZ6f@N^P%mS5u4u~pPg;>Sv3he*)7k|cnzmoLIi!X(sYXHWo5nL)z#XsM9hKfQE z)SwDQ&AV0a9fL0gQvvcG>nM1l#b*>xdYb*Ut0`Dzzn!OmV&1)cMrK57z^NpLQT$eJ`!RU@@ZVy@HY{qbeZ#W1zu^r1Vyp{me@M@roeK zFtAuauC2W-j=egFp*S4?kBkP4X!mu6BSJp~Rer&^z~ICXk-qjT3fR!RdvPsPCKx(W z6~jaVP)5nk#5laaHh5tbD^hEoT#XT(?Z1@-Btry zqoRbOR}7LlJshd89;Imt;DZ>8Wu+L37#})0_RD#SdLDqGfi8_m`PFd+=)zTw$FbS} z4Dd%sVVaLnJcrm?vgwUC*mpcVovJ$%QTr3Te}3eU)0G||4S&Y?k*Q+Fq*OMYD(Yhi z(y_`u!k7HTnB)VvlR3w!fj+7!dCxg=d}Tt|d-l3L13zK(7DozxrN!bHmG=PE#6Ai@{v0syi>tZaCZ; zE8gxlAI*PWd?(@4Eozhf{vHy-kM>-5V`k*uFsmZt8;HeMe z;KgyAETKbOi#_%pfjhIN7NfJ(AD)__Zt@tp3B@I0kH|yvACnjXH|JK`SW{>O^D-#U zKy!IUei}<4+|LYDfBfFhW9!7j%N|Nqm6fbyPGsNm)u_TAPLTH7ux;Qp5kq zbRs935oj30`0w%@CNg+h0n;Av=tZo9ppRow{zU`WDClg)jVE1T7*dCb`Ya={UCDZD z@9j$`8mXM$!>&!9XOOs(;K#rH(?3qDSFMadgIgC^8bIHnqtFw|Q3Ov3cxYo4g`=j#Q`XgG6u?+L+a3d$}ziI-B1;Ny7lIHEYbEmPUTh)qdL-FOH(S-+kwu zw2W+n=hvFCJuP^_ps2ducC$r?i~;k2LSQ5PkiOE$eutgS9Qa)qFg&VxFS`2(w#OS} zV?K$^;rDD;8{QzAyg+B}=~%Pe{Y>9PeXGuMuEk|9x1`Ab7PxLCaJQd@r2zt&o5(hp z5AT@q2>-f0#CH+!V!DL$~q$dlzH)I$zKSiu@**--fUn2btVM5GE!FC2;`uqlb^A zZJ&HXP@!u$&_HIu`~_|rN;ilQIZ5tc3&)x7dbF1r4FVmA5kPL+PNGM9SqQR_z1dhe zX^2VtZ0F9jZQGVqO{8@Rfq4AEidaOR1(NtNJS7d3lsc0d2aXB;(55GL?X&;*`89dks?o#Z?SJ zS0hg$J5^Vg{_02nDGG#bpaw)4V5Q+E^G1YH+R{b<32g?5LxW%cgD!k{hnG_k;4{pW z3cAI-e(~0wNI^~GPKp?v$n$#aMzjQ}H_fps5_rbh$nu={NPE+qsU2%ITRes>%`do*)mWcwh-*70LU zN!#mAD^@+4o?5dy9GfgK1>exVG!L-lyTN<3FHJPo1+OsP35t2ljYgnGu6*CnOpOM3 z(t>0YINs}VGI*9_%o${H^T(zrfm zzxr_;_Kn~828Fh!1t?kv#XV(TU|f4GCeSc<>ZnxB23E5g+&;lWNbfXg0KJ)O=N!V* z59rP~7!Biuwqk|Pgsv~r~gIxFX>gcmZ!^O0%6$6~_G23zd>Hq%E(rYij znC6hFV9f~~VFOJnavc+^Zom7}pQaTnSEZNOH*LW2uGvPkpDUAGMtqN;0{u}QHGCoi zhH*$D=OPP$Q7j8(WML*(VE66Vncn{9Tj>b`cY$@TkdfCq2pA0b9OiLkk!Q7I9-@@4 z4hE!QY>(*@ihp&bcmyG^lyNUT*AR>y-JqPRSa^l z@3x=!;}jA=7zc)VLeEXwxptf5{CaUN*;72b%=CN=At-m}4$cP#0bigV#rSlYMo)C~ zroHuK@6ey~j+N`5{;cag8h<(I5&52?4-Lq&R1iMK1&(Z&@%8Kjg^0CF8}66MG=N3%##{v_XCWr zD;U!il~rja2E~G!nvmz%yDY}@42?yA*XR)jP!`zL(9(#C&4U^ds6aL~*zzlkXXMWQ%j4=j4N-#z7TdC-`g_Cr&J+8@?r4ztF#E z%-m%4d@O;TarPgXQpeI&njhv(1{d_A9d(nuXz*WKt(Z&)>yDVg^AW)*w>UjSZ6dck zPR4mw=lK#xf~Vy}XmOW*D?6dHomcqLd9~h+a;rRzqEBPSaqKYxfp-Wrv?5O%Vug1; zwi8Fj(wBaYq_lpNTP#M60e{DmrcI#1;Hb_Paak~p_Czo;(aZ{qdB)B=N7eUtKiQgo z{J|EA{<1&2{j8%-tIJcGH+xp9m{6Ri7qJD5{s6vCByA{5+yuXv&7kFB28KGsfsH`X ziW%Cr-tTrd29xQy5m}(2_2SiZ!EXi?AYbsK@+4oHg=Anx`4l_D zhUN48nFVIgXwzUzx-Dk+zWwP}1Old_Kb9_88igjUwI;0%kmws|>uF~P!+@Q!tu$zX z7>S9{KMF3wBkDl$eFBSOH^JbafAFicW9#O$;gyZpdJja6IQ3Y5^1AfFhuB_5pn;5S0}JAy!BY7_UdVlr@Co>v-BwQx z!sF7#V5tiO;a@RlW}@_h!v-1-W0Su1_P06t=TZ8=R@T5=I%f;Tf6mG>C?l=EzpLMPD{?8pL9-QeG6-M~Pw3M*E|H-_^6uf&I4+p<|^n z^C<0a@|-)+Y%GC>EA-t0>qnqX7eTg8p5^wTP1uy1(BU)6D`+C4r!@7y;s5!=*Yf(! z0}T#4o6}zt0Kx!iuqH}qs6QP?AzN&#r}JEz!`bssKl*rjV17*~oqmWu)=9^pWR}8M zarO2V3}zcf;DcG1B-^t_!x%tPpe(?+8sPg|Sv~$}%SUOxP8SjS8rt^UciS_tAOi?a zxe@1TioYAJG-~OkBdU=kn8^H*3J7rY!OVY6MD8dnxi7MRX8!#7;XE2qv^@c23;>lI zrMbbT5NogrfT4IC2aKnH%G3g+f`6Jo!+Y#Mo&_*H|Ln67Xo!d)eGcbb<;;BocNj;E zTcPp0{Y2JP#75J7o^8wE-s|2b@7c?0(NBK#*X${Op48f>alBmN)cLg7%5X78XrM8q zp{P?JEd;1ALTOWQS1A2m0CS9jNDs8xiJ@o()i+3eT}}Z$1ui1B2(QXY5SP}r={yK1 z&ZmDfy69!Q?nm?8IrnVePFAFvnw!%}BBGN4r)Q~#uQM&^gh5Lm6m+-Ij6~>N)yxcC zl{tY6=2l>G%ti$ym~>+to;h z9kTh;sK{2nRnSH*^OI7VpvN9o(mKv%$6KyKX{sQ`5dl^4_|k#1-=k?$AeT15=g>nQ z)bJXCG8@J5Vg(wGIHvx79jErd!9!FH-%3#`G8zcjEnc`N3`G?m17x-PIzXHiopb;h z_(>M#RNjMbeim%=mASRhphxXkljKxmLwbo7Bb}nd7^WW4cM^K-=Gk5b8WxsvKK+a- zsdVx<3T43?(95(^;5C$={44KT91D9i_#h87WYJ!>@i6W<0*ZG74R1-+q%^BIbPA6+SlRd+tq5OQTf<#_{HaRpYzcJRwR=^HO?N~@XI0u6GN;axHp z?vfoLPsk_ZOkZbn2YtFmI<=1M_CNX;v2|kcvg$M&V`Vb-XMv72-%++T#ys=fHtbUb z6u_6u@NQcl84cGXC4u&-c>*5{@yytN4Bc*HJq}_#8$>PPc*_co{wOBP#O$DfepbX7 zoBTOy-1u~{e<&Sf32n=Fm>+61i0Re<(YVmbwS9TW@7r#q$3p{Gb;Lt? zNBI-K!|-J+W_x_PZCk3ZKa(C~l}=f;9*^|Zz|ojfMnWDPJO3e|(f0^G(4Oxabp{ee zvHoyaz&PmB(A1Rv{4f48&UAm1RhQYU&f1o8W;U95`_=u;;;^*Ou~M8gi%=b9){eis z#msr=yU~|w4<1fGd-td5nYHU!wO_|Esbp0_6X~sdizmuSw8wa2CDYG%ZuD8>oiT)N zVpP6+uiKD1l?yU`bY9+KMQSBD9IN~EL!MCQ*e}Op5J_D-#MTFtKp2YhNYrzJD%?O2 zjV)XgIbxCTxNX8Z3WssLN{UO^&rg~?Dg3vtvB-dNIF4Yx!MzBIGQS2*oDccY0F>M4 zbl3-w&n#7%d4l%xsR4HPtJlGomk546uw*GKuusHloiq~Vz?Cru`hL9GK8P+Sdl>zymR>Jq~w>OFO`d=%Rocz$g2 zAX`(0bzC>(Pi%!k_@4(x+U|~>U+~P4se0bL2nJM;EjVQM6@dmUtI$oZ+(~brt8?Q0 z(%?GIpL7{l!ii3t5avRPxMg;gLAb5kx2I1({x~gP{&48MQXJCh1bfW7vF!j5`W-8O z@}n$|zSC(j$fFad<0Y^AyBQ4z8%7rvaV%U{`uQ*3=R~KL^uqJcaiq4k-ZcIWCSLAM z{m=(?!D;4L%W<57!8W`;G6KxB7{Q`f5%(2y>QNzu97mvdL$}gyLu-3_|I_X1C!cI% zJIvWQdQMPWQJPZa%qgjQ;&^H&u%eD!j0oEUT_V8T3pBu%JU8qy#zN1LjV#bG5}ffi zh5HV&Jcte3PsUpx84WGny=ni^o^%p_8kHLLavrQGPyhH2ejoj^GR*{&oa-TY)>9`8 zG>n8E17LtJ9a8zdhXsOG7H5u;j%_WWXVqlSKAH3N`C`f z+DdN4KyfjTU^Y1CXWC<@(fucpr*o{lR#sJW-1swLtIBh+Fa_@_r{VO{oexn?vR!NzE8Yz&>S2pj(4hnG`$mV(A$xqLI0_6(31gcU!O6Y(}% z?S^OQvv{Cg5%WSH3^Z6^@eF$DJr)bEu~lmk!IxzO)~xa4LX7euuB%7#cV#%!9|nn7 zM1udtFt@9iNn$qN7_(@=NqrSS*j%i_l1{U%ubzP@yA6{^@bUDjzOjuBW+U}IR^cl zEXe7WKWr<;sSb%n1msD4YbMa}L;M4Mi8okSsv<+kEEz9X`jyoPN)6Lq{F1)GGvb%J zm9|_Y35*x(#WDEGg`Z=b{PO`B6HAsZN$b|G9nNSV*hb%T-jOGQ&hWM0RmbN3k@VFT z9!CJ#F>6bh<)W@KGkt&U0qQ6mqL}b+r^m6!8&Yal>Mer|RpY2B1NWUi8SuZ@kILh8tP%m`#s@DS4;CxbpYmU%zH= z_b1Tsl|c)!ut_K+Oa-F6gRC4MBctKt)Oe>ZRA!G`(3RrNH zv7#Ml8}CX8|0(POr|FYMA2nKUz;Nza-??vBD#wrzK+17Qr=Xxi5Mf%TKfZ6;R<7Kf zHdm{|!JzRd9Eotm-}zmG%c75$u3U`>y@ujyoYAuKvPj8N@p`X{Gty^#2G0@%^A#_h zPy38$2ESy^OlEAUR0a8#*0%IHg)B``f9#P}k%=Kl+dqXuU{dh>-L_1f)4B3F0@7^& zNq|xzE2Q3&8GjfB^zQ`5(B{pbq(@m{)Q~eBO;FI$*HAQQ5&MpLhV%)r;1=}>x;21BH7OZ2}L8i+3_3H`n%%h(G9pER}g)ucechUdh{>9k1$N5n*RXPf$ z^oi&nhD$GsQzN~xu_=uwE8tP~c+I3xjjJcND_sQcLel56`K7-x2FAey?6)hf&SL?J zKBC|J-RE7Vpi6sOdun9`p!-61npaa3D@L*U&6w?bq#E)Zg8(9QfFb>h3Bu&@BB1xn{tRRypaWVnl=>Re*6MV4X&eOgApU0I4V~k0Vh%&Q%9NaJ`of#(diE09^X+gvPuwhY|SU zS@Mg2&$4YsMS-tcBE-#YZE4jLk4IrS11CpM9#2giyLS9^9iwOK1a|DgIpb0#srj=? za5!~>0BBd}-7l*Fud>tOiB(Cz1igUhm;)vqhIZ?Oe#3A-8UNivR#OR}oFk)QS6y4$ z-bVD8uj0bR_1}N*AEeb(GoPeG0sk8KF=N6x(kQW>#8$QnEm`tlS`E(|`B#n{xAz2p zLvMM|D|nB7h%?G$1bOJQe4-H)D;hi_=l2r?zRnyuk=8x_RC)-b#pnAS)DBh7QTp-( zG%eu#c2|}y26>wmrXzR{VVcJ9S#L9{1&`r4q2NYpfQA8?@o5AU zP-?vxnax+&gL|3Ibvr z-DTx&6a)9Dq`T0zyZ?4N*xH>wK7BD{Jg?F4=EfJ&Gf%B1pjVcqUGf|Y8>&c0!ZY^K z0IR0yb=vh50Mk=1l9hJ)Cy+&gBV=y^ERLJrOHtrjVDkiHspxiN0v)JL}O&l-)k7j%L?>J2B?&%zLfP6og%*eFi6 zk$v#o3ok^WGutsEP(D$%G&miLI!LS>;d}rZ(pl=bAYsM;azKs0m(Hm{S&e_4V0DK@ zc^fe1+%mcP$tOwmo`vDBJb+Q~vU*!gkZ*j3{g)?g+sp->TX8|BM!jQSq?eA|SppeW zY_}M-SvC(6Y?zFmk}hytU|#5G91X{u?WxWJY~qD~lODn6JjZsOeEZPOf{dA2Jw4qx zFB3T~Z&9kQstS6z3aCS2a5aJ?JWosuyoGM+W&>TOb&Fxr!mW3=;8BkaR}NelI7D#G zXP1?hlBHQgfNEwqE&UkJ>LY{T1{%~?I(ZQ&8K%cIFu^trG!)XNc8EMF7PzhG04J4r z9N+w!1q630BPcv+JViU{xAsy2^JjoWTSDd*SNJ$q{mj^lm38__7b4&g@@tj?{ph*a zo3`)R!Ko9SaRg!&+bSosrLYirxY_6GI*zY6!1jdEMHF{tHg17m>L$`XxQ|6{0tVI% z!juep++|#?=eyI++QVt<{)3!OaE=wm3>BA^k-0a0Qksv`SIYM|JUfj9&%|uy8&bu* znbAN=o(PVJJK5iOI-iGQ?Idwoa|bj{g9JiuV!O2PoZSal_yE50K*PM5)6#Fh`Hi$p zJpm3`i|IB&hJJCFzKY}8eS_*#=%miMeC-OWu-#EF%S@z4$tJ179#-yU5+g< zSx}aaKqvX%{)Qcc-Zn$dXBdceW!Y_q9DPV(Zm4G{kYYKC^oMe71xxjBUQ5s<-ow8`r~tgU)OO!=T=rl##&ifY4DwLm~||ZA)9hMzWkZT1okMK zQ3MhmifjhjRi9|P94C-r22u%Ild7w#!v~pxJs*JvWGKtPhWhj=3ku?Niet2CKw6xE z5CVVLly2u!4#tgV>mh-&2*zT6J^t9^sk*u068b}X7Xb^`^rTR0q$bpg@F#dl}awrw}s2jlrl z%!@=5$Hbz>=BzOKJmz#2+b1SQ090N9Z)s1T!}*NGOxm?Qb)Mgs7tCmoH{DVu2I;pL z0MXWSoA4?88y5|qeeU_RgnDI;+iZvMfoLx>8R(DC(B=)FgP-LU{h$b(&~J531RIbo z_27kzJrTHbaqTwq^d#GPsw*pl4@o2iD+xxi0AnEOF5?J&LYp)l^f%xoenp^x=ZeGH z@MG`?lr4jT&8=6$KS`S3{8G4W zDi0DUrDH~z4tpmZKY1)|`S8Qor+oV8u{0iGn8nJA4usndbVf`i(kO)$qF{z;ej0*; zR8-j2u;u;`BfevFQ|0XQI@#XPap4?$*e9WMCP(cBm6r_XaX#+9)Ip5uzkF_yE`>wT zQW#_`4UAwCm{Nhw3?={u_P#VYeWv{s-~|~4-rr*$_)NM7z4%Ppx3;wf2%AY# z4A@v`QfI^zCuwdPtU)LDCHq;dLSYCPsBrJ6dpo7M0=qNH>8Eo@d>Vb|U|muk`SHaVjkU1aM!E;-lf`Mey3fZ}jnOD;R|Qmj z=l%SAZ}7td6dGJOt0jR|rcciT?x6%ZR%$tsfJLjPYXOZDD76TX3!|U3IFj{pfzCb7MMp$S2NL$Sd=l8;uTH#j4|Yku=*y zRjf>#D(xyDd{%%{KY|Pb8VkjA1tr9krFj?}Q{YR_s~&M+e|mcEjI?^(*P> z?W;JA>>V8MIpeHO(Wlsw#!yE}Kj=UxD0NX-^60tqX$vQMh{2}oVnU!uXQa8TY+CyR z0z_SgCsfQkqNuI1B5sLCx!i~+8Vs(Y zOXJ{2+V>KJ;}|OOi1BOW$}5+_$Tot4V(TOfZ!trt^Ji5PO4}M~!u6H~2-JQ;dTpZs{zG z!C?&0rt>HN$Y}oEK)B9)eRB&duTU2aMC)cskzB6b>jwfDte4FX&)+Uk`V!wRh z{3?$IwoOl#em!7{dZcRJya?`u+;Oj3(|$>Bb&0hV5RNpBmGQBxK$|I`LltfYd@-68 zM(qWSxIQwvLY~nT_MwR2WhuBZK_|)%(eG?!*A!#$7oM?RljHZ#I?GpaO5_(Y)!<8@ z2Y>UDhb^$%2W>1`Ii4&JPbqN$z`2qR?)P?XJxxNsaPP1B)iFs6^`z}MUfa(z2Dl+s zG2764H?ChLdvbCF*GwZ9JDt;5jfVaM$erVGTf!u_Ch#}2y0mM;9%A{GS1{gwD!Ndke?5FKcNB=s{I-D*7XwSej;n11UYUY!t z?6N7?MKmE>L83T-~hh!3A$EHW_|$XJJ?N* zpM(dVMevArJ2(NN4Sd(`;kLMzmUHUF)XAxatrMl-yC(&WqTdD3A=6ykMt@!Cv9HRf z`|ZQ(Q@{-{@R>tWMhp^LxoC*39UkLspkY_-g>;%Y2ph$crJN^|eztfK`epi5#)nR4 zO#RHO^)muA5?zX+_=rpC!j5YcBDj7(<*pg=O6px=60jlu?^~3=C6c_+cI;UbuWP9-} zQwI+-z^fX{;=3&Cjl_JnJN}9p#3?pZUN5)i_m}Cc*?3lYcXb`g|Xqs zz;$s_dkor%k=i*r$p%cvLZ3deJ1?+Js~?%Q4wH*|6IrMbcVpF_ev7yMQ%@CRQ{|4l z7_3d0IoaG1!2slmr@3X(`99AaHa0heUYJhX(?Wkx?3aEhpBc~7H`+J2DL?AiN&{(; z7xs)y9{M5ewYSX3@b6~v^j_#nb4tt5YXlIvLt%KHZ=uyX7z)})aG+-?6A+_Rr@L%>vOo6C02@I7E<>;4@~EH<}>&&F8!Oc zv_FS!&t+^u5);ix5DS%kX%G+0{ulZ|`UFNYr{anO)tAx+SAY0jaquR5ZE)>eTL;Ho zyIpm0j??EKoUwuj$$iYUP z#}f31L24SjXA`*atvtD?qMmc>m_ZPI1hG<-kXOWD9y}ZfCj*J#g7q2PdUu7hcr76Q zga7mU6mk6~!K8T%8GC|%*_H9;@GoD>xBC=mkTo-A&=@y@8x92#Te;}WsS~lMeCHQC z(~o}k^SJkK``==27)gj1U7pVVZ8!fN|2~EL2~tz_I;9JL$M62<+|H(r*jL{1pL6qn z!96vQ6lX9 zA=9kk9uxYw?-v=Gv7*7WrpEi;IzfRMD4t8C;Ae58zw;AV2uGm6@)Pd!Z703P%0LA)DS^GhvA@ug?2=NVnFh_D?B!-Q>~#k#CC%_I0om* zXgJbxA?;|Q3OawMBxERoYqv3)?&Ia079&rM68`VuDyPjw7{s?R(yB0`pPpZt7P102 zo^20B9*fDyrIiX-V?m{aj*p*xw?@M?=z0-{_aZA=g9W5d<8WOgP52g{7h;SKvP{=~ zvxkD2thgdz#S@Cc7$_kyWdXDzj3-^sezr_>U%ipeUc8(dF0y3+A*A^zLN=NW%-3!? z6Myrfrew^I!HD~Lari|XTiV6@{l*#lxoYObFw(j&5Tx*f`*=;Kt?83Sq?4E7?Z1ah zEWmCdAe1>C_xlkQfEm6;YIpMQ^R)fA{NETY^HoG1EDlf{zHez6W1l)T)ldww3_WK7Ujq%1(V+7XH}mfI z)NQ`=Sp*us@{>qmu8;0m1TJ*P7>k!F~4recw5s=MM*-_wF-m z)~q&b*3A5WKn<_|ZzXl#Tz=N+yH3i1wbpIQR^>}$+W!SX(+ytIi7*@APT9xnyQ_gR zK=`Ez_1|}mA9=N9n|kby!_+;_zsn>|Zn}O87METWlfP?0K;Cd_s9%*c|2I-cD!?*T zF%1F#UE*C@Z%wo+Gg=ep|0lZXm%q9^jy!q*5iwoKt#ULJCxd^#&*?jGG*l9hP6L8m zPm>;ey+-=*6!4SZc_&5=AI?h3qvP49hr|jz>Yeb|>LoLpLGQLnR2p^Qe3h9C8BOO} zL$_Ur^>P$TFPomNl))1OWglU^#H>m3wgJ534;Jy&*;96i)KtA~xgK(uSy z61bbEhu4mTo;APqV?Au?jIo1}`CB)=h~*tS9eQlD1H!vs(93fKXFemF^YDPRVPvz- zI_;=aZKMP^GR#z53LMB3K0TL~WfB)9f6FT6_^L10r$Z?2=g<3;(b2D>eXC}S9=7IN zyN>01vZJ#{vkJfPMw^A--?&rvwe^&Br*v>@i77|d{Zq8$v0a|FjI4o9qKF<*8zTL1{p#^9zcYmJn-Yuu~Buc473a?BU= z8k}2V?VZX1;a1|22RSPC(X6?t&>Yq10=>7Q1HS@TrKg-D3y!64Y1zmNJ+Fo^1FV^6 zxsFyjva*b}Sx#H7!Dy3k%!6j8&R&opt-DsEgxwth94Rpm>n`m}kMfZtj*hbFVXx+Y zemH9;c~X?kc5AH>E$HmZ&-JBme&%baU^*JOc63785jE0>+2~x* zzDZ|;bOx`jtWTNsSc#f78s3{RC&o`*obTwEk_*>cd!1YiX-&%0*dxA#yM;nm=NWEh zN7E63r1{b^$!oTucr>(d(Sms~XUUh*5>&Nnvko1+rit$yA)pSznsNrf3x2>0cryAz z`giRQ`5#7Mw2)B>M>47F0!9jE&HID}440>aY9q?ro(O}UL>6tr=wUOW8Jh5G4ALBp zORqODRwQn?tF^LubvCdid@Rj#!^MeA;J1i&o{v}l(=QgpXN+=xMn1~Srg&1@wrv)z zSn0h9@HB;1nt|74$c?G9<}g2SL43lCAM(>}qf#Vm7XEC-h(6moQtx@QX2m?BL&R>^ zmW?x{Qn~&)BLH7hw!BlHkk%q!YH}*+y~rVPt`}drw@%_ydF;`V?2l*6&OPHby1KMu z)V7V?FxRDFw2))s+A_eaBP+^X%Qvb)>6@bkRsI~67Q!Uf9BG+4dtMq6tcyvMMth>b zS|m>!VPM|%^?YSXHQ2l~0c@U*Z*xBWF%0 zaQ?q@Hggn=ca$O4+ff>SRq`GW5=Y`oTp7jnDbXg_x6yVjM%r5uUBM`pb(dy~&f`1Y zl{U>o94V`O$9s+{OZQ%@hZ_w<(Mr;kyc4Ww1YSb_O#2r=1H61>McHL3Mj_-yWv}1IydD57)V7;xgGTxCX zVHPirY%1Rhy%t*H#iYd?4HU27%k@`2na^%itytXVryEgN+&BO9+2XiN@^0OrB zKm+G}*VdW!5hIgGjW*~!r^7lbte(pVx*ArEVsU4h#fur)XKUppBAT>S`+BhfeA2aL z(`b)Jx;gWxbTl+bMOZ78Jd`^nd2TzEYyT=+zk&&z3ilN>5+HEk91#Wcaev*W@L`_TSRol zGDho_>B<;+Svevf+Aed5FrJCRvi=>KH;i`cZIF>e!cj#S@+gy07SfMxYSX38faa}V z{&-88H`2n6{L>twwXChjSJl{41Gy#3CfJgE%#Jz?`&C@nL0 zBH&%81W)~Fb~@A?lx&Zzaa&(oHR0z&Wt#X&xXDADo1gO8a*O=rM&2tlAy4?+DN)m~ zRn;HswrCRTx8ET7U3ynm2$On_>@#Y&=rtn>oSs&2nsT4EHpwHF=Qr}hY;4tqutmF; z?9|etRZfl5rmMp}kV*qa>Zab1SA?HDD%qcHK;C6E-kMuGY!KG%nK_f4bvSR+ibcQ~ z?Ke6`dhw=F4LS7aa%~`gmtxC;Wny3du+jc?6GBE#d zzKdK|c9#C1Fqr3Z>X(b(+V;Gsd{>sb0PCkU8@@F#t=E3Nj7-!b0kFiqZI-qG?e?Yj zgq`!nixYZz*=sMnJe`wh zDq@mpR8pyY2zyb8C{TT_z$=}11ym6>Izdc^=e_jGYjNkG!Qlva-~A7dop;(PL+7h- zMl#BVmEh7qq8@glQh+D`d2W($>|8Wx%)DO+(2!HNi+Sex=i`Gh<6@6}_bJ=mY}_$g z(s4BW%Wq0}kJC0>BLTw=hV;HdQKHRqsE5K#zVhh2Q0KJ1`~Lee{F$NA2^_lRRkto( zVtowV5^m(2c-nw(ODgT4GN_WzQg|!yxoMcLio#tUCX64S`*)9h_x(8Gs3T*WEw{iR z!l1)&sEjKGnJXTH;ABVzL59+jmx55kPFz@~Ayv*XwO$k7#@RITxp-vc%dst?afcst zAPcW`qD_l}vZmrVaY|l!?lFHw;dxJ{EeC`pWj6sf=QzFa(o1put#|N3#KHUQ9s4j} z*_E_)#Hhfel?;PJu-K*=ks4~&-8yNkDX`N3)_H=!DZ=IJoYU%pJdclfA@jfB^iyM3 zXr?(vu_28hG!>o?HRftSb5&D5K%6kw9W$FW(0peij<`E-yEWeW=#%K)x=EaP%2_PX zwPgx$+e<^(5Oa+-uicu;a8}E8!Ab?Yu;)4vz}<+teM4xq3xGM-?3FQNC+Ljf;L*t`3m5m+XU~ik3Hv~5+*)l>1Xlr%K7mzB5nz&s88G2&tL`x^bL=Lz_lB$ z2dy-SPd;OPlDVI!!kx~D#OH`IJ1C|BEXdcl!gE9a002M$NklvsLs>Mgdp?(kG=|L6_Dp#reB_&OS|a!TSy(xix(NS5^w)^d zqvM8q?u$*})qVFrg!N-~Vg>f~6GlTaMTK*4l{wOl9rHA3p`(=T94mZy^qxHIv@k=6 zM~oU3<6e0+diUKU*LCRJr3;QDoC1_DEy}aPUk7^)zZR?^>U28mk{u6>ICY_6w1!8& z_x|K~crYuZBbRsErDu+ws6X6}F{g-;zj>!F1Xmj0ZlNeT)S-$0DsS3A7<~U@){1!N z?YHAKgp<*azj@4<&DjcLA5+Tl8782K1>tuD8X)bWPbil2|@ zEV@3*D7M3#OGn`FL;JHs$R@e)p)x)l8kC`|G+fp^%-cMKQ5~xua5|;=IsGQ5n1Hi6 zbD1aq>ML>Qt+!=_ zqF2}Kd6~t5AA4d*I*?8qa5xK>ZJ%53CLW-7=}-NcQ!hBz_Ao46Jea48@+mhBkyo#( zzpSJ6dmA}+_uY5Ln8{P38{6!j@YD0y0jftjL42-G_UF_C*W;)<1KMcTq1YWbe=wSJ zR|A0YJ83|gaXaOk?z%U2=-MfEVnI{a8j;=;-Wq)7W4=1;or>c8Z|xlONqYm>#k=p> zrWBoF%i?Av15o!q@l@>EWuxfXyU@JrG0By7T-Dod57`hUqHIu)B+p=5N={DSk~ixy z#m<2T+j|jCu~~$izx)2AaB*XI$LYOmFV>OjiqmvGV9=2xJ!{K-lRKci_11V6{T>_B zKb{d&=9b~w9_<^%hB!Yu(`j43S$(GcqRWsw^;73)v+(2l{MDVCW1({`Nq;)inWU7_ z3~u54H4eTNMEuTRy2iM-XT>z4YyE=R6wwkn+rD!*Lh)P1INEmB2UFwXGk(mP4V%SU zc7&*(bxipRj;jHZl*PzbpNSuFC+&Kz46swwf{vln3|zqQo?HGEZ+x;acH6E;9M%6& zI$xc5mq8@zr!8xHY9H!gNV!H{wr#dG@7Vb-&W*yy%6egOCH+^)f6%=T#w_Y|%)vj( zg=E)d(N5*BPD#<8TAE5Lcg$0Iln)d(RfpFya!M-gCH?EfaNhs0XP${+FTa{jl4DOi zA$GtPc5p@>m#4H9g+HfbgCjG}PGe0TiVr)AmYZv^NV~xA`xD=NFCM)A-gpPcX0I(b zWjCLLV++=d@Lg$9dKO0Uns9SJ3$XqWWIC{{L%u_3J#8jloo@B1xM2;Ge?K@dwrtiQ zcI$Uw?6~8OI8Ha;TJI40g?+~tO)uR$kXYA@;f#euq zwb#eQv-F*g?|*RY(4z;_7+a^~)%B|?yaHB1H}IG9!V7?%$+B|#GtZq$X#Z)_q)9P? ze%XW1j)+d|Qgi&V$FVERra8sOX%osa@gu&~9~PjjaUj*Bw4{tr3k2I*c?|O4>#`8* zICf5Y^09|v^6bUYZ};7zAB*pIqW|HyP8rjQV!qj@L{>SFXI?IL=^A&#o_aER9ndcw z4ISEdeyp-}mwFcj{wo_9cn^%8b;MzD_>o6M4>|!db~+3=rXoan=6oC$ zD@msX<(VX4I~=MI8CIdIXI}!G$-dW53>_9%UjMh)XY(#`&=E()-h1zr3+f4LDm9s% zZ_@}+2ujdai+qv@d2UITVQ04ig2YiI=NBrZ?tl1^m8OYEnq)>D1S%k%3@HSGR}Z?Y^4jSYHyUZ~TA*-oulhlcJ`#U<;NjSBkKS?CDJR9& zTWp?2l!7%83dn_}fK@uO3LFv*UUOgqB^Un?_6A7K8(y0Fx42aqb1jV$u}a@s%Pi}n(@%+G=uq16S_ zpUv=dY`Ou_9Yi#&%gAf4{gNiM)Q^}L%3b>c{ISjf{rRj z!xwBxHhbZcm@s)pyhv=JQB756_=@u`jJ@{k8yjORHl@BU0;UlvVhWz29SZYY8qp}o zf0QF1xQ2)HHe<#|xgz~2l=4d>pJ&D2!=g8fOuB%UbNp34!kq>WZBRKIa>R)IrSUR% zxX7DE%q?;8(Ql~Z5=N!poBDpdJdPbI-gq-!e|SiA0G{pm_1IuN78YA8S}|XuIqO=i z0fD1Ja}G5oId4cRzzHXSE#L=V5LC|X<$Q%O5%JM%4c2Kv`F{GvlK61xf|$1avzWq8 z5RSyHz`39v6z8yOu>E_m11WW4Rd|Y6z+#Xe(_x-MCaEl4(5@y-Ge6KSry( zoa;4^w;f6K$1g89FWzBf3sGs%x^9aGk1|XE0WI>S!RfAOe2%C=+rn+znuoCYt(^~L zt!0U0>#-J2E!$JwH;aWMpB^?W{(1T3@fvkI_xR&tK>z;OC|&a%;agh6c{&DCBW8z+XLgL9cv)&egSc zigavYq&eRS9R{xDcj6^ zqyup)pGqHI`x9^3;m!Pu9p-zk9&d674OhK?Y{<~K<{vl25j}T|AMCe(F5Kx3Q)HSr zQ1{t!aaSUp4T&pwNPEOCzUy1K{iO@AxwWOcGR(&rH4R6#+p`XQY)~$a`6C?cZWFpO z3$o_uJ@r!vsO~Q$?xjBofEswRD^nX!5Eu3tj~r<$^yQRL$sc zt^}XMM?4?@{`+5J;H%@}2)2tp=f|f-59~3W73#HxL{caRTufOzFBgy`Px(`t)ecu% z<;c7Cwn#Kl&J67QVb4Ajw_fv`c!OKNIOpsbaM+=_^{(`y{8NV{?)a;oOZYja7&afC zD;FIoOh*H7=ycH0@D>io`|p1s{yp%K*os$wdiB-O7n)qRExV6U_jEe)y>dVr7C+K@ zMehkSb@G_BPF>2Nff02$Vb~J>Z{TLcgtz19z5B#T$eNwD+aB6Oe@KhuCt|DobRs0+ z+)I0dvhyED>(zv)Cyz^s0-3>p-Y}f_*Z%Ggv2*8*qTiv1Mc=-Carkzr;}>okyBGgH|D?459NLeQTxl`Nl5hG&I;3wj|^UsaGyYv|4IU+&W}a=O}oZ1#~vMR+ilDf_yoJJKF&xv zq!1W~?`isu91Y1VAx$DI9c)>pVbPglr>#%zD4zUT0rN>@nBLizh ztqI{7D){Wkkr2X9gTc%=?})?W#FJ0V4z(jbdRk>Pm9qw2hG^q4(rc7u@=b<(A@EWl za9zCJz{dZNS@`QA47p4G_{SKq%TBTXK?lViZq-AFIy<8ZCJjNdlh_I)k_p#k5vC$! z%q$ITg%v-E&`}v94sN;szIbcMb1~qQ6LLTK&2coW&7wLoy28SI6IbTRwTzttO1vcs z`2+k46Jgi;WoXXy88cX+cnpT(9T|o3!#;i3+qGMc!a4$5XN;#H1ZGktU_F++xk)h^ z1Rkrf+-Xy%<;w0uo*T~AiO3Rxv==f?Il zcMU}A>DGo#2+w_g@}#)=_S@sPcie8#ap&*<5I@>?-&}}sDGHg)R-v{g0Mi_&AoHuD z9P*qySp(k7Fhq`{z|C*2yDo-Im>7p`yKVgRXFtmw6QmPIXaO?wPmetBuXNEagqBp4 z4g!R*u;-Rnst4%N{mosh=riDZ8s0nol1rl_u$*?zIdKTv;BDHqTShdvYOW!{DjNl% zcuB*AJXA2BpOIBBq<)oW)Dy%}F1yP6Hif-kZwLblpW4#{v8N zAU4GKYs7c-sk3dRi(EvE{8R355Yxrcz=Z%%M@Q{6rslA4;bca4UqrdxbLZ`G)Un6M z-o1P0ZU%01Xs1-=Q;Z@Fqr&&LN!`MxWGUZk?A1dl)q_u^$z?=4OrB21Yy4QYM;aT? z-Tzp00fZf(v8@Ti?A)A)2E;})7P4#vvDasmOnULJNoseIA=}r5%@l3oXeH-{+)+?8 zX~;+~?<^o{WhUEKPFuc^sSs@M1`5By&$K3^Z!`!adtiY+bqi>@(Hd;`M!4>R6>Oo$ z0yXc(bm4^;WmJRfYYrPUI0jvFeT<5Eam`t0#3B3jgP%Gi|46_qmV+C> zm47v~0L|OLYdw@{{Az8H^n@(4V^`;BxcR2|7iAdfan;}d9{XYtDN|fTPMn+kye26V zCo~^7#R2p~DasdhL6M;t!Qfs)VZ_U$;;IWSh}W6Qa6S&lqmMl{wxd%jZ96h8ex-L) z$+9{x$9y3CwI3&0x8i7+9}i>5{q(wP<3RE}7&)`oUT(d+QAQfLFlBK{fd%T3;h1y| zWMdvd&4!|QtQr#2gYDV)Q&sxq}YuPMPOG6j*xO%ouP4TWnRwGfYO`A3?w>TY&qx$KgL*k07u8O|9?wVWFsSkw5_rz&k zs?l7c>(y*|`AL z646lfk!@i+*v{Gjx%&|1D08G29S1rg>`edZ&wq*sN4*sNHtZZ1UiHi91Krs1{v3W1 zFVeek7Mg})fG^=SKky|!gtdy$P&W#bA;&}Llpc4%&!QXOpKvC!0Gr8?Or1JLs21FU z9SbmluY{TJvn{EE`O8P*Nj~yrN6A0@=%aXuL4qs)@sBtihusg*tGo2<2~D=oc2E0) z!3%e3Y6Pz+#?xL(TLe>`GNnZ-i%zj4%))FqESJKEGl+tDosq`7AATrd?7!au83o$0 zbEh0-b{jmW^yzeP2dZa?6dm@|;F$dJtay{DBDh>)o3;&OV)$@Y7RINqa2qMcT-tG@`S?MF!Wvful}JUPZ=OW=`86 zPi0xQtAiZielDZagPwRi{`|`;<1LA!oD0%w*Fo#z zNSaMPl@4n%Q+`rsy@Wk>^>x?8DC~o?*y8(`V~%BTbla32_E*$T^1gZ`@dfPSSOh13 zWJLJly=Kq8Nj`= z$9j|`?6d>rRkn@SPKPp5WeST<-$$E1ao62(>}jW_({8J+wq&7WwgX4jq)nqt6aW0H z@Sb^F1~{|4ERvgUU)vaGuZ|}djeOGSg|oeVv-ps?ie9qCXzE@y1vK2f!~byfAjf0b?|rZKSSF7=hJ{ zjNH-DU?26XmGX}Nq(k1tuyqFsDww-r%wrIE1bx=KZ@ncRdwpD-#X#Pf=Vx`OYNZH2%%d`}bf zR!71A$5qHCNX8=zkyEuef=LE>8;|=_2%h@?>97N>FAIf|7Ajr6@{Q% z_UJvckw0RWg!>*J9G9S&PuhKt_+h_((G$hywk}mfLy20jb5x9dt7M%jBh1SbFcLq% z+}4QltoEd-Q{u*Z?v9C1JQv5FbxQQyY3E!)*m+E@P;K54up_1#LlSoiUzkW(Q&Di# zU~wBGJG*+nT=iFFs1UsVpEnSN(Kimj!0p?xR~|RO8+;%zAm1bG%1eVVW&6)CtFXPakl3II)viY5!;+D z!TIO&S@qldw1;(amE;ESglkDGW>njC6%>fg*b%~2*q?sxx%lzrm&PuQ){OpVo*6$x zL2S~wORk9QP7yk(#H-$VJ^BEbqh`$+EnLW)yis(<2Mrz+??T(7`I)xE(a@b?`i)w( zi8jRMH~UsZ1IisFr^j48s4S_s4n+|qkLzgg=Lr1@deTNT)U(sTNh0lTJQ0`r&Zw$m+<38Jde7yGj z<u3#J4-aFFiV}ADx;vWn_#U0PtxSM+3Z4`)3)#3b!TQTdIx* zDa?7k+D>vrBMem}6vpb;F$ZVE)Mble`d16%%f>i6TCnp(OGXV*h>MoE6%--p$jbV7 z=UoHiGvwu@IrC!djD_jIScq;loqO)Nam3+ArvH5S<4?uYzqvU^#>}|pw9_#v_Kl4g zEltA&_?#LbA0=LaP23Bc7%v7;K1`XWVPU7o(Na4F;|a09`PN(G26Vy(lzYS9{~7yX zC@S;R5$c6>HY5$vF#&Ie-^&L8kW;hVqS8*T@=-^pv}YLaLc3OO&E=)D5O|A3v~uB?P!{ep?LFy_r*Q;-xEJQ{^aP5 z^J}XfTQg#`7Sjru8_W02fWuY%5D()d^Iic1Y#XUPLU8&Cb@(NX?1qRCI$YdyrhZMYmKnp+#%4(egoAaaC#=8PFJ4n05g z`RC$+#~+KUF25r7La*A1(-GyUQ97Wd58x5Ec?53%`HpxI-}#Js=n!m)BS1a=Dp6mL zJor%j>FLK~-yL?2OV2qscGz<3d|v}z-K2h2ekt$mfE#_3x-dJXPMJeL;h0v>>bSQo z_5Ko~9ELyteB6KQ?QzdL@inc|{!ALDhhE#dztxIF0PQ zfEw^5&1+0Hr2f;UOi7$ygCT1A*Oja;zW)KNq0*f7sOBf!(zy9*57@5C7ywLK5>HZx zI~p~DmefzqBX>O+r_qfiO5@) z;k69wmZNnTw(@2*NRV|#S2_au^vDr$*tusX>=zz%Xq<>KyaoK^*0(yaq!sBSX+*r> zFcY`7x%bkM0j|;+1Mbb+I$1v>?jFR^aMi#673cLk0Hjs5wo z6}AQra-DcHKAsUz0mqXM-51kolQ-!!8F#UDtA?==j)skNG~m2#)&QLY54fh4@LPK6 zw8<+48lf`z)OPa+a?@UMF~~0fcm+{=pCi~mobv(B5F8G?VtKAH)tM--zWX1X(WI|2 zwQt1ZM0{NSi|D<>4zaco2IQ4(2d=Yo1U>*I`6mew0K|!SPCDY~h_~%vN8PA^w}}cE zMFh;Cd+&}-u!GMy{)E_S(@pamX~W$nwDT4&Ku6GdZ^jm}I!j$uKO>XKGxa!aBmHZ) zx=TWH?4`x*+%a&_qjAkuS7wCi6+b>bjymKJ^hf&~jH_gO!CUF9_4&?!9 z*(qdc!y+F&sxPdE_|o2y{$CvPYFu*Jr7?E)%sB5y2NUIYL`F}^mwqqKlYaTel-8+$ z3wP#JyUV@oLm&&XEx_Mr$l<}mpN%uFy*du<)GZD;ynpoR(K=` zn!hw%mSZLrEn6#X)-~X#HE~WkWpLWGY4HjJC%2M!_s(775F&)O=+5pa@Q3*RjCNPH zxNbv6@lgjIr#d608EGV)nZT<1a^i%J-=ssJr#e3iyZrm3{4PpGh|+?KJ7$sT0!sqeLYyXE&BBF1jdsA`7xl10Fq! z2IY!$?^F=!eHq*RmdJBtI`HZou)pW@A}Sj#nZoPNPa|F&8Ta0P2QqkcoZkP4IOpV3 zV)HIt;TL}Z5cj=v&V zvO?d}KhRaxB>#VEP#Ru^pb*h8v6GyfLiTSnCus;md=7?=M7blLq;6firsB6VWk*B> zqVqt3_{{SoV!+vFB|vB52|e?yGYKEvIzGoKF^|PUR9Je;B#nj;R3nBm8^VX>PBFG} zRGNHcaOWke{1qrOX3mTUFmNyb>tEt16xsm@KqDG9U{oi=MN_dA#`aswkN~AziNvGV zKGQgo*xXOvQJxgw?@uD4;of+YP|0IYJ0s@>ZnfoBITuK;mPQa#f_w^}C@3^SJ&La! zB~kEEND3zuq6}%r$f*;fUN4S@K7IDU(Xe;UQ*{q)J%~=nNW%)^m0_w>U=`j~Kbzfa z=PFu{4+&u$XQ${n91TOCj7u;3MeKo-#L-L(qg*0cf&wQbx^Sd~l~C zl8TGbg$EWKHp7TsvsKHOh5)?rmYd_(ciooX-g@nC;~+*}TH(E4PUk|QAY6W5se`Nn zH$9qC5PA)ce3_QWj+gE9(rd5A)xY{xjGQ_p4&Qp4IFC{LU5O^~V`*L<5idHcoR4Z4 zqXw9T>1@aj1$A)R%5v~-BtscpH=dy14SksI8!`HVgQhi(hNgN0Y$xE% zP8Js`X0N3UMP*rl4|H*@YX1hBC;A?L0qrARsKYmOhTS@04x>%uCw&rc&MMn}P03Ot z{&2~~aY#QL4J?GJqk&+6RC4mB5e>G1iQ9SRwRb89p7drXKm&X#9RL;EU;p`!I1NX` z4>7npqVT186;B$>z$)&Q11cc#t$g#IGAkEWqy6i{AI@j=x0H_m2Q#L|7@S_CQOrXh zemuGWLr?P9u}jD3vNqdi;W}uz2`iMQ-f?E>Y1TavD4N7w@?9g6Ay#BHjkR5g)O>0eY<3 zY~lcLK##v-l};Wk@qPPvZhQdt>5T@sAsBh?}2&Di>zD`)~h<{r1|6W@p<%I)IL(i{D}l zl{Fj6=!l||s495VF$NX3hN1MO@n`4K&eZcnG+c7dPeMvPkIu!>#~qh**2P{K@d8NO zk0ktsC4E{;wP(tta$4TiV0G%mz#&h?*}uLf`gQ6ahp?7S-#&eF>V!sI8oAJ-bf0<( znWJnL#tgfqZo;h0Gl@6(LBqv5y#L{}xP9P*F__NLX~&(Mp|9I8n&wu4i!q|z>aDRn zU!y}|lxHhPgOHl1`Yxw_Q8{Iq+r$~gW5?xRx8D|9Znjw*xc5Hkfa!pfMA>L~r*!XJ z?rc}!N}b0skp%sVdmWh?T#l-0Fj<%B7`U%9+BFQP=0iBDe|6a}qA!jH;kLeZban8g zexsggtV=_neRaK5IUmH0ZQiT}3qB(M#=h}JJo)$&amzh-M7QmBj7xudZtO@zgFI;) z34<*t&uWks8$=x?ui6o{vkJ}do;Y*#&-3Pt^nH$Q9fI@dmaBdrPb{NzarAL<>QTp} z6F)<$d0#3wnnBukbWO*A`6zRx_iAl}GIGqjyrUzm5&CJ`)G2YtJ@>>fZ~T|liho~q zb@V@A|J;^xA@rm@P$KQ%b#Sfxq*~bq)=3?a_n{+oUbX>rpb;(2zlIb44>(I79y2=j zZrUy`yZ(34r&n)~!c-CJmYpK<6kd}$+BPxy%uc|UI7hVul#O;`{JAiix_bzYhNCVx zH{ZYV*b@lvJvO>-zIl922SSI3?I$j6FB?G~)DE%D(|NDWAl`&O+k=sE%G8ed2z%^7 zY^AGj`d6I2&ktj7JAKFy8;djzp6+&+v z>*EwrhB?A3jmY=fd3N6AE#FtSHf1WS5e=>bbH#Pn#3#V>%QMc5V;Q;MXagJ#bh^w( z#E8HAQC`~F9P_${IO$c~84>a|PIH||jj8`T@4XxU{P&IV*MSe@Ld$=+?sw>qy`v@e zm=U1aA+-$hNf`{?*#VZG#hToNG+I z>(nXjJR=%PUcjZ|CQ}E3rX+UytWRu>*Q%uvn?1elbzbve!VJaw^NZM1jZeK%e}jy?L|z*vmka2XL=yKcK( z4g%Od(uWz@hq9g2hnA^*DUPyHsGHFYIvQMn-bkC~tPA26p(9^>A?~~5&Uo7aK{@V#iH?T*@4G+RZ@x*KeA0>0qEjan7Sl^C zm-l$Nl+T^-YeGiSYTr?^kz{6-W>LH#3I=$4{Dc@zNARN$r?VzN^VpVoJ>9#pkW+f9 z5WWaOy>Xy3N1&g7>7_X1(n}JmQwZ}u#jviewn`(>Mf+5O3c)W|(1<9sCK%C88Za*q z;-JK2I@e@KM&#N~la;i?HUrPuW6unW>kw4^Ht7}z9)5W2iAT|?6OLfY911EK{J%0` z3KodQB-5uLQE8))m+{?vMwutVEcXt2B;FeSOdNLf39%cDuA`wfqogWy!=bW62d)$( zDt-4g7iSW)aA$}uM3^O64ovC3)n!DAg_&5iYL}in#}9VjGw0fGz(}KvZYW~T0fv~x zk#(p6y9!?Nvz$WhWt{-)p`&3eog$~LJonr)aqjsS#BPkPx1)2>0%K2RG*5BlJZE7S z*JZtc;;gVuRA@4x(@4ZuD+HWEaQuYvF&qIq5D)r>ICxIOSW&TAcMVX#O{11?%vbn4 z{@3%WO{|$K{5OT3W`6oMNbc{CX)H#Kocrb!N0V1Adcok!% z1cXz^NIDsy5f!MNiYAOk8Flauj)q%qzn%3Z?jiSxzg=-9ifx~0gAu&~;hqL4c?eSx zBL%(bT;N`|0u?FF22R93$+nj!Mq{A=`q#gX*N9l@*KN}{|6&{sIC)%mL=U=i`|Kb& zI-1S~6psR3!K)AzOXh7@^Oqc(ti`$%7*IODX3hB|qf{=u=ISi-g5yqzqmLYbqhXWm zxVT1xs{@;NHPWDBu)}Qq7r<{XzxGND#t3`+1J?0)x2(~y6;{!v8#Rg!I2u|uWrg8} zjwsT0*?xA&b%M}Z;w6<@!ME6u9>jrVXhf{!J4bp9FLjUc6-e?=7P2_ddrRU~EH7LN zfxjWsbQatiaoQ3YAdYQ;JW@8r)~?Gv6`LcZj$|q1KfxGsG02yQ*0}TD zd*TG9PV{9I(7C}zR%yVep#^Nxhe}5ew+e#_rK3k@kI%%H>#XD&4OIMdM$#vLI0Z+; z>uKn|{M7I?h;{|WUR^uICTwrnnE4EizIJ=d%F&?nMYF2VzwHaeS!YVnF5_vMW91DD zKmKEYHAqLp#04M5+e?58ec5O|cAQ}4dBYx;LeF2J5gQ>RnLSPDF4IQv(!VwB{djRY zFi?bhIGZkHy1~(e{aM%(I2!)`+iPPs_pkdIQz{NQlzEx!Wb~39KQgVgwGbCv7wE-T zxwehPwftmhM{piO5na4Roe zCqVrytmc)`d*EM3gLsplthbJaH|X#VM}Is$^7**rXBWoq$S@aZb75VhI#P!KOLlCj zvwW)zHu9igs=!J~r9FYg&{ya7PMr95j9~umBe&cUYqE~bd8eNd+XK6>W+yl0I((um zfIo#v{P^55#FP3zBOZXkZ*n|?bvB#q$mt}~ zS?!dt#>j?r(1U|?MDUIscX1@F(y8TTvQJ$0*FUi4Nv~X6 z!w3d{(wF$R^Izf24yyE*HUse1ich=AXTp@x9;052bFR7~HsOV%Px)~i%ygv9x_3+1 z7a5U?tnyudRv;IH<9l_eW!m1>!E-yQT)>0HSw3Ut$Jk@f#P9F8El${NcWg1{eebY+ zE;i{pQsyTfbo2nI$jR?>jVR=acy|HFjA($rT=%CbcBNB3T%$op!@wsWPreuDWsQc8 z*feGBk90K988KS)X&i`8KQfRV&lbj;bLRyv@7TIclh}~Ku@0=!(56XoG}Ob9iBzn==ZH_¬r!ZUeeJZUaC|pSEzW*dj;pxrtQ-b-Dc$D zh!;3@#ejnk$u$}(CzLcGzHHgjz8<*&;PQjdr5S6c zb4?pNN0hmKi^Zw6$8LFi5LXd@zwCucjpA{q|Csd@UDXT~nz-iSB?42QC5l*hr z;QW{gL^do!fOYNKH9B_em>ryAEa9EwI|<&7)hI?#?-)Ed@z{aCXaC1VI3}1=PQ$2} zGx4rMo(SZqM~9;UR#470mmnb|1wpbQ#8NHl=Y3Zau+NNP-Gw0wUMPj>3~&M5+u-hV&-a^KzgQJ=Loh@OY+8=K%% zanVH?(Vv~e91(EcJ6>(?{FF`z@PNRJ&8=b%p-Jm96Ja+{Mx8oT<$Q4xl_kZ zEMC_-8ATzYfUUf(GNhUCd4ZJ^Va|-RLN3_INGEAF9>sUwoDla8dn%Q~k-PN5nXwC_ zyKOR}!SBph{P^=+rK*FYgsCEsC{GW!P6k(8x8OFcG_0p_(tGd4$cG2TusJicybF#y zo+%~Wi}67lC9J}mzXG8k3azPvx*XH&$d2k72;q4c&@ZAmZy)+pzPnS~4dd_=j$%$= zhcwiL^$QgQZCZr|+YTm;P_P1w3V`A$u`mUoA!&xIPDOa%{o6mrnA*;}$NzBu*pn!j zwJ~U1e*$7l_@uW=9 zeBf0BQHKCsh|IK%DnpOdK^&)}0sO5&2UFz?wPmQ@$QNFW2bq6r>f3$u*#FQ&a^!y5 z5~f)&0$`p-G$h@NfAVV3$Tb?8rlI-98*juzcik3KGKW=vcH*=fVG_)qh^AO&uvdD3 z?KY&NLDJ>iH3CEe_EjE5J=M-18%(g(7x$TpQJ*0s*CJpLKBkY2c&rX_Jg=o6Zrv^R z|IwkWMhsoS_ZiVZyQTu7Fh8k2tJ=e78PR}}FfzwBcMIKVQ>MnqhaQbrSWvO&nyq55 z0f*$&uI4zeDy3lih!;D`cK%Ho_c{!7Wo51%u{R`Dnz7&+<7cUMSVgf zC&yo}zrL>gv-=+&yRmSfo!zAvv}VMo2}f~K6=PJHuCWMXr1K)3$y}SSa>%2+^2)2P z#ovhvF!kU!fH3>b2n#k}4T%v<@#I^+knqX*}I>v$XT^w1cH3^pCv zYmeAvw_Zs%;;o{W0(ZWW?dY|RU};f&P=d@gRKCsI-wF*KjWR2$LbXi=I4jyeDG8D z-9Ne$+0c%Tl=QCiMSYYb)8yi=B90zQ|EW!RCXHH}j)ux1D?iO9O#N*-MUOo7L^`Jq z+j-a6wb!oMk+0e(9Us7(I*@krsF7Scs9;0<@m##*h!QZ_sc`^f@}$Y}(%`4#$&Wwa zIgu(y9)kma%anu8@#7o;PeCMACJaR{Kw;uWZqlF z8gcy3&I_l*WcvW8wn1^QF<%|HG)}Eg=Eqk~Rk4g5B!EBs&H)ai0Y74KyodjEL%j55 z**oVD9QgZYM8n$Y0ItN6!DqPZs^3U&tU0xD?lekN|fnF@ny7-QZXTE^`xaYZH`Q8uPcZ&Uv z8xWm4cfuxNOHw-Y%GP4TK+|L*51O}*933LIvym)1def$oj%XkGaQ1BMv0LtrSC)Mi z8&SdmL?CUsO%J9&tW&cyO2<*?a%~J?6F=r9UD=W50(h}K><(b*0GU#4mj;Z4QK7HfjDdaYubSuU6H2*i4oC2amdqp zk{5MV4(AWN$n7`^W%oj(XTa;kjY;IvggcTiz)9$45>a??bwa;E;wAC8uNPI zJ%!H8j@$3Z6b2mH)K~hgc-wkZ$uhx^pd~Ch1($cFADukz0;a4P%YuhD-*QvTtbKST zQ3u^O*(CF|6I4w(b&V7q4en4?IT~Cv)TtFll-btWtHNNJ+LNC${cQx!qlXxvF!kxy zJr3&MpPk*-NjkLsd|6y6fAa`UROb+2;#4{`Pq)2x>u%@sTkpwJr^dhj^!prCGXE3z z?iam~!7e7OZCbU7&q^W}{->h>x|6Pj-J^70?Mx@H*@qd2{y4VU ze2e5!?ONrC^qjx}eAa-YxGy*J)66^N3_ReoFTv9sA}OC8GAtgSXslqw5lp|^ndsyV z8Q}0;@tAs!Hb`9u0Vx}FIHoM%8+q1UozkX}_kcS)@bnR;F*<(J?YHG_QM&+H?_-XM zZkuh2!-(zDm0{#7{*|=_|G+QqMNtj!-sfiODD6r~U5Dd5oMLY?NO13nXMH11!5P+_ zyq$Wd9F^GRZ!4>lL|Z{VRR)&mCI&hv-@Z)cXvnB9XvPTB_uqXlo_yqim`vXLZnbUf zwa;GB7Uz+>HpyE_W8|%D71m5y3H}tI%h9@I<1pxkqrmT`PGNnCXNJe4?@i3lPV09- zY`g6?IR#utkhYe1NhdfkS_d6J+Qsg8VVP36ww}|HjQ}%(c1`MSM8nwE#>9;eKa_cE z&imKIA5~>I7;9f?C3N)3+)v}#TOWwN=bjix95o=icI%q3J99MH?8$&MmW)ve!j%x*l*!CP8#5*y4)5Vva^xiE%JVLmPbJlm5m6l! z63`-?35y_7lkIBaARw{&cnWJ;4GJOGe}ugoZsx<9YZ5W5I#k*~W! zsNf}JnNT=1gj8;vmOZ~jGf06<%z#qO{fg7 z0GuOiIo}@zp`oD=vn|`;xwq^zdMI1m3!^{tSD{o2!}roC;+ZNt!+WV~3N!#wI9h*= z7X?I1yr6BE*XbD4m(&TutYMUIdA|ZbF`WSO$D_#Pzark#H25e}`ZXHH4|6RBgjW+f zT?%7IU=>i-$>)wTroyC5X-Xlev994+g*C6F)2c!0%DA@q!bOYIAe3J!&uXp{q7VfZ z7p$q2nr-Sx2AStVH|DblV{#$FR6JKoc^$Sg*l_JN*l}WwXu-Mwjp<;2MaN$lZ7n-N z;@WDbQ-}MdBUCz8hI;$64ehYhqmDX99PRlM!Tj0cTcvivnI_5 zk!%i5kQKlxj&lT)awL^hzTia~lfG>a+c6VmX>1jRE-u+G9e!F2{++gEh@Md-2|q`n zPsdss=|w(?8$HsF*2xF*hJ3G5GGFtzTeh6lgqN{i#y87QG>ewRqG?m2!`vmYTl?0r z>ALK54`I8#<(k0h)CuvbtHD~x@s?eF&?|7eC}a{(LRX%-7^G`k%puHf+}x=#fp%=z zimgvK?i{T)T0a^fe-^_NEMJ2&1H%f>Lj%@oSb~K+{nL3d^D}l@p_CQOU(pEByT9%_ z>t?z0KULxs4)hF zt6?kS?L2D`%g1&;<*7^+Z3v$?vJ&~ET(5RZSXKhBTYW7BcH25f_ZStIKZ~OpTB!0M zZ}Uug0%kk&<{__1lb%~oJG|oAx+!Dk;y880#GN1|;7Uqi^03!Fihf+By3=hRQYy%Zg#K3$vqQ$Gn4?`rrIUKPc_ zyViq@zBzgOP3vrFHPr0=QeiPu9_Im8qgy8IU-j9^TUs6mDrk zSuOwCmO8I}SD0_bBy2IvZ&h>y__;1NFc7aZx5{(7lmZKtaEX$p@YbC!NSFf zcVTD_+-ozUUO6*`(`XA}cl1mm)RCEOz&-O)?o_hUqvD{lDb#sRjj^3lzDpn0o9ilB z2XSeAyzje7hvco3)cPpP?2t;2w!3ZNH%3#+Q|g8$*i@|;+1{@TL6lVznd|@=f{M4hu)DEgTKV3mS0_yDNS4>1W7k zMo4+)bT}6lZql^uisBj}MtQB>lqdpZ*&5i%!Vhp+_Z+#Wywq!!!MV6kyG~ryXh3;l zUDaDUg_736jrdpg7@^a+u`;n%3l6rQbfUv6DM>s-KNey~-TWM#R+cHF(q65#sd`mg zSopN9T&qQ#3!C3(DYc{LwNmS3XSptP?sn;)Lmx&A+Ha88b($JoYi4bT_A&}lcw9_a z+~nXFuuCh2UU)U%E`0!X0mUcYQg=gR#c@>@Ky@tz>#rTwRNNq={2)8&)`3*zUFC1x zs$ccY_v9gEoxJUR?G1H^b#%u)?SAD_m5=YsPwFn)D*1rA$~R)Ff?Yb#2uK{yzTsP8+PV&_F_gbYdGpHyH%T+;0z&`W4^!P&%5>ioerK9W| zY(siv7!BuSD&9*?M+3;$5i4(`0R~|z5H(C>VDrs<1df!@n&yzR1d?j3#nZ@(h zqc`*Dxfccaa^#M9HqYc2=*FXMsj;U36y6koer_FTbIWLs!6c7l=Kupe>jpe9NQSvN zih*^osv`zpq*6(MG?sanHn1b%$f#v_Eq&U?@``XKldX(>XHYw|U$YmKj&Bg`5D z%^Q3j%@MYZ_%89nD5!Y19!ZyEl(a#P!eB*|7l{twRJY~GG)Kc;K|VZ1#{&=2=gVm? z=CZnVWIaRw>0P?umz~j-bgtd4f!fsCnykrRT2&6zs>(O397f*snT7=)<#+O&G@vqB zmNZa0Tgna%-&Ba;M?+kE_?`DO?5tFulyFC{Pypxd1I&@#3|ayMVPnz~|bG7+9K0($2pQ!A7i+ z(F{Y^(9$osb{6__V0Dp8N0%E=b`x-@S?c^lz@+WCNce>Q+kEgXzMy(`9C8Gd53Oz0 z7D?~$gmjY~oqR?ayeC~|TR@8%Kenr*3Cbf4tPFWXPuLDFR4ae@oiypfe}BJhr1wQImNk z-E*$)(2%lRqoveO;??F;hB^Y3yvuo+Dnz}2t#rb_$i;VE?AJvQHLiG+#++V2L^2S?2yxjMei7fjiUjW)Sc=R%hz}n7AvCjLgUtUPP>5jr3Kql13YO9 zyek{6gj-!^rx~31EFBiBl`GB#T6lfmdWj3`Z`mFsQom~(y8e=pT|`@whjZDjmmM*ajt2QvCyn)# z{&XfwkM-1bl-+{1Y0iBopy})b5WXZ=>LTrczC8NZ^XiJ~CX8~J=cvcxOrXBsfS1qF zXNy=fM+#K$>2NnnHg~Ha7x80$D{xwWvD`WEv!yKv`pTVQlLlkcRghp%j7^OH~IEz1>O z(xBf7W6~D1k}X5qieTXqKJ!wJ`762|XGXTMF!D43@{^iP#rK?MvOHzE?|ZY@J2l%A z9C)px%jjnFcYw)tLZnyU7mwEOb2_WZuUz|{4hrjInaUgKQkjzjRlH+;yf6Kme@g}+ zeP(-#4|zSy5K4>UAS}v(Y!A+bS>E!P?|6@&cvt3lp0W%)DpSR46&;w*$Wy#aAC{?Y zsr=FL=Xb(f$s}n`AnX@q-wYa(|JTH6tz1*)y555e;7dbpuUz2Enh0KjQ?Na^WX>~F z?pTHDiL~e=>7}yughyLP+-Gz-A1J>HT>&reE1!)(w0|Q0&9WL~b3o60wR!CS=`3(+ zi{D$g-`U4gw?bX$>M~GLMa0(OJaNklw zguRUJ*BbGPwaak0J1{^}VX7DHsKVkg@jY8)JDgbRO+t}Sh^y2C1*0`$#TvnnW zHx-fXkjc7nl0PcxD~_;YR-^*T4kq`r{;6Oz>|L0qc#36yjm0!7dC9i0+-g-?J6bLj zWYRDZ7pff%IlaaSH+a#&wo|HspCen~%MPIcDa?h-pMZYrSi6@GYR{^UmBLsfQDY|^ zJ+!xQYHZpT{ya~bp$x;|oLej{Wd{pE?Htv5j&`Wvp+_>JLkW+NkL{L58F&Zz7*9Y! zKD26vzq{6hN?)8vW8z7w&|9n5HXRK(7#h;n=B1;d;a3>0E0<$TlW&r55j;; zMq!n6x5ad!O;_MtmXSpbSiGyXh>I1BDlT1GXj?}^^R-%JB*}7UV>$R+PF+?IDI-to zXmH%s$Oh?1$ZCKBy*1z;Cw1p__ev`yj*`~%%fzQNn6e1^QFc}xbu+U5%4cOv8dSib zoNUTkBzDZyJ<1}Tfbx`vjQrtuDtp%^P+mFeWz>dkrXeSQ1-Dk9q+6{{SUoxezAW0L8g-ZvF_vR{ zNtfztWu$UVe8?}-w4E{W@3+?9d*Z}4YheTf zTFL}x%3|(kN2ONh9QXll2Y$?-Pm@k8!@PC!J3n4W10QD{lb(2{lvKu79W8k#Wijxm zS6v@OXO@yjXO7MyZ`ipw!GdQjcsf_>DrX z8i@wvKj<&X4C^kuReK;Yc&>i*Q|g;~4qIXwKf1%@kN)Mp4hOgDG=fn2Rg^eI^NXcK zt&jyxl5J!ANXxeUDt!Dmjt1&#JNlmVD(=OR->gmKs`RQeR=h|b-WQ(|ue6vBQg~dQ zy4k>&f zeA2dZOWLmJOvjrxkua-2gj4#KHg)3popmj67y3;CupItp-GDKpcA*35Li;q*%O9tHY1R>{tHSpD6mR=w|hwkxV|T9PH{B9T{#t ztKK&9*2n|%Pr9qsp++X$CHc@l9;@dZeMcIxD#D%e54w?F9jtPf5A*bSaYSi%=w#E` zgA)S2bk{wd4VB)~$)LWiWN|(1VsM=fO8FOD_}yY`RCkQVs&uIx+6)U=B{ zo?FpNpZ1&VU**tK;T5Egk|C>REx)hnJ8?AVr7c8I&>&K!Pg@$^%RWawVU>6p*TyvT zDuu2u)RLo2Y2?G?P;X3ukr)`8EZ(&nQS{Pa$nRz4kro-+(Y^=X7fw>e_)8_h(fSE*8psG41-f;Up;OS3mx4`!>UV}J*>+xA z{{}9E#J}Z?B4`vOE!cL#P)l`nsol$K^Yyv+IPs9e&vVKt55 z5Y`i;pBWyHoqA@jtp0V@dBVW6SNgh^_kU869`oIbz)onQwjv9;H@uO*m7IOE!6wYgbxBb;#Hkro zvPql?OMZ{>`VD4oscZU zq!p=*5_s+cpv5lYBhD$H95Yw0&Ae9U3J&ggvmEN4^S!W{2f8$!>g2T&`p#%R@FZNO z6}*D!2#ox=HVf@wb&9Vf&GBvW6=f$*Yj~Cxbv}vff(LM6-uaz!rpSKjT)I@JFGrWl zGZp_7I|n%r?h22QM}ltNU}m+lrBP|p0F%R&~#^s{6t!&YQ4Rs1kg|3Z3Ib*Kp4=E1X$omdjg7 z!{qNf6(42ahqAmU07(nf)4?X?Pt(lbwW1i6M+PZl)VY-t#JW^ED(k?txXMns=cH@_ zUd#a-zva2*sJHDn%Nyyehn~Gx@&kv^Me;RySRd^Q;nc>?f#IwxZ2;WjzUXx1s`XQ! zXPt_iRwi2KDw?Lkqwr@#ow7#rXVkEF%$)C2k5FDlHBvXfa~w!V zS{1cZu&p7c%J8fz^?xcuZ=S*IHiK(T%${d{C3VI_x}~TDi@E` zV--3$Edp!R8(t&qfWdrH(ADr^Su(o!ivd|ma<0F^TN<_AJmrV6S5q_)2<>MWllNEE z+>$Z}C7Ne>QS!_eSNr1|mTxM5t9+{W3nmn9rPEa@c@<-M=Np8z0@FGr&(!$C_pPs? z?isnj7vdXghbrNl{I?2rbF1Z;M>~s|D&>rTSE;1&pfDs4^Aj)SJO6SAgV}F&P?%#b z9>;6aWikFJv%H$w=egJN9pBkb@~cY5qb1ZZnw{t`h-mlq6heq|D}auhSE5Y1a%lh$G4=4mEPsU?izb5lrP>Z_y4Q zf_t0`m)0WDJ1-A=CLTET^ytFv?mc=$3(6-ZC~QqAaRFZm}w_rW(n- zJr86|V{~-vyE9_ZZrj8*JN6)=VfX0F_NevO>p)Hz30XUNO=F|TBOQKUp==j1lI8RV z7t*3f0sNE$*nlS#{HJc*vU~Owb+R3-TH@VTvPB9mDxBx-+Mn{oR`AVov?c}9o~?SL zy6>?riFev4^9Hx6(5b&|CRIwONgoMO$+gO{%41cl76?|AUA^(YdrZnLFxCAnwa*fy z?bJsF602BfSjoc#%X>M3}y3Q4VUktTBL8M?P}YRRV>ldDoy zs%0T7$x~8GW4BgU->sl4xGJ*Q`<7kk(yIzy&r34*73@x+16!HyNS-uMI)FUop1Q`- zL8Z^?DfN*Z9Bw9_Wjf0P8s&Ux>(ZuvCyf3RM*sPahP^zZ-BI8ZqEc6%8v!CLCgI2s z=X~y+^4`jtBTbu07L*Q(9<)r~@;zvRwzrPLDz&Xj1$(|HU1``We=^FX&bBCTn};K{ z=A%=;VSPHTBx;;(DZY&SG`R?`9f4xp!xhxA0iB1U(^oG)Ur$)eS%JGc7kcSgTB&eh zl~DId_r)%(>RNrp5m-v5Vqx{fhn1|#+m=8|WR+)j_Hrv)+QwIXq`0k;*Zvqnf+oQ^ z&8IbK&8wEoFMvT@`ID~7sC8BM)t*tAs+~%^k`c*zSKpR9)my?0Kftd(Pv>Y|n+lna z3m@3&O8uA5OIufER9EG?T$!_}Dyf|Nx0bJ`Rq|GTP`>hVC4&n_GTZrVyoL@Eb({K( zHmifN%3!slc&gF5xJsFu?Ib_d^vD0h-kAnla#VLddvB>*3tCvTqLs~~jc#oq4E7j% zaM%%c1O%Ee7>vz~KX@7YgV%_$O@zNV!b^+^2LXgXIP4h%9vt3eThK-r2_cvOK>!j$ z3k{N5o28c2>Q=9Fekb!^_uPD0cX{u=ZZ%YP*Uik6=lsvfQ&m}&=Vevd*nke%E%niR zxs8_Chisn{$NCZJwB~acpK@NJp7+vlp5jBl-?n`G`~kzpV;c*&-++$*dvT0o+K;8I z%lE0*vR^pgNFKN||Iki?d(^KiyL2Cn==7K?k*>9Qys~=n9q$RtNnR^e&$7Rym3t$u z10)ZA`Is@fX5|2=`NYPgjW!14V?`K9#j4q%$C@AYyb9I(1>G+mEjf=H;#NCCk<|$?L$^bA;=#DO^F|u zoJVWShumlLxl3>fhTv!9MI|fs9AtU=#_>WA@(BfYYY#vlrSbkyD@RW! zYkQ;IjM@d7W6u6{37?YiyCu<|49NTZCL zt1G{mFH*h#?q7UtHkp85%sD2o-OmlMkfl!9c(L71KB{b-K|W!yn!hm8Z&R{V=FmVG zZMCxPtHaz7nl2AC*oDo{J#-jm_S@*FLt6XK4xOwxo6@-$vq|o9Yx8boQnuCFVe$TI z46(Y8D>NYE?Oya@fRQGtrh`JE+2M=PF|u z0TgcPd`z9VV@Os{_3 z>(lx6o`%h5pKGo5*Jr;?&Bun{EU<5Ve6+tZ*mB}EW;0*xu>;K%+s5)0z_Es#2nKa4 z^66AAid2mnQp@)=8)Hf3=<%A5Fm@d0yquTX2Jg8pbIvSlQ3l z{FhP29L`l%d*u{u%E&&(nY`=bd|Fn@xNb_ZL;J{&D6<=F&_?~CWD>c<-kO;*M?S8M z-vd_p#e{zTF=kr7L6Sa=os3nw!Q%!6|7MN+7F?H79S;8GBx<%4>#&{^SUA`#UiLX* z4sOQnpZO3C9!&IlX5^P^g|78nhrQ*oPhyH;kN9#$M^p=RJJBO2TiHGp=6)a_>xHv}(iuNWe*8*9JF> zxn~kQF{o|b}RD5aH;Q!9A`Hv>t8{`Bg`;hxCJ3`zZ zT7-)=RI}Yw7(e;vWC+%Vt=ZmkU&bI)csvMT?VJnV2b*ki9B>cl!413j;2MOyA6w;K z#1)huYw9eD#{|}8-TBxTm*2}8D(y@l*bljHvKwIUS<#?A<@Q4KOkCt#(|mGkePIlR zmiI{Rt?JO&;9MKfWF*CdZjNt)EL_J3*5pYPTqbP{ z<$Q%u_JtSG&GBGR{zn4*gg&dYC$Nco4|48>wXa>as%09SeF=L>wjazYj$if-V;{jO zR;ZwZ31rt##t5^|gD-ww8NS(^zeZ#CrW{8$*7AoER$zEQ&c-UqvkH{JBmUS>0$x~v z4NKF=zT5^6v`A-vNRsksgOC1j?&ae@^Nq$T!!h6DZ#w{uUD)OiA6snSx$Svu=3FI^ zh(7v1y0#+M8PQpn?Htja1=fzkZ1sQHF3NuHSv6zBY`XE8-8XW)@pTYSJ_hMHw4;~% z3l!M?0fX_;`^ou>59}XfJm-h@v76#xDg|3R8?(Am|FVCf>RNNy1KnAlkDFzT$N}m6 zK0hDRIF8K*>~ddoEV(nS?luyzu}607-p#Mk77)O0TifV;@>MfB3(V9t9Iw`%gP?}N z{UKf87(@s9Tor%NGh6}TQyX{crij+7H>pljl{rvElhF`B)J7 zxU+p@BSc=#miLV-(EV(bG1JJH=WkPVp9}#k~|L#Y>9^r?|U>5GYpM zU5W*YyF+kycbA~S9lrdYc|U)i_n&0uo=j%Xo@=jrch8>PJ{LA~=%yeAzF)6RTi0om z<&C{Ks-DNdQ^Cv^vB8LT{D~JGl(d-!!<-)AQT=wH~$r2GeTWA;AMS72~1D~5DgBqmtM@H{RJT;A*zOm&s7#}&3>TW)bKU^?F zg^%|Sd>_YyT=g4WIE%x^bQu?)xiO619_Lpm&)CPV>5L>lvUk0V$G9ToB{t$bFHXp3 zlw_#+S$Yl&vqae3?Ugwj;|x&+X&mG5jVy2brhYmD$Att^i;5fR`5yb+of0K@2=S9Z zC6!P085-`&#_I;KNj2z*V9F?|$z|N`HmfErr+n>7QusVTAaAH_AyMCX<#2L{t6D`M z!be(G$>1)@u*S3$BFJY#FqZ^N^3KAv^?+ z&q%3qHF`XP`+aS(4-GxZW={hG{j;-4Ed~*?6*!qus0G1k^zOMv4+fdgJ`G#wTiQOt za2i!r1Erueo!dsv3j3SItzV4#A;VkW`qwczQe;3hY{TY_GrgjC1!L(G%Zm;r;lzCr zQ3_wVr?+cDHl zf)tJf%6QsPIFAr_{UNuZTi`>i(6(mr3-3%($uW;3lRq>_-ORCf@fUAae7np|@H@Ob z?hZZMXr|t2-BzO2)joV&*I*)q^@T5nwGB%gL=82)zgEBBujwTqvG55TYa|<(Bj-W+ zZu5t+kh$*E_Q!m?#bi|T*RUlUy;8N$sM-P?Y zBOHAWeQU?lYNabX?I{=}Hm(|}nQ~OO@lnszON?BjZC7fvFPhfz&y+DM02+HTafn_W9a9oeo=bz7?5(luQUd9}) zGsc7Bm()jbw>EkjZ^PtveS9~o?%L4s>eq05ThGphd<^&KPo1}De)kP(0RxK#Pq2O8 zZS^{z%wvy)y(#*H8#lA{*xKXgM za?PDp(ik{zE`fVOcLdfw%MnfX`MI>+`>GgPBd8MzVnzQBjE)HC;7va6d?2t`zU1C; zmg>5o9v*;+OvYE=JW6);FOMR3ARm$V96Q|JPv-G!s=j?h`PD#G0_fyd7;iBAs}g{D z-CzsGZ2mT5#@ZZ_;@kZ=MAwhzP8~pJtCqorD^be7(N*9!Q4yCRZvgF;El*Qv1@*tC zajGA&*!~cJo5{EIiXV&86nI_uWbLBN`jCYAA=#VwZEMjddYX51ONQ(BW^-TCb0n{q z3`foe>2|pMoV<`6d}ge7I_53Z>7xFicYX9#l;np_-_bPPDI@OJW^F%wAajP4+R&#< zJKT2jZGMio5s2Y9ulbwgCP52B`|^DNe@IhROTA!QYEnp+opWNsuk!T-Z_l*$yEK!| zASD&tX07x-0_oiGm8<=US;wD&6pZ{y{G%)&((&Hc`gt(qPtvG8j>$z+2X5MYob!qBK0$$)UbJ!*Uuv*(& zeKejj&MH{P-+jjXdLLdbzr5p>hv6Tg;Fjr?8>KWW7m15bA$WZxQGa$x#8a#jNXzu0 zrzrZf8dat=X14&VMz5twU;W}hM4($euCGGBo73#CJ~lG<_LwlAQ7Yg0U^Qi>=so#M zWUBhEKl)>Crf=EyP~T~0bleJ+f4!VBE5XBXxtcgw&K9B+_;ot2`<^Z>)x?JhocQ8T@lloL0=zgu!y@j9SJsT&FY*HQzxln-CU zNmC=N#-93tr6Md_(t{f-bL4eKYu1q zmJ7b0;@1gZqmI=DlP~*JknzV`e2*My|1lsr7==qj(}YAYeTwmvx@fdVS%1!}NWy=yt<|7rc90YOz9jKK@L_g8%{&0Kz*F_t*pMi7^ z?pQjOOHR#lcwFaNti&fzcyBT6BGe4oY~c~#&G9{Hz!C9|xf-GCA5u-YsRjEBC5EqG zFGL-(yIxiRlk(nRQoz$5`p$tq-$v;3zD)AlkE+p(S{t~Tvk<9qNSuZtfwAcw(3m~c zn^}-|7bl;LU9`SJZ_5nL{}k%sZHIj&s_%7X_+rB?Y#A;;%#;-F@p(o5AEmeGElMNm zYb8}c7aqFlUP4@(_^rH$RoZW!BBk@e=74NMVQrio*KYAJIdR$Ug=5GRIJpAn3+;BY z;s(HO7J@1|hZ^uEXH?6rwU-1H7w2AK@(bsk7tO}<_-Hz1HWcMu+E^Q&H1jdJKmaeO$=xk(4MKV$=E zL;G?(tS^WtxwSd!=2ra`9n25OArBsnpc~LUOZ?GDuP&n5GlyUE1>4$J&6b_^JnK4p zl{vkKpi7{pjY`^R%?&4f<1Ibf7iR8P3@}tP{ueZC0o{Yp2~i%Jy@>YQiGSTJY9ecM z&tU9FOL3l@vr z`!JS+2~|!)`%-u~`3fL9-Yq9IS;R&jRjutEmLG&?tmIoe7N-!r)DdM{#iTzZyeYcg z%T}U1{N_#5;C^1Z-2G?Q4Lwq<#xmm^v-Pu7!v4M?ZLcq59awS9``+{XG}dWM5o}cQ zNGo&vn>sqNDGIv0W~N8lgP7?vj3&C=(hpPo%;iC`D%QbD zw;WWpKPv#WOu4d)1p{I36l;uPtd5>0#94E9M1S*H;l-ZA>)&R1M0(ZURn`9ZqkbM^ zU_028dr!RD3FR{{QTmfW=~vODhrUQy*JKjUE8N^P$mA}J*JrQuHCt+BOse#e>f_MV zYf}-MA-UJ@ek-qocUW$t+A|4>=mj-cjwyC3sVUAmWo6tuV?6oXRJ;4KclHZ;pqBZh zZh0erraJW*OY0aG1?8h|t?m*P!{p8f&10-LzBGo&Xg|hq`qsWD%V_DLUE1Rq%gLQ3 zKjiS7h*zn4Z|o|CAp&bkk?8a^rVv@{;m+}aVD{i}Z#&uLg!}Q&LpkaAifhC33(9yR z)nr->uk+_M6pc%&SpsdV>^jtQ2l6IuqWI>|)%33|#22iy5S>cXo`s%HU#^}nXR{s$ zTqe-T@bgBgc%R7M0JkV%HB-vV6e+`^<_$s#mUef-mmikqAo^f(%4yrm@}Nu|%%)#6Q?Uu9Ku_Ab{h^Md zsamRg#-}Prp$3kW#4>FcIBga3Z>Bvthua18w>$n6*{_9^J!K#I4arK=&*uz< zjps%hE}i+%717G&64b6iVDYv?D=%?y1~=O|rz@qnxY5P3CUN{=H=~&y9XISc?0Y3L z5H{v-d}d}yqPrBB$$wV)v%b^Wu2Ri#LM4+!714Zyv? zcBu}cuJ7XIHIIU?a$3DtDPSjG?z6LF`S5cte@g$?*f(Nn!|FaxQOELc*?-X}9g4*E zjp~R^4W|}g<33w~gq=?W+mD3TfUhhh4hj#7V{!xHNBVbW9uwMh`kby*I@9_|p(9;P_dn%=8zzm^6>0g=+&V1*a`-suTs#1`YZGG3;8 z*(>B1C+PYol}3Qb`*W;74WV-~VSUz422!8q*{P>)3u?JA z&4sR&tGBdjxaw)EZ*3^9+26+bRAD_@z6IW!*R}@IT5_bPYRu{Kn<ASQuA z)PLV3lP5RW(V;!UyT#Evpp_Ae?Plpipq#r{y4^hl^o`bM?KJePn!zh(>2gGzpa_$WG4Rly) zas2|Ml|N5q`Ed+Z5cOi#1ou}cwY2uKn9Hr}-2Clw0OOKhs&5wufR6ED%hmM_5l8fh z)^DMG6OHy_rf;rk+?FhCDIb3S{Dt$0@Yi~|qtJSEz$>#G^1T|g6Q`*!Yh>fvXXYI` zWf@c3yE9_eS>uQEQihX4bRwwDaRm!=wG3Jx_<|~;G{k35N1-LHV|C(QOslR&*Z`!z zQhCa(ubFGn>zI0w*49Wn0wfu^i1q+sxyZu>x(Y7OWrTHdrWlS__RCMZA-&d{a;QSa?_2MGqwVLzpOWM#@t?UCFJ+Ik64{f(L-lNXSIrs6ELB~>+U$}FwGrqPNL6kI z{J%VwC6~;-kDEzkM?ekEKZkBDuk1AtJ<2uwH4kk!=0q>1AK<@g$=k%kJ&&|FR<$2^ z!k%SrstN2h(ijZbr;`4bRnwMS7Xx+PZ$%-7fcJp2=+)gyRyV4#qj`+8%br zw6C_Y%U=R#oUU4Hx?BVBSSdy zHw%g)ZgFv}Y%++7t=Yk5{RMbkFF)<9aE`oI((P+jDU7f{53l z=6z`tg-$f;bCv=NqO|+EmjTMW5VOZP@_~0;Mm(G-iL_rBdR>OH;F$x3AJUyCi}j!W zxtw_J6_j45h|xHB9GwMEqTZ~fwRw&SOw}I`y`ki{Q8sVAY;oy8CtLa!bTL%~NzYWS zDtFaM@4Wtb@^Pz-gW1{r{EhJbrBFL;d9~D}UuQy6SAQb93(r$V`kIQ@aZKCQ>a(o; zbJVBBFJx=%p52m}Uc=@cTJKeAbni9)y!X6P5$@k&7T?*_1PV2}$Y^iGTIV9%bySYo z4F;K2(kP3~q3>H-9LpgbDHPH!XLSzr9EsN2Mqj)Dc30@bi2z^|eSt@OUmZnt*<1@p zID+*%LK-Tm&SG*ocCE@`MAG-&BxXNOhM0=4n_dBG3e^#y7_yQ}JR4v8(WPYF$M|Ch zF%-6s(gG0E+c2Rz1Kv$FPZRUeleM@dO=3euHp)t4 zAGUxDItNfQfHi2jWu6Le21e+gLq_j*d-q(;0J4A8(DkZ%^o%p zhlD7n*K|$G($uqpY6iJ}2S`2(>HujjTPno3$9NXp5re|BE#JSd7tehUsSQVe`-AM; z1TU!}>(oyOjGfch^}1vvcq!yqK>xSUqrGA)>VwtMJ3GNvxt5D{zo!Un-7k4yUip=? zQ`LgYY;;1mlVwXbs$08!r6t=E(Sg+t2LwLyKPpSi$avUqee}*$Q4zf}_1dnKn~H08 zUrKJ`%y8Q!hxvzbDne}aPEXyoW#WEoX9BN_T-F3mm7+w?wS+rpvIH-}lM1T!-IRrQ zwjcX{i`DLeF~U4O=*KHSAWr*=F|$O$kiV9IudB2bdrIw|K-3?uY`f%V-iP%KmxXR# zH3ow`TG#5I{GX~qUO%u5H;l>X{x0+6&H<>E)v?T)X!CNUe+@Gmhz^+P3==I@OB5T- zjaMmU>x*52cV8|RC>`+h9qrBV_;$R$Kf3?%s;&0-V4VDjKVu0JKp>+7H#`e9RO$fNB?rmkt4%eB$?K93w* z+6r$3I<=McxK7<$Q`S#k&kAs1i^>cfhg2!Qb7{)VJWM7MhdB#Aj63|6V|{gW!xM#c zF!9Q=zbKlDhd~8vdm{t`Py|Kk`0&$$kMh12)I2 zGue@E$8Js7r{C>%X9ht#H}q&+$s@(viz9q8U;l^-9T+j`CjS8RsNFBQ<9X|b%KBw;3SLdlL=kk5*p15*aRt%cj$yG8fIrRsXN;?$)+0WiEuMKs; zj*iCtZwB#$DGw$#>VI=pM3C}u#faRd^Hj`|%F-yJ4sGJ|38*}8;AzE9h-Dh%=OuP{ zCFKlkspwvFe$XCCS0j| zn2Z=G|JnRa7E3ik&g@hmOp+Vp*OKg%)!1VwJmmUU)1u27#EmT!E7|N%BnmgNop?o= zdnQ3?l%L#dz2H)dTJAQ;IOELm@=xhl?Ujzr81Ym4y4-VOn~w1LoGs9GPT zBRlu>Nuy+f3a_D>Eia;!+o{5q^k*d(U;ASG-0^h4L7BFlYFSVdr&q>YawW~sx@Fq$ z2?!bcV!T{tthhrS?c&6hNgo}`yI8i85+yZKv|*L zd<7xV5vSMwp|9W0l%(%!6)5A-H?A5J8>pn=UOy%KGZ};H@=6IHxFrZBnG<`Ss+bG;v>BUkiW(zs->owQ-8)RY5!l`93s^O zq0(WiHP!VQ|J8$19jH50T-Gv6#PdVr6<1MNKz@YVARobH@^o2xomONEAO988uyXkK zK6B4^;Gh=c4m+9Sf_Np@M9erWQ7S=i?Tf1ZD^eFj>tm?)Q*lP2UbB&g z=h;~54J<_tK}?7Gj2aQG`(DLd7xNNPVsh$p>~6J3Qg(dz5@BV^_O#ANKa5C=&-=gM z^vD>plYIZ99T~dsabN=mC~>B-r4%f9$x;}NrwTmBmVL4!V=|2T$^Zn{#Tu8omtt+( z@P|s678AarS++O$J)b-&>&*(beb>yh*f$~yi9i#@3WDM`u&8oi;~@>UrHmx9 z&8rGF|4L$$sNmw2*QDLexm21Wxl(|f&(CURqJw_5V37_12gzj0@kj&EaFA9EV){v8@edD=Q_W-%`F$mGqi4ZU_s zm|*@GFSq!X0e|W{GEtjT=*(3i3Bbe^yNAjTThZjUS3rYHkfb}epiGnt#G>^^rw&@h z`uJ@nwoM`GJXK=$!6riV!uBpc4O zljw)X^NWv7QyqY*smsE+tD%oaq@2NkQd$vFArmJVMzrXdPD*S+7Y(hOwNrI=c-I_z z!v%kfjx9_H#>!OpT}>pkuSq*bOlfTF+A%r)Jqoef$NKqqvC#_PpBwaMw^k^F#=cOO za!?p7tIMbqh$H#;?Yl_X#DxNdfW}GIKpE|AQKDyquE4U2l zImPR?foP+?iJoR<>e*-24G-M+ouho`iA?~A3RkYuWYFy|GU;^`M846}5TOFE(TE%x zbI$I9e%387DE4fiUWb13KJl*zkLvhBF>lD7@sPQMs=Da289I=;#0@sq90)I-*OEm3 zJX=R)+An02HyO{iL3U5C{)uao^Seq`WTDEAayjk@-2yh&UzRN7e@EFget$$s^qHhx zHM}WvmLn}%JMR@-$4gIcZv2g*Jw!V^6`45zvqIH|O`qB- zt0;^glHcd*f)DuHo?HEv4>g>P^(Hyqny5&v?e||&q&$-X3 z?u3$`hEI5ov$_SdeciDJh28dRB->6^1YFA)+amvbEUPN4? zLo`d~3V%E`Jad5zzSZayUh2n}`n|83MtBI6ag8P;Pb!)}un8SXd5?7xJ+Q->DM_Bp z@cfbH9cHt;C;vW;J^ZPtJru}ut@}og>1N3-?jc|DgYGl<=Jp8fdR~DtnXdF*gArHq z<+g85Ohn1{^l`gDF^6;b(;x5fuS~d{@5Yq&e^y9RzvYuxv2~fNFH?2CoU;}i@^di3 zH;=U_Em+HT8~Sl1k7wJzP`G|gE>YlI5?iV3gov1#_)G!rLa1offlJ$`>imJ?*zK-e zOPlr+%tfWg<%gWQk`EOzFzdr9v8ZsPxnGSr)3R!PqD)qb)} zUWS-3wUzTEnOHaWbsKl17qy5uPUma8xOB=CPBVQFQ!bdKaPDDmB~mvV>M77W+O7~P zrZ`+CPdAx9!*ZZXAS1QtH;Af8vw2~omfnnUSp(kWd!M!nWPqOUU^!u&C(r(J(cl|? zn~JoZ2+`u@r0v_b>s0;g(73&X(#rdTNuD74gvuuDuyO+P#>;}tneY6;F%!QRdxZ>{ ztN2~nrM0`ys5P;M{B&BWSGKSfkB^RUQnXQxW%T{?u=7=}@hcz?DR{{VR8zh!Iy&j; z0r>m<(?=ceh)@XX7_N&Zc%iiW~0aAzxA*lW}@3zVL^Z;>yi%BK7esvGQ0DpdE>2z zJ`e9;W5mcO!lq0?s#<-CDXeWPNNy3NoC_dPN;ouXk6~;wx1J!L_ve*X&*>iTr}tG( zMwaNeXj*?mL^U}h)V?-s?+g^hSjITc4E@T$JHnH)tgI*yY9wKuRpWZJa#GE8^$q?R z5l9x>t2`*j@K@(ogRRW_9m7P;-h)7UZ2XGPukDOnWt4LP5qy$>)8Cr)bhU#M%p|$H zh^U!?YbS(kiGF3!C#4TVdkFc6@;!qjyQbl4yd|AXw~gKQm|#;IyKSgfiD+s2n};*? z+DKR6Ax_;39Lv>{IS~c`1j|~DZ{6*PcGe6|h@S#pa5wrMe-}5s{*a-vt+2!0=ftwi z`nt_-IbWG~ZRn{$ZhG?jg6VWW(o_wj%~^uiZ%1Oc(1z{XXor4RQF^_{fCf4ghMPSXxx#^_oaFTCM&pOLcq@!$$ z|3^|pA8S*4f8&>{sYQ`D3Ys&KA-o(qEEU84+(hmGDI->z1XSt!LFCq98V+T=wf=&h zzsgcNL7fc*4EMa*k;ho7@{(Gg7XyLG z!Q{~&w;iQNaGU>4JBWkAu#SHW8y7-Gg!6<`%bq{wRMrW#K1HZbV9Wgzanm8UVp>247%Xq$#x z&ZRBeFIZN)jD3C1^=k}FGQu`@V8E2R=ih+h-=C={mL*!#v=5S9$v=N=ies6bDLH*v zfi-dB?L_int0G!4r8&kOS*Oh84Ad}bb;^bGCOU*MLw^ohC-9c%mz}5sqImi24AL%$ zO#4l$-8vc1u=qYG7{~AN2r%?IU5YK2_zX4vWWKV@J8CZcA>5L;CaZPXY7YtUzb5HX zedatrx-3hk70&vx9Oe?LvWc$cQ*L$kG*44x`|mKJXyhM!#=^D3MQNTXXYbLaRHka2 zUVA6DYhzQ!xI`O2b15owBw&F2SPn(z*<+|l5;YD)JGgrkJ%mnv5PXDjvtXX3BqH9( z@HCM1DBpC}`;xl)xGMljYT52V#H97}Le?mPeEktZ%8|4TiQjCj2f}uJj7in}fG*a1 z&;yJ&xBl!hWD(~Y8gFi)%C!pXA6#$ghm+;-$au`k%2iP!q!>Fr8kx4{Kh5uggB%Ndssn47 zJGLN6VcyoW0@_gxWXWlr#$xKXE>INwlF@TX)F`#&l@*uOzSxonKXhEIZ}5h$CPIq} z?!Z12el4iqnfpr{kW^LBBCDg=L94=}xxP+X$pfmEvl z`VT`xFrLfc_76sDbnH)j1Y2Crmuo@fo-(H{L&Vp`|{XC+n!SsBskpND<4u z7w9Tj)JWkSm?qT-5@B8-!<9FvFD#F;Dd-5z-Z=28#j0-Bo{H6 z1*ChCpQz2DGj!AjSjcf6fptY(vM#a8X{1b7_Vj865fx~>pgW~+(^!lTQDGy6w`Q}u z_#>gTMgnC=VY_(ZmAlAjTV9)?eN$pL%W-y%JBgPa1VC2c3*~CGFC6owy40$nm*#In zznbSeMuYU|ws3>jP1UyjGTN#h-H9KXmDyuTd!4%NYOXYUBGyJi`tq?UBIw%u?}v-<-9(^03Xp zwyV@L;{b@EbKThEh-oKr-NVH!{I#3C;G#qiP^mVo%KBeq5W;IzGC@^y=u{P}2>;W| z*ha*Y#5_1NEOsSsQ+cSR2Jp-}p(rm?XdAT_O`=?(ley;U*BK>`*jKdrk;&v7;Z!1r zZ$-YdRjNU<9UCNsrTs*VEEV^#)?h;mwZf%f-=lSPd^dXAZEHoN`}$8m)!m$af;BHG zTSWo^McORV*UbrBeH^1baWD=6b3^iC1SH(m6I#_IKprRIX5=csc@b4Il&Dk8w1|^A zCs$j>l%}JTR1vk$w^nG@HrXJ=upqM$MJSgMQKPZoS`J0JvTP*eUsd?wIizUuJ>Tut zTE|AckxQ;FE~}u0z_jO5=(T&VvYIfa=^mK$T2D}nzt+L%7~x$KNYdRHp(hgAF92wVA$Ub(X`q0EKS%fd@4_)Xl7bevqo115qq%h^6!X>(*v7YwD#z^pgi=K)eW zdqW-iL|=v)?i96%ZWyoF4m2zO1+Hzl1>QB&Ex(a;acAeRLkd*v2*0Jpq5A9 zvFj&>s}*w_h3+`UJSRG~oeofp>M3Dbn*S93BEBeIJ{&^Uyr7t}T`q5%t#WWl-1X}t zB&j&xdP3MMLB&GLwz-Bt$IDb>h+q?<^mbE%wDCwg@B z{smE4jOUT#F(0Mo1q>CYLH4xergO0c;~r42mAsgre3(h_^m(yQWI=x^#-#S>kU9wV z#f4b*2`}&3@ZwxuJVAf(aS9AcKt`rJvWJG$UGMw|f!Y;5eEt(Nnl|(Upm-C59?Xm{ zNS}RqWEGtjQpZw)vpP@%FxxQ2poQGl6o7%8=@4PIQK*22Aso66K1C9?eo~_T9ExkGaw@E+&<5O4j&%*c3RH zDF&3!E7>xnXV#r_@%DbPQ`X@Za)F(f_Av|9@g59^iJMDxlz}Dw^xwlOYeAKrQDZL!j=4v|#*>k=q4u`u5R8I9Jr8d`BvS7&mB z6~R9-@3B~eK<`I(gB`7CF*6R!n} ze)0Maan#>h1qRdlHl(>&$8w6Ew?8elE7^NZr4dIde*vOVV387Bw0C+)e;XM4JP1|No~_>8`*BmOE!~# z^^W7520C)(8<^M8h-?0RE+&S`%06ZOBzrXMC^wX;3A+x!Jj##0UPV8HvIw17@dX@Y z>gsjON;c?S%1on1-U}CxmWgtHX00F#4to7qYh4!fWezRa; z-2T{IZS@9Z$~S7T`2B?Bhwm+WRIr(;CvovIyXL>S=RUO8-yrAAd9!}fWSms2( zb$p=`8JCwtQdGJf6TKLA8DL6c6wmNHD1tQUEA8_wMAcb$z9KO5r%;i2a#_5Bm(^S> ziA?22i67MYd#^U`bAx~5@x${Y#(*cz%1doPZ{fp|>dAtL>#MMBa9c#9i-Vs*Vb%9=0&>B>s0$eCus^ zM2)YgzYzc0f-obrbTK7+s?B^X(`CuFK7Z{lV@uC-F#CH|4E5c0i{GmL8Hj@ zI(SdO3s=UyB(af-oS`lm^rKy?szT8JCjLX+vn>0+#Ntde-VhSbKTV%po@U+MT#mZ8Im@>ve5dlk^79B4c4h^?%F9^iDw1Y5osy_!K) ztiyKjIgiV_Odv+1tg~H8KBe)SZW5I|1+LcVGi-jiFK(VO|mBdddtvy2PUne`>H1d6o~Si^$g3pZlCv- z?6}MhAd}KZL=n#osG^Ghu)o2{Kq#-*;aEMR_Q#4M&$e>+JqC|5^N-Yc0;?V-^*DxG zK@qUoB|D||yR>%LvCqgRhrOqQaZh)#{?$L1dl*C{gVtpnGB3yHMF-X2L`;CX$&Uga znZW8n5B05~GkEqsTa-YCb;)&qcU8jW+jUHdWVfUFjVAks4Ghp8+LJLl3brCTRv`&p zcBJp>A^g@P3c}?J3xk!v+?PLz;Y(af+t>L5cB4RqHXWWf`IAb4 zz#|(OHTiYiL8!Hub`T~7C5e&$D?}bc5{gDaacZ+pl6VSwc`#A|U1@@LNL-nFy-txp z5qlSjElE;fT$hjFIs&d+6MQ&{jbUx)e+2QC3}}CBN5JXkCq|1RvFBxgHou=4D>qm?k4Q(6p!bKO1$wMJ91ZA`!ECT~~j15c+XcunUMs)3C^O zKBL!EK=G0LfAEd}i)ed1)?ZMOkX~MNUH<%Ea|@1Iv1>SFTwe_AfAtdmFjbZ8KxX;U zf!(9cGdjha`X#r_B8Pc`(X>ZmU@Un@RApj+@=Na9Pop0x_K+PV2?^gw$q*8~1`E6# zRu{J;N^h2cCyh55-Y1?n$6n?3O5XqMH8nL))e$poyVme=AaibLA}3UD5lfQttjhv)$^x?Yg#{9RCl(#-87aT@|S)1=Dz0EY?`6 zHy!*dj=iKK5wo5x;mK$|uG8J5d%Ui1SNhLZPkqch!yC%-*bIgJB>-9o9~9;)?|KG1)=-{6U8y3)a@U@qxwa{RPPKfwbk;}`&T6_J7=O>#p#6PV`z`K}#N!4*J?2Z=%F(Y~Zoe1M%MEA>@y8$?vC(*mrzr^~fwr@VsW+N> zF}~N;St-?92RhZzWiBNW{wSVFK-UO7{aQzOl*=%a*Wo=P~)4 z#xdZe3GKtYOZ&shn8ufM=TRXT<=SmfX$TYs-BJ>94Kt;7 zX2oam6tJ1BVF49BrGQ<{ z9F<43ezRNY(`HoeMs?PcjWFWGmH1US0L(pG=<-`uub_t<~i<=Dg31toEe|`sS znsIrj2)))n`=goHC%VhC>j%Zq0JOjZxfE4AI!SEu(Tm?yfHh?+z;&$%_En*Mx$RRr zrCfz$I2$fs76|ZBZRmgDukgOme2&FvT@mYbWtv{y(zI;pNVX}USwOj8+EUHqH*|CL4ZDrp?~ag zY;9ouiUh3%@o&m4bscP^N3`HvuwOt&UybxAW^stbe@7)KU??v=w|XST3tKBqc5TiE z?aLYM)PJJ&n$xz2R1?2eG6x*^KV&v+tx!oQ43?o6x)kD(=B^lvpas$Hb9wEnWBDrLxBUCW^ zvBFt4rWotS?}k0GQ_D1sP1SWi>}xCNf~1Jx{CG?PRfz?30{Tq&TeJOsX4hi;AHEQY z!?*pbxOu$E>_7kgYCiskDhg6Ka69a4dc)t1b=6YgmwaE>1hqZFqk~1e^&{5#aIOuZ zmJSm#WD8yQ^=(%i&iwEH1ta#eGkQkc}HRiLLsgC!hP{!+%rk+sJN>Jnb4 z<2yOj2X6R%cT?@*5ySwL^UTtpe zUbo4Uwzulbv%2_ue{uBT-Op-)uNvvfW$^6Z9bux>!mM(d`JuFaOa5ya(EZftHSv7EeJc4UlutM5xjSe^6ZxP2(P@H z`)CKnll@4j?W=DaltT;_gp9i*fEPUN3}pMp96<^<7s5agPF@?XLGNVKy^6NcYN_&8_mbaYR5<{5`V%I&}K%9RMnYW+quj;s}wH+vCI@yQ= zpi59wAT(#0bjU4GUf{T$aA3q&%1?=|Cg_LZuL;9sb^oC^l|s;X3;`m0_N8k0aceR8 z9?Nk>lz0CQo*Pi9&$56@I*m*fAity)ms2TmiwUFeJ3cp2B!6zEL3TA4)Fx zXn)TIeE|>asDUi13W{bas&ft8Bs-uO3{_21X=A{V1q`DEfE2x-oq_fq0$m!5-U|^o z51S` z($tIK>XjcWLT1kkOfDP*h}P8);^ye7$0wf%mE~+!x``>Z`HlccC-AGUdNTdu-RcJJ=1+OI)Ly{l&i6@#F^k%WxM3X#`l!X>e-HIgcsSKV;_|8Kn$GgZa*IF& zp8E;FS@1gH0C_ja4qTlb5LEuEq^ITRu(|612!=In#zEkOiy2Q2Pw`FT-;Jk(3Sw8S zxIlkXnkfzjL_(b3@Qd4)6y>|jftNVN52xIGQe*65pL6IjP>Y5dRYEYgu~40V~&m ztw1?6V9!yYwT?#LAUUwmE5iR9+W)s4`|*%?)-9K`Ji+W$iUmW z+B8n}#-6grXFynQR2HYWWd#B1%l;%IoD2;K_qKbPDCk5ZZ2wy0Q^Z9F`i0I?_U}-Z zGENb%_a`4(Zquis>}N1s{sgA!VVzn6p-KvRS$_>S%kha2)9jP;@h!+>|HLK~u#y~3^- zzZ_^2sdnBG98GkXKT#MUS!~Y(H94JJU_Xo{sm zlUbA!#=W%>@99Nte%rbc&9FJ7S=mFIDmzHLWU-EH`1J}XsB8=?jdJ8gC*9$QXt@9| z>wCEbqcTd=K))mL}26GJdJ=tdx&^SA}@AsYE2I$egvgKllikRZvP<1ahUyo@dvz zkpe$1OqQzRXB3big6LX8Mx3B$Qu?Q7! zYMlZ*4OygaR{|V_qzpZ=ZxJd7F-AVpq!BNU$30rHF>*nM4p~>0`v>e{O*NF32uH{H zI&MpfdZ2Fwbe5}T;RKZ@#?i?IfT&kW4& z4uHQe@6Fbr+CT3b$@1v&jTE9Niu%WsC()s}y2~On_y@UDtm(u6^An2Z)p8@gt~os( zmmr0J768JOrjPuzVrgWKaxO|`h_>$N94r%wd7`UBO?t${b`y;JcLclsk_v>4eIxMb zOar4CL>+{Lds^~lSW0C5_cB;i5Hq+iF-L+yv$2;jOt$jLByWd~8h_qdB<9d!$L{(| zp}!A6(o>{mOUvkuRti~U+zSAA?I0G_T+`y72{BH#iB=#*2F{RX3yo0w^ESvyl~a*r z7Lg2ut{dk^+}49Aa6?y;WMdK!y4ZY=P9jPtS@EvuDc1}$dI{XE`Ub`sP8hc zzl8l`7W_B=DQ9YsvVll3B0h}V0>TzvyPZIF#1Y@5Kw7h&>Bz8ItNda-d$F>o9Zx}F zU5QL9`44cffWCJU8AvBWdO#FJH$nL09}h+<0Zb4cN17ku{|L`?RCtkr@%B%1u>U&J z4|o7LfK(9QSmy6{0wcgfmu-6`5H=F{k4wlr91xxs%t`zA38#&L{wc?pF0I2->hG7} zq#dZR@e#iKJd)@%#S-ro_WrU&tW(cwwUgK_=s;fxZ+jdp*QJ}6s! zXl?Jm?%NgqxWs_pge^7eN^rN0WC+8(s)|zu)lrga-BGGoihJ zr8%;)Ol(4NL zK$d`UrAq$y_kxaiXlXDDyZJT25>PbehK=LZ(G8kIFUnYK@=kUBl+G z+Cu}^MUk_`{{Bl#JR@AxG&C(kZiK+0ZpkI2>2jLE;Id(|Vv=!+l^_TO zEmfjZi$SwAH1f&cM;`@=6fy0Q0I5AI46UskAc!9H;@rjG7vDDAwBt4N&dGlkq%NH0 zZ!h`dD&Lv`lpXocQiH^wWvLNb^v*P<(*Du^#2fS|+8yu(tQLT}8wCiR^amOC0*g?0 z`RM!NFZTH@ndh&bf1e&0wFMki&R51kvw_ilW{%}E_Pl43ghc;XV$OK*9{XwY#Jod* zg4=!|>x2Na%IE`~>%B{q=*7Ea~>cU(Hh*}OsbT-4_J?eFl1P=kms8&U+DsY zNK{jT^zY-rih-mBaW}td#r28)!(hfK3o%iAygS}j`Mstx8Y2s~iVS!VPQ7nu7nK2$ zdvaj%A%?}-P@;|{wTN1@>F>2`p14Pn=+5-{Y z{{2cLD*}uP`_C+*#WS^V_Ky!mC?;*bTjwbFBO3yvqUW)ro|yvvwIw^tLeR*53>$rjR*qP@^GoWS~xx9uThcE=Dc2fOxKm4Fz_; zsfh!N!EVv+8ua6y^-iA!HM(M4c=4Ld{$v%qAB&J`e7E$IEm`b-^?MJ>j$jtULbX*~ z$L?hLH|{;UtW@Ab0wKGN8XIDKnY{(1rn48e*UMfm6%?rgmMlR?=EG%>c)QwU*JdL} z9`C-%?$b?d(o^GA+asY42GV?nZ?uQoW}D)h3#Y*eb+tM9VP1c-jJhlpuJLSb;%$ht zb;;`zM-wreB8Yi!SR_|0cSPZENT87GG(*e#`G#8khOE+S4Xr-ez_n0RNaRiPmj^tS z_tKXL`+cJ0qTt*=cZi)j`=0j z=bQ}4lSrpMb2)u3Jon=kOsU3|Z6mNXydXayzG!cwTfY8bCLKpJ({CmlM=O>L&2Y42 zvT&m8b(_i!7xFVxQ_(TN-we z&3Rr^ng z@)e&JeEpf=#6e~<{gSL6|IgF`z$>rJ^>IXndeFCtF;yIFiS^#%@QSHEn&)qHNPk-Q+78qKJGzivx2zR;{xA-J(^cvkV3Kf!Rq|x>u$Y}Bo2HpZf$2R}B zW+kDU!4HGw>Y$j5DO23y$@8u9)C7lQ0w4?1FG<+~uV}9kofB#-KABr!ZLdXI;fMYE zT7F`uhzPTLu2S#?=%idq;BmDOB4h{syp7&5$=+P8vmk_&ki(Ks$1hXZ5#wfo+kHe$ zS(lJIwR=4tFLsC_j=yBli13AFBFpg88Z=Lg>NxJB;r8h2Ub$l172^4?uHs=fSAvwI z4B(w-#AG-l>Sa=AA>JqC3LT9nWA3~`M>}eweSX}pOLQ?0}=r5!QaL`KiiS`}4 zfKfW&!Mg#nqEUgAIBu>i>DKYH#pc@|vkMMaqlAeH|VdSt^rt~gV7ZLb^$BPg5nK3kF>dsx zmpF&_YI6e=a<#lpHO#;EHA0i*Kk6`v04ZFaY?pWAXQZE6KKu~Z%*|&9y?vb2)+aCg zBTA>b&pcfxPQ>P1*wj^I5c9Dl2U(|5=iAQL^M}qKU2saDyC#B-!M! z`AEv&n$hwTu4${*(|=y`HsZ$02lSWnJ-8Ket)l&M_5k3xikk1fT>SX4%^hg2tNHM( z36!n?dzO`%<%F4EIksy1@;Yh{Ksa)a0+Un!(`Buw;BI-GycbJY+Hh5~RYq%cp^N@y za68H6?c)8yfzw{m(68_h6Qp6Jnah(R+nvvw9fYoy{0UpuPTa-jX)6eI$g0dgP>kV3 zjEqZ^yT%@nrCO85;G!g8BHr8uh<)cYI6Dm^m_+jA8eU9}1LEm}7;**}-G|EJS5J!q z0o{Fj8{l+d*BHMtf4^`pWslD`?Z%dEBcXaE|0l|V5$S1Cy02Q(xE~poRhE%}>9yO1 zU%oqO%MD7!CS>txYTdT~eZ5(52#}l`^Kav*-t)WE?HU}WfB_mR_r=^Yj;pCjkO^CX z6t3&>@b0<2>6f%1I}>ZYn%p<8U+kWOU6b7$ho90X|47wFs~zQs|W}`A}|$b5(Sj&kwS@rwYV5qsv#EL$;#n(XjuyVP)QI0F^NX9I zD~K~Qr<=%#!K?dXb1>#5_a6{cNCkh}sOzvqbW;)K*eT+7z?We4+wyKbqg^C&!U>e9 z?O4o-TUw%POYE1UW%8 ze)sPrrXBuwH$D?~GzQF)_?`c;UkM06gsrjcEX$4#;sp^n^^(&ZFw8BIe0cD(d}Fy_Z#sMJ z#19w`#42v*qxB{m}>;k8#%tK};) zFJD68Z}5#=*0q{Xh@9vf*V*j27?3l+0pEiuBl5AoiMqdvat7Q6Y$AY`pnM1a)E42f z!GC5aIG_K{EvV9-*V&gq`VT~8MM3;UMgvwd`OI(;M|zTSq*@jvSNa4_JMa$GXSsgs zOIUy5QDtINKfU?UjW1}M7P}m`QL^>cv&0b)au1B-U>*c{!f`w^evg#~Ve&Y5J146S zo1_AS(6(b$JeJm{Ssh+C(zYDz}b^>WQ$zD6!GSJq38FQ9%hstavjN9m^NEb$-Cu?BX|oh?0D+Xxaix4NCveJ+5miKUVQanGDt%9Bf@DY57BfNL#2)K zn3hiOw2kjb+Kq`k#s)zp+^YC_jOP`97Pbk+Z{n7bzIN!#{CnpI>PK5h29=sVq9BUTA zt4e{I-vN#bG(15DP9{k-u9kcrXfg8P#r&q|rTn-00o&2#Ajb_qrbD2lBFW)18q@aanJm~n zSH$hXPF0P@k%kT0Q-2f0?qdl{gnK8M&d<15&EGg4{?RcM5fL}Y`c)pBka{Db>dInQ zSsA>iBAOSRiDR!c28g!08aDEc4&;a`z8F6fR{O805JOVb_Y5rSI<(!2&G+;~u6g|64)_C;i)uqw4fd|8i9p{J+^qd~$a zd=xBX;Ik~WX-qWxjR{OQSl=a~8B4h+wYL!N7W^3Ip){@c<$&YM|F}{s+N@)RLA5jW ze5ni0_gtvl8C;N)qxNC~z+!)CL!`667NBWLf60GLi%Tj%$`}+_k#QW?2-@3g9NIzE zOj>pmI0>d5Q^IX5jJTf)6!!a8Wo^@;iQ{a47z~sigoro1PWU%`EPBbC!z%Tta$^kc z8o`2CrxX+TlTM*lGxK>YAZ&xLFLnMTD_T4w9#;MY8p~M8J%1%LG9eZ9v5+A0-ulf9 z>pr;_!0(m^c#RB--kFLVIaV!GWywkq@=iD)ujIc$0|&Yn90LBeyr#*n@{_w0TG>Zu zr%LVblE-?B_m|MYn3ahhqjSLld?c2Recbba-D%x~JT&=@qkj-3D~69rnDB&WP!#bG zYi6%SG6oz%g9YNZ>%o~NG?`f>^_3dyqpQ1KGbsO41@gmvJL$(=BjkNpiM4FN|Fx_Hfv``hpPc`RCvVU>D~{u+lme;7+GwpT(dSUIsJ~_i(F@-2WnjY| z1lgH`R+*%Gd!FSg83F2~ukumvCBGD#hbfk?_5Qoo>3R8^ql3(Z zC5bldFc|$Je9r~rnm5p!S%#-ntXkT2MA?|-v36@KqU)SxYp4?CJ>Uc8NWZ&JPa72c zz*!M*3O&v86~>v*t#7^c*cyJ6G1^-0k;;!-{s~@xl*=H(G!IO!+6cjEMgp5 zsh-)LQadrb=bZHFLvD%`4TZ!}1&Mc?!kdEps8x+=Dq>Y!mG^5^2dzgml*#Yn%wB>X zUtEBy8;?Q0QJD} zGn2@HcLwau`^G^zm|%NnZ=Zip76iRqHML=|SC?9FL|LRiTSd+8|EtW!jTMjSp)C%&{0zlC`S9Cb>JuS8K zwocvi5OShlJ6+T20rmtQElkqVYoz_r7vlV9T`53)I}Hx6#!2!j2%Ew)ed?co->jlU zW+5i=e^82N=%W{81YLfS^oayI`hohkq(q%_UF?93ff1rCOR4USrIAfxn)?n>FV>=^ zSOI}uVzs$bCt|nGrXnJXAbNl$-6tbC!0@gOQN_lqr`(H}UCT?zybZ=wVZxR56E(U;Cc{Rz!ZFbs@8AfVauJ;DNWuyJ(GpWLY18SPVRT{NAF zopJ}(0>lD!lmI;=_NpMmqbQdwEq3g;Pa$I=Ykj03rKq` zaQYaHHzkfs6egVJf*gj0OTt6M&xU3NC{@P)@YtN#C~kC7 zx8#Pg!>zCFH205RQ5jyV89iOTEWBsXJ;7R5jUQXr@i0O!I>+N51Kop`!f+iRA zCOHs@UE4J5-siR;6=Y91t3Nd67_|mw_HJe$g~DIcX89ayagAoy_*rZPh0aYTZ;sqw zzwTu%_0Z>*Z37Ij8SNhyF){&rY5xekqbLl5-2FQ9Yc%B_$exRDM3V#8&hNoSZUXNV zTJ+Nnff2ow{N#zrO@IwB47a=x5)@6$PO_pN|B_VJUH$s4^^^&_1w^EnRA<$53>PTz z*y^#ic`D|KWm$Mn?Ow=~YCR7aqHDdu(E$`GpQyvK$a79&14=*ZxCcgJM?58r_D`=y z)0ba0qy7lkOQ*k0C6BK(9z*5X8ixmnKXKWrc`miOPQ=K5D=#Qvfvb;kO#|aeE_>3W zM&I}&xU7cWPF&{ul15gBs%i26G)nDPC?uXFK>{RWB*^Yt%fCN4UEWcqXAWKslJftq zd_9EL$+J~&u_gM9l#FusSlKiq5gEJk>*=astyMUEg3Y#nt-``XA+NU#ck8#v(%EP5 z91dfTM2Es7X~gf<#iXCQpUcM+7DxJMC-NK~d-83isC^8|5akf0FS({QF#EnE!e%uR zmFsd^FWNxoz?xV2eU7*3rNI=Ud*2p)YOOB^PBO6XcKqX@>EEyEGJc`%C1&0E z_A?~d1FFMwaU}QCADg^=*L8xUPn*;gGJI{{5mwj{TYWTQ;jb*5!u@z9)%NCsCnOhy zhFq@Dy=wRBgfa@*91>;uq%R{yc|FuT_3CD&!C)B5)KXOOIWc`ihwq2rkBauzZxuQk zKfq)uY5q*ceH)G8b=NB)ME}DN33!N|LY-Wl_MJ?f?xN~FnA{hJR7;8$kKb~jLK43k zJ~De8sAb9}OeVz#wzkoraG=P-r#SIa6|69eOL)J1EZjx$A+3~iRRgorAPsY_z`kVnx zYLxkeK8_Db6dE{Y^p|mIh-^o*v$i{}cZzSN743}<5jir6N|X>W2Aq#%)awFd3xGQ} ze-dasaE*EBDEfx2gAjY^#}$qY##vl4(Y*UZXB)ZV8?mkqYj=`#!b>nnGF62Eo3#wT zIC3TGbxb>9*|_$=mBR3Ve-eKL=G}?Y*@*0H`LQtTs{L@exWF59#lgC5ygH2Ir6K>y ztu_0fQ+79}5ziO#!(}f~Vbn_D!e-04?i0lj^Gq3@l?*WRvn zx@YktE#`MOF8}lTW2Mmp&%K4gR$ejPC$R&skoTzUvERLyO~x@uT^rf7%HB+AeLJGY z0U5pPmiqoumO`Q;kH;x_T4!SAHv)l)>PsVk9!R>|D*2)%d1wXV)5G5EkV&rN6)Yk^ z((B+TOW6#BQhQZa;b0eEu1n&ptGqpmL${!bh<9o4Q@$KK zYVe0~MFu{QJ{$H^A2PiM3dLt6I_ix? z_gyci3u2#k=0plHQ#?2#9X~69c{~qAAeTM^Rt?ekN?H`=Q=cFk@>99j1pFq1cg%^b z16>Vgl5J3ZoF3`Pmzuoj;`A{n{7W7W-N0_<(>gpT(R7(gC(5)_aAu$ z54|6_>14OC9dgX);Lh80YWtj1+m#KiZx%EAa4>xt%KMF}Djs7Y+eS&l2S!pKowJiG zpKH*8^Wa@n_PS+A3!3F!L4SdHV((|5ZUPJ%96%?+n0m&^6VLcq>(0yBjw!e>wk%S` z4c}l?&2A+!r`^*Yz~WD(U+jo3DVyAT4t!Mkg{+^ANd_ImBl8n9sziTId|Cg;tBLGC z0FCk2&k?w%zKYih;Q&u}xz_`I74g5Dhq2JYa-PRhv?@PGofnVJBM+oEp4+=qdMA6v z#%C9ick&Kv|IAk7*X!8{I>Uz6L@M&{mN~3{I5QntUr)4E5>v8OR;&1!N$uwYu9l67 zZT`YT%=yTkai0AtWO1xHW&2JM+oNo z-3ytKCetGwY~Ohs_A988yXEVTU!0Z6Jis4#7$e$+g2)`y0?#*x18rg-coZJ3f!I* zh}m`logB!wGo<7mVw-|MM+-nA*;H9wgaWou7K$k&vUGhG&7b`huy}ud)dJVsjEoWm-UO#rXNPe!ja?5Nf!uJFG^ z0pvvNTr%fhMq%42jh3TdQZbSFkoiq1yBr@)AD*jk^zoJTxsFKYxT+VVK0a@rI}Hh{ zRWEZe(J}*+_^2*tf{`T2{Qil1`&Eo|;QuW*9*#G=Tc`wCR8B7bo z!n}!E6gL_w4ZE$OCsrt(8aNTD=U2UTMYjYlx!ISOmh*P`#&%oUg6LZwS@-r^;GsKN zmv{RQt*}nKM;hhwD9xy+e_COevF$9y#KPtPxpMg;o+u4xi)I7Mw8VbOy1Z!=?73$= zS@R9ilg}cDLZ9{>;bi!XP5HA+E4NR@*d=K6qrWvUk!<#t_t z(a=b?^EJlK)^~6HVKNB^)ZUHF`d-a8Ggii*_IEg@hP5EGTBd4~vZ8-hjXcd#7gLXU z_MgUN<=Ki81xt<5a&Eznh#KJb0KrRlNg<_%CP%#8CX?+8_apL}v*v-3Wq#$&_ z1U$dThbfvjz`(CF4Fm2v$=^6?{!&gBGbsmQ zJMt^`k5ILez_l3c8Pi;6thTKUZ&Qrn7Q?_-cV0OOyQ%(1g#Z8V6z)h1M^>NopLU!j zy3t}sYV3p;AwdjP?^oSZ;?X^fC=1Sq9bt%T9mIxdS5*GJ_Bhe`cGfk@iT&T_*4Zy~ zJN{ThBZL7?e`Z3yQP0m5gQTt?qM6Timv;`^w1=+g?l=yuH-~8`Z z0-!^~7{wLPdYlLNCaVWgLD&MwoesHw)GA;n&R0OIW@D*qw3Q<(6;>BAnlfq=vpE*- z32NLOgQA(VzcAVB6M%@D18m_NfUj=xlaMgjLzY;o+bMi@%f#`2SjZjU2xJ=FvD%+q z5z(q=nu_YoO4QW(YDXZS!i_$vVkhvC?RyPRr;#gmh)OZ{8h&oU zTJK_tj0W{@_4V$(Sm=k`5R+xTftJL6K)2MyJA2|1Cn8n3cv8^J` zQ@T!lC6=hAoZPqMrHY%#v$UGH6py3!y1<>P(*+J%=e?#3=5xi%Y9bY#OH3)0MXn|& zJHI6}d~!weMP&)M?etaJiwqUVI&J}(jsC%KP-{Umw3wsG2}@b=MaGePUe}5}8u8wl zHf(vBC=}@Bf@}jSos{yS?FN+?m$yxR`NBvR5n;_dp#v{ED-V@5+|zMFLrbUs87N1y z6s%anCum`BfEu+Dk%~0Y_fQ4kTcI$}ghm z)G_?MH6$;6@dX1m+Yqz&S;q5Gs5mjwo+(@m>DSi`ahZ-noT+DeD2GBzE!N{;k)#RDm(fszxD*|Z#@dE|j7)JJOvb#HL*)Zf7hA-j;8& zGDkYMEOJys8~#i=8Cumv4ibM-yH)#MT6pTKVDJWWgG?~f>X9Au z_MXqC> zU$N*tnLMA;nH7FlLfq8p2R4^3lAwMe8!6Z|uF)mYzHM z)`D_N$tJ=J$I`DuE0%7Do{QFoz%JSW*yQ}VO_vL^nyet#DdUUlS2qA9;DT%jc*2LB zOW$OL^LLLRP;{kCOdrEsue#zw1jyW4+FL%3TEO6aiQXB<=W5dKf9Sia2wx@L6aTVB z&$pjD_NNjVgfW@beNrmuHKc^PNV=K^(zydsa9%L*wie4hO*i<;28r1`Umughdj5X& zlUkiofsH{EbIYZ`mgpEKpYtC`3|mF7^X!Yn(n~^#_-4gKoCcG_-?`fbyuVk;+`ykhwiirQ-I{_7&Ge5y05Pc z4mt=|fQlX;@Qh(Rk@}YdHyr(}RBQ8_?JT&xE$X2^dbt^7X&_J93wU7YF`S9@TI0>e?D8&qlpXEIg})^P7=GxL6& z&kVwr6#kb>Gk}V!!0!Y9*YKnhkD9jJ6fkfdYEs94T!&Nw!2*eecq&yQReVK1OCNgo z8nDx`J}RRAhnX^o9%-PM@O9w?)>@5Yc3*`rkI5(t=*LJ_6`sT2CZ9MJERM#v%6I4u z0RS1#b~2hs+N;<;mOgZsS?$l%5L$T)kkKQVqW`H_{@*hs;38_$+e}yH&3ghYt_e;W zrs&tlqM#=w9!Y|-ZE&;KSe`?sK08on-2S<Vr&l4}QxyAatO6T3aP>T*Z(g;GP;Na3gqghY_ZQPb z-t(Fg_RFUeE-{zr;r`=}nM!ttgYg-xj!r}I9LCQBI?#X)9Al%%KpA1foU9Cg$281# zM}E2DW5z1vW1wa>;%$}Ug%y$)9gHFp7w$PZJo2`Zf4!%jpLF&!+ZAH{4s}|{uOiGG zrT$sjm77GJGd@-}zL9H11XW_Y0sT`^g%Av(jqXH~s58))*VEF>wcrGw&X~us4Os2q zar`8=O7=H0Fq}ng8G@&;<%YH5dQsyid0m?O22=6}KOFDLk)B{w)~~tlxBO_&;Uvgp zM@^FDoM3g5lNNupEr`NMa?p@xc4ddFM;(jfNQ)6C+Fcd>4@wz>(5>z zXB`TqA0gM?fzsEpv@qIVsH?8|PQ`t4w%|$EYB_V_7LgR4xD4mHnA0ne69I3aId>p)__& zHp5I`O`ly$-4qZNuREQ))Qo%`|5VSKm+SBFL;=k`bB#!AAxMFN-n*TTndp?UHnci{ zH{i}uM^$yZ?Ja@k0Lv`82d_p)4eJR}Pns7`u1i{*j4oT2zhlSK3E!e@ilnoc(11Gs z(tD->{3zPl-DH`WTHM)|g!p!E`$mh>(m25hoPY{FCMYIYGk+b$7<`5ftqFOt+0CQN)hNv*HvVB|E zDSc>%t1+jJ&!+h%VVKUXysw9K>T^qEZ`{?&qrA;mY=i^WWa`jKHFiwQF=Iwu?9S=|iba9Z%b(%jOE0{3RGXm)O(8c9bn zp;&+RSh?ZE=?$xzL`BbiDG~O}*!Yu`6r1p4nQN=|OI@`-6x(5C7M%E-@Fht_tx*gpS}R!-E=XvS3bvbKax zL1}8kN%Cd!%n#kU-l3>>4M$e0c!egokqqbC5-k_wN;CMbJ$p+@?_zlD)I4NstlTQ& zI;?;C%B0Oi{qk@BI28j-N@6au&Y!_#ixmt?j54;M=4V@gT-jZuPiiA6Tk&Y zQkoiH^F+)01eb?;xcf3-0@%b@rVkR&9ZxFAkuykJC+;O989?>_8AAMF>sV}8j zUw5cppE0_Iyq+74WP-;rmDY8$<|wl)MhP-nv*-?lDacv%rDFw}4N+S%X?gv4K5zWR zq~k~SVDVgqZp=w&=`atjhFq_+sokJ6AFefd^Cj@<_enpCm}R0s6E!|94|&{Ic*v>F z%oi&k^3MQ*0{j*6&7*uInE+>hRRi74nAt;1y#CR)(7-e>i7NK%FN@HrKACXR5@pF& z&epVx$6B~?L(~agYYD1V#f@PaE-WHo^0*Y(;3SpibqYwIC6-BQ-g5FQpZR`|h}kWR z_*+HHRI*DNEn8VV<*=`sJ0~=1tS`thY-`O6F}xwR&rJ+RLUpD?u2bgxw2h9|M3qW` zcW{w*K|PH(d2-WTpeAZ|kHft8Zt}>C*19+(VFtlkUGtsCyY&}SOOIe5tTM*VQoarj z8F!=BRi=PWXLibZsgbz-$Ht@=dV8HkMK;q?o?Ti5PsNvS<=Qzb520;E8jaAVdd_9N ziP{|# zW}e0*u>$tltI6up5=0~#tKv7qbUEzB$va*_Occ*X>-ySHTLm`nCLT)`p;q-y+Gy0| zDsl}z9hXs3_|E53|9Mj;WvA%ZIflcv1DmbRyFekaHJhZTTRdM1I=}E2KdN}sFN>qm z!Tqr%qfM2(BKA~ibrac@nuHqb=GrXOh`N%&i@8A cuD^|aC=xX`L)$5FqEw4USH zzWJ3iS_`4bXOPM1i8NmnIHvSYfOaAv%I*p;so5msjIlmKQEV)pw@|(0#C`u0%p?{g zR8NPNfFQe$jzTur^khvmLb!V-D7~RlV+!v^xLP?#W5PUVO+KNABuMo!3+utVhPDZ< z+cPglxlbzz%?jP1F9{yR3h2S056iqbWa%XY`6Lq3TAuq6w4O3nK=nsLbwF8%Sct$E zESp2MW6bP3DG{NJQXx>CBH_N3kEdu*(RD9<3Q{nu?Jqh_S9E$bVdHcr_nZC6P?)@u z>Sllj_S^XK>7pH)M_(F#Br>rXXZ)O0D{I^%59NWH^{WZItm7pWu}nSt8J#yWL8qZC z-7)OOT6|acw3g;wV7Av_uswPZyOfspG#*a9?OH%Uitf7g)0pcz69?~E_4+dqs@6A? zxU!MvMU~Q~14Z`Q#SiDi)8#@P%;hE)0TTjm8g7*asNAK(>tVo))ZE9C*Af;zl+UYV z0TYaLyxAo+*@~?j?RE6m(@)4g&Tl4Jy7#LrQJbS#oS98%YzPNow2yf?RQjviW`M^^WFX>`M`@K}ZI)RwlbFsXnF;iDf|XSg6Ggf^ zbzF1bwNwQQL=0SA;s=av$d-Do`L$}sOVf3(!Eu6aSFd!%!CxA@aA?~F>rNbWFjsMY z$ESOn^pjZVQ_jDR|5jxECgGJao!0*4j$SI+4E>=zGm}$gX>dy6Ai1&n6!!rBb4Fih zPy=Gu*5^H)@P3L4X%AT)t!Z8ytd+p24O74$Y2N>;q%R^9Hab=7 z*Jxfp&LR*e3k>XuQ?2=&Eo)wW9ahtUQIfh@6zYtBg^4@CNG_bN619?CUZ$dK0NJ#z zr`;)heKb(ZZ8-f@fcZAmuTLS`L`x&gQR55vAb~l4p8z38<#I%goi0`)*-f6qBHA_{ z+aSNFNA$v`Ssqf->ph)z@qxg6J6T=>GWpfHxZrKcDVy=g7z?4OC6T9O&u3PZ)v*lO zZP5i$QNx3=*n+xZW%G7h)oe_C$bOH86f4bs2*vDOICjNan3g7^OuS`oZN5hRrdo2; zW^qt$R6hHqduBp&8TUjD*UPcT2n^}oRD%{nUjqx39fDX3FEzM3dc(5_;3O*A6RNI} z*O6TqHUd~LK6*pri#U1Ck7~?l2_kD`WzkOY)MdT3VyrjP-qm2&8#p(E->Lu>wQCR^ zg;&lDwN5CV%FSoPUV&K#mr%9Mfs5^gDVrkf^2aXWkXjWjknPV3oM~>WU!ys0+CJ8U zYlNjgz#|63Kh2RU6Ew!;1A1?-UdpoS8g7i8PACL!9=rAi)`^ehc;nm zg448~J)U@?X*e!LLvd;{M!=83F;u`Jq=8R(qex(oy(6meMeXrEY%Wb5ilVbugTowN z{k;f}uX2xnoatMR>SYNuC7rvbIx>)YO*S2hv$qj_8<$lb{N%agn|W$i8fj&NL}sn| zF*Rb#07C6uCyif{#$-YE`VBrxPS*5vRkAo8qL2Bi%FaGv$v>C;-j2O3^)@O!e{fQM z3WON(*tGlO%??xI;}PW-Wj1=RoC4oO6f^QfDC}fgyF~QOal0`ok&%wG98hhurbIz% zCmL?Ayy{gxFjJ~AHqpwBTXa$H6O8d&efCx4Eox9W$nDj=O@rrE=P6{WH=T)xbNdEH z6;X2YTF8tPD?1F#!X`UPJ+A2Sb)jv;y2p$Z*o%y@qNi!S#(Cb4KjU&m&^Wu$!uXgc zSX@h_&JET-8>>^=4M_P=S7%T*=i$_|K_XOgX4($N-fAk%SrnU|v5JbI?nbjo$y{=& zA2`RI3wbxtr_ZeT^@{Fk+h{Et5Ek-7g?(8NN@jUPMge;#h4UqojOeDPMLx#@+TNGFuV(ehW3cj6xx?&8WJX z=>G$>Kuf<=+lRlyqK{-;6r8BJ<7ckiQTgNA(MKoyre()Sec1@r_u0Fs@*bR*MAw)G zcHuo_PZz2u}_d0!gK0aSx>#Oskt>s(3k626#jkC}$k+trHie0JnHCA=LuiZ7C zb-s^p+U4W6XDRG5Ohy^dfF_bUmQ5a8r8}K<5>PXWN##3XJUK^$f#i`AI*LKZr{_Vd zA@vf)(N(6p`7~JlC;@{V;tk%e}a zH-$2#i-tPN6(dyXnos4PhICix*9??U^l0An<1~jqNH^i#)f|{yQBw-byXjJX_ zN%xi4bmS}1LnNwGtV-!uzAJ8R7>Bq^0A;O^{(jYxNKYnZm%zRs6>ex-fAPpjU?lB+VG?`nhSFm7ahCLG5Z?e(>? zt3<7bJbYbo#oC?^m3QfrEYZ|)mwwTRw~l>%S6XF#ajmna<3UO~eVxi$>{Z~2a++d= zT9@)&taX{>h(|JOy1KlNPjtk6GDI_9y<~`0(;)y;Lx4@PtBxf@I+Q1#BUj8KR&2z|?7Z>h z91Vs+MymzP!zzGOru>LFleVHVnNN$WF6)xsRVMz0#NI zm{T#X#9f1KNwBY=n}m)^fjSipN!gwE;`AmX_fEdu{s$c!k&0O`LOls z=#e?8;@Y-RcC>Y3Qb7j}BI&ZTgS?B(%0|iQWpWiV(G^89BQPJXlftdmQ|EOuy7YCG ziGIGgOHWsswK4tE?r$^UA(@mPgh;O7};LW z&X}$-P#gNN=qndr9oO>fyqD+GwVb8Mds}=OU0t?xmCa{YEf;!UCYg%8JWr?ct}@m6 zxJzDF89d|4^zx^X#x88`vrpxH?ZU=Ub<`6ir{w1Hj3Yz5iffsaca<$hwsh?5aaY^B zFzUmutNmRvq3bK}l0jLY9ewnDSh%b?i#{F5E`7e`msU zp=}%0?s4kCM#s=#(10d;h`Z8Whj8}s9N7}$8A*Glx^5@RPuS7W)pCbaADChjY0i66 zr4>W&(_&Zb#8}aMdGYzUmhbaQd$~UC<<#kM>7=9PkNn~h7zg{neSCatJZtRc%X>|= ztU3>ET~^EY@<`8DU(?t5T3=ls`F;d;1p9Gt-x2x!R?lA}+Z4l5+fwJdXr#%@=_;%1 zkuCX(Ynu7;(xX^%=F5AzJ}tgki^sLGZvQ0Ou~?bo+B^vxcP1GgPo-8^Y&-^&|S=jleJYyG2W>$;`ZU)$#O`LyinDpMVCEw3)~^^&F7%ZYS1mJ7jUTDYRe zpVx71Tnx{+vis z4UMl>S}`O(?ZqnX#rZV#bzVG*YuSBy$x$r+QSmsmwLZxcZ(qIWBJM{(7IB}QWarkz1njOV|KHMiEe=#y-mtvh~FUzN? zuk+$jT+8x#pO!4iQ%reH=kq=-oj&$*d>WcMFIkGcoLNlIXJ_5MNws0Ia_6&mQugg^ za)hU1?C-+Lm-%#Gd%e8Aw0P%}H($Nv^u=C(7Y*|JXqH-cmtL>ar)4{3DzEuRzQC*E3)@>VZK#S$Q9 z@;T^Xw=SDjZb ze#O+0=IEkVz3LQGuC(zs0_l^4ZTZ-0SZ9oL8O2_QcooBA1UZrnD{KD1+lU*|Yvm1% zWYv09?&T>BZC5B`X~vQszb24$8HFzG6@Qn~4Xd!S+%GaF!ey9xvN_pjHe{XN7O#o> z7@dZ52n~D$(Ob2{ye%(ei~4J}Wlm!0RGPf{62j3>pewbybD7Gy50cKeje+gZHpC5k z5z_pX92Js>&c~`-NQ?~n3(AotdC1_3&{+U;=;#M^UqA-)3ajV3QbQ0jM)2+EBZsCh znEAO9wQ2*jlyBWiFHZS+AorDANtx**oy)V?7FOkR0xxBCpq!w%+5pQV+wZQ z53=aLjE(4AQ;i#4qOnK8+hTL*EQ>ylEThYLwM9I{p3lpxX{dv?rlCxS=i$19R!6BT zw&W*Z>*K3)hc2UIsolDLYi8J<+n%3|8_Nc=v!qs7V+n&3Nd_z8ojgpy(NGWo`i+~e z&Bvy+Zr!@H+lJjT&}U!v7k&n!M}Bph_$wQEaPwYnj>*>2CA(@aXYWjoQ0{MFou=)6@>n<(~a z@~wSjavsQ>n}Gp>xZkX zzii&TIjza(Z{6B;opy_tSo(b%>U!ntrWD?Sr=9;yNSoV-@l2rh<9q@3HERl1;+5=d zzS&af@?goNfy#!E^GC4BPL8b~XW`x^NDU7Nb5N~l6jPV2A!-L|)hVW~P;d=yPn*Cr z+q7<7b8c*qW!4T$RS72F+6>>IuWikI;AmK6UdA{=AHUUEC4aKi z^1t9gWlt#j^EjGq1=rzo2CjwCCNYf+in#Wvw6Qbe?d@t<3jU2vja7N<1(U&;SDPi? za`uZ{FPnZv+c?GQC*0dMl5{p*6?qvywqfn~HOlvAxlEuy_G%zou8Q67?bI& zEZe0qsob;G@_}mIXGCvy(P-L~W7%of&46uA%C6U33Y`z7$Ct5+^Svq0e{{}i3w^Bg z=5n2E-IC`FSw{IG#!H%;#`euyHe0`2-`p=`?_BEs5-b)UF?qE@dAMz^z&WQr+o(QA z9RXU}rZG?FrXHiHHw^MP%Dl)2+2PB^NyBFjwrm#?$kI4_S(SKd?FZVc` zyJQ;Zu!nfl=1qpj`aJihev(00C`PvQ>iT2!!d8tj)Njp$)iu{%YqY!VzI(oA%l#UD z<{FGK+`EysHn)rO<#j+uKo&u9$&LS4d|*xAG_3P=sq!uSK$`o8-4Aj(LE{W*=(>3jj$q)Z6cI3Z}L8gD0Bv+Mx8uz$9!5M5f=IfC1 z_3PKCeCIN|^9(UR7jNVQCfdGk)!-SSSctwxC*vh;;vD8m&QTU#S+MhEci7R;oDYM3 z^VZF2a|U{CzA18JB-rG$0TH-3#XPvtk?0KNBF^A8SW;dt;7myeW8^}P{VlQ5O;J9L zgew(=<)@| zg=+0@`RX_ z`B@Hh$hE<{vDey!v@EnpM0VCs+cI9|hE^UDN`0X#ttjYGPMZx2n62F;NEWgiY)5N;GYxLry6~k!zT4PrVq$o^wNe_ z9=02{MNiR$p_v8YIlx2OZj>s`Wzdvtu5F07WE0#_?X7VT(g;M4VkOeT~j4n1ZM z^~HYj)`uHjRN^EXR?UqiSL6V;?Ts$$r`UM%xkE>hFGE`Ma$Tth%S_bd8|<3#eg54f;|-llhXc1UY1|32j~X!vrzue(JTFm(allDo^pQxKRx`~b(!r) z7O0h9Y&jRrgHzMCa>FTor{Fw5gB3lrmlC@kvM{@!G-Ze`(?aYoSgR%QDUA`blQO$z za+_&C4_MnXR@jRK`XDsiKMKyI8_P0*VV+~16Y}L86$^x^b*08C9_mbP7DS&S&?k!? z&PQpdRdoI-ZL6!WopG>ShefWPlPsHfO?E8M4xAC~SlJjxJ=YD5RzGRy63w|WS$1vF z@T|RbvL?drVmo$aas1^^DIcJ3W$m9#2u4(M9&~OI(DwICY!5QceNOE&J9C|lv6&wG z%qfDsjXvZRD_V_a9PQ`8cpN3*qI2jd7m!3hqMaSI$MR)7LRf*Uxn^@l^wM4KCvvWG zFCWN5K660qUbk+&_0g8z#wPGvcwmNsOnAYZP~>JjGmeIL?yK}quvR~X4x5ZOCuoDl ze;!)OdCh!HKQC>EtAwIA_tz{@4lmVp#rVtREjJw|jqXhl0i+8>6`H zn<||X98%0*`4Iy<36M~)erAO|f559RAO{?LpiDm=!7DA&Rn9|pl$j$T*^iH$BhCXh zt!^9*jJ?(r%IM?yJecf8nVmk@R}|UxO2^3T zT&V?fEGzxKTpyw!0K4N;YgOJ-&#_fC`%R21-kc%m!KVh5Z0>gcU zdd_C4=RzrME#q$%RL)Nm>wIR0#f8RBY+~H!+Ql)bAE!#s$)c@UP1|x-V-8BK4`WYG zn^TDEg}##IaQ!g%VQ$O8k44;LxK4&0Zk)Ls_>%<{O#^*YmB2YAWhc8S8<mUo}M|h*<9@Sjmw5-gj^L5Ml&E-Rm2FiBwFd;`n z0h_=4133P%Tx1*Gr`#zx@dg*?FAp|0a5g~G@iIY%l1d`}6&}!t-)^aY(fJGT{kjYVU`EM?i?OHi8pey|dn)Z6j{TM;z zfhSKw+J{g{a&2-W$St%R z1J@|BnYa-$YFTft&*w|1Fm`|)?LbZ;Gy_YXb4uHqkZY`sb|cI5c7w^)I;Yq{fJ1E{ zPkVI}qteJ4u}zfw9oG|1GE|pqlo;DEt&C;#8Tx|yeWN?Kt(A|$I$&0#2-~sKu*=0v z(8`1XovdQY4`3O)Hk2kA9$a5rGCelVp)&;;<1C+kAdDDWR@noj1T~VKO|7n;ggC*m z^lyGGER*0e29D zPf$Og+O*gS+@7x8c&*{LA+N$)w|>pta&yMofZRr0Tdzc>Gon29po3qKDOjKT3s`clbK`PR zwl|CM_=6kzDK`hV?=x8nnAkn2us0Z$bHp_dKkebZYI7w7Ei$0X?ytEG*a99lHXuKr z=Q4IT}fI8@Vp99e)1N*K&}fi?sR? zW29`f>&g0ib21@p!rT(o!df4N_lYt7C< z#%|~wH1cUbV_2?iFkt0FUR{{~m9a7_&OxI>$<FJdEc1NbcXZ>apoR^i{iVk)6xR znCKeassMr9B#XE%Gfg9da{3?F2tTlLJ&|u8ew$U6&@DW0Z_KNtvOMf$tf38DOWdCb z;AwLaJIA>o8>u!K))}>-Jk2Z30Z^-xvxl*TD*7C4w3Rciow;hk0Xwl5Y{5ojnc;2y zri_>1X}Ed~*%+oGpKFIX0xQb6Uf1QZfK>(7NNbfBJVv_FZP#D6 z!R*a88kQM1ur2sv9a`v}=U0!$t<=veERSgop;b2T?+0JV!mH~(^y3Zk5#B@9v}HRP2>tzFEy zFxzk0e8JH18Biu0oFN&rt@+}i^R3D^wuOf*3ry8f)p-%b4S-;Shi_;pUesS?W}EXJ zFQ3OOvu%pbXCsw&l(+#JmbGq}RF>0O9v7iq+(THm!WU&~KU0ishV=Gx z4%c8G2W?S%pvYxlG^d}7hWd=7O@b=i;I$ifBi9C=nx;{a2V4e1dnoe{rI;{o00-+I z6+@%GDjm+!25Y*vFOLJ>v*iT;cI1fuq>j8tH)OB&1Vl6p{{R#s>aq?w`Xj|4#I2<_k+$c zuY-K-qAW9?yY}HylTBR*6YBTdbKfMaT3yd;dJMIDWbU_iEp*X1q^( zb;GDreSOY`gp8k|Poin4|60jh8C=(PpUJxO$^{FQ5$t*|$)UeSpK0eC!-kl~&1BvA zK4SfS$o|aFwO~4H47+4E?W)fc*EaU+ev$Kb?k>Op*>>(v8NW5=q|0`4F0u|g z7qu!7i*NGRtI>@}8U z*;}*IY7O)EiHtQFH$V1qy%OxadYiKi7AWITo`5k~_n7q;Y+ZC;-C!s22mV6%ro_Dzlfk}d|38p_HnF4jfI$(m1`)Qe8MLl^Ag z%ov-Cj)r#^o%XORV~~J>K0mfpN0?=BUXX9?+EIB=&nrX;?M5mf{PwHYMMpov77dBWP5m!F=qgSE$2Mn2pNoP9CEGE z+YJ#~hmqB}KUs!hkL@wfAM(!B1pr-51O0YiLobz@LJ%(|8=U@!h1(Ed5$9kmL*put@gGY@y_26%Pr$@#_ zi~IU@U0&y%5$ea>d)sqVHw^k*rnyjkPjlkNPPTJoIW;qOCZDmPqZ3=7$W=AA*mm+|LAlPbJ0<*rThF6 z$*UU#Tpf6&%`=^2``4U5()@y8%fqmX!7Hth)-Li_as85uu*S<`!M{IYH<8_=5t7{*zHEp2z23>Rc&o3PPTG_ftq2k%A} zzj$j|sg?tkWl8Wi2F(-AA(BO@Aa(bapmhZ7?5+$M9v^cf;j?|m@_46B#kt6%6Go;g|F>$m2X`& z{ugXd`OGJ>*#x%t zwf!cXva0MjjjT??1i#k)4jv5`k13r-g>pUaX_qfMa&M?%yzlCD#a=e*uZm6<9do~w^_9_0SkCUJLaXYW3}Gc~u#tWQ=L(xG!dJQ9M{DYLe< zR_sYWo%>Q*uF*W&qzpMt(Y9%Wnbr^8I$#7&NhNtUcmmt? z(&FNBFLf+>6*_e8z4TNdeA}P2$qPK<_wWjYLL<(Iccxu-a1?U2DL%l-{I4=2kcxAy zztLHI>yn*%-nO7!@7fcM^hg;EA^2l`@=yGQTj%!ilr#ZveTi-HdUxqYFb@Nu9^;!*V+Vfce4Yap`RLvW zE-CpMytT2~4Dk*=90ctKd`^$AQ_6c~TBbM1d)t&{SKOD!_+$ITFVf3(`B3E!+&vHe z!mWPQy6T5h-GwvVbAvxA>^*(Bi>+Y^7~ zNm+1TjV#BM9{kphd#rfdW+C$1daSoq@Mn%`Z|5F;2@iL_)kv7);yv-195Zbnx&?2p z)$964X(t{XS+|YAQpPJjQk>^`Fh~A&!{@%Mj6J;IbDcW*mE!5{(s{o7H($ISe1OCM z!1Yh1BmE|DkWTt-27?w zZvej@w|hGHc3(#adCDauN`_PSBa6Vb9ohzu@>ZOsbm*M8uEtj4+$#3FGG=?_Y2rR& zAmz_`;-5I?8DRNnwYQw>*{*K<{`{9lv&egg_Z2?R0<&G0#?{tUx;MzpmuXMi47;{O z(6&}NulgelVTyQzYvVojx0die1iS=69$n&t=dIVOJ9ggd$U|o5f{X16&AFa^aAE^| zuHvbDG~HL9L^rd-xL=vXyam2bSb8?cOP7_N_l6GKuW#(c9gUve*5umfbDra6use3u zrE0!tKz(sZL^uBw5DR$P_C|BQdeT2Be)|u2cCP*D15c#kRc4JJ#qkoHTAy;IT!@29 zbJP*fiBC$yksr}RA%rd-IoYv`(n1~$95kqm88f!@?%O|41V)cq>+kQ@-+xG=L2@>h z_GE%a2T>~f_w6g&wrnXoy1L4)ojc2U5)bLban&8I)1l@lV`NY(O=#ps>hL=M!fF(y ztywYtoraeH_1J9?RkWPb;Z#SWuo&pX5i8)_BTg~q)EfoW zX@P5urH+B?SG(3x!RgddYpOyOx&-g;i?vqa^Nh(5JBW4+`}aq%xc3X%V*q2L6>J69 z^TEyE9l^B1Mi+plG@98aF*C>mnX%b4(KOF>k(rpm)6cT~aQE4@Paa5eoy#y@YYY{)! zrkzDrY|~(rPa3%f%WIyi9PIG5^IQT^@#ngwr;*MxwADJ@v?YlszW1XOHVF92-lJmqzVaeZea7E|1`aBHXoIx!qcOH)CcdK9=q#LY*8`=}qteL+Sf54QrH#dN ztzO}zv(EEA)jlz*9hnfOQ&>G3xTU?ox`JS$|A7AB{8c%A;&}Kd&wV>hzkYpz)hmIP z{EKs>j@SZm?tEANm3?WJ9o~^+J90W6>0psIXHK6<{jS;dn(JR}drNA0Uz}&0NR{L8 zlDbowxO2b%#Mfj00Rv)Jr0=PdCw&N+ts8h<%`tMOT=UPigbuVn=<_GE^><|7dTNnA z-rJn#$x|n>Tj$|tpU}oS#MS$p!W&z}_t>!}FWQpS**klE&Q zJ|EA)J7wLOgXe(Ns{`Nj7w{L#hBztfeS7x_&gZZZ!je|fB7vi@y5(N`SUZ>1mVt+| zL_Mx?wY>&-%DnR1o27g;800>1i)4r+r5^mw^Jzd%Uv`gY(hhDAw%^ae(=Yh=+fU+}6lLxKW^VS<#;TdUescpdK@{q7oe@B=7?M~$; z?zIgA2Mpvovin6%%;#Q#{FTKzD?Y>q$cONiQxlQmZDKWYX``vc*u&u2b~KwJZlQ=e z06cw-I%#Qb*N6BKhH;1XCi>OU>)iYo{z-k>I`~J0(68=opnuiZ4T3h(*Ld$sM?Ixx zML#wuvIZjRsj^`Elym(^Vmxk++yldVlo{pTV`2mRtMYyUIaT*TA*IrRuiyM#F{tM| zH@QAt8XBjnuT4G%5jPnd$cIx5#%T)^4}*(GaaZTG`?2L6J(2Fpk+Gt5HNG?Um4D)` ztVxsRyIZ@1xcGMHli&R5G~qv-5Bk()ViVMYzoO9+Bq~Rq&9TPvAwP6f7Q9}4cJ*W8 zC63xdVY?@e0}v+iZR4rar_!Eg50oqAKDJAFYY6`p$GoWn+87HJ36O) z`?17Ertvj4RcDMn#asSYJHmbZNc;gz;p@A_J?E5HFqRIXMIis>f2>|SgeR|05nC$* z{n1x#v2}-t{E@EOA^nNI(@WB>>3ZZE+-;vSpYySY)i%i!V|V*d#`5Z#eJ9~Hzw}Ma zt3|Yhmvbd}b#C^%xTve{g(TiJ7DgYzvzs>DBOGDcmbA+@z&B$c>8_3lFMG=b_i9ts z=QemHU!{Hg8f^_t02UlCN3&v>syd98-u&}_3UOEbG;}?U57fsF=sy5|+V*iW9tCH3 zV-m_@`_zrJt7GSFPxG(xL72+CJn**(H|6On@b)-w!NRh5@!~RQ$Z#Mw+!|7;<~#T2 zAChRW)siE`Y@GoJ)=0Bs>z1PA@ZN%}zjm24ky{(8-IjxLEw&vkh?^;7rB2Xd9IY`5}xWhYpo}yLXi%ySJ6u zx7<~x!dss|i%d!bzgLoUaHKs|t~J0d@j!5bk!}3Yhn=75V@4E zI(*ydaws0E9S)8Sw)&ZdNgEo784VoQ7Y;x_?TBt%zpm`xxvdNxIkt?QI1zmv7hOJ2 z;OkU*<-mHfWC6`v}z~SYmtFY{n{Ek(wjG|FFQZ|sLZ-^NfEvQnDuHGg(IKRG3UFD zX)+_Nqpty6VT-q&GIhh(i=Bb?>({I;=SXJEoIk$|9z3|}p-s*6K3q!`8QWfedp%6x zsNHdd>k9A^KZ~0-9z1ZMY+U|H899D(nK@@p>EE|scrP9TYPibB1ljT>n>qri(-!fyc(D5Vr~5wJV-Rk!v#5PP zxPM>pnlfWX88KpHXdZhLS{u04z*PK|(^jZH^@u-=Pw=1}=s$2kz8^evupB_2jvYB% z1`Hljrc9e2`LRt&eqm$cL%_*@u{;9x)3HDDS6W!>1v}2*-j8ICNr1h`$pHu)|bpQZB07*naRLWz+wL%b8A@Kn=fG_c;{#NH&;&spNJ*8{o`uM*Q zqetUkM_?xgMAt8bx5_y-Ahd_J9s3{qOhxLP^-CM&C9UFUqE7#`qpPbNKyF5lA0OY{ zk4~>04{6{>1jSKo>jw^m51g=wKmTF}xIw#PlE*hH9LI-jTDzuPL~p0goLzWpS_i z>3!O}z(u}{xlSBEUUqKXoI$1eH{KMv(SMkXtPTIOSf`!RJN$va%DhQVlT$~J9x2;5 zZN&Z#EAtj!TL#hraMtWa;2Zl?YFblmv$Zul;j!A9DlaDQ^o6~VnKR&i7=7LM`RC=} z?j2>?fuEa1CAE`mz}G0u*8^q+`FR>aq00BC&~t5;giRXqOTLm2x1y_O5In-T9QZk?@9NH z>9_n%J9woav{7I8?cG~ezyD4dG;&m#G;Ky1ggw(v*!nuKS8YLjtTN&i=r7;Y0Xwtm zhjjP6_xY?zI;+~Ty{l|pvAj&2J*SL=r+x8%>O|tX#HG2NKYv+KPQzP#_c`pz`ZcS| z;XOOcf}3xTKB>dv5E%yn{ibn(c1E3y&D56gU0bIwYcQ4n_^S@%j~qQ()_wX(=?A^% zFS;)Mre)q!QD>a4cQ zq@ezzFUiF(kf(#h^2Zo>^I9Lysq0TX{Y-iA!3WET(c^&J2;LL(My2o0@gJ6Gu*r7% zWv(OqzAd0}b<4VSUxW7$^K2E5?3 zjYPnw%a)bt1kbZ)&cx{qCgay9uyy>Frr@?G&^bU3uXJDYXRdbWChj`?)pQy+Zro6A zx#iX}ZOSz$W1Y^MSr|N_b5kz9S%jyd%e2Oh(T>tnvF$dXI*b8XL2^o`bnDGGmvJOA zYCxu98|-)FB|L%9)gXJ$D~>W+kHN%_9Xm*7940vGSLQF6k3Nl$v2zqGcPq~UT%A?x z_^Lsk_nt;0JGi!|AFvXf6HM&r+8!Q^g61=jouNaABwMecSKi#CQh6XeY$YonLIj9;DL`kRu4=d$dfoxuBAY0 z2$^Z*CXR$X07LybbpPOk56TyGvZj()8&3yAopM)S9W7uY(|%9T(4n!k24SgF>BDc& zrPB*8Ivz)bwsv)um7gsy+OVnDTvLY8hJnn~kVnB?Df$~ahUc>uS#TI()c% zj4hDY>eDFbVw-y6+u+Dl#iz=Ox7en7G`y0h22skSPS(!)ZaTcnmoG09#!oDZ7A|0< zv39i4iqJ#-ke_xSl{sltWv~XJ(!r1QO83eWM!nTnI(1#!ca*JLwv-!gSX^c!laAi2 zC*tU*6`!3N(6!fIORzF5wlM*UxbqQjDd92b=R7A`+o%Vk zm_=seN_MG-_Q$X_n>TGLJJDAYX|ra{E_3({phNuyb*rQ5jkLDC;%%Ek3o2>2dp-WC z(-spBP_^tQfw2kydKB3)Sv3>7Pr_dIhW648-gt!S)hg`o@N(PDx0K=dCkK|qGszuf3&g`` z@$eQ)aFf%@!mE^}Zga^bp+GlxTCDAuz+aK~k8P~pqH?&zlZ~%S! z40$|GqG9rsDP@O;HR>u`(`>tK(qYpnU!;u;7*l>JzKVk;k zsD9R%Tpg&fN7KvbO?SmrS3TEklkk0hE%Lq`|2mIYa{AOM8U0SoCNKH?O@(^o?h1+OJ-Nkie* z$E2-o0Y55KKSE=!HyKy9?5szwxXZyvW9?nQH-5U7M8FjKf5yADFCboG=ARCo{GKKu zfxzxrf1{iInDgkWtHD0}unFeD=jqXk~xU9 z^&NQL9JMzmn7v~>xut6x{AF7KXmw=IhVnoEZ~t1Jditp{X8dFjtvb_bftY_M%io=7 z=-KKEI1z&n9j$?Vq9zQ)8XUrFue@9~(edp~meB=lMiaBM@oY`eG*-$&V26CA~B$EwFP|jo`fm7?b zB!t%CNrl2X%(5Cxyz=_%Wh04<8*#`pX3i*M7=ayV5RHQ}!yV^iu+t4OaxBIbZ{b?3 z5ZJ<35LFf(!}HHSp8))}+ir_-)rcFQnEh``Anf{hJ*sRfQs5x8mY%_j_-n*htzBFG z_}uTyb&GE-H$ithT?ULAMuUAz43D^0A_wQtrh{wy?hP%lGzoKt*&gqG_)+=ry?4vQ zk3U`(%$=K&<*H=WkQvZeSLK-oq!#OHbnqCbiX1e&ea682^*7&4LgUegAC5!TL5YWO zO->~#0A*BY4U@sCMZ@I1!8dJ7g`t;AJC4BDZ7BINjO#SApm*JIM>3VtJBAyW8ad@h zirXgXkO08*cF?4c_;B>1Ndb-IVPNlIv}nWn4P`eSjQbyXtlWI#V&HwrwIc)vER!J+ z7B|~j*xgV@6GWe8NrKsFr)HaIh``85 zJ~7z962IsL6*wZ=IxN-|jQ2Fqqk4x8<&B;8^oXu$6jF~L|7)X6JNC8Y{GpN5; zspoXqOcvTnYKaW#-izQw<1AiI)gQ|2g6Pw8&y{m5Z&*O^KMlH!BgmC@j=Dr6LAeD9 z20iJt06%iralFco9qHgg`@ANdOa#3B>Z{m+nPuVpd2}wuWM+WZbu`@Q|J*NWlt*P- zUDqy3Z)q*>eWnJGm6mpR-+u4Cvf`6Z%6$(#ROV2JomHRp8B3=7@?6uGoaB%E6t*}> zYvCrC<2hx_`}g21UwrxH@JfA}kl^1D3!d+^KfL63J$7t@*KJhiXs62#kt2+bX4%G* zB#<_d1bFqOm&+VFMN96wi)63CO4T2q6))k4i_fTM2AEL6EXB^Z(I6x*bntFPW*XUJ#tPX^~(w{9)#(bpYa+sb4D+(m3p@jsW_uF!rw;43BIOD?Y3Gz#Y>2WU?kfpEH?Cci;OF`qZ;qWG!mK-|@tRE2 zhG`%33at+P)uSX!po1MaOWMhGZienA*}g72cke1IR;*wK)$S}GT72V;WiFi;gMV#s zljRPQ-FSxn{HbIDvd!R+^tPDr)`zbkHhA^L7voQ7(V?3=&!p*C?)$RZCGq4rag`2w zkjRa;1zfd9`ohQ-cx!+Bt}Q!Br}2%q-YTEG_inird7Oovage|y$7P9zAQ!YMfAh84 z+1;2T*?f>tAOC@a{WqFT)u;v2E_b;k|!t5p|!Eehv~Wqf__#OD~p( zpLnt?zV5pC8g(=D2EO-O+HdjioJd=2n>}tbyul#Br1BWHYz(8+E@?9+NXHU7iEZ`awM|t< zYHVk1@<4oCM(K<=XWSiQ^l}UOx`EF04hCs%zWsI*88?@KCa&N!0K?ZtoW_NgXlTEM zpL3o75%onI`}v;Fu?6eO_HEk$^>w-Z&byMxFafJQ&=>hJR>;5@_t*~Gq)zIeGnfE9 zj7jvV@CmF#{g)m?JM7>3jho5~#0KL?INpH&7|S4v z>*2*i88$H@J=FpGF;y?CZM3e~dFbxZqHOuBKF}o3hxqN6pMS30{k`vJ;A$W*e*|RH#avj*?J*8QLf}Pd)Wi2K6%7M*ViG)oF1Nv&@3wi@*7w(m~lq1b8o{@ULM2aX^m0HsxtzlJg``Of(pq z+B?t}8jpy#`mVh(9+z~=`<3V@Co`kLWfDi==^AXoD&iVvH5?(q_W6cS%m4Jh|DWXt zKm0)%Ic`$$(;KuDco7+WLnht zToXQ8P=g=wlKZwnnEvCd$9loKY-Cl!I0x!5IRC{je;JzHbI(0x>J&zFn3`kzTw|-y z<}v;nEE;5J01cEhh%|!p7(;HNrrawUKJWEUKKrcv`WL?_H!-SkCr;A@jB7GgSVw#` z2GYi&(&fk>>-3ME-_&oLxZaGDj_nj3yw?fj-hJn-^5hSGSgvQJE*+fkU%GbI$byIM z6{lLHO~tm=ZPG+zY-io0hJFuI3}5);i`hi)*)&^dNWL|!yAf) z2Q~Oq?hhO|n9jwT)vGgl@%RsZQ0{{E1`gJ15=7ZbJK=-%>1;K!!gDmjV8X0w)>m^~ zCOEP$Pq%e-Wi&^pXQKv~zCpyZ6ci1J_Hm7nB^Oa1aNR8kQkU>ox#& zRN=EvJ`NrxVQ#DPJKEMYz)$P_}g(^3u~9R(as}1QR%yy=0%? zeEaPz5pc@ry!i{tJRHLiGU@7*axHdF!}PboN`E?REohO))?uQ-QC(*=ISS<-8|uww zg2Z1S?`P@wI`TaW{4)ZJVOKV4@})Yr8aOCBRVS@D2|RfM&CEL2Zhd(k_}8+G>f!tE3qKOvc3^g(bhqC+ zl}j&&Cctg_nl>OWw%6H5jwmd{mbnD)iKm_}cafCU)+i(0xOUeQlmQ`C|6_qng3t4g z3LPY{Ri{1%_6Y)rAN}Z`p#8k)zUxZ63(sjO6AW=ww<^H^rfmUN8DYo8D~^^q5@qne zdiAR8Q#5VX?DD_^_m@e?zB4t{*CdgI4N_WLvGx-nAe-<0<@%RoATBBg*f*CS>}ST* zG6LLnt5#ztPcu4wTe%b3m~?Z5SNI11%0g^2Fr=~cR;Ch6(=nFM>G*QJo~wM>wjH{V zjNL=W&Y;|6xU;{sOLmNe)95e4O_!>?)HVoPnw#L)A4?lY6SWN=F#`C)v(IK-up@!a z_HZQA4v0aj_oj5{P?spyB$4z|zLIFbepfc>`B6J z6NAnQc%4MR0p#;1KmBQ$kG&Lj?7?4yap(?bDl+8^b!iW}n8EWBNs`G^rj{T7@Q0c0 zc>L(G#0_;n5BvkTNT)VyFd(2^c)$SEX{#XYWRJ4d=;}5S?bd%Uozm-&d2uz~GnSD* z;Q{(-k=E+3M>{Uky2ZfS9NQx=jD=S-u=MG&Pog^$SPpX|%T})8sIF@VdKT$nNmA3J zKO+BrsYMf~FYHg^?#Qv@#Cva+Pna<{0UceiU}3qISX;mAsP(1U4D5kGtkU#T`<6I> z_Evx6pbUuyDpt>JgEJ;f9z92_?Gm;{Bm$g`F^NuHf0lH9fvx-|?Hi7N?x@|T7VB*Ay#aTA`?jelaDqj()-i`C-!Dr6|T4 zZrE;oquo42|7<%6!PUgt4op7u=%d7Ci+nu(RhaGLIls5k{FX-vRO{ym{halE8kyTf zJn7)l=1rTkEb;M2A1TwPOwGWG31$bv9CUL#0OcY}!=S0lkgdtVSeIa!$kb=sue<`> zug2aS#$GKaE?B|m7)d;rXdF7YzdZTle=d(Ra65GLcpx;QU&6cL|6MxLx9@QI@4yUxtJ_2EIq2j0-3RUf(5_oaW zkI-$00auKlj)yFniG~e~7~Sru$ZXaCF>P9>YKPE7LvIAljFyN7-(ZQNbc7^Wcj(cC zUdLc(edFdW<-h&+{~lqz7pFFL$`tmm7><#?0{qX=nXV&_8tt^3c6hX8x;iv>bdd&e z-cNO~;;&Kvh!MbF{`l@V!SmX&l7g z4&G}d8a{aM-SYG^&yZ+X7gGM@fxVh3)l5}v^08{X?2~IzooZM#p!n@8nzImIJMJcz!T8sPG}GD zvX0$ALLQ_JaQ1oe7hh%5w%I||m};O>z~5)2{}znjaynhxa5{ZRw%z~WLuCO$wAXwV za4C*rcut&@3+sc4TsJ7Mjwt-(KINRYLV4u*+_b7yK| zO}O$wTuiLFA(wR;tOsA@{cC=^*3CChh?7&I2cS1Qp!Tv@f zgMX7#%8xt{KTD;Hl&SLSh_u%;D~5U`mh!G_wT{s&M!avl{)Qwm)K^P_D2|Pvo|7M* zS2hxKKnvwG4wmc6yGbnRbBrMOk0fM2eD~e*6v?SY&_z3A-Hw>}oOp%K@KtVt8lM^v z*$x9F`QbC(C%ycwd^rO9TRL^()17Ege);Eh?}r$HE3Edh9k!``E<*oIH>Qr7XtUb(B)Cq7>Z;HM1!4D*V*es zgkzxU^J=KF=uupQZx~Sna=+SnQT`oOKSKb%j?tD?B-^*rxtKj!lC%*J z8W5P$r2YeSfpOlF+QGq~NRGW-= zY(?HkdHsU4_tKD|!>l+-lIMT-J7xt9sw1Sxyd8ja0D&)m#5eX)WNE*@ljsDHZBUo= zeUW$S(w6n5{b!Jy=SWn)^~y_S2_3qH^XIeg$+*;&rANv^@CH9|6#vk=L+{Rau}{?; zcmnu!Hsuaz@{3>ns+^_+=9*fU4i2P4Dz0rKPW4-z?SRNJ0X{f~F0?^>ea3p^i}zc{ z$~9}t|NZ~`U!ltb1m~kjG{{FkIMTrSYyS9zb(+j~^!Xih=>=&2gCGC6+=<+nAkoff zBTe3f7S_jk>x}P~P86@j7J+}WP0q0Kyd#w+8eU-pc0X&UfBy4-Nix~}6WTz4_gRG2 zzURa@{-ieQK*Feymo~7bg+v53_Y{>V{ zjq09qyMz4`+^cL0uw~%`bV?mvM=`K-C!;@^`4)LZ)}XugUHp>>4Bx8^w$6KaioQyl zHAyrqi|;nk;0&ZoiH16xNR+x;01kf7?=+;xHO`BMe%AfZjxgiyjkn(_pE9Fi!i0&D z%LV9^NkfyG4h|?M&ghW`;-wGQMkKBSUR!PjbNHng6B|PNzKs6w+GQgAcPtP1oTY;- zk0a4AdD6tvk51bKZ9#PZ5`LoF-Ht%JT%J13iJcd(<=Dty5DPoNarI> z5?~H^j-+q%qaQq7#-dMd7HhkNaal6T=lEC}Z8|^dfhV-bBBm{H_V99K{zYbPKT1;Y z;rs3@SKEIgo=hAhEgLMJvA%|z_E0*jKhn~8+<`IU0(C>*?QF!AD_4EI;8*?$+mFSzgy+}}_YE@G= zNrtO|Zw(H-CDx*z=sS9=A5+Fb7DiylL;`*4O>A=reUdIKNNSqYICk=Q_HugU2R|y0 zKK@u4KF%2pTD~AIir?At4@oq9b#~iE(7SKGUUuOeTnE48 zt~<-zS+m2aBV?rPsAuF>hVX$UA+1!E#5s*ZRe`91o>_lKj84-TdXE6{P2js(pfeg4 zkpE#DNTI8TiT@DnVdl)~4TEBqQAJ1>XGB)-7ZPS>T~a{FzW zitQ#fPW{n{_5!cIDgo^dq9RR+qC}kQ@7f@Q9NH+*8ZtYF+^C_(R z*7$jkful}e)u;+!+w16bbwD-HGRy7#wn>=c?tKdRCrk(a%`bnEeFE;pxat&CQjKYh zD+-VfSK59_`Gj}br_-iJE1jWL;MmFa-Y7b} zXq(qL;_^9xkcozm2%;CUChb9tpB*Cu#27bVOM3%#X`jv@^)x!`C(<Z%&U~yK+U{8-ppkj*1Ln zbEz|QjD)T6miF>Oo1(6%rzWG+&jh^S>=bfGFy+@Eo*%?0uA@-D`sJ^ZXt<71h1s*% zIB+6s${AU7^gA6BV9PIUjb^V_Zg-v3 zV-iChP+#{kTJb3}ZA>&g`s7pPE;>eipr^^BBwWFhFaECuq{W*`Iw$IHugeeHEl<74 z1dsbmd)XYzcbJ>*_%X;ok4Dv_WBZSa>czS^Q_i@&9K0Zm$t{zGDmyY zF+y6Cj$5-?)qUT;k05t^zZibi%4@qK7Rq;XRtXY8iarN2>aMT zmrd)|XA|1R>@RUUv~dL11dRzhVF^>cub;XOS$P%js;8lKudzS1#->ulM_n7r{ z0DC!X$#SIRrDzFcl+xr)gn_iWM5 z<+;wY0N^P;9w?zbe=oJ5UecyfTSlc!0Pcb&zy9sB$y zP1UYdeNr||c2(OOn+d-96PMpSMd+U=JB+;;OW4V_^zgvh4ts zoq6flW;m#?eqW2Nap{C~aOuPii`nakqp^z5H@wBGaUsWV`R%>Z%-Mq`0-Wmo4z^$w zI_vU-*|TP6#-K}jtWV!&tS$b=Wcq7usP{EZph7;gamf}O;Bzhjy2 zzR&j*efLakfxf#x&pIdx^SW`a4fzZH(k}O8QGQpDg!vVNdd_OPh2=04@qf-nRHtGm zA%r+8x zKI&Np-JA*Y&p-KTmQ@CD5D}N^Lp;|kSK5G03=Z5EzlWc#oJSWr!f6|wP4a7IV~irs z`vI}X7zS;fjo_@_$l{+sKC%OyzIl{(^4BE>E^k zPiZeo%3SwR*aGidQ+A9gq>28(*%IoM{?(-BW5foF>HlfpPcw5_+NaNDE1-pS_|H1@ zxy>)7dDJ66wZ$#bu!Vi0*02QHSx#;&{x~xxrcaqtPNECvI*Eq#{ishVall+(CAzWI z$Q>wTmg9MFcVN=E)y-881LHIBUbTL01`tj{@4b6=mWQADCzfwMRz@>JE)Ubr%Clhk zo&56;Ni=+I{{^PS04o$yR>iss0ue-Yks*GMk?-v&iALidMo8xo$hnEqsbj~v4P}5i zKIp6lK`0EZM6o+U;gxhOF;FHN&X8!(VZQmsYh@S#|9nP7t|Oy0jwwK9h;{hx)-3!4 zbl?;CNJ5e#{7@K!H0P{Kqu>;MU&nWVAj0X)TQ+WBpM%9^>a=NP6zkQU7M1K3&tA#L zDV;UUsaOlrPdY_@Q^5To$O^oM&yN|iU(zw^O?#HGbi$5H+oQn_fpq1u3Jl!hG=WhS zqIT-+JlUuSHiGU5w#6w%pVFcG1DVjpOpSD{;V_aIPFu4W++U`6z;B9|^HiMrM8FTt zNQVHW($P6B_;seiFZ=kT^2|?uQm%vc8Uh1E+ZF@PZw;RJ+is1ub=VQ}dQ*5Ep*;6h zhtf;~loqP%?QT*k3PnT5mQsa(e$_`kZ~kThXvruQ}8w@wPe-@^@gW8gS-G=`E=9L!9xbK6zNbB4eQvQ zdE9t5;Y_08S_1R|=@`jVUwJ9sj`-Tyk_PhIjdqkBWz)=X(i_l2opSRxr`Nd@>G#k6 zj_J%NGh3nsE5g)4rGo)&rH^#-ciIDdumZJA)qbF~DMVP@?_`(rao)_P5E1jBhUET7{ z3cCq%S7IyAAagqTdC0wd6MnO~wnKTW))gFEy;ee125iF48fw~T5NjgR%}-Y#?_KEa z6yV-ZQgaf4dX`SO0V?tk*Z{GvbdiAf%|wHhe98F>(B3^7l$o|i!zOH*YseShd<)ay zZzb`@Yzh+X`Y7#+xXJ^4gZ5vVJ8Mi@DeFy74L(hh2-{$8OV_sYHa7kM!M~%%CK_Do zWTHWP6Md5Izz-S3U!Ckh`^c&Ha6{8ObwN70!P#3R9!D@pFq4jp3A{1*ZskLmm+6ZY za89lYC;o%qk;P7Z)?&g(|9qVGzryr=6L*W~xXhh9hnXaklGIR7q`S{HK8m1VlpgD7 zAFCDjBpSR9d^=8V681Yf>c^PDb~nCzCN`mNUdQ@ge7Eq8G1^Q+;b~8jz{bW~neCMR zwnf~fr{|^FT4Ijhp|8_tvabg*(ch)F{~W$cRl0ro99#y>oRfq z9!p|gL0=zXkA~YwG-xBNH$EO&(Ke|6%8Pg^Gyb+sRw)hhyTc24u8g^?aX&uLC2}Sj ze#9WbJQ58iN}H|iMq4B;BAS!_xV$~N1kNVcw6Shnw`I%L?8`M}#?12c<4>?b+o-(3 zOJ8KtRvZ)Wfv>RTfj(OLMyES6Zfzz&OoS`*&S=;~oa)Q~2bb<4f%Ls4_mn~S7dsd3 z$t5i57>dh)4&KtP=WK??N9!;VpdK32tYQ>%)B1JL>Z|e?cKAAGfPIB7IS64~r?1cs zqzKcxlvBP$Ho2y)(QeBlb=TJ~>t|Q5T~j{BM*7B?2@G1@e9O%&k((U48<%yUh9-Wm z)$q+q{GGp-{wS~6qXGCwSV#Ug152y$f#Zk=oN-_xe*|{U_{3$&fmuOy!xXmQ<7a4} zK31Ar`PJ}L+Vt+%r)+1f{qI=Hv;Xtm(N_~0lZl7>!Ot(S%LrhFe+j)F-#VCg+R;$3 zeW54ynz(z8M7aLieW%<&d+0FV6jPG{Rql-{DxK?0qdF6`$-Z#aALUDaSd3ZqBX2Wk z^&+wM-7M2ueBGkF?ZYYb+L-8d?!NR#j2oWq?B(a|QB-^8UUANL+|A5`r%8m*o<1XZ z*uJ{quQXOhF6W^-sjU=Ob<^L*t`bt55+B32F7^_84qIlT;R!m^&S?|k%(DB66Rh8R0p7Imv08ibI7v|h#sX*_yC=Sml(nR z3bb!NM7ckB&>0Qe@!cykTlVp%o=%cSINIQDngl0(lis`1RU4Z4PP-P=r4_uzPP9bB z=51Y(n~fv}O*FW-)r=`qGf1vX_R)6pw6U^-&b}nT!=J8PUQF?ypzrZHe0cn)KP!(v`9v8p;Tq_H{Q~y@;qP~~{QZfB2n5aV zdDI6Ic;gj~bh8QM2RNOr7;ZcKOK_SC8NJY9UO*UXasdGRR|G;=xzj0C@Vss%2m`_= zGtGo5tnV_F>y6i6O`^eFd>7xaILjMO!$=LT>&478C9pub;-nFZ3Qay%0n~U~t->b~ zcJ%hyF?!?mIGuS57nG^f2!xnkG>lHE28<_?jm~S2f*ok40V)izsHN4UA|=tlbse{# zjRc>+{M9e>`lNgAVMYU;X%h{0{^A&bp>jkig1bf#^fY!VO~aRS;#?J}8WE=sEoVy6 z>lmo(8MVKaX>`8o&mhm>Ml_wyTGudEe5>)ShBo*{(XFN`r_NggCH?J`zDlR)!w=ps zKmFOyvvfj(ph0s4Swn3b5?s&@>EN@{I~^|qnBea-Iw}a}$g9u0=6gFz_vV{#<^8fx zk!78V({Y5*`)bx7@nR~K^vI?=ocFpXbY7NZ{K46C)|pu_Dl|c&+5h*M?zRA@^Dv2q z;U*erlf}%u7@O3Pku`9s*?0||G?ak0DLgg!pb|TrjvR06+Lq~7dl~g|`lU&pEVnT@ zr+v1O2NF<(=G0*zqM`Ge0fhMK6buUOuoyfmqg%FaW8=Ed%64SOS6JC8b&rN~@LR)f z=PdY%9dP*{XD1(YdUjl645^1p-StRQ-wLsO#mcgrb>AA#X)|Y)Tj{vC&jAkyH>a){ zWGcUwbXb67=h_agG^usg83OX;s@_+Xp~HukgLLX%f1NkbAeUpuj%UNhMOixG#z`kw zqb8qxdxVG?uvXqeYXF*P@OShNaT zuZ#-Ek8MvI(*G=eG3(l(t7Xk;KN z{iTJSDeG_Ll=`?3Br**^)e-N zf`{4$9i7E%+Aoe(-aEF3x^26i=1rTolviGUsZ61>xRhYR{a|YHtOg2#4FjOOaI|US zuDobpS{syEg9tk~>Vs?T?XY~xNS%8$JW4R(j0W|?&Tcx2;A&8zj0VS`YX7#NLisU{@iV@=9Ct83Ce8g?vq( z`>9NwI<<_$zv>6{^ZF0#$@9?Nz_TUUtw;J)8%G`d@FV`(`4iZHw}AZ_9co_>>Aou0 zps(6_{ZQfoVAe##B{`R`X^Y1W?QM(6&94#rY{m)QcI??*UclBIfd{wWaYr`EoInT6 zq^Fx)w<$>)|50ZGJPLJz1ZDx7EOXV7tWXMzB662tWI@N4g z5Y3+|x> zH}lw`o;+=OdF+vgv!-0%=gs zP5m}vvZZ(3RR*(k;tcTX(uqonx-n=&8zejQvGU-}m)Z^oP)OXNcRT1Py6NnOHEUxx z?HKunp|8Q=FtaJN@5U~WpxPg4-0c1p)qiAA2E5gOi?+aJS}yr>D)xKC+NYV#a}Bgn zE~ibI5?|`9152Lj;3}QM%x>hVx1P)u)H<|xGe~DNy!GxoWd-`=tC#0u2TVF9p=?}; z{m7m$;H+-xPwjYF95l00+7+qeMtk))dagZ#{#%&>?^4pT{`K;d+L#> zb)yGv?R(W&A$J;PrJa&Eg}Qw!g!(j$aV>hN zeL|)W&<}BA^!+R$e3%)m?pG!b+FNBh_EANl{mp(!UqOZme0^le@0)7|V> zW{l@Rs63Tt)o*BHs;>}~rSVl7YNuUh6a9cM>bEl;w{7FiMGO+SEcda_#wzD+ zfp^$3@${c{N;7R%?7uj3t@&~5IRk$7&sMG`>9~1w8O^?bj}RNom^zij7l~wSiwSp^ zO!#VDW!_EAl?Mm7jW6mRJuHXD-b;UV)z?`18qpIZ?%rdN_JdE@4~=J!pFYWJGl-B<}#i!dxf7-yA2D=Kux$tG)*zhi|x7 zZy`Xxn!1%qX`2osN7Y0bbwt?LOX`>mBy`y7fwXetJ=bRY`YqeC6`64-_%8Hm;2>u- zJY3h5UgRVO4q=86(?j2W`<=37Eo0w}{UDS4JcN}ps*H|L!|UjLagb>1NCB(I6b<+fgD%?39VfO6OT+rX^*> z!S)3{bP0{P&uQ@Q(;0P-sA<#d>z$ny=TvX`tdFu#Rh19m#7}V)c5DyGOLogw$WE4P zakPG?8^6F?Cr%tXT<*BzPF^29gJmD=--O(11H~!)6E|c%vH~3GZ~Oh7zplwZJYMIH0ExcORC_nUc_ zfr9Um__}%V;v^c>Rq+#FlcdUwb?QHpbcs)g-yOJkb?&LjPHm*tO&|0*8#%v4694eQ zL*<9;QRIw<_}HkMSrIKGT2vcgs(l;UijN2i*0I&hN>6v8`?Xg!H$cGhOJw-mfP;SlYz0j z$`E3~^Y|2H@+*Cmydrsi;VWlwx@j@9T%;YgLfKC&5+0H0vh?G!mFd`5 zGCSoFW>2~CAp*&()J?QI2xTINM*F;R6B+fZX~UH`(RAjaAr)17L%mmC&Fo(Ab9Utl zeD{0k(@B!{Q>IQYZG&+;>c$y}ZgA9AT5P*AAHC$9GO169t&vUOBi`Br_h@*RiH4V6Wkv(Z7~kUJ>z!L7UP$Vzbyz%an<~E5 z?g%qJ79M-e-~5T4G3MRUwXM8>tr?9TJx(IS*LPPNiB3X8eTe!eZ7tHaJ6THm<5Rdt ze3d6@VvKJ*xfgzB`5-atZRnC4qq~1a8wBxw?U?|ytd;-(KmbWZK~(o^(;WD*?c%BJ z*G`Lj+6y1;tlQ>u7nnJPEpR|`6-zVx{vd;HH!Pwb!u?6^$Wv*}e`Q8W$DnxdJ9SV| z?71?i4$1QYBwbzRuz|r72WvOcR~SETLS}n7qv15|xMZl(+IiUTSBg zwe*rl3c4FXwnW4GokYVq+IZqDZ|m8=ml+K|C1LUe8*~2ui3V9zi`>#O@%fUeU=fNK zVZCuZ??zQ`vKi#AZCzz38J{I=R;AR!d&FP-!wVVFxsi_1SPY0ea;so5e%xcx;rP*DNEd10_plIL5=_trr&q=xKqp_v z=SG~%$jE)4DN$}-r}Oq%ow-Q?M`PuabxD^7U*|7Rg&RDeqt~RVzYP+6kNE2(0u(Vv zMW#UemZkJw9g7A~1Fb^|d}T-4V>~n%cESu;bPlb}?#^sbvV}n6Rc3q4BSG>An|Ya; z*C9${9hXKg)BypHPO)=#j54GVOP~sE#4pB*x*g@%$F$MSTeoBy|B+)y$`TR{ZVn{e zLj+z1qV7r18zbaQ7S-qyLUcNHAIeYfp zvgGc2SkFH(qY7tFlL1FR&SMyR@k}pd*}zD$Ur7LV5xh^IVpA*r4I0F2TH)upFWC2@ z7o+L}u43uL0TNRml^vV9%IIO^%1qYS&Y13N=Z4W)#^HbETO z;6OyZKe!_Az578cf|hfvvDJ7pE5bcbo<*NdW3(6GaGZ`kani)dm9{|VxKmTcUg#v>1416j15t z@S+z^I5tCKLBFs4@cja+`bF<6%6>Kjdh5OS%bMk@%6)h8W}aCjU#@)Xrxz|Ddjo)XpgrKIbb*_u`19%~76lvmtGnHcCCQ!!AA4 z)#wy*se_K(P}kSUP?93h$&!6<;H@K>+8Z}~+CXCMT}IQ?r+bkZ*Wo+5ug;hx)6OcN z(y7@HbzNJf{54yw4l0`lBidQ*jJvh3V6<-S+BM}qMlgNXw+UE-{EI9<_!@n*BjHDS z89XA=FFIxQE5lhweiYG zvpM1!9Rl}8Z_g>~1}ho;g8u^t4}cDRRc%de2MAlQqQhx0+*|BglPM7w*N`Si;TRd*!glsnHC?+T*xuj2)=E_b2IpC`YkW1eayNryz;)LyVz$QwmVunf+Z=qgogFxJ$`RXM zBsN_$uD#VeDd&(R_TM^sBWD^Tr>bg)KmK$XzI$U{l{a(Rj539#6T{e}LHnJl-q1lB z7(k1Ua_5XA>E9ckqy0$=(yGw?B2~M5#rk)`Pe%dI96wp^x{E=AYo=srqH<}+%VONo zbAUiP+euNbO(5%slJFIGZ5VV{wp`o33b}dqx4-3evGbC+GkMgDM%wX8G6VV1&&to{ zua!}MD_4<8Y1Ju7&U4-P#o|B3lkS~ZZ3RD^06;5+92Pd#;lc!9L@1Dl2fOGh5cgc^=fQR^6OcrL3 z3TSPjI>{dDRt7;heAccx>VJedZwUR+5yh;S$WZ~x(}LsR(E}s;7hN(%n0~CHg%t${aSqMgnmFfCQp+P=-A2l(vEGg ze&bf-O?`_xZKBM2v}4A`tJkkDzhO3_a(WYkZquhv=e6CV1M?)apXHs25q+C@EBk)( zrT}Q{rsVoF<8f`T`k}8F>T;k}9Dz`f4&s`?qf1YNpyl=j;` z^&x&n9kIX$2dEAqm(OEsHj@DR0fTzJ`dYq3@6{2Wv%RW{bqZJ9GHA+KWzRl>dX)YR z_t^&VaHh+)F8d)YouJ?JBujnmKk1*elk!#Dp}t64d1ZX+5@bX(vsC1zb*jJ0p*koY z&N6b4pd}h^g*Ltw$-Qg>Um8=7@+9rG57JfNr@p#(i8wej#y68Fm*aZssM=Wcf1fwO7*{^__QDS7hdXw zG=eHo<*6eIud@5|28<_(w!xqn>Y#*m>Xk-!4@&Yj zQ>9e|mwh$8fy)B!(XM8FJ_btsx<~01?gp{bS1o9Mgw()oKQ3OP4N9mQ_P$-Dy8Co7Zdni(7h9*z`f zki^lp>iE@%I2Dfa+D_5dEnAb_Hh{TF=<%qXGF)frWJ*GbeM2!jsI z)VHe%<_-3gnbQOwTUna1b;G6@(kWA>F+xg$ifQl$d1mgN8v6w__!@ljsveUK2L1#| z7fA-3MlSS5&bH9t8pwRv3mNUh<~`769d=;LoJ|%+@LDBOGv)W^Hsl=1jSlb~sk26JN>bm22!A6?y%omosz9MR3A+=^cF79hu^^JMf+)F?2P)VowSYVaPXvw1~(3Ti{Ss**;D1trT37~99w0U z`)xaDrqdXmQYZOskn=SS$ld^)Q)awRzStJqtW4Os=pry*!6>P(i@lM=nwyuZXX=ep zX2r!B7>@8IV4+^m+2K{bE$VFD2c#w`oqgqNRrezEn>KCAES{V1z6)D6H!w0a8hiLP zyfHxZW4i$asrVRNfUu{MWS~(VeNCZu#g3(R><}|;9LY53x#PAwSl2u;zC-_^jW-C5 zpOUV8gr_ZTzR5b`PoP!o6Gz)@B15>F!TlgJohD3~!i>8cvaH0mE6eeF92>8+f%4D# z#9uqzW`|ji<5rGhy8ibFqxL2SKi{!4LAHB_Or?$l=fZ}b%C@)(w+1~mn3Z?JOEO3h`B*Eu=l1NjhP6-t3|mj+I5bY#^ylNF#Yt z6Aip75WXHddN}WI-$kc)A{`c!rQ_%nsk3#|75$UWd}6zSQ2h(_1U7QY(Y9H{|4Vc= zuebzvlRWRUF8e$-Gi$!bjtkw@jV#9!267{@)P3bbB=tom-fT}24f-yM>w=XTd14IW zvXxg}da2C7Kbfc=M2E|u$e`Q!Lmy?5Paf;zA~zhBqa{;4Udo4^HWPu$pY4i%P_KhI+E)_=d+CfiGhpbrQ5m&& zj}LKBr}a6~*1-zfE={%ZwoSg9#4*7j4L!=6NE6?Wkuy~-odJi0h336`*Xio+1+$hB(gQnor?cVP zz-CUL9@#oca@_W3#sp6atH!$|@)3$&CK{lhaJi^sr<0`Y!h7OBJ4oBMb>UyvWRSpp z6r9~VfmwI@?k{+&lQvyjmd-fe?Q|-u%ARnn-#uWILF=%CYAmh|*G{foyRK{?-t+Qo z1~(Q#8wW>(pIMmV1`pI9@sB)lZ+OVjV#iybZRgYtIQ6l{Apq5##+Fjm^Q&T zMrq?uA+s&fkbwy0LjF-#W_v&zXL3p}lNQF>%A)b4w6RUA*Q_neNFpt|aWOL~XQVT& zJ|t#GCbYe=zv>Ymag;{t5ND#d)|vD2S1NO#_^4wpMcTf3b6%h6Y{b|u@QNMhKJ{9@ z853$x#ZSES9VR)9@$`wxzr_Tc#rt-%#P^L?*((RzyL8Et%z|ZVqmL_h4_Ul1-W$6P|LjvpN82wyjX{+C z%#T4mLo!qr!dtwk@=Q@4bw9wVrM_NC12c_auWz#k{+4SvY z{D>@am3^{KMW+Wd8`0$Fj$OMGcWmFbjeRS|mV4QYX99NqIEg&>MDmR&8Jsar0ypCw z?XNN@%~E7;s<&-5iS10DlRUp>LWPTf1~0(}gFIA_A7Y@+B?=;##pn|;&Z^k-yJ zM-40uve8(X8-Jq)aiJZLCw16?}t!cfk>zJdVrYWE~KTaF#%ediE{ z6|&$x9GRrkK>&a5E85)4B!WRF4&{Q0DMnN1B=>iEs6jrkTrTD8DW{%(P4J~|nF!F~ zIl^ZU>T2{sBtQlcNa!HtqcoK^IB2fQr4QQa_{C3Iv>4nD8qhBr2AxJ0>@X|uu}j=@1)W`&dmv!tEJMP_A&N^& zU~ic`lw?%@q1=Of8DN6jSMbJmKn7;R*ug`N_;6D>3*FCBcYiE9y4c zaEj4|69h8D(325Ne^=(Tui9}#PlduHKoSc)s~jnz(kn6o4xW=g;Stw-%R*>M-KUjH z&JAJq#-I_t>W{YjjIsvK>NbMY;VCv0+yIBH6NvJ>@rLcS!zfQP($4cv0d+5*<0nXZ z1AqMZvFVH&IQ#LOw%2-WhR+&&D?7qJ3yrlKo{Nv7-O&+XYx_?#a$z8>EpUbMQ1rY$R;i~o$x~%h zyjcGW?gP*h?V`5g0yAYGOk_%aivL9q+C19$1wrNhJ$u8~;n2k3F@ZRE7>HY%--~W3 zAHdeODcAAo+^cqYP8_69WC&iI!Cve+d?dDJ*r<`QGj{g1iN+E>ugpt-+dGiXu$yhm zcX{ej=++tELS1&|l?6LcCl4Mf$4D#<0p4KXi@W+?^|7-Q37n;??e7nLjGy$Yu3uJv zq*awITETa90|SylB$Mh=VLY9eOzlTUOf>W}fxvy*Cgsyka({SkXI>&7rSqWwc7Q^C zO;3|PM_|* z7N2z#^dfkjJq-?UV?>{Uz#oOoV1x0S>Z3DWoY|u9(=R9s+H?t3M`WG#U`&Q>V&;T? zDzk7fK(6gRcjQ>&T5BCPXgG1x5IXnuZ8AP3C~dnsD*pcK1CPKqzUeHnaFQ6xBJE1D zfi{>ZJjI~J@ngJg2G~+_aL51kQbuT>a#;T%XVQpz9Gr2+iufMKf1bb=W|SA$>Z&~U z6W@ys)|Tnv27uF0lKARP2BM-X)fRZaF_WDzzeiT7Kd~A#)GnIbGfua`&UEsvQ%6ah zf@v9yJoN4)A*4ZKvQFnynODDt;eXXTui0rkCtbLPxJEX8PC3(-X`5Z%=VsK}$-(Yb zM%@|2ks|5@aMUHfhBn6W+F^Nl7W<-K)MKd+&7)a|a-?1z$4(vruOYN|AU4>MYvorQ z_#gSQ{nA6b(Bh7>*zV8+ye!?ZvGUn@)?|pbOxl<%b$`0E)TJD_+*mvkbMu=@;~TUE zKJR_n0_$z`SN58%GG;hKLhvwwhwn8TO{}dx$!}?r26NuJlh9OVz~9$8I{WAhxG6j8 znEI@*lDF|!QVO}y2OfgI!@+wv$s>7Wo8tqaZ){p(>`E`~jCR`i_$&P+_iJ19Bg(mZ z<#19hW|hU(j2@YOj&hJVj-#=Gw!=5km{?Tq`$9AOHK*_~r?BHmPEn^mLz)`b z$uwpCBrG<4^93UOGOru9`1&ACSj_b zK78O%Ieebid~(0(W)>rsfBo10qx|G&|IFatIDR!*Lx8@+?pQ4TCe5AH9g$kbm&2IbVb zugmt%^>*+XY4B~uYvNKvu!0k-WhRGdH{K8jwrd@0fogn`i&Ob4t~>MV+y4l6BA;E~ za@qP8&z#CmvJ(=}ZCJS`?f;fr|I<^_m@YGS83?Bi9J1|0;tM_FU1PFnYX5hHok)gWdM3}h+9K&G0V zE-Tir;>xA+{ke0JvEKRF>T(Fm4ZV`RCnl5p8;o(M5$RBUMQ5rPued{x&cN5x$9I#k zBIyEAhfSJFFwa!b^ItOMZqt9T2lCM5R;4I`Cf}7W`7n*oH4EoKEZ&N8>O?uZZ+qFw z#c$I~lLa-m&zBx$2H(A38^R06x{LC@09!MZnE)plE&Y7^p2(v-Rer_kFDb*gN!_r1 zVai`S|Gj9)n_NfRGHuv0_xpnZrlRMLI0jG5r6d?!Du!s;&jxL9dD+D$=A13St4pf(2=c ziVX{Pv1{xa6HSaplUSpPC9$Ab5F3JuAV@D35Cx@oDI!fk>Ggfz*z8=Bo4l9zyZI+e zH~XA@)}Cw5F-LE6pL($;k;Ux@#QBRC#J8)LkVd*^DuW8+&6X4`TO12y$p7MU&eFm^ z@=$SO|9Z8fW}SU9k~m|+mwz|6;&6NMgM9p-;bie1_jflCe)dm@UB1(_X~U?3!)`fs zj9<+CA8M7yxCh?;&*+qoQwF#{|0qMGlWM!`B<09rqAVKDOJ~lEIsa-P2m2?N3Ysr3 zl?7kL>wvu|iKRvAtj=eD$Lk+)fsg*zC2k7RpN{QK zjjNT3J!>`OC+3dqUOabUj_Kcidi^U}^`2_H{JZm5%By&ZYc(3vpQQrz^(dq3mVFz` zSEE$(xqMEVkZyk}d-(O=x|Cac*Qgd%Yt%|*{JU>v#nLr}en8Ulzk4-=!I!OAit>YP zf46Su)~Z3>*t2GBN(D%<{c1|`J7vH>;_$!oEXVulJ~d`L>+OF?X3>2Ie;Tz3bsv;G;A+8&_{L&v>kc}BXI&Yc$}*Q|>wbe-41vjeZ!wlX*kO3{x=K3bgM&SxCcpe9D& z##jRXu3VMO*gfjT`X5%sn(x*`?R^`OVYfFKX>2@BjkP$fS52RXj9Z&{>Br@(<1DO- zV+lSzaq`^%g`eV{k1XoAJ0F{G``6els_$JVgJA|8rcRjjcQjGFS9%w=Kjl-!zX{`i zg~Nxz<9FMA4{)Ar9Gn`9=gj|Kx~KBky;6shpZxTaXDBPA(|?@5a(Ca>9J7kfw2~*M`Kk^Yj|7Vx@xoqbj_62eFIq=}b)iucPFXt`%o4nYEdn#3j|0772 zB6I&0PiR_&-Yjd#3fMWO{IST(k3sL)103;~(peL~j>S9gDZU}nQm^=Dx=8UJ^?~Bp zepcjrd+~FN0}mi*Lf<$}<(NrEOi_k9ZarRQ0PK&Dpm6{Hx|AKt%p%3s+=PWN!3*jeJTsZujM>v;%!m=$U~b;@nNfoj_1g3b zD9!h_E&4qc@vK|H4m*2N};4FTF_l z0?G8Csg&!5(ray$KrfrAb9$cj?&r#WhZ_}*D)w5eTuCfrp z(zECoMvAQ~^Jk;6dL@OaURdYs&;CuA3e<1ETNYm^PRumM^o+eew(swR*kS+jX<3{k5eQj(}3}ZEz$n) zLrL*%M1+Sf)_5yD4Z*pK7tTxXtYe51!rJm4quIj4G(h3uJ_|=F#k$aWbLYnF>9f)S z(x%N3QLh$#1z4Y#_heQE;~EW4uRHjeSu3ndxSO(-Sr9NRYuQXSb6>36n=}8L7&CNK zGSBAqYEcStFlk_WFe8eIj8p>obY#3zAfJo z|FfAHI4ZpKyc@+c!XSN%$F6Y^IAa6D&6~GH^QMinr-Mg3xo@6&p|@PTkhf%i68D$y zZPWA39%fku`)Y)8BRC`);yn#u!TL?nyhe4J zx*e1yZ+R~?$kbEzq^t#2nGy>x0n7=zlp(-gnET@9grgC%_3X=RaAqj5sftF}d|#Tq z?!$4@$Otoqgtz-+bkw2d4uVTIZ7u=7gF6>8ewcq|9TEw*oWq*g$unleq*?Rg zkmilRncA@z^jfK01?Z^2M+&m7fD6J*e(woEW`IeTDYIFm_+z$;hPJX+{%T|CNtC(l zfOj-*1Rtwio8vI|NH{D1gr##$ATfXO-MVODVhLVmMIsZ#UFVU}QubFFXSw78@Nzt` zQU1B7cGUO0dP|kWIlu3Bg{w8xc1TzMFeTm$JlEsz;;#E_iH6F%@@c`s1(g3xC$)G( znC@S<7LIP_mTAL`Z}e0BLs{ZDW|296=eUNf6?F@HtJL=j`~-(ISxq)uWmS1<%({(~FPISlJfvT7Rl4)Jvu4hY zNn^*y62@qMc&j+%0D4I=clo>fWX43|9c%D(g(|>JzK~@E{9PGO%s9#;lf*N1Owy&& z*=seRr?Iag~Qt3ZZFM;AP2Epd-=7y^>B7FL@VcmO`p` z3O8Sgzr4Hm;{LQ*v*Nu`W1V^&xnGkw=)giLg#8GFiF%XxXjInus2db<+_94W8OJOS z=all0c}VZ-O%o}#7(01t8k~n7Nr?`y5wFyBi!>rQovY3rk8?IEZl;rbCDZ-6LB5ta z%v@ZjJkRWek13y-w`^q`+^{Y^9rn$WB+M{SA4;8%d!;?~J>|Fbp#1VP^&88-+-q?s zO9Q}NGu&)qIB(&?7(MFa*bQ~0N%I!j)4|eX>BFo_X~k>;OA(x_%^xjU^N4hHZE39t zbK&d0WQGB-T}4K!CmPJ1IVV~kdI%+?duOSI`&TGuLAPdn`MVk1u1R`Q4$3Q>yRuRG zQtnwAqE6)8rPswc4?Ues8>s2NmXcRX-CBBePQr$_%tTp>ZdwI9L4M@56g@rR0<8)g zOVz}A*Qnh60oW{|%;l>oGdO9daqQQq5t+n=-fZr><12fLQGRLBc_to#GXi&5_ZNk~(Fcyu~%9e#kTYzPM0$6?lVmmVMuV8GlYZ z%nUv=c6hcWT{EUkiLV!MiV{JaBaS>OYGH?XF=hA$^JlK|bmwGwV)6oDtqibVlaf|? zkjB-~3#Bz=M;zcw{m{}&HwyI91Y+=Dn+U%{8-=`yy-;;oH1?c#i*Ds`~fwZbKZrH9E%nJOEKmR;#y8m~M6sH{5hI5$DqN8(T2n+=n zVdmMTnHI~#RP1z8cu8>oqYM?g<4f!+(+W9>bOl0f@W_$z)Jw0%{=1fllh3(?BY=*~ z?(qs78IlG>ru2ZAGFOSSG%3u<=y;w?N+cA)v#}V$O#uP*Qk%ax`t=_WAAB@Cy0mE> z9XfQ(8h7jRSHc)=tRk_>@%YIZ;xFbXi!t2CHpKnegaQ&bDaw1i&}3^Jc&HaxdjQXpelPU_dEUwj$Q_39nn z&+ZzB((I=OX}>CLx$Q)7L6 zoJ!~T6v%E1a8RI|j%8yyA@3f$o`Nu7{xVbN{}Uxuj3ciXC3>8!HQCgG{Y9NX;Dh}&2%?z9ZpDWU+@OvC< zLx&HI=U#e&Z$w;8qau$At+B^moMVqbL^znz8l_OeaTS-Q>7n>jg51+>8<^`>jW~pb zbyj6i2vD|cCbSKDD^V8JS6t5-;hk2 zJ)#_&Rf2s~nOhIeuce2@#!}EFbJP$jy@l~NYfu6se&5dX9XFo^d{(bnm3=_Q(41@1 zyeZMKT?bC^z^O@H>n=DJt;aQ8R;5Har{f3|e|KKRrgSQ);*;_s@dm!(dwFWI z*Fwu4AvbW)fEe=0mvIdAblzEAIc}^$^1w{ZM!DBGkypx>efJqfLtbS@{L^`ud>$MS zM!QubGmJ92!NZ2eBhMD->GBJ^aeUtid91T%`b_m&%@4Y03-0ihD9lOg#E`{+q2$EiL(na#Nh&S~k$Oa5o0O`T#{ zE6hHm(IO48E%JR8bN5|Yqx>_ae#~d%w3*pw zreh6yO$8mi5l((z<*YAhOW7)~6ldIH|L%Q-{VtT>NUyW!&5bc1e-dBMnjV*5+C3fl8td86 z7`W&0-h5wPQ4~7vhhyQ2sZ2Hl5vRO!@ljed5s8t)tr+r_)%o zZt8a8qH9cj2_#SlbFPkCsj?AhPPxG8D(p2toI6vOi|yp)8N@ zeT7r-)t7q4=VbaE*0fPvaKQ!Xc$7CfZ~2WzzGZbzl;H}`Ebb#P5DC>ely_be~P@p zX5Isa42|CJeGrY9*E!c-6>ZS9J&j15Ro70~GjI8VJwl`b4S9`a_fq}P(nR&(3@N>9#Fd=cl<;Ah{ZHODJDd=j64zm6~OUriQE zHZ!I7+sI)<;{5Y3%ssUqh0bQb?|9N;2FF-G;49E6&r&wYhjq+|2RbH%k37>7^Y7qe z%D}! zLneLob@c4}eq40wDbeoeHrd0=ebS*WjmRI+IFmQ73);{?Ru$K4#?(6^TXmI%jlvVjC{9OE9@NA-v?rS2RBR(1u zi-|_;O@yFBn`5FGo4W;r^G6gb4Je6JC03;WknD$3F1y^Jk?_qJ0tx~JG&knEO4I}*jF0^3 zN%~uCjx#tjwoU6J@SxL_4hF5Ut2bX_D|+N45*6kg7dWe6NF;u)aV>Lj*VbS#+8oj2 z^&WoovAFsA>o|t=sHlrKv8b#l6l8n~@Qeb$G;)5dLq|?B02ri9Qf4NBSo11lv?1CT zC=>6~-0FLrMOR*QVYH;fxMQnusPrg^6%aB`hRiui_|Da<04t(CtV7083dIG^#>pV7 zGE?GHBHz#Scse>A-z6^Yc1|>6PZQ24D8j~{t@lqx;XL`wxhin7W?1;}TopQ0v1B6d z@m!eSARGa&_v#U!&siQ1+gyo z5e!rHnJkWsfUn|>H(rmYz?r(B^&@}zOB{-7#6Pp6L2G`=;CA{26=A8{x z*&C2H1?5(1J{8DoP|k;s92I}~)lD&#+_bYWc(1$q$~d@r^YpChW!0FKmc$vy)zd01 z^RR;9%ibC(^w`c-FhuvdEJrR{Ua_1y+z$qP5Py84psd{1y?b;8FKgGVjRJ^*jnLXa zv}r3T45iB%!K4lvTrEK+!^R(g*%k~u;8dy%g1;<6j+9d!M_bslGUa!P`3o0C-+uj~ zFC|yacB>n=|K_&n)UF+hQWd=JlmvhpIw>>Cpc4|9?Fv2_tx{PRXB2SG*}arE$rGe0 z6_-ywpAf%&;KBHO>WsMgB8<9Iy2Qaa*sPD$3$1b@_NlC}xw#+iiS@r_q5U)}_}My3 z`y{X!GBZ#@x!n_M1`it%cieezTzTQS(f-)ua11t&dV7Ds&%E?9`%p5@ z$AQ#@XjC;KBObSz2%@nIo-;#eAKC%d(o-rJ;HwClPC=e2f0uW7&w>RDW5R^bW5}@K z@jOP|LwDX0o!L{Hib?pcx43Waoz4XLP4X3zRTQ)VJ?D z@$#Rajx9t1e}CV7@X6MN2rUY&`zaq+Ntad~C+7*RYQX5|DjG9stTS)-+1^2RrS_zq zUcFz9H$NDLL$hPt06n#6zJJOK$Fz~5G-?g5jt1qMe4*&Lk|(4B1K#Lp@OdgMRjcow zPM9~}c_(i8&2O1y#NBt?5*J<2tTY8|GpScR={b;9vRnMdtDq(D!Th+ribIYe@5k`FQbea{YANy_{9EK z0@g;8q)~gyi1*8=l^r-_Xxw<$Z*uN;-EwW5*7@YvpGc-rBJtRLOFUuK&R1B28X2VU zlq=~@-9bK~%wa;%0{Q~9I|pZVueaZc$DV&7F1xU6bUeNtM?xRUX+*no)GtmLoIJ%- zri^Hb8^zu@o?McS1|p;K8SyBMFxH}CZ8JBs8J_L=GR~rnaR!d|gJ`5zk5VS(g!F0V zWHk)n9T*EMmM_nsgpL5`sxwLD-y_$=84U~Nt$SfMg=feM`-dNTFuKyUyi?n@G{tUA zn*LrXmyEimyyt%RO~qRIEZztoFKJHtD>xvOyOgt_4}D8?blQv=F#sKI?3WYbt~-97 z#`LaatrbsBVp56k24s|X;!NT=d?8sUV|fIx{LQ9%%Gup8eAHFGM*i8P_Nk|yjt(6= z$90!?XHOer)he6NU6`}D==7X>(eb1XAl>T7=1=K(5#L=?e!xGA3H;b#a3Dt>zdh=+ zxa<0BqZ?<`*T!H}&O!Oflboyla?F76C_$sExsTAAc(fhI?{>1@gjQxMlF_ggq?cK)m$&8wtb5fAgC-woRMlcRwQcP(o(?f_M?CQ4g&)zU`}OZ1m)&q{&i&TQE{UtJxPl|C8^>mNf%^7##+P5(t3a5# zx2byo<8*W}w(sH%-h$i@pP>#ud)~Zw4SM=>kDhTbto`ac?vGBLI)+)e8=whk$hiX~ zo`EsQGvo*I1s!MZyC*lO)5{;^Yx0=V;89t0{Yg`&#siN%9`6nr7FV2mTAX&~nVBgo zKgl2i{D3c}QrOpo5cMr5Bw6!q`j4y6X^64AN-BxDV+ph5r{CHg8L(iT5mDwmeU0>W@zO9=gr- z*WsLEPwQ|Blo=h4t&Zru>c2W*)Ctz%{Ln!o-l{v=d{rJ`hJk#t67;B%ZBTF0*I&o$ zefz(y7@t2J|$hS~ ze;f}z^J3g_<>hh4NuBegAOmB{JE5Yy6DG-v8CP00V?-N98LES@4E+qW&CDioHf99a zpmrFJyVv`?5>scbjOQMH0KMs$JVi+!FRyg(wz1xH@Bk<0Z6>siP4#T)$9`_?m$bv*XRAK8Yq$0i7Fln5A_8=IaxltdZXV7xjvU3Xo~=A)=$<=YM!Gj;vWZ&cEs=m|v%4 zAQHFAn+l5Oy*w%Q9Yl{jGT8?S4dePm7aL zggo=TG6=PC^$)4I6+l!_mPKfpgu*~&T!qT{yEI{`H_?cT9fckLa~utiKmFIJQn`F| zIpM@OvgKiU6r0fn=V%(g%7Khdf$N%V$Yx_D$Cr3i=2YG#lvKoc_qeP1q1M=l)9I&d;&*Ai4(Oqmw}f;~ZoFDh77`{u<`@ z-k`y;fDD1FF1|Qg9q3uZ)nLFxNnxg5*@c_=tL(^VB}m5+Km0wJ;Z7k}g8lZ0spSyq zB$Sm=V@Ahc{`zcmJ>#sn5a!yXL4)+*^37D*oLd^}%wMMAD;bCz;<`{$#1+hs#2*!C zkByp#0y=c~FpfrgGlou_84uk3%jnYiglx*Aqd^9kDa~w}=w_;$Mx9YS=j|HY2h)Vh zqR?+8b=K53JESY5J%aSDx890}U+Eon`Tn0@crK1_b5sgmBWW5hdgl@6>G}709&_eC z6tWN40b#;??aHn)D$bOJk?WZsK5BG4cHbQ_Zpp^Duye=w+0|FY!5F+*_JPu)GABLd zrn(kijOY3_NNonqKP3rm(R zM+qGjV?G(h>LdPe=Wnv}ZynM{D?oQ;F%(LGZ-*xoGrOStx5GP6SL8ZGV6|^aLtce}^6iSHv2fLj zSo{Nxuo%z1D9zt>G)QkgM2huDC->R&qgRvWy%+<)BkHDpJCh@WkBxm%5Np@2o!K7F zy(Ij=BkSDXOwAT2p(~gqC2i2Z$^$%6T3xehP3&HImpr;@H)`5Tz?F1`8;>0A2JuwS@vQB0gT5xg93 zZx{vu06+jqL_t&)&%e_*etpZ$(fRncq>&dI(wSMHGc$oJoSCn*Z#I|?B=@5%&RXeL zrB*&ETq@&WVlwgd)TtahI57IY*(+9UDG_)6@|STmj)vWT-?(UF7#yt&fELM5uH66pYr*Hjq3$o;*s>FF*6!t_nzP08=uae7v~;- zbX>jD(IBa4xTNfcrn12o_$Ysr{*_5aOWjZ5qG7E;;qR_Vhrn_iEguXS64(9m*Um2P zz5RyhddjJ>U&BUu^sb6x!LSp>#Tgud;*r|{46p!D^uX0b7$(HubXI$c#0GfsERNTE zjckucdb}8yp3@~x?9eHW0B?+bZ)EN}a12`RsRK{E5e~`+ar{U4tg=v^nT9B1>--g` zRD7lLFOh%G;Aq&wyIOC3=N@)RQV3>}=xLV3A+tX|`D zT&HxUlhv`m`DOvI|16$)>d83mth1v7!Hvck>qbe_35D~*y-Rt)cZIj~>fEJGv%>t{ zJ(f=voej!-`HUxf4IDZwMot(Px8Hmde5_?usaQFklZi9zso7Jda5R`bV!*?IKpLUo zy7Gjl#WuD>TGfbAIsXx(!;FIw!-vOnPd^_WJ9mz&FS#i7!?KJe|CK(yq*C!N9ht1b zZS?47`GW{s*n5AM9~E@UZ^?)ogHAKx-G0%F61Kaqy*kdp$x}y117jFyNuJ0YRrnX- zu(1>Ta$u^lA`VHfJMi>wgZ7js;=8YH2;v2c7IIwkr|}`jw|iZG>7{W90Tk&?2bptn z_VV$fU6W`aB3Je^L;)V6rEbPj9YKMIgL^c zXZeYAC7(&79iCRu2?{Wg#|R_wM!1RR(w2PK=(-t-?{ga5<+t47)Z>?zUmBNQbW!5X z4*0tUf6@)OuHNJt3IA%Fglv&?+@wsv0 zNhd{1@X|(mI_@kV)bYj4GLtEJGL93+ciK7vN?6tGx$UMK z$(lMkk3T=GWvggVuRc7yaB_pN&i!*arxEPWL8<8mRB98rZx!ccYN&+$57U3|46q!Q~K19c0WC(%g=RsYCkPnxG*Nd zYvg4%yu9S>v*W;K`$u(}vg*k39`6?h@?PhuzM5GeJV(cdyiGdY3eI>6Nl5~F%9&+L z$q*vbWAy0J@l?-VapPs(<8*><4G2hzui{D3dE}ghi%wB(FEg67b!?2SK9l^B&-~o1 z0O@b~Ov>7a4@IARo#4-+c#blHj%0snH>yvkuFc%t!_4MEF8LgFKKD-EV<5(o?lP2D zX*ZdzRt2Ywl=ule^5vI$65#kSj&FHL-2L<0qcx6(q#<=-;SFR8^WI6jJXeRE_@BqP zLZ2yLz!Nqj@ueKuRmr5FepEsjwL#f#MifG!ZHHf#c5r~JP}eq+^pii{{j2zbPi{aUpWUq+sYT85 zIWnLfY?w-eNatfzh6)O~`%*L{3df7dG&FWJyfpL_Anyzu7u{)8gXvklectOI z69;}2C*x>1_Nb#VTn?m;6hw!~2`9hr+zXyLJMf}BLx?J}DiSI!)?-)TcZGxLbf&XRLZ29tKq)N|;kq~0vS6_{j&+JNC@ZlWGxF2cM9K}$p{T^Dz*z4+ZRQMWkcP(e*|XzHQUF^XZ~z$%yGIoi>~u6RuJhF+ob_l3 z8t3j#o*SOMt)vD3Sp~FtPbR&s&?fJk)4LJTX&r|&YZ47=*MOg3;1YfC zs7ICD>@LiBmJylysS&JjHDYW@iN^>D|Lr`|DCVaaynp!PW3dk2bk=1TCogEuv0cJ> z1IC3BOyP|*V9ppS{Om~&Iydkjv3`_u@MViaS;Yc;*$!V=gK@DCqjA{iv2o8I9*y=# z9}y?E@0k3c@jmsV3<77vsvkHaZ)wb!JBLW&=ke$(JrlMS@n2F!LLF~{CGir!42q~o z#Kd{2#BYVCt=$M6a4&!-BZN2ZBQUlz)wl3&+ArYE7jMaGRrqC|8Xs%c`Dw)I$G456 zh(6b^Q8RWUYhejT8ot!~^{7jqoURxE&Gu``Ioo?CuKYj-l+i8~9{Gpks2mv;mzSCH zDjsBJ0Po_K29Ny7UMkbzlVdn{{LQ!Dj*Gf?kB)8HWG#P11g~|p(z=l#9T)P3jD~>A zI-1Ku&*f1_Wkm8AY08BQlMOgwOdB1G3>h-yqxg=DxvQ_bI*w}9Dvx=Sr|V?cVrdC< zo6HP)m1lXW)appnP&bRmz8mrbVP0`pYQCAzC*#LOpT2KL@4=(u%uem&n(mj7ez|Xf z<{8u8Euyi`9-k%7B)<{Qxr)kqK9O-X##FjAS{E%{5+4j26n}Z};h4g`w_nvgx}4lO z`{l^D%9`bZ1J4pf`HVcJH1JWmH&Uzut`Vo>!gq09*`c9oM%Ao2bEDU5z2i^4-^@l@ z_y7LBlq0*~G}JLC4^!DsIR(GecvN;M|B8yJ&r}JOUur;FKIq(i_SnxqkNbc3yZB`O zf;jKEqvG-_uZqJksCDXi0+P|3B27uFLPVue9&cn&m^gMieSu9H7CgtO(f2501BMOH zY!4fD-FeG(>1dFiR+Cxv19i_vi8S(3S!SLp(2k$HS@`ipowk-?3NsZ%*RUSEnYHj6 zvQ!4dW4(ICd7azF2^~)$NN~jeI2zUyr3dcv{7j)`{^>kpe)3;uUohyH9G|K98p*R% zz+*@)D|rEW+W7s7IPH{E;z;W4_iNHLaaq`?N11J*K9e$qd8V$wybIAq=m$bBIvUb( z&0ZL=5aSSCiww4Bwo5cogF&Xm8rrzc_n|-xndU1 zU>rOT{pS8y#JzW76m>oAbOKk6lK#!$5%%g$>UA1=;*x6?Uh1l;H}QMc&GQUtN}5%7 zn!jjKyw>NPc=UyrqFsZ%9WgxK?cXoP zemysy{LQbT-BCxyUf2mb=C*w5Oy><)1r zuFB~%*qX?Z<&?7yX6}D}9Qn15NbFJs{#Vnc#oMF_{-CH%gQ4v(J0@9R+&o3)TSZ95qJbwNON6G+nPzC?wi0^!K;|`TF-jPJ976fo zmtUstr)Hc0V{O&^KpYMGWTT?YypSOQk2C-nQ^i3BDC1CJR1kR?sn7vn-vB+DdMalS z?b6Zk&g;ENL&MQPG^ZI39_!MCZF)jsNHRa?>sWf@6fVhB-A49A52pJmBepq?j)O%D z7iGQS`*{9sm~!O>7e*@_4ZCBk=b7)^?=!41lcp2`I%1r^X`UJ_DMWd$+yKsce8`~b5B1JZ4o@CTyMe=u!FgoDlNSj z332>P#bjKbP!KkZt>Poov$>24X=TPYIx=GH*!c6^x5mflvX^vhA2(igRUEY6{;?HY z-$Wk;=V;_in1DP5IPi0M6vDN9fBM|n@yP@nIip9%`=5TC`16ndR4PXkLr8ul^|Jr@ z3o9B`)$7!gy2cUkkHZewFPhNUvK-G`hZ2tp$kA>nroe}f*z3ZcSZ6LRxGrm9-QzSI z6{P(9>7!ik;ZK$H~?qO~{}t*1@Z-+knzAy5|Bc$BBk6_0jw zoUQP?ZO~Ck@O>Lb>M8`>H`GcFAMCc&x^&DAh5CHKLGZ2G+{fT-SM$685h+tBEBPgi~hjfmCwwT7^nnOd5i|bPiY>sqq4uCZEZsN9<3LC#kGVojNrg4ZU?VAXGcG zIXXNW+&WStwK@C&XrJljI!8|#K@NUWy+CV zs#eJ(K0n4m^2S@eXg;hFX!I@-q zeD2s90m>`;1iU}!Lyow5EWQC1ZoT}HIQ8Tcqdtv!Gdia-guz>ysEBh{@%OtrUe}?V zs<;&*L^{^UWP#8Bh!Smd)->ccI2!o=4`j^< zkJ2pNQa_I}Hj-)ZK;Hj1rxD{Po$?Ho&>gI!6o#0_#em@>;)Z+g2fh*a+C>Ze zz51~d`L$*x$2fyKMk)(eH*zGAkKrBz zo^QMv>z6NOPfv;Cjy@(@AOkH~TJt^4Q;|_-W|bqOq*8f^n!Ql2s27PVKF7Ig$hi#V zxwN2ofBR{4g6)!=)Hi6~2z8998bA1L$Zl0xZ15e?L>c`*#f& zf1bZ^L3~NZ;79QP(UZn!kA}nH6}9NYQ;idDbR6k?NvAt>WH7==zH`>t7AG~}>_xK; z`BV}5(lI68YV4ZbG-Bvbcuil7mbP&*Wm+v7@0-CB`xt0QS=MJy8J&qbGL_Hj2Chjb zn)A*60X~?mrdE(Qg7rgY)`NTut_C8T&RMBNO_v)Mhw=s}?O9#?NoLDUP6-vwErN*uE>P zSbXA(GF&6neN)aAo1+$-BXA{njX%pbRvZ?i{lme`$Nya7)N2JU3l|d(Y|fl zbTpWmroG_&Q-^{kcc@#!-*j%Om%65PIIcB{%2_m(o0d@d5?6nOm&(iT`}IB1 zvQgvcOtwT@WOoy2D$6plQi0_07ZQRY~To7r|E5_>7msAngy z1g-}8=>F(?{E^%g80*&zrfLOWb6$OR^}_a*Tai-Xy|xQPWdd?;k=cD zj;V7%+2qlc?&%(T!v}%I$Jhza|MltUHFjLIMbEqA`s<@LIHO&MF;l=5@sjcVZwvb; zzttHjZQ08%o6Rzoc&=`+qYS)~`L84pJaE|1c<`>@#0-{s)%j<|1?QZdjt1ul08;1n zJsschw$jL?qWv+K%;~q^d^74Fb_kA!OQQTfI~@&tl?nOpf9>_3aWn`-UkEB|XGDAr zWOg3rw=Jd<4INHO$-G%JW4DTxL7bzbMU(vyOc;0=Qm`$y)Z3|z!do;9W9H6Z-xYKC z?COr~QA97H`OpE3#r-fS8EdAe^1Fy;)Y9)OD6I_>p%h{Yfc_Z8XVlMNL0h$Ww z_#(5y*k|Z;FmuC9ipqE|y?+_XzmA4sqycL5o==U?ad>c>Hf>5n$Qn7%Y!bu#QV{{3 zDx9VtI=0VET0&U6CW&4qY;!C3WX|k4G|BH@sD z0E}U#j-ewaQ)+p4la011;MT%WcVN)%QoS0Ht{8LWoB{Qr5zEp&{&PCB0ICxO>?(t}RynIJIaOdrD zDh;>xNaqp4gl^I*i3&BNnL0MaX&IMFuFrBUI*~G(&Vx-At3;mx9Sxt;!=y)#=i}MI zL-XjTo=^S>N5kPco{k3hRt9d@YYknqB?@WS1^gE7sm$#Zk~$gm%G+E{MPulwQSso< zZi?~TcM*-SZbSJ$V1F`%fXUW%cEc?wDKb_bmGkr@gbFZEOM+&7Ge5>d!(-XMUMS*T zn*Lsb(6yH1Wt7pM!EpAdz!H3C^!(j>RnOu7&~4#!KZ8po?)W`l-mhC>YYAw$G%0cH z-?j}jnBeNx^*kaAN08CbG#Zl8P@1UzY8-IRC!3SOyro%bOxRmuQgHGh*x1{mLZr7_ z=i?_6zl?hxdML)vogcTIb4HwoqIC!YKj}%s2%e&c+Z|P*F5})Yd}(kVsmu#U8;jTi zytXoCN$7PeKd%Nqzk#NPjUE&C;Al9OlS)n^LVD~`$KYsakQobGFm_FqU4(Ht}#)q&)egiQ@TXs2K7lnwEO@sJUD1p zO)5R&3<{5t7ip=efF(_(@nX#>(Q)Wp2ZYV#vM&3RPvT{IDO`E!rEwyu-VN)ctWY~F zFHvbLC~nqz7nHQj1Yl3g`&7AO|o3ah>N&lMuW0R+R{la&&en|&ny~58Rdb8THcraGEnBsg6W5Xc++El z%00RL%1h%+9H;x#ss%E@2T)S*fMi)sd3d=B7K}aV+!|NqT{_r-hvS<$wHD`}4paN# z%$z$np6l^qJpFdx9KZLY4@Z|y9n%nBMOJ`3QeIPhDRa#TP{PW?GGmQzW>y@qvV5&H zhMs&(UNf4kr(fTDPfYlBX`IpOpt$aa8{_a+EpzT`;rl9zI!$*Yv&2Z6eA#r@bTY7y zmV0On8L2Z1(dMc;PklyaGz{0#@VlJ*eK%bb=bU;5N^U)PKp~?cjR%|x%0C@Z_H;6> z+;87A>F=WPdWtUX3%4J(Nt6)8gnhZL&np(us65V6adD zmNLailxe!k3QvoXu?YheYVpW`izOvynpm1>Y{$Pwm^bqxaN-Y3#0} zN%cB1N|YnYkZj5de^TEO&oc!d_^8MDJPogu@$8Al^z2!)Vib;smtKA;PKAfHM>%h@ zZ2bsKDO$U66eW$$9hV(HQRwoS~y)^jDw9mEA8- zdTLm=UY_`&A-9cv6wfoWPds6~qVA;wO5@F!Wo6>0`zdTztyvQjNyYZ$pQm2y6Q><_ zY+OdFw~mI&7)3f=GDVuX%deA8piTEqqskzL0f|E76g1;L=}TJM1*hdoc<@II^WzPr3$fz-UtASzwLZhyz*N8vr zd@FJC3>-2nuD|DgzCrfXIT}XiW`IWHU#FmsF5xdf06S726K2-eYs~3bF-y?rIlg;Z zaIlpnptLAndh_jg@VOpwFyFrVH+My+4jt0bpur}uOv9G3ZP4mEq*e7b`_AaJ-GDt{ z`BWN`=)~&v8jc!}pW|qFvS-g2Kqk*MXPgu#qQ@TsY%1c!GNVELE2GoE$WpV)(3K86 z*JTR4dO>OQNjGpCFKLSeN*rQjClde|HGX{j?(X~I;CglAn#flYK5;Ji0sOW=Xc^;)sN0U8lP)}XkG18Xd z-OP*3XaM#)sU24bqx883XNQ?X%2i7w%faI}!%OGPnN3OMm+|(%0ni}*l}_yv2Q)1> z8ayc`dq}{$7=%%|c$XiPRkvn-W+dr^71m}mYy#e9ep!AXuNg;4$?&1W;;Hus#_i{J zi&Jq_H=@_fZa5vyGAL#oWQHu`%0ujVA|EU|q140dtg;0j?|UV)oCxgAoINK74H+DL z-+d!KnYk24!yVBMCrnKp4e)j4#RdYu;=A@)%2?)HpgU-ovD5*?ai3v-3HP+x9=oS3 z(b4e2vwzJps^f4p+lhH6cYi&9m zeO$Bv@r^8O1Zm7v&=@NNqHV+Y9Xxt;+;qeBF_Up`=yFnY?|xYv*rLVX7=(%(Y$+8W zm9OIFOO$SYX^9`9Z=}Q&c+=QaUMir7E=AzKL63%;e)m8$VvL)Abw`|W#_3U`PVHEW zqUF(hdam?1IVY9SG{itSpJkLeyP1M%dbYMQky55}?I4YrOoS;jX2vUT^&z#ke_YY! zM6w!AjiZk^GD@RZZ9$pH23~wO6ZUN961oJXZ#kVqsJJ<@s-OT$DqF!o~7YCquw zfhV5tfy1U8jmS=n;|^~_Ge}$}Oz%h5COVqBWu0ZFR{`5J)S1803>^&`0>xBSJ^y;C zJrQHh+_~}5m@)AJ<6m{vm0?t*LH!0afP+YxUm>F9EDOfDKNaVkUR@q8lgc_z;B7On za;6-?3}@rS_yi}$d!z-gVPCEw<*GGNk?gunisKgGZn~I4R^s!evLbz%B_Z?mGIh*F zs?cr6lUM-;Wk$m!jP;Ss{m*~x3FAH^F6w$_G;Poz6=;Q6)-$q(6qvxu^(3POKH{qi zjH}6U8DD(K9tsGpZ!ok!7&tI`J@-(2ye#6OU;R8C4K?@VTy1bs4|y@oUT?gSN7c5h z0aw`Zb4CG$p~^Y?D-$nGG)-l6A`PFOdG?w3>wv*gpL-vB<|%6KaWt@2Q@owCj5YDj z^`or&xv*E*n>vmA7-5gYgO`p5*JR^KQ?iCqBz>rqdnsOb0eyA)aSCIuQN_&99mVzYr&P$W zf0JHmE0Pz!jZ~G7IH{pEqx~$vzaV&!8kOP`g z7g&q$BXB8M((x$lg;`;bQLLnWfRwP84#0omBJ5RyjaGmB#TRkk!;c`;X2RW*2?;Z44g6eSdr?*SOcND7BPCWb5L>Q*y7R0G$HD zw+b&&b{*3&&Rl_?oeH{H!qjRNvpxK5GyA@R&v}dLywKfaJyT!LcXeE-;CglK*dB+- z5oC(gj~Zm_EctF3b(lSISXGV-FkYH8ZkP?+boOaf$Rmr&iM$XHr}9>yU88C!j_iR- zlaU=8{FT9YS^4d^F%E%0bi{~wrT+(U%eB|WNo|jd2KDMiMI0HzdjsWT>Cj{!d{1Yl zc!rP{UtNjOj5Pe>GCRUf;CGPqKJsJ)@G^(?vbdo@? zg$$%Z6r=#$LdKR#m`0<{U9*AY2O_72Q6(G=@~Gj+rykG$HTsPGGR{4zQ`}6?lNS3m z$t)Uqf$~DWAU--@jcXNmGaC4yz!!GH%4ms3sgAEwz-9%GhCUcMxBmXYJmdVHn|~JP zoqZ;b<-N0Pqy&y?Pb4XecOs+e@JNYI!@SsJPenf?mpsd{?a^SCMr91InKNg_6EvHB zviIA$=Wjppc%IOs%v_IrDmogHj!^h*plAt_b1#EqAQ>{eSlG+UbTE`chCmz`vm0YH z#_oN;|6PolJwGlu?#Q^}>T7T`v`U(kM`nfx7MDhUDe!0qvOr^+C8WG6?N}l<%B|xI zA8A$itVFSXf5@=7>aM%fv3WPmAiJJ?Dv{rYsYj^b8tu-^8Q`LVZvC=+pfaU}I>zw4 zBn{^}d=C36?OKL3d*On3g$8QB@9{!he#VJ$LWhp@XgEAG8gx#93{jerr_73w7cj2T zL8JDWz7Jo~>6pfs@(TD{@?iOoB?6XC^yvLYtXaGuPAAIPmNfDMDSecGZ^Q|c88G0E z3Uql40`(1)jNB)UJLyTq)^UyOYjkMD*u{R~qJ=mb#>dl-KOU!@drq8i45wN&X%c&2 zxbQ_%(4}%63PReCFxvS~eMx7&`iBi&&3;H-gy*;>W$!n@W#Z(oVjxbQA>+ox_19b% z$CB;XXrKBR^HpIiI1+K(xwn}SBcA6TLbuW;&$Lv_mrB3#Nm)|?pIL)PFl!h(7@lp@Ala0iF5TC9714w$}i9<2Vca37c(Rahgc9yAvmA^a15jqIz$4ePmg1zYIYj_c*KJ(yfq zy8OKga_`tSZ8`pXFAQ&*=i%@kLX@|4%LC(%+i!~_chZx5#qtUHjW{Ddh%@TJ!bTm^ zuKqf9(g6mJOH1O8*(x5t`TmE4qWkT4^3+12rOuw>zqsPPzG=n_lwA13yLtD{o zn!pwKSS%;e;cf$69n@KF3cO5Tm!6UzgFnTrDe?A)4Qu1u<;!9?k^B38{o6S9&_m*+ zP6P>#J|^lmYLqmoQ&1gSzUZ8Eyr%uZ+;!r(7wW;vK30*sY|<0=S~}s;lkX277Vp0D zYFu{hHE|U3sX>E=nK9^Is5|;y=}&&9E^J0$(kajNnPy7)d!bYV#}6>vf}Jpb-n^JV zmeA{zPLu>MErN+&W)i80f~0DPUZHk&fLqCAIjbpmOPSbo3^vMk&ZVgpy&315t# z5F^kjpLqGTxbf0UqU#CtXsBH$n|!B(QRHVFe-=OZfek}PhSzH+l%;oqJV7U$83FQx zbdG~F(`U`fjD|jaUX4#?(+u+dd!yqqWR>k+Jq>dmYdRau5G?Mce7L}~3XT)U&gWwH z6&!5P8}iR=htJ4TdHuCs@pS*e(Xl1XAn&-N(4zsINGCY5N#_M4B;P6EH!uOeeTFBR zm5>%#k0msYX;80x^{SK}u8H?P{E)y#p-01Y7k48|_BOl(y9F^bwH(&pEM}w;eVf`l?vH|=wq96w2 zBA{|ip7K?mIYl{M+0^m zH~jkNaVARi-Z&c8k?o)-)aZ@Q568}kAU~G$cM#BdTK}hj*NeLuBGKSg0g%~PZ~gM? zZ^b)rzZ;jHc2ab~6MFQKM{z_PjgRoIt4x@hs<$saek#)ZmtIW1?_90xG%8|*N`=>6 z4K|dr8}erurBC;Gk@U@tG$cGZ+8@(44&1L<62_0Dz6w7b4Ed746E1?Ps7zp(?qrV1 zv>I}o-q{uey-vr zgVb4L#Kjaio7k8wVfSY{SFdB=?1bC;;DZ>y4!sI0rvQ_2YCt$n?j>_q@$q*R3a{ed zO@mi4CmxOY&xEiBA?^jtr=D6 zQYn|os;H~5`?5#DAUu_Cz4~;FS+p_k|M^XEQV05akOfl#FS&wVytLPWos-2MaV41q z@5QyS5EqbwK2rg4e0l45gu;t2z7T)uKPZ|L&A#X1$LWu8Si#W%V@iWgVT|L3jU@|# zNGs2Cyga8H{3wag*Mq(RZ@dbI%2#FJYWlZL_a49dmKeEgYg~Bzv2^t=^k|S_>&4Y@ z)Z1QCMI4-QZxt|XVEjPD?i*@!O(``s_ocVq$$j8t*rjw5}iBZfY?$;PF`f18LXX z<8>9slO2Zx?7-&DvagD#KdePzO5={bb-&Xg0Nm5L#CH;(c$dy{PuU~s%M&?tG(7sm zQ!$BVkXN01dUU}6Xo&+%m`JOR3qUf;qI1w_hEao3z^F8nSD|vjrWmRuZez_`*q6<` zRuHYz(Qy0S_eb~hxR=wREA_ z<3M=JyHr+0W{s7=V>wTsArF`5%7;}Vl9pJLN>@cnCv2)&a5VfS-WfZw zaEi<2-H8}A$;~m-LuZ4qH;OLK*qAg8c%CP^`z-eG0tv zo_;2te!bvm=*_7UCwJ_Sr3}h|V)RmnjB-vVgFT9jCb>6W8t%?n{%@v7Iy&)anVmCs z{O9r5YY*t*_@whnuqKjyHcu2xJ9SYEr28HlR!$LmH%ektY8xggyiTR7637oT@}(fix$SKI2s=4@nT$mAxCE(eQahN?1hqR)|!#1GT@$?jXYiheFJIj z!dJeM$15sZdAtrDunb-g4})K+)3IbuH7=YwA$^)= zt>UkvUPDp&C+{*Fpm3x#nHsD?n#+rEZ8YgVf4gK!Ohvv98ZjaUjU}Vxy6fYZ!w#dI zhc5Y)CT>9<>6DdEijk&qyAQ%ZD5wt#XPq!M7q*Xz6kvmF^|Kk%rl)T3>RY`C4z!4C zZ3fw>aXNI;!7Dz%PdBj+#e&9)O;qI*%2u5xIvSGuF>l{BL_D?OJ9Ms3F&GCA7!ZFQ z`$^n;<&~t8cZqs+>n2Q{pM8v!cN&{hF?4#p@n$?rBp#NUJe}D`ZKhBa&w%BD;%$XW zHshndAIJVW9L5|P#M+UE+*7gQt{C>5oMDK--8`lOsf0IXRuh{2k z6LhqSJ~`jAwW}CoFXW_-hT1q9@&pDPfD@=GZ_@gZxSmvRk4d&f&_J5OA7zwIP4!7L z0*oH(XwcxY6isJ?Wg)^{XS+DLD>|Lo!~F*iic2tzyzaW>!nl|+<;IN~W#C8or>-Oq zE4$MOU5mp^n$l>_I(6vPG3^5*4@!fP@x633yhi5KV?AGqcJ-^pMOWX9Zq`1J>iq$p z;`kc6W-!Q`bsSUI(VH<(I`oM4h5S@-YIy$!H zxLch8_39^IS&!pUIhTet>zCI^XQH3ZcbyQ$&y;_nXN7ds7If{o^X5nYVZ*XX=@nO8 z5r@Mg_eP)e*wMn6@N{6|_sl}j;N1)_&delHUEadGbI9LVn+^&4FDza}nevn=@%nr3 zu^$!E(O~I>8EsjT;un~x`jBPGc_IyaW^V>RwSP^n13N^!=EqI+o#1CrxiFK%Q=P_) z{WzX}=7qST`=yjso)~p0uU1~Thw?G;#+ez!)QKT4(4bCR0T`!)UATcN1;+q;5B|)U zJv&B>91;Ec^@`8tu8AIhxGy>!-6k`ql-J5_Wo$a4d=`An9w-GJ!xb@eXkTZSan5<>am9xvzI zyPwn!!{G2}T)#oiQDawTx03@wZ|(~w9j+az7572d%LF|S`V-Qn zpXoO+;ePJPoj4WZh)k)q1HTHELQ}j{D5``CT+kw)FMVXK9(17qDn{vK-s0xe88hSE zw_lGB!5Ob#U2}PQSv8oqpx`>L^Hv}$d{rhCLc-ikjBI?vT#Z_o(cn6yL4~x6@VL*v zhT>gxhEe2@B^j zyYjP&IO)_pyCPi>74+Mg&-W;4v%g(I*~X88H@-9M!*wbR<_>AzJnGjYZMVAp0x;zG zzQ&Jxtb$%aLB`Mab1`bcsuI@~9hOyzvkEnpqc1T^?|Y_4j(zgM`$b#I8;k_1xMg_? zc%mX_qe+!l2#Mbn7DS=hGfF9^_HCzP54iYIxNsl-!=Z`_PHJIRf+8*spOD zj`-a(N@28U^qBs;?EB?0o`~V|@Ab`j?2WEp5`C)Po~5Em{f1F>7mtO~frlfG=cwrF z6)%NFQyL+s(rxC7k<@a~gY<3spD@{~cLAJ9=PPT6GI1Vljim_1g)5iFij^q123@$? z9C!dFHTy;FJ!|kx>YJCZh~Gc+*J#nOPMmdmSCp)}S@&%Dn9a}Rhj4?WRh?7v#l&ym zBELzRR9ZkhiQ>R+Fxapc3V&D4p6AmfMz&+(tW|jea zaYo!M7(@KZyp_*+f)h#j&#N(fRH4 znzY-OGk~s|b>epEN1{OrM`q;5F@V+|{dBFO3W7 zP-lnt`;wlNwbGI=bqmWP)k6$Icn_<~ca4LUWQ@(Het7V(p)qRCg18!otPRxE4QxVf z^@3`$|%0USd zFhKSt0e6I{84c1)W>11AnU%q|@qej%DCclpo@h zqGi%T}()M$ykTntjN}C;!CDtxRnofO`pM_EKLid*WOGlYSDNX=y zU;bTLCZ4Xt!K3qT5Lp3zam-%LsSSr%Mhs56FWy_kXU8ssF5;N-H>2no3}a07Hb2j2 zFs{#(&Q~#aGbUaE=Y`v4-7m@X{d79P_p}3?s(Q8fVh>%Y#e1JZ;t#Vy0oUmtV4&W$=s#;bTlxg`j-z$p2L25IhO>MI3wM09~+Xq z-MMS?%)>eL*|<;RciePgH?k31MHOm9g7BgbydzQwP!#2@2C^n_v1zSj- zDeW0t5g)}JOFujkbu{wn;hw#6?4w#95Eq=?HR{!_&Hdb`F2>7p9`P`3KzNk2xgNT* zgm%>6LD9C`IdN{cbE8_FdM+?=ssOkg_P_F<|A?c(h_$J+dcaem1qll3n(003WA@CM z)b)HElZYNpCiTBO%2Ev)2~`ABf|TA5q!}K&Y7Jz8!!0}u~)4+(Xc`N*d0%w z-u+C6!hld|D0G%CnQ1MiR;$D+*o~@7@Oo`UFr$VtLWxpjTeNI>D!Vqos>Zn0NY~9{ z;P|@)o{AJyVV77DI=i}pbSl1HBAJ(C%e1q}3BNnO=ka<>)*6mUs!?Naghkany+SW* z8qJKC0#O9wl2Bw6GLZE6F@_lp3VadVXr6|cOx!hn4})Gv?R0rywWnj_g>)SnMn2!M z3yL7OL%dlh#@e%Fg88Zdsbnau6~ra0^+6 zdn{o?pfVPj3eR^B+(++oE(P2u)T!xJU%=Quum&3)RfDOfbAhoeYZ1P}!_P7;2{;RD z;bt_=^<`}zYtTDvpM&fe&id@?y_BfVcce=0wRde46^`4%o11&Zm@;n}la8Xico*k{ zy>oXTQ&<2G;pPbi={S)I02htYl|-dh;4HF^t~QL-#zKyliZW|R$B}ymjwz5CIOkjx z1Ughy_GM7^q!3r#2ghDP+0GIaT^nXK->-Sp*>jInW;62wc*qFTm}bm0V1P*~p3Gk* zyabB02B-h!1%uTH*Kk^jvbAWz_d)l{002M$Nkl$Kwo{#=rjhf<|%K(?J|8%j1;1;#K%uM~T`eC@{gV&;Mv zH)#d)3Ce8{?%dN9ZL8Ma4PsX^qso#^lIJH=>n4ni9Bb@~f5Jn%clLf{i%A3B*9DabuZJ`jjJQ+Tzm@#$=LwIFL;8PjL zfpfx@i4$j2ELgcZ=8#FTWcm7-ONNP8lN!}&GFvx!iiYeuls)TgwXSN>6K2;GvhZwh zyfkyr;bQb&qbrTJq<8iJg;5?RJqcs!B551Ai~I63dGbn>XtO?qdkqX}6;2IsORkKT ziOTW<4I%lMPBxXbqA|v@Sv#=idrabQ_j*43_w4J^70ckw+oCDX9miKq$y96JopY)! z%t<=+mGsZ2@>=mk`jkKVv-1*fRPxr~*mUlzP`XSZ-lyi?^c>I`TUe{jZKbU>++&m^ zjaugJe)x>+N)Mh|YM_By;LX4l-f20HP1NS&EYXmu-LL^CPSi>spL|^<#dR}f7Q_Ei zd_guiR}ek%!9V*K;ZxiPVQCa|sr?L?yIC7G;bnVOFTh^K+c8vtY;x*+K8wO@p(%vOLcVm`&`6T?^VJ#BRW5voVXYvGJZu|roJX7vQh#(tq>HDDXh>^}UZBrM2!frxjNO6$Q$MLg3ZQ{FBG!v5 zF%HHmt$az>%iy^@sIK&x;;ujCdwEX#!$pp^<0p`r>$E?Tz#7FA(c#LgMHyi-$rwRo z>sB~^vjhCT{I9Oi=8#U2dE?*Aq0e`P^(4CcNJl$CsnHZ_9G$`_)+VBlUXIuAhCM|4 z*&g$O@l5$h{!(ZAzWw%ZdDLfFEU$wa2d6KdOOtA9sRBPTXzq%ldd4hGh96^)kMcSs z&Rt~K@S$5_H2k9u2V)i+)H&+(bMWH{($x*zR~8qiQ670M1~Yq(&y%en6r9fA^ye1Y z9X`h_)geQay*pXed_FV1**@_Abjy|0MJA}3Lgxwg6cf0uEG~+6JtfQhjzL04K0+B+uY?iTFszW?As z#_rZBQ_pmEb*j~Ww;;wvoZ-`CM6{hbmUgw=NUg8|y9`nx3Sc-XfCU3NHH-UwmL#wU z_$X{L=h0`GX%uq>9bLqd?#hgIxcnpEX+w&q@{jW?mc@6VUkA2i8}_Q0>T2zTu{gWf zDcM2{^4cS}@&bzZsXhTdWW}?Tg!@9FO*sPjy?Hy4x(ITLg5}t%ais354UQ(<$*q zY%#+$TLsTDr}AJ>Zu^RtVH@!5s22eJ3@&R2bzLk3^PmC z{(20jeYahO+6+JESzF&{yDjAmnJve$2gi&W%ROr0=7Vr(6$-w+8IAS(P2PYS|Vo2DZ7aSpJgk+J}xI z0vXWA><`;L39e{+3>`i)vZ{w+4@h56|1uLveiT1qjv2SLVdOUp{=dF`XZoAJ{69I~ z@`q`}_!4?706EHhr2P6Vy#6SGhRA4O0wNU;;dVk1l^~5NWQRz*-m-CH+P`~GI@#8q zicy3X=2GcLC3hxGMQ&QE>GOT8OF#-NGa1ZkwuDBlz{Io%`de(v4sLyxq zNNu||rHYwUKc)Q<7$KSS?RS(#g$rj5!PICRh~XnB>LlvinSP3@38%<*W95dvX+WF+ zY(D>VQ+%&x%2ZbPvkU@_k6cKNxZ8h)$p~8%%HeOb0F3?$p0T3iJv`TW&^cG(H67;2 z%HO=2YB(}wQvKurE9XbW6Z@+X4(HGIbynSSLaRSU)d zp(0K8ct;1vxi+WnV~5kEMJrNuO-&Rj5?oY*Dq5qOJ|hAf(8SCUovbVL?Gk_(yvyej zUa)ljRU~HtvXk`v3}DQ_Qg!{5NV|*74`{E0U{FrSP4KsUx1gxRm5ED$p=o%IO}ZKM z@Q6(7T^PJ*X>Co14;`SwIf@=9aCA{oIM4eJG^TZ%x6=Ztq%<@NA9rf)z*JvWf?SZBy+*xhnG z?P@$5+p14MZvIOPD~F}Zl8RJ1v62;l3DA%1AHJ_KtK;NxX1lg;Nf(Ycr!f_5uc)fQ z+2M2wc*AFCh)Ev})658f=lHIHg}%s*a%3u=#;*ps*fD^>hsK2b)6~of9IyW>mDJ2g zmCUKziZp)YL6xU;RJq;9JjPkhI4ZqyY&6u&PBDwb0$&C6TmH93LudEtv=3f+W6M@a zm&WiK$!k*i&{SVBF^w5Eh`yur*j5sO4%+Vn-CXf=epS$BuH1me;)^`q3x3hKRX$h( ziWEwOgWwSvK-7O|={lPZu_dOf`+7P=*0a})@>0_Ls@M`#g7ZHrwmQf=wr|?@buucH zsebf(uyRH}qL3dv<8}N5#cJPpCsi$+7xFY1eAa;y8^r|iNbHl2L38-g-^ER9GB__@ zVyATXGmSJc!lSp^T3S-uo~>!}L(56;tqxof%R)YAUxQ3K=d1To=!?F7K|1L*c-;0P z4KaQTf;AsJm^vEw0!cSg?W~2VZW60{^i3So8428g55yh&-VdI%@Ag$4=-yK2 zN8OdZ#Ja4wnJdD_Sj|3<;pA$435H)$QE{a6iq|oBw4r{my}s~;wHK6m^;2XNNk^U^ znHzk^dC>4vuN^tknhx#Q%C?T7v8XT_=i8Mxu{3CcJZ7>AF_2Fbk`dI9T?1|~C0QOB zCTqaL`~*pvXYO;m;Q?%q_ND_km{lxpjEiE_gX|;yRsOY7bSzwzGPv3so^%!3z40Es zeWyoW<;j>QvZ0i9J9h@Y*}wbqbeR>ziFNhh5y3bDxMH|{m-eA6xLR*V%PnKv95qAa zd)sure71bx_e`s)%|$)~BsG(L*g>8O~#Ej`qM$}0>S7;9>_ylTyzYv8X& zzjLI%ws50%kAc2Z*i0QbuPs|YP37|+N^{AE@`Nyp>}hZ5oT}%vjqLltLFhSUUAjUy z>wu}p4MMt#ZDxf$rK8YJ+nS*Vg{nKdlY7yIKhQaf;u5OLhaOe>F6n+Ri zV6MG9M$+Praonf8MEmwdOqO>%nPuPZU8(yx!LpLFR9spXc8%y5CqU6g=vwAcU2EUn zexuG6gSCUhhU{rKbS^Z}7mx;REGVpd?IjBLjY+lBW>61dbl6-9b2yC7A8l*PDW`5r z6{}(~hPk$V1F+fEvtY;{9vd$%9{`89zwvsigdfW*E2DU#IzfBczC@N25T#BN3$*3s zPx(|F&Fr?G_MI&6g+5}rH86IQNq6eV;WTr>!y!-Fv|d->2lc!>EX1B1*) z)_)R%ZPx4r?S1FNV1l-yfw&#-znMl<)};sLFJKGDh)id5UyPr7LRUc#?cuO(XvZ;W zO9sx_VV+>0gU9R}dR;8&A}DbVJvhFs9ITlbSS02-e#c?o?&>G{FF%CLGJm#jW=hVB z@{RLiNbejAjM~B{kG92FYVV(wijfzwF>Ffu;8^Wn=tA)e+sn*JdBv^r*Rb;p@W_X5 z?{l2mq1tgCKi+ZlXgZ6nJ%nvyb)42VmVli2A`V9&mbSy^QWo)B-IAwjQm5X8#%Asq zSTHl*T0sU%#I$n+HBW*!Cs^ZCtl5HKFwHuqk*3TPLa~ma!rS8JU2np3S7I6y5h? z0Yp>2j3miiM!gk8gA9>!0_{!FG0@;D`8EV_!=`lv7{;W^s_Il(QJF>&fsFJfCR+zm z0R=~4V){oO(jG>wAOVnX3DlU#A85Inr*|Usw zP&9OnbPZ(-h>o4$W&5t+L?8>tooBU>Hu%n}Riu^oPYVF3BBGB*HdP$9Z@&a_ z`{*TbxsnvCB(~cFj`m%kQgHJX2|?hqef!fZzkV^zp&;dhv+fU?g@R&ycR`fCha(G3 z1x+2&3lzK2>DG}6;L^Crx{v`7{W1u%e#@3PP2zhLpqe_Vj()qM&k>zC%LZ_)A}{@= zjVqImMG){vO~E+;7D07)9C#W@V!Gcs(SrNvwfTjY8)gE}zm3kq{ z)nKz~Y}3MIMz7<@9{9zv>MB}Q-{PsC@7=?8i|t`}k07(6q^vAH-@I){dhzwQ9dIgR z;G+qU*O#*rjy#NHW&IW_u>iG)yz>G$HS$q+44X!b@InUzD6VR_ z!Zd(DL-(~?>A>+bsp04a0xK!C`B1L!&Y#ZFoOP+*tdHV}F-K-ZguH?o?sHr9-g_v9 zlW7uxJDskHC^n7Hd__UN3_}abXz)4*f`7;)bD@zh|5@Bsc~agyZ9)FozH4{-)z5zp zuTM_1X3U6m|GYZ8#*c=u-w#6qht42{2EGQaynBr;2P#bi4dU4)3QryDI*~Txu>8#{ zuf`b1^ZzmU4^>6|Q`LAP?n6+DASS#Q$TGZc%PR9&4J63B)tDdKDdLzP#$D0a#h zUK$MHK=F4tP~eVEv{_ode*}zgYC06BE={bdiz0yI(Nz|hid7>Up+k;E<0mrO_$ekv zP?S|!>180&$+hl^hNQ(cPvh)v%|}n^cwM|mAw>F}1t85x6Dz@9 z=wP6sKQe2|yeqxA(HArlGoYKstCg^~Z{JQjZYPfPIL@h`nkvgHg2uKjU#oXAEbGxd z&_*5LygCMH?cd5r7}*%au9~THKHsx1tzG?o=;WH3TG}oTnG&xec+NBYDF#M{iTq># zpo21eo8pcZCUtB+MwL))W=jU?T_AZwHR#UAa9SOKG5 zv$>pK=f%QZcrobsOb5q(WYIC$xW9w!y!Y39kS^fhE?l@U9KvC&#JkGuxTTL+FD(rS z)>_Zv!FpapKV zndC!Hby4s7xlUhhKZ|d}u;GSqU&En8>DMp57{0-r*|Vb%`7pNINsq88p(+2x9Lmq? z5NV@rq8uxu>Zn}j1P4GHZ8r7D<{dlIyRW^P<~_71O`9?~6+$C2yedWnH$>h|`LUa%^)7HTe?jL?gt-8`U;(9Ey=(q!89XGt=@6y(y@}M-+ zRuGehuz;lOs{i)W_Tj_LWQvW6Eos)KiES+Kvv_8J&F#2>k?2$xydZSQfizc#YnQtX zY>2f;&~4fW`j#FyeGq;>OZL8}=N)hTEd4kC^IxSGC}uxu^#31d$T;dN|2M59BJ()_ z;!I%Pqyq;GG<=Mq)szN6>;?DFNt3Iqqp*^z2JUs1iJdUhRy8Cv76ej7Q(%%2H8=!w zOpVw}qf=~J`}(b$)0&UoC)=PnO(Nn{TU$#i(x?z1!PV3@CpQ8E2&4*3z_m?5K(G$w z41;O>Xl%(e8j775xbJ=N0q4H&P4~~91Gut6T3i%HrqO&IEBAo8chmkUD1wtrtKr~k zt-viHD5OYX09gna&ymqy#=)?_+9MQjDj`a&<04>cJbURd=+K5?!8jsyi*W^b!O#k} z`|lJGm6%4P?-p5~X>Djcm|6)qEL!$x znmcE90CPnA1#NkS{ut$yN99A)d3}bokGci4rE?nt16-X~_n*l#Iu{;0R)Arie5%Fr}2m@u8WdLtb?d6qx}TMMXG*d9+!>EArPJT0JFaDB}r422?S zNF52BR5Mu$2v9U*D8BRFD&D)0>M+oi*Afga`C4N^g(dCbp2+wxJvV||$f?n36}JE6 z9V6N*4V_b0Ql$OXojcRZ9RE56XZ!)8=LQBX;1n|Hcc8mUSp&f>1YtD5pS{67=h3;A zU*gy{`f`CXIr>P4egI1(9qXFgY%`aKpXBQG?*Y` z!tn%j;C1@vKi-Y8p<CxR zKXdG8B;?3IvRGxC1~|j%g(sbtaOvo`@+3xk+-6H_Yx*3gOSyQKLVc5wCmj`!kP9q; zfId%t3rwMBjzz=G_H%>T`L+$`LW9ngsKac7XlQ7lNag-i&dT=_I7TJNOc-d~8!IpL zQ_POSYdlB&B+f|xzZ=U~CXefuNO@Zf{< z-^Ezk@lsD{T&Y`K`Hw&|^C7>xnx|9mI2#X>5%L^GsEpb-&U|cB zFy$ONNE=tv?`9wHx$_=1ADHuyJ057!NcV5MSYdIl)gP}-8`iB&57O^x1koyrN~8Wr z^qct&o}+*Ah1eY@R7o$csDpxi+neWmpICWAQt}K9?G7?{-rxkQi#XFu7B5K^1T=Mg z#FX4#k+*Hl{!1T&XU?bF<&*>GK)oa_HToyKhh?jB#cGR-DvYCuZ8Eq*I| zVxiCQZ*`SC=@t4BzOny-bH2}<`W)>)0}ZEG0sMIVhA2$;9prT~IBcK1>?2<{X{U6U(#)}y1%95%1wtqLE zES-6#nI`tYv~}Be+mgWrvn4ECY!=?ZmX`D)_SlPWuL55gYo_AUvy%ukunlM=Z}z`w zu+`zKMKaqU!yx9u=hEg);9g#dBQ$xB2S#HSkJcf)i5GJf-oDI!jq}V=%ju5v3ERfI zxYd%YX0$DSd~y2TbAOU%5-{%%ZEuS!&`Ud+$%tA7@}-5b9h)^$cA>jBZ`=?vQ%-i8 zbwEmsaaeek^w8;&2x5yg%IzZgLj5Kl_)}S6;Bva*9la97rGg8Cb&{LY#O%rY8&BscU@CMXi%;TU!0mM^Q)ZJJ{Mal@-ihkT&{f z|E0BasxGyk>MQ9Wy$r(m@^ke_;4*C+Akf}yB^drL3!W3Om7ad`30Cb#5!6D*)2`dw z{b{@QC&x<1C7#POf$Ov#bf+KMt@g*-F&!Npq5t;n-IL}ncqnwY#Xs`^wTnE?o&B_5 z(k1W)+Q?JRiJt|Hn9sKFb-6mvg>G?Scwu44@d1KUJFp8HvE|3J#l<7a4Om+n#cTz!&URe{)W1`X z)OQSo|8ddQZDdb=u||tFz5x#BT|dFPXM0(IKSzCsGnX%>t}`docmMn^IHLI3G^%id z4Ma0E*z@z-`Qwk1(GawNpn#x^YsF8&19pKbtV}j=G~UM_r#6h1VF=~Y`3vKCOEVg7 z5Dk+d!WrseqT8fc3(&pYB*)KC@-eYlu%W-s3BuAJ#bnyc#~7dQeYh$Wqv)qho{}aJ z(HcW~i^hbjhZeSy*=UIFDD1rWDH8-^3x-@e>S1tsKmB(bK^F$@du!I9*bb)qNw2S} zsZQfD59+zZXi1k?<$=Kk5y4J@G190I=`>p)aWw#9MuWz= zsov2KzAy6&47mXz4WvgHrt&pyNGl_o3X^Td>M!H+J_8LOZ`_bR-MA5B<;gT1a5Yk? z^78V2!AV)kRwtncZK)UpC)*Z`VqDzoNd4QfImTla%vrOVvE5GJ`|fwyt6UtJ7WP|# z)p!tEb$0x&3fLobq)P-mpo_n&^`w(ym7gwPkXZQA!Y~>ulj!&3%N}KG22ou2C1jgE zUhRT^|fRLo4pN%8IBGAx&Bt3-Unae7p&aTEeoeJPK z$l$!X&)t<_(=SzujwkCYkK*^>CxCGvs|rw)J^xK<>-KFCWi4Qz-ty&-QP%-*74%UK z_7`GA01Qz=4siMTTYfXEg2uzBwHVYjoEB55T>;cMx5mh41gCcI+Z$UehS2^9Kv#!p z-NsMTfBdIk(gRl88TcqN$0t>q(ZD`w+Vz}yCN}0U0uA(?kOy~X84dj~HViZv{BY&? zYLw*8KyfmZTgb-8qOiB^hM*`zH7Mn42^S7VrV|x%*jjpIp%q9DzB|ePl1&h|B+D# zPl|P6(9ynpp&s$?2teHBC1ji5ZTUK#aZh;`Xdu%AL#T-iCo}f$$3UM?Mv43LuUy~^ zdU#Ae2uzU3n`Mxuq2#h!yWyPghm3a7fHbYfbt@F5Jj$w7Nh zqcD|Q{VmPaS>XsU-#WGiku<2pub@A)w}ygzYVjAk* z-)zT;#cWZ-F;Z_tAj7%jrTjULASh$dNDm#%?>%ou9|9|+AM@k$w~(o_as4N0#mcA1 zcAOQst^Jk<7_<{?D|m;t)Fon^#<|#~tr4e$aF2S`c@^&rv>C|%1iRoED}pOSp6Wtp z=k$=K^0zwMK!SExuAep5)z`MIQxPkxj6^yafH%7-wuG)*m&Rd>J@eF4)Q}m^XJq~` ze>zz9S)0<}vi-deo6!tdjeKc#gJ)|mUE?L)4IX)fj^Xz_Cs%ghkbbt6v<>u>dMT#hZL#wPE0 ztl>rigKixOZb}zJ-GgMH4Wy+0z@}~5LSn+!lc}1S&MNd9E zgChQzwl~8wg#;HYjyQwBbS&y&V?fy8{m599SNJ=(<>Yy>->fX#i=Y~Pvd;!h-I{12 z_19SxJ8|+@x_{Q}2sD(JmBon^ZaFmjSvx808|9QygzehHmyRcR+__*ZZWr>{UKc>E zO|uJ|X3gr=*zZMY*8TUhrIOk@$dj21>JWL`fQfd!3tievW_;LJam)VeKpPyB&z)C! z*420AaXkT;wX4^prOTI70DfBNMl;C535BlGLY}vK{w{Bdy}7(9v$hwuHuq>R%BzP1mmd*^z4%>vr~@n`)uEr?JCpiC-GBUQHMD9p|^ZA<8iDJ=m3M<=4N2z zb9izW{_%OR>nw{-r_Oe!C%*qDX(cD9jE+EqlIi63Ot6#pExi8afd+^dmp`32CQ3ya zM!Ktbx2~tXL|NCaSxumU^pl|@(qj)l5`hMt63^2$Kp`XO94g4ySwT~oC^(>(Fn>_jETFa0Wi55Lpr7kxS$xRfG~r` ztjbIV$rYa9XQ09Av+vUP#>R#;3j?mYwk8WSU_=_o=!KH-Y;8n33{edr0}C3k8gdGv zs}%lJd1~xxl&eGq-NUTFzWfSDDIu7PIR4J!Tm~_8f-oa!smAa#_1X>Yi{dx6e-c>42y>W)y%(n_wdK(Y+?`yoetRv8UH8nxY zPL_F&_Bg};`ZBOJ`$eMEswnPw!u_>q0TZN-+>EL<%puDsLL+-=(S5shc5|yH7Ag>rJ ztYSKk?mcD5C>OT?WyY>Xx2uZogLOMaC^zm^PNd7Zs~1!2iFS^+{51VffBo+zZ7Re^ z9tb2(E=p<2#4%|C>74`Uv@~=@O9T41PHq-x0C}OQCN6#D|7KZv4CHNi>^5L@i{I}U zXaHN>I?>uiM#J$=()UQw#zyp7jOaIVxpwL3+q98YarQwDP{}9!HXG zgYtN(&k2BS+qxw^jv+LE?t^|raOh$dFoNDe4}F! zI-S4e8*$PCd??CPFlW}1RK_`OAjx?=BTG;%Q&_s;yf5YGAqr2NEi7-dKdtg zv7GBTLR7E>(=3Mh1@d(RjPEmeAcek$MOFP5$!_XCelk6=Vg)N*6gb9lG5G0Rh%*Mn z<FjQ0 zUdN;NrlbF6(Km}EUf^hT?T=X0ga3U-3?0VQ`IV=%SFH=>b?GX5dlVKpJryYcC~$#F4-!+ZW@>k?`V&!SIn|CaQEtK zU`=^>`u+>ghyQdDoh$Zv%8@j-|K6{j$njj8TD%g&!b0Hlu!Z3pKQk-hJoPj7?AxC{ zT(g=W%;Ovtx;W-E3cJ%+WmJF8Eoa)n@=N$3ysr%Bfd=)eN7|b?Y{t91bMkbS(XeOV zz9{2M-$x|KH&hjJC9o zlm7OSjZw(9yXOg-)>c$Rk>_jJ3gL@!pR{xyzMy`R!5imP+H2D|f0;Z$L4Frg`(iU* zMxM5_Wp>A&-4unzCn3;qf^D=bzW@F7B*D`O<0mo-7$qn#^}oH>A1BZtEg-g&3RMHZ z1TBFKD=Ll``e4<&?7eEH`uAu84T~uvR~JW3U2p?7-!rP`WZj36;L4$A{>rGavdCwW zISVv!CN|18(#!#fi|nJ`Nb$Gz6iq6cSQ5sHfd*?dT)lWX6u#|ie7Yj718;!9_cG?l z(rN_TaDtsnghb|Zwc(_J1`MHw1N+i!oW&X(x^cx5NMRfthG;Jgt^2NH@Bn_Uj;ick z{Z)DC6lxf$)C`)alzon=sv29wI$wTtryIiKdT{@&my7w~l{i zgt}scF+v+MwUx6~HsK%%Y|MpI;?@W2SG@7^%juz|OVh)wisXR??}(_O0O(f`fXvWW zso#o7uFiZEBZFRk=A{$tTp83bEy^hF?%liM4CCpf(W%V+%$I`fo;+79taTu8=RpRI z9XlBYBloH(bb=LDzb6Q{cXXsT-+3GQ^-6#Glb>*IcS-Dr)`1X|Vr85?@6sgO&uM`r zj7R2ACqnQrVlI6&voJqOjy)!=_8M%k*wYex^kPemgWMK;NU!HKstxF zpoh+_Olf+jPDSp#xPoy4@DsTA5UD(Z(p*k-(iK?SbT7If=ratGc($&UsNFi_b7Cwy zzR>v=#;6tU9g{}I2$ZqKW<0)cJ5kmaehwHkBt1r;!L1V(TDsVMo_=RR1`U6KRfAn; zMuPh<0x$gKer8_~UMnoxHqfwn+qSfgm&KAyGjxlB0Q|xF_35vE{&T)bpn=y2x>-}% zKUJ5E&oUY=1MG~+dDP&)3jICu5$X|OAkY9`^;0f*pONCkYjE*9vg5e#^Im9t9lD=E zrjA_1NjrOqs5KG&3-Q?W!zZ6g^JmRYbI9PRE-ogR!ttr_n1O}?7%T_Dn3s{K3zyEP z=@=7cHI$L*q>=5>xM)FW&kq8G(%-7`R+3iP8Guw_8<3IPUB!*}4J{{*rnRIn z|1bakZ)1={UQVld;@#v#rtcXL(w0NMg<4dPbMeO&K zMK2@&8iQG?H^yxb9{8CnF4hq+(6E(2!}6zBMuw0^m82N9sK3hBy-*wboMJD2(29Fq)&Vvh{YrbjIhV;miC20ya$Jh}RIRzIDH28h>l@5^n z=A33uE%VLqeUYF30K0sk&L&qb-7Y{ckYO}*#PHP4*1li->Q||&wJkk`VOU#H#rC_A z5eUeS;Z{$H>+*_*r+nxYStMYgG8_Rg`f>}Vl}7i$Pp(++Z)_xE;uW$eYts@I3Oro{ zhKp2Yb8I<@ya9LOy@M3SCWARr&&c z@d$2h4cl=qw!!zXk!a8CAKP&yTDuPkhIuRd5(8{dW+bl|5N4Kf_ZcwCGYoMF= zj-2gIo0_|EIJn=$w`;xAcb@rS`nNy(^E7wH{iz?Px7{GE8pg$j0>j`Fvv+daU^D?2 zh?({pXn-yjiY_TFOG_3#5*ZEGp!?PHS)BuE?_!oTc9Bn-$B9+EuhVEDOBXmijYYfC z)mH-<=b`V~b?ef09O|M8Md^Nm46_M5T9EPlsjl<|&&adB#NeO}ZOZ>*yMZG0w3r)p zZNLSwUGkbo}=C+))?d->(xB#VyDnmsFxgJ-O%;`h}T(nb6gcYVdSUt~ra8)yie zpdGO$3I=L}^IaFnJn3lNrj2R!+i$0p1n%65q>c}JR@rv^@SSbsPN;I01pu+VXg2~A zjNvjqjWT3VLL0)&xNf$stXf0;iq_WjJb}CFii+TA^{TQizvp-$U3{)>`nk{Xr#49b zw}A$?Dv23p47%;{W&DJRHPz_{-}w%H+Nd~A*#OUdh>dw!>JJ_izKwk0?~#24Rw+XU zADmn9OdJuXwfB`tx2?SW+UsdKwboYPi#Vrl?NeX4c%trbJB9O`ZNmY_9EZ=aZGN|X z^|o8%EZlnod&iS%np>%_gtP7z$fu~UG@A?{b%Kk`290iG>&Y`_+-ZXwxDb!+tA#DY zk3w?o_Z9l;F}h-b`s5gy&+6~pv_Gt1XnFx#zNV}qY;Ex@w>Qjck>>d}c{7LoJKI`; z{mb*6Co`rkq&lz={}g%J`uR>?pQVe~R;Mphqv6!Cw1P!d0}Z7mWgt0Z4vUpvzQxxc zC(r;h2_`*M2>=IWg3;i#)W9TtOwpv{IMriO#7h@EMCvmuute1_u*cL}7503ei$;$I zzF?YXG}yL=sjI)P)Cy?5Fo;ayUAKjdhEF~u&``>rv8kNfT~CGSF~Mjuo1me=k{faw zF}{~GaR?}knW<FsB_W>@au!(=!-DQ zSV(RLM2uUd6Amcv$0`LzhKg8)s?b}D!Bp=TDNv)Mxn%L;FhD)J&p?Xc7sf8a?z5y* zq}~8P_F4Ugia=@MJZUVcBz!)CYhN@Zx3Jpv(l39J7Si^j1q-4ocBDiGK;G*BV07|~ z2q*v&f~1CtZCPAUfYMMB3~gH@-lB&eezJ~?hVAK3e)OYsKWTIkgn$=Z;ZU*X(bNb~ zV3_Dg_zc0r7Y#>yf}*Ry;hbTdn;?Tb zdV?PPboJRii#q=XcW6A6Wvtf0Pe!F(`LF<7zI9>>O5q98-8^P59CDm9+cYjOC`H9y zz{=ACWb#BZl?L=fyunmKz;nmTP-s;sC8+Q*Tj@}5{lq+X-lV3NTY3If^ zjG(KCw%{1OO=ya#&?Ukf{gGY9hDEo0NPdQ297z$JlX(Q81TH` zb>VDk>}X9NQ`qc(`+xpZjBzMK>5aj8e+hwx%HlME)!Dw*NWkzjpy8^W56S|uP!n+D z>9oz5c=dtCS=|`usVp*x2sCg`Xm1qj1@NkcZ7Gc%-5k@HQj<{zuE$u_oJH{Du|><$ zyx9+?z64;tU}e&idHNtrwttg8Xjr+=*kNX=&tk-l;Q3cD#^cz9de1p|qQKUfw92H!DQX+?Qgzc+8%n4YHa>_UR3e!+|eS9uG- zs=HXpJc^z1qOY++irnbz8lutJMc_h~lrK;IG0?D+Odf;K&p-QooR_UAHUI!X07*na zR8_BR8j$iRWqHQ-;-mxGk*;RKi7&1`J0B55V$MT%Aj4(_7<4{_yzV7MazE*#C6$%2 z`aKbu3fe(8<mpZA^>hGw%hMY zClp8DbuI|0gpn)lqtEnLdD3xl4sz_28I@CU=QhS@e`w!*@j_bl;Rlh?Fn8Yk$Y>}p zE{Wr1&0KLc%GE{nnIykU6Zz5kfMx}~afHPso_CE-T<6%FUL0|#bJd1p^ow8qDs{FT zNh?{!tRtP-(^@R}XG(1ZNZ&UoU!d4_~C+Q((MVs(nCO34R%T(Ra`|wQ!QPio(k+P|=ucH@^5kh8G-$sIV zt6qO2J;{FHtgZ)V)iZDTYG1y}s;-w-%7bzc!7Ao40_@P;twPFH1o!EOwGuor!!-MI zIM6@BaIUSvQwO`0FLjaq4<4aUw&Mht{o}ahYiS@~%A*D~bh@-h49w+=1ZzM1FpVuO zj#O`P*fB@&jGxL5jWTohI$+siO4NLS_IXBzE8eb>%0K(i+kg9WG8#BNKxu)!<9cQi zM=KN57}2wJq8}tT(BKOagnT&*VUO{~4KO(Z4YWx&;yB4;FKi*)l8 z^@v(dpH1ryo@RlKMr1jDu3Yhh^xyyaU!-~HnZDO9r<-R_rrtNGbwjU$PtZxR0!yPq zM->J?eNLd^leHhEZUQ}J6;*6uTbfGBD~KH6bm0u^h%2+&TTC_`&S<8isEwiQtMd%* z5M~HmGtgjQ?Hs4mn9=Yl!Gbn9J{ued}&}x zTDw|p&@_S==n(^&y;&saVDOz+&JEpNg-jJ7D=r$s2x0$*&Zh6mli8YL zq|XhVA~x`B7nlsB#Hv04G%L_(bSsZq!og`BakWQ*$f7qQ|&OZ2EocO zULNARFn!qDVvl;AAJKNukv}Zp?Ka}~*;c7DJqI0V@KlFWese)heWvaVyO&1<-tZhh z_sVT#gM8kvoH-_+ar*3;^fuWNE$EW(5*VCB5GM2*Z3aKn4!;J!+g7vBR-4quYueN_|7pKor|4gi*t-vcj zlacf(lv5N=%!k{4kM|UVw5FKbp`XRpo-=c1%%d2rO`xr(?XK@6ugH_yC1QnvU+rLd zQQN?6R0ezvG`K){xQ)!@0|#R3dn{lWK&@G%tnZlg*pb>a}a4NaNJ0)7U#UB~qGYf}0qMf@?1f zH$g-&QCaF#$cPSKL6)IIQhUZAxVVaWvWrT%AAAr6EoYEgY>kF-#YIu{$;BnllfRF> zcfB1y!Y)JjT@|Kar<17A88vg|%cz{u)<`2GqG%fYFMj#UFs7C*U6RU5%fdi6T}-+t zD0wPZIH8PPLq;L7imw9V{&Cw^Xao)`?V8f;c(!4jzXZ5GIDbCI`Fw&KgTt6`H9;dp zL&fjdwgxC)VIGXIVwBKtql*!^fbKe~0)m%d<+hSFIGL!4aHU$qIDiwqM z6o}*>!A=8LV@2afz(co(;Q|B1>gaK{W$Y))x*on%sjb8@8cS6DCeFV6qOy`_1gH30 zaOOEGIf26HbOckNpY2O~PfQS`j$xGVZ#;l=u`hmqoD~-xBUf+CXowXTXzfZ!J_gMd zok&5Jt}+L_qhjV+g1JUlKMa2ZDMp`n?A#Gf^&qw)J^AF5@ciUxSL58syzN>zP{ZHA zjLw|Sp~@)&4G5EpLKSzBG)4`L(WDZpMBKZ(jpBrZhYU+&c(1gy6bJEU7HIg}zjaDe zC9gsj>uRe8kXbN3jl8>cLInx`(}%0f#dYYROJjY8fxP;mgp@&X;x+*VR1*A$j7VEv z2qLNB{Zi-En`z(4bLq3=XE`E`y{qU8umA36|0*q6_;8w1QIRIFmBc`UMS1#SbTL32 zqsH_S&Te=2nWVfgZG&GYi z=@aPvfBmPwk1-C%E*gmQKdro1npROsjRp)c3Xt6Uj|a z=+8I|+8Df1B<=JnDYnM;~6A=G{LBM{`iR zgcE)Zyy}Z`?~Uv*Z84^BXpj?SRsK@0Eu8em>#wKjRP`Mfio)zr$;)F4PoM8jAK(~m+O$5^vj8!Jw(F~EBGvl~ z92e=XJbFbYgE~dynV%Yj_tEhoeW62-&b!6Ku5cLoZJuKgsSRiP<(FScUF}Dy(eP-h zK~@b`tGk^$F*uxx9*l97($!Y=u2t~Gcb{vJ!EyBk-%TS|r<)z)=|2VxcJ@6trMSuWgnqmmm;ffofzus zu6Qbqxj)-#z#M7=&}P(!VJvR3ux;hXzADf1XQajRp8K-nC_w@ZX9!e&|9jbqR7gcQ znb8()1{U*uZ7+E_^eO$*ez0ww-t2v72~Q5hIX75*>=?!6F#gxm{y4H&Ee5GPNo)R# zXSm`V&aU%7+o4b4Bj2;2q*QP_n-04fBzT>DQys-1 zM}W6(oiNZ~{SJfq%B&6AruT~h*ZHyqA*GL3FPxp;1bEf?9(UYt5J4TBnR8%q$Hl9u znbp{j8aQ@ZVd;7Bibubj{@XwO*XcoIy6<(45Ioo(!`zC$F3ia{^3g7M z=F<%u*vinI$}6fk;pP#3RyavGN10P6CfH}`C60j-nQbHvKr8JHvBtoQJgTg^4eTr_ z@E@=HBz=m_WG29LbcKNikNY!2NQ~53)DCu@bRc2Am^DqSU~pCESz0y6b&W|DYvoxqP(r|p{=0};2fC2piQgnT0GLr_r;>@ zk3`m8S9*tSPA$#N>4g_4t_of9lM@Ug+NKvX1}VV@=2%^u<3h+7ZH6x7Guzi6@wpz6 ze28{ey}OD)ctv`SRr?8KY8n97ud&d*_LB5b#~B#a$5D3t+w2$hN7!J{PWp@W;+!YV zXlw66|7}{oK0VH&*z(0of-VLbw5|1Vg7)-1=2X6M{+J7G=AbcS(|3x3>*zjt(~O&w z$c@1OGa9T56B!LN2sFS8;+6VAJ3e$cZ88C23kTmb7nzL>H_>nTUU^jp`VV4TKD2Sc za0hknnhEffj4w`4J+>mYPM8gAV9iBHaV*oV@I9Fc`W}%f2d+gH3w`l#`9!_K45j`o zGGDlOKJ6etvW?f-%NHZiaOV7(^bFbCEAbh|j2zFXow00Q`SGp2{^fxNhtB-T&@wMn zjL9;prK4=xZ6iuy8$xK>kEc$|gApbXsqD+=PL@m+3?NbYejq7~Y@k8rGGZ62;C>|Y z^~SO5F)l7%rl`?pJJKey8isQ`UrkLdN8e3~lxCS&B^i-bCRy;%C{a=RnAm>|Q->nr zc?=*Fn@TQ>EdbX2_8%i4hg+IcJ*zEc#PnX!nH)C?1a| zIN5HNalooCV{}zd14p2;2+M02=K|-#`3u-j&VF}RsVz`r9|iAl_Mww|z^!mQ6ejgO zk0Qzf82}@o6f4Pqh>AZd>GE8UgnJ+GtDlk;ud@=a&o6FVS0!jvs@QweZ z5p8Q2`89O#^9iiVqb zhWB{%=BZPiQMr2i_HAhrfvKgBJVF7{QPHk^V|xOK&#-^~lz-&uoE92mDte6}K{fU_ za-;j{np-$>r}+^3zq>ecZc$V@*0HjpwtOS720zlC1#6_6G9bOf8G}C7EHRDLKJyWv zNcI8mw;gRK6}yqWjBVUAAod^E)zn10IzeIN(_dGPG`M`8N?zK^pYn$*f{~uu!>97m zNDKxIUMpAYbg3+c5qT{tDvCgZCye~ZfBFS2r&Nt?Fp{p-m2omcNl~0Sai^z7g9`o@ zuPcz-K!adufMFodv`zzl0AnJ^!MJtJJsCko(1%xV4Hf#?Nk+r2V`tK~_Vc8~5@@g) zt{*@BLYj+lGo!9Hl@*Q02w}wzMdutF>^anOIF5_G3~<*Ie5u7@oQM(X%H`b}4Pc1) zp+O;Go$m-_(!RXyqcn!ZBBR~DR7kG4S)*a~d#h7S=*`Wpg{Uc>RRhcIo^ss^X2 z<)vxdFaizKy18=$g&uNaDlv`&w7n0*w>R4-;2f|8V*|zCn?AU$$W;iYo*}x@fO4j` z4T2x1PPCo5oSIO~Cr=Y-=-HOCcn);MA$ypU3uaOb(tZAyiMroFd7918hv$f$1{|c9 z<8$>zV?{m_%Ra`j^Ekf6ix$O}k~nQb`OqMPw#tk~pua1t8cRAw8YIe@wDR8E$nyRR z^g$y+zT8Ec;R@0t=W>FMa_DvegVe67i}kVcD!((wrUx5b6Eh+em3|nM&7EqEC4<2h zkve+xD1pcQA$!XoT^`3?i?LOtTP zo-9hU4%`xC3cnaHZhOfG>IWSPY32UmUhJJ8jI63-?11%Vkm?9zm;!D<`Tf;vINtJ1 zn#Ze&}h()aR&MV=m~2x>dbyz~gi1vYqU; z2MI9FAoI%tqUwj3GurffUO9g%Q#vvJ^b`3-zA+P0zA=4RZEi|*2mG>yw$CD4k3YU5 zf{)X&oOwipa9IhT$}J4Cz?Pdx3#zU$-~Y!KhCGlolK0DwS$znVr}3~K!R(;IK4 zLGaS$%zsNybG+pw^i6i^1WqA+x(`gX_CipD25nQlad+#4Vi6SKS=`r8K?oRuj{VuD z0?(dC&$XSuk`8mc<;KJCA#EgJddPqYY31T2=?Bk$pSn3y$(SYE<1$fU0?xgO?#1>J z`mN(@puw?-K?fQMYNDguzT}oiiyoGdJ>{yaj=DG_Pf8c(H{>Yr03M-x+D-;#%?ee{ zcv#4-{BHXGR)SM|z+m-SU=2D@yD5U1(nKtPmO*>?ET?@08F;pQ=QHH>SR4aqe1_Rn z?uTDX5To;SC$*KZS2PR${0jfpj&mtdoKgjVz9CzR>_;%@5+@c*4nf3as-;;Suc+g zHsfw9TZyNDzhdNQvOdgOR^GI?yu#U(FS&-2p=w~kK)Tz0)OkAA+TZfK1M<7_RVNvJ zW|OpI6I?dF*XCo(jenN*y(bBkgnEltuDJH7Ce zpGLrB?1*u8I_6*f@om2T#eoLr&+FcwVl(DsylZMx6H%e<7%NRM+jRtTT1{;fP8y2h zaK$1VI~2W}CHoiUf0m41%N2(g4?36Q~`V|H9a{PXM{!jlzMXNLn$x4)FFoWc%UgI$tVrh1h2) ze1eyTzJ@>^DYfnBFMZa?@O~AxQCy2n9zqx&S-ON(-s+%X7(hM3C)oI1S23iC`@#fq zjejG?F-HhrIKDjJD!)EY@I65!bRU5d+gLzGhQ)g{>V38^0VE3=xo4NXWPsC9R*Iy7 z^&cItBP09Z`rJ8frbK7-P}5n)nYK~AqzCfg93MN452>su@45bTPHp{ zcA7xL#RxQHG6S4>0;d9V=#x06f$SW{3Np{sn3g8~3);}W&vF8e<4kKL zo<7|bskT#aEUJ(zF(y_4p-12%&$j=u50>`*J)Bx6)r>RYITPgNH`F7U?f79H+WMo$nF3{%yteJJ78FnQ?oDooBY<)Cu>n>zsCB{BPg3 zE%v6@vt84SI32J80^`~l&S^L>j58cA`%PQwjtF)^=ggU5KB2w*s1AYKz}xE)thUa9 z_%)NvEHkHU8^T3E%sG|Me2$m=Zh>iajQZ2hBWOpv-siKFRry4IZE9+Y?RVC(sYdR_ zDd#eiQ6H1>rMicy3w#6qHeA^?#e9HcgAU58I?DFsQ+1+r^K+d&js8rgTB2@|@-&KVe%eBr6Ugcz-w_*R z1!P){+)LIS(} znVSL5X&z{xG3mow;h^JwWLqa-o7l$5`vvrWpqWXS#b)r`Mh{qvsEfT4ZRa?7=**?G z<2W{>{UrufSyYqeOq-pSKk{grR8@n{#OAr?akXLrXwF!iQ}wb(n;VqT>1)GTZ#jH8 z>@DrostPjVuqneqr|qzHoi|?2S@1`Xe942c2mu}_1Kb{bDXpZD_NG|SO8a6|Y01P? z1K(JeBzRB)$PctFkBMd49LlQL;@lZf7Gn(3YF`Jx^SAPM40~ob&gdl;2_|4u7#wtw z!;G~k>_@xePF&K7KFN>rwY(I3N?#q9@+zOnqw<8mA8u)(`1j_}*^}z(;-?FS-k)vh zMZ&pXKJ~az<N=gBeTSgHRbro{N+ zJ$0cxBd^4k8~i&lp}Dm+ipHDuQ8;WwnhMSrAy4{!(uD?j#ni@}(rD=A*nSJ0uJi=7 zBY1@_i#l&S*Q{3c(_w6bMlyI#F@{cp44vn@($D_l-^THl6Gn`W`Ql0T%pc#{>yHv> zfHy)p=Cp9id=?Si`?f7XI#*vu0@`t+0w5X$2;ycyC7>E;Fm27>tu-J(hQY{v z@z4A16K&fEjsN|-K1*XU;xt0-pGxXpun92cUi+tTt9%5e0B`2S{wkC@01;?FxK!9a zU)mgQ+?(btULM&PK3kdx=+UOnv0eM?m|c~~=gsybTZLyBWD?jNyCblcf%~%ElP0K7 zrBI!FzHKLe2^=vFo|7vG!A}5Fp=qpWj60Vax}ku$*E!LcaZgusQ)3!8p*V_&N?Uov zc~vpw%2;J4_=iC)eR=sqo^%Y3Rhq{9@*K}dKYgYv!228^TwRwHBy{|y)H^_bxBmiQ zW}IUPL1RDDaj}1n+xe0?W1BMrOGcNvypCAqfJcaw1hb{^h?mp3- zK08UYpT&%$B!a-vsghM1D_&Ptl&A5evTE?e{$qKX-#tOVRqyLJu2IvY3?rRYC}c{Q z4h7Fod08G53&ODGz05et=F}jV^bP}y`@-pBJeeWap7yX3IDUL-)UI%QfJzZ+I|yFL zx{jOkz(a>I77b*L+pDb53XFYv_stvz9?*q@-FECKM_e9FpYGpJPgv=IZlmyj%Ek;! z_|^WL&>;8=rti#l$N7RIZcDUTff59!K)M@^9g23h2bSX!Yj&3 z=6Ku;ENk)@C~&5xwkC{BaYXqLi})|-EbqHL%b$nrpBhWyy>qwsMSXb=;! zIgl;}Uc?mn-e8*eE2ad#^w356I0naJpj5iM6-nc}vWnwkClm#4832*?fs6Fraaae* zEE4H!-^G>K(@a}pm6?uyrvCJP1MQ6m8$w1b&ZcZDGX`;E`vU!lthg92zwT7?jpg6;UnWX-0@?^5ago}C4HAZVuo~%KsWOx2J%J( zzs$BIBoq83H--ZV_t?J1sC(8e@OcgAqoSgUXRs&R@zX~gTl*)C7tWnPV%wY1iZJ(0rUBsU3y4bGi@rV#E3m$QwJniKe2GjR};I$b62G)Fr zp9jYAQ(kvYeBXX`K>POAmQ;cMu;^X{0=O^co@aQ!FE26Ej0NRNnNYXNliBB4pustC zPJO=HCk{6^Q^(_6nnLRTcveaytHu6`NsKv)dvm`*CwWrd^fT=Ww}nPvNj=6rjzd{i z=X%twLH6Sv?P(YeQEhE)EHF5S@@&Q%=t>+2$L{`pY47{?SuB^G<&b5<1Gi!ZUh=`qesA2vB!%hBcnn7h#C!~l)1{Op6?$o z?jy*ns=LFpZ$d9moH&8rY(c(u97|D)i0*JYTVbjyt4%Ye&LCxb0^?xrZctYQy=I*p z=SU2YPvjr5#@|m7Ftt90nT-}3AI~;{5!7qZp^JXfN$CjzGMe_tll&u1Vi7_*a)~wG z%iZDJDNpTf?W|BA4SJ3rR}^&)EQTC>0I%e2i#>aXA*ewSwUN11A3i{BvT(qO6R2Mh$&bW~H5NpQr!!U3)dhF2^TNsuvA5o+LnW;&=z!pUYEOSy}Lfgq4;C zkD?#+QF)dAQEZy_VlfZ7ygRo%yB7-{Oib{r!5>dUaXZynvKywcSZh|eG?yow8{3ov z;$P3-`TWW6`UCP%a1Ni_cNZwdgyY~$8#v<;qr(ReOBECG0hu>tI%uQunte0A7nwR> zjWibH)X(y+bLA1c(HD7`K3Tu%IC#^Jeljzo^Fn7jcH%<%cYpKm()WJwC#jg@Eu&BT z-@bpFuRltlL0SjBGad}3DS_}sBCp}Vp$00oe?TFxP3bqke)${erD1G5+oYl_hWzE* zbWSpn`||s^hN%$H?vGHLLVb;i6((&*`}v!`!`olGY=@e>U%F6xX*e&pLU`oY4Of0) zO51c>^H=ZZt#7{fe4~(e9dF(r+hjc> znAFckvLbzrRff~7{>ZM*i?sQ#c?P$C?ed_a(NrgQYr|QhmR(=FQ$2RVm+qDZ&i7CRejr7TuHz`QX%OCX$&1d{ zH+}z}+rpvy>OF*+(hv-@0i3iUkX|AvaQvPx$q&Ay|35be_FtNOm4}^EO0}`4m!J$c zT>auw%r|cA*Y4%5-+Q@wPHCz{enfnKoPT4OV?%}EaRDXA?uEGWewXsuSco*GoRm_4 zy%5EG+du;Wf-rhC^tssrYOam+XBB1;FAGAdC+jWBffK_2(eW@5&&gnxS&_KhU zQ|HpI&I_cp(l;1H8A3&-f%g#*VP%H{wZ1k#j%8G#fdv%oxr=lM1#yW1)YX(88*f6JEeT$MC`E z!2{B$L1aI$igugS*<06fXnEjpgr;;%K^jASj)8pE*Ax+rT4v8cgP9JPb}?4@!(fiN zIX4MT+{QrAxNT(x?cm8yBI%qu!Q@I?Y2)R1<-0%RlHNQ$=sS#`RuBIIrQD7&@1>k6 zS<=x<-j!zg_^_Ojpi-v8CV|eX&H+l3Ay`+iXaeIM3;qErDXC>&WnD}%Q^M;ua4i( zynffb%ljj+JIr|c0%P|g!I5vGdo=RT{7+iQ!}sEh?~TSL7{sclMP@I#>dAZ3CBK|c zdBE{#GyEZ!bKxazMqvyOB>U1V)AQ&*?T341$@!EvzmMnT5$R_i{Qf9jR3HeO%oOK~ z7||zq@AtLCEnm8%yZ!Zh_x5Wfe;1%T`lDa(V9dL{>)v_g*lkW0?eC%^`em2mMZ=D!mMgtw{OQx7dR_f~6R~>cTm2B$-KYIcVu72K!O!g%U zj1nK*hoga>vlh_>zTXMov~-_LTiR3Vpu?;?IBf5~GztpPkQ{yx=?!rQdzAhuy|2)<_@erG0QOoe771>2LnLdx=@{ao%?R zf$bOK;OgjIBctdN0T27`<=lAxf6X}jUVe$g%IiRaE_lW120TN4NZ_!xo^oWLzKZ$0 z^`%SRbIh!Ldd4k0K|Kqi^~O$Qk^-$ZA>_tiP$t+?brKhOCg zdpFa6h1h!isPSQaq^swsw}hO0Q~UXM{?MP!n{;=Rc|QUq2Cc5szFa95{h|8fo8-wp zIG)kG3Ru`R=xG+I{-wOGY&cdg?~|vc{Wo2|OF!BF5!xN_jJR=%nhnnB|M8dqd-};w zf0~NM6h(7dcK@FbG)M`J*?9RoFDJkiHY*|c_d!;T*Rwrf`p4!$$0u`pC4P<2_`UlvV3N-|U zZ03V0%0?u0ejTT)>;7)k)|L4S2x-Ii?Wu)!D|ywDLNyFW->9n!-M$&Awy&-PS?tVI zQx$_Nf<`X$)d^QDz0YyRDg@5<(Wa)f8-vMf0=#U>G!h&U zS?Fe_i+#5pBZ7`W(Q|u^6^l)2w_d@Ptvl~J#4F~`A@W$r*yw9dB++?wUziFwBJLQ^ zKF4vnuhh%-Vt+EVd3hdZMw2%)YLwk-s&p0 zebqQO-7Zd>;JZdVwInpaB5jcIx}Wv^9-guN`qJ@{mOqr#Y_lCSRILBueq;-r%1frD z`7+BSP76V9+<$H{H23#kb4(Cp zvjkRv7;hzjTu&8o7G>fP`gtJQwOwP1WYrgF0L}gy*#RJMWpOv-+reuWozE110^n+- zcvgasjElv{cPdK;NzM;{mxES6@cZ}Ba2;)ZvUX#xpnf6N`VT*xlB&jCvPS;7czZtR{`> zXHm?WHEZVzp>wKi?Xqe&d}eVc125b9n)lQz)+{K?N*AYPRC9#iq)iJd!Q_S}zS z!CumLYF?MZZqz>5w2%qE7m*>kCi*fq|^!<0B!Eq(X;Pwf1Ewb#^iO;uv&DIGJ^!3zM z*y~-@t5uzqM+)6S!^+Hq`e4#tJ=~ghnjOt)K6UHEcbxX~6={ilrxL5f%DFP+N{sTP zF4=}2^!?0|!6}vhDs_2b@sk5XgQg;PrVR-m>ZngP9Amp)%X_RZqY9ey0yvS~DH+$4Fd*zU%v4uOiY znpX04>b~;~(^6 zkriV9U77KIFIOd%g{&>%_s}`J2)fiUI(csAa8>X9`Gq`rPrvTe9jaF^^`OOAt$ATR z7LPZ}v}$yjOb-c)_G#CZX>FmjcGcF}G!`E7bevga%*dL%zmQ- ziaoM>SF7n$?&*c*W=(o}h=HLibg35{3(v+P2sKMAw8W3>EztF&w9*9pJe;~b6o2dd6I|Q1?3Cd z&f}GtPkjV!h%%*J%)*GpzuNMjeBf89UYjnK^sTj{wA6dn0q~*&nRBlJ7K5x;)M&66WF^#X1suQ3Xh6sqPSQ<&DrGeM2sH3s zdD- z(bZag7v{A3J_CpOsa&gGhI?#H5eoQl{0r+AzqI-`5}9OkI~L=y`+F zhP+y}ZAXnPd=3Kg;=2VcZQraoSMjS8@G7&?!FDs-4mw!(Ngv)AMZ39r+47i8cEVcP z_3A@L?Ez#!Xj}C;lUMmiovREvcUcdN&$St5o!EbaYd=@Frw!(JSN7MeTuEWgxk(!V zj^4xx)|E@%gSKX!cxf-3OZABJopzOn$|EIEPF}$^Nj~*+Gj$itn;DBY6%gB@)TnAh z2B34M?bde4?`FcAC7=yA1H!?S+Lb?ZYc~Au@$G`-#w*{k$Yqw;lxZLS2 z%V*jJ4;fHzs28P`g&`HlQdW$1BzsPLdrgiJFU-A%Ae@TOcfH`?gpjAsXOta?C zkJny&CRXDRAK&@d=tdRShKJNo=RSc384VSi0T+g-)z8e^7O;0^4d%= z{yv81g}2{{X8hgbt%@~;28L2GWsu7~8f=AKM<|^X#|g8^ z3u`G_HkPq2p8jzb0c_j4H5HK?5`b3BGwBrw!4ZW;he1F?<>9@ysQ~)B4pSDQ;WM2X zokxw}!lg@N#JlgXpM4icjd27JN~A%(`p^Q!iNoQz6>Jrh_mtAWY}e=MM0jO77r(0< zbb?eM7F?S%e?h!QHRrB9dPJKREuxOf4<}crN&4!9%J>=*6_*N14eAyX)5-)Tay&T> z9U}vW-5ihR5pqi?tTH!2iO%e$@+@E#U{xJ>zN1qns36T%AS#FKtF-pn&_u<@;}{FS zBivQ?t;UM?H@V-`vu-C(elI#wDDF7gH%(TfQ%aFn@#Pp0dKp4R>Kr?^q8J!_#WPK% zRI&RE-(N>MV(ulT=;$n}=bd*_|2Xo{_Ia$K%1-_j1k>pIJi#;Dm0z51i#zIoN;82Y z!8G~YEkf=&UdrCJ36mzosE=mEK}6xFpL=e!h4$5PKy6Run$_Itw?73Qq*3xC#Q2`i z-3#g|DLUofpkNJ>1Y!)PJ&*m}VH_K^?YrpOp)E&w_MwnseT+P*_&6(7IbA?SzRRlA zjM;!t-nD4?vRJ%)c}$x*Gv`F0fkkzIhVlRnbtwi3(D47M(U3p`{VD+s zRhe5)o`AHe7ZPY-90siJgRaC_ejotc#qX=w8~gF9wJ~}Lzy#0wBA*)3?eI>~s#(iu z(wN!>fP}8*@1l=7TGAztI;8&wW2TSld?~vIb;<;UD}o~0)A3rcY*`F_Yh-)@?|1CP zX*liLW;&>6I;UQtO%0rUBkeUn%CGxuV5@wMIBqW5;&D5Bj$m*_%by*GnS?7o%jrCO05ix#FM$h#!Q} zj#vgLa1>&31j?&^jfSj5PykirrW`%l3p8XgNbV`Lo_&Hxqyc^3gIs+<+bh2K8e_gG zR;}L|3k&Qoj%?dHje1>x(He|@8&0~q%+ubjO5d0|Ahqk%hF7SIvD1L7a73UePb-2i z9gD&_D$W5{7bv%dE;4nT(*Q`3U9@mv?#G=nZ(f|;uU{P5zJ2Zs)uB}nDlf`;$w5<{ zI3Mc#3=(lf{aqOr?Dg#HN;rBt2c9Bf`tv7j8M9jV*=L`_KIdl1=^|Q5|4AKF9vbASFK3 z3Dsdyhw2n*t5Oe3J3iCN6bQGd*w`UMVj+Dxr(fUb%pP~sY%_frzO!g5EhXrp?oOQ! zUmJv_o>$M&zHJ*AsCTppg03r8t&TC{$H%)LeH_hczdtFO9on|dx&|yPk!G=xI^YHf3y+_Z~^U_!ysSK&lbm*kL z$8Jh1_tgK`E^kR2^`y_$5w&j94(#)E_HaM`@~c@e^~64XHS= zQjhE4r$bvB6Vp-={i3KOSVH^iID-~J)%Eb@l2xH=VYZ9rjhn{)IQWJB z#oE(Y)lQwe#No7UZ3j=15R6Vf zqc7Sz>725aHVPU^Yx*axO7qL(6Eyel%`70SSiO>>WuL{&d9$MHaow|+_rYv|wfJRG zqY4=(Sd>nM^AA68uQK#Cz_;?LJ<4MwA)Yd2fa5WnpJV^#&7H$35>s*uD~W1vPCewNQ1(6)TEtanhrhKHon)3>+6AXm6odvTxl+@i#IokRPd7k|)A`piH1JZQvw zjzWG>n%$~k(Ct=*S+i$R2Wx7~U;jm1eeO9NHQkz6k-P)ibIi#N+$T@yXKP1n-{)nU zwC7wJz`H=;f}1}5H_YwQWy|7Y=raEO>BOM*;uL(3=J1U6$%6g@rur4>TQiqgvxxST z7r&$5pgwXtseN}*O};M&|8GMNe=_^ic=P4gVkKYe+xeL2*{y3FeBc29?937OVU_T8 z3p&XYsx|?17Y5g|@H2VrxEOHBh4GVtKZ%;ywc_%jQuM#~`p*Fk(!!TNl8G>uC`^&b z1r%iZaO$*JhTxV(I6H!BwrbKeDlnm?b4a~eBlQH^*aHg4~%vg zPC2LB_~Ux>7|0U9gUIv ze^|n)T(rs4-l};gZ zX!{8Y0PtAN+130B6DP#**9Vi{xF&va{k74D%JFqbH6yl5qp$O+65`gqKLJ^wvC3B` z(Q&y2$9Fei=e-?fGko}E=Ibz8xfd(Src1&E}Z4@+(#z00{Tm zth4)_7Dpd`B-QDgQ7DSjU!b3-Ja|;nw*V!TktH)hcC$+K74qV>`$lD>{(g0#8GEMzILv~O8C|g~!>b(1K*?eF zaJB&`W5>Z2XmIPql1>8X9xlcUdS&DuJ|dPY2Q@~E3Xe8 z{A#>S2GvPDd&Fhu59CCH=C+)&WZw!qQ8*^*n{<%qTRJpO3YR)wwss%4L6_Mc>sUD+ z`OdrX>%Tp0j1f0oercSBKC6d=n;ALuw>-YTmB0-yV8Wc_v~S3bI?P~K=gnXvS2t-} zJ?iu3O+H3JVKzj$;|LI+KMYm3!az#pqHJx&FxBXQHbcT}Wi!T4@Kx<3X5dtzk zOFik&4=C*T(4YSlGgqvP)4O+#GdPOvFhC@odudW6-Y{&<>kzrwvh~`CP#stL}S* zF4`@5HUR=?B+&33GQ524>UaaXJc|80r{D2eVce5t4kF`AevxlVpsxXvz>VXU&($fp z@SyzhzI4|)mmlS2>kiCaurQv3_PcRN2b^#MN8lYnRsE*vD1SkwpSL;Ffj1!>Fjvk#lX932V+HNja?rn$8rjF3& z8Mu^ewY-(VgmbEV@VR}FXUw>piw`#*+P@Fb@Y72!CAc_@)Lsf#ll|m*^50VIR(+Ft z5}DOePp4nL;dcvY8XO`S2}n7g9+|kqRlvD(W7@Q792NQ^r!#en^U=eeN+xLR31iBq zzJXWDOOAt)NDp4pU$4*SC7_J#>PxyhzH#Hmu%PBh?CU!V7sss^UlOOIC;@uf z^_~P8Kyw!^TN;C2d?B6#EGwl{`}6pARib&_+5lYW2>@zqE>u7VmIqxc*?sA2ACv=Y zGb5ngvYgbQnB0K2{yQ0Mop9B;V}zFo3;Q%qW101Zq*^y)}}QU?GHUA<#F zg(9a;jziiuiL0-=f<=xFDKpw`GxvBzW|AmV2{K4~o@rmCy^9Z}V=E1u?4P=BD?su@ z=JeqQ{+Pb@m8YK`=bmv!%9A`;I&nw6pzrIPR>ih@uR7U6fZyyQ;HFLKE!e2ebf%Q8 z&sVLA!NW(yBQL)k$L?1(&b#LN=+V7<7JL1Qtr5A(OPh2yd0t&0zbmhTXR?l2PyTd{ zGN9wxf`ewT%~~)&{`Jf=F$R5n#o4DvckEaD_U#fN+wtWN_z@qBHdE)|LwQuOH1j#B zkLb4mp!7&EnYPUe)po0E-uw9DcmQAQh!$-)zV>)dIyxqrHg24H%0lwWjUa$DLadECqQ z?6W|yncM;fTgfuzm#k^w-xfLdw7FrUM$yi4xD`>if0EjpHLt8;3$ zhxWsa25q<*d`x?ZtQ<0fsY3wiR3&vOg#Yyi!%W5&dDZ;y&jZQH~RS6&%Mwrih$dP%pd z>l27p?>Kj~o4}oOpdR9V{XQ=N5)@-dSf-^Qu9D z>}DY45v|ytN&qMNP1-l@^-jjK0zLaKi^%Pd>yj~V4FNx|BW1dCs_>ggDF#E-O80wi$JUUv7MrQi0I{uFv_z$#;r9<5Q+2};L^zNwTnCZepR_f&c^aRLnh0|E^qt)DGg z9FITyTs-;mD{&J{*8jx*aV&_U>FD2MkZo6o!k-GFzn7dqgB2Kx*eh|NFmjAV=z*)~|mYfg{wkVI!0TyUe&3k0b#ThK7yNDZxna%D^4LQ^^>Z zT9nG*z!Z6}jX3|V0*;swAmeqNkU-xg7QrhgJidH%}-+~tk zpNOgBaa)N>abJRQ?_IulaaPS8GIB(0M3LQe1p-crq=w7jB^@^U@ihj>H1`Z5R2H_+ zWlETViZI{Rd({9 z?HW}0yKUxk>F@W@TNGQxU5@tl2sE(Qx$1tT@i7M;GdAd%LGeF>heTug^w-B9k6vB7 z6ls4bQ?!5bxnP&FV%7@Uk8g6xM}P@}3kA@?*~kQ4I?k2JMA?BOFb?JS@B@E{iLAh0 z*#E@1k-2pR+5YZf-du@tn}Lo*w#|4Pe_0$a=VB@2|Cp7;39L>$`PwV_*hc(Y2Oqdi zlSXIvQ;{9gi#x^oa*7|R$*QlFElo#UT~)ppxY0$ z`6XLJ9FxvV8Q$j)2E2ELfIb*ZPQ{tH`@sjuh*=odUwUbAOe+C^ef|dLKP&b##~z<3 zXk-dtG9bpnpFaD0=v@vu#VeKpVkdup!+fmUx+UHnKOt_u`**C`_lkbU_l-_uA+>1S z6hjE{s5rh2N7$8<(NibI-T(NT#LB(vHTYSRCikmWCTi5G8T-}Y1PGkh6>FBpo(*hk zYEV87-j8e`o?FSi70D8I$kkTTDe0U=A&b7+D$XWzx(E7hVSCHM^;={1>aDRIylx>` z5?<$U9(_+%T3a+~OuAnU3KOl3haY`B8XdH6TzcL)(X3IUq-8}4c9x+K+IO_G6DL`o zF;!Z5cZEnA>9}|q^a-SvHz4EEVO@z8l~l!t?tcKAb8LdK z88qua!0+nvBAd>;S;56=FnAWI)d4c?IGuF*psue}y=tZ#Pom#1JpXLGICesuH=uvq zboJG&y0n4T^n-SF(rwpgWe~!&$nuUw2hs6mki<{*j*hykYWuLoZ7Vc??aephs^8w5 zefrH!H^#to&Q9=0=c+8cSdLd2XrF)vv~k716!=?gQKyA>(~jtDWy-9!is#J67C$j) zQ2gVy!EqQ*xZ}@%2C(jxwFcA!r2xaeXT||P)oIRY;V2g?#|9NTSyB#4X8N(uob>+t zapy1Ziuac;i;Mam9~WG7aU6Z*k*Uja4)@w^1Al3iKm&Bnl}+rFgmNsltqw{69(j`f zn*i=cj2RnO1CDt8?&cfg+|$owI}*Nxff4dw0vcS^*6w>b&$-&pcMJ?&fj3hIX3CdG zw-zg;pT~2rza9@h@pxQv+JNZW>v;O!F+rZx^XhnL?-}aOg?;ro5GU=1StQP-3NGy< zw3q(sH&1AqK~?vEvPe*dv7deFX#_4ubIMDL9PbyT43{PNtOl5+&aqm#b6|FW`qWEa zk;VoC1_(Ju+W&$;WBKystRBA~fBWm7;`~c4i+(-GBx%+xYLnF`U%Jw%GGI1;w0W8J zLEA10WFQH>wTtqJmo-JyCuSUYmi)-kqhjjZPviERZjNpMlJ(i%P=#!`odm)=0Zh&0 zGXueAcx8|QEzCx7YpKEEPW2^i3N-A8jxnQQCRuXh#*U3AAA2Oa_UaecUVL%1Z`m>` zA-is!C;<(2OP?tF$0MYR0f2mIkL7)R9fJ+|ryA{VB2#Vb*m3dtD=)>XAJ2&2-f&}F zKtO#+-Fm54oJ8Bq6DZJOpDkPv|MTd-;$N@6oTIQ^s1UvP0uB3Bzz1O*72t)k@{%?= zM_lxae-nKB4w>|rRqcT~K<#J9?6zOs0}>gq6J>H6+eQMArOf~2#YN^G?j&1|dXuSB zmyE;j*%G@wCXE>pt&yYKZ~J+4CcDgq2KgkZOG#1OnT_RCK%;!A1NhsQ z`gs$4^9~sScinMkZqB&lqKo2^^DpGs$`&b4wyz$uZGB($msj z=mdRL`Cs32@#o895PtCek3AN>YVRMH-~Nl}2f(&Je$$scTN%p0QQhJk7(`;9n80FD zPMVRO=%r3p=akc51vv4UAI+W>58?~IIdMYVa?$xQ;N+7tJGl~bukCjcNV{D=vzQ1@ z^%3y#%L87O3MFPH3~ia4Se^`1xAwRIu@zr?9N^c_Z@e*%ZGU*2a>~ikz3XulPHnC; znp+gor>0NoW7EG}=uA$O1VwPF&GM2j(yno@na8Wx_A!*~qbDEvM_haLbcuzT%uM4;&N&Bg zitT;%>qo_0gdxtMzuuETgL;v1n7OQMSxDCY8XsicALL5AXg03df-~^7Crp|ge|!Fg zxRXVKGl)YP5ENUewu<@+Js^|2h@3GPZOU`%$x_hn-^zg}rkM3qjao5oBVDqXEE0n4 zSKoLwrhK{}9>4FtIDw4zn){NO1x?j2>P798{G)D=FLUvhJ{qGKxF^7lPntl3&*EhU z&nGix#PH$6;vcWS8NFD1`1Q|!9-WRjGJSPvhu|a_r9KouvcC!9%cIVRlcN4*4tzt~ zx)0AG6(@F3&~-R{zZ-vMAz!=svWw%&OD>KUO_~6LLv!kS{Q%IFTPOe;lo55gv7H&n zO96<6(YFSNwvF=#o*&ig)lD(We;DI`^Yxzr8l(Vo^y8~EBm6Wq+w)T=qR`f@See0D zPtf)R8gP=nB>+o@27!|C-KR2U8mks}{vwvqfrr4!*^F$E?87y7S&$ly9Hu8Jr~R-N@M-7z5C|9b4v1R8p>($#>h zfSP~>idj1N+^290>Uh~^3D78^&Z$tLjpKE{rem^(!YmxEp`+gANWb-Q4bH@o?K*H& zXN^>FIz7_Z{icq=eicDQp$vV`X;h*3Wa;55Nkx>?7J~MdX z%o)tkMQ1iwq?|t;7wBWwgbtC2wC&l)REqpAT~vgEAD$JweC5g*H-3B!dt*oppFKD3 zzy0TNN}s+_mpTXK@bU$_beyG;eNH1oXQhLe&hn2&NZ#>nepVr{paVEsGve{bAB%qi zW;Erazx?x&P)6K?t%EEekj{So{J+0zfaJOFm|vAuritM|Xed>z)luHx@cvkUyNB+$ zJ*J{)FYMblZoc-qI9z#>H*geGs?KRC>&3ZEpoJBoT`2TrD8NsU;qlP-i6O5#q-Y84 zYm?63vSHu$5=S-JOWdZU@U)%QA=r8Kf@l%h!A8yQ@mM zvVjAyGqw*h@dJ*+CemCNZ2dYu+q5|g7B1IM=DO_EQ!^FtC=6%QMvY00EYJRb`kt(&cuZIyGxylsWq8Yv}U54rLKoC^I^L%8@!j z9qiQmxAU()Hu&-qXqc@{0DOKKnY!s`H%I>-J@R-!fl9$d>74;Tys4fv;8N$hy5>Ck zdpcdvT8FCwhF$^)RL^7eb>f5x@%o@=Vhe5E_xs;PH^5$3TT%|?3uxkes^hgg`MwRy zuFR)>Hc&EfbZqwDJ=|spO(WxO$m_4gqi?+v=ioTseC3sFVQWF8iRDD9KZtmDwR z{ZZf3uKl)sb)0?nC_`7&tgT}e>Je|h9shXXzL-UK?!5AfI18R{+Nfa$UF8f^1a|}m z)#db2dC!#>Z7BD+Lg!0csNK`HNLPc4c?%cDQ_nmTe*@HP#dq(0=%MJ>yLWEW`U?Gk zKxUtH=+rL;FGY}nT=92;vCz-JLj5Q(t1cF3ax88=xcA29ggyEM1|+7|i9Ky{-)!?qwZhOpZM1Y2wtlU5P{PXc0LC~3} zoRV!fZ{93x9ORZz+LKPwq!iqlY2bT;)Q+dfv~ey9`|db08xj3A<--r-g(shkQwI)= zPLA(o9as%r~d?B=4vT_8+Zs*dwsrqS#IZfYwXyVI(uf^ zbp3VF6#%9#K*PR(y7ITWFf$P38F@+b&#}iTcR0*>adBV?rXbW zn*MRzi|zXfw69y|zzpW3g~5VbVD!1>ARmuD^K?A=#^3~e_wFi-0j-PEl`Jk=2|aA) z-fp&!$x8w($!+qsyy`gl`7N}TFXZ#e(6k~ym9OsvIr*X)eP3ay1%8)qV(SFu27I1) z^$BDHnZ@KP=$Biz$Ak&v;|S#F4pw+O!IOe#J6Tm%zwmYVzwlAz6={-Sl(Zs9lpm#w zyec1+1ILkgCfC8Ms?&MrX*JcA$nhbNwh6ZhXYF1+>j=!;J9=)^C{!ZDcE@6a|?#h)#F zGi6m^L;s9tG8X%4|I4V8c!n#;>Y7ie*K+^g|2JNrIDtjIGvXxlI>)+fVyBCKIMe>$ws{M&ggvP(a{gTsnapXM$;xuvd{Vs z_RG2b5j0lUFrExT`AmJQ?NT3={6B4)`qY4Z*th~*yXvwlqdUHKtJbZf2APW%lQauf zU()+4AUi(HXKFi20EfY}I>ALOe_F%AOka%GG@kt3@1t+mu2BPk zM3C1xl@>)dmfOk%NderTk#v#o)iLSI(|;Et3g3hJ63ELZWL3XK7Ud&vycwNXq`h4r z>9E7n7m(kqonYVPKY4&VWaSq(Shnjfw^JBhDMW)N5lo(SFL{i94lW;8-w2TL>RWHc?SK1goYJr{M)@bvvsW()Djpmc~0!gRjXng3gl6MjBBsDI=ZvsQWv_^pwLU<)S`@4 zK9JKsD|{uRqNC_DQbFw%1{JUh!PL=Jv@IAga{T!C95nYbvJOmHszb2uaiR8EqoYIQ z7_9YB4&~=_TV?xu>3t?gLJaffyZuhN_i0 zPLsJbU{|_-2#|`^RBijLg4R*o2V<5_BV%#vfMCxG`aWsOT=F-X60JxPwo~T}fec{k*nTBf?duTa^^{HWRl~TJy8~5Px+9DyI8i_jU(mCb8+ORQ)qyQ%=jDhat@TYvdn!s z-cJLBJZ~l~fAJUJ#KO%SjkGahNdfT3Whb40lY11~uMUr94V&cLZridgX=LE0@k#@s z@~55Rc{;uD5i%>km(ueE?%rb`{~!P7e`442WpT#93!?7{Cq@TA82SBc(l;}(g$DAB zy>$<%ylH_cS0;1@(h=ZEc`^UrGXAZsL@nR6rN~rx_z!WxX=g<5u3h4&L)%3Yiegpa zJ3qj;YcMWzX3dN#@W8{vM&~I7htp6Cw&&Ka!rt)jkZJo}g>&NBh_Z6E)$Jn=YE02L z_PSQA0>3d<{Y-c6=xr0r!vl5c~X(fz|Y$R8n#k&aKlClYVD5s zMct)1se7+D`UrrKW=+U0sFMZY9tSk7x^qjMjV?Q^b(<`DScw`9JGL{|WjLm@aU_WNP+G;xvpMVuvQR&$}<}X+f)5tm){=&<#fk@@vd+v#DM;w_B zmHI?Ild=ylByh>!1}biwGw4l_6aG)0;rlv|J}*~bk>U40o*r)udlO*roj4mk@Ux%( zG}LE^3znqrQpeGQESLu$I0mKXumbxID_zh2`Jt58 zJ6I7pmEfx>TiA4<6KG)N-pmF8R0UT+UEOOS;Y+7q=h^v4T|nD{>^hmBEnXaho_j9- zihXLp`+t1k{uqExusGvZz-DPE$e>NNef6eupzTm^?Y3Q>Z+fuDYI5kSLXho^j|LyR1$&kEfIaKZfoo$CKA@TLCbcO7!|k}|A~5s2A9 zYU&6Au4@5dIvlW1od1*S;>4c4Gu7KbE4MlEJ%#|UkXozF@S@KNq@t55vq~;BrjC#= z4Z7r7)1{ZLUKy{#kAHsgg*d-wx9HoO8W2Yn84aditLL@fX2WC_CU2?7=zQ{rK87|# zr&_+(A8@;kW3eEjH4dJ9<>mMWxjT*Qp^orm^JdL*Tc!OGu(q#`-+lUa5%eC!;)z>A1x2L4E6MVGVYAUz z(imPzPy}0MO(p+U?>d&+1XX^=J=v4Uq^SMb-F^VB2&{Xl_QbYS3dbP?xyeOLi>Z!HQ%t^!@$Dv zYww)mxr-Lzzr7HTj~JR2=P^Bb4FHvEeMmiQ9=021Fb#j_4p+ws-Wj*qWAdN!tquE@ z{#k!V8z&H5f%huF`1(w4gV8?kLC(IW&doLgkR=;e$N1S1NMKat)w{>h6vSk2H}dxt z84Z&sydOtU7wWcKZ)0)khz!PekVPWFH0}uH(tND%`6suzmSd9x||#|KxK6MK8f5+jhQv*3y+L z$q*V6e*mmLfw2$#)vuyYuU@I=-Ad{zukvsGvKkaEcYfu0b*MTbXB@hvP3M^~a?X=L zgZ|V^0ObeS0{!~riE#rNrYEzo*AXCJ-Q{+olzHf^UQwR3;nF|li}xIdIzWHVv8ZEw zmb|nLAAB;P>4U@}osK#t`u6OV*%D0}HTJ71JIb~8LYn*XO8$g53Ok})0W|Pj?Ta+E zZE3m|nN^oPGw2C|(MzHm8F#I*uNH9qig~r(nKsaN&B{;?lucz=+baEOF8l6JX(OqyMG5o+vMO!tD-KS!VK8lx z)79|I?0Iuy3NhO2uMUpW&pwAmf}YWo?Ey8abJVx<4?&F)Esn8MCdQDFZ^Q=+R>o6z-$T8eE)=L{Apsqe+xxiB?28J#=OWtcK z1j%`>TXD3HKF9I-9D&8^HL7PEG8)k9@!#JaV=?hJoPAbY`jc~`d80<~HH*FU%bFp^ zs`8>xwR~&_;&$fEI%vbtQ!Tn28y8%7VN_=!oWUe-CetOg{yYEqe+L>IxBQZfRS*H0 zR{Iqf?=P4IV$FV`HKgFVb)pN#yG_$(St))e1V+A5&L~NkO=M>*!R{TuC^8zZBZcvj zOD~PXaQ+p9tnQDKB{S>9B~$x+CQ-qWc}=m>IWe$MaVR7@UpkQM%xHLPWc-{}%x>H^ z@YbKl39L#rs9!(#(Tg@_dOA#iT4P)&Cmah=J{e8`Lc?$H=&CU)g}rt#950`-5N3Ib zbg>se%x*aCwCL5NXB+`yR&&4o6Ui*4>w3TK=sfGldFjYW41*($mHk$Ms0erLJD;gZ}ih&&D-ZTmjHFtqm3`*$Ne|)j`=yYfm9?lw7}-%|KULumRi&G1ujfC2IB zsyMgbU^JI3T@DgFi){uU#S8DgMauvTylRrw*s@uTXnshos71g_dQz0#y$eU)zM<^# zw)P+-rYWoNUG=wpi*OkTxkBOC%F%btwCSi)(UqR{q?ygzxGmf~YDD_$aOYFZo*KPkYW|BGU3D&+ysusP74438=hB8sI$-J{Yr? zE{Pif15RV*{zw8Nzo$IOi=O15+)Af(TA+>eS5loL-$Murxx+z6k;NB`d*#;c@%F^A zar*)EbSp^2G#-zl#;3p)PZrvNDTX7(s=>PyF@jQI?=I=QMe87J!{ zf{|yYy%*=OLU$8DLx+|v3pvsT(MO#MdBfF_A}huK&*!4k_v%jjBA+U|>g5Vd{$^HS z-yq}ej}P7-i}>u@` zp9diOKwEq`@2EY=5hAkYM_T#BGJ_8y^6J=SNXg72Q4d1gUn>^3&23Is)9Tl?CZ85aZZq0<=H*$}6#(-%lMdAh%SuY|%1-HMdGgBiq$pId1)%P={dMAjR4^22W

VN{DOI=I zl5(po`YiQ>K)lb?7g0_#dsX>`Ps;#m?85@k3Uti`K#VtDem+JnSrNax{`w5O>XXs% zEg5C%7B34;@_+;yo_z7Scy#!id2}8*J{kD;>rgdX);oaAJ^Z#G2*9xKyZ5g2XCTPm zKS1Y#Z`Him7Z|}YI}RoiCPBy0f1Uhq^v|TA9K2>e-2{ z69;7WjCSa~cP4UzS=+enmRsXk04jMypGf*ho8(93$hqY|DejgtgGB>9>78`(bH*tM zx`iy85u-=PPw%;h79#Gs@FKQp5g4K83x2eqqS<8(7afy8Ud}BKcW$9|W>Ps%@Os)? z$IAOIE-YQSf(5tN?=V0(yFvUo%1ZOq&|^ij3c+? zF)!I~<&Dq%$l!4sK*hxAAI9%~^P4z=(WOOFWRAA8g)F!KYOTlu^J2a7<5+vob zLg(U-F&@9CK2_daz*q@i3N*a%+@QGp!b@^HsKqSzqaMt61kQr8@``f{Wiux6xwfwj zEX6kJ8i<`4W&(pAXS#Gb1rG_R2eY_q#@6}hgAQ#xdE&s>SAECWrL}%J9b!DrfO?JA z`OGGZi^Vbsr@nX5ts+3UHG~8)CcHN_{`u0Yanq%j#_4_fQe37@?VhHD#hP9RgpKa9(^1=y;SneB-sZ;u-r|3jbOzMhyYWr5pm4z`Vj;n6I zCC}@=;^Y(Jnrp5hE1-Qk6JL>b=#hM7aF#3KK!~7c5CGa$atvjZoE{trgJ_x1y|yY6 zk;KWk%}oDOn#Qo&`craZ!;ZiQ>EvY2|{D` z9u`ipRkxplk>4CTJg%asQSY9;vglJa9O!NAOS5eQYn6`e%iI}UO9MW$U7aJHbXTfW z;HIg%7jDz$P4NMHum1OmC!=1insGA0ZYMySmQ9;ydpl8J3AP{@*>}d5${HG^^M!y* zgWT85gz1dB;^H$_uO^*&?%Ws)(D2GDuf}DUU6MdUlg5oR)lFwJQ^on|^eTjc2_=PV zn?6fn_EK;)Zk0i*f52IpKcACF-g_^Gz4K0d#dod}XaGsvpK7%R++HdlSLYKohc>on zMuKe_aQnWBDG_r%b3dJR3CvQl!tNM^{K>&@u=;um>5(UAMuU!!&X04K28ZVu$cVf< z4vj?`0t7mP3f|KY`wRnZQ=(Rp0yu)&63;zYtTI0Q%RA$Yz9&R&GCg+VWVu475wJaj zd<~8JM4iu)!b_(ael1J(j>^x>hT>S(vN3DUoESopu$KwC>SH8-@xTLd90pSwt4MRq zv|mV=wAZ;3bw!EtEJW{1=UXh87; zG?e?ERUSTbf22*9AxHM#fd<p=gTG-Fk&4oEl0t3nGwC~J>sgq0on-Dk<~%9Qjelr@2qw1IyN#NMOk z$*=FfKi*rkC~iCH|Y*Ql^RbscKcuC*zk;qD*E6#Ld} zi#@C|0G2`H?^(Uu{VkLM1la;`x^VLsF>3?aRV<1v*$XtB2ncno>7k7p5Jc?9QHbl~ zvFBfmrsVRTd+I6Cx^a`J1N1TGNPK51Pzg77gUR>6Z9QAUOrb=UG-94)ayDII?M)i%Bgdx zQ|9OU0%E&@w2--+JaJ+SXM4a3z}b6Ql{$`n&1R#>i|Q2}LuFrmZ=kLXa+N6g0-Dln zeuuB6U2(;|3cA1}h9^v$8iSsAG=|LmEY8DmzTvV)KJZMP53&~~;?yz<5yaU}qN*S*(W8w1Zcoz=|)vq+a24b=z$)j6&t zI|iLjc{_ms`YYX)0pBa7Gdnh)KN~djjT-y9b8Y5yUz1N!&sP5p|>tO8S8r5=;_U<$IHK8#=e@~)VSJ-G~Cy6T1-a*Kf3Q=7@; z6G(DZ%`8FfZ9x79hXNqZr!jEUB45MjSN8OB2RkBhw`OGtmShv)wHMTA;A%8rtR8_jY^<_Y{%W( zwq-^`XXw+qRqM=D*$$d2O$1-$6>H6y$z#B;&e0AyF56Vb1PAQDmqFo10)WZbz&~L- z`jgS%Dr390ZFArDZl3Sy3(ldd$AW9pCv_L^sXqmY^ciIR67V3e`rKv9Ss^8G5onmT zd}-W#-Sr&(c?72i)XYBGZ?j9Ki+0X-z1Mb}UjsMiMct&#Dt`inRqzcAx~6|LJ>F%z z(2L0Hu|0dn<>=scEm|aB>F}q{l^@Z`&Z9gpXk_4M5N5ymq0>S8{H?ABy%ub+z}k3p z!QkhgjM1NOjC=P24GjTcRG!|eJywtD&&^%DFrEPPf0R=yw79gKymnlNn$hf_8nJJA z#wM7KgP2?O_*^Z7bHaQRBw(C9>)^*6IX+`cIi@KwIiZ z<A2cY2vhDB&+C7~U3XWwFB9C_`Q(C#RptF9G zyeYt`OnDjXItIZ8!57DfmB>;5MVh;C%vwP@ZvX>P4Eb$G@c z$fe`X#T0477|g~hGC9r2C;)@pPRRGRp$n9$krOAx;1^$rOE0;MnkVRjHm##3Swi2# zCuUaX>b-Pkyk_OP4O#gy8&|nhS`+Aj=M7l*Wlq)0OP2x+;;RiIqrvT|=c5nWW1l?X zZ9i$-JztfDQwy2TU$&GQed7Qc zD7-$;jE1`b8oH*hEr=oS$=B*vdD$#sb&L8$puzY2I{{{NoqmD7xY?fy-v`q_ikF@l z6#twwIr^~x{L5Qz$*mKPRi3m6sQ{HRNoKyHBU1k`7Im{RklV0btjsJ3WdPo(3eaE? z%@O#=f4KYJmi`TBnb8WhZbe@ToK0MK`j^4YWJyZCI*+?Wc`U`E6K1le6! zU25CB1+^9sY?wj^-j^pJSiEjD4(Nq9-jrv|Uev!gK*QBpX;;BBqhU9zop95SXOb!$ zI)WNfCnQ(Cm>~bo02l>pA2qHk*RILR(zpHjFVT|suDbOm9Ey`Ug0ew6tfuQarTO9} zm27UIfEi5nlIc`}zEpf=XuB-w$`(5Eh{rh#7Q`R|^)bUnQjPq)I36eNNQ|;TgDXZV zyy`eV1}>)5W!s1p5fs#s9Dy3r4SrBOW`x8&Fn!aD0gmOI=prHkz zjfO{Kps`Wu(O^DHW3M1Pb`@wUM+TQcHHN{n+ojRxD_6!0+8z(kFai|%To~OWB3rj= zmD?vw_emrYK~~@t6lwIMkx>EgOda>a2o;K|I?lOZ%HkzOM#G5FV<-msMf{X~qyi1@ z)6^N%U~+ptqc8xhdcYs1OgoP%-UJJLuJqU0LUC23{Vl8zz5n3{@h(R5nZZLz|2rkl zp;Eg?+NoHr(?ExF?h?i2LAF_PpbOqWDMGtapsItQahCSWK3@^1HPd5I27&w}aUQ0{|3ya!N$pib_B1jA{hSmAHQ&3IEP)YtEmzx-OOFkeACm{6ldFyH zUv(d=Sq>hFlVuPb@^RaQ!DW`K9N=MT8TSen~bz^_PATuJQuj%_b z%og@?9x|2R$(2!Q-^;NHkolK1d;eony#XE9E?7hXp7UY=prfb6DBlLKC8sA*f8Ntc zFRjpJBlO)90QSLvlmn^W2UMTRhw;r1tfmn>yftxr-156S;%4~$Sor;5_^CWPZaEnu zpOe~8snpo7d3~H?S852Xp=niKHE6+ zf2c?xzb{22DUMo!It||f`0W1P6)(_vn5ZHK)AP2m#+lJDAB15h=?v?s_pqc$sEWR< z+H~sNIT|*oPjSGic_gi;PBdf8XW(dcY~O**uZEcwu?G<5TL6nZa;_k4>MHq2lwap0 zQ)>MzX3%(WWStyASRH5sM}wj&$hbOJ*;ki&zgxb{ zEKpAhUZg|G-}_NhM7c1dVd8`dF#@B#Xw|B?`|f+9I}T`Vz*&!ORgdXZlvbKjm(foh z6;m(;H038{4K_+%QkG0R_S6XhlBXa4XS^|MehfUZFV4ip3EWu&!k{f3W>!0Wj=Zh2 zEI&CepXH^4n_wir3kaH7W-+V{YuCoB6!E&@j}PVd?!Do<7r z`zCo+KRU}gO9hYz(21^Bm#K3MezO)0-}m&G$DbY)kG?rP8guU-9(o}9_3D)?J_#h# zU!BlQ?WB)sTYU!ar_Ay!om)Y0pCSEq%G9OmG*2!1-EV&zQ&+Bv^NuyXE z$7Lt?jgw9s5XW`yk^%L$O`Gy0o66ZI=Mrf|UgbfbrR}#p9Y=Lc2G;aNnbsNJfg}0p zy!r9i3opd>)vMwx(!9ISc3aY=U0vS6{pox|d&ew24T{RZ8z7D80LwYfXMzG!fbTh1 z`VsmDQvezsq4P`b1{H>>1FZw7UY zK@dn;wMgbi*p)G(M#ZpKhs2@1dgiGU);!sdJ?B|jpT24{3{t!Vp)#nUJ?FHvEhPOh z^d`ba@n7VDz-86CwR!5qQ1*Pk`QenZGmzOyz_8GJxNbM2j5CiIZfSAoCw zVGP#Ikyg^=2mH$2d}ljD+VC|s8a6V2OLt~b#{Dbo$I<0S=COEg$=LPHj+ixRN;GWM zl)`~maYDi2S#PF9cNc-Q6aJk(FTA7g;d9)Um42V2p&$NGPq-DwVA_SBOMmf8z8Ue$ zi!S6ukxQac)26W#zu{|azgs5MUGj!oK+G0!Om4H0$K^%;_NDxm{3m&9IlA|GfaC|C zekS@JST!!V;kK++QI_|paia2{f|Eyyp7-Hc~ZlD#@srTmq06+jqL_t(8?iZ+VtDQ9% z+|n+vVKDEw9Fy`VeYAgcB0gKPxBwbP4v7zDuZSmEBw{D>rU zt)sAqG`V@CwNE6#T(M+n?8}57%UQbC6{v#Xi`a_Vq$0yOeCdi2E8mwhS+;csDP$L4 za#5c3O=DSEK932(k;|27l`2f2BFdFZm`>v;gD09SLm-?oq(Rk6R@2@F^!VK)k40PB z|H<`Nvvs0xI=Lzjm6JlK@=zdUC>=}IP+SaDC)Dilznk0P52fOQHKN}UngR7iBxJrYZx!PPE< zB8~DVWQRP3BeXv&m3?~l%551<8#PX#!9tcQ>{9;~e3lr#mBFrvRRpIVe0K>al;~pqkaAI!7r5HtdL*8@|G+*cq!`%I6x;^Tas3 z{b6xLn-=T~tj95o%q?xod!qc(Q+d%Km7Io5k%ZqS@X@Cn7yH;_@!hf& zapJ&pqg(gmI6AXc@{5MazH5XtiwSzzMpiecJx}(ap#&PrsgE!s6+HTJABs_tF0^Xf z_S^<`_h0XepTd)eHEkAE;e!gu{SWMQEQd@8)>LJ#?347*qbUiO1Q{yv(#iGumbN_- zO%Tc2BwKNIH+}bYY-bg169CWpO@N@BWLK|2W1Ps!R6I8jBp^qJlx5y)Rsx~t-XD0@ z7Ep@?Tcqu#SiOk?lja9=9oLt_wZ|TVydO+qC+2`YzQkVsCIGwr`}Sd9_7SPK)hQb` zZDti$XGfkXUV>`=u5*%sE;1#(48U{-Ql1#++I8#lh^(paQ&e&I+i~?3m*pudo;qO$ zlKkLmngN*duOsbyu2SecYy+q?urjFAVJ=S6F{6R~$Bb|Bk|i+>M`#pAf8pXKaVy*K zIv;gp9C*NisgImjgERTiOI}g`*tS12BMF&JV8HM2zhm;2Kma1&&Kdi=f|1I z(}m|!L#S1&Vg(jnDFE5MKm(RT-jR<=&aKXgD_-hF1z1^C{#-#>O-93TYCrt?kw>#{ zw_ScooC#>!pkBS?S%G^;U9{gpL~&=rDY^8nPI$GLs} zozc;ZC)|4XucGI1ICAJR$7w$i%wp{DcG3X7q7JgZDYtw@JK{X6|JCu*QU}uGE&u-T z!!dpBhUnk6W&HFS_P_$PtH%tuolD1``i%Arrk!WUq3$=!!63x%YkRfBUS{=qw*4r! z#N2%UgZbVq7oJC<%+okpv_%3Vse_RxHATuk{O4sb;p!d8V=ivE8m=w(eKQi|QqNdl z1^_U06qVqy-xr>AeDv<#Gi#RA##y(xoVL%xe>$BEIB70OByF~{N~ea&z}UG)AEgas zT+&LO^K_Y~Uw$PvFIyC+oqkpv!`8%BEnB8<@C{=&SS)}YeGmDjs3GFXKURX*CJAiF zwYDj})NStP&TW-5XL9Pq-(tWiC&lsI*gAoI{r9aCPHs+bf|ZI41m{CNpnlM% zrmka*+9$U?PGNh)grOs&dDqUIrgdVpY1tz7ud#pfmUCzUMZrZ{O#t3(Rvmr=7kS22 zYjq50hfJJl*dFh^cH@S4pVK%-jea+VPMg6oh-bur<9p|ka~{p9ZdWb^226oofRFm( zkk{f_GE)EjYKv~IOU7*_woR0UcMd+VCWX!EpP8}(4EVX~*$O<{ZF%;y;68&X_?K7a z&_S3ifXwILLXa;68ot>>F~~1s+UGm+n8}*uYe(A-WTVuo4Lt=|IJxb;nbDy2fpPIg z=f@GGe5X%JTNw!H^C4GhtDFnw)CCMDpjh>#P8Ytf0GywxZ#6r5MLdY_AWJK#Be2gm8Wdf6BGMZeI%Z`Im$@!GKA@pn?} z`?Y8gr=G{+6?|EnEi>xh%v_b3xljF}4oHAe8RK{7MX*CYDz*gzcp$Sb!0BtxnLnRx zW+P+4Co|b{(>;0~-zN@*FWu^EpS@o|(>NjP{-o>*1mj=wnY?bFogjI~zNh~Oom{kd zk5fwiimvJ0r87FR8zCKYd?;MR_M}8b6gQ?TA+~BR_S6e;4U4I#^zD;J-I`(KakRy@LF59R;C3$q>AYW{foHlPsvS_j z_&op9pLd(aLNcbtzc+|8JDrxBgo)5oa5Z;Oy74h zms_zPiC7Qdc5$ z7+lfG2~)^r046>K4`z`G3*(Uur$b;nDwPcw&CwIa#pJmQeT%@WOB@MeS-W;E0*@l_ zDk*IpiexYt&S@?ofI0-WrQ)_CtNV)-D1m~-%a+GKUK*TjA5*77bUFT1sy~wks1ksQ zZAYc)xJ`LfIasvMONT;*tI|`5M2!_5gJBJ|1$5kF`|QY3`TbLlIh=EYJ4F4u^|PO* zb1J|-L!*-lg|^ZF)2>QGMQ2;~UFGD8l+W0-X=5y2v@phx7!^ynzYURJxBmU3apNXY zr#7c6Ah_w+;EZV8RnjuQ0+wlj%(`O|5Rv{l4%#=R%V%z;{iRD5$1`IlX5Y^_u5+|* z(SlV%G7jj2h9&z;KUHu#;tGE5MP&?TYG@pCUipsmT^?mnkzhk7ZypthN53{S_ca>; zUpMgVOvQEuGXn^OTQI?WnJRCsSGJ*}r6<6A=E^ZngMBZ3E^XEkaD9Yg9s0qH?0e56 zJ49bny=#du(^psj5`dB-^i@8z?W8-;ksi*iW7Nn?JI7&gA&)J_FueKPOWAiHaM6i< z@;IWxs28bX(pLKC+{*LvJMGbYVKhN^b^QH?Stbb>(AIWVo;~{WCBQW=cId_Rmt7o9 zP=31!Rt4YeYp#IMm^`5zyW*lEbmemMmaP;a(lMDhgGIM$j5qs zhS>lOGuD3v!1hh7qqw5iv4?f0E=2PhN+JXMoK|wuA)IF>0@AG(J>?_dC3ao z<)D8#0{HS|4eTM4YX{!fx-Y*50*Z8VHd zroikz{9OqeRbgNinFsr@6Z*L4*C79U2>2EEZRfkY_}(V!BP=9KU_B%{utCk(mkQte zu+ewVKIj;YCiFRgxiB638?r7o?j%)r`_7m{hSjQ#)Zm~7hF6P2+edSN#Twkt_GSRV zwJ~aNk->8IQSB(|*AWN3VfJAQ$iKW{MuUAf&=qu$K02D}M-6c585^e$@|iNQ2_3u$ zJvISQa2X%(Vu9;ebl#)FU`k{%-JX@TKk&WO06VQom$%+aS-gw^J`5V;NBM zjMb}F#f<46#*mK+UOlHfML5~6C#Y!~%A&z6T}?hIfNJ?&U7)UkUl^PEARSTqXusV9 zt0Vf^{P{8J<-sx6adG{Om5b($8$lQB1dXcia+?-3@IC`Ze%>9Kp9K=<;YJ>zKrPD^pH6Hl+*G=4)4!>&G4EIkG83_(q|j?J%eicDA3?bnhVIN zlhkWwt_^?b>6neIdJR0jM;yZ{pjmbXtzJ5ckOsQ*ko-;hGpmfpETOa?=u$s&4s_<2 z@^tcM&7BiZ0v?sFn+Bf4s(tIEv+|iu@{jbjJ?)?NP+g`D&P)g9M){Ry_QPHXG<+q< z!;1Q=<0obF$22~WY{avoF-5an?bc?d{_-X+?{j-#K9si0Fg{O?@TaysZIli!-~0|) z666_#9^Sw$2lG1Vi~-T6RU3|&tsXnE)jH;-)z-AH_7A?79s=0Oqm0MrW?%SCxlk_~ zbm&MvO2(bniS3)m5l0;x4I4E|(Aez^P@(I?S_HcrODZQPWtP6VskQuTnB_9o|&Hk8}+oeZ>SOPgfBwUds)vC99h z@~t7O;mtQk=##@+%MCOJxWpAZClEsfTDcik=SN%`keGdppCMTgrm*eUP4w~MSuoR zG5eU+-Iv~-NKYc#lYMt$zmqb3-@?#l+!^){EDx$N?^D@JsoPA*6OegeXPWeNS!R;1)ppDLq259glH5xXt zC(cuVCN0_=Yk6cb<;5KYUI>Vwp? z@QJ#}Kvx^@yy~YHAVjg+>$b{?Q>Vo1S0NTDEM7F4N1=Cny$ZEZ(Ob(Z7_% z(toF)Fi?Ka@z?>uaToaX2My#s()*RY{_4fOx<{L~ZR0?;u&KxFzxqktmlO4pn`)@k}Gs?1kaH8Boz5Mg#F?7hAY5xRd4+X^V*w1PN^C_3yll_uk&{cM^0@;!- z0;x-sQR5|be)=}FEP$sTS`A=2XU?n`_Ti^FzMn#u#`t>zy4t@SE`2ptkhV0PV@ZI+ zzmO|wq%9E?^E(2v+S+YjZAXtSjmhs#h>w?Sh!!;}#93zz1azy7?}H81E98DDkhT<_ zm&(RT`o8Kd3u*gI=U9#5rJwEhK3}scrhYUnMo%xS>#1Fi%|(L!s+zfKEF&nY{m>2p z?m<`E^(PaYbEAEicD^UirhfvRq|KZ;bK+m&X>cY6OXU+|CDX{MlToCyJp7b=17spM`<~!nx^*i~DJUwPN{+nAaESf8A7PM}**bkrNq#Ra$D6X#!e0XF~t2O3KA1c@+E5ZfX}Dj2Ky78fWP1eMKZaU{~) ztP;$eK0P+CSr>IM6bEojnibJ^VE}P4AUYF?V{NgiolM*=7)9nQ&->+Jpdy8gVow+w z&sP@F7S&a;twLy5%$kcJU<{hHidyWybEQS(&s7vBRrFBL|lX8a>`q za8*nqZW=}J$#ff#+eM##65G~njzijlvJ-SyB3;nW)8XR#85GlRmEjM(zY9jxz?f23 z*0!=eSDlJ|brvS{yKY z@QQKc8D^VQ=Ghf#U*JfkXZ!MRbwC*%h4rimFZpnCtj2dVv*6G!N5{eS>d`)PLjO&l zGqXfKbsK^5`7Lxw#Y~6yh4xiYr1YG*DFSqZaUCsF@;+a-IF>C~O@SNasbR~geQ^DB zjFzzVX~x_I+3Qm8{X?0uHP#H{a9)k;>xAu3ri1(WaR}*?g|hY#9RDBo-ZZ$*^GeKo zxr5+Nf*=WiBvujtK~h{LZW0%X)MClDEZLUa?sPhxb}C(|n#|u+YNjTYsZ4bxsi~AZ z9Xqkxn`BFN%d#zNp-6GxDRC!ufCNAi1h@j=0&ep>=fhR2=Wq8PSM?`d-iv#`?_JJ* z&U@bT4oC5fgkDYWH_#$Y-KHY1_l!}Ij08XMM)&Op)DR%!;NneAM7fi$+?7gGdTb%i zZfQBkyQ1LP9x$B!vJdZNnFlHsE9bW!+7BJ#TvyfNbhD3`K%k03S`P;SJb1;*JA?Na zGHpP&V2oDY4B)LH1|y-DCY|JE!ye1bw9QD z-A(nJ=wYCt^+tdLxj8eCQQY&;7<@1+TaMQH+hdmM7eV4hu4y4?WY?Dwu?Y$K7qI?GfUV9JS_r7{$?=HHnO%e8Go1WeaV|1EjR_^ z*#PB0p9R!F9_@R&!DwLVv7xQ?r&G_l?o_&seG9fPUs9JQV{Gdf3kPXHr@&yD0k;S? zGar{#G_dpNPqi&xg}rc>>UD;kuistj?BEE$rc{cMpZEB>uxa8qe)s;cYqTjCuXL#V zHS0-xX|#<&FFFifI?_4%wQVyj&NbGj#&Z{usnuytX<1N&&b;H52V+YM?Yns3X%`mh z9j2^9ZcFcRG&1ez^!swlN32-l9J8dln25{zICgdwwU_W z>g&n?_0t%}Yfw#R%@s;{ZY)li*DVbCs|1DG(M80yQw_R%5^3GqM-ga4ZU|f#B9xPT z=ok4_N7i=72z#L&^aZSGL%vg1_hNG#qpJSdu5P}R*WeFs9ch!?$6Fl3ymn6FSm)X3 zA-7LJ=ggFlNXYF7G(bnnxEu|e3uikrFtg8i1eok8_E=hK*wj;3aHG}p?QOVR{fFv z>27a-Dqf84rtoms+O%UKKKqd7wd2E9p}+pnN9t|lO3VX^4nH^+c}3??eluiw5eNJ@ z3ni8wpEJKIO`}$X3tigTN<(#(^l6&E3vdI_{S5*xW|3J#Y9jWb3x)=5>TT7NVO5$+O3O2w7XpeJCbT6#xk|3wwH{MH-&w<83ie4pvRoONv-fB`+IPOz zW-z#MY}ZHWMBhVf2acbfJtxNK?*=opsRLv5Cr`=2cY&|+O*y6vcH4`vkVmw;9KW!# zuj|-NXAT~vMilnRy7dvvQ}^mm=-?ZaP^R67AMOL|LFTPJY{1*hOSi$hkReY+9RuDS zkh0YPS69cmw6~!(Et;H{YF4a{Og6`0`^vz`qGfDWp18&Mlw~$Bif700yS9jSnRs=s zp}U!@^yZd@o^uVUA4V!&xg-@*IN3{mmh%-Ndx9}4N5bA_+y-e!@)|~a*60x)5yS+? z$`WOvCjee!yU4W*=fK_AREkYG37T;cO8F;V4ERhX6Gi!P4IUYwUl+4HjV7NLAj99l zcg2p~8jvJJ;*YO1KMP1U^I>!k9{DP)ZUg@J~aW3^qC zn%}8-B}hK<{}6-Q2gb#946OsC%67H3r0TkbsidSNP1P8}F%L$f4=d=}ltzYW>k0;m z)@ZB>!POg$JcX%!yCSC%H;KY(ofujkx8iER*cp_|DIDZ2R-OT$Ed9Tj#0~;kTD91@jntU0q$IUn!&=yJN|v)J;S&7){NLFWN*2 zg`p3#dD=&;0MWkDVU08eoM}o&NtHczXkS|M4AsA@ssaX~2xMx;WLAd#2utS!h@%e; zaj#fyMhPnLBKprAxzsk(qfc<`pMS5UW>MJPvq6IarnhNb;!6!~s+G>mHmuzPAYgBPY=J3jCAvRzm7RJP(Pj8f=Hx^X2!+&h2o zb1Q|k(b3V7PMIZ+3yf zwFel^20x^GQ^O5NG&Am&wpOwW2o%!B^kiY(5Yc_8F4P3@wfA>!I zrLzb$P*89@N?aqsRbpSmG0Hp+QuK#mr~zc*LJXU+1Q~`S%pX7}mk2Z*ztoow5@@)^ z9@ZN}1q(N9*qrJxp60P_qIfC}k46(GvS?)JY<6Hw?Ax1ndM_I;0i_nh)jP8H2XQ)i`8a7T3(j8vRK0RoP7d<`^= zKzZu~#vXOP8ALphFfsJ2cOl0Z?R}oR#u(4tyq?bWQ^1SjVvlA`OcRQ!SHKpQ2OLiz zu7}-XHIQ*xPo|HohL&Ekqc}J8QZK6r=J|2e%&$phr4=0SS(~aV$_Nx8=b-C+Gbt=! z1Wa#3_d0M7uu32DiWS{}9gYh$e}L5Xx%1}5URk63%4Y)%!dm?h`~;o*ozAAPSB`m9 zo4lif&he6RQ-jW}S{f8*aa=yzy(4XT^_yu4siyw!v4P56<)VM<&?y7Vgfauc_LTwh zt8J-ca{W3MdF%#h@!dEsjrH~Pb33hFzX3SR1@{;{w3m%piqS?VAUZ@J(y!kt%QPOO z8Lyx(esf$J=Pk|6sh*XTu4bG@GSJo_4`xvG%Xw?eD4V>TcWgy~E|fLOHZw2!`mze@ z$`55y$T(?*mol;$8Q*pOT=ZK}U7hChayy#(FXyNSZE?Q?W@you@={q41||L5E@Txl zNXNsunaOngQv&Uz`%Y%Xt&+A&SsgQtS9}UnSND|hj?d!06QOzKbHJOq$v^Uzawd3= zxtZl5E*cw~Sb#Vbt8K;b>fE`dv6WCbhm*!&LpS)&fUJJ5Q>d7_CU&XdI;4dz9E~E#8_0p2|%tP$RY(15}0J+YG z*%s{t?K}?px4ZU`$ubgW&@B<-BhbQqS-@e-TuxppDJIZBRtJJLkDTbyxr_$prY#e} zR3Aj|jEs#0 zVn7-Iqwj7%mSO~``N(7X$Hg=G3HSiC6c($#vm_garhN{iqPpR_@> zSHl4XwtWJL4;x-tFcZ9L%UZKX*f~yDuw7x7 z7sQ8w6X{jDSC%RFwCVX4^dpz$C&t#+PEl*>IavFnf|QgfjtEcLzx1drY)~y%`zN!L zUFC+C=-;4@GF_PD>wgv74<+EvHYWC!g6u9i=%j7G;34H?oj;M!6KWHgFZD!s0sH zleFcf6Tj2JcHH_CVPgWDi@<#Uo;?J2rli&QA!Zlq1E>Y8yPzx2~<$HVRbk-kBD!ToqgC+{$9zf(SAU-D@!Gk*Smf zibn!xVdX-H*<=O=bFx&~C(O-=QvY>!bfh-?Gxg;1)oZeoK>{wB?W}x+^Wyo8E?I9yqsOD7!q8wa&O@SBm}mQfhllX{faB5@Qekx^<5&2Z zh8pwdJ{6FLmTme9{Lx>|+4tS{JmM1oW z>|5tTqd|PycN958iB85S@V=JTHj3#TO`SM)dE@ibHmWfsPzDsYugo${K zG*j?x>b9>(2saf}tlEN-NkfL*DaL∨9)-M`Tru89thz z1g<(Y4hHG>62%}tyKpt_>LSLC|KD#6fa}EdRlmy>M%RyVfKpIimxEdk9Sy<>628FoM*>!T#Z;p1vue5gL z`0@0c_kNp-Da^Hytp>Bm0+;078V;4E1sJ^~Fc&tY`LN-*$LMmM66w{6{;<|79- zKJ`?{XM>T_UT)v1)0Brb0Hs%HQ-0D}74|we@|1M1Oi+gVyL%^(VdNgb*m~*ZmnojL zGVq~co0FH)y)-2s*^Y8pIjEyz&^HWS;2L#nfWPCgeVrnMcgMl4fk00os>V>1ztv09 z0>khcfa6K}T29q}7Euq)XYNV^w+Qo0G5JE6k;74J@5r zY2RlI;z)nO%*Lg?zyY5PIPS#&?P0&QSssfB@XW_ZcdLbS6+YtLz6_L3h8J{*?N_)5 z{~&83=nwz-jBQ6P4(<`ByS8r+{;aI5jI-pe3B+wYo9P7kPQ%YHb$AS9^F{EQ+aTgJ z34Rw|SnUKF=mXq%e4nYTpB*{On5(HvGmmVmIZ?sf=WW+TlBl_Y9P|{UNv!@#(`L%t z?!Of$T*ay#zvL4d7Jp>;COXs1kkluYMhQCttX#ZctCUw79em(gx_gqO2_7CR}_W$_N#RDPR?IXfJ2AQai{MKGOHa^OjIpRd?D z!F?8lG)u$GHv3axn^iSN;qLd&pRpKdh#C!Km^D)ja(DA!cD&_?v8kNk(yEoq(+gWR zr-cL@#_PDS)$swi7{qZin4^4hbu~_gpgsA}I#{1#4@;9p1O%6}RbkGY*`GVn!kX!3 zfd;_i^V+$>U;QZVtO;P?BDNYZUg_Qpp{r!@>}S!wn0g}1Olks6V%xHODLpEy3}i(n zHS$q;D}5SNb1O;cG2raDy$qBJGi?I{#s`4=j*qvp@bh?D%)*{oJQnn}UFq0MzVdn7 z^|_!)<`sPdBj1&yGJ$fzdAQ}_8am)Z77SZh=&)dQ6*3{mpWY|G_>#vBoT&Gd6}A_) zD(}h$ZE)`kpFv(=T-w)esrv}s?e+}|U(RIg24|Qpv@74ZunF-)ha=dMG>VsS6W#+i zvp|EzHmyP6R*wkCGnN5tk}DiPf2yHA?b*4L8dw|BdIE#vn3E@hC_eywHfL-(gABer zElIw$9?_t%2X4}&a!+|0x{%*5k=<(`;OyBmkrA_L^A;9LSk&WQ=O+AoIcMQ6O-29= zJo=sV>Pz2B{8}tC4_Ob@6Ikmb2+)#F;=f)())y6(qz&tyq&C>xphe+kpjF*3tUcK< zxT=wJC>o{hY zge8KFXiCI=Fo;fP7>E#t|9N?zzq@L486)%^s<)nIpWl->qZV(PN!tn#3CMXH{bj=O zw{2ujWajYM7L!A;WRcj6VY5_kSJs+ZTM0D06_K<}wC}iem=r(?5Cw-(Tm_ZJgO_tq zP$>|BbP#t8o#E#K0~XnGULJGv#*cp-*%D8#AySDT5l*pkE~B838DY%#b0c<$F`b(! zks1<49yQKlg;gVsv02DzD}ws~frf8UdEFvK;Xr~DrX2GQq0DFD5E%>cgW$>t##JA$ z$i(0t1&VVp&~SkY>;`!h^k04H%c-)w40u3OJZl8f`&44mj^Bj?4@?X|XdKzL!d2xO z_wu(9Y0nhzAi(3Xk~=^CIIZ2x(MVrXH&0Ry(-3O1lD#eZ09A8RR%c)V=%(c!pkC-_NM{i z%e{v>!3x%+7|$2k&*lo8*&dbf(=eP-pK}Yv2$X~Pk5pXnWwbv6MvPh0N;xnJgV-Uqt|~AZW7+TB~8z*^Guh=+G3k2?RwNfX&-)znup7ZV7?4+8S0yPz=IR z#gK!ye8_+@r3_7k!vue+q~$;17}0+4BmRwaOGgGZ|K`U(Ol1pe*>AcWL#QN82X3R4 z1sG@%%wehzIBJyK$ut@ILmQ{V`}U>n|L=cDV_Gk#lJeQ9m~j`;-V|Qrz&RiY<22X< z*=Ydr9swBB4wZhxN1*(G%b><9H=E8aZh6%(_1Y0*=8?mvPoBDA2cY{d!jFvg0asrZsHrBV-!m^s{o# zK!)@x?>la{PAT(aRefmut^yu9bU2;CV3A%Q#}HbxY8C0$lc8x0SH`NrmD5YMr*SAh zWQ8;_a4=%+Qv=L*;iD0$-Z6Nzoj`!wKZ;69;v|E41O#&1LNr)~p<|C=h(@lwhP(;m z4ca!yq&~H6<)~wjpZxnE&f;&O8B>xMz|%`vByhD({!6qis_hSXQuj+Hm~&{g)xG=r8W;mq4k zWUN8=k+KW_Iacek;KCp{aT;m=91hW2zxox1_RaMCv(H5!-0gSLgz{Dz5sr@EMHC-Z zSE%EJaX8)Fr>+sdF)!xlXZt&Wf&0eK-bm#Y6$HXFnsK4QcEq9W<}P7lztWvo)^_HA z2(}1f(2u;K-C|1c-h+qIwhuo{FMs{(QT5)jx)37$avOMKOpHew)lLXwnmHMma%}-ku8wwgcBY2D|5xu&cLgAb)!-gN@St1F~BPs$3NVQm_N+6IJYmzSqiYu7{uQfym+2BUTpb5-AI z6Xk+D*&>hjUB+9ESy%~sWllb}(KYD&6YT6y4;`Y0L`j-Ak6=HtV0ytc#sY4Ew{&Sh zL7AX@)p65iQD>RCBaQ@V&?z`q7HBUkd)hkAr*}AB_F_jz@T(`Dm7=@H^P5|y1E4$| zv<(am4&;Iiwkbc@-siOBT=-raR#=@nb2h#IyWhrQp21iH4ayj+A5a zn>chnIs3t}XFQ&z@heLWr0hV>{Q9l8(o-8ZvGTnn0x;Sn^0kYXnUlkM}Wu&&K?~c{44OZmjOiq`^ z;v=-_z1qkjgP>V?zLo5$Uvb);+YY|QahOGJ9R%h`D{L%imGOtn(Prc{mq*B1c~}{5 zW{tsEw`=PkSfn*8cF0y~^#8@)%hbC#o<4f-z4Y=oUQb_o=4oUJ*?ttqcL7u1Li~wO zGbJr{Z8%q4*j~=ofm=hT2^V#jwpte%NT&_1p`iz*ZZ!g=b6K^FFa57{M=}l zkqy27;lBODGa952uXqn~;q%Zt2!>NqBUOcW;m~!pwz2;%pMq{nQ!N523Y~!joj;^= zq3mWtTa5t2pCVA58RdZW2_ixaHZZr!wLco1_Knf z8VoXt<8$>^#2dAPqcOg(V#E>H&{;$%W*5Q+CRF&1!%)0Rpy3xV;Bit6pTU@@si}^( z-L|37RFFjlU>Pw4Y?cOTTcO+`x?p->p&$uiHY5yXfO-VSTR29h#Xr4qBZVDVr6t15 z)8Sw%q>X?nKxG`6U%?P7QV1#|@q;)e_9gQu#B|y{@9qp%jX_N9Q3G(x2FyMi)X>C6<4KZ`K35MaQivuW?55d z8ur4%wpAhldz?_mDsB}1rosv%jZ){QA>;4j!6<7zk!O$aYb7n}WgM6Ftay2U4~6g) zW*Vgat?-tPd=EuKTlURQC_$p1^k?MPEEt8WeKj;Trb7o0qzj$r(-_DtSqR^ zjrO{QBH+m1VW_KAfQbg=Fkb;Doj(o9OnCDH84XjSM#F(4N7KFo2MG4zD5G$S=a$AE z*KND@r0@Rd$C5TH_@s-C9Ys-B_JI~oOcTfO#qFDHAGnn!@x7T09*L@=LO1b}&KO51 zxh!fReHukpFCHFZNVjoJSKy3VdEG#RJgTAz{s0!@G#qxv34LgINizl+OhHyT z2OV>t0jy~lQ^VmKE0}-pum5|Rw`gHng+pCBmlaZKQ4HhxL6oWyZZi*tjU~WE(U|e{ z`v4hp6ytCAcmGq$>$;SRXU|PV%zGyDp9~H>)>Hm-TNf-5bYYNTkSq{W>IkQy#Gpfp zOx|W(_fS~Q+d^i;2q+nTyatXhU`U=vsb8HuNT8u8JtXVk!nF?g6gox6LOz_+4W338 zre3zDT(~hn!N*&v{#u|ky|iXiTD5dV1R54DT!0Zfmc7!gd0M|FfU|B(2@Bk&_Z$jG|vU;a)l|(zLuS51U7V|K*k*PQdXUe9MxjYBWuPm58bDJ>AEps#?Ha)bGBUuO zv_h9L4~zUd_Tv~?$2dmSQ#>jSG;G*F+Ae_xp3{jNKb}k;+E>1ZjK?UlPmNqMleLs76yW5(?v1{$QvlfcHl)?(y7g{*O<&T$$n(HL}W%0qRV?b)_lrF0mr;I1r| z_I+0_i3{&($d1HC7Tn2JderagG4EB@ z34gZ;nhx)_#9zJnX6UO$WMeE}z9RZDC>q-ic^BqBD~!Nu;6dG~+!$n~^WmVlG^-3b zudspEEE4Q0;Cov?V*A1Nv~K)<-@)uz3+=7O=KXf8+_wQpkjX(Io4^m}SReBcVd?qxb9mLbX8#x0nN#oLX$a`f7 z-x=V@Io9IRd*lb(_VRD%YqrPl*|z!GAOCS$N3dFai^tqJg?EPEAZcKaBLMw`Tnrn7 z05fy~Cc;^eR&{{Y&1Uj#-?<}oc6Fw&z48i~Qq@_I!2xiee5rG107H5Z$MU-)i~tq) zI9GM57}w5u$UJpiY}@TZ`*-h2<)vlmD=ZSsB5*fA@Fes$GDN4vx(o(~lr_1zJ4WY~ zjhUNhT*qIUv9`x4+Wnu%u)qH0uN>*;*P8N?X>LJ58b^D>a0sSMKsQdzClEy&$iHDj zuOL6*ua;F0I9IoVkk=P4=NW+pWWQMredx8G+Z5;Rxs-O*V;|6?7o@ZhJ>Z`qi)BiHwF7oHXE~-kg%z)bqkt zf}eOm;*B<35b^owP#n;4&^q7AJ2_es-lp^mBeypEiae z?O3NuIi)`lbq$8-GO~n#p$@y-U4@TxaxqIezIE5m^yUwLn4U%VJ;7p#TdcFKR9Wy( z{~!zSfOPuNmQ+@nm8ZTl`&7B&yD)ML^0_)uyYX#~J#K4hN&oWC{w&o3`{*CK$nkg% zm$9fc^u6?MFe!8{eR)qVn5bW(TyPF8*uy_XmKBlx^7_|bjZ-A#2u;RBh3IRbOW zHH`XL9$6`zlogtG>O<{4166)D@HLE=3k{dBNe+JYY5EO*&L98F@1*CSdk%g>7hzjO z_Je2*x}+Prx<`Xd8FhXvCL(u>bMpXQZU zP;Y_p!EXj_bHN4!sbkgU(6jgyuKI3JXKW4CFVjxVQ>TFY8`rMlpB+y73EbVp*0{-n z-@x60^bEepW=`Ijjoli847mQGU;j9P1{pqHf`iXO)(ZrJiPTJ>VK>KHUVxYO)l-z`V0P^3BybngfL{x8g|xv zxK1STm+$_X6ElvbO+>R4uG3IBDnTR2_HW&SaKQPjA~s?e1_J~x14RUp-(+$bUguQf z%U2_jvbTt!+ulZup&|k#`3hF<)zC69qOdY+LZ)`SI>OGkj1BpR>LX)9r`AV*lIA*K?rGapm8niEn;Q_SpjwG z3@23(WqtDb=hLgKl;@G@GJrv?La`qOR0MhG&+imU`8;ns;#onj(O~<|MQ2G`wW@w= zTWh3D8-d>Z(o1O_j*&R+g`UK_N+ujC+O<6m<=Ex`-HBsyZ(Ax%=VHLXL^Gr=@3~e}Vm+wZO$~IgVXg&!WvfCrl&SEUpWZbwSEH)W;8r{fUKfc zL^!ze2SJA6WHngG=ng5|1}YEy^Uo}r1_t}r7eOi zJn!zoL4pjo81oGRthZ3M7BKRJi*aMA@&FIq0OuEw3r)z_4(^*e4+LSL^j;_Z8&;Uc zZY%!e>~;&@x!r;ylI#t>a-Dh&Yierd&%1c8?ks9hETRUKegYn6->37ojiP1>}8 zs7M>m)(M>x`M~epa`VPdev;O#-;llr&5y$|zQywz2+9KaRmH3fR+0P605De8<}!~Y z2(t*{dvGSqHMp)3XfV^}0M5miQN-(>SQR=UQn;ZfjVG^gBH){hN9m96rEPi1?*y*j z32#q%@bBxatenTl-Afv|s|?>JJF6Cc8U&sON_^Irv}yq>_v=bPZe`LKy@Nb)#X6ia z`{0sqvvbV{Vqf!TtXx<}VLp!fbI)#xK!dtPG3sd)7sUmBl~H9u`Bn4xkhCe-?X6|5^w4dWsv&B z@5F;}k%l8U0FFE!^pj7vN1#E&XC;9EPYY6Bo04ll#CBvS<&LnHzcK?h(%+(3f zfc&J<=5d0D4|F`U%;HH47G`&6_q+pmmaD2W>DwA#PKA&e;<3iN>|G z>UV($U?&X-#~jY(17W+H0M&<_+y3fnuctLQUOKL}p?(d1qBChaU=RH5PJQQMf;fp2 zC&UT&N5-JP`z)~QfiAa`Dt(axvEQV9x2?FUu8fUUba3U^b$We9+Hu@YP8OJ_~ma_PZs3c0!vwi&CI&`K0#14A;E z0TdUvtp9PUxhZ|`CqGXA109mPSY%Dl)=f(DW==^H5vwDxx7-F{@Qe`?Kc^>n_7QUv z=gtF4i5CnKeU70KgA$I<#Q;c(!jfd;QTes!_Px~Bdo>+wO^FheX$r%-#-Lu`vNrvz z@BFK@l0d`Vfjj9Y8E76KsN)=&l(a3K8r+E@g?v79_6%Dmjzl5tnX^mMO6-oZ($b)5 zVQ*kp{VNW128FS*M&0PxbfQJHiyPv_lLlOU9Z7AU9^kuk&z^LWx>?pwsH~_U&|XUR z6#5Ssgnfi8i|6Slg3`cW8W(-ilDuHx!Jweya4V_yu(e$}FJ4H$g&wcMPwMWnGU^1e z(2>u44K!#ch(CEKwmb#(zz=+#!=Hq<6=q%`BXh=TVyi`qnm+H?;SKpSDEEJjUU~v^(tg<6XPbTj;+R$Ou@ubXjbp zlINsz`9=8``iOBV1I3{*$?9=snG3>2ev=QhqqWW4(rnh*F9`}ZH#Vey{wIHusw*o) zcjz|>+kh+2DSP}b?05SSHoOFmZ8=YWci_&~v3a$!9qG+q{5;JfSo#`)!CAoFtz(an zufy0j3BW`44u?lZBL7?f8NlALKkZBDJ_^sO1E5{u@7z31;acC#boAu$^e%yhSHJab zj>Fs%LFT?5_HE)*4gGhsukcgA7&0apV`+TQvn;!=OcK*K2bSK3i`Uj?T}uxXCKPuI~e zW;ER5wS|SxEzdufrq3*Kq`VxluRq-DA2-kdkp)Ey69^4%0#2OMPFm+q&ZoWvF;Bxd zTf2NEfrhGxgbkt?Ew*ChP9__TK!YlXoJrd{?b*t>W?m371P{l?-l4G|-e~e}6wdn} z{ywVf*48adk0F@d=PBVRgk>^`N@n+xxcoa?6?Z?GE5LNfkQIsw1etw24uq-n?{GAy z1#s4_-;gRRE2uEa_5+y9h?Yl|$ll=~*Z|KvW{Fisw!KjFGC!YB%Z|3(%PDS z{)=D0Y{S#~r=E%ciA7rkp@z7^+dzm)L17{TDVP)<8tbU&U`m-Z1P6U6WFpW&UpkF{ z^ZoC$?PFuwNOW7rU#`_)6TUK`xDs;$N{1k#hx{g^I3Kt&GAU#fBaEh^$*?Mk?R$2! zDz!g-_0?D7$SdckFq6@oZ_E>C!S-ctjhM{%cZJGXas__KmY{F%_c^msEH3vxshvEQ zUL&2Tth5w-YBV7*fkPM$jKk+toX$lDR+xMFZlB^)N7AwB;HyM5gw8fl*l+vx^cY6g zi_bonrm?@+mC0zEXKhznk&ZOL46=MN!mVMdp>A*DBNu2e)1w`S?+mH0ZEdY-{gy3h zHGL?2EdV2}N$ZYD+VHcP6VjB%v=wj-Y&Z@Dr8tltt*-&G#y-8hdv~WMjEV`<3)r*% z)l|Kpj%dm~qT~JGEz8O=7^7ok;L4RJ`;9;YhLU{%K%oS!qL^8!v)Z!hVs5uFO?@m1 zbTUQjW)u~(b>SXGvi79^_M;yO+B6#-H8p=&s;(%aFk?ZQmXDGiB+dRlj-zq_TDeaJ zL%Rs40Oes|R^#4Odj<0lnj-CPG^7CMgCkZY;m011v#h^D!7@&szy?b#LxG0xeCk!epRF(&y%ub1YH3NoW2@66;JSG6Vz%2E{p*# z!3{F^P$&i(4*u1DO2gW3q{6a-R02=T0PlI+p1Em!U>w=rSVxx`Xa)vM-@OSOuR!;` zxBAnKft#Vs$Bd$ws`9clzh-`HeYk@$;fk)=WXfQJ!Vd{FcshnB zh-A)zeElGuK^gy?Y?760)})tT_);1N%x)tiG6P=&DC7T-UBD;@bLn3hCm(5i8st%a zxX)fgO@qtRc`WRA80YBaue};8u)?aJRX%lxGC@J&czi~FQO+oflr!R4Cr;TCbO&7J zH!qDiQ!vd8xI)n3o3FnXwF2&<{N2B4o4$A?_{pp?)Arr+ApM2$2BC)$126F*Yjm1VR{_dR(40UDuZmh=1!CSOm~O z!#J|RJe&OYTep%0vy~L`b!m~?sAd%>k4m#*xOC~Nn7YG^BDX2|a{l(=LdaO;246&Q z+O`cej2;i{q3sJ7yD-k*N;fc=Um#drijl6Y6%HDf5}L5i;a2(YCH-Zvks^UPed=iE z79`?+o-<|lml)^s33_e9Ht<+LVd3vVYgu!llcYuI!`c$!A{S_|pMX8|ldZ(!6!5#j zrEKfO2T}86)rytyO%~J+z8TWfj#XOFMv_W0-Ku*bnS*O?FtDJV<)Vae(*Tz)x3l`) zO}(Pm|LBj%xT}gjZ^6qEXrM30A)VNtkkH|X@xou~iP*B~@AMHzRx(FdIxTK@j#TfX ztYQ`y&Pva3*-YWI0#*nqdWRgBH_Wtxp^(XBf+EM2Ptu68z;SEvXAX{bAM;>51~N`H zHKy=W>1puy8XgwH*kE9Z0%nSK*J*FzAYtrutPd`g#SuaKc!Mx1?n%M)3iI} zCxdLtT^+5kg~4G28lc5~oI?Xj%9zp0egh4x!0y_+Hv$c_shv<&S(Pfv%VV2X1m?h> zI#@Xtb=SaS1WBPK@hTibHX~PbwAHtL$XA24+SDGWYzC`xWf3-fd0A;>@r;G`EDERu z)*j1v9kv|e8*LW@jnb#I6bvTaNW;uQ+eiE07=ebj-h6}OJ4=v}tD>;GnP1YLFj3!V zQ_KJAe`!g2Hy~iY+JM^RF%SErf5+k$L9-FJAt!&0EpH8>6$DCh`o+12tfgH)3j^Em zbM^x1jKQ|zKk0Y{`$9ARWFb6I7jKv@tHj(E^~o8`;bN= z=mM=O2h_RF$?w&>61ih*!8dcusey*Cf9+*zG!$k>`cfmoK!aIh!exZ=Zvq*g=ze+G zb|Ryj83^l;&A@`mMB4^!ZbEa%PM=D@edisvJ$^O4@buFJ>R22>ryIm|q1JZzCyGrz zLPzP>*q`!_0mdAKkN6etX8H<8?E(w0e~P_&&TYy#=^kY*?(|Qx02=yCdWQ}I_Vgod z+qN=Kc_6HXTLet`-NLu`m`6ivD<`d;N)7l5QzlQP9t?}k@)Lfjr;#vW+R?|zblWKS zBo=b{PPi&Vm`cEffrtHIkkdee0hr@tV+flo1VygiqA(@))^p!@H9bcijwzgylwC@p zXldy0KfJep+&}{aEKz{Dp%+3NL^NU`ZbN`{pYKSsC^GWY6RT4-5pJlSbTF)3?vaR8 z4i;j%3z7KJzz+fx#vm!qljVIJM*J|CA5Nx9+(6ocqx;FO9jRdEj8u&gA zX>dkCD&GVD{7W0cAQ*#wGa{rvgqTCHeT}A35PnNbOL~(it4{2u4I5*BYMd^>*t{>C zO_;*5sRW|#h3&%_w{a{Kt}4iY74UMdt}x^jk%5LciO@f_aZ{x4yK<;tHEq@Lxq1^| z5j1`u|M8h|E9_9g@iNGRYzcv_K!B5Dm2tyTSWBAyaK>oG=m?b1uCyI6 zVQfL8!i0WR8WC_{?5=o9v)<>ia>BliaUaCUY9XUxJZbySld4yRG5U~WylxU`$iwMW zpx#qCNIM!kJf~5}MB?QNgm4~4_*uF%&CMb_RuKM_+7b%DaRdd;>hZ|Ao4{;4xc;l3 z{50k`hkpyn=I>RKEh)1Wo5P*%2uf#bH4 z-@f}BvYrN59bJs$Qk~{v6a{_gBm)nXint9}Gxy=p<|AO?s-{YeA7W+0`U9DRO2>RB zJsW7){@#b_vFb$}v-nsPO&W*dO(WpDVJI7n9@7hNqd+;_A&#y>!>3aiXgmM&|G_zC zy{WLGFwMqjE~MX)IxoyS0({~qW(fuJJuT8EP61=>g$6HDzor|$KtH8%#5P8;o#HmN z7KTlr=wxvfr(6tAC)-b^R(3lW44+&;?TB#}KqBovWF5vGG;p0&iVHUfQyYbDFI|3= zP7f7>{L0F8k^VAp>uyB)xVjC5Lz|%@R%_5Vlj2Hg3g7RBG|9M(W z0OreN*#Lt;e80H=^$vK*(X`|jyr@hD&hoWK&ap zp}qS^#r}GF3Ikf0SzSHHMyk{Qun^RAK_w6Y-KCjGsUSF&gF><(JAH`{jcM_AuHXGk#oTG`#i8w>gocH*F!9 zTvg7oyErbw&R~?|S9WJpcitJDhzn`eA2Qh}eHr{mX7G%Z>OH3j-2IM4j#Aov65C_C zSyjMVJ>+Hkwj-4jp)rzUlMEod>DA z?{;dvd?g)j`}={0*ETIn|NH;;ZzDsO2pU_o%uZuK{BICOy*|j?oYQz0At0#w6DQJM zGD)r=FN-V6)264{a#L9mc9RQw(v^0RV{mJac7`(C3>Vv(s9g)LAK=(4FM@8s|L7@` z&^v6M_+&>qMCMmfQE_Z9TUb}e0?kxl>ezI8Gh0Kt^FJ?fEj`&*1S9!g97zW*){G(8 zHwInPjST)<;C}vGTXGxK0{FEO+Bbvajl8bFX*J_%_?)RKk1vAH z-?Qj;i7cvDS=4hIv399#3T1iQV2g9HU2&OZVq}3C+c3~8-0j=;U6@o}Xb(pwD8V%Y z4X=FltC2}E2n|q68W=JTp1n(!i@wI_iTDr(1F%sHw&@#$J>@unxeEaH0iq%pafM8n zPfwnpuB=hhnh`lfK$%u8VH%kUvH zngT=uR+;*4)X8FyA29Yt((IRDtdv)jr|F~>X@m!n(yB&yMs$!6o%n3_!LR9$w*5|L zR7N+l=-)Dq4E{F8if4PTU;h;8mvh2cF>Tf{DSRS>LE=O}Su??Rm8S-{`%0ri>yT5V zVW5$t(sz!g8^8O@U#8XTEE4uaM4ZKzf<|HLXGBE^L_WqPoI)suU?&QVa2L0xM48c` zFmV;pEdsk(1w4B6aC(x|&LxW%#ZiKzaQ@;5CKP{8nC4bRM1sOMoOk-oDUKX|oSRH* zph3amaYq)2`wEOFY{Zo~R6$A?8YMEaD^rr83d1=W@r;$FP?i`%+^=Glo~-un5tPj> zt?ARFN777`ri#aXo(7*Z=A;YhMtJ7Nrqa@|@OzDZS4lJuEevLV(vNVJ1f6eDxng{P#5JDm%iDUBb6y#}>(slawFZlkatVIjQi+ie_vZf$Q%ClTE3?X6+( zZe&YO&3sZ*2{a6l?v_uQdls<4_<=SZe<%am6G)!(tvu9OROOFmtC9-V*L7&hy^N=D zT=Fsg^9eQ>aJUJ~b`q5NUqAmv&`2r&7LpuOP0_(h>NHGc8wI)MC??KT2X^wFa`zz& zt>UypPNEB1ixn!qk_UvR;~9x#K0M}%Fa}o!8XB(jr!$xPSshEMEqYDq&%g3~T8B~W zsQ@!(7DbA<4yQ(`uxV_hQadZ8cM#$=tYB8p&yM4>XqI!AH&m?RNqPup7n;)`71kO) z@`I`A@@tlo>52zODbnUq6xxC9yVH{D#cAmRDobOiP}tVWFipj^?GsTnzWLPhE=Nw)5#3 zCOry|n?zPFbyHC4vrjQ{_obIu6nE}xf2eR)ZX8d$z7 zmvy#1bwXq17_!n-&zIOn<#B(GQ)5M05cl)9bZxLjSO^#Ikw!vK**>uGbI>;LH{qxD zbM0~LTr0A^2t#he`VCP;R6*tQ)?ZQ1L}z_Ua8~qcS#h33D-{L7C&WLJQg|gUr^^F>@6tc$0y-y63#x82jNv z6rSzsjQiHET9XzpSP=R^87*9dzlN-M6v@ur?|lh(|5IK^#vL#c6`7%ZJAHPXqp5f8 z3_h-?tc*Z@5!s01)=T-W!KZ8u9_KrGSG=opO{-Qv2`ekc!wq2!>p=9u2Osa)kq++P zo9ft7S;z6M<+DlkCR58oUbY=FmoZCoAT^5NI%Z)8m9RISu`^y_p{sQF5ikPuZt3Y@ z``vGT^V_J=uzvmeaEh!wk(1r(I1Nq5EA88cw4pp!e+VBP_;7CEO|QuMK_)oovki^u zqmMqMrpxTmAD&2M#)Ni4TRz7Kx$9_D9&Q72k{2s&jH%8H8=a{grJF5WMs zmsupJt)9==;5p=)bgZ1^F)l}(!A6`*ulA|#a~#eAKoJZ^S0a1*XuA!)efp%e2skmS zsyZtMSu`u~8LQC1Mm~XgVjdw=Xj^;F;NVTN3SE(mz5CFQIB+@SHa6$U#>Vs$igW*f z0MBHy7p~uhp15AD;-rbxck8o$q z!J~{#IS5f9H`x0QZM#iYIx)M9K@+r|#&NOzu^ndrp4}8woRJnTTtv;5#nHE0EnMW0 z<^{cWRM^Mh&_2`;LEFffki~qbP2g|xl6s)Mvm=T@wzV|HDQOGg*(w6F`RL)>ET9<7 zu}x{hV2L_Av#p^Iz7HA4n1x3sFEW{-Z7p3LKXo$w?OSih(ZY{okIja!JSE3A;a@n6o_QZwxr*B)sKc=~7rrYvD^U9*h3&A^@}fqmR-{IJ?Wp$S@Pa2h~Rb1IFtY z22GWbZs8Ti2KXGWIFR=JtUOX@${p&(3uJqkA=FDI?w80GtST=H{t?#B%{i+pgn>F& zdrvuUTR9!*Z|Wy)p0NM3FKHbY8(#;jjuh4WC~m_>7yESoOm@CkxQZk^ad(9{!joTK+ez#cq` zOCJtd2CQNW27P99GL&61bdTfC!}q(*{Li*DlW}k+PNga=m>#E2RF;;7ZjfJsu9d^^ zwl8Tiwl*ru?1wpquZit0Y~)=Lr)_x+-}P)$V>;PTpDy-XPF+_n<8OASSN`l@q%T85 z1=Ig2&;Yu>c!kD@FEX{^M?YoJ;}(Rsm1-$N^;z zUt=R0?R9lR0+CoW@D#3Af%fcd&vrGP*8(?(DeAZX(0)!0m=w|fDhw8hBE}HJpc0@h z2+zyx0R@GBXT+EZTnS7@bT%5U8oO7BnC&1Xsu^OaA$mKPf><6~Gm-u53RA~#ph3p= zL7CeB!qAk-Y0Gpa3D8T2cN9#jcrYT@+{$r$AAAr>(0yZ`I^hvn3JsY-LE^llUFPEV zpBs)6wkkvBr%i>2#*-0y)5R22R@!wR=0f%cFC$7kfvpqar1Ol->iDu(hPhxw`jEk$ zlYtF`3%T@2R{k<^Q&*b*~3y)}@xjQb6MjKXX1kKZqf>y<<(_#P8rvlkx zSe|Cl(Rm&xbJ){MWc`YM@aAzo zzDAIunUAA9l{7kq?*79^(i`u*%g9qI!w)FnRXul7sw$eArj5lczlT%#@GhzLz|fxX zfIXV=5ijXKik5K@Yjr*$h|12~M3)`&jjM1w>vgol_dys3x)JPWZb@BmQ$Z4A=t~=`=I= zp(|jj!zF+CS(=r5rRfu=PN#!A_M`=6HEAJo%+;KHQmG$OHR(R#|KY57JtXLNgOo#I zRtPVT0e1};^~Zno-87=5C(SILn#zzZvygvQHdjjMib%;$Qwe1Ca{q!V(hcx;5rfY_ zLpK&^-yQaa7D7K91$qr5^#Kbu(`S}}!%?Y~mFGL-?xk`JkqP54(8w|w22MPOeKaz{ z?2Q|&ina8hbb~aAHhwpR{7&R=JeRnDE`y;I{VmkOy6z9cfN^ zc^ri}i;O!Rxd>!Je-RAS`5GcQ+t+zi9@uwWj$c`coRNQok$Y4skSt^y zm8VX4`JJ-PHpD{~l*t@(vo(Z+Mvr<=ya=sKerAT^c~;PlqhGr*=G@Zv1d9Z9IE@A{ zuaOZWPZ=0>n8I6FIb7Sz+C+9SDf{siz++tENd4g6*G~y#XnfC^TN*Wx%xDnC$~@;E zMkW1atLfqnXOw3>HaBl12DvctemcHuRs-Fb@@>lQK2BCRdGZ*UjumuL0j)G75J9vP$Y%h0(vjdI{Zb_HNa7vHDPo~#<9G^8=6i*Piv;fom!9v^)O-P(JlH$9DQP*GNv!H?lMXLY1 zd}jbdJ?xm(34tT%Oq$g$Xl-suC&-2=!XeuDTJJVL1{=RALk!$)C4;pGr)$B&x~TsU z1yC9D0~cn1nQ}s!jzE>L47mlrKts~0b5bU`njf-*c`6^oz*+o|kI4$qH?S6ri;)(g z(jNdBNb9d|=>3d9Mu3Ag@+|t(`05u{O#fwt?*@$g_rH>KBp`XZEo2 z*8Agbd5C+3g)q=2bIi&`+Y$#}x#tY>OYe_Bwzl>Gc(oVX(gL5QC9|U~#}x3T4d)m^ zOk|h>N88A@)d9jK9=sdRYuHAd$2-zp08EZ6X`{qG+ELj2|?&ZGw z*o~wD#bSyw!HX#=e4`KjA>~s9KIvO~_cFnNrqf|YWgt{nhIv(D81WfawH3LDy z!i-V_xn_-ddV@B*_N;aM3^GKZkoz2m^3LlD3x+Nd)Z<&K$KBpuS5qCohkSR8{IAXs z77kVUD?C(G;#Yqt7cj7GAF(jHwpT9Da2cAMK5cq>eCe_{xybFL`mNHva>w@6A1;;~ zq!QNlE9~V}>A*}#;S>Kcev1`1w6vtNWF}u`+gI{NjJou;@flA?7{msJ&UGa5SAJv!R2}vvFL?aqgzNTB=e&>AIp75h2>L@Qe{` zqy8FtB2l50$BLcBaH22_ggpVnM`d*iB0Kuo5e%l$sfc#V%gRD2OED6a2)7Lh&vslD z@ZJ5l5|+Xv2$x|SfKd3V3}w{oq>H&<{ai~kk>QFot9VvalT|>)bIjF1gTlxw2-fjJ zNE$D4p<|R76<+S6QpkGgxOjf;ej@W81GIP%E2Ic;E804C9d4Dm3}(BodMijAyM!D< z1cm3`(GZHj%#|wl?WsgvG1U0qi!n5}tejQv`B6kgg|6`z#<>HbJu#>d)Tvi^#i{~I z!_zBVsW4h?Dpf=)5hMyoR~k(#s&6?BAWj`CjYS)_>EARL2BCA4E`^VH6b~BH&dCU9 zIGWt=K2lGHD48=SEhF8^J+K-%Av73Y4))Tsg3y&3S07bmI!<<|Qc@s)zRJUQ3P1Oa zT|juNC>AeY9%s)x-y1ky3cV2aj4?CJbFj~hd;4&VDjZ+V*ReYW=~cSDMvB#??n}_r z-88SdCe1D>fgUlInRphhHFYjq?F)s*v$66--{EjTXL_!YHqSZFN`0=)7~C~g zRjI7JG!@Q388Q!*Jktss^mO+G&D`a?0t|{7$QpUd)NJWk86bS64RPj*jgFYcsm1#= z#58J+u4|Y{N11}wAf-4E0i;j&9!ll2$|z1+k)|NS^2U*ULZIQEfrfklgF}B4nBF3K zJ(+gL5NPbcp}O$?&(mb01al@Arc(Nug;6tsak$k4&WOT~(gS}+27(x}7~~Cb*NtP; zdFy8C?Pq%o_Q)8mQ34tRDC_$uw)_c&I6$1%fw4Ax=J-@qRSH}=4i3Za!65R0IgR4} zVf1_BE++v2*V7lTrJHP<=p+N)-4n|yD>zZ0Dzdg_6;qKL-j&A~P8bpz|H>g>FlZQ~ z(o*mSFjV1xhI3I#7Rhq>$?YsRDBLETtr?&pEd4q^gQaq5q+UvgbP;^Y_>_~b5E;1h zS$WLNfM%5P8MgH-UA6*ew>ofYJK}G^G)&}{Iw0q~=~U!oP6Q_DS6n(~-<4rL>!}N# z2+`iw76I-jOsi$J%in|Vn6EM+b0&~o$TI0xIW8aDMi{2FtK1J+L|@XF2EMYOy}gYS zjCu$(RHkLn@KoymIA*g#Tz!#ob)K{BO!6oO7&1%1SWh4eykuENuHMN%%2xw0?F1PN z1UTN=C38|)X(<7)DIs^wy10U~=a?oU-!$IDXy`-k4|x|wB_ zRh7ZBKI8AP%1vAHxH`pPs4zEB;EJ2U03C^3@I1C%q7QW#`UoPOM1Pq1RbF0^<`$Qv z8B;kqfO$LshvBR{9-bF2S)c*E#hBfG=BZfhh{B1^0%@LLV0{cUL>TB+IX@0P>a^C? znL<7#=B2}}?vO?_G=pd8N4=`&Vm=AV~Yh9D=6(%GeW6F8a3ze^<9zd+GwgL07(Am8}Cd9;NFEZef28 z$;X_XBRxt(!aVqack%B6lXDZ-*7CAYv_UuvXg7mbx5Zhfp_E|0Ixsh;+@eM-05MM6 zGO%HWuJoyGWG3G9!s$Uv26}Z^y{8-bc!-51x9e5Sqv$$%Tie&gEsMZQAKH>mT-p(a z$^z%2Q=a1?dC!1EW=|4)Vhma%=gxOTV9j~H!i zkJns4d0A=TM7XNUq`{cGvW0%63$b7@-|v;3Ase_qjy2}@srVXhQ*S!g z9{#2E9;Q*Fp_TsLge0U7LZ-}XZn0XuOe4862>#D%a^=UOMspi1x?-+97S8@7S< zF>XL}7K7~SY)=37|NM{XMpgi+R5S=ZipvPJd(rbqN7j%s(BM%y zI=LZ0K-4gzYa_4s;TDz3AUn=3E*up4wkW5qKMW)n1R4MAX zM}PwcF%3#;(YW&E988Jt#~3`q*xP8Lf>&|vJfdAwBUN4|lVD@(1calo*EkO0&GQnJ z%&1b<;j|L927qZ|UIr3OE!=au0a&H9mb2?siq11uarj+BS_3coVf;DaV%uKUX>i3) z=Sas=#+3LCrs!CmgHd+U{v7VDTlQF%aR74(+gzZ*`8pSckb+m(D1+J* zHpe7v#Y^K6R*V4MY8;y)qO7(fNy&V^E4&p7_TiX))+^el4_8LKVt<(mggM)n%-Ihk zep=rgM(AqBZe`+FSqjDtl*aQun;A(Mi~OhJk#1a#74@O$3}^vAiyWyG6ga)4D<0zr zMPaje?Wzd&I39mfK!{JrE{zHkzYhbKcIcfsnmUKm!JNG>oEhL^v8s;7GpYFoRqMHP z!-DEGr?f2Kp)i!rGzP_i^l4zpj0lAuKgIspn>uLpYgUa{1hTkSW5N`+You6pbabcd z{I;aFoZ@oD2z*v1F>bs^Mek?Ft+DRA3V;qX;jPmzQStX6G$h>ID&d$~Tbk0|#&dR? z=1d%s%Hb!+;_7BYi=4psG*w7EtY*$+0u64RfZNGv7{S&F%og}x)vi%(*uj7}!6*9k z{AE`!gy4XMhWIbv0z(XDI8L)6iU;8HGJ99+dj}{6d6Tn+IqKByfjl#JS^*XN3#bLc zmWA=-psOs^RvHywS8=M2A3Yu`L-V+QW);P%re!M^;!(OZ5GO6li@y7;dpxBR$C(Ro zYRrT|0Is}G`Z;&5Egfw-m&$3oV%|css3wMSd!KC+gQV0BC)y8k(;e0j|;;FXNQavX-SzQ{TcYvV9v=nVJUMtZ-dEQ=Q)eJm7pVEm*Lwi zdYsfzcr6S-`cQ6&8~=7C(aZsZ48m5p^pWaqpj!DpjPD>=0wPY2Z6!Ez=bGx%*&fSz zBI64tr_y;fSr7(3Qs-PJARvufN!y@+GG4lto|RwnL@wYHfd&vRe8i8ALH*%RQ&+T} z(t321!3>>mPb3K(p(ni&4COikB8K7IUfYPxzS%_S~8x3ZS) zL{rJ6M5aQ&J|}#Ir}9k$QG7a1=Z`@XE2-+es4&j(Mtf)`KU^7!1(9Fw07K7)+AR#Kj2u&LaTs_JI1v`qaQN#NqMdW1*7LS87J5+L;8@ zi7<@DA&PJja}`c;IZhCw3xgJjAVUNid{{X0o2T~ZfW=&-f4+C?#O3}$G8(8r-`tn3 z(qFF4xzqDg?SjRz@}BVvv;v&9@f?51B;Y6GX{X7<9+`K!t%>8INy%qm3zjd96O**{ zl!3}i`&TA97Pkirckv)kSy)n;AZ{JCxKKuWT&%&0`qRf#L-+M071x%{#^#$7&bW@6 z<8Vwo@cEdOliHQ?r?&PLGF`Ma+=^k)N%?5|>S9k8+I{da2V|$TVjlHQw1s&-GLUII zOUcjVx^}h4`??)f6gf@<6!syF%MWye&XNE4kIxr6&Zj+%Evbb2tLti+JK4R^M<$n) z0oVi3qB6^ur%C85NYCoGN5}*1UU^o!2{{2QUBS2bWixbhxbsq4FkwuZJAXm8ot8Gm zr*!OdULiAqi85ZiiW~K-cDt~Ve&q@4sNBK<6@H%Ba_UefhgVn4P1C2(K;9W()jrQ` z7~59P`=9vBWDP|d;Z=32;}!SvUg%x$t?Us{p7gN;Kf&v%h4TsW6ofsgpJm}+aT<%T zWTRRTS6(zQ>%7E!Y+D2e;y(fn^kHA(_d10vFLt)1#@;(=(X6Sdw5%$|r~I`Lq%uvr zJ8TPWEqGYp%XzEY2e8?t1Lq_Eisx+m$B3wNaH;cLI^Nk6i#6+NDp@$38{=}$AwPgg zCi@I{ktqRe1Lur8bRc%TxDn6yfU{E?N3h3?qfRnJj~zQ1#j=Yby_!YKBB1Q^p+ABb zu@ixtK?YAd3Rz5_&c{V9Wtlo&-zWN3Mgk`b&zp&O;!;;+PXzG!=P&>3Us6E#TdAl( zD^ctyTXIq%zWRgv=N~1|Ak+H_#|e&(i~s=3IweBj5s|)AY1;=MrUU!-rTsg1r%|k^ zdB$%z#Sl_N=Mj4D!Bc1)IC+Mr{_d(OEs5feAqZg_0}aCvw5BB*9i1?lqfQW*Dl5m} zDq7~K8TG<2j%`@1FZ`PPtD(J_tcuRBNh5m>^IISAiDU z2?z$q?>HqesngY|ZiHC}^ZVjeK5bH(RyZ?^UKJN(xZ8UxzuK}OCt~Me_6b2rDq=R;c@hJ>Ln9{C7CJYtc6%IWe z=TbYzIDPS2STr+DBD$>L^-OukJYnMG5YQ?Y=b?g9iA7L|z60j8uMkoxn9k{5xAV=- ze{bwX?3JH^z_9|gbF~7ytZI-)K@g13xK+^NM1w4{E_fFvA;6(w=io|Y{r?Z{i#gVC z0)~5}dLoE#6OfAi&l>XdDNTehqU{il(77wK2ICa;+1w1+Ji2YGctlstWxevORM^)A=oTutJ)M%JBg{>19$M+~MXI6uA zbPSIiU#4($n2lIlPr$M3RNjT=`8pJ}<}+mufDJUycrN2XpSXA9X;uZt~1DlZh8FzQ|~x0eR721M&92$!OYiB}Qd_2Y|bM;wr(0o8Y*g zfX@HN-dTX#Rb7jEBsp<6h!GFLEm>HL0{{R(07*naRD?o8aCa*OiWRBc3f7ih+EStS z)`i;^THLiz+>?}qK%l{r03j|X?!^85|5$sS9MVwldtdMORTH>^kp{;oU%G(T3}YNNGG&`yj+d!oDUu*%wHaFPvbq_ z^?hBNCTvmKl&HN1=z98b+MLZaX@7SjnAI3LAm8cG30v|x&ufHewCen8?3uc&3~d6x z$xn_XI+CIcS%Kp`bK2CHO_}AfJqzzPMNV0EI(>Ym@d3;_f6Bt9$V!89$})GQQGwgX z@|(2oPAbcmEX_2~B4kjME^X~XhJw$@7aG#`t32p?(uascTd!8^w+D;|-iBtCch2Q2k;M zz*Obe#=ct?ou9k+Vj2uIo6a`)ka*Le1m}+Ohs~Qq4u%cc3qNp?9al@(I_^sQmpQsx)oUM$Cb#r513A9dmJcGcj$nKBl%keIlD4sgdKzG?Tc|zJ*#`L@yGiFBZUe&JYfK$*6C%YLzEf?QZ7pP-h zW5svVmJ#)cvkg&RBU=xEz+I(Y5Fe%)cm?NfFk1+qM$Fc7B9QHB-HePQ>Sxv~P9S4k-| zC?0T%(Qa*vH{TmyyZG3?Bhy2eQjqEP(6N1H`{X^>Epl5yb*(h+z@YL#9he-iRCe$sjlq1)|Z<#Hy*HUItm-do+M0;O+=(JmpPQQmbV$9@e`Mvzp zm%vABaAUAWSt!0el{Pw%X$wQ2+L6|8`@F9nl!%nW@~c7d`BSlnt-ErtgnCZ(G^^C9 z&jv2ij>N{Z9Cej)UK>*x;KH6}#96-l?R{xj9kCLAorH`oCE2!=-MQ;_DYLAg_n_`^t)(RCNEfkEsPIU`%wRN?a~R|Uku>tfEy&VPwUfW zr?FX=g*ZrIHktSAAD@-U3=-Q9W=T(C8Y8vW9Q*FjSB0938|T_t$d;r_o;SlvnIMez zdj=-p|D4W93AW9?_n!1L{rw41+k+DCy^%ErGJGz1gt~GN0G?@%P2w7H%1%$G(P>AC z!{j;IWZCKh`Qep!-~CX~U@x*n4Q?A8Sx<(m3!2u$CRPS$$J-tXNdMWjqTYn2|NDpk z9p`=O{OHua3^Y_oz6K-zeqa76fd*NjE`rAmiqjE0pIDX>97{!S2p1bap>69+|V@jxt>6x}EUS0Ty zB2sAjelC6j4vY?`GN29O(eLR1fJ@V+#$%wr_R`1{fQKJ>Sgz9T!kYGzX}Gpu=iQM) z`_{H7jKsHy5XTzQmMhL>R_oL_7(Zb`y!qZr?c;HIoUgcqb zTAv2EeP@4)FRxjTMvzB3^gJsZ&VzoF`FAf6Br}8H)PoO>{=4lKt--5;NheA}&^}O^ zBy4g%_Vka(&V4Y>d8Sb4j$$}>3?T)r z2)n|y7#%5iPh&Kr;)x$+S5*dweE%Kz>9L0%3>~|@yL4gI`y=7M&V})V>0!FLxG>wo z1=X51H_}fEJ2bfjUYf}w36oKb)ugMA0nZ+tIXf@|Xoqg?qgQ1y$U3Cx*JXRl3^dSX zr~&X(I8z23*B}?*u5=~=uu$#@-n9x~>T*o3KIyFWQFsO#{y1$xyf}FQf<17uvs$*O z+dX>pVA?`=MpMXa(1~7#W7q&XC=?yWH;;-Zd9CDQmA5=0PBk`s#*r-dNxtua`!h&& z2m!}^1`W!oS2+U1{p53KSx3&(`LP=beAHXZr~!+~xJ^?7f)E>+g0h}nCpIwRwU%7! zrS$V0aOb?xr=NR1fgix%{kE+WJGbc)U1@&@jJ$sc5DVx+SI{57dtnHWL>x14KpX(>o%*w! zV3{}(E)7P3^}9w^DKEvB#+HtP{bJjcWqw*$HKXK1|L_Mgmc~a<${%pV5h>>#5l)A{ zQm*g|r^dhXMt<^eL{$SzC(pXezPEgxk@1r!$Nl%-o5tK8Et|*w>^t7Gd-p;|QeMi# z3SHQ5@~1qOfnUlHUpi$Py3!FK=RKWb7wQ}}dQ9BInnrzEH;R4OC1r=+eWE>q9Lp%O zV&DsT1NbvT2Ka?jSzDJ#%0^_(dK_yVf8|3HWSw;2R4G&KUt=oW(AVFLZj2oaI)rtH za9p$vav?8x+9^Da#HUk)!)t1{M+Sjtzj%-r(un3$oU3<~J<~CupLzPJlz00N*bisA zcW!fPP(geDiU+l1f z{&Px{Y4*~CI51!#-AL~aPN-W7yQy&K3})qE4yEgG$`cc?Io@FBu-B)}jy-#J4{_6# z>`2qr4O)m3oj0=;O2-IB$Td1#AkcuUc=t>^%6Ig8(-zHAe~lSCCPuL4!g&0>qd&G! z4CudibYNOt1Ev}}@+-|bEx>8AQ^4cvEUr2N+0lTY!dj!h94G8thg~PSL|dl*H6Wm? zt0{5H6@(F>E%X}wmj7s^fdLmoE$!K_M27zSC zYuvOsI;dNw_OC#P%mepx7A}tVRCXM5w|n>KoOw5r?LxzPTrL+q@AQZ?kNY9lLjsdhmk(! zy3cD{O{1@#U;)DkOqcA}y>sll{{gAL8bNc)*#hT31k@GfA>65R$76b7QcG`8<=-G>@nDDCbc`7?Zt~8}=7RTDE-cz0!z!M+7qi(eS zgJtsPMn#%lGPTuUoEd66cNa;hJOnt7ly_ zayBw@(hR2)jE%RZ&W=HQ?i#x?FynLr?Jwz3-b@%N!?hO7gi;=>4-G6N&rqIOCi;L* zW73v&ux0)drUK4niVN%NjF~bs&O70_*xi92U@;&nex*b0v(y!K1o!ln)FGLTN$Fiz{u%#n9#OyYYr^{qhv%w#I` z?{2vpg{ykocvD#;BV)R+u=>0z6; zZmWet7B4WOxV6J=foj2pJ7s*!(e z*eVnOZrKVNgNxD(}&`_>`$?w(9|ddOb$xsi#T5kf2>8((~Rt2=VaUF*IpkLxBvJT@#eba zaXhQ_pL50;u_KXI=_MoQ3Rz%s^uzZZ{c@zQ4u+Vkd{1V9#WC-`$G+|?rUZ^Xx^T8< zno{3x?P>xIb=Oq_4LC#6imSRBy;U)&Rn{7Sl)iztF3!2Z3>VZ|L;ijS4gtJD6Ourr!zS8>Tf2!B#MV_|{NvcqBDm$QFW3I+SMUi_qd4~_O=#zKoufOWjh&!F z0}YJ;#{1HSr+w;tUb-Y{3Tc4Bh@$18wcyBS8o+DfaTWMn1aHq}9_5tfOJc&z4>Dc3 z6&+L`zF)f$XN~ZJqYe!bg;fm*1Z=7o^9h#BMwTwZvYp6jtp|RrU#^zjnfcT$S~knT z;{$H5*MKcl4>>q`b?u(>agD+o?65C2WPMkoMB0~T4F)bXI|f+gvy=_AQ=U~`&L$W; zmWAkCEN=KKFEbzU<1wILzsy=wVJn-ISMp8<6Qmb;2AOC*#Xr#`W^}rc^YD@N*=Nd{ zH*pw83?3ZIz~Q;)o)>!&kafC(#+vd&r`S*b`Cqt7Sz%Dpa)iA!K+-6teJ*bG##?X4 zvrj!4Px5&*L4cFl^V+Qq%XR`8u&6@{U6BSJ+%T9gBJBr@=#q z#E)*gIcefQ&O9TIIsEY0maICbAV|;ZA`gw6(g1a2)^bWcBre3G&)ViR&}r|4DO2Ln zC!UD=z|F3darzg($g1}J(y5cqMFx*$S)jJ&uzbsM>tuC6I!yc)hti{UDD&T-Uw?D` zb@3L4^l`|r6HhrMcG-F7l({wShi+1S^S=7lJ}v_dsqd&Y4Zez=QNHQ0DvO4Wd?l{A z?z-5!XJ?GKBM2z7dOW(@Q9ehru>u(>#s*Qx(iSsHgiShePB2mRJav+!C!Jls0C*3LIbDvWt^fnu;o61Do~rIEZ%=?0BlOT%e4 z^O^edGHYNx^Y|k%oasvj@sGy%@5}&-){1oKsIBxOeZ4<6 zQx+_aQ8NgdgZCy(gWH2$e++P$Az~o?<=6fgdocy&>@&|~p+Ouk-qmSK8<#SzSKF_K zM!<)%LEaJH$~*Z%8Kr$Brm#SupzlYtC_wg7rSg}(;9l#k`q z3E^>$yq~s9TT|S~N7*J(1s-ja_V6;C>esO;fBVZ{<+iv3_uVgcX6=P8UAmWK4?h%#5scjne(lqTpeb_RzEXFj z?UE3Ig9@yEDrX8gPa8N4_E~T0Kje^EFcXuGhtN57<3t9Q)K4vQ+8M!JX`zB!-?1$1 z8~IiLLs_Q&Ro*wm2GqG$CaCFW%_l(e-n%i9HSt~=GAxcc<)j$oBKE8!<2nisM$-7K zL!LLo%&8ETn=$}iWgG^+;pDRjG{8sngY-Fr-8DwD=G!m=k3;|XR($tMUyOmQyUmM_gb;h1}JbuR%o&EZ5ALpNSRt7S( z^L~2qMhLYFhw}#da^y)z~*u|wZ*_`aH50GWU(NA~&@|Q7=de0?Da_R}} zme;upfd&Fw>P>=>24(f{q&I*hGnI^TXlN<{#mC{50mmH`=bUp+bRbjxf6MVt2{dRx zq=N?HH2Nee3Ba8XRPY8Gh7BGP(Qc%U}LV zrUG7Y`YG{=Pke&aN_R>HW;R1pl(`1JY5Wp~X-_)2h2bb~6$;5tl6VT?gi!%8&Re)3 z9)9Yn_|KpGIQHiLnU`I`s>p}2I(=7^y-u1QP2qqV9rU|`(K5}HF#0c3OW37Tsq&N% zH7JaN-ud8zaW{_R7g#a);6o3Mz4qEO=X(`XCQwL}C9E=dGCg(56cW3PuhHQrz^CD^ zfb!kkg@JkAH{O1GYzs_B;u!VcyI)3e6|M?Bjr>eELr@?)v&|YmSuTvB@Ks3XTxN_c z6^Me>Y=)^*StHk`lB*(g!Lnz`$a(Pg+hPQxQs2Acia74D!--UqMh9FfR{LJ~q(u*TK-vR<#J%`; zG$9p{xZ@oiAL}tla@U=A#&y8niFbc|?X__riY@z;e#{hd;7Y|wIR-@xHmGncw=^h< zz=m?(y6a{(%Nls|4=)XmUtD!{yvnWxXC8h;T=KckWsqn2a#FZasM4`UL>hF^2n7Pn}wl$^o29_ob1P28IC*@TZKD#|$*6#EsCuN~X$>uKfjy zc~V?_`WbNoj*&`Vx-pGUrKJ(%Zxx)TWfhaO8*HQx2sC6W9c6FWfB{dSp>87_E+XYC zaCqhb*RYpgiLZX+s)T(IfA?+AT;H}Gqbu^xjD{BQPa|N4lQN=jpQ=FXRss#usC~&5 z?n|$77Nh$Wz5`>in4s$%9H^<#_S8izx&%5KcW9BjcPw2+0FSLg8zR=&5CeVzzAEM- zZ*U7yw#{0Ap>Oz|bYwJkw zY3#rw(zg6B|H_;8p$>xm>M5_Oqxz$ixqd2(42~&#bcE&YT!Ee68jof--F@G^anqxZhD+gH`~B~; zH~1lGteP>Qk*gfb{sdRz$i7r}iVK|yg8+$t?pwd_IF&-meFdZcd)HhOeLcC;q><|w7$!85JFNPnVCK!9^HQ$XLS?lDJXMZ-1 zI`r`9)vbHVU!CYQYN3BeObvvYot4fm_cjuUb#X_-4hE*IOS{2fnOiqH&FKO3_OI@^ zBhEYN_&AJU`#yW@MUba`WRF!;E&_ z%J#rjJbwa#c6TD`-o1OuB=w&-5?1k}4PY7eL)ufoC!WMjd8GY88_Z~!QC-arP^03e z>#vVvPC6+LCCg^}?b!mD(Pp8c9=RqjSiW`J$Ld7;IPqfLl&urxqLgER{aN(u z>+Jh}8OHxUd$5BQj!6zcP?p&uW__qfO*^*F)L+_z2Cu~#4a^j3of@Y|S+@bnci($2 z7sUSEy?4dV`wWP4354&wecyy7^&I?N(wV%TJfMye7vM^}1aOl-B^v`yPMv7U;LdDh z*mLmHUAO!;MogU@SAOQxaTLMBq3t;0&|1AR(7^Nj%8UkWBm2>^3?AEubYj#a$N~a#A;{_M zt~7DpLNXee`o(iq^%}(ig9b!LoHresRp{x#Wby3HS`?RGdMR6x?ujkn6shF}&EP;g zim$y@+JEU7QI^3fc_#%N_!m*?dhNf(Ou2dL+2`ZZZ(hy)h_77msW|1NlQYPZb|Q5v z3sU3os&peg6oJ9QuCo7apSD}_2hT{OX6cv(bN53J#ZPa&C5}ONoPzUo(18a;Yh?Ul zGTDSh+fNxTKUt4`kxnV)Dbv+`DHrT(jvSx^7M~ph-CTF`&GF>0VR7aWhsJ663GV*l zU_voXxPTwDTUGY8_!my;Nqr@L(soA=I8DxgrVl&lGJNE#@%1ae8XwzpZ?ZrSXPuOO zneAxyKxvbSZ?oJC3}{zaw{20Uh!=S&PvEzm>M+*{n_fMWpytrH_qJQ({0lE4%Vr-^ z_z5(y2w`D|Vyp9P$*aOIT+)6nUPznrKJCcs^sU+3>XJoFjeCFM1Z3IcX~Ud->Z!3C zK}{ExHDfsC0R1F>g;U-a$K})s{Ty|eZAtqUI9wN}8JT%=7R+NH_>b}Yus_7j4?Y}M zeCA>TgGZ4u(SgAa@JSn!X((G;CAYKXf_xwz=v+Io;5+*kxskkqoX{?uIBhC&?6r7u z@N+Tr)i>f--~M(SGH_tD0&Y>DJaAB192vkYgFFUF)prKtweh9z)K^KrY#d;_!Igs> z_uq9_-1@@cIFRg`ORgraUOxe-l?CEi45)-Aa#cx`75V4gI9OEaa+$R)idIE4?i5e z`t8o($T_hsyBPg%IsPeu2KNR{C6A&}u_Q%66%vKVdnlt_*YAaY6hIll(Mr1PlZsjyfvS(Om1n zxvdhr27+)Jv?zs%!YfBdxUO?k1_Wdlg|WuUY@&T`F?j87u8(eH0vu1-8gadQF`v=& zOJFwelB4UuD`Tf(*tD?eDK?Q;Z2fo31bF9xvc0M|Q=zTSGv&GFNF@5w;J z^*7xdhwMKn19d7vk2LUkuZT2LF1R&XUn+gu0#Y=8s84g))cKZ4OD|xYfB%Xr=Ls_ERW>Mr~kY+TL_|VAGjH<(Q2T+`bh0ZA4OwZE4Dm{KNLxcLr65*FqCuWn;Fb%`G zdKpd)duBH4z+$+JzAYh`vTEg0jN{de3Ls0Gw~2MMVJ`cz&%mIV$zq%Dny<@o^07z9 zfrIvsUOjuTfLLqx?w%9Z-EwPmTw5>BI_*?~J3EtB+ac=U5DTNJg9e7BHD#^_X2mSc zYxak{pz~xOC@ZDonT+O)X5{-1!wG=hd3${Qi)=a6 zP7P8nc-R+SlYZnadCX~IT#Shrpf8YB_RxdBi^(kb`Xik7gUCQ?fgCTgYrr@CmIfhZ zDz|Nea>&4+bYZ`1Tq!#|=>A-FUx#uyd~okQcgLN`n==`)_}V3x9AKZy^% z%kQ?^w%B>nrut63;xleFC?7k`%aqzDNe901>Tkvyl=5vHi!%vW8#GPX1Rzp_I1)zR zlQz{s%0y+E&n3Nr3;QMcPuTzrW60pS<+j`7*91yD?qkGGr`L5Dma}$-qcjvz=s4uA zPNOSvm+~+(HE55r-2jjdqyZ57*R~C3WcsSFUlk*#OpXhVI4VB-`OimxjDHJVMLG7V z|I9#0eIY+7hj~|B#RoKB1obq2ZJ+JY30S<0sXRE17k%xk(T?Z7{FSf7smGsy{_DfK z3mBLf%=MA6PUVv>T}LDX4dB3e{u{6#>SN937TFl(>M3QB**Pv~J$d@{xbt@p#!qgz zA--_VC*z2N4k6oPZ?+k0muou+M`7d_x?70Fi?ZG+3F2Qolr(04*QM^&z~XKIuM=GR z4MB`L(A#OyO@Bt}diU-PuF2Mb-gSJ`Ins*LD3k>{7UE32ODieof!Tg818^<~T3uZo zFEX0;gYW%Uoc*a!#W4(U>`3sdJ^EE!#zk2z$M-F>2;dbwo556QNm`ND@;=XGfQG)F zMwaHAqesV+=Qo&QX-3CO+*qIZS)V!yxdz?q z%!wmu$nBrsC53zhLA$%|zBBsnzGr+EyUBEHgI8Gwu-N__2%;R})1h%|JZ@wVMO>+C za%`N<92Oh0XCETblXk8i9ftIDZT|iokcLY6E@8n^o>$g2hF+O20z{%KR#|k zCS7;`J(N@&#M9%bo!Z6r+qR6>2;TZ+G}I0>7-Xp8G|*t0zc9Gl#72Vb>SO;AcP21W zu{C(WK!ZB~EkVy!FI_{RVNtv^0XpGbq*@$K|C#O%adkaiT)4ZN3h4?ewa-3kkxQm4lKjO?jLki(xk?$|hsK*m6v zQUhE|8GMrNJq#u#A3;0f%aLj2vvo=1%26|w42Ea0n)2PPX~;`2#g{(!A93J-{p0v! zkByHJ4CvLXCvB(qDO;Eed>624SEw(_>(*7uVP%|$_)~{WhhHCi{<*mAx7WudmtM}G z-hLTqaEi6>Y3EvYDRTg+M%D|nvQc|A>#DR<*<)MgFPP5`6$F$Cm@PpzT!8;$(URTg;oSHH+Dhv~$Ww<%k=?6(p-DG(_F| z`h{UH#$^b-nY{Z2M%K^x#2M@jzH=HU8|a``O;B*Gu)kJ=5GK&+*J#ioD21THNd>2& zD_jOKTxHf(wC^#{@SUsUkj~xXlb`)G!GIIQnMWsoWjqh>o&r~wn@xP_B!Bg09A zmR+=!rlOpjhot+YaCc7j4Hy&mJ@`Oee&NM&DcJWMCY}XxbhKkRIK-XWCMYfI{eN zh^zP&B1S9~bTW@+8j#TdsE<=5gF33SkSOTnsZ-)P0}Vg>SzJy^?V*DPMPHOodkifD zLN2H$E;ImyGYuE;st~cBELTB8zo*jSQ{!2j8N_(~_16hBJd+s>pT?L__~~qGT#085 zOvxvmLi#~PVZY{_CX|=dq(aNl5gybTZql+vj*5(;?7=wHKe&lGPNYg_paC2ShXS)S z;BwTC_G<)+Bg?m7gAggW5n2M_b(NqC@=U8_H2m(Kd*XQ<(w~3p+XNbpVfz`(-StQg zaN+zdVOKb%Va4xM#+8V z61*I**&Ke+N6@$$mzIOmvS<1+eo zPjJ5xJgCqUZY!wZeid{Mfv^uZqhU19^%+LJ`Bn@WJ}iEF&mBG)J$SZl;|9^2#UOjK z7-YL<(A%a}0mbF$4oJWeg^92TGynk$XSxhB;0(c+>v%>wY((GI1721Xg%&aRz{xxo z$$FcGAV$ zVHyCmT4!MM*SFjfoz_-m zprPL`Y?an|JJO_x{v)SXRd_xl^T--u7w0+=@{Pa6v3;y_;itHqJ$p9k((lEv5hLPP zH{TdvzT~nvmh3F2I!Uw2NEh8x9w@`)0~cD>Dc8|cJ zd*J^2HFeEC$X%d$NZCzO}lhf=WtY-L7sraH|b zqv0t=FK_zRH)9mfe*4nPGSDDygj*wdqp%Az|I%=ShOz;ar9)7*%WKMFVNYj@wvT=9 z-MH!2TjN(`HF#v8fk3-~@KwN}W1p~sR~^}uRV+Ftt~F$JUX+t5gD6jZBJXL~Df@=M zIx@aNpy8D%lj6c7kB(2H$M?ZNr{lAoIRysZ%8?@sFL7c$!dz~RCyjV512bIrUjt;Z z>%~0w{Il_?uN02a_b?LAIOXH4b z2oD>u7suA4Rb}%wt&^Xg#}U2nzPsb8S6`2B0sALUIW@Lpv~ZL3 zSGPiE+IYyCiO8kvkV!wk^VXEM6}1y5@4Rj7$cp)`>r?jzY);w(*CCaW{hURhfotNB zvj{XuUp@uQzy@;_4kVvd;H@ronyELBd4ZEyqv6#F%VH|evNA^Yr77 z#_r(!n(uy>z}>#F3B7KhL77Oy(=Jn1de~>uNA@GQ0$~zRst@6@U$lo7LlcjXp?J|1 z1wVc3bDxhhPCq@@JyDJ;w-S1qByLN3_o6yhUe3N1=gK&KN?#dpLLSUQzi118=YPo1 zY~D65{^oziQP`|5P`;Wr`A!Y(QHH!_a90{q9x9i$-#ny$QCquBW(fW4x?jid2fq*( zA&1X6`;#$nz`)cOX8DwISDh`t=Rh3os)J1;4-2bu%&9ioNjj!x$SU7lD`&_{!{drC zeJKt<+HZ1Z-d%`}j%?57eDFY3+ z6KMF-Wmgn|27-=l2{aV?NgV`nP)Cm9gKKSHWubhjZK>SV=2p&GwlY}VG7DMYS^@ew z`XuL*A++bNyJkj%nI_6~<-9Pb{-8zqDUPYnaz(awhwx^g0o~Vxtc8_}7Q_fL`kY?$ z^P6vpZxXmW9h<2OgHp+t1lMwkTJ{<|3%u*39c(0Fv@cxap!i2M`i`~{`@kUNyA#I8 zGecj9dmni)MvWaGxBmDianykar3@B_;zr-7#JvMolw9a;`qO^V&eQI*OyQS?TCp&! zZE~>luG?;lUqALJfrftZHRQp^2skKbQnz6b>wid#%3HU-HTYs6&u5f14v9~qO!!(}w()s7bg#;RQ?2Ue+FY7|eX5uR=i$#42RHLu7<5mFo zc(!4Fh^*$0?3{7V*=I*<7G}-E2Fhyx#>YRN(I67a!|x?h3K^709fKqFJPTwvb;8J$ zX{r()r@ouFN$W&OQ00IE@jVop#uPR5zFp1>B+`DN01r zbK5E2cN9DgNQF~{@r`(<5aYLR$4{OVx8HYPJjfj0OFnTXsbUAk9=o#@ z8v@L|r6qbtE+qOiBtTg*r~(>;T0x?KT0^^J5}h=I4H~~j|20;wzwss(OX?g)9 z^>*TWmyAYgd|JK&RUzuBkZ{_ChK1=x>BNI?6^D#uR)a!I!8(1$jBwQYXE)v$mtJr| z96*${R}V%vi9j3Bu^hLfDKk~(ZZj~x@wzA!iz z(2nyz`ALFJJLM>%0@5rZBiEwWAqv8BPTH zmt+N;k0Ej9$*1Cob}59I2A@U~eda=z(p#qF*}t@1g(=;X!3O)lb}6XD{q*V?xq#YZ zq`kf}yE?wZ2*5EoMjD`|K{5CY+_YW6!+R=u`@z05ol9IO05=C3RxygXA{`A4;j!<$ z6AwP{K-}>7BY`-KpZ(~ku|LK{5ojRTLYcx_q-Gy6%t=gs#oKZcS z{j=YV7om+iPyiksIJe>K)4fG>@7S&gG_a&#!#X&cb`t8^XK_T-I+$5D}#|pEVj@pEfsMdVhINp(@6)nL2UINyv|nk*eM|x^(VHprKez zU0zbDsyyve@h{IvHyZl}3=GzJ=y=HA%A8S5Mf%ZCe;VVaPmRxIQ3ZuL7_pJ2uYB%NYfDx zN$6RIfGgLn&p@V!3y*2AI?Zez!Q^K#oNxTuk7E+|zRa|eQ#9nzPr~h1V;lH1g;Tr; zm-zLMbgCY*?38EV+D~!ivz{(wdHY>=#cj+5^|=1K*U;~WL`!(i6nfikapFcfqmyce zoP4D$vn-7}Her;KAdl(BU;6I1^7<8@x*$$J>6GZ(t9Pz`FPvsH z0DNUF1#AkOczHbo!SHL!8IWZAY=eT-DHhm(F>O{g>Bf)7_4nQ#7o2)ZuF$HhnT^-sKLGP+upK#-bfi!mQUN{ zGi`WnIc?c#Gppkc0clQQfALjckHe6c9mulLAx=A2dk#9(50xf;FJ+oIq-@(} z-zx?DR2!FkF!ud%1ch#jXI>c*XA%rJl_1GJEM{q-V<|SKYlSG!T%gb(UOMo|Gig%U zVm$`#q)Sh2VeK&;*#!g!Um|GwweNg8ju~(O!G?p=j_*pqSI5(!rtnDP(z1Lgp1o!} z#6_uR3SEHA@fq6VAk$2O0nZ@IZo7*N+zUP(`=OtD_Ue_kb~#8=;>AFuc7TJRmR}P* zm4D?|>a|bhSM}|T>KU0a_z>$WnNf8n89X~9XI%e5{JKkSGuC7t`J zovxjkeMuiH8^uY=QFzFm9~4fbm@4}qixuBa&~(5KJI1A7_(JTp>u%X+(p%~!aHC#w z+OPJE@=ShFPOEzj8pvHK-?V?IH>Ys3mddk32FJI)^PO<77^iTbea0u)k*a6D<1~>5 zbr^I*L?mrW^T;@-?JXxTp6mNP@nrPfcds}L|EMkUhH8of*#Di6e_o(Lgp_BA6y%)_ z>gc!Mj^}Xh-ybtJ=eHPSaKRY~r%XYT2qk8X7*~G&0iy~YyLRpppS<9FR>tm=jOMNr zupKAL0m4=&s~i=2nIc*d94dPWO$DulROtG9A;d6b*zmajxu>)I3s1mtVH9s$B8e(J z4O|T@VUyT$j#7mg;J$35j3`m6*mSb17*$mVY6v@@@uA;85^qc#ABVD+?!JTe&&41$ zK0#h6M(x;B< zDIgVk3S`T({1hUz-#SG`X>{snNGpyOnMq=hM}=wn<;yP)i(&7-hXC1`RJUW&IQKmb zLvdoe6%yjxx;(_Ob)`YWZ($Zk;v^LaLd2EYM+|={?yAttSxi4T2>dt=$VEvNlnN*h zm7slRzbg1FLt$r>RiWaRZaQc>y*gDYrSbIXqxU`#BdVul8DG8N;^@b`F(atru2Nva zZyTh)q(Sb9EBo1#%ArGW$Ti3yh2LuG9`(lS%#*w^%kIM8FMRb%RweJ1FuT~4_!JwZ z@>P*aMO8SaYna#U0;-cHPmNbG249=_PL@;t>Ccy5RNbC}8$uF|_^#U81Ul9*h_(@u ztcUGfhl}!v!3EI86a$`vh&OP51q4x-&!zy;yf>fBDOj*-6QgGlFP0TmJ_q#Kg$1QZ zVeHWZ#n~3c36AK~GFWLpW!G3qoR>U#JSEq{`*H2i zF6}eW&>1+|@q9Brv0Yt8vL?^~ha%VLSFTA-^fqO4vNnW=a5O@$3DXA7MJ@zMkl{T7 znN#O1jU|-Vp(i^XFok2;2a94oTctFn=?&Q>q^ceJbJM32!TBi4nvo?Ie_A$e5XT*R zGP~q-VIegZgIq8_etzwB(SzHkF&(LIPgb%g8^hqM&M}~+f)}42DojV%GCi6|eO^Ou z719kuOMZY(=aNP~4t^aud_;_#J~=*d_))PhhE^Lg5_I;Jx$=*#O=aX}*aQFoKmbWZ zK~zpX{OM~j4| zj@4iLQ^gF-0Hp_;Uwp zNjkaEiUwHX!@jA=Z41+J)EIN#^z{$ko8=!jVE;G~S*$H#5Zr7R*LhMWD{nPA%b=n( zr4}$Rt`0&-c`fba){@{*2e^9foOpt4lIKRf%6{)1<8Tb<-7!Ly^QPImPLcg8|4BFY zpY=HZSOZ?%Xm_Zqi@M#CuGpT^44ny+C$s+14S_!y$20X{zySxu4t@J(KblT04hq_* z_v{Ov(-z4u{-J#FuFg{K2!phw?w*70ev9cy_YnL#eAhivMt13f?q(!UI?s22*H7^; zzZh83rtr7$+kf(z?ea4-7lFYb#`_b-$FS#z#+wW0#OW+9XC`Gw0)y_nq%1WEqi$B_ zYAbk6+)ImsZoT%aI>5k#x>4M_mc}?7#*qXAo_=E#Yj1RjGtN4L0Ctbmk2)sGZFx!B z@kl$0vcyjYsd>g985jgz>h3zMlT#0xnMW3>nUs&-dw*`bdi22k(`huQsnM?uDc+@R zZO=*5rp3dID!w*#eAZR|*@G`TF~G=XC+s=_J<>+dMSy|&xX0!`nHH@R;o*l)7R}D* z8nI_*BbJca$h&KoSMKx7;+aKoVFKUZ;w%sK^mZM)C7mu^Fe}$<@!r);Guw^9rPN>G z#NdvVWQGv3&)?$RAeXd}>yL0e*46+OcChTWxK35 zoi5%LKX$6+m2{#$O}krups$rL)@ysyo&Y&Bp~**|cq(3a#GZWSke8adCPUPA*| zWcG=Z48q9!6KeL{D_3lk3 zAq#+_pX4KDfOxU5^vX`wppi1h!vQfDXx8p=9h|9Cr{)?+cRcfS4hWrj&bc|g z+KfMWJ*OpC_(|QQ{IwqW*UvKWpziaq-woiJEoPu$^n33xfHERpe&^jdYQVran4qTX zmAP=F)6#Ms0{BV%DvN1APGeJ_+OP7l{aVtl{jMyi3(vZ%-jJ7GjE7$soOOTZw9|73 zxppntS%deamki7cS4F;vf8~sHqdt^t%B^*6<+)gPb_BEI>h zOJZkauy%)XPy0n#Bc0n<%E$E#%-DD0#jH4e*6dJwpMfRm(TuyrWM_@QM!udwLyv{bX01uk zEJf*0nLaI?H)$K&k-^crdCO?g)cL;{Bec~l0~yZr9!Jx4TwK6W#jhYWVp#+LiaD^3 zqKQ)#=zI*(_oqzC5%O(Xx6Tz!i&e34ZWtv`r3djUFk~=3lIIi_o;hC+I9CFL^H|d` zrCbeY(@p1-@v#VoX#>pdNj+@AG!<8qb^3uy-ECUz2c0*K?pbhzd$=5je5zbv)aiX#-}rI4@d*Mj>GtrLdE+?T1nk$@Dfx234>$A_Yvr;a&C%$ciLi?QMhH@Yv7EYmrT{_6Ig&5lRYc-Im@`NKzzQvKZ5ve71~TR> zSP+X?lu1W&Ta5mW?b=6+#zZ-x1$RS{b`+QjKM`(w{H{`PWL<+ajVn`4`KK^U;Yc0A zJ!3Zepfl>Ffv|n|?zt+qydiBTfACy7$iQX_ulMSM2d7XJ&M((!S8<}2z?ac%X?`Z@ z*wg3EN(Znt4n+ry&lVWKI>^q+)=7t0QrH@`H8=z^P>8GOHiB6yYuIN%4H`DGt#NPP zsffjOI+ygfzx{4M&_ijME@UK82g3#KT&ULRFzw*0bmDkM+>762BVJx0HJrt8Z zqYZ)5mdJu;;K<1Qda}#RkdS}n`?b_#CXM`J|7r*UV9G?Vi8s>(YTDwM^oI(w>rD71EIXpXq0!|tK1QU($KQ+l|>m$qJNd4uBN_-5v_&D z8|lDlX7a0W+Mj9Aay=b2VDy^uT^Kzy61``g(v1DDj8MNQZ>rHBld7l367)=S zu1D%Wb=?wVoPmZ$^tscG)L+tNX1^)VXh+>D=o>gJKk*K)Dx;OvjW8A$Em_K_(WFe9 zc8-0@;TElOT1k!|OC#{4sr%yHz^IEc63^LoV#!Vuun_< z+k(;gE;w}ZlN}*`eMTH5Uvf>OQ@v`RxX^=hU=lk-^A z%k6SIv~HVnxH<9%(1eDx^r2&$89S7(%+ZNc=Q#kO%$G)Wz%;mZ96mq?&IkWG zGA@?e1G}SZXZE+}J!!+mt))5Jtl_I+D}H=m+$p=nyH1yVoBEu#>Rc>V{~^nkP);j& zwLONldR0e4o|AXfb;?O~lJsnbiL3uNhNlhoTb_sfV1L=C9*Zd3g<+Q>``1!;b98T8 z0t{|@-I6)q!YR!-FMcIuO3Rk%`zd?nA>oAv#fjN{6rX`LgJUz1J5HZ96InBl`c~1@EE0+=%%BtcJJ)}KzO_$g;Y_VYmN#{9h`wC8a#{3h)g-#N$Bv`idKefaq>ac!YF&)c=DjTrX;I`1Dc9VKqd6NrnLf2+J$O9hIru`}HDIb*&;zrpeZ1Sx# zPC9j660>l{a~Gycx^SJrqnwTcUu#3Aod7>cAC{}UQg%65C2eZ6G(na~Qx2dw_1F5A zX-^`9rF*v_wNE=yM+*j*(uSr#q<7`KJZfM=9xiNcWTNt38URnqp915B9c+Kk!xkP( zz;qe>;fb#(+>ID9r`0iUjOpi?jIT!^z8dte?@ zxm!bL+hP+qMcEX6@h6|=+GLbr=C-m?*u}jzoq9=|Qkm17%pLWj_T~!OG;_|Z+$wRk z??3~s;i*>W7Uj5jPuVB$0Jp!DjmidXd+EUGP{N+JHf74sG%}}{Eu}B#E?q>wE(TAl zvh0p++C?kMHp^TYn>zx6kJPomOGW8Sr~O6w%6~YIZ}0;38thRH8%$oXY)MRHu$`bCm8NdvDQ2E?z z+e7ctj(XZYEPN*Dk-BAZahO{l}=2@mP8j#DSFTUU~;G#NQIapsI%D7$ON z&Scy5ik8rVzS(+gv?>IknN$)W(i~WoTVz_(pUa`0nb;P`o$>KF?)c-PbGNSfTm@BG z-@oghe>~7oX}OFGKO+!|paJ+x)7b8C{@|nuiJj#xdEm}O>K5baiYxz>aXDqai>_)g*l zyu%487*wblpfa9Dw*u8Ya&7YhBEYV!twF2N<)Skh8b$<7MYA7r5gnctt~3-VTO62) zk|PQVPlT|F$89cEYz7`wK#HY8WozW2FsK(K<~(tOJmSXw&^Q+Nu1K8=5)wtU4~5x& z6K?LLlCeaUjH5%v;#&wW1&1ePId{*fzguNBLztUEVI9KmdL9NDniAB|_+J6diF-$F zJ?uyEsgg7ZrofVpGk^qaHb|byKRm~S$vYax8V@=Vj&f> zAg!oW(pW(@7#ysEf5e$al@9g>7P+iLQ|dNAUeK4DXm3?x0;#MXUI!$sXF7xF(wm07 z5PjOUirz&3JJbGlptA{mTLn&>Hc?12M>2~bLlwp@DC0L}W;O$=NjSmZTJR+v-L7&~ z-TE<`;K4NdYR0%JQUBNjW0(E=N2?C)n8INY1b(8;?pMuY?Ag32maJh4!_rmkaym(fo$=Sv{VsLl%WHSY<6y=scLwV47q) zpLQ6y$e;jE7<^FnD5LEYd8-^zZHXh^hQN{2fRynXKpN8GTwc@AQf6r6x@e(#S~;bR zPuWPHYfyPuw(?J=ktQ^Fn>WQsL7uAY9Zk|;(|DqoG_cJ0vOhJ9iU4pCM72B(51kxk zoU%>2b%p3P!0KqM^y}*T%3x>z^UWJ3P0vV%h_I=y5270RlEDhm9xGHHwgH${e^WSMZ{hZD=e4a7|_;tFKMH*&) zH_OTLl!peg9F5la)8GVw34c1h!0!T@t#E8Sd{4t%qexhF#FX#O{})d2s@#wVl%L|a zkS*{T?NV-Qq?PhqT2|JJL!b2>@o(Tk{p0BCagS@^RwY$_3TD)SFb5Xb;<|eqz^Z+%az+{ zOOL5jC{&(IxWp~(k_hm%L;2_X@?7d1`azyF(<@~ZcoN6rR^1|^m0^x- z3Wujz8T(s-v_2Q*6iOL~wtKxFcYqq^E@8SJ60;z&C~aNJg1{ZbdB zALE7XBXKy9GfN#H;5`Fv2926=x+vSa<)ptO#|o!HsY@BO-97E=H$(O@0=x#@^ugl! z(XDlp=-p`>rtQLc(2F4i0TU|iB7+Qd6rf(Q&k19!S1HiP!oP7X17vH^(GZXNG3`?L zVGVM9DFONF#j9h=!d0xFVIBPEo+^ty{q8B>+eXXDYa)`v>nRg#KV@j^ z+K2Y1Wviq7?iyaUVFhi}=4y@}P;QA|C@ zFJ&&jlZW}#HulsP^P0g2{S!N0{x!3~oe|v8XOlq#ZYeJvSTLhU`RkN40L#oCN9}!I z`V$`IwmLx_k!yR12c8!<8PJAqtKixC^eO93GXWPmkw<`I1N6G_gB949*uU7N2@kT= z042mjnT6kChKVx8I;0O;BxP3WEc#L0+h4+^JkGv?5~RtLDSR3XvOl#I~-b_78Fw;ca)pux`c@Dn_8LL?Alm4wALg|`v>C8V&;$B13X z{M=1+lEN$682oi!r#D2dt|Di2Hp|C~u3*3b3rtGFTOuvQ z)I5CAxzQk;`DxduY)(2H+*#m1n0#v~-LcDy&uV5BK&@eJ?L)HKH1r-$-2#bJ-8F&L zTOTDs!B|BOeq--Zi7@j_m{=6~t1Gl@bYQLfnDzbLq7nzQ+FH$TWW=tqN9C?wkC!3G ztdzBuG%I>Ji%f%h>JBVy3^mwwi_n+c;DUAQp2o~@FWrdS{nrv4M##yd=ioE6%52U{ zJFyMfTYnQ^!MQ%0_hgzTtJ%qetLJ=X2Hgk0eoiuY;U<>SyGC^4tU##C_Gi3LprfuXC2HpG>z39 z^ze~}WtLvvS^bxI>BOh}S)GPM#3E^3ndt5u()$;WhzclO6zJ6wd?e}Sq6Xn%D?Ieg zB-GJ(dl~1PF+fqmYkWTYy*$i1#xiokl_n#9zY?8UF2q+Y~1Gjv` z{#I?G|F)4J%+=Q_tTHF(h`GruMw@M#UZxukiIH)njco$U82!QC^+#Cqp>})#R>dx@ zuZ?@)hzP;^#Zf;V6bfH`$Hg{YAd2m0C^@^D?Xxf)cCYKZmy1TQ-C3Lfmd-V37xCm^K2E+czQzKV?FtSp zkne&7MEpU%NDd5Y*V4Vu;3;E{rUsu+DowzBzbvO8W8E$9t2s70bDobeE zd=SDwUCno=i`FV^`JSnPD6)Ws&muH`cZuBMkW4{l0%6w!yyd^=GRz5V(U&Fnyg z20^ZpEnLZfp`%}5VH?NT`83Z)Ta`LdZTO+e= zps=cQeL44?PPaG(>%#*oM&57iMuc{pYr$90r~WoV!^Pratt ztW{6m$RBaEegRDtB=B5d+%Oa>2ID>N<7w726hEp5FoOM40_U06Dq1Q%;l8Sg7kh&f;h*SqB+kE*!>X*m^$d>Fu*{WG}T988^ z%9vRXqKP8MgDc_LCd<4VI(Vz|Di9gC`f~1tYr}|EGIVu}*B=`=hAUhvsIcc<%LSVb zKz^<}_GOJwlo2bEeXZtgeH&K7L78&t##H+iUSGiOIKt@!{q0S|_2&Yzq?D6hvE;%d z`~ds4Eow7>0HRB)t^ai;DLROQ61Fv!DOt!01Zx;v%5iaw`e;L0|2C_P<6TRg3 zT74Tdx>2p|r>B+IhS&#O&R#@UeULosWDRyw7Eg$clTlY`|KrpfBylub645i#!&hhY zLrtzUr#qh#r6~8vHr&JI zP8^-GfIn;&J}t<6HHazxIwu#4h^saAk|72&1A#)Sa--LG!qSNYx)8QDSRTJv>cY^DK|@`tHK!FPEHFk@VFT5nTBHJx6@^t%m-biqx%J}5Ij#u(m zOV}oBD}%6JT{3;Pen0BD2{=O3?#>Hc8pk`uv;d`EjCh8CHBUoLO z+g+ifs}y$)(B*MNPL9|A~X+YeHR;|8sw$EC)$>DbuVMQP=rC_T%6-4j+~|D{`PSZ z7eg>P%S#ie=qpr|+3v{)Y0js8kPb0}<8foFD3Jd?S=@kNF(s&1#pLfU7TsugnJk#6 z(#3+zz{PwdH_}!(!EPJ0+RBa{L9VubnFh#qBUHM}@N}{nuTbi^DEr0_@y~)&qt&4> zZ0FAJ3Il4XkV{o{IpoFdobPu)n5_oFSRc(*W_w&MGCj_+1eN56J-NFNzR8lkvUur< zo=5B9PLMrDlxUetj7a21r!FwYxj$zv0~Nl7@N1gNn8U1V+9L)}>s2r%t}y6*5UG!A zMwKyZx@T{b>q1I9SN0<3gOU#c{`2C_mP^HA_CQ9mucE%_e&Bx3H|{AX0joIy(ZSMv zxc-KH7WfpDlo6Q7K*BqPIG=lRW~asUgJON+Tw3vhO-*l+;Td0S=slSQ*3S32ch< zFwUo($dM}&RPDj1P>v;{^S}5~xl2opmJR>a4^3b8Ed=3S<%#91!fK9l1?&5*v@LST z;C&M&O07y%P5R>|E*xiru9h5&14k*`=k}c_A0@Ji4{?5GjiM!5WJ;uoPVhzjgp0JR zXyK~`Y9Tc3=~Au`_QB-BTK~@X{*VCY5Ng{jhkawM6u}FYkUbFN(`Swky|s5)hX)pi z+C>&1vOPjNuCdH&eMT^3`0;JgdY_A z?kUqJuFvj{nAtbLVYw)IMI^7iS&osV)(qs23otpEe?ORz9?+_8naEG(JIE8e2L;_@ z(U2z9OGG*1W~I^f)0JCmu?|9&D6M>vm3=0x&s3Px+7&5#kGqM~ulK8p&5%<)LsJ4@ zH#T6Y#-ILxo~75NbDsqW2MTKLS6L9;S{`7T;SsHFcbJL6c5=n!kkgENC)U@ZR4n2` zf8b<)ESfa08WjgTo%@J8j(1y=vk0=sb79=#-^>)PDBo|0of!(Vy;+QMFyOqcI?dNW zj4$o_(ecA$s#KTO-!~omki|ocihJ(JAMufK)lrr>gH_S#GMYaAFg|`yB!C=H75y@Y zHCYZ(5B!)XXG@sXr^tNAaH-fqA9aYAU)*yO-9PC_ofZt>d&$lppQdo;NiXGn=T5)) zq7=83=4gqB`vX!rlZ+AZXN1a6>7w6pwB;2gHn@208^I2*i;KKOKOk}6eHTR8=`H7D zNP1LFlWu~%dyqB05Xern#v;21!@oWRbgs2&f`GhcL-&u6Mb=Z`sspsZmD!B=hjrTw z2i5^TbzQ{~yT=z-Ry|fdVTA=&s=;Q!sxWV(jbza2KA*eT^LcyYjCDeGYj)kJ4HP*W zRyU~c@nt=P>unYT^gVZjE?HZXxI~|>hj^Mmh*FnP_cDU`r&DGit7oE*F2FB2d00gz zw(dd-%+8obx+0RltxT@V`Pt@alMIn!F|tZkxNmJmh9-1e7{P2#3M5^*ubHw4IUuY& zLglHeC{jN%3Ro9QISVvf*az{S2MErR>N6YForRJ$(=ec4Bttqb>X)>Q8>=frCneRKgonO(FR7Vbut>D& zO8$Cn*Dap^1Z@_CbON@?rd|z(7BU^P>`Deege+L@6B6taL*C*jbWb-)wn62Vc6oJi zob#;^u{U7T6V(-0=jyMmP(*?Xa8A=HEq3A%2?-PB?+otlTyEgAf{p{%Sj>n#g@y1X z$>7c9j6Tw5nSamQSy=Ve?=$;sn}P7E^ZdtmHrgd0^lpweb!>ijRXz(` zm&8IS-MUMGHQVQzb0-;7CQW2JG@TYD{N|lIN2foDFi?-_eoT~koDRDhegB|l`mARx znaZew)-H<27Wt51UBlI?MSij|{@fDS(7P-@{WL3fGb?tb;Xydd(R0!B_%7RLL#0{{ z5kCmkD>$BPv*9PJM8GYFvb2t?4q}h*Xq3J`Q?UwtLZxojr}^o)e{50q~>xySTIbaeQ5qkAWW$wiW$jP1&)Pwi*D*!#*U3L~i6aCFBpro~$b zXC|=YcsOu;(&+Ne%q&VDS~bfif52GrKIzdtwtVVJKrbgL1^4st$}$A_UVALi={5@a z^Xo#=jCqLibF;EN#eNM@*z+|+Hp}Li>GyGgV*ny55Bx+^nFrp^X3aPKpB@%!h!>SW zQ?g#Ll5ZjCu|(%l;%xd?3JHT(2$cZISp#h-PhEqisS9$_m&7juRmmC8_sSa!x*Gwr zb#|7@ahPOs+C=&7a`+DQT#!q-0lheH@B7IcuzG)K|~s zxM{6nj~!}ZDxgoulZk?M=tb92YLlTq#;jnLbo z3oQ-DJ5Pc-9n_9p7hx}Xn+DE#_6*$f2ILbj&R7n}EEsAht@`sf$CGnGzTZ3g`Fzqf zON^c8WSI;plUrv0DpG0RfeRUqI|AWnO#k1WeAb9vvLQ~`OD}h1yin^evFlZhGW>8O zN-4}A#(V=&@me+OI?&YT9*opGSM~Oudm5hXfGCRjqE4|9=MD0a#n9SD!@EP7*ZP3f zGgC%3!_p*NkMnTqa_y5hs^u4CXsx$%8N@HuZxh0 ztnMu3P#lo_3`|!_T6L53$)OS)m90>XtK=Jp!22@1ls@@2ahHpvcs<-Ki*xmBDHJN$ zTJ7-i%g-(#zVr1@+K{1OOfRUz6YJ@8yXi(ZYOASu?OlW37Xio(zgdZQd+0K=192_# zQM`F%&*_bk@WtA@3gnbimPb+hTW&KB*>_|bWa?~PWvfN%btPDL?Z_%1t+kra zuQyl-$#o_88zx!rvhlv))JyzSS1+tbo+`q8GG>kazP?evT#t^>A}a{snQXnbH| zg_pp-{ou_Po~RCL=QnS?@5E1&KbBaWR9ktA+njH^QwIx}o#E;=lnt+D{@gY^-Q6_$ zttD!BAuaxX8g$%&L~myiHT(J1I$&`#kxE_EKl__cAQXI+G`igr*q4plV@O0(cF>ie z`^B(c*X*v{#Th=Tp(d8C!T#*D7IaGfQzT=x%mf^(6OeN1{1eD(@k4uCN;jj*g>%(6 z^BY_)+R=x8&3QAUPBpR)it!l#Pw}J9+~nAJTW(teifWu=jo&+u!cVkic|4d)isKl{jic4>Ea^{2b_WdV~j( zq+zgFRirsW!wLp`EB=bc**GF7%o`Ika_f$l{DIQOjN(cnrdALmhUN=eV-=(w6%8F7 z2@MIqUs^$7B5UPo*Zlx|bFdtcg|s)8HBz#*vY?vv{lWkDfv*2*30sfKVHNXvWQYF_ z3*B_~t642$wP{c$oEhkF!S5`a%B&a zuzP`ST%rAksP;VP^nQ23>BL0i`_}TSFpD3*x0ufw`Bo3!#N z-(gwAQEcuLIL26C;Q(y&Yt(&K!|q_J)5>q@iFN=zZ9SGmuHgMxFPioIy65aSx@oBF zY??V{ZrJ!Q*AIHE6leIfas-|=b<AE`z?+=4Xm$ z;0Xp7C0}TYDo&-8+Lwff@8*R=S;0&jcH9}JXZu%Z1D$*;0U5iq3P1Swbo17qL{5?p zpKijTmm#={HxOd08s~t=!OC4t3rIInic(96(U+6g&rB-Cm+w zgNp}W`b;^0XiKMTFY5>^pEbjrwe>IkNF9OQ%&M_VfVq{_(X2lrerjyD>??ddT(S&6 zb}OZPFt)V{b3utt`)$YB17cf`1Dhru>7fMJt&x`QSz_Svr0nWeUo3t91-#TA+?~@K zBw#xnUew^sPGR6mxoU02va?EC@FO?2WN8F_$rc#Zwz_|Oun)X3?A}c7M!IJ$9$3y) z(0wm)e#wVuvA$stP$2X}Q2PU9Qb4!%kg9+5GAQk(W+wKe)d)s=Om2D2&2rTMvYlY?%EKUpt)8hwtT{NBGg zH_zX0ml|*L=Bk*2YsjPMPw(A@CfxOAHoZ+}HgB82t(jpaOR~lz1P+6`&kOF$icHBW z_^e0G{apK{k7CmYB}z>wnml4UK<%moodo&@P5CzpMjGrX?Y?OAiR?E#-ehhWn~>(# zuZIjLKFW6BuL_KVh~zTa2x+Bz<29zO{nurhZn|EF7&sW?RUTq)b^Lf}NGQbcr$i>~ z=WfJ`t){|OkZr|3PqZ(yJ88(Y_6TutpuV!QBNy4{Wu`JV<1hQEOVEm<^4^2_#Mk+$ z+!#9gOm|Vyu@V7)eZDGnjPMcHp^ZDU{565BTDG%Xy{THcxn@U{Dal3oltZ#q4R|DOuH@1J3H5vH`$5qBNA#%M=i0xk~llN2T6PY^i{124*J7&1iHCLe33Sx zwhDUp$+Hq-3p_sWoKt6T4FTV zA9T9P(nN%<-RI3)CI$Y-&@b{-_wQ+n2H^3Im)b8v~aXcKYzX;L+v z23P=lQz`3HUbCAf#hP5ExUKlEa3o%@s%e#GhdBXk$)#Dxa|XHCm_QL*YYtQ5K^rnv z1dK{_mgl8wu1}d>UtNKcG%)4CPT}tlnGi`lY?%<>DKgl1M!X1jy%gPDoQx#;5_SEOOE;A8^q_Juvcc z%z8}lYp}<26ohN)m)p9FNZjwNMN2j(&3{Z2UkqP=^8ROIeYB1FgDo=|)CM{l_6^>g z;E^tiyCOT%St-W%-{tuumaNPp_FnK_ruS>T%Y_e!;ak5#pu2bopHh&!$9A-g> zHf*-OI|MSW-k%2!8m&J1*1%>&^rug=TR|#XAgs*4V^lJ$YRil->xNo9W0oEljjXPF za0kYj+oTqz**1QW2hgKZ2L`u3hfv4uw;Y!avfrZK!Arok<@D+9TeVz^48%3YTNVOo zMt4U>Y54MhyVF?o>QlS$k>QyCqp^P}P6-WZTpfWS@9!r^LU=)x zuo8EjyQxTqlQhq5a(XuSb5$Z%eo`b#e=-f3B$M%fDw7f^*tQr^i2?b~edVS>upbyJ zVph65`1~2}f%o!d;t9$~_)ML%*g>uG09uTqVXbxaQoy2JxiZtNf?Pgq6X&p@*dINEPH2{ z8P%GOcwOw*EXK4zz7T^GKjV%jE(Z8U0gUQZR7DO|NX4AL8hiF&PY7ECw_ZG6Slw^6 zeXQ-rmh-FI`;`bt-8()8F)@-YT-ITT$cQtOF4g4jbR~aqE&cq9Zm1SzTs=fn_P?$0 zUplpaftHs`6dUnZ*eZ0S+a|NDlfJR(0%d~Bjk7R0G4Yy$f;TD3uBx&%j^^^As>@i= zla^DELqI@s>*WO754OE{WcS^E@yVNH&(=+2p?5nf^8p*Ob`%BV^7VX!3&fxSwSa3a z?`P_#+@rupQ)mqDXv(HFB{S+?O_T|f+JtcW_RsCXt?Ikj1IT9uAxE=iFe0nRrc&GDI!H7u5%a_$;R}NelFSQQ z$A{Opo!z}ruC!F9|EX4*HQ4oCQwXL0i?-IZaZIZe_qMVjhMe5{zkGlNgm0r&Hj{1D z2g7&5tQTpZ`$a?pkKVBmOy%s96f?v3iN8&l-zJ3MiYgQySBLY}?XM>*X)8pju1veF zOD*@To0^!OZ$Ncw4wDAljw1U8>e>p~({gpun;E`+d!Gd`dTJGIcg+PDUnYHIn;)N= zVS7LI-Qvb>((=^*X1a~yQ(ZL8WII+pdq{n$9$E5ByKyT55*CsYxPhPxuP=Z&7Rt z(I`Kj$m>;*$m_yf6N!z>7LDK4L$b%G$N&F4!QVSr{0bn^^7+4nngbxwkX2dko$Q0G zO@56{Oyy}g6EWrwh{~H>lZ@wNaI@u(mFeO{lfK9;lU&#gTF{>ldIRrERUCYB^?2tP@ACr=~;(m*E|zb>kP;8;nP&)o;9 z+t>r6Oq72B?qI7 zy2Bb&W-=Pur56XsiXhzEMv(P#4-lJv9aB4~seO21U`p^^l0y*nnCNR;bxf4De!baz zyJ2HAJ2@AdBFfVFrHbBAL*7dkSZC1;k=XalXx5BqBn<=^wXPtouv=Tr3Hlev-x0-{ zzNtnh8ecg?qNM*qwg7_v;Z=c>q(B-nNQA8D-)r!eW~|8~#Nc(+-TP8be}zHTk8YKT zUe8&pjc`^NRqDlf*ld-hRF3$g5X^p*E&ZQsa=79H;l^j&i2>ViL;X@tqzTnBDLW1# zb4fM8ZDNQaY-PFpCX1uGZXS>xp!13WaeH1q*ayvhJEj?WUtH@GujM3D3*u~y3-D3l zcK#Q-{5RGt@*zm^IZjdsiu%D0u$2r+p9)@aEGN;I=_r$7{M(QefiJ_JCD?D#4EUDV zqaqeCGJpgzFCQBp!2e3c$iDE=>@(k$JYhoD05Ucid{8VBJDVY%bmtrzot%d)`IMU! zyM-cZK+4IguuHW@t@-HkFn7z4q{#KSKmcu3f#Mxl)-HcH*fhgU^uQ zui=woJ{vHUx=|PtN6*Xsr6Jj(*xZOsK7}9^8D2$Y(fRsvMg;Lw&ZO7vZX|&b5wF7LhQRGj}Z%6W^`qJSoGEnOqcGqtwX1AEm-R z>NWm9#bd!EAR?+nF1oOYPu2yNjBU5?2(Y4Jgql2X4duxNcs z+J-Q%fx`g%0WTWdk91Z7-U1Go+m6P7?yHA|Vy0#l4aV)JON*aZZLJ|C{uv2Zeg_wy zybNz)2gxn^LO~2o>*`~&(SYpI>iz&o7|C+XxlKnpFVxUiL2syEj^=(2PZ#DIzPu z^X>uUn+xlS_wM79zOTu!{%LjEcqDvzT}%r~WZWODv(A*c+87#^+@g#>{Cw%QlV$@^ zWX@tBU{+N*O!Lshd8HwP#hq{ktk`+zT{Ti#qV#B_Uyek$yvxt}$dx!~B&3%-E$<^C zRB8FX{a_+prF(GGciD7m^Tb!UX2n_!Qv!A+!k7_OJl1&8J>~T_+7dpyOA$l)VmEzh zyOYIXFVcNTFrK+F8511vCbBm!WBM8=g4?3z(-ik>kRfC?ghduHz*Obi`hVZ~|FQsh z8FTfBFdh(B`)!`+)s&VT-{Wnc1ZYxC!bDa4&T`(Nvdt3K&{q@rdP@@fRZw|VjG=#x z>5KuFGg1hs)&u70Z)#L_nrL`kRkr+jPI68Myn%=u?U@-p;@ z-7L`ytayF%dstirxsM3RtBM@+37z*6Siy#c@CJ7&!WnK5oM+-y5gnk-mLo@`FmF3L z{z~7#cY-Bu5>z9ZsMIK=$ zO45#YmfW|V!hFXMKa1r@(AnpmOQ?+gGM8?W>GpFK((#$OF1i9jErio(o|3MIPWE8W|b~pR{3*)w! zO-nf!Chq;poYq0h0eEhEfr;1u&11p1yAu^qik6Ij&)|fTk`je!tE=s1g?;t;>1I1Y znX?+3h89Ux>`J@otQ&J1+r=xSz+$}95>x`*DKD9 zJ$A~e#vIM#oyEC(FJ^i@cm>+D@{XlXX_%bs`4i)=M@dS()ZRI*n_{|3x41aP5K{L+ z8Rc_>UuQ@ytGCBwG(v_D@5}M&a~M`AqK8?x-5c={;=iovGF)T$T;k?mP_L6W(@$5p zE_%QN-f1ri|4Y^WO(w!WC>_MfG)!T0x8y!LK0!>)Udi-8p}vPk)Q_Jgw4PBG6$QML@K|IocrlTEto{Ty&Jq=i=U@FYF%Ck$A|T zvSBga&HL^#rPH{ca6}QLsVfUZaPw5UPVHqbmprE!{h{>-tL8W(t~Fvy8McJtFk^N? zX%DJO&5Ff)rXRNIr6^*%MG0RW12hVfE90PVs-|2HxIgjMEa z5hyvZ_mv9dGHKTTdlrD`-BzO8Ax8s*`S~a@jPrrt{G8kW{$s7J;M47<)kMA`&!;1O zvBkCmo~D~v1Wg)G@jK>W4ieGTa%z^uT_NvvH~(e}OI4JdM0RGHxU1%+8|du{=cCVE zlVh77*Qr}?maXl?)r_6)TGKk}pOnL!ASwvgLciZ)g=lp>xs1x^FS7Jx3PI+@30PZ& zO}=!b-*vGg>?>aCq5rT|(8cD=f*6n|7@i!ktZkQ76)bSPoHl1v-|}AiO*bF4JK)`j zhxt#yfCEa=lcn-i>Q_q>aTqc*EPu-I+azC&V^judGhH67o)rb&7r8Bc==&2oG5H=< zhx;Rl&s)2lB)ViL?SjzJYLP-1iMJ93##XRYCH0YgWL7*9%9|*z zwmwAdaa0aYo|&kfJh)HMGec`$;J{8fSH5$1@s_GkC&Owy$Xt$xyRQ--oAt>3hAaw& znY2tg*_>Cwek!1>n_w%tnp;3^$geUe*gLg8O*yhj>~lfm7sFSvpZ|FYr)aosWf2XD zIgMF7mpxLJ0v?Xt_6t(dKg*advKD31F=x64XZl~y^K4d;PE3{UbSP2WGGs)ys!b@q z$3IE*zPxS6>5t1Mz}|X50=u5XZD&7!+Pk9FDyg(yGvPQEHi@C&a`7QOO35U^2OmLu z-^SuBI0dhdz97QJ(YXb7R>}QKsICk(zGBy(HMx7JO3iy3Y_cJG?<_-ZULVNtdueYE zH5Cg;&i>^4;8Z&qA_MpP?AN;pE@OM3$ zVk>++c7)@vqCRrfmbf*=p#8aIXR@8U&^tb`w`VioG_RYKo4=ds%lh^Twi5&$6V3&- zqQg=mMRO^+RQGaOK1a7VrUh8qC{3(g{*_q?oCiO}RKZOF=-?Lt{{hyW^)Y{**%9Hc z{iaQgD)8|fvIR!(NW>Ap>v)6?A|HmG!*HDGL|mxP^Bo*J(o

xoypf6>GSA9_81&D(@(^tan@&WxhOol!*tXsbyRXZIB(#fpyVFFXU^HCGUPd}7?4 zLFGSX8t05Es6xKdWiZGtv>8*J>$jTx~DPB^9<$bHl zA~-NMKX14HO)k2I$FyU1Q`}?ws)<6JN0mjL+0Assf9qiXtR{)MKkp)>E z!SS`pi+3x_MYU&qQCwu%!w`1f8(AJnzAa0cr@9E?`5-e|a=bhY&hF&-j)tE3pqgyU z(h}9!I8#On{DC#k;atfdc-{L_b~Gcu38Vg*9y9*~+-rS?D?W$iZsTu=2QEe>Tp($Z zEmx8;H$REZ0GZ++V52wsw+0f~6F+88@xBO83c_1+qr^iu7BAW5!-S^p$vCnfqB z6RBk8qWG|hZtX~@W1R#g)p!rV(FH7sW4m&qM^P#zP#{9fQB73qv6D-!6_GrZcYZu-9D=xk4Su`xvamM{K#tx? zk8Wiu3K1u|ZN+!>@xUKOWO=SMg$d?h;qbsAtZk>5)nn!Xo0(KI=UfuhNSQI0G~p># zdA2N(uVh@0>LyiZIJfSFD97FFnDT=OnD_SdS7|A;D0wWpkwi`=v)jz>6kys0T6~sF zZ)9!;hUqYE%Q~V|vf43Kwuik~vkp-DF3(4^jWhn}R?`K2O@HOsTg;*Zni6qZ^S*6l z(6R#w6vmj*l6~(s6)k~=y--dryljM7_3+31l(8WBcAP(F)gCkbMK?k%!5xu;oR8uDw1r#-g00+sAAVUgc|q+ z_}?m!wA)IPmYIoar8$^~_-OE}qGr*#WxkgZ3g4Gcb@$p~X0C)pP3$Tuhgx%EEd-ZH z0kAJ{AjQ_2ZcT!e;vpA*Go za!U>4i50~2yvG-o{*`k3A1HR*{2PMq#QuqJ;t^E#h`CGwYNF?%OM%b7`7Qq3B!E_t zYB?a>90A7TdvuR5Jb3;E@mrKA@q;K>UuX`yAb3-gJIibh42}7^F(I zl`$55II6WCsOqEg?LU1SIqlys%I3s_6D-3?9h10Oa)-j!9%{BfET59Gx}G%cF1*T^ zEK;ikjJo27xQWNxXpg+gY_GGpgKoRQhOZB*1waX!j%o(C9Lyfl{nikvxf6N@n*dk% z*MfKE?!&KVNmzNUhe%*sVSB80hSGSP7WjPmExn(Z#Gp0hZP9dL8JmctT|a9@A}1!6 z@IwM**qni#har;5jtW=PLro4gP`0>j`?1==fTnFz$ZxlR*C*-US$|kT$~~G4OOnzj z*o1!T_^zk-eP@zm`JeOqL#k--#&Yvi%?0?AmH=O?#LekOCy1>UG4%7%k(W&9oH z&frp$`!Q@33}P7>j_@8$t{9+TjlfRVt%rk^2H;u|RWC%ODw-;}1e0{lL$0%B6f)IX zA5b&kCNX%GU@#HXRde0ySbpD{XZ-!UaEd~S&hhUH?QQ}S6P?!YeA54Er$EWD&Kx{! z6`wRLcPYN1G+z0Dt5UOpoAw(qBhxdp=PNVlFM;-Prg0UJ2`I9S19uE%z8Cz$`&Go% zz}0u1(yjVM=fu;%=ZEg<)Hs5Uhn5a@X0TUYmT_0_V;H$}oC}QQS?hd&5eOr3UkM7o zGg@H-7w&g!QD%>M1_Z`l>z|=3H|?|hc|)$nNOs`_xcY*P7dE|g!0X4yU5S+EhmPk& zHU9%Ggr@4%fCnAbu^iFk(UjM>38=HXKF+P@aqHj0A##OUxJMAlZ zSI!pf?Hx5RtVU2BNk^{o$M*Q5kU%7v-aBdavKug{t=&e^7kykqm54KYzMtg@eDbp} zK$7kGO3LdfJtCK!l+9n0{LNAfGWs zUu!vl-*mT=;k1v`+h_K)Z3dAShrY0wM^UDl>jAz6_^Y9#!Ba46nOk(dS%6v%ZqF<_ zCzn>X8$NAHJoNzhMqq;>>D8;8%_T6(C|xT;s$AI6K|(L2O&k9g$zk`#y!Zty69oS* zNbwbcI|UJT9Om;G?z4FYbq#YDsZFNF-PLkAB8yC_qPuvSb;3w!`hZZ!+C`}Z5vD$8 z)ezhv8b~eE=b)s%gueHe$E=CX1C_D&cCs6EfO%09g+E+Yf(Q-Jm9vzwa>?Y~L%w3( zXFs6}wL`tKpsafL6GMu6P(oqVeN@b;R-Qi%Hu)*EdG0a6=CQQnp55XODMO=15BaL9 zHQ0(F4nvguR?=~SGk*@e0JXlrbHYd}y8yyNODQMED(+D02xv(>+91W}E z<|_O%EB+S`NR*IJqHWE2j)^ewu=QW~tz(*1*}Nx3Ch*JTLUqMNfxH^9={{9vO;vF} zFBSK8Y>(gs5U1Y0r|hD_1|*uh_dlGpjDmR9R((&~>c3h*w+8B&k+y|CCEm{`L5sh| ze9weR`u2yDbZP?YtGRkxy)PW;l|W7uuAT5a4l@9e+;^32*F2@jmnLoljBdw2W+67> z7o>M%;o=P67UW?8?1}}s-h?wnFESAhAhDAzc>CoMdlxH#X!a>3{0l@=L9~~kF!QD^ zaiTS(`CxY*l%cUKGbX%-|3kYGf3=$sG&q15ko9~X8|X+b2=x;h?<^q(jsaB@1B3(2)Jz&W;iFP1>R5Uh7JfMdaHhfy^Q)( zBk7N&A1e&^;D`)eOXhG=c(~UfJ8k7-p`ik3Q-^A?Hpk_uUpGZ@Hupnnjn`rSL)Rg! zbnAO*1y2I7fCP^y#nh*y^>!ml&bDe4VH7D1F1{0;LLczB4yy_o0IC|0Y8+Ju3e#4f zt{cj!%IF1!LU!K^p=@C~Z8ddb*8sV_MAp|DGlCocmZ|=M`7lx=6Y&Skj+92=?Nx$4 z)Y^>JD+)04t_cc74W3xquL(_>&#_Cu+mU zCKfG1hzws66RK22sqySPJb!HJZw7c zlZUd+C~^c!1RN+xlCSC`BF~1{sdwyA`@_kfOvEA}LG(c4q;c~r;4UTbj(9O5fq+5Z zxqA0fte~Z6@gRo^z^?!0!{d2h1`b>3kU9NerT?*muEe0U{tCQlICVgy*thriAWRgE zKQ8S*X!PGtVXyv>Nk{vABxS5B+fGBE*)A<9%?rr3PqS}+Y0DrQx&k`WO#8=;=ieRA zHUxnH4C|3hRsc|ND^A8yOP=YWzvd`dQHWf)25Tcmc z$a22dD#gTlKk)e`(8cYj1P(n2hu>j~MOooX8m~3P)c4e?7h&r!aaCp%77;m4!shqd zV!&AFn?MDVN{3uasaKIQSVm-%bfF|rJnzdQ61|Y8_z;@uF=HSnSjEa9c>Yz;h-dtp zFW+8umXs(7!-xMJrsV#TKUfG`<)V8#CWAYF9&2_#k>Us)oqz)|aKoa2Aj>tj7C&@k zOC%g`ru!qO&cbL%lmW|3E#|YxOCP1AImOPemPU~byHM`>Kcyv1#BNIfK;2`r$7?PbI6oOO9ORIt<-zT~` z$i%No)aG}-s$9O`RMzYFcW{o}%m zbh+(z^D!)8qc4qXh0WEFL1vP2k1!(9vJZ34NN~sZ(3B29;L~m(X9tX5xF8{rOK5T- zg}Trw=JJk;YK@3LI2x(G@;J~IS*dAjTfVgLh9?c?q!|4i5QF%0mqmp_ABfv-B+$qh z-uL#O6|VmlxfAcNkShV#=AFVpTFi5`aN%#@d~uSPdsP8(;9V(cuS|5Y2S8OHf-Z(W zck6ky3!ei@8IoHR3V-^Rml7JnwO-@Jh=@}q+QJ!Z1-bOoUhI>?A5xiD--l3SVE(pK zF4}Pc&F(xt)~}b}(Qw~miWS!PAV%J46;s;*a1X{}?>f+R8 z6yQDIWk0h9-gpMuKm&YX*?Q-`4{lH-5Vk6fB%frMahb3B+8hgX?tSb_{#48N$`YRu z%ZdpQP&ARG!}tz9YW^bZ<@o;t?;o*Ar2qKXGqZ(ieRJM^_R3bxc4%_t+&3w{ssW4n zR|bU?oXq5zLFR#omUCa@-;%ks9P?W!A`D{azjGZL@9Uqk(<&GBNsXv9{GlYM7_3Dr z7>z&&f0H)q_X}hu_^RtwhCcg}*Jku5za5T-rFU*Bw}GcO0iyuIs;`Zw?GImB)=5{c z>l@~4(60@Grh-(2c2eJ~fUSrDMV%J$z^7fXzbX~@q6(HLevAc}wJ&Y0{66s<9I*ev z{b55k5w-@lXb9Hz(o?<8a3@dcope-tD*h7og}Vb@1afRh23HR^^8aqNuzC^RA1;}C z>2`i79HS^c$XI3T1q+~#dQl=!n11%JFTLxcDtZBRZZAJL(0A@Q-Y|_6Z%ygkZG}Wv*2k^Ty6s z05Ztlf7Oxyfy?H_e`<0-R99$_6{bEP4E@MOP5rN?t;g3odLMe4Tl=!AXkt7N2Dw21 z13FlMv9@e6-HDEmhl5J}v8pcCzB0{GE9M(R$qg(&Qup%V4-?WSxUE4hgR>>SH#mT2 zg^f86n6(sI4`#%i8VpMi1kjBL?NTg`CA3ismLLpbgH$Aa%oWf7GKdUSS z0H7`~EUzXWu{3DO+xPi8oh*wptTSlw*x+1VqEZiX25x2Pranr&IJV&+pJk&rT6G;~PsDvSd(-8KY12+(82NIZF2WFwW~ z3Kk|zQo8~?&F>J%^=rN&)U4-(;P5C1H@WYo1NyXUq!@_MRSp8LYqRIU*!uc$DC@vC zh@`chSO2vMlu<1g$LRn0>91cR6WW+s(X^J5vV zP&8RYWyQ=Oc>4Z08d9vn|D8Z#5g^r*jJwWTr3~nG-0S!b4KtGYxu7sJRN;F)-R(MQ z$${9ptF3FI8Q}WNHKPce7h#pjQ=jk zpU4$38RV!BOR!YEqW5Lx9&mASNI3yJ)5})@%yCh!Jv$8%c;MZF7;zn`2HemtH9+;% z)eN$c4aD8RVMaT4U*0iY{&GtLWY7zJ>70;grs_s>EhS4DlCh9MbYulG=yF~c(*Mbk z5dTPYW)C3Kr|axZSL7qEXeiQ~sW5Wr*ovhTnTdcwZt7VqwZsYlH#5gvdNh=xqf$>m zO*?OG-X{CUfM}7fq@f?|_>*x1Z+kus6`Ue>iK9(nDh6?uy`bUqV@17RvWVn%SrMh@ zuCf(8DE>CI08fX2Dg?J46pIs6y+w!hY7K||ONMjvKp9N{G%(7IH9)C1)1E(wE!Zc|0B;& zwlBFqv*UsPoQ06Cz{)6j-n!1ratzkJ%~=vo`kf2Gz0<1!oeF%`EIuBjp!WTDQ!N>o zl|eM*t}06lj{B&;2hmuYBEQltJvZB~~>e%;?WU}497;;qyJ0=P2zW~I%VI6S$a(JR`$@zFApq`Mx zkIKFQ1efmQg6*Rw^}lrT_}`|XpafDnN!Meg-RML)rldNxo5%m7G5p^})&FCc!7_vN zhnf14Z|mDnfMteq0qWjE_FBFaaTa^YwoFJM$*~u(^#_8fM9%$nkl&%)5Bu<)h!9oT zo~OMGH^cltYTS%2GgNh}gNqI+k@z*%^N)K2C!ek{|tQdprdNGdm(0 zEOY9mAI(FJe4c%{*THp*2=RREkU5~G^UFV=CND`Ew;*{uKY2Vm`cYsg2Al!u|IOX` zUr@l1{`&INPvWZ-+I!0`*B(oY`?!} zpXckjq_TM7-r1SJjA>P_!Re}YZ`%rc;q1lbkTvNb7v;DgqOceWdrHb{lTHz$@qhk$ z`TdvwgX!(3Y>;Y?)23-_aGtZv)(0>3(&sf@nm) zN4ak`H}UrEJEc)$MA)-{gQaIPAo-(EC_SgZ4L<~;IIg9#<4|9^5LD?M9i3BPJ;Vuu z1<`N^%yj<$Ff%p+dg>7HY{$0&0OcjQ_|0&YYz0UZ?^g3gXoGBfgo#A}85PB0Lm{`B zE-{yymJEp;LT-Bzbp8On4o?IgQ?pfjHs&t0yLo1AbbRfIV{|z7X!0S)-#Jzk%gNr2 zlWSre&}8n&f>iv{f4G{XJd`#MQ;WGL`bF=uaO-A{Cyi`brM{4UG9}#HXbUe$nsM!Z zAe+EbEk%K`eYdVyJMvFoa3-kh@VZc;u#R)%$2T$$OM-mz-}$kmfrO=)0TPo;*kC9< zvJ+4SN5<<>t(KNaR+mB7W-D7(qP}~Mw82DLr4RtFs@a3G~23r7@AIkSS ze#x6w=AGWi{84WK8N9m|8~Q*Ob2i?;U{aZ_K7pT`n`g6fKSxo-2iEYBLy7#_n+5ea zK7MbgpKdKG_8;s~!%VcDne+CL#n0LQ%Q-VDwu58zgIOtI-dJsALS9ybR{y`B2g~p` zAY6yC#GBCmSTAtH!B@%ZNoKgWKM3{tHH@6wHsABG_tS1T80flf4A2KXkp{~_7xlt+ zNH{PW_=ICiZobbW(4#$l@~kWI4|gO({qloe48_lg(gu;3xBwy>MNV-59F1# ztCPt4m=_WFZ-Wzq0CV)ckKzB~6gVT3z|}9LqcMaym9S7e5D;EonB76!+v*St_^+pk zaryVW>$UiQzW_i6z}Z_r@_J9en|O^R6NZG{O)?Uq(>;yVA>Eu;Ts$4T+?LIAVw4og z?*!JubP$ssTY_pgVG-o12?=Ln0`DBhD^aIYg1mGsy7^v@y5bZ5(me|S0nPLv2sP8_CsOE>Rp1OCmj=P4lCidnO!lBGh0{6 zUo)IGDn(l}whk)a#Gyw>2o0pv{l=u-!$9>S&B%7bM?n|oFH!qGcK5%Lh4A-q@@*== zV249czfPrj*B@it@u14hqwWfwaR%I%jks;3>6$$!{&}S&V*amw(hCBJOZv}2Lk|I+ zZCv1DbPUwOT-iiZa%84*E&~0S0+}Keh7887U~4W1mI`@>rIP@`AHFqIYiJPK;5qr< z&>UES-gN z_fdNsXLHR?EnX^+Q<+)OZ%pF!m@2()dhQyx`!APRIsy3SH49#bGuwY*_-p={x7Dn% z9x(_(HG3oaA>XnQqIS;%8O4yY7Cab>LB&-VMdKF3lKm#OYY>=>H#{IVh%)3yruTiy zK}yxM8sptJB}kirJ9%uR(2D;OWRpG^aw_~xj6e)rY4Ut!_nbo_6nHqgfOy_)<*P-- zDnvUF5h8}Peu+?I%;JHeV53;Tf3O?IBVb_k=e&8Qx&-vFNF|6c2f(q-jTiwhmWmMK z5$R*-vpiX4A?DCKpCp2`70AjxUQAYkllMz4tMp)C)g==9gn1>zFfG9b(c zt%lm)*$>7K`u;_x0z$s2QQnOx4Sbr1pnE?=xYFWz&i&sgu)<|KzP{SpvtA9Z-C>Yb zZIbjz@C%iLT6wZb1ABkT7l5tl2Ut#x!C}-$Sg;^Wke8r<#fI6M(P5E@y8CW~iuI>r zio`P58PDlN5d%sk1^N@oKH=r>*2G?(}Zxf$ZvX0u~vZ-G>AgW#$+_?fg|D~%YaDZH88H=aT)PR6K15s?R z>QroOO*x{T@@`qbN4N>yPVR|fckmSoPBElUd&EnHt^i+()+2 zE#V%uZ`2KHs{9E_ma@CU@-LSc5i&v&>=&$kiNLC<4LB+iZ9bo@rb z0nftgB*40M@WfSlV%Es5_(+Uk(!}J6wt=77KIn{~i1=3x5F-Jf89pSrG~MTH0+-1o zX;8PQuDFt!tU=8*{~Al z=uaQ0UA}FXAc`A}b7*3Cx%m-Yo@s^dQntxErnj_{`p3h;=Niau$@CO;P$tR(Qx9+W ziMBv48LB|LStlX({&%`Wus}9PlQ;#gEFauFm@~rN*n<1o6s5@DX!j(TrW49;yEsC? zhspn5eMqg{YRCiN9h-RP}^ zKl5aGOiHlU$jLXRoPMo1sqi2ACjt4$e?I`o`G8o{=qW!l$)}4!7=sXS>!-w?$&XxB z=avJL{6Ug*$phWL^c!~fR_7W?AX`Tp;)HkuSVNj+e+mYV?H#9YtYm=~=Z;$+K$-6tM;-DQI9enQV~Q_U=CE_^I@3SEH%{&e(v0Ul^7<3FlD`Iy*N_*m4W z0%cq^?4p|AKG)$f?O={T*t^`8VN`fp^J;wT$?cPa#i@q1X#ZW8MW8`8bvWA3>;M~u zuoItp*Lq=iubo^E{mGW}CpuAmoLqnwFBY|?IQ_{#j_JlfSpkE89Pm6qQ#r=e=hoD82Ty}S--Oq8`9C{C{lN^~7 z8|zOM1N)b;?I2yZ)ZBE8WW;oiKlIRoENzblxkopB4*q!C(Fq3yVTa8s2V2|<{N-K( zsPY|ulc=i?&rBO&Y6yGiOEwSSCW6ITSY~10MQDr)_>88D;$CFAQ)9Om?1W z5Gy^eiBuh;!pOALZ6}R5q@|VXgP2f-`eXX=6Cpq} z$Uq!TI^7*6bGU$hZQvRd-Xp~2iU+owXIzJYz@^X=lY`3-8i7(x%$A_QX`}B_r(cK1 ztwsE-xHr22F3lfy}+mD+Q6cFyK}*c!~Bw?l_1hI!Fzfm-?y*|6{+GLh_OD;VegU{8Da91mw+$9z8HZPS7~EsO`ly;u1GiYcbOiFz0|uD1)BOgH-%bLn9T z_C-PDa^37kB%8V;#QM`0hJO{b{B4GQ0H040AJQ@rl76@EJ272RJ8Z+NV>6Yc=u2{4 z*>AHxbyV3GlEfidw+QQ*g85xweD+J#9CcZ47s0JScL{CLErNw~KgId8oQKEd@FKq% z+8;k6T-|1tmDWT?2s298LZSo4WdmUHdU<)_g8u8h=?W2TZ&>o5to|(eoc0);M?XZ! z2E0T?p>Q&9V^5cX&fG2CHooKGEFX6y^q24@LJtxH&PGhdJR}g=n_q+e_9Wp`M)#sLNJOEG~apx&2WJP5ERbIX%wr|moBmw(bi!& zf6pxD_Btgjk6#p`Qbm)XvUD8YgqO@sm9DVK_BzQOuV?+&2@8t^Rf3zn(e{|W#RFn7nEsVtb9jf&)=?28$n#t#}6?NN55 z@Dtp`H*xaIzso6)q`M-7Affjlv9~3&wIM1Ha(po%;N9p3vS6 z`K@i4R!X*pfyiM|g+7SvNoM?@>`J=GGd(8L8|4yI^USPG%K$U|ne^`J>pR;qnN`iE z({@8<(tpW5f(gvE`9>la39gMAE-Y7r?)_d`;;Lj`!M-gH8OA+0Y8nowK)9cV+GH=# z6dU`%t2k(5S8~hjcuqcWGk~O;gT~6sL7VYl=r0=@klX?EkRRJMl063=^tvfH$f13n=eD?glxbl09iwUmP91;i~ekt5X(h&vz zBk9DQv9p*SM<5Rki^7^y;PiUzY|x}(aAbTms1mewY5f-&)-y9rZfGnm;q*6nOJ0m^ z5EbcZ685p!RYUtyc0RQ(Nk60V9|;HWdYXE*aYX;P!n%e;zDgh;6;286#3Be8?t1p} z2x%d~c*K}F_9sq>fhu{qHDf>X_!;VW8jr;y4X10m#z%q-uVI*Cca@sqx-MPc0XK7& zP+z)OTV&uZmf-nM5EzJERl56A9<6&m)zZTNupDN7YqX6&vcECV-~>ax=W!t|BO&R< zb^(~dXcs3opBs2+nrsXl>ahWRVJYl%+kF&?V2uzJ{Ws|^G4aw>i9=Bt*&KR3C5?Hj zC{rMAv2Wfo#9-9S*5D5FGJfiqUiR8aEB8Ft^-6rw3xfR37>!q$lg$W5V=C*&q`<4!2L+tEQ8 z!A;E!i@Q#9>8xh-&_7w2Z+}w)L6TuHl|%v4J@YU77Jkhx_Vb{(B~`Zq?`;^K_gRf)AR-WP}a;qu|Ge`aXJeOsQfWU!~>M2TT{T4$TP9!raky zb|Wr+swAToePA$UEh3w@ITehWB<}&v21s*;sjneq9zQ=MI;5om5bP)8zzYS z0LI9v_3>9DEDw^{IH>U;>1OJR(t9 zw}kyVcJVr`MmWVKoBG2U$un!6#*b&$W=2eYExrV^1%pDSi3lgsWdYsz{3h%F+j5Baof>X_M7Xt~Epsj-fI0*6 z86#|K{$;odhy`eNvL;s|SPT&u@&zfJC1;k28VMr-U|qNXZJGjA?wk_?=a_ktj5Agb z#P`5LQkUx|hXLYz64{Fx5ct_F(P`DkPrY2IDzIL1lHpfLM_`0fhDeZah+v2q^FXmO zopbhpg*xRo0{-^rdA-FJZ83eAdmGIEO`PLzUCP!1Wuu=mN}GnHHed6W71G8FwPw29$5;67g`qgA^foox`nndP7UeWup34h%u65gje^ zMR1dn**_v3hYdirjDW%y#6*Kf(wM`l^*PN^9h;#`NQ#_ZL1uCNq5m*R>8N{!*?^iE zyC+kN%ZC2k04sqE)`3z1Nh^tiTvG~Q#`=e4#|HDwAeAu-+VC?mk%vy}CP8(?Hy{WZ zc0LZCEn0M!n4Kd|)jG!XT&yBQ<7JLGy-JR(oS!Z{VUc*WA-jjX2t(^-yiuS%0cI3q z6jC=As1!(VJDuyc;~@lG3~GP<#XgK{;x4EUAy1E7Hkt#}uM!n_NHGTHJ*sL>gBbjH zQ{Ay-K98M7i*lwC-Gh>xTNkt@kuI#`Iq$ww$He0&Q`Car(sM1*o})ci8}~&c&`Hi$ zrezH-WXT_DtXXmB3J+${;<0Y??zCCa>y4ak@Xrku*oy zwOqQQrklM2v*r!dJtz*yMVWA&of<}99WtzlOzka?JI%Gg_kd zi!z~_IE0J^O~kX#Uo6L{AXa7Rtk?zar+E|Zz@3!ZCkfo~(yg-$7HofyUW6DJn|!kd zltkAh`%Dcp&v^_o+@j8qu9L-kdnk)dJ|z8lU2WnkA{-*TXY@l2u34~Y&u`$oT!q3K zYt=4!cXV!II%;idy1TP>_>>_j3_4E9ERu=#69UUT>7X@7#KkJ~bk4d80p?St)l)zD zo-#tXe$R-+5bz)qF$5I|#VD}byfQs+=IjxHay-& z`yXixLl4r`CU`@;&Hdgh-VzZ^ATxQMqq9;@A}BC?e`Up?;OXFj(RrQiV2RT(Q=RYJ zZrXdc?W>E3^VGvSLOr8#=1aaoZYvuRZZyx&CH2SJg1}&hYAfX2N*|AH;Zi<$-{11p zRfQa)Bl26;ii(ArX#u4Unm|OTZBovXHIeY4P7N?siR79yDXsQIkmy~ zmb6x2*T;5ZWuZhIoNO2^2p?w<%`Kw-v;cfLaPfVOVHN0Oo_@t>B|zgRst{BqLcB ztkZ*QyODjf1I8?qzLm-h?I@Ex4W{FVHeOky{k`{>vD=4R2RACswnV3dx-*eZ$yS~K z?kO1e^$)Jh8s6~Yz4nSX(82>FmhY2JR==7ux=ZWQ$LP*HXzWh0MvPPs_0{Yf4Qctx zpxuzYp#^{H&P-Q2eBhZ4aYUdK2=#|85KVE@l^^~|e6wj6Tr_j-cx*jOxW1U5eZ%EZ zcwG8aecaM84C^`*p<0<9up5v{i}n&C!ZO7c0=40#ox1=Cg~hS(1&uWKvO;Bja6lt#}nZFgCt}60e2!KER;^|k+bEjKUh*BYCrAtW0FY#)X z#*!>yX#Q-otk{daeY>J@DeCSVU~}d$ePONw!G&S&wcLQ4MKA4V=65c z2%wIQ`6KXMbvi?YUZG`lZ31-q+Dr)XLxD=5=v&4^+~+gX^K-cp zWDR$Mx+~DJZZL)?8wevP^;gNoRV|v@i-tqeum$k$SKk=#2I39pKi@*nJMu^1ISBFc zKm4VWJe)u>q={taG&t04ByK$#c_wAIvzS#M;5+Bg%;S++c%)=1K~CRybE&IXE9@9l zuW4f)9Y}~E#e2XF22?2h>bLD;JuZ{op4LgDHE+GjqwTIF+@&~f4B7YL$VROxt5=ES|pvjk6{bJbMsBSFsZapXnzRX`*-!m zMG9f{&!%%^PY;C8K5|g1>yp&6M6jS;%*+10GA_$Q9zR9cWb1r3QoU(+K7FUX;(5su zT^>izCvWpNCpF@qI6qw{DA&;@b~u_yr1EhtTnBLd871Bl0Dc%4y)~vYM1Of^Mym~G z_5ilq7(h5cSRa*ANM$md@21+aB*s(#1>|Xi6(Z33I0EWmj6HL`KsgUkJ`KNrqn&9Y*yq*l|diIQW+ef<}6o0*`PZ@sa8(0 zKRdBwzXhK?a0jQ%J`-bxt0>R7a%#&yD^szdO&&kgqZ3`_n^Iczr=A>7%3hd@SFGIB zOddZt;NH5Mj%^;l({cf*h2KUH@hISN?tg8yo%+ZA8NlAkN~Z4Sg5z}wtWp&F$#nUq zu|TC>NwYBZR3$uatL&3k2YsLO4Z!8VE!n-rJ7~NlTD2!yTIrb0Cpbo7qI4p@q0+8+(eUsMl z%mJL#FEAzxtPbDr#5gZmC|cMY zM*Z;ZW2ap#D_t0jb$Ag@6Fx*&ebZF_xW|()P>gF`)~ytkiezVO zZIydtAl3?(1Z&X9AI|?e%;RzAXm@Wfi2O{MOrLOVtWE^DDRo%*&`fRFhu3wC3uoz& zNaYWSyBw*XSX(E{t;rCcU-;Om~FQV2C;_$VJiZkrPGJHN?7~O6SIUjFhTcbyox*nNZh2L^gf0~R1 zqHB{EXM49r%#mvL55j@W@QF_HdK(!QIye6TxL86{V|CrLK4vUwIu)ujW&DV&{KZtG zyv*}m7%eZirKfc>(U+)r@rHkIHn`B=3EhtOuksqh4HC5z$4g$lHxaM)R*T>iH_4|| zto&(%-0^_hM}>yt|Mmhn9tr`UcSSOujZ{Z4Ag~IF`g5QB2%OcB7U3;3F$mD$`dqmsji#yiqaTcyVA!phPoWl{{uWLwI zD=Zh3-|DB3Aij=mB%_f@uTUP&{bl5Wdhn(h_II4Leb9w_1`Lw zUOZCNv;@i8IbJy<2~tH!e12zc6Wj7-n$}nJ+kG8Pk~JxLZIh*w*~%1WvxClw$~yCj zUvAH}Ms;rv!B`@6b)1T}$3)6(MY17Y=DApu;mnjF=;`n?%nKgLm@P2Lscf^HWD9uIxwsW1=s_L{0cnK)-^v@hj$lGtZB8h9IiCKh5xYBlo%Fw=YVU zMI9YaRL>Qbm8iEok+2_QbUvToT5k^1_iwYc33)$fzDA3A9w=G?yj;WA`;)c}<@&!G z5&I3NrO^y_hlF7q8=--lVSL`Wkf8Zke?(l4p+Am^3xz17c{{7+v$LT=%FL0Az_skl ztI#ts9FAXn@BU653f7cE!9rXwfz19xzfHxS2fVQPa*j*ow+2}0*g1N~Y(5QN(Z{~6 z)9qhKBy@=}cNTxAnjIG=H(#(2>7J~WtHfO7s!m6xjf-MO7~5mrqNMYAVqAI2$-Gaf zp5aJcY&0aF*NNqDyh~HMOB#zh>Q;D6bxL5uaSIp$emh1E3#H6=G%^T>Z*c6#zUZ`4 zz^Sa5qAd6nV%c7+=+Y+sz|^73W|@Xki+{C@fm(@qty9nQn-WhxDf=Gsm_#|B@1^gb z7FdEL%6L2bo<+M6pP@BwrC;3#Ag(DxG`qV8bKSIX<H0CZ5U6)9DaP)s1P}al)MQ3t}zKU^NnsW@l&&+^ATe; z`|NI60#PL3wQ_24QAG?q>puhu;7W<;$8nV>g$%dK{PH%Vk>pNwvEGnv$%NLoX-J_F z?{%SG?d-0lNpd30ev!7I9$hD_^W2BL0c7vT9x^AB@xoSa|nzIOfVV<~H z7%-sTsa&l}l8I6@vOhPKR4R%?C>4zJgV8CCa_(V{9;?kpEt~Rcrii|DC)l5d)LG+R zOY~~J7_GM^xqz_2E1RMg_xIEBUaoA!gZxX&lHX!sL^wnyIOR6 z${8O5di`M<$ma(wqmF8wVpaQ&J295`Ydn?XSEa#({!WY_d@O*&I|9Z6vee4NJK}WA z&~7jsnFx@ZuOunggcjIfi8BixXy*(2v#!N5JRcBl)cocK1iOXml%7W3ZuQCO2?DEO zEq4W%kh23xMD=%jq^Au_jBavcHI@~6Qd&%J0{UB|>nm8)?Dl!!Q`Wxt_wj^bEjBNu za6AQ+al7RHr`v;?;Z9Mj*)88BZsN16E4(>yHW+0( zE;tBJW*IxhP^*UE;T$weRH*}TqbB_Ync?W+ULut9Ycm%9vqdvB<~NBsMd9bCa?}r4 zg>+#er*cI6%H*Rp*LG^99@-r_-33mcugEKI!K3a1#~7T8bqWv#I6(tH3@n(}8#kPr zS`VddxP*(cY%`dy>YE|W^6yP&y7EY0B`_U9CRio3D#K4B5EeyPPI^)Uzdw$r9heqz zOTAhUqy0lhXd;0=;yBNE#Y@EJ*>F>}dA6svqRrGmJ}^NjMMcxKDX^Bnh~=4O-niO^ ztveC(i|a>$yy%4lo8=K#5vtoh(A-|DIQIj;MgKa>gD@<{EgE%x&BD(2a!yuf>8LQg zDPyMEKNw;$Te~Azx!LYFT*WjA#c^&?Pu5$k_2oZ^;YukA`qu+GY>bZf3l;lE1M3NpN`6F7I6{ByV=_oz6*Mop1a|Cq zWWzQBc}bCVBYqiorLHr4v251q5BEe%>gud_-NMc|cZU_fzG^_N)W6VAUk#ILpV6>x zMai4Iq1sYWjI*VxcB@_L*&31T;*;|_GR*F*w(f7Ja)B9Ff@DLx&GY*qCY=qtTj%$G9jS4Mz-_8UN4EzsEGh5(#kp=$yBH1>LJYG{I1_m0exOOH^OK=EiOhT(x!ZHZ@y2{_yE79e8uIPdWG)FlGf) zTRYHGpV17*7dbw4)O~Vgjk|svy!)*l8bOrJJsiBG1E7r)quUNHO}eeQby2)#cB?U` zqn(1>%Z&w%B9RDFf;bad7rU8G_pkH;SB296tpoPTk)(A(-$VgcV5h~EQjjIVVkwN_ zP5m}ee?YhBUf^&tk*w-9kh*h+V(KC^l2Q{Cfh z=4+kh+7~_ht`@r3-b`D7eqPs}x)Wx)dQK^B4leloFJ29%jI#JW;DM{Tu>SCVr&-;a}kERqhRBtQL^O} z6_~2>44M^~rso#Tra+DyqMnc{7tu#N*D0FbF9)}SHku_+MBVQzHjdFj3gtrng{M-S z(gxnBvR~)xqF@GFl!Rf=OJx-#NzlooOs0T3R9C77YML@ zdGD`i!!x`+WPp816PxP6UE}V!pBIbpu7dTx4DnAm0_mQ#a>^NHI7A-LsT0Bw}j7O;u&8v(Rl~O7icFLi5 z_EV`C-Z9cvEV8f_@V12u`V<(a03$p@A6I;_8U4SONHq+|;+3iBzIUNK@_kF>+S&CV}Kprc-VKU^Ad?iBirFkI2*4sjc+i)xX#PHA>dQk z<~}e;aM9>O{YMWk?gy(>J~Sp7k3;Ht{IQ^#9t?<8{z9>pL}?cBIN!^jh5ddT>fY|* zE8;4}qC!THgFRbcSBl@KAw zh{|x4@2j_QcoomfD6@83AB;znYeok?U&ZI{(@dC4dDz+~B4AdOj7?HLbxUd5%FfRI zr&jYi^E#W;G!n_wNt>8tW6mBIR2~$B>^CX-4-rF|jn<8D)4dvW;}8uQQrBkDC~)q` zpk87xYNoqM_S=U3{FIFk-%im1s$ZZ8gu6#YJEgqdtsh*V#xRh3miOiR65+I7vRa66 z)W3T!4NwKn?rR#pbM$yw)^d5wMKZpP>%`T@s~fiCy2L`6V-4Rzw+YkhlR5RBEm*o} zsYF*S-K~2#vQCOLdM@u({4~r{j~r<*YvU5;?J#B@KBzY!39qzmtVOHhLLf>znhL}a z*ZgNb>Dq~OT{X4|rR}yT>ZTJI?Qg2v4LZhL{w+E4IA^~?jcHmh&cKTh`I0Gf0>fzv z>?gCS;!C1?-GGA3c-@=H__~ERg_p{gx-*ZZj+qL$+LmKmGKfcFVHZZGYO>Q=s1;bEv&do&v9^Y?hk&adQc~{ z(DqhKqSK)rPojx`xjP!4VBNAD*2;VR^K&wR*cdmLjH_!jsvCznj1;WD9}Yku^t~N5 zectKI+mX5Sl+)Pm`4^insP0g6ORc+Z*w zWX~%^L;1)lqu;OLkyWX_n-+&KE&Jb2T0X4R+%Mqj?n7T@e;$df7~N(u{*n^sWOalz z&P7>m+}lIXh=M1^Qonbteu&s$`n2D}I61XW^z!-gsym`6KBnXGIF|d)fn;qnH`0GOl@}Z@5P2Oy4IKw6L7fnbEidPjN7>T=Y<@R^qahXbpq~AC2!v`)G#ZX!SY! z(#ou8(})aR6V1L7V)iU1$(tf0j1)%UzZ1l(YVpst+H#>pXJ##Cr=a#-#%C9p&v8e3 z(w)`0tpr=iKXc6*=G(bTvOu-cOmT#xR>$L%b91ymyB7wvL0O7jI@HwnZ>P_nmoyb=T7b|+B{}e z<99cmmX{vho8VJVT)S+^;tbIUit)*}2b$WHFVir10t%;{7(H|G50n4~j1WjMp_<#n z1-B?fSUsCzfO-PMnM(OL>36kal70o3E#mO24$-0YkC<~7L7DU%e9`W>y^M81TpT6I z?A83tBZ*(nRkJ)zcIzamw$r_J!|Wy!Z`6&n*qrK%a?#dF>j29}QwE}Tg>ZQq+)8zh zlxn?A*oER*M~4Kg5%#PoFngnyI@lLlouop~tRo}tjq$}h2h6?}O_g8bE=yBKp#ZZJr8ES9!u6v5IveiVF|RHIY5qFt+v%$xIWI09s@<- zB2dxsYE0Z!9gp_hC$Q_w6BX6R?g{HvsmVd0&Ib9E*A*joj&5Vx z8(s3na1`_JT)}8V%h{PZwnoz&rZZ(VhUvWSlC`23^W5v%ARg`@&qztPDUXBgy(koR zL!a1VZRKW z4tfk%tkleIB~zAAOZ%A$XIOXGZ%MGGyS5E1q*$n=n@mLAof=8+$Lea8WbTeUUoBm> z>X!N0#xypfasmU2AwfJFru7QqAYO8fk+ToIaCNRtcwYBaF5`N`xO9;}5x%cDL^q&= zgBqrQ4Q`1vxUZ|bvqe(2U_@VAo(l)rc*ZZLzM3S~$|ThNOF0;xU>z>G)l-==;2qf$ zdrIs8OU&7Ou9MwPewp!GrcIkwmoiwdHazdr4uRyr^ac4pn^qg<+S7%~M%eRZmc0gb z&qG^dbLM>=#y9dS-Ul#@Zbw=RWf6GVji>E38l&KCN=db~0TYkoGf|G6kM$Ny&f-@M zokr2k-D*Y0jQpuduREJb&KEcAz$2y}a+7LlwdOf;Ow!dnUct9P$1+T&-hV-C3??x7 z?6{%%QV8*~6W$KqGUXxH5{}KE!03*8Pgtb8VoZj>JQB3t()kpUM>FHJ7 za@LC$FJs>s4TfOZrH4oIMWb2Hf&eCdLR|o}g%N<4GmXzRgb%@Ar$4KBF_vH)+Dm36 zIQAr%RUR``betkn9hjPDHO%Auv7cfVjY^2lpib6@SHv0T*!yG1AyO-$+ z7i~17;k&fwb=L8<$fLC!I;p>2dB>JZ+sBrn@)rpBSqo+av|hsz-Ph=EmgI3Wcyd8& zioUWt?||+rN&wmeFAp7eHPtZRZ~U^dJ>#btyE( zZPw=l4KDoY5F{A>%McllF6?*!(rQMU6+_WqP7abOz@Qyyx(@2IR!6v9NcvIUWe4pG zcKotw!Q^AW+HL90^0m*51>oxPjwdS@GG&Eq{=yiX|FaA?hPZB`udLl8>>96$)4Fwt z1D<0R?ZU(N!ZiVvJ^0jOb&^xuS2%9r7S+rf(Vmm!nk7@P%%a~_eF>&kYg|!CIfy`5 zumRgHf_+bj07(pN2*q#as-n-%yb$EbwiY>g)bFPu2frRht@QK__>q1eZQ}3Z6exl`ziAt1zmIQ-{gMw@LQ7He)NBy8#1q>15{Lt|U$d z6ZF)=plHVASnD$W&vY<5HGkT#n$j&BkB>T!zc+<9;ced32u?h%Xs8F`xj>h~MKYtg zMX7YRPyZ};yXvmMVv!)!+C(NX76U`}3l+@i6-|RiG zYV)Rhc_zTt3}67)z9J`zYb4{DM_uH|BZ&WsN28~S3RlAoj|vCWxL-!Kp0@)^_7Pt7 zN1FGdA??|l-LPj_D?caJL*MN)$U5_hUjfi%c! zXJg5D>U=;36kvdBywVmG%9m8#%+-=}vX;6vgV$T8)$m?aW2vY)?%Cv8c_xcg=eS{u zR{RdFmy^jU-kc?pD_!Ur5cGW(;?aQ9vOLcTKQ>bWD8y{0QE&fmSp(P!$7#;YI3$vOtjnvSKFuYZm#yAnWu8c)qHKOp2L z$(NDUY`3ci+dhz@a~yeSRd>~GbX!-#nU@aEQ~b1gQt6mC#=rA899LM+EkflxeUJI$ z$*DC%P@2?beik}$`v4SeeWt8FbH(D3{49gFKd9fw9U_97m%~ZaZ5}$dulOx z#>kKI&@`k0coCCXYJ+w54Dn)-X-0c`VaaY&op$z&F(X>Z#zO5l&l6Ylg`={nns%6- z@RU}C_(GK9Aipaol&gxEchVxQ?V=>Vk^0_AeICWk3D;@E4q(sem9fMWt2{UCHq9@% z3OYC)EiC9huhxuyv@dFE6?{*Q%`{MX(NJW^t;{|<4DF<&KHhjZ=p?n2HpKiAE1hnq zl}yZS+U&fUhQ5?QTc;H&PIf(%kL$hTVdrYV6q2!QscN*7Tp@v29i)?INkA*q(DNpa z2C>>zC&6VCmh|}29#e>deCXlh6}xeBrn8o*qGOX@-8p~wXLH4PJj}8!38D|HlO@?= z1r1}cT5(7{tM?McYPZtrHrwGV=%MM?Rn5*tW58}H#EM@v*JfLd<#b)2R9UXh7JVac z;Af*6Ivwf>ThN2IWjr%IHo}a^N&RivHD3z^>_EWlr;z$6g&RM<*~3H9q(94U+oowX zEsWNglU9?Hq}*20DOP#cB4g#lu+soP{?fpVcIJ@VJ@+on0R)ZR{C6Yuwea^63+lF< z(mOHiv$n>G7Hcck+0ZlhmLEdt2W8U(ZWeeaa-!2h9tJZ_v!W~Hg5C)h6XEx@rv#Be zQd-GmEZ#(Pr!Q7*aVRH9(erZhIlom9gCmZa3`KKOni-Es$%&vQ6{1*<_~t>rWsRzW z)mZO=w<|;u(6!$)zD>Gx8%QKk*Cu!DlXfxXb$4&En4R1N!C{}XPq{_m+6^Ezb-IRA zaUk{Jlm0#RA!$H?r4V63^ZDqIfagA@d)N69zWY>i&X%iaj1AC$0Yhz(m7Rqi>sGT5U?B^ zdd3LCN43pb`@gt)=cr2C_kB3mOtx*?c9Stp_Efv6o$V&uwrjF&+cnv?-Td}E&*xd| z{l0(hwb#1u`@*T?#6h5(MF9~iLdH@F7cxdeVvzKxCO8t*H6Z+CIR}dr$YVGN<(gC+ zDxHTKW1nd1!l1lMoT{4(@P%y(HFuU{GNnz^=UegD`fQL&y-C9RaKSD_4c~EYRm5V@^p!!V@QYL!^>bQKEuL5+4|JF;X8GJUj2Sn-SuXf ze$N1ODJ7%{+KUFLt$tky$`k$UIT?kCF28JhTNdd(m{BclfOgzVey7Wxz?S@aU8$*;A`c?B}y{6-_1usFYShSfcu@p{fe#;(xWzFZ;}^Ya2r8`Ja5El}}Z96Bg?I zYK@e!;ODzH&OIAUp8Gk*y#u)n=DKl6o0JSdyeUmM)+^s?+le$w=cXrY|J4EY&$hx z9cxoHPmuxn+cOdC71+;3RX$4bY4CzfAC_hc!-&0ZVU^Q|IS>K=f4mESKsP|}4tlp1cYZMEuZCCl>5VO+Y zDGP0}+{~a6<>is$2p?5j<2Ul>0iKrPKh}rb4v@QaXz^n7@p}>x$eZXB5KyDnMqkPk zB&8l-Md$2d2Hd`mI1!RD@9;5Ck~8nf*hG>G?<{&&HYGJNKAS9P6-TNITLj?we`|el zmpd#>3Vy)%3e`SRtH)+_6XpJv?Qbn-H{VfVH;;a&V~L-}*CiBvBZ}^|sr~Ns{337? zRvRnrZivM(qo~_7=(NmJHP+8-x9f|L`U{C%Hb{yR&Oo5b*!e@; zJcx5sc<6w6qsQzE=`=Z?<{Fs6GIY*CwKvJG9g#wh;L~Senx1g9^)s>DeRO(_Bg?6} z=muV;l}+dQr7T({x4h-{=kZ_a&2nA?1?s9AXGtPM`0IQ1xB!}2ohg5sn_WIW?4|w+ zkhw2btK2VfB5BC;Q~&g&PcV;!P6IhghLUMM156@h+Y|Hkkju<4Yy86n2kx3qF`)QXYdYL(M3r zAg#S8y(T-vxu37Q*R=R-Xfc>qwHo%4zup}6aN2y~ks(ds_^-7#K7w;vRdFtF7Zb#r zlL>dv^UNf&K#j+~mu`^>@0_oXZKBkk{ZwHp`{Q{%sr^XpF1Nu`SK3?8JRz`X(xxM- zy@dWGgl9H1f072B!wG@#S+uR;^jm8VWu>^@pQM$_W1Xpdfnz(O_wbiI`2q*M$EqUu zG?{QdTD3z-_x`=5T*a!fhFM!eAZpt*HZ)%9^-kEbh~?S}7Bi_np|OQmd*&W-G0*9O zheDgIqpb3yRA@gl@HvyK{*F#(&{|mdIke%=4%+I4Z>Civ0ltzSby!QUKkAiR_BQp9 zOO5X*`j}DvNk*nS`h2z~mNuUO#zwmpvDIg-shairSBXPZkdXZmI$3qRhu>Id42M~W zZjM0eH^>TuM9z%r%{Z+Qi|B%GR4J(7s8=bLOxKaaS2x-<);aPoYVa&*8suEpbSpqT z5n5WxXqt_|BE8v3<2m^?#}oaaGq>xma|7~*78~=T7QIC^4uQvM?)j4?p7Xva}m9M}^l-%CT$0lypYY{ZOw*Oc#J zFjq8dgp!a32T8i>Ns1Y7%nf@~Owc08JtO48~TA zML@`y`Ue$6JhtCUF3#y?R(%=_#ZFqY5Vg%$Wh1i^0)ej*P?dJ=wo~h7T~DR!&M!@8 zjp;UZ8->YZnY~P08mo@i*MYxcqhUB`FXr%;6a^323r!cI64)pc`xtQwZj8b_#fzch z_w;#*b*sDvV6o1P&eOn{-M4RnliO&$jjNLup72sUT~MqB^(c;pH13sS1hgiFuNL`*&@^P zlck$r;5&zFG}*1@?J+PA_0Zg(!-AB@;HB}t=Z1B`Kp9M~tmhdujQhSG0L?Sm&6cg1 z-TfwnPC{x0Ow+DFg%iux<$ zXO#xJhUrP`R(0PP8qTrKXeBF?K7|KVMGP2=E`PeqG(La|d}MJX<1Q)v?86|##>Mlnu2IThYjwZbcH62#Z-EI`pashH zz&C{?47#&>>N~O_=VGxXj!AKrPc~c`EC(wEID!x2X@Qj{^$Mck`U=e1e&ZB-Ly*%9 zS)G={nnjY5=l%WqiVD|N;X5jvZ(|}@WhJu3ba(z6rFiS?3&#hk#V?ONnQ^CiKJFxW ztC-7h)3I|Q#?6U#|b`T8zE;?bJ#?e%%FjDQOY)6I@6x zyV~lC5;(e>0TPERpn2{Oh|^jjr-H{Yo$_}r*yRoCkJJesU4CV&F8^hY=LykRA-E}1 zPd?={dpwgFiy#m-lp+FkSKjma4ZzX2i#_`DARn&ELO-GinM>lD~Q6-|cMi&At;geAf%5i^zUC#FsOvF8qN)$j6(=%640!86YO^fh^?=GE(Z_8={ zTJ_46#COa%_u(@Sa&@cZ+vq4&%`bGX7foHjOP{IN_D=RGzV#@tjhdZ!O#uWzg>x6d z3BqV!OK18BIIcJYLn>0zDhg{;un*K(s7Y5v=+8#zT3 zJtmZBu=xauhhGZ`O!04$i6jJPJV#>Vao?z#$wdIA1#(Mei@%G;m>ScWpF)An*V_24 zClKiyGbU=3GEN{mRuT0q4Obd%&7IyaDs)?AMs;Y{+rF1DuC(Z8e51*ak!al)OF{?q zPUUzdl6^ISvE(hXGbBn_JDoc(FL@de4U&MI`DR}7CaGiZ$58)o ztTveD*98l>y5=%aRQM3rkHk~rV^2S*`ddDdm4)%`HbS=Dp+1SsLY+KIe4o9gB^{zb z7;*b~GE?XNxbD2JG+Af)=T;c#{z#RcZ?X}woQ5C=r;6Edr5;duBN0ZK_^HOYH9*4# z1Jv+rKH>{CNJNXwvOc7>*n!Wzl1ZPuI{gq1+)(6S-54UUY$IZrQ_ZvlPjk*QY=Rm% z3)jbWvNVN)@JQVLiF)ciJWXj}#(B0~Zr1w#u?K)g9nyMn&;&{*;6YW;2f_E5U$ zv&43~Q9p_`o?iY z_M@zgE~89D`BeI1QFh=5tMu~26wmJ>W)Q)k#y7+|Q{Gu}QS3740%HtBO%7LaJSbO( zO9B`5?0+?=oivytRT28zY$75H>CYRMXn)wA>a_^kG4&K^P40$}bP0*vRtfriA<#R_q0L>*rT}6(+*8Ugl$>%mTlM3i0lc zs)??5%{IqkZn!~8o(ck7&|y+I#O)`!D`*x@&6FUy!U!krAtG+YcL}N*SImK!*BE%c ztT=f|62caIw(*L)@jfLu)@yS%gJ2ozib?X!Q)Pl2ijdPB@@NqvIVLzy1OiU1S-g9Z zA<-5ZIsO7kk7@f!Q5AK5M5h-2=4 zt3My6PpoAt3wG1eZhQ2&0={N7mC*{zgZ>j&c*(~nLtPiQv<)3rk;w$O;&94mdJ z8O-893F7cfV{GetxojC)T`)=E{>756!>AWaUP4n;eA*pY$!PEwKW|c-XSUb z%|!^x4Jljk2Jd9TjGXQHs3WbX3d>rl%lbsqO4_M)y@z$n!nX~_c%W|EtUFi53=?|o zni{Tz-DCXjS_21I_@karN$txJerzRM;Fc|PHCnGmpL@sQVmLCgV!Dx@D%bd?i}0$^ zrI*!;{_AkBynt&XMigoCfMH=UTZ>{0&gQ>j?^r#J^@sySOTzZaEzf z39r$_e-b3V5OWR;MvWPGM~N1bx?As*SkgAg-6%3h0M{gAIhKw^`RwlvTo0#&M56Mj zZ(s`h$p=Mfk)Hs=!U27<2WJZD6r9)l=~uR$8V4NFx5O5Evk_B`Rc_D_|8sxhXW!%1 z6t7)5gF2IFzF)qJWt_uS9u1UO+{@rA6JnvJ}-Rw^7gSRHex>xJgnQQF0BLhRM3TbIU`m8mA_h;Kn( zU$`4<{jlEYqZRSKeyDfqj62D+(O8`&`xdh_ScV~B6dj4TzOk1GKMu$3c=Ix!={1eI zAB?m+wq;sP>U*r-tvffIKQ3ux3u2Gd8nx1C7??aU_R-^%+Jn*=fJ6?u$Tz-dPqBpE z3{RE{lUdTAlYu+-yeH86Zn2f{3{ZP_s_EpbUQ3$*OPjWdMSUNCU`+f(&w|T{SV5oJ z=vU{)q~vR8;GAK$b*TPl1|_4G5I*I!JaWnUh0yF<{B`=n68s}=*0#j!^p(r{$d|CD zAMe^a!JupZ+f3lTl*`8ET9D3nd?cG)ew}29UfZWONcciq% zT9qJIhBQ9Lm2kESHx-vXSg&bGcP~QIMhUspG*C$9xI?3JC@JJt0i1V?mDZkDYtlG` zRmjA;mtHR6KM6^>qgj&W|AssJvyut>FqZg!$!-sIDYvNf^q_q*Uw+Sl$Sq^Z&rwW4 zM|IRD(;ypG!BSgSTF7p_iLXPbSobbhsLEnzZFO3S23M@@GqN+KzwzNvB+kZx9}Ewk zpW2b$#k__D20}s4W(j&Wg5_fBdh7T%%jcCa`s9@rOc(9VU;B%!mPt->%lzuFpPibk zbSs`!B3xCd4OOI^GVI_-nLXolSNvXghQNzsb+5zLX+*s`HtO&_mR6MyIZl_Y&C@#$ zHyYplU{}rtJW?5TX*MO;3knT&e+3IUpa94~koGS5z(%s?ck0rMX3sHDP(i>i4`bbAHJ?bSV-pbSJ2KSusR_&>wU*xlm^ZNDb zbCT~)MEj?At(`K(Q8egx1<=50XoXBr;tMdkVDqQ(phOE?9PUBj4r&vd+(3=sE{0GC3&uRoDxAcB`Hy79KjPJQsv+V}0thjE9KdqyJPN3Y{O@TP<2z zUTR+;?epDX)+rbq|E@$lXX$lB^)IclFfuX5TyzM~T-V`)JJI0S;3 z%oD%k_?i2+lZ2ZOjG(&T2{_3?jF1|rE9DTQ@6oStofiavmlTrM_<3uycOOVyc6JstUsSx?)wYfN|dHJYOXz+Z0e?F}t|a;IUqG zf00tAXW-1Yf0?V(M$CdcXdqsNlwqBUfugrElc!+d9b~%A;xi>^^{VGm6LqY%FQ|)P zV};XBz5BjPM&4f36JJ8y6UWq@X#4g%*T4A~YW6mv3V)W#%8S+?1Ciczr1}O)i=$l6 zMBGwi)%FtRlwj@q97WG$Os&zc6qn+stwF!Y+KcmKN%78|zrLjyZWNY#B@-yUsUc13wfQxci5F)+CGM-lIePyf0<$%H>Y1UXJhArRQ z4vI3q_n;CZ$h6))HZ;px(|K1ve(%{G0 z1Ud5xUTj#yrnegADx`BS75zvxOiqI9b#Tj;UN2k#IWcH{*AigfeI~29!4={^DQlIU zze0BTJ<4G1&{8Zq2}B1%ik9WDUH#e#N&n)eB5~vQ$(xfzh=U}HgC=Xf>Qo`lKbZ2; z2>?HK4g#;(A7drwJZW*4d-W8jxW`_=eK>lS0Xu$TG%(6AhHk!SISW6)-9S@Chmpgf zW^)kT_a2pXd9Z|JoRp4H$%IeJPw}}W{cY!ygbPQ?3IROlmIh6iJDgs9bo|GE-i7&Z zLX~2JTm#p=mrWa=KVE@h2?%NhRw-n@ZF_qN>?h7ze1QF6x*4Eja>m*`&*+2`G&*-m z5yp^QVETs$xC}|StK}WC#I4BldyaiOikQHO3bO&?@xnr7|Z zMV>26i5R>RY#5i^-`nmePc~GS0sbi{KK^zWp)VGNWw+$f93KbLVqQXVD~2wSvhWJ^ z(dc4SX?iR0YfTdK-yNE5;*rj`7zbH_D~^Kk?kT2T^x}O?~^OV*WFK+x}~L^QMW&#S|}5UBBvV<#4$Mv zC6p7EKD&8e_0IUAAP{95E5i*{0>I*>Sg%Mc)OK-`@{HCyT$Y3QleJ)pD~cxKi3f=+ zG8=+h^~HF?`awA2$vOVn0(`Ck7UF1fo}VcS!NjYs`^-@!S!I5iW3`>iQ{iK8V&Bsu zZVt0ME~3>*QzvH`@HT>XvBuEPY1pbs+^kJA#qn3ggsRNFg$wG-oS-^?2#HXcsLdTn- z(Qppq-XzFN9cC%R3J^@*6&nuT6G#_ANwuYE$6nxfuZ&2H0h-3 zmeycN{czz}=LhvmC+EsAdfQ9@k#|^xrmYjLN@8=Ks2kj60p>pQ=ipiU+lm|)*>nt; z$%cLWVsYuV?@B_h4PybWbpFwHWA{l zE;M){EkuM;RK(DfBh_(0-i+Im^{`zNq?aLSJ`5x;w2Rl5`t$w4*SjqA4!ZLdmC?;- ze(kBd)WwNpMKSU1?c$f`ih~gVl=}H|h20+dlAErYL4n;m-bwq5r<^0Ff)|n(XzywY z?}j&3mly4I(Y0BB6w-ese_vK@$sylRB@_jT1*pCNz3GAdCQq1CVg8SZ-Mq?>N>Kev z`+b^#m}Qst7{;&IP1sT5Tn2McsRz1r$b-%;8DZIi$)`aFyZ!%^P`)dDBYfLPV%^5osy zT#LB#BFE*P$8~dUKBz5p zUgYkyF!#RYZ~TIV@aHM1X=VFWaOOhWIh~RBa%jL6x$t7`CEH|In3ArQ%`{Vufjv zL4m}_a`27ahRu;XKG*yl0)GDhoTn=WX9OPI2w*SvQ;-)42|ot2YST}dyG6-`oAPN- z!go-u{eTrkf(cy4QLKGgh!*{%4;Lx_tIbeTelsx|_9F6Rj6}zDwAM(*)HHhA)2Lv7 zcCi2b=7c6UNBK#0Tf0OSMS_!yFyl7vr;Q)lzAkER9TElwn!Q~VzvO3V7Us4uAu4KO z&?;Oc!$>0rkPv1r!R^uT=;PMGuD9xfxS|>J_D#E4$*;;s(D~m6WD?04dHJCela1Pv z%n_D<+?!{@y<8=dM)1F9)p?4G)r{U92Mz;Ts{zVR_k!wD|3-O(nBdJ=z5HbK?eSp3 z{>3lB)WXaJ(e=IYmewI}!)=niU3C6S4-WWMQfhyR6~RN)?eH@cTbSaUx)=;27yNXuHorhdH+Mz4X`62ZcMZ?nUA- zJJ*MwBK_@$o8ER?4xg=;93t}aGz6rX0H!_jMzg>bK3aiSN)BtH=1nB`fm2|YNz~#6 zd-(mC<+DUGl9p&q8=jvtk$khlnEe$0r9dBb--gF!g*q<#n!OQ-fUg$R7?Z1&=wtO0 zIqcGCd5f*(B{C2K)*`n6fHga!85XF04R#KK$2!b6CH|WQ045-<0wMEht+~^EWZ(IL zyVKO%`?ZbB_R#*dnESmD0})hq%Drxg?RnBQUf;0t6M7D~UG8RIO|Hi3Rl3Tc&W28; z4@L4t`gv#~VCFT~p{wUd{T|kIOYYiFdpV~#Qq+`wxP-$>0q|=CHeDh@obN^wluXfT zUvT{-#8R_LMN^M%DemvOT?;JknYjjj4KKxUjUQ;?QC8-Esl-7%_{yTBK2kR<48hpX zKFnE4nQfkmQPq148p)}}MJWl+|E=0Pf+GQ;gN2Kg2QQa+x*A9oL5w#(`7)5gjd(X| zap`+YoCYAI1S(48WcFI3SfdJU`^~<*l!Pmfz=tIxK$JymnBuYUcoU}Wxzr+vp}V^b z`jgPEcpJ@DRROKA1p*3_2QO|46Kd*%;&K&CRoI&Iz~uqpz@Y5JZ(+anRvi6wQ;bM^ zg)?8mtK{zGF(1}{h`XpKA&NJOGN(D!S}&8-ZG+$Yz4k83(Re(41bwNrF^8OdL7bXh3=elNal3WL+FZZYT+2=hA*kLm zuMDqwHQMtqm2tjirSq0WR%ekAuEHfC($MRI@4P!G$~UesohP%;Tz#l!($K*Sn1}a@ zUCPhm!i@j9~^#aX;$*%QJAcOx&Reiu+t=%|YN07D!B1nIJgYssf zS*AWHtYBktP|;A8avPWrRtH04`z(GiHmub#91+*XO{YKCHVDI)=uo!IuIQG0e!GL6 zdR~)^6YLq|v|A=RMvdoG`sDw4N#CQw3&d92bXwUqi6nTZtij=UNh;vLpn~V>PrB@m#UW0&u(SZiQA#2Tmd4dgr&q-$JweE3O z0(kCE4eA;(>CfLUU-J+YEpt3J zbCbkS`No~};^Yq^&>{Tkg-ta@3~7Mk1yR5Q(yFPbaHK(>n5Kr|9IWIY?gjb_x>yu` ze-~ii?>YQrV*KU#Mm_yLua*KuJc3O?Nw=Bn+Z3^UU-p!$qQi_>j{ z2o?;!yXc2w=Z9~eEIg`#8Xpa+lok6Y)7t1a2(P}+f9l{jT zEdRN3*nf(umrchyQF?vjp}cGk31BFKpZJ`3qiSMg8#6qCMOH5)AP4OfkUXQ zuSh~k{65#WTlB5d>``R#ZVWmRk739NvPtVCNOej3W94y29dk%tyKTTB?9OhhnJl`z zOuYT3{ahNn%9aDXR}cl`*=W%FzC@-e8V%M%EOCh7gcJ3~J9QQLeEqiR< zIP+U|y`N34S~tk~JVCl?cP*GPuT7er1j#Sy#j1oa7Hhn$jlp(D}>1HeG3$KEfayLRy zWkgZLWuv-JX_Qg;R{ez%ykFeY7fD@d){y!Gv}@Js80B#xdfjrJst|M-T|ULznn zqpV%9_*cn*4j%!+mekc7>agd9G>ZI&WY?Fu%{~bM^}6!frD(&XpwA&ZFIV$ev@cH3 zpp&|c@vx6>j>`K8{g2seVDT$|^e^>Fnq@fy0Mew+Mv`u*uR$X7rTNKxuI14Y{QFKe z{N<=W6VfPB>C|>a-044h%?_?vzUUgECvwYyRcrT{!d^B#z z>W7Um31IRMRjns<8f>0#yTpGg@|0YA(a%E635{Nbj10s-)qv=o+csgoPw+Y%G&evV zo+~;YW7r+&N-g` zju!8B{i!M;#2hu4tH5b&txN%-Kq(3WWqdd|GeJC&o)pLKPHlOV8A3bvP%iE%5H8HA zFGfjUg{wQ~s(QkmrIX98LzS*RR}xq+Ev*~#wWI#p7TUJ(PrC#TGVr!nba`|yL+H5@ zAuM$`8ZM_WBd#OjmMzjrX4eip{)K}ofrnr+XCY>nDK~kYSNROXG(tNm&v!+%D}h;t zyyK=SfuU<3dPI;mSB<%xmSJ^zKjy)XIL_It?&QE*KJk`)<=`?m<+YS)zve51JI4*w z)MFBW{@-dsbbsGlp5HOQkge4=IIqTUHvFj_65fK=;Cxge-lhYMU6au~kAFVVy6Hzh z5$umVVz^X5lN9)H9w&)6#908Jt!SMPl>_+DK?e`M07hAxu8+q)68(6~<*##_Dwpmh#l{Qv-gkc~) zIg6YyylwfxAQ~9qLJci|($CqiYlmm-+0Wx8#xzJ+KVEg;IL6bdxnUd*R~Uf%_!h9l zp4I1Vmz_+(b&keq1pW>IJ3Vf{T*>_&nh!!O_n!V*)$VGom2T1akQF&*1F}B|n>ECl z58`cxBZ&`#;>b1B7j;b)1}(GSbf4r-wd*$OPx_B(#g~p$TWABnoYsz%yMgzMdVoSR z+!J3~X+gdTkcj_)dU}mE_w(Z;FWYg&k|J^{k;NTFB|{z@x(!bko_v>UH%9&yf@nx1 zPGovDK$b;4AVOO_c2I}oB(>@KjXVY$c8VVBGt}Gqjum_~>hzq;iwM6prxZjd%EFhE z{SbFY5Pc4^bcnP6W#vRP}(LTN_?dR?nrNSB}CH+q*B<$xLZBI}8ABx@p!`3RFV;w`wN}Zr+o@ zRrP8<#J_3QN`YA5a~8}ddAE{3w!7GF8pjP;wtIU4`vdfsm#LK4K}K}mf6 zLoXf*OO=nx#`RzBRX|V}SwMuGHwZBv{QJ~Sxc)j_;nOQvq%4yx(aF=pST=#Wp7@iL z_TgfITI(vLJ^ejv<6|_dFsN!lgO|^%kD#`IJ3{B$`OwBykPG+-mIsMGn z(oBQ?X<#j;8MQy4*-s}te_V54j`2AiPF@k}=eh*Jl$e09-NX?ua_fs**qvb(oB$LQ zDO7q6VvsD6sTkN#qd088b~u$rYwnwz-BiS)anAex?`iHM(ky#h87Aee32X9)o_Ua7 z`yrik#jTfq(t@2w!uxOu+Zid?2+a;era0`QLEWi*yQT$d%=mWmxc9M0g0N1D!A$91 zhaa;S}cB%T*!Vv^f5qZalI9d@D^= z0TuA7C*^5L0M+}G0aB+{a`;EX;55olb9=?-MLs|gbO+Ds&p}v@&&zF(SzeP7R zP_9_JA?D0avJ*PP@O)Y8TVJlr-!R`R>h$pPBZ$&mBAaygf9RGM?=*mW{lu zCvqsua1 z`b!;35L$ZC1M)KZ-cWOv)Pou#t)TzQWqgy8_G z-MstlVY7ZPqHeWdwWMFrcPV)0W&+U{h~@9E>m!HGjoN`_8_q!fnS;jK`ErxyeiD_a zZqa0PjL&~!QA)t=6uT{UV_vvQ1b_cF$0d?bdiwypb#kVotz_ztb@gA`LiLXo>a{5v zW{tfUDC#XIkn#>Eyk1+kvxT|&uZu*#Q304an+bAEBByg9JqgV(KOcCq&8VB+nQFq0 ztW_Xk<`dULjy;}>-?JS}3r&jm)+g`d+S|`9GoosE;jh(?G`aVw(2T7FZOzpevZWX5 z6(8_?1?|^Asbx67v?Y>vOzY@PoTt>TeGG@~KN2G4Oa5Y4#z%M2kI7L;yf4PsB~FGNN>NpC(ksFPN%iB zYwu}b{j!Lc?NE{|l&(p= z)208dy`X{v&ocORK)N5Yg&>Wcb!<1nxHK7_@Y%pVZcBy1BPR5h&-GH@L!;x zPL@Pg)~z$I)Fz1!+}O7bb4zaP>XvojO)>P;Ong;qp87)P01CS2Uc1qC+CBbaTbxnh zH;i(frb$c$P1+dYq`ch9r>j0>mq5rx1ZI!ru`|#Ju9@c(%)(MoUV*3#j^}kQe{60? zzJfOfwMd5Pk6U*p+5t?au?B}ssxLa-;(GqRBMd2opqqA^u;J-I0tM!BhE^Rg&FY-{ zbd9>@_uXk~0+Gn6oEuDHIYk13fIkg10M)O2CQm6Tbvg;NL~@1%8KLvS2}~H=QO@JD zO9;0kowaxh{+UK+lu<(LijXuqFo4ZvvQWP@58O2H7G4rrT=_K0rOoV*q+NG2GiCoOkxUHvh?2U-LTxrFi0E?={ zLIk;)xjFK{xRs;ixKeQrwE|awMuck0b#t;&2Zxr(EI z?y0_+mRfuC#+>V zx=1C9^_X6)kS1lxsc;?OrpOLWSK0Od%(`vR>DlsrqR~}*J0-k{iQmz|u;RNPde}4O z7=gL*G|0UIA`JfixXI#hAm3+4F-aB+&V4NYRa0JqUq!mY5Kt5uoF{5u3SV{7v>CsF z_}=&piJ1G|I^id1GV6nNj4F6lq8^vJKD`~+(0MN{@@uWyaMxFNI+wU~9XfggM5juQ zkHi#9<|4R>2Aq1FE+zYf3=m3o2G`7!Z=Msv`SF`Gh=3MERlx}nR)=BCntbILnNOP~ z?9=%*qS&S`Yr;blB{LkSy621&c*D`yDQAmW!{xgqVyNFYC(N8JvN>jAbmi~cC{?4bWW1A8J;E!88p zSvXlULAT`Bn9_yF`{z27s(&6A)(5#@7YbuzobVv0@_&{b17ea(=Lu1lngOpr1y6zg z8_e300b-;BTP}8!WxGay%iYGdZyPB~vI~w4`Kovo?bxL8<+Ak9W=>gfeV0S?7fI%q!pv2~jj< zUk=iEG47XtP!b-L={gv8QrG@?CAciLN$IR%GEB}dF?F8jVAEFm8-JEV~f% zZ}~#5Aw!N)#yn#)=x)gdm8uoDs(m4l+F^+EjRi9aK~5-$EHos^Byro2)~Xylc9A(S zN?Dm@@kG6i5Y=<}62iEM;LA8Y?}*M9Cj(sjs(A+|zTlQg#7*R0;A-u^V_!K2iUTR6 zyZ@YdMeKk2As`f~!v5*)T-oOnE`2uIgnNdFyc+9NwQ#h%zFeobV0M|5PS#gpe?;xy za}I=t*T@>pG^p#Wt~j@55+_UMN8!prS|A^wMy&+{ZQAH@AF?O1D@Ou z1c7&R9t+*$c6V{6pdn(mxig`6yRJu0`Jbzkj^^P8cW+MGb-?8%?jhVmU{JkLOG5=ROh5d08S?f}P_1%El!sg3m z=r6W^{dHD245qIvgR=V+)OMTBXH&)OrJ@#>x zwQWBKpxNqJddb7O_>h#qchS6i_C?7(?$y9BT+WkSImsX8bAYmL4Au|-VRE45-!@l6 zvA$eQ+lcvJt|sgxXGv8?69oca{({6Ls5r<_t}Q*TMy;5egwen1qWLe3 zu)waMBPAf|n%oR*bY)dBTc!lfKeOThazJt1KYLpZgoDbKoSBIGRLN=~zP*)%xYGnR zE9e}r_hiqCz3~lLk3E_F|N9gKh$UTzNU!@cg9i2~fjKN@eJdJ_s|MSv9@w@`=r?8( za^oJ~1+n2o)@FtbG3>Crj0f5X}iRAHB{i6>=Y9@5f2F(Sl;+K(k1^nLf18N zFlIu6`AYOKH#b|9W@kAVEkTs6p}hsqW%e8De;N}0d#Rx+X}1}Im2_z0DaQE=4)}A7 z073ezwaF+6yzg5g`Waln zv_o-h;^G+0-TVb{Xn-yz;(gAMW`zU^GZF{Q86g3rPl^BV%|H7mkcF~kDzatDB0wQ2 zZll6+)f)l~%?YJMztRS%&0M*@(2vwm{f)W*ec3LeUy2R8^`3C0c&KuAKHzAv@d)*2 z5L+~#q&PxYiU>7%znh>hiYurRk6rO!vG~mgai!|Y=$XKiA#&3T@Zya@79@STShSp4 z`)|Yky6PYaA%ht9N^iJ^_`o*4P{4Dr-s`Tm2WI+v@Xny-;77B7w#;eBm}KU;xu{N5 znh16&p!p&E?SI1en+?J^{cMFD%cfAdt?@HbcufhE8ZQKM^43IbvfaO5|KB3^L`V*n z8sbR5OJTrW&xCRSjERVDjQV%|2Ak>ej=nmkfcJL~o^Y6TAjDKG|ArO%7o`gAh9n2u z3}})P@#}Wt3H<&n0m%Pi&PbH27+ni$9{z8O{=P&&2n7yWqJMnGgo&tj*OipjIxMJF zJohV{Bt)h)=V4%$XB5kJ$?5Rz|2CiowImTC!y&@mNakAEvRrM3g)1sG?O*x+-yw^M zZ01tnatX@>f{R4dB;oT$zr|3-68CLtBs}Zw+Np3@mD(*L25XG1EK5uyBg)R?+>@6A z;3U}oIfbnrQs19OeL;wo^?_46Yr)Ad%%73;39hvD`PzBJP~Wz+znuKv!;t2O$Ymip zC^7A=xXid?vgQs)B*T*atFT(SB^|hAJfy1cUy+|?s0Agyg@mKT23%_ z=6_CeBnZs&q4l)#mXYZZGzM9x+R*P-eel!eJ~X88fhjt;e#Ylu5%Pa8{Qs0B6)Z%q zVF{z&(91LwAxCbAp<+}m_%dswtWQaZd`O;ORKA2}mv@JcMSh)HF~H~Xf@vwP-wXizeh7Mv%KAAa{`CueyCy=HHM>UF>z#vea#u#2Yc{__G#TmTn15^E|68u% z4JnE}aae#hQA8{kCj3p}Q5ZB32bZ{T@YG~JfCdi-3@;YnrhTTe>%)B&)bp+TWE$;K zPZ59vcbNMn)L{p18VIc3gQUp)kd=0?7X`r+CvVzYQ7<9+y8Sc7th+(fPe(&39FhI4 z20Hnx+C(M?IhRgv#KL*hGYIFZIVY2NkNaq0F3@_1K}1g=C@je-fS4#rdS zVaC2mzeB!HVrv=4dYWJexW)dTYavQ

(=!uzA0gBAsVt*i;)e$tGNNJGATBi-CyG zZC(G@eeQf3U|t#1e_->taLBg2J(zHa{NyhtV>S)YMDbm&jQr%q_$D+RAOKb%G+9dT z8zEpk`$JNE54`#-3X=6+d~jSp^>w5vQN{icM3(&>`5?-D!>rhlXh_YVlVvJnp&A!U zLDV&yP432Dckt@BNKRAJ5@t)+$9>g#vG9B8`vG@XO&_xGTGpSp!_`=6B8yd2|+IlM2%8)YWP@yi4Ft=hv|<%k$J7;;3yG%*3w|6 z*<(4ly#fa!uY!yw@%}8tcR{!9F z&!{4)ZQn=GUPqL?jj?rY{W85CmaTao7MnU3l9d^>>xVJpuHv>LX=pz6gi{I2^7j6B zx&Bpb(hzYZAx@e8k#dwWGAY&5v{cCu zxZboHmMF33&!Box=W*HX@L`C^hURpV=*MZ7WT>r)s}Y?(SAV=@5o)Mg##1P-+knP`Voiq+42AL@XKs$sr__R0OG^ySu+V z_`bjQc)s(O*LALoXZG{#z1F?%`(A6WeJ=Jb%=DNJ2b5UoLmO8DIVvCSzCC@J>~dB8`VA$82Bpmg zVo~=%;UM`jG<;)TC> zIXR=9@cWgRu-tY<9xw8$Fjvev-uAtXgGi*w-3$XmTaqaJ#^2F1CK8$poCL&hEx!#L z{22YN_RjZryj>J{XS{)Rmr0KW>tNEqk&n?22vjn?Uv;pjg4j-TG98);)?cKopro33 zrgX;TmWU~B{$T0Le1J|eK&YGfU03zdb#4UwG&EBMb3TzvZ!`@SC9AhrC?mFCTg-%FpG5pXMA8)VW|7;K$J+c2jfOUu22q zX5{qL2yR0IlT(AlmEXY5C}4hxg(n!dcWVXNTwyGR5%0li;a(2&(3}&M10Mr)y{rrs zmYbeV)9s&a_)ivglssdvn_<~-U?Tz3VY9!dinMrnd1bgG6*6EExO308NkjSk{}c58 z8~ZU3jt|7)UA1852c4ge^wJe~dAq%WRzy}r-hr=AI8TvJQ`OipUMOCY@seMCbrtJLn%QBe4f z=Xa!2ymp!`Nk7@+u9N;v!_q?6E5_*8Nea;wM`eStp~o*bYpG@z=}pi+L_ID zynhdl>9jNl6Um*qPe~mX2^X&jw!&v?D8{ zNQr`!o!*SCc^8YK^0~dsrK`Y^cts^>d$nj);2Pu2f+F1jhuiN?sBA0tuePn? z>{7WnW}?B4mK_Ae1TCpQ+aDcQXn`pl->C)GjwoYZd|v15y-${&Q9I*nm7_(ShJmIP z+ew|#1~GzvANwhF_!u>b*2_Dh8E(I=_sg@-z7;YW+-kbQ*pwPTx0@F$|J#Asvx6hF zT4TciyNG9ZmW;S$RAq#QlY6P}u+>PLGc*xq_25bzEtQuQMbS03W{D%R8@l$Zx7oA> z&FlJUZB-RslO?Jk0-dh7t*}Q2VHkg$ZWY^AF=l?T#T==hip~d{@6<6G5JDN?nkvR~ z2Kmz|ve@Mfpr&cb?DnZd&pqq)XcO~!&nO$7H_w;x$E))v;$FsIZV-0wiT8cc6#UXE zzh4?VqTjGhGx-n;0R;U)p-0GsGtyFnQ5uB?i&K zuMx(629>zQ_zm>3dGkDZ*E=Hr&LFBN4lwK|A|xAR(EZA)`tQR7lq-R$H+S;0J8wLX zu1IqBUU{q_dy&?!BZ!9+qc?W~O-(51UeE zs{9>=QN3*;$mTn8#$^s}k5BikG!}AXXCnPxh6D!3xVontU(?JMc7IEfQH~?$X^!*z zH8IEWgA|TzuI;uDT!WYBg##nosQhWP%;?z^nZFfuq7Yk?M|bgjV&g1}k6Bmz(rWk5 zm9T0<+SK}ytt|e;yo?h^J?_7OL^hCdQ*0}Sz&|Y@-FNw3wo_z?UO`+RWvXtT6`b;{ z_C@NOJViwcC1Vi{p5h1n!m@AN)ab+wpCy#-#zV1u-x!Vmx}7fJ=~ft^XpKC~1?GWJ zud#S-rah%EHU9l6RtjAf82~dSFkyNS7!pjn4Bp-k+PFYYxDTADlN`Rwi*YiAwnATI z0P=1DFB@U`&tKk#iO%6;-W&C9GtrWlITSRHUYG;x)EaHAg#Co-{liDZ0UA^g5lHEv~>6n^|=mo62ZBWYjq zY_doD!7TDsk zdcdzpnkUo48GS&?{SE%-8kIBmn$|K!vWjECGzTg7k<3~}f^Fm3euHd~TP}>(@-bV2 z3-{t1ssz>qm)}NTobuUrQ=Vh(mC?yHOKZwi$0)KKOgI-CJFnd+qBb*1y*A?=DF2d8 zS`4sS|oVDBw zbh6hI9A6lJVl&wSl84O17HP}Fhb*c0%MEb|L%M|;$9fble6ml?uOhExhC>t1!5u2q zN5U1nSN6xd|>o-?R>KMYYiF~7#>z8itTl()?7DXXn2GwxoI4JfjvC*>;M$C1m$Y>jYnsXRrSb;WGrasD? z1r%dssB|A0Rz%cg>2avYPEEqA(ks34Y4WbP?1pDAXq%K9s;X4o3ja)PffC!yM+wA| zRX8R7U2MccumIVHbi(|qc&Jo89l^I+J9$>*yPLVX4uS+&Fl_N*Zd+4>ey6j?>?c)Fs$BiK2=S1QPZRz+-Q`uIH zyFIr%BVaxAb>bYklX3Iy-KlsFt+MZ`sQw^~Q*2fjaJAIPQbD%e#lHQ8#0TeI|MMN# zHO7+lz+cFj5@Dh&$q%|Fm&D@#0nIB|GhxVTUPf|wnwHqZ`IWPm-6_LWjc2xzpIZ*? zp!2Eb`38%iWj9s0{YggZ^W_{tYFZ;P4b#uhk}|#5zwEEOH;xKmfD!>OyH8<;q1Pew zrB7k);dErQh63J{fW2oVpTw}HAE+oi6|1d4M{PuCE$~v&kl6d}q}Ma+5vOwGK~T&b zX9Jo-pLcp>dbQ<`o}8RbUih92DxBRzbMr=}O#|_^6tfI`GqvFJtpRb!{-l|%0i{Qg zDp#(B9gK5}(gFS$v(P@eY5tXTLA36wED9q54Hmdbur^7llUCP*?ovmVO2ZLfUlMrG z-g@Z4E{iSCRQLI9?|)gE|He#s9r_TdJTEX<4^V4qJne4uppD@anN#btxNFM&-9ko# zd!UfRDpiZ?ejb>j{{SiCT& z#xx+)rIUHI`uUfM+n8hfktlA%d2fc)pfA)1%}Ar+n%_~ksaHBWFh*<0^e}JKZphcp z#K?>ZVJ+}d>*5NJwBPv++{yKj$v#op~UkyF{>|M9b zUSwG~0J=RApC;kJhcQJ+Sb6$HRPlmhlOSVem*Ro~+B&Yv3ocZ>-~s;I)pXaMrOBaU)sA0o|mY-6zNC#N#ES|)H_p%*54 z`m*QuV~9C534hDsl8*oKElhsK;Rcf8wrI;*C@e5H;{bVQd?3c%|^&8onB2!3G_8l6k}Rt{b3V zid2tU6i!w2C35fyg0Ch{tLKSCsd(m|0nHqz z9H`y+aLHScQ~J%XY~7G#ZQ(80q58FeSX{s{;3nhn$`2<6&N1_{4rgNF;0%#L-Bme| zHS_fc6QjT6v%Qwz+bJ~-B^l76jL_mr+W zG`uPHpX*B6PoF$(L&MUV2M`d;Qx!d%4jq=&AM#%t-U&HA%=IpY2}N5O zVR#*yTY)=qAd7BnGI+4oVK3BD=+3uoU*~5$-_@B_m=DK0+%7b@iz(nzD0_9e0}WgL z_a;C(eup1b`x-&uU?A>;!e-k%m+KoKpvKDeu%huh!U~PWJ(b(sBW;8nYQimX6LI^@ z3CO8j67fM^^ER?Z?%S^#D0zM&HYh_DQHQemRsV9HPqQ3Z07IJ#EYiMyG}*g;&=s?D zi=Rdp4)T2SYez_1J2ciyy9gn zTL-0S3HU!MIwH$(P9@+=iVv6NPFBmu6|m+?Bos#i!bLQB&X0>PYQ98aHWH+=m}4S- zVovFt&+4pN2zjS@yHENajE@Up>)~IVZ(Nvcn_lqjkL6{rD9fKS(R0Z>vKqusm$5JU zo~%odx>R}BbCMZ8BtQ3!?Sb=$Gu#5DgR`w^Dep2)?a&v zcSF>$HEF<~{B2z@Qrg~eJ*QTyXoWyj+5WlbCz6u;sUqef?Vn(zmT?ATC}PUcSm^yH zN07O+F_re0*xVO~_t{A_F{v32O>>ClSr5zFop6UF?}cn9&JeLjV1NS%KITLrJK%H< zFx6TB=Q(^|9Q7pH50#A>jOSXG_w|9k@tpa^j{^BQ$yE8WR;*ymnI<9ZTX>(SrGLvr zNR@wM)_qxG#6``(Pt)`oag~#o+b2@XH~gDMbKdlqPVFmLvGiEHj15QM?T>q)t~{v5 zCQS{?kybW0Z~JJx2s(fDe`?*JgZxDbBHGc87{oQ)^bSAJn_G27~80jLo-#k2=SENtJ(4F#u5I zF!xhoT_MC(M&9daai9hV+d!BVs|#np4(5qyhRk95s=N<;J=J)=()dcAQFj2PgGCe# zJP$E<#RKlVxGxK#{Ik=?U_r@m&qlISG94fPX!4&*gPeB2J%ia8sNZdt{4t084@)9j z5NM8U(MHQFEvLK%yOxi9xFNn%E^zamMwv#Z@S|ST?rLj5$u|g-ms=)uF7cjho9Gl8 za1^rLA%*9XBM9U@4T<=(p<5(8HO*N0c)m}|dWVt@@4^Wn5%CE+@*{RNOWf{|@JT#y z6-eiPDr88W4QN2O)v&FhFIpo4Ef@?WQM2(^srkQ#ou};?I3USE~Ad2OAyeVZ`Xdx?-PI4LjldK*9}ENFac=@K>Hx0nV#E=!~?f-9clcD(?@-76qkztB*FU>{+RLrrJE z=L6;gIJ1!h^0hmC^!{DCTUg1)%$~FHcBRO5+QY!Z@AiH(q#_Slw_g3KYeSd$9)^c* z@W&;`=Re(+>;*rgQ-GT$IsXj@Ee%t1OA=uOtxvN!;~YK=wZL-eqqy7yQ|WibGoX+9 zkvUU1O|d$%TdMkD>x~!Zb}Y1-Jb??`lc_)ax&Ph{tas4oKEQ#AmI$q#_&c^BxTb#G z)7k5kt`#I#?nKcY6ChFu#Hp+ykF|U@OnnaaXtbc4Z=L%`U|w)#a@YUT^Txxp}IJXy;z*voC>(nnwWLX?WAnf zcL_pB@1x1=`r}T6-781XeWhQ@S8D|vwnuGhhStrufC!dX(e%Av3Pa~O%C*lI)L(MKebI)vlbwnPs z5!45=vBejl@9@yN^4Em-$m!8ey}YLX8IOzoKSQ-rcl)5?W zyUy@6d$qY1iEqsj}-|wbuGG)N7!8XPQ z)AJ?BDW(ZU1xCxZP_j-=#?{!G&QOUM4NN%c-y9X{PAED|F2|RuVyLyeTN7wEkVcef zDtZR6e^+Hhqzd;bzz>S*ey!K-Xt!Ko-NH@2DZHd^KspDR)a^(1lbun_Tu(Jg(yZ1s#JztX*0z>+Im3hrJQK{ zOD`=Ir@RiM8}b-yPd7$7^_1()&Vx7tSxJb6%q!{0b+}DfSn9hes*E%D>riv>GCOp&*)c+XD_+}quj6}5k6gbt;byWPsxG?H zD#cF}0Vn>UmidE?il~?uT^^%EA{94+scQh*3S}CWx_=;V!Ns9q~^OYn>Byi2~YhyTLCkw{aW8^0? zJL!2?{`3nOezJq`wH!9yhhcXDb>$O@wWOcnsE+HQt97I~Hm1j|O@$t*z>CeOcGovw z-|427`ED{z9=6?N6l)6?IEQa??10ZZGT)Oa!)?s{KmX4k2hB`0lIw#NK1Vu%3oj0N z5dj6)llD@9ATmrjs}%yj9}H`_BumVNSiZA^RlGzbbLIs^Zi$D-zZ%yyZ=g%9Nr?mt z$~$yt1ZpaUD0mv~IgefKnnYC`oJmtFgYKItJk!{syPKDeFk%t5d*gSQ-%~VyA4>u` zeVE)b>d-U%d*%2c8LNb>xXtsSBFFYJXr3?VsTq7^^W(mXM@7R61JvL6-pM%~*+d zVlRBBt?*s}@^SP?L2h!W(9|-OcgBd4C((dIk#2|*_`6khv7h7mD3v6FK4rjt-y3wt zp2HV;dfcQGwoT#v7~QdiG$+J7#Of8l)p{%yyC9u)go-pUG{bR4D+yoeOl{Eg=SjFV zi}+lSzUsuu#DTo&Q-rA4e|$%ZoE7xOZ~i+A;6Jq7rUUzC2N;u=a7-S>^%Uh8gJOnZ zD4WbC&{FN>d`!Z*6O!tKwVOzW*;pAEfIF29UC!6~!4h-z8e8onc-OZw;#1`k(pS)A zGey{0BFqe+ckBk%juv-p3td%3HhB(Ry;j#m9_}!$cB^33AD5z{Yz^oT32l7wI(J@! ztM@Q$(D0BzX4=SWDSsdIRt~#Q9refh{b0UQ_vy3IlZKP=jY=vV+5WrzZr8hxyUNY}LhK)Y7#YdUl#uS$X5!`36@_zt-zG>T`vH?SCyES1a=xORL@2K^bqnWmBk_$W1yHghXYJD8GhSDt2$k|mV1l-_Tj9t zvMiM=;^5n0Li!KzrEm=S5-L1Uz6)}tQXyK%$+_Rk-S)!$BUX zCp?Nn-U*WjJG&>ogPva`SL!?KI|mQ44l)MMfD^{Q_GD>6wxCxkIn*O%CW+dX(Q~*% zMY_Eq)nTla;P^N=VzF!BTCat&&a0*OWKhpw?C$p(-RRShM~Bd}6nR@HB)iWrW8>qN zBJ|_5_u^EiZZcSBnv^={s?agk!u*2#!Iy1JU&6r{+?D(vEZDgzj{n<{=s%-^K(@Jx zy9jQJM2s-|*kRY+2-8@RbC)+=G&fQSZ6aM0tsiHhQ(nn%V4xpou4Zh(I}tE$q$kgow8z2RcIHOH0sCT1o5apHefH#m2_sz zD;z2z@9v$?nt2Ggf=MSpLeMmLlz#|_L9_z~=V;pO* zci}b&_Ya`L*oP_1{8q2k3dBMuKikZ`wwcbgWubm6$<`$@DWR}+*}(gRE5Ofi=;#^o z%&+wPr#9Z-s6qudBSL^Acrs-L{xOks+oa#Zq&`;Lz#c01|NlNN;m6?jHA0w%<#~$g ztL=n77%~o)+GC5mQCE0M?MLA3I7*xPB0HPDHte)ed3l&^QdRzb_A!Z>r0&Yy6k>}= zfvT{&J`@zrRS^@itP3aDiRd+PLLk){62B6L7HP@(1m^nPl#HHn$_Ag1iwUz$q2_Ci z8N2268zqAnFzgMhL!e)>#cHF)<*jf{D+lzeG|g3EMj!NKGQZ8Bad&aW1nHK=S^2-n z1UQs@_+1PxQ>_~W&R_l+GjEt_S5}>(*sageUYNyO`MHlw(RUT;txvj0)WI!?)d#K| z#+BsAZ5AE*_Vn0jZ({#}FE`nTbCvw8m^X-CurHq?8|S`@I6}HOgf{E~3MS9`I$za- z6iTm#FI=>CQ;|;iEyD)u#r=Gilj4TsXR^}$wXZSjo7Lfy%f!=?>CW{!IP< z$9`3bMs_%gThSaiXj<&&=-em+USj-fzYEM1HKf< z@m9p)aH+7a)aF%%qv|jRzwN_JVmE37lR*RZ{URBQ;rm`Q6+yaDSca zo`y7Il=eDE6aN4TA=rrM6|2RgWk`r?vE%K0Uk*DA+}DneG;6QdBu}V&7PsU?OZwKj zKg3Q_c{ONznveoLd|41}e^lhcpG`o=2HB2dv&3n4i}<9P&4Vrlo{_`(ciz!{Aoqo5 z!pEDSmRxna1Dd6;F<~kvi!b<|XTn*g4uyQCh^DMk<$b+WwivqY_GJ+ZVz!+JU0kpokoFLNc_ugt<^ARYRdtNj4 zw>Si1Y_Os(AAV5{w`M#{a62PHA_Z&Sje)l4 zx!=!=Nt_A}r0K7h-vt)1I;Z2Mf)rqzOk@yynrJ=v_G=g3f|&8YJ|QI{SDBrKL?!si z_N74_PC|jahMbS|-RRV=GZi0gsMrFExq!Zjqs7s_dxJ5n2MQtTzCOlF!nk8T$uzP1 zRx$|`ltmf9hd0-!LMBl65wZPS)O!br?*G`?;MJAL^X==dyL^wIh_JTtHedeQ ze>|y;wQsV8q_c<4Yu*5+TRu?sKb)G2L9+!_KZY0(L4l{6HyXKOps&AW$<<~6IcV-p zf_6l)j*HlW(!ZV}OpJaCz2fcUKTjdSDs<+M7ajDB2<$c4Ciq5Y>La2jg0ec?El{YZ zd~Sk4z=F_Oo=#HOXS>YA9c=(m%YcLm^ZCVX3RdhC29l70{t~-ti=xZJ7D9|E!+6SzE z*m%0Vy;tlnH(mb>^S4FLfJby^AptdxBxiX0)z$k3NqJMi{Bs@cxs}@aR^D~3AR{9N7d!pr zpP_&fVWtB1Q46l^pYjwAhnxs|GjQ!d_VlJaz!?&Qgi(s{HU6M_~3<6CDa>lzU# z7!R~+hl6t08A!D$Dx^|ZOmIE7I}1AcOM((E)4*S6jtG6`XblpqFF$$^SAbZ+17aVM z=9mzZXUt@u>T?4%%$lf3Y-P;42F6rgFDmz9+p%3~dAgD+W)7c-0EkPtYKZ$jkL* zc;o3orm$UpH}EIP3-nn91_)kLTn4L4YVm&|2N|LW-Yyf?96#6PX2B#cQE3tiYAr<$ z6*-|;NWig)Oi`M)Is_JShKwAM%%eEPbAifXPWj02@+nXh@Zm8#DE{BpHtH8vlzDRh zud{>f46T-)$b?8r`3ipn+=5`%@uOt99?J__=ydBF=7lGX5ZSx=|g zAffE43^{MNtvo8Un`va>UwN0B9d4*ol~&>Nxd{Gw_>I&dcVe&PygXP5)fvAGSc!x; z#6i4dJ3s>qh8-*C5saPi^|e}L7m-k%E}ACX20G(gA8@g%5rLRhN6Q2$QOuMQ^!#w9 zdn%O8Wa4yQvfWXdQ7=$P=bsfUeLp^&>$oj(O@1=947-_zJ=6Be3m5UI7kW1@fl#?} z&YtW&M;ZK68p575U8tp63vmBmNQ1oGN8zA5`~_8gv#%G}S*c7jp)*lpT^c-@_Xqmn zPyX7G$PU$#DroD?x>&1(yN$|9?IBwtk#az$JZW!cWV=Y@9{N|2O`62Kw7YI z$3-8yNzi>&Gufq4+Hu4pB?&xKfqhDj_>Jd)wWFxQw1+|qtM}@iiGzuQr1Bp5k6=dA zzJN9B-?<@57*ay>aO<};tAzBh zIw{uJ&1T%z_sD1-h3gcQ%SpszshlLztFi-w{e9Mr2w73C0_%G({{$;C%w4w8TL~c% zEmA0gpaDnj&6p4-yXsscpRKQRLx%POpPsP`rzwsu-_=oV6*8`=NXI=>IBii#1PylO z%uXE~7Qin@%7c4}S^t4G)M>GXon+-TQEm5rJxxq78`<^}BYkr2Yv|DA&&oeWxQcOnUg!HReT7*!{;ghRz7*ihHlzP0f2V>52bd85O4_YrB1OGVs9f}yW-z6iP(}dNtw};oK9hW4vD0Ex2W%ZlCop&*QKM{xGg8Rb|I0dFpX07OJr^^@mY`%er5gqQAoQZz+4Xi1v#b1{E?Xi)a%~XUr9(T>uutC)W z+!X#SdT-e}MgkHr@oki^Jz;^cKbrZ(iUxAV$Bmg|kGtBara4_t&+Y znS4~`weZPd4iGA9amr57`+Ak!$`osfpotW7-|dR9+2&6IJ#?0<-|=W}I#Oiz94*A5 z1yNLc)3e(}yrSb0?*HF5;=;xpb*wyqT3VpZ`Q|O^t@5)^6W0{3WDEN#r$Mc!!yf$v zA2Ytc;BEx^VNv8rC1mRq4GFW1gAEK~n(49im2QTGgbi2|Z&M}^d7iCiv5=8h)YUM! zz|l{gm0^7JJyekY>7$1c7#KI$McFIjX8R55eh=%1xSPTf?2y=F^;JBXvls`1n? zbr7*xt=8M=L*uk%d)FvHM^?2cFr{xNSJmaCA+(5yYueo3m=+nP6yWai-P^|G%TAF@ zH!y=4f-F&51`O3noe4alXYJANz@N#pDgQ2kE-NC^HQHIdZAQFS3Sn9-AUHgJ#fhT< zQRl%jVt2l?TDw*B72cz2`otOWjqL)m=;j#GdT6OV8IAYRW*=U$r{8!DZA#T-Zy~U!fnhx20WljOS7x44#@>xeL~q*5 z%qL7pfi#$ok)q2<;J&?Va^)V)^v#WW-o3BFTiQWAyYxmjZ=|4^&IR^_Aq;zuogK!Z z3k-FanF%yj&w)$Yi7ZuwGIyAWdZgwVodLvj|7rL8b8we=ZO_qI82)s7UdQ*?7U?)&~r+~^$EQ6FM%j2=s-j92*A9O5C4ny)320RcOe#foOkkZyN|0v;tG!bja;?3tId~6AJFzog|ir>3oi>Ji2lLJv9 z=H@qaeGNnpfDc)kRjC$KB>GPDiW~4xKH9HXNWjPaOmYEo4`Zy^YQxDog)R0gs+~X> zAJZBkOE2L|b;ByriqoAxNclDa=8Ccl`{=NUm(u9raX#BJgI9UEGD-b#Po#-PlKKb#n2${NnMV|#sM zRv#Aibv1kF3XdZ#jQ;$+linM+g1SM+oeA1wk_=W_EPFJYQ19RxJt*uV^B&%sM+NyE zSoy5Q5@^58bo_3>+AC4xO)SLpW465$-X7RJlJPs2NQ)I+&pnOCaHhwVJB~{!%*8YB zSzgp~xys~Xgps=Ln$vl$$(*`)Ffa2k`P^09_AwfoA-SWGKtP?j8u!T#-P~c|cThX| zRi+YH-6uVm-HvySXB|@Yp7v%LJIHU^;o9Lpq>F}}#m9u)u8Dj)M~RqH!k8hnP`46N zwsoP14cuwNSyAj>_f;a2i=gn@Vb@{W*bN)|;fE_Mn+6v=Tg#v0Tky}nWWdt8C!R5x zPDeAfyUhj&ZP^|k_+K1cW*^o}_AHl@kQ5QO+7cdCzc-g{HL7rDwH$kE(}xuvcNSHc z=NH@b+8_CgO78c#7Z$M+H|m9|=xq9x$TD0)7(uK^TEXkRau-HWrV?y`pt`ov?RJJ! zz&#?>aHZ`W)D%Pu*pjb?)g#t#!c?lhY@@;25H6-E^7S`p8;bKV@CR!f z3s8Qo=UH#fH{f$i^)s*?`H}<$c+^BR%4=&8B7`^{NNKq5;WC}1ZxVjJa@b)tTGiZ+ zwXN=J2n`9_abIW`2zeC!6`1a*juvl;F+bah{c3^Yx%BqS`p{+>-y=(ftnzqB8}}Dm zW_SxC+B3R+rRF(R6=09@b(kh@1j;;`IO#ZUu*LfbTUI!B@11 zRWj~2nsiXNAU6l9JK};Cpz6|@<}Xs(%m%rL+sxv2Oj9BHBLbp1i8*4Ad6_kle8t(lm16c29SFU|(56OFG$J zm?UD*4Xo|CAT!AjtEZJFYS9{y7!yJZQahW!EF3dvNEnCC+&naR zi^=K&xN&QIX1Umwq#2Q^KxVpK`#IMZyP;?P0bTlI!-~D0KW*%aIgL88=K{t9#%b^c z{u;`KPuSAwwXv;ci-!7n#Ul=)ISMSy8_tWPN4;BL&|Ns+sW9z?#{rX8`XNcjnAHJ^ zIR_+pB4H1AI-!WukzPMNySlA5k2|v`6DJK$+t+y7>8`00J_c;THGz01pnTwC5??V5 z_$}OgNNE1SoPVSvFveVlRSV`i!}-P8J)@4)EMO@=&d)4a=#7RXi>zd@qVMV(Yd|Gj zZ;A*(OUP4J@Ru9`YN)}c?%|h1kGqc)r_ctrZZxcGUWgYCxi)yz7M+x!R8o0r$eK7; z7~T74tr8C)$$LV4zGuF<-i~dRJr7q*=OuTm0g`iv?k?Y5B#5!pVQ;JmBwMke+T z_YHO_nnpT8)7_QqAL%BJhpLjrdZ1hxX=GsN^q0LM!*0-5u!csk$?l+m^b(7}c;9Mg zNbvq?qzY4Am(K z!XsQ#OFHO~7w$gkww2ZiK@G+XX6JX*%U9j=wLD*fBL_liNI;_?Vh5qq z{kevrK3v;!X4s1*tgkbx+shSNLHd@fDB9f%U39_+)dA0M`l@=fnW$UG|9H?K+-t&f zfrgntR=KG_KnRVlo5=ixGl-q%zg-iv>@l*=|JkO_`(Ka@r{)Tv_{ze(52dVI&A#r~ z->uGwOE1*IdHDL3`Lqa9__c$e2ToA5@bq^o`Bthho((Hf3E`1ZB~+~iT-tu3&I6D+ z__kInB-{|DQUUc=6(au`^|8`+R;FxauWrK$%HHigzj?|>GK^7T-V&kv!;Y8RQx$$s z6)AoHk+7c6!;2~Lg9X90oAxWQCa{#(p^ls~25g3=hK*kKH4^ndPqcf{K+)zm{-!pr zo}ldMX3HG#T!tNp!#8r7`UIGF-VH@Dh;@B>Sl%UAyGof|U2z*q*{1<(xoH)g$U#A$ zj}O0D+M0c)XJ|`9*sD(epiJp!n^Z$|`M{Ov$hA_hjAm`T>6-<_ScDb7*dt%u*)=yJ zAAyp$i@0}s^po{YZe7bmV>P~?#EeXt5~@->6ASatCt77TJ0PYRP*A6Krvp+qHK)Tq zs{?b0{-=3+p@$IeR`O`YeA=Hv3GC>{=l$M{n_|Kj1{b+JwyUEWQ9B6p#hVL`gfVMY z_9D+*KY;kucSq3hWA^CjpTH}DwMZ^uCtn(fpi`b6Yh9mbuJr~}{v+H)9ipK4#{6mOY1wyd*qf5&=|H|4wYYwJsXC|w?l^`z(;DQ;tLq#RQX;^%!R z!!T7xsL7U0RffO$+F*Z4X}dNy*rzn zOc@Yam9`xV`lo%4A}bgIvAPZm9a|00TUqnFL`#S0ohSM$@DwDLr)mx}@|{3yynmhA zAz&*7CV?%&ME|o%yYhw<18T*iBuD{a&%aaMiYLE`a2k4OnFI!Na!j9L3)re4Jt47w z+^050_^owsz7S;omhOwjlcuT%UT=3g7m4l^GKJI4G62z8?ap(^q1_iYukkyK3@d%U-nwri%1p9|$(*`K>4Lp4@sYWtuqv(Q_M4qx=G~hc z(XXR}f2g~PR}i|IW5&&)#nazh0fFUPUq!llV=$S?>5a$6J<;O|VnV=omJ>9JmEGr3A!7E5(fsXzg`z zK#B}X{;fT=f)vN&RSzzoXZ0ZN(8aFK#r+=nlU0K$41qN~IoX!*E01*U&+_bcF~QS7{Ac% z0Yd_(U`TbhyzTFb>b|eeM5b5~19Y_%rQxT;0WPjKNGJJ=xudy>lXVhU3s8pi{SI5$ za2dq2JhXbHQY&L{2g&WFyPWH~PY>G_OeW6vtJ*CEZSm7%t%qfVybqgF1pXLm(z&pp z3=aI?GG!$7vPxfKwoAv>ZGC2+7uAav=`F26^!Bqjwo+^nNH>&;n@vX)6Cq4x*xvY! zGkf13lA`dC!>Sy4l!?5}&YH#^^RvFtc=)%)+SZDc{ctLWqj=60f+G4}+6(X#1kpZL zu5&a$=HrH~BZ#?K9fy$>X&tRdB4tJn*4P-8k>bl9OR32UV0alwUVzQ@tRE2dXZgP1a#Ut#+5KQbJcD zs)@Ly{G(<$!qAT$x zS8V;<{I6{h)Al<@8kl%*=#>maT^C&ZvND;Z;DTk zCUcX;ZdPsPO&%S4uP2wLSOY%DqqF{}yVX}>O54J6Z?mk&1TG2m5w)ixKtPnCw%jWg?m5^KTf$I_ASJ)N(RohE8SQcUm8okTE^_}$V zwFS4+F4?jz&@%a=1cYS1fA^TxUe37|hG$d*JhIMOI#akv(7&cOu;d&dT zwV?1LSPP)#=QkVJ`Pt2Wn0;g;(644Xh3|Alg4Of93azF5q|Ui)HY$D+LSYKvhkfLbN%wo+E%7Y z9Hd>Fn~=r!DCaf;^RcsZ=VM94q1&g24fM|$^-sxYQBB_!4n?_nW1Y7t7rq}ca1D9Z z&%JDC+TQ)G!lA>H<@DS6kSr|^vyHlE0!UvEC6aZWe+>{O5SD(Xc_0xSQzaI2Jw!Dq z|3Eq_p#P>~I7P+;fbcy!^sinY_|1u@3_2M!HRjI^%YI;f5OMv^+~C0O{N5MOL!TU9 zAss8do7GrC3x(UC_}%TL8%o=; zdoAp+J_@BxNlss}uKDh3&lOO5t7Jg2Gv^9@N(@&fbentXjVCL`?!@HZ(hSMo}S#iMOF}=Y2sI zBkqQEL8cy>(W~bA(S^g7(wXJ_JFdPeIlG%}UCyG|T2cPVf+Op-R4A_Hu|V&Ga`%gA zW>^b0nJl@jB10SNsj(ovr{Jh%w(oSa8K9hqCKA6wdT-%1tSVi&p48NHYsck%`tr_t zubM7ev-A*XU>UQhs^E-U)r*cYR~m2S>oO_Yib>y!}N}S0fdZ zR9NsRGWM!_7DM+O3Dk>Ukclk?ST_(xsZ<22a4;ln3l(sbjRuezt+;%q^q zP?`)`?T?Q1T(ufNT6@K*c;T#IcS5=~5mq2ne!xuT-?LQP=X&zKhV7RuWO@{S-s-&S zvLd*{QTX#(Yxy0CrkMz58|u}oc-vmi@&jSc4zgwD_GUAw2XRnFqqqa$(?A6hb@`vR z`>Xx{-u{o5%qfv#vBTOI&r8=&2peW%kP1EK@pKRk^=7b)Dz$QkT>Q^=gCTg0szSm&t|NaZh-+(ghFnzd0T7 zC^f#_Ei1`+i!FX@QrQk~=@f}&=Z%Qkmqygy)Awk=?>m$@v2=Z~8CssJo435?o}2HO8_Z?O_yxY#7UKVor&r z=#bB~ZV0oUZraJBoDP!&108Yms0M4UM0V<72c#^INhy?Y!?74{_AlN;8jdDobeR{| z#g3(}Kud~kS4i_X?YO)Bj*IYpJf?CPUVP3e!&`psn3^vWcbfxrc9j;Vd(wuCkDr9P z1Al*S1`|1i(>WledMr>{Iqv`>kzUDC@0UFT$h+8mlO-NoN*VoN{FS#GKPmW^FlBzK(q5DpoF{hH0tVlX z!*7>xc)1h@Qd9Ylcv5p|CuR%YlQj@m8StJ)c>PhvQt;YV8@D|R~ zk-%u%NSfPp#IA>tn%Khof0bd~r?f#;aylF8=3pt~n!WJ&_E`8K`gr6mD_D`7+s`Q% z9$57%M?&MSM8dh4f3sa%&QjX)cMKz)w{n)bB9pUpe7O~qeJgH~M84zF)!yHjzTIK^ z2_XY&2C6nRl(gAuNL^ZbVVRW?7noNuTn6Dx9C{<~D&vCe;tLg%r%5|MpN`rdyr>S|^ZutJ@ZpD7TRn z7t05#`YTA}!Yy!X&oiiuA|Db8=4DZzR#!JrPIREd5Ng4JvOmLoIfN5+@;gF$Fh%-zH8@K~F3urA`Yg{i z@3X6T*wV|X&F9pN355`~CjYkghftQc6TfuMgaa_31b&?42Ry``D-_TzIGJl$CiQ@{ z=U3=+-+)*IM|*d&m-MnD?C|VQw6gDbgw~LWsUtEA!ow3Lldl~0lbs-UwZue0^yF-f zl5`O9>n48&0oa9|>KZG&^C$m7ak@*xiAkA&ys^$(EXSNTV=uA@RO}|9k2|<%YeSM7 zQ~Z~Vt|nxnf4tf$I&$)yc>~1kxiEN)ag{ph$vzKn?G=eN#?THBw^zn~)5FX?^7$1V84aIG|NR zC~&>hDU+umg;cVrP-47&28@q_i2v6-y590tXK{edbDD~U_s#E>Cc1yuo0Es zWGF54eZ9GGJaQI+^($K#Sjp}Dxn`@ZgmTzw51;7IWDPyh-p{XLO=8N}YWyGsXat5G z;(azI@}6Fj*hzn`+VWITp30pEFK4Hhh!_!dr48rv5go55(OhAB;X6cr9mH+gl$0M^ zcR;5a)tv=k7P_)Fd#-?>g-ms>rO%$wIhWa0sn;+nU~+zMkqEI zUEhtvO;BYD&w$w#i{lU~5^MjwDcoe_W>{JP^)m%0!LKa1<{`2Vj}D6V*&u7jH(o4# zh1iOU&1;AY>N533Ubv%;dE0HovKNaFzjE9j)BqI(^P61Jn^(tn8WSyYPZURY6L)~z zG8`a0^83yExc3CX;^Qmv7tVv3EY zw_i8k7yPl?Q1ox%+;t!&zEFfaLo_Q4Fp(0GL?_Ie5#JERhyT_fM$`=3>0L|*K;V3r zC|fz{7iS2En`r=7@|4xuCVT*HYHTlBJTl%58Hw8V?^%O6f?gj4&Zp8w_Dtx41e>F0 zd~SwK_k{eE)kMv`LYc_S>zF31hPPes0gmcJwS#gfbs1|{MPTxOz-wA`-3y-|y;+-l zr->`}Ums~Ygh?rxh~|4v2^^t~D~S*00=$V!c89)APP<}ZHYAUSM3>JvN`XY z>~ zOSaYK`$=a;)-8Mz%B#gVwVq+40+a9RK!P|#zc>4jAHJr1(?11AWd++s*oMG8fnZ1I zPMMs~b~BOfF2T+)=fXh=j8XF5POv+I_EdKomSqYgS{rb`UbKwNmhRep12B63d+1GN zC^29-(g1`#NXd`6N7?+{fHL-1J?5{BI8J&NQj_f-r94sLvx}S;QPCdaNzur`(b^WC z`-};{;);fme^{0B90&#mdCFq&zAlz(k{n(aW{!rzTRRI$BA4UwAzNPVV2pD+n;znt zA=J3Yj-WWxahCa2U@i#(}*@@WZ;1;o@hLr&kt}xS%p;GYK4uhW-LyG`0?JIceD6 z8XZQkqaTzk+*7pns|7PcJR3~zXv}hI4>;M~LU&vlqdxs?oAvd`S$4w<2FR%iCRW=Q zL4b}}i!+TwK`q)hn19b)h=^?$V3ARVuJ%HMGJ%V_{`<=M@mJN<6JsCr+8MO@waLFv zrf5F@jh{Ku1%0lWf}%65i`Cq`?gO=?;42J8(FWQY=#kViCCIO7!{e&8xx)z;2vB?t zM&PDqx>G0^m)s?E#h}>&C2^=P3rk~1sFIz)eB-S&<7?-SWgq+fOhy%=Zy2<8-s*4^U5{mq=dG=yTI?u}IvKwl@J`}f z7XfMdAoF{{*{Jce%U?kdUXC5btHPF^7YZ@M)0gMZ8&04c*VmuJM9W}UCuN2#Pcx`T=t_j!=^%|zYWLB=W>YnO$;Z3zXl_n4my!q?) zI{)WX!Vf@H=U@9IW1>>=2VIy&knD}^*FeoYK%aIrwpPc+Xjm<~JopmZCt+PmMh19R0lmyTH*3j32#vX`bau_Hv_S2whRGee*G z#Md+fe-HIsvNZsTGKRh$84j8>R47rg8V@odz^nx@4On!G&_qFHhmW~EL>gtPn#$)i zujOnaZPUr7Nj1(Wz%lS)c@&K)3x`90Xe!8|_jzy%Qb1nm6~yF%E9fCaj!hV`G8Kfd zV}A+THL7iioHnnxDEYUBf8&G7v9w=;f;N~p_|AB-82w;(jP9PK3+hEJ%FE1Mx)UEcT0B_#y)|4_CFq zUnQ(3b1f&!5T|vYf+$0XSm?+VL%;oW`5yPol@r(DNs#~;GeDV-@3^9EFu29(Mk8PL zfRh1YQ%z^B`_Wz41Z?y@A_q1j>21h;eLy%kZV&P+)JVO$wTXdj%bGAC?sp;H*xzS8 zoW2kHIRZmFlW>TvTO9JA1tfVW^O{u%7J>+1y6citUicHZ0uDNKZk$hRAUVpk-1UMI zi}5Uylb9_ruKG*qU$CH+xVCTt_}RrM9&g^Bx(D`1x`VdO6WR+lEhQfGdZzvxxBFi- zl>Fof?FOks^iJP4;d%}xh1awh&`$IoGrR6GZ+Qh&QAO^L9{UzIg0O?!Af|K}tp)JK zm7g|TN#_kc4Pkx;+uo#JvW8>5ep_idZ(QsgCK;zcpSEyo(-6h~*~H!ANTMx}jkNSB zE&9AYzG^^8{(-P96|LJ-)7+eMc8poJ8BPlw#~j)=&*FLhIpm2e7%5@?DVm1tP7e)< z;$R=sYEiKn^gCqwe%mnZd>FV=in8O1f@HUVH&hbW0!6a0+js|u!hf#mSnU+m-+1eM zmwem=aBR-2Ei&M={Mcz7*l`^Rt*d6QTRqK3o&fIq}Ck68Ls?$>lS0_6i5)8sVr{)<-&Ag}mah2+x z=FCGF&_ljgh+9f@Vh1{Xhz>Pdebf!u$4ge zX! ziu%G@+>^88M^zrjp@)?NaAYJVVKV(0d%S3th@!OIKFCI}%`p29FZXSWj6y3Jk2;fC zuJ~LgjYUa-$%aqT_}rYBmB^K+p`yUVT3aLUATcRtMDt8Ew1qA6qO-^+Bee#2ewY#} zO2$GR``favZkwz4Nawwd0CX#KQa@tUo$TQLOmga{aa~=o+}O2pyFb9l4ks zPhhpDo_@v0`XC%jQiC4{a|g06cSh;sO&n@#MUU8;z4aVsx&>~d2q^()G-|MLy+4kV zL}=s#_0VOX$H}upX68i`Hp&_4GpF_frO$qz3rvlf26O%}4^rG?4w0xftZ~9*gtt!r z2*|MnH-dU8NfIn!)XuY3!^_VVfKZg#NzOd+LJi|IwR_m9+yn*+u+yGnCc=MZ%9%^2 zA%VQI_fIN&Q?5Jd`_MP0k0&If26R_f^FQi9d+I)4SMFlnq7?&v!+|w83o|ATZKhJO zsmOf#{55{N=rFB26*fa!2FeGfg_GQX!uWN>K(9vR9B(?nIj)r}xb;HD_cJQ(#9%*G zEApZK@HXaGLY;9G^eUy%8NY>4G2eRz-Js~95brPGT8t)>_daA%mZ4a!pBAH-a1=Nx zcJ5brhtt6kK@6}>1fP76^U#9%BPTzJ+CrK5%>vAexX(cO>DulzD54fZAp)`uu{YY< zJULTowHsgeHFBL7YAA9Q-Kp)FxbL19pWE0%?cjOV(nJ+zW!!k(|$yewO*Gr2XPd>F1Cikl&-oI2!9+` zoeRdv{GIKNBQIH|7osdd_03hUmWn5;s@j96?+*K$JFmXGJm2jNwe+RBni!miC^W%X z(;Vbz?MbGv3@b+@rH|F3ZFNUTatStZrXX`A-IOb3H6_)sh&n9J1qiRfL}CV@W&Ae_ z?ti&rV9{UQsnfrdI=_p|b%W?z7}w+=0OE49>cJs$)FK1Z`@9!j8iSe(QVB9OfDyB3 zVZh4(o1N6`9OtKa6ekmjzR5}}-FNr@w>ZzggV+9kiVJ}=&V<>4I&s0s+AQrb9_6O; zU!g#3ms1bj>-I?7x;38AdJ}hWXyfe`B}3 zKk&TqLx!llWUXM9uQz^$rZBj4txNFj<|~+Thutj65w_&Q;za*Zj^sbzYJzb##IV~R zwqfD?C=Q8p@o-paY@W`x&;nCf43ZtDEH*sI#=(QLz5Tx|fY6QtGk-Z%g}!^*^t*re zF#booVBG}4#Y>#Bho|jz85qIDm|iq26+}*gr{V*_Mu_0yZ6F;+3KXWthPV71yZX<@ z{7VZ9sDf{4$G;Svoy&`mXlqrhRhv}Cc&N<4%v{Ba41d|_|HBtKLvT+ah}ZWu7L{hY zP3-}yc##OfvzV0zr?9L`NaqE~_|^B%!lZLVJ!5}`dH=(W?aUCJh&Pn2C{VL51m%na zjTIHX&fI-0lF$+Qm0wa|T8gU@@IQPFcCBt?`JgnZ^995T0xv2+&v@j{=p`lc6Rs04 zPA*xwCpTi>E=-hxN$j2eKi?Ua278=E%R;H}6#!tNhGb*O7_PhVV({gU{C}lQ{`JBC zGtLX$s2if)i$NDb3bbB!Ap}?f9}!UcCBfmFPQozT9zY;~@LwTl|1!uJ0tjbU(M3uH z>1WWP$csGxkG)tC+TdVvT>Ja4l(1f^B))I^fA06sWHt$-4T9!A)rC!T#}EIj^8dRI{YOh0ZG*FbjX{}eZK5Tf=(Cjk@oV#~Y0F)+BIeMU6U1?CSPbV`m5SM3%iX=R=eFwY$x@-l z_!6Xv@lpRS&v=uOTcE#Jv!Awmd#5>ucI4I0kGC1w{JM*(#yL+;=kisX zyItb$RIJs@ZuSp%CXf7P?dBz8S|g5avr`z!os8b|jpMt=j~zQnYh;#7e2bYc_oupA zLNYYQESWp@qjodPw^w2wdKFt;omXVHZQfc8RgT~J-JY*Jc;RXV!W`obGhXSckkG}{ zlHvomK1z%VIqj2s;uwh+6WQ#Od=NVW`ga-}kp{4dT*L@I)x_I9x}mbk(?{u~$?|SH zdU?85QkS=8n=~Dvpz&4M02e>fp8vpN*&;)Rd}NR*L`FM5s3z1w$9_KLe=#4`=5#UG z=E2X$yn`w=3T9fvzydVjr1%;H0HrZ2nb=+1z#0u?^r8`lxBYa zOf-Oe!DVizKv}a7`5^SWS)sV@o) zXc7?}&*Rjvr{vsj*$~j6ACEQv=~eG6sK=!!$Kitl++lv#C+w@lac@pkN(y0gqVrbX zqIbwXs{PE4MU)jC;N{B6s9_;f0rj@X-*x7EuFaiN$_Asd9|X+1yR_Ra*YnVfaNZ<6 z0DsExEv9xgy$$RxwEr3jIVL^oHj z;=hoim2Q>@GtlY>=b9Z1Gxe(an9&-0K2yuL143ictlNBvic!nyRmf+G`wG7o+I6}I+H4i^-b2PO#)`POwImMXb{%g$A67$A?cUG zhb5bz#m64-TWwn>^^fuCkGZ{Y9+*z0fkqf{iuVQV~Z++gKr+# z!hQ+0{)cAc-!eNAnuyiGnZtdl8uO+sC z3Q3BlKT3&-IVomj>bdL(?@@aEko<>fjcO`r1#Ua4KwwV!g#!u?L&~|77^jXOP(iaj z%Ww?meINc_eteeC`gd;pf%j?2=1Qp_`-ZbAz|#C6ClzwH zTPuvGFlSamIO8~H3J~5+EuOpNKFiY<8d9qtP3Y?rQsb?e^?9Ofi%N)D0iYFcsy4l5 zpXcf6DN)=5;jt{(CL)*}J~vVV8Dvq+tbxdaR8)zIx{Ay&oxupo$<@Uvhrc6YGa^4% z&En;PpupAjRjbw2$0e=cF)FK1rJS8V7Zt%=8^hubD_$dWROf2xqI#_f#`_$G_%51z zTu|X8%hTT+(4lzEmD@T4_u{n;O1JEh%n?5lBJqaka|M&nZu+T3y;_-8307H4=B)O3 z?wTqOsmVoOuuV284o;`IOfw(`5!|@np!A~)X!>tcc{!`yjpjyd83a8l_Xnrb-s`oS zIXCq5M<==Q%h#1U(p2Bhqz+GT?Z{^YmATmbu$iy!oJq|2%og}d3!^(Lwr78)m;F9& zoWb3M!o250Iw;8iLDO=$I^=%V@?+NmPJ~Zr*Rtf*pCrFW8Zz?=3rLwbGW$~M4LVU# zoWk>d{4f1>dLp9NAHST@U`;VOO<$F%4vR`%o*rpF?bqWC#;2ifg|eQW-~}$J*pt~8 zU%u^1e-rrfMXtw|^^TqgnJBG$G}T&voU#qaa7R(pT<17O7FnA>W0_(MHlnMFANPM( zB%wH88Mu^UO-^Yy@c8Fb-CZh(CWIUklL#Cg%n$!L6Jf70RlZ6qiZw!y8dP$C*;>it zGlsoN?L(jS+T5%!571s`aj8Es6nS5!%B+S9M*b_&tl7jaLyiX78AAu#n&q@!aL{Vw#VU3dL}QvHejp3WRm@mKKuL4(7+7XA=!o7RzR zj7rY^?&lO9=PkszvNyE)MuZ$b3~mGT2i>(_-YqHW=L`m4c5cUX0>oeC$v}0#l(BQg zmtsyKDe+P!q@D3wpA+Us%yTzRg_Lrn!;1AT3L`?WNu&cqV{5cqrw~4N%~V12DZePW zBRL)h8H{b3{3MT(milAGG9sqR3mxP+(P{?(e)?aE?Y2((=f_SCH1&|Z`Ffix!?-EC zp2rcdFad&3i|McHL~$BE!Qb5u*A1Y6V{pU#BjWHZM5F_?iFX~ zCP2$`(#1}#kGDwKjJXp_w^Tizd76)LrEq|7<9;tltnk3hw@WZWqC$JV=KyRP=oz1Uvv=j~&VvmG>NG2Vp-|h47 zVwz!QB!j;(^$Wr&6v?TR`o~_rOClCYdHMX4>Q}}cUgujQK_x=_@lPVJqUO0e^Py31 z7v|?svzaWChWg0t-s??wabB)*oAT)GsHW$NS2P*5$v$Oq$x~_MaRpBIz9#XH`Bv~U zW5h+7&!I&^9XpAe5CEV!Cb5q>VmzRHlXRi6$?x<^+qC3u$u323h1k`1|KPhpAjf4p zq^jv_9gJHZHJw7_vmMnG<^0y6oCTVGJ6VFC+rq5iZegr68!UYsnZ3kZ3#o_F22 z-)HKii&a!{l%V4RrwP*9J~D~G#BiYevCxoA@x)?xP-K3#75-YqHD?eadyrcTokT)> zw?Lwl$F!-`ksIfBlMP;Rif9cPt+3=H^;M$ypfRkr`b(k)N>Aq@eoyVz>=l;HOrf=` zcc;bZ{)#oDIz3Hxh+HXAX*M$dCG0!f{WCbbM6`#_PWDz?S;oxtc~EP_|k5`suSFk+TY~18p0{V=fNRjFR2+`_OFPdRJqjF>{!VN_D0?4a8rIxGp(Ce2eI7@!*5S@+Wk`_;F5HtTo6C zzM!8OP(B zc+p>g$6>Oa_w4vQE`)lVq2JG=$F~h-J|m z9Cl1rRIj9Wa!a|IHYmWvJ3}VDi}eO|PE)PPyu#VtyS+tQjG`^w_>TB1g0trNj1416 zjA_y3C=onFR=;whJB*dWO|k8AlfpQ-5JYZNG4$15^EkPc&CkmE;-O_E-2D zIF6r}dXc6S27l*UR2~i{FH)%@gE&Z@wnDWD>>wiSx4@6RL@VWqmFRG@o?jSaM%v&C zsMrf74&wtr*SW@;MB8vcub^y>mCqlFaI8%j%0waGlf0Dax9Y+V+Xe{rg(Nw-BEkwlq|*bClr%2-pS`3O!3lCjZ)|;qoBJT%94G- zfj>s&P&_~ZS>Gf0#I#IWzDJQTW8`f5T%{ghW@=FIFgTfdIck+;KE*^_-@pM4f0oVA zSIMA#Ds(Ov9G6L}D6FcNb8d8cR~~47VwYQ;yB#GXNslik&iW>#?xS#|3-K~c1!uUw zOJwXtbKM{Ww8_5|I`6tatT-$dB(L}r>e!G{6H;3j+SMcV+zhaQD@J5Rhm%hUn7oexo28C*i|FRQFOs4_70EdGWj~RI9lW2;8tS~6Cs?5GmsIFdNp2wmG`3}%b zoHM+hQc2l_85ATIJf)z?l@>SSwdykZJs*RemD%_C@h%Z~I9ErKJU*cOOTm??g=bIQ z)9tmKDbM7~K_sFNIWXJJt`=69iIKh6$mc*VZh6|dX+)!%ouqzwo%VJM|vuJOqqUo5m+bC@%oHzG-o7g9A!EOs=IS@b(27)E3?g@3m+S?B|%S zBbl@DKxT!^>u6kmQHXv_W7Y?<-M+`VhdTfv{YJWHX;K{ca#snd`N_W=#%{pui)u*x zr1ALMi$Gi>Uf8G%-3M(fuiz;|=A%Kf^$KpsT!|)!PL)hh5}YBADnCM9!Jggnw1Tul zdbz`JoC==m+W{_#US!hq!K_MG&XU$CorOou<_uEqj(Z3TQl>MK#Y%3OeRmd$>g>3r z#XT8!^}egAK&b(QJ{xl}qrgC1fO=m7Cm54B_{TBN;G4il&F|4)sRl>ZHrr4s#`$pD zvSq!rC8sd8;s<}e2Qmxo0}!nehrGhaiwp@+e#)AL#Z7;Y-%7B}s`-+ug@SH;WS)$` zk1r6!7!>_n4y`^f5UqiO`T#T(gokz`sq9JlqapHLl1h3>MMRU>P;$fd7Mr9NbQktEjD*c>W7D;grk*K?V{20)Ycvy4j=RBlmo{$+^9{$x& z&_demq$lXJMUV;3$DL}QST0YNRvhyLPA@JuyKa*j&IJ-wE$?YsEo*h18k1Ob<&oEq zMNuSv&Za~zWd;LzExl16NHlz{3Xe8IX+mmcTZdz(`Mxn@CsT8)Q*Du)HvY7IDn+fy zXC^*nWf0q$CbpF}mkQy?;)Mf(sp3{WqH!{IW73%)XW&Q9ae~OSDb3pA&<(K?Rj^w<8>#xL5?|8Fk zsgi$&@76in2z!`8(CsV2RO+;jxhZ8bYM*)fgD2 z62{hJFrxP~isY$7;oowgrOfSb$dr^@R$!Ch_DA2;I3KVmUS^7YEfkQ>m;te8)6 zwGl6(ZjcT}9lmQ!D--Lj!K2FhE=Y=6$*Wu1rp_*}A$Z#lc)k>ocF%I#My8*|^rru0 zH-<>=2~8eEgDQrUP6UbSvSZ#csjYEO6IOI-s?Ji)jwtCnC93`~X;*k?sfy8*Ws7=! zg+1O`N*^b3Gp5$hW*9?<)5<_q_wh}magzFhZ6c%^a8Kgps+>~@9+PW~|D}Offfpv^ zgKlU^C!AIMB|O%DDZ!_1N@pV)5YkSZ>kLm;EzjH}kDa-5X`(&If& z6(sjyVwr)2H3UW^{oAfl_Ig3F;Bu5!oL|JTohmPcRc{f_oN^1G!2(MLym?SLybH<& z1u<4{vpBqaPqKuz;{2gWlb1xwi1|nlRtupuJk0CbZ3(yShS|syN5ioAlRQ*`DjCWat#Za0{VzqR!}~PxWyIN z7kgc_S_{4ZteV=VT)~`+fE4Obrli_vr0ViA;)teb;+r4|M;~2Akg|cy17l#kmu%laIk7 z+*%p_`T6<3W$lI2>5MmE1c57y6pL(;NhL=P=tt-6k4e}$zpnH~U9g0vm1!pOt?H&&-3ZsigaYlMvpz-z9Thnie4Rfq|c-Tf{%U z@^rV)8JRPOsj6olcig}#cQ4kD!f2lO$1nm^RCr(!#<|8FoiB~Lq2(rv$rP1sBq7t* zf)lSv@v7^(;m$dXH@M>WbhVSG@5rI)KH)IG>cOJf{PjcAWOrPVJTpEYgxk8nCW@s% zm@mR7mz7I{p1H!Ad%Lx?Z`fpV{qCV+lz>A_$Kvg1Fbb8rM>bczUHx&Bu;y|FkX5fR zTK)0&HvPA)z5$FR+H9vOX_b#}BSh4*x&|qzcUB!9tak_~UJiR>Apl_s_rX8rX&u+o zNYQ`Zjy~{O$ByLB_ZN@QvKu722fzc07s$mqMrhMpmB2IZRcqvof_s2RPWKJ z)hWM_Jr9R-kyXG+!&?Pu2+Ve=0i0slb}*A3spEB4@J_|jj5VH1(aV6z+sfbZ`Jm7kL^wKlcyW(uZI~` zF~R5v-Id>N4wIu?5$EV)Ll=YA~iYQHZ zCnJb%#BxhIcnuUw&+7kRLFM$|!fzq=*&Qi?u%#Ip{lQ-+SpsLf%4RgK2bgY{;ODjU zG0QvQ3y|Rfo(wOU&8FXA7eocbY)~$LDW$%3Xaq>na`nu+T2jYNoq~Da?)N!s2 zjM=dm2GI}z8Ey>zAXW5GtZ}T`YnT@klBSj|KO%x|BbJ zQ~VoJIe>{XZm<=P7qy@Z4+(4H)K59qx|yn^{xo#h>13Md(e-|pLHf(KaFjQAZi=BpYe?^s;*3H-&$HXTr$s&Kq2g2i!`IXz ziHF{tQ9glHmOn-9CvhdIVmAu~tQlRomlvqvAaceIhD$0jBR+@MNvTURUNo*;?aeMDb&-W(q{Bk$8eTgcBXG5zJUk`AFuvSR`u+6n>j&9t8Z1 zp?}OgUcdE2l%h(Qnvp%tfACxc$=%`4>>I1y zp!uaScr3Z8qf@*d`Rq{*-1}urIjk?fiv%tXsprj(Vq$+(*{1vkbw4OzwF1MF2j8Uk z#qd*8P=p4n`0$yy4;hOBh<4&4QW=MSR$9*pI! z2R(?NH_)Nf8S_;YuRW@`gU;$0zu}O0`TPqL1qGUNXJ1D?e5On8FL&H4D!J@z8a0lM zl5$$|Q@8czaYil0TVVB*1OCau(pvc)aOgn9)_kXzS>!%u3rzzX9(o`21K^xBJv3NG zehJTlMb&=u&E@y%O`2tjM_3cxx<{&8+`aNp89p+LkI~+x$ZjODh>hbt>f@HQ;#1}s zslVd+jQ&gI9ZY}6dlOsT;2?CBPWRbiz_cYui($-t>s?K0tA3V`qUCz@+8y{I}8kcCcp)*B#sQj1cZ{)3N5^5wSOd*`L9z0R)W)^%L8UO7c2 zXsp4~{eC{+Lt{*osNw(`icFR(d6rN~%)%SN{Raqzj^U>&U!!}S-2*PmM{~jc&suqx z#4LUXbOsB3F&5~^F|o0BCj?3&c{dq>*6Z^|8OGmy4@X>ncesx7ybrt~Q)B&c(rWq3 zIr>&UFfB}7XK}*z<9vp+4-=2^T1eD=;%-wLEBNnlC6}?puMrMBcpY1>k`-gmlybD6OWZGRQ09$@!e6e)z#PlRH68c9hOOlD3SZI* z1d`1alugtYDKZvkJ+wt|)X10~J z9kS;qWY z-jbOp>%@O2>fY~szjZN@#zg<1H7yXOhkCny|^kyqmvhIQt->aEba1q0X8wV|d{*L8TV*B>=LP?|4&WRv^C6^%#D zt}3gq!(+8!qHbM)GHGUG%%y2LZ=`7?NUAG6em+I!(AjF>d37>c#bcS=akJcfM1%C> zslj^6nmOlPIF=Gq{?t~loG&BI?Tq(<8*6Lv>x)?p68h!nA*Bmr_B11p4708-a?kS- zbC^^y77gtayX0rui?GU-j$pLUxsu+*Q`lnXigyEY5^rWa7V@&(&fl3Uym3T^w?<@q zXQoia>0wS>H-uxkC9jH%rn}*_nT3X5R4++%R?T=$Wl#9z zsZt^f62)`9i6zQ2y8Vzu@DwqE0t_F)jO-b;nNffd^F+@lL%&MqFr)kwYA1Ic<1!~B zA*f|l@zS(RCU}p>+A@hkQxly_d;0O(8cmezbWmi%@Y@jIn{}TVm7NUl__Q}$-V2Ee zsZTen980tBxzB@Iy<+V#FFld|6!K``*>3(|Ym46y?nvMvw=OMt?b5Iq zJ=0#AauClv2z?bLvBIVC=tHpqViXvi?4J95%Nhfv=C=f{%Vp!2Pw#z9h3cj6}D%`iKYPT&|e~;sAl>N|J3|n47p<+%m@_U!jIwAg-wiau? zqueGKTuSG8&t=q&(8{GAjeYd71gj#Q*@P5}vuI{LCvfx51*X7EA*<>r&$_O1g}^+b zq)++A6TegwJbB461@X604H><)LIh=1q#dW!NQPw393pl;rPSzp5*X>-e#+?Dm_5IA zok(7G=qLjDyE}U?>rcFW_#;%$8lY7N(SR7*a(*_r`R&hoZiV^+L8k!FA8t|@6pDNl z_;x0z&{2FZe!UOe>1n;Ob@|bJz2&Bv6MU1*zL$rZG!WA#xRSTocE*K~wS>R-9f zS=yJbepd*CGuQ6~KkTJSRICHd{`hvo=b`Jq0<}-(DiNzSIA>K%;P#6{VqlclMuB6c zm-rp%r{l9Iv#z_{Ot-|V_lw?p2Rj=8?6>vXxxKft&6C{N5=gUMe;qJI+Z+Y z{F+t5P>avynfH#RL?<(Q)S6#gR_!ob)(H0cBvr4l>YIX4nSJ6$5wEG2p0I#!-J*#Z z)yqr~zQD)B5cE;BHgyRpXfy$^5p$q6Cfv%FGC8g_xb*;u#C41cd-bNoW!!gN6H916 zm)LTjn*DzNhhVnz%EA=sliIQ5k8YGZAm2BuG8Rv&k(aUhiTBu}t&D4$#r8x`e_2x4 ztFlHl?xz|i-xYI`R1Llt2TWOVd)1=til0gv)O4MW)teh%4HbZe>y&4ZB;9*$`V-XB zBS2eGs>r@xQv!ZcVPjL4B>KXPxpc5{d{{!{-&plau_;&qJ}*z#@w1A=EtL-Sk4+rq zpsiKhwY}4V7nzBlsAerUoez-Nv=>!>Gth2)$7p9=hR1;*DRK4X#U#p?oQ?+^|I98( z{ah&U9{Ymw0&l#G%%QDz<@TWhvW7ybdyVVp@YcQpy*fScmpESovu8f?q6V!iJWEF)+l&<)Ll zQJp02Hj&Jm^>{{M%#csT2etG|xJe$YP!y8Jy>4AzfTtX}!XaW6gFlv?!w=~A`49A$ zlC00bGg%=EeavKt17*QE5{-z1)YIH>y5gEBD( zrPn-^tE;Oy6dJ_$Pf)oE#(qMmU2J>Ov<4Nm925#|;VzcU8@j4wR4a@YS8!0eO&)Q> z*nQ~|y_A~9sJ@J{zxRzysesx~QCzbn+&zg32GI&?=jrTqD;__p90TrHgt$x6p0Gu8 z$6#o)njx?DSTdzE)bK-+76e(Q1ka+}i*EGy_dnd0M!!l_-S<&JzRw%$fPMPV%&8Xn zX50YDty<3d%%?;|q#c@^K8>~f7$EioaV6$0b`^)|$wd8d}AHB*~5(jaP z7@2UbEmjst24mLwD86Q~x!H;z?NTHT<-C`Me>b7bNc_y!XNT2q8x2+%f5X(diD|AM zH~Tf#S@&4Ojb=xd>I3}gsl4}s^=!m1y27?Ql;UAEiLT@8u-E4r*T8M za(ESQMHYS$$Wmm=4fA%EOkbZn2vgjPK#7`2u@?ljD|ebIWu`tYzSeBG^NCh2Ismd1lO$l zEUj9(A`PH}hGFDZKoC0YA*f*{m5_Q!?Od8*49bhL6rdc9X(FyPzQFyWEeb0Y+g=QoS6+D~bp%MUDLNLqcFnP`4nzZ<_C21@QBEN&c zQ&<3V;D!<%>Gz(D9?bp?VPd%oM*GJRsiVh^rGo?lwh~2Gu`ObBVE{_P{V zQ{tTe_LcDEHes|VKq$-GG35cerTCy9QyHsK#-F3ujvlU!EQxzj%43Mot8gyUCmxm| zteyi#;J5t>Rnra)BvE8OtdDzb+hOGM+!yres!vu#Uk)BT1VeFX>eH)F;6P)=GQ>|V zARCHN52XeEfmgUgn3w2N+&K6393vykSFcJN*M649j2)APW8i9_YbZLRQ}icL@?E1* zV?Qgl+`m~Nt7QCLIP&qG--mHV-+bpC9EeM4{zLOp89_k}VCg*@f7U_E(QMMcIEb=T zL?xUXan~7+1(={yso8fll6PW6FMao&R0&>Y&zhCGlj$L!S-wq`_lwa`d0e<+)Iu7e zJwb!kV;|6l9HnL?5xO(5ww?gex{aTwg-<+2aB5O1(7;G=5ooxR(STC358?nnG{ldD zLbFgl$Tn^hj!PF=SnAZ7hIIJYk+gBs#?<7}we-}Y$I{4(!Rh)%Msx`@v@{hQ9&(zL z5&qk(=|FFCjY4RHDAPo=@Ej90m`$g>Z-J7_wKY8hqrvhP;mcH7)Cc$+LR|< z2wvm&HP7W6&)Klc$7ptd4TV6VRN9((j<5=m?N)7B=dzk8?Hl ztvKc$ZIDi^TMeKgB%PaaBL4SatgK$MI-MtTqJQ81>7H>D(y+?Gu?~ukoirJ;jQ6wQ zNnMt04U`{f56}fT(}2&rUWGw{jX1lXLi63b_ejGCmJS^@H1#H+A+3btWoZF>)*DEw z;4f*%_Dd%e7qn!Z(wFsgVDu&e)yUsnjMz;km^pOF5K<$1rS^=@s*|!T1Sh;7#vFB7 zrY-QV=O~=}mYoCfT%vC2`rx5z^vA0a0C;%8g47qdg)67E-z_8PS^B1I?+b4sW4tDo zxD@>$pUGq47yme#}zPF3?~v;8w2rT^$#=qe|(=><8hNZq!Z3G2{**hj$VvX@~5Z zKYv~-$L6qaBG6F44E)8{jO$)`0%psO`dPmw22xVm$_VVoWSF+3F0)8R5D*xEjE9gjzw&PMFE3h# za#&am{>eA$Lg5UV!Efowk9~H5eqFV8OfG?1WRtRsTnw(sL;1b4ph zpZ}};(Q(v3e~&=*31rR#I7Sua6$IQngyUe}#=r&b&|YaFJ~PMshO{0d7h%7Y={NnI~*>cJRnJAP9c2raJ9r z`tyMU`%@oivj+4E*`HL^oe#$r4 zITm|t@}x;I@N=0Aq$V`Hx$p=t2#J4zYv2S2g6${dBi}4vUe!^TP7MmKfF8d>-t+_Z ziDZ}#!)DSZjf@F(5(S7Cq)VLr9^WXx82q#!99;6Av}2$_eYSq{ru4x(@21`a8b%Qy zF&NMb887eav;t6+C0HJ%Q{X;Bp05WCKFdd38VGMd=Y6>RleA&o=V?0j%!pyb!?$Tq z05a^c5i?YSub&bcTP9`z7c_JexsP;G5`AAYhw9)jNcGN`0tk109OpKpZDwjRnU zj-YM};!?B@JbB-~FL>PcZ^!0%~L*e+IR3^I)sl`b@b0(y z07rJi-}CTIKiS{7TZl9yVmykO83r;0L+|jP zPyB-zcrE5H+fh(JD9@-1V&^RRJDSy!K!b}+uKaXuTE6U~R9;z`MlcFnSy360If*Nn zojPo$L?l5dn1jHm(?cQ-LRP3igkc=>-AMTfoQpScTn=DZ%$_qR1e7WKZ7_l(dQKTO zwfF=+qEt}h#lPi{(R4ibAOwH$i(fBS>v`NO5nIj_tfCEn@{06wdtpd}*R`6T4Wh#uU zOJ+YuRIZMQ-x?h1>ObpY;tc`)627nvkGflEkmc?0Ih-3TR&anT&F>{#4-_)TY z*MZc!b2z0REc-aEH4DZ72?p)}vX6{Jo5CzVwFJf{t`EQ(1-D|CmmE}x=_TTX@}&do z6Zi6zFqrygl=$V>Ur!g#oJ|iuyf9S^8WamGDfmOl*oO*m-j~)rEUTau;g%1m5#fy_ zV2zFl6i}yWklS&j-+J>60*)in+}X2Jk8a(=A(Og%uLv4hhjg8dHAi%_f^)qW`!?`S zp8$B&Z{}13BO>ciYM-uKn;v=ki8S@z$vg``+{tLr7!qb_PXi^xZ$C$%K|JIZW!Xq~ zv}n}=opL=LKUtsl*Bnd+?wVe{o}OLuL>fAHDDo4hm0&FhpjbZq2T|!ZQ!Z|kP16*3 zX&~2f$&5 z`G@|C>(=i*{-gYw@@b9&R{qqH6|^2c-Amcxb>@9JsM(G{!!-hH8bm^;?6xoC;H=>$ z&&Epfwu6TvOGw$oJ*OTR7}QvKk6^D;waUvY(zMA_(nvFe;1}uLI-}gE#6P+HVUWi6 zz((}7_pI0Fb@t`kwHR?968!4Zw{IGYvpX7o>O*kTjDrXo@T_&n`|?<9_RSo>cmCq+Y&-?)wsldM@&P_^_b_mAhf2ni&8b1?dxQz4o`M3V@X&oc8hnSXu zLt2k9x0Y;=ZRn`yUU(r*9zP-A73X0HA|r)I*%<2p&>!j_Wu!)-bt}u18|o(U;pY-T z%z7NsgH=^&Gl9W2EG)cu@!~YNtUTH#E<|$3U*V00$eXq!_d}e$S32Sm0}ZVSR1;{} z1x@Y(H^*vg)1-T+riXC6oUVBu8DXli8C1n6tbHhq9)T(T_)D29+h#|SsY1NtbeI~- z{Ot43QcX=&1R5q0pc;q%XopR3H=`kni$6ulg$T&Mb7k?J`mH#xn%^V>)l1)gJGDbs zjY4OS=3_9~X-M`<*c8$TI2K;Zu+L2U^{fLVtjc-mr{KM|1TqXXe7tf+TK4X{X%Yh) zFQ6?_T)Tzjfg4_ah7pEdAj9bQ;=u5PnjBgx)RDyF3#x z!&l)zP@?+5>-K?iU4B(=8+cLvs~21^L0Pby!G|~Acs=zSFfayw`e5t1UVyoCFcETG zStg7bQY*{9I9qY!rT}x)%VkGj&!F?Zz;Ri}2=#*t7o{2Wt2Um2G)GvqIpjIB1Y*Hw z0!zvV@vfB_HQPRIG5AQD_kH1Zz~le}GiFbnA)xX6cfXs)p}Sqj!4Y6pY48ldHU?4J zv;oC6&%&&utBkOp&tYR9tgcEs_UuaAfq&qT!D-1Oj}r9lmoA(=7c$aC@xsQF&M7m> z;jcPeyQbiK9Yk-cXTx3qx5pS%lHT~0LZ)XSG zYvRS4#A8kE;q*4VDjzJEH$MjRB0~(=wUq?W5qxnZ=;Ar*@a!SXK`&sCv-(`z_>8h! zd+e2$UrH09^#yYuOdZg<%J(~iKfEIx`Gby?)`8JBX@^;6^ey$vyB^w;W;TBXZXEbo z&p`8%r=G?xm>lo9o`diC@nzrVThtN3NZO+xpbc(7UHu~7T|dn0%7Y{LAJWYx%D;t; zwq(iUX*h!fPMt9W-$85b4>1%KP>DX3eJ$>#ZRzr=zj?$=xL5!lo;6FQnxNo5rf=6V zO|G`KF4gYXpT7J1|0F&A)KjVTfL?SKd}6_^kUYQ@4Y00n>GA6cG=xP820YuVV&9(C z4#QC1PCD?15c9=`Go-u@O!tl*pN5u|rzUjrHJr*k;^nIlDSzW5jVK-c6bA&UG1hsp za;pFUKmbWZK~y-KCL++IQ478mLJC^fY|t1JH}=0#N`;ArfC8lr&O-~F zqeIozY5DR`QVo6Eku%zvltte8C%fVU~uA&0GW>R$h#wR!mP7pkl_k_ zr2_8MtxL>R-3Z)E-+m_yli|?25&AL|s0vv_R9GX;6W}r{(gNrx3@*;sX`c!dKmsqW zG_29<9OLr@r`~0>YvsG|0rvyZrvnKzbYgV&Dx(Xxp@&u&2~F^vZ{Ki!BaWU9FYm|J zlJu$d$DuPozo?9*xu)R$_>rUOMKXB4I&m^BTC^xtl$AwhhWHHr1Fndm({G_Dz^_N+ z06`dDRzaD~F}_<8a8U_4IeAHFj*8kMS=*S+~6I=!k}yK|;w*TCon5u`o*4 z!FRx7dD5}f2$xd~RQl_nn@`uSA<*!h9B3fe5sHV5hUTDD`Q%}c!OSc>-D~y-GbKtg zLSBPz3G}q-z{mvu>W-84dSGuDTuq2(zwqQUOamJRaiQd)59OF}ghR#iH^4i>Dijz@ z#CIyPQQ+R^44fz%nmKBZF?HY|fd5h$?gSQ`KWc|MBGgAxr=>|rxBLLE&#*lR4A-^kI zr0W>jg70mDJFs|7`s~1J*iC_7hfd?)bz6pjlj)PEHVQQ4`I@#_Fyjwrn-ZUB6yLdK zU;ELq^HJx~N&~BqVQ-Nx?VRQb_e@Mgh+B2(oUTAKFTeR_+O&FgdIV!-#IRw>)yoYAD5LKN8my&gLP(q_D|d?Z)3vrp zd4$}t52WiN&_KOrrmBb2>^)ul>@>r?uB0%#l6o-@0PC-dR)irAb~pq;jIavKFLVYkctX) z9&0qvUjo<|#NxZbu;M7L`CHS*6xbH*aAlyuDTzCn-cVarou&~;UWAd}wiAH{9AKwX zx%O0K@mY(silMLsO_O$ zAeJJ4ubxs*P4YZaKyY;YQ+^zZecBMQ>? z(01$vDjnIBbT2uSQ(iGN;8m@mVp&)KK$ch<+M0c z#-GEEG;?bE?p;GWF@#FI{5rP@5yuIz^!`BICyQDJ$#(Weqe1p+q3X zJ~cZfR`jR*lLQ*fg85>@hLHQSSZn5fc*=p5i`YxI;iu*V8JbeI`b}_^h1x7s0A4a5 z$xB{0$Pigh^szEQhjAH!hGV3t+pqVN-8*hH13$cf5qhUmz9UzZA+}!}L+{GQ2!^Y? z(jeTUmI9f7Q9r(xfk}l!6N(LKvI@DK^hcRI!b-%FIp0R zbCZ;1*!j?O1R4nReug}F2pisMg9aLu)lU1+sh3~%Ym|+aqfXI=5`N`;p=-{P9ig3L zCWi0W&(((yr`O+lGu~MQO&X|nKqz#Zn2xfrRYK-VDw$Xcd)+ePW8HkWZtIBm_`YrT z?)2(QFQqB7W~PM%8rlK(Mf?=Y4;xy#77vs!E|u}NN&a*}Uu!cUuk){rw4L^?!L!r& z0tR_LCvdj}|G+?l?Xukfli>=)X6y=^i%x56yEBt@C=aqfVxR$^5BaOUJd6xBn7jd+ z)NXy^sVCF$!9y6>W(PLPFp%t`>e6@6i|wYYuo-DjUXug*Lf=S3u6?AfYKG}q{KkFo z>h8V!Vk+2iGX0P2W3cug|1drIohMVP0c4dh*hIn1-Gy(OLx8yn63Msn07qcu?|b;B zpUmM<1m7hxM@n0O9Bqngx64)j56ac4wtHdo)Mjbp;FpdsK8w_1X(O!iScW>Dmfrb&ohqG{!(aIJf1l%G{$4em< z8U;9i^^xl+?kPwl?7asMrq^D5HG&uOnL3f@20KRz!NGmsDj3jq$Ve(xjm%(Bp0Ei< z!c|x@uZuFt0HzR`TJ$y}$a7H21{$39VS5!)Dxh%oX^XHIxG0o^iYA0DcnV=g-322% zC-87xZTb|Yc?<{OIV0$!MuTg%3q(1Z{bIf0P}9D6hG%`pwz<7p zkn8^zTdr;M~~+8W6x{IJm%ztMiBO20F_Y$vR9b8667g!;u9jCLH%` zz|oG8vsQc#)l{cXNY$%3NT7i!F|%;kCyW~l-QA8wW~AX*Z8^$?)+5lsD2u|^;1alz zDIDE(0huezaB=?&(&Rh|nRbzv^^1!!XFhaaSsOW#kk=gdjtN9AmZP8emEF>-H0XO0Ab zPFg`3yz80)HpKvpqb54J{*Dn8`jwy1Gs=rH>W>{wzkuFP)E!InQJm!%q3tnHrQ4uq z9u6nm_xbq8v$SD*bwK6m>(G$>+yXk#@U=o|dMl&$uf65qolOKI-OSHdN7}%*cOnQI^~{8vHeg48X&Z046_6s zQl#?BtgOI;@Y9#^u`>IWK6R9?1Hl~^_d8O5jO?cUWJ`ROnxZGa_w+N&Zzj+{Hp6xJ z*kF?Zq9!~WFoOqBa>s~PnW>O(h!?(71-!}vYS6TNUR_;HiuzvW@a{-uWCP5D=KC`0 zqRgL=39N4{OTkyvNlzktLseNM> zn~Nv$W*DP|gJ@st)atxgrlUpnr}Q2?%nO}x)LRq0+p&9BdXr%3c?{^mDEmp{CZ?ek zmFNI=4WVC!J>V3#!dW^jFUv@;3qE~L8zR6&olcGOz129o@4Wm9frbH*(J%r-+Nl%L zQyvY>@8y!=SNKQlm;oSP8RXSi37KZ6P^NU$ni1|xMWBH>>yJJ0L>fUbyr6d-IAww` zMu!F5^lwzeAJ5+NRD5g$eBeT#1_!Db8F`hA1~tVz0@aQ(hSLQvhCJszi}Abd_9*Zm zPiYiN+m3QM!fV^q8`6Y*vyDK53pr1jIWsaET%*Cjlt+LW-~P*gY=-TMU?-1 zvPrhUQ_rA3Cgb#KWSWtn9u}WPu)*uXCO(AUwyRUri8;_9PLRu7H?`J4!~O$|@P4|M z06?eo42J07^70sQw{EbU@to27wYEgN8eR9RwB%xttqBaC#$eyhz=N3>hpVc{Si3(x zJa0h+uFkNw&<*IJwMHfIXWfx$#!f8k3oCb2R!NzIYh((bn+#Uh)Yaxd1M;99{55sP zj0jY>rq3^(#W5mip^o+_ff=1qd@s&Lqoi@`bqyl%X`tbCjDLeh<5-`_QP=_f`$wOg zV}x2cEB%UJ;S75zWJ0}rjHPU|B|2eCMWzh> zC9oy%1OD6+Tl33DZVT|kXDwSXbpl)Ct)=g#Qv@6q5YTksN_ccilr7SXg-XALYzW(h z>$Y9{LwP9t#q?L{$AGFY?uBOFBqOdLdg&qbUoQjIz}rkdh3<8Bg;)B?L6AoMAg+og zL<4yWxTSq%gzL3@L7>-+hKC5UPbV`=9J|Yy`pVS7g6y`bgjMq;fO( zgZ9Yl9!~44VXDv?%07*4_JiO2VNBQ5F*0~0!h>c?0N%m5z%{xSZHs5Kv#Vq68bZ}L zUOV>fNgLO%OM`KCpCMJfAF}2=^4$RlxASJ%pa{eUkAfVU9(b}(>;vVGZIzeIXmH#3 z7SQ|&`qZqlZCkg5ZZV@_2J)sovZmoA13&1%)=jWIHRhy4{wc`<|KLwPauIoN=WF1d zIt>hHW9~nAFs)j-GSw3h@69@2GnoQ57F!kSCgY4i2C_x@=?HbSL#V+^$V_B(@G0fk z2RgaZy#3OFfk=;aOm}?$t+!KIMR{by$xGd^JM1INkbkls6(1b_3ABG5_i;`>^Z=(P%O}!h=nLA9l?ccsBH{h`SI~@oEWFfX!-{~s{G=VXW6z%OKc*7g zS%5v(hBnCuA;Y09UyH#E%PqmIUX-6*a9?{y-jU{gP98Bc*@2%1==}4I8_D)qlNJ*Q zn96h;+oVninFmDvme+;OzA*SGF61xE@_PgtctRRgCiwdh0T=@fo6$`zJGM{Xf!>Ez zR)!7fg2I7sX`XW9D8XLnMzg-86=j}wyullJNgu?i6RxwigMlBj8yc_?PShSvi@*D9 zTJqRqOr02j@d!0rIQAaMDiKbpu5aP#*Ar-v=;U(OX@IzMpaFqzpn>aqw{9hU|ASOt zTbp{IjHWPucX)+{B8-R;ssRp_1#!TV*+>VsMMgtG*fPIDA9e~O^X?iApQp8}SEh0Z z!8IDn%5tC~B4Kp23eoZv$`Y5~HSi?HtVD5`06}I6Bc3`myxL+Yo-xosgnKta(2Ry* zLx+)l&@&XVtK~Y%-P%9{L`7kLXA+Q+bib@!wgoeWpszf!iY9=Kp1?7OVpL& z2MfWV3Xr1SP!=$(%&1~E4bX*TJ|ksX<^RmH&qkm@MQ94UaEny&t2EJgQMlL^>nTS6 zEXzk7J+W*ffsRNOfd(Czo&)+5>3bp;l{))X1Lfz4XbTvyDGZs@8L5tc(WlUkbxJ>> zcqlv1S68{UW+aV8EHSpW)2Anaefs^gBcs6)o-Ojiq%=_;ng_QMD2L)Xfu%{It#c_JD0vv5T{IC^6~u=*jxDuNub)gG(#wg{Pm5(R-LU9Iq?1`6`NAOL!6J1M5LAfEWDa z*{gIU9|Kbuj08#?fprh=6DJ7VVF>NtxjPJ>SxiHkF=cAVp$lZOIpqdaM4&-gBkltS z(7k*M%|oZBHCaFx;P=;=ma&yO7C!Pwq+c4G(GbZ-sPrJGH#&f=XoJ^tt+q$n z3IYhD#St?D4KKa&GP0vZS_nV&r42ycX`F9|~qG@K6Hn;G!T^UtwH!}#D~)9=+^ zclk4@FDkO{Jk*2A727D?D{CxUIpV0*F#?*-&2~ypdt~ra7>bqU<*|ms71l(_CEhJJ z3gu6bPN_5EJ3Zr1d&m*kHXYlAp|};8b&Tr3|I}$SL)LU*)czd76XiiM!kasd66`#V zpnb|J^ppcB$_PL5lcShAb*tB|Avkyt`Oqm%Ba_681_KQjBhZi?h=NE;;Kt88->Iwk zE`3SwX7H$E4K%#<+G~+@F$TRfddwI`G6w|i4aTZ})Yp=shhjl~6*-n;zxczTf{u1u9dTiLARC5K1mCgJeFn| zjHN#!mDASUDu3JO?6WaG-Mn~OHLc{aCGC}XbhPF+yu{8@Q+rA6u-{w$uT&B#hLTo74v~{!%?AHU>*sHO}P7!?UMWA6S zx@i;xlG;U1{kUZSiPv2BO}o#t?f1xKbLN3uz4Bk1^>zf$q#vhKzE6hfK!Q`!yJrIp z+8p+0;4ye6ip+lsoEPUtxVKE-$$u=FUkDbarFvoq+-~IPa7X++ib$ zYuisP1?~G=I*I@*Wt)kioKzOL9?Z+g0{Qq+^wR)>N8--*7XfvBU4B~P9a_m`Bee@F zf5Dm0WS@kd-~s!4=bqi^?Kj?Fdh$#Le&$4`j%&wx2$!-+{tMcp0N?YU@U?8wDs0KC z@PlkDUK~7;mejdA=Q+`JIyCS&N5k`PE`3{%e^{WwR?8@U?AJKw z3mV%^T543Jw3{gIvJXCtIa0m5bx$)`v}4rZp%L+?C!|iTpddPhg-(@>eK*j+cZei# zPI)<_0m3$Q2_d=?rM%*kWvP5H`;amkRZ&q9Dbv0q5os(simoz}xx&D+JVEB137vAe zC%4GF5?yN)=LI6g1{&PLW-fsS7xU^yl-r<%qxWz#?LZ*s!YJ|YcE~JLk`C-=jfS89 zJas1>YQemDEb7-Ym`S5a*klURh6-aL(&Z5T3K6f%fKW6=A&5)xt7Ij6qiO4jwwg-* z(87h;P{d)RuwW*gr^3O{l$?dQEeK%+F09{A7JddA@*Fj{{d8`f84ad-np)&K1V|{H zX5InsF$#sU7d6heQrRm+GSHrYgZ{UjF@l1lt&r2$sl$-izkh%F5~sRX|Nd$5qmQQE zIMdhZ?+~t(skze}q6i01!D2-)w`b83*)Y-(?GP?U1e!ntW~n$LWlHvO4AMzcr=g(jrlw$(BKHLV_i1mlSjLSojQbHe$YswOh>y7F7Ptt=P3dPk3J;pz|_y-EDq$n zy@4nQ%Z$JsuLn-(hk!ZC6*(N>NdxSFFTqdaNr8WubY_kJ z%saqFPemHJjw0_$DAKbL{J@F*?p4}i**UUK${WhfQPz_Ls9d~mJ%NTLPdvpO+bQrq z^T^?&OoNum2Vib;;U!;CFf7Hb`&EsS8Y(DS>N0g~e5DSlI?K@MjfUIl)$5HxhnX!vr|=2S&0pgcc?x!F@E zG5?sU6UygUJPCd();0)Q0nR(lfaOAekS!njh`tp&W;58gyZ7%)D;be;8%;;iCX>N4 z0{vld;#L?Hxvv67;42RMF!wW8xO~?bQrEaR9wUY&8Mzvo@7}Gn801hFgX|S@PyJCC zotEV^A)&K8M_8px9Rq`tL8BU6l-*2ugVEwtucfS~Vn&>c2|IN{S>J*HP{L&R~IbVIKCauMIKE$~_fxIc` zrwB9e$s{)R?^fLs?mQ>O^LrQxELRIKBaQ zzWA&E2A<%j7HkRZ!n1FX%~yA*I?Y4A4}(|TVN9BJq_GHOXxHeddqgmVcKeL&kq@Ln z>4z3ZJ7a_$S?tt_zx>O;!j`N|OCEhB784G>AU{8JwG?p&=|v+NpZOl;dd=_RD(fa~ zrq4G5ZuPIJhFX^xDzO#sG`&>Vb*KgBm6;S{eDPn^PQK$~rLjZ8KnUioh@M52T?bixF@evPQ#rWTXQ>1{@e#08v_}(+kjP`%DOQIIUZ+igK78P8+~RbB3QlC=#0}SI^?c+(HFGL*g-;> z6m=pa3_c(qv}q1jRmFfL(ZKX5xN+L1I@>IEeInl#c6CS$NYRF{U#Uu*2!pal%t?#d zdKhFe9q3DR$JTAzS!nfAEEs)~!J1hQ&SlZ!`KiyKvP^gC0|_H{1Yf?r$FC>QVEaq` z>Q@QHZU5X+!ehsdZL#abQRYZ>MR-gbKM_N5aB4+oxZ{M1Q=;>uptu`oP)OyXgK!iE z)PqPXWi-%fbkrJ*mDMYkhX5Q-#IL-(JQi1!z$6F_3(rQ6v!R2MFA%oD6;1|1M#WQoy2S7GkozmGt}F}4pIpJuS| zp$3b%Hc+Cl@vNjX%5A$SDFlhQ1x!zI2Jpa_BVGmust7PRckIZ~I_B7ROcN(hiU63x zP2~eZgXYa>(0DO$<{UvCG57OA?@01XOd4J~@s5OdUCBX{ejO);`NZ19lCXy}f^ zF5kKG_H|%z=Yys+z>y|tIg~Q+-@r+}!YH#TZ%wH;G8v#t>C6-|S2Tbe0VQPy6v;o@2=1;xYbU;Hh&0BHr0VIIKmO?A*jd5s9;Z#H>~2E~ z(sa`nVfWvm=JJk3KM^kH;IrJNlGp~>Y1 z?xS3bv_H7+?YNN*J2P#lEaZXngSWHAmuciq+ZhKxx$A@(Lau321Ri}Q3@FRaU~?(s zp=8YjpT>fa=nvBk4Qw2s+zrSX=a{-B=RHoHfaXn2*NIRb*?!yX$Fe<&zRbS_-+Rh9 z>g1z7P>$&|nwn}bt-PWlRl-wl-DWY;PV^OLvn?XfV4p&Y>I>VWoXcxBz<1Fw+R3}h zywi+uuf*}H2KN&gaT$W%>qRixt=n`qg}tCM5A_iJwE*LY@osI@2vk|O-*`< zsX_(-9$ENsOox%Cgxi3hG;cbnb?8LeCS_nuE5vB_zI-npoiZW4yT*fXInp@)m`?9`Zb(KzH3w}!!+27 zBl?mb!s1~&3R&RxW=B{HrmE^7`eQe1+jPY#E$uo1FWqr=c~5-AA!19%oomGf&T$+5 zbFOV(qhVLtyL(rx=`(8N=rkSu(USoPgACGwI!Zp)NmZ`v5Xze#VUxh~Qocck2$Im3 z5jcb2T%gU&DKiG!ktH{Qz?!z!A6^(Xf&3l%8Lsx9F9^S_&j;r) zF!&{)alLep->A?!8e zO$0tm^1CsQY+$-e#ir_Dv52K zx9!{!3r;!(b=c@pOz9aH@;I-51b?H3nw0_=QH~7&K9LiF2Fm4;tQ)y5o|GTj%4RmL zT(KgZ#qR5my)kC=SZt;WbT@%aWXo-A7LZiZr^;?|oOPSB)BzvE%Z@%9Y|xf)doxJ%!Di$HbvWN^*FPJ<5WR)d}qXwZo+;l99gV4TKCn;v)iN8Ix<>&> zo6=7UWVgYFSa$n%;`U`y?IQw=XqCXpb2@G?kO8M=!*j@<>^t)1z~Evj{ZM ztKk3zfK(#EM4&x$ zt8jKFrwKS;S^3&mS>Z-Q`6<&`M+6oyl>A=c&-!v(!9Uk+s!>I^Zri?NC-a#Or76>< zvDj86c*%3WG^YIct~e0)))5B<#E6df=;IJFFsay+fzO{Om532uGbRobrFS&s9_HLT z$|&3d5K&X#N086~xgPFmF!+oC105F2_lTb1y2|q`j9yz;m+EkOPg74hPK$<|j)v{j zP>g^BXMY=L2&V#?18YHt3d1lvF!)vG(kg|=REHxh?B~34x14HCV8`h^<>lo;ui=mg zj7pR8Rmu@)pbkwG+ZLk`1{wq%VH0x$IUB^dgyZP~qT2{IxGI1De*GBb?HlQIk@5#z zDt-CHlt8SNk`UC0MDT^PL>nl(*yC3(N7cUlQLZVq?u62%BlG1E&SJn! zo*OrvYYY6yRu!o<2(qD9M^eE(XMY=Ph*1}Q>g2m>xTBafGu;bK+NTD{6z~y1;)c!6 z=maD7t$5;M1T?r8yle4dj2r&5pQL?9cvoOVSK!dyOBB5WII^!ylhuH;te7{)*+ZJl z2B>9;ehob7i3;dzc}m)K%e<2W)^?&C_U_)pLYZ@8VJ1_gbtoc;5K@o#LH-RsIita1 z=@ZIpPLa;>wV$Jp#1Axc6}X-ET?cM<@7+V-;s!y%8EFv4f6#(5hBa?)GomVAMu{3n z^ruJI0^$v%X&@+DY=`a9n9%Ta;Z}nUwHTxQ2UVmgME{jF&NnqE6wh0hJW@Jy5%kMr z;v(O(Oz9>9derB8PDR?ccW*jI9m?pTLx-^~>d@GsK>E{ZQ3gj@c4X-&!MKA9bEC<5o4#A zZ6TZCIJglnI&|tL9qBN#XrFKfyuvJC!f)N4y;k~g;s8g`jW_*Q3vQO7TMZ!3oIWiA zB=VbYX)sB}dr{<4t6Vd!%$!%8z+ZYIpQz18 z`LrO=eyV}#HrQisZ#fa0psbXpt`p+o+|K6~euMftg3`ogf-~YZ(@@ss_NTH{eW)`c zpD62H9PiDy-e%W{0crMqGgB8bO61ePx1iiXY9shzTFbrzXaTSd@H+2^cWqS{S6vCe z&YAZRnOPHp&U0G3frcyL#Ae&l(Ov`W@;fpH+^M^i@0o`zoPOZ9?;Fr`rTi-B(gjb) z6Pzj=G%)NIVJmDn+aXACwt#34fBX-OMXTaIvdwhwi)8avA3=XGeZsZ5x^?dnyEgRb z)-B{-*yOzFIk2EwLcYig!fV-?=MbIHk~AL+TY^mSa*{sXUv)6n{4!%;P-P`FKa9b* zPFYVv?=A>QLo>X*Q^?0C%j&2kKHRf`>W&-;ZW@Cd8wpfjfTkdqWrXv%oNj(-G&XkDs1=;Y!^E;VArluz7|0)iU1q@3j`Nf z_Nx4r&*I6${_>;E;x1qg=ItU7GaCE7ysRt+I+geF9A(;X+QWtYB+XcZ&bo#Boc$m^ zd{(_6Z5eQOYtfagALKIzk9zg&!T0QIC~pm{2hZ}Jx{k-<;AiM_e-v=LehPg-?N1_OKnOJr;3z(9dhdBp*gJ@_}((2hI1 zxlq6T<-1u=NHSSwS+0C!FL?Gj&)MIRzwaIf-Q68dyT*k?wa?s|x-mcLTPah*Hsw__ z8nj0|gkSuIezy;xcX1sVzUXEEU_hV0`?RX&P;43N_cPR0hYj+>-}~M49oBK`gKZOt zjMDtm7`i(bzg1u0F-hj{fB3Rw<+<_4YmO5-^0j;Kju5Wfw`@tLa31@2>yi3&@5v%E zm(t~P=VReL7xz08*IgjmAXGKxG|&yggi{KfGP&>8C|=1J+feGi4>nZe>T#a zgCw6&6oCXJNI8?C2hc%tHE)ph33cJGc^q&-B^0D&vLc`^se#5 z=LS)QTNylh1K7cbDWGwtX6Mv5CsHr(su)!^^#r}@>S|dB<2sJ|h!`Oi$XH9G6ll=- z(vY})9qJ(1ARaW7l#$95Wry-in51L3q12f+<@g9?pJpwH9{mOd?#+nN_z#88v-W}X zEgmcj%m$st2nFTK3-+-*>o%^wATAqN5UiF_*pt-Z(I4C!0F$5WTjhqzJNU^WJg7?= zkY}^ZB|RQohcU#xP}IC<>ftFy7t9X2c>Y|}J7~b5aHypbY1aO=t#@FjPl8Xmrfl$@ z9}jV7J+@It&{0NLeRh#j4Ns@Vnd#vw`O-R|fXh5G;R2op8q6$eYS0HB@(5gm?=Voa zTH(8Wa~qg1rWzd5^Ym@+zWpQ9E*9eghsyOFBoVXxqp~od=|2DsY>RaRUjaRTA}9;q z><;N&V`w`;$2Q2_n7_;Dy^CnseszKLWxM1*op$M6-DQ~unZ$)ou)Jx;h&&>{i!b$v z8AuyHU7d!G9v8tQr!-{Vu;l=h(Hiyf$N%80ByYvLj}^~xQ&==e&!hJZ+(|c%M2{q! zp+5mr`^EdVLD)3Zb(}21d(yxC-Z&U&*A{(j{nF%FMu{AiIz?Kx+hA7`c<`1{bLpT9Mp8$no!?8?CXG^OWrAPk$?GI zZk5l-4`w3P(XaA#M`U~toD1n)9T$TwlrL<4tV^C$&Iz}&DguVUtxWY^@Hez3F5KI` zwyrJ~-s?z~W-oMWZ|pIhetB7*i$jn&#FhQ+zq_z&H`pin3ESa!@ptaRIkxHD&00q% z>C<79-3yzkbMUHDeWYn=!+vOw{E^?yV2j{4I!;{2nm!a5@W2OX)mo?u`ErUL&m|- zA@H00l!Jg*nIh*XwzLv9FZIdqwn3d>0JOM-BEwycntFOM0fP--#;8`vvAC!bbY88 zIN`la??6cTg`5vr%Dvn_+@mi0TAAS*5PJxGU55^O^z0QhDbE^=@_zJTCO&YGX+QL- zxJSl|7X#nn7jV`F%~QK_hGZ4;{mb>Ag&jMvVsH#{7^oJf+PU(DeJ^6NzfsVQq+)&i z<=G6okHv#wlV2i8=2`)Vs`sa|N~ZKd?;V)_?0}(mv-}EzLzn0ih->X*3X3|6c7%*6 z>0;%n&)PNv;oG)v3p|Wsu+7YBc|CB)*=Y{0X=6F^N6-x5Sx%Y?{(fgT(eC9a( zwC&4HsVn~8U}UiCBB^8K`Jg$8jl+JhUJ8oq26bFN%KEe+ou-`4iI-;I{-++L0p96Zrp)R-2keQBkAk1j z0l`o7sq!@JF67{yKm%nM@RTnDFVyQfwxptv{EARU8WT~DQfY}P~dr_;av(?3bi zzwlk^=^L~l7K4}Kuh4yak6&w`LAOkH$>=Ep4T;6Pwx^GoQ@)-^^cqGRPoF%OhV<{9 zE}cF}C*Dk*F{0bS_}3sFM~b>J57(`2pp4ks=c_Xf5L0z9PjeQ9xqXFnE%>&5=WYm( z%W40aytqiw4dtC%utGnnORScA?Fw_enmgLhP7M%Q+cxdO09IIQ;7YJx0mr%1$61)h zRhcOtLb-_}B>^7!ij>l#V9uTR^zPXK!>&Ux_s#2Umv!k}kU~oqE9%sx4~s65W)5*F zlrQ3Jo;i6qT|Gm3jk_sje=^#ly|d@+-NIY(wLkpSl1kj_D3m_eWZ2eiJL7OuZ)+BE zfv9B$SHVAj<}@q2vt?pi(z!Z-588A7KJ`9>}z)h!0_bSaR*Dj=k=Ncis zR1eKdT~H7$px@>=$S$08?QBE3&9i-nRhPPlvxI=;ywYA2~R+aq7A0yI*7-d67X*~^IuAYoK=uV}(9ETa&>%o(Kp=b@Lw zHH=Q2&aZbM+GyMLi-|G(>Vsz>E9Ot%z1ei_{+m6CG9G9=Mg7(F;EI?IH zCY0%Fyw?O{fwYR7^!erUx6;wOMI>Q%cDi`%0A050(jELVzmEl=+TwI5KQx+L3E8O} z25~M!_g6Vzzvi}yY;%gdaNEvvXHKLlantDN-NBW?K|F0U)YOFMuU%q=Zw8b*_U;?& zbGU$+snc$wbsiaW9j8j-16>$h1czEMDgqrJJ9;VAH7eV$gZM~E;#wI*HPN2#eOuwM zmNSaok$^=`dp~vjP&#$Eo-%=jPvJ{7Z{0kdJxL}B?|$ z4HDZg{LaU`a^WlH=(i_OGa#~wG?p)4xr8%&I5pIqO>F?D75iR0t>HES$J^|tvSSRso3<#BT%5I+E)`RQ9Z8JB2A{ymh4Soc^H0c$Oe*WWPZy=gyoY=zR$p zl~Pw^os#DgPTihkcX8hzy6(UhyB^L{73VZR=(1AOYClBv8`$KYxEQ{AeLKhtmxz0@@ID;pjLyfRor_QZ)} zsexcZD`cwMiQYt4(y-JF{ribk{p{e{3sw`b0W&=_d9<*VMP7vgAMl z7s1?m0xXvhh^<)Qw+Z@5r|Bj^tZQr;eBeZ5$a5`&2a@TCp1h7TeG|GhKn;muCm?_O zRpOM9O#$9DZq58TaqLhm3~UC5IMEqUC*R_wgS5HvAr}tl&Q4YG1^wh%17G@4-}XY5 zDJOLdoL+OX{wVO*r>?y_M?Wbim6=!0H>9KJ#71H~su|Q4dDxw75{-V8>J1zSd9xY8 zx{h6Y$J!`5AMUE-+8sv@>`BKcq<=>iXM(qS@KeChH9+T}V-@CJN(6Ww=1K7p^ABa8Rc-i4k^sSiAj z85BG!bt#8EdP1vx2Iy?FUKg;N5p=rY1UAj_bOI6YyB%pam(xYy@wf83@zDj?J9KDA zz=Jla7Bag+hY6>tPwI;9Ye$gG>^BEq+=}}qcAqjYJ1{t`VKZDKu*1MfwN;JQ(Sk%7imu?C^z*H&LGE**X+Y4059!XP#oL8 zWve{3%fQ)|s;_JAffU*yr+;g#}4CvAi`Qv zzI|&SH%AVhIdL`}_rcPESwz5;z-7D6A;au{nJM1kJ=bn9GgtpZUUjhRe8WisRhLq` z&P)g78D;V{oM_OL4nfd`xktCB0l@Cj8e6p$cGtBl41gTJklImA&kB7Tvhkov2ine~ zA1<6d$vSrIW&z!RZsZuHXq)pJQI-xgGMUt?Jv!+lICvxPp(DY$L5H@T`amzp_Xwcm zsj8>&4=$ZOMSw|t$(lVa+3|?I!9b$`06+jqL_t(`TscEFHD$pvUpu<I%W4ADEkra`V~)qyDt4&0uAzkA83ot$#FSZ7g-S*4LkO1Pam<) z!KQWV(t#bjQ@8e=Vgx|p>((;P!*X=S(E$Wk-#K!#4Pm<(qOIge1pv zScdI4`l$ewpgkL{6*gCybw29>oOIuqHD+|+#gt#4b55@C8buC86s4B_P?qJ1qXKUl zH^L?3Ir>wLu-eUx z+jD|Z!+l?TnGQz@DNP?aJQj9yWnGOLjXR%n#41N>bF`X<#R!FP%Xq@<;ph*@V=*Nb z%)zMLw|^gt#?{2V4m>h@&YaW{yj)?iB88b{79;*LuJ{s1wj~TD4L9o$P4s86IG3ZA zC&0~ztJg-^{ux{`fNkoA#j4%05FppYA!tQy@6ydj%a-2>IL(|e zF%2FvID&ZwP3%*Ryy!b%H?7+}!$pn}Yuja=_OnrQk8I>-dUyAcmCXP5m^7##!JvMn z)zfp@qxke);SI+y`Zky2JKT*!{MgUobU_P_)@nfPCz@Y<^+r;GPlTU3kSeRut1J>O z6{>U*BLd(dM)#;IGB>zx`!YY#HhP{~@NhOwM-A@7!k6W#Esl!8 zrki9V+;-XwnGNDZgHGd4qg9&JICHm#$WXu_ziF0)UN8N037S4!QQchel@ub6Iz7-I{6`h4<(Osf}l)Znwt^ zrN?`YuqkI8)s!d=GKp*XMf&r**BmueO4>iJJ)^8Xj=}lys!uICjtRpDry&g>F}kNw=m@#I z>O0bl@>lYc=3*4bwt#nKoppOCv*j@tFuRPL+OlN}&RTZBheMOYhZD#HH#+ShgK4~V zh#%LHQ1)1o8Aj5Jd|{=^O7)hw(eXFP<>=d*?K`60p8Op=ZglF7{?NFSe#O6mD`lE+ zy4#U7<6&Tef}a?M%Cf*(1vpb7t4Taa+M*Si{84xm-dJH)Ge#pe2Rqlf~ zWk6(*lw^j%F0a=!;<;<{mv;h*>JPJK)bG}>oXdt8vW)hM?<^BC&4(-!A6%C0RB#3Nw z14EWCordnC7Ymz18Le!So`Rn!TYJfAEl1I6rAr*Mvd%wIk~ZMD5(REgdBYFn~bM`0?XHugZ_MRbG)+d|teZ zkKh^FpqzC;B>IFplx-gNjlFf8QQ94wSEs!VS(lCI-kI%=hlhijry`0|%zT-Lc(G7;0dEW!E1y8Sa1nsHHVW#L8oMIKd`2vf)eu7_P&q7Pv(a3ep(0<7RLu+LfE zb<4-iJNMoxfA&4&kv091z34RfLHIIm#Se0vcB@}4B-HtX@|PaBCOjr%9M|mY8&l$+ZcSz{nKRXuGz86B2pz~ zSBx4H`a?Tko(OrsJ?YqTtw+5dxTa9c^PVI9@`v~_quA->E?8J~V1GJrsv*k1ci7O# zw9-dV-|1rsiy4&#zlL6h{>7_h1kLiS?I|!LE*$`K8uJ(IT&4Eu#bD*QdnScmjloG} z3G}8+voD2LzsMtS1)o`{84PA4h->@A3sr8@yDVH77pi@+Cc1~%>Ci7lfLu+2O3H!6>%P(i;tpF!3h}?e7MEDv~BD< z@j==TgSnu~SOjK;b8JDR&W`&|yG^7**g0C8+2P?&|Kp!WWc;bQ_obP$X2o2*V2JBC ziE?86V4(Y3gG&VgMMS5{tOgn+5Yw`C8gwdDSQ3VdJFX(o@Sm2xm*x#0lBUhN4+Sxv zsCqXP3!|AZmmMsj%A6jdkfob|qv(YLMnvzs~xHi2D(HuhY&u7(QS9CV* zUj?RPCCtKMS($+d5QKr4nLm_5$!J#qTZcsLJVS-!9vJmO*4XVH6)KHF0ZuWEy`X#zKJ@0Tq9>wRLF=+g`0>d%b-ai_d-c`80my$ke54 zmoQ{=Dia~fDBr0BIiR5Nt5OOf0|6NH2%$!sydK|S#A=NHZ8$H>-+eE&FB_PiT)a39 zADkUhap9IX3JHa_@C&;P8jQ+!abZeWw2ekO`a!gbED^UGJHz5xo74O6zLs{^olVa^ z@^D%-?;*BQWxFw=;O>9j3d7224h9=c^V9Im3eP}84)ExJQBeqhm`~M;R8oXNbzNm5`v=UgoEU+On`GA@E&v7CfKj@$Y*S++TFdXk2@>ZzNQE-efRSf* z?%A7Odhw@eL*21-U*(`Q|B=OM6v|WQLRt}z8k=FH1FJYt$%qdZV^ldPtaUV;Pp09k zf-rSdM{n)=jpH-Nc{2ClA>l4#IQfo5G<;pn2GG=a_$vGzDo ztyyjT7Hv^D+DEp*cMn51?|r;1{p`)R(qhV;Gk0#9GZkKX zhLtJx0Po7^rq>@nek5(*zdNm2zb4flIFWwq2j5F$MhuTBD6N~5#XxZ57Tcw@Alu5+ zZdWAsYzn-6dlh~#B5xqB8FYA)sTkLp1nWq^S6`9t_~rJr^8Hom-OoQti|%_cefP;{ zSRJcNA7MvHB=9XiXVv#&=EEM>O=74r`lKb-EH zHZ}H?*U6PQ3^X{xDy}TkZBd=?905A$T4O*wnAK(4smSqJr~4d4zP$AED`~~XFO%cr z|J^_RQJOSiJZpfkk38*;bxc&w_AAYC8{@pD0R}Gkwhrmg0HX$qe566)Xod1(6M^18 z{wENF$iG1wqo*cRo2dQKTE47Mrn^`5ie zbh-|bTD@%bnpli={-OnG1Wu##TU|Fnn3Odwp$`|>bpLu~g0yKnbue?tkZj+3B$b^I7b!R|J-H8pI|YlJ7N14nQ2Dfzg{oit`HSg`x})i#A(iRDhZn_sRug z7w6tL!^l37$8;oZvw^jZ=a(hAvI9b}E2VV0_=Qv(1s6 zBl$cWr&5_Z!`f4}OTHC0^~Ztg>a-Ml%uLS*XR{6ndbMBw{t+N^?HXm5_K)w`hdRnS zPU1v+P#$oqg&|M%fcP>rkm4G*dFk=pMECYKYd0_|B+Xv8Fw7eF%s_3 zKfE9H(1+qa`ZP2xeM5VEryVpQJp0glt5>aHE6g|20ftw9lU*vb$DArD->L7Vckvkd zpLhK&J$O%isMDoG%gzDTrjh>bwJr4N2kfTy{_ef$es;uq_VLHlkg_uFWImP0)y*LT zXhS$W3NrhV>+-F2+4+_yXGuS9aq8lB%T}yN|L0GC9_9VUV~?f`Z;yjG@qhG+d1cRX_%xi~LVf0#`L9NLqX<9B6@ zwq688fmlA1-lJXAZJV+*)^;Up1YSKx;BL##o$197K1#o__>nY)HSv10K3IEfB4Ji9 zOE=oK>O$L+1HoiM(znu|zMpvTIpvI5HTHx2^y!+_>BEmc!Io{EzW@E-NMq>JJYAYa z*1>_n_~2LU5OI*RF0##GW~6;-dCCcYi+6e5`sAl&@4T7TkX8C9L53v@7p6h|`@tjF zTgcrK83c_<<>4cPC%2ESN0z+v_S*K)@gT ztA7VX;Rw0u&MsB`jfwuq_d8!E_RG>{kw>NE8yFg024Ksr2qA zpQJzj^Pi+8qlOa8&v(zR{{h1WeKUhAUrAbf?c1hBhZ z2{`=Y-}#+19cQ`+jIQ!6oM+(_t}wz27{P_X7!_KvN3V)XxGmpErcvC_m^$;;PhU*E z@0pnXk%5d6BT2n9Ma?bA3^b4t0gV0@zZ!)0uQ&;Ksn>QW&J9T2LYcPi)FGW9itEbm zFaFI>(iaEo(?9#cZ=~nG^LQAFm(G!-MBkYO)55-zc`3IrdKA>wAdYmbO}lecR!628 z^w^9vzdZ*JrWap%IsN3-HzG^tkN%fGU^~oNF%{xE!n@eEP$xhdbEG=@nR;Z291yTg zR-GL?jYjF+x;HXH`e%RkXXz7^{-fi^r02f({cyb6Y2b(hgjKBG4~+7OO5f-`RbhNe zJ6s0#Yuvw%bH@WXV@9Ie#(d(BR;)_D_dowp8cbc^{cnGht*Pdx%Ca(2!3{KE=z<%A z4TS+7qai#iE^dPdadC@)##M|X7ix6{UHRcEZ9jCVF1^cQaeu+e_s`CK5F->raT0-s z9^Hc`qyup+eno)&=Lj{$#Qjiu^nv$OruMUKlb0MNH5=pQcitwi^m1&kHv!pESy>UI zP8yohhp z(eI?m1Ts34&DF;FMJ$zl^SW!57)S&*c?kvT2(W<$GjVRfH!Te`5WFzZ-~yATaT{pZ zx_Mh#@xiL}>Wa71cOF`lzW3C#>{3w)O$Z(3!5>ASK|c2*?DAv;8Yt&Byb$w4y#xLn zNo@^HIzN0F^7_U9>&Iz7_x`7U^n6H&YNfng;FaP&HO83v0p4wvg#P+Yydn_yl?mg?UM*sji z(g|{#K^?9u^t0t_94V`Hth}}cXZK(J^M4URl7II2W9eb`2Ol+JIQYm}G|^|^Lf)5O zrA=wy_oa;p>QR?81(yXcO9PHjpC%Rc-A|UMKlt&F)BO`hu+zh%X%>c}`;QwWxe6YH zS*O(UivVN}G-PMkI>Uh%PvBfy)uD6#`M#>E^!ocBq>bxVrNVn$3+O(CjSFQateYAW<`aKr5nuRl6 z1pC7of^MusT-sm4sctCX4B1|)!~OvEc^fxqdDpJpY4z$=>8+o?l)8-?nf}QSf0!nY z9u@RwFhTue*_I)^1|ABz;BODxP@Mhl=%{m&9Z_1oa%KA2kN;g-)^INU=;^1@_n&++ zl@I72#(e~xc#)n${zDNIqpT7i%3bASWbX0%5>q(}J}{%K4K(k({Fh#RE&cefeirrr z;lKF(G;i($q{ep+nu&$2kxLZHvFL4vjIpyiVsL6An!TI^6Km!4u z^_w=Ozxmlu)AzyooRS<+f5?}@;M4@4F9u}nGaazNF-~nXgum7&U+K8mKL*x5|NJu+ z3SY(|>ecD@fB&DSX)GS;D5^K`_m zS6murVDvVH&txV6_ZIu^3%Sq46J8Enj_bSdqf2xUcn`YA4qnO>@nAMa(1!ct5;^2e#Q1Yd2cmz6rFS>hl#MzVN@08pE5(oILtpC4IUq!PCW2t3-cOF z=IuidKOB=6FN?GK^oaA%J~z6MnQVYc`ILM_1qL{K*|x9L?U;*j79UfO=b2m|?w9YI z-86XQsQAT$55>Ved)if3aHQd}(Ym4{bztc&+jR0=!dF@0mAVw`ZhOj>Qa|?XZ_0y( z1PS`TKPZL~JURQkbD}Fn3_Er#YA=*@Y~`QpC|2op1{>t5S6+=9uedyVQ(#`ZtTsA>IH6p2{iW}Meu^NF&+9;vZlyULNz#z>)4`&H zb^44M)Lt1HZ)1N{YF-vMTyaGPmfU8Njssxl_|?6XZH}LR@+IF&+l?`3ugL2SDvR@V zfQ>jkYRt#++Oto`yJQYuLV)?AvkCl^8{EJyV(vOEGC)n6a>mRm1x{`wvIzKFZw-hh z@TIfQIU7eqYZ+>0JLJOe!iD1V5A)xDkE20Gp%8Fkmn5VT8JL zj8sAN1+x_aMPNN&61f6O1>1%8CGzP(e;q~c*MIp-^kkf8-SYE1`pTmdGr|kO+NOl; z^CE|eR|-j{=R9SCsbuhn2$VGdXkTQUHIL(wIG1+f`vc>gOD>J>hj+uPxNoKaC9=w# zfsICzM4=I?aUns9xFtfAp!}{VI0l0v&3g&(`((m|c=Fk2@+g&N6R}0KKg;JC#Srok{@h`m6%nBjhCXXJ6(_U5twBFS#TRgaOJNY}2qesQ_npYk1}?zzubdh!|S!Qr0YU&MWFUZaYS3;e`YZmZ1iQXE21;8q6nd`27>wO}?!705&z>76?AIx- zz{ztsu&;$e;aGhc{h@*H(*kXK`;H=8MR+j9qG+JwMj)f9rqQ<+CHnoL!{Yj1-;wM6 zyDKi{d~lCWY|TDB)({3;jmWf$t%|wIpNgUm1r^%O^x@HqU#wXbYrg(6*6Za)DfYCJ z?HI|cSFh!4a2!-)Mn#`4U8565Kt%=TrW46DLY}Y|(U^NOTs}+dUe3v%QeZM4KZ^_E zPZ51ypH;v=1Rv1~<4~gNCtx&oJ>*dK#@0$Nbm6!YzkRk4ULsE7f6{@i0y=O@H75L%b2_Il2{pzi@=$JJgz*zcJ z*+RKzQ{k+I^J3)qPvY$l-l0I(#<=yyn>h~CEEuvwa5PlqwVlEht5&Tg3bBH%7Qhxm zRV7@7#6r2n)(M1O6?hsORd+Bw_bP7MMCR1|#WD4>8S&Ai(b0XsgE@MzcRB)qD$|Ew zv2H39&Le4`Hl=w`w7_#lTyUZS-a@|x(Fr3r?(u%-owwtWKR*!5c;=3)uZ$lbcWfG7 z8vWAH#;@7q2@WXW=>R7eedc1S82Umn2ai0OlV9>49bfVbk9B&CjI|dA3=CA;xczT` zj-$vr5Z}!R@MI3@HP5YQywX)hcHuWV764!)F@|uDlSX?s|I&f3Glt*O$v}J@^dU_Kl%uV;)6J6W3 zOlQE6RJ^VrLoadB?JzteZ2a42=P#9y*ykwz0((6nSms(coe2e=^TO&&%g9i zJoxxOa~Kca_8X2)JQky|er7ayJYeDrinRKTYpgTLmre+y`PMTqTkV@|{LXyMbaMP& zV+jo0|InY~ZL<2#+JC>e4EfQWtxodUl3}MZ{=MNSegXs6(3fkh-r;)qlBP;JkjGUH zhW}pt>)%8L_g!-FMR5wzZ%=+v*|vS}E%1bYoqy5|IG`%7fpPqawE`g4YI_Bs&j3A0>{BBQ3S!{OA*F?B=maQaek1|z5ZmZJ&j}V6asBm|Kx($k2Ni|CGIE_q`eGs(2h9c*u)We7A%gw&>MI+ zo6Sgb9UP*|SFVgV;9=L_^{4Fn_t#$&XPkJI2pj6z3h&D=zuTMR6!wLX}7IQOEBk ze%P+OOnqHiave)oi5H76;*j$)dOdL1@VF8AaX2@gbJI<6;z=h(MeA0KoxS_uyq7wd zI<|d?Pen~R;KARnwf)+k@KcBOdo#m4HRUCo3=hF4uSI4b1&=pF$l{dJL}`5LG>)4G z6E7VbA5&j&eGNdEA!`<^*_NKPBafdjbxOQ|ebc6*Rh)RtF=XDhXB&L89HaBq30oSA zI=%A5e#AxPk(@$WE(PC|Px2eHOQ*4}AB`Cu|9I`SxDB`*gX69##rJE%OKsP6EInr* z>eJdT43R!`Mivf6X;&DD^U|Jl=c!dAI9+4Fi_gWj22J9p*It`})ZzpvGEBj5`FxT6 zrhTS8LJcjPfVOAn;2&3$FP!}>9+E9TVWhEo3AU%s&8HCyjk_;kpaVhCg z7Ua0$v>(Ssmt34@Y)cGAjf^7iK&jF=Qg~%*E`5qv61)gsia1C-BBBggqhKYeRWGAN z|NQ<3;`oLQ;`A%8jH8b}8Utf*j2nuI?NZi~F(uPxp=m_KR#2DPwp|-mP#I-(3`S;V z&7T)fpj3>1_wBgg@~fgp_akCooFsKHxHB!72UR>((qw|dOl3V4Pne$sqT=j$?ZVFz z>X#TIiz%oxX8fn|pD5`)NY6RGPoL<7VbH9p1*k0Y;-12SkR89T6hOeJ_!Osb2 z#wwF@9c5UmTt>tcUeTr$8is!Tg@M&N?NhEQ_8(9w(#WhO4h;Uv`g7C9ez4I(GMR+LnAJl?c|*_nl-QY$Nh$eHqjB zRciQ>XE5w)usws6dkLYZVhu+faZS+11$~j@y-vHM0Vyl79Kv zix)8~9uc@@YU85cuB2F+edUAk#9cBiglzAD?=990}gEYFWWk34Qf9COYC!;79j)ul5e+xsMtrsfBt|RLw9OMT&IaIvl zzbZ}geih;5pNwClYtEcGF$}}#Wg=d`|K%^^sBYadBTh$yGDmnPP4ezKY7QnEUQLTD20G$-6w= z8YJSlG9$CU7`N}cVX*9>lYwPaU=L(9-(HieHVJ)E_v zl!aD>rAoL{mq+@+x6}dntTEud{+7;3+SCv+fZ$e;LFfc$(`H+qyyVhL!1>ei$Y!%q z-F}cfo8MB#F-D&&vKIJ~tE7vh-of8#NP?#h!fhr08aOcScEJW+GxvN?nK?6_ef>3xeXotvaj+jk z+ilz7XaFZo2e9!`L2eC$7_O>OXwvwharR*M;5Zol!mIQNXxqKuO&bfBo)xm_p&G3qw7CH^PQ)3pBJXRWY zZ1TlKOkgfuxh}3r;y&~Aw1Kxj92!^Oc~|tUQ!CEA`r0@i2UycqttbxuRXSqi=?+-q zRvd9HY(sjL;fngI!`kio?~5g-2MENQ=(6wKIvRjkC&cGP8WHCZOP~P zKY6=2YkT66SK>VPeFuJ-0pi#vVIw^8!t*#`%LzUlM_{6T(yE!v@+X?gOZ`oGyv_jM=S}&TR?0&%{X+V<^1l(KlX?dvEzg^uc_tt1bo0bvi0Po_y%OcxT}kaW#RB>n^$o8@Cm5*TSU3}js|iy&|y)TL@C-0^(_asBk60( zMbVVzk2wnS;lKTz$nJ4Oq>hf(E!iW5VI(1H{L5?#f(H5kwO~>@0!Xc*y(B=GqN^i8 zDL8a?tXRGxkMY#eFyO5>u{#de z)OrfziM9+Ro$g7zm4|lk9yeWjY3@06JYFh=M%2B0E@8~)6nIP|890MhX_o-M)xZYV zs%A#Rn)qNSg#M5JjH&FA`o$Gjl1hF?w8Yc81!FqTV76_P6pa=mMXCJLj)It#%l}mN zCH}1#jN4d?It}Vk9lvqRbxogrCLVa|sT|+Kf4VD5hN`;iJ z6rv?heIf=hNu?b8c7==xXvpiO9|LUuaQEFY8l&^9BMytJue+Y;_rd9OTek{#8-}ey zt}^4Tf>G#uMon2a+cwI(g)y66sH35hG(f~xrufyy4KZ-&u($?CLkC8G;f>dj?tOgh zQ{F011lf+Gphgu8K+@pTpkw|b0F*#$zm9F}QMXp6myZ5)Y`it-y;z8oVfK>6D00>j z(0O3WGKD@@ttHc8Q#7u_Ne(z>gssX@VK^8mE0lBbC!8%h~tQ=TOg;hEvfv6qpVc5iuP{QHlX_cx4>=^yzv9p zXAU?v_wz+5_;tL<6Tic#NJj$}$99g{*-5*V;derB!}@R1+3@8zUq>CPrp}ldPd@c@ zyavOq0u;q3UwJ8BedWct?ux6T8^(G^WS=S3Uw_3BMa-|JJdkIFy*^j^Z z*}jwozEtE?#MY20IB(uO_6LuSXI_3OeoqAa7@Q7vm)i(;IM1UC7pnRxJoVVDJbVQ?XT-VYZN0F*et%$R5MN z3r@1~xm`%*QRB<38?zebFIp6@^?xJo{m0WTN&NlpJK_|adUcT>>sGU;96qOUR5f`! zaE4fPENk3Zzl!b?#sDXIi`jgeko7tmgugYd9)yPtU~SL9SiIuK8>1VtTfNMqGF^Wo zI=D*2wW)~ZQo__N1Y}9t-j*E?`gAV#WSz}E55;jdHRVbVRRjo zN1X~c*WGccUoFA8FzlmYL_I%>ReZm8&1ww(y6Jo|%1t?)bfTI{?)-$G2Dlj?D>-SR zHvF(Yx=u|DCxbT{7apgm6V&+&bGNf4&L|scufR(Y#W|@J6tJoXJ+^J%f%;hWV=T^( z8Dl<Ahmc9~ zX#f6kEY9Vh5pe6=u3hpFVOOg0Apeq|iHpiU9Vhl9pH*MVu`_Nzn-Q=l4wB{Y0=G`w zeD4Ff)W5m*syK&$VHq+?qs;c?OX^3qt1h3xAJ*0&ijL;w_uzXKa2&1{Uvp|hC9(x; z)~*?I=FN}ipL-$x^Oe`*0DAc4pZ*kmd-j4aR*hoo1i?E#>$u4AI|};(AFUgt14r6a z*V{~n5N`Q&j8`k^V`P~A2FK3KFIL6H$5a34jC0};oSRjVN9h2e9dX+=a9zzPP^Zwj zrQTc6Pf;jY{h;c5J`H%E1fS^xA2yTH3>^8i&L(L)oxS!0o~7;q z+~t>vPke8^A!SG{_bbLUZa>XUc_C&t(4Kezwl7n#wZQ{DE|_k^?hsO<@( zLPur(e74?E2I2V32y&gJwX)`AnfWoCali1yJ!1ouKCGNqGRjU8GL5w*`_+J zIODbyzDOIxtcHclmc|>%hZdbXQaj>;XjER#0;wAmqbT0#_y>GJhc3_m;PUA-uwWJ} zk^szAVlnsv2D;_{=V)li(U08@>=OHcpp{@S-{NS{Ybrx%(4c-Qq#ukP6<6PQL$Sw} zVkwtkl)81oJxJ@>pZqPx2N;)WWGWS#IpR{qMW&vfdltxP6@`xQLV<81Pi8dW*?t)& z_)7%ym3Ykh9(ye5sW=+gf2=~IF)qQRKopUgQz}2ar%@{LFm4y$6!JW_gn4RA+n@XS zpF&Zb{=vvN@A3=TI&pY(>d0PF5dNz#ze>>fIaAJT3)o3KGC>huL|2)XU_5Tm)E$j| z)A_z2YV`4E63-Mb|5RYUoa z_!X8lh!$uFnii!pH)#0qc<1c_@%uaefTQ8iRNRECFp&@y&?=6Owdjj=W>zv%Cs}VHDnHvBvjs@H~g3VLu!@*I#sTIvONaJ?JTjcQK!YGcXYr_9w%2T^zGaQ7@lD zVkg3)DhzZ5YijE2Q;$Cq6Y(hi{L;(gywgsL@@8d3y;0P52{Kc@OOA$8oq)s<#w+d` znbM2)bd9U8y*>^*xJx?J)^J*f zY_B@$fI1sAZv7iOE}adou|j{VxP-@lXB8AY+SJ&CG53ov@u0iMmW+m)9C6CFiE1^VX|e)7`Si1R z^|k&n?vu}A*7`-eX8GTLV`eD`|NBq;pYOconj6?#cs|$_@!mTF;^q79it&7Y2uH(N zq<1z!@!bGSoO>;tP4X@kM>&8_t&D7;$YqpBnCtWc7Xf1aW^~teu%Ofv(9+8Thel(b z{To{+`u1XvEpT3sBU$50=R#GLAmE*b9Xv$dWkgZjHu5BmN=K>KfwS^S)S4JZmdedn zT^+M&`&JwcXP$j_bjDcsSV51~Rr%03GQ-A9EVCATiTm=H63@3k6<=kEhJf>v*Sy6x zt)Kn*p*Vr{bSqC!3JP14S0&U}@-k$B$_uJ)DuOELwvm0%o?4NjQ=VzWGgI%uFSkxS z`RdE@%F8dr^<>0#$0@rnDcLHM>xj_0MXMJ48^k7}%F)fh)--VWt}?JBL(-surzOmQ zyXU1ZAzQ-ex7)zFvZe2&qx!JNmaP+{sk<(lHf?0?g`7x?A^@={_s0HE@Kx_kUx0I`k?%I)7p8tK?`< z{t8Fes&F(+kKw~Vj5nWoHtM4E-*m+l>1ePm;aE5h*yCP{W7%j^nPVG;^GF^H{ezSK zr>s?;c!@KfWuA@(G7(=yk-q6H91S?CEm$o~ea7vbrcT3b(=otc(;=cGK^`t{=wPre z$yQ#OWeGo)*UVqEINqSx*L_bslYRdE?%PS@Kb~z=wKxuObsAP0M#_-fE}^3VV@o>N zwoC4*6XbRw)>8ST;;$azT*u>Rc<3(=$D0!-#%XO@$2CL)k02vX_^oBnx-!#sa=rX6 zjdb3XyW*evfzBNbd+QeXy?A3?DHUV4vfhm1&&hOg9@!oz6DjS0@gl#~IMGlSH;mr7 z4$5@tse~t)aYWy)M-ilPD8Q6HbTp`srK15J)29y+SR#!L8#Ts}R%~JL8IO#uN+eQQ zD$R;dj?I2*vF2VLjVTV5vS6&yFqM?)XZpX!mXvSf^b<~uE;un-wQikbbicgw);YCk z>F4pzyYI&9fBSpP!t^9D^1prkSNZhce(3*lqetKV1RQK$)||DS5>tkM6o0t&7rAw! z2|=YAtfx){=kI)BS^2kmm+L9*C#<<4*+h5Iy`K7$Voe($}w=gqg`yuQc8 zFRs3ZBJDVjxX(3|Po=!%d3BDGUL!A%bE$L4gG-KNGaU9nXD}0E`RY|{op>j1{L_6o z%imt7qv6zaG-w<<;A+f)ordYGQ7=c9G%qvAs*=sH34C9*5j_h>K>dad zV(x+k@z1B9iT`-{wG5uzao>HJ-K(SF%QfqYXBo2vz}5L>5aN7c{@-%+a$sp`t7fC;6 z8c2Jth5S^S`U*$F+c-?Gy6dhuqeJ^R0jFJ0oa|;)E1RT21ER%gJqBygM`=?dTe>V| zuE>Ywp{|orch^|jUc7W^JV&5#7+GP9WOp2{tNc+NT?e7EMHtzh zV|9(SnS_5O-gPu=!uDE6R`sN5)8mn6o{oyLz2gjIU%S?AQeW~Jd4YUU984z<{iL11 zxNJ|m!*Ls=6bGeiGtz{Uj)u>G`%rYvrv|(ccijB5+&WQ)Y^udtp=G6=m#HK@n3kT^C=hYvvh)t*{h?FP5p6#Z>mu%ZrkN((1Gk2%?{B7oP)T|cniBv zCzZiq#t&VY(Xa>hN7H5mGlAnrBS*x`IAC6&!1Wd1I~v*~oUPgB<$Mi>sV`a2#JXGt zOy@75t_It8%R227KY_nCZqs8A)T+?(Qk7VVrHuFtbZuO-Fsvdb@z z15hqxP}`_;^I9ncghCNa24HlFYXBo)Hp|$@J=_80)XTH!yzt_rK%) zZx^SWeNOc5-8-5>=-<(X3W$g!A^N-?VU-`1&qO+qMPjs{^t98zT!T7q002M$Nkl&@K7o-xp|9<=7xnt`DOxAXb2%0bxhZrj_;gw1#pG9^V zm_%hUI0?~gh{Y(1V@Rd@&nKS1fx&+D-hGJFQI))`8N@-9AGjEaN;uHA5n~k*g^kS0 z=!1%xjIqefAobfw2MW%zg$wZbjg5gH4vnEW8-9(VXhwr6j8;OHL1~ni914y#6$#zSax08|>{oOUFO?s$nHU6{l@h-yWWr_y2JM7T(_#KGyuaYbSP6ojp@wROQ6bVi4-D%%KI5X!{cjNiz;=yO1VSW*hJ$N5k0mnui@NdJH z>jHM1Mv_rjoltt{HICBJ!2RNmjxO;KAY}%E%3?L(sv$NS*xYgFoz!TU7pEO|P+WWC zP0@{gb+)tV>kZkq&H(X06biakrh%-+~ABq0k@v(a8AaUH3-? zw_JYxRq^AKPNqgm+t@}V+l&TlG=O!v6~Q$X7Q2&4Q>iY-Fph?yqejF(UwkH`?$cKg zf%|`W6|O6$y{pf=etUbIbnNj_hEsBP9E`^IE3>pJdvb_N>_akgYI{&*iSzrP-5M92bAIB}oBdyp$NzLk%;cU2 zh>+@NXigT1d&pHhD?w8*s5CAzjT_}iWzFmwvwU{xB4n2!KRQr|6U&yA=r8%UP*UXM(vHvSKuZ3rQR7(QG19HP8o^QU zIuK#`n$__JDf~B+s@|tvJGNz}v^s{I^Hi~OtjdR!8O%psW(TGA zlkaekMwP`Nbu>Kr{PXE}u||WZBJGWn#QRioea=h{728yrX-+;|w1YA$uaPFWPdc)1 ze$4ty6Ts!c$c|Sr*nWTOt#LFN4UI7vy~k&iAu4e`o6&D**57hJHNOjg;pFd`_6;1< z(ZGFKqv6A$(Vvv*+WU5jn=ZSYs^kX{sqynu!Qw41>JQ|+07hO zurmV^xx5Lun)>?EqmRTZ3l_#NiP~QdKWJ56p6jXHlfP*ESK~P&vC5)^vp5ZWq@kVs z;MSqiR-w|nhEadElidH*a}FW?e&=oRW40pIt6L`nC$^WFQM~J*cB`M?`Pr-luY`$? zaMo9up{z>h0r32c)cSkD$A6LXeQHH{{QQnT#NlLXdTk~HN1Rihy0$u7gtPbtYUaAC z59kaks<^X8>N~Wnb4J5x(1;On{;z%=`_SHnz~*EWX&nu&q5Glbx6+V?iq53eIcP&z zm*6d|N;u@W5`K)yVvy=%w>`$zi9UVe*yE1N?Lzg*F#T><`{E5G$heSGtfilG4&oF2 z*uVT;{l-h3LZiwI(23}t&%NCD@$D? zx2+U)dB7p*DfMHC(%>I?^dIpbFa66= z#OpYHPXS)L)r9}kzFVt(URhm<@vHZVOIy*0bck4_)$JG}Qc*()uF3dITPH@1`!sI5 z=);qbq@7l4oo!FOYYwa_GPL65vl&Ngpem7plLA5)XYQI9q?oM`-#ULHKYiTew?N&ygSy{Ae z!@`CINw~SiCTl8TE80(O@ZGGYEJpvtKjQUiv*Q}FRIYrvJQo4$e7V_;je#{O7LaJ9upT_@RK-j zzs?z5GW%g0kw6tuqYMffF~P+*Ra#H0h^^;O;U~gKSR$v3ZfcRKOLsl-Wb~_FJ5IUe z^7Nvc`kDkF!qJYAkaQ%7V2n%wrxGM0D!66pPH=Y^W>u6WtA?*$T@)XB1!1*h(zN)| zsi(vd-Tq54NC>frq7`OSdd^f_7_0D0W+bsVfuhqQ)th;&MPXR55NE)I3GqDDf)Ch# zzc?CYVtpYQ=R4BgpvO?@eEi^3W&z~P3j~T-rsp0Y2 zr{m+w8*Ydr4(<|V2s=~BRh%XA5@E}zQm|!j#XpWam37C@CBt;Tp`Kp%KYqZmI0O2> z8Rdr@9G9GRRth#5O%}S55i@pi#B)dE2L=H8mP^G_XAf8bP#WG&W%@-2mIF z>>*r>qhaLOPvVugUWXwrj46wj(h8A4Y@M3$;hI&5sA{~sCeV$w3Pk68iNm1dHn-}b zv7twRYvM(c4*0{*ynLs7gc@YP+Hc2evUv;XlAJ)b(cidA%HD0i_$8-i^o^zn&fUHx zZI}D2A`ncq)aaBSr18TuxxEKCB(3td%6b|X3}6KXt7Z}H8Z~ZQ{Ojdc<0K;AeYzFd zN6pHbxsu;U0ECH`xToVwqcrO@uofBVVJ+RxQWe-&qeg?mbml^w7@vL;gN6@|`AgTu zRb<(i(a^MMb7+F&pir8>TE8hKPMI772YnFJ7|Y0MIEJg2rdEHHM_UUKl zqP&fw_~^s;$1;AuPzz=^a4ieh;Yic4maoWDti~+8=;;@??JHkmJnOTY z(OvkAgPTl7!(;H@*N2XXgV6VG`Q!c3yGM_V@ao7Arl!=297erVOjU9-IuDI1e05~l zw*{+IIOO%k)`=aN(Qw6e*Qb(uO~1Zz@nx4r7fvftK4@H&j8Mm7#)9q2i&IIVpMw7g zIWB38|C2WX=vDCHx7Y@FD;aS|Vi5fJ%rm2Ruikmgm;AAmo#$d1jgl-=2GLH5hZRav z;b@RY+P{2AXTZ$49AEt2JMkGZ>h$x@%cE%b#Zg@shvx#`=oX(|PIJ0`)+TzrSKR+1neYGKOKKGos82Mx|NM*8k<2D!wJF^bl7AHQM;22={hRE zQ|WarfQPWj3vMEm_6UI{~a5MmO;V%yB zbWk_anVUS)F{3xA#H%-DiaETKVdVGfLQB3_9&eH%bk8%-#zo*uzvGY3ES{#M+2@+V z4{SpiWH6&rVT8H9@^$fBS?=FDmUR%SQUHqK2>~YA^wdc}thXv{kE;2kY>yUQK7Ab(dK0@8tQs^SvV7x%k=sebIgL zUZ$JAXVKW77=FGpd~k-p`Htmg%ounCg1_N2|L2kJZCdWlvFp8JFJRy)V^g4~-~H^T zaRfDf+&WPMgWgLza{dk?*OX3OzkJyn|Ev3^bB6nM80wVKi7*;R!z=&%XS_IRN}Nta z{rZb8${G#ghjP;telxIia8}n~M~KLWU0?eZzpbAjj?4Fb_d8En`C{dYc$>N#ciw$( ztfF7HPMmk z@l-s~|1H4~&;If5I0=1hPwH2AT9YULc=Wb)vUHRPo3ss>m$F%BwGJlf$&5JZH;X~4 zLvxQA4fo!6Z;V^8B+l!7MEvC33pk&I2gQ%iIV-xs2Re7|OxAP#q$kInb_{ru`aEOQ5iW0#9+iz6 z!^szbll8tTL9<_i51%htg8Y~quTTS`tWgs(OOJ{JXuD<0@^tECpcD8p*=*1GXC@hK zCl9s{e%HQA+kwBUVLPdl<<<$D;3Kg8-o_zt#T8djO!)A0G+39UGV&(zkFl9eVte8< zD4s8EDDhlASvX*jUEGsdj?C3!^k!7Q`C9*|y?67t`qE1a`O$!_8Q_$7?fgqNjgDy7 zE*p1cBzF7YC68B!Ph5icti@413ft+`ryh^@7c67z#E;^#bI!@Eefhb;$IOaAW;ix8 zMG8j)b!XsN^9UdhAPC#ARf{-_?8}xF6^WZV8ni)~2qXAmU;lGQ1M|-a4hZa(9#uV^ zAQ5N=L)}I($Z6DQ_%IgFpBL3J`nq)N9Bs?Xqmqk@0Cx|Lj7MjHi#8HM{}qay(Yyy#W&4LCS*#y#;yWcCD+tFmE24-64^mA1)#!MLKMM8q-7Wwo-_O43ok{_ zI+f$-vo44ux_8H*Zk7VA#6*l_Wp!|fUqP+Xm>yE*B{3F838C{;L>m@LGi zqv10NhLpF?Fuv{>?4BObl&k}ps$&-=lL#S9g|0$chNAHClIhu>9#CJV8T#E~qFqL$ zKIYh?c^ExErYOlFICq*7S6y{*sAJe;M@4lr8WhMFz1CV^A;t7U~yR zM?s@l1ytOCK|n*Sr)#QUVvlPTQe$^2%*ht`igB%2y_#Z>Qg5WuXusE9_>(vi;n|cl z{wh3I6FRAeg5XWUSAe8|--YL{qckP%*p5+g;qMvkb1~}l&<{r`IszrM>p=%a+cvE; zi^p*mN;1w%)<~QY*X@9AbIhhkyPZqiss#*c;+!#pw1q7c3zsd4i8IOM8apNyeZD%* zJ@ag;lJ7_L=O#qlh#>6de$7oB^*Ad=jUE%T=FW+aXH9a7d0u@z-W%;%JsQ`qLj+5s z1w(;?kXhUj&B#KMJGPdTZ%_$XgU!HOgTfTrU3AKLIYkqgiXS+Hs&QHexVm8JvY0_| zzcK5!o@F-{csUBy@xVbvZ^%$iae3ichZ8q)hWl|Sqb=Z(!dfSb#rG7>^7-m0bG2|v z3Ewm}zyaw-oD}wcRw)vGDg@J26#w~53>i0}s2g(g^;GpfkYbi~UB1M17A)y06&1$g z_c|nnuQcPfGI2*dDwOFWd&~YlMq#=2&bz7WL8^DRu5kuOO?4*n!ma7_RN-@NHE>lB zlZxaizQhwI;(Ho6@Ed=3o*HCdV(bqbF(UpzG0UE<%j1}S$Hk#U8k++f9WOd$l}VWq z0o{t2g`!ay?c$H)$V-6nS=b0SPZsic%lC&5k43X*#nIH@If$ssKJE4)y_?f}xJQSY zuu;Vl&%GRL!k78TM^gqeZrj#4lNV{U+5S}U?fHMb7Ug6y9CKukEDBjx)|^JZ%Zxn7 zuX1BSJGUh|?{q5Do(i%7A_zBLP!^k4>cuN&=*Is2U zGwHxZsoJ)MlTL`_1GKFiu@8BK&nUw+RA>nWoo_}oLIP-)PI7wvh?{Q1{ zpH5^R66z%dng){>sCa6m80au!^}X!ocaOJxZ_wcQ`>Xx!I&Q!I>No~^($Qc9Gx;uZ zNj{>3O&L-HxoKLjd`OsB=uoJc&7eW&8Y#P^!-;J7cp5`}^uk5ah4wH1<*iw~&Kg$A zHP=sE_Hqq`x8wFooTptCVHJ2`qA{woz5b zp0XNTv=7@8?#h0@m+zWsU|Z5#@&NCJcZjD;aei5o>p2X7eh2O!J^OGx@*za-aZuT| zI)!5{Xtcm*aYOub3bvm{0`1HHZNDzYxQ;t3*}HY(9UOy3*^lm{V{QMa0DqjL*;mqZ zMpU_XIQaG9;6bqrU2ERg8v`j7Eo$$PM@rVOSp_+VY{bj30|z&&o?`%l%vsuo9^t_{ z;H0+B-Ec@$krj6rg+g zvq^C*Jmx&=*mP>!CTU5)=9V~~GumAfKA=vcp6|1^r@^n2OxXuyrMH~Q7=?GWf zGgvWU>a=*|u}5S2%5~ARZOgdo@~g8(gZkEH)=N6EEoE6rpAok57V$rWn)FlBJLIF{ zgxLeE0TtI- z-sF}Sx21UM#NZJlWBlMD(dUHY*oM?4I*_U2F}_8_-tB474`X#5LD~GAIumfv$&hje zyxpDqJVsiB_iMH#eL)?!Y4G8JWb`${anaKtDjA?=#2GBs(W`R`AOKR<5+3Eeb6{p}QpMDynh7F6;aA;c7swsS+Hu^VLI2ttGTqrTY#YaN~E-;Q1$vcTg zOo`k2uk;`tv2A-34FavadJU+jxP z?eQ-nl=r6M1|rLpC1MHKXKP8=d@nJH+(y%6PVTqS=unw61!&~RQL$m!(&%zTk7(Vh zb$X_2lh)-}9peV1iiB8;?~L*lqDWC%MCtU#>uJ}(Hxejeu4CLwmMkG{Y*u_qD*Qee z>(;F(Bh9-Wf>roQQMRigCFAq6!dwrwpLIqgfie!6xRD~~=)Ei0V>=rqboTUVvGxnb z-uvj-r%jtI6qbA5nZJrewoh9UyiDKXUK%wDd*>!ImB^FuSyvh1Hz*|Y7tD{z<3FXw z#N=qccT@H@bEFTEGzr>vlIejqS%8gkCXv&JaCTiXipSp>3FGhFv&y(Ns@Je(WjsYP z2XfreVleNFUPnf61W#ku)U{H9(;yUgTmuEO!beyXOaw;aZ{Tef3gY|3V{w_wESM1( z7jKOHH2=Qxv{T~X15pH6AB{58rS+ogXs}(|R}oBw4lt#c8u(-Zv|UWm^#$89^5T)G z17CYFCT`df-I~;m<4-%A)YNwHGaNXyEk0%hjWPOJm}&TC3OhI>?20-K2z-X@=`F%V zMrbj}@kA{id%1t?&FK5|>l23^+BKTvKyn+B4!e@TPi4-vW!|1zVLKbPY|fKZ#!s0@ zMf}fW`n*L6gL1MI%bV1Rrgdvaz3OB?06XcIr&02W5X&1Gt4COB9EsbNaWteioxfCo z;knQa@RPSA)b?O|$WG?AoyuzKs2#D0x*>~}ux|XkEPG{bkLiuUzAurTJ>d^Tn!rC5 za`Do&6!*+XQGqliTcgNrO&VZ|sM5N)&1vb9r7?TX?3g_2ljzv>km!U!Hk+XyLbNbI zi%c4o*4#2ddm0npIv??tK2?TY`?}Ck?HU+e!2DZ^Latc5n!R_6@T5i*FQD7W9n>g`f5k`pK_647F@8Y>R%NG2*SDh-+ym9>~Yq)3Bt>KhDZEfDF-**CsV>ZO4T|WYGzqe&fW#k>&W4?P=xAWe2E23DqJ=ST@wZW*@owgK zHx!(FbYG6eJ3RTwXVB{K!2{F5bM8^Sq8kcJGor`x8I3uk>(WdbgD3)~E6c~^T{M?; zFVEG0X0XZUN=C*4@aVmF2gcB8Gvl!O)#8wz$3)xKIAftFqyKIL^O#9-#aD4bxBRBU zY|&d4Ug=kZrnK%lk)(yGvu4K&&pw|{$CLK!7)SK(10QZx@F{-RxRWMTFkDx0CY>g9 z#87ko$}@S7-^(*pjC6`_fR~Pe*Zkwn0nxoh(>UmH#@fER@FD=33BB z?iZy`oyHmpZVM9*e&?-dvUf|erVhag-ijIxO>#|@F@;PmBA-Ts zRG!m;V!!!jtZ}2v)acUK`-1HOBSwylmxg?lQR}Nu`w@GmJ*vHI6Aq!Xr0ix*#dCAV`O*{etN=-Dfa<`&0W z;zXtmFWbxZfpO9%G~jpAt2m^tQ^-biC~(Pa*OjYQ$0r0hJ{mD9_AhT92X-rJlGI~M z%m!qa&&fA*NZC)~9cy9x>Mf2@M~3tx?u#=XPpro>)cZwrH?eZy+e3};qZ-D=UG2Kep@ZpVmay`5a* z7JUg*aj9_P0CL7EZVON4Fl+(2rlSD|3~<Oy2>1R+}4o3iErSXD}pd0yLX6ezU_-OX1b2q!owO9X>FX@Ps zKdP_EljqEt6XVB>ifNN)aNiXP%ak^*W4QymFl4h2yuqYVdiDa*arx zmg2kjCC>9XoiM=9`*k$Tnm0e*d;R5@wsA-FE-#A{PCk|6fZJx~ky~<<9Sk>dSx1IE z!u2od-0~~&G4UR_C}+fbY1=vn6Q)c}`Bzb|TI}DwckF|)UWVQw?7hsov)+i1kjFcA z^ASMfHJv$gR(w3X=hBGIvt=`|{P z2rs?G9;IYGfF%=%8ZphT@V9-s9g)mQW}3xUXd?x^ghF2mo{ccP^~|{{?bM=u$0!jg zeC$gmEaO>EHpZ&Y7scv%i!yz$tW9||#<}C~wpH9;?14>Xhqg^?L&PT0RO2&hb)hT? zKVYqJ^QA*$`I66L_QYv1nK62uc2MWoo2a^D6z)ZOrO}YWNN0)(bB#LJvL<7MTyq=> zaL4SPz{;$#M{v!XH6td^njg!#r}y4_#lhWsBr~)K+D3%qR*Y&oDimJepqKVL7*}Re z@VzHTFqAYNg}HboGf~;|XwjLUjf)A(R;NLBOuLHcuy1FKyP}}nR=mlkjkyl4>vu41 z6$X_IFVDSKF)`w=GAdpg5fC=w+EU>D>G&ymoNFiUKd|3X2%fUMcf;2Rc3}YiX;8{` zY@bC;Jj_&f@WYG&)3ClJvbG0pSC#QXGYX+;I{GHf$*~;Sv{tn0M6s><4YNi{rbIIL z6wVkU8KswMaSABltkS#^EokxbWkf1g#j>@=i6c5Rh-kN0{b*jVb~LC7?ULRoO&D2M z8S>q6>u3-PZmrPKAXK()L*U?LklCtyZKMAkl~`RAkMCg2-(iHW-S{n;B%E?FpFNj6 z^#w1lUI%o{V}q&zgU!GO3`3AZ=eyQ&GjrHTzv5ACzL&upbx}x28;O(Pvj){Bg!$5W zvt#1YHPMQ;E4om04<)q%t495d^oDHSc1Icasn*IyFts+#?&%qaBN zf3rSTf4MwnPFa@Duagc2-%}7rw78;ZGp|PQH>+;7T65)SsWmG%9K_Qlsdp?Pj7w)~(xmhe55T;^f%$dyYMQ*&l% zU_wXhu3e&0lf6(_F?i|wYvjuo_?Y~*I)=J(OW1GLNR+n$7h$Io$8x01bKc7CFX0hO z=FG$)up}1nTc3*NQGuf&>*?@}N_Z-`j8kP%d8$FQnU{S?KQ)jUM$!2?C#a_+GSOc$A-ZYFX_@}WV9+_oh9Ue0c<*|rMcoJiVW=isu zTT=!zwN#>45gb@T##SvdwK^PnWL89X|E9uJP(O%*w?a05RF&+4(v%5YT=IR?( z%a?!3BXnv`{%~-73~0T2G_Df+9@+==0!y$3zphQAu+faqhUDj$fTgxoyVOR@xLURrt;$ zS(Q&ZfW6Xj;C%VK9w*OaiWQIL^M1Vc!7*5lLsmzN+eM9%`dJ*4rflIG;Gqs+aX#DL z%01$*>!NJc024kQb+{a-=IEI-1Ii#cuzxfnFk^bZS#<09U0E*S!C5l6CUAMg}58*$W`Nmh?J>3r6yD$i06katQKj4al|XO_>Ig4`hp#W$_?-6tBN z2V1aD9C3StmyU`2n+eIUbhIMcaT<_C%ze_T0XOBV&OvJ^Xk@FyFP=Or+itpFyV$$J z?A59mu|@HBaYcO8`HEzw4FiGdU>Mi5Tb_Tjej zruCvpYfgnQLlYivyKZ4Kqay=|z<+~l2z;u;6Ftsby+xiTe=a%N#RcapJxv)gCRXtI zfbzYf@!sX=fdn@gtNh6;gDuiMb2Za(6W?1Oqpm!T0a#a0o|p0(`q;@!y-@viEjr+W z2~)GL=IvTRPi5)Yv)ykt;&kLb?VM7eaT|TuzSQoT%DKcv=}y@zKXc6uzOID-PMSO| z<%fFkK}U8=9bVf;{^GiNuP~DLO2Zpi?@i#_p3rn1#;+q@9;U-VJg-9n`cXe>QW?lj01*X?s*b&yg-xe6cJR zO!_#+60s?#{T@9I&ulxlPJmSDY{=j#pRHl_Eil-^yLEil<4k*V)TnrXBJ<~x$Zsh#GE0%#}|R;+Q;vz4>p%G}5(n6718Wg8jZt zAsT=VqL_9r15lvooi*iKZ;ufH2}DCd@4ZajB6})5R(>}%P^IUyNt0sK+XJFQ*TbS! z+qTh|y=@8)6`3@Ud6)Ieq-2^35D}^HrkXKOL=sFJl7JOhBDKF;yk_jD<6`CPIk7*f zLLPtTF-9_A4T^jgW6ZW4zl0#-r83L>z|uriw}#lBNUi5lW^KCBQd0KbedgKN3olsr zBaWmV0>&Xrk}zZ(jz_{&IF_oaZ-((mP>F!FV_PM3^nRI?in?>xqd#`g;5dvu)}1=E z&oQ{dr$fSL zc}9lGf+h2@Eh7u!jj-^nY{i0t#O)}0ufJaZbu5@aFBTyT*RNY1?GE6q`i>kSw+o-_ z-}F9b?7F4VKznv015=QgP2f0Oo7{iJcRE)TJj>amIA!vr_+r7VsM&C@=yXt*sHmt& z#wy%wSNu{b_LWR@7sC@SxmAMS_0(qF0s5A4XVEx*pFe*=Od9o33h5SY+C`go?ee^O zjmpj7q)LeRF8!#8WZFFA%=t5J3!Ax@ykOpL9}(wahV-H5dfLnxF@N5?XxDjPQsOD@ zgb-N1dSxtTJ!UOj%;+Qb#nI5d>7LP&)c(e`tKkSLa0aL_F5tksFl3?Aa5GB1J82Hm z*0*LOF;-JAcgoCx!FDt?oef6a(I{fg2FAe{Ce1J49HDXc#+#;)2|>nwR|^OBDAI(iI!w zgevfp?_EDYrIG0oqFI$59IuX&qX3OSa=$Y}*sWf@Cg#tXlZK}7>wIw6EEcDePUmpq zI50@w#Q24)d|uj@uZR;GXUSvu&L}}D#`L4I{smE*nPkJQ^B6gfP~E3(`)C1Ar~^;b zz*ez!D}~Cd_^x7STaJ&%lTXVFlh-j04I@9RjQXr=I_|BvG3q;}{AgBIMpjF`Y+K04 zOT__YjhAWh;*)L4Cylb&PdY7mcYg9?y2)ty1mxZqv!_JoLwk^B%5lUfm5y@*hK|av z3V0e)Id&C#jR>5d%tyzSN`LY>#+-P&t3N+4U%4tq5zUr2bRp&3wpHG2U-){DJW)eH z8khgc8Wl%w1k#B-@CWd@zFstfe%m zY)o0rJ<1Q|dEyph(b;H}b?)3bF>l7y*sx-8?A!I|-21P5{uYOJI%1%UQqm78Q;Aj?XS7qHoNH)`u!8xZE$h``6CSW5EaIVs#@O5p~Yvf68Hb@xENRVo~vj!hlY zK4k#AV}Qs{9s7TEGGsslupQQZD)K=BzMARD`E+(MR%hP^-g=%h@($D zE!wtf&Di*ses)T$WXdsE};YUWNP8~A}FV9luxfQ}1 zCa#z3s;=T3guD2vUYNKGj;M#JpNnJS^x`E;V&sSq*(&-~v}w=QnTl4i7mjVmmU=^SVSz@g#qBYqG&6*=WI0{-B zVgCheaTL&=yk2-I3u!Fjpgye}P-fV#y0A`7v*cWpQDer$NNO(h?srVIEH6*vS$(j$ zfX}XRIbYlKWP{ZIfRl1ur-9i%4kowUFh3nF&VLP#t}$$BHfyCTHLBc7;Fz6Tt{o`r zm_WMx&OW8n)EQ|uk86 z$MbSd!X($)?-Mp!TRLu;3%tO&dDQ6gB}-%BwCNOuuO5f=ID%}~vZ6i%_MU5G5Kexs zyp^XVyc{q6djcJZ3GRZkd^W4WH5F$)vR$~SV{gPcyb&koH0;1XK6qc8Nk&7HrhCIj zlxvCybqf~Z2Y&s}9Syq{FyR1zMTYzj&AbYpThKCQOrILVKKLM(ELce7qIw*L;B4QT zG%$ew9ZW<=gF-~X=0bQ>U+KJC1+j|13ZXco5e7@ZQ;r9Yh^@kI#F)`B;=`frYuh&& zRLhErR1|$i1|%a&X2@s~0YNsATZK#HaLf|42AYb9%q^99kbeyZ?{N12uYg${2y<=A zxSNntnL?Gev-l))O$I2TGqy}`-PNAhA`_DV8v*w>Q&?p#B9RrT2T&oljI_0*`}EG@ zSy^C;$;vowUu9l{&y>LL=*#ocbyf%$k0n%ra2~?PIjGp#zQ0dHAdmax<2Y=W5n*P9 z0w5VB`F?3MuGRIpyED%v%>All`FHR!{UVt<3}8MwO^-BDZEq` zg}cJVwtPPK>B1Zxr}MEwwF;q1RthGVqwAp3;`eUlSPU`Fq;On491ML>bloN*(^gQb zSb`c^uLI;s0p=KGv@+iBVP~84ulLt?*M9{C5+|Vy&6qYdGf)mX^swmG6();up_4&H zC65AP8~`S>QL<z#kyS5W1Pl*xiJN1~W_U$`hP#?hY zdM%(dPg*E&-e(G;9!iQA?nfjt0ijeY}@W+H0)6=R*}9siG6h=Kc`YQ{jr5LuUoFUio$_MLRon;pK1lKZkowZV!6v~gZTWom|r=)*jlZFNO zl=rbN(v!-@1Pr5($9$4|D-WWsfC9#-S{-gRRJDFx-X!-JOg9oH*;g*&4GyUl0@KCd&w;A6}QU@BNtG zeW>3-6a?koBBU;*>e6nsxnp~=-O6n_IvPwJ)X}<(wE5|5|5!9{LH2*Z0SCrG6kV%b zgMHB8vwSZ16$^7Riag@3#CaT#yMFpV(C)OPMDcH;9MJf8 zEgYwP%9~Apc5Q4k4Pw&6RkGc7<@T0O#*HP@ZE@6LpZ=j#j^7X6#+p63?UDy=N2iJo z1mRGkE7j6sJ%E+)M}J7?0KJKG;>?uk(_+Y=LCLq;cIXfXz{e^oD$+o6y);ancS&aw z7WS98=@@b9nQ2h)Pn?jz-nMl@X#i*#DW6(Gqa8REt4&*?@yKu;=Z>>PFC{);`yh78 zeffzr?K<1OYhd=4C?#)oYwEC%hQ~S_NnOGBcC@XNq;#aQx=GgRaJ`^)vqscCT-$Zv zoO9DDp*&DGNy8VOv53rv4~KmigWr8ER)u#vEwn?~0c%fE;z>~sH$K*~|a z9Ftp%q&=NMu93X9;DtC{c~*K6KGMHBscY{#>cA@ajt2M649tAK1fy%w!dSL+DJQfw zPkb+P`=xk7AEkhgBNDNF-b?)Vi|=_eZ7Xm6+n*fMN}}W*t*+svezPz7OqVVPVe}Hs z0N-@9deWQ@ePx}z&A^*$C%ny~^O#C?Wd&BQE4)Iw5>9hy_oLy%kwu%MRjbyiiY$V_Nz>x{1awL33N$41WgiOFiuXD- z(;2`V3z!%6KvHj27vi!#=acpcI;Cw(6RxM9HTuoKet*c27>5ngvrnIN;2Y@7t%|@{ z98}*0!Z}yLDz7TR+xctDyz zbv9#bwj-~TCuI!^`ms&d+u6xyH(^juM~D01{Xx+QeW2$N)X_l4ri09a5q8RY*Qq+Z z!>loNigYdkbKy?c1wH{E@yzzcNojlyTMpdvwqU`6IHG6I*dO^JpAsgnjdh9sV}m-O^$CX`il7W4cp{AB2`*a zekSceQ{t1E_d5wFX{*wD$^dcQ@qI<`ddBQoS?^-a*I&hI=ye^o)Q>K`C{FtEDP)N> zXAH#_)WXgwbPMP3L%sfejs}3MU}g0ZEi9dt)}eYX`=LpX6G@S} zVr_cZl5w(V;#O%dj098&C=@aTM?OQ8F1Jpg>|$BPFpCU+Fen`j`>}6G!B!n2MH5WJ zORtkxDqIko2&JMSF^PCG#bn4Jw#esq3USjP*Wz)0_x*vfaMtV;Y!+5&Ue-KzgD5;Q zXFCD_ERuE##<>e&3y&VZ(VqR;9#~eu2xgYB;``Yk^Q*7EiWjtb91k+fpe(>*gN`XP zCU`fJvWN4PrKI9qFnGz@wq=Ye@A(XbqB15E{R}2J97ffLwtJwk$T$@a5|>dC8I$ub z2?hxbz`%5k%yLQvV-fD$EC}fy1%U5WM0GTLG-?!Sa&y^RbWR)u?3rvbh!jB1oj#Ij z$(Ws&?Q?A-GGqJ65O&Q~7Ep5Fcof^5*`&3j&^2k=EKWY@B(`!ij~xm`#-Gu6#%@Zc zLO+dt*V#VkSA*RYLQ}MK0Jsf;iR3)iGHw;zslaBLT4I(8RSc>91=B(j|wU_f-x^O`Kofatn{T?dQ% zz8s@oWh;)`{?UGf(f|NJ07*naRPHdd|Bt)(0J8JC4m1yP4vh?SH_+W^WP&6JfFKeH z5MTl+QcRMVJf`KfJzm+CWRF$ewYSDWp5QQ=Sx>ZO$_l0!Bry{p0TLM`av+f#sk@OH zIXB{d-}(E&oSE8^ri9um?N2_ue((MN4dc)aoeXVpHaOpv zWRc8$`z=z%y2MRH?r%jf_r+0Vn*cQ#t?OAlFG#?3;4Y(c%nI{N_iP!zeJGqwIX%tz zK3uXS)?+wMoO}n-BKC>mIN5-~u@R>J9_#HjhT)DVkEp>QD=+KJwj9&;3wT)+3r?Pq z2$doW%cVlhd>oTeLyKV<=|Re5Jqgq(Qf`@Z8x$WD%O)cAt2b|nW&1eUg8s-X&FhbU z|M%klS+k-RT+q?bM#CMP5HIB)pMo>5Q{<|4#E6*5n)YP;PE&dp7ZXpQ)fDoKBk`VR z6?Q7TsnoFknH2+FDX_&iU#3xigrjBA!bLIX(Z^%*?RTW$aO*-x1f)t1nsmM{Uqetb zJtJxsRl3HWT$hJY!r!1;*84P`Y>&14aM1^`p7*zwF3UMq^Y0L}&YFSUVo1N9Y)!%V z#>ltgd3zjL&NDMHa{SB={MVu5tLOnr;vTw7hfe0;;PkzWf_s^)ildw~vZDc|w2q;2 zkIJpr*Peeq9_DztVbwLM-0Nsi>1ri^#sCoaRHfxltzA>z?WciS8tYcCiMp*@QvtCC z$Rv!?4&diylnsS#*0c}+z^Z^b;9@QSClvwHZ*{QhTyWevNu*h~zHQsd2_8#Gl|`}W z-?v{(xaGDOSvxFcfst?5C}+;QmwZN^L$^r_Dm@w)@|ygfd*tyN97f8P;}l#3j~t94 zIvR&yRdsdrryfP}Jllo`6bd!GhBj5s{q3^Kt-Of7Y&(@_+LqsQTi$cDsVU|o`z)|K z9+-^8Nm5Z>p0wP|7CQO6cxM|vmmRds1K=i2Yq*w-GQV@|-X|_=l)nDP8;QTO?#3C5 z15UV!&xr#Xo6Oy@`MKcxIM8TQ{;Rxju=0JKoo<0)AaRYYdcxc2v_-TgVo2XP6-ANg zu?n1R`h4;Z#$hBV`()aFCl6C$EM3JK6$-qHqE+n=pyaN=iJ^h>LKkp>9oti-4 zlk!0p=(~DAZclLR!dCetKB6egFWRAF5bknX`C0nf$$sJ`%aE(PcBW%v+Fdg;(@2B! z3`(l)YK$xM3mLA#QYg+WbizaDhI0@`CHS;Khw%3eYuCl=KmJk5(3>y-#LM!Un#2Rg zCax7QE@)NQr(Tfq1AYq((@_oZ9fx=&?As$huJYRg_~U|i-^qFiH&Xz2_=w@rqc>ZZ zz?Y2H0&}o8*U(5z?!0*GSblmixrvWqbDQ&1(0rz4HBNJVsIPBk*yqNkh88 zhX+Lk^%?rKxftDBu`LGp$n!O9&C=8G)L7I&(Qs0hnthXeO!@;C++OQAE^)&pthY8D z(dF1ivF|Vu2IvO~>sf|%o?hz)!3;=<@ zI8ktT)i*Y<1#@+t-1Z28AA=j>wvH|7Q~B@wr5!KvU*kv^YZyt>@*=hMGbEyGi$QCheoN+1^BNu+47y|G~jc+d0v@hK}TOYb(ATY=8yhiHlw(;b^G?1 ziw=JV2jS46wK#Cb<*6xRmFfOsqgw~m_td|nS0m8kbO!xc@6=i7o7p5UlGmxrUO~^a zfZ==Kq!DkAlB^k86qJ^4m1t0U5{K1C)yFc+MtJc`y95}~ZNe!HY(8`)ka`xKY4sX5D*l9!o5~cf>IFlrQxu>CcCg#{y^Hz5L$){Oo(m7v};zT@%Mq-_Q_ma4L)Z z;sJ`hTGUv%QaIpvN*L2TBQ4g9`DZ&k?-~lHJOa}$X*VZ9yYi6>@VE^)klrMadh5iA z1Tkht4;-iBipIb6QqW>y8>pkXr5VO{UG60jalib{%nb3$OI^%ur)%NC+t54ine#yM zNY_mGNrUnb|CR@ed%hA+rQa63)Ojio^YZ@I%69Oee(yfAC^yIYHESW$j`8p#4`+6k z#CP>7V+ZygjauMcffE@_MrRVQ($PRRLpvOc;+OE2UxScw0ok{SwuQ|>f+vTLA5BN$ z>?aY3a-Y91S5gVNE8eT1HaS2a1IJLJ&EpXy9g7OSQMOI5|-o9le!Xx=q(Jd z&prMa1rn!a8%B&|AdZ#WcolQ^*^<(m0tsQ`Ju;nwK)IRA_RTstdh}Qr4@N*|!mBvs6?RH(~64v}{=n23NlH zR=B*QAPo`PXI_TfVZ zW73pqF#~5n5Bfey8lPDP?j7{qbL-oJ$GMjfMrz?dVIfll!I>MVD>Bh{M* z5f1OZ|6U${bw5nceW6B_HHdXIEFe3^>t?{JqhToN{pGzlbpS_$%BR8_wwm;O4Th{j zq_QH2#2M$L;eCZKjJ6xyF+zS3Sezo#eziTGZRT~1LW!$MWnH-IYVMUhnY{+*iGPiw zMQ247(Ui_S>&Z12P=pkeMm#@3==|`-7h^0@y8BQ>HH@Tf2jKjR=s~f!RRvmFl1_w? zFfSvEREcy?IAwjcFux<=2A2v6we zDvG9#28I+DpdXEK$1Jb8hOecyLQm3s8eEAQh0;=rJgKmo0j%T8>h$s?PaK%X zsWLUSwYi1LD%wV1z5HE;%4bq3VNGq;b}~}JyY#9OkqV>t@}2i+=$H{V581SJ)5e&B zp+0i>h~)9sm(WnRoy;_1Jkp``FU_j-n2s*Y3L{cwk;{fzSB(bob0DWd9kqY$}J%pV%%q&@@OyV&e{b_h<>lbIC|>2U&@n59Iq+0 z@(gh%+vB-h2ga^EQ5MRCor^EWVcWt)dYAnedEE*xShjR&bVIp)nq%Y!S64?f3aYXw zmD(2Cb}XLiAl>xFS)ehbBSb~m45(CEftS%X3)3CV;$K@*!F8|u*fBT9^eI!L57B4q z0?5;aq3=4vl>hQ~0|K_CY_&ge-E1}S-3XZu@s3?PhsB4N!Dn~u+@5tNrcR%psp?%& zcrTo>76tU^e8C0bUeLQTTAVEKRi)f}gpGPa7y4(Ze61b9CjqTgKf+w#v;} zIo|miDRlm+Ybc{>L!3)J0K9YcQf@m(9a``S;pul~n3_?yVDaMk0K;o62HnjR+ODpy z$>^+31m~VQ0pl_&)Ah3shxn*oBJPwNOV%Y3-OU{Gk6t+K55ogq=FIs$WY|3juNqb} zGz+?^OSxq&4Orm+SgQt1nWA zh#CM*ML~^m{Ua*-4Txc7ouY#CoV&Vh0ytfPCwjV2CxQ#Y)^u-+uxgl^Ia$>PV>G%Q`dE4IM?N{)unM8^Nc|M4%Ahj#1I4gCYLkDl4e zbD~)j7B%Inxa3RNAA^<}zgs4Jvw=e4i>LmL&pJpbTmr0iIdP%>Zi2p z`ieVdt+*zAaqP;Uw*v1C@UU(0Vlx_M-+edR*Kjn@ca8_#u#Ma*NBf<@Is0=xb4~0Y zUBEVVz^MN@cJ;x-1bcKesE-N5acqH}f}_C#>ed`+#TJte&^9Aa99JLJ0qquRx6HxZ zlIJN`r72U?fec7nQLJ4 zDNp>)b><5V<9+oF@k5Snx31kI4?i50$Pas$Ua}qJo%YRD99;5A2d6AiUn&{tj#a%+ z{ZD==zp)SLdn0=G>l}x98`-7z-aWG@fD7)W901PQ4`cCOx2ZX1Wq#I?5HAtl*U$}V zF8dbl@+LFTEPT0Y&FU;5`7rj)r12BLxuPIy!jmV2Ps%mcx3n$7b#?3s_ZEFb=d)LL zYjFU-y~tIwsdY581-=gh8;|rg+x`-;Xa!u$iJZ3-nSls{MoEU_ok){%_3rrBgzu4D}cQmj_ExAZQ z28DnW;*CT_7T}fB3*Eo0PfVY1dyE=d3j-ml0(2c+sj=%Zk+wY8j<0D}>EWrTV*Q*hFLGDh08T`Qyw`2G2co{->5992acc;Oqv8*DL3KWWiW0oMDLpmOqhsuD0SfS92 zqoIuk3`A&O&cl9G*jAv#{RqSB@n@cnSwvlA{wfm;IEk$Uha@@`i5y~!5(lC9y)f~z zS=(2c(Kz$SP17WG3b?mOM}uQlp~(CB$LD2!rb#)Ek`bItmiF_V)$m=#QsrMfu+2|M zTUxqkQ4EH_pXPkofx!JNLe!#W4yGOB?F<}R(WluPULG~d#8M#01Uw&Ep)XTVV3?Y% zva)g02GaF5#bKD$v>A8DtQj-1=EsSnRCA%djOH>v3vnrs@`MM+tI{AKWGl?gl*q!E zBcTDK%R*W^_w0@jK3I@-AiDSN6?Y<(J-=Hhn&Rl#HH=xPeCcSAaf?4HcFD*Ys|vM! zn1P_9qz4{;Ye0O=n!fR)AB9zxO~*EBR8d~eniQ3X6=XW161Mc^8i??&o8PIBiw8Q{ zoQXz&eYw~56wKa;(L&(<7^(FA*~?hReAWZ24VyQ|{EwFNM8qvP^hZ{-BBP;CW;Ar+ ze9KGVq2pJ`WQW3>c2x|3T&}CXWQ3pZjr62y!{3(>Cg*W5U2BIz+_gJV_lvP^$L{!W zcXQwa&mum&#UFqDcVZ3#cQ7e_nAi{*JcKM16-^bqO$mqqg#Y^JzU;I)`!Aq~ey2w_E zHe@ig!LcH3OMh3uxhu43m2u&0hc2Y6w@v^6*y-g@_~%xHLj%_gT9!RQL8h3lvpgDmvQbWs=L402PlSe50Rm#N;4PsLe#YJgVT$grL6g9+j zaQztL;xtjak?et;cE=Qs#zp9}Ceo|8Zsf|gHB9A^_MvhpEWE_O;$3_%G7~&q#I;(2 zGxKefq2VJ(vh{9E8eP5ojdr}(wg7eFODgulo|kx$#-8(#mYf%_G_sk8spJ}^Z_S+> z8`rE#MR61k5}g>PgWGn}qdY3{(`Sp9>zB?>hMhc!_cRKGA!BhI&by9C?29kIgreOk z9wZxOAZgx437vbw1I5;qV-@GzV#o8Tj549*3*ZxzD8|j4tb4*Xbk+<9HjXooQ-1N4 zAI4pC?vHzBz#}_%#UTn0#9+!T0*u$IFiur=bu>W7d?#%vvs{COi~NW06Hc_RvbY2% z&&R<3i#Vz$;v5v_(r8IeNS`XWDva_k7b2bRv?&angU@KB>iozW6?}JqY>6G)x5v^Y zOVX+L%u`S2`Q+y?Tr~32xx;-bm^x&YS&mhF7AG}M?N`|+p4yjAhPItLq#;*wR39Vb zaU2;ocTJlXp7$=kw}zLwzSfc|ih+qgg|RNah@VEpaxXb}dl9;|$XpN|S~B!?2+6t=nG2GsoN0BX}_q+#$arq zFz>delUXxi42ezUead2Z@2*kVjV+imGkEP4oD7$s51omfSvQNuowa}01UyN4hKFS& zoHa0lt)s!>t>;DKjvN`z_KAH*P7pZQ8+%Y+h^1ym!w|B5|NP(lTja~6)I*Hgw}mIR z0#`K%t;yqjk_SNR(zAL+19MOxYdU%)p2cx@^O(`818b1Ff@yq$+dk`>N-uIor1k52e>N;6M+jl58uTYM3R zlGnH3jBSel>ZXq0AYc=QmKmm-F-mptO`JA0kDS+#HzTYyyhbOR`kr|0sO37BSi{`U zkMmt8gN{0NJdJy|Cb`|X8;+zMbvrrb;q7Q*AN=5|s+fR5I%3#}lt(%S9lH)z;Q%mG z*GoDDSH($-%9_pO_6Z&0;#blW{N1@M#R>2lj=S37!`X&(YdRd<_Td;j!9m%iQD5M{ z1}Xmm4=>l^y1eGI>mnU{rK16d$$JDg)}ePyCqvV~l3C9sM}x3;JhqW*n(NxalYuo~ zroLl)8rt$W`}W;p_j|C(zVrR>$9ZgmFFf%Cr~6f~F5Uxt;ZfQ(>Oo4KE8v}d=ee9Xd8?MW)qyiODc!uOF3yFw3enfu5c?y*-6*^R{j1HJ`?QwsG%2(nPJe<8kj7pWrm52V-D$m6J_g z!l3?taore4gP=$vm3hHM)o~$yu!tWh28mbb%^&|b4%autkn)O{X+#P~!zB!avoJ`F zIx`4Ff(tNk4L2)$Y81+tR6Jx>DytSAxyIfX7qQ4_XpTh~KMOebeQ*tq1_-fc=+NuO zRi@{bF%?X;AZ!W5OC~51YNUwpCBf`>B4u}?8z=B?{}92pffFivl~yUw7wu$98*PiY8Lv8I6&VGG&p9TAwfnn1!ocwTQ9O!Ptd|KSlYuE0g{TUqXB#EP z;=4qd#7?^sYZ5AB>4D&PZtjsXBDDe~w0}i;JjuDYmF4B^(>|UGMZy$^PzT1OC%QO} zscAgK^K@v(npY1Xjg98K`hZ za4LKhp5p0sZ!K`rC~C!gHHzGKU#g{Gp_he=7E-OdF8A2x{xK9f=j*;~-^ICfTENs) zwDi=fRO=keIt{cZ4ywrHdIB;}DG~n5f%(hd`(7Faw@tb|?!5D^r~>yd!vJkxhl9$8 z_+lI4wRBK|xohbdqzN5W3P6=<_x_!se+?szuSeK7-4A0|N5eXljP)o2?|rn)rHotC z(a?q(4ZUJO50qFO4fdh4#P!!0)+s_qNzbYWvWU_P1WVtYf~y z-r4S)ywM(qfYss8z}FCE@G#oM!z~?&qo(f)Z+T5u)>7~IIt;ma^WTg02%WjB3P(dN zurs5freDvf=+!NHkdLZwK_?_pTjYsD^kQogcxt&Pu)d^;*^a+Ya0kkYg>)M@HQHN(6 zkvaf9tw9m0+qx~`I%)Fcj4sHpJ%uM}2Rs)4bn?iXyo4*7iNkZ)D39PH_h@XpW(s9f zL^tB(dI=tO9)sZ~oND8Vln$$|$#zS8!#2cYUpfJ7PkPrFO6L;r%QZ%6l7H%SvgVDr zx)|mB-Pd1BM}w)agQ<7o{#fZoeDNN~DlKX7sNiNHIr=D0eZg_afRjHm4iyh09xA#z z8eV_<9Tb-3aSx6!9SzokG2$n^>liUx!ue{9NHggm@o#xKvhD)7XZu|>UisazJ74jt z$Y^+#Xm!_2eYFs>N7JTqtfGb^F4KW|Ugx$aw8&F5wvQe^#=S%zyHlG%tOW%t-?wy^EhF;xzqWE(k74tnZSf{1DxMcJvuK{k3&6n_Vp8l>(aqK!H z#08_5Zd+OP(Z}%^8EX^R0w$a@+Ufk|2f#l02@5LTxW3YHiQZjPKdaE&m%#|{Kd7St z<7maQ<>_en;upRULx)u5eslS&@;IGbj8&RXoTDB4SB4jgJG=>H+x7qmTPfjlWj$C^ zj6-CH+l5YIB;7G-O3a!;S}=VdIe0j?+IaSRMza#JnFIYKQqsQjus`LL28>QNi}<#~ zi6Or4ZEV0`Tt>mLT{y41h4geQSqDa5&z(dWr!D1^WAx=E4AeQCi%x5eXi$W)7lw-Z8!P1${a-rUTx&^Q`7itV5k6*)d(Unu!SgjAUNtZkKyBJs$-GyNIft0C*Udd!_P zykOzNn2)1jJhh2#8a)Q**Ps@;F07>|fg-FmHi|I{_Y$vl4kg-D5;$N>~?m!3>8a zti^@Yd6h|g=Nc6Md53F`4CFo|&3hY)qt!pA{aSdW8K!O(IE7U zI+RLlEv_a{00%6n>NbMz7;#77L+jSB&n?#K#&=*)-#L9c&bm%n)U_3DbOi@o!xD}c zJk~5m=FeFDY)~e*%JNWPsMZQl}<(lBY0< zZ@gUN3{3H-ZHYIjOVN-0NfV{)HEkVX{~?Z&;qaL0Q>LU`b-rGXTLvI5+lJ4oAITq+ zH_-ldM*}mo{j62Sx~k_kQafw~8K&#jtd1vfR8PjS>3q#{FJwmHY;_&YW>Uu%w%SGN zseZ2mNLp}SUa2p@)Aj+EtrUq~wc?}bMlkK!XP%8Jcx5xeWow|M+~yhOJY8mg(wLcw z>Xc`Yp%yXiL`_21TwKtB(@O^w{cpy$u~tq4M<4G$d^k=LFnQ>?r{W>Di1#(4!AtYG z7*?WUe)kLd&y8_3C^#_ui^bwyuILK@3#pAL=I^}zMjR!2TwPunGbp?_dg!pYf}(Qf z#L3KPu+ne}OFYgVcV&$R88fSt#OH4+zosBwK3^DrU05`*H9lZJ{JV4CNo3YLKZO12 zdK4wF6!4D1HX&k}XDUV@t%&aTNiZNsMw7V5??t|Dc+gMcXfRc83kJb#_DGE!IWo^3 z*X!?odn>VPDoczqeF?7+k}Xj+nHPkmQj<)8wj~6W0ljQyG`vEM1{I`PGiToV9{#@KOby^y@_AhK5 zgN&F*=tEXTQ~>56^K#5G$D9zqOHBT5{~DAEF9q5%2yr(G(If1E9fuK6O3#%cr$Pxl zd^Vr94Lo%eo!LV6>>;ri~jiqhacd88LgtObi3|#DR|` zM}sPyP|-+K7#ZO;YXrnfrPg)Sf`A_(Y}s`C5snFJ@4HxC?^x`x`h-{*U@Ye zVc_4ct%6wNK_=x|q~Xu}#Z}iph0(u-R~}gg-m2vO`#Je~e z)o6ijo7yU#%EWa%I0qLy)6&2h+w{J|_-&KXJPQ=QjS?yYe~7{~g`;6lIvUoYpuW3w zk;@dfVmFQ~rx;}Kp3%P>TLEx1SaYIiuMql17Zm;)Wv+*KszH^kg6|dHu9@S@s{~%Zl-VU|`C~$?Ja5SUg#ee)q zc)`fH59g75AeAy;nYhbXRGz&QT%wQoSaLWBlM-CKM?oZA8MU(}iS;qo0RIQsvvHx$UDcYnN9cQua(J5t;hzxOM@9FOBsFKwOBu+bau-dL4gx&g-U1bBtpC)`gd ze(tB3-+CM{yLRqOetR2{1y8R~@i|Q$0{KkIK__o^0v;5r&i2LbKl8l&Q&jwcQ1Ouy&5>cGA=S>QM8C!U;7>TxZ06k*^BRT{T1G|#urX@rI8%{jT=Ml)`GJWByoG)}e)cNa zdqoCC!z9+@V>@LGj~@r9SaA5-tYH&b7GbaWp+e1tih(kk5<@hZVy z-1ExzfU#?#JWb;l`1z}Aq{3&l`4yZBv3~8kc=*vrIeu_l%4XXVE~QrqUu-w!IdeB7 z!MS+Zo*8Y*y*!zT_X8MR+js29LY7^Kq8X8LUC%+s1^|rm3qO@&jbw4iv8gkNdyc=< zc8-Hz+ap7|aqO(=%paln>!?0{H8T&%&RLJ0=1RB%6>KR?$*<4B!pFxi5_UD()c@@hUOA4$k$Pst~RyZlnPySB<} zN1~%z-a4OcgCESD7q?9qPpbD#7^FHH*rp^d@Jzv*3Lapq>2#sJlJP6Nla6W2HOYXJ z1_Am~13Ki()R)-5Z%=$4rF_KD8XP=0b(r(T^Jmh@W8|qxHtpx)gL<@pYGs(tvuCYiz(m*)C2tG&Ce$HXUh-C%^E;EY9tE$Rmq&WL;@L z`2x7FToTUWrp8b@3;5l!8w3%r%$PG+vun@pEbO;#&6=nhF+3js{G%}dN5fh0UENEZ zux-buEYheG#dQqWhnM$gq|4{d62X=REaK_*vUTjW&x{5P$lKAEbTp_FpJrZeUp1RS zmL$w|R5|C=VQEtt=x6b$#HTgtGfYO0Zt_#tS{tJHK8W0JkGH7NFbtT_B#_z<2aGm?uuX>wW9RXdciJGfD6aBPTe$!Zy&4E*j@g@A_E%dEJEXTw5 z!d`k(hdab}&|SNC$HzF4tVi|qQ%|R(;nEq7Gv{R>Q*a1NVP!wki`zw|tCUC3f^7qx ztnq&a3=xIGygr{6SBW>|J)Eq zgM!r*!6X>HLn))d6fp?Y*^EKwsS_ufjzlFX&(kMNit5^7022m;;gv`Cuuys@p_Y6O zwvlO38Nr|p+fI+2N5r9U8tLg$UctQ)%MqHdz4qg{6~%un-d589dyq1fN-YSTX9t7C z7h9qp8V@DIPK-`+X?agVhfqa&Q)WEJ_;vQf@4$dDb!p^C_SoXNH$~nPGfZm(LqR24 z;TgDHIv>OY1tbme7tR5Yzo?C%f(wJg2!z_B0VepucfONp`=-9?Bxwf|aa@;(WXX)% zg1k^B?ZOO!smRSg#S3CFjTLN6;>4I4=FG^63+hbRUq0V1FjUMakN(8ZHUpdj0iOd;2S_WV&r zPNtxOqe5>qPbRf<=gw3_EjoD%3hrHGdsyh}9D-9Jo5xz>MF(IBdqRL&m`JBXj#woH z7}>stpS_jVd*AL|v2^LuXe3*u8w!@5=v&BWuxO6Qxe8Ak$!HVfO6803Y8d6dRM(ew zxgmv#jsw@TJ4_11%?zRU$vQCVI%33#tcKf{bUHn#RxMB1h>O6(^;60BlCirEGE?!t zxV)#hw>7Xo$(p|N-g}%pu{P#B{BRc9vPQ!?wy~_m=y)6Ny4N^Qofyy_M?;V3-<`es zI2vT)#S4M&T402i&LS=uk3K7lcHioG)=cKx8Jz6Iz3n6)l(6#{MU5w$F@}%E2Yb){ zcf}z8>Kk8;&);`%3?5X0;$oB>x@OBp;v8VL%JJ(6w(6Ri%n<5L3cP*D@QY}$ib~Bw#qv@6QD;MLKLAdu;FoAe+{^ZWDSsBYB~5sVXIy@-qHwjv(QugKE!XXBj5l`? z<>NOnGOz#hpZ`XD@$(ct8eD}TL!ZFo0(jp6TxoBXm3UH8A`<^?`C1D6jW}ZW)a^=` z-HcIW)`5IZPrkUOlh5&}G`d#erRyR<3MB|xKyx|(azgx_e2?F^Z`~FPKl~um(#tC< zV%n6cF@(qt(mT$O;UwL(m!~G4L-X{Z+^{W;3H#Cja4fE=nLZs=GFktNICGbyC@zLa zmWn~v)Ko_wlsV~J8qC6PwCA|9iacM7-(EUm+A;LDIVXRR*U&#W){erKO~;Oq`nrIE zhugD8!)Oe<0e$*qq2a4I+8tvnoU8JztMCS+W}YeU_nuPJk*F*`7P3;_!Fcd$C)|XW zMcQ8c;Y-mS1KdxbdfHKuvB%^2oMSCzF=z<5&dx=dlm-;z zHezZ9Pg^n?&SU(nM#0rVVvUAz)H#@WC)-NM{sQrewPO4LHE~gmSs3JHr~WOE7lmlo z^m_SYdoo~9T;e3rv<2Y%_U+qJ&zOSIH4)fYsPiJaPZkm8VaHb*qs|_imTwgSh!zJn z#)mvvLo9Kgb=ZhLHXk0Z9yD^~sL)y6m+ey0lg3yYBn-_qbu5;20Q*uoFX-1Ps6({K zDtQAmeibF$;-?GI_ilj)sE<`5w=Igyz*tY{k}=qZfe71l-Nc&$G{`IZOc?Qn_g?^K z&EC>sbbuhiD`dy&Xn1JO1Drs^R-`@@{>Djt4Y{uFkcJmdhIXBL0Cx;q`e+SZ0&J0* zH6pE9!iBGlGC}I#CyhwFEa> z0aGB6sOmq-7hDs*lh-f+sX$i0n|#Ud#eLV=ahUnotaq-nP8QW8IPT2O z0szdn$dq(lHI6e2Ks=GBA%|TLbpkW0~o zwlA7tnpwNdS6os8sb8f2A-@M#EWYYJ%3O87jyQLd*Lk0Gpgz__Q9o#D3l1=g{F$XW z4cXd-%r6F#8Ch z^VQYWd2&N8p!C5rj$Pa_DCM}YSTlPzGtA(Z&D^7IEnTFeQ@wz3Ss;4;yYCjoAjgi) zt=pdd<5lR*;CaH?spCKfR=IA#MLr|^^CbkG7O0st0WY`&pZv+&Z{|r__hKJ-`ixGD zBBKFZ=3b3u7-O!p@-_8z`cA#i?`;&^vuLP#w{R~qKicN0MX$1LP^ZY8Idh_lXnIFv zsexa4iFj)kkao^hK5H9f;d0tnE_&IPSIS3VDW1EPg@MI(c>4?A{&tKSb5qQ@|32g@ zJW{=jd#)wlR<0If5~uSw*OGA-?b9|mFHOm(<)ilF5%mWT9!dw*4s57<8T$l+8|rVV z>x=hX@(E*sj^ElKZbhZ5=2}VbNd(}+QasTvfw@-|57yvqJyf+yc zZ57!O8i>q;K5bW_<0V{RN%^b%UWnDZ z55}Sf_G{DMbz}H9o{xL);!NXy1Hms1q5_w$5?xi9w(!$J6y1u7id<8-n?9Bj)r{)k8)#6 z{2{*b%u_Lkg0xlTIB~dFVSnK)js_I}GPW5QQOlyPwg>Et+6zC6L2hUKjVQV*Vy0qS z@jMG2LU$@W;=bdOH#mOrO*r@xKcwmWPP}xmT=Gikde`pVD59jPlcsC2zKKLGhS%1j zg)G}$D!6%*F=AeVP%;- zMZV!tZ2%%8hh|`DjQG7Tt-uhGVS^2mS*%;QCO! z&5S_hfc(D`TX%YN?GB$LLdE>u?%-AmPlD-&9D?)bzSCwLlqyPHSf}nfZQvUgkz2p{ zlXzp^+i}ONndw+-r=$NA`;ObOHyt?2sU0v4s z>B4vSl8so!y6UtoDfcCObo|aE$4(o5UphuvexP#e`kNweCelfGSs-#7lUo2n(AMkMle4ldsWHY$j;3bjjk3fY#Iw&68FP z&M2c(M}me^2GXDFr4vT(lI_s0cp{87xcuFI3R&MKVPk~%BXlzBWhwVeu`d-~O@j;E zwS8&PHXVEF1j=kK@y9s{FEc%|z7sgmnHm^PIKt=RBstVr&z8aInbFX%4_mCb|H4_a z9l>#B%e7WSKFPjm%_&C89Vj+y=ukx*Lz+4QI1D<#SEb{Nv|ZPDAQn-Kcm7AK$)?;B zb^GgcEVmB|ju`I4DL`GKe<#-8wbD3*4s$KN%lU|p!pLudjeMZUXz*u{pZl$SU@f9c zt#ICS>m65-5qqcwv2@Mu*vO6;Gbr#k#IXM5@%vx@t(b_u)&U2KjszpSIS*u5%5U)r zyp%4)XHT6lmE7YkHP&a(=0px)FRi%t;)8} zniA?XJCPw~e2%$=?Q!T#*7cBn46x}?bgmgBY?*t~4`Y*d#FwOJ<|yPyYJW5qyS7AO?I!SmFu=`S--nTzjc zELgi@#ge6I7pO}PVf%qLg0R0%Gqfvgg>^c6XjA^5r?&t%=l0o`u-C>oar#uu!wJ58 z`4WoJ&&aJ4eOVL7mwb%%6V|Rl@*L(t7s-cg&-tm7Iu7qwex!W$H~MH~i`n}N<|i+@ zlVF>CK;u^0md}W{Je)?qj%e3TJ|e7LS1-Twk|${Yq%I5Jly`b0`aiO*#H=Y#oiI2i zKNTl^K6wf4J5Kenbl}jp{L3w_+zeb?TXhY_lcaPtx8A6aZGo3rxY2^SH{CQQ@hNdD z;pxzeF{ulS>&jI7QNE~il(O5k75z@$w1q^G-~r=iu=Dc6LhYpcGmV}q{J zuJn0fR?w;ZOTH;9&|xaRW8Wb6-40W?dv_kYdYG+uhmIVH1AFV^@h|_gbZGRis35>Y z9Xc9Tw{e|*(XSigXn?!sB8mjX#p1$tP2V*2=F?9$#e(oXDdW&-9@4XDHOf$rBbcasjt)-x1po`~xt!D#|Oe zs<#YAL=q`VhOtn@H=+BtO;2fwVi*;@+cH88JBPI*!0v&VB=g%%sv^C?ebhn!1!z`wZL72ExpIUCi|f;VJB|x-B(YPcWW9e zZf)qt5tAx%`8+Vt$>4HYIoferU0lbOOx;(B0ov9ToK)^vx8EKJb`?7-1#jK4BZiN` zScF!ZP-5!$ABYCvwSCtv!5O0n7K|9w8b?D}4Cvl5x@9^7$`=B{h#NCO_?u1%yj&~s zR2<^HSUCrZ0HiHQ#6Jlzf%6Cz5=Eo_6w%b3`(ybbgaa^YrcLMch5PP`n@5j~o)}Np za7gHE^M_QBxJSWh5m75MTO~MYiGCB#;JNf7>`S=snh95p74gD#ENFzzxLL=W_@zRi zfw5=r9-NN*;007uuc}HR@80%nR}q?5NHxUycom$~$>3S(Z87YH_eBK9m1Yby@K5Dj zqvae~PW3HLoITL#C%gC3DG@ZtWhe@6P2b*8Ny=_-vL@OA*VZ_6=_L6GQ%6bW<`!pz z@CKqe<^+`U^fUkZJ)mVwc<$M9)I{q0#)hNu&UOmF@mo=XDdL{n$Hy(K`2bED$$B`g zp;h{`4u)M7_`(=~M;oH`sa!)R@`3%}#}Oh^3hb(yp;1#^m2H^D=s?6xd7-%Mc;q>W zhkPh_W1)lz{{oNsf&W$R4%6-)l*Kc^zcb3=P}(oI76I#%kvE=kow6Oi^Ld|@5BO3E zb&bWp;vVpxu_zbhB`Ngbkvi)J;A~Kl)2Zk9yq|yaJ)LBRJARF0SS*o~7_ z*WEgia)kD;vY2iy^qB)Vc^0GO_Cxk*?3NL|7tWV(;^|mXxmR&^?Jkhf2SXsU242NH z(n)|!($OhBIQAm4Unqha<-2v7u3gQ^KSL>oH9YTFv&jGeKmbWZK~!ZTRF^zm{x1Jh z&Il*RC+({Kem03%W{LI|^UfSyz`^k|q(ob$_t3LL3oq3<|iGX>_)X zSKcP3+pk7}hKQF=TG!L%(l9+rg!dqkqW#Da&uDi`OuxRxc9>jK+Q@X?9DICNJ4KLSO!$W%X4nLP@*0sJ0@oDUxICVM= zyW>X=$8h-j!2W%y6pw?ZBYYfbqK?(f+Fd|(xkw!Z7!~uzsc7Gv+RzH8uv;hE6U^#> zj+qWqU~&MxbnUjfSc$Xu{0w^;xMq%M8^bDw#K2DNsM$a#y4D$4i+tF1_(UvO%?VpD;U4s7MnnHD-Q#m} z?up^(Ydw(NZWoqUTp+mS8cVmrNO;Plq!+ic9wWPJ_nzIkEnysnx`7!l@z(ot9DZhy z;*mN|IxT>8iO)$}g)C)`{Ab|9EvWmEs}1`b!1ohbJEyjG82T6)2j0c>yw`Ea{~e>o zsNcy$5|{W}T#--vyZ9-6$tyJEJYIA^c&S5V2zWEBwiZW#TN8?HInt49t1}>;PB31+e4&G2C5hucrhu+d3kL3c;)^YTDp>{vDM#Ytt$8611c>bB^m z-X|_5T|p1NJ3hC{eo984PR>Dt%5%G^`k3=9jZ0XI?^38dML48!3$6+m@m=2K{lzoz zW7@Z7mh`k|?{4U+7DvFK3^3V-JSx|b^-S7iECvX4@Jox1P2J13#Q}9s+qQ4N^JRSu zoxR##W*=Eh*CMrvV~z!w7a3Fqf0v&WJVhQy0bcGA&gxg%=-E2)N0ZSz zZtP9TOLTzCBa5|@e?g`^FFcdx8JFwe_+1})mbjEx3+~v4y1Q9C^7)%^PF0hY<(zbK zCk(ka$HjNT$+b&I6@AHTNXNqxG6%o)*MAjXdip8) z8JM=Oa}cK2=UzbI7xLd5>u4x}0L@fYUZ7rOPuymN+WdL*Vg*sy4}S7S9O1rUyoj4% zG*ij9Z-1&ecO;$iD9RSc(hMHKkwc_BON=1;!J`Kd1UqA3pJ5bT>p?0RRnSkJ;5^bp zarWS)IEt=OQkG3vs;wPN#d4~KgE$(?)={{`@o&v%Pjiw)ujpT1nZ#k5_=zKjFaq!+ zLuehk^eobKSz3j@2E7$RS8ez-+#^1OSKk3W@c40zA(2iINX173(yH&r59}d*vN8q@ zuFl_%VQ`)~)?lUT0hD&+F$J7>btVjl<;zIYzP4TYgKbMDHX=N?1}Wg7l|8r(Q` zU{6LHdk?Hm=5v-*E7QtMA3by8SZq0TB856lMJ0b*seuxyet%S7})IHQI9blQC8{r#RC+)vnS&8ffI2A-h4Fg zF8-HX>h1+X>ea= z4rfmvk7G^eVsA^2Bcc21(Kn;e6!d6B%Ct>s_A)%DQ_sG@i=u+?P1nZXvgj($o8cnN zRTx}Pd7pCO)bUG6uc{@|YwsZgp*adK;S5oUay>6m5nAQDd*1=nN9dM{(5X|$i)=e^ zt#fzyJNR|#h)9_J*owKS zRJa}Qvgz!so%Ib&fA7q?x1$oh#T3t+I}@uvsSC}P3SNWCDNNg$-x+txr3)Ov3{Bw| z$Sn_D%gdwpK=?m=Mn&`-HDgZg+8V9!5%fgSY=!cD0q+A93BVs}*&rK_>^sMr^~h5j zy5m%EE1gR7S#Vk<$!&fatwu5Hh?AiQyedz8I>k1E(`Vu`Su5?kvYn&{b4GTbC$;<{ zMw#2Zj_+%XUEl=63uUWx)ngbOhq*Na?=wgCv;NRSpN>&BunJo0l}5icP2};H&Lcmd zU)NfvTX6~td=U9^V*l~jMtff42KELvmAQ_}o>K?wiQW_CEo&Ry`VeL7+?Dm#nV>_7 zh!%8q=ERYtg^pdzqBqK!vPA>*;O1>{f-xVVUEWfD7%lD&GwxQ=Kk-J~l1P-};)FPt zN+;vgfpHc^Q$?>Ebr-zOAXCnRhYXN{U^pe=1F)uGS@OCC7SyvpdWDfjW%G``Nt!*u z)9%RYE=1!?*=lCZ9oV}&j>D^@&W^p=de$2W4WGF{A5DkP#;%rjM>1xn71xlp9pLdD z!CAK#D#L|?3cCi0`icg>^H2t!XHj%AnZm5%Z$#L8Jn`oQQM5e=j$J>=N8VAzYfx<^ z@aB{O#_uUJo~$4r>;r7O>e!_}jV}ve9&6Yc=Z}jOz;#d=a;$K&DBm{hIgt7o8yaFr zFSf<;o8yot*@g}n*b&4|Ab@tudV8cOMiuya3YmK9(7w2In!=s~`%$xkQ$U!Pjs~~L zoq`@34joMS*M}z5nP8XEr@8~YygGHU(-v%F`@rF*Gtr?>RSbltl*4C_AC61MfI0Y% zx`E!n7AEvbv(HXZ+;sQhcYr^!4aq*2tfC$j_@qpcPoROtkiOJD!qIG&m4Pv9 z6&%JXopqMDr}-Smud>EwH??9-gd2mlYtZY*k za$B*y_8dm|1=d`F;%D*11yip*cd{vtowyi>`Bi)eQ)6IdKWaLa<+}0_{31FJuRedO ziEV5>qKu3~>shJ4s&nX=aw`;#rd}@Jw-2|no+kjOt z45>#rH#P30{qE>w)M#?vw4b`_p*mngmP+^Dsf!i0v~Ze%!zba9`0oRUNbBMOJ|@1`Isk_NdMY7t>M94SU35e9iN0w zR@4_-{J4JIk;`R_nNd3^E(?rbICVH>Wslzdv5C-);3LhncN99bO>GJz^|{`R=`8Z~ zbiwp}Wa25Z|s5uMIy&`-V zP8;AZpDy?wu!0X?0FU?XCnJD9Mt5%;6Z>&hfc_j5B=z!tS6PvFWI*0uC z9Q37qasK3CY7kPp3q7zc{6+a^a6?{vs_9T{LHzuW*Ps8ZZ^pB~^c+WwRwmwvJ1xs_ z{r!J@<`?Djjd3(UY%)L@u85%4>!}g`C#h{F{c`?$^J4kZWgHdx+E0azG3ctQ;+U?} zAo9M(LIMA&5B`id4DH@Ix+B~a(nsrwO#F<`{j9f*>fbws?KpH#8l;uIT)<=YE#o2e58sM1qZCoIJ2U_7!@>&+_QcbWcq$&aB1&ka=xBq#AhR zE*0S3m4gxob?)pvgXF$}S7m1+8k}?>6WqURZz{1ju=yBMF%ah89tX#{*mkh#Mm8Pz z11K;vFe45p%oO=~Km(4XqXF)l84W}=22!J;8)@QjVO~f)6e=AJnT`ohP#C+trHDns z5#XTKZgB6JmAdm-OTKKc@r=;AhGNmksS``K?umsUp(%4etMMV-^X(5k4+UUILe^<;}nHvuxQK4Q4dxXxK=h&9}C(*PdTRhfe%{R;k)@ zRnllT3JaP+cB;PNy5Up${pWoj*%yP9b=GNk6kc#6xq$}Afbs#UB%H?SSAXv3LHPf9 zrWS?Mcr8)`t!l(>h3+kbR$ZqW`?Ja6`$E${`pl*Wz%) zzBGRRSK1tnAyL_G^SN1d(k z?$*#EnGDU;kT`vlYhzKssW#=|&xe*R{!w}3x2%E+kDus(Hgf9$zdLmiZePT zhg1$oN1giE)eLoNK>vv<eBlu+eH z2nnQ%?1{6Q>_TcZSh4nC!~UopTopqqDw6pdp>yF2Ck5w?!t~tN^Wxlj35ba!hsKm? z(=)wKVQ~qswgTx2??yYUuuicQ* zya#7Yi<>E8XmxtiVoI+}7qWdkQF<;_5Y*W-0!Q0=K}7|PB@M(ZZig4Hfm9)jAvHqa zceA&0)X0%}jv|q;IUQ~-On&vy7 zJ>tU#4#?t*Zdd4o0%H|wy}N}sUCXAMW>u`*sE;!!OnG07BNePGaJi!42fpd8w=F%V!Z&Mh*l!E0O!cxq zGhkfv#9QVj9$Ba3yDz?+%HiMn`PVE7P-D`tp9$ zbiG$Ez2|Ft62m)7KgtY+yKf%{zK_fFaMOFG3Dbe49aAP#QKAjAiL5W-In_IM)x|oB zih3;QK@<|NQAp!bM#F$^9iux&uLXlzxrU5Q>TIRtNQZX~qX>2Pa3Owuc z*V?m38)wwPbC=_zod;vV9#R)+tE8qpFmrm0896GCl5-7{_Gw4_N&HTFqR1V;Nz1~D zF1Vxz#^f49XIZ7Y9! zb`j%0qlVzfHB)$qc6B6@EpF~V)D&At#ht%o5r+KLc=De6V^|H_b4-P0eZ(`*V{RZy zwPo8@(&!Gv&c?zmIhf>@TDGNB;S3!}jRsGhXv?;VHo(@TS@|FskhtbJU2CW4ON4Rm zEq@kY@PjP*ig1Dt9cJsq2DVPTwT-MA?kM?g?wT@@B96E6{MFd7aZ`M-Y-P4Hd&(Wq z(|BOsEmK>WY|>|`Kj$O9%WpF+5+3K386?0zqX~@BbXsYnfj#K+=5Z1O3ZiTKmX1TycjYUtchXe?(Z`*kd_tO|FFv2d_+PtmV|=)3O>~0|SwwaO5u|?LjeJJj zG6ds)NvF9^wpFxai{8h_j9|G|9&y+V@Ak+yw@)L z$@E_EPhRCI2p7P)V`L5NYOLoN&9@Ms_Vv@R(L*aa0b@ke;s_hq3qDC!oU-^5bG_&~ z0v}WRT~||a#i&ctCm9c|c!_~IcI7?SQRLm;J-cJmy4A7y*qOLz;`kUnVmN8@Yz6GX zv5LUg`=!y6+!OA?pRW@Zr9J!hC0*(8&h0IX>i`a&9ox6X+|}z6XP$fHb1}54Dz`?t z{)NmJlQHjTu*4q|Z=??hAp4Ow@wfAm7x=qde@v~OJO6`J%5NVvJZ7MC^hbW=I;P`B z9?$%tLD$bho%SoOTPRYz^O#DpL}F79a*gccFtT;!>Q%9P%_cz=b7tKcCdU7T75hceB0ljh9}I{qUx~-1pF9;to$hbO&FUE@UQGl1wv|SedF3==juWyd01BNKeIc%~{0Ig18@V*&bstGRBU-ojO>YBthzV zLEi=E2b#bg8h7{$VopI*Ubg|z%04}#ws*G}ghSm^Ct8s` zU`B&0Ba9086^@3)7uqa28bGh)z3P3A@rpVg&ITO~=9BGZ%f`x2nqnJttCnR(Um4E( z$_gU9$dZj)HagEneCJk#j7$y^H=$)3-mr_jhG{;yZn~ zMX;`JSFBpRAU-*EHnTMznDe<9TyBiZxTW@Og2?xw_7#*?Xz4=2oT_+DaZt z-$&6?KOu|x-4%uWm@(nDm`qKFGS)QpAnsAWvrY8_d1i@DZ8!BY`f-l(0%=J-+iW-Q zb9+SJ{2kzw<)zPU(tLOT>IOgS;vmeGNEc_q!ZRX6!g`UdmG2DYiqy%ayUx9P-P|rK@B@X5YvbVP`G89mwtV zY$4cw;9%SZzKq3oDvpB2K4LscKP~VTRz5H7<+=iD`x9olZG*49N4U8aqM?DUsTb9;;+Hr{k;0EvVaPeDPL;3Li?|v`7@hAV1jD}~~LRfRwY2p+G2$ zlxQ#&dy^!_ESv?Ad!D)Xcr3}Dz58PB!bS1#zVqD}%NW1-+rJt2%$}Wl2}K}@Q9&$0 zmK+%t43S`*n8+@HCIU%}2nM%(SdrGVjJNLG5kGq4&DevY{*XuDarD)gQ3Vt9OnHT` z1#nD_vap(h-u;UuA*@i=Sod8(7oJ|-wMhVRGcrEawGHHsxjMTkTwrTpW`(kx8tftMkUi(SBFn=L?!6(F* z*^6`&jKq2SoQj93U_R#rBw`t~OjI~Hc44Lhn)_&FmI@!v9zRG?m}P9sdGpPm#7Aql z$Ma7<77yG*@fP-Msi0dmUuQt6XsK%emFN6T+n1T-`Miz=Sb031XWd>w%X9y9-M+ms z_x<DX#CwfWnYWBkqfNZBCWUkJJDH!a zk|MZr-TL?s-}+W8-LWg4m~wkoV88jMvAIr(0}=+8%)e-_P#k6G3hBhp7RDw0*}n|f z^s|F_hL^1PIR5M3{FfNot99J-_%FrGyJz9CugrpMo`G#TS*DE9UK;(pTPLNAz53P> z@JPpZ-kTTOcGks)&0BLUqp`(D=GF<)J2Rs}M+0ybZ+WNtLWxyC@Y%UbPhS3QMnh&b z0FS~@xI}vL$-osBt=Xe`_`T0O1A8&4(EH;zo_{_j-h2!D zD~UEhe>%2Kq3C{s62EBK;w%Qac+G~Kr8OFA%gJmg>mL2Ol9G<2p(8ZW8JzFl86L;` zS!&drXMU*=FfTzXZF(hqeJ?&GPj)?YG+b(NG+3iSM+009=oZ(n{qocC5CYg$TD*8k zyz|2s;?tv7;tziF*W;o4?q_RM8L5~Y&kAgXyI5&o!ql{Id82$mWy^6X^yM=pKGp>% zOGlKl&D*xc-@Wicyuwj(6U#cpv%mSZxMSi33hon)XVB7yMy5hvzJ3g!ykV3 zH+j74;@(Sva0W-fiq&i5TYvJ$v5kp6fB$Uc$D=V8e(5;ntI~yhK5>%ul^@%mcq-pd z(Jnj%DxFDZKIaH5M)&@bCGnSk_xEwfEu-T88M9;ZxCv2RLE1bpNryC#<=o*T8li&;0WA!w(jqa4{}?HAWncv~k)UM@|!9@3ZJORJxySDg@UlkhoZS6y9Q76g6w?Kh(p z$N&8rk)QDxyr#2CgBlnb(~eU-EF2oeet+pDw-wNra>hPQN4I~M*kY!OSkv$Q#b3vI zVD!H|@mM^?(Y_j`iEH3Rt`*}@hUgH`QIQT^=AQ)%QSzIqN0r4wAvTSo-0Mtg``-G7 znD_qs@qhpQ4{`0C4Hn!1E%T}j#>Il zxsIM;U+M_LT-ufXJRZEhp)uZDv^f6$l^@09)2Gn(w3hwQ9Mj5k7Wwr8n$+--Zc4SU zfDJ^{76*5Gvb*3E%#rLL91Wd;;mLE&v18wXSiNa;yvfnET`5+4-|Sg&+t@LTeF!I} zP*~Hna^Xw6`}QA-#Vgn1TwNXe>vu=P;l|`|Gis=@L{Mj7mv+&UBaAyFZ( zS;EMle z5!a->M(Xt}UbZw|`OkkFn;F+vfBCt1?4bv#i_kA?csV}xX^m)M;(uPnzjRCcsWar4 zz>R*a+2*?hyKTqLcH;MA9F!#Wkt!*+yi z+6TxuVU>;u0!Y%GV;1+MYjI8ke$T#rG4I1gvEcPLW9IA`ao3C)F=4{QtZ(M;jy?5K z*3vdy2LmhWW?4@|I56&9U+|@!!2#@(Hpf+t#{Q7UI|d!G zg$xA-@R7t%#$Vtc+jP(~wRx<~)65*~qgxNQnZR!h(5}WAy97P{C-WD?Z~yAA#I)Nd zMJ2S?vs<^c5!J69zr03RqytC%5y-q;Kl?1U#<;wP&&##0;x z{Ven}tg5O-|Iwb&79jA>Sfmy0jEjs_9j+d`Za(ti792NEVHfoqfbyrSf%~=L{t1H< zrGFv+xiOB0mZ?j)0N-$91)WX&LNdzz$7C{>|_2C zqez`XSR{vWl$;C}eai@JV`FAxeD?=Gh{-q^?x6tVSR62w7K#Gtb;9J>7`JQTr4nwt zW{PM8m@1c%L$Fw{olI9IW#!g&L>3kx^gmj@EPm%}zZ=sjE;az+;AsqwOGiLP&l#^y z2CG{aksFOg-~f!00b=yorV5NFBN(Y#xpGy!@sl6NzkBVi_}uhq@!Ma1K5iXDl~|QM zo)a#~oOn*67mb9u*xeD%w} z98Z4!5i)0nq|%lq5sVK+Nu$Mc<%{+7eFa7A% z_{;zHLc;WK{`z0XLokzG>1ZI`p84v$@Rf!Guy9^7Qkix#N7mF!W|aaO=ZAauy?@!t z)$wQF{IgiRy)K@+b4ogSZbwPiiDrQ~VJSRhsJ>E=fjb(O=?oJO>C1jJY?2Q6&gVS# zY96%rl|TMwOrrnCzw+xb=Ycs{{L;dm;=KDLRTy--$OzT#+Ay|WIEgekmaJGFui_-K z=<1qJ3y<(v91SA|wT)_w&jC6b+A~*StRlh-{-15Sb~0}kwHUv`fcE*6{m5`FsN>q7 zLGiN|L^>KsJ=@TDCKm0|u%)H~vLDc<<~ONVE|^pnMWFWbWdf_$|z=CY^M| z*nL;oQqgri3Wr|1^v+wccnJdHRp{yQ=bnqZr%cI;(Pb7y;$C@(moOI(bz->p{XCV% zib9lTCZKRJ*DIF^Niq8FL~S%OHsdr}NJhXLbKheP4#hWq>$fqyZcAmT1CEJK7~MLv z)@)pl6K5__j!$F$%5~Y_V4UY82IFV|w*9(v$m1>Bp*VG74qYh>>B$x6B${ z_mZ9l^y!16fk+=?X)n%6gRFscE)MCWaw~-I;$sT_0&!C@P*^MYo$KGAX#K-G^Wt_A zK)(9t|2AgACpCx6vU=eHjN5B2m*uvDm z`uHR9g)e<6Zow$^N=1~mY_G(Bw=DHmm%@t(7b&2wUl^Gp6eB^M<-%uC7@yru3Ys%ypKjJ2;>Vs?u zndXyccmwv(elu`5$6B-o=XEwHk1k_iU3WBKaIyMDHXg83eyql6_rc=D@&3H|@mpX2 zYRo`!Dlaci9B@6A(;CL|sf01l>Fg8G6BwfAF2?Tr)Dh z`s@D>b!QoFS9LAykq~!xIp@TMP&_yZNpN=vPN79_fzr}aT1pGF#j3Pe6$x4h0ph_5 z5kiO%cXuOh-}{c0P4Dylz5UY#JLjCe*Pd(6;Wo#-A&xlcpbYHEmj)K(*OHTK&|Uq+ zB)=ZdaecOzbg0bNhOlC7#K=+cm!I7iquFYG$5mHkAiN`ihHTKO9DvR$As8$3Q<_K` zb^hoeT@>}_>6dX{ThcRC?b*uy-o~ zyc(>-6GBYD?4obSK5Pnuw!*=6dCH8{Q8_-eZZJkZ7(eNYc>LGDiMPg%j{y~J z)w=M;>*ExT+4HD3FXisnuxC!rGm|oY#xvFH;#ynDDgxKyB_0e=*sS`Ep~K?gXa5{G z3^)l}tbg?G-8)*aZOg#16|CwIAWeV={fzETU8_DJ&~N~H$3Vkgbi`L%=#7J*t4+3b zGctPa(p52@K*K9@52wFl7~iv$YA>(C>-spF@MPl*7<3?GwS15#Gd6(!>hs}m%|rmciMQwbYE`6s$vAOC-^HUkZ7Hphe+oI0`EnIIEL#PuS`a6Gc5Ws7F<8BXt~L*I-0zISgNheO(g z?E+TQ_>7dZKASZw&kEZ+#b(Mz?~ym8b7@~3ROk1Nn>NSTap zeRUkvt?SqLDK#!srk3z&mO6Va@T?-h0al<9Wxeb762CS$ehA-34E6=rI@=BNq1EA(wcnLRk>0Z_+k5vU{>X|QR&WdNB`%C#CmRgDJ98o*RAp_Km}(n?{W@0VuyZmiPO+JgI%}T$Qs$9}P$f_}BxZ3Qo3xhIIrc z=ggfOV@Vjk@X9Mx@pX(d2MnOPv}?3t8;D0DE6c>4lpr4cnRLl}!dBZ$y3&@`i(~wR@%SI_$KM7Ij{ClIdz?g7S^HKk39@tA8lwr@v~iW|%vU`6D$$?z zuJ}|}2`g#W!#U5j9eIRwS_)A+G`gGo)OyyC~ z46rES$NRLik4nug1Rn2Y#^}Pk?o7zue%?7T5TqU0 zy+<~U*@BR)g0ivHQwH;UTWGQ(@tPTxK{P-W!cw|_n{}6we9zL<*WP_Eeu|-cWuIeX z0GT>VfLb90b-E-1^)(dX}$MtaFi8Xw-j z7-Ii|jMQ+Vejko{KkoVQkK%aBml}hw%;Yjpv&I@F864OTPYrORlNuF{V-Ul8e7={Z zpc?-MF^0YOUOYvQj^mC!I&Qo6+J7rH#>)A!?lja{gHcF1(`PAcWo~hpK^mBUJI~xr z$z%dXh?(=|#b5sMk9hQ%Kj(KId+7c+?d1N^xHel0Hhq;H=N&ic z1_6{}7Ce@&LeYU!=B;4#5>^Hp{P`~w+xB7s7E%~nA>e{RM9HPsK_odlH?K~4fBk5I5te}l z=8)STfM3kj|{Mxc{>AxA>?_lb_mDUg(_Kq-xJDkKf`5QX=#j zXqYuGMiXfG=aBa>);GkxcaXKGLZ}+^Q+71qv<}xl{_}~HyuTHbaK6WUZvH2t9MbGw z9#Ph$MZ&f|&J0Wzm06>w1t^R507T^iOXsZ`BEJwN?Le)`k9?ud(!!!6n0xQ(oc+hgP$+WBr?woVgUv5t7E0y7{k`GyKcEH=JNGBFE}SIyy#*&YWGO`&=5^W z3Yne;qicaDbsWEz`TVXCQ3^ol?4{GhT$Uqi-W)z6e)z<%uyRnf#+n00Z#0z8^U#1N6+t*x< zu|=6ZTb-<)+Dymyy;RfKXCW(T;P0Rt{_biK3s)?SPpKxDIeltWML#YftN77pV`I&V zEd&!<=h^XXD2-lDpyZL4--%nVxG+woGU%X=-J(^KmMSpL@?L|ktQB?Pdyhgj*uZRg z8CX`vZ)e5^mXy<){(G_t#Z1*A^oNGx2!fh#yz^ds|GRfaUz}YXMg#rgPq-u>3Tt5M zdm8?}SNc2kDzxN#;#r(qbv1b^TX{x|jMrXxDVq1{Nyh7XDjMu!4zqAyR`UT<^^H2N zgj*TJanc~=r+UQaNOoUC0d^zO!_KMm;` z*c@o&4D@JJqcKuPt1~&dO3dm>^~CckNo5ZarWt_ z5@=wrGsywBf$m23Y17o9Ngu$VVv`^#{4TvXPYqK~8!_Cq13GdWi$}Uj2cJ!z9FIQ! zM7%lvvpA!3dE9j8-El052w^C_3mM}TiLo;L9;!OH-!!G{qa ze;n7`b8nXR--&!U@4WM~R9&OIIDw*Yyb`xxKgX@1+5~LHz^<`!Qzt=w^>^XVhp~h$ zW3S>EJ%9|p>EwRcV<*Sa1bmw!Yi#H!?sZ5Hz&Wp+FIK@~iW#%x75Hf#eF6+L9CPI1RG4-l&`_Pmlk0#BfoYn=TG23c%)h86 z`Y0C6pT#z|d1+G}Ob5QU&Fa&bw?5n0Xl%(d0brgwp=?t30A4O-(tbOJ_xJympQkAR ze;at*&BS+AB7snq%92WMo!CT0!}6F;{8k%IP1BY6ojRZoW$7(r0=RwujW^=H@BT0o zKh1C$YlAmsd^#=s6sLvFtK+NOmCn({z(O2rGpO68{rV*OUihx*gnsfe@mmnOS>m+zG4NrhT4qpGd~_bKJNM9 zy)l)2{MT~&$CZ~2;IZVzmOx?SiwC8=k#Ci6xlZ`Nen*}{ z^!CWnaq|N|i!(b{#A#=r%h8O-Mj1g(@#*&+*SUJio_a%`vqz4d0?|DFGdek32-wxFUK8Kut5A%{YJMrStb5?aB42Ki-eO{^qfGck!yYiJ+Q+hRzigX>-VTQnnN>?OBcJX>@RF zRt(QwxFFsj7}~O;EG{27Fj|$Bp<|#e)@QS8{^9%o-PeCK(6AdsNCZX>WB}cBRr-`K zC&#GwhQ?B|9?j@#+J_8K4;&q+kB+9BGdm`s8eQ|;+MyqP7?*tSyL>m|`xji8M}8dG zts9+`?ZQfj(kc+Ef<)v&RJ$!rmiY`W*kM&6i*C)*%ndZFTY&%{ zi(~S;KRp%wPU;h<_U#+pJ9LOvWOrF<1{#Ei44uN8_hdu`UIqkU77Z@nD_t4^3biFN z`s67w41;Uvd&A=1AKgo!;fQEN*{jBVsp3FK-|s8f#I=m0z%B(EEc0?*Dl@<1(Q0Nc zrm*E>3=Z$h&%YSu7(usQb9HI$ECp;wCc<)K0}Ym=8lcin&^dLVV=5w^rO}px5V%{_ zpb71s>8f;MuY=<_W8U2O%k%$WyUpJdY`=c^0Tf%mXh zPYF<5r|@>2z*@KnJInE<)lUc>J^awaF%sIj{P08KhFfmU(pO>PcAqqig)?tJY6%mK zHEGh9IQ3GXs;C@O;cGvDub{ahqsGKFKm1X2l*|bIyJ9FSMhq$ydK9}TG0R;Q$Ru+EHmfe zPfM<)OTfV8I{X(JWuCbrmZ9;eGTFybCHpY8mw&Y@#?4(F!`V84Ysr=hZs5BAw%d~K z+fZp^C6tvse%C4r1-i;u#j7z;+OH{|osddI!^=R7d&=j|of9A6oIUyUvvCddc(Q>8 zGSdx+QtM<&*D4xeD$azFGDqQGojKa2*zWbaaKNhKd{qYq_Gs7%9H-8l6Qe#F8~+^q zPDZWoxt)pz$}ej$H*r%Nx^f@96%9k^S1^eZ*-@WO%QcqaJ9TXz9B%6NBn;S86)_=E4> z9+zKoVe;KS-*_{A^57$B`2O_H@5BXXpB1fW6uV1fLiq*XK*Y#0aqBa{C(rPi&P#(W zAG#m*&LM+_tld4T8j62@Z+P_J{-6Ku*D;{aiJ4vY_%vbtb+(W%T9T=J^!qA$SEsJ= z8OnJ-6Zd{5FOT_jY}`Xd!%W7$^PDq_iiVyCGF`T%>A1+}&|Yrqa2$S@Hl!JO*G1UW z$&9h`2gE18x}Ftl*Toyin(sdLSe$+QF>zM^Q{sf)RKm1u%{D+z$-p2~b}1k8IT$0# zamRO#i9esoGxE87o;@1ik*^38&X_lkK*O8y?myp(tFOC~?QutQ=mOhv;EjNAjL zW~d4M37H zTlu#mj{()#^0>!Il+}))qG8ZmZ^sY6dsm!9prJXXrB<@Ic6CC^bMWTh;#qzz8H(aH zE9QW+vfuw4+W?}v$%fLelc{S$(CF4{ug$F!mMv>knz2{MYg{^pxK@uizVs+w9n(vC z^>dAE_rtqAV8rNA@%-<86K^bD9(P@NMchQNp?&Mt*%wKN`QL#CWEOOvd$q+ez^FtZ z(15}op0f*l>`Ohuy5Mz_5mv-K|Kdw*xA|K>|M4IHAkJiqQWKmew}57&T&BiI1Tq*O zxO)nVN1959(vHDjdlDIJ*a@wuujHbp(5|um8clc{0;Ymt7j?6U6U< z?)HAOpe0=S9EMFfnKFoR)aS}$X}u&z6DQm&4=!VC-=HBw;y&!L+kr{{e*MFvPMhGo z7--OW@u*#9O5jD=M=826=Rw+i_6+g#9Wa{o=xIFFNdRo#xjUAu-VhV%{qX8rZ^Z@z z8fTtzavan9i0Ij^D<{9y$P$B~Y33yCqWpEFW@*eS{kd?X=g#aY~@*Sq8*Z?SnJ&-5$5K!96i4z<4&Wds^dq#B4o1Gt?qbZFdvcTv&MtN}ewaQ>8eRv(IEzLI~J zY+N7c=U&2I9H)K8d-BUx_-P_G$567UkD;F~>`S15z+JB{T~f{^-w0#AZ)QDhUhwGR zv|Gfj^aNvJFYLElfq{Cp4jJO**r{)V(+7X?NGxNF2X4KYQu3mr!C;oWnwLBdTm)Pp z?+YEBfRuKW%gh5T$98Dmo-~%(PoFhA{`Bm#@ia**LZtEd2lc#LMDvs;A^d zZTQk1L3aNmTST1JxApyspx_w)y!66V(#@{P-#s}MoH&b;a`J@Eo1?br^J}y z!>MRkKo+=O9COHFILIBNiU`0ss|7(ws0y8RM45+u{88NT<9jifBCfgg@;HxZXpb%^ zHVDl~e{DK)t0cFRt@Sv->g?06T#e>xFq+LZ{&&<#=fI|G1_5Nw6=X7BBeSkzyZp#Q z;*`_Q$UTQeMFZIdgojRCDtG3iVpG6mR!d`__cF>05$GrxXxPiRTOb(E1O9UM?0CsC z^I@anoPn1Yfd(oX+>a?0?_|A3C>0z!pfb76xdPn%s|HKVhUkD7=d0s%qtF#lHhLNN z#pm%PLiVU5kBC!G>=Ore>0E4`V65#LEf8-CH-1qNDTI;u8# zHr@LegXN#k|1IkGJSc9$nEQskEBL-^^*cU89Qjkhlo>DPuP|Wf{Hb8ET-yEZdx2AZ z$_rOxkPIC$BL4i$lkw@SC2`kv*T%r}&&T+0#qm4rr9zk4r@^WNBvtln(0CNb3L|Mm z=RkwssJS^=&$rbmsD?o@WA2=I{^ghBw=WH177>5^<%8J+q8>tLD~1AMhrkyC8NuVF zFw}@n*5VoIa0oX(ONU;?!TK~5HFT^}c>>4fHH_&i4m%_UUVB{}amc|53ze6GUu9?} z-R}tx-^Vnk#9`bq@LS)EbIv{|&#K-5jx@3r zpd!^i4IXx5)AyLrGmLGCP#`f+P7#*gCqf@g?ljapb3$^yP2L2Az@Bt1#|n&B{Q-b2Q?) z`f4f~jyWdUwV_7?4uI7rUdl7+IAP5IxgQfF#*#RdkAVhMTr{Xpr9@q_k>F`3yfJ0^ z>=^msC-K&h_c(@dUwr3VH)f!ro;U|DmQ-)VahwcajG|%WU1nPXLKlrfF>pWKLA)}2{|~^K#|tW zN|XXz>3qox(3H5&|9HN_`ucQYNrA9Y`fb(kb`BHEh*l4bajojE+GVil2TuIxaf@lIV@D>`G9+S%ZcI zc;IQ~Y>Z*3sKx!QzEv&gaBNem2C>+6g>1aC$<0jwfu@m=l)ZleKJp zn7@2sOkT4ij_PwbhE^~3?;aVQJ5e%Ca6w0I*DegsT^d$oa-cPj6|2FvzajvDlSeQO zFaT%E?>X8GJ`pDd!DmdL9;4Y~`x1eY@7?j8tZ1;IqJakGk_L0a8<-0VVJ&wiX$=p8&MUY4sk4Tt1OdO{SG6h zTolh9RcA#>>Q$f5=gzw>-``4E@URgh<1Y{1A8&5j7I$Z$;ficn{S|sw2SDdV3GTK# z22VNcGXV^UR#s90g?!6~kT6?TvY5EVo&+c{`g$5<18M$@18iVf4^wNHmhs` ziGAU|djk%8v@r-YsHd{>4tXrBwn5iSf^98iFQJ#+IC%C_Fq=C5i!b7#U;ZlI_-taF zS5X$X{ebK@K_u6|9{DXCg}Xs;f6rhHG-Tk%^FOPAz19Y@DbS;W{WcZ3U6PEGp<#r0&vT$-jA}`akfE&I|+6HHRzOVX$=i{wgFDOJc$5 zMLEag@MOzdw24-nIMJ{c$+Jq}241ZMEh+nytI}68Jpb}m$_{k`oS*WwxM%-;(h2L{ zg4M8=QrLN`*TpB3SH*1N{S9l-qExW1AMNJ_HRivam_ozS{x+K#Rs^u`RPO|Oox*Ud*W3iC?AH4n6 zxbmV4*uK?r|9C~!u#+yy_^*G$3x$~gz3{nO+pWo!u@!9m?HZ?`E1&zzU*qY2z7-Yx z{nLjZj#K*fiCW-&BY`z5qjMV`@Y#%w}VZK15nARV~28d@L3Y6@*YE0PWLq)b)bajyXi`FZ~0 z#qlzU)Q<+g6_;IeHBC5=jBee#XD@;bj&i@cjj83Bu0`3VePj|8!byI1ZT9N{a8U*R za|^9a3qMB=KTV*ata+dJ?8efG3bw{Ul|nNXKRBM4egWaY#{o^U!RR_RPgyeI<= zZP^BYB?0ah9Xb??gT@k3Nl0SszxVo&1R8{0mLUQ7{7;zhs)}-ed}AuYatx*It10Jf zK}5FqLF|*O=#ZJ+1YAQa)bUsFs6f83OvQ?|&RfOOVe*62l7W zDul+63Q)sJL8#DEJY_b3=QCVU;lNyN0<~8o1ID+Rm#0D~1Ye-kZPA1;;@k_)L*XAy zBeDYvgGplt!b%57!iDfu#u{s0GNN-;QTP%b3RfLfn?c$z<$D}VNQPJ=|k?wcn z?jPI}CnBVpG@%PWj+IQMp`c(=dFgz~d@7vG*ufOO?|nwWZS-WIpb7i@ReEmAu;Ixd zoVvDTEN;K%nmB|=t3p#)TY~BM3MKq=S-F}B z=?xfrACvWe>+Qk7VQzdfbEd;bFD&Mctr|o-woWw1$*yBX1H1@dQSO#*f zteklY59iMB2->WaVGUn>wUyiUMs0#_5L4_RK)KXF!yE$*yv4UrQF;CB_S@MqbYirn z>v?rxS5+R*wHC@>c(`_-R2YE8_X=7v_)=^oGV?KK_Uw3{wV7S_{NhuNJ1#m@R7B$@ zO}?h_%)Bz5v@QQ=fN8WDsLE_f@{;44X#n;H-H;Pm(eUBe82sKajNYwr$G2~cqYpVG z8d4#YrGwD<26$xBRH}$ZkBUhs+2Nl~%*nQ42m=ijWP{r_t`m(YkFSh_@Air8b`A|0 z!0}>QNyq+_Pgs7^gr6066#o+UjXl6?7mBY`(eTb}wnBlT9gvjQcW?c6Tynv=InI0U zz8B9w{8(6H@i5WnktWa*j8MIBXXR!7TwgsW>YJG~ly zdUe>)xa}9eh_jGmXP-=u2C5FqTer=Hi0E@%0GJu^ zZ9H=mj{Ed^bK}Lg2FJfX8XA{ebVVFTGss@udqfkmuDb~yRN+36{1wLhtm!ji;nZpI z)rys|aqhg>iXm7P=c_)ICvIQd0Y93FuZR3rudQ3ND%Nh?9P41SY8XLH+qQ`==;HE@ zoyhDrfrhC@BQQ~kK;K@n1-l4rRN99wM2~BX8c3~7<&J$CcJ0xq2Ik;Y*|QAYq%k*& zGW*vEH2e=4DJvRm6lP~`VW6Q~;v-?6vP(SkeP4bi?BuyL*!jBwfdJQQqsgJ@?N`ws z^{8kt1KXR7l#M2GO9A`xX2sKk`rpmu_PdPebF2UKC*m`#V zlg~P(_~Qfj#aXAELgUA}8CXNZC!P#IY3yg90r+U===?*VY1`O;0D{bCs$bOI2FE8% z`XU~F=xg;gZ@grk4oCx%-RHn{NyjrS@|Vh=XOf7kc?|qR$NN+X(ND# zn#i(k*evgT@IhR2=UwU44ZMbmIAlR50u46uHb|UKEVPk99&jfPg}d|9zA*?WyuZft z{<$chEwg`V$UE_aKl~xSGoXK*bka%L9IrVvY`M6GzxEiEM}nZ>8~^s&jjq`Z9s08} zj8%aF^?lruL=b285*(^xXl#Te&OR zQkL;Et6t!x?NxBz&~tNFt&I=HFN@g>YY&L^JNBW2$_O;{rbh#T2Izj~$N!3--}93= z{&4o%Q`uAm8Vt4)xC72<>oN~wY_Y!4X1mXgPZjfl%m z>YH0xd*SFLUowue)XOZj^3Wr3rI}nS__ONP=V?nSiZplD{JsLdmLRq9e4MnCsCu|%ndCZ^u=X1W+AL8HOJoKp^nTn15=fD0fe)sBY z(Sb1@#CAIMq<+QrWNbl`mbrZr+EM0sNqY+1v=5lCcD8nza|S?Q3%+1{`PYhuAN}OV zF>%SV_%cF$@OorCEo_U#8B zic5NQjnmFKH~o)xY@OHxTnrfGILwhRBzz3OD}PH{k>oe$tj=>CCN9*0;&t|X`iZ^$ zPK=@_%oW#P6Gx+?3^bT9ln2$N1{Kt+2GYerzK0!_^o$)So}IfDm-~2DRd8ycVFk&V z&+z4*#ul!ig716+4L!TE^$!2TK$NtSNhWaUnEE%uU7E9M&A^Fvwv|x!ClDX@C$hP% z)e@7ZO^MMs>`xAQDelG2JNbAk8d^qu?Bq(!$D~f$1;AcBI>!>diaRT%lr<(1{M#f% z4QyBdnx~+QAVKizQ_sNAW^!xN^`2BC=<#~(ZW-5lSC%Mt1Qzz!TU;j8J-(vuUu>_egaQp21#f#!qDjJ%@ z_g7qgc@b#Hd&G_xfMPEH&DVb<(4aC9F*2A0rKp1hh~^T>*}WsCAS_3NSO=pzo}GgwHnSHRR0?v9X0snkT*uwPdkQ_v*K1*rxOHOQ{COE|{lnAG z&@`!UoQ_iN(Xmss!XdGYd_9}_?O zEQS*G`vhb0dt@+9WJ^giGE%vp$Z?ogQEn*%z@Yr6;855pP<(a-P)LJ`p9XpM;aJxI zHp?)uhmRN;e|zc=@&5d!anCou8COu=*{OXw0-Cv!H8;z=2WQQhi-Qc9xCZ9Vj}#zj z$T7CtChQebhZ6#-Q=-3g&YbxDQ-6ww{`_aY9r4^Fzl^g_#ZW|u*<(byls-zdB3#n3 zbpc$ZXtvMF=kY+-SIW$MJYhmSNQC>n*>hsxq2Gw_eE*&}go+iSFC4YCCSh)Mg33+! z8|_wzXEP77f9jPT5DF&ZBQov{sAyncH-QEKOt67S zukgSiGteL!Gw`4ShDUXfg+bCO&oIJk^jN;KLDxP?x9PMHOEz)Z#r#zL1QXX*X5;>_qhfN4uHlsk_DbWZ+-?Ee*fFw z#l-_JXV3Zx(Y;%@Xu!Te4O35vF|eb9Wz|S-+u>OS|KK2j3)jbjF^Xx_N1uiUjoCHI zy|d@c&mIkfG2|Ar|Mz>8j~;XAVYyeb7Ce0bw4*|F&*Pi#4vEj%S~O~05ol-yY&*BD z!uj$|qh$lOPE-f)&~6oQUJc7t)ulsQRE|K;EY@lGlH{a6aasHctocQQ*FeK=0y(R; z6+If>p1mV#V`ptar+WS5dw0gwmtV^L`{GTqMSr~Sf$SRo_`UbW)fZn(lR?VNF(UWE zr!|oCZWrWU#?9gNn)_0}b|>`P1Nc<7n=?`?vIHIQ|4O zQq{BBmV8vmVAsW1(3ASb-;-9MEAi_1IXe4As12pj}rOZX3;fOfr)H9;bQO86X zTW+`sLL~s@_nDhxsS7P}PTE7pyDn)~!%5>sxgT|j+5yA0(B$Nq)8ij(TNy^M;hJw! zWphGbs+$g_DQ(@@i+>@#+GTdaR+A0Yjeb)&@&X zEsqr+_JP;}|80gA)-k_zJil7wrqKi$*S15)Xia~TRuvtiajP~_l?n%_1|3CE2YTUa z$zywHy0?3u4vtxH;DcQ9T1ue$3j)<6Kl~^LGxwWryEOw1Wo2dbd}x?Km~8~YrBZdz zerolr$*U>X`7DD<;+wge39Jndcugk*JA^FV^MCnUG^6|e_iw&AD;mVP*CzHpE2|9N zx;@G#$OqDmJS+}cOvD32u!XJvs(G^{03qz5Tr_=+S_oSi#(-y)ny>N1k{*ULF5gT*KD8 zYrggEI2zq8{pr{V3+dfo@^{`>ccj73`n)e`l`##l75qdJ0^Pb7S{^cHOq_M|t?AT# z>)Na1oO92OjyMO#bOMgd!1|)lBIzY{ANaHH z$u`pF`|32JA!MzXw`yIC_}9Xi4SCk(-pzcySC8(|zwfaG=~{r>N%8TUZ^eT@dVs{w z5gBl_dQ!U9)+)B}7S2pM=Da6u$WQ4MF$eMKOB~lU=!cW^F@0=ad+~+%?Z`1Pa6rHK z4mOj4h9X#0CK0m)Z9!{;d93~2Z)D?SzGr9eXl0Jz`afPCn7KjoS*H%Mc(sWiMzzGK^F zHEfkl$nGUa*2Kn0SuV;0(%^+KK=upUe#;2uQylHrS2DRRcG>40VDZ*E>ekA^o#jEsk# z{Y&(3-7wC)^eRf1IP(;OwxrBGScL<@fIvp&Z*MHPbaAj(LHySMSNjw@qCAeo$fX`JN3c)6P zUuK;^S*OQa{vO44>S2e*%~xHCV(Xd=?ejH470hN<6i^um5V?-U{4E*tzTBRma7aWD zC_%Bg9cB~}#lJuDSm*}dgj00U8JvAgMoPn;$z`-vruTQ@ppaFdyC#`f__zjxQyOxr z&{}otMm>&Cn+4phXm}D~;PvPa@1ajXpDgLJIi8AuNec3Wi9hoXeh8n^l?E%%P`C*{ z6^BAiL-AL?`elq=xh77lXdkzH_q*BUSbB5+m(?A@x^Q+;jPe`rNvA%`eXItjjN%sM zuLv^Mwr^S=)!+CTPM0eHyVXH`8v?T#8No}IBrd`lBPb&$&(Rm zSm^O=U(T5wpG=#c%c)?nw#{l$p;QMrP~K;wirrhI8hd7IRH11Wc&x^LSq-f;yre;3 zYUP47BJ8D)3^Xuzm3B>?E{v$1IKxXf)1zVjniw{p^W_-=GcvFHZo4H;?sG!4AVP1T z!R&AvC&0%wNF&ml*VhgW?+JSqijiyK=n-G@=g;SC`_I^O_(Gh2_L*7g-4$MKwm-mP z*|C>O$FY4mPm#M1=fG!G2TmScwrS%Uf@K?{DO-8m<34@vf*A9!3GwcTk!(v^9=G3o z6J7GZktK|^p{wff^%h|N`LwC=-l&mT3H1rilviVta_#W1T5+6Q6N035$<$RMh*1OU zsD6#Q=}0Osg{K_ot7PiRFG+L%i}0MX_ZSr2O}5&KhDnRaI?dS`x@o0dr+43cV_ZUT zRH}Vv2&J!&{U+?oe*dkv#pO5`jWJSJlYz8xo!eZ@fNCfTSDic`X(rd7Mb&{05wd1K zZZc~Cyr#{Z6@MW!{o?2kv&!bSAOA3pC-Y*7sK+-d8*TEdapijC*&Nh=SWNb(;PY%k zEA6l@WrpKxsC_))vv}b9KgdA!6-OUQMFag{ICa7dyjdTIRKAq(nno`4k#e8+<-4Mf zj#3}s@tNz<09%cYczev~xDUtZi1M~^{+Z{}4DuK%8rm3H$smPt%yp}CG%%gM!zAUn z1b8e1m{Jv(~{y=Kk+^5eL6w>%-{LxCAB#d}Zno>?$4WW#j%GjeZ z=3Zg%aib0u@tqsKxxXTgs2rE4C|Gi=acKZodFdsODhC}Sv#8LD?`cpexPa*wxU?itYL{tQ&GPGya>sho8k&RczvRV(}H6GFIi%kbCcG^jrcUQ)29>%0 zb71q^KRg*jznl@Lm$!?nZ@MY8L6zU5EVO@2*2R=Xd2N zD+kpd-~7o>gSI?z%LV7gX>`i(N=1xLMCu)6ftM%Fs833Eg+U*G-(UiVc^C*!X9*c0 zu1#DlA(Qzwj@KhJ`MmU?p3#p6b4Su&!V1&0gBVZ!=Ci7z7vxbdD`2bQ1R1zC)47Kr zH#emYti@J{tyDiOU9*WwF-`${{Z+P}?T8Do3A#huEt)l9JBAGvS*s2PfvI^*m&ec# zK8ZIubzN9-a7;Jb0~^+4t0{7(`aWR88az@w^V*^*X+$~8+`yHy zR1zADP<|Nj<8A99vKi!_n)Rt_s2+3KIx+gw#W9oH>hT$z6`i_vBv5n+{Y{$0L;}zs z(Kq6!-@PM_#@TI55XGJq(zA)E)JfpVOUYld!?Z7apg2uOiD#Sft&8r_85>JQ!y9Cd zUzj*Kw}9P9pxq2?$}4cAQ!2m6OVWbJgG)zQ>A+aZUY%V@6-G^ZH?XEXxg7a49QpOk z@BSEb`1m_lToxCec{-VIt5gUy2oL6_ZDv3qIaS_DSgFe#5*^F)b^|w)9|jw&R;fXC zmVvwHX}JE}+wX8^#8da(7XwZ_G3xS}%}?FFCQmuG2^z;syVaZdLwHz)A%6-deFWb# zc&g29aOcrSABm}J*2g7B9T@|0{ti8`SK2Nf?<}r!DCVe~DR96zu7S^Ts|0H^=^;O< zn@YCkDw3@>SN-9We~Nze{TOiGg>me0MQAhy7F3 zg^f&Z@ZS1$>$CdypHz>(Joufs_S`d~Hvz})-MeK)L+T}ProL0RidQupi%%LAze&41 zCv9QwGnuDsG8=!sMKEU^Tj*9AgzIk1qTGXc5{|Yo9iwu|w&!lz6a-I^Vv?pw& z+rp11Xwg0w{_WVqsEGU9koVZ;*dp$_?bbLPn?OH6J}Ky}&M6c_WoHWlT}39jIt6dF7`373EWTd)6nprOEX3ZbO1{V?%uf89&A z?@N&U{-{wgi){ZM49NpKbqUMb&5YS+L4~UFw(Lp<`jn{Iy-z-wFzru=X&v@X6&0z( z3^dfl8L3v8<|8OJv#0LivzxodhI?mJz-FH`R?H@uZPS62cs5EDpN@;?U_|!^54hyK zJWi=ulj8Unov+L~Id_P|2%r0WRKyy=8S!GQRHi6mCLX(?2?GrtZ|NSXcM!5mrp=52 z{rbcqI2WCWY+1s(nP{kt>|Qbz?KVnojHG$Qih|DbSqp;}B817^3Stz{qwws}uyFAr z_H<8=!9#||fd}=7BMAg_t)Lks%xKxuR@N^==&Vbi(x-;3jOlnXoJ^uH^mz()vm$2P zmn>aE<;mpuZ2Z_*ykZ^Yk!R8Wfs$Gn$%c;ZdsA=-A2YEc*Kw-@Q<>boWeUnHHR8Tv zD@3u6RM^kNx%lLx593v~lpJ1BhT=IRI?(_}A?@=^8RwGm>3cp;XFxpK6T*_FydPXh zU-l5Fjv!fsGw%8Ae;M>j2B*&N(j=;je|d}r9u7(8w~BdItC#<7PV#&JsQ)t3ep$iULMXL&L6(@0JR@Y&$T zH7MX!vMML(M<-2uPXRX1Lhmzo?u~=^+T~}|lvw(=lKI0K(XgQdeAz*nWK@V88H zFKbv&rf>!U2G89V4pZhW%yF7SV%T0$3t6bKWe}qhwjR}<(Y9$#_L4Tn86`Nv95lGx z*Plm%0Rw=L>o>}6HB2^H1r8c+m1wfK2mV;Tb$5)Nw>I9LyD7&nLI)97UvM@ZpnK(> zbxZesr9qyvDx&@xv%)ze_~M3V2uF>xbVPvTTAKRJojWHL=g^PG#(?9FPQ}x{eY-4& z^Il;tjSEj{+wtmS=(#s~%jPX?^ZJTpG!;i|vDv(7En7e~L{qZE2ES&`T}U%Xy6{6c zI`RWAyev=JvDD5jDOFhG7L2u7^XJE>1Q;xNoH~7St^)s!>~utZ09(&WVC=}f48kso zXw#Ilo9ofZpZ&aSNyZ34$pSm+LE}Nb@E=ITck&Pa%|HW6diVaV6O(8LId~3RC-{um zd|p?bdsYT(JGj6yNLk>A#4>^;Dn*6~Rb?U@}!P&xSVQD^t zF&$fDSK1ff8fWsK{5z3~iHDzhF4r}nb48qf)>-s9=$L$;h6A*ahN!sZ<@cl^X~t*f zGk}3S?e8wZ%YFFk(I4-V@p|%gj?ClwCUWff-bZJNr^dKOuFptbM1Dx)%1AHiN&ST| zCIdvq7``*B<6h0JR3B{K`c=$F4iEqEqZsx1lsNbJBWXf*FhRkNG*PZcpotzv81WMc z+OGI?R5Y$xCt3sWmep!SV~pzBz!Mnd<35XlXPg>`vNf(LdNog-0G0-eQ$8y5`MPkIxBRK@v{c@pwx{I?cj4$y<124HW`#ja;UiDoOOpq#EyTJ_SR_G7ka+`qsTU_9q31}zCkM^+{ z4!uA8_ZRZxi#UzrjFb9grC{!tX3fq~ec^xF0*);$OV{3$x|=mhhndmjGasT}TSTL? zF&}&wFOK;r$G`RroasZpkdWzEuG?iXf!>D=+MYLolKaq495 z^Q003cjK3?$f~tFZoP>!;t$MuT1g;p3Il1<%Ol_98R4r=bzIkHFi3c36FTsst+R$I zn{i)Ei6;iVnkXN5+)*^IJ25Jdlj7aLo`cIfS$V*-imH-==H=hgo^y4cFLk@m65q>6 zzI=>sd2#dy(WiL>dWZCngRyI@q|EurQ_R!gw~SxHsm`3V?dd1Gs4%dqstN)ypb?AqvJ*lk3HC41E>P+j1k|0U~oOQPB4|+BDkv($Fr_r9+RfV@bQyl%X+pV zZCIVW)CgHz2d1inn5)hG>=s1+2FFY`<0w*`aMqG~9S3ULm0Ym>3bhrjuHj9I=udUvXz4E|J( zEG$pmrd{D_SL$VDl-X+S3+dkGcRG9a=hAj6$+_(7#5AOXuLp)pCH+hIT`z-lNd9Q7pHVtDKSdwm)zE(4+|CPVW3vKK--hL-WVAptA zfpqktheZSJXz7i48%*&T21;^F?vpPKvKe68P5{e5jnB{qk@*aSsaqz`oEg7);UwUo^c4(a9s!nXvb#&9oQFo&VYk`vFKBSURNRuGfz&Eo~0-4dIS-{ zh6A!G_|j!dWBTmb@c~YC8+tSxLEx)PM=Ie63f6+>3~U={FgPO3IgWBhyH&h6Ujrk) zXY+o8lqM#8Z}qx0BvR*R4~W6zCdL)$p~DXBNu&E_X=51-Q671fWUt9t$I?#MFG<@S z{0aZ0OV(t?n|PYZygwX0DhA>fpP6u@^3z%MG>|L*HQ6KD_yLdGl~0@cVnlnX%sC=8xy z>_Z;$-q4uz*@RfTd_{C_SN3)DEIVmSpbDEh^{}KNnpq1L#0Q^@i7gw~Mu#2;$AM&Y z>|SkD+%C*&y>dz6)x5v;&@U@k`4HENxYMyHWE2}40xC=JT=V0MXHCl@Q2J?UtsLRG znraN2epyD^u3NY0+>w2@^t`CUJPb5w2#N-ogX!}N%7^C~J<}N$&IO_{D#Q~Em5j<7 zZ78+`Lva}foebN#ThBcASOJ>*H<^bKVwpX+P_TaIZV9Pd4h)+3{F)ewj;YX9Ir)8q z9L{|i3c|9ws?68mOS8s}lM$0?8B1fQ5Kubpu7fNx^LNe}r3OaAxL6-+1W$gx8AEg- zS);``FygmOS$PJgbOIF~8i!exlEPmIaq$3!vqq2#SYazZJc>uXV^b-gt6*PC_S>U< zmM&b7o!@&LemL{5NJGyOc8ETe0E|F$zlw%L22J>8Dz8KavV!Mp3n=hZY|h8$s|a<< z78xlfz_XRow^p6IMW;@kDMxFOaCD9;0E228;VLy1yho{KfQ~UVJT%}904dBJUW3CE z4ut(&_-WeY&$D@A>(=d}9VOCk-w~I>+frkdib~SGbK=KSC!GFf@VW>EGi&Y~l-P<` zuyS2i7}W3?+#p4n5iMQE!NT1-;`}sd2cM$o4`A)g;Q$RSf3n^*DAG78gt!V%VSWIH zqUVV3u%dxeC&n-2e0#P|AWAY5%r^7MKNP6vY=P@=m<^PT&`4tFMOnBgJ;Sf9mP7pt#%!aNk~jQW7{1cF_?2(HR<2%+PM8{t z2?*3`R3~~Kd}Ne6KCsNJ^ZuD@Tb%D?00kH`_^kj(7 zr+r4nPcyO>ouW%whpg1gt#I-Xa`xW_IL0lGo!Jog`&(6Y0D4j$(C}3-*ty-)Bls3U z)Acd=%W1K4<(#PKaA1_TZO^fyEwUd>b?&j6Van*Yqw?ad(YbY%sA$+GT2`)-freU4 zG4Tu@8wMJ_0>0~zBkP#cBKo1s=kvStLA!ua|gqQqn`( z2>fn;q0}D))s;tHh4Hr|dnavV%gEX_YiK&T9R8@u7N_oHrr9#c*pB7elE=YUv3AGD zh}DqgKXqRQghe)Yi*I?`?LZp5Q@@-ZlRg=P&e|De-PzjNxigL=+nbc9++S3E$&E?L z`8*!XGkCW01v#o?;hJ2p#&E8a=dEGhCR-Lv`ZB6Fs2b(n58`y2wkd0BAk(GUjReaz zkge*>X0hnnbefZt9c?dT?*XCd1mSI5q;Hqs*lesKB;IRZ5NJO~n? zP?Ek_^{GgqG7b9Dxyr01+g-8(miMYb7gd?6CzMDV8E9bMCP(%mgSS_%9vjF|&0n)I z#!p+Gr%o6o+{CLTHeJuI^a|qW?iI_I#+unP*-CkARPf+>=oU{z$^aB}Q=-A-FaFYg zF0#G_{du3TF43iSkT&rO9MT2z=f%PqQz*S}8Q(bg&}h@DRq8(BYf>!vF>Pz?K4?Qg zWV20REI)~VopohcZdp;5!3$OfFIc!R=FOfKYZtAL9>*WS$!qi}Bax_WDNUs86_*KI zbvMKCw>A-GK=P{eB%NxLD2vPl8<<-~P}5-RqR%Hs<94m1C;mZ2`?9ph#Dnv;8LrPT zz~Upc&$VOK6VhMG7GPtrM(aa*wR%{YJQq87_-n7CpE+i_S2rq>yMpf)8I*SJI-}aR zj-Nrrl;dng0!A5x*9L(Ge2#J^m&xz)n0ANFVW&_2ES>!Jox4XjWSLFVl>yoqR&gnB z+=^h&mReM*`7F0a>w|~`b+2|{+VRXkc^P<_ko5G1WpiiXI~@cswdJVTrZ~jKDI82F zb*$?!Fz)TXhl-B)WzF-* zRQ;ROtE@MJ^^VW8w8str2R?5Pws}_FGXG2fBVRl?Ks(;k)mE=r%@%G>e3>>c4nBb< z#T`2E92>zx(}2-2GI#?%-PT~x$X;LiA9<`aj!L!x4`j`gAwL$a`W=;Jf7S3H3 zZ7W*SXXZ#`O;g6hI^%irkED=WG_Z5@n>@DF#P>?pJ^rmX;;Q?978hS~QM4{ENBJRm z2!Q(RoRmcLUwr-N0u9>5AW8=GEMtvK9c0KOw@$pnc7pMg#jISsB+4nZX~)ZKoMpI1 z(RA3dF$l!%nYmjaY@K)+&Iq2$MkHGSfq9!14VLdp)b4v)kE7fGBSquD`%C+Hig~aP zk8va#m6uMhO0=;INPxks5FkeLERjW7L3}#NHba`fcxf_y8}6@!8TX?ib& z?%X{^K!RF{V%~*7sb}LJl`cf0k)yL*I;zdUMwZ>Mrs?w*u+&QIM}qJnUO}m`Y6MN; z>fSWzOrh>xRE@4CG{bAjOJVU9rHPtT8cxnXaR8Gk^w%KtR}%ba+N4pmz=_h}P_QcW zd7`aPM=h_h>GNNKvxw;2x`;FN+e8X%cP0tPDn6~KKBOl)JT2E5D?C8L8|wMc3F z6uLY^rqpnf>q^fTH%2`*=rve()#BX!t7ZJx*r@Wt(QA+Lf0_hqAIf9!VN=twxg-T1J=s>HMV~ zOI-~zIbTcWH9J!l2}@qC+ES|3l*mbAe%Gv-$Al*AnR~*5@%*XaG(h0k3O&!E_B#$_ zg^n*9Ryl7ogRapm(7d_xAc&pO6l1$XMF&dq8>Av|OTZQaR*tO^Ew0Q=s00%?DlGn1 zA!@Kl%V46wKlt&qjb*FX#5TTfcHeCVOINKRSTUbQMi}~=C|_fZ_`>M~>!@me`_f@O zn6ylnGAbJyw5PcvTU5N6XB~i2w5oyF13ZC(09Ni@ldcP+ock~u@quF#uSGm(;*$08 z(JGy%e+L?l=-B~WQFVa9RUHQlUptLCm7Ht#I8GbB)&X8E$)*;i{Y9orxXR}mUUtV8 zo*Pi^2GI`FYoBkq0N#rn50rp*Nx;yf-#*{oi%7)uTXRu%f* zPQMc1pz$fJH}Ew+6|!n=sOlmcL1tOwT8>5x6&EllRFdwMzZHM~|AB^S%QnVG zGchK)gI(fzeWP`As*K9$J%XWwfmf?WEw(e%PT92u8KbN<8*177UNt{5%SUX%NnFP| zth{j=b(95^g{z1GO1_jiOwE52{?ecD6(4ok7GO!QF!uOK1G%n8qgVrL9nW5dVQh6- zL$;CCMb1jsj-9xI56pO45vTLDdB2P_=qa9)f1wWzC9A%4WHY$N{H28rI2rbCuyUd{ zbWo4)m@Q5j$$Cl|G3EVsWY=bNllaphtc}xKmB_j$LYRF@8P9zwqtGKZ)LI7L_+5MH zG-9na;BV2epuG_A**W=40>5Wl?+A)@ZtS zXEcF-TT_1B99h>0IMrZI@}a>1c_FU?MTr;RsRGYbL$_^VKI@PuJ{Q=` z;@HZ0;H_o{`ZeH~?cBm?N=r6G^V$ugIVHLpxI3v*%#)mO@N8_FTk9BGy|Iq9u1CK% z*TBUH73pbY0e^9={5AmXWiZxi0(ruU!ursFbfNLDOc3|t*tJL-;@V4oR4z*&DU;C` z@}Wj|_F&q!0C`&&aAj*5G%&lqu>&jY?@rn?jvq z@L>~%@mJU)>L`zQYul#Sr@V`GYKM$_%HcA*^Pg=gnLQu7gcM8(Jf4t zV{{uNZ72=%OkwFf)V)?P%1i29dBFM0m)rT=D$hE6M>y}~eY2>-$!(w7Gvdvx>M{~a zb)b#9(6)L5@Gpbht0tz@8~8tbqjqzM7#w7g)T#0m;48n7^8;o8md`OIZ8kEuv?29z7Z@BL3Y zo@X?tf5^tzxO!zaO0HY0ZrUjFaPko}BTY&N(xjQy^#llZ@O~3`wSjPhm!<8ZLV>&L-MAz(p3g21(ziHQzUMQUo5Cmq3cN3D+)m-?R|fO_tS!CJsDBK;6&76D}qIosVo< zu3eo$|0YeSuH+fwQ`wtehA%`&%YiNA%*R%D{GE&8dx_9wE-0BXuZD3%av>LzVd z?c-(epY}mBn=zl>3=1V_sIN=;O#41|Ou; z&6_tyi&kwIzZrfMmE!1s0~yLI8kax-#vGxM+swEov_%FTwGl2$yh#ZBp_#d(qE(mi8Na~)-S@G|^JtSrmaj#aX3MVCWiSjmWP!1Rs zFp&GGs$#$x)zUbqMaft#i~`4T|D*58Kq|v(2w@~!3X{4BOr55GjT;;9zwt`+?nl{Y z2clpIH5F?L5C~2uLPFB1R7hkX0>X8Vp29$;*GNfXV8$wLOBdaeVc&&!+4D4i%9QAL z+G$ZnR5_hbgn)ueA*c~;aKd%yyh-F{<`m!t797~|jK&&m^{jY>h{Dcn!7J>QYl>X-^z&&4(B>2qa7g}zMSPZ{jXnKNU|yYIx& z{Rgm(qgT$Mpm~vGNsy68vOB<5rz%TOfrm_*FYfYl6`8PeAGP;skgS2J#*Lp4^XAQs zb1u0g%acnEnTl5hr@-{(Si&{4kuZ*ewSc|Z8k{Kvt_Hoq0ZaR2+Li1F|AMm01{iWD z_3cY#2#ObjM8?&q@;?I(26DchF9MQ3SQ&~N7--<95ypGY+vgZ@pD}AD*|#~lr>`p! z7j(y?pz8Gg?-r_f{GjxSc6w*t*6cvG=9SPD35IL>6=pHKJjk zVe0U7iAI0{e?t|NyAx1k#KoLCF@Zh;?=LIHFNxi2FFrSpKAhvvF!DUM)ZQc+L1%2~ zY0mulF^r}^9lLkup8n_o4ily}+##lh{Hrm)Jg#iY`ph&XZ2GD^5sxBR>M9YRP*^AHn zrHTgVP`Z&;3&KsR;XU8|cc5V(O0HDVFnQ^^7&D9N1nw}1;dKdpUyh?!LRo7nCI~R- zkSe3?ChakNj;%4OQL~#~9GQ&(j;jea&Y3+YmM>e9vZA6(XR2~KrPE%@?k7+241Y?; z;vy@6oFnh~zI3@8*!j1HPHl`x<&t}H$BZ0FmB;odL%z2!qe={V&uqDh8{fpW&skp}flKv6TDBPIy8Z&{3Q@YZe)%$r)U2OD4E=tJc{|BfrdCN`Zzvx{&F5 z+?q`gmANv`wvA+-sBSS3qGOrm?ToD*^~>nqrdG7B+b|mPouG-U`!I+Een6_X=P*)R&{m)g=>l;1UvamE>{rwYh z((xD3SgdzCpk^55NA;3;(^(LWj+=O8PST>hpkXJBEP&yGns6v$CP)3x50GBGlQsoU}js#UfxiakK|N`4E^ou0bF1>y>=Uy*!Gm2+#;a%d;KhU*pEb$X8yB9=(sF z<9#{(UNR+&J3C*K-g{#M~IzBgh-ES)zy z`uFQk6V^5v%%}!#_Aqw{CgFp`N4~;CRVab>ICSQ@*DV(G7^$S}!uH!ufT9x5tBj+% zlyN_uIz2v|{3UvO5xr=ZX~IS|)~JqC-&t8!hCpuFjH`%_BYMK#klUONah*nMcxy3O&$>=m(qK!ffpVXRU!<%6E?zol%L(vIhc2z4ITCv8P+nfxRp3rksUOvE!bsUE zkLCN=Y6kf71>D8IHnTXFUJVwkS-pl{L-dmP^2=z_x=kEULvOdY7+fy+P*l3Y!j?0! z<3#;#Q5D1oz{%&yr_zfw<}=JTt3Q@fNuYhxkqUzDUAsZAR{LNtvF5Cj=DYHgV>p&{ zFKuXR>M*JUwB`L?edx{S7{pk>xRbCW*J4jLWX?UXgDc9*QwFGyb3Ep1KtMSn-{gz= z`Lt4U!T`8D>)+CFW18H`*AvklgI{@>Om;<{@X)4Bo9x4u$wGKf{&B6+xX&=S>AdrE z@G4G}r5PmU*}_2l8uZo{{@|mJW7^nHqu=RgWaXbWi}Jz*oiJDbiCg|i{&B0G?;DW( zT1K)i#}p>YqYNUkhULKI?IG__@v}4f(+|&+K};^Gy9{RO{9CIRf$rHxK$>*NOcH{1;TZCuHcJn^vmA+gpzOP)-e@GHa zGAjHK18giVx3Q~hRuagXht8dfy=Nc3ldz2{%F5C&6OP*P!bjp1*7~p7HA(dQ|IOqr zx(*~vpIxf!k`dEI%o6|A%mkg!nFsA%}lOLA+v~J z0}D=5BfxR$5y3XHmH`Y1TA^1=+Ph#y{?t%#|IVt_tMj<7c{66j$v9q}I&{d0rG%V; z2ALdUlQ|?f4RJGcg4M<`3The8z6|c&_Bc;VKoyh*L^PsbeDTF-4uhXIU;z6ETM(cr zj8%o6g2Mf9PD*CfQ8tRIP_?{GV$P;F2nVYtWCHgt`@ZwjF&Y8vkL}wxj=_mAs+Z!P z@e~>|q4Re=spR=xp{4LSC}c*l;NI>k5WWZtNL!UV#%M!Fj*N+uCPn|#P9^%^n83zt8bW>^U(T8p zqsJ9}Dr^j9?*Jq=JJfhY_#FuT^6=UbFjA08rgMuM=c|G|3JL8O#`{mxf%E$q*@pYgUF?M0uA9Ty+J z|9+f%{snm^yL*GTlSymTfGkm6WD~IdiX(WpvKgN6AAu$^B4oX-#LBH*tl9F}24n+l z&i5JH%7$P#Po(sD%m*WKjaX9|L}|!h4S;cN0I&}c(2Sl>ZCg|$h(oneP4r}76Sh3mCBIsTRzWaf_q8GA28LT0vOp+G!V$I4) zgADSDKMl$%AH;|A=i|hc-&f{+`Q`L@_wBct%Vq)%710IUmbEWKev-L_mX+zsL-FRb zG?H_R3S*0JomveJ<*nH~oi62$d>~#YAtNV3*EYVb=+Gg`%ggh3=OTS-95^Yf3|KXN zL~t&oC-~1S*EWuf+{;#)n$WEVqycvMTG+T>c?j}%`n0KWVxK41$1jKTAt~&iYC4mqm3I zP(7JtRz|J>?iEaM)a~3ElWw>P+}x6D&`+R~r3nK`@||O>oYsjjdrdu+vR~TaU#4`^ zhcX@7;I%fv{5KZhd~J!Y*h`b9OktAXs?O<*Jr_omrVfVMp+(Cw! zp{GuEVnbVKHMN*#KmW4~PK+YJp8A8O9P*$xk?_e!sq=YN=ZV)06v4CdkHH-A?Wx?A z%ADaf15|tL3c)iR=F{j9WhG7K_;|g1;_DHzRO;&MVl}%M9m2kxcJs}- zTu)qU3urTXp~Vs%1L?8gF@mN1V5X)r(L?)3UUfXoC^74A-@b;}S-Uef5oqYgGPm2= z`Kf-1U2QCjd>&gvU1*1ob``L{fL=jk}hzXmbZGm%%jeLL!t8g9_~gz@7u z5GJhlSXr%HkWS3r0R+^>Aj7Jv3;iKH zIYCMv)peN_jO>w5)KBW3QjW<-2IG`N+H1-U{TnAY=FDT+InTI_iB5}Eo6VOQO7M?| z!Cc2lxXdh(&pnh`>cv8~88p(4)#=5K1s=1u_te$J(-e1fLgCKaZzpg^7AxZ?A7&r~ zy`5vdOovac(#6mJ@?QQ6GSVT^Y*W} zma`8jtP;wP@1M&QXaE5qKgEZ_yI@@ejf(G5M*d%ai8&8pr$bh%T@M;Y+F-(PH0CP&r5?UJ^5%-&JK^Uw##sbz%yk?-`rP(nK!K_2q zivl7QFq=Y0VVBtf5SLMY2fhO{Mmi8OjKV`9n1aw(A*L@9h1Qksd}<6;cwj-}5J(F6&bGBn9#|gsXuDQ{ZnW(9n-9 zfO5SX&lh(Jx*Vfn$16lgjwfczLf& zQ#{0h9OEIKDqPJhP=F~2{Y^z`KU98&W5lut;4_N5g4s=(XFp8c65FDhF zLq8p7acgATnLCxU%GFn&sS~Ah=Y1-|);MB1mKMHTM#jV)_uQRnyA}Xij=;4L>8nfL zPMG_m<9c;PsWFS+ktGtQ@na3KD?;n&PT{(aIAa=jn$uaA0sQC?8+dU2yW?kn?Ptzz z@Rh~9E;61LENq}g!}6U6;${f zXH*={K*QoU5)P6hf+fHd9c#v}6J&QmH|IZipJIR)2;h+R3C;~Nv?j9S^Id`l`u_I= z4J*y$>ml9-n3&*Z6!QLyFNgFzJXx0Q$J}Q4TDwP`=Mg|%zj^)}_by7MujCTuC1eBA? z%iQu&x&c>iY5c-Vb7LJ@E7PV=kC7NFy-8DcX^$Cc4xEKoon3WVoHC^o{G$QR+wAjR z3b1abAm5thOC!jx8#A;Yfrd6w!8o)RceJ6Vl?Ie5NeljII>dfvA%I`A7^J&q@J$P{ z3oWV)2gOmwcn`SPeewM`T-hhCdhD^da>7_qcG|Gp62{nI7sVgZTz- z96tlv$`Wy;4D@&DMVX@xDgq4@HO5$UCeCp_jKN{OfpVB`%&%NX^a8w4F;qmJ0uVuZ9E;yQ#&>v&3 zzM8Qj>y!4~-p~vT0|Ux-ourTQmF@ei)PX$L$ruf3$IDsJ)ySMVEM>KT_Q)$oQ!s8^ z^sB0pS+K!QfmbIL3cl2KN_fFe8t?R_Fy76wEcn=K#aCM#r3=uIf$EpBIj*_xdII=Y zr;ch5y<7kW@hz-5juI}Qiu2T`yb5|T7CP?+FmN(~*}684Z9R6uQ_nsd^|d?V&O7gj zQNxC2W`TuiNxRA#C^UmqB#6<%jEQ0b!`&a6nau#7p%r;P&nDvz&mhm8b@l8xu_&H; zbwM=j*}*J$EzgdqBB;;lJ_Ut#9T|JUzNHDaJTC z<9wE2AcM^n4zE0nhyi}b-(sxN{4!|LK*KBoYoo6m)pTu8NA8F|1F$)ooO8#}pssROK2)d5ugc_t zPm8unfE;K0<#JJ%GOu7lX%oR}uQwZG3a4B8HsWxKQ{}4d>%e+%38VIm&rCkxI%Tjj zzL`2*{{w#8j_tkxAK^IqV*o*tvC#XlVZ#^{CeYv?F)BXQ`vwMd7L^YWO7d9JCN!RW z#nlDwnN)%{x2EgcN88k1GGtPuz;%>_3eant4u!Wd+5GU5<&?XE{Y8TZVZ6%&kLjPw6KJsWa;pcg zGN!~S)A+>(QVd^%SeNhu&!rtQBiB0X>kO>-3$qHsSNkQyDKw0v**^`s zjI2S-3NL4q3^csRwvy8bV%#`saz;}%2!%!F(xA%}dl*4x@jC^sLPNO4Lm@~Cn8lAl z4tF!KFw9CE47a_xg$TDsv~YQ92o-Q?5P}!l5nKM|QOssK28D5FB-?9@>Z+LPNP9Kw zU>Oc|ugb~{G#G7l>4fmvKeqvMt(d~j&na|edSG`}vl%n$M!|ievy0M}Ge*`L*uH&x z3X-EokKm|}j%%-(KxPe&HUiGzMMo7CZK{BEVl@&RGXJBuc1^u2IB+|VEe5;%;a}zk5i70xpc0PWY7y#AjaUQ zj|zQ_tk#S}E1104>I<&snJOtjKra=Bjdq`b2u%KH!~tqx>BOqt2jh*sm!ccO{|JKD z<4=D3H{vd4R{OG?#>^(GCY#lw%+YBy(C{oue>4W}%o)>3ZzO_F+Xa7^Qs0e78Pfzki`ym_(q-Hq`!MPxntU?)`du82wsCHAgpPsMW- z*GbkDf`bYiOlR+)!ln~GV63Gr4c4rw2JwKsnd5~Vl2=W|))_u?f%-87mE`jVl;lzz#&_4ROT%Hxv}w72 zx2e%?Z6}SV9Fc#(weM5ugMST6ah-+}FnF!BD~)D4JI~w9t}OF$yi9#{9rvV3lS!=| zk#z17E9qQAL^-cMQ2uJT*p9}Y!2$yqj=MZ0PNcnZ4W&zk=HYl%RaNJVlz~T!4-1<# z;@WuSm0YE%$f}r}iB6}9aqUQPVhfX+GH<^uqGd4Hx;+*yoBi^<%s`sLjLsDpD}7iy z>sD;SWgt)^&bEco=$ye^pXrR#31%wykX5j4-TK(Nc1?6x_-2f`VqjE)`%c`~nt_++ z?URSJ;5a$viDzNvC%1?@!+Am8r`-=2&y&c6_AKw|0{kCv(LVIYZZ_DfgQxq#W7Q*u zvc7g-{P=r6iH9Lu?`EUiIE1UOnZ-)RnX)e-}EiFlc?QeYWj%iuvp_3?}*AuH6(| zqutf3--(U{d+%aKY6#<-*-X+h*ZVB~=l#Md?I}B@rV)IxR?|A` z8=&_i1Rp0*d~w>1H&MK=YX$<$0CHBFC#1e8b-hF; z>OFtK0@7=D5WMJ4VXubMnqau9(Ab*0bu-f~=h@3`h6et2Kn+K#QK*C-Fn z7_va$VjSr;1RD&9O~38-m@#cCHXKWrvA?sZIP%^5QkQ^h^{BS1a4Juf4~~H_OQ-h1 zELlHq-nK32{R3#b8hdFpSqIwj!j#*;(uQs6VA{U-NRQ&n_sVF`qHS@*Q-MVubmC_j zHt?$illx+WjT&`j3>m@}s%+)SC5dO{yw{tBAYb~7a$Llj-(}_r&ntMk=!^V!3|aH? zYp=x$@N)x>`jsOof(t*n{K5%H122wc8EjMr+MZ)u1~Hs8vE4Gzkg@|@860+5$!z=^ z8ptv2N87?}pgSiug$XnpFma;Rc68D`e6G4inILX_@9#FCFJh*W4z)XPjX-|6yiC2C zfoK5q8u4JTL0n4@>TTbb@}UKRaL2+448Kb{=CgH}_PJXF8K!15eCmlOViJJ{Y2`S- z2}d!0(qTc1;@XKm;Wk^u>_&YdeTOn@MVgRb4ncRj!Ohw=ES&(JJJ274tE=<5!fVEk zwz+n-{3LAJTuu(!hVoK;tH1p0_-Oa(AGp)R=B*S>hL=7JG*Hv#P67>g&$=gi5)6Zx zQZFR(#p%cV_}2#-L;!@DXA?4o21g|BkYl?Pjl&(VRGy}bG=@Jz4YcUAn;hI2| zrfIMq5|t^O5`xiNjW``FhfbzULBgOa2z(EProi+99XW;Iiv&q_;WXZa@Uv|lGP5Ei zWY@rJ+&R0T5ZAequqE_#q98OGMTXM2lJHczGO_|vA^7yuPv>_xPn(u?2xM>tPckj7 zX^<$GJxe?r5jBWm+s;nO97afGL{qC|9MdWdG(1lrV>%9m84adwd9MP}D6oAf@xY_f zsnx(!c-VG2gut0hOP>@%DRj73$7?Cdp?3GqOf4EU;))db8dEv51+HcMOpW3>21#VT z><7;h-#*7@SnS5bLOnX$yD=1g?LOjrtPZXuVD9)3^epjA?>xoB8;|M2nc%$#hB^;Q2SYhv@H1yT zXiGSp&6Hk~Uja6a7GRgRG+6vz`n4FEOD8f_@12!#_r0^&t9~3~gi<7<;Y{O6@a}fC z;2guX8HVl!f(@q|p%rF}+tAOp;5dySXucIjgpS?{@cJUD_3Jjh8*i=KkbNA;4BC)> z6)}*hw7y*^PRI=Uxl`1QKrwf~IBtb?djWi0M8=9%xH3mk+Drz`?;Kgjw)jo_W&nf$ zg1b(vW7mmS*mVMvB#m2M*h1}*n1%6PLqJdY>ZxH1=jLhK@^03Sfy>N1)8J9zFToJn zz^uKrXHav>q{$iGm)Ny()YDOe zf#?jZRlswXBj`z*a+b_{gvlU_fd*+pS)(rM(w+ju;HsPzrFa`Gz{hy0dw}z!h zlaVnahYio|h}|0Z9OEgU8z7ZYikU8FJzZ{xQ_~h2A#-fU#?7(moz<~zJx~C{4d9=}@rUdbrnXT;98`@~i zc6$-EECX7{#+MzhyN2wMK@?g(5~~-jjGBIf*+pV7@|!>$d_4{)Qe7+WIcA9*o-58h z)UyV`a}0Pkpd>G;{~Qw?+Wlpq0XhE&j?uO7tmC5rD&8GSX(MGAIzhTfox#|p&Z1Gr zTxTbr3Erh6<(o#LnG)-;Ju1*C&cF_?s!rW5&K)}qOpRLuzeR>bL3_feQ*KbK&|l`P z!AE>Bc~#@ha|ECs!Zu{F?e5*_b)dO8Vj7J-J8uzdE&$qD3M$`$Zn z4IwBrbyS-U1gxM7YvH^}Kxt3iZkA4Tk8$HCq=V5GozzIcF*9LkFH@kwv2s>Ch-=%` zeo$XYR|X-9=OTYFg1u(l#tkw5)mO84>EL0*VmuCQO?7p)qjMlW9WU3}iwB)Q1Fc0n zh0c~AJe1?gUU^HK$n2r{3m3*)%phNT{q>n4WZfz2S~+$A&@=|vW!Qaw*OhDs$3cF! zALSto2?*D?zS-TmTsrYQ%cu_2?@7mK_~06rJhDs=emQeW+`Ek&_F>x!YJK%YR<)q$ zDodLf^LA!1T)@%BzHE+QYpX29#%oR=w^JN?&Kry4+1K7=$>XlrxqlBmBDmJy?V8nd z)MV&Doh^$b&{i{fmhsD=0)W~N?XYyV1Y4Zw{4%}}E^-u`#15fXE+T_30^gYyZQ0(E zg2&5u#u{SYBu}I)uIbVIGsDjQoBrkkk{;kc8RoP;ZkMf=51Tp*@R#x zlRy2C3)aVQ_SfJL}&#$zz*2Nd?Tx5oy1qdlQI!M4{7}@IV$wziw^#(%iXm0vy#~D~%gJ z9-C<><4eGkK()F_I1@H-kU>-0Nj<`IoJi6p%>c01aTK^BD*+nT9&>59b%RC`+!;dK zeJIo}0V#`g`0cN@w^@?jQ+}rnq@5=Hh;#Ajd!H@rPE460wCt@#F%cOvnlZJGkl9IQ zG#gy^(3w>p*j~Yp#dkW=Qj0j!-ckN&+j{7;7}T5tZtVL^#+nv|I+JO(WhNkJR%#!+t2oUCR2>oY@4XuZ*cI0n;y&X1zXTH~J*~F~-%l zb0P*Fk!I|ZulC8dyx!~#eIv8V8um31Xjm3&(XEet{_`1V5QpN7=CVDXQ@k(eIwzeO z6ZMLxwCGr-UB+|7y}=u4a@Ve1v1;WivJhI65%)k0sj0~#k@_IwUs$9y@hUETPT}*K zXn#6sQ#ouu)R|`Zx5r*Oi7n}t@$YWlk~>c9!^b?x(yhBc{Rn}ESA1_#PBi2_-!@;rwjtP#QwM1|JGE3@ZNHG4mmNBhLYtHu#%sG*uK1dI|h(&)C7 zR#t9H+Nj&OoH#`ddys2{E0sP3;5w|+oECx0K!ZXMq5mev*Q*O&jY_KI%jhFUT#;K} zN$f_Pk|AIoqfHt=I$;u^vnw)2GC05MgvmhZcreHsx^6x40*ts5!k9X3I%$B_zmU<8 z>BJHQ_ZtMp9`Rzjn$>J&k{&pp3V0dXv~-tFsBCY&`DUtblUfAh%8VMg znKH!dhk*?45oUk)lnHf?GCD|Kb)*y!GQA4MK*I~qJ)41sBBP-KX8L&nHR1CaB^~Ej zf}B*Ce5ue9&O%8POe=mgVBR}=B;H)S7(u=z4aKVwg5uI>o=Qrl718!zy!*LS0>bPw z4K#Qd^zblJs8DxL_DvXyWk$n&vj{Y>j#L9w;q74sY^%K6My7>=4;k8`Z5mk`z-Aiw zd<*0_)9HKHu5I16H4V|-wY4#c0M9McXJnOT*A6?5!mZLYHQSj*of#FK_>q3>r-2J+ zFEa~)?^J9C11$8iVEzI!8nzV~4Fsq%&;ZRHJAN#2<2Xs5DoT}{f?cH`UhJcaNXN|Y zGw1`Y+DFI1Vq4Gr@JFmo?aJ0pV{*M=nb9CD;$Oue{dvDZE%7fs3BPn9Pn64Ll3t;S z3f5m+=*&RFTa4>%q>EYc+yaZMnY~-Tg%re9D--u)aE6CbetS^Q&SW)^$$=4fo;9); znB50?^uw$Vg)6*DpaE1h(UP+RFffNfL}}SRX^0tUxP-BGj->|s-ai{FYa3!=g9Q;; zIzgKrfA*UM8rY-Q^z#c84oroi;l{o8+pPhgCD1U2^!l0bYmw1V@VG{ocu+y40YtlI zrj+y~-$|nhQyS13MTIdVzAU)4g4qk#%HQ{pOD85EB~WzLj4*G9w6Ha?IpKX;ddhIxhoi@|83!-kkx`xZApYN4&LY zVJ<`H+pn?+G*B>1qjW#dRzK*-7^L%A2F<+B!*()w1bq}mvoxZL*>&Z+phu%NXDl%NE2w9I8Bxw>F$=lJEHr(>n8B|yELiav(#aXvxb&(&aw4-uhUSJZkC|Coh5yQr5Xkrlu^oU zd0AR=9KA*;UOyTKZrsJgoP*oKU^$W|9**oT1zXvDU4Fl@6UysC_p zc5I^vIu?@<%B8d&fH!L>NK=fx#ZNb3KyTf$g(~CkK{HpA>P?^ldF;|N0|6;Tpcna4 z9qL)a?yJgAIq3Rl`N{EfSxIXGNW1FlQvNnH)MtGnQ@vdh>R$CaT`uR7F2%33?;-qv znYu;%_ze5$>2=x!UTdGsXn39Amri-r;K6a#*sCcrSC#$udasc`o%qpCF?irip!zU% zHoqx99aj(Kkb1?mVU6eo@amE`-iYfaP0Dr6Su+bfEBCx#IK4+bC!F0_+TuijHj>VS z-(}le3n(cM7<6P!CuRT-6KHrb8g}oZc-_r0w0aPkh#d&xs(+ZAVoX&!t)S<&9htPC zR>KKs_!4rV1G4%OfrdtwSb%-{hF%0O7K5zayFcc=^>)l&u$TbPj@Z6$H^EhkqV{Dw zOEUMWdUhhajG#6=XVFQQ=g9v8nD8Rk)VBrf0*;OYUm%SWym{Jj{PtoEM$Po2c8a2J`L@UWjbvz7qkXaF+x3VpQ?`VR(Sv5U@OYse4+ z4P-Pp+|skSRJL@+w=sC)=d{mk51J`#cxKztg$6uJo6T`@_nCPF8r~-GXswnpqertF z*r2opvlbc-xMLk<6G7FJA9qcZ6H}#{2DyW0`?G z>?UPdL8nELRd<`%3Qca>x|JOPsnKxoQ0!-E(yY%u7PFX8?O9co_~Awx&L=dz`u^j2 zT$Vt?1!fkLh#_hXCe$jkC`153@c9epVm-48rqUh9!5h%42s8|@uAx92ik7IH&LUKX zU}4=Pgk;d+15Qa$M#&j|m{MYQ3o-XLw(S-u!ixy~16FjWz+`P zgx|t}3Q%EIK*>M~Kn0`5(@ACv{7s|SS8*mI{@{l{h=C~jyP0+APTMj|5oA!X;%EYk z#)|^PL&r0j)hE!WJQM1|xmTD7hbeVAe*c=KOlqff(5~S^YWEz-tu$+`^Yc$*k1NOxMIuDaN6PR}ahiw`FP&n%-rceS` z&W72vXWU6@>wxtrQ5_Oj?&qG_IXA5g|B@8IUe!;s zVQhhC@j(B4M(#dAznoQVfuXx+=dKTHG)OCDjRv1@s<-!Kd-k6`>y+EB@5MnH&(Nj# zN#%wzavWMC@EC|#wtPj*W;u*oCR(4t^@au-yk0y@zd63(z_yF+pIRrd;$OPWbbk8a z`0Lm?8`BP0U8Cy^>>?EZ&9~o{#e25a)@Ehp4H(w1FMC_m#~45vR@p78nRPeN(4m#e z$hF!y6Oum6=9YuXg60_KImYrD|FWN4)EuKrV_W5_A!ZtQbJDn*x9t%7Po9mXTN`5j z?naC|9BWRGzx?X&#;lpQL?33E?1Ow__JP7(rEZ`>#pX^QGpA2aBR0p0u@fgA;a}fUSOyy4BY8`HH3fdv%9XKw%T{oF zKCZiNVq8Z$wzIR1I9}45_)A#>FUbeKmk*phl4py5Lfdo#w8nuvtwMfd!Gc_4TZwTy znf8Yd8=l34-PYJy1bI)sF>qw6wfrKj7r_|X-0mh!p0BzFLk#?XNXO#(6P;~=uerAX^Hu8%2G zZp@5^KHYm#O}^MR)C{;1Mk`leq_fh8#2FiM&t2f+ia3Z7w0^~Eg6uPM7Z=CMD%l#%W(%cZ#k0jt&IAI3M>_xDL- zXpFWs^7gWvZ~OM`*dFVmGc)R0Oc*c_4wirmSIQh)wP6l>r+nnc?6*t) z3}DqVleTE_qTKe;Wh&0VI)TywhuGkhfpFVZFG=Sq5VAGpTEY1~Lr2na@Y!CMSwmc~ zj^O4iFU?D*+$m4&rF}^KF8Yi(Jq}> zOrT-n#nSKTV9aCZ9_8bSt&EULk>tqUZkNJEHozgVX*)hvR22 zJWu_jT4vR6W|pyvKm!%&k;6s(1&|6}E;b{h1NnQ7rE6!oAIuW$rC-#RIgg%dNk)SK za0m!x+%mS;?TvX04K%zJyC?>^W$(_+3>r^j?7-e#kj3aZ0}W&}T!enikkIyUY;)F_ zv2y}PoY^;R1qiA5omW4n{QztqT{=;F@JK9Lwl_9$DY@-FThOr%sgzyW&H-)E=`& zj#*i0H^K)AFYQT}{LM2RYJ;)Z*w&VCDUvqsbvNEXhUt`~*AwvCC20cOnmtzFyWp2H zQ0Lcak0GOz?uCO>x@tpkO*!x~83%Pcc0_Mv{LQ!Ag5x`uw#cj^BT2tN8Nl7ye$qal z#E+-D!W6ujS9n#@zwO&ECw}Jq>}R2FatE-%@Ra()zAMY*8Tlm-a3I`%vj5_`ye^-` z_k~O{aMdykm(P9m73|=*V=9wjqZw0|PMG>{ut=O6%+an8sp?wgn}=hmeWWe!b;>g7 zQ~s0RgvpGCXMtV4edq0WL}g`V{-&KQ9?ZfKR_hlyHU_rbBGqv)(2)KPa7ruoOX62& zd#KmeVb}bWUG=V=I4N!i@9qYoA16IKZfOsR17Iw0#WVRVtc6X?SPQHD1CRdZod!M3 zI#>$s%@%x^jJWHq(Ln!Q)-CST3nl&8M%s$p?@=x}$$*A!N}K!__l|=*-tB;14BR!x zrhokL$D{x7;clanyCZsyx>_9Bc6nyj67BfAI7+&b=josQbvt5<2^;)!_a6fdW;E=t z-}_;WhVEpnfQ-Z?9oBeDm_N>ckbPqKUw5b+j5ayAI;u9P0u?=HFupgg-w;bkeSQDP zQP#WljBCeS6~hKqgG^?fF=RE?G_tI9pnz~lF2Map`8`zf4w%&NCVUKFn_To9%Kj;83|2xhw~Q2OUFa-ETAD?>BbrcNsu+>aN^z^PGAM3uY7;8!ttVN%T*}vxW-R<#msRM9p zSj#{uXcQjcM0h<#jAJ3ADsWb=ekWdL>BmhoW{}Q2DN~&tauranYimNK3c`Dw^)T{h z6kL31AgF9ye{4V~@xoJ#rZx}^n1>MDgHiW8zx$QwH+CH5kKc>qFsZP~d~TtoK(#1b z;*0(pI7uPP@8UpsQur}O!k{x#7B^bK8mw;Y*?cc4MLqiu$YPKxNe^+Y!|wg!L!oCR zQ%A_YYp`@Cf-19~O`%AtEJDL{Znw1C#<{Cg(iLmyx(op1Y)DfWz~_{&*4p2K6(5lnuge_4h56xl2&rFP(=P5X*y*|8!H zvg^d+%?r0bw40_4{9odoXhPk>Ym=2hZ^b{YeAT(grdEo=0(x7&($zk!fTK zbt&+wlOSzyjYgETFTNd1m5VT@lZw&ln247`NfioOnpF`lW?biB=-x%(>xPNfXGQQ! zmkh3`WPy^j_Y26U^UVmZ;qG0`sc#;{y)EctR%dp6oD~3;b!*qeTmlU%)~%0c7cR{{ z4n+P8WDB+GUhLo8vs-j;k8_5R*_`WhjjogjUD$MS6tY%46v!wX4gku}{x#5W0r`2p zWg7ww=VA@TAZKp}9)2rv`-i{toAK#~K9QM2W(&C#;5ahd?6F=rl^W8@gbZ-7oI`o< zx&Od^W{%fqfK7wOf>`62!D!Dcrfa6tU;w{)0He6qC=vH6UW3sZvl`d3UZ+Nb^gOWtz!;B_IDGJsG*+yZ?$|hH%3H@aXFV{8a;$M~G?kRO>X9^57XGTN!?aHQumS8nWW%!UwF!BoO3tG)SA_ zz?jj{9Da3&o7v2EX{6tTGg|ICQ9+uNmXoNPjH$=wT*98|b{qXn;oijeeY@AIBNfJ&ng>J3M}p zE_G-JzaOIt{ZVGyfTcT*_$eHz_qtTXghwBtQutVA*Xv{6oR{OqsWW04ffARSXml2- zro!(q7`$Xmd4}U4zLaO4%1I4!$Hmjn76Y>|o7+#C(Xf5%ws_#7hbRU)mi`n5zH}gO zJBH%ifU8EGpXEc1T;;F&#eh~02ym$1&3xR4ZmO-V&1}jFWWe2b-xK|-sxnY*L9l{1 zGy@m~+VwSYMf;^}@H?|#6k5U{U7E#XYOWa#8#iu@T|DDTc3GK$tm#cQqViqGMQ2W& z}cO-n8{#zu6?)wZk4yDl3Og(2@^9KtaaedRZeDz^`snRlr-vx zvLF1Ea?L;K0Mn-Y=NLJ`0nz7{ZQ2ClS9-Uu)c~`Y;0N`Cx=cKZV^fV2Mt+lDHP*$y z&o!`MMxT>Ee)nOZfuNu@gbXw|1KY2%A9hEl%*60IZ4Bi`P8`W!v?=WvXz*1U(Pm2B zPJg@yYwU2RSxje`XT_U?$DtH?k@I|r9BGRpuY ziS8UX$If7;r#$UnWv-X=ExcY_=JuA2=&f@st!pH6ZzqA1#Vc6K$?rY5=`hz{T{A3x z^%rd~x zmNqR|n9HoCc?LU+ar0Zb&2p)an&rd>fv_ff%-t;BgdWXGu3&l7ZNPrzgb51tI1T<` zjzTZMugYPw_blFO{WvrDT0r*()!iXRhfzGKOFEK?!;SF{!P4iRX4eVuVf}|{N?33U<{) zFIYcLI#8yRHjv|)b~-xGfRv85?dJi^@@%1FkDFC`W|T zQ(3F*F8!Mf;y_EvHv6o9WBd9C+Va+IvTuiwGdpU@Xkcu`(<21J`-6KTbm)70Bd#}a z?gWH5_Eo-0e&;oVG|+$2J)db3ybve>rlVx@xtzy9gS$@bgZ}s7L*2pT)vWvOjjq`8 z7vM*wi-8^K;NyN=mOz67DN_zbHm3&gMGO{52If4M)npegSde>xLy~bt&5)?-*B`qa z0zfc1dt;!%flsH086lN=Ix38i11K|DoJ=8RwRwx}xUT&JW`CAb3}hLzJp-$%(&?(A zn3<8YEd0UjcSdO$WY<~CG}d;o9n&Xuh!wucC`k$q?8&YiVkF)#Oo z)_Ig6OmD}E%Roahqg5DSnW6{|Z2QCd0Kl)ZFP#I4S!S%=xhv+fG-KHC;W1{B=(mbPLKp9XT^Q{}bX$X4p&~#I14k4V+%)(0iW%m zVI{}=QqDHWXga0BAj7J76qGWmhJnu!KjQMh;e&-k4Wm5vna5)keX#hO>!vlR#F43~ z3RbT#a9sqA6f$5s1+lPX;U30F8t}QMMx_Hokg79#~sqD-Z;Xru7hZU#KyLvbh%sFVyIsVJn2BG6zIT6WOE z*41o=AqvlcH=XIV8`dYybi!cRU0w+bUY_##;i``LA3={7PNb~)>gY~X5- zFF*cR+=zqUt9y?W<_hwh`Q(0`*X<|=D@<3{)a0zXye?kkamPl*Z@Q!XRv9GUfE(|1 zEOX4c&U;GZ%=hUy(2v!mk1lxq^|*1`j2Meik+WjVlC^G$@jb{(0i&S>&6y3;ZXhE9>8*=S0 z@Bn-oSb0NI3L}^VQ+%TV;F!wa{{1k}K(@t!+;yTM=5AL;!#kWFpMUhBxQ*aaB{L?@ z#_B-m$kT%~5DeCeBPEW7@#t{k%NexV?K|Q?!@k7p&>=%&_|Rdw6|w8#K`us-as~i7 z#eL!wyi2RnUm7jq2E{7BO8**M8j(9{cT(AVY0`2(wtmuCA5_^NO#=NuJJOUvkfbr% z@;()`?Fz35aDAlX@AxVQG}3&IK|c9u(}s;%&3gdBOlNg+w~_=GIRKr&gh>yM?>Xum z_?>Ig-L>HifwJ=~kFo7s4#fCEaH&JyW2wPH3UbWwAkZ>o}aH?E^SLbz8Q@&P^Ml7a3|}hYyH;6oa%zgX3zT!JxduUu>&Kzy|n0 zo#>`*mP^s!6O2RcvHDokz)T*$^%&R%qlqy-d@4G(>>S+&^^NzT<%V{xV)$Km#L!VA zqmD6s{nhzwRd{_|hjFgclj-T`vXAnI^3ie400DSa?igrr`HT9)aZrEw*&wHt?9GI6 z-M3j~GnnnNn6Px=xRtV0ezonAe~aJGr9LTVE!DR*`cGcFi9%{- ztT^7np)>8UiZkz3$0}!io`z{US$x*U(54ZlGBTNSDYK!K zwBf{~#y7H3eIb1I$>(ZU_*`YD-<4yeZuK7PHmzR1B9~+s1UG=E9u)WLFAaO)@V(>Z z`*PfDH=P06_E~a=zhxjFo;gH-Y5|j02lwrbiDZ-wsO(F>SQdheG?6Ir!hNUDvQx+@ z;6x5vRM1SY<`)R|5@g_M*inovH)x-^z3c9M2Pn$8KHgffHX0fz26=dY^5w+d5!JoB zMgPw2qbC)Q+Y_v40gSd$P!ISP=Zv{>)c5&4pl6_gPj*8&>v5JbbJvOU6oYi>#4c)} zELnLlw(?!MbYe*F%6R0V`&jxwt(YF&b1PiOT1P15C=U})sq4X|eJ<>!1IV(?IgxTL zlN*DptCO}8C){rk$snMg(_W&T(n;0XwQYGxU6-^4-swb~A{gtetF=S6p|5%)gKwHL zCHk^FK>9YoP-gGQTN!A;{`Of0rsaK~DI$D>xcVn{zO_1KF3bE`!&$ZDV&>%TZ_ zFa4ofGo#@W^paV_373Nnrt>U(4&}LR$`9&~)Fr&uVZXRDK|S`KK}j>q%nVQm93zl! zznxi^UmeJH;MA?+wIP)y21eaU$P7(sT^S_Jsw0Ho?P6acaA&5$u;Ihl_OpLZaFm%o z8NA^-ciM4+PWxIsE92~g6L8{4yFgx3hL(=2xLLG>)3O^LoXAr z`~?xnK52r}{%8w0w&GiOlWusW;e=iI<@deFU?-N;Im*a>)R|Csio>)Qk%j7Sm@wN> zb{oLaUds9qJizNqdo>>j&B(L%$r^O-I&sbQ*Jnnxeb0I?G^w4NKArT2eWR_AOE!T^ zy3%HspTviH!+U*hVJ|l(&2J#X#>}$m=#MgkM>&(3+1%$Ct0#&;gY;c2pLblPRkyR$ zHrAIj_~y8H96`?1)zzmRudOqa$*sZF)oEkcZ)roEiN`YNE}rEZ$3web{EKprLf;hj z!EtE7BAm78kRt@2^f7mC+!UYtz29N?rH7&?lW6j%{9R-mF^C`Y+LllRs0T|#%?p5dj*0-uK`fU?1d56p1phJnrxj5(|vUs6;2%?CLMGc+8IHE5Ju7z z+!CA5QE&^pbfLhKc`W92l6x%FR>yWnqsClK`>ZE~SXIUvxduI20TbdoncEo48`BdlRwLo|25fI%^0=#VscjCvYDlwdVzGh)V#l3OZ$7^5I! zjLdXWSw{?Ws-O*KDByCIi9R*p>~6+s9EM;WP+6G_C~Pu?hXTdZ{(Bg4l%Zur1%lB< zjWBT~W2uBxASwilO*XL3)-_Q>5U^=zB?F$%0EGb_+xA%oN$kB5M488|1($aCou4&Q z#FG(mjTIeo13`OG4jsu#u!vd(OIb8>j4E@f+?z;Ixyaa#n{B8Jblg2`*Jnrz;!I;p zA+Z+&`T)gb9Dh>*`!nle8~&z%6lNpN76etOm&TCKPy9lU3RADkF`{j+@%hep?O~m> zONC6I9zg97Yj60wMy&T0#uH=fJwT|SmUfC+r6LNez${XHc?PuN_}c!#Lx*E`ZEf;R zHym!)19pbyrDNMyVR@bRYh+ptTtl}A7U6h-56C2iuzV#C>5fXb)>lyg?!~aM(4>V$ zT_@PU=l6~tkE1ANkKs(R3?qr6hCoAQ=XTL40}U9};G-@0a#xt7b=vnCKKnegwHm%{ zP?XO6o`Z+^DdASJYWSXqmrhZ@tM0^^Sh;gwEZK*0XvyBv%p!xexT<HqLM9=yHmeFU7*wJH6AI`xYq!lW9@j#uj0UK z{OmYu9G1LlP}UU8y><1_f7>iZ>zZ+QopJ0vq%m7ahl;+m#6b~$Wuf}y9Q88{G!)N= zo_O{pPG_-B!hsP8(ON)*T@FY%XQ+g}|bbKjO-+Vf z4=p-HGYXBiujrXOp&Z1(TYvIsG`n(m^kl2$Lp*osij~nD{Zs=#S!+Z`i$N;_4m_ZA zaK%@FTW6G6Dxs6W^%~U5Z1I;tRIXEonoY8w?6(uh%V8r%L{I45dkVb(-k}p^s|In- zN+VY^vgJo-wA7R8Z0X$bEDS!g4+u1)zm&sf-APM>Yig3Ny;g+$+}SSzz6NcTn`R*h zyUSOk6=9dgmDe(rFsb|0O-JF~!_ZEj$^o=ro%Aj*sOzMK)D7G#ohWO>g*ZwXBz~X` z*Y5hgdP>J#d1N45r|SfA*Cj!{Fg&$8yiS8W>C8R=pR&fb%anJJkvLS3*-zmu4xLJ= zg+1b#7}&X^HjQp)Ub~@Rb%t!qzI#adK1aMd;bP%F9S?)Fj*)%z`L?HC6;B4<44~{J z_)?2wG_b0gx?9*w1Z$GtdA<#oaC@`gt7B6(!;6KTq0LtWe1y3eb7l8MaPxlFY_TrR zuwg@~W73g6Dx(=6Xd#z2(e7CylxHrYYdUt$`d0?BKRA9A8GH)40bU3=WbFfBZ-%XS z93I%c|Gn6`?{J(tc9;yHBG2olff0kTRr_^l9bNHwI{-fw7LxB6%EXa!OZjP55l|G! z<2R+R*O+ybHZDJ9pn;5ri*4CTyH(rRefU@`erIoN##|xaBm;m*9tsU#9sSYkozTBd z!kt0(o`yHmVF6}s6nRR$BtJOb(vAEi4OUkdxYtIO<{VdPSXxZEg-lcDrfdUl9eM*l z;yZ0N#xehK?-}&e3F=xLCTLnumQC00>^cMP%_PyLKA+iK;*`ERrqHR|BTE+%xac8k7( zH0*cUgwmAwl2Lub3FJi zdnw)U{xnYQ4s75LV>FATy;XA>{lFc}09r#we|=Y$QkpOeD$BkiUp+VZ3SeH{ZV%Ar4aS* zTC&Q>rtW8540L%@f@gt8I^hw_edQ>L+Q2igr)}?(1k&|ZIG)FEE zs;WxAF@w<3G5t=N2M_2=%3I%JGU zPw`Km``^OW0M^ER0H&eS%YGQMs^L_n?&oxN=W-q-^)lnfOq@2*zri6pX+B^tGSho` z4}6@U;C*a8ae3Pf%oN3r+#qFg!Z6XO|enHjJHchRK&(4KrqYhR1R5}0 zP(mt>)>s|Qe_=7mff(s- ztJbBBfd&+_$`E{|piO%O9Ov=TKtoA8S}ILH^P;hPf!X(SIN=9RpO3XHotU$Y2tMsJ zBaK+ac=-4)681olGkElj@J>G#iDZAE&xu7w6?Z)O#fVv&T%t!OPt^?Mai; zjxzFc>sN8pi_>xXw}8EhcE!8XDwkLD(ICfAl%Mksb;ZZa`WMqIaU-kh-(1c^nvqWT zUd~28(v~3(=C4xzUT)ZZ%peHTz~$ycm*4+Tj%nfkpB{hu@Bb_wd*Uf5X8Od0jX9*`~Ew5=1!{k=yPN~xVwiqP&msF23oLv zvX8Qz{ZIJlyb}b%Ud(UMSK4aVi3s)yaNP7;UfUixiTE|LPML`w)=?TsrtZKgo(D|c zFK)!Ar)>(iaQfM!{La_%@HY})z!gRFFm&HP#+qNgb3DA?Lz=OD$B7K}4DL7)(VB)> zvPpE8XMlurbGMp+_r(9&$dCL;1^18|-$ z$=BX+EIe$NiG9{#2@hsIG~h@%%X1MzW>VrqL6rUDdM0C-eSzM2Z-4yW(|&e>zS}D?cx&Iu*?6)7_-8cx1DtZl&OViR6(5jh-otWL91Y;70oxW%+xOMa_St7U zPPWmJB81IxNZ*IvkDg?WJu|rHq;nlzFXp_WD+UU%qu_3D z>BEg$8$rhIg7%6`k>&&w3^WkpWfp>L6QcRPZ$~WxD{|}b)YGSB+jhsodY!4FAHvoJ zz&p0by<%)s)E@T3q48|jkxJ~;c+dbm!z|1>X72@C{Cc^Hl3mJN@kD{Vf_7}TLmMgr zGdppXT_W(qlP}sq+s+6&gK^}8i)qjdVFsxy5$DE6Qqhkv!(=obB%V8a6k06SPt#n| zB*~EA*V$|FN&zxnOS}uK^IWF(o+Yi|6hRo_lhy`9mo+252%Uc_xE#IGZY`6q58eO{)<>2!X z(&uVi1{FSgW~w>v#47!puOd=?Y@oq_!BNKPu(K$ABX3Xsyk2M@jW3waOB1Vz2NBj$mI@$h9 zSL$oYLXTm&tcvSCv-Gc%Ni;=Qs#cKC45{vNHgh1Yxh71V#o zqe)kMAN*d#I<{D7Pi{_b?N9dhsk@F~u^5NOuMIKhmuJdtDA z37ZTZgrhUhB+()9uFg~jc(3iYXY1p(EL~Nh zG@_pxVN&lC_VzZ;o0EJYtj!sVi!4t#PY28pmDgJFpb|ekqR`jS!QQJcMMfg3Pi!K5U zo#HGRzq<|{iNz}$Vlxly%I&9VNL&b;a5`Sny!7n*uJqAuP(L_M{Tv$PmV&oceZJ!*UQzMzC)W!A1JIF-vYe?s zc`QyJBkP35guynfS=^RgQC9 zz)u~*FA2A838(i<6Vi_T(azKE5)i>888UyjFU*6a{mi5>1+&?~sdG1$U7aLDnO&mz z-9Si38X>7B8y2!$YOpLp;g9{bEpaWZK1Ta)d+;GtnM~)YpKGo3JZ8eP+ryzvJX_$yb`Z&Co^O`vDn{;=ehz z)$udU7)qI3JfM(BMdYAmsvmo4wI=f3dKzE<2u*k9K%prK%u+;F?(*@fT1^W>I{mP zjbVS+?l^)7PTJ3<1t?ROEA2X>tvhza(?9u1jF~V# zuBS-Up#G$4k^1N?vVAu-xnP}aCgJ`$?0nZmvDpVcnhqr#)>SY)c_oF>UR|?3e)Ylo zV(iF~nRaL)mP{!JH(788e3%Ze5s~ShNEXvwHAHg_6nHij$#gksz!d&{;APvkZSnf- zm!j=}zVYyV_s3Ayh89X$haAwF=%@)q1XjsnD(eF8`5WKo=pY$df+N>Cy|czGRG*72 zM?Q!LZ=D&p&zKQCNjE)7a7E{*9g0AD(AdcJVBkuc5zmf^MSmQ3*UMU@$h0z_agGd~ zU3Gh6{(?7RE_9<1`TV1wjB#v(*OefM(k2s9xmVcI)c1`@<$p06!v6F3{OSdnHtI7s zZP^-6{pep}?ZM-5ZJ(}j_a`2XQKYeD>Y(s~Ytyn!v2&@11<+hu<~lZ)R%B`_sT|H~ zy8OtrHq$v>OK0lc(pB%o-+upJ@~NK!H&br7AqJ2lZ(${u|G2E6*ad3p(TI zx_zwMq0L{oAofsuqPBj2wlk8jc@6%@Fbw%YJvv1N1@PQI-ZjJ*!L79f#IJ!k6^{sT zR>^)#^Ga*^2G=dUeyJJCpG3!#!96#~ky`+_n%hdU1iF;^7 z+DJ@i^98T^$flE~^9P+*VUizAjk7ZSI?@K`%wHI@ZoN6ikG?YNw}?-dUpdR4>2T1t z{34DLSKvzn%WMp5OepW%eWDGtJ__UM`&=(9jw>Y{jW_rt*#*-90b?k7Mx#z-w)$8Y^*yFi?#g`_cH8lI zbmncj!$xnG>Byv_(XP-dETYDSA=VcND$7a1_Dw*=?q_o)M*-?iZVZ~yyu6GwMWxjrUN zD%Q3tPfXb_^pki?@Ob@b2LzfU!7uueaPZJ9Vo18>Vzx8;&eP9P4L;)Wdmo6Y*G!E5 zEa$MEh3W9F>Ac991&xg)avG$Rk1gtZ5k7GXN_U=cS(e*noyBa%54+(QI9%Y~WUb$c};w*Hk zfqRDcp32`<^8&IY=q6M_Ey2M)z+^XJD8UVc5F|0K0grchs?1M0gf5ZC~Z|y>Lcxor-#4kw2N<3x1}-Z)B@3)HgCx-6JOf2 zEhY~i8u#9LN7PvD-f^TM`Gp&kC&gbS}TB(~I;iq7sgozC9a+J03wc>y7anDIQ}e)B!0Pf#mqg3Q$`!9ONUL1PB^`;Y4%bY@8s|B5aYG+Q*_dj?iwZjLb|qBpHs8!ykD69+Nud-muN;~=16 zH8r`mMWyZDxDvb-mn|$dpW<2H`sOz?68FFppN=~af+L0xOU3KD9EF?)g@j@I)??7o zRv@aJQwY$m1gtWZ@MR*`T^*$Tr{=yCU;C@SiATp?8Mn{6HyyA3m6f^XM@Cnf$p|S{ zla34F>*qXZi~rf?MV@;J0im%cD!0_`jPDR6Sv_Z7eEQdZnSylJvbM^#Pn`?+fKh`= z!I1_E{Z=`7WSe}i(o`sRz{v7i1&{0RjziF^C`R`W-~Db(yzbh#ZR*q*fdK5ot_<#c zp%C=m(kahI%Rlx*`14Wx;b9JyOfR$QbjgUXE?gKd0sB|K{?(YuGkUY$x&u)?*JK(n zDC-E6I8xYozcn2)(4cUH5jD1S!W1+*@jG_xh?N-VPyh6X(W!b^eEFAuDXymAj|}J- z0Z{%I+yv2A0ra(a$=`ji!>ID6@n{Wf`v{WEf8)*g(f7X_3pUrr*M9BS;tYPW8F^i%0>feuD{!>sM=L|i#|B?qyQZJz%nC^6uF|+=Nfl$BJcFXK zLcg<|r&tzomQZ*zfgQv|q)8YC2rdDvA`d5f?@ z@j2Qcslnk37c>|h&jg{sId4mKQqsK_i2GcBiQG0ou%1A`cfa@j z_OmvQxC-*cil||_A9b|^@p@l0^9_CcEb0qqauAO7kc?Q!&v?>`tT-(DPT7Q7zgMo_R4ez!)0 zfloQhqj2|pCnfNYZt8j&WY87TI4UTn=%VD)iol*bXB>rZcVh^?d$1u^AEn05UDE)Q zKy1IFW=J)1@eD;9kFk5exEMNk2s453Bo6tVcitLPCQi)S0k&CRPmxK2y|2IdX1p-x z<@m-Qd_AU3ygt`4>u{&@BQAwQ+D&oHyvLeBIwMQoX2$`x z4F3M&<&5b=@wrDn8AGe9G8m)$Ro@xV)P**PD*TS8^sTPY=~ccc&r^od7uOV9jM$n5 zKl<7@@KYaeh_{LxVO?>6Pdt%zuX)&Hj6l+q58)?E|lL5ut3Kss>&XLA#w^&ck zm}2AQL<{uQlB})M=*gqUPQ-eG`2URVHhbg2yYG&%SF5+YXIy+-r_X#5Eac=n>Uj+Yx90=cIbJ00!$j*bjh`qHTuLzxk%=RXtJgr5S=C zhi%*0{RKUDp*01z2{i0Iay-^Hc#Iw~ z+$QLVlOR3?dPA;i6WcTS+_oHNYlmn*N$c9%+>${IX}AFyKKJF9)<&Sexf=p~uv-5=eeZkmU!Qq4uIBfz zeEZu3Wv3=DNHf+E>cJ$5b-4_HN<#)%GSC3r;>#eI(;HYaOu+c?*I61Jo)Qiid$}&!t8!;>O`>l?0|!kFGa9a zd1u>82*5o12a9?4WRGCQ3ew!NI(<@l-hC2+BNYi z&iyfzid9XGJ`RCUbS){^oE0Ryfo4^~WBKPd@x`j2tzREyNnL z2o%yGnO4Tl^{74%#&M=v29nTp;uRu!^4VdN=o?_fAHO&|zVerU6%UUd7PFW=o;q!6 z^y%N9f^8Q1Bha95woQ&4X4~_huYL{O61wVJ10JbN3NYz*7zgie+ZNyX(U0QY1q-)n`UTQXXudnr}N|L!0E z5ruqH+&O)ETw$Prf=+F4aGXspjbh>Zg(G>-KKN~62>33y1_M`nckg1xXjRNxupnMx z=H=_(z))n?#Y(!uq0yt#DUFFTN}JJ7a9$dY3K9*kbUGmlQ~#YgU%wGY3M2Ff|L{*S z;D$-@yTA4;IpdWEs6ZvSO*n4?JwfGtz9!T{TwLmSB57F~(uqQahvF5Ypx^t4{~B*> z-xGiMr7w|n@MuO9Ph$ML|8xpG#}K?YhKX;5s{#!89Rp1U1}2qKbMUD^aTaqEfrfu# z#^^u%^S}7i`0ihRJMO-9CTX%Pc`;*xu`fk|pey)(;nkbUF8b<^ysG$si0!Rb#Gm}T zKaE%3-5QTvb5%Tv!#C;LYZFET0a+}EF;ZA70HvMG3ShSJ5)YHsFL4?a(XmK}0wbg? zDV7ErW>Z!8v%me7Os)IfFFhF#noTlnSX^Ye%UJ}d?E?-tD2z3iNMuIC|D^6c;Px!4 zy#Gmg(trRWEeQ}pR}@h!AV`sp3W|yfDu|-k6)cP8wSjBjUDsV~U_qoP>Y^eY>C!Bq z1_((YfdBzQ2#}t<-|ug(xt}`^VRhg2|M~ox=eh3dx~7~tbLPyMGiS<$karc$C0G2m z{NVJ{a;V+!r_CfLTPNs~H8f0Fp97FEG^~Z8A?;5(f~SUtF|2ZEhK7|GKg=Vzqc~JU z1Gt(u9nliXp%S)Y0D}-llm{MNRDOTkU(2;K>e9d2$+eU({?msT^zO$DvW5n%`_NLw zUw)UYDLZ$cy9}XYt!J5E{?&gj9orpuOrvA_UHJ|JfFqB2OWE%wyRkxOlbrPKz(gQR zY150LfdhebO621JU&V(WG@ZXPV}OC>Xv#ZMWrecZv0aJ5^cO$>X_<{a`-zWyr0o2> zov?-jm$YlGy)J_WW(#k)uKb)hp1yxMhqmgr=3EfUC(G$vBj(B6* z!x^la`rwJ5NywKz^pWxgc*akPE@MEf!oSiz2FS6Rm$WzcS_h#$DWd=oLHgUtsvIe^ zqpW=UyD>C4BlX?y{Aby3@4cN8E01ufqz%NuX9ngJR5_Vh24th{6kt)ZGfN2k)IDiD z@YKP^#aCWk-h0eD%U!_!$m?I7lboNu{r2HYjYg4S@`2csPFKqTEyY)lt`LE(d?Vfn z4b`kPIOjL#m-l_{^Bj)2ZaMzV?u59IrXfcl$p133N5z=*irQ6J!dt>-W+yrfLO{caRqly|mJJjN2zN9R9Kp1IxDd?jM*GM?3R5VXu; zmCB6_Ue3SlvhtH({HlEXgb$a!nenp!@bEL8?L->r>@SqN_Hzz^4D-rB2|lo2QAV%9 zLAJ`gKm75J^h@WL?_(6)gqiOX-v7Sx0tStyHE#MF;3Yl$rjviFe;piI@9A%nKXMd4 z8q3NhjnS9>_Of!usoyPU{%LA?{~Hf4#~ks7x?%#J6HkrPQ5r$Np1L?gUj=t zyJML$Wl9;(fvV2NYh>`6G4sx>I=SHd^UCcQ8gA|mdU_!OYVyVt**Y=0Y%pd8tBC09 zX{*D@E4&OXZE3c>O36W4;%uiO3ANATT12~loNJ|q1`K?&9-LQhy!qZTjV1A;fT4L~ z`z<#qd+q;nJ_|arT#FIu+Vg%>zVew*m)-e%-*{we`M)04Vb!Pc0y514{zO;Psn75T3w%Zn(bh;e4Tc(r|&}lcoarKbSb}R2F zk5ltJi<2u%?_>4qx#;`<@wtDFq2Y7yIkp^e=&Q2&Rzq*(x{1VD*Wn)Bnpg9!KqDdH zd5rU1qkuh@_N1ZVWOU%KpLtf9Ow_Ni`rx2__lq&{A;uW?(;5(ML&|#xl9Bn~=b%>} zSJ&~b3l?N5-{`Jj(D>04PAE6dnpNI$;Qr-J%rd_Kz7fV!Xs7W^x(093$qP( zR=rB&hOM8v01v0;huZ)EKmbWZK~&43To8Bp-Zb`oGiJ>$r(>x8`Ds5cZ+`O|GKuPn z?WbXA$cj_yD=Qj+FP+m~d9p7^Ie1n_u7hEUNIo8h_y}~IL*MK~r-p`YF*?8cpo4Nq z`vx0skp9{6P56v}h@|%hvoX z+~%7xTR=zk7y~sGR~daB28|B1FTCQ4a@70Yn?0GwV;wr`=%e^V;P#vt?8&fQ`k^+Ejr85-PZKn(~aW{an}C2<{X9?HlFbttOR&4?Dc@qxL(=cTB${gVK|~ z{T)8HvQIf+&ppaE2&j#ih4nkp4)B6|@KfAX{CjoM_ip+0_w$n)20VrOT9$C1k468g ztAAHM_@U#S_@cE5jASmc!0zZN6cy!r}Lw z{mjj&XPr}?yX(&718-wR105UE0Ia}NWN{t$l<&XmoC~G6c9wBdf-x$jb6Stn=15WVdzKXxh6WVja zE&Ov8r@DXglmDk&!3_RktY~=G`#!*mhUY~AeT2b_!cT#zLBM)*n~EzL#*TJr9cPnJ zK35(n2o-{^5Kthxm-7);LHzoni_0<0sH^UOgw-C09DFbas;z6gK@c{cR;gV^y{T{x zV{o(0L-cHU$d1Dermj>piju-wQj|K)cq%dB^AFns(6%gguOr%ZB1 z18{qW1|Ujf>##>_>7nxPy?eH!(>?IO+%kRojB+JP#kUv$9DzYoL&G*(ZB;hpQ*ZL| zV+x>@G_Y}=Em!-fuVuU z-r2V$C^_(&oq6qqPOb< zYhXur>p=OSO!yL_&&?vw;{?ufBkD^-#vHF%Cvmd1lqg&T3%PCyGq11AgmOR z4t@p1R!+L~P`Rm*!Py99_{CRUQ;vPxu`x7!@ZbZ>8xB9B?C`AZqf9))z{~zXc)`7r zOKdxI@$LCh7N5Z*h6ZHb{qyISpEJXF+&_Pb6+dfX2*=Q{&p~AZD;iis$zIL{?7hTb zN27A<#0uKLFpO}+Y?pv?%fuQCC_RAD?}@v$X_@gbRJkm3=A3)Vch5Mp{NdUw%iE58 zOWAV$jmvnp-pptD{dHGgS;nxMV5jXcG%&N$Ry5RFNNLE!zbbcR6Xw9OWdcg#YnRNR zn|jLutJH<1UQUHQgbcZdYX&PC?wz^OGf%HTDzs zgDyMP$e==MpOV!9B1=Tuoaz4XM?N9P_RH^|@sqOEj?XT~9s7>*e70_QN_YkU)Vr(h z>|d=k`7CrGk2)}@@~7sf@>cZ%KUMt@OT90+_@eUN&wjjI#0KT}9`X8eG%MnqwNoCd z;EVrC>P(}ut0#LWzVjZLV7M^plk$mE_|t)a%bahcZ$0gdv&t8K_+v{|{^OG;lvf>e z0Ly~wS2i3FxwJU?3*j*uN~BJ&O3m@ET-N};ggoVQPf(YSZ-6#m`0`iFFK=K)!**Mi zV?S_QwmNA@aJjQac6r`Gq%;<^?NPW6hQ!~2mjshO_BC1AN4@x!hx0GLyu9i7kBWNv z*kP|JuX)XD%Cj&uC?i$Qb?Se@)-SXNej6B>w|>^Ke&%63%RP(jct6E}bmA%BE642i z;&K3kmtA+;tvnqA)gt8YLeAZiSLA5F_M*XZ&{ZQtTT<=-#ubWdq7yjj;};nIaLb>| z56}4-hd4ikapz^MXxO1lre5V+WtDX#|GAy(;!7?r7ybr$J?pM=%f0SE=ZuC;2g>FX zCY4E?Ik6rGJdERDrmSe799hw&fRNvaJDhfG>#G=c^yN*?%N04ytTlKJ8?#0X4Kwe5 zpj>?&+w7Kdo(M3klPTLwE-%`1-?9;3HToSZ8g5_()fYeciRfc%Qr~E^(Ql<`23*jx z4#4adq>S&h2@(kI6taoXbckVhTBo>p$LU>>-gVMEGA>>w}Z+_=HG>d>o>HbJ;{I8yLy?=(n9>Dn}!DauB(~&`Q)cQRc=709f3~pmZOd= zFMQsPOg8x0#k!(Fx(9#rfDUb-&P&P?J;e6QpW!;wyLJ0qRy4fhvnQ4PIJ@WIBabb6 zvCMulpD6b$Z?-4(Z6`XEIT??jZ@6_UyalX~%WU}bd;%u|tp`^=Pn|ZcocXI?mkZdo z^5&zCD7!HJc;+*onXf4cTcf6JkIt1#yeU4A#Xp9}t}d)2TU`td&~+YiWY(6qs&NUxJ>kJX!}G za}Bm$%%c5W&bZG{ZJu`NCFP448unp}@5UHN)_@io8uEoH@DjJG=ShL;a<62zLgKHi zaOJP%^-E+Ioqs_&`;;G)k&`zqA3yGcWoIV5vvm%9VHDUyi}h@V>XcwQM(K3(nNwGn!21*>=<; zO1*T+R7b{qu5%zOxTIDW8S$V^|-kHNc z-b3f`RtBZd-r-rX47tBdKUjsIks;nwBlhrYJ#!Ri3dj4-|pJA-hwG?*#E512MaOO}hED&PrM5Hq-V3;{F; z0sH$~ZYgK}{O9HV=`&cO{))2eE-xP#KVED70t3IFYe-O=PPro*r-6u zkXk~=G0=4jg@%UP@0eDuV(;5GPdTN$bgw-zH0)WoPPn3h^mg3M;um2KzPey8;ugs} z&T#$L1b06*bO!?Jsw=N57h-6*{<>>feyO41`B>E_aDdJ_5!UIj=)m1uC9cj=D7>tT zd{drs`HkBQ&VcVAdORJvac;y~`J3~8T~7bendKR~?o!_KmZSJi^mdfHDj^lA{8ki$ zUw!vCXoG((hO-1Xl&%4UtScHW2Jau9@||)egY^#{byRu%D_>c*oV*}CNY zIKrLELV>SN63c6YcZ6Pg&U%;XO+0#ThxuG}-Sy>TANxePcKV&=)jRD_-hcduvZBEb z(}9;OepJB4S=>FOQr;Pf5E_9H($Jvt=_&*-_lRc*3I99*-~8s%OUipc{>kiTd^>y7 zUh%S*!8co#<)mAN!9rdXMLU}&q%~NKS!<2*5HpyUUwu_M^PIEFG&+Mn+&(h}-5U9~ z<;KjqulMw_G5c57MCdw0lu!1F3jkfAgPK-drx5RnKUcn_Nrz{PD+^1NYgRlX>~>J9rOBYxqx!OLGTQ-mL@6QZH`g z>$5^$Hx~oZbOr!d(4M}1@^{J+N4~M_xBE-VGq&9pWo)Auru@8|GR02RC5*}&+khRV zS;oQ*%&dx`><+xw94ME%|j{8t~)9c?57(Zhf z`NvNDOb#jf^2abV@O|f}qZG_zMc8uMv)kR|%jCyR*J`2BzqJGFTN)`dRQOc>zj5+6 z%a1TLya4;babNs$*=x65V~q8ahp2@a9Azda^!J@kmwb{3usrj?rI>E>aSyj=mWY!^ zxJ$0Oy1b7S4Ku;%*aP=1Z+i2aIZxm@k-g54inHtx7kW`;d5NU#p1WY^im*?6az(>j zWcbfeSdKgK^JUYmCY0k|_ttXgOAja$`TQf(|7AJ(FXa@>7#a{f%Q1?q9Dv`+a3!*R z1O-6FU{=(D779IlgB>BphGE2;K5G^$;xIH^cU3v&sH4kP8zO&~p`dDLxa#sUaPfs~ zotUs%LxW|o1ol-H%eGKgG*m;0Gs3Qb7{jIF=AWx`mT=8Orrbw6oq5+iWzHt0?E2Av zDKFZ6H=v9ubMNC2VOCYR#9ree`VsFAMp)KP|KS-vZoPBs#3ff;S$@v!%(3r%PuVku zhD|x=2SWq(s8QPb_wv0dUA|XEudd{aLCVU;InZ%g>!0XX-8yj&1JZSN+<_GdGcJ0XXm5fe(Qvfmn+EgeMh{Z zyz#ZKiJ?InR<1yN>z_P1mr)p1WN7!ppBH z$9(LQF$x}W^ikzyFMD~;5V9=QZ~+`})c9dp>c9@!WZS`62VTvIv-SNrxVf$5+>0(M z-#qnu){% zpKdOvL3?R>C`OF!pUJ>z(!}UJ(Sc~6!kS6ncIjo8mWwX4bw1p_PP+1w3nD91z^Yf)$X|q@GOPA+^o7W64?G?|W=&+nC=P?1 zTdur%R+&nir*Sd;Q8w9TO4;E>yO#Ag*r;4fo4SpareFBP$JsjZ{IUjhgPA66QJHEP zMh*%Ihr`KoKKDQBH_TKOh>`Cp5n!HJ(|Z?_!~>dF@D zM}xMr@VVeeGK#@MKFWd44hKIN41AFR65{pc%S zi=jbTu#f?P>UCt;+Yx0H|>}+Z2=);NbXR z9DT^0F*ICWEqH8e59`%U$HH1?oUQ+kz`5 zEbpIgW?MLh>T|w*Y8kfqX63{0eQ(*B6?+QH`bSb9t>-bssVF2I`|^` zyhX?&$7vdV*G4Cr&zSU*OD`?o{>InKC9Fz*D~8y*qG7A_7xo*{TUjgpK`@85BFHi^ zIAiv#@}tvFFKbL#pH(P)bz+Mtp(BlqxXS5B6$|&2b+m12>woDQh}3f$LkAF#6%1tl z0CWEOm*BWp-HH`&8GEQRjt$bmt_A_mP`H{sOqXKh z`P0pRDn}mu*79OjG)$T_DW{INvmETeRS?8m`fFqmjt$m6ZKMp}PZN_x=*q&9s z+8G-D<zsiVk!$JLKK<#>mK!iM zy!?3>8jd@jLFx0Ocxq_K83!b4#)b^KpwtQmE6Y`W!CM7%6w2>NW)w0AQy|i5-OIqx z_VkH={$kmh{0}?!*s?#%47Zvxg|7%8Fc;O8Kz25+^sp{e95gfx&>kOPZ|l|9{jU7t zSLbF$!wrAFHMnn$MzrOGu^d>qZrNZh&J$q(;>sj16_OYlXoHGK2Uw|F@)$H`pd=EO za}GEh%dHbDXv-@HP~cgq@!(?%%gt<^xS9nNEY8k0Dl`7f`#%8R?^!0YTyGTc+`AX} zg!SmmQ|M2)3?)~s&d@M}_T=ov559X!c^xzPdm{(7*?Oz80n2tZmbs+b4o3^UGYry4 zzE(MT9J%HJNgAlKuX=^$UY>!M*=A4RHCMA7_u_Kv-S?HFjy$ToNW&e6D2?ajZkN%{ zV|LxPcFDyTb8sXF6oGGPzoM|pOo3-Q2LxH4bjPSkk6sL?|pvKUU|_B4X$YT&u@LF z{N$ob%S$%jxV-u8?7kvq4~WSRZhKP^*l{zEzP@FU7rtZEs*VkBEi9w;|n&DIGF4LfeL zQJIhx4Zs1{Dm5*AFi(GFDJ+(fY$<$^0RhjW;hAyJ)^=%`mSOE%OnaTrAt?{=e8=sx z%1qAueBlWvmKV_;#*SNufeADCqgdTVoe#G>%NH|y_8_00elT=b_TR_s@n1PuRob72 zk?PIwIJWFYoqEWbgB$xj2jwb%t)Ei?^xe93uxQ=LBleH>DPFBl`RmlFSt0Zr_OcE~ zX?~l=qh~)0LjfzGXoEW8#n8ZA#nH*zlypX;;M^AV|gTbTNjka8Gh-mpJnn} z@|RtGO*!$Te=ggv|Fm+zYYr=W?Zx4ETWuv-6HhuuE;3uK;i0Y)sBl7SVC$?)>)!Yd z23=h=U>NwUnH<=LErU;o?ylO%Y&`HR?_I>zFnl>HhBP$XI;Wn| z@SKTjmQC40IEk$j>+vZSS2PS4kFHOXpKO70nOEANKXFQB+ZpnJ2aW1(6Pk!Z{B+Q=YaEi#WNc2V=Kp}Kl!ywVRLPvSb zb|nu<2V1;;>0|R&>nH7qHYNR?!F83&HNU&I{FGVL)2_Ux9Kvd{cjSzQZ9_wnA{XQr zkOr=Op!%i7aor3m!0z1O4AIDfVyw_OIpYskfGcp8vcU8eRnL2WT5@ zRj+()5#&ed+b$7GF$mNMCOy>e<$KfK&9;)?T=v`YVT|hs^4Zmc4tW(T8urSHhDR9> zh@S_c8sCGF7hz-_kBp0sVV=~tf6-NGpW^JQ0PFvL`eteKGgfS0clG7vFxu)1cG{_I zz0KA+)ID{loT1#pk>-wV0WGU4;Q9iLma zfM3;(9N$P3^;E}b3)z}0uF5e7{7#rEhdd9>x)5h4Qr&)V*IlzX=iu6MDSG_H;C~F` zzdaZ`O{DGBGa8zqq2d<$ht}rM=d2K%ej1ltu`R#eg3fUX28>_++Cp?N&sOjpG$-_2vF)m1x5=LIqtiH` z^u}@oD~69^+v9eOafgxKmg5$GY16jsSZ`VJ2#h=Lo}Cp98(<`UGl#xzy5$zN0OVU+ zMw2X-?5XMgA%+I6R5Gs>tCfEhx0G+TV{!i#gYT&~-;z#RWqwmmEgpc#8K}Y*GQ5Tc z8BlBMSAO_|fO#grM;`ZqvhB9pP)`U3!du5^<4!{%t->jW2Kdb7Oct0ffy zrLuJk%GNj7kEwh0F1wT$?7Ryn9d8vz^$Q5X%o1$!ilKorh@Z=Ym0C6+g@~3{l^7Kl z8>m8P_T96}_1E7}&SYRR1^BOmDW^={oP%$khSk$;7zj<$w?>%OR@+_h4^rI^(IO=6 zaAo>gH1yvypgi;Z3k!4f<**mOsJ!S!J7=k#ilQ{Ner<$ac0SHrL|}op!dr#R19%jc zW~i_f{vzt^HU!|6=l`nw>b9A|;KR%yZ@0}hQ4&=U;zX)B@oUfAd(TGU#hVA!xP;vq zscSHjeE+|GnG{>Y6|X(^?HNpaaH0bY2LLf5LE8wB#1sg4(t(JBiiaJI^jAU9V5PC) zP85%`5h7PiyCbO%f7wCBGcwkt-j^Zlhj&8Tz&7COf7UPW^%mSMLyR{(+{ALU&;9$! zU1%vMec-)i#~q$S+gKK5%)zCJR6ymviadbT4C{=U)5lTQ+0ByAmF(TS~Orl3v*Gp+-6?FRLTwv7+H7PU1f0lvA^R zw1*@Q9>nyFb@*oUMkq)a9vCOFq5)4X#!v8cy*mciO0KN+A}a#8sP=r$2>lmZL!NVh z-tf_7&Wy$7moTD>t^3^}w5Q$os7m?({P<*shO{LU!kfu2cV}fqfW5G+^q57xUVZtc z<-$KtD|>9QY1#XLgUaN|lQRRWvf`)wq_y>wnGt9ri>g5QNlsUixLV4~FKt*~Ypyvi z9rv9m&^MyYopSy~`4rTfFnsN_)ALyp%!-D!)~5U@!^~LRdh4y_GGB_`7dxHm9&9Stci@k`s z&Q;vb%uXC~=&Kswx+0XkjhFAf3# zo-!u9#eFI>QYU=rYlg%f`|3k-+Pq4EGTs4rGc;7=vD~dXU*Xy|<@n476W{u=4kU$! z(Cd(q|MsIZ0(*0Qk9zm9EFXPFW-jcfl=BW=bf)QdzE^4A`S#=~eH04sL-54;7#e=s zwWq@mJh1G$%kE_}W_UC-xJ}CgAT=K3z$j?%r!YO7)jWqWm>i%00}#ypw=hf2a?r@& zwyo*#JZzPA3&RV&Gd=B55Wvcpw+ zIbY|YRn^c?+oQ&b+6wG%q$LI#aMI8)_1@{_2HM@kw;WNP#TLg=qxlTq5(dzmlCLZu zVYx7R&71ci+mG#Pc3gUr-Tqh2rl@sG>($BQUW4ZV#UzJ<-#nywD zJmh<3+h{+^HwOpupnT)3y#2|vJEoQ2u@Cl~oBoi}z3=eXalq#@Q4+^x;2C*HVKnBb zQ`q;YIM()Ve#ms?I~I?#eE*eqbq>@&947=&e&n)_3!*ZzI0_DFE5Id2DU}4 zSkcg6I*k}A&h{DVCF1J=h4v*He)$jIJK((l1Ie#%a(=gz*X_MW2GkySsO+}wYWxm< z;BJ1FyBbQAIaMdn$Y9?@N1Qw~ut?XNQKCQgwSNh0e@;01E#>(PFq~P8p#dD7U9@e< z7wQ@=a~DBjr!J%i`Fh!A9ca2={2{g+TuI-0#zmJ1y1eEEJC$AcVg?o?3`v5&h67uA zCP&D}ekun{cJQN95!d!_ofzMNh%>gK&AI+3bWy%&?@Cje^CF)7q+t*p< zd+)oqT>rak%8$>xnD(%$dls+TZeG~N#^eA+9j1C?B*>Y5jYlZ}y7kU;bE=Y|y2>W2 zx18K$kuNJ6Z1-!HJFZ($eqn?mZVTSm-(tIR?H!sRN_qF|Ue8M4=kU4qYFd=9Ewgnh zPfI8N^s_yI3UA~szkrw%SuvQA-t9DgUE_>Xe^90i9QP?!9c+scMp_tO9jUgNikyZ9 zb!~N0^ODD+{+mtS^iIsKyF8d~<)e(UlY@ZXpfdh$s0uO#FLSn|Kl zyLbyUcOK1M1A~SJ4Q$r;wCQ)0ADs00td=nPTRG5u&pq~_e;OY-qOP~d2_VZIUa3Ye z^R}&y#$f6STxaa{i)+T)zC>?+QBZljxGqK^EFB)eAy%5#e7%<t;injQbZ^~%@3PBoyJzL_W2|r#AN76f!GXKyn>k6TQPKL4 z_SW(8l}w6JM(cVl4Y~Yz5TZrp4C>ZPRKmb%4bFP;9GmNzu=@8OoF-B+7=D12w|-r*9U$D!L32ez z9bdp7(tXrO4)DCMeE+kbE&Ct;{_>Wi*)GZW7={5-?a9MrgSC@9o@zh;5JN+je=4*g zjtY5?VLNKv{ue&;cG+d+&n$nOedk?SdaH#_#azOBnPyEG+6Lyysnc%14J+9Qtk3J` zK&iD@#;w9(hn`Q6z|1NXUTGvKZa(Wgb3maNp$On8NXCcZ7GQn4y^hZwePrz`lWC%O-yCRq*POdKtPyK29reTT%CpuV zU$#Q?n#lL;*BQsGK6HvgNt;GW(_TE>%nl4_z|c8Ju{B9sh#MT;hqls-SstV=Gq7~_ zG^V)^^C_h}?`97#hdaUJ3t8IjR)dL~PKNdymoX5Wnc#Z#&og-@+j_Tr zzRQyiO7ENdK)HumhRGOSCSX06KcsK#jFo3zZF#f&G8}y6VeiU3b6(7n|0NuhI0pVP z{z9HTPexfbAItt0TWlG+JE%iaX6uB5k%v(x9(Z6bGjQ|yJmP#h>J=OSIS!?EeA$RY zHrHEg4Ch}^7b{uvxl${GN+-v!8m+i8mfiDT% zHuIixGY6-Rz<}u1ie4)if+AUR#t0yhQd}GOyu*fW6NUrGg|>^3o8cTe9E!H=aJR{ zRY(4A_Zde$jHJQZp3`^IpL17CjF5M9#xcF?1Yv7DYM;K0uQz@_JIsdFE_lT_k4VT1L`hU=}v zCnv{d3)^Tc3&WQ8uV}EZQwm#GwZ0;=@Y6+Zh$CC&1}M`a`Z2$*G>k7}*yqjR^Ok>| zHiHA@F#C>D7E=!c41CyLXM6M9uZPiXwqP)~VJ4KS43!5%U-C>I78<9Ymrf}x@7AmO z)OxC4Do|&#ydJVRW%A?<)NL2iQNA({2VNRx^93pVZEKO4(9bL@|KrEAZQL)EsgK&?4^#uzn)Bi~RK^=aFUGDlpMG1+!Q!!wS?7~}aRl&QDf7JX$y^d>u>cASo#zAAh!q*PW)hH+*N?&D}bzonm zZYJLLb5ccr+mCWU*^r4L@RnAOvf^qwa>jbybkfA=e9qd-%T=~ieh@Da6kqFEngw@r zFoo8!B0lxgG+*R&4jupmWyY|J^S*Q{!`=Du;5e zpTc}WpUY?Ra|7$~o)#(g@jW!*6h)E{^b4gqq@H~`+yJyWpINTfI;J`+U ztTW9rZ!aOq*s>g^B#^;5Hp7d5DuZ z1UKG&uCoo!ZVF$kCNohmQg~Aq1x6Kmt2REXTW3QIYvW-fS-ccxqG1iruE6NTaRx-| zYG%`U4)dzqQBD;Xg`s7T>B7j;5S$c(;wzpC7aO5Ukru%SL&BuDifRPEg1QsdmZxGj zgf)SsYh|cKPzgjKgQmh&SyLd1gF;DqS0$c?fe;i&;~7Um7}^3?99%78IrKBUS#edQ zgd^^5VUgxY^WZK#%b@_SxHas2vlH^Ymd9IvXpKR!`ICoSQK8Z-Ob50Ra+aZ6&M7}Q zc<~TRAz9}-)0##+Et|{MEQ2_=PE?+0haD+E`?|&w0D@_gW z>Z&S?Y@^^^T+$xwaDXqb~=<++7Z-aqThczyk(-9)YD)A(-dX z6@HXMJ`uj#CNxqg!tKbcZ_6V8#M%t5Zk_PJ8d?*BCKMp@88JW_a2mnVh2cvcXTLey z1)#m3U0lYjY~2cFo8$t9?I_9%C602*-MU!DN(?*7l?-w`Ol|}NwGk>`48oQ{v;`<* z^A@m#jlujH9GvJD3k?mXi*=YfrjnxkR`r>73tkq>}4Ol!H{ z&vM(=;=miQtRy7W0)l81J{z!R%pXW z1+cR%*>-F&l_q`}M>=azke-VfRC2~&Sx8U0g7o^+vqkCht3SFmlr;>JsVq)TW);(8 zoL&#j$D%NMNYYAsS>S|c`1M~Gp69pT@#y?*^KslfqefYy(>NtR$m<^Fr=lhO{OqDi zf`1ZEzKjwLtunJqd2KiL6OY0de&S1+qzrc8V4JaDQuYd0p11zY%Qo*NMv<2y8;nI) zU+(qR3X~G5T&$#Rjb!>qa8t4$R`P@Pe>KWu72`s zDZ?pmWVU5Az6J^6tH_LH&#E%y6oT{ z*756+UZvda4JeJaaoYX>@DG%gVw(Z zJ9S04^zgl|f>_QhD4$WLE$O6vJ%gd1qhXnxm~d9L>J62KD)lxR^Qm&pHm-q>Jh=dT zK!d+@D)q{M3TTxvTbY7kazXZB@OVmt%vuzx^=~wv==Y? z^cGeRA|#AFtq;p-eMMIxZ}Sxo|8(IG+U6MA8g@O-H-Z0bZCY881>&ll6(=}Y7Orip zOD`P=%3Ekp{kq+5A=juetYYPQ1Owtj3pnr+`RmNRZPEV1uM>^*(|Q1PRhL_KmcUc? z*Vd=>ZLZ?nz2RR&{H^6MytPYpJ^MX%Xjg%02osd6OCDzcZ~cj@`jq)N0i{f{4(#{M zw_U=NFElWz$9Xo1XP!uJ2h_%MP;8#I2kWedH>fqeDfj}b;@#&jV*G1V&Y)V{si(0_ z+_~jfJe3ii#~_}59m<129OTLsQj%_T5vPF8zmyc7|$~HfZ>-Hyg z&FE~&UpY|QvOI21>fPQo&M9ZJ@`HEjEl-hy11X;cz@Q91ZiOBI zZ{Tfv7Fv?;6-lbU#qSB6bn6G)jJFXP>(#h}QR^>3fMp7s9Y~LE3 z<#AUyON+{r$V7PG@qrU2_9f|Cl-=O(N@OQy=%xcl__ibC*gjO<)UnAhheB^OX+qiN zncK1AiY-8-PdjB|$m0Q?>JA!O6aVkd#O+Gm^1gTpmN^=yh6b%&)OM6I4?B5`%Z6_S z8s;})WvC3?fFv_mX*pK`hEs9(fG`!7Sj<6J2GwdV9MMMvaw&XkN2%~r$&3O4a_iU)lr@zj|EyH<&s4m>#1M2Hi?BZJ%E5R@{x4aE*IhfR@A0b<7)i+|`)af*;5@8%SC z!PtABzrNDW@~1washz)NP$?6q7#GM#VXZPJF5+yw2xWjPc++qYh6*l z)``29btes@V4oIA(yEv;H2~wd2fOHUJn3Yjkew+^BG1^{?3(&+FRe9ddEsC~v z1ucZLd@-M7RNyN3C};Q+xUI7jvu0>;2{@8DhK7+0Fl;)*;Q8fzkzyo+-v~md8qp}r*E#RDn;mq!=$qW~0Gt;zyWDLA* z8{iC+X7DR$uT|*HyPomuo+AW&))5v(2->PlNCO9?8X2Td;}u)1oxVI}9243`2QZ2Z zM-giQy^oWqb zy%HG3mcg$qS+9db0*6T_=d-&)q5#wVb6IoUB~c8QSEy&Kp`3^mWt+N#vgEDev|3+0DEpg4N(OcQro<*Ub_R?Dg zRBzj!?LdXme!xqZQ3}A>wq@H@M(H0~V$kv6R`+%aM?=E`w)m(ZXwV$bp;IcO8n~2O z&Cn3J06$7^ja5B|pKKa(>B)on_MG9osGw><7+`gsOCF;Lu>xZpds9X(!KlHYE35OE z_17SgtrKLUv7s6oP-ek^{>35?6~d5Wm60iYXJaz6m3>q>m}YkMcLx6IxRO?KAl^dGGHJU7?39h zFs?^1B+LWJ+ow(~w;_slJ?SfD*FE+u>#VmC@jNKkuY6#zpMLTpOk?%cjcSyxyoM8U#Nrk7DqX69Ob*S^_EX3->D>uU*nDB zC1Jr^e44&tKdEwV8g&_AH~k{{SY9sWi~~H&9zz3uWFFj<)0V?LylOeB-qPr2dr%gt z)Qh+6iUM(N(83rnlBeYtKloj~H;pn&9Bp%QcG^QHr_4*-O}iHD$OHD&L!^nudDCSu z0~{4}>sMo+Ize!iwjIrqABd}CSXYe(;+ug6w3i-(uC{e$ysH_EFOH!Z@vK9YevQ5k z$P70Rc|?8CI(0B$UY1vyWbnmZ`JpTj7vY&cMtjN@gD`%ruBCNk4fQ>M49wS)viuJ@ zuZ-;(8pOQvM;JQ=p{}g2aK9eDbF-YvV0BIKABlWoPf=Nk{8)g2(p7!Kp^H7bMqv#N zF+`I_8Z5#Xu?U`2YANT!gEAv|CAaQg@wNapYcm&}#z)e}`c%FuJ7Y)!HxEAU4Y;Tm zX(zwij+}^ytOBUCOCHjTztolW%cXATV9~npoH6-Md7K$#aF1bDI_QE_MN?FTuj}3G ztIQkNOOg32q&rSs$-%n3ZyQk$b|snZN!qG|SAELeIEVOOt&q>=Jf8KM4TkaZA!+PKhLywm>aGc-WBlEHQ=FDmQhG3CE> zU&$)FidQADG-~KoWNS5~To%oT8Z};3&f8{czVfwwk-T8NDCZqt3bY!5t3DP32Xf2_ zCs`vpGw*&aLR$Fs35^UIVyp{gWhOBxzgx5&|9WtD-8w9$c0O{9ILXvD*7{i_ z)NCr&v|-b(Ey{SwrE7$u(4VXCVner@Kc7WQ#l@LU!`n=86;QRo_-se75N-@#%O$Uq zNGyO8fev0Ow+ahG^vi08z<0LJ*(LF6!dn<-UEv5T!d1*0@eI$Hdqx;^H#uU_=#|#P8F)+Vh5F_vK2{xD~f}t z5BmAk`L|*i*_8`RHS&;;jXdADH6HmXM1n72)gefzV+VHfpTb+G;1PeV&X&vNjXDpW zvO|(uv4+Zz!5yUwy1S%My4!JtcRKtU`aQ#fcm`s3Z|LCHXxeCFP*Z}dz^*)~fU+J` zI83A9vz>S@fHcs;isk@72eEXZD80_^=MzGdEe0wE#d51cFazUmWq_Z#>mewf@`B~2 z$9H>xTSxNQOhzcfY^yjpQs(9aeFUkAiBoHjHU@30Yo+Er9X;=qAr797pZ?~rAa(16 zgJ4xDyghruWu_xoIWUGny>6lYBz3Sf+zu!T5Il*$u1E7B&mdWgD1m*!)i%dKje1pK z2@fEfG)l=g`q{~Z9+oM2)HWQP!PPfu<)APFI1%BQN@qD zA(`OsUj7E)XWi>6`ux`a_@yv;LT>Zox3h=Y-iWkh1x68gbS#Djt18woVc8zKYWGmc z9Qs6EWWWc{XGKHW1R2?wiLab-TaxWa;S8(^n7t z`YC0PefKHD*WG{uP#CNco=FlT0YtYQHUgS{OQ5Kv406+jqL_t&xnaa)(8XiPW zWuOdf|0>PN*>Ie)Km7&o4$?Dt>d6O`bL3cUhZ^L_5V~3hmAalBArF;ZVX2U3Hq1!y zX=Jx@#x(Fn`qPdHYTGwjH{c+R{Zi7aq?6ZT6i^jp{nQz(@A?;zd2cc#>_f3)jG!#d zSZm{U)?R?6c6Mm0g$Un2*UCE+h%YD7`b>kzDM4}a^jwMF&M=&H8u z5Ut`^SxL?^-*bUztLzU4W*?Xrn5ZKrP7ABNjui?r+*vY^!Pz!z({Bs>;zKb>Q|lo)hnm8 zr||VFY|6;GDj+f#`nif(nyV`{p0xi~9!Hl}mP%V-rf;W?%*ZzBC64l;GDKOS@u430 z3Ej~z#b2dD*hwggz!Jr{AY1#g=Huk<96s4Cksrh%pe zGRUty-~>|mnF$687d_i?r3Zsca}CM^Z2i@(1b5}Hyy@9_Z8C4Th$)XH0%_%IVYwxf zt~cYC;poBoFLrwt!K2XIX_0~ZRQ~yg7#bo7x`rg{S^*B!tQeWZgJf*{m06%3jmXBA z1|SnbmDkZxgKUEbDJio!<(TF=5xuB zX>*{DWwoQVL(|FhUd9Kf+=*-hwgXr2C}7N5VKhhsK;o&tKi&h8A3^202KB;?)X1Ni zRvNa}eXaP5Ik89!v=+wEHm?5%Ck_oK@4A+sI){F?%Oi^#F=cEX~UmU?kULtc%7W_S-law9y(9sFA75aB8!g=sJe5*WfC{+ZzL~)frop!9h^jfrJ@axmsxsE zN1(;E@;9^Z%tUHvu&lM!R3lQY6f?w02QM>_Cxt0_$W&j&qx-WR)Q+J|YXnJL{1c)6 zbbj7CSUmRdj-PNzYoQdtM3e2^BH>b6XIh=99f6=#k=02GojKa#9oIJ_gZ|C6j>eqL zGj|@_U2n2T+qXTbN2>eT@uYpx?oxEqSS+qIPc!bExY~Dl*U@CsjPoM!V9Q zaL=&(;%vBhnY16LMAVauIRhT7EAMuaUR`GWhKA6OpjF~@KpOO*(9t>#5M(hpAU!Ib z@v~^AlK$4T9jr7~?M0Qzy@##S^X>~UM&R+-=PXnIl^~)wIkXfbQU+KM)!FGNDu5J+ zp6e$JMYpX-=_iup)zDA}EHy<~%16SYM09P~*(_z+YGqid}YJ;+wv(3b9hK8zLRmCy=Y6pG@C)7O2*zA=*)zHAG9o&meT9hwL4@|nC*2dsl=^hfo%6-jxY!9MBi!(GbT6Q!%m zM|`PF6?SEm0?EN&jK&1DL5UThfy90#TN9L>;-;{|)iy->PA;AWk~(9r_=?$V*nHpdtPJ}#G*a#^urefPV5LhA4PkSMG8 zQCycF%Oe>)guaxbOM`dx$n?ATNf&8Yb5E&{3PuY9AU=mIijp4RxgfWw*ALgEhzmnK%(tp)T)?EKWR zmotb`x0&_2WqrMd!1J@6MDfvKhP)qO^>Y!5YErUhhLoVyo&H#CfMog90$vH zfn77o%42X+^I`-Xe9bg6H`)92)OP<6LqoOfFz|wi?yZ$n3N3}aRErR3Euzs&Lbr;v z;q%usJanCm13CxSDl5+ZcQsCB0GqT?P@2Zmcz{?6QbAjvI%QuP~ zUYoPl(%PU0u}SRkg~-a2l`lJND1;rI0w#w6O02)(EVHiN>sx)7E*2qy;>#r+%}sx2 zZWOew|4dqnrvETHffQL3ND##v{8R|#izN(%QpWecquB=b z&>!=bZk9nALQR&@8eR10s1^*Nz2SA?N5#;#R{I&=MG(a&1(SL3ay62MJZ%;Zdd9Fl zW+7Wb?z`iz^5+|WUoPT1;7j<1`L0`YARjX*9tJrY!ZRmiA?y z3qz5K48J3PmCgFc5NhUDT17R_$}9VET^l?nJU;vohuL zop}0bixrABLX{3txKd|Q0U%U*4?Y9C4P^j zz8lygnpoG~>s#J6Ziv5SmwquK5S~?QD%A`KhHDhkb#%ycKZ1C;JlXzHL;|M^7dLr0 z|KzW?KMfTJJK~_u(8x{f4AxrR_xcC(;nJDj=WO2~eGDSN6`px|E>6qC_@ONU^)O+5 zs&nkvoar2NN{f*LHMK>eYJ<19TfK1|0>TX<-Mg>GF>Z6FSC?%xuE@89wJZV|Ok)^M zgan>fegG7mH9TgW^kvd}*01)n(!GNK4C;jp8u~=)xq$Dzt^UC{%0Bg$kqAO_S%Si6 zoyS0khXYknRumb3A%kFb48H{D7+Ak_Ck+YV>DS(Q_FYF%y^I6U)CuucSK=h#r$4Ou z_1~-RTVd(njC3-G@M9!O1$U4_eCEA3T%D zt=|7rCnnNF9x{7}KrJ_Ew3KswY$sWPL0F52`WAYCB0Np`h^v0vP*}typ!%mqpnv+U%QaZC&kuFf%qMgx#m_fC6p zPz|2GYrFw5K__1B)3%IUUha+7)k?kc&fSowV}ZRFM<|p3N97=S^>2|0V4hxG!hUdB7QoJE-kmf=)e2CIw$Pr z+VjwR3lCm4FocrjjnGRYspZu#4G)Z6Hl=bELj%mEbqm zz-+9-6kcoGhFLcaw(ozhYxo)8=Xy14R|f?vA$6ltV_itsTrMHULHXRJbA{D%5T@{} ze_n)ucYGpvh+Cs2xcAuS-Td0U!l}txPR*~~oBuMFE5`~;n;1|*5H5h0L33v#+(Td6 zi|xp>LNqMUaWQ+Kalw{nnOok%?Y~0*7U*5zUg1aXR-RWzWm;+n@ebD!cQ}{4m`vcy zIN!Ze;kFH6@$NY$#)}b%h}kwJBcwqSA4hQ9(7PRlGpgn_facQ%#x>QdX?z=+e(1Y# zOsl__&;9(^;CAFlq{PQVx~ep&WOYTXqymPDKLv#T@R?ehjx=r?TZST#<$<&zCXlEr z=tn_Xzf&U*;*!+Tlmqyd+W|TFQMORG!$xW;uRLr4s&Rt2#*aqWdA8D}PJ~F!k@Xm|ue!wa^YP$sZfbPWhIig;B$s&Z;j-AM}# zuI}#5Adb9Ufi#Nx_kA%+VGamIah%Wdeb8nGXEZ#p$@p^kzkaK{bpQQ0I)yJgsO(Z9 z{d8{hs-M?&`DmR{wD|VtaYU*s?po~X-F}VhfWg74?RxMchDiu__D*=2Y*4GN-np;x z6Id0V{xKSGckrofY65|7y6rbeB(VE2 zU5q|Fr0y!X(A09O3przMJJR6g0L3r=$SS7&dtK^CJ_ldGrB3v-EXq9jzixF+5$X@P zh)yWqo;&<3XZk&{;JN9zp>K>=Mr;_iL>;z6Ud_Rn?doFX)*$%OpRD=oCto_FD-Le; zL>%>UHl1->TJN&lB9`?_)0_|0(F5FNZNe5qR?|rlC+kv7jKpHHLT{*AEWxzcB3XuKGe5Q?YYgK4??f$6W*Uk1@$+7 zO}7+1P8lTsb|NhKDJG?{?ZIZE@!fXQ;+eBNs6j&iy7I@B3+Mx+i_WbD9cMoMmwtu> zhA+4pbI^aNpXmjXc>J{Z`nwudol|;^a*LLJnOIeKfIk)iTD@{2OrCwM5LV?+5q zD<6O=Es__o(y!=;k8N2w?VoMB9)j4gNR~BSef*oh=3#2@$*+6whe(r88&}5E$-BBb zMn1Ehn9y^o0*Hjc5${wOo(*>8Afst+=tZxbN=19dhLJPo19o1h!{iHG^+F9>exXR1 zS%s{Q6?l;__&#;rKg7_GJ+lx~0%;A(N&}h5OWLG1s0uq8T$BL9tk|ZM$Z#^FXvWjaMp!GUk&mZBCnMr{dmrF~mCz#!9u^;6%2gjTD0zZk7uJ8PIn}hvGnzfTn!^pE6`mS#&935atUzM2|grjFO34>)HCl%2163g74z{kodxk zp}~^*!ma*rs}MbN!%%Ah5uCEfZ#w;THKt|3G7lVWCPv9Xg~HRapHO$E6Q5NsUpm;` zt-aR#A%uJ({M5bg;A!1kCjzs{WuQpP6oI(mO@ei1;g57QiExbX45%^OQUYcG7I%wiV(F@!vbf=IywjH%jtif1Z-e~IB+;j(F5zSAICW`yfT%c! z7Gxwp*hX|3<$Ha8pP``+X6<(z%*w~`YS%u*qxHp6T!Ala{j2Ul{4l=#6SOBER~uE? z4({YHzB==^j8*p5Qu%Hd&aKKQ0QfB55#7Sazxf$oKk?*0ag8TUTf4$L&bY=gZfMoT zlhz5S(P}+(&q6d^ma0<@aSdIhqrh;%p+2U*9Q23IM6lc`JJ0rkZF_`%(kUwzfMqcn z9Xn9f&$`1S@Qh<1@Ebq0cfCcZLn(TV@UnFZe_i7C-G#${Ty)F&m=+>^k`KhPo-=_1 zoKYOa8(UJBt^=Kv!b&>cTK{5zb*H~^Lu>p@4og*;M?kOsI=H5bBaPU%e7px|;tk$K zwxf~l2H|hp2+cZPGu$mMF`fWKKCD2I9l|ucyArqkm^rSy<+-7#pU<*;WTH9)p8AVX zX4NTVbm0zw@imHDH*E%3AnFLMZ0Vzc;-bV>ZsB!ZduYpR?O(WCL|Ita&2`!J@XmV| zA5vnijr4{ra@2YT0Hrx@s=MMB&E_G$2|Z<@OAv;2XE7Y|_%4lY zzv_R&OFH};egWY-mrh*0d~X+zz3>)Kzc?ZbtGSvUDyxj*Vm!oC`4FACjm0bwt}kiY zPU2BWWv#9mNv)661sy@ngZj!}qVXdnWLO8$H{<0SM&3W zTgnjqB))x1_{V2?nKH|T!td$Vgn4kI7+Veo*A;v2S$T%Pa=BKT@Ve5%&-VXH(Z!5$ z_0_29Sj1fFpNKql-9N<8AhC5eSgq8xk=STy&@zz(g$Y$s{Zm=Dq1%b8U`YJdu?x%n zVQ$ATjx)9`Y$1Dsgzsm0Mv=z2fR5m7Ld=FbxJ`m8vJ%5BvaC$OvM^5sC0`Fd93VV! z@b9AWwEE}%@D@iFjiCW4TrF@YO*BZEBL|vwQ2W#RER)&MG~p=i7UcjhSm&Qlu ziGP+XQC|0oiL3k6p3Kl-c+0EZ@p^(Yp03@EySn&>H<DtFD=rps8EjB zKZ(ETgymI{^>9ea=3tZdE8gjtsJ|9doGP_zl7@#MbPXS$g)1J-nb!PUdi`Cd*Ki0P zAW|h8fsMGGPx3N7X@q4$;p;E`b?O9z*y^K96DE<-dfS%{0=i~sq+0yGdp!EW6Nw+a zGE>DsQhs-Jj&-a-$9}{7TQYI79qKXwHB%67#Y#B{R+dONXW&&l>&#GtG6*k#hWwbf zF0uI;OjZ5cujE+-LMj&;?D#Nh2Ie7N2P28W#n&FKc|#qJ@-Y(njmXG>80H1i?bEEr zH=X&z{pFGQ^UCZyW|Tj2M#FE|I&s0z&MA9sx^Y?8FU>r*pbTfF3rlA>AAzs#c=|pJ zISig#VITMCBW2|pYnEYrCe7KXC3EkCcSo18e8t5+auElAdX|EOTtuJqD5ts4ntEGV z%E8wkIqmGS?|}!FHAjpq3p;!oP5j!9;-Q|;LLkmIt<1G7)}L`Lhi%4L8)vPZC9>a* zOa(xHyc`Y;T^&q16PAHMm)`!h)}z^y4bIH z9#X}2FucVxAN3jGtINxy>J8$npYf!zEG{+Yl>BkK0{;G{KT=^=~eKzziD|253kNuY#QD@@8sIz zRD3PtGGw%bagZQ9>8A^=@Q5Ekn!(z=*@o$a-SSn2^t;|`A`OPL_yTTll8I4_i@){P zo6ge}LSEe|UDG63uR?JrzG5#tVF6?tK)r&Lf4jb8pWnBUbqK{sdG<`k*!vzK?A zK^^FLwuO67e1C{5oCeD_ zuAkSn70NRj8;qiSaH2{6vYl4FN4~4FCh(!3@nSfmb5R!6fugG=IHcaXuy1FzpoeIC z5W4MXG+(_k56f%)btnn)f9xQ0+FqNK6Q*?-xE)~2Dt|@~1kXM-tk%VlT;&P-QPZ_8 zM?QNsxndlhSv36Hz4?3Zcm3hQs_*7wKUT+b#*c1npTnPF#`C$+zV-)|7mTkHp5gLc zHTv|o|3smu?D`Yyn0oEUr^aYFwYOF8=AjFpa&L9#8C3Q^ZCoPHO6$~#@wr-^NI$QX z8C)ILDLZBQDzh{+Apb}u|LELSB4@e+#LVrFvs%k!Mo?h{hO2r_n=K_ES1DI%Bks~T ze4byQp4#poXlQ`oNcJcjki|y7O2^VkeTk^zZROg5#7ZqAb(A#R&e|F1bTEBk?kN?1 zj1R);Xx|vZ*Hlt6;iYo@DwSlApDnb5v-7kGG&nr=Tz|zr*|U+8Uw&a4a;jMmHny7I5pw@)RT(omZu*;l%B$BLzg@2DE9xqOSloMUo|-Ryj}buTk=AISkL$Nx9HW&|N(G$8?f* zpy^Bu=mL`t9Fs?IQ6ce99<=OLX!))oz-0X^5=1H5o~=f^O;glj*MKB$Y6i2MwBZQg^( z>N6ygN^mQ#!>=d88zV zevO`{v&AY4Owd}RY2y#?+df-66^6W&$qAmTjHvBCvLx->)OD<(5keUy536%)V5>Sn zq`TmPXTvof|HB_i0jbGDeCl&R_}&Lg15nx%5slkiqh0@drAzhci%O{mVYYPr;r-91 zezNzLw&ozU^a*7nYI@%)ts`T?!&UC|!^xl>D9YO>=2Poc=wi1j{0e1teuMDq zQ-fQf022@MZQ~MowpS-UHvrsQ8og@&qF!wP`1HzTnrdtiP+JjA=>sf%iAez5Uy8v= zIdbXBU-PcCsC1UkYr6lgtfKV)clVDmG(cb*Msw*cO$gt zUVb%I%PMcHghj5Hs-^4_m?8ptF!s5H*TuK#@fjm0gh?6d1N)9heP;r@H>O;=s@+jQzFC#NNO`NKG{XLAO{-e z7fUR%MfH`ucmR^8nJ`ULKMxJ^5%^s_D7Gmr6{=Zzn~5g-Mr#wyjYU%%L${?tTut`7 zHT2d-Bh#y8Y9h~w~0q~XtQ=BG^32jHcDdtq($LY{#a2`r z>`1TlG)PSd2|rtXE&E#csa~%;R*F^Rs@@=253oq6l97LE7-8;B`m)quM~7&WnK$|5 zX}&xfzxv^b?k4?S2AjpVvrhHipryCn>-J?Y>C3$ueCx!NWmEq7T;;lDWc)$9VPpc* zSTg0T(8H5}YwI-EsJUSsOXCt~C{W5E<#16EiOY{6ITXkA5T?fv8DuAXo5_&tfXYpq zUk9rn`N}hk+50xpe#n;WSPoHyveV)t_hn%sn(AI$WpZB@Z>6vzv=k&ylWum>~p;TMm4ZQQnd5E;%#iYo}h0-gxMO z=pVj}kgqcq*eE2t9bfLYHn`TY-{BPvz4b#}@X&h#3`H(ZagY~W1!rftCV!QCiF#Q) zamt6pz; z0w5{=Kw0kESu{b^56d+xq_4m8Y3_vJvt<(FTczWn9?PTOs>WjZd;OnBg-<>`k% zJ1Z?Y}){hg;e@d4WkQU!f{Dqd!+vS6(TSeHwDA+Do~D>i*X0x~CL*sm1X(7iG2H+D5PQ zsc!ss@5$e0%d-di@><_Br#;9Pn!SI%EPcx5N1DvZ0G6p)&8+ z=2^WBPoHk(@?l@@(mfmhiGaUGEMSGK&xx9<`&B7Zh8au_5_MZzmE{<+kXGl&#@WF?q%{JX62O(ysL-s!~J$>J&<~@#PrMvIAGhKG+W$Dy!e<$6#bZOdS zuf5Ve_urS6-g8fS?VH}5j?7CeHq3juEPr^V?MJcU++xoX`qAlKQJc)a{XSCuGPvv zH?wS! zV3vBDKW+3jck8;v=WS%2y0fZT`LO2TYcnNXP3_3pC!?uRf|H%Mbb6#Nwy5bkzlF|z z-;MsAmyJQbwYPKTyHma1-8!~fvmYIczFlSISnhCk%AzT6{UBBhU8i7d9hxT6;}d8Q z(nNd9HCZ6884k9TBF}KJk4$DMHuTB}az9e)eoRWAg+5;;ZQIoj~@lIZevuZfoKy8BktgK=I-;b8H% zjqZ6=He(3Xgye+y#*)`mcc~hyoqoEz43(A2UM`g9pO)%JX0Na01$M~wCYq76y-2wK zu@E=w4~7i&9Z5%F@tFEBsb_k+=1wqqi!JfVGktRA|#F zCkM$7(_Xh>y7Qm>UuPDUekS|1$%VQZ(Uo^>lvYh3{~07G1>=zq(-GMj39n?7_v@2= z=U^Ppz;ImsVZ@z6PvMxpO>(y<@8^FHa|5B(X*DSC_PcJj<9EkKN3!fwU8uv_Tk^ua zt?LwJVge03B$3!~g@-7XROCYsRQ4&#EX;mj7g*b1tzpO8LP`FcRrvGc%bW{4A7+yl z-&$#ypn_S>4isKASuQ!o#lF{H=q)M2ds6%Ey42K3@2q33inL2kysB4BwL;aN3z9J< zRYOOhB#BLVhoOH-8kKkKm2y3pw^*nY^tadA+NicvYM(nKbG^Y%qiBPnF43WcGE*KY z75_LD64EW9H^;2Fag-ZeDYsl;8sRMW4H|2Wg}x#L=g ztDqrKNENy2>UF^-%#?TZAq7>o3SC}frQd{eOOui&nm5u`HbWrLqCk$c$q%Bps2wCW zvF&s!AJzA+v{v`E?7IRDb)Wde@&hT$3Ym&sY%p31m6^#%Z>FtzXjNKz`yJ`dyOyN~ zbAaH%hgRer<5ycy;3>Q8lD61lV|!DFCJNqt_wu}a;<9wdoww(=G|f%B?z&6bJqIP& zk-s`+S?}^Y?nyUXdu_Vy*4xstFtpzjs{iNF5h? zDZaJ1Mm9O(L2D{!8b&OVNP$3uf(_`i#+=Ka!neYk&Xt+=j)(9T{Ka4Nh|*T>Xsl$a zXOBW=On*B-j!8|~tggmhN`_Hek*Q>U$9&%!3}@(#=7l=}ER zu@01mrvQ8U)j8WbfjS36^jadGbr>8g9u?}jSLm-a-Sm1*T8!T0TV24{yM%qix>FvX zKm+~dGmw`>uw%RJ>YAr!+QmU2<#slJWG7>L{shV=Vj;0FXD);`460M8j%t}M}R+G*@%=(F7q&M4uyr7>Ur56k;j0HQ_%o# z*%7fnK!P6$^ppM)Iqr5WWNFFL*NaMgV(x#@!y`O`Uy-WM{`uiV&;TLXPs{4aDW zmz)x;Upz%G%nbk6)FP~-K~zpQGz}z;)~|tz$Af{6>1ffXzURD-kR%B-uqiSOylTsW z@KOhp$AJ2p$I^-w`3)2+dG&LC?QwoR9y225=GXZ?VdD++>*NX%0u6bxLRz&lrF-wa zKfk7Jh3&At@g`45n{Bp{dA>FW4v7Erx{SwGJenT7|AG9f%N6lYN8zo5(k0z7g!BxefTW6q zq)H4@igXVsh)Op|Dcz0quu;0ZgrU2;&+>Q9-ru*++57x8*EQFyHSc=ze(vXa--Uuq zZ0+8r+m^;^vKK=d z@``L4(#kns16*|_Qm|9zw0XWi*gQ~)K3Nce#?99Ge37$Tc;6s+x5aGMyu7VcorX?} z=4U~DR>^y#h4n&-vuD|=)%zv_8^jhyIMDi*gdi?Y$=5Sc>C(#R2t>t+s1?(UbC+jj z!V)|U#nMuO3bZtrx+k3|#Tl5V1@Be%ApgO7(;S%>arc?`S=QGbwl@`{W6$qjy!hJc zVZuvYQ{b;1B33~CYb7^wu%pY}nJKUJtMID;&9LsfkyQD8^ba1G<+QGkxQd@aOeGc) zF#gbRY5w=I=Pym$+64KsLKHkcM2gYf=ZlxVU0@$z`9LPaGWq@#_)0wLz1Gj!P|{?1 zv%2MK*X&o3{O0V>!5L(!_M@hQn67g}k)8T85(OT7c8uWQ8Ne zdt5sFhtbU9rIgHK^Lihjlbgdow1YulI@>j+UYm27hnywD;2cRw-PC7Cbr8M7tTx;* ziC;8%=ekt2-G-T3PlVp$WTsxN%ddp6z>WPI3lU8b?Du}g$u$jG@v1c}c^4x`j30QM zFPTVMoJ~X~VNY_u2F8VF1E7aL+n=g6>;rYpj$1obU6P*OTBuN?&X~#hqvU|WOBL9# zy3*sZ2l;h9#rs~=?dEK3r9*jd!J2e4nO{p^D1ge13)t4)#$ojNMER$mGAr)5nK{hX z*>PoAceZjunccs!%^d_wo-QIYd+T^w_=r%hKE-doxu5W{*bziIr9KdSv{ z5ve*s zMUF+Dkw3UZiv_)ATw@ww`^LRF+wMG@JTmk6b(}j$6Z9;(?{bXv z;K@}y{Y-Ywm7NvzMqfPZ-p6(Kuu%e*_5lx*#6LL1#SMg}7Tx(i(L}c(moAl25MLAF zXA^~lnI0oCp80Z+hxhsq9*I8*_v$UosU4Ffuz(p#EnmJW-*Sg(9sQzeI!Bl=oxK(0 zS(=AL&mSdJyuK^-a`2^XmYTl%eeU}qvo{^0Ir-UwiJO1u@D!;Pm>#`)fFCa{tfQk@ z{M>r2p>(OW-ch(b=0w2_R`^{xcK2;qx0wIlG@Dh)Cie4IY4&;B3Yf^9l@SY(gOXRJ zgeK+^O1jjyxF7q>z3W&qbZ(?xIYlf74aa;y2`_-SRJp}25)yXgebn!FX5nQ)X4hXp z`2#!Pzo_mRzZ?-pydQko{a9zlyfFRk%v9j=wfD&%<2H|3QV@+JS6gFYAN3$zMo(?x zo-dK{{y&@7A|BcW*!Dp4j+7cE+^nt!hPW}u>^UH z3wb>tIDWo&hh4t&DTT-iXX@Js-juR_padS-C26LP!Ut}U#H@SQ?cxXV@e3>+Y(AE@ckiNk zn4`+b3G;C}ZRQ0QfkE(BFUMpD;_&k6B}1#OM}Fmw1-(ftsxuKPk~eswb+7n1VvBsEz%Qy_(-srSm7M1{-af*HEFF$Cn;Q$U+9L-gq9dX$D{`}Mg-HUb1(8YAbo*3>xTO~(2y z+e%d!8$TIK*}bSVf*u)tHtvpDb}kYYL_tPBQmDj7PzUX|;04==CaIMcIho9Sesz5r zQad@i%*8BhZW+*n6wV#Eu~1`S;dI**hpb-9qVd$tSQ?9aQi>d5$x)H^k~-#&zaYgaO~UNC=QYup{`r?v z&$sU+t#P6t&y4S{oLCl@jcHwo>UjHAZ^i|?-^(nJ>yNe_Ss7j{l({2k?DX`DkDihM z!@MZfHfcetU?8s^_H#X#vipx(F^>{%n+o2Yx~W=Kem|_Aa)uroZy*lI%eMvfE~dHY z|9tW>fe@KO@~C#pbv@D`f%I;4nenM=+~N0n9llUSw#s?B$@Dnt+0HQkp&v5p6L!4P zm`7~x%M#d*e2b&o*G@U@yfI~YiM{^iEF)7txu=F<3XSfi+YfW|7ISr^v7_Rc24HOU z>}*mVQP=+EC&fBdVkQkF)}Arh`kx^7ED)Ge3cDHo_Jh;16$Cn)j#;C{=eQv;B3fi3=Aq)qPEo6o z^=|1W3vHQh=Whb7n+)ztOnMX6oe|c9JSLMH7D^9k6Zyqgku1TUKin zh?{w~E9qPJh>FCW-(n`8NB+KviP63$l3}O$LKO(uY>ECE`;VQ zJ$>}DmhPNNWJnB}Um9P!z@VWM1f{o}xf2cNYh0!czU(@;+;?c*EP&)ja81}m>LfY3 zc}?)%8Kn}diL!3zJ1ZL(IDu+(e;s+Z{^Hf`3*>=igMke6=)q?(T0!d+V~bKghhZMe zSptH^`rL`~P}iEbTXbm?G)u;EaRnPH1SW4do_e~POdPLgd{z8I@{X3VSh1ErD8eIo z`K-%Q|8(2%Nz{zugT#-|wjAp8LrT-vDaS^>XF;0hRGk}CB-U@ge7UfD3~ZgQ`}y6$ zKAPF;#jIc_ZM+Usu6M_=_+oTtZ^@;mQ_hP3pNM)di^km2U|vHkia*Z+;GBC{!v5XE zxZu^}0LQggog6yLA1KFSU#OuJ-@SQ=5SLghT#*G2ABra!Q6qu&2o^I4A58B?lMpBA z!EWq0v9vb*wpSI8*--^(d0#=xsrd9JCofeJck&mRF??TzRzJh} zG#?CwD6X`tg;s6~sOe4NR8Pi8cH|ZEF!$cfeNQ|Ld%t`!-!;fn938f<82`RuyQ=KF zd45Wg7KN^$vbP`tS;QaVK@#=yAkm}KS$-{Vh+M}oj6xaSYkp)*tBcQ=`AEqLeyn;< zL~rrQmb(~|VdBWpm6>WscYzy^_n|6xGd(}QG5xgBhPUw9{*$!1ff_ooF5O+L-MM~5 zX>`u(Eoq_{Gv(rk0e17570#Q>^6frHVo7*wI3*J54wc8n z68J83#Fso2$V*SW4ySBcgyB{eb!L@$!>pPUE5bR+j)tN`!c`(I+G@4(62TuDvUgUI z6n-i1`zJ<;yOcOCxAv*Hh6x;okz$={ON?3mcb*STTNlJ&sH_Te^C#yJig^6*#b3Jo zRJ4f|P0Waq5s5HcLLx^YJF+dwS^pH%m1FJFWhBsMs7o1J+-tVKB)tv`dGD{BmsEK+; zUB$Vn?>!L=`eOehQHkhk$@K|wXJ!(8vD3#YlI52qV))dKAgIm$Jt7#TZsD_-UfF~0 z!{VFsy~Ab61`)XxsXh&Q`@2Frp$!r}2{LW|L_ZC=NA<&>hmwlDewOhaZ#Xc}OY}R< zY3%d9kd=ddIZHLgWaa%|qn?=?jtvYwlxq(5@1@%v>lXE&dHH(P?B;wkxaQlDR%NXE zsw3j8*)+D*_3LZ$?cAJ|m|r9|xgh`V#-;4R$wo_$`$b&2?KrHO^)vD{vme>n)uypo z1wpc7w4c77&!qBv+_h9jm`xJT6Q{v=^_A{r$h~g-Fp>0$$b%4%`$Eq=f%Mp~v_Z~* zoxXj~xl&~Fy=qmb1}huhebG)4t|mf3kzkpXlnL+;gNLyO$r{c}AM%Vo!W~zl=@1ZV z;NjZ ze9tAiW&Uc;6&efM9eCb%2kchJZrWo|Pciuw^4Msd|LC?A5fmvD+w(e>5^458(FZs* zv9u(YR7u<^anFB^>`XsNA={?QnL2;}%FQCSCGPBu>9a#VlLvQCj{>-R>a{(R^ zzVhT7E--Lkdr+mV?x>P%4xD87&y_!lRFyW3ar9}XY}4|G$6DvNRGQqL z#u1E+03$ONZd({H2@W2Fe7uD?)% zkiPM~x`oJhpX!t9T5yf=boNx~5<5HRc#G01RKK>$61O%CT*e{A@yrzVLn3wfM`~(m~F#Ii%3hf$6y9TAYzwHK~4G&DTuI$Qcj8H{%66 z#>6`2Prrm_Wqt7!F?He3>R6`=7<%tPw^j4FYP83z8wII_iZRIU3NyZ)kUPmpvajX2 zI?PtkV7~d$l&Ro;)-^QHCojEKdckB}w^dahblVcPTau@dWw}qL!;x-64jj=A7t&H( zDcd&h{Hkf|(6t*4>53`wzMU8L^nMZHmHBhU#t^HLo#ZL~q|nX?0`7{5L!bPD`Zj3v z_XovKESBWT9;{Y8)Q~I2+AfLBV~L)o_?pQ-w0_^K<^^!9Y2?B1bjy923&&2!H$1MP zP<*kwn$AsSPyE82*HJ3eO`Go$j{c}D3yR6&yp{$G(?s)p-MzMg*qum zA%8~E>S=PA3IeZu{iL%vPX5y#&*Hv3S}lRS@$2ZBVfNStW3OgzP@B}9sj`hkX~Nc; zMLUe)8|qh*cV;K0CJjB#xAg}Mr!N>v`8}9D4V5)%ADAkbmfp=VHVFY2uYG9P$=`YV zv?yS0y>W+^k6L~(O#XuDQ?oA*pCz4Imt$JD^}wUjxc7>#90oq6uxfjw7(uFay3yqG zcpRvo%AJ*jcc1ngiW{YqoktDMPOZ;JRcBQ^w=RaArr!vu2wi zKV?LC%2L9qxjmS&Su?M6MS<$kyF1m`VS;P#nddhx`6rS-h$rqmi4v^LFD#kaE6M83 zi?n`4zbPIkZLoplc5+$0vU6H&t<$NV+RG^s%h|rl-Pm_FJr>3F`E}ZrwZFd2-&|Yv zQ3UqAY&@E6hDYYXnq7O)!usva@zt#Sz~1@xFV4#z4cl;opq}#cvcs2s)lV0N-|PkJe;!lRrm8;6CT#QO)F$V`i(}L=jRrNa0*RM%6Wf1 z@-&PtwF(OA5+~m96k$t8M}$O=?dk^ePctIh-(9*Za@Dbqmn%zz766&5?`Jkc89J(4 zdogU8_I>{TgYNQuAHuiG3eAb5MV-x8vNkUQWWR-Tgz}aBf;wWJ+ZTPq>EL}AZe_6h z63Zbt@wpmnxv{*U1mD+r(T1p_Y(o5Kxtm1kf@=NMki1VKKCs@ZfsyWra^{QyO(2*P*i7;t3c^Kzs zy|KiD3EU=4h=nZmKNZ|pe7UC~m@zyvcla1L?1nEj`l8CC=3Cv+pwdRg?Mw-#33k02 z!F-P-l1j;?0H-?vGxNw5dk5>XNsWyaNspSFh}IV^l%Mys6cjQ&XqeoT2dSOT`-*LO zn1cm7xOY|@6gC@-3=JgKYfh>Q`I8q%UHd-#;b9CC)g66)E8ns2@v0DybKu9)A|vRA zro2}gus57k${4642QGy(svi{e*pV(-$5ESly*Y1{Y)ZK1Vm_I5)|-4=+%WVu<>JfX zN7?c@zpE2TC*37e4gD7)QIbzrvE{lBu)vHI7m_8zFLbXfEg(Y=1?E)TUt{};Fn?iN z=(AJDN#;pT=yfEKXiZFD&U1r3n9%V8kqJ>IkuY5%+elsJvO>g*S6d+786ofF2cIo; zHDSfn=DVgRr7K>%JmY~HL>~3YH_{HMw@3=Vo7rpC-x?E|4JCA*BtEe2m^XGbx-q}8h#OQr*VQViubSRVFnV9wxo!B(iyVr`!G+2X5}zqL3`~5A z0weO}H+%6G*Q@Fd)!tA)S#H0nQ<IOTnSGwiCRs=8PK&$$;SF9{^wee}PWm)G2*Olbvl5O;Eik{L z4{oLif36fbnoK(&`MHCtarL-2|7*)5WzKGg;j{cSIMyY7jM zoZ#gzyB^*K=ic^t9`RqwI1M-O?Q-A&kX{MyA~{M|NIOqqH@%#op^K~ZN&UfKko;k~ z6YzdEdSW8i87aAooNt4Cre~c_{Rq4zQ|;x+d!a1D@C0mG2{(*?6(=4WQ_qkL0Yi70 z>C-YLd!fs@&x;<*0daJm@|37x24s6P!6EFsq{pZoHoia3Qb+fT*x{zHx|iN!cz1PS z@5S_1%zY>7DMY*$u|t1w#Wd$Bk**_kpMH^Np9ZY}N%AF*huw>Btfb8*&tnFvf{VBKG5c$11E$Bh*ClAuwmd`EwuU5k*?eSrwa($G zLSkXAv*H1#tMGUmNAQRDwVgQLF(u`5syIt+z<%Hf8Ex_)m{`fq3uNhBM~eZ2LQzps zXN2JVxLxkWAUkZ>+h9xH!R0<3(VBhAcH-DlSHPynOqQtb;{7KV!WE_G!kE@&?q#?ufYCZ#3ejQ>X01E<9J=pW1J{WUL{%(<9JQId&CA-7m8wky`Jh zAS7$rAj|v9BXFA{wn?fQJC*KJ`4e!yQp+cQlW1v+Z=P4*w)7jm4W-S{A^S0gHC`6* z&8T8n(p;#_w#rJ1r@hCH=WLRFE)65nU88N%62}_ApJvJCQO#w_> zFB~Od3o}GVmKzddWCBk8(`k13^szOHr-s|$IPRP2Ns`9l3YWVrx8dWjuP=)**w}=7 ztTxP4^7yO0*J;dRwpof&WOHk0FnL1Coe2b9Qu^mk~YMOSPlz5RFA z(@tyC2-gUh6KcE!)zhVgWe0pcPln$rt}R2e&Dg5mvD{j`5> zibayhcLh2>8|~geLm2IcxXbY;SkEh{`f01wyd@HYnOL6a zAr&IiTIQMX2>#&3)fw$eMOQ=7Owm%h0?7z*Y}iI024 zUyj&&B~jP8R$1(A_pIKnlo1$d$cKj0!lT4?vxpU(Aj8C8d0@!4Q06aPc;*|8B4oaw z4RFs=&3_1a(p{=Gt%7Cy@tSa@c16ahgtf7-8`w`(Vn}N`d*^p^LmIgCd$B{Vo4Y6| z9FdVh%(GM!Z4jS_q0-;OKMSp_2azvm{loHshY@~{uY-apAbVPl8({*p#5QpCUi25I z4vx4C2d@SCwa>6#l`#`fI}Z#BZ&U9qhEGrTjDYJ)_{@H6b;dmssUM3pPB6F8G)B2y z*r^pus6C*V6fOC1n0_(j%wVR|y`(P%pS|*1loA?#8OhZ~?P%M{>`#@y@7bEZKpNn& zmj0QkBnnzgT}$FNLVd2BOiRRm$hu<1X{P1mg&=iatiQ=(`8V+ofl<8uXtXXi1R8sB zhTjAkAQZctr*2YVzTOQQ%FRxB74S;qh)V^HiAU{Y<1vKGU+;yjG|-X2jw*PpF(l9{ z;*uqzsUdj{A%S<;g?_W{o?ocN$cCA*!t3?8y%Gh|8FDt-zJlF3pBz6B{owfwv17F z@~awg5MTmnu}bxJ@i@viP4+pdn@zwEuwGqk=goNyn0zK%nCze>e%d_`%!2mgB;+s^ zOeQmFs7b?;jeZYe+U*xi$&&VH2;0?9 z7S^h{!I2%jmjt>sZWV~@vez?HFxN|6dk6RbGUfkc*iVAtRLC5ebZikEV+tHoNHxRJ z5BO>0#ddkM#^u%Qjd$(&dVU>1yM%WSf@6s;yP7W5JeFap2`=?c_E8pZ?Oc2kIT<#P2kU%e2dXlXIy!*l$WB7C@nV^#| z6_1fmu$sGa3NW}5yLeZdM_Bf&EG7PzEOLX??*C%G6Zm3ybo=qC*n&9EAWiI$TDtHj zCpf^XpzC4AuD_hC2o_fqZq5#;X0LC@@`@mr&CuQX0;cDKaamTf3$#^U{u->_ibBE7 zmklQ~NwGqvDQ@&&ykHkbpZ-t>@a>X&UqeJ|oF41?Ke$n8e{4m7K&xwcAPHeI`1i8h-O-IUoG6Ek)>q=UK--##g$H9*Ph!)X#1g!=3jjf zN{%EEGgqc1+dw-&hNaVB$gEz!%dw_w=kqyIUu1D5Fm=i|xZ`_sk(W-f>Q*Fn!vR+9ZIPhMe6RtOeOmq^NSMRw+UBI+z)nUj~6;h~yNu+tM1X=nf3^EEt= z)fQZ8qi{`yE2pGKuMY>5r|3n29T~+HSN;q?+FevnRp3j5YC;-Zsa}qg$H7xsaZERZ z6&KreNxt1GCDD6btn}q5#>M!|H$CEG8E<=~+Wbj@p(EGHw|#O$QK^^aM34P=zNh0b zd%p;SSSFpa1UiH{{)p( zE7vdwbx`p=&-P6uk==!tcd#(j5nrnE^O*_vCh-e4p3Wa$?f5DP7}pL%7Cg5q^(Ng{ zk_FPxW|w~u38{0XxV`YWK1g*)QfKm5O%LXvC5?`|R!~K-j29%j9mlz3^h^6%+ zKgs^TS@w5miYEr=!EuJpt!%?jq~f*W&B;_4;vVO-}SNp95D_e2g`_!Gjo1W#G11)y?Az>-*le; za5j=d?V|y7f~lNmRnq&q+e-c=HiS{K|yvADL>rrU?GgVU4>_(~(21SczAZ{Nv##I{i+*tNaS5GbfF4@)r|*&oFaCsn-<(HfDX;(8jfk+lIE! z)yVrlX)?x;x+h>Ye}eVN4#isTPO2Zn+&a`uUcgw7C#;waXVPd%6|UB_>;iv2Qf7?N zPi)4dA})jprVc|e5H;4B^U>-=8jnz^Wf~$QGO$^imRW$Flh5|sR5b^Wp`<}TJd+hu z_H`3zUv`If7PHqA7I6mX`A?>oFFek=Ozq3>jB`gdFrl$i(ZrwcavN%M#}Rz_|D?^^ z$aX{gae2_)R&?wSbP_@UPZh_w^4_-)G^pwO#g7@nZo<>uAO&0VV;Q&Jw0mv3YgT7$HGcv=i{0#GjS#GvA%d8Ph^E=lKNh@`P!lg z{8{+-;7uUHvJSIktPkh#w7KCYS{e>OXbD-u6>>w&o9*Dm+VC4z@sr;@TjWx(-eSI5 zRUS&cnn*S12m9Mvk7B#==)?W|4DdZZ;a+Yk>;dhI;x&cq1%;d};M|?2Qd)YjV7wg4 zw>>=o9neeU9F|PbmikY?5(PK=NX`v{-fbSmuhd|s9d_)8U!s}|wO$pIx=ncc$=#xP z7nKNtzMl!zTwmp~GSkrZ3t{Fdrv~A?2GM}&PM1Eamna1!kkvazNy?Rof#~ZI{?)R=_dv-WG3;BLb!l*%3&Gt$V#qar3k%tv z!p(t#L=vjedpCetz1Z{DhOGmxmqmaIh#3Heg=fV+6ydC=aP+(%4vDbO;@m~G??v@t zu9o-5JY412#Z0>0&9W}RK1<@#=_kHvrM1dvx~OYXtCx<_V4}S&$7=!X+=+-x_!G(iqHxxs zWgCkFBSX%*&Uy=wy#cW7c)^Do0K8N-P{lvmEwGa7I!4?D>LNQFRS-$H#P^dK&mqaC zGYvxuR1=sM*nxD-VpsjkMZyrJ!C)ZKydi6#ix6I@>GLkaWyLoy`5a(DwtIPGdQ&;E zQkl?Q#iG4W?Yl?4rggv>Z%e288pnI}MJ_?ovw3=lzSD0C=WI!p%^Tty@jU&0z7hWn zyHIQI&>3L5%g=%5X%hj6BvNVNCoh&dW2%%}E&z8v%s0L2G%18_uJX*;J(*qD@i_()Qtj0NBY%OQleACxB*h=jn52N=rawTnoq*(-GL=DWh+DX1`? z_us_Dxz%@DvI~C$8G>oYeNiEt38f_qBr;h~^Yt<}iksw(od)i&WkhL~r4a@;?Z*_4 z8;a@6H@8L{!X$hTQ)9XD{^`NhmBE|>{b(})_1mE!AYwu>w zSfV5zbnnTS=|-#L#j1yo$IboP@u}X*2HrThxr6?UZAn=Y%wATv(^xlg$82{=$X80l z26N@Eg%@j{mWtg3g4%Mcn)#>Usokx>`;jzzxO_MtS3f=@h7tnb(&zmniCYC2ROhnQ z{X^H#&f-EE!weJbZ?PrvV(AxtJK7DLE_cFZX?(fjd!5~r1y7Nqk00@K0Mm`%1I=El zlb!w>j27!&U>@gm}{%9f=>y5gu=` zn>beAY64Tm@^6+aCkApk`Y=zgp)=M*SO&9Qx1-6wb~+f>Xzs}0gVDIvZDjVKg?{$* z!M9uHW^8JZb84g42r7KHF2k7@wDxXoCx8kYwOH|4lAWbDXhegaFGl1=|K{Bqd1 zTciQuCOHD*=W|Pir62wpdx{-I)txx*GPUKnC6Y7%5C7xk%g=jU|B{3s;H!Uv2UvaA>~&);HgC9zcumZv~b#M-d5 zB=J)sF&dPc&{BXm(GN!%FiFtAW0awnSQfMR*T;JS&ay~DRl{~6K~TwQ;ZoWRparFj zSvI6fe1+dCcf%ru+jIw%ch zgV<&`GgGW({rO076)j%3pEfWHL~JW43+5Q|0(OC zWbyLAA-`dnw6IT^*kEcVg9DYsrU5T{qgzNbQd~<)VHGQ8h{RL&Rdg8`G6$s4ZPzB7 za^m&xui!$`2>)c)nVQKHKR6hL1p*OYdZ(c>Y1$ZFzx42$wfbAClsNhO;h`WiOwHYd z6!Z_uh65xm$cW8g4}YuK=zIT+QnMp*C-`xE<}MnC6u`1qjGFRi<_kwKI{hjHGXXlB zTRE*c?SsPqDLeoEF+}{^d(2+<`6c=J`P5|h?t^@OTJ>L(-t3Y}&{&!EVWn0p%O2%w zRcf#{N1I_g#JcT$GM%QL*Q=kWs#5Z=ek}YA`)d4of8RB6x04x61w_DZ3FGdEqZfYM z(h`$yCX}%G!EC8YwrX}y#ZoQJ;VhtQXmBcSa)x{pxA`+Jg+m|4IUcO4uZTeVd2_}w{0vt0fzpEGamc#PEz zhDgpJli;GeT>a>Mf@5K`U2j0D<5L_Ji>R^3qVZP!eV;*=Y~dyslVg+ngdp(d3UGu1 z=|ndK1SP&4xR*A!<=|VlSFVgxPB;D|LQb$- zeLM}6fmN)TvqbY8LO!a`DlYDnE5mUOj^oTaaGNP8%IQnGK0|TMFdV2)jxix*zW)@U z0WO2*f!Q+vVZ+~ce-VM%34fzeg55)L;M!t!pi_ESV#dGhVFE}r@ff|r?TXr4Lv1hJ zdZkt}hBRe*W`vsyuw%J}F*nE6O?Jg8N-1dUa;mCXA5X(kIEx<#0e_}GK!lw&2Y%k1 zfKLLok{twaB*>BLjC*!N?tDoLNjWVPEHfU2!fIKOKaq;^T;emeMv%q2li6ZM5=~G4 zpx)G=1`A&=YF+;@Kji#4<tmP z{xt{tp)2sk$aFB;FEHJHiOm;BW2ULS3O8PcWoTO*OX1y*UGLq)aQw0OUCnS>hqM&r zjDey`LWK(-o%M-7EMDrZuJlg*+aaFpFOl}&=O9zz5iTIIdS?(V2vmO^8So>C4PUGT zwfH1upR!yvA%K=_bI6auA=&MCpieVMc7crOqZd$*Y1MN^9cD>3@W^c#^p*Lcf!)>i z2&lPx)Q{h2{I+cqOV1baAxmxHh560$KFu2dh*%VF%N~!vv}=XvVBduix*f4!a0zdqa2UtgcHzPxpBb}e43NjW;Vj=#K5hf0 z063h$q&Cnrp8gcd67oIkayiE*`SSV?f@N3|JOyYhAKxZ8M<)rb_5oNc79h6i4Lh3~ zDNb9}aVf4|8vOK}Ibh0%EuiGM<2evy_Zz>G-r!4@JmQ2Y#1CKz{F~bulf_G*AXq@S zMELn(ix+#dtDxb@6U4-Mw6BMPjCG{O^g4@ zwd&X)a^&kYz7J+N7qV4WWV3f)vQ!uLG~?r9OhO8k|=oAIC- zsS<|0b2H|_@|L>jS##zDU`OOXu~%qwHZl|>=sO4+&do=I!Mk~}LkL>LptQi);W4sy z{bJwJf3;4q&Z0={q?1^5d8Qhb@nE;43|FI1RA|joJ%R>qHo!Z(0;x>UDHaMtV1dWkJ4D`@9uNV!a4dk3voiQ zfS_mU!#L0{Un0Qtn5SeYQ5aP_fjl=H{_B8Tr{6|UPHPD7-d5+pP+uD-BZBCkqa`N} zusZW-alc}mB5d#E8C~Ttb9~tXlZIN4a&Q-q*bw6Q$5d9|5XXWwTf~XuBa(l)&2O3GSS-Rna>;Za5UuZio5`~&=6m()JOe-1z}&hz9$SqVfM zc?6uN)#_x(a39;zt-L~2z5c)S6mcib6Y3x`Xp@*3AhCK`eA+1&_~X{!`Xm8lAK)!4 z?;i9Qu{5V){7$vyKDdIH1H}KV?r1*vfo7(CFE`>hP`G>KWI;lIORFt+$WVdLBM2M+ z^m8*tWq32#A0H;s-gRQxn`0@MV*_Tni+Qir{HAGGtNw5D>3;_ZB~hE;*`Gn8B!x8% zjRFxYvilQ+$?ku^rH-$G!<)H|ndi+6(oDKGr@sBorWpaP43h_Y{B=Fk9XK2nka2~= zm-wJbEA4zt@l_pzDq9EB{jCfa#s@AWR^*<<`7=NrVPWHvt$xI%>dd?~Dn8?;(>RAb zS|70n2$tK(co|pw%CG=SIF0Y$a8ep65Or2@G{yevlx+}!o=GD#`_aseVf^1%#?hZ4 z0x{a*h?#d1607o?X#Mr3jj>7y z2Nl>OIXfLHP&IxBDD|_fXMj2{Zm9WWm-Wxv;e$t^zzs|6zhv)<{`n;hH5gyi$YsJ} zEib?5A;9Pv)&i>;1mN5&pvD#i(6hYtz}NfMI}InAK(p!XNp`BmR8cb8WEEzP4@ev1}A9r;(9$-)NJ z^Y{m3R4bH}ek*8A6ZV`-n!U6R6Ub3g65 zbaKcp$Df)&BK+`(A*ZtHyH)rU#mVfC#sct38EtfnRbiIBC6da>gErHvb-gt{)9Z)l z+b4}SqUQnp4)MY@vgHU;(TZ}bmb|C=gY!Q>4FR287oxi*rZ{39s$u(Wqs#ENmo|KI zV75dM#eCR*b&qPvF(w5UA}89N=j5o1hV3(1>fM(h+3tsw4Te+0!+?auzXy%{sS`6L z{MGb(q)f7}k(Q`faqS?@J8tNJwqLHZ$@rqb`vhx?QCgZ~MsGtZ54!L!!Nhkn`sfar zk%Z>(iyvI_5h(z9nz>ayI}`gfjh^;$ARvUvXYt#lQrtE$GxO)4q%mS|r`F=VZOZDE zOS<4WvHIoeyffO6Dseh8WB+{K5LnY5P0;&4e{MES)_)I|l!ZZ7dzTO5WGS@!8i7H< zae{l8n*i-+3i<4PlDLHe&PMY$C1v-}-rM4BI!NA84`OuDe=!@#=sG=M9zT(0214O6 z4hHdWJxmdNw)od#So%Z!wvV)(6~=rX4%ehkUP&%x2A?U|$>NY9$6vQVvwy1pfiLEi zI+XKQ034#gX5x0+?ME9sLr!F!$eheDS_up3OQgW`PJQ!?@E$vs^KuyLQ-ZDH%9(nZi{^2cTpCr(w!*Pbu2sBkjhN%baOn| z9=?9^vJXbJgfFI!yZ#*Zr_Ix_f@D?5R9H?B*tw6=PzF#^h0E9TRI#bohuLKjDL98;__!?5mp4#{5aTvklwniO%Ebv zl6Gs?uXW1Z>UuqJpE~n5jgbt59l6`#1L;9@BIGo?q&(w8EyS{b@7p~qGgtLkpr4H= z0m9INaidqw7Lf>$8gg^}Z>=tT_%FcT!kXp@J6S)M8}=u**`MMZrF2Nb%ycy*%F$sm zP2y;K*H0aRsNl6nZ1<-LqTjK>;fQj2xA$|HJpG*ji5z>xeY9v$vIp|GF8RC37TSZ%Xd^_h{dx-|IfPlkqUZ>As2GH$jZ9Dw{DCYgtLUFv=q! zG!3!-4x3-z|0k=__+gQfJriv%rXrr#D>AYkVsmfcAmuputRMTn*Sj#YRyb=kdd5-(ROUEYsmmf6MM_ zkN`pV(*Hu!quAg?OJU)sk&^1dX-&X9z*(I^T!~@_=)eY@yGJ9-K0nL0F5BioR}L-7Hs(LD z1>2HUHd4~}*@b@T4mJu0azMOk(B%GmRwMOl)2a%4@i#a7L;w-O^3I=lSVM~h%+1q| z#T=Bnmu3d8FKeUcj6R<6bRZIAaBOF_23GQLbIea`)sNZxzX(OMyWseQ(+$&`$?cUL zV5n;dfyZcmV&G3W{c@-2#wV%94QR1vM`_7Rc>_~Zs=s+LfCV|R4PA5G3896yBp>`| z#aXzZZV9svFpj%REN461Y>v9=^!_=(r6!*qwQw=r#c+^gVOZZ81;cS1876cKNbSi3-e>$9b;sr|r;S0})Pmoa-)n z5S*o7W;72>3zo3pBt3|rq)hult(z8 z)^BKP{o-{WwyAd?E-qEO^;j{BhTsQkd6HDOe%4jE@Ekyay?PdDC0T+~MaqwEA^!`r z0zqgk1YqoQ-;z8PT$JZo$ z|6|JqC-|p`9HEQ($bwnhe&r0ArcDG zAYCJ^bT`r+L+9P-Ip?0U?)m@nA8Xd0+3VeVKkxJWYNvq(QS#%k_a&yOPb)N=LEK`j z-7#Ui_}_>=$R-gvG|lAZH=KXUiD8dQs}&!29&wK_q`xW9r=3_z$`g`W(zs8~`*6h8 zm@fc>Ho)U5AX8AKG%*gJOwVE?Zlmw2YaE++KRZAg=0546)leQrWMZXoiVxez^qhTE zZ-6EwY{m6D@>WpwFqa2=Xh<+;#_~rMl?jw)^;0C2&T=nqIXyqrs6FjZ%8%<`R01{- zC(?!b-YT_uLtPe8`q@WrieAmatYPU*==Gs0&C?GyPyVG-!`YrWU&9~!XT;{Ah#*T< zulw>`pXC#GU4CB5d4Rlr^B!oxskAu`!p+1`iRz__%fJ;g?I*raju>+>F;2fvW=_q{ zD6R5myNYtfaSCA3NJ&GI>@Q-5O7emfh`8E0!K2p!@pvhfp(JpTO&2GUiw!?{hu;CF zuy_z*JUg>t6wKUCW&Y>|L4^J@g`dhVnvVx0#c+O__HiUKw*b7t=~Umyos?%tksWDV zp87@+mtjJtQ!~zMRJdr%vz1WKz>{ALP|TnuWcnOnXex72z zk5$EwM~)`@y~j+6$}9bUG@bwinsO&Skn6kPiw#7hTJtHaeEu$-5pxh{Ppy9VdFDf!r5Zifw&;HH7(CwS!sW?Z?OMTqOhP%fph&>moM&@w|N zKpXa@Qnw9Xd9Y&NYEslW!Me(rMAz9~v;_16!e9ds{H|~Kjhx?1T6P9!ZC(9a&G>xx zJ2~iA<@m;XhU|rta}#dq#*;%I75#+B|It>EaNCa~)ha~$3EvLsai@ZdQW3f|H zyi!^p=dp)2ol5z&!xN;z?IZvD4I7~bq80RDw*^0^<57+LexDn(z>=RzvOYR>{PUgC zRu3_$w)d(M*nl}+fYSahD~e!!b;`+z!Qwl$vIE-K;1~D!P`64(2-~I@-$q`4z{BQs z&V#y6dGM1Hf(53cjA-=DCpCf1hU?8C%zpFbG^ZT(kfR}u*o%G%Jy7!drKFoX#=L|c z&_|6A0qRZMxRfHe*uHs=q8C}-nKD2R&Y7f1?*db4=s!qSaJ*3GMXq%N58sOP&7g4l z{b}hsp_t^u^^K?cQG&?YbeS{zM^S38n>S~YAjrr3FC2#B1la9?ZCQclFz4%QT=LSHW{0X6@OLrpB z$@@6u6Xq%6$;pd$zeCxlR{ObyPH;D(ZkMBmV;kV)tq8A7f=sVW`InIrD20LhbAL8# z@EU;~#S-I2hbXy1jXfHp9h+P-VAS%>G-G_oV{fu?;&K~#=c#LK+PVRYi$m<>O^@if z8S`sd8!-T_Uss1`3qG1!%&}c&3Do<+snfSsW$(Q_QA<6BFV?kt8{06(%^J7Pj3kAnX zGH6f8=u&<+2`8_fSKE8mi*@c$FTO*TvWE?TJK-Vbt@u`m-`SDw$T7Z0W5iZd@pa`2 zXYMbZ0cYK3byOcU>JG4JZb}Lj5$Vrwi7&mPUJeQKS~0n#{&)sG2WCX;)6=^?8c>75 zpNCO#t9F7tt*Wek-=PkWs|9>(?$3a{=ocWOTKTv={NmJIhn_YdmVhrDvw@WO4wGCs z2=;A0*AUcoWdR4`2dLvA#dw|?j2a}g=4KA^C`3)IM1e~OB2iWW@E@QzZj=sHq1=t+ix|nttO+NQT*m z3mArc#@~z1mwnl#=f0 zLqtCU=CPOeCf0i+Rs3Pb`VHU1>ODZJ<8;1~G|d)mwqg=9uIs8R0!Xo*4EVxvm;ti& z3hWSL zthx8hd_%@y=gLVlzcf7B(MLpwn(DULM^tnT!bw8hRN(ja= ze*KN1oXbe$^ZCAQKR{g4nWsW-es=0}>zan!c8E*d(pmxyQ4#mjTzY(Kr@9{!2s@8b zAvwpm`3yp=OK*H&iB!0gx@ucjB@CXi5FJ$$4{~@^FJ2NOQPU;y5m}60WM48J=f`q~ z5Z;_X!{^W?m1%w5wz9>MrqfLbaawu5Ri46`(TS$@xtTee;UMlo@gj^^_mvszjs7T-U&{A{JrUzbQocQwZU zqSkyft~hA~QTt`rA|t8%g@yU%X!O=6){9EcbcRIIf zF?&EXT_g}aW+r{QDG5_^^2DKKqg@<;-1Si{OVpU+T2!}kvd1!6zG+;b7c;NW z6mtALvTp=6XMg1CgX~mzX^o{D=I}Qt`adt9y9ev9D;`cykG9aluLD?`-|2WAv~Q#X zQ6qrkp_-wqY?v?E!WZ;wNg5#r@L2wW6PRYB?igd?gjXx{&vN{(X)=zB%yR$eIfPj& z4P!4#9CMl;L*zOY+>YF%mDL+}!`#?8JK4o0RI9k-M%PLy2#R_M_K_=Z3oMt4Qrr`@ zymKpx&%L6Yzx}&=S-2-W?{1_vKWe0Fib`ze-gFTEo75jsETjE3TGuaEeqI+U-q@G$-*q~D_ixsyORNj5Tya=?O<-Yg; zz2K(b6hn}?>njH8Z9f!FjJn7#)QA)nF`l?%3P#A7Ax>Y;1dBT}ilh~{}5+Rp+<Eb`(0rZ=2#`DGSW4&KGIy8lIkZtHS)k8EaZb4TUm z;#_QY>Z_%mOVLhhSbs-S*$zj&B|EmQk_nslN-PUL@A`8N&hc~0wlTNo^+S)ubGmCw zD%dIdWhREjlh;^C`kG-H6Jv%Abj!Z#lkU0kj zOWFihJn zb+XdTVj?`lmo=w93h)y_FwO!q@5V>Y;!;LbidjaA_en)24bpobLrN+br)m8(RKU$5 zpm}cBJ>*G1^HEl&_kyS3)QeAvs=)eKl3l@BQ`n8mcEvVcEkfY zE%Fulp!U0cR$>Rulxo+VVT0_PC6`M(ztc`ZbKX~a0zG%n_cNR;SK@9D-KnXjko&BB zRXJf>VBvA;UF-T;8M%5Zq=(NnpWpq5{1)UT2QTUAE#wbe?3p4aH>`?_J8_ z-vj!pHF_=a7D)>$U0L{)F6SbIO3D3&2W2bowFb@oXkmmovKCXvh2*T?zO`)?7 z5>6?WO}nyvrRYl50+Lz_6W^TCfc7n3eD$+Q>+^OxmK8?OMtc`KAp1UCKOl@Y`FhCOB&Y8zmX5qTf@@T<95zvqqA;^ zO$itCA?L+-l6V+keZ%$!@d>1IZ5~5%XEott95`x(bf12-q!XDqdxI_WQ(~!Ls@Kx& z+OzO7s5mz^2&9Eu;QVWZzb2b=i~h^K%kJ$T3Vju)VQ8tZnM(b<1x5YxX<(%1?65ny zbS>K}z-@W(T`KdGoUI8M?dDq6Kvq#)s)8H|6>(Vy{I&w%I``In}p zJ;dXeS!pl<#R=bztZy3{%mkw0NZy{H^&v=fF0uHbvqxN07I6rM z=H>DMV67TykEsQNDLv^`YZT7uV9 zt~3WMN9vTZXOVEzqM)!Oofdr^_> zNAhPAHVm|%=lqoP&%@3X>csIDVr7Alh;Elwvf|TCeD^a55V(%_IZX2si`!N*OY^?K zD{<)A9}CbN;-wMJB;?SKMxkp?d8n-F9>JM6Xy(SAAPpVugCk|Pmvqt z`hcdX-g2xoN{WnYS@dUiAkjD-No>>7dwKkEj5!!4_i1gd=>=7G6t?MEILlub@ zMj?yp{fp}J=GfY?%ccB@ff*OVtt5(0Jp-lf+4%2~KBmTZXc^a>Oxaq71@OBnfICiQ z%46%>odfOd`Nxbe%4d=Nn}i4r{e#}|ppq#>+S)_i+NmytRFqr%a53h6%|F=nhM#XS zSzZ6XYYUgpOA{8Jp4Q-l-LmR5{z=Z-`+mamN&dZb2>Ce6F0KyT6)=e&0n}3&fza{- z@6~>}6AA2uIaS=ugkMN$qeb7c<^*#b=(s#>yEQL zm;pR+rm+}U4q}1kyfRK@iwl5{E%RjB7Os7(Rw^0bc#e|B5_}IP?;33XmpHaJgpg=u zx=P%9K=4~xm3Jx?>b6yIQaU_R!;*r9nqh`Ma}18ShuGY^D2-*gf9+L#KY^8 zZKbrl;5}OBzE(|&n(RzRU&N!ukHok_<`mVH!>cAP6NdPrW`Hy1#S{Q^Q#kYZX=rjL zAqQ96?jh*EdLj-%kbfL~>$#(n;Bz+GS}=zjCjuYX_cq1rMc!VY?(FfaW zF8Kf^8iib3t=eWoko&I1`f7bdQL(5_)LAh_k_rZ?dQJKFy1MYU;>+r3v4X z42G5rN71g74@ zkw8Eo4|Z+b)cW!tqa)JkxEXAmy5 zNViQj1UnvYz7FpHnou}|0N$yx3wU>(W}U|$B`TSJ3AEzb$5WffzhZHxb-qwYo2m!P z^|+kL#a*4t!K)h)NYBACOqJw~))be_JE~1vs?2V&t@2Lz2}l8Re+f+g1jo0AHK9p& zo!!q3d&>($97?m*F2VuJ^~gPQ`~CBkihH2)sMS_%^~}*s!=1<=wdAez-<+VDJ4OOw zb568{4v%UhXjq4w*}uS-UtY{trD;f!CBK7_V{waXo1ZSM)&Fq)xW{PH6yRm1;N|1w z!=j+f<0mpN+|3w5dC5wbT9 z5d){%H*v$eC5SWse%345zCEN7vGi4TCXN)rO%A?xc}PuXP#tK_EXl!>EGrn~)w(gJ zZCho@GhVt8y-sy@(7|rHVBIviYO&i;JG!6`YePvMPN?VGR+=~sg{QQGAnU{8An!*T zjN`&XW~8Yb|C}Re;L}4nQ4cUbrc{WulDRd`3TQPxRYt_>FSBlsSx0GSVY0mJgHGbm z!cNMfQWp0BN`?}#6wrqMZzLni4<$C>_j;qS`}kJfi9>og^IPFVnzIB~{=|n>#6x@M zQ(mNMaSY}GQ`5^bwy_~{hp^FeFGR9Kw*9itN*Js7iF5rv-#J%PwN4!ZIw$gL{EuD; z#h69+!G`Pmym!4g*TKSPI!JTP)r_@xJya}I z5~B2o09q;o=q!(M65FrK+!k_m*K+#mp(87zHACF{!)6LMyz2FnihWB+Zcux;jb)ydo2>#~zc*Gz;J z@6W1%D1E-#{QxHGq#(|#<)s&Wmc_Msi#<5hFaudgR>VaigNUY2?*O}4K#L@kfoO-b zSMKewk1A4R6mhl~!qA*IoU~4H!r4jCR%Oc-jow%UJa?yAKQim+DQEU-*D_8xn3mWM zSwxMXhdIq_VgvK7{(Ry1;ZG*SAs;QXQ6awsR*#l8lWwodmqJYSDEvS&wedOMij10; zgwGXGZc8=oZNy7^mL-jE!t@F+fyt{>)MZ;UO_V3kAM)zB9YneLoPI)3dnDh?t9{qX z+WOcreEv9WJ1N%0jNT@L=9Urvc$Hb$ghFnzCs;Y&`mFTB*D(7)EuWDT>uv$529H#H zS0+MY9w|3mZ@}tR4^*i#&%eZw85s^VJK^-oU6;km z52BIXBuRJ_;%B4l>w`JgX`H9396WWjS`oq&9~gdmSn;ekB=s_5huvR&H2ZztYZ?i> z{YXH#aDoy4vr15=m}Q+xy*$Kecuv%UX48HtLa;hCNmQljb{AkR_L?o-+f9?rXq)3i zr#PRz_}(SK;C^69A7-?5w(!DvnV*8PdBWvaAej`^fvg}~<@V;{?+it;x;QW#8e%_m zW6``2KsboMUqLMib`!k1i1EG6W-Pr&Ak<;dJayYNFM7iWKh+Cgnc(ku?~{=Ki}xfp zxM^iV^0uYvfDk5nFy`z9^S*Ku?Zup=S+Z*lJiwHK5FkeEEiDVhC3vf&6YUhzYp5ue z_R%aj6J->VP4W0zpqkGs?~0f*2;pbEP$oj7(e60*v|m<4WBZ_z_j>m24}axNLm#Lk z4x%;`>z_sHIsw$3#`Jl=DtW2zk7{?*D^wKS#8dB|5|sNm`W+sW@|rRZMM?ZC%v2j+ zD5ePA3qZTy)K^#_2iwsGX2BjLD|!=B0shRag`V7vM=wtSb8pq@6Cm$k(ex+md^v9S zd@a+KLd~1zX zv(kXP+c=hil?$pFDe7iETxrBpN+MXrAh)Yef)(D+MJrKhN$EjTXpO3=v;f;pw(kSo z()RE84q2aKm##A{9k86%wh57e6$Tt?_4ZLI zwvkJK@8YL>I_*w_4X3~H6W1eq(ND&oExX^P8|?M~ru>Fbnfk1s?xB$5I{`*@TD-1@ zZS%E@r+Azou@G+zF7Xt>@dg$awK_EEq(v4o{3b=AQwn>0LMqULs(OI&@q;eW>XN35 z_oqNi1Yed=dRT%hiM0E2jJ%7T^oOqtsxmgf^Fn|nY4C`EC(+W5@(D%Q8mcgX2r8JG`0ksIr6~BE_|bs0wV~N}r{Rt=-nBbx4t%#_;RjV?7C5Fl&RPd3g>T#T0e{y|nrvX=-HYTAiSXM|#uz;2 za8LGkXqa*jC<9IF0Zxs^)~fALKt7J*L-%mno`r@P8WmHM$$MCH9v=2$dwYwg29HzU zIulF7p+|>b%l*Ts`?U8G=5ep{=b`K0J*490uiL0-9(TH!Hd4qnY;cqW)XC#Ll`!3n zp{ji^nul;CTRky1W^MF{>DFwxXy9 zbxzJx-WCpf8qS2?{zxin{LLt?oD`N9a!^D1EGjomE<`pLh%)B{T{ud1>7&W|&XnC4 zGA9S^fD-)O%*3jp+VstJRqnRP3ITTib9z*On({m#1fAWxR8y{q^G6j6e@JnRt?cZ2 z?kNFYsUn(r-qmCI0Dc_eLB7^t2h{TiGMEA+edcb9K~y5J#kS|;fH!(PenFSbML6*9 z{do6q|1IVOSX&=3KtUB^StU6ng|Qo@2Az&OMW9PG@MhJ_-L1&m1Gj0z7gT1ZE4aI2 z%RYd7V^-U?aTF0QwR%&@SzuCbVjeiyy!@ z*g>(5;E*gz@!d@Aw^C!6ev8Rr%GKDNdRO6Po>lkseds-NgSfd4YL)d`moeunC@KSn z-}!Orr1!RH<6O0XxZ4&qoT_A zAUqf`s-6juGwEFZRD8m7`lnp}=ZgN#NPsqyq?Y|r$p24RSWDI^j25P~C3jr&M>aa!f( z?=@?gVs6m{J)IL>r85gX@~~mfIJw%J`|rR*)KJ^sXKjx|o=ETF+K$$~i| zodYy`H;*pvp7&>U?tL8THlbls@9E^B)tgM4@Nv!LWVE}I3!fKI3sP{Vz@A^+^vSgLcyrAN&@ zOQkbmWyNP7zU($!cs#GpHy35M@VX3ruCENUZuqZ?~It+`Hj6q!ThY^y=orI^nfCN7xt6)>}vShEt*{;kP63v*X)! zN3lH}yTub`Cpv-W<4m`8FBrH76eqtnb-i^Si?Yl}1!YVO1fx>c>QX~I3*_q-+Z)fd z-MBmRUbg=VNO6zE4I7j5uu?#cZo9#Y4~d9Oe*|E=;9nfTuMI~KGm*DHqxL_4nRv5( z()P<9DH{wl3XPttDP~h!)M7~$1w0#e{dZ9XOT3+29Ds7%_R;m661>4}|& z&+#c$HQ#)ra#mmCFO1JuU48S9d=Cj$T4YPnb?T8$_+U0823AFNw#5r=oc@0JE%18b z{RyL}suIOg6lUFF59f3zjn2%()YN;!^c*)pYv+6y`X-v@S1Fc1Jmy}!rqy&2Qmu9Q zVSCEvvRjIh*5D)QgCAed&dp$SL0LvWSfh@1O{taQO8?#!6GS-F{Y*qJ9}{d-VX|?m zR;RaYC#`9E_xJ*Ps%C935rrtb`{h5q`cJ4@E#VHVwxpW4Se3VnQTcJp3&I7FT4@4# zjPS~Wrd`x(-XhNz?|b?kVx0mN+O_B(h>MN+`sS;Z{#gn&G5a?sKyYBT(J5AD`RC#& z2GOyyiIy#j?d`?mP!{>fO0h1}dN$v><*(L1*4!^b!>E>d5ssI>h`j>~|Er(DpLSl~ zmOXKMASc4{k-3&MTnTO=^|yAF>fq3yAaT}JIYy6uSX%u=CEuW$eaxqepT44I`rWl; zoI}gj#y^qB&V5}M*A`J?lVJaSU&Nj@$|RiT)iDp!V#T)RhJmWEr?_=)B^-B1*UsB^ z>%wQVn4ZEt`kE-X3-8}14Z?{ZaB;Q;j4w*<50SO+#kwssD1|#Sdy+iYSYAhRggw)Y zKhC;k)HNwG`4n(?^F1@*;M&1>`4eIgLWj9_0v)rqZFLoGJz=F4OXeEVcTeaH!khkT zlEQ97s_BYjUQuaw@$tIdr3k`cep%_NAG$C;U5&nI3#$veuwIVqx{>qVT~zVOR@Ui7 z#y3L-`#00#hFZDZV%6}2wo$drtI2szXnv#ICM*Um-04i9&))Y%1)Ok z#>z1>XgoS6Gt~idjl>HsIVcWus0_nn#>&b`i)Vs2o(Z5!IyB}29d|mU^@i)%)iSI^ zY4zM!5_W-jvB~a^LNc${{9 zuyrrFjlLxa_i*efUbDzTY?P9Ja|oE?jR|k2g~kfAd_wM~0ex|D0mN{0ml3Wh>D(kE zG6g}$AuHf-zncIk5u zrA66=cH`d)B3tMhN9<`4UDBd$v;8`L4qtfJi$u1r-|24k9@SLoy-)41!u5$KMg;F9 z2|*Qqj?%!-3j*GP0?9On7X^`5zw!K3WPGc2rqKgxm*4ey`Xo+rrq(QPnHxG@>nx~E zO?AG%;@D;Hjx2&*>5c3yP&eJ|N?|_>AogmxKTE^iH4l#UgdfE5Fu~okQ#vwZK}<+6zRo6KGKef#dC0%oKtc-u($uHbPZc(WQQlrSReo>$<|?*PV?{;diJs$86QMYxoQJfLzyfNKQdh4%g&Us4&AO$ze)lemGyO#w z>Iz^S%`%$Akj>HGZo$ig-}=qo9&QO*3Bj~GY>M42Q?rTqZ5VcAv}P0J#R*CdMKwt2 zz?)20c`SRMuMRWYSJYGTfwyvBO;)vh!U)5TGkh{=z&Lwxf83sr=s&nDB(;O^s=ELF+>cFdm=fpgbTlfbdG%!RI; z>52c&QUAT~2M(a8##%eZ7qx;=xEsjkW&O{u{)6=ZU$s!m932#ldRsBb`M;fF%YD)= zDb#%lwV40?3^?!3popKY@&BDXfCGv!{J8jvFpeJ3;QTM2|Ns5zeRy23`@F*Dp z;bGWgWZ;v>y7@f_2+t%5Kjr z<&vjat2ZJt5>YM??j1j=ikQ);YbS4aV}IQek}5#G@zCd&P%_Q8qoX&sNC=HFOtCl! z0>=SP+tWx26sb?jeV{Y!9IsOfW*M*3SOdkh`nupD7`}?6>O&R)yZ@B~@4QtN1)syIs$c8T%dCHjSKx9bMn^>p}<;t@l^?0?D7k217_#}c)96G-=n0SnIt#A+Y^cx@^8)gae& z|ChQ?$rLMPZ1zbm%*tBXcc{Wv%$n`q+T^R~M=i9t6xjv#op}MvF=}6{-+b=1$Icw* z`z~Gn6`Om9Op%=WsMdE%mpb^F@{z%4rQvhbSKjK)9(6hv!D9X4z`B+Sx56s8C7d>;NpcuJlA*)M?vMEq{#4~rS)&xXX5!^IZap1<(te}nblqPtOUJP-55hpVpVg_p1g6-t=_1^D%g zZ+=~nyjpErcrs4kBUbfdA3@{S-PggO`gK9&h?~*Qz_^#;!teU~Ao!=`f!OU|<$pcS zAhYsASweJq))*+@*yU;4vSh)3g-wLTg?jc_^)d7d0n0Cnic;7o-{5otk*~vJ$rnZg zb%cf|KZOnix-sf)DXku8*~q>O4o7L9(i!d@F)S&%HQ#F)-xr=_^LnBBL;_zJ^~ZY; zUd37QS@SQ#)1yq>S%Yl$S*6KQQKc*P&6`yS^O-HDzvA?+$`q&G?L2eBG)JW0c{~x4 z(uGcQ&`s->t|8n$f~9n^`hn!IP{5{ z#rZm3MIF}d)H`}-RgUus6)(}T()@U-@iW9vsW%pM(+>pnhJl~9p_)x1gwvCU0!=s5 z>j-JuyNn1jrAu^%0cHdxjhKsg5-5D~o%;kvXs`8n_gV=a`CwwAQ~JFB_6XAIFlF>y zYl!(RLI1;0LHs-fx;72DhwQ!#dMM|pJ4g(RB=3>E9&WS>+aS$-Da=LTLAqIFd-)Ob z%a`Hj$ogSwBsE`ImLtwd1;yTD`ID2FiXlgbi(w)$V_YET3(!WrGGu}HT!+0DhSxuAEUz-4!9a&aT$FhW>rMc0QStTVf#&- zDgw_CbUlR8pWnYztovQ)zoti*?5cQ+UxPr`RZ!+uglg`8cSKP{u-!ht^fB4D(gv^2 zFLU28IdbSH-eTYWD-V?Uu(VdDCFcXLYiwVcw-oQOuTiyr8h&8^#Qq~pPIyXWO7=Z! zS`N`qbJD18@)>N;#nJB~{ci>-7|EVGh22Jt_@Ee%pEZ{bw&w?4L0kyI=0rf8AfOGokif~ zeBui-{93x{x&?G6vaE)Jk>mM8}|_UX6jR%P*b~+XhvqKLCFeoSEx)LC?3?E zKe6S<0^8Z8cbZ?E;|zS;X&q)Lb@Sbvkrl5-@`q$*AGEx`{GEYhXHA$V``~A-%R1#1 zneeMs*jnO7!}v)~QuFMiTC7_3TD(1(J&!Yuvpyn+$j6ZZM8!lyyeYf^sRX>G?(Z5Y z-8?tO_fAG;yENCKtI%zO70{C6hW)@~E62QZ0^F3}Pd9JjLyNx`{JQDp>Gj#=9nK=w zH-a*j#RHeCgP#YQT?-ghPgaqv(09=Fk&GVQV2%-5;P*c*!Dz%C#bubK6kQ!%Ek;7NY4_4uNG5usRq#y*N z@4Ro&3x4W(awgPQ8RuNIuTySIVViBZHm=-O=%fTw##Noy<+XJ@dNq-F$W}TrsOFy2 zTWL1R1>@>y*n@qCO`NcAtCrl!krmV{5NLqGgH=|h&?GcJG;IPQc6LkVS*7x=8;oV* z66=V$IW22d-Rgk4Y@5FJVj4}^o6ReOc6N{@&Mco*yajwds%+(>zpPNZ%xDVTs}T`l z19(Y3nDO?-siHYZa&#Tq55;kBCF)3};y1qbaI`+2KlNMS|V;7uLS%2tAn0l6u+0^)pB#$6g!CW&4grnc2z_|t`SuXi0-V5B{z%BPyH{xyvx(oH(w3>n*ongVDjYBPW$G+EXL8*|S;~?codLlL+ zCvT53j*PQq5RI%`sze(4Y3xn@nK6_l$hhSi=Wz1kw&#X-$Y>}?hu+=v+U|;ONOkw& z!9!=AjTRyg#oLMV-3TD0mT8jpyfd*mMS%ptA|r@r`Gmb2*kbru$=7;Z3W^bsaRz!H zEOs~{Y?>mxW&C;5{^EpFmg4KBMZt$f{!b_Bauo9jtZhkl;6ctOtwecFa$9n-nkQM9 zK5i~yc_ORoM0;k8uXqkH=h4xcSReX~A-9T74-YQ}{`e88`Kf{f;XRk6XS33i=c#C3 z`$`#%pGQddW3LH3^L^>1o)lsM*#)YNn7Taz0xre%Uee!BZ~^b{KV~8&`TdB4IWMW2 zv>b_$wVe?O8zU>@TT;F!BqSs}c7~t16h4al*&X;FFR6)xgAErGle4okqcaPmwVg53 zJ5Ekcrnk&Y%*+hH6AbpQRt}$B7_98c{`iu=zUQNny@8#njf1JR70Lbge$uygbl@c= zy&vcwKYz^A$i?)ZBU#!1DHb3g(|rrmJI1$6|M+g8E6@F>Tymx^Miy!xO)ZVA?13@( z-o1POmgjeee`)&Xkbmo{{?D$QZ{PpD=igfX?8(D)FTvj=`eV6%e+sM@-xD6Df2=*< z6LTb~NMJi&n|_p40$v~7?+vhXoxnfTf4ttmpF^Hj-&{pN5I_+BD5&IuxRdfUIac`Q zuEm`byu(Ps(Sd_0_ZA6{>8nd7W~@ZxHxr}JxXTRN*4g+J-}!wZkg8~Z{CoQySzc_cuG>X!{~mO<~p&lpKPCMpOjL$!D&378=t(<-+#u<0>60As%yMX zV}{}V1>+G30^(xD2!DV3>^U{*qTyF^tAF48`oW`Q%m;t(@Q>$wRPbu#NwH>!al1|6@J=E8g$r{qOGmo3rv?<^1p2`#+4&e@)9j%;n#V=zkr< zzx8bY-~8U-wd2I_FiD|Gu^rcNt}HPP9bMnT;IQ4lm?;4PR8}^&o;U{0tG zv=3$=gKVKbiW}!RVJC&9&9nxcVKm=whoApz=V4TO^@@+^+&g9I9EydWkCLm(a8jQm z=Kds5bbIta#cHDzXr-B25!!x+>9UdHY`EZg=Ey_S2Cv^pMQ+4xep-!VxAZeWMzkxE zcu4-&PvXPYQ%nYACzB%cml{=8-4CZfIlS!tR9+!(GSd4A!!UP5zbtUA9fLnC`K{a4 zZmm(8=P9bnL$vBZLYY8;b#M|I0eg44pntMek#36)GWzT9aBW!hX(6~Y)eS~tYGoQH zP9;M-RavY303^XBjKJXZgt!wKm70O?U=? zh6-@kf9+Isy4yYI5AC^da4Z1=uLm;P#YH|7#-WSSD;swozf*?rYd;Z&@)2L1XMk94~?9#KNQGirgQKhZaCzj3?N&rWxm>6h63) zJ)evd5j0q(UwCsp8vcRKW>F!C!0_3hme28Vx-g;HbY;2GjdUxG`>S5Mp_<3@$LViv zlm1_Zjlt#ooQzg+-XDW-q@VMvLUTUugaa{m2S#n(I7{j>`tav3%S7s12VlC|c2fzI zKDg4@9ck!@4tYXoNfwv_q0{LhvV?$4K^mtP7V6&EHod8VhrN{yejL2iQgb=M%d+u+ zOcX&WrVmU;Smm#`Fa?6R#>#q-5v#tV6`YT~0c6TE8tVLGSX1g!p8H|_|2yn|7x}*` z_1^>Z{~vR4VXC^IL=|hK>}$cJ@ocqBZIar-1o{o7rrqRSnUH~Y`!L{^=6;(wy)8!L z;&S2r97L9X8fUHBsp6SBg*_M75_+8`IgP}mY}Oai>}eSpulk7=#yivAvP{g)5MH{k)HP+T;pR&WTeKbt^JQ48vOBuQsZ^Kifo zpnVUXy|?>V0-+77e%7`6?aZ9s^IJ3oZdbw>=DQAuPaDY#=#>{Gr>kqLCFO0SUh{9V z)-NZiQbCtu#G%16G2#vSu9M4}p3cEd7Y78ss4yc4RqrLXp3L#a2eV0Rfl%$C0O^oqRL&<#ZmCh(E-XARZ3JpB#hr3I3M{+{MfNaY8@wXd%61QhJ@k;ZN^{cmkTWzF;z3=K* z+|KOTX8ByVCy;&)1ssqPI3`E7UWAg^K_ofN;i0Zh`xMD{j?ERkot}x2RtM)`*V(cyR`m0?xZJEnOKG5TI04YQ)H<+sxGKQ6XcViw!wn8scI2x2`L$A4f_ z&T?GFCXT?6m^JOH`&+9WKhU)YVZ_(YyGf2QX7zxm`tUlv1p}WEExULu1>miA5?DJp z(d0kEacI~s0Vngc@P8gmrl~X@a;gxCBw`r#=7Jtne;#;MzZ6JdxCP0UnGeHfF`Ot; z_hRIV{T#Z;jnvZxoEMZQ;+#NWWbfA`NgIwfMqa?mF1D)52yG4JaEXOIPSuRmE$iH- zf;MP-&%*~_S1WRRQuY(AIp*H%>_*mr=<(em=`NL{HuJJ{r$2}p$k2b0rw`*x@A&z$ z>%%6J#cu;G zL@Kx@3{pHh6fYrZjG{_9J9tbskxRTi#SE(@_HMDGgg|z6jbA337^`0D$?QnXjKzi_ zXh?|!HI|SAY98$bYxr#(B#HxMV&(4iRaI2D_++@Y$X$2JyOyufUa@v_x^dX8in-pL zOs*V4zdXd?ky9zwSbM#s+2YldWU)Gn+eYBKX8ZHku5X)x3~G8u|GqOjLX5a&zMn8Z z&l>H;%qQbqhlIQV#mELV5tYgJr}@2xuf7kXVdd+MqWb4{<193CRTywU8=6QO!R2#+ zq2Y%bcdX4Nao?`UHn8{fQq0iAgm^QjrSwQTCv&xzvF!E*Fxcxe<|*b9BUWvS22^PQ zVSjykYMspQql#tTDi*<|GFfY_+ZC_d+T)(gI6g=L&tA@n9G@n2A@hg*ZMMe;?hgg# zeFC@NKndxsE({m8bZUwpAj151>^pTxGLea*`?EnCweFp>O#CPXy6tCE{Kc)IPx7Aa zf@O2zd5&U+zfOe+j}+5-D+;FQH)@ITYV``ZBgS~;Bb!fE)i2huCVyR= zn#V85{BSsz<=YISUZC{Kh~J9Gt7>O>J?oJq%ww1CUu$OwVe_`H~Z}vefhbm ziFqcSTQ!gQ4BpZ_`(CGrKnm`AT&H32M>ZLY`V#`E5cbT4&GDl8ff`N z!0~JfwsIP!OmcU!nwWo*v8Q0DE4v=joL1G#qP9PrZC`_8yl0_%!kBSSG=<&Nry${R zmo7r*ZXkc(&SI$Z7X10NTN%-MA9gxx9iOk5D{>)mDul{4y#eItG4BjI-wTiJ<-=ew z!;YS-FrUP_aSAvrv$G*1W4ZEmGs$o@kQ=)-8uMHTsaIWZ#RQC_$4yhsf2+{4Kx9M7 zE4ShAx;+#)dzWeLD0sTxd_`3iTufD?8~lL6szt@SLSawcE{NX4^~cWKjBFyzU92>t zl)CRV+W86;k`k_@r04-O11y>cZNh*wBr%t#gTALp|3! z7>+LvW1@1oTl6p7`&`qsZ|7ODhqlH_FS8hJRU53BOhFkF`q;`S6DaojdO@8Hfj@+| z19{2_MMB$NC597li0Hh|De059Zf5$0ftX7lQQ#~JiJ?(ky}g1*77l1qj+bOhISF;B zC@HoAr*pj>PO96xlhcE%SJ<p_Z*BPhd&;g{ zu#kedg?y;Ud$<%;X6C?O2K3JTHRx^Hv%gTsh6n`2+!6zA8@7Coo^WD*9d^r^)nf*A zlKeua_qJJ#+{^~%W=?g>Z1#Ym=lx8j|e_B=WuytiLU%BaGjZ!R5aLw`f!4Hq$WI7rQH+78aw~jrS0Wj%g5t zW_u}mU))B?_IWShOe@Ti-?-)K)4n}Cn$XDCtP zn)Y^PX6UMfE(0}4*}X81I0)%k+*9az-M%=B1>8*+yT#gjFe#0f+e=U9y;C7}L>W`$ zSEt1;B}|Dcd7b&lJ8#8XcMeW|(KXYxmWYx=MNMIM`fdT_Y&Q9EuSfyO{cMk}n!84{ zx^4UiS7$C`rmWLPmQO~m$!*EsyZlx4q(wuK*wbC-2=BecikNm;Cz-WI<~-L~0F#H{ z9D;0tft~%vAkK*s*GbPRdM*&Di8D6WtyCys+gQ|B^*^F3#bC4LKN(Y$!HSP|>)D?h zzjp?|ZWs?vHPCgNg_^Id>Yq8o2@Vapxb-eEqL)9Vfhr7|NhoxA+ECx;Kh4Y?#xvmAZVjD4bVN`IePwpNGG+MY`^3qaxzT(L!aH-*z30t%ra8x3^6QUg_AWMv zQyNz$YP(CFTBKnZfkayZNJ;A3d(!t}Od@zs)m*oWYhRaoUyi1&7F7;PX!xJ$#g+Q(Z+O zxcBO^npt}8^SZa$uM6eSs$Ja#Lf~rOH+_qpVGzM?PoA2sNWaf8MqzlstH#O%c<~^ro>Pj3cx1}dXhx)GPKOI`!b0sua(-Auk zb+*GHg?AEL&0QM#JCh?!{At0E7^}sRQE2@JZ z4RXt_52eAg3ORaqD z`PIjs_dh1~R}}pzQhhC|Bwz}M?DPLP88n)G_!CdJP_j|lOKEs#H^)t#c%JikOsDwp z^36yayW^w%{S!;(9CmWDkOreF@a8}qrMfciZLaDRoDav;7CJRUY9F{8lO!qwn&43B ziDN4jPm8u;rG1*_$SriJvSP*je(bwbs|+EPR+T~6b*@n!y(Rw#l`lWJArhCDwIw@i z-B#3&^rh}6DDvRN>#!K)rZe7)*dA7C!hHLOE(tU1_O9!{JcycpnsIB;7ajC(%%^wg zg{S_Gr;#0U{iI><$06C0gw_cp?#*kH~*Oy-R2 zDSUceGH<)quy4N3jg2`orWWlWQL21PV=`@j9yz))xS|(H?>xb@p6THgMoq{f> zoa$M+PdE66c_fSLrz+DbW3;oOvxd^jg^dKwcCgIUj*5C`F%9v_1Fv@@L-|R zU>Wm;Q)@iC##A2_04(T_ntOfC2Q?_(Ef?s48eVF7juC8p9!QLhnuL4bT@6N18^vt; z*}@56V=1yNcQ#gmNyV<`S?nJ!$}O#H50Dxaz23JL{t7D)WJ~RX&7e zC|)OCXYabmx&YK$q0JpVCX*NKy97?WJdSPgzOK-!)XRz4vjFK-GcfOfR5+J!Bsfbl zR(5SlTGBlV`?^#EnQC=LH4O)Rm^rV%fTH)TY~fW3h!`j0HQ>+l7iWECyr-bt+oLRa z_C&r%9#p}(B)FNrsdA2pasJKFGu-L9S}7-qBv$1BXCdVnaB6l4ikD%_ycZnvlz?RtJXYx1AKRli!RK|WYCK;K9ZdR` z{AHim%h-I5XSHz%R=XaxX3bQrsg|bMNvnty|+-5KzogI+5Et zn;MNu^9tP#if8&pXMGc3aRFaC96=Ek@2koDxrXwdT_{Plm#it5(sL#03E#D&z02en z(U36g-AQ^xVZMP4T&1cPC3bf(s(MCeNl&uBBtr?TIYuZBBz81O%2<4EwVMTOQFgG5 zV{V<)?Hx>WD+{~%i5#b|(!4PJ>FGHVydi!Tg^8<0qLIRRb^5fp>TFLA5LnT?+=G_x zs=CkJvmM+P!KXG+yf98_&D)cTjg*`LX$RLk=`N6{p7ANaif<-yXZ!4=UO#hkTy0s~ z7g!MyIs&Su;$pgXYVM8yiI^9k1)nd?a(p&qPCSkx8_1vHnJxCjdMFe?HO2N#K8 zmoDY4pA3cbb{uAlZ{&^qZ~ZynZIT(vUJYmP8W0|*W&md4+i$awG7R0yO=HC1+4osl zI$w#5C$K(l*;l^l+ijNN9%+)iPqFhP+r~waQgZGb8lK_vd<4KUGLAVLA@ZrLO8;Kl z#AOUXzaI#7PD{<wU*_GlKquR^=pgLWcpAL(FhR$?x@ePKWvl~AaOM5(6XB2- zmsV=gUB$I^T2r=j+T|T_4yEDGgp(%VsG~^QF@q#>5G31PxCR-?w3tS=*_$&(b zs8iJMBW-IsU$7Hp{&j$AQOITFODk@rZuJ|pr> z!KQ^dpAqM*Qk-J|w=K7i3~DDew-ueCRf9TJBJB9A4*se-Rn~w~uP7WOJ zRli6Dnb0EDTp*xK;&{!FW_2Acw*A;RPf2boCpxVs#!E6YaL-y(v^(CtI6~s+RxVyA z&Cw8ER~v(4X&sj&qD$6}PDo?qkHURMm5-p_o{1suzUxE-b^rPzXmq@mqi*@6I2B3~ zMez3PK;(_3S&$+v|Gb+vgH@il>O74mVRdDWbuI5&=FBGdVW)*z&V_im1@*MH#B5SlcHT;~o1^-5R!wel=(4pHx9UVdhBL9_dvE^6hi0+Q zUS4x-v8?Laa!Jl0$mZ1E6{NxJ_Xa?`6xYOx?+$8vr3(s$l)(*`0yjbYe3;!xK&0{% zHnt^-z;G$wqn-HYX;I5T%ynSA@>-1&P39PBI-M~ee8*wL;erti@rQ_yUnT6ld%wo(6fa{DzDFoizE$3$ zcySQtTs<`hp$Ew%uhJhkfumI{)NrTOKVMF%P+BM@HTmLM6GNs4u)*L0JI$ni@A{-; z3t7*PBburi8+R9ruhr+BzFAQ3GHr)mayoy=7ub}Yv5FI1;=sFg-B3T&KWoZzK3T|y zw+cgy7ucdwtb#AsRO4T1o`_S)#RsEb!(hFvszC)Z0M9}^wLu?$)z;=#6%gOxg9 z8E`{qc;4dB#gR;86^DE}DJX>@!9+fmt@`K}^af{3DkP|WbT8IDZti*YLrJJm?4YNx zSrTS&a-cdG6^!&w6pn+JvUpyamxiUU}R<11&F;0PhyD;_M&9N0XcKJi22$ zHP}2Yjkwxf+7nXWM+Zu=@^W-E(xBwp>2;Ei_XNzJrvcFzQ6^wx!+vW`8$^3h!vLuJ zJ^cJIg;g(zt`E68?th_U8+o zKH{~09gJSD*y@7|afLC835;0yw;<6tiFO@matbpqhvOq+v$IXLR`&sE#8YJ_?imcUEP_rqz8vmkD2kA;)$1cB-n#TUhiFs2#?pa{?=rrE|;*q24y@~ziC%K zj}4H(EC&9XLH^O9ht~9;mwKry}I%oX;Ni6nX}=~a7csNP&6^OM8sYQ>^3R=0X6 zru0;sTA9M~)(9)h3W&~=oEP3OO)5#qD?4CHGAxf%jUdejGeTwLlp%)I?dw1)+!bs4 z5OoVVNeiXCt6fQe5(?!j!8qfN*N}2PQ#E!<&ejZat6XS&x)<;1_AELrgh! z8(il}) z1y0xNT}9u#OoHXeM5n11CS`XX8h;Ee5?*8rhrJ7ht*yDGRaNhbtCGf7C-alz_~AK) zLt3!mNNm$nprCvj;W_LU0i?pD|FPywxH{21O`Dc9wHbPl-e!4N4U$*|L770O{CCPF zQx%#@oF};DEqfy*p=aBa#cLgQTR$l|(~Grkb(EPfBDdcZ!?Ls#lk)U@XP{Y5&!IQ{ zbJWCM{By1CCyG`FeeBV3d!%z>Ml{K*8lk~X-t_~6$6wRUbDMECP%A}UL0CFGB~S9T zWnigPR8vaHmjg9>gLLqBqDFLR#deTrn(4(9V8 z3(w9`1Rhf=8~Xbhy-u7LBvDMV)Nwsju|28oPK~@W3_7_w&e1#vAG)+9G4SBuT3%~V z&R)e*LaQ?vzuaCtErt|oV$d{gd#{z7hwvc{>CPn+Uyh$)e%Veccx3vd<;V9J%<$lSxf>dRSKEzbe1b{v)m zM}8McZenUex$WR|%5~y1I<$RgR1yvzr5|a*u;Q$3ac<<{*gJG`#*5)NU!QSpxp|;U zyDop1{kQo?@qdprcU~-)FE?4K zneN@X_-=EZ_34=rbbjfquVb#`h2q#n{nf0a-3=^6JM;$jL%|XLAb)dSa-Gl7f9?h% z?e$qkBLm6ygFnyE<3wC#cc~^+S+wvo^jt&4SVLDYp&i(-ZT=dqgE&h31FOtq6N`BN zt7mbelsYeIAlE~9o(of(xN7PPlBrO3o!fD@?>yR04lY;9x*T-3+#X9VcR$X0h}zR) zd%b2?4h^nyoa`7H%%rolD)>G=2_Ozczf3ODZ0Q?J%1s@G3UAi7)0%LF?Gm)?0wv;I z{O$C!7r^F!`H!2=LREX+w079;-b`_F!j1Kc%6-7|;Ekwc+U%a4MH9Cfg!d3s2H_c^ zc3>zdkAV8d41ViCHr2PBlUy5}7R>g@=LYK}UWmjb0bUcty1B|wwCAb;AO!SgToS2| z!=JWvm(L_MZP)J@;g`W5YiGjUOM&uLuadQo{VpKW&E8kL zzH?8oAT3Afr!JLz?xSZ>;oEarVJ#f&aea*gy79Za;GR$l10(Icbr#|ig@#$|iiOSD zECBbg?UIG2N5b06RVT?CwfI+%vp+2!9^qCC2F>3dzSaWp zpv<37r*k4yTj^BR7E%~_b7V$4)~8(IU*$#Pnh!NHlQmSUx6ieT&OWgzu-(aQyw|qC zZP}exkEY$sVx-coJI${Gj4ZNwj28q-xQb^ee@eSKR^t-P+H~$$#i%`(zX&?q@V+>| zf_P6AGwY4543TdjKI{0{p|?>U|He^SzX7&O9onX{Z;?Vb*grp&Bm;cnhF z*_T*=H>~g{=AvyLk8N+zc{58k$fCkYmO$Tt=amo|MQLsrsbs7C8F5q3&@&w1{D;W- z`Zpc7CGMxDre2l_RrD9RRZU04H0UjyOrW7XV*a%K!CVLwxBJ_}JrLhjNz_KE77f6$ zl0VbB7|+C(J3Ly+xj#pucA;<4&X9$I%r}MW;-|!yZY158=qC! zOs2_v>#dgF&_q&`t+$AoyE0Sf>L4=$AeVbL-XV?B2RS7(6t3M*f@ko-`(&Fr<-BZc z6D+KB88#N&8ma;xY8I5j6jwPDVY}Wjq2&D0({*he*}P|dE}D+tAH7lM1gyIKqg1mM z0IPXV&M95?8>Y-l> zwbVLCt;bWV-PVp;@YTdo(iRp^IdGni#%YX{R+SKA{%%6PYgVJ%5wwsS-I0+zB-PssZ*k34)nk=vt%$&b6t zio`fRT*f;{6;@mBgVqsaoG;JGL?3;}{=bvBfbbQ!Oe(c-wI-xh!|MHfi( z{9G`%=R0r2^9M4F&ztQ9eK_CYjpdIz?1ovBKa;w61$rsk%FfV<*!|%{gJ6MF zfm7t=#dOtVb@wlCj_wgnA?A#{BzV%Rn;nR>du6t`myLqySklh*1F=0BMvn8-`yzjK zw)%%PBfHjb`(6bc@mWQOI}aJ7@D1bOV;Q07l7kq2?a^zB3X_q;>wiDcfd zeHAg?R-}aegahbpD986KFIfP@!dKVEHijWDK$^5XZQu`ABk>qX7GH=)e<>ktO`cND z%BQ+d??U7z*Jpo&6x9t+EG+LQjqul`P2OE|o!ji^8;x&64(GkIZ*ETHsf9!%KtzhU z!r2F8+(5A4RQGvwI|Qw7^=wF&j&9cbt9$8#$x5$lVx4NzXM1edjWG?q5 zvsz+xyb~vGj_)yLI+q-dy*}3RbKip-(_}V8MvmdVtk0T&z zqLp{jx&-m7k$PSp2TM{RKF|gWgg!yktuv$S>G z448rcUx#Bj;~z`1-l^LlI-yWKi1wJUu1Mvx)g}dymSxQA;a#0JsPV(*tF7X-ah+>5 z8k{-mZ|mB7DB7G$9>1kp58*lK1ROy5N4u-p-z?iX82#Jo`^yBa33d0E765)vo+LW= zD3BqWX4D_Vo9a<1)1|a3N`hb4705JSs${>O%Sxt>cQ?bray+5mDNvZ zo}i>ea4mjJaBBr(!xjvQt*1=lj;<@l+1D*Zyn1oT=i8+cLwwvu077^h;Gqyn?2s5X zz49{Qy)CII%;Wsq7#mhlZ84`U(IoHZ`@1gUE?>M!aOY=c!qFe2yscuou@rOXgd9mEbXqkJ?w@ z=Ebpro^aG_&}<|#yHDU+zU&eO!QJ9tHN$tn*)#EEZ;Eg57IdSu!ASZP9OOPx3guX>;rj7mr9mw$v*w&Z?+<2QcO_&9+vX&{MQRMXgT~i z9=)r4*&E)M4RBrwI(B-{(MAd*#S+J4JtEck3QOAj8)LS!udwSs*#RQi!HrBpqC?-H zXS!I`v*JkgUT^hlzDNk6!fhlR4fjJ>ycnn^lW`SwVQJ;Q^<%g()P}&c0(crO#yNn> z(!n23Wb#uU2nYR8L9a_9(DQ~Blp53={sZtM&7lAt@)_e*qqULR_9Nl8!qbM|* z`kwF`r)wQGLeVC`v$1n#Wze{F(9qjR@%Gl>PSI*97sZ&SiN#&_WBiq@Hr$@1nj!@7 zmKcBUjbAo6xw;dG{gM0s&61R~7`BmG7e?}JKC1WXWth+Ewy#JZ-(TZi4Lr+q=By7q zS#nQQ*`1Qa9S@J4)WnFP`mmCfU8Ru)q$Rff$`JQ%O5-39E&tXp@xi@NN2aEkECNXg;@4mpHYsOxbD{EHevm(D4k(#s`6k|gL6$Y z#l}1jXF$;Tj?$TIev0(gx%4lRW)X!a;Q-b9N4UxDDGHF@?fh$cmrj)G^4H%2_@B4K zSf_5Uoz7e|lg*rED+pzJhftX&dMT=Tn;1cS)>e$MNqn4=Rcxu!lzDLy9WOGQm{kXH2?)uBTNje^oNqdUgUj~&;|N}65$ zhw}MO@3WtLugA$bT!~u&?*pbCcmDgjdE|XkHTa*ePyA(Pj{0* z9DK@rc9o?ZF{eclKjiPGo>owo!f1UfaA}tKz`;Q0yXJIAlBt4$HnPGdCRm z5h*6_s;T7~Ytw<>5(hGuIU2CXRwP7q=%bjWS&Lf&zXcpN?t0z2LFxT+5B%@T{d7UM z0sKW@+~uL%d|wYoiie-|u=upK1%140QVSzTtkBJSV2|7V z6+@Uj-c_^u5Y6fZ*{N81t#qnBGyM9>XslJJQJhEfgAeCOwC|w56;LWfi~he_a|dVC z@n^(j0GF_5dHiX1cD?#o$!}f&rvcN~C+n;`Q?%9C5#N?;;=b&|+T)|{j7Dwk>}Tr% zLrw8`~~Y|$~{fNVwh^;^K8Ky#A7gK%5Y)fzMAMI?_FQC$){m;D=x;Etnysd zsw2?I4!Gx%qNn;N@~RgP#x7v7hJ_Y}eenarUp2Y*gvk^^V0^y+ef;Y71p_+b7|y3& z$z_#WbGfT*DqJ3`Jwa=MMylPzY$tz_PBh8))R9sdXE{YL(HCT`zynL}5Hz0kiaAuZ|LAG|Do(H!>a7IwqZd)LRvsTLXa-$loSw!FnVSECkLH`;`%Mc>`|w>wkC4COIt%q8p=W zHusOu`%7Xp=&6_1Zl3}5#MPLC$ch>zK>dPYskG*7?v7fwHMZCj7zonuEW;5Gg~BIw zj^nZNlqau5te~~k(GD@?1tS7Zc>Ld;@c-ZOLfUfG2^Px0aF@9bO)Wv$Y@Ak#N$TZk za`_VC?)^Na#+B;R4oM1%e3VbVwup)M&1E`CL{!H3IZB>Ay`1eNcR5H799(r=#XsJd7GE}rG>QckZQPt7|`7dJpZg={=f$qPsOU;KHzw!f5-8^wgD-B?%(~ejHstX zNQve4)Ub>@om5)1!N>1kUy=5pVo=&AJy(1mzDn%?8!yF6{=!Wh-HGce6?5&1s^;Q~ zyzCI6R#o8**^@nhtG7^a?5mIKM5pL~N5f|nNP$k$194bs(Pqr#$+BH%>xL&={ z;1Z?IO=#shNoUU1cHP1G<^;65A9x&{z`du5+jPFX@G6<^C0c=S$hZpAA=EBp3#os$ zg;!%~i=WrJ2WA(YI}+7m>Ob80GqCl4N~dP0+CEPLRrlYnVm?XYP>Ok`C16NCrX%2( zI0Osi5>F?;{n-L~`5h8OwK70j##NmEIA)?R>froaUo1PQ3+pLGCL))0;ZUgRa*lp} zS389usx8pAz7g2y+4OKtE<;=F^B_5LE7SkiZ}?Zh1bWbkH7^Bg=pFAAW%39xG53eU_few0sR!DpE!6G8?Fg z1j-%)vKco=CtW01WMQsJ;zBQ-jW_VE^~EUNpt)3O-KbAr;{Z7>eJ(}u*n@BC#4Dxl zhOo#A|Ed7|4};m-k=e7eVZgC8w!p@s1pXibSO??2S$4Jcf=$+*Z|wW$pzX{Bqw|y7 z>c09Pid+H|KWpyzQg{kHVs)$;GdU^9Zp+ZUnw(> zIMYhN0R=vGSO+CuG71(@ zD#Dq{JfsZ&+)?rwL`NV-#9=ICZ(8co&N%XQ18CcXrBBG&y`cgJmcQNr-mejxZ?vU zM+fdaHlUv&_f-J02brsBvhLvwQH|EARZi%R^X-vYGCv7jdmc;bBvj84Gn(p_nu!Jb|_trPT{W=I(ocXoLS{u+$d;B zD!#W7)&n|c)-+{2hNh7q;vzsnB7HsUf?4-(Z{bGSopqB!e=RrPqB6+?n=oonO&K z_zzXH1F@_?lvpVUCh?R*XTlk1(mZ)8>GBW}doxXrrynSgxBs5LLVV5Pj@5jvwarSf z?x@2F;JaqI{pj77+COpUP4eCosLUO9*E*O1(ADxOKCvRJW%qiP_&a-l`Ca|Byqhq~ zWH03)ObV&5>d!2j$$12cIRPFrQCfNPS1aX2AEJ>vgq`>JXCF|@^}81=T!A}rKEosl z#Ar8Ac)RK#SJymoj_Jt&-Wv+vn>bEt)73wmev))U@`IjI%l8My?S7(anRcA*_5}cI zld5xhg9#WlvkC1PEh{D9m?fNxv7=m}rBr;r&Q${Cg38zSDlZ>CLH&EVw&EU$SAzZL z9d+)M((GHwH3Wn-)sruiEm1Got*+8BHC7JPNI(E;^THl9=c&XPnL^anMarVu8KK%` z>VV4OD#yLWaQ_c-KzkqpSX>yXy~xoD?PK6NKmMR0GyY(5^l0+D3fcfM77F{%;6%rM zTG2A^WNvxQ+;eMH#CdDNVj(kkbBygqM6+;S)TG(2S^+#q7?tDkYOZL_(NiJO*UD$H zn6kwtGY%4=p`{FJSI8h89kvEDmA?uk3DkY0i;yt)?O#;z{}{E>D($~Nw~BGuu<})_ zzn3+KtWS#O%?yE5v9F%!PlY&Re1jfuvXXwJYue}yT|TS9w==iPH`jWn3;v>`ji}q> zMSVH-=e<88His||$8|*z>gCp+& zGACInf`Sg{{MvENrgfct$(>c^+0DpfUn8I1`XL{rXd#@`l+$U7yNUSR>p^k-cM+=iZ`P>{|Bj`|131|E1D56g{3qDL66vHLiVXlp~*47npbw$i6YC zvdoz_!iGWMW$vHB%e5esTL&)Z>p69ta7NEJ0tV;z3G6Bki;aRF*4AM+r{#gUc4xZV zuJ_>({hFiaI53nVq~3^U=-a14v>qHfgRBz{a;|*=@kPb!^Vl%mcC9{F$2hJ)AcK)?8XlGty7%u`8s# z@O%UT#Has?YgYTuEZ>fRklEDJ*cgn8a(U)B+O7&nigL7~b4eYv7TjVAky^@%HzW)t zgj3Aro_UNVo!g!YQ1n2wOXOW|rr0Nho6hKqA0ep1_!J8lNohyMKyZWK9}qtf6xhS1 z;GG2Mob<lF;<%OdJtA8iDS3Uskh+ll|wxA-}0s2rd(t(#{5EIKWXK+KsoEtotXp zi0co~XG7dKDV7$N@ggm02)De;)9I~v&PAXf0KLk0dwCsc4bbd~MjhS7{w^^9xgIM# zj7AWiM*Ayi;8uP_PW+?XmVekjwwFN4q*Jal$%ZPzCMy5XI5H|#1Y`TMUh zNji=k0Fw*wx-&oQ)#JHB9072s2T)rp$M4=r5^t%#2R#;lhWOxlewAMT!1FL8T)f)3 z|LxyI^%pOXVCovzaF#2@Dcq;gO71d)X=900zj zNmC{t4e;h4gMZa({#_LMH~JRhd3d)D0iAeXA}pWO?3*fPs*&{->UVbAi+Fm1vWk(Y zRb$%;bCzNDX?PUwTU!S`9qdw}vuT;GnV~fx;WVkAqQC_$3X!2acsSX#KRemxtzlQ= z8bsQ>M`P3It4XA09pLF7b+%M0R=F#_N##pbh+1!dbvt%I6&<2CB$QBwBjxN-J9b80 zU(MDA1UT???MK@5pCrZdHybfpqxMiiMx=ZoHU6W!^evQ2!Lp=)HfW(J^NP^*X0Trf z*3TsR;F~EM_>^2UdBP$mi1#)a=nG(@-ioCCg2f1S{?dfhmjf@x2y-kO#Hg`k=nZf* zZFukg%moULYIB{xIfHlzm5Lld{(984zUx5Upo+qM%y8WO6Ey-7Oo4eddunX5=?y=r zz~+tteGv-+soyGlVmH_!26R;MP`m$c21Ln1kX?Turm^LIGmJ3m^pnT9&M}#xe08B^ zaAtelb2^I2c0<$VoY~gBpG-o}U!IBU&iQk;@V#bu{Qo5}OhvPQ?z$*1W}Wv!*4Av? zT{>_gyTgy{EqFJlV;$!#reE|4ZyJ`}3QEo=BTR#5>DZVK(O>x=k|V-DIx{GIyINp^ zP~BhS462IAY?d!_VN3clYpTh+vVmMMb*y)BmKYMD6(`?tZF;yeL&{I%bNh|XJlB|| z0zr3gC|Hdivfa)<%8yck8^7}f6q=kHgCKl_^R0mvq7+M0BZ|6XZ3*}Gf3r$XaZAXx zWovWbEKN=)WWeJsIHltjD)xT@7nFJg;932%k*$Ho_ZsVxpX8V@+O@tG`+X@nT)X< z*W}*^F0&Nv!@|N5PM+vErJCwl^BwvkzAEYhgQya;jh?C?12~V=uWv=U|BM4gRPhJM zFfCw;)mX>qI60q-i{a?1eQ}2GIfqoUgGCrH;%fM)WZ@k<5ZU8g#=CaSY+f3>;gn;u zT73)`0)CSJp?m&=oU_;P(ENQlfONZ~{~76i&hNO&=7Mm1zMZaaQe>TX4t05_Ahz8| zKZ`D@(Uf~d`Y1;3ScUKFM2R&1TDOnutW-bex={CHEJCecZE&-C3r^_lB+HZhpKRir zy%XSdc8CL}pI%BQ%~uZH$AXOUJxF5)@6!`)$zx<%W4!Z-Zd_Xbfq6D_tcMSyH+O5&dtq0OIbfp!U(nY^i(~K0| z0Ee$qRG0Qsg~)6md@k%7F#Z@O0UTV+>FUp4I#`e0qW6#~V^3oK*L8l^K{?2<&x>p} zLAUn6=#=o>W9mn&c9Km8QaSkSQqi3HWBQ$+dPhx%DQw;jmd&p|6K1F&f~@#XhHDDA zN5!JV^&StmH@zD)s|7(tkN!ac03e1`8T*Uhl@)oCy5DIS=Q_|dLJkN>KvU$W))_pf zCN;HCg7B6 zO;*JrgbGT?G^vfIh=+HYUPF2x8(W`m|BA1a=Ny+{^Mq5>i>nFCce(kiMNa$0RF>{M z6cjRFRNpV?+W3k?XgIw;G<{kB?FEqCZ=4m-k?p_*s=828X>>`eWMP*urhKI<`ZWeJ z@1~!gTbjJ7igm~Us6kv>bcANERdPxV_nr-^?XJj>y{CLjN4`so>kSA!d|7$^3>|&W z?a(#YJAet)aqirAkn_$2lnm%qP;h>% z^m|;;+shwoqGoDLWrP0ZpL4t1mZb1kfe7wIUibc2iWEbQBm;ub95(+9v7g1GD9UV1 z7no+|)>6{F0N_^`7=I)306>YH9*&+3QpH*tFWtq(S9aoBwm&*=CESC}|K)Eg#3EBe zo-7<4&)0&Kl8`mY@)=^bKWBHTmuKz|0aEXzRm0g?h|8uJ>+6;Ggc#c4Kd1V@CyzDq zm#0m!bKvNjt!#m}c{a}x*kYLBDC|3rB^d#|x zpdT63UoU0f#YEtwW9#|_r8q;90@Kt#w!ds&)-vv39nON(G4D`^2pS31%=}C`HZ_kq z-3A_eJI6&*hkUDDDKdLIOQ7jZ+{}swnEKV$lsM18usDh+8+6GAS6Sl=q>s@Uf4HWi zf0;n~^s3SJLe?5wiO$~b2mjyBBB`v&f za!j`-W;d5%OFO(uE)xpeZGM4lMq}Vp8*A^B3qDx9eO#uGMi@lcg!s>_9uPR|yO*#_ zG`AY7=qDK2_&l}=f7qJy-JDz7?0HW1TQ@D*MWi=d7SGd5zfdHTQ+g3q>`^O_S^M=F zLY%r=a=W5b1(He-C#=LeE`UUEN&EA?AMmP5lHIQfe)7AH^VxEOaC}Jk0jnkh-@-|#tYxV@xtglldLl!mxa*H^q5h}g zP7)d}iIlM3@8MrF7zol_>;D?a)*OAD4hNAhypH{M0Up5Wd!a4ZEoR0@1{W?yb;d>`_DyJlQXL1EZf zw!~m&T0?JL0Oal~T`cem(iXn|B~e`^$LVBOrTwB!`$YP^!t;nGt@1Y95*Z`jUP1>DPb$Ri$U(qnkx~cLH?vg0qgubm%Z{>VMNJP z{l)xGzMdaOj6E5;%5xB!|CiqJzlFg^1lgjJfCg{3*>-(Qnmvc*u%XBGY5=YdEWH=9 zSLXHtNB08#kkZChKP#WCr#7Jm(m3w0@2rh@=0B2aavMGWQtM{f z9_P<0wns=16M!?TA-Uk;k}{GW1NWm2AO&p2_?j&qpv6k}Lf~d`84?QBq^L)oVswkz3lxrE@hu^JGc)rrZqL_ZLrG5BZJ>$B+*Kn+bllPZBRJc7 zZELdQ1o~U8+13z}t&Y|ATz86ffJ^fhry$E>=v#5EpkvyL7#`-jI+rK(qc;P;K& z)PU4T`2Q@`0cLEQ$4I)%YkbFXW>A@>^!HrXRVkZ`$*gaboo%;F=Duyx>h;z2AX=EM zw1_!5l!c zUy2~}+!X(_oqWr~Rt9E6vS|ODEGj?h2tMBTT#RC0a1sIr)i5Y3Dh|o!-kvXNMJ^_B zJBq~56{)drgBogb4|v_LdiEO*=!N`IqV8P5F)w}ndy-xEsUAN;`5L*|Mh_jgGfdC5 zeeUpEkc8P>N3U`>CvhGj-?E6Oq0*0kY_r%4DHP3YuNi1ITPEF{dr_YouDM=Cn(7@3 z7{2w`Tz#xM&@D?dzy?ta7W`-LD5L7O(o6A50WXldFY~TgrQR;D@oJ}l$<<-1F-;sc z$?qvH$?f%d3^2xaQw28v3cN@281AW+k0NzaL-u=`<@*Xp`a@Z)%|%a)@Q)a+7(P*W zTCC7=?ZU5~d&`6+P!fm1MCl0ZkMh&_1WI0*B0nokRZ7*YWrhEY=hK#|WHBoE_SKh9 zLBu#!AJJhIh-KfsTNoI%wHex<0aaAkI{etb0iPJ34A{6tT2Hc%6 zEL6lBJmcAzl$`=M<>{Tf)STPG@rnKzxbYUR0hQ2lJ0=4paJ{^w7nIHDvM0WYt7Idrfn0+55d=(f5yw_Y7BX5^OV;)uZ zNT4_FGc5FQQ1!lM#d5JNS%tz4_<+T-*gst zJ!y%f5);j)@-sByV1_C1_>W!&4XWc^t450=Ri6gad7qqW>x(N5k>qb>&^SonYFFmA zQPlH9Z%x(2liby`MA%eVuadJ|dkeqBxAVb{itcnQMF6NR3#i)@eOyn{rA$jlWBGD; zO}ob#tJspy?wo-CHm-f_mhif5I9iX<8pY9a6VUR!ty)dcs93l1M@H#OyEQwto7 z9ED3SZn)#3U9QkBNRvJ-ktN6B-L(dXGc3^bXKb%dbXAd0Z4KPTJ7FRh=auwxE7*sT zgEIJ*rKnmB-Xj}vzZ3Ht094CNl2~A@&%n`j{>P(BhEL?Q_2a!gmFIFgBzC{M+zc_r zmeKLfIzG0M&Q?E5`6>|S_3pnZFFmUoABw%sm`v(^3? z=@jI+$O*RBSuB*IkWRLPY1zd%jDO?G2J*PxiwqCG=_&lD%1V%;nk} zLy>r$kGr>6DP<{V$>)Au@#NIGDzA4`K5qfg zjp4)|8l`^|>=l6z)e}t@v?N?Z^FNH?>mwxEz1gaMM(zOE$jJLLPyDx@(;`d2HO~g` z&2dNPm*EQD?(b9Z5O?eh8ECqnO(=(Cx$R!@-Cv^Kp10iF!{mRk>I*!#?GA!Xns!}u zI~feQ2if$~wJ!oDuRkD~(zCd;TUkdqHh08rrF+>`?Yh0TY-s1$t@uV@%=508K6KC~ z-bR^4gDG~a6C4~LaT!?L2*Mmr2dTYFz7hxmo0zJ6UxeqFk#H0!2&VPHL4Hn9W0Zc_ zE%8Wojf^6PfE(B18oYN};&~gyd$IJmKf1NdJ!~4mmbS-c&b)@RS!Jn9iU_=jk|5S) zU{yxuvl~Act#dD5TogOl_53w90k=b@nq?D~0A*V`f65k-3_5dSq9H}usVHm-y2fsL z!F*q>mfVjI?smrVlALcA8Kjg$$flEJ)N%-{dTVUqDvdTL!wM{h)0<}1qL0|2rNE;a z!zQG_Nk10pri-V%Il}P5cJBS$0vgE>-Coro8rzq4C`fQj;j$N>4yw?%>Pr?e%P_Cr zWwb~v)T!fCn{~qsA|5h=&TTkvEfV9Deceg z;j31v1@)*A8I5R~GxT5JLs7VH(;HQV2_L3I{r&p2_lKOVb35*5j*iN8=UMIAaiF)6 zVJqk`M_JTwlbe9*Sv4F%_93R#0o5m>N_0$MS~Nu^B@t%BA-i2V`}HVgj0DMz1OGvv zo#8ZJT`|q`eUP z2GW7d%#R$I3K!Y>8?mXx452;zTxT=CF)h);)SJDMQSfa7!S(yH#>z>MvC}MvNz8bg z?4*=8rID;TuR2WJqsr%Na8@pjw5ygdiHUfclbL|wfSR{zg)u+#X+jT^Fw_lK(@;@a z52(&on3)Pjw`0smNaT4_mXY+~bs#Lv zEwW%4zg8&Wn-}=uHKtQTWh3>nhtgV@b#lXL_j?+Z4PFLVQuaT;?B!&_xPN%LNoFU{ zY$zL4pvnoYJai6jKIf*sH~2c_cmg+5S#*b;pR3`Lfag4sf2+#N8BZuI(~-oU?J!p-Dfch1C2*r0S1$cfoOA1DOXH-1_+m@oq7w}<>l#XskDtR9 zzqsZsa`WAiGX)8Wvc1pBNvB6cVln3H&-gJCxM0tmRCzw2Ua_Psa@}SSh{*7m4p9`* zKM^KXSjq}Jt{1ZRUJ|I!@oGSfs@E8{4kAbNYy|$RX#=j-b$!wVOba*p7H~GfLsact zQ*P~eoiI0MZd?>zOj*F-&P50VJGq@7RNsiwmc2O}@Rk zDY$5^DT~gzz>vgq^R>AAe4I!m2+u9OUmoN3O6mHAm7LiOMk{Ar31zRB zyHF66Q1BDymyhUNpq?$wJwz?U($d{44&X53`TpkPhj<;#__C)oU4s#kklaJ+u;l^Dt(j}TrFDRZE=;?iOKSba<6~^^uC`k0_HsEqE z)!`lKqOTV(&9eXTU44ALtn=$9BBMF;VD;lF+`g~m=7bFf{ZKVh+)Ih(&UmVoFBl0w zhCiw_!cg!EeE8H<{66K^x)3vU_`8|HPK68_sFvx#Hr*WeXS0VJNGt=WOk%gPykWn- z-@*Ga@Z?3j4pi=Phd(#id&T*{+J+zB(#iv_Jrw3H4$sZBZD9$swZ@aZSWM( z@ccp0#E5n;AN-+rI)c731diaR{SA)z=yn@0-|ks@+QKCC_4hX^rF-7r0p>YqRDSYA z^{K_rfmlXg8(UlV;?CWfitU<~Tk~l%HWY#@T5m7hQZoBD*)?Nt4iawjPA`YZ>Kk)u zkaDlh$BcyYcxx40wnbfBTCwWO4KQMt_53jUJ~2a`0+CPSKSVwp4(>^jARLBlGKuKe z_~3SE2_e6yz?%k%t%`E35vjsZXt1>(_YT3_mhwkxUD+|l<&xh4oTrTkR6X?*`jDJh z<>^y}%`zT!7TroH zwE(~DQH#mnVpM`1{QxVP>~Jb)dq|u{yhi?Ze<$anqN7KFcfCwZ*f8hjFVp-9(~nlW z=PdFPRpf@#Rph*Bx@Yyyb|y|Y5-j5v&W%sEMoxQ3L%)Fx$LliS3F=98L*4XIDa_5O zA5ff{X$6bK&n=oAt8)#OmNk;9FZl`Eozat^`vUQN<7Y+o%SU)QDH(}aXpU;#J6E`O9f z!IH7WC@LJqkA8jUv?s4{*6|U9#L_|+LGE_Mh+I^tCejVIiRaBtb2*-G#&k70dU9fX zeK#1g?qc>M8xl?RV$8&iCzUoCz9ASfeycp9l?FVrv>mjk^aHx_o{FYRp#;!Phv?s8 zO+cBh`&JM`^AYtH>4q>q=N@moK?kIizc%?XS#vrhZXhZ zRmx_%$NVWGIR#$iP;@3AmzZ*4fLh{;qjT*;s8^5I9C`|gCiZ`~#=Ds^TuI0<+eWzf zY2qaF?=LJW;=XPP1c@jJQb@;TbxXBx9cidJaA6csX<|8Q%& z4ZEHA?r%<5Y&YH?vt&>yoVP4z*vufRp86-do2hV@yZ6Kn&FoS*LIR5D>oZi(3*REP zdVds9RqUISB&qAP;|3dWHP7# zyu$9n2qR0(n_SUS=R5TQ0v|O=R z^=NO+j#uk>8eXLeH&nvx06UX-{2$V*p+pTaF@&s~99O!5kZ?nM8VU*uS33M+*wij7 zbCq;pAUzk@S+&8Ts5?e4XI3(vg(~-+fZv}mp~r!JMpFtvlU8|CICJ}15&kK8{Uyj; z!Hvf#E^He*8VmQuE1L`%)0K1T$G%AbhH8L4bo>0MGWT0)cg=(0+>GPT{rm_F?p07# z6;E+HMsUAa_TSNJn$fB~IcbtU(r9+$d~>nnn{85VG(yrXl9Y{jE%Oe$?b@qTLDp_Q z`*oVkBOr)O3WR+5a=4Rtb`DHJQIL5utx1EM3O%gj#sB1pahLtae4VW^@Kg(-X&bb( zG|$mn83P^x;0Jtd$75>>LzKU9|vxHQG_Hchw%MPO+EJu3@SaxxXiIZV|9MV+(S9}SS8!Xc{9k7AKWfG zx!3({FctuGo|j)9o}QjTRb=mom&_J2OJ*+0>{>Fp8nl8^jFZs=^qYF zCkxZQKAl=8n9V7@HLG{n%O7mFr-L$*<;9If=7F{Oj%oMYh0AV%L;V^qrHRj{nfor6 zyufF2!2F#?^c#LVr%>{gT+RC@xkqC$>^Kaw8vGTAIXnBNn4G>T8Bpd=j4M8A2?e!> zwZEi*G77^?6gK$1TmG?Z$qWEI?@SgYkfLQ`h0J(GIQWf)k&611zY+9>XW@d%0IX^W7{9OpszA?>msOLHAJF~bq*4MH*2ZsxzS0(u0Z#Es| z-nl!-0T2&SLMinOX0T2LW{DRhk<0&KHxO{NH}t|u*ihr3R?Bqzu1++vWN%o z@bR{^Kg)vWz-5}I$&iJvGT@rX4GPuuNzyTTrkbehYcqg`?DA={5 zqxZmkk^xb_hF#H9h|}j7DQj$;Ka9e}#3X3T0}cXj;hY_l>on%$(jLhCMe+FBZ`dO~ zdIaLwc8=#fe63$Ro|5`}rift>cts-|bhU2JwR%rhUwt5H%cR9vPxcB`^_dU46bx{5 zu>8-qprI(dU+ddsA#-T^$zRm)aP1#juF5zI8I80=$MbnM>)PsOv@vq;Hx(ArQdUUc zx)v;b0NTNqExL2!8E&xThIODK$&5%i_C_WyZf%;sG1cKm zc8~_kIZf`KMw9WF=q8KvTeIk~RH(J-3NgnH;x@3|EZ3e_8v&!raQgF*!xcU#qY+O( zk~hRlufnt6HdnSU0}qv%awb$SwB-v?_Q4Q1QdX-vP2#GqnJPPsZXGUn^lrsEVjJo7 z`<7Q!Tqa7Gz|x7&9ujIM+y%}QbRXj}b_ zrIHecG!dTo5gnozpVak;mJM5R29C!KcGQsGL`7hCd@CpIvqH-Fc5~ zCbq@C6AB_H7E}FnD{^&v;A#1MX@Vp#FK>jrt~gDI-mIF5n!7pZxTZzCZ`($E{jVH2 zJkx>CJSTW+JZmPHCOJ{e{apHlt0Mq5^#eZ=bD~0GExa!D7S7&8?ZeH(DCG8hEVZA% zdZ0BMm-@!N`R>YeXFM+=1Ab04Fv-t9)DgOHb)j58D1&&8W1$aOrfCX}OphFJHIrA6 z;BRzw+Mn~BQ>{Fr^6sLWZ>7c1@HP3^aJrZb29E1>Qq6X6p7bb?Wq{;9RwP-}tz*}m zH-WrRn$XM7Z)?Cs={O56v!&rN^l#<1@ejrqt{34}fD|Jp07NBK@seY%V>>`iiqk+C zmup0?+I%G7&gPyZu=ZJAFP0+$U7#+4^c?{FZdWO0uYfmScNTsuH@3q=QMC1qh)}!F zu()ju#IaZ{@z)ofnA_djPjQ>rU-S!Anh3wd!p6?8T6;r4MbdtzfHILc2J0#kK`xnF zo*$l`k)E_qf&fkY2s%w7wX$;DJT(9oOd%Qn%8dcHqH=gMo(wB_UC-1L+}ve}H3rN} z2eBC$7?8hty#{rIZ7o5`WBH=w0vJ2!D(je@cp}HKiQIYbCejvQ@#qo%BeAyv3ft&- z))V9e-(=4zMtW`cQC(!*?i!b?SjyL5CDCC3>k@w?g92MF%@7TZ=E`Qg2o-4U6`$4K zP{X%kYVgOL6MFUXWgA@ptLdbSh=|`RFFqOphgIw5x;+mRMGaOvGR$f!)Ep)}cxfVV z^LjO624x6uw;D8!QBRTL7QUk;OXRCo6KVArrW5mHOTu)apd*n3*DJNF`1p7{rhD+! zm~!1JTF=eLsrv&_oZ*;7_no6CmC`NJLAVuJMT)J?9|z+zPj?P6HO!Q>Vhkg5l^fcC z?$f)%1w`<50ahC<{D*gsxN6Xf#inwkQvfpJ70t6Tv?Ud}97adiUbfjpCjG!wUNyMz zh=|qd!VzTJJmz!~a!XLXJ&NcDISN0D#zSf|o!c?^sCA?Zk%(;Du%ppptW@DzP<8L!ySATl+x@$Xl5;*!3SD zJr1@=BOg)ZYPf5nNAG%m(4R@0qYEcHGBVAgE{YOhMdsx(qDe;sq|mM$2$M-l90oDt zaYceawA>!glMj)P0PllLCkGTb&707zm_854!V}auD^VIlV)l=iGvn3n&~qm|C1GJ$ zpH3GuK_E>;`zpshQ)5Z==H{@&!jMNYnJ4b}_?YMJyx*?JfW5ql^5{w0aJamSCQS)* zVkG-R_Fw28)ZDa#LMCxb_{}5C1kZUfsM7R$fra7(YeMQ2_Ui4w3L!&y+z+4$VKP*a zIq?H4IuQFlK+gj?|08tzPe9!H`PyQ>HjL0|2};zfnZ9N}ABgOoY^dGcc)*des_UQD zJ00oRdm?R~OG``V+}yZ{OG!C2ufG%W_xm77Vr#S9p-_H({N7{l{i}?=ifjKn)^G#D zIia`!ZhPTCk{@I3%}4b-8J)l4GhNw?qBY|}KmO%m&7DxOgnZhd2eEA`k6Z@-8Ypn%v>nioX7 z_h=X+YXZG?RrTDTa}U~XO5JMJ;#xY?Z&v)^m6(~CQCjxbLWY{D$`$aI@P+{@kr2!b z6BQHF;H2LYI*q}-_k?SF6u#+aItZ4fz$$+`kceSVSZi<4UPYCibot4wgBqz2pBYsW zQ$$}b|L;s(q{gk!7u&u4b2~Nwf9XE;FRKEHZS=VHmyU=4z-Yl%I#ASXz$}gPpZgWS z^NQX4fgr=jIY2=Zjhp<#ny8xP?y_DoEtkbfq0Fc%G?S^d;xaYf{h?C_nO$65-07@o z2|9NbYDz2GHMe?;iX?P|q{zBb+swF553#4VfLmr}m(Me23o02mJ>vqy|XyPMo!*E_`< z5=bBOSCy+c?;hL96x9gC-`iX>JJ3-`c&Q^~eHtL57l!i`NRnRXHh5+~WMlKDt>a0+ zc|k&!WR(7A6B83VeU;Wg*n~#+>4EGRO_u7{WD2Oc&y1rus}2CE4v|YxJ~a?CZASPp}D|z(b~^ z_4YqsoLh@0y(FJAys}YEI%b+f+LReOSKAIV5EhTVdb8|za@xho zi1dL3jqrg#*MX3r-08nb(4N$;_5PSK(oi0qT4l^tgNbn61-7sWDLA^m*=h$jOYBe0 z_jlI;N&MS4Vq#)xkO&TkjQ7baf;kcGov9%QRT~lWgh54OZh9!`7RzRQj2-!T_TAek z<%y|vXYr4I5fogtI3_TM2Ng}K@Bf!d8oVK$i<-+oG}-3nro4>}69exw!Yi~P)n{K2 zieWHg+060EZsg91_9~p|4l#+xQ)yCc-+6jO%KR2#Y0=P?HSysV>}EBj zPKaQ)1;Kp{QDc$4SS3TVP@M>)2jfRj(E0myfPDbMmWCByT$CWCOm{f4}=AUm2jqcr|<@xWUp6kv|zw&X!*HQLrJo&*s4 zi9m`GK&`_7H}*Mv-$u$Wvi~F={%1Jkr;z^Zr}$#eXi5T^4k=qhFK81$Z+hziN&Cq` zZYMD90zn&#*kpU+UfbVbld3I1J91r`O)ewhWD>81Mn8YOWll82byjuA8M4WDFG9fC z7?yA8nQHpDokg^r=W(WCz)5w@=A59h&huD&Q$2z|CD+@#KNW~WzJZJD%fHUn*oBiB zQYD!b{!OsL>(iCbz(Ypsu10b?9xS$adQ#KVJ2>KBvXP+msaB$kD0E3fzxTInIbp+U zQG72ELvMfdoefi~*6JnL-sUBy3$Abjl9AG~f<{-=jMOhO#KYNPjE0qzl3AATXYk%; z@43-RarrO!(pnn{GuDBnkF7`1n87VT{q>;h~HeiDM=C-ahz{ zY%=r(Sbg9)mEQh!oUC-^SG)k(X<^7}zdIcUq1a#O57B%fp8Xt;?fV5WwECM@1@%JY>Lm2K?iSD;zXFB_#9oopy#8sctQ}KYrp#xE93aIlILANg|#HWuzkQg~z zWvW3qc$Ew|XWf7#q`2X}*Q%O1p#FfS!M>jN5HNA2b89#b{v%f2kxV{O058a2_-W6qcW?7NuZ# z&Vn5Bb7<|u9;hnXK=5&LIs5_=T#9AJDi{~{DJ{uIN4oMjSO9-ywYLl6K${t~0q=aj zB^3>^tMmUlObYzlk5G0z*58YrAR4GheS0YcVPfd_XTlc%b=%`MOB|-On6yNb8r@CU zde#&C^e^NgF&EWh+@SuaVomQ1F*9B`qlcl_yNU}oL`wB`5K18;xcNgvS>EbUHVSb} z$UYd^a;7TZf-t}ad-n`KBdB?atq14rl~naXPEHW@&FQ!0R(dkB&ydH|(XPK!@W4;2 z1T70Zx77CY!X+r@zX0O>Q|U5Y@57e$``~h>iUA%JeL*k&)4@wf^+vqj$;*MYL0Wm$ zqefZot=lsy0kU;9S^xBz)P8 z{Z+@DRt#b`7_dr&)<4z!P_Ofr?DS+eziXHxi2d-h7Xw!(2Des^pT&&mNyYZ(oRo~* zd`!EQ&0VAV`X65shQ`?0JM*qNCP3DnQOp;dc*73guA%Q6R)escxP+k44t)Vl!V?~( z_rGGNx0B#V7NoAl_E%lYVT|ObyvWz*0{CoZR?b&1d9nm`_Dr0eem z#?m-uV0pXS=OsB~RJ?8z={o+FXlMX;`Al-0&-1~SkEJQJbs^#>_UFHC*(<5ChYgO1 z)g*GcVClkIh*mqwn1ap^>qFyLX&5KF9y3CqRN6u2V5XImo=zezE`FRxNNL6Z-Qu|% zJp1PH_1G6A&osV!ov>n?$D<5#k{L!C$vK~D#LOwAHK!2M~t7_Ng<0@|5bR0ug0D^QL8o+D`c>~E5(JPQ7+Cb)@a~b6y$n} z0HYS9{pDFnr$DO~LAm@cM8ej=8*EPLad+b!qT1Gp0<)m%>J2B=_|~)e6h64tBtkW7 zRDy4G>~XQom;oC~clI(hz51s|P@dOaXii<<^3xy8QBXX3Qc($jGvr_Xf-~>w$|I8Z zTkbtNZsP&c2cU^Q9$+r`AqzBoG+~6XPV2))M@#F-5Dgtoa$GQWYBvA?{WehU#GW9u zC?an);M8!uS*+yRmOYa-q}NE-eoQh^Ir7;SE&q4MpOJ2o3{RIoWCaE70r=lrFGKIV zhrQ6ENmJHG0s(9e?yms$0mwo{7n|J!%xg_g0q&BqPek)MCVVt@$8##pU|%mv0uxUn zPGw(n@@9Z=*)+=(@@l0)^33Gp(-0xjc%z^^=iy%9&Xq?`%{BXTV>!Jtw}29ZxK#j9 zsd*Ws1%MZ005A1t4$p>{GuOEOVri7`O5IP7WgY5R$|XE)ujpf%Q-vO z75AC7WV0{2Maap^+h4xx5h5N|jr6Bo7{`H5x9_>>>gvK((mq&d0z`^BPN;EUve)*r zp{HA}1eE3VeX_lQJ9v2EZr=1&#g_G>fR+Id3vt%VYs+H0@;#*dX{1X+j%glv|z9dvn$1 zNOS9G*sQX{APcJhsCi;$v<{~qD9sHEG* zbz610Itn;4LGEJ^mOF`mA>N-TW?a-De;(~_bYl3^2v8O%D5{8={UDF#E0I^qe!Qubcu+FC=EB=p>(&jAPv$b z-QD%BeS_yc-#HJz_Zi<9jN$MP*n6*att;o8%P%Iz--$d9G_H(|P|u(Sj6T;@ZIhxj z4-hi2NiWW1jRb?fo}S#xm+_K)`W-RSLDVvKKgHgUpnmI37t~1Fdkv-kfOv> zV^hElMh1&>`K0_?C*_ty2mfB@du&pTj6%~vmL^(TM$Ru3{K$_AX!sS8)*}StY@j&5 zu&}_m^XP?=plXCF<3V%IJr9euk`T)FXt_tbO=mc%`*I3~%3Aar*CG@R3W+_s6Lup? zt|8wCox~d<6Eo)kskgWD`+~s1Fr5Eu9tnlb$0RFqwTmi>io&1;HT|7#xi-q(kl{Ty zV?~SzDoT2tl6R(|MJ-q^LIh}gdXkNom42=zlZ<(Boh%U%~q zaBY>urKD_rnJx|$W-{Kxz_X+xm+)(M{dx^q8y!{12Xy4Exl5rW%Wiq#X>M+AmEt|U zE6*qX{LEf3eR7i5tX{1Ji*1TcEI4W^?S0*~PuWBIo^?vcuq(N{83|Z`-33-+C5brd z`cLS1Y}|i_D7nFN>U?lhlO@9zGk$nV!#OReI4oe{BXfr7bbtf^XbC} z%XH)ThlGLSxOWid5m8g86h<2{o8@cWJFKB4WjVBZK!d5ltX3T!AzvK1`0vy)mbE zdNw@t&)-r^WD`}EG@0Qsi;#!&@HuYNfU6@Qz>ke>1Jxg%JE2r9pVtyDu)Cw?$KSDq zxzVCt%tXd8W}cj7&;O3MUqpc|kAa@lM?YVKFs&y)dK3Cv;@uUYm0>@JY5aFfWFmlw z(|qK4rQ?p30~;*S`l%-t0qSvA0>&N<3Q7t(s=Cj^hYy2evc`!&C^^@?$L4zbLlJY6 znC>s#;sTZO+C4SJ%EDki^0QKM&dN`#H8d({fTTNN{ zebACrVZxgC1sZyNka^X|*fB9F#&0xks-q{AsxLT{TeY&kAgkRwOx+QhN8b%(rA<}Gzt=R&XBRh%b&vPc)X6(32*I&{NR*pS-7rA&lOwY<> zJbgG-{EcN9%SSbr;uv$15qQGXqY%@&we*O5n#2>GFekgN1j&Xk6l9PwNnd76>xNzP zY{|cVNvRbY-?U)YK||p}xpO<`DsqfKSH?$!bJyR_uWnv!KFWjo+E(#cCTXtF>KEVU z^iP_B`W8-pd6*;)hvj2E>fe+pP?K*x!0Cw%Pl$kpIqZ>vswtRnYH1?CH;;di&+{(4ci<8h>+F9NR89IE1M`{^ta zW=74hNcaAo4Z?0pFR_~mKO$8y#Epu2!fUr22T&#;(R^A%jZ$UUMcqV$g(85L1IHO$ z`_>-KOK|ktHAN;C#?8$=M6Yr5wB{Emn^(gW$EBsu4zkpw2Kg#%0|a{4BMFSFx&E$v!do3QQ_HllUSvk40lkF7N~+y#fYL`*gSJb zlw2p!oy@kxVq8E%QZfCddxWPXtyx`HT)>#p*}!cuJ^rf=sztHes#$ATvDF7MA<95oomiQ74g$KM<8tXF@R8)eTOq@}&-%w%%0yu)VK2SCEBJVhRim z-KFqy+y!aoEoZ z&AeCO1_oaExDkE0ePm3enUO_FM1Ob$43Tr{U z&yL8O8@~~5Ap4T{(Mf86s@|32@l`7kgXHIBr@umn{Od^Ndqb}FZp5_y zpiUNTc|R#}n>C6Mf4_*pLw139rT$k-*?DVH;->c(3+UL1|2=k5h0Wc|`zs(1TGGJz zmjiTne~!|wrl^ni!TFlAhdU=qd{SLtAiji*jJ-oLHYtZ}M-0E_=GRG5EzV&cnKjye^&2ZsnqDl56W0}nIzOTgb5m%ELmMeUEpn+U*u1`=X ze%2Lf^5DY;!F-Iyt=AA)kPypua6JN=$~az3WspVuLX<*!r#|2P>@OZ2W|V`BebnWL zgv6vb5J3@V_%)D^6<0{kkB95|JE-*2lBT^RnFF|z zQ@WV1U*lIXYOm3+Ri6ofTxp}shYUTODz1+b1(uQ-_pxrh2*RQziN(>oHAN_IwMP(?H z_L7MjvH?R3M3b!8f*qb7tr>v^PrW`Duyqe|2tYH5g=))J7a^Fo_@xibQOia~GywO) z+EqF!8vWMQ&ru(_0*ClRU%a=D``Bh#wz)5}y;u2$aW+@_mNG zWz=ir6Vx8EzbTf=!SHI?s@70W?gsW9u1*=2NwfCQMkTEh!;)U0sx%NW4TMF`Q&{Oj5n@wr9?S&npSUknMW)i#%4vE`r3JY zTc9bA=b_m)8IBs8Bh$3^UC0j2s4lTX1lyN75~+X&qD$hT6O-ZGVs`(XrI{(j48m7S zd;9MhiZ>DN_{^J)bq=`H$}vW>pCimPq?wczs&QM4oV`sZ7QSoGb~X3=lnfbK)r$B< zs?_Rz00rhspCzKh(Jn5SQBFp%8l<@#?J^#5uZ)%x`#imcUI#wci}Ex5 zOfZkKD+riN?W=C}X&Vnv?znI?x%+Lsu1t`pu>a*6 zN7y1lSnbS0qFv{X?|__<6j_VGam(+>85Lnz^{D|l z`GL^L4(AfXDp~llGE={6)9p$n6)tE!*WRZ;dFX~3Wx$xLu+Xh$pZZlZk2YCVorRY` z0yFq(RMugIXXqW%IQ=l~k4a%iYbmM@x!@hVnbhdd!JZlIC01F*`4-@1h@k|QxSFO_ z?7R!+e2C8b2#PV2e`5^9`pY3ebnO8F9Q|D)&TxT|5FqyUOw!QNB>)D_;^vo50_I5C z`d!DNG7~ZpVbOU^C-J^u6}gSj7azZ6$xD7NOZf2Hlzrf6!R_HdUNfkKx#VL$C+u-d zNkl{>3)~_mpSbT~xlHULtdn_;JHMTDPGVEIZ^hj@wR>roTAJ0;( z<`dEAAf+}RG9umf?T0;ggnG}UXqWB8qUGuFL49bq(G#FmkoxD(D>I@jemsB@c9gQ1 zqnWJWEEce~r5=M;vEeUKcPS_!gJnbf6Ro;+N*zn)E5%r2C^ z%btEeT7!K$08&1g2pZr7^AC>|= z8GiYb^Y}f6iY;W8i{ZQZ_G?`ieoCyUH7%Fz`1y@`e10T3mD-9#n7&oaA-nv8$9E_&~k>k%#!2?B(_$4VYgD|J~n>-kP z4ZE`}OyEugQG@TIOlH+xpjC0C9UaTcxC>XW;WMKCT8*g3@(&%=t3?NU!M9blMNS| zhyg7HnGaX7SWdImM?f8fDP?a02l9Dq1@O_BH!M-wbDlUP0(f8IwYQPQI{nUT zf_eFTv8zzL9lC5ax+VekJRN{qd4#zNVLo*>p3z#V%l@y~rkWjgdpM627PbQPdx)hS z<((^yceva0qr!<)YiKFy0uQ$xn%YH zqcEM2Fld~tkVB}SKi2|!eFJ}6;s4=-nv?1t>o#@*Fr97q1v0j8hT>(6;NXTP+ioF! zz_oKQ_%O}fANo=H)WxA0J8Vvuv}>WzOZmF2R+MK?Vo}dLUDelspe(d)Lv#)6*eDvP zuNR3+k**FrM>KAbi9$8+QG?;+*1t3Ae!$oOjuL7?QjiDX0IHRwlvEOg?*qDpxB|3h z!8$TOS9emzV%r1{=iBCd+ih(kW(Y4hS2#~9)Oy=XSd=ITQIMHX-xkg{Fqm88BaDL} zRj{@VaRfLoIRbeXS#q+rIr}+C2N_pj!SpQ$o&jmm4|AB?5OH0wS zpXdbKXMhtap_k;GcYG-Scai>!oR6xis^W_mX?2AcuvJD}41Q$R*12sW+jMJf_QVtT z?=I{Rr}@Op9m!kSZ>^}ZrD8cg?-=IB)SD&2P9$nn}by#fjRQqduZIw^GchR^{ zhR)rpmWti%^1TJzEt5MA@KZ!DqXxbd>BI}BuL$|M_f=aAv&T(ZlbKlrYba4z z_WXz_c3RIH8OMR*`?p%biDP(wF#-OMgi}x-LTSjS!lG>kcPCPX|=ol zdkB-w^3OvtJHo{cTuXg^s9RJDMt!WFuZ8>bMfJ+^{hV)gjhHFR_;a_efETgiC# zh|~|CGOW{{5(2UiUd;N=WpMr#eq7qsHj03vvK(5 zwO^012t`I@__z;;V~u)bNL$Qx{wP`odd+6AZ?_h5)} zXWHj^?N3E$?O88b`@E$um2TyBD-bA!t_o^wSxz8uO^nF8W=y)!r;B;sM zkW7=y+hFNV2@328c1N}}bM*q*VJDcX6byoVCmywv>3YLLF)JeHI$#J{wJ5!Qt3;03k1}+85=>A&|7i zMt(xs$M*5}OsQl}vLhr315kP76P$p(?+P5jc@psdbOcCbzva|{B$M9j`8^tliaRqm z*MGA%1QR(wwV(EVN4Bvr!&E!1IFDm|psT$_a3qH{1m3b#uwpHuxq>o=9;dx6N|Up9 zj`nz=Ik;jlCSJ zPE9L-Q+V6D2s^sMBCPxm<3af3v?nTwCq|q$Ay%)<`2pKhpqYHd2rVx0Ws55-loK0ffN#HnAg048WeP%xp{jcv$wZ%3QQ(>Woa}NNj1Zqx;Fz*hSDg z-?i+%|5Sn*tf;5Q;ljCVb-n&j;}?Ws*uBKHB9WEJ!!H`L_PU@;85|Up*edjg#p9

~99yuN!_|z8Xl)mJ#qIL} zfmcyO;~U}=LEFek^oMSWWpCzavC#(n2FM&+G^5h zWK;ETP7E}x-Q913lcV-DWIPp7!0xl-D~CeXlz2%h>5en100$RJgVvRdN}P@ovYuXK zY+E8L&K4?sfo*H_4y1&TZ4sGUaK#^XEX>fvfm?0m@c6{~%vDS)R=_1KWo+i59gyQN z=GJf*BnP&Pg{rsJaqdAJq~FD7J4pw$ zpqZ|P78j?UClzq~2c=A46F8|av+PdRLc|0<)U_jSFyEjDAYb`OC0y;tefilIXRwM1 z>0s;$Z8e|!?bUcwzaen~}=)1=#=pKf22&(bl1LtdS z`{Z4e3bY3=FSY%#^pN0SSx_!zk;5nJ^?4?zBHYU-I>D@R+vmrPf_dr_`m|!#BQ)dg zB#fN}2i^vb{Rls63wY2JAusXk<_U6l*RNM1y{XPyHL}9-(`rz_BDgGI#d8}2)xNkw zlm5l)_qeUzL9-Tz=e;*9wN_`N?jAMcZg-Zg_Oh%-8QUxu#ca=zxh%Bvu32JmtEuNgb9OLT1YhEpL70=E05?;yiK`DfGDSk12|RYu|2 zGfxi5Arl!Vj>j|?0R9_58suOhal89dgJS6+-QgA!QTnfTQQ@AL5!KfPMsNF5EfOSw zP?)Mcv8hbz_a2;*a(`z~Ed!^gB8<#{DAZHkTUx4cgP>j{(*NA3K(aB6iR{WNds+8h z&egTbf%>Id_i(yRi%B(y-Ayunmx0`fw-94}FTnY5elfnqtZC10YBf0uEw;<-cDv1x zi|BO`;j(Kd1&!=|?4Macf@$d(O@x)@LJ1axS|gPBT*YMu++U3bVV1soT(%(F{*hhu z)byG6S;|MgoB6>C<~nh19`5Ry%=uVlsB+HgiDTfU>wr}s~GV@x7zz{pY_ZqQ&H(XOSu+#k;%aJK$m>R12P2NU$E zlIuCeQKX-1gNp%5oP>OtMG>_^z`{z&*ik;H#)Gs^eMB`1#S6z36<|zy8VlfId8RU| z9I3atG$(?2sL7unLb0r)nV!9Kw;YTh5|ff1NX8P=&!KZ&^{Z$Dmx4@)=w4EKf)9o< zJbL5@l%tgD0O5P6+&()pbfb0|i`sx=#>qUXxSH?To5;$DP_fv=>b*~?ZQMsTM_iAG zFJe%;dGB`bFV)~K*PO`4tLW>%(=`jV@sJ{tGS$@hFPl(^?f}gK{}x%=4kzdNReMhynEIPq%nv`=`LwZ#0lLs79QZ!==hG{^F;2s z!?#i<>&7dedzma|w!>6JyRHA>RUA3voYsXE^9~hBY7x<3;m_I{8vKgkamNN z-!a&{VnZ}~BSFN^aJujt2!%&%6VJ^MPUoRc#qUfA7OTtZtZ@~O_ z=(qG1EEC6smgm;=`jP5)rfNGsqaL4^8eUu~-Kj1YZSYZ;QzR@w#{-EWGK$&eV?^v= zq5WXVLq*`Idm^iexji=5PMI(v!9rYD zp^JsW5x4j|oNVLA;7LSRcDpJO`{+z4T0#^CoZ~R=WzMl#=zDvLQBMj4>1Dsq$r%R7 z%e`!jBLvSoOlG+BR)2kk8xF?{m3dwu$k{taeQk}AHQe0=fyrF0C7h5z1SOPud>lrE zTe>vc-IUGDkGM#}+Ma_P2w;uVjWli%=(MgtJ>wEpKz}nkoR7+yh{Ji()u3;i+Am!; zXH@oNhqH_YBz;Oy(kBwyaXygV-@aj|3|Y+Xj|_YyB+@KM3!v`O1kfR^Z!q}0ZeL_E z&IYt73C(gl&?}piaBs7GMe5hD*x%Xx=awF|ey)%~Z^`E5i*MVxhXK!%Z>M`e@^*O#0x;9;1PRwan=Lg2$y+a(O88@!jL z8x*+gm2E)y)vzU)w(J)Wo&M}?|Z)WVL^=M24;PZgDmaOhTK?|w2F_909%lQBNXhXW;j?>@{bc`(D zC@LsS1yY+_gSQpzdmR+Goar}JNlSDZ0>#b4l|YK%%58%(_nuk>PK7S!6D;ccc97B~ z5PK9Y{(^=w0!+#(F~43GVZ@=$)Z0-|x0S)`a=$lg+yj)Qn?MJg_l2^3#9wwa!|k0i zt=EJn)h6aiaBV(V;;To!&aBAPMT2jJU!yYI)_xZOqvO{20MbY~RFO9V=Y0h(`Cre}mu5kPTi5y02`$qYck0OAu? z2A_0J2wWAx#$RSDgBZypZ`#Tb2swuJ@JJ^(AQ#Jmp`4n|V4fbE&Aco-!|+x3B!HVQ>=Z^{f%O%_eV-gC zJXmQhndl>O;&Kpqha!Lv9(14C&kwPtKVMOJe{_OAivJ%zYGnBJIS^4z=NzJ+ouXI1 z4q9^RI86fnFr}`K-DT2sH(^(f`V%uUBt`@IW@0w|6&3-sh6vh1n!s1bh&U+zN$c5| zAGC$C|FDItW{}Q-X};x5P;juYscQ7Mdlo?15R)t9Snqb5^BPI<{(x24|4nCpn{kgI z0TeW70eOe+=$*qXDnprbCgrjsCpwFFs5vv(WI{qy9G zD!$VS(Z9Gfx%=W1X#h9Lt_&Sm6PaN>A2BKizC3EvXT2y;2Xifg>~?QB8O_9OrQ0sw z#pG+#wDt{L63b6Iq;)2b4viX3NE!6Lozy*}1*-r>N1^1RjwPBZxlRmlxLe;)Dolgkz1=s(<7j$r3AiXoZSy)+(`ZAP^dG0U;t4ghUKD}^kpH&R-B*pn&exe0o{i_{BX3V3N2E*AuP=^Av0r(f6uVYNy;_Ts!p`Q7Z|$dwGT?WJ6iF_uV@H1r zRjvflHRFi3p~6I=UMn@U>FbxaulRZ^hQHBkJQd1w{Z8~LARu*Xt|N27vTWV{Jwbl< z@u`^Ok@g|MVx;SqK;bHXy>89Vh{P=cx%NH4ePD%rbUa}R%ejw^N-;fofM}NegFCAj zHgsd6ORlrMN6jGw-7_%5KI%%^Ch+R8Tvwm;BcJuxvBR9I_E3;Tg`P69n-vO;Hi@g( z0JeCNQ%uT{f?FbkrwQH!_|C7Ga6QqX)9nk;?qI&>!Y$-fo$lhUdm_m#!rC&!dlq(4KyZ}oLR1H8Cz+3nMo{$W z_j5+ zNj!+EtQJ&TaWVW(i<`BNf55W+{JJ`nH@9O<-}hGEJz|)ND(y}VFLn<~9aLa!|ALG{ z1!4>vGOfD^BE2FMlp8#dgJKNnKg5`bVsUBdWWfK(P8XOjun)2pNgdhkn+g)pS zQ^sRiVGT1VtVgM|PbRQiZs7WDIgwA`A7U}PNu0Wey_)nWWECuKA zAJCs{p$1GKpf;8HU_(<*WoF;y8SQ`BnKLrf6Cx(O;?&=n zY)EN}wd#3|gb0L2!y7MP#fXFYhwynx1k?gpxnvBA!~;SBT>3&eE8_-lDTM8nZgmBz zTubiH{du=g1yS28WS=|SKBi!h5Z_^q8laj6ZohL>3HY%BUQ5$BaaFD>Co@iLFHQ9r zxoD7%@I9P6mp?vTcwqVsVIBWanQo1yKrnGITI;g} z!qx>kKTy~iwi+P0<=$43f`XDr{KY;6If$7UqWM+07^hN!*wT2U1f$JW=LW=)3~jiI z{^0>Q0S~0lT+UB`%=et?Rnx&dZ;)ay1jz`*<32f-9Tj|YK^yHM`29^)D7*TU$85YR zIvhPHFc9d#_`7bw$6p*0-v>HF3cBGmpFR(xJ|M(6SIF4FBLF}}f-kc5Rw$kEGatxs z!&wb*q$5~FTwc6-m7uE{9Z7K@(zS|GrdO{BCML4tBZoUyhkQI9-L5?L2_Vamn1ux2=q)r+(Tw@#>qlLkl7G@|n>{{RPin(Ad)9X? zs@vvZsNO_Z1sa6|?u(cEIOLH1Wz(*lPkU)e&45Cls4*BgnhoUqnCuI4?*YvMpa8jm zQw|`O-9U0-J_T-`001@Jm`oLdkRr{<1^e}h$%-+UW@?U)RNt`~IoVzH z52_+z8K+vbr90tn59e*Bn{NPpx!wF(M=*%Yb~8Csm@hdoK*xOrm^`nzYW>c@W}cDM zdVzn1&PXD6;!YB2^Iy8T^V=;@NiBuj`DKwYtBA*y3Tb0F0ru#5v>|p zKuOte=gqD9#rFk2?&q^cHGU!y!X#$2>8&4SdtD@^2#^_f^bqjSvnNh-#H0;xnl|n= z`gk!YJ)1z2jH67G3`~sorU|7H=Hp8Hh-ZhT$frXgj0H;vVm~^mx@-QOWkNAQrXLHurwlgD?|A*M{JMF!h5iUd}YD zr%J2(1y9LYkU#l-?NVKsZ`lIZy1bvck157k=gXQDBV&yii{?Ckk5mwjWpGCXpjj1JJ-uDP@p5V0ykTr&Vq|G4YnsP?^&M9Yt31ir z!L_al={H3uxF+*EzJ6LxW<6>WO41)(tge#4Sg?DgZ`70+eoP{HlEnvz53fa;Y9$A- zs8tO!kV2v`^bQMo4)}mzuXbvlr-!;P`ZWw7FiL>pUq=I0LPD7NxjT|gIMV9{yb5`; z>=$#yF_fP9TbfK~E;9~v@JPa2IAbU5(XOj1TI%hVEigT!n1VpESxfw8*~ib3rV^fp zU(+bv1l_72EMS%rm4cEoAm4x5krwmgjd{QSM0op=NH zQYm7=QXM{cY`K*0nXC!6LbGZ;3t;Yh4X#Q$p*oYnq+p%9X2UCF=rQ~#E-o&L+S>Qx z9<#9gX|uRJF#ke#f9BrRto;xtgN3Euo}aZd?g}-AWnG2UKHcmG)Hgc{#Yj zuzR-k`8cwgn$i(cqNY!*XR+AX*?o&lLh=@z)>H}JcYKp=qTjq4HB?k3rrv`dSe6p@ zAd7hF6@Ktez+*NxVIZ!t%@b@@iw0IEvNJFEen^JO^Z-TbJ?q;n#7e&dqp%xV+cxv^ z%k;)79LiGae|&53BQ_bX!$TEB`ukI(i4rAlcYHGSN<@$92Z@ZUzAGb1kxWRc6=#?f zFE6)9>s|g7aJ_^1MC9?!#kcp-qFUr-P_nx>GHuPCEX8@xgm}0bx+9?n-$iam0s3>< z_Ak-7LdNz?RzB9YPxf|oJ>|=#40C?edqDjt^-*zgF{EdGtl82*gPbZ~O(Ofu3mF~! z`o)iXAksLi*70(}3)=`@deyvolcvhpPs7>{n?zV#6E#Ew&gZ>S5g%o9hcx`SxOxbM&xc1cz8j#C{YSIN`I@F0=9F zlJFN7uj}@z6i2Bd8lcYPlM)0Ty%@TWL^hm3r7U}t|rwb@4!0@r4$wzolqI8j!P^= z#-j5o3f2$-*Id*ry0wHj`CZ#zi^HNOlUiPEMmI-D9=HZ)YnD?{y_$Zg&&$huvMMS7 zBE^jtfdp71_*ja55=d(Fbgp+az%@S-%(4u(k>_&^=ZygLt)Ae+k++Jj0En35HnXgp z6Krf+PnrC8{FXXgHE9>EX1eT2GBji#S|pSfUB&7|LdHh9Ma)kA(D2WBgb;a%7G=X4 zwJ#Ro7FGI9z4$Yuc9j&^Izod+uQ~v1UO3!Y8sq56?#We9L1l`&ouMP0jz8IN$q^?dF9vCuOv+jL8J8m9v$53JN@$f=}fr@SYp zi_|tdnH@$}uRL26XdPc3$nd{D+wVt`{^TZ>{_(2f9wkeHM)%hRlZFz*NJBoi^Bt3+ zwwYh_?1*<7<4&L=5Q+xz2R<2pI14r z*kv?Mnl+`rX~PL2+4T~1M`~<9`kcUtuyERxUMrO;+0s`1d(=NtB ziH@*Qo8#lj8a+MMpzQ_X^qQi`GmWI5n~@7<_6s$>xQ0CeoIW@l2RP-sdpfJs_pS*P zqU&h%)&_@vebfQ&q-zKcrh6W|R3%&EYv$zSR2edV?b@{p({vF(A~{V>GImZ*1tB4! zEM8qR6;unXflv3bMpArhwH3iZSG1Zp0E{O?z<3e?2VOK@KTBryGUp#s;W9p!54}W6@ z22ND2w}`~m7l-Nixz+SYaQRf>FQr?`W}#(#H^ayN^BpzV8eLg}#;T7lq$n;IU5*0d z*|W`#yCb~$bAb^Kvk`;5`L0_B^WTQIzOj$*9MQkPHOXEvG&{l*Xd&QoJ?7d07i0aL zggQl`p(%Vpf=E&PPN7AngMUmT!@|UXT&PEQJU03Va1a{6g$qFd>V}HODhHe|O?zCl z*-(Km;M_~wf$THkF27@VO9F+0#$&kMYUbvlg0e-GV5RPql1Cy&omNwV!;1pb@9 zLzS)Sxjt1m)vCK_IP)nn9oAIRZjw&~A^jGKHKb3M)jL}etoe!WGMJ^Hgvx|{7qb|` z+5_)c3d$3ZxCMih@(xNTg->LZe`7UZB!C1*hYPv}1c++%H;YM9+HVLNn;UN)TDu-d z5F|G}3}5^mdrRnv_}g%+)#@h2)tC*U*H&hUebp!X$P(t5S`eubucqu4dUA82oZcB= zAWXCAEyXC_sMvm>GZ_k=rvWae17wsWkiT^Ut{*5fre%W)BY14-%tlJOEF(igL_p>t zDsUU$e~#2p>L*_8lbODLei;VtD=^Iz+4f2Wm!Yfj9t1EC*=M9GC@+XLjb6kmLyrpD zQOj>Y2ajSir5}O*HgtI+p!z`^17Lw~z!|w?oW}vQl@i}fHAY0;<$L>ug@r{*FPgun z3xnDMIW;%-Tgu5OlWaSG{Mma_g z$plw;i#qQ$k&O*cHjUgviWv}@`% zv1kl$!DZ8u&}~1(ZP1h#Rki1TnSn{gTCGDngByM46ULAy(o4;PFm%O1C;?|0Rpq!1 zS<9`23JD2ed-LjubVw>BnkI2{JV|??@}NetAZb}{YrdnnGgDnx zTCbh6x4}TZWhT>T{d+Y_U#UJ%8ME_`X=6%OV470BK;i@QI$%y4E+t_ez=h&cb z?`mb&lv;`2<17r(=sJ5-Hk%SAZL8L(-uaU~&6^j__a&Yj9hkS5`%RCOjAd}u?ML@; z9wB1rEg1jlEmE?wK7)ydbUWbAN`m$pYsetCb=oeHw06Xr{fErEjHwYFL|ntRPX?u` zzl$@Q-e#=tWY?~m`?XhkDi$1C*_XBzQUjlN{`!>L2RIU(!u7#4$nI&KZ!apwD1nol zbooifjFo=*k^%(XTV&I-v)!N#@d?~>N>&M|JIiYB&)r6{`n5?7PqfQ!_Z80J8$CZU zH#i;o<}<(flwCAB`yElu?LdxSD(o#!$!VZ(uf4h3i1_yF<-t5+XwbKF{KL0*=!5SK zjuC?K3!IBM_UNCxHG1&1G(o=74s zIHZ;fBxw9$0Q3JGTwlkrX(w%Hkw~h*@?c`}d-#TWWcjSX?TS4thVLup11kcfaC3`8 zFV-i9Qg=_PUMI7D*JR6z{aEWFeU0%!tsv6Ut6OpJC*(s;K-o$0;X$MnvwnLMz{^NAYX<<^yJLToVQ>yQ>k|wdX)|_3oXNGa_OL2L&vd+}qUSXX)*flbc zTk3kw~*L8So=D(yT0ziNqxGq&n&#w7S2ESm|-lGH39?zdL-S2*h+iZ@l z;gfMsbREyd!jflv8>XL|Cx;5XwQ0YCcfA${_IKb0TAv4EeLVw3wmFo+`m%nwe0`5O zzzyb!3q7fD9&if+HFQOD3QH#I5Sf%@%iSGrtd*>k*%Yd|XlZUQ^OSV%e8cBM%mz-{ z$f+bv#N8=Lq7nt1YMu%GYA-pG=j z?mC#CKb!^G>b*4GuX|x|8jvXbhTB(=UBc@X$GdTbQJ}6Xk{o)K^pe z(#*bpoJgj|yEJI3O`DF$a5HFEMa{NHla?ay&!=xVU-73U`IET&XLw%YimV00h|Eun zm4GIrU4Mn4G1terQ5xecR_Y@|B9N_iCRvqjhX3pEr+(H z=tpf068br4P(3X1K~e`R`*DQGv=r8dK1g6fJLvEaJ7};~i^Pu^?#fd zH01+#sNFnE>lS8_9a4%1{m0+DceP9@Kh2jKKShB>>aVOHNqdP>Wgzk`n~eW$zE#*f z*xT19XKb92E>u1;WrGNJMpe2kY@HS?m{d=Uu5%bQR68g8c2D6~uv7C-Y=<%UvXS$L z7BsDWj@s{Z;4z-7qD%F+Go~}>Y-2N<)@YfJUg*QU{?uI(Bm!X?Z1?hYV6A@}JJ0a`0GK=!s$$)KU5s zgMtSPn*0?D$f+fgEi_A6)Sn!+1C|%Cw>c*l9KhPrKx_LXmH;=T|6DS=fGyxd)mG ziTKLh?r6P4Ik2AY|FoVdtfN!Y{-2MAmkY?{_JZ2Bhi_YVruWa8S)}al<9nH>DYCU4YDpt0W<;h|n5zVv@p5t^8eti5SzX-NRr zdYN1!c%2<`)M9AV;2hLPHr&w})wn9EdXzjF+xY>_oc$_%#7k;OeZlJ5s8o+=d&5sE zFLHc&@VOFSgEtaePQiWlB$YOfOpqf=xZDw`>Q1fPO>Jxx1=8Mm`hv*2WoP?Zj&GIX z#g9#FDyivPi;Kp$f%bU%FY|~$9|sGpwL_Y6My|lryg*P>xF`lU z4bOhpo`4H=WuHFf0!xa8rc@<^h^ZUw_)4MBv%3G`Sq6V=z-zJqssOG7W!|)tnr6KF zyiHpAu8=h@*MdFQ&P7?%tL5|#is>mVZV`=J*yyqcUhf>U!J;}gyi$!vBwzGF;gvj4 z^3{9!sZcdw1=rfD{eDc%&DKqfww zcIJOIIPx?;9p)63RWPBd5K;We?(spHy>cg1qdsLE*_rmoZ#lkEQ#KzU`+7+Us=)#8 zcd&>P3a`kQhu3fU4&b)Od2qoY+qEyDp`w8F!U{hAE$`$s!vx!(eByaSXDYohj*o#( zF&rnsO1NP?UkYBPuW77M(}TAv zrFvu{v~z+tePA3Rr3M8-(mg7(<-|_Y{q5=X>MML{aW&Dv((EaJ&mvaf_4jtu|3lha zhef%yZQ~{erJ^9Mq=1CdASE3G5`qq;0@9&$gD6N#=g&_=XGA^g{}gR8876}D7XdwPo5>Ap{dykAkX0H zp$iM|ugp($d}R-g9O>-7{Q8$~<+u7s+kFw4O{191&LY>|Ey4?%m9c|1D=@lt+2z6c zS6YE!Y1fuA>=pQtDf~qy9c=#SA2#39xI6X};&y;hx4G1j$;130or;bWnYFm&IYw2Z zgKjYVwXBlWx%BZ-KvhOi(Spkd@VIsmPnXudCA}fp{Uy{oIiBb7O4A3sa`At#@?#*k ziUL|n2Ir)urB}Xkw_SFwVp^jeQ6$c1%^uU(oX8ra(`C{*T$8Bmk znAT@Aa)0K&*#5O9q;GR)fx*kZL+>_#2?2OkV`toF0)b}_{$M`)K^^QlNNP<89u1a1 z(YV`9T7Wr`OluvhxIe<}$rY?2Hk5HmFJbkZu4s0nM!vC-3svjL8Rnr=$^saMpF`(C z)J)ys?}or`m@c1Pdo3Fr_2{3D8d;r|$V67EpEg83tdT{sJ?HbnuIbbw=Du0^ImzC{ z{;6AFNf%d1#Bh1~gRru|CVS!D#gJ#3dGoI{6R^iy_a7W@<3PeJ1tld5OVdsdzqu@? zZ@X`cGiP+lLcIZ9vWa4ls4LDXoF}vwM7pd8<$oF-CnR6D=q{f_j*ImC|5qa&gsgCP-D|eZPSx)QDkH zaPoV)5NGt-vBl2rgS@#`MSf7U=2u7F8=1Shx2(*9f;xdA>o?!Ry`I0p@K*VN3K--3 zV#Ze1+v=dR_-9w&ve!|T-tFj1ZhaDx%g7Wmt4-atI6-6ZmL(=1`Mzwg`EwQXF=r~} zs#v%BylIo((fO{yE-CmcY{<-OOsdRRaa?+s8Ejv)>2_MQK*{ed9R z+Vc9%n_zE9WHlf#Fu0nUWc8BK%4(h1V}kkmMk}7#AIkJ2(_6Hv@HI{P#iXCB(L(DE zE_$x6x=(KhBsK7#J^^yrNAI%fI`3fPoAY52yTVX>!|i>z0dYxyMzw>QRj~KPOP4yh z+in?5%*P58TM;6*+cF#59g-JdW&9;|g;wpcw`O~?da@m1-=7F*QONm$o7G@LLez@8 zThGwaU8RuUAUQl~Z*ln@kKcIpkKa&oyT7%cy;=4qDAjVC4zXaF!?mRCX&aBkfpN(7k-Gfp6;C&3*}Ys5T|A z-1Wb)67ekyu~}thmPyvzC;-9&2|Ya;pbA268Fs{54oWxW`}c5hM}#N)wGIdeS7ACd zvFDw$1XJi_z(gx?vRbVUC&y& zM{z6r-}+(WVeTkkN_$If`lHwWeJHw@{_bw~2D=y9V|Q}zK~M-CZ#U1m`7ojR4xuU!(K@3Of~{TT^$Abhu39QoCiv25I;pm`h~EcMklj+Q&I%F)8??RkSKcoo|EXSXeOW4df?OHGvy zu$<1X{xH-mMltbdmRR*3li=7Rn-5J=XXE5Zz$Gvpqh8N~wv-iOpQ4lt#rJm(HzjKY zPlyGEoTm{e=jF$)1g(}Ar~8Lf9H(jrlrn2Xt*gXuAt`fpzNhqYheK|2S#^aS1i|(*e}x(#kiSnxQI3OPsW1r*B70=6-0rXI1l&viU%}%CgKf z_7S;sbeVzJtw0Sp;;YEX|?l z)BEsu@Z+HYpc_sd=j;eCl6Aig#ddq^OIkTb)&ul*BW_7~Em@3bRL(J4rzSpoRP$|m z{QwFTol`yfUm(gYG<*w3vsl!T(2NQ?A%S^A^h(sG$M#?~efNrQ<(SGIr{#~EK6x|y z0=l;7FCOzHc;?d@V;Sn=8SU3J0AeP|c+ET?`!eni*}<)$Yy0f*yaHTXk?$Hf9N|2* z&XWd<{)+t9^`hF^a7+omfs!Q?wP%0>LvXr;!BVz%GF%;z|1~>xJO>2$`rX$~9lZfo zY`7C3fX$jBUg`+dkwE9E{-^Uq11hMQi3t~8vFo}OPy^*#3X=nw%uKasPI~PHv$hUJ z*Q(g~nb0ny5s}D8B-%>$wKw|_%H4sYKko)VJ$H`Y%U+cr^Cdktg!liPxr}pvhokh+ znKCD$_`6K4Uk7%{x>63shF|rl+MZ;CMbgAPFykNJxZNM=Vk*AQUqMk@VpI2t@~6%m z=*Tz&cE@HWev)xna;qr|5WUMrBW>HRr+?Ld4~lUTSOH!!M$2PYXv&2x6Uo zjvm#nRJGW@kp5L`tmuoHX=dST!Ns}4Eob)9)$hL z8y&;SSv8p);mP8|YFP*ym-&{<=mN;T?0rF^ix)>sSshzuLOVxq2x+m($p(P9OfHP* zEiLvLoJ9I%TW3O+^}^wnb@g{Kh4Od@P5wZkfnQjt#)pwJSsNtNGn4Tg$We{NuW9!^ zx2f+gu%%~ST87!@k>8S;RydCNufi0-Z8rrR$VPDxc*@?rdsjwO%|8T`#*|rtchKbU zJC6RQ0%AK`sxEKMGL~;tNS2&384_mu9d1AQ^{Xq(+!M~_e1lM)@^O(Q-U&JYB|gfK zJJl14O>~Z-CA-ShpkVZm0U8b*-lmp2dGe$N2)%xJn;uQaunjDRKc)5Brkq7>{b2jl z9>s5Aj?XG0PjZu)oXOtazEvF#Yk}E)ns)?%%XY$ikPPr2Cjf90bY$X6CDtOSpG$i= zg@i0D(cyu?ed~0DRj0BbCYhZ3arQ*hn~yF&0o2$w^E5aQQQk*fa%=k20d+XV||%{D@EvV;nXe{B*wP=NMc6f)&L+?ZnF` z0$)mm6JC?Ke^)YxyUnlmUK8a=0&RV4K8lEXC!6n z3ONV&KRE~TTTWcmLUx}oe_n1AQz5?f(+hk9#B-{&{6fYv_tw~}$(~@KRxZo6>T4PZ zUOJVCtqZb4+e@2FeGkpc_Rr=>>a2Qo) z{hr4jMgyL7Pl;ct(tAujUdUoDw{!K;6YJG$$B&u8EumesFkY!4$G?IZACjIxkbrl`ZK5EGf-*l3AvQ zb6oDe8`(0j$CW@?jt-<=J^lPPFl*OVCM>au6GJ{i8KVkqnCS2gn_Hr)5>Ud4I%2uG zxp{pB83?lHi*Igj?)@?k<^heg=QN(&416ryBRrrVy>^kXeDYEM#1$_BWr34N&cLL= zZMxV%Uc`-c9WSm&&Df*>*I|r*xa%nSO(rAvkpq;Utt}UN+Pvou5>B@2+w@Oz30qeB zJwI*#u=;4s+1|0CWW1Yl!?`P0CAY1V`tEn4tdN-$4l3aOeSKI*valCvgTkK`8{e4z z;R=_qdtF?M_E4hh}=0&6!fe$;Rlbd}x23j?z}!Q>vUrBQ|QBpZslaf03N zN{-382M~r$PnJ$?Jl@C_Te79_>sT!8TY9Qj$ShFk+$%b8ivu!(aQ?YzCKK%np)@3a z2vgw+jEd2aKyk3d;6Y{woiYeO99S{E`6X(h_ePi#8$F8R*BqOk5M>@9?%YEi{!G0> z^EWC@>8I6X76U^kUd-{o=Y*8V>^mqg%{5~mk|CneqPrM`T)uxqnq_I6pGR}*TM;}0 z-9jjrRWs-l_M$7zhpkg4Wvk*VbAocRcn!j{2a@(stM$|Vk1E~O_sf5kg_Tk^Z0e_86ulN&$+{_AHyZdHH@R_-LzsySG= za?RxS;JM6(7#f#V=?#i^+44q$R^iKaDNhVp*z`m5fzj0fprE@D1`NxM&X2+i zxR*{nCmsiftZ3>Vui*9T836%->-47dEG#UkC-F(84DU?$b1;k9j#wgV1M+gS>U5KD z2Qycpz4;yDXLV?^xbK!5p{nAosBM@5%G7Y*$18&JiXpuMc;!-0w&#_wcE%$!MdmoP zdcvPpCl_(yxvQl`>C;Y=p8)1AhY=e;vhKJ(yS>1d9$1M_HscCx^!f3Wy4_z@D{b^D zm+hsng*E#g%!@coJq8r|R^Kjbv$1Wh8Std^9yyVyWcaEO#E#N$KD#bzVZUT}TE9XK z`jWywe#vid^6?*ULag-&-AZWZ-qEHM^I~7N46VVtHRcYh@>mv5!}keVIPRRNY)wT* ztFpWRR|=_P6bNh_;R^{TQCl$s#c0S11zoeML*Sr+{EJ;CSS$1gXrSZ($xYwNDk=(R zQclb^u3vHo6bSacx^WQ>{Nz`zN${#quI`BkI3{2AFSo@l+B@*2?&q?z&p!AzegIbJ z>~X>l958?Tq5>)w0v0z9rx!fV4Xz*MB7CsEFcgVESh7Ym^CVfP&@+o>BuBTTd0SIu zp0tm-oTtl)zyEXIZzgbDjBgh83G=jeow}3rgk#POm-DJoFM7APMe1FSq(U~qKbaRU za{miPO}srHh)BT@6Eli;g$AEMD`<-bse+7f%m0Cn+|(H=+$Cr+{b4o1W-x2o;;5D= zkttTQ;ffx&i^&v`K5lj28b!#HDgs}xmtchA+VAZ4-nS)%|BIZZRi+A{_w`My=>GoM zctRFk97w-DJ6`+R#U%v;E&<$URaaTP0dP*IB8KfYas#bn(1azQFqLb2U3L%4^``gc zJst$SxW7&rh`YhQU;!wc(Cm7V?9~ksic=&D5nIIz?`SE}b zC#t)%6vdaMhqBe9) z41-$BqP{iTqCpqLsuHQqezD{cX5_-qX3{QkyRM#PFeb&3>x72)e@aZYho)FS)4&Xl z^qXeAW?ht^OIP*sA8a`8j`z~aWgUh2@bkbv%q$c8qB}&Us^a&G7{faA_Tn2O3CN@$=0uV6<+A*)-AZrDN^#}prr^l!e5+vIOCl?|E?Xj#M>e>Wx>sF-$w=HwL%xsl;xQvFTo=KGy;Uqbb6m1Nkr zf75hu)WhGkR5`l4{F!9ly^&Xae9vjzuoEDiJnlvwuDkp!>u6|fnsO6!>mT8bk{FzH6eTy|!M*jrG}_LTT0CYV&oBb>=l`RU_SX~fyuTtIz=iyWWY z!`0rB9F1(T@ZujHi^2Go;~n=CkWM8E#UnzwR7P{9liJifjW@sK&f+(LnwL}SqOhTX z;mGwb$s(qarv9+DkDa=X@gs&=QRd!n0fj3?*RM>NlQA?fG%HbpAKjIBpNGLRw&&xf zH>o|CcLsIctP;d-JL+y{^xm>n>6tobQxpw`Hfw=s>)oF|t=MvauX9)-%M%D#XV=#1 zwFS6Wfwzj3`dd<78|&-{w6&)W(nF%itn8BV#r zq&1HuQcnVMJbsE}dnVS12%Ym*xC@<&@*fvJ2r-4)a6}n;PQ=ETF+S$Q8_xK_QinMS zUHyG)1)5H&u0fAkOct?_31)1q>|0#Wv9IERN1xp;E&#m|^&tY;M7S&|@_JfXAyhMv z_yfB2?P~&mC_rU`TeFnnZUem#uBA?Y5_&u}CB@<<%dazw?Tg$=8G?#%*kp;PQU+T- zPhC@M7swk>mya;;_(MVibg{=5q_APbQAN5+N{AtT{|`mEV2D0u3OKwn(}2#E0XktR zotr*xdV0uYEq-3L>6bgYMEkL1eGHb**3{d9Z#8{hcZXHDXP@7r$=*g!3#^88M?a>-deN>x*A;ez22<3p^12*Prp&kdghLuX$@hG66 zSc>4eYJ0)nPSB~UP%zWh&rqS)$8&noP;a=24NEHqN_c zQH+$6S}UH3c@-EV`g}%EK$*EcFr)$?xJd4q$MNypfxa1p+$F!Fy-90SCE_lD3(uCl zy`YZ02(`Q^8W5D5q;dGw3oDaXQON@0DzQRSc!@;aG${u!TOD1od@(upI{^UdtTgS0#ToW3DW8DT z!0LduM-@k06_NhL-PaIS;&ylyG4O3LpKMdpJej?DjWv#kPT3`HtG|z6k zezzNa95$q6Im@Aw;<}}KdvV_Rlg97?2SWY+mAEp}g{+C^7xQ7M()su9m_S3`kIhiq z;T{8#REk;@bp6!-aQ#a9Dr}i2r>5eCEG;a6V)C*)gZl9@rODcxaQKapT$IS1z>rh| zU=8Eze~T{e%9ibKpiW8T^b3D%g~b@GWeOM#~eEdXMZ24fmac!;en z{0%L#OeAyyhJQK%7HlHB zhF@j;HCEz{Rz8u_IqIRI41`7hPlxNPFGG1ZU32#{SCV(bWDYyI=WtYRY- zf3aASiMlU$D0A@gmrSodUAL~zY(<=2a$tm5Ropn5=HGA%=*)lD{)C`T4vhCH8m^_i z3l)Kl?v+0Zp=Y$(s2@yMu2Z)Z&>WWLAtk)dM(EwyHWKA zyJ5_2KdaGS{v^F)G?GQ#1WaC+5q z)xQa$HFf-LaTMFYv3eXy6?z1W*2`3)Y+U*FB!l0Kbp{k%A6~Zt{Ulp!^NRf=BCBov zCFZ6;Y|e!*#d=<~48yhzvn<(;dTeFNgRnC5_fNO7u2GcN<;>KpC+ckC)K%thpg|^X zFW%T}zqvPjYx-fk#8K3@qf{Ewkw;MfS-uJSY20>xed@~B7gIMrMNE?s6hr{orj}EB zX^cjp6tD;^7gX`)5}aq`B5&SWz??CaZtY8-C z*}dZf699rgqbbenSYyUqE0fj?HTI}b9GZNA4}ru8z^rg9yPjfWm93rSwqUmcf06wS zlHJGaLN4p?23FeV^fzw}t#I=9qHF6up{g9+l;{`gzQj3#F6t%m;akQ$L|2Zo;{h<3 z?)DLQ(CH~JVO$gQyYQC_zR-Ii{lj}{d_46v4)wT&BE9%G!E5j%pbuic#!|8%Gy81L zJC4-bnf_9#PO@sQ#W+Sf?Q-6;PU03i{r|EklZXf+gi7#{9q2T_$;!dOw=^hKU&<=9 zjTU5Dj-2Ohtx8}T9ud#qDcrq?zMC_R@uBty^T(y)HBpN;?kNp6VJ}7=fI#8>1$=8) z9Q3Uvi)e(%w@K#?x16KDOZw`vRgR0uA3rSA$(hx$jeSFXR{h)X*@}whISeuipNhv- zX5*RCyw4S5adV(C(wbIXU0r}zrn4!Fw%U; zCJ#E_Gsr7Bal6fn%KiyKY|MuP{qPM-8s~}g@LIQujt(%%H2d}I=Fhey!!%iQdvM-) zVUM^^379?0JRh0_vN$xXf6<$?qWCPXU%8`w2iFe4gOCa?flig{Pp8^JgBU0_4())Z zRk7bIcn6lT7h_F}rnW9k@LU!^Y-5-L%#n?|zq%*}Za1A_nV+wZeMVY;nk>%;NPXbF zVEYk_%|kCbu-JzXL0l$_!@Do=^MlK_69Dtlv@2WnZAeL3C!>8$Bx-T%jPrzmx-nFH zU+-uU`zbJ#Q5Tm7s(=A1N-0pfi3+oYs{0Sw5V%%!Y=br#jWF&+WyKJ!Z=juC{=-g7 z`cS4MUwX_HWk2 zg}_x**F+4iG3^}_eAGX3FN?gD^Pa+{PpPK^qRQg6FT?jS}WT1;_ zU6g`=vx|q@kDvX&(?I0|rlicUe%e!ga`xQV#SV*|5bhNp?jaz$U?nnR{l&p4(W)|S zf84GGHuWy@VOR7$;jEk2nGq?{TFr9W;DY^Uq%zR43lwSPU7suOU)L#rMarr7)>wE) zRKwK^na`6P(n$b6U>=p`uhvC+Z1y?yuRHcGsa)G$7+~QmZ0PFYC=bjMjIBW%^9E^%FDxZ8DVkI9XTPa@O5Xk z#_oIi5Rxeb4O{7QNLwjCkzQTMeq?odN(%0XY`liPu&2y#YKi)^49eCijM8H5Y1fnm z@V$XMIabXTi%kMp2*xl$98g?5_=g*r+yd}R6F@FU5@C7REKM3yY_{X$ySH91ym_5< zD!$S=GE{gq9~FAG{|hxXWqdj{v}k2!ZTAb+H4sXB&eN3|HKRao$_9*@X6O13ZEQN0 zWSej358X+fKitXU`$dLlOhel-$zT@v>zo_Ow>#$s>nPj!+W|FdYHXPu^@~_aFjGtx5Nd6ifFFacCGO+qIy64w%KI&;1Y!+~8x^?t==KTMUj0$;7a{N#Q6 zfb-tUoRch5aR<$p6mDSE0wi~NBpF2OCamkx@3m*E zRVD88K;T?{pA^u_SU$g+-f>(RG%N79u34ZLyGc*&k~_|CL&0RXq9HI)C)l)T@0IJC zUa@2Z8H~c#%m6ru8HMAfZ-8KjX4v`X34hdFTbzKNhtt-;7VOR_PpXWka9ec z{xZUOc}msPG-s48cJ6BR$pE}X5lKb!0Tq7J5Njd+_>iuAuC4Y9P@7!U*?c6B5ngcI?or}nmw8o9)1B{ z@Zjhd*=sVdPm5lZ8MY|2aZP`AlMRGQns;QAhryr2*(uk7C`G*-$@wL3n6ouF5qj6ZqtV#Hc(;@bW7*0Z7F zzX8Q!(Zqcp0Qr#B`T)r|JV~}4Tsi)t2m8q`9~zqvXR^F(`jF>Itp=1{EFJeIjf(NI zJR%-g8h1AH)G;8twWZ6ivGwx6#kllLJA#rx=$G0dPJC++n8szDLbFZt#qSVMM93<7 zZWtKfmksS?$F(LI7Dct;oNd zkiQUxk}V-xciY^gUyqMZmf7(Jh>G?~39e3|VUqd#uk`Lw&RL9m+-~NwlYc%}WK)BW z{eQlJEKHkM1+ED^ZhELFk;Vq7PNaaj;vGO*PHtPW!f|n!=jnu8{7s{?!PLTh7USvw z203zg6xlSOgb<42v$7C#*SK>>d~$NqL)h%rh`51*Z*0GyGJnU^?3yeF)%;?=IyfnC zTiUg%{PC7soAYd64YRZG)$ZW}5nkX4#*?zv)G98bu6??YbQ|1W-$s>wIMxt$Hb2}# zA6KT1GxwCshnEDnfL>))?tFV%&z&2L46*yK94t5bjFUUSuug`TQ9mSm6nv0Kxs#o!7VlBHZq!_(30B`I1JcOCeSYxVn5*AS@rA{d!Inrahmt$WiG_nWdUrl z=Jd#wBgg*d?{nw8kyA`t)5iN5fHbDQ4f?%Kxv4Z+i|WBV_s87LEKQKfb=^vRh4M`L z=E{5cB2y+}BGM~of)ibsbxln9O7Iz$>r)vcFUC+|+f~mUIePvWr0xWC8-(4jerI@g zQCW!Yj+WN+@H@#?KsIy{>!El=b;k zL@fUb*@j=w1Fuwe@c;UJ0t`$cze*){!N$E28nFmUceE!bhgSuP`6WSbL2$tSO)A)G z+i7+>Nsto}7_W>0S-Y9!^YG`%Kz-DsanGfEF0aZ2LbJK&8TJ7|TP`6%T#QodYw9zy zHzM(_gF_ehjVYe2Ukv>;d5d7+tPbrPbZ15VQuf4}zKc1l8s7gEt~g~VpJUQ#Iv30J z@R;d7Ji|RBbf^LkmErzn$Hmp9gLDC!cz-G;CdN-V@rNKxA?Pez<59eDL+Eo-;RYV* z-7Be*=2`c~N8V_0V(HXsIJ6ri<{$mflc{hul;2`n44vYh+g;_Xx+Nt5<@X1YO<6H zoNA_Gg&Qwn?Wz{d{K~Oj5*R$r+~WYZsWH7*o7zzD;DtIKkQzG59>j#haMNFA=vLt+ zIxG&uz@W58x`1?c zK4}Y4?UaRS2vC{vl_$9-n%UIV%9~#Ef&<_*P>;d1_TtLULBMa0F333Sv&O@OOw&@g z>pxHnNjkj(-lEy&c}zPnk*VCz{lK4osoVq&K5L; zSQ9|ZrQ5+%w=qc3-u;)IMFWfeOFi#@Gccpxcv@T5tKzW(wv^jbV0Wm@MvEnYDv`x# zoW%F>P%)&(?v^0CV2tnf9KZ^;$In@akS;v%PjxScj1(Py-FpD=_%Qmeja~sp%E#=1 zXbC@ORo(o(s#|V9z7^6Cp^mhNkE#4W#lvN$s#lnQNTA4{%!)3c~`?w0~o{rf)E}zb$Ff`9|Uuj7KCvmS_mitK3SXC{-9G~GbrA}jxwc>@}HRx$*e}K zLU{=6u7TKn*ml*#Wg}14(9E_Adg&0{Vzl6otpS*9-y58x5A!3XmmqgP0k8~$=V}xE zI1c^O_@zGeky>|zJ+L^?5R6XVULDC8Jr@@DwLW8%`?iA%_!9$We75rSp9}&-ub-Ge zZBSRKaC7T>IJzc{HyH*>o-*+QTg%c%;49F-1LacCAy$zORQEgMdCh}90D(2tyLY3w z^>G{s{#hLocnZtf7bc38bz2mwhsxr$K%8_j^<3~2H#1+y>nzSEQ^dIX$4`N)yr7#9 zVmE)g7X?sDx=@cHaE%tE-nQVx65t3y*Iu9&@_ons?Afy>V1|iA&1ikHN{!y7_j7ex zvy}K{|7Sc6d{d^}2bF6eF1j=G;&DP!k}?=xdn0j%dAa0WJLn^ksW88d&o@+;>rG=a zI|aAMkab%-Mjc$|^uCO~B1&|q=S5!i&7SOD63xMmjP?0BO5CQghv4*S7n|Pa7*I=P zH~?+Am4&KBq5bXeKEyL$IP2_^Ody3G-6su~?9ed&j<@%VrA8E{_v%65yS+%n8~Q?6 z<5@urq|zDoJoygvS}r`VIRWC!XODi0>MT-q=MvN0k|QT4*T9MaRylRb=cDUREsBgk zc`cv+TgFI4k&R3MOzt8bfBGc-1M-YX2a+WHdqIk{E36U=hW|}lGyV_~g^C38Ba8() z_kL+q)yZ!kw9?BU%*SH#c~o6=o|%Vn57}Jx-AZ=zi63{-f2%lrTkvE<2IA%a1r4k> zpjBvyEbbg(?|*QC>jX21#r~5%D8hN)BV?=5Dn1P;f8@cD3d_bcUSs>$z2P_iPikg)f*o$sg8(N>Xi7%vVilI+ec5wg3Oy| zwBQ!53iKuOap+N~v$X$kTyujDNQh+yQ}R;~agfK#9cNy@v9#cyFf0PYpXGSMiPTG8 zWC*}KjwA+|lCG<#+1cylQC9w-_DKnvK&>0lG~>nfr{Jji>kkMhpywv^_ig=;6COO{ zt8rO{B>pLgIve$GyIb+p6>^mNn|w?{+pYUED1>q+TXYf}$Vi5cO1ef`y9E2NX`Nl`s<(zag&=^TLg8P4`oBe03sr}2M?{VJ+@g~_&LSp5C>)X@V@NeL^4x#2?T`CES3uI3Z_uy=K4|)G4#%4fvjD{q-e#yHE+Ae2Q09#zE0~md8%j>5X}VNL zDVvXPeM@{39Nhz=Ol5wIH`6*F+ymSH)W7#Rxr}d=738zhq#iy%wi8eBdi6XGF4d#9 zr&xp#{@aJO1>&jX9-x8fcCGfQFj<;ZkP=WjEUfc8yOJO}%GnF2ChFP^*y}8+@^f~j zBG<0zmWh_+wNxYX=eOA__Z!I}22uWM-V4BF+9HUrD2-5-#EPK)&Tp}%`a^oM^7LJ( z+Cgv#T3P=+n;K}$p|#>wSe%!?vzwsHto1whXmUJPK4DO3S;svU5kPs&(~7GVGZR%& z=LpKAU!AwkMN|AEG-)Z^Y=|VzI!-&kknLaGx*Eb<7krXZJn$LUC@TXXm&k2=#No&c z9EeuT9SA!;jCT*d=91P|Bx3vZ4n@VO-;z&ERYBx60~}k*X&EYY$fEUdC3`q>>cjo5 z{5>)gl|e3{rB=^4jx$*}@h2KS>PsfpS>{$|Ract7$a+pFzbTq!cW6(G@s|i=1X!+O z!S)XgZ2l_Bn4*R*68er&p>i_np{UR!kUB&>1o8m5VD2&YDQdg7LXD@;YV2oZQ|85;f-` zSn=|Y>%YUvFUvS^CP_4{RRQ|3s1EzF-sPC$q#v&wXP;SK8$T740&{T@q85Dmv0y$b zLaKLi6*-X)pIH|k;3Vv&xQ_XCY4=xSU}*3BYZH7m-YIeicv{=4SQ_d_F7jqmkZXZb zr=x6b3J}Li;Rpw1!~cY+i6TuUEyvp7NlDwd`n zX5W0$8!PIYMs1wzZa#Wna#4Lm3D63Z>_1siDb`1e$qwvokWn~#>Z?;XxJzsECn4GL z1yvx$R!|Hep7|v@SS0ETEv!vm8Sb-B2Alb@;F;RD?a zg2QjdG9(=Fy#?r+nF3A3EL$M@n<(Ae0VJ4Whn0H2tz8~Qi)|3GSGbZBQn`ohJ!z&2 z`mKX!`mW!=Lsr>M4k)eIMOTH^mlX0L>pY)CLc%X_r98d^fDySRX9RwgFd4Bu;05@I}n9R_64GKP}7~@96-ucUizor@c(sjeMr%?VVfnA z3hl9F>K=neVR~pHxAtgUjErkQwlC)1E}=-~THB;d`w`%t&L_fGgyskAmEi4PSD!~Z z7^}CYB$%4DUZaAiib5sR%S_E ztgANJ9guhi>?#0!+mL}t3aqe@AI;dZg&Ixxxc z{D(X(ptD>YoSzch$R{Y+XR?FHklI>J;h|rQ&j!sH`bO)>0;Eu<~#=)$B%%guF9mYa}8rj*|pZo3sC%EiYYbU9Ys5LHM zUyG!+*1Dj3+3>Y~#XE^&;|-6<)~@mhaaOLd(Ef%{Y;irjMJD`TO z+ZWzgk!if!ML)dFl350)obkq2%-LjHHX1s}oJN(*vrwuMfrzJ%E>eL2EMH#huM~Zx z-VhBf-V0c1_;w(Pt*WU*P$RekPgYN_iL-KTk|SFQAozpS93Hf|TOHlBVr z5a}p-u_SB8*U1q9IXvuT1P zmhhmdih#8dJobKbUmUUbe-qW|K-Obr&XU)V{B0`c1LNjEO|+OU@jcbNoqB%hKGBE` zV)}}XLL*{Jt6%mc2cy*Q282k6C=+alVorkvc8KbC>}-R?ttIcT61OY;cCnCnDL?O~ zbm|aBqvrFjDqr1W4@xQ_yO(&xG)g1#3K{yu3UdYS`6SjP4am|md90RDcapUtBt_g@ zY4$wlI-I)$**?BN|5(%MHFu6zSNp0BdtGPYF3 za(xNo2B`+EeEs)IA=vbc$A_j>(DN-iDliHrI7@=5rj8EFIwKnKcAJ@by78Sg%Jck_ zr-GZ(t=!FEMsOyo@s*j6OeZ^#(g_b5xGsbB@K9XwI7lRjZdNG|S}*a?^}cmbE9bd= zc=FU_XX6(%^~{*R3Qu3Um$9+R!8F4Ws}!{R{=>{GR!16w^>uBPzyqIS~ar%(gWdC=s`I3(sZ!5a;K)H>|P|vcNt=aVHsG%{U z4!_=W31bIO-Z*YN5cx$5{axF0vO7!jC5bYiKmw&8nJfLELDf6pl>yeWNz2`FScLN4 zw&VY9OVd>Spmu0TKG@#?8!fxs5SS=dJ$H$s{^)VMS8I+^^AVTGB&~^Rda_Q97yT?% z{7}3+eaGTaU|T6@sWM$%*IT(y3%k^j-Cz<=8|8ryu2J7#UZXceB@xO8-aZRyJIx|` z!}~z`Ff(X4j!HwBa{kfN^}xoM1N}=kWz6sk1@!i1=iZN$`b23gWT+$I>xv(A2WCy@ zBO^Y3v-fn^4bf!pkK%8fOaN$gLhvPCoT<94%lAVa97Ou3f9=%uIxE!WVW6gV;Z!IZ zM1S3bT@!9!VZ=um5wKK%FUGmm3CyrkBy@r5nRlaN4ss9AI3c;6F72DflD&L+Q&>#U z3g$Ye?mf+nXQb>tfg%4fDdR^h{D6LGoIX{?nJUul8tgK^hxF+?p12ts{dl@;4grI| zKcG$}+UM;rugZw@^1)r^6PsTtn^tTWE7HJGUz8qD0gK7=x5>Y|x^0cupf=Y`gd> zNm4FX3Q^+NAU(SIt0)2@@{Ila)%GHCS4STc?{+PFMc+8ukzKoXof@ug&bqI;KD;6} zGHZ2~uVkc8s%yD36r&w+7Urk`5=*0Mc23Zz-AU88yzbw_-zyQg_n2li3}9z60d@~| zaZi~`M9Q5FdQ@SDue^NeNT;%JP1!81-QF@j)3{ihd+b(iRf`7SfovjSP34Qd4Vkyg z94yvkq2@-Q`1YzSLW9X~#Bdm1J~F=a)Oub>ogDQo?lD{Cr?bFEc>JA@Xis%Cqdw^+ zI;^IcyeMRTGf{BvDC?$eFvd>3q3L@3{5=)GRoY4^!Y7mq%x+lUETX$KXHS za+A4_`vS+G^;eGn=uA65@48}j0wrgAQfHm(WrFH;&kiK$CZZ z;TcM2#v8*XdIm%!4JJxKXIZUJyzo*LC%}^qx*|g)eJ`(OPaWp+12Z3o$;%za#BHrj z)1!6owxPR6w(bkBD&1YZhADEL(o<>nu2L=UB|n;#y9D&A1>|IcDJHLrtt^dF9h;Z- z@+hp4^Q#JFAGbcHJi2mcDbwP7HO4n%oDX)G;@k&T-DQHgc>^DzIV1H*@KP$&LH$re8J^ywr>AvC>sNQV`Ab>d+P@t)nwpE-7Rg8+HvmObg+}edzO5JkTKdu?0nwU2O(fqtY9?Lt-hOkOy3P} zvon6LCw-q_#VTZlmim>Yc!Yg6yuOv^C^Xk+&+c?e{a{zu^(h_g`ce&XNBwiVf8+8;dn=FPt1_D6!MHVfyw1ZnMur8j?$K% z9=22Oc#^;rAf|iFL^X!W0eL1x8d^~D2=x>ax%R|mmXf&Ha@XbaPhIoL3VTYU53dP} z2Kcu=*Y2-dFSW-k5Zc+Sy&o`?O%CyP9+p~EV%$$s9ez4&yZH5*wM$`gdcz~@_nkRn za3xLcerRiv*M}~>}KyIaX1;z2HWb6kdp`$%hw>3 zsbi>zuOzr=A}yaO?{G(v=DSEXirOgO=?LQ4A66lclXmka4J`kq@OBpbnuKP5`D+%d zSMA4JH^qvzebKveMfPN(CO`jYd*dl0J{GjqkVAxUtLrs`ahnq3uE1a2OoJb7Mta{en2!1|1rB9a7?*$H3_vyDdCNEOxCJ`OA zyR2lnFj%qFA#E^GZiVo{-%#`HnzW6p(U1C3TdS%`IL{hPNLYKJk8@Xop~SkYK7W{f zc_e9mLzO$#mzaVjhK84eULb17;K@`x+FM?5z;FKcfP1?5EWTX<%;^Yzm&p;I zoZ1{6WZI=D4*5 z_7{DyJP>0N_#IYuow^Kqkc?iW_Dv7L=qor6FcU&2+8;8N0IA7l(DgMLEjna47&F@$ z$Ib5$W4+)6Z|&cc6|9`S>-=U^{Jztyb;g$k^G>5`W=T96CdFvZpG=dt)~&B372Ehf zPHVVe`Hjx)Ix6<9OtH}p>>bPfO168Jz$BTzvjbDN##Ca!6iP-vgy}Jp4j$DV%(-hu z)H3%&kODhK-N(oa7Ym6RH%~3F>H>u4*R;sHP zU+^t{(pExA;eMb*n;p7FYWcT35a38=s%$%M6xGD)1vYn)OO8^`7v#YndK})HV$s_}GW@C`Rqc z;5*3f5&pYzhzua={)#LlPK+S)j+f_gYnQ87$$oOPyzQK^CJg-5pZB_2M^E08bO8|V z4Ti2hz1ydv{$)lcGo~YxkN|OuYwZkq|M~;T;Q%x&$D~jIqi)W56g88nx?zj`fV24} zQeDso_`?46<$9}ijIMI$g;xYV_Pw1FU7RzHw6%`Or(RhlNZ4Ng25VjDfTq; zqu%_K$epmGI8mM8yS;ofF^j{B$~Ga0#vxCvuX0YUBh8*r>ltwnX+(E+X;9r60Y*i~ zlW&6ApYapMh73UW=z@4) z4fy7Utvz~bT76fU^ZZJCK1b*eB-;0MDUy&H6W%nkO=RPWYH38SfFBrUsrkAs0Q|s3 zfBOSV@=ed?MwQJFIXXuVZ8< zfkVL`JW@L_0D0C4b0=+1OAsloW&XRFV8Q&1V^nE|+}BHqlL>p%HOfzQ%38fQt;Pc8 z36~J6bVjwiiGyyd&MO5GhO@ETxV03(TF1#wGJv&Ci+%6G?&Ty;ZLmBPJq&dItG!R@ zvMYD$rd;~Gvu!jS9+R0<(IJuc3`P=jH-rDQqhL*4u9^d;oo+}dATq1j%G4?hpJ;@G zP(=NVV2EFyhXUR@d3gGX`$8uaV1Yse1@d^{Y6Lmhm_LLpf5gC8v}ZpE%v%24yLzkj zjOLSxvXU&8>nSId!1iqOlgORAC})&)))jNihp&~{Zzd7U_R@(kk6bM_6IEynUs~9m zpjdt^81sCyO|2)*8SWGm0mwxWR(2!U?MnB`$itynFj)5A%>u(*L2iPD*v`-TrHzu_ z&*?r}k5g2+<77OR6rJmyzKrZfeJ;upYN|b6_f0C1|BKOgv$8-2^TMGkHtAC5!~^|J zeC-%5$URAH6!QGK>a6WbE6ilD{(Ya^Xa~2_D-q zs3Ern;>n<^#?$U!|9?*PX0zvhdf+58b$-ml-T29hPp>B<8XH=ZR6xMOPB`EwXY`4c zT+}2($E8bP&9wOn*}il*>heDNsUHJ~;hW5;|0-ni&X~E=Vo~{HxWk$D>WJ?Um}~ON zey&G8w5Uk4IKgA9>DSUCHL@vAw)C?BanzT$j{C90`7ASyKYA}pG1j6oOm5UNf3z(G zXWeAR^0zDg+#=U%8kFW<7X8psuN=b9xT;6_8Fz;&feOHc0@d^u^XIsOGP39N~MspwkRWSPMB6UbCs*Z<` zMdwhFmAr}E3(ObZsJFhE_d_SdyX%wJxBMOEh8Kj zIwINLP1bnk9noqeEH~ly&M+x#A%5nQ#_R?TDqP1s`&f}h)^Z}E<$CH_Ir3tob_7<->QSLK#q7fe`6x^^8U|L6|Rd( zSd(=+DUXVgtTmqLZpqy=i>}mTI(zim@8&Yk1acqK@es~yIVTrD+H#9fFCY$DcMh9X z{jaG9Shpg&+&TG+?pUe)vhmXDGG}C^SWCG4wwt_J^Ox#|#N}1OOG_i{lSOtb4&*m~ za&68v^COI0&3eMC-14KsIRC%)-a0PIb$c5ZL_w5L1U4c9(nzRCONoFmgmi-_U4x`_ zsi>4l=g=^;^Z-K`)KJnnAl)%^|L(zazVF%lyWews|NVW={$qb+Z<%?X`&rM5>$=uj zzEp~$boUIHr2_AX-Yy9Ib<@B7sn+RYDDFT|DTGyMLb(e@g$FMIpjf z(O!9P>BT7amHvif7-{_jRprh4y-3>am~AQ~a8oRb+v}FHleQ-lx{Jd>}u>6kT_AR!{TF)sXLkaB??@ce4YL{2(yY*Jq zC#wyA41bFEDf9c&$jqm*AX93w)cC!(nsKR1IPi(*snAS>sxe5Fi+4VH>WD1zYbr#2 zm!y!Z`>A9JHoCQN>qS5q zg@^T~rlr563n}<8hKjuEHIDan#0v<`xRULX|dhK1yey-bYUDFB=oRsnQt9R zwV=#pP`kisvCwt1Ql4x1L}e&yTnZl0ZW0dA^pP(+W-@^-Dn7q=>M4%%L>wl%Ihj#E zoY0?hZ@MpkF818Ej2*2|1Q}~t-wOlRXZYGkvlqErMVI!`k14l_+>F*B2zlH$-Oo)q zEB$;3bmXH5f6vHL7rUrgKe&lOpTUg|iQ&syOzvB&+-u%@ipja{R^_d&hMru9&~f(N z<#Ejem%KLC0X+lynPZZV(S>3%nWCFW4b<3u!nw-kUFIr~@Ve}TxBmRn(n?v`Y6f-p zQsW%%2%HNI1>rd~Kg8_pp*!{}`(Ysk$DY5(GU$Sc{c)u%VQH-KCUfrR6NfL$(yW?} zvk#U!9^5dyH0H9qOwWrG@1vO@rcq^Zx)w4vsSa&s*j(!zv_A4d5`SVsQ3~uMPFl*Y zD_$53fjxW>?JA8186Q3u3dQT6P{3wygxSLFIdXJ8!`2rvFUp-8VNh|b zWvL{-y7v##ZCJ7hEg$&z( zYp_`T`&zX*8r`ow&A>d4H#Xfz+kD4yc%&8X-XYc*FwVB>S#18@K zOuzdKYQ4j&RkOdHpZt}>@dlMVT{MM1=aV<$55bK;)N?|f#hCQmkJm~{03Z<`{P)!q z!ZC*P>2*gKexoS8FdM8j02r$`ljf<^5PAaJW$VU;CnIG zoh-Nu?#ig_T0-u&dK<1e)rw@>itYy3gQ5z_oFK#a5fXS+U->4k&24ZLuRAM0pS_-q z8LA1ySUc!X`CB{i$^H7a@uJ{LZ%;Q4wM&WhnwJdXXii7bd5iNoM%5Kuwmj?CsFHL=4ir7TD2h9f3^HFtPc3v9+ zfz8-a?1PipOBSzI$X#oSWxa-vd7B1g3#~tS50yd`>vUBl;D$DZk*73O2F^oSX*|O0 ztjXl1^pyiI6G}oHLFia&bhW}Qpin2q$?ErbVj%_)onx&4MEKb`8TCGspaRjWitX^b+)DPH%M7Os&QK0LW6!Ns)YkhV5_pp1HOe>1DEqg1vIc0CUIEIX!+-SQ!Em0`y1)% zWyr(_na*(FB44u?m{KZ$NGXWQVS?@&oW!W1cZ;@Ot%eGss$$0t_un5GA2aW&T=Yr{ zaHQ@U8Y*N<-0KVn1t0qh!NlqmM4eu_l?&Xk+@m{O!bkKT)rvUhWAGrJCuaA#s7rAsTzOS%gJgebZlv2py$EhQ&b45* z_P%QFoxe;=@4a2uaHh5^EGD@-8H8@t`fqu-u3@j^YP&d-3UDsP#=mtTl5~s9bS|=S z)eU<`6=skZlK$C_Wes~w?j8zmN>!4^?T3QUHCqBNRGbn|D^YDtsN(rZiDuAJ{s)#{v%(XCr2h!&J`LhPLe)z2iA}M|$A*9;r$+KkUkt@unpB~Jl zW#(w~Ui=wfyJ^D)?HHZb?VDOHV`<%L{CvLvQ)j$AOF2D2&4(I}iV9+%jT?$kzU%a} zP;$^S`v|phl^C zz|9Z-&dsyp9ie{c>6URQ(3s4aOmfNo(@j=9IVeHYe2Lw7VAF0MtKyXVWa@rcs3N(= ziA+_Hd-sc1Wm~j;EHw2xHH$>9#wW-3f$yz&x4B?Q;j)Pki{N>ikf{7Nup8K?R@{nC zkkT7)MV7yFMcH_2U2_G|&}iT@(#@#hKAm01#L?a&8?#%VO3RvPxJ=^t(#I;))KP0X zAz@a{fl~4Rw@;)s&vTyi0>3#kdYO=dIUm!)PG&MGGlKuy9 z+-D5ef8-?U`+oK}a^7F849_Si;QHF08IXnAakoW1srK4F4Tm{Zd6?;-+`>XtOJKNB zU2t4WhxKqJLDer8L$xTPeTQ={YX&Z+$OPYD0)q`TM8rtqZ-NqE&?d$5`ER(Z9{P`v zfW>^r_z@JPHyUH+~6tEgae@NU1r{JTw)|?@A z`Q>`^{{s@YvTo*f@uOkDOsT@2AwNuA2u9g)Eh=}ERSg1xflD=eHre^Al+P!NefnE!G{Ao{1WnQCJ5 z2kO7cA0PuTx7<;Hx{g_fGLT6mT%p-nWdiPJC5TGFAcv=)=C-D1x32M0D6(Z?b9h*1 zzk7jKr2-o57`Mwfa!V0?KVbwyCmF~AFVQ5p^vb?8#z%Txt>Nr@mC{B$EU~=Lz5iX~ zmOeNZ`6nkKn&1{bntfg|GA?I0&&1v&n@W}EQ~+}02DR}tiEW#@+Qnm&H+eQ-+Lf@k zMA>WGrFD{w)J%V|J5vWKxiC4XbW&Kun{B*#vixZA=jW2Ye|zvo_3D3)#+)MFi=6f^ zXa!h${ngbpO!cdxtf-Q@e{Ob)vM_jk6v@tDUq6n7H7oT)E!CsJ?m5&-#W)wl<+!9x z|3Qg*t=P|bBNl8d+7Cy(_32`{?UxQfD_M*8iQ7g0vB><6wy%Oj-%QxT$N zg!jb#n&gV_`2x%5hB7i5)|jWNnwHi~^l}4%!l)TEOL2gWbdkS!g;CLnV8WpG*h=|C zdvQ8{;N>n7a}ho{$4NozRiAHzg(nHkJ*dO6Y<&6OV9ZfTbwv^hca_lHqql*pQB+na%M zuGQ=D6nm^za?k^R$J84mb;63}a?Stqo0T!6bU`0mqLl~4VfxHwn#OHDR+lHtj56pJ zEqtlaY;n-75H{(}oR~ATPg=fTd>iSDXnl&Bo~;uRUb?~pExI#ug{9169gt~R$J08u z=hfbN%Y}fmXyLW^Axa9sq@Mqb=a?_-tMVk=C|@Jsb!a}_GJ)|o4_&ShY$@Djizaa{ z{8Zcs$oo*;>2MdtPYqU~k+LFQte!%vSD5!#`nJPi9?Y6vmFSimJf=Z6`FG4+9Xpi# zKD<@DJp7eyym1~)rJVwO+>puu9IvB-MlrcG$P;yb%QCCn1>nzm7)}Qy7KKW^Ug$Zv zzKP)HpM71Hk|MjRgA_%|?tx~x^xfnn`yphS!|87`e6qI zYZ(@$FW4Sl0H<;1KSO%pG~AEZyrW+Bbaw7PJ2@9zReKVuJF{0joZu`Go5kT~XaGHW zUdUX=ws*9@37oN_qrV~g5G2NgOZ?`h5d-{l-<5nsKktncsU>02E~YbEl>2vRSLuVJ z{oVV7ZtUJ4+4N0iN`hilxudN|m=dqg8h_upDCoHmP+XqzoejO4u5a=UA=C1@2O8br z`BuOJ!FPAJziG_9Wvr(KS^H`)@_y-BLw-&;s<6VY90{v25#Y83M)`frD?`m4U_br; z8T1TPRmn@A$&lyAKh-hJ>21onm=;3Y#B9cZ^vlAh|S9z=OELtvGY@4@7l`v zx^#ahNTuYH;^5l!6Y7|{2SzUsR-Aa%hs<=O#{L-FUh=+G@c;f8ULLCQ#AB5b=>g_| zs&klywhN|Ne8X^JI_9j>Wwc|h<&P^E$jvddB5yTOXqKH0up=0ieH>np;APui(dCMg zPJI9E3JaLe*115oVtdLcBBCR&V)btDKMFg{Umjkrjt)DFh=f^3yU%Jqff1A2s^oSq zMHfcFJZr&vpZxo(mn@}K3sdwnB(pGi4a_E4J4z}|0Db>n?a?8-bxh_|n2|h3TqUDc zS8MrF8xMHqz~nFv_-!n%d`5u%TYMLL1;RZtA{m6u9-H6Y5XmW!3CX&n1yjWFniUV< zxm^m!=ni;kG3Gv0V*(LZ=6E_2YF4AbRrHK~!}qfi-fCY&e$6ST(@^V1RF$={9803; zXUE~x!&hVVgl z=l)CJGRA)6GAfT};(zv*BK7(?1PwG!oobqQr0iSG#y`p6Z`*8lxpkt{49N6wO!(8fOVXh0dhSP&b1o^#3G>m#8qAcl|k!Rphb@XD0Uy84mQN=r8 zwA(5m=ukyJ7vBpL-Z|Y$G7uQo-n*IHQG6I({a!7yf_)$gZ;gYQm*>ua?!4m~S+wEU z!LtETa5^IaJT5It=QwB0dXs)}Y?eyuOnU~{)P=0;f3uf?BQS67G|naGF!Dlg-9<4W zY2#yt+q&Ky$HEaPi7bLo+Y3 z*rqNb>Mef)eszXYMZLDdsw&Lc+CReN(qn|l5zO|ktY?)>jKVk97YUF+rEqYw3fhtsM&c;0s6Q}n zs%tJi)nX0QFo^iM9zMAUpw^!1lS!iIIk`WiWD;(88m?vFQS?wAd)@6c)Qd%LIe;hvT~*%V9A&B<^$ z)KG8D@T_WmIVNP5FAa$n8ruFm-m*awbe+70kW5bnhYOm#bVMJW$#>h3L6^FsIT1RV zaMiALMhRKQ6>=P3EXqN}q(s*t`g!{2hL1FWa?=DxmfOxiAU;UOgPT|aIA7||XeMbi z1?(UEz{28z|3&@~gn~4QFn=O+={@1e=xH~}OpnrlFv0b#sEKU`i{(gdHUK% zae5Z%2GKXcuXwf7i6fbgNTsc$xB$ntdFnv#TeAL zQ&&*8I)17t`F>;q{-yS8vAeoc4&O>GIqQUW#JDeksCWYkACf=S&xLBb?fRu_v>K1=M-)RN#pxbJq1MEc}PIjNcol-+T&on`Q$ z@DwNX_@yHCeG?Tif`!3r{(@;vc0DhMxgkMq~Ch*B(AZ25}8I^!GY~6##r$ zft5T_N6?oJW`XeJPM%OPHeLSZj|#N5;lZf#EE^Wq zu>54<)r^+ee!@WLuHJ=eu4(}0?Oq%@a@CVe=EOVF zF_zWWHGe)r0bCX5R@=x~I%jMkEVb|h>#A=4#Z~p_T&a!@6~5fquK)|(LyLyRcN6ik zN$$2o7ms>e_#rk^(dnCFRm};44r(eLlAN%3A-ml?69Y?lw9GCvjOuhVQ*C=OQJHJ} zM0wxT*5vZ_3kzL!K~FER_Qh{;-SW!766ey$N*^CKTnU{AGt^?F?;ZiMc?!9=_F0NM zIiR9E+JL>ZD}TN;UxCt?Eh@!*KjuuT!{huzkHiG8COdEYi8AUK2OjE*2Q72C<;`Yy z_)(4I!p2R*%=~xOvfP$Ni3}H+&35HE^Dhff@YzJ3QuW`4tsxx3r(G**=OS7u_AU*J z$x%J#EVRZf6m{8TE;bwC`+De<`r|6a;(?0)QvSLW&6y=0q_*daVmSxu*gta);0>yB z-_Nc(IM0kOO-6dii@}zZSO_ME<4&#!UzQ)!+)(9-am1BxHMkI~xT15%Y%3d8WI;i`90Vj``r)6`Chsywkfk@UPU6Sgv*eRN#s%&y@=0`UXHn?6k0A-A`l zyAtz&(qN~6;~zWd2!9_Si`?p-sQC!4jDDe_w&DyZ%O63vUOx**e|;aiQ^lIe)Sxa( zN!E}OKkL*?c&tJdwYCgWvjB4vD{3HW1BjW?iYW{GS%bvsnoM%r&Q9oy zRcbl}t0fA4@)y6JMRAN8wC@us(3VEecp_Gzx6LPa3r*cb?w@+ap6*y%Seujb*E{cY zL0c2~kF`wOV!*5zr~Igv;OzWQs&2&LjZsO(8J~rC!xx~%(Duxl9jmw-Gl*eM%ydd( zx=D0v-b~+eiItaItt!-;{`AVdZ9U+qHz@-hX|jkJ)L(z;2kMx92;IGNUC*D#eSyFG z_c)_D3Flk==eu2fN-Yzjl8?kvz5AbjG%6r!L;8}DNsz4_m$X0A5%$il(3;;oc3xl@ zUv-Y~$e0yjDeA?tukFFbOl4QN+pIIQs(VpwION@HuM3+c04xWTxQW~7MFsmbVgYq* zU2R9gRhWV*%7;>0lhC*=wF}}EUlk7=YW|2uV~>`s(^Ks1XziEk7Ym%A3&>v!7MV9YR%eGW|gbT>cS z8j~6EO?nb1FP_9{5oH_}r|e|at`y9j5K(2JB(JCl8i$Ao-bjekc1J}g95ZBU=qfl% z*zdY#aa(KPme5vztOJ2D@X;k<^hhL7+3qkW9eSNbz?ptuUIg}a@&Ajctu%l_;R08Z z&Q|3p-&A8BL2p|Ez@pomNvbM@@35pL&pqNS+`MS;P}?_a5sInV-!w*BZ5sbbmBI{L z70P;gdOjP{dv6kn4}oMsKP>Ut$Ddm8y#qlI&#j(Oc|R|Y zeQt#N=EKZCNQwP1=_*?i8tEL;H~B#1oNsgRO+)}BQ{n%i?9vP*3MR52hG&_y`Q3ZT zP2TntQu5{2P?YI{?FkLD`DA`PVRCjFN7=%TlNtKPg(VhY39yzH+YYR_5fU}TQq#7{l5|Q;6C&elK@DpTY= z+*!G^xK_9m<`$ly7CdT^6!)Ex{1CsYs(9mK?C4TxJ|>EP_2c-~D0|`V66=V&y5K(h z-OP~eLqkDn`jd?{sTp)9FK^k9yZd}sJ`aqvSqfAQsgefnKwq*VD}0JP^YX2Q7w*WN zX#xL2YV-FeoJk4%|4ITzJCzu zGS0C!vXjao+~zW{(`8gE^pOMy+*qpr@8XL4r74E zEW>I2aeKFg94EOumLLF^+#Dhz8*sOLK?LJ9z8-7lutN5XJ*EgcOHb>6_tq<(t zt@X;smNeG%+MltHn}OAz`nRJAxsF{>j}hr}5LeF}D*5wwoICU|6t%Xy3dJ5;W>A$z z1nL<&f6XMl>E#a%5#wA{Q5w?{1{&OdwyT`=#{@S0(p|jTQgt-I^6hW`!nYHE7$cBo zN@U_rmY_@PP50c&l5FKb7)t5t@?Mwm7>;{qAW=KEcJ-rM+Hmj-ua7#;0}&3Y>!rSP z--ya9WhHnLdU;M}xV^(pJ(sgEdwDQa|8{Wk3!Cs4D(VJYlC4rF=-%5_y3QSL_MS5b zZ86B+l+%uxmkLWJ=3lEn5r)bJ6uY@rxE76S?82}yL9f7m_Bb0gcYiYm5SNv)625%= z+zT)XA$hk%xS<6wyNscN?|W)k=I@`%!MR@P_fRl*9<$Y>gaTu~5`wu7x0hJvVBWQQ z4(+_3tvxINIL^=iXK>udFtGDC20;#<5V*OZR4H1z7rZ2-g znp~mX*Cg>9mzX1(j%B7Ag;uy@Vm@U!Q%?+S`KSoV@ZOdis#cYB)(uWzbE2LpW6iBd#XscRmn6Bc8p)5Tg)0G(S?t+HwaE&w2Xbq=fB&k$3EBM;AS}To00$CfFXP7%g z671D_w4!n)XFgW+QhoivKm_`$&fj3hDo{T^>vKNqN(wK3+(w6W`Zn61A$>bO49Q2eX`H;pF|i@j^4{aHrxR3`zmxz^G~Vw%q1 zrLnutrM{VzTSI@I**-HlBt-;KGhWJ(#~ zr^A8gv`Y0@oHLLbC@d7C2xlGl@+5>FWSSDGN63EPp|Dt>>u}YMX16$aK9ZqPz%Dk# zRi{75#^5Qb8s6*lL~#8kO(8}`z)_+aE)MrcYys+MUG1C zgXFrSWYrP?iC0xT@lGl_kZ^sud#8JVS?PM9nDg-Ml7r|L8<(~SfD@;WRlA!a4_ZsQ zM-h*J9K~cgcBa;Z+vcOt#zhL$|U!$N}S=NO&b(xnd+kZRAsg$1A>&_SKS39sjE ze|~vmKWG#nSccdcwwfuZUM0*M0!v8dETacSY_`Vu>N%iO*Wm$^fuVAhZe8vQk} zf=A!?Ut}z8pRVd1?)q4cb~Dmw^0j7bRy0@91Y?%Xwh_B(a_(cUleXtXD>LN|1~gE~ zi|j+WRq-ViDh`$}?49r~#Hk%LSa~r(xAv=qh&;2~JEJvLnyX$vZP##1Ni|5i#foV` z^LAV*_Gq9#on5ju8BLDZUGd!Kvv;ux{24C#`463z5TR5l;bFudN!I{S8TqSnf42%2 zXR?9;Sk9JY52{=8XTd^`$L+Q%O@M@$eodxmS2DZ>yx9mITYXH3@Hs-+3-q7~!7nlX zfZ&xGKaJp;1H$!dLG87CZYAMziB?OOi%_)!LIM4aFHss2(TBPGEo&k9kz)NY_V&Vu z(avgK>pxVErw$WLJX9Oe^z2W1E9BF47wf2Zmg$?EMi8grg#E9gOGNft%rGNP@iW^t z!p^k{1vSyV8qlbFG;z~l%wTI#N1ux3{&#D3@@K6SdUBeL4#l-8kDPO@MV4gAwR?J5 zy*bCZ)_VC`@Yx=(ZRbSLhzJSt)b?)D0tHw8;Mm}tgR7ODWoS+gCaC=fk|+LQMW|zr zpUUF;sxNtq1n%V?7Um*lj{IvnrKLZ~_6C9L5B|j`KXRPo%2IXbw?WqkTIJ7nB;H|= z4zj~2aOHxMQ@g>^wCkmn-`6$)&?0)1jhNxuQ&g$f`W{h79yR#`s$z48ljCTW-SvwJ zpo9D)S(I(G_fW(>bJ-gOU6Z2}&JLAIRMb`!DyPD@SMfr4c?SC809#pGJGELXYsA!Z zz?kfJ?w-&`?<~X-Kb>JMNX#(3tM4Mm{w|X6#y&}z>@L9R6Mf=aRVA{*2Q*p=;Join z`R#$pn-;5A%HzYuOxyl&oqW$y92NWtgn_iX zmvndDQz<<$kz#^2T)G@&|Cw|G@|Z*G<&951!X*|xi=xFw4LS(RF&#v@OU2U$7zkbW z4|^2sy9&y>>s~A=B&wZgMxTfvudkknIERS_yb46{L=u~?0%FeN9^}q^LC!Mo zSL%!uvnGup_AZA`raHMb&%PWV7765!&c}CI&1qRWZ5YQ@M4&^AN!6auC13a_@R-ge zJ(ta6aboubs<*yyOyf5&4x3R73y3fM@`vZf;HUdmmX--|30?;am^Ply={$8Xz&4S8 z2p+3gSc8%4D7MYK=2$QV#;q!@(Ql*O*JNR$p7!J{YcM>u5rj>$DO_FCY&;jwob=sU z*9uqd=GB<>WvBZt4V(63Jni;+mW2#XkF~v`P^WL8g`eiiZIvhy=Fy7xohDWnmaf*ubg2TkKOYi&$7x za60cYB9=GuI5JI1Ud=&EpQ_Z{X_IB~=a1*9agzOc+6;%wC84Tt60xJFVAD=~9^s7~ zA{-V;x{=97VXKAIK(0?P$PbrGN=6p+IXt>^IFL)( zRE$07B)Snk+wju^|K@0s!+VG)qja5(QN7IQb`vUh284;9Xk8tKY`^6|A-~wGr!M+t zwXP;hcBIXwty8D>a<-fe1zNwK*TunOdE5d~@^kkSr+!9?iT*Qvb&0aA6`Auc&Eu-> zciK&A6MQ1U`dHe5L!8qGfRD)D{@9YQ%P zb<>~2ArL=@n;|dm3028`(O+oD9j)&iyP1ubAcy!)wr-7Ha5TbI1j6nB)_5$nkC{P9 zis0a6J&j?-JNwnEm#l3@Z}(6r*zHgXt-B;n@AT^S*EFGEwow5C9#Quo3jpe;I%I-R zd=#E~!YSfzb8KoR30-SrE>vN%Et zvRMU7>8Wlq6Y@#;Fbm7F>#J}~JEn)sGUM}C$`bEJlIpR2`)ogn(35SM4v}85Re3u8 z6ij#`&u3@HLi^PL`m!H;FRNi}JYq3dUwNCjOx`j>8Hu>8w$C5D6dU8tSS@?6#4kQL z*!8g|@z9!|1|uej3cGZ6W28Rfj<|RUsXSjFh5PVNTsJjjPNY)gfcID@JT#S8Xg~jM z*%{RPBSgIXgmiY@H29FOJH0{4#031>9vQ3jaB7GZPJRq zG^;Wbj3Hcoz>8l;&b2-Z{}ygA#HeY#Jc(DW*0t0>#^0igzjj3j!Ds265j!<*7bS0a zSb{S7SV@}kTt9L=MO zGyCHM&93)XK0Q%Nbk;IQnVmXGD05L}DP0-+c0CAmyaZ9*U6lm*QHpXIL?WuU?6Rrt zO*W$NaTQuSRt& z{+^CV@pl}n)E6yO;G8O0ozQcck0BH|-n27ouN-h+`wXi&{VCjGG8M%yY z)TA#ZDivNIyxVRqGhS?%JE79EW50n$-P<{K`1yWn`iHiQSvs*iQlap$e|8H~5!BZE zW*05v0i83roD+1aedN5Tv*P;zuKgDZ<@!j2Y%tC2FM&Z9I+^WBa;ulUdif7qt-{;8tRv z6yS-{t*!Wu*zRyGc^7N6@9J-J6{@^Gx%K`66qkKn3D^888{-?mWynF6^8(HgzDqw6 z-M$V1_&mM5T!RmaPAJm=n+?dforRp_W9~{YE5t>VSw~y}H}FO_rWo7+t8%6Yz&3Z1 z+eGZIuH!3?(tV;9Z#5M*o-isl-uDB7tDHP)I}E;_+QeKTEq5eVg)w_Sag|HI`X8;+ z8w23?CK zjOfcZ^?2~Td_TVq(t(_VG!sYj49=k<4ZK82#-bR}63!xAK*6C!7jVnXJb8poHB-Qs zIdZ>ORjEbWERkG`%Mzrwp{-1Yu0pFGubZLVfPp|hae(RJjb<1ro6^FQyF{Xo9Gqs77}gf zg?P9(;qS{Uyk39a1T+YBBi&uJtDWaeb9^r_Fc06}d#8n=$eQX1e22U87^E&_=C=nm<%{Vn*r0S~VdPnGa9&E6fjiwlj8o4?rt4Rs73p z-yFxEy|RN7Ay#Ci-pb`wm3*sagU^B&s8m;vzk21+=@p0@YKh5m$iQO0X?!kGH2=}z ztTd^b21KVHewj*lVs)OPI-7Y^PcK~61kA`%3|0U+BDUAyeCLFi!X! zS$_oANSk!*FYoT|w>ewoQR3@|D{Sj@1gRUP3y)v(%E>TvU+WiRcsetSfEoD<+q!Nq z5WR+5d3UkvdVXoM`%uLaQOA`d%1q*&+?l@iXfIXiS5*c^x+>G>lY+0I&o-<3)dx1j z+qEhP*6c=rjT~}dU06vp7{om`tp^<`SGeWAd@okivr07!8>c3}2kIhcGC9f1rPghX zt{X#|X#NKw>=5xMsMI-{`G7y;uXK7tjgf&<)2@+rqUG+E-ZUoV16+t^*Z;f-#lDh1 zu932z#-^<&_nN|&gUdM(gSjY5JE!cs>lE6k?@uS1WCAbPp0kC47L^{>YcGFg)VHU1 zq?nSxSVzQ!-{pkl9!j`j0+2^-c8YNyAMT#s{!t$b+VOqZzh0nm`5z^mXhjFzgyqY= zD3a+PbtkM0-1D~w8hhF4dWt+{4%(e0cGx-P#hI<`nvelv@5q~i7*%n2D>^*9BtSof z9R0-B1I=Vv>@I^pQ==pjRKP9k5)4e{FQDG~ z@)uuyx#*%sQ+(memy7vFC22>UGsupLtFGl$uRQJ0aXy9tKr)+uISkj=8AwV;aPC(S z07UZbmtNa9XN939zbw7NLpF11JOFLn1*$twHX+luV9F+NiXh)qKHi9Y~A zKk(H(76G0m)H_-7`AnNCN<>Bv7z)6!yc zG&f3P*$Vsd{1J8I7fb9Ior5M?Z;k*O=NMJ^F4|q`V0R7nKgdnsSo@bZmwWuUcg#{w zNPW%_8Z4CY>yN(A>5`c}ZUO}7`_sN=C&r2ERN59dNbT6$ooCneb1cd^E?pT~zr>*-rz1~ikaHa<#e&WS zrhdLE9`HHk`^(25EZ@HSp-CEq<+mEB&o|s{28$X#(>#1-*RopI3i@1JpW*o?;#m(Z z2k$6~g694szT%9x=0BpM6n7j_zZzGBDwIhE@|8Ik!^k>-n$M~W2GFb48{rMK|{9O{d;t|k(Yt7#~%1Q!06`yqIGb!D~^~)Lw!;gGI zM!?6PIHZ1`t_b7geH>U`>R1dTqX8dpokOEj3NH&k&NII^w4$0*#xS9l!-;YzyNn~W z>fF$#faTKZ>6Fv;K`n;;8AB=_;Ce1>%ogP1)hV;muHe5v^l1)xa}Fm2E_6U^`J+ZaQL zex!18CN9rC4rsBZjkgS-u(4b*7Q3S(?|c|xxk4ZiX^Fz)9ys1m66`w9ag2=NjFFF?3{e`hQs- z)}AN;ZuGq2gX*8G>>sB2j2j16ai?5FiTKY(`0IZ^|NrBcqA%j=R@g??9nElKg&(df zWdmm_7VLJVTUd1kt=FCr;~JnwBQ1I|TL39cBQ{p;675ec^yI8a+3JQc?5EzvJHiVQ zoc#kVrV0@gT(8Q=V7i<5nBX;ik!2ry7PtGsLY7H;9IuMLKIielw!=ZORRN+AK|B?3 zpR|kqsfGqctM#{cS23-33SYBB=n3{N0aZ%Fk51r464!j8wfmW1bx#MI^A9P?7KYG= zlR%1mJQ>K{irhut*_`X7>Xm$_@6b_gxyC6pTvE7a#oWk~XJz0dg`K%CPEU@Hwe=+H3Bccx zzB|cC;;SbVc*CyhAG3S3*It36ZPj-fi{yn}sRpG;>Vf+a*j_bzAp&}H(n-9&1>(P1 z1YV*yOj3dbuLxe@udiA&^7g=MYtj2A?8{eJwsZU6vn0*G(x@{Zdo>l@QK*xvSr`Qv zRW+;{2C;3VF@e2`0yM5l+R5egTMNG^B%`^n=eqhWB)Hm?Etf(E0O^ zIfgqRZASQ9mp?akpJyj`)Tw#(^3K?ss!MO^J_h&*@2U82> zRT>KghHJa+L4JB#3SbO{YD4E!Yn76yE^Sto>)lLrRc{9+&f&)5rCv<93^0f$x*-B|R@fnV;yUEWtJIL^cb-z4g3 z5^^Q}z{eX7^x=PXoo{0LSmGY*lfuPYi22JEwU8Ku`j`J(ft!{PaNgh7!4K(Sshul@QkeC=}5P`YKHV zUkPJN4<)bJS-MP*7O7pja#Nto^=pDoC#`9Z-7ZSH7K0YUv+mc-S$w~X7!^tA^)liy z>j>I4eN_?SL*1qJivwNS>`WBaRO?cuVPF52#Hg(tmI97aAcb4OC&uFHIx*%eUP8^x z=7kG;Ka_K2^LSODf@)KjonHS)WuF^+kl+)3`-@TBIUE)+?beLbw+M&v!V{Z*Jyq4I zBBA50o|#y)q?T3%n?`pmNxwf}=#5O@dDNm4b%g-$s@-|qMapgiq+3g|396fVl-99J z!XE89*K&bUkJMQ11|H_x{ExJNP17omx?cA~V-&16as!v^>-(2>6Jp|(@e8LjoK z1}t~uy|tdK(3?)Z${pu|Vx5%VsqkIFS)&s(JSV%a3f;OX;#NAP95%0@BmQcI;gtJ=S>dtbE1Tvzz??t)Nc7^Uj)OlPXyqKR6 z2V#NeahVA!A&Xz~N+}unW=M|eg-=DODqiJHvjG0Y$?I6N?m1XW z)visLgXt^OhSqFctb5M($ITQ1tZvbH#D+i1I>u0SEH-%`p!`*WZ|Ei%x)2U#$|Z9l zB0E}h+ZeD+Hv+8t!s?l3Y7bW(yvj70m(AwRH<`o}JWf=o;p{q4~6-UxN@ zSh2^Wdf^eS0o@nKbo=f296d`mGo3=qOx0S9!FYnC_*K%o;>i)0D!sc#F!0Q{w}Pox z(rXH@D&>!LE{HCEicIKemVe+|KHpo`muO#zn^8crJrjE#D5YQF>lpb(!nGYkI(n}u z5)+j28ZE8R1Qre7=HP8b;0=Cd+s^k-bG*c%U!?}NVJB96afNlm zW|2EEmz81l#l^*%S>L%;G$Xt|92@A1g5u}LqGeb3!$53=0G<@jJqN^lq@1SqBb17r}j9S)8^UN3cB?=7LlC+&Puk|ZL% z$u4?BPwEe&s_wcEN$tB+o7AyT4{f%^;??L}*=+nKzci|8blN|+^Qa&g#QLGZ#fJ_Y zc%xwb@Z0coFWz={k_wO7b6_-l(np6*!GVqFI2$IgGStFg{JM|08m@BfIhk#R{cdKv zwtG!aEMZq=S61l2{=kldBET3q@mXnHP;nnTj$%5G`|>Jy5|rBR$I@fjL%O28 zDE(Ei4?b_bpmLHB3&)4U;*hr&WtfP8I(ni{BWA*kPfTI~FTpSSBgI=#JOJ_hd0$ez z)S3)MMD^Ze;Eb8rVeFLlg>1EC_W8XIm)fZs@<%fpCJgULEtm;jc}pp9!ox3fRo1`O z_0ST32DY<)8t!RuRUv;RbTFTG9yXl&xwn?FgZd@zs+>cDT#~mN_Slx{P~bu$4r5 zg!5b{tn=2@dFJ~#+xGr{qKFu=bMdT4E0sa|@_FkPqh)8+_drT38*5sG${$)%;+)DV zO(3?;ykiLYh};>5^o~Evkl5bU*>+llmJ02~FFu=~Rlv0rs{&4%#pZY+3-)1{TAoHu zH(JmBeVWMj*i)LJ9rPBLjN*l8<0FLul#kbWlNtOwGv&0S%-9_DMQ4%=@x_x%bQ684 zi)*4MdsA094V?Pasiv;hQH&wUBW;xgXRa$l1iBo!zWj7QEI||I z7kl3)#~ALqlkGw&PkV9k03Sk-ch;$Ofyv7anLy&3iSL z7avD*eP8?1D}GFePIGuz+=U55>%;b4exc>0r?Ccz;y2==$9sZ%W#FCV{xBTQHlAWY zh?$~26|h==02A4FCIc0+%i-o$9G=%dQt-%9+mG%!RbzcfVqO!m3eR{kb zz1blgYIyCDYUVRioQ(XrB=?S3^;9oT^}3zhf!Q2x63>IJu(S{%xekHND}rWif@h`D zH5}f<%_R5Lmk%oJXXLWDmj()93En6B_U*g_cT3o=DG-amN$UT&gw8^20Zj2F)n) zqoT?Vx~~3-x&D0JnHCn9<3am?fqVOYNOmLrVgLj0l79OK&64QC+5=0!Evjk6yGP(T zUDt{DTj+okTNSDrJO+E" - ] - }, - "execution_count": 2, - "metadata": { - "image/png": { - "width": 600 - } - }, - "output_type": "execute_result" - } - ], - "source": [ - "from IPython.display import Image\n", - "Image(filename=\"ekf.png\",width=600)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![EKF](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/extended_kalman_filter/animation.gif)\n", - "\n", - "This is a sensor fusion localization with Extended Kalman Filter(EKF).\n", - "\n", - "The blue line is true trajectory, the black line is dead reckoning\n", - "trajectory,\n", - "\n", - "the green point is positioning observation (ex. GPS), and the red line\n", - "is estimated trajectory with EKF.\n", - "\n", - "The red ellipse is estimated covariance ellipse with EKF.\n", - "\n", - "Code: [PythonRobotics/extended\\_kalman\\_filter\\.py at master · AtsushiSakai/PythonRobotics](https://github.com/AtsushiSakai/PythonRobotics/blob/master/Localization/extended_kalman_filter/extended_kalman_filter.py)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Filter design\n", - "\n", - "In this simulation, the robot has a state vector includes 4 states at time $t$.\n", - "\n", - "$$\\textbf{x}_t=[x_t, y_t, \\phi_t, v_t]$$\n", - "\n", - "x, y are a 2D x-y position, $\\phi$ is orientation, and v is velocity.\n", - "\n", - "In the code, \"xEst\" means the state vector. [code](https://github.com/AtsushiSakai/PythonRobotics/blob/916b4382de090de29f54538b356cef1c811aacce/Localization/extended_kalman_filter/extended_kalman_filter.py#L168)\n", - "\n", - "And, $P_t$ is covariace matrix of the state,\n", - "\n", - "$Q$ is covariance matrix of process noise, \n", - "\n", - "$R$ is covariance matrix of observation noise at time $t$ \n", - "\n", - " \n", - "\n", - "The robot has a speed sensor and a gyro sensor.\n", - "\n", - "So, the input vecor can be used as each time step\n", - "\n", - "$$\\textbf{u}_t=[v_t, \\omega_t]$$\n", - "\n", - "Also, the robot has a GNSS sensor, it means that the robot can observe x-y position at each time.\n", - "\n", - "$$\\textbf{z}_t=[x_t,y_t]$$\n", - "\n", - "The input and observation vector includes sensor noise.\n", - "\n", - "In the code, \"observation\" function generates the input and observation vector with noise [code](https://github.com/AtsushiSakai/PythonRobotics/blob/916b4382de090de29f54538b356cef1c811aacce/Localization/extended_kalman_filter/extended_kalman_filter.py#L34-L50)\n", - "\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Motion Model\n", - "\n", - "The robot model is \n", - "\n", - "$$ \\dot{x} = vcos(\\phi)$$\n", - "\n", - "$$ \\dot{y} = vsin((\\phi)$$\n", - "\n", - "$$ \\dot{\\phi} = \\omega$$\n", - "\n", - "\n", - "So, the motion model is\n", - "\n", - "$$\\textbf{x}_{t+1} = F\\textbf{x}_t+B\\textbf{u}_t$$\n", - "\n", - "where\n", - "\n", - "$\\begin{equation*}\n", - "F=\n", - "\\begin{bmatrix}\n", - "1 & 0 & 0 & 0\\\\\n", - "0 & 1 & 0 & 0\\\\\n", - "0 & 0 & 1 & 0 \\\\\n", - "0 & 0 & 0 & 0 \\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "$\\begin{equation*}\n", - "B=\n", - "\\begin{bmatrix}\n", - "cos(\\phi)dt & 0\\\\\n", - "sin(\\phi)dt & 0\\\\\n", - "0 & dt\\\\\n", - "1 & 0\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "$dt$ is a time interval.\n", - "\n", - "This is implemented at [code](https://github.com/AtsushiSakai/PythonRobotics/blob/916b4382de090de29f54538b356cef1c811aacce/Localization/extended_kalman_filter/extended_kalman_filter.py#L53-L67)\n", - "\n", - "Its Jacobian matrix is\n", - "\n", - "$\\begin{equation*}\n", - "J_F=\n", - "\\begin{bmatrix}\n", - "\\frac{dx}{dx}& \\frac{dx}{dy} & \\frac{dx}{d\\phi} & \\frac{dx}{dv}\\\\\n", - "\\frac{dy}{dx}& \\frac{dy}{dy} & \\frac{dy}{d\\phi} & \\frac{dy}{dv}\\\\\n", - "\\frac{d\\phi}{dx}& \\frac{d\\phi}{dy} & \\frac{d\\phi}{d\\phi} & \\frac{d\\phi}{dv}\\\\\n", - "\\frac{dv}{dx}& \\frac{dv}{dy} & \\frac{dv}{d\\phi} & \\frac{dv}{dv}\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "$\\begin{equation*}\n", - " =\n", - "\\begin{bmatrix}\n", - "1& 0 & -v sin(\\phi)dt & cos(\\phi)dt\\\\\n", - "0 & 1 & v cos(\\phi)dt & sin(\\phi) dt\\\\\n", - "0 & 0 & 1 & 0\\\\\n", - "0 & 0 & 0 & 1\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Observation Model\n", - "\n", - "The robot can get x-y position infomation from GPS.\n", - "\n", - "So GPS Observation model is\n", - "\n", - "$$\\textbf{z}_{t} = H\\textbf{x}_t$$\n", - "\n", - "where\n", - "\n", - "$\\begin{equation*}\n", - "B=\n", - "\\begin{bmatrix}\n", - "1 & 0 & 0& 0\\\\\n", - "0 & 1 & 0& 0\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "Its Jacobian matrix is\n", - "\n", - "$\\begin{equation*}\n", - "J_H=\n", - "\\begin{bmatrix}\n", - "\\frac{dx}{dx}& \\frac{dx}{dy} & \\frac{dx}{d\\phi} & \\frac{dx}{dv}\\\\\n", - "\\frac{dy}{dx}& \\frac{dy}{dy} & \\frac{dy}{d\\phi} & \\frac{dy}{dv}\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "$\\begin{equation*}\n", - " =\n", - "\\begin{bmatrix}\n", - "1& 0 & 0 & 0\\\\\n", - "0 & 1 & 0 & 0\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Extented Kalman Filter\n", - "\n", - "Localization process using Extendted Kalman Filter:EKF is\n", - "\n", - "=== Predict ===\n", - "\n", - "$x_{Pred} = Fx_t+Bu_t$\n", - "\n", - "$P_{Pred} = J_FP_t J_F^T + Q$\n", - "\n", - "=== Update ===\n", - "\n", - "$z_{Pred} = Hx_{Pred}$ \n", - "\n", - "$y = z - z_{Pred}$\n", - "\n", - "$S = J_H P_{Pred}.J_H^T + R$\n", - "\n", - "$K = P_{Pred}.J_H^T S^{-1}$\n", - "\n", - "$x_{t+1} = x_{Pred} + Ky$\n", - "\n", - "$P_{t+1} = ( I - K J_H) P_{Pred}$\n", - "\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Ref:\n", - "\n", - "- [PROBABILISTIC\\-ROBOTICS\\.ORG](http://www.probabilistic-robotics.org/)" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.8" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/Localization/particle_filter/particle_filter.ipynb b/Localization/particle_filter/particle_filter.ipynb deleted file mode 100644 index 65f1e026df..0000000000 --- a/Localization/particle_filter/particle_filter.ipynb +++ /dev/null @@ -1,72 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": { - "collapsed": true, - "pycharm": { - "name": "#%% md\n" - } - }, - "source": [ - "# Particle Filter Localization\n", - "\n" - ] - }, - { - "cell_type": "markdown", - "source": [ - "## How to calculate covariance matrix from particles\n", - "\n", - "The covariance matrix $\\Xi$ from particle information is calculated by the following equation: \n", - "\n", - "$\\Xi_{j,k}=\\frac{1}{1-\\sum^N_{i=1}(w^i)^2}\\sum^N_{i=1}w^i(x^i_j-\\mu_j)(x^i_k-\\mu_k)$\n", - "\n", - "- $\\Xi_{j,k}$ is covariance matrix element at row $i$ and column $k$.\n", - "\n", - "- $w^i$ is the weight of the $i$ th particle. \n", - "\n", - "- $x^i_j$ is the $j$ th state of the $i$ th particle. \n", - "\n", - "- $\\mu_j$ is the $j$ th mean state of particles.\n", - "\n", - "Ref:\n", - "\n", - "- [Improving the particle filter in high dimensions using conjugate artificial process noise](https://arxiv.org/pdf/1801.07000.pdf)\n" - ], - "metadata": { - "collapsed": false - } - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 2 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython2", - "version": "2.7.6" - }, - "pycharm": { - "stem_cell": { - "cell_type": "raw", - "source": [], - "metadata": { - "collapsed": false - } - } - } - }, - "nbformat": 4, - "nbformat_minor": 0 -} \ No newline at end of file diff --git a/docs/modules/appendix/Kalmanfilter_basics.rst b/docs/modules/appendix/Kalmanfilter_basics.rst index 7325dafdea..6548377e07 100644 --- a/docs/modules/appendix/Kalmanfilter_basics.rst +++ b/docs/modules/appendix/Kalmanfilter_basics.rst @@ -222,9 +222,8 @@ described with two parameters, the mean (:math:`\mu`) and the variance f(x, \mu, \sigma) = \frac{1}{\sigma\sqrt{2\pi}} \exp\big [{-\frac{(x-\mu)^2}{2\sigma^2} }\big ] - Range is -.. math:: [-\inf,\inf] +Range is :math:`[-\inf,\inf]` This is just a function of mean(\ :math:`\mu`) and standard deviation (:math:`\sigma`) and what gives the normal distribution the @@ -279,7 +278,8 @@ New mean is .. math:: \mu_\mathtt{new} = \frac{\sigma_z^2\bar\mu + \bar\sigma^2z}{\bar\sigma^2+\sigma_z^2} - New variance is + +New variance is .. math:: @@ -336,7 +336,7 @@ of the two. .. math:: \begin{gathered}\mu_x = \mu_p + \mu_z \\ - \sigma_x^2 = \sigma_z^2+\sigma_p^2\, \square\end{gathered} + \sigma_x^2 = \sigma_z^2+\sigma_p^2\, \end{gathered} .. code-block:: ipython3 diff --git a/docs/modules/localization/extended_kalman_filter_localization.rst b/docs/modules/localization/extended_kalman_filter_localization.rst index 5021563b5b..507ea972a4 100644 --- a/docs/modules/localization/extended_kalman_filter_localization.rst +++ b/docs/modules/localization/extended_kalman_filter_localization.rst @@ -2,14 +2,6 @@ Extended Kalman Filter Localization ----------------------------------- -.. code-block:: ipython3 - - from IPython.display import Image - Image(filename="ekf.png",width=600) - - - - .. image:: extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png :width: 600px @@ -18,8 +10,6 @@ Extended Kalman Filter Localization .. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/extended_kalman_filter/animation.gif :alt: EKF - EKF - This is a sensor fusion localization with Extended Kalman Filter(EKF). The blue line is true trajectory, the black line is dead reckoning @@ -127,7 +117,7 @@ The observation function states that Its Jacobian matrix is -:math:`\begin{equation*} J_g = \begin{bmatrix} \frac{\partial x'}{\partial x} & \frac{\partial x'}{\partial y} & \frac{\partial x'}{\partial \phi} & \frac{\partial x'}{\partial v}\\ \frac{\partial y'}{\partial x}& \frac{\partial y'}{\partial y} & \frac{\partial y'}{\partial \phi} & \frac{\partial y'}{ \partialv}\\ \end{bmatrix} \end{equation*}` +:math:`\begin{equation*} J_g = \begin{bmatrix} \frac{\partial x'}{\partial x} & \frac{\partial x'}{\partial y} & \frac{\partial x'}{\partial \phi} & \frac{\partial x'}{\partial v}\\ \frac{\partial y'}{\partial x}& \frac{\partial y'}{\partial y} & \frac{\partial y'}{\partial \phi} & \frac{\partial y'}{ \partial v}\\ \end{bmatrix} \end{equation*}` :math:`\begin{equation*}  = \begin{bmatrix} 1& 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ \end{bmatrix} \end{equation*}` diff --git a/docs/modules/localization/localization.rst b/docs/modules/localization/localization.rst index ddbf056c82..c665eba694 100644 --- a/docs/modules/localization/localization.rst +++ b/docs/modules/localization/localization.rst @@ -15,7 +15,8 @@ This is a sensor fusion localization with Unscented Kalman Filter(UKF). The lines and points are same meaning of the EKF simulation. -Ref: +References: +~~~~~~~~~~~ - `Discriminatively Trained Unscented Kalman Filter for Mobile Robot Localization`_ @@ -37,9 +38,26 @@ It is assumed that the robot can measure a distance from landmarks This measurements are used for PF localization. -Ref: +How to calculate covariance matrix from particles +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The covariance matrix :math:`\Xi` from particle information is calculated by the following equation: + +.. math:: \Xi_{j,k}=\frac{1}{1-\sum^N_{i=1}(w^i)^2}\sum^N_{i=1}w^i(x^i_j-\mu_j)(x^i_k-\mu_k) + +- :math:`\Xi_{j,k}` is covariance matrix element at row :math:`i` and column :math:`k`. + +- :math:`w^i` is the weight of the :math:`i` th particle. + +- :math:`x^i_j` is the :math:`j` th state of the :math:`i` th particle. + +- :math:`\mu_j` is the :math:`j` th mean state of particles. + +References: +~~~~~~~~~~~ - `PROBABILISTIC ROBOTICS`_ +- `Improving the particle filter in high dimensions using conjugate artificial process noise`_ Histogram filter localization ----------------------------- @@ -59,12 +77,14 @@ localization. Initial position is not needed. -Ref: +References: +~~~~~~~~~~~ - `PROBABILISTIC ROBOTICS`_ .. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/ .. _Discriminatively Trained Unscented Kalman Filter for Mobile Robot Localization: https://www.researchgate.net/publication/267963417_Discriminatively_Trained_Unscented_Kalman_Filter_for_Mobile_Robot_Localization +.. _Improving the particle filter in high dimensions using conjugate artificial process noise: https://arxiv.org/pdf/1801.07000.pdf .. |2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/unscented_kalman_filter/animation.gif .. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/particle_filter/animation.gif From 1f4e5ed8c32249e07ba3493a5b195da33e5de77b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 19 Nov 2021 15:54:52 +0900 Subject: [PATCH 418/940] clean up mapping docs (#571) * clean up mapping docs * clean up mapping docs * clean up mapping docs --- Mapping/lidar_to_grid_map/animation.gif | Bin 285406 -> 0 bytes README.md | 3 +- .../mapping/lidar_to_grid_map_tutorial.rst | 195 ++++++++++++++++++ .../grid_map_example.png | Bin .../lidar_to_grid_map_tutorial_12_0.png | Bin 0 -> 5053 bytes .../lidar_to_grid_map_tutorial_14_1.png | Bin 0 -> 14082 bytes .../lidar_to_grid_map_tutorial_5_0.png | Bin 0 -> 121806 bytes .../lidar_to_grid_map_tutorial_7_0.png | Bin 0 -> 5025 bytes .../lidar_to_grid_map_tutorial_8_0.png | Bin 0 -> 5035 bytes docs/modules/mapping/mapping.rst | 8 + 10 files changed, 204 insertions(+), 2 deletions(-) delete mode 100644 Mapping/lidar_to_grid_map/animation.gif create mode 100644 docs/modules/mapping/lidar_to_grid_map_tutorial.rst rename {Mapping/lidar_to_grid_map => docs/modules/mapping/lidar_to_grid_map_tutorial_files}/grid_map_example.png (100%) create mode 100644 docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_12_0.png create mode 100644 docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_14_1.png create mode 100644 docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_5_0.png create mode 100644 docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_7_0.png create mode 100644 docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_8_0.png diff --git a/Mapping/lidar_to_grid_map/animation.gif b/Mapping/lidar_to_grid_map/animation.gif deleted file mode 100644 index 210ff5817cf5f97c7fc2c855fcd47ae81c4269a7..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 285406 zcmWifXIK*M_r{ruxBw?kL{yyN9;tzQi#T#+?vq5u-~Yw)=6Us8*SYTd`J8jz$I;or%sea)m#)7HY9XlYrR zn3^8Y*HgmU8X4Oiv~;nwaxgXXH8uA*pm)O9$U|Sw+UB4m$=b)p@Wf#aRg)llE0U|V zjgy%Z#oETknv!BoGO>?$v$gZEcXoELr`XwhJGl6|xCOd-_&GWTlRbRB-Thp>f;}if z?uSFXd_uef0{ncP-MzxxJ>p$l!aOMP9+Yrz-#A~tNdLo;et~g*fzbiM$AXT;2OLg5 z5^~1(@JX_3LRd&-L~v?kKy+YO!jbU!;OOL#@Y6@56T>1B!{g#&qfbRdrAI}l#6_Qu zipz+OPmMcv_So^WanYH{CsL9V&K*xa6PJ8G`DA+9>9`XK9)7W92efYKs<)~sENaU0 zbmSLwv5Q9PJY$_rGtDI}xw@nJ(+*~PPNtvTO#X%+D)RQaL3YkR?tddXkd}~`9TUSi znLtZS&O4EubuuL{B{lnWdVXqpPI^W`#@XzQ)Y8mz)oE$9@zFO=9m_i!%JX*m=I5}J z=(T+&?&*op3})K3O8rlZ#>F{ltz~Ds8-4e4f}Z84{LYWwuZr8NJ-u0y!tXq`-*JZD zo4$J^Y4V=`?oR6RY}9D42_)dIkXMIr^nGQYy2FX3(x-_E;0A}a=&*KkM`gBdarY`vEb3bJ^pyX zpP@YdWcmJRHGi)5FYh9sU$gf!e{!_<*F@`|x#mAh*ZwTD|9*Mzf8%%ltX${wJN~@u z-Cuj~XX_z<^X}ij5Bd9dH`eYwpDL{Hoh(}T*}3q)TT9zx+|lO?ldqSS=I7^l)8pF< z<4bGvOUqNg*GK;H2mkUX|9l@^+gkd#{^Hl>0{_n(pa1ID_l3>R3$vTw*4Eaxwmz+I zu5InS-}fgS-2{CB1E?*RT^CIA>8@Sl)^Qx}Vq1(VRiVVfHZ<&0x_OcHoi zR1u-e-rt6ErmQ(3Rb4JBycqM& zLt+nA;z=kUAxSmYDuu8CNGGM$u?wySn#-HRyRwKitCBj49j>)3-`cx*wI*Io554N7 zk4xey^@y)%DNzZd_)deyS2+C34xc)LdC$-%R7Y|5PowY_W>l#~+7kXGxT#2%<<;h- zV%NAa+u?mJWUBwpr-f@?g}ciuU?D_b@)Q4VY?ROvfl`J5t_}%Z!rB#L&No3}FEI{` zYOzL$jl}9lizv#V&3Lq4XkDMZ5~#T_Y|QXa*6N_S^N2 z!3s6Lu>ao?S&B1an4INufI3fiC0qy4Vak~p#Y7xCdacw+{pwm-$8=JVkQ$^$K9O9t ztN=SuL5&d6tltKSXskIXB&v#_K`^B*HW6EB)C1EqT%mK__lJ@PkUvl7*v6o;1?`a5 zu{#ao){@hWbVG+^AHfghBRp$n>9pCAdse3F@|MFi~sl)?z_rbMIzOhPyYY*C8nL2k)a zzW8Tf$+FzC{?U6k)p{O+-ztcG1>Y3#Q)uicvPgr7+qnDfP1N#vq1kc~eFhVk^9$n# z99ZkDk6MX-NkxPurv#C~UpfQAnuP>4m_Gi-?=KIPHM2fHdoN&FY3*_&N_eF5+RWBq zlRQXp#(i{9w*XI9OzqP_pI)Kz z%A~Rqw^SAH`!njI2ku&ykOXSApNXa+81l=Z0{->D#x5@MZ|}!MrOD#lgdOB#6*s|C zr-}vtEIi>0aU!HM$aE7QA_H0CU7LZS;XqB6A?glds~p5??6rw4cIdsC3VW<^8F~>T z$kJ5lKF_Q(jJg(kV6sKM(jiOJ__M!%ZJEo(nAWv)ZS#e)nG~CCfOr~98iIBtNR~eO z9KeARc1bZFRT{FP(+-EXIKNzM@X9;O!ny<9Zw$3oLDcV$>u%TnE8YV*(C!gKI)|9R7tmh8$e-po$j6FMVt(|iZ zOcKsNqn237hAbOA6+h=c#u5_EXeYo9RdHZe3>9&mSfLCfGkeVLNrBUb&N6XH+`qdl ztc~oIWf-0@KFQ5en7cBlkW(rrON)>}Nv(a0Wrz+lTWe+{qmn9X5PBMD7^2v zvfUH9Y$*E_TSgB{{_Gf{Dz@md{Oo4Nb0jsPOSZy0ffpIm-UaRch@8gi8@gjN7`gFo`B>5DmU;ZuMhy|A3wsIoc z7G@+_{Fii!rZ&U#%!u!hqKaqRn5(qd`G;{z}G89Y#~jI+RCfa*`iU%k3?RYZpkDj-mkzTkzpqN-l95_Bx{P2#h1kw5Wv#X-VEtY9w2%ys3 zXAnB+1xmIMB4FRqbS^qniCw0F4Q)X>m<^(T?#I{`XUws}S@$SXVOG2Ps(G+93rJ&v zpi=r=&Z^mH!p-?7THnSnhH9GIc`X99-7LQB1-G(ii|o#6P8E;-fd-G*efsEg%cW@8 z_(!K3fy&!6C)$2CC%DIeRd`eZ`d!iNtpPatGRal?&ceb)L6}@vak%z?27gK85H@e) zkAHlbt#7&EislDLC42DCvir5)-ot<&O1sgD!=bqee-3W!K4+5K$l3x}=Dj16p?jUvHVO^@x?81I8xtlZ6eJVcE8URf2A;-ERjTL#$_}CNFp|z1|jy(V~(1ICs-e zlR}|?$go3A)P%}#<Q2(6pSUd|8PiC2QfzNT_w}Z0^w?RfcCl;Fu)g94ahz8F*;T zxU<*ugABt-6@1Uj)(;h|PXs+B8DrS0degc&KNS#EfHVsbnI!U>hPZ~-MDjC~8 zgm*wwQ4&&91vM;i_ER%5)aUGPX>FJdMSK(u_~=93@$Op%D>0*N*ckY?vm0xvvP=~R zHpHGN#dqt1NPrTyaN1=yAy|9sVLv6^WPw~N%z}CF06X~F9B@s8!NTiaHcHoCQ7b)T z{4m*fxCe#d0Y6imVLTw51vtloaj4>gNO3DEYpYPOR9M8VAAzP+YvXSStPxV!Az}WK z=?#-(Ov+i&v_pp9l@(|8^FUEm!%-n02zg*1+n@R}Et(h*v4SKeVW8q19hlVarhp4V z(F~tp{6LgF1W<4v{i8z56<4I2H>w#F(NzGgPdDmz|>e!gRJR$NtjK~Y_TIVHlWfP+uH zSp0`qW%|HjBmh2R z;D|UU^5$VeQaP&X63FBm+E@xDxkAV~9sj#c+4gSyZkc2H$)hlDdb^?HIVU1`Ro{r{ zB!9{KR7+8+nNLg#IPIU)rB_Q)&J9Z|n0tfu$i>VOVKdh8SQLnPud;tkt}s{KYv4SN z2nuWtHtf|6?QxOb4iFqA5D$GIZ$TgwKpmI< z)z-mD!+Zdi$>2C+=Y0%Lfqp3Hd~g{P0!|8*CXd1R`D_@IE%+NDNGyRUl;b0-k)Hkp zDU}SZupCMKgz|xSjp^L5{~Flps-L|A($|%gOEZP-;&qG-KsHBT`Os~;A@8f1OGf9A zk?1%8UUorqrX3w~S2=ghRQN-IrdLGopz)WFsw$zt`$FxLE{NEC`H8Zi6s>fPXg`mL zgExDD`KbUQ79a!Dkz8Yv!4`alfK(zOf4?P?0F*T_1)~OTn@4D{Bk^H57dxWXHtg~5 zt9_~*Nn|`_p85l-HMK^HJ5zpZM$=kFtLWWPXSG0G?`yvK7(IXQyA%}_bWsDx)}v2; zs0^gBMhlJl{fWk z-gKc8yJbB_l3GtORV0!dbI{n+sWBf-2jZzuW($B`ja>{V;|dB z0}Oq66S*XSK$75tq}xx&U=av`sAUjQ7_u&>^u-W-h=|93MXWwY+{i_Bw^M5bkYcvh zieHu6A0YW(HL4mR7eJkDzIbAi=H_0tG7>^c(yHA!R3FZ49)le8Vp1B3Dp(c0_xKsd z&U%bz7lK${66{M* zM}C);CjpuoNtp$u%Nv0^MxG9uIswbyrc;o+eHVArq@5~B=t`ZAC>I4=~w6wlKLE~QEw>5?`s~#nmJfTq9D~7yaGBELJ`b4d?LyTzv^`z?Xcs4Z21kT=EUB!b%@g39fCfguGdD!+WE>Q*IgdfOmGZ$2+)_gZUK-Mv1?kCcUhC z0lERzjD1N7zN2sQd$L4`0R7Dq-xCzezzCT0Kpi@9hg*1Ss^9~}d895lls@>H?nX>R zcFzi*H7TPGH2Ez|7=nl89gF6qYt@dT$@WfN$d6r9M1m__Uv0zb<06R1qX10 zXuE!i&K1c-bwoWzKrQw%!?r25bE?mdjM!%jM)5$0dsU;{3)gI|UzZsprXojFz?1k} ziMko$$&^t$+8J929-;i+*k9>ugyvF>vaYu>O)|YA>dSYqk+pY@zqw+>)T-VAfWK`!m`wH<>x#C74^Sb)dPTukw&$N%Ds& z4D~M1%@no!KY*Lx0EQ3hMY;qLW3U;rI7mfUZ<|m3Uuq98Wd47@?$anAEmJ;6T#ma` zYpSL+d2EiLndGLC%o5|M^-R{j`v%Iku|}K&*$|+~RH5V~czcrBy#$aC5#+aZAh1d^ zBXg>5pv$*YAOJ~3l|dx-M`Z`VPRsa!578`=jR}=|RqS9FIBX&3t?;e7=Y9%ru(tP* zeLfOuvd@5W%g=;}0PzRX!f~Si(NAA&qUPTDM;)!lk3&5qKEW+>Gw}fg#h5D3*dsy(}+m4lu z8&-Pd7gZ}PR~+|%+VZQWPmd7hj!}pCsWw(=uad3*OHq#XSvArQ1>U>)o{{=EW}qta zrr>sy2`5RU9{{cXO*I329y;>qd%m&8S6=zE`CPFR`bR%nAtr5-J|8Ukdw6LNP>RhF zk<^H6aY|lgFhy}4{;1p&Z|(A>UT4c?Bj4dEEpEYrTWB2+bt>y0RD zQ4?5VAw=`!yAfw)>v$NF(#%E388Oy7N_%re+g#)3n59M|1yb0yn`}Ao2wYZQ>pWE6 zZ_B?YYO2A$&hK;J-T0_X+2kgO5CRiY!umwhV@j*-pWkJZY+<4>1TK{5glrxzqzfHP z`IINDV5qaOJ#CvqLLX>*%r8-i*c6g%^pdRbYR-L+wvHa+1#hQ_tJJzT<6Ue8iXpTG#aBm{)*0%&ANZ(UR})C#xPS@T-hv*LDw|>` z9(*@#)fCPv5>Sn^ZM>&cwuCf&ZK8USp=l-5TH$W8(h}r7sWoiwVJB3ssyo#m4JVZo zoI9#hK%jPPX8$SXCF&{()*Snall!B>WxPi=dcE_S{l|%C)143dd&6>-b9S{Q0pBYa zQn4+cyoGhuIa%T!=azw@#Dvqxa;ZHvwDkZ+bs;c@06cst`A+GFH;LN1M#{#&Io!7= z`QRF1tM{gHB;`vm5O?mcyJHW(BrmuGH9KEh05RF)z6kB>*&+nRYE&S z?k49f&N5Xl1|IN~O9i;VFiVg$fxQp2n^0tYrb;${pMM~HP~5Se2z6xj%?cY&F8-T6 zeIp(aHCiWvp+Ct(zNk`;y|~p$Dv&uIz01i~K6$R{gY?Pg<~cJdb2W}i`V;qAl5OYw zMrS<`pvERjNx1yEr7`^G@#Zg8iX?Oi+e%0O!}{A*=Q2W`#H;U!2c>cCH>NX5P*bWC;$qRmRoPtQurv<6K07HKB2zmBm@vBQ3>VdrsGH^9 zH0(2XBDrn1%$87Lz2v8MZYp;=^u=B43HFHLCQ)xA{RAa_s7X&_@ip_0=B)%Mo`rZ^ zzc}VWRI$0Tl+tb~L`(diGrX~aLg+|~*3$Rq*z9W1TVok7I zp>-R%)>5KCJ9G5#G7|2Q;2Qtxm)!ypEA37WM^$XA5j6S9Lgb1lrTMdBx>h!K&4wZB zC%ms9-n3<@0)_<-CKd00kdcyGWC=X60A38IUfKU6Ui{JSV@oWt@li^?jarFt$Ua3y zJklc)>_2??i~hyXG=jKp+L6s*X-3c(xBSk8lt}Qdv-AkT!2nT3GMhzvc9ua zD$)syl=v1rRGPF>-2HIyQd!9mPMt<^_6g6AoEAuFn6=c2vy}=?`B1;eYB}vn_RkPI!v_v*`@?zzLB+{bu*!D_|J`Kas>fC2vbb{MoS zT43E#U3@HUKw^=dqZzxQd%i_gCK>@3UrouXWaYxv&BZgqWhEP*KC3%>+v}F}`x^PR z`5}#wIs4ydKtj)>iZNV&m`Tcg{;m0Noo#%UP^a*8b=Zi3;V;f+h+y;UF0zRZL{g+J zdqFW|u4xTQgX$2WWVZv4!hv-fc+O0fpN;fgGkbAF$0gB+j?%$(m}GUxmCY=+AbYat|;{g)Iwz;tpwokX(OLeXN|JaoTuP*{Zv|rP|%5 zug}f?_(3GkSllxPaD=F@E=dR7v5^5yj>fvt{qtLudpmJA{Uyc&KHhmyqF0f6uH59v zN@vAE#z*@0HyYd@dr3q|*jlz=#>EE<){>Qix&50>vz`fBovkYE{XK?SdVfuPnFy~( z2%lJsP_AVqG+2?^QuzA=GEV>kjVD++mli)AKhqTS`@GG83&4b{uHCf8$VYYbukL~k z4t?Iox-d`n;v0&;H!Iunfa1X(V6Yi9V3~AHsSm(n?SD<7LCD!_8b_yq97iT*g!$%no}gy~eA z7bUa6^h1Ebks0{NGXRVr9ChcQw<=;11IyS^m0iCX1C$*C(;v*JimKcOvUk#vkiP= z0KBGeYVuSLE^euc`1qOgOvI zMjPjl8=&z7fs^rexY1d^(@cdp0T3_1c5G-8elWiSx)@fZY{n+{A9C-fY3yiQ=-}OO z?6wILUZ3!4AHbI<@DXVxsAH$k$?@#Fe!K*fz0OWJHPkv=6vNl=KPJJ&AmLL)>8P>0 z?J&^=`TVI8Ac}Y!+CkUh(shZ9$k1V*o&L~es3jhxUJd>%n}4rSqF1=WR^mo|iE=w0 zZoi>^uK@T;Yoz9(B$_8&pm|948UnrnfZ_FE%n>LL>=ytDW@ktBIbnf3_NH5{DoA zW|rSleaTk)iX5|8HXq(WuHZ$&(Iw8ccJ6%VbSH5FFt@S*dlxd&2?>IM zP`fl1w@_Av{%WwO|0)epKlFWL0<$>r*YNkf+!K>I+tY>*BS z5+2G}9n3x|n|p3K*Dn-gL2-Cvb@&N`idnZQgj&gc zm_>*eMjBi=sVM?CqsHQ>28-Zw{qbf?0o&zVAAE(0i0ouJTIrFncX&^dz&~q>|hOSe@&(nic}L@TunZRafk^42uBA;^EYxJn2Z! zpZh>HqIW}59Y%PzoH(0Cqhq>6r>bfFT>yUXtS%QCwhN7AvHgf3wNTJ!=E5%NN(%yH zYdm+C?+uqH!ezUFz)YG-$s9dOn4Hx;8i!#cXc;K9s2LS3OVwhHptIeaEWoS1Pl}=% zr9h~KU9X)0(YCD#1zkzY%np`t5o(btE(_316HE`CIks*PG4(9L5cNGxnuV`A2j4d3y%=)~v4#)%z`qzkKsl0Mb;Ia4fCsTmZW()i|5P_SWOvdJ~&!!Fg9ZWa6g0VRF zLufvuSAMt4*;{hfXz{LnLBx*glXY9!<^lwOHc>;BHU3-wgHwASMeC>&i~*Vu*ygi}Wg*>;vVhFTG5XSB5oP@8#VV zdWpjqHx2sX(|E@!FR|QbXW+#ecyHXIYvOR;i5oQGjU)Vr&~$>SVQ{u8@gKiqZGeI2 zD#>5q6??RN=Q?rvjW^2td`OBuS4FJYTncUhkS@xO;AYzs`HUt=u#?4QCI7c;Ey3f@ zi90oSvh8TfhEIw5AWH~JwN6&y1wg8rDukg6hfaY%lp1_47Z5|4YKm78ip|UeAG%q% zyUjindHIL|!a0HPu~|ehx~)>AZ4S@i(IM(LDx3(2s1{65yMBxPPm>_EBz1S`phiG- z1HM9bQK|Ha#UNzM4K9#4I3tk>H|ozg%4X4O|ndyKe@)e^lLhp_d^9g zZ{^#t4irDnYm#4!7ma)r3^L*5kv!ILPV@#oe)d5;P=+lmx1Ez-ohvOSoJNGI5%S_y zC7V78kvJlEX-10GgtpN9tpcFBf0VC>972{R^7Yz%UdT`IJxB=%?w0$ls71PZwe+&e zcwLeH`I@oQ=*1Vq-@Sal%+$51a*lqg3D?X&HaMxwwsK!`vp}v9#k|$bd_5oD6|{<1 zhS5{`z*~1>QcG8oL>Jqxn!#m!8YVgKee?%N+}% zTX}cqhaS$?3@vrsZ3Ms6ZqnEU6a7tjLACmNY+)oSzGm& zNuOO;Gf|?vr3}_uS=q-llJZMmRo3=oIZucRtZ=zaQ?34_e4YzEsb8F2vWlt^BI3F? zbFDF#f1UH5+XLp%OJ9_X*9hIeIv0MvvN8DV2YCc%@aZ*+>z?rvt&PiDMrsxb{g?m2rmJq=wrx7jZCvi)LA%XzvnVe{0}HG);-;OipE?fAr9Um8C@1<&{nOcWJQ zG)ZprUpjop7ycnJar4gDlVx4mS8smarcQ7)dWcYIn51Y0EvQ>6*qkEQZadH*UDA4m z1$u!7RLEdtCqs{7!j3Mi^NG9lmn1FozF`9AtY6{?{fW93e=jZwp00Z&xpGGD^HmR! zk$;v3*AI5*V^b8V6;>q91BQy`W&jG#A_PMFvZUD&bJ8E1Z70=?vW zpMe*}u8;3YiYGm3u%n8t3-mZa6+#DUy1!N{9gZB?x@j3=qaqpQMdCJy%QN$SO&-Oh z&$g#nd8WuGIUFZFKB9NvBPNZ!t3XGEd`@y->oECl81u}yW1&2>+>Gseu3Q`)$5 zQHA`*ix@ZV=C}FS@)+Ibiq|(vyT>e|;oHpWh`kaVc07$fn)h6K7845Y(EV(T7biaT zgSRa|Yxvfq|4GA=7IEQwI{9KUF+B{Cqa>0OyKo9VZ~HY)Xq%Z=Rox}eJ*?ypsyAJ< zdE4l7Y=plfoB<{NV+Lp{3){ua+MX5~K404L-xJ!|8f7N>=&52FKz1*>sHbSW$uN)+ zlD0tT{~kBruX!WU>iNH>_pxMrLr0$E+KGG4XYoX^-rLhHVss<&?koHFmS~yKd;Fvy zc}+aY$a{iG>)_xLfk7F8NaDV=6BuSS%e^3RAS2KJ;k#}2KK&fmRZR>o1Qf0|YZPQc z(aIR}3yq)B-3n`x@Lf-#SiV!yX1)xb^ zyNWV$D!-jye7wTz2m=(Hs?AI-%kAe%Qzm5bIN4757;shiWX#I z2?kgYG+v^pZGAE1@wr#wvb5^5)dCrL^Z1Id$?qJS4T2{z>DZA%CC%)>ULiv#M1|4N z?D~sleHXOV>|V8VpasR`?jNr0W5ve(>z zu!NV7qT^z=OoOo8b3_CA(;g3XUio#!6%UgY+)?{OQyL)-Ibw~FUl&|v!uOh(3 z($6pV%<1(-@1r-mA(Eb!(>WbvOFu{usn1>|t34V|5hYwtYLyBKRarEAhRLcXjBU*p zDL8i6*AzQMa_3s?-7;)Np-t1c-f5SEx_27KmPx|uX+#@X-$pbC0+a0m$R7DX;TiCj zdqz!3tn}ByGIz{vU9m^n+k_2zc}NHG=Ku)e`!s>TPd7o|=@7AA+mi^ec_=xTNg^po zB2CqPNct43bUde8<9ERsQNH69fv#pB7Ew(ZeGLDwqRPhBW7oe{q15YqSx@v*9uTF2 zAkvd&{qU?wEBK@D4pW-VUTAO8*P$;cwnjhg?)V0sGoEiAi>50XM%j$$LN(IX& zP5N`zlO4s)hTvckgNH;^no&T^WqZXxNu_VpmoO4;zcqusLUQ5VAu9rd6_?JV#KS_w z?O^)%&mTT_M>E6P+~oP1uhjJO4^BE?!;UEHd1;~~GIkl0*Y9zp=#4ks46YReEjxsD z{n8*$KcPDG`*-T=O_HA&+R1$a>hw62!*>?Z3n*N<EkDSkmNzlq*wd*Wp7oea9rTXDFK8k@=^OgADWqKWIz-cnWFJYT8&qkWAl>&c)x|1jW#?)f>JlG|kq+tml6!ZkP|3eAY-WTvR%)XKv8dD8*xOTORVE%t1W9a_xxAgF3W!lbncJ$0%b2GIlgWkpYry)i za_uJBE@e&9&kJ*VWQLx$5K6aGt)*V*4y{Q%R}z7R7Z+?cy-_u*tN3v!WaD3zSzx=) z=lVy`H88XsPpyj-?Mxgz!?787cym)T(fGB*Zhu7`4ydMw=Lish;=>Km@^NXkQ983a zkPlE8zv7V&6!D5YtlGVo3;r?PzsqIuTB<=xG*uT_#34IqEk#79;u`uno8 z6E+YN^HhQUoK7FFBwki@w1s#!FOobhZWlxbp%RuQzgG*!xzEC7C24|rbK{Y89}4jH z{VCQ4P4B^ot5$XuNMctY?h7ZEP@;mfTJ}gQgg;51@vEP)oO8g&H*9RD-pi$T0_s{J zbvXNL&SOr#*m3>q70^hH2kl}fBN<{=0^6W@H+6Qt>xo!P2TyS;hH>Q$gP@*zU&S=zmqsChC?))to^zdX9rtg^Q0Ul9nGg&;`G!4z=W-Brz zD?8KXV3VmPlb#k}@e1Ng71;6E_M}>iie-!Y54gGQ=8}fBEJ1tmWN}_visdes08h8tY@9x~7J=TNI}o-AS)(W03>;Wdld4Bu(Frfuii>PWNCrTl z&OwR*8+au9$UUD2C|=r6dJ}qVwV|U$1NB<Q+BwrG<<6EiID_#jKrP%eaM%)bt0c4V-8PS! z(|!4jVTXU4XxW7eD6b^>qm+N~NkE%`67}QEvMPKE+ieGvIvzFKC-pk_j@`a2bW77M zt%Y&L95FN(bRqL8L|@E}C*ezm9*lc?KIJlnB^cNT4YsVf%HNX8(cxw@U6={*BMCf# zR=2B`0=RUTsE5Gt54pfT;f$?Uo+*y7>o!(v;6v0wGome0J!?g6@W3J`CyCo-skCn& z_JakeOaMUB0B-JVU_HQ^;CEq#TAMa4j^LOC3<)p!*%!WXuq*VGEpg*gUu6!Nr$Ziv z+R;;n5AP9k)`n;mQp#bI?$;$0PKP>dOMQrhU8N0^6qQlC#11pAMB0py4R)tB&_9J) zRwO2Bg9@4(4#GRxy{3vj1PB6FbQ3sAEq+LAun{iHfVH%GbvP17`|aGQ8$KmOof7a5 zgT}4^oH%iFAQvv99^;FyMKTp#&|{;9twa3tL$BQZ1(hC+nh!%bxN)eo{UdwH04LG* zfCbN;Q6`b&rNb4m$k(_Ctv~}+)wyaJ%mBNk4m*y-+@zW&I_(@+?YY~qI~RKVEmVqm zfjldmNfk}v zQB=J$2pj_FHlHpWeY41L?HF=pmH(A3^nyK2hvkbY!2%+g^UlK;d|vw?$~t#mQWPez zG??m?RCdR>fEp9kQJ7`d8q_k`S;&*{S!yScZidYq*W!v{+AaqPde_Oggjo&(*TDt)m?r+!3JMAbXlPLxE+#si^phCH;V}YG!++j1P zvPaJY8N6Rn0t$Ha^&hHN{oi)`XGbJ8`Sum~a*MunwEl0KW>h_BW;dusbI@%W?r5Zi zd}}?e=lt&xf;i#lid!&x#$Qzq6V+ z{d2uExZu4P5n3n;MhqN~ePdQ=YjNFnI%V)1EYF1rY3ysCt{mOSE3YFQK0j_JP7N`x zbu0pk1PXD)657sN0%85b?toQ#WOhWyFu8X8y%`)kv+P}EAA~0*gu}DPKcJX}0h1!H zU%x+c(IbOX+dy$aB`qDfe#G&!pbJ|R77GB!(w=PtjdP(8@pwdd$pJd2 z42>NFBso`O;)?V@W(irDOU|G2Q&Z%H@C!%|mKh6z0=2tsIRFsmNd^?OI7J#Q=bONYYfGVYR@aMUaF~3%fx#u7$0a=z1bn2v`BcvRupb_=EjxG+~w_ z^XpLU(q?88d%9HqY!hI1Z@z|QXY3GnZqsf#*j~JgF<#5cDtTY&yi7M6z7j}|U1ek$ z_>iV1>-_A;DnbLg+-~Mw>M)|@`qck82S*V|k{!^dwuNqPXzr3zTMMby7$vggAm{@$ zoU@gw5;)XLN3w2wy_h4k6%Gx3192)<(xI=|-!hN%G8A$?y?#SvXllJkX*9%6c-yc4 z^!2np2nfvs2xZS1xneaZ#SjbJ4Eqdp$1=;89!rULv5!!Ak0_KI!O@=0-)vCgL@aS7 zMF_*)7soKqipcfPQV|`p@m7J%)}={U^2`aF87c@Em9!+ve@Lt-Ve8CgS?c)34Gny4 z=(54x`lFZtg_SGSPZ&_azq$quF4K%g##tmm_(Qfq)k9Q zmgLV`9EJKRj>a)-GNe${OR8S>Ig3m{)^K3tcoAC`PaB6k$Ubv*@@UN^KZm3%=gEOB z*tEZC<4B?e#j|8u?hi<-P5J$WQ)^pFpXeOs2qiS$ftMMm@N<1$fLsZak>j1)zCPAKOY`|$H=O=U zDvU`yz#Z)RJZPDcW%>|oxdXP0tW%LczzJ*&g?|84aIh@lYu{+EU4|U0iK*O`l-Pv( zjV*F}()$pslF-w%>cuP7xilwx(cTlvsS(e=$^}Nsr9j(Lgg8iQMfc)l(RLhDj+CKt zg9mr@iyl|AYEsW%7-x_-_P+%a44oH3+xD5nZgrj4MEIJ+fgOC>@9k~FjqjqPTyb{8OP7hVt?HBCtF#I00Xue`_m0W!} zJr?w~^dF;MW;qY$z70nTTwH>UK=>NhUq?-`jD%~%zU`BobBh-hIQxEouq?fZeM5wmrg=-a7#kNkdm2sSr{k)1~$jJb<& zJ#Q16ohp=+S{a5GN4og)f}?q=8461bCupP&_az#*uE(*P7=~pJcb=AY0*fYn>?i_nNMv~Pr zv&xpFI_Eez_A!!`j**aLB}sLRgpiel>JVjBNTu=d{rUZO|9L+i_xo|(@9TBFUe60H z7#%FGof!OY97SgXS3jtQ#_c9qUgh3K)^%KqlM34giIMlLMfI&Mc%Jnt{t_5<{>^Q> zS%96Z>c@WitRHiAM{u}7*2frD@?T(vyXELou$PZ?i?0oW|2G8QQEiHU$@XGt;4`8% z3oI)$@BBiHVik$gg;z$ypB7$yM}SAO;i7B+o2I!6GFk#_?|?KcF0l*Q5O)Cl;DmZ9 z%$Nf>=2*Oh*Zt0?0rodlRNz>X?dG8+==GezZ9tEQ9x2b?3{{rbK!&=EfSHmj~XoyobEy z>@nmzY{6sk6OJYDRsxT0QwSgpmXk+3Bi)GqrG0W~efEd%)8pvOe;RrET;+IsR4AaBLJM!^E@~04SQ<$&@sKQB&Bjt-++f+RM%?gHONuCEKeLu z=8^IupJJt4i(Xi8jIRH8_u;FAdUpx#cMh80+b{NMHdE7bD$t3Sl>~i$oe|xX*L+UL z=6kA@-KH=u#1@Y6dD`}CW1-~)@4(0?iq-(O~IL~mXhOP7TSyvcb)p5-Y{ni9sKk;qKuy2YW- zMy$6^T&ACN`qh&S5={!2rn4iu+nXOTIlrnW#%kRdW1$aEf)tG{H^IgL0-eOPmDO=kx*Wh28!`)Win!NtlNGE1d$T z<%pe#7@mBa3d_Zq2Ce?vNVVb<(>*7o460)=Z)v9hkgjr!d^w`mq3Cq2H4}IC8v3_p zqMDH0$t)hCs|B)9-ZrOBGeFMvojh^rsk-aw%(rr+VmTMBBwMnQZI!V>is)|9Q|Gy6 zV6%m0aliAt2+=GFx%x2SmfRTugIJ7GbrFl`b}UBV_T^Ln&@~VSLV@m)HEmu=nWRZk z;m1rXlVU#pwQ(SsRtMe9y3@15R{37fE#{Lj%KAFcz;o+u>QF;5kb zQ<3KE6A@i2Gxy;#`>BEsAa1qEySOpKt!Fq_<46^(PwEa{&_6XGS6tm+-z+osqzTLr0Id3>%8;C@{1dQ6*o}17zq@n80+=K_f0@jj5STm{77AZanVwYIr&( zs6u@LQ|y}mR61EybwUcJLsC~tN5~-M1bEC4@_F--_XN+1$K0P3wg2eS9x#^ zL=Ahy385V3*|J)sR7B))H}%x*0B@Ypz1-7h6GT6Xp8HR=Z7d5AoK8)tORXArK|eFbcA(dRQFCd!36>L0;c8ycsf?2ov?&`P!h}XPmF6(PlrBA(I^N zUH1-0ji#m_A-b~tZ*V&5BwNS4A0hvAAxGB`XYr+@C(9;vflEHId38oWE_Y_w6eZL5 z?2zXi2-RbyosjERL=MnNH@S9dXn4tU;JfE)6dCo|d-kC}^c zp&*hw?~a@~lu%0x>D|!hsD{{HaUVyRI>33Zr(X7^u`^5)5Bxc)Bc!wTIr8MCLzKX3 z2;}YXMoOeW|K`$9lS2+137g4Tl!N2d0yI^wwee&e3X~xXthDb`y9dh*!m_J@T**E@ z=R8WvUBgtg$^*XpQAFGs$<@5@F@4JP138&vocCMX&r@jJ3e=1%eFO&cbD2Ss`?VhOaD2M(ty23I^wBb`4nEUlA ziV!iLZAICjmuEfdguZosh9E4@UadTg71Vpqf?yFqjRj3UevR^};oX}s4`imbP~h{s zx6=)`r}7A`tf5mKeGa9HKF8Q{rDK0J6LUb|19tB4=XSq}9CXDa2YJ7Bqg$Shs%!sx ztrN~8J!xY{{zXehfS?RH9Q{!RWXh%0c*b1(|Htb!yvMZ+PaWmh=<;YHY`ZQe7c*08 z+c>Q4fTvLdYKx^Sl@N3ok*k+KFHWcYea#nNxD*)((O=ed0Tzy_E^wysnY)9ZCZ1i zy|0J1@?i0W__-=YSS|UmU08BD)sEE%CsE2|NcdB?Hnc)b-;|vY`s7~Hx$4(^8bptk zmDpR4e$sYfR4|?e#u1J_7drFm{qE`6QY$k^A4qhbHERXbbq*#i`UW^IZ<^g8sn~<- z4+kS(|2v>`7M9#^zN743_m%uf`?%%Z*DRbxrWi_s zASe1tk~kqpB62Y}PGN!-mdEThOqGkAUsx!;va_Axc4$qFs{Ckk=GT8b&dd>aS2h5E ze*EmT11h}OTzU&_!8;r`Bh^W{nC_nW*M%W#<4j7GN}b&#Rf`|;qm0C z62O8_@U=Ns006JE7k+=%4i8H`*mOb)i|h)C@S&(uwz{H0j_n~%la}y#h?7v{g^AFe!Sz=YpR=bwt4^E6 z)`Q#+XzBn43vaXb-pq13LRasc&S*2r?oK>;HQFNtHM*@+&OXw;AQEh#6&aq#LM}AB zmOAEp%6oXoxw#JnEj7kvW%`9H!xAattJTt^R{m@l)R+v`BVQLF1ANf1|2h8l$@)Ea z*oT=tj%c!i$1v}_Z}Brb@7S)OSiY{9Lh~JhU+$)5?FXuSP4%0s*@^yA&I@trj?i+2 zH_0h*EsdzNSnkH>?%|m&@lN^kY}6Q^bZTGjdsD4}iT zJhXxVQ{dDW(&H8O0Sh17R0b zOQQ+PP4%-(uEutA`}v?11zukjUc{<`)5JM>UJLoT0QILC%KO1iJ_C4=3x3_ zryS47xTfnD$R7v(&p7FoU6l%pqn7FDo&hu7s%|BrQU6FJ-JI(9@L=Ki~ zC;~Z)H7jLRf^3M8RMb5CR5@pN-k#TL04~J=ibQk$!@`1Cs1*t;G+#6Fc0L|R`a0qw zG4xUaYK9&#?n;+*BmY|MQ)!FUFMtTxvQ*8natc^AZkBW)9(%_hLl2f1BSYu&!b57H z@po}gG>k%1A5IS{=6p_~W1ar2zF7G@2dd3!jU~ zT(nN<@&65tJ#h;8*)_@YVdY&N8S;;fw86p{06q*SK4o zcC%o+PSCz1(9<2@v(GfoMn+|V5mbY>GcDdWI&${2iz@S zU_=p6pE__?HQase`im+BsqT+t|4C++Cn6h~;Wp2{4>zxsPuziz7OC=DoZ>qYL_nE1MUsBQW`5Awpg2-bF z!^{_}?zOP6TvD&@ePx^?1XBJ0eceTu!4M&Hy#1R;8VV z?>YNNusxkXC$mtb(haX8DAT7m7R=WUr&qNf&7P`Zqd0&Cl~m^TdVuk{U^*FIN~YKZ zx^jUNzA%2u48{|0zisJ{bx;U&fF8fVPBdqMn<&_Q0%ol5V(P`Dj1v+0+Ls>u1naPL z?A_G3Iow!k|9e*w0N3x%Uxa>7lfK6z!S--ej>aa){{yO zGWM%@#*cu{2(n*E{yzSuMXF{F;f5b8y@|lxMc`reNeGG6Id~?yut8lOF20|A%@2>p zKgxD{ngAK>^I@vQ&UJ}M&!fuG#WTT~rsJNQm$7GT5^QfY4cp}J`!5Du&o6n zjK=D;KTY2+$Hvx9(OA3ML_xkj65xESrAq$yp!$1+I@Bi}qzwV4x9&Pm-q4vlHN+Dv zB+CMPiXY(y*nZ?wme*^jhpMrd4+wlEeHUwi7|h!Ow|R&IRv`C{lsU)uQJ%o_cInK% zqC3?^Mq)Gb{xeQx>Iuqs=zwKLcRMZM+nALTjP5V((Yz^hcjA+UnKe=_d_M6)@Xt@C z2H^X>2YfCf!LPPX<%wMlo(_sG%o}e+=u;3Yl(7ZC{ybZI_`I1BAN~*_PgId5Pw)pC z^EGVAAi7{M4?RY$FB zj)NBaCqQTAp9mdW@JP+6R@Wl%YuA*eK79L9A6VbngTfy>(y91--?3 zvr`|EZ&na7DaWerB>URVf(ewW4zCCkEQAO3;nS(xA^_L_ac)5kSw>|ie1O$4wk-(| zzZI{`H#S~(DXY)j&oNUlGy6(TXVYBi(QX4-|NGA5s=u-I>oA(@BSNlY+;!lTj=a?Z zr<@o?t;If}vmtdHq#DUhf9AAUl5${2#r+@1e++7I;k=o7ie3`biv?=tJa~>3v(j&h zxa@m(p{eMY%e_BfCsul7s2@Kd13~~C0;~$eADtH!iN(V7=3zN-UrMN6iW$S_i*B=c z#V``NV|MDZMZ3%#w{zNkA4}8@`o4P*VB^|+BDMK0;46q#XPMGV)W z32OE}EZ|Lvb${vUpTj&~73ek^BYZ2BG?Q7YLb*dP?L-Ouf63&-%%&=KoD|}IjsfU3 zAm{90tQMnfJU;G6rdD_!lkB0%vDLDsAZh@4zwdxfd!Y24^RAX8{MbVMX?XJQz~wOd z=a@P&c^>M?0=JO4lYWVX7-3d=NjUyKFTkaO(-B7hd>>6u@_Ye$lGL8DL=D9rK^LSh zhz^D3bTLF3LxPNS8gkk4zhu_q#ef$-)YKJjaGCtEK-Z!e68GgM5ytDMzJ6yO3gYFy z=UN8g^*+CKH&H$-vQSI`R{|8dGrunZP)2+q-h(bn>p{%D;PaLz#RBz;F*ol5c>Ykt z_WPt5Yf@Fd6ZZSyCSMnOfS)A?a^VnsNMPUn-kW+Z9PqP14eZN$<1gJ*ZMdjaou+g$ z3CqmQFztsk5W!d7@=Zn>N|09VUuW!=&DL6qM;5o=I;Any25-s@A>{tKV z&ROIj+yS)1UvK-T#{CjCF^Yj+rxm>E68TOk6gHGhIOhYD5Zzt7*Oesy7QEeSVb2;c zGKT7>6!m-s6MP0o3NfH35~J1Y&xxp5_7F3}IL{g$j~y!OZ;bTOwACm#v(%Q$j_MC5 z>zr;?M~t8zBRLeUf-_coGnJ#A-r&k)`@7J8KO zh-J1@3-`GD#*?~+CZGBrN;SFesvEo5QmQr{K^y>n%F=!@PX|t7A!=+eR{i$RHXzpj zx8XJHTOt|&O3xG53t#H?pCt2REiqb=o)(z`(pGsAVpd~%jdo@FJMOn&)@5}`A+ zJw}1Nqvvs#nWJR(jnK*FunsGfgn}KZCTDNewxT*}!8jANzdk7+vBW0M3@Oa$o(QaC zfZ@CqdXZJlR9gDDxPyM9nE`jOBU2}Ivi`Q6?sz%Nc2mJcz{R#O4NvYx`$xVvzWSF- z+%!kOZRL56xY1P}gZ9;tVpaQ+WvWGppoT-KQq0OAV^Z3NafB^3&qPa^#jg{9KoA&& z(T}w{e$n7Cb}f1FuA&k=Uq+Wp#9)2LzW}GZqqjfx9l@WEs#ZHW?NUD|uYKj`cHYoh z;dT3P*W4@xuHr`X&%8%x6X{xQc3<|<0CJI)PVCTQ*AcL{n-+#M<`BoIc0iYO3E z9~|Wbn%hp3mNybko1fTE0Fh~DU;zx7Jez<_1r;kWQl*>#LdcaygOHl(BIP-X6p|S? zzVlN#R1(Vs08#&lV;8J`*5{e-vkM1^dYou5pRQ;d8f~iPegrrYjtSma4gmlG=ttsFPp;SInfztb26(vMvCL6#L7MUw{9n@O z)*_NeW?L@1AeZjN>fMm4TQzhm!FQP#1)UrSYsV}0p$~*y3F8lE?-;zTgSllSqu0gH z^tD;JxWCm|_Tl#06Bdv1-xIkO-T0>7BKWKB0JmxmImdVptq?J)a(^r~P|Jt3mEAKT zF~F_JitdN&^KzSU-@U#=grnn`YydFDWvs*IrxoAHxm7aQ3=^_-p5N@qaUE=7LAm5| z+n#Pue}rr76sRysI}v3c-s=*2$t7je%GTt8*zBF$KZ`KesIe(JYwdL>UEEM?w@>2C zyIFVf3xiKANKtjV%0h{R9xF`g@B?LqQbxi|Ly|I8(pq(nWbVxQ`niilQcbR=`j~orDO6Oe|l8EblXZ8E*!s^fmeN>tiO3_BMxVx{~ z#PV(a&j~Hu7t68OlE)I)^e%SCrq#&`$xU#jyw1KE!S#DT!n=hu+A2!hEv7f_+M4_tfQT#OC zeXTUjMrGMRBQxjGG}B_8Wz+L2^9~EF^jZd=X+$CNDd@Gp5B=(>sP0Vhn*Ni-*JOB- zSLMp)Yo*%Gm^e~t@z5OMk*)*7DHvDeXXvV+BGz~9&Zecl6Rh9HZZB2S%_S^Ej4fA!iHJ}J1%3#ywJC^(bux9PKXmuQj9Gd`|Ynv7pBNKwjSW2~W1Kj~$Ilfaw<~ z>56K7UoK>5SN^brX)}rU13a~bf$E{{BRC+4-7KBwF1gj3VVdN^TuxH9zxjY+W3l(L zYWPmqHPAcFdk6H#>y~A4e~Y6U-*zh@9w@5&_x~RIRai56N8X8GcO;R+#NRlhWLQ*> z^1|2Mx?H?5!{VSvFZFV+9HtQ}nkup9%~%I=z+2`@!UzvE$bFy6O-2uCS83+OcU~L| z(&ITPL7)I5Dd0#LFeg;VrDEB^8m|=Te|GY0_NPcs>1Y&$QVan8Tjrm|X3*a3nqQtD z5H%*#cv}M@vNrQs1y8drF|K3AW#@gG)!kBNgZLHp_s=^;n~_)?NEi&Nbct?je^6re zp+#Gz$CpdOiba3k*oTUp+!W7TvZ`Gl7wFf``Z!N=-U>XFm*ZZzLU~ zsRRKR7etP1-n(BK7Il|^4Tg^-0iFWQB$$%t!)wYIjFEU(kp{Zt+x`^_u%TUaEA%n@ zos@<4Jl6i>M)Qpv3XEUeACaHe=3)kd=FsmU%{}|Gh$rZ>|MV(cZFFCF35?&^&s7xu zJ?!jY3ODEl`q==jF5fQokPs|m5Fm>of?S7o4`OPO?jK`yzrOK) zt^nOBI1z=0+v7p5lkU&D@Na%tWowJ%yJ_Tg#QjtBpvc+8@dxkjUQKGV!Bc_}toV67 zo^ck>Fg9iIGfmne;l(ikFCNOeW2Q2j@=sU`XAZsyJHno8KNc`=oB|f=ilaG*Rs7ZH zi+nVIysbOffnuS{A6s4G{58OmM7m~zJ8p-CF4KgxLz4Q^ylh-dedv;~YVe^8S64K7GS;W1dIpJFTMIP%fIRRhnW!kfq! z`EI>6Wg0SoKEd&PT@O|2KHopdQ`x{&F9J#6f#K&;z$_(Y{9%@W@RdVdyKf#YE%T|2 z2N$#fV7*q542jN15KkqbdTsc&S_^q$+ynj)F!kcLYkZ(qQdfdWI87kqg=z08Wde@h z5}IMphB=aT4VgY@G{}epr?I)3@lZ3YPv=@vKNRXPN#QbwC-&zNe`b6;x?^E|@<7nH zvrdUJN?vLD8MR@ADScN@6;BVS4=MB6B+p_!4|n4YWpj`q9*9B99W{@Is?f#gMn0Q4OoGfGOhb99BNq}p3lxkxksw=cBUg88vFbtb^2`6aPYWXSk z`1pR<>wU!|6w#@-F;O4AP5mJwYXG_!;{GA0;;Ay!d`H82S;LMjoFtblz=P6fi21wAz6w;d=Nzzz0rh1g;L1FgGpp{KfrRitBoiP6xP{?} zRrMv{gIqM}AbGsqpX;~OAg2S49l34_aDw0~Fpy+40JH<0h~`s!o2Y8b#~Z>Ef|s`< z9kaZ6*<;n)k$r7;@S5?IzKa~u{Ds21scL(E@8bm)4|PC%trb^yDl|9YSDB89f=~-I zXbmFl)RvF`91E$7(W<#$4P#a|4Z9MPB z$Pp6Z1{@DWkbygAFsebILnUmY-gnz40`%Wv=Ktw}O*}ny0AL-m`lDZ<)nH)zE`XoJ z^OKXfk8R-Z;ag(CjF~W7a=B}%_qle6%r9?yw4MV%A&};!)ON{lS2=PeNq5tGk!r7u z2c3cg@tE4D8*m4#d&AELdu&rI04q4`lO3m+I31DOp3mhbG(F;5-T?y!-2K~;Klq&S ztKGv20Kt6+;mGjEOkVKo+f!aL(wrMY0C6c6>CYoupN#su-3f_v_5RjTx|3(2Z5MPo z;5UjGwjc-x01kB6(J&1^u?>GGdBX|i+tZRF9!2?03ak+Cm_3MIby%c;5>-p+VI$0p zd0F;oLj~s$&|p|wPHA$8uCP>u$da4}p9>R)GJXMX(%O?>*$REJ5Dvg8Nr)4?uLn9u zYq*L+aB(2XN$ww5(sWjb>>f~v1)OUFmhS?8Z-|9@d7k8)lp~#s?NZHE2J7Hk(oTW# z%q%?wsDX;X0)QAi0ENCvF>Ki1B!3~nPhis=rtSxHK!Rvq0@aR@6(@FNTIG)^y`Q~V zTz;7spUVHY;z?$cb*t6wE{Gc%^uMV}{_ectGHa*ncP*wAqy?&G*a zJFs%}gU*9<57!ZE_y&HJ2HrXP38wcie!1vcx zo&+EL{5RKQ6W9@Fgz;-L5R(6iof)a}4n<2GoLfn#vndZ$BmI#dGOh?Zl-PN8%ZPoh zSri)CGyjKlu7@pl3FH*9|7 znHi2HMkPUwQjalkpunTr&p!OI*0z*pooEosfLkGOXe4LM;N#e}+p19#iOM_29w{c? z69tR^1DSY&O*mjvK=#pYfDhZ9I;|Hp<+3mJxG0DL=U5ZG^?Z9At{)wNuS4}L*^u`M zN;}Px6Oato)=8rgfyN<8)C*@>b_kACYB*`)6ZEjB-TU@+{x8Q(HBTjWc-Z;h z%qx7E*RS!c5%oN)`)&b0# zy?c@GF|J7lvpyfQcQpT24!8>`&#LF!#v&X@c#p&4H|M7zj2cTBxZ$S(!NsZSvVk)g2@rnzDdXkushHMk+(QV88?;*@e-0-USa3pLGe2uU zNr@kKfh2gj8mzJpXvOmFa^~}MhZHBrt|geA80frb1FE>U1eohIxR({Z2G+ttOn1f| zU$(xTPOU%Ras>#6{{dijj_y?SshZGD{Ne@9#JwiV2f_0{3r}PyE*%tmE5b5d*zSsR zio(_4h`O5B2TwnttTr2-wsQHJGqSr?AWT0oD%GD=dUY@YV3ob$2b7hj> zBqWEoMzl5w(rA^BJ8fjqh?U9dza;LwLTh;YXqMa5Cx5|X?T?jr0Bv}_6PMRCOwLNP zNYhKDkDLnf-liChn}yne*-vf5{W#U*pUft~wc1g7XkB;=SOcwt0RV+f0m>XM(zu)h z^V0j`KvUwA^_z;jS`{YC*V;ch63f=Vf7Ez=V4_n$s!pV60O9Jy&A*=Txad<7f2}Sf z;I7vdCt@I)lfY&G_ev|@`^iJTZxp^AHs3qIO%Wv@rOs5VD7X6z7KfrMzW&6 zs1Vi*U(Thd`^ZsVq|uH8aixU!2}4!hKmwjPP8Yi?PDnN>>tin`$8mgmMIQBjf_?S$ z`Pio(BL%t(ApK?SaD6}>?C{1A7_>Tr?}NhlHjlqRVTv2XWO4)p;Qnz`N1yKMzx<$t zKU#Q`_2_-+`MM8d3SECUOM<2m3<7c3zQ)9 zETQ?bc6oo8I!7{*-Z6rNWokSPX2)(l0Xk^Au$HF5)*@k~^AD8A%>tb|pT19sGyL7d zz2NBGXTlzTqBCoG#r`3L{~-jThXu(3&{#9$Bs}YlDINK6JX7GdV}+7^v07Md{YYW9 zfUaI)uWq4kN0pHpfRd7F7 z{6x5%h;mIWjKSYQu3r3%I{WbMzn&+T_Ciqgx{>%cD!6UDT$eQ8NgRMV3g8Tb>JTw< zOOKKdkw3n!Ex!47mQ987DfrCq_zyB%nB<&(I#Ni>N#80)CXELZC;yV82DaqG6ojD* zTxzZOF=c6#dKYuXhWLpbp~jfnVH8$Byb{e%8vvsu-tXo@zmLQe+0QnYjqHtBHlo+IF8HPk}?ijxk`Gk zaF*d!cYnTx@jARu3N&fMQwQpl=JdJm>CO@c7`Sl8G8Aor{w$FqAQ)pIV6U@lA@tiT zQcJ)A3rw3NHK^$d(TBISCIZ+wuu1aZn9duYS|Z~OA^WAWWNCO4Lh1r*8Ty`fco~~^ z^}ucor<8ZM1$iPQ3)z!-JZmL4y~n(^N3q?gv3gfx#g7&J!gr?b+?R zyStrAIQ2{|~M zOP+Y8E7G)7UWaeN0h!u27(}`#9lL^{7JSbNbXXz>-upe*kfI=;gAPa+G201Tz3eJ- zC4SoZ`ts{zE=f2oF@uT++ET%ejz4Gf)Io>^ibSEdbjtB^8|i?%_tKA991y@Ln10&* z=+TK^xTl%|H{NBAZZ|x}Ka2AwruTMS9n;j7|6ctmGWp1U^<(?+nCXpPsp837D#;*} zPHA92LMHiVALIMnpUi$ea+b-jM>lAb0#F4ds;BcG0(JtIpHl2Z6RcyAlgS`qo%+)q z<*&yh6SU9tF|4Y0&+w;^bb?S}HfHmE5kA_@HNZyLB&ZK=#_T<{^ITj*^QE~KsGy7) zgp@Nl-K$WO-d7#u%~ja{I&YHResAP_VBE}=V!Y(~G9)U7#1!wgQSRua^A>zW0yNF! zs>Fy$0k47NxdAJOd(Uy9E|W1zUG(~101V6Q_m%M^5@4~kmT-Qgk9FDHqdaRZEGj1j zB8xlNq??jQBXWX|9sy@`0sV3j;8f9K0OSyRWFnLxaX(eFh}57Wf6MGi=GSH7UW6gu z;736RFi>&w%Ao>mwszT#<@5KZIy|X=2B76H0b9yd`<@(js%1n z6w`%*2>RGfwu(e)TTiOc2{b zz53R{4lvd4c3*S{Ma~3~O308|fp1Wp=kwu%KKJ<{4^8#hu@;3m+NGyoLwp`w&tb@^ zwg`;qh;8~3GIbz031YV?`=-JB6Ggr>}@kq@uP z8i|aod%@q?|DgT$VRYL6VhxA3RkRd$a&m%RFH2FPJ#>2BZa-C7np3;$X?Rq-%p?ZH zh5#^m{i6s~YwDZL+tPO!=GdWQ_xD(RIC~P3J_?=Q;Iu1HzTAFYw}V#hJ&n8&(Jw*k zKhYN4l<|A-lLV-`2v8N@^090_Nsca5Rd`#CyT`etDcw!SXAohi?}Ly_$+J1*`6{`- zFPmIXoI8&`-LmMiO{g7ti^@FLLOhk}hyt2m>QVf4kHrx@lb{l~V{bOU{H@)`1U5kBfUBT+N? zu-0mkUKV6noWT2Q1@&l(njQ4#E~#o~>U*F4W#_8{0;L>D%}bwa1B+!QwXD0C zb(mrXuUqBjDs82|$nTRsa#(A?WhE} zWdv@AvDSvestzja7IVRGFE>W3aOcQN8qgN!t}A3- z$es~0$a1tU*9duUc#x`+{j{&Ls?^ik^m=UV>ftH4-IVJ}C>8WI3m=Brsu5p7_!_JArqS%<+AENX$P;kg03qHB9V8M5K(Ch!g(^*{!=u>v?^ zI(xKst53I|rXg0DH45G3Dldzfh)mC(JS76M+(xgH)XY)M+F&z&6Ewcc9Og^+7oT9} z`Mg?9Rd z)=w_k)m4-MK{`D(9}657RAhmddrNs<(X`-SW}f_IFiHFI z?MbG{4#lhYx%s?h7&AQ>Z#!U7V7hn`wbgp~hRUy9Nxe`+ZTcfTMtImXT33lIk;V!H zRM#2&wME%d{g(hLR8?0nv1i)4SrgfA)U30N(XBSs#cJr@Vw&h zYvq|aX;#5wy^@3JE<=pvEVvBJU+%2`OHDKqgwG6NY=Hb|pl~Y=HKzF_G_8fH@eNBl zF@jK$(f@4pU}YeaW2+tUhmr~(KepXVXq%Ph?YpApK0#gSpV|6B$=#g-PXd-0oKfFjZxdSbY? z^F}yf!x9k;4WtJ8FEs0XBo{`X%6~vH-lxDPA*Q{BCkV)#9*hr2CMU_lN~c{!qQdQO zPt%~<&0#J6NW^tO7gwLS(%n3`2}r)7UVB-z-#^>4*|16(B)iV=T(!QchGiWMJVmj3 zn2KiOY&ir?Y!C2kc0%2g9;*b8#b*QpTwUdJW~NT^&b0awr-|ISIp&bO2~N~M_gam! zV^f_tnkL@B=GUk4aa{RI0iK-f3uO7vf2)$hcokWqvS5Wby?m)N2vgsR0!)QmGd-5XeL`L*o+gHo7hj_t zXG493Y^BvtQJ>%gjlFlR@Kh{pg;H!9lQ)rz3 zx1RHR0<}H80_NeDZPIS!f^yv&gAJu`)-XhF-jXAL6_h|pU@CMNjGw2G@fl%Qcmf#) zuw3l8{*ZRvcx*kVanHcoOHL^C)g1n=-^f#F?6P5=f4{w9#7BDfnDX)}{)rHRcP7*gI;Ij)D-F22lnt>2x3m7QX|F zQ%VnL&A5Vx^)x=%1=muQxl^l|<%Ht5trLoLKp+4fVgpYm!xKq|@ciq38tigXEBB~CrseF9`apRQ-P+c3M3&Anzq z9b<#p2MiByk|O?5kA>F5eI2!S!5%lR9z*g;UxBx+Kygp%QZ~n?Aw6s{JF%7T;+3Tn z+T7PwYC8yACrY#R~T?iiJ#c8`G1cM$9B3J%O$65+7>n>S9(sV+`Ne; zk#FhTLA@0gz}ltBcsMXH>>9f`B6rD7Vblnwh?I%zal4#(Lq{rKo{$x_H~MI|`co2U z*__jjKWk9+k%|XfV{M-uz#^xSKYA=4i>o!=WbQ^kdT^*OhyqgK`m{I#+|8Ep{_-kS zUM}?>&y6t2OGkuqSGhU++>Qk~JHzT97PK*c8rel8m8KHC3J_5GOh16B4MFtQ82Z7F z@88wPWm@O!H@Eyo^kk8uE+Ok0^evFSdQ#%ir&{i7ofh>3^4kEUx&!-4)4oUF`aLX^ zi|p^1v@a(Zd-{Q~6siaZpd6av`j&f8_Z-!dYAgp_oPK|_JxQ#LTJ2ViOEK=S zn?EE(1Q+V&@QVDC)0}8bdO!V&(bGOVu1#`w`MOdIhoLjVn|=YLe1NDZui$D#^tym^ zy)Dbgw6~F9dYdbpmkOa!PEzQ7M=a-t!NcoUZ-ror{3}FBe=9~bL0FDGib;!K3A<%_ zPU5|=PYjP>H+HmJjQm?=BI(r?y<8_P_K)HxQuyj616-YE)yFcx<;84Xh(5LKtsotI zIkTeeXBDH{Mpu1GxhVL480}y_Q&SsHYaYe8^NtL8)z_tViOAQKgj6O&a(H> zZlUNiLR~=IcjS_`QM;5^1{v$;S4TzWjf6HQOB7kPH1uEUg~zPf?)MnPmpP@}MIh~k zf??Itxyvn^zQ7lpNy8^c5L|p-Uo3Hh_4s?~H~~m3W@!Dr*)Fj5rNB&E-)3W|Ccl*Y zc%@E3lt$%8PJ@${6P@f6^OM3B)?gUGgRTB`xI0IjR_tX0 zeR`#s`Ma8#+IKp1isDup`6Njd2cMp?ef@fa^~xspY|MyRh1jn#o}1ONpK5YD%x1-t zj$c~5&Y7er+eCqhqgS$J9%h6Ny{_wdofO{NHfzgsc)cqU26VlVkNjxb&$S&*}%@GE6A|ZFmoxe9DucYK0hXhQpMp0{XFxe85^f(VxXSRk^`c) zekJV9u_T`lb=`UMJ2Ce9qrW4Xb7}HzdZ=}aJHW-3QQ<|Yq_*BYcNAOVaSp6EQ7J*; z=KQWfM*jZ>3nkmO6do?L<$jQ9?kBZzwC_qyM;TtO ztX99=u~G8P`$KX=-RSfcrbNywQ2Zmp*0`~)%$R@8fh6J1plV&ywwbRL{&^Spm>J=8 z+*Yh({P6`=+ItJHm!k&sIW-#ZzEQ#|=X@t4S5zf>iIh9j=qQ$FSE21KikT?MiCwZe zZxL5Jk{eyydL*|UbuHKVMov^O6eU(3#xHO3c4@aAQ8B2L+E2)bAu;ei!$XGNp6-S?c^Jmb4Hmr!x&1dsoPmaRXp>RYIY; zR*jt|%ZrElSYg+UJmj7>PrEoBezf|+ zGcrn2UPknT+jN4%-yjCYaF1h&QXE2q;UP3jN%PzIX@-nTyYX~N(!jE)SD)jovz?D- z++YL_xl!)=k1*F%cf~?R!}VCz7BMr+eZ3~sFiB!Q@7g$fIj|04_zq?99e+*aCgMyb z65oXwfE~HGRp`3K+9~oJo5EyP8~>^&ksqnd%auD5mLYaxK)Xef#@l*w45iAgJVA%} z-aTH-us>LIp~jz2x@0LwT)#4YjEq?P+*>)5%ewX^fmapfqj zRzkn_x2kug+9FCfdRCB5`4vcAleWqnY0E}w!8+6O%|N9~Bi<;*LL*YR#qd@V;_%q- ze!#skzLmXL?9g&##enmySiFv*|8@4T#<;V6BG*6mkw)+ul>O$Bfh)_@T|7kWZ$UTr z)hYd5LlFxpg&~w_>V?5xK2YIHNpzoewwqXV88?1!{-ew82|#8WM-fNO*8ME?xQGAe z+u^H7FOH|!Dp+;v8)g|WVQvqYL-|s%f<6jDQ~=DC|9d)* z->+MkTat#rm!<==>;j6x&xL}x3R9Vzu;bjSbsO+C%;}IIgPi^$Cjbb|BnSxOKm*s( zuec2@qvFRTMXI@G)vb6X>o6O^lv;?I!79SIPx0Q3I;hbk*2344y|R&O$9|GA(ELshKAE8uCfU_AEVUxI<2R8WgAFGG3}2iI?z6qXAkies`M z2c^;?ofNLdL|K(gIS+`*xIA2HT~>;Qiwah6-PO&qReGvtTgKvdGK1qkFltDHv+;oz zH@9hst)rrr&kPw^70oFjdM_Mn-6f2ItTYY!6yydv)Jpmws>AP2{D@$uqv-^oJJ&*D z#MbFTRYLX2x0~sFPX#1~te=UQerNYOLlPj$)cXBSgb^UEkkbTR0-pFF`T!`5B>2Av;nWDfX;-9#&#AGw+>Xek=NCyXWkzPY6^2Ruu98f$j$DQYZw%sjInt+( zq)qn|#|bXXE^e7XEwB6{$^)gPrzZh$V_I2G7?n?yGMIsM&d>#;)=Iq`G;HN{mzU03 zJ(j86GHyVLSzp+(EKe0Oz53E6w)TZuQHN*jue9RN$tzw;P0Jle!Vxzvy1Df^GP06) zCd9ug?fb!j2=l#DZeo;7?I@x&=m?i~C2~bffB3et6z=jnTPboQ0eYdYYK`1oE7qQ) zf8|?S2$@_bIyM10a*c!499ME5yX7^6`9KbSpnZr~$+m8CeTKVTyi?QZ|`I8!c#Lnbt43P^IsMi&G+Ouh1 z;S9qn{q9i*;1FaqMCma4@5SKRQWZw#e9>vo|j7YHD;jSWyP{dS7~u6@WS< z?<9DgJ(oAprER=;{c}?Mo2PoDJf?uqiR6MTW8`;sBeqnKJRFv2>Owsgy!!2WXKRRngbjfO(?MUvXY}Oy-uHNvoNj7#|H_VX{*b}< zb~kx040KH0`Acs3%SnL1!JgZ&wH1_>hyFe(#v98h^D5eU?|s$KBK}j?{|e18D7H_h zZKHJ4RrV~(^~bow#YffNT7Oh~&*zkf)i%^d^i>WATDs|_<%TZPPEc$R&k|n*DIxvu zlzj=wa_lzWKM|K%3{Rwq=s;sL^eJ1Y6rMBtoUS)!$tO=;O!x&=E;;Nbl? z*r2U84NkUCVt?7s9}K03gCYL+>n2)!&LdXRKZ$+3jwyKkRI7J7cQ(EQT4>OV=yf_7 zs~OesIe*&M?Y!{SCTR)1qS*DR$)TG`N}-4=B-Gzr3;UM$VCgQpfWnqeP7Tp1g>~vJ z<>r60R3cV+ zNG?q77iyRMzw1}b+f`L=DcFa4|7QPnu)mjLA&0$Gba{@3nivX@odG20Ct0D$Tl@IK zRyE^)IkH}|+E!w0?@S;+Ap1QAb_t$_?y(hO5Rh9I2kHGL@T;GueW8klNWu(b))~pl zN$`GFP{e8sI(fEo?D!M_Icf93hJ3JQNeNX2mD|TM3bf5#ZXKURX+YYofR;EBoq6u} z`DY0>!;V{!(U(qSTB(TtL6L4p3<-8sd+`jrRAjinZI875X*|l?LqA+r4qp=HVy6m(o{?*(I@=k{r2xde{=)U$uWP-%Gt`pRWYtz~w} zqC;as1l~TdEp3six#e$k2nkE3!%6{yeE^|X1cme*U=2Z06Mc&+iAK(}VEr(Yt{?j7 zPa$x46adwB`s1gmPVL1^Ot!s-++WU#6M$uhU}81!LO0(c$&<+98dpIE8>tYMC;e3}Wv@|eN! zQEHvhPJP|n4OkD-}nmaUKAi6sxc-B>{Yw!q9*|jg@z>n1sBRH&>&@^^R z$h^?tcOa_GW)KNi8b8~}I(Af#ny5wcD$%LegFbG8M5N=7Rp zK2YUnff>aFIE@2A(gisgKD<0~c<|B~cE!-zAy=gcE8%3wIJ+@|L8pZmaPpTy% zdZS!9tsD1}r?aSGMY7B9erR1720%D>TIjD{ z(uMO!;0MS}^!0*ZnQOwg%{3a#)9i$L##`kGzEc7^xUxhR1WN$=w7s@3orz_-Seo=p zeRsqFT+ja2=)lxJT7+1k5F!_RemZ)01;H%l3gFT2dD~=4zx8&7|Dkmu`|?}&-g0kJ zot+B`Q$`4Ih=s{eM(LLf<5{&krma46n|Dk(!k-Ap4bH(M!A&N@xM+B~%*`NrR7)2< zn?n#{5+X_JFt;Y3E>LV3)`7Xy_WhkLy8o>DfgjP4Z>0Lw6@WH((EDSD6K_T2K!~0H z&CfkoYENcvFJ9}!i97YZW&lMVd1Z>*@@J`!M?KlFjd^Z{yz>|h2gea`*qnijmSyHq z3wi>ueG0>VGnE68GYdFw2=zKWMqhbz#wrW05He85#Q>s(36owM8bP8CpX54} z`(;c5J)KCFxU|9VLs+KhH*9(M=^@@{;lK1@wt?KCA0x*j7`h9N9Z|4bs#HWjgfyn* z^~xQdrc> zw27~2c?Cym8`oS#D(D5kL&!y6W8p7=p#h&naHoM>_m{6NTa1ajZ8=I0INQ}@B1x0EyUs$T zg#Fj9|IDCIl;y=9H&Gg?J6*u1@C(~kgp3AqL$vssa)E|EG>aP{xoeqgs3q;HlAKvk zguw4v`$H<$?vU}6xao=WRy6JrK!NXTPO2`+VzDm9Asvroa0wu5mIYqA8oPN00 zU2xYO808au$W_EgI4db1$q}!B-ULmv8_!P)0p?+eXc%S2hm%fh<%*%()hs1^4r%_a z6=fARMB{7tpZ87|7(uYJ0p2XGShw_Q%gl4+fmL^`X9q++N>uIZ5Y1-j7pdRcZRm?C zDP7=svQ1`{04w;IkW78QgIrPNB1cfp3WO&}P}2^yf{$?rO{>II0UZm^@&qA@S*hZR zxAI=T)bak$SEPqi8Q^(MSd;h$%IkWn^uxnP{s^EGb*jQl`#WX+)1D1HkvND3H??XPpPRSm)*Ki^}M{a=3QIAlk`De z>WgfDqGFQ%u{lfApn;l#Z-X8a@YFznuBT!O{A9m-R^nBc1$J0|RO5xbAovKwVeObO zU3-zQ;7TZ!tA8!3-0z>f^FAWf-|?jhx5$FNAv8ekW^fYQ(vv#3^ZlvX5fKoJ6Iaw*h@ibr;*Zt={~J;pYaR_LDzT7 zLbwmZwFNn{SzNDR^?2tmu4t*7*~;j%pO+BuLkI`Dpj_}p5ZF_PhjaXI>~+@$?h(^XsE(=Py? z%+*kGzl-yk`|p<45+K7!IV(6-Um_{Z;jU%M6-)V?gy0vOweIp+Zt{TB!itv#gZbz) z!Broe@6&@EnC88NjD@;LshHgckSBdUSfd}K@l!O>(H}+p;~NuK>f$7qw!|C~y%=Ed z2BlXiDn?`c6;Ku-ULpVH{`DRG`^8b>aes9WDaI{RwL7gNRUkU-jyqP|Q+UF`YwLbJ z5mV(Zq`v=YB#1ZNS7-$vCHzPky`Sp$;UBX0g6HYu^5}|){A1NTr8gz(spJt#he{+T za&jLwWFa{<`t!TC#~VjcfSLxXABzKG9S%M7{gR48lmi{7Tf6;NJjgQR&xGwubs%S& zlC=JNYsmpxA1BF;jYjFN+Cs8@MfA@qD=j7Y{@yvH>5CVQc7WRq0q}IbWFqm9L2t_7 z{nFa08W2xh zN8|cCkN)WdYhtiK@_~Nzq^Q+-+542IYQlNiVs?VW`Di7zYAe|Hq7yf&By8Ofjh4Vq z6l2>aQDI;nL%QzOgq&vaIngKw1Q%esXlXKLad3lps5Ik9h2@dH`*Q5xrC>z_ZbwKx zKJ>)bYhTI_HfU@f5x&MC2lXH~69KR=g898dZ2hkqz48J1={2Jv?5E;P&(hFs>*pRq zt4D&!ZnwKlV3*MMgXGncEPek)yOqhgC)fI0G<__$8JBGmu}1Ti9;XgX*=FmGWJ}f7 zRtB}gCezKv2Gh0%56NYiR_sGg!6vi7VB^#idVccJcfW++dujWwu!h`75f+sD9|cnV z_&WeOHh1xv-Jp?`HY8h4QliRUs|uyTkXtD=FT z(5D!d?Oz+)&{6U*QLeSWgdQZbQgtiO-=JC4ZaYhNWq*tTI#$^Z(dlBe3&$1}%%#BE zfG1jW#L`>;g-p;Js)UgPtaqFX=bWKJE7ygR#!gmGhVlT;6LSx3`;T)n26ikp`yelF zu08RgVW{6RZ^L^M8dgS+{C#{^`(3Oc;^{{6PDaX83x0*k>gd}z+3bzOB@7@#)+A<; z9sUA3Rbmvgs%^H%osu<)-M1`_g-ppfL>aYV)M-!(?o@OM`vE<2^!cCZbs{sA3~+03s-D7%|2o*4@sR zc5D8D*Qy&u9yAY`?9l~}2=(HOn)b27;3ChZt*K8EDib9|VNQpf;~}A+?jer_TAvkoHZ%88|8tbaFbX2-A>lD~hP zzklw@6(|C&W><q6!RHHUS7F?ZAA)eocMtT*G2Qdiy*#EW^^E7|?Ett*LN8^p{eLy3{IYj`*2c zf{xO->cr4v2OL4RCu8gugPWHxY*TFQMJqmT)6hCY1{BQR~?iky%r-n8i%yRIr%sV>@iWgZ0-I|X1D+L^jp}bA*gbj1@I;^`785VIzW^IBJGe7B?ha1HVIlUhD-gFuW)i*M9QUDeqhbx0H0Y zVp^4p-fN~xE6OllY216E<#I1dT^Q7Av%GIE6*lq8*q$&p0=*v6wQ>ZV#znx>auRs| zA>PvU zwAOQCnV{1HKZj_nNZgkWB@M!*s4NABH?{bK+Nt~$OJUQ6u%ll-b^mYamW&f8kMTQT z%P#AZ5K2gZ@H7C+wNMg&c&ANM2N)>ahY`H#${M?)d~^B?%Jz!)%L$6Bl4y;Vn!Fy; zshkcO(q50hbMj@F)HfwidDx{BIq6^XOCBS zLY|s6CK|h>WAf-n2E*81FQtX^a~Mptd8G2~l6)$|vS>3b%XBTxS#E=3sg;WmqwJxD zmuJ$&`be(Fmq#^c$&b3kMpX692AjF8u&Wo)nCIu>*)l4YqHAth==>IlC(fIzQ^rn}FAa|rWLRpkJ= zo`im8%}TzNaZ90WT+o=D^i!i=#b-7q40OrRCsb*x zKeJ6hDJ>}XWZc&2GvvMITA35_F)Rg9pmh zySttvI^yk{S3mpTtDhJ=`8(tBcU*wquRIo?bn}6~g8*M@LNlLE7Webbu0JVe0wDc@^;jY@(G03AX zqhsmVSADiiVRXB#WB+|}JhVOB#$qd~cg@|WojGPN@>tLOOBMYp-{~(MX0}B~FCJEZ z%dwP6XJ#2z<>~3U6h$0oK)i-SLN)c$qx4sJ@|7_ycl--PBh)51VN4^H+spj=3??Lk z7W(p(s5aFM( z{}0z<#*GUt59hfck~+$hv{NVtzpa_(Me}uMgAS@{;3@>11Lh0yPk$a3 zjpBdwK7PZswH8p)d}6|6&XU0-ib=QSIOLLR zzs%?C*y3Fj?)#F^ubOBM%Jrre9x4WDZiurd-!PS5^EBs`fpEPXApBn1=FMGq#g*!@ zb8D3BZ6~>}3l9Z7I%;p8mejtu@omk6rMVCM6Dr6vo`|h&H4I zRK0L) zo-Ls7uc*HAqU8kiR|9PJkwx>h{?bpZY7y~A^4)*SyS2v5b7E=%za zOW$Bi7cV0t03!7T3$zu>bO1{5llw&~k5+3+CL7tQx|4<%eS&qfaEUQ0p-d{!>PlkN z*bg4U?&Q0cwyaY_oA=en4QWcs9sDn@9+|hXU^txzjln?zmLc!fPSLY*`AWj8tRs!F zP%Y;Z5fn`d3$phNa*}Wy8LYh*($N?Vun2G|UQg&N6b@cKl|`y9=|aw?obh1YJ9OB3f>B(oLA%&TO-eFL;P=O?c5&J`lMOKTpM zuH8b?ISGfd_43tp`Gp#Z8%>;nT)m{=LXvW~hgEQ%-4*;OB8w-Jkd;`Nt*o~~CXhUQ z8K$)7K{yH?WZ7cY#GLPYSs2)w2-O-3fIn1(Zte(l1wb7DkN^x&f`?=*D;@1nD(jbv2a1FUC9F@v zJ1A|l_^POx>$Jiqi%{mC&bf4g8%fFf z`VVXGAOVnLJUo>H4In`30cNYj9KC+y{x#fYFk{zN`?BjX?o+W_EA4i4ZP5R%xH%`I+a~L<_K9hkK~IwvZLoSjtE>OZD@rc-k%LD^9}!A=P;TWbEg#oS5zq zl1ma*z=9=7O+S#59(e7!z(4l6o;5}0n2GDIx~7xZZGD|?3r!zt>=&?r3n6cDW^2Sk z>mFD;hF;^#I#kwtRCflX7cY?sv@NRHnS3F~QxHxUwlWn_;Rf@zL<&DS?0PW}Va44J zfrd#to*Oxys_(4eV8I=DGx<6AZp@2_p~!TS;n~K>WGE;GecC!ccCMYB);Mqqap9 z#*f;EuDVfb3lEem@ZbdNy2ZrEOANchjV5>>-g@GhHJ6U#n*;@&)C##6VQ)P2(=0HU zMGYD0GNWZUMc)n2)2s~Q)a)6&Oih<~{6%RKXX0<8q*r_Jjd*ydB5gL*S?2PQQJC{= z(AK>%s?BH9=joSwEQmYyl-gRcQ`Ey+1Tzt$)Qtb#WD5!0q}O66dRjm?pJ23eqBNa# z88=oygCoM~Jo2b&uowq_p=_LiLSJquM@4BaC-}l@$jMCl$>3tM0sU4(C9@#&;SenX z5555L2?rg}OA~eh`oI+xr2-U(7$+$P;cvtht|!p+4iQJ**DY8$?!JThwCKzz1}Hbc z@|)2jp{J7()Gbv=mZ!v5fItf9fN(To;l<^-629Fd^<6>j-Ssf@!EozR4vdQsOeeGe z+&-B8Q2$_SrT9}93wF2>j9UB@j7fA;4Wx&hac^p{*<|8Ptv{SK7I311tJG@u1SQ}? z;;GrjfA7??1?C1+Mc`iDO~1F#_|e5vRtgYvmi{pzX` z#EvC^#_cEKqAn>)gw%gpZ$)1!VoGWMqlv#62v>WTvz#6 zXCiGCx5ETK;5_KD7yd z#&k{=ntaCM`~!5s8Ms7?!|G+6;y`GzLQ?{HG=v(Ni_yMd9pc{dIa0e0{@}}pp8Hk8 zo*y2J`4MJ*Q1*?)i5rzXhqX_(c;vk?%@Bfea6%x0;qK)}fb3#xjn1j=Bd1pA zCXa>kVFAgeW5vQI6$J?u{IpU^RTPDaJ1VvY-Rz+4y3=O9nCi}Lk)1m0n_SpQR6{!0 zgwA|{)cg8%KB>pD=l-Yq&z9&hI0InthL%!<%V_otNn$YbHY44#JOK;HgHt!11vV#l z9RxNz6wjnQM9#a*w~|JE4YDu=a-HrzEmnOAM{vSeGe!+r*FKTH`Qt{)O)VYDYKB1 zRduG=YWH7jwnPK;s8gp& zS$jAYw&6}pYK}1g+=?WsCoRKPHBXx|rp%N>x@e`Ph1vhTc}9W|?iN`cIAR#Fe$Ozl znGlp_6x))yleO^L&^*Xc;F{q_3P^GRo=Awarox7RX0r4Q1L5J2N@l`k6V)`C=Wo;i0DaGIy~xE`MEUY+&7=q zh&Gb#0E>0ZZ@vj`OLAI69QXy3D@l2Q3%SZcRZSc4cAKJdz-JZ zBKT{F#n!ZZDm(&Ue3UA|v8?^2AhCcGKJdlPEZw%kvZR!BlG!?Z`5Ual_Tj(GfW41( z)MQ$V#XD^w|HmNc??LT6ob%(A8EXvmBr67hy!EfY{Dr?XvqofL(#MVQq&c;8A*zi@ zwW5tBe;oTx%1stR8W6u(MTs`M)aTYsC9$lm?!CUwNPZhs64cu<sGq^`ynykx~x>oC0LTjI3|x~EoZ zI9#n!K)6AB(Pi}OWvEOrh473jn00jaRsd82VnP6;>C9jLa^f?4ZN3qu`BvYn?m<(S=b$qwe4BFPciXAsRZ)(Qv#}5V{K>J^8ajHp2iZAi zvHIz<=D=afNC5HLCx{6Sq7DEC(WMK4k~9UWi$JL?qEvhh|HowKu_69m!_|fL7v@hq z69=$D4La_d8!Vv@k)+|N8<68l^Lt_P#gdb^giX_A-rchwnT9uyK2;NVtZ?U2?LjAn zR$m*>$1#@ms&-h#Z-xiIa<#;7>kI7EJuQXdA|{)hEun%~y`Wu61={M$0dwqc^d5Iq z;s!zCOGZN8I=FWvJQ~DH4kpNyYm> z)SI@&7QNC2AH?eH@~~F%U12T;_T|dn9qZ#I4c2uQn28V+Rym{$cfPp({k8h=SFOtn zS%{JwWcp+drY@r;d1w8ztV7a49h2AvLjSI6o{v#9&hk8%-&?R|6k8G0;M&vq{yEF? z@&U&OT_0XFx!xxKH%Jm@ zw6(dJ0XW{!>lfETZk!f;Mu8Cy1gW!SDle?-?c3xp`&&a-@7>V|MaNcxYJLn$(*32!{vuSUdL_@ z>jeZ{xidW?rt>VvJD|L|CPJ1*oq2bsXT9ZPTjsBQ-;P=zK^Z}wU}5}he*Cbo(BJ)m z7F1T>1zR8Eu~kUKJ<6J;KtFo0OqcFm3|c@a<=ej%NSHiSF%&F;jbhh`IsN^$Ybm-t zuhC5T_-pt5iFCaO;$pUA;x9#r|G9}{x4UykZd#}iXJx{%lM*+)!_WM$@y1ye!wmQF zU8Qjabw%;=393f`z5LPgW^noZ#K(Q60Y54s^msXwi_jP&uik%vG5{lS(xqJ5F`R*H z{P^h)yCNgRE|v0GLvITq1urxR1ZGa3J~voVnXj$)=&6`Y=9l*eE`0TfavgR#vgzh> zT%cu3%zn!NhqXf1knWu?w{|@dsPX_JnsZ;AvX-%jI{Lp`ph2zx@7aGDERI{BMNYi5L-Hjpj}XrdY)L-s3bNCC_`W zl^y#_2NP$U89tql4Cg_w6ewE&aBgaKjNZ@1jPV*eLqH;ymZsa;(X!NDTU0THSAw z_`jFgj*iaP-LU$18=6oEOST(B?yS*osbw{(?YBmox*|nq8V@$vOp4XAHM2At6P1#u z-!Bnh#$&^%nEec`oz1x2gD)`H`TpX(AnnIU$9T^P6tR5GAmsc9*qCm^3uu7CGVZ;A zP`HH9;P-2I|M$R!G=42s=!J-+6%chq7bJ6IN3BkZh=}? zY^Vc!6O|xUw5exOYkP8s1)p*kx!B#RI5pyB?^3LGw^Zd;KS1f^j!WzfSP=uwz&-Vb z3n45rRHgtBHMX#=DUEJ02R7)iNq)DXQQd99vU~bsR4DM8IRZp!Jc6rHTyuVl zwRhf7QQK_*!hh@fTwK_lN>u^281sbS=36LE>c*93`e26CsvdVd(|>zYaPonkqVZTi z3sG>J?-M->R>L&g!1l%Lrn+%S+*iBNaYqeti)nXrF(ujNe*Ml}=l8SwxNBt@xGw-C z)i^`?^aGb-BlVT%ij zMrzjHHnwUTbe+A5-e+UAsQli^36I8>r1L7l8m{iDD?E>$XWt*pi9609<6qAu31&Vx zPfTE1Pt-W?DjWx-Z|{r8SKPY1b@!Sw;qmoFnh0f;Jp#;tm4>KSGziML+V{6?m_I9| z5oY;3qgYWrHa#;n@VpQuOHsXdHMcRvMe3rR7VG;6TL1r zfgdm)AmXWj$(;6D$u_Z#b5Gw%dd23@j>h-D>m>Kr z%j8$LF)5aqkohf}gVC=7Juh4jL6LCA`>8z!OQ$eswa#d-`0DYkG=7_+L35LxbH&zO zS#2PfTreTJ`U+b=5bYds+wR1s$NM1#VKuCnoouZOUie?VQ{abO3YZ_QP^(KjQ1K_i zzb{RC)|*TRmkG(p{0ALL74U^6XUHu*_;AthDpWa)Sak4rXN&k9;~p(Vp_5v; z$3i*5H(D+o4@)EN_6so`(lJrgeRvQoED^})QBJFV)kj?Xv;igx2&mORLbyB!m0Eo7 zI`psDivsz+ZqxhW!WF%AI=XKv6e<&@jL$MNyp?A(wj7jD*}kcWfQgKxF~xV)Lg%S^ zPkR(z@P$(l!35C!Se6%QNo(2x5#f@YXg98qgECM=t9Dax2dm-VDDtH5E0Pdd-q*Xw zzX?;bOx7rl`qgxhcB9r#0s^6^{9jeM55 zx_X+~`k-CvWPEh}$X{n?1xKfTE8_QPqQTL7gD84Y0HfVI5~nrMARYJ;x@Dx4(WMw) z2K&JkA2i430xG{JYsf5Jb1fXPJkG2 z@;mSV3n;SXcXL_r-H3)2^CC3KTJ0S6I2zASDpxb9(YXXN#?F}R#U1?lP3+wd^$m#o z9jk+X{GB$f(Z&RC8MYu@LFxuksG=tDZ-QjAs|2Rl)K}NE1S-u;3qR14-R24=6r)3~ z+TM_mQ`rcI5@pGQDlHNj3E8r6DaAwCJTHA**jWxpSskB~`dvmL zE{9%0JJXFeqF?9@G)w*&fl%hl-P3i+0d58#ofHA;Rz)$Pq zDcw=Wbs;&f#(ywsKR}6VgAxNqZo3NR{?k#hA&_v2u9_#r1OV3f4ido$(YFaV{58Ke z2L7mroM5X(@oca;(57!b%`RG1YtT5r*=3W`qbpz?0;tm!q)r7rDMov~0NHpL3>2rk zcRE{(`WbEM$cg7(anH*U$1DUWIGpv=*a9l>GM3mP|FMxyyFvpLxE9`ELe0RCop&bC z^_p>vMYjYe=rV!DIO_tjpy2tUSjF5+1fV+cyX#!7q!mv`iz0sztQYi3F*gm$)Ya;~ zngXi#>9o+o@bwgfx1kocrH$cAmT0i8ZJ|w9++E#c(4zFWnP^$H3-&XhZTAbw3g?M* zus%KSjOV_o^MV2Q^g%Qejuzmdkv&^NZxxWebnxj8S!1-NDMj6yh@C$o@p(0K*(iq6 zaFr&e;7-JU>~h-u=_)2EfBB`32@j-$H_##&42Xg{0eYKcsp}a;Zce2E+0^B=&-5HF zGB`Y^Ci_+;>&OoH22@$OC+?bC*$ofnx80tT13Gn$ww|JqyhY zu}TB6f-<*m*Tl6ggC3^^U6K-gdE(-h02ksic)3CL`Dz3L0lrni zyc-9yPbVO-VIvrWLp;y~4D68%*axUhjOG6Uh{Us?i4<7a#EHRD@xwb|jR{8f1e-*- zK>4y_6BiYzdTS{{1}8=H1&O{-x~1M#_*g;vLWJz>wps7A%IO`?FT;E@p^P%5g~L1$5p9>& zQe#3ZmfVq<$i9F`^fR8leTWG@!h*K21%I9w`OdtV5$7|pX=N%|1!v^MtGQwu+rduC#~RbuBdHr!PL zj$WA64J!>Um!JW(@y(C9RXuc}Nw$b$9XoSc@EsIvM9)iJwpdOl=}_f8!L3^8oBEo; z6U(ytEwbL{(VpKxXU;>S@vsDrU^`yu3{@Z)0QCVtPxCpjhxH;4XQjW=1byE_&D9iA z0>TseA^1j3M~=8NM?97baop;3WDD-$rSvX$_1Q})-HU70l6=VX=p^;Cv?s3@2nul44wEKq4NRUE#4OaB7 zGe`^lB<_5k)H2AN2QuM;9=FJ9aX?ZW5Rw4x;-Hpk!aGd1#)wER8hV<;InC{Tc>88M zTHpYq@_?Jf5rplstK!$Q($cP`(P*Uy1gWoRp+_kLnM5#-0K(yq$r|_BsM565LCbm( z9{T&&^zIm@{LGA#gydbhmo=WyjOV}%z6K6tvpC@O0(gWbq^T?X0Wb50jfS+F`Pe%P z)F`XZ-a3o}c_#E3v%scohznEjHd?5Q3iDvXu00h9z(Ga&gl-lE{N%v=@z4|wESn8? zHj~;T2=yM7TB56mZ4#MXYHZIl-$qJ&6bL^3di$y~qaD?RPF2qz&||yXALA|KN3nsefMMzj>U`^jLxdV~^%@hH~wy+$}v`#y*v(dXm!fjfGRl zuwo2bBp775gH4t*r%$1$iqIHhZEBjfO;Fuj95~HEW{VEFBT;!P3F5dv1hE9m-UtR! z1g?J^ImH$5VZmzb?<xL(RzB$v#Hr`=s70ioIH5@&A|w~OLXCFu65#3 zsa!snbL~IQEA3HMk??vt(&j&;^;_g8ybLLNwq72^Wg{8wf+a*7&#NU@mWjT*V>_zZ zZJ+^fg;<6`totKqaP%wd>*J#ckhAw$96Sp;pcjD zFF4el!%Hpo7}Xi#k6n_5knLqIY>lMi?|;YN|IK7)=n5y(M~_9rFEfRDaI-g^MV>SF z-$)+7Y2ntfSuS;UW(#TccJvQdP{buWNep-1GVM$nG2H6FPnr7(WFOX+nYmOS6^Z;AX9+|~tfQbQoCk@6v zAP^-7{VOl?6o;H(A*Ton<7_1Ii}Vi`ZyJa4EL@wW@M>yA*6C~ORAE?K47;EaBWylv z61%5xM(Rc^wFTk`80(^E`W%z&dI*Untk`IQRnWA%(q*e-rTqgdI$g@@^VgpHlVaYd zLoj|FZX}6wDot+ZUPB4*?`lrU}C91mRu!!b7G|CP%36nNSBosGTeLw+s6({LcAKwY?6!8Rjr^S&zcp@98a% zr9H=9l#ax&B=hfdeAA-j`hkp(4P2KcyA9?Ei*n*Ybt6G%g87l2wh;*hnAh?Uj}`4j zi+p6|WADj~!vv5eb>tpF=)r!+CI>mnM&7=GB%@H6Md@3Gvr|moQ_iu|2iCiNg(YHz zpYLDYagnVp;Uy}v8!gmKhndj82QR}+iguzcbWb~*8hjAG<^ByQAfdZ<|N4J+mi zv$g#pP7!Gw6JKgOJguGKTrtt=+lpd=GP_{_F)uee@eg z70K-y-xZyXqeuCrTO6T)f}aI3Qd&wJDItgg3W`W7AShsApn#~@fQ5xW&iVau|GwwE z&pr2j&-3+sKAt?x#jV9{aiL4+)D?ugt=+z!^8;%PbAWGxSfmLhAHBwBGGm1BDW@Ly z1F75~_w*|#sVv7oX-G>*1Z2#VJSnaJ1Q=i~^m6O_;TPZU;(s)Th~CGGEV+rkWD1Yb zNB*$HwiiTR;DyromyF40jhVMi$R4s6^UaDI3=E^J*b2KuLQvz0s*4bajY+GuwAK>M ziNE}NRP3s_0ASH>wazfPO3$y1=}>3%Th<~A=iU`{d7xxjFzdA~3tUf$1QknkzJn%1Mww84GIn{4)!vX!U?kv9% zd@D&kKd%$wSNY%3lt!BbBH-iGA-$R~DcTnOHpg<(Q1 zop8x>c{j(R_%%F*wCCHAb^cp;uz+k5uQ6M??CKb)HJ(-|FrE^e*o)uGA8h0)60Jdb ziY4%Pgi7_aNRj>$RYd>!!>v-i=U#D&jVhctmtw;P@pcitrZmM$eLiU?Pv7g_C6Sel zXls%6YQ;Wh-Mcnl8l~-sArNtz(agSYliZk%@@HwQ)PF5hJ6C@vnP7g<<-8>fC#qG^ z(H;u`b+*^<0O5Okx<~;GvqW$VNB*lWd8{hkt|rjVrKQ9){Bcf|zmK1?q*@bwT>$qS zEF^HDxHF`8G!!xim*?P}c|?#d5upeuzi6kNPqm_`6fPtC^eIjtL1omA`)&P(L4(GG zr##LTWs#kv05yBC*2+poTvHzDmb31m^f#^2M4T%Vadl6O#`rR<|7ch@2gOQqQ!xvn z0HFsX$}G*XgU1=_9c4{x7QbuD)NlMv7!{;8AFHf3mqAr@!hJs(aSKJ0gW1`26(}MU z4Vp6w_m|*agsXr~R529uqjh@mDs}r-*&1(i&fqogYt*{BykUt5$QB- zN+#`C99VRP%58e4aVmbI$Ov{E{QUTf9MezhpB`L+TzjJjgjCuLdzzuYW-x3_*kvI( z<8t5oa%-E_#WZf!TvcECr}XV}E`INtrAK>k)*8(D2*wyz-mO z9+kdpV;N*SYbPrl3RQDQ_=sPfS}pRBm)5!@0r3>KRFxHNPPQGB+De0)g^p!y9==U^ z3u=m9YE{hE%gXefTz?uXE|+orZGyS6o7EuwzHZ&HTBn80R-C zWt)XIwfHSoy+0YeC%pwRKj_{p9M78Xj=n`Yta*1F#k2f|X=Qmg$`)=hz;MtQd=JYZ z{ts=MN1)ghR*Yl*t#;CWM@E#d_!4+&}u? zSR}=sK%e8IOxG=&h0!Xcw)QA>3!0mIxOip$+GVwhaxX7ZE|~f~D#@ov&ip^$ ztTgQ;hDXR8G8AH!(fQ4G0t6D9^B*6TWk)+ylhld~&E{w~b0=iwMQ?Pu9}W@H3-RY_ z`ChCw-Ww!1XMH1~&ysx?x9oIp)Wo69Cj3Cs7-B=wS-mfpK_3{&=T7e2`y1P<`me?& zr0?UH{O9PamN?P&Z)&SvdiF!>+9e0C{AQmtGuD%oB%}_hYcQRnv+O822$nHNw1Q82 z`1ixr14|*ng{{+B$9K{!(*)HTl?Os>Kj*rXZys4-b_Z8|&6Cdrp&WH{muTsPHZ|XS zv#(wZsXN#o&}Y_0_;VjT?01!4Xw#3v6ZxYX3CoGy4O#o6!AN>&j*R1R&_;klZ;yc9 z?p?8-*sOyv0u@=|C0@oHBGA3bFx$q-cyaIjfdKqqop6D8QM0XG=Xo-*-S2e9B3^Y5 zXivj%?q7`<-WIKjjb(yyRzI^sm2H~5p3TROeuJ?YcKV%`BIs;C59NV=k=UGL&Jn$! zvS;0Gk3ZzC{rLt$Pg2bexG%(A>^R8R6E$OL*8@H#Z(1E}Rhxs3qw<;0UI2w=1_xA| zQ=rWq}`Io5gk%p~KD^sti30VGB^vR4i+7QwOimOYL!yw&1G zQNI&3em!%`bk9h6!uRoyyBK&SQY<~Yh}}|{Gm0S@!G8K206`@7jzx#qe^k89IP$ml){SSefUos$y4$)W z>*M{)C0J}@cAn&_;E%Tw7$detx!}r@R#S=ClySdxqS9I{y8oKs3Cwt6nLvaF~(3Tsvl$SHHR>8@AXu9a449h+`L8 zMF^G~$hVOCgYCB(nF-d2j2XjW!X%(I2E_B^S%Xq+JfY_K4lH9D*XvC|9byHlr9wkM7p87i+P0rj#FkJLGXi(^b{p7~ZnAo*^Q@ZQ>+u$)_MVUVSKFdn+W+*2#0WCtT5VAywwEkOy^Rs< zfj2Ai}$>D$#+{`U*p9EP;Ur1XAIUpEuIJ8oRx zX;2-_K24&Q_tsT2fYO*w-ScM+3l(dh_cE7PJ*zWZWB2s?C{ct&|EbOI8fkUrG^0!O9mnv+uQPxq3R&#Gy%Wr zDy6j|x6ZZc9sP;Q@&o#r~Y>-!_5IguQLJ zJ2g@riN3pAC__ZJJRfr~rC|1`}1(;58_d8$sFz1^<6!xU>}YR#Ad=Tp>; zYHxPGSC?C;L>5}CdA6*`6b^p@riIh{jtgepu8~vM3rVNDnMjdE77EIQvqQBz9JtxP zMEa~iach&EX@iZY{Yd6swYVN7VY$$W~O#!>C) z8SA}$bJiQ;$m8@Du|Uh;OmuFMsS&AYc{P6P`L>{5rVZtKe%N1p z$Jd_TU!y^ZPs2(}JyDdT2*=2f{-{JwI?2|b2O=18rl#!8ySoy*3+JihF~}#(%4>7t z3fbbm--L$r)3}S0E435GC~@71eT0AEl&MZjTlFYH=e-ka}uHHr$E3xy%#GJ zWyYWms+3d*Q0t=uB7eb7y}#?YVH$VjX34B8MWYLKq5f^93ku{(Y2Zx=D-3!@FAfj~ zTN7wd6*^e9ywp3cs%>cA?a%YcpQ|Y19 zM$1(6GkC3>*`bz^qm!Z|n!aBf@xhn$Fwc~DTn2+9Q%xa`>d@B;)%(&n!Vt=UMu+mC#&zd zUvK$R-o7l@R)T2=M{3xPJ^j)-aL;6~5Pgm{_LLJzj<9hnJ41V^aoW7=aDx0ZXU^lA zz}w3;tFlt?%2LC>SjKxvr9#qdb=6EXPPNcIihYT&jWkXhdcNDD4`1;;`6#3UD6z|O z{h0R-(5zqD{T40;^iljAOsyv);1+_tbo1Ucs`byjl8(Dmt25S#jjS?^>|kdQw4tQY zu{FNpz{;{61tbkAl)ls{XVPU`t9>)r={cQqef4P+p;l&_Z7a)prq(dSwA6n!*_z%o z12}NA%L!+8R`Dltd*Vg5(q`(>;_S<6fRRTHCH~n+jLBl(9_OOUH@!TMOtuUh$*>id zjTSt(rtqVEE|H_ncgR;<_UN8qdo~OIFNE{dNrMcvut*SWNomEnw@bDSV%J)pBSC3O zD#}|xmFVoz69TEO?NgFf&l4|tm6zh5V?%46UFqw56R4aXaB1i`c)Zg}ZF^wKh1a|i zJ8~Wbn-3tkeh!q^LT z>p*f4$EZ3xjm1kV$u`_-^m-~>T_G{$e!_0e< zl6hx_U)~(ZS8p0LznNw@M)Krk$Knb;*rN*lS@8X>NolPwJsah=dj^vR&-#rV3gKLO za!s;m67ytgUQ73L^WvcvqThbUtm>ER9~Q6evC9$C@3)x6W#V&OhhY8KQ#D_|9^q#w(3YxUx5R{l3FIj!NnVe;~d;W9ux34&><3 zpt-DEzY^{!om+fd>Z5XDEAYTj-{gm1HS8}n+rLKkE&Sf$^ybCVgr67G-d-Cj8&K^1 z7Vv|{*0DR;U2JMx4Xc0BEiU_+A7pmQIpKs|jhCC)>FOWL`2p_RVlZ4iwr2&bvGzc= z%HHDW@MxclT*iG##ZlnB5u?xk!l7#<6`G`%Yy%q|dt1EWJh9#FEB0&+vbWsyLwVI; z^3;FmHczWJg`P!mrM0=aX~7k{hUqikt4P=XGiT3e<{9gl>rEz`MV;ceBOVv!ohb>5 z>;Iis^Bv7rrS1sYaCGE@&tRU~nYGj#?S1L9s*<6-!Pa%9dT~5=u|fCrmEz-@W)8jA zm10|2W+y3s`rb0=82cpST3gLMT>abEF=|agJgk~7E9KRNe>5C??$RBVYi|$piZ><2 z+4}J(AbxD*>HMwWgyLgb(Xz_|Ugplmosd70Np6K51#+~|GtoD!=MfyMncu-bTk0JG z2)|9aUfGxqVWkYIpc8|yDy}>a8T_elgE8jFIsE%})pRb(AkFi@6t1OPk%fFJ-MKv2Y6 zN-7)xhz9^-ph77CKn4JiCLk0ej7}3q#Yo~ZBqY&Ge@(1tcIbl zfsv<%W{ir)2@S0@Wm1f$ZkiS)#=ztRMgN4pNrtI;ih;=y9W6gK8D~pVrWZ-kAi&AO z%GTV{%fdRw-1>yMRf@Tlv$c(rt-XiMKE=k-+tJzI+11z1KG5CG$H_g=)x+P#_mI2S zAx}SlA0G#MpJ;o>6f4^dE87%X#}l@W8IH~=jxM3D9&s)nQ7%3yE*>XbJW^<$p`PBc zUOwSI{;@v(k$!=30YQ-r-xLq;6Q175-u@@N{gMI?od^g@4e*Ngbczo-loA>k=^qjw z6cXzfmUJle#G%mSpvZ)fu=t4R~h>cH;i9C5Y@mO@y$;71e z)YR0(!_J;D#y0+303aU#;39;|0Dw9mfGdK^lER*nL|*{_&Vc}2d197|T9!72YhYBZ zr`4^aQBRVb1p<}n%I{vpoK9XWZZR)V~AiUoXYIs0{z}EBVvL{{*~yr323SCX`AYoh;7e7!3c^ z8vbQa^~hoP>!Fs1#uI z>A%p$=QsZu%>B|^d~4w1i?)5NVE*5ks=fQQpXLkp_NxE<%$vV8@OQcW_mj)tZg=hN zwf}uRxcB$!&-I=MvpJ2AcV?$=JzieEe{Xi{;q33XH}`%`zk2uN@9#(7-#yseeDm?^ z>)oGk|NQy-@87>~-@k5u{`Bb8`uVF<@IAl}geKgNYisB3;{St}=b;$3Tq%7Rt- zlFhUkjItn>64}Ch3yKg#tNEL_#&g2*B~-10W9p1`4_PKfJml*n=cvl)$1VW$xiA;3 zZu}A;NHAp{XW-V@6XI{@f;EWm>C6lBzK=5uzB1xxJ^S{)f$Nn{zk9D;o*K3|4&?Qz zh(5WRu*!(w>WQ}N^Qj$d$19)i4a7Iw6>%%yKWU9GJoG9q=eD#qVLt0IeDM}q+cRT# zwW;_2jo63guMWgLu!z0Scjx97;Y^sz(Myv#<u3k|X=jl>g0*{#bI)plQoY^q#(f{AX7f z$h6F{_hY-?bdUI8;}wx{bbHahIz%}HS9z46Ae~X_4#NVI8qZ>bzIr{T;ftmTSgEAO z?A)NNwMHzNqf}<+!AN|L9zM)|DRtv;;w174Ry9DxcsO#Sl%~?LQFhKYq)yZXl3G_` zwzU8$F<{Kd6k9~c$Rz8d1yoWDOIT;Lhoj5S7z`~>x~ZFQ`8G?vj!}Y15!{uag)bY| zpqPJo_y31cUVpS!2pkb83zsKftBCTGSw=NJ? zaQ5Wxs-5iK=`x2siM3UT=nz}IqeI31WB}dh@TMAonvxgz0s#vj_FM@Sb@lWUaob+AA0NKlg_$Q>C!1_+1v0N1$9+JW z0A^&4n1ApIl<9B z8ybMWeoyV$bBs;4jA!+>!sQ2`Wea0_SZ~&|R`Cj?SUA za-R&Q$3*2f5FzSS2_=zS(zhJLJI8Tih4x*qgBM~c@O$Xz7sXCQTbpj6>NN68vUGL@ zg!Y04?>W%lP&Df|2uJ&5ez~faY11c#PjF8)=_Oy@z8@zXfw8_WC_VH$2JTswT(Z^! zYNEwJLTMq4{Huc(XG_mhLEeiE0rtYn2h!Z?~OCXXI>g*d#08DFa$D0`q8rQhusx)(Zg zI47kK7c7Eqf0t>wQT0tlO@oVH?5&vdt_7N*XW|@bWcx)st8>C}0tR z$Jo30qJN6pir65)5xh(7MJE@TQR40!S7~UVe2LKXT&shGx2Nv;Mj?+)kkp6Emj*1? z>YA``lCoOrWENNg9|}9YidsxxY_sa;hxVbkkk&S1p|d{Y{3|_eS_->h!qdS9rHzs- zCH}3jk5_4!LpfKA>RT*8_uwb-M8)rUS?ybkF_91mthDNL#`e$)S0+|bm)Arg6g_Lv zn&|-3KMF~##Oz1-%NwhM(Tr) z=I2or=;;5*@WY zg%W3Ep5YO3u9v-<$quW#cl_sxjf%}mrhyMe16DeLR7ool{MM%OouKH`-Av@=MfkPd zCig>`TMGYKBLAm&{n<}SDC1hCws7#iImXrN&}{@ySa7|G6^v-sh0C(MrAj7Md~<%B zxqC!08QG;2T~-u5Cg>YHrOdcu(k1fIAjW5(SdK7;3QG&!`BhQ2#H@p?Zp@v%U0&qp zlq{%DU3=E0rc{lyb|2v(B-!`v&>^uXK zA}gyHTy&_iS~J_htG+;G`WWXs`Rd=ZH+HqDF8`pV@U?de`oKEr>w;azLP;40BUC#* zWpH^h|6HEKG2_8`(eJLA&m0%MDh&Ax<@9rrAR}pP%2qv*1ly`KMCdVN@J8X{ z=K%oqIoD#`cg>;t)X)X(Dv$R62WG*FwhdnY4 zc6GfgmE|uhD?^kqm!WGv^h_3_h9qTII3Qdw;?0&EoGs!)h0@3ev?bCtl1yHyAYJfC zAS&K-LHyr-!6H(TA7LE1imYzM%UR2thoJ2uJ=$|%Vd6$R1a{rggTFX1od*ZgFrEw@ zN!Ts(6HDs-XneHc0n{30FC79o&(D~P0?VaFrb;In8s*(sN>x2==6wk)Z(uc*2=Qcj z>rzh+WdpUCU;;qs>XwLFr1+0unBXX&cbS4r^p)AhChFU`i6cEqve7z`LD4CkFbld3 zS`%y|W~E>;fahgLBpBu9D;vus;puutjrttox>_U3({&7{a}*W>I3&|dtd=g;vUVSB zgO;j7je2<(N`$&t0oD{5oL%16O$|4?CUHYHsFilaPXCcq{?Jh{i3!B;f#nPOSNS44 z!QxA+AmOciL8^O5j{N5<=?O0(=2WBv0finr21G%dEy);m%AXLDDv|sunc60S0{Z6s z_KXlf?G;7R5B&ZjZ#za1FZF2IF@)ZdNaMi*SD|9l=5-w39=^jq>GdzW|w67^^X+H3)(L-t}r}CxkV%qU6-s{eEeKYPc{$)sh5} zqk4amx=TphBa*;P|EXRq?Z8629}C{0SONX&t{6AA5%jKMGsoC6Dql^d!?hUWT953& zdL>naRiXK}_18y*p7x4;5?6@fD+Kca1g6Csn8tvS&7VjAH3;C)`o`%K?ru~Ci`QX4 z1`fL3RKHk(Z945#8qy+Um3u`A?Fmzi8O^1a5+Ghw zJEq3uwriSwV?sXeQB?fmqdJ?NN~NrjnNToMy-9Zgq|*z+lHu@~`n}&U2UYK=#5 z-C!h?>Y+FEt#WxbGf+8jK?kfO4whyD6#zoqclD5Of}hB+-c7(KHdGJ*aR(U5z0C%5 zZIl*GE0v126r$1Oq~q!{e31!Pl{w?&EsK zPh~vQBlWhrG5mVXw5I4Lp`KO2&{aV1G{6Bs3Spk!eTY;IN$7Y9_1hHB?%-?c;=fwD zzm-7#7*m&NI`Fd%y*o~R2UWb$ul6P9vYlo5bOk=Q&m$Z_B@hXMsp>k)CMK3njRF)U z#Y7wemp+BP1lPEcXc>-(8iIC{-?#Y>RZcZEUjJq)8>!z1?8ov2pOX7Y{`C412y!c5 zI2ii#b=+r@gCdI*(QR=t+i*E{sW^d5WLvyk9N0=c;1nMFwJ)~EPJNftS>$h&gyOZD zz)ptZQASs~?67X7U2*h_(bj0`+lK0U*2Q}S^1iUT2Q2HgN@a{Ij=Y4N3K+Rxt7)>8 zcwNoxl#-cwfy_Y}u;p#o_Cl5QQ=uUMqKA&4^Lu&+v29?8U~p{Eu5Zx$j&7TbVFGCg z7W2=rtT2+t*58*>iI!D|wiA!@&p8EMQM;7-KU0Dye(|hNExPvJA@i}bxR=zrH62iZ z6Hy0;B(#xVg1wr(8+ZX&LC8kH2w4M~_&werz-qKH^C0R})Xk{rA?PQn*wcmjCtHF& zqX=iFm;OzF`>w*Lcc2+0)Xzw<`>S~OZ^)!)+is)k*KH{BqM`Q{-y56A5N0poi$W}` z^Oc0{6(wpa1|3iG_%rUYm;1%SYz<9IRI6Aohei?jOH`>HwCrO_f7gG3m}V&#Hg%Y!@{N?-jE98fI3^zS8}o=Mfw?!H^}bmY zwT1q*e&rWiwJZ|##1#1(7vIEI{Ci85F+Nyxe&&dJpXWNHD!|H^dXvtvx~!u_!GoX2 z&SIECTL7_NOworDj;Y2F$u)?WaY08pK(-fbz6F`l>F}hRiLF6J*04cF9YZ9j^fzep z1EiW~!)d~v{HL}v|MD495eL1iuzyhOz$l~Q^UtTY|=dqGSsQWWY9K`>7X zu0qn4pn|~$As;|6s+rW^MaiNI-v~Fuhfk~gjcHBhyL%NpZN;{JQRpi$`JcE4@tb^s znQa}%_Q2so@_&pbE6&;hsRv8#-$xjC}fmr-Q z=(b?}0wlEtfDk{~p*Y$h0loQh?Os{wBMMaZulSlK+Q3}9SE>_1v?5?bUH)@A|8vS^ErrLJMvV{A z-e#>{NvGL!_3Qypr%{2X_-b2;Q!n0iW5oe2!Qv})5DfseEO~ge=d{Z6XM6S~&onl` zcdWvn$z8*(iPwDpZ#naF><46R)N=JrBuD~*qiDwx4He+GZ2{^P!IXf%9p{({hPjaqU%i6<@5h|C4yJYF-eiT{!H-2Z zaAzS;Y}X%*1{uv5q2fM(gCHYYyPoQG2secYq&xDsM}~ ze)Gk+e1M+zeuGAj?~Gu8yFE6H~&CjC4je<;ka&#H*OWK5MYU8o$hoqbeQzsga`7BqOlhvzH+g!u}a zjR0)`as~+mlm-i)QZp}BqKUskh$)!kEJ}$`VYC`r(jt9*!AXn~e%x$(y!FNZP+7)S z@OZX}f?YjhJM?D$+57Ed*14iG2DM(76T!MKWKHn5_jvALC`=d&xV|*iC4Jz~i%~Vl z`>SBIMsSN4eM|XexeCl;D|&sy0S-1GM=D_#TPn!zwItcc69v+gL&b4=HH$6dIcCiB zbBWxX`jERN2(7vD$CtiYlq-J`*p)YnTclMI!eAn`x}G)f+`>BkHV|KGYB!93rczpX z>q75lYdJ!F#H22(EA`b)d0K6wYj7EpmiKu#?UXLsNVwVPOl3B;19N3FwloD~)vqD)t6JQDsw^`-B45uRLBctiBBu&vQkg!Gzjl&kGjb2BPEXa7H!sBErSIc2m zREc!6kaJZvV|u!Pa!Rq8@c#Jnr#$xP(>+42@vLrJO+=wi+nMp*m>g_mp>f-}$md@? z$(hfG>~MzFCSe+yExVu9G%wE{>Fh8Obh7G~-v9|A=1bOvUZV`sFFl$20Chcv`S<5FcUtyp_;Yof$#~$0BR{S43yj+D@0MA!yqE0)O zThUf|Wuy9h&H?)-R13)!HgQ!qlh;?6lzIZ*P3qsWEDFgXR9t7BTDw;r{z+|a^?Ig% zWXQzV#5Qb1j&ZY~?jWziOYJX4>> z%H15Mts8$*t^L%TO%6SARk!(Nqs!YnvafL`f4z-4GV2;3H4O?n21 zuDs|jsy(4N{ftF1A+HICvq0!MahdPCumc{=MMpG4k@>6E5-nR0ywWOI5@?N5FJb9y z!%mpTjnf3T*g5C#I(pDO%bWVjPT3?XnlYwDkB@>sehU_eVE)gwo^a#(cE`z0Y~jIr zom<8RVZ|S#Z~cXbk-w7_NwZ9_#5j4nAn3ee1YqJ-Ly{D%N;!NE>6hFSeYHYw%rqqi zBsxg8ay^DR=Ek2ZN=Svstx^TXIE{!nG#A@6Dqwx_mT~`LtpbrF>f<;rQAOH^%0LLx zr68--y(O*+a}==ncr0;*F8ACfiZD4`9IoQoBkK&rvF;)M>|QpEgb2G^BZLn&Acd2v z$}w-e>_WC0&sls@bGwrUnA)abyMa4Sj2 zE)v8^cXa(hQNJ(u4!;aG(iH+|**<-;`lZYe-G+c-YSGpCkdSr}bUx#9s`4n5^pY(i zEDnlpD6({Cybx`op$h380>-PBQL|8yRJa`z7~n>)Z!Fw}-&7bUMS0EC*#G%vL;sW# zX4R#k4l#U*)}TvmX*uWY#9?w7vN&c#;snNJVNPLP~;sWid81|xVZb9 zu+Fb5!V!Q|qnph#?z-#fGIAR+hviJCQ$g)n_XIHjZKGwj&e5$>wZacVio)9?g{AYeT7Y)KZJJeuypl(*_cL*+1d5C&KbH0rG@71=fkRca1rT?Na3;Ad-M zU=xt?8^+@Xmp!LuGJ4iT;~8N%W;It3#0N?CF`yHpZLVK+UhZN4fw9x0&AL@O2RV+7fj?0&MhU!d6Ka1#eaOsToWC$J8ExYP$(0FZiDyb@&m^~AC)B3Um?v&MI zQ=g_$+|Kn|Drw~dmn@~=s!rpWz!G!ypTU7tl7oa^FyOfvJLTV3jvK*wZGUfyRy13- z0$A}Jl%sH=vXh)OCK87R3;$k!WSf}^7TM)NHQ`i%_A1zjYK?m|m@EJJNAWWh7&}}2 zl9EL{rFd8o?Z5qw@)<#Sr+shGW8sa? zDBa*z;Uw{}(XZCR1(^-u7Z{Ub&Mo0E2DQ=x<(In0My=d#Tz!lVospwgkE5afB0l88 zaM@W5M8^4GXhA^8+?s$MxmC0QkOQ@91krd_C}JI;5VHy}+49o}!V1JK+bF#BVtbuk z6g|1RAfx)iPUR{y&LI9y15_QX=oHbZbUNRX*~mlp^JRqw3h+`_FZE@Q(6{|>!X}lJ z)qdnBV(zeDQ~8zve(4h(qY&q080hA$3IOzj^c@&;%(ZTGGU`tHMWotH%5cftbxKwf z|L53^s_lkfF}nvo;&WQO$+^eBusjf6ERYc(D^CGJKpT#(U8rCv0777{2e^70;ybj@ z6C0`rJq%6Q&~t%3)c9cj8#PIoW91(EtPhLsk6!9YiJ);^mNyn6KF=J;x@BE97B|q9 z$-Q+q7^*Q!6^5H)V##=*YqNN-i4t_dM_tC*ac>u}Xzpwe45@(R~hS>YVQbiwjW zMk>%4ALf?PY?=Z2B4#W*{M=y^n4rnh?-4k;F1F?K5Ow$HbW-LWwi{0b4*)Q9W);u< z$IDF`9ftnV(Pn^OtAiJWuK!sD)oPUdi7s|ndc&BW8tiwIGDxap2UsxQ<2ennS(InX`s$=7BreIwra8oq?UuI($gc5b^!7G4dSI6 zzrq0IU>1}Nz`+4Pae$Nr%qKc4h&~EEKj6Fy>cE#E%*6kuqnYCJQ8%tiIlcdknTMubW1!@UCLzl2Uk1AaHd$v=S5alm`Ig zFQ`)C`Zb(4Ypm256d4XC!w+sX15a+VV6n=^Cyp30S^*ptL}mT6`U2EtD^zf(|b5}=q zkHKx*G^0ct>o3=Xfd(E3NzJs$w;p-Nw$I)76ROHHckZ9Ai6OZQO1UppeqT42Ar%S3 z%Y2u!kMIPZEFt1a`*A{midP4OB&kb>hm3QC)mWO1yc91U>?Z(P!g<5vBAg$u#bzQJl1q40*x!tk)$HetfUXa-PexA@NvQ zaJ}?-RpX&;7!NB;E=7!BH>VFJrak(c+IkKw&RlM0I*CA`Q?{{oT%AAPmTgMCG z01SYu!vev`l}DXfZ&z{9Bv(`ysq^KULckMc4vUOX4-Sc zLXHlTrEHA*<8vRAh057NsTU_Fl@`$HApRoz6PqAkQ#!{3#)C(s#2vzCpoe?uLRz`W z%L1v?TiqKsUTuM(3|3h*N|X*zrx%}BE5GQ(D_g78V}o?8?BOq^Q~3fJ(E{f$HHTvc z<1t(*2B6z)_?bAlCs2jFdeue{45e~)s9YF}{g$~0f^G^@NLGdb@H2jKj3wwj%fiCb z0<-|IiiTv&K@;J*&_aQFevTf4tA_`>5GWpb9QBWaPHK{GIpSUKhw^DPK&=I;GIDkq zII>kUGkpaI5K-`B3k?EFWg%tHvJbBkPR&A3GO|a@c}KliAGSEg0mV9b=g*vQ5apM- zxd6z~B^N!d8#v{kUjni1z_cxa??KUCkL7yZl=>7Dj7PsR*FOUHzk0gP#ATS)Ex zu{q3yrbYu`?bbTMCDW9%s%i6PaVV8exZ3E|K7_j{sb<#+fTv$8T0Vcaw$Z59JK(RD z{Jg0#fHRp4%(K4zWLKGzHsv^Zpaedw66B$33x)-A^r+x*r%Mz%%g7T9+hWbuNa-@c zdJKT{7Ds^Y3XTSfEOV0%XB|$fO4$|4EP=H%xGnU_h_asUKcJiss&(9!+Vi+Kd=yJ^ zc|@zQP|xJ1VI>7)9GT1nb)lIWMKmxz==A7e$VAD@@HXUtDhR2?=bhPeW($5_)%lS(O zw-45L*Bd*=P?o|bGixj0mO`X<@sV#&e=9f2QpY@rwbk!5WQ+n!Qp63KAMSxUhL@#)Izo7$ENtGlz zOIxyh;7iSu?K6N9cKlXuNHtf4%&L24*JI89{fk3kX(}-ypge%5Lq@n5L%4j8Dsxv@&wyI$H9e&H7PDrS%sYm|GKwVbJ$dn<^Ozc&gZ;}0p3um@ZK z3Urw)yt#1OpkbaSkEID4tWc}gy@2R{+1r~_vY$Ecr!d%Z{DujcYvR1M6to5uz&4s% z{*r0m4(Gx!9E^e5VQ;*CJ3u^5@YPW+h0cZHvkhq6SGHh7{u33s^>A(AD;ofa3`iIh z$S8?Cb_PZ>?&(-|JaBUIgBSeIvmrI+rE&CF(!+N-JH=AQ${1p8*oL`+B^x&?5L4KC zcsVES`^(e~fZ#6>-qdvIn`cK=0i z=kaLYTD(J~F5PD|j5R;DOuP(;&CGvWFE|#r)T77Uqp$!N8rTp67O0NVh-UpvxiyRB z!UjR-53?Y2{6`nFBWnBcR)LJs+zhI1F$czi6j;vIkA#aZ-M$0O;x2@ivLCtxoG8h)7y%bv-w2ldpg)FsP-t`-ClOCLeTsi$z7ixr2OJOu zD+Qw(Gs8QCzlMef%I{O3nL94Try(>}PI4P!jn5gf%-Iqd?tlmhf*gB3 zLRhX_X-@Us`9GPd=9y(UKEjs04=4v$Or|#I7VYJ}jyFncot-t2qoV#RWaE816pc|u zY5K-*AhjvFb1ifBM!n{xhG)3_2&S9Vd7S9Ot{5Xq9W1@^D@j+5I%&4% zbX<5{AHSR2+2`wG!NDsjbW=<47^$Dr?L&u?f=SPV+0-29p7z=I_|T|ex22G0Rx$x& z0l4k7-8K|5*^px|g>b-I=t7mMGNif@fd(HfQ^T23+yTX~T!xG0e{W@c;JhvTxp)@e zn`zu5y4Taq)&p@?>*YKGsmSoB(h^%)a8ZSym&;IQh4?#sj(XgB*s_b_m5KVTyh z4cWg>^vJPI0*v4s6Q>-z4iR+)geXJ%LQqYSORYba*cC{@6TosZHH+JKCeB%v>Ni$$H zbku}MgFltV$BGO$N)c}K*CYxF!%|ldVTiT4S4N;9Lg|+yAC%)g%V~}qd%4r^CJPPB^7#};z#gR zB-?HzUtM`TGVABcil`Y`kCNRC&yC_h-Cf0D#ItWXeEWgdG6@dDc=&E~r;gEo2-`+8 zc(zumnHxKbVfIBa{jKNWCd~cn~J!N>xx&VAJOEn5vxIm(%E6wdk2<`$DNL(1rHz>)r33GZ*^)@t* z$*=V+-P!^^P8RK|)npzd88L4B@>%Ef>exrpLZuTqM7ztpqY@-sFWYq2Nl|66vFE>t zFMXQ!m|6g5eC{|*H{27WOXbZ+be+@PUIi#?>X`Itywa4-YOJuO?xer-@L#&#l*ny^ zQ7EJBV;b>6&*`*(To;d_SXKU8zmZaWJlj|QLie9P@pR}i&Rnu8kbSM?d9`|KZem113?5te3KN6rcD+0$Q1##S?xh zLX*9@uxj;)NuB#N*xr-xUHFhrqTa(01>JRW1sXdu=fdX)V)9XTO@>lb!au}7qd=BM zC5W~(%W1wVC?`m#gT^(eb8U{=5WH+mud@wK{xq*v0E;X5Rmx-wH0?Uq~s0Wr~t)~@kC!M^qdKT zF4gv&W}AQpg9CLs{u8d47i(E)-_iVC9p5py&?IsOovikOR(_#NVVG!gjIS*NY}hd& zNyQa-<96&yTiC`UNzQ!x5V0Tso3Pq>^X6G;UZ6F<{pW`hESRWt)w#SHYO)=f}m zutM3U&-5XS$dhr7CE=k1+%FAAmBJy5ugO|4{D)Q205|m$;rv` zf0zitpImw=2y|l_de?6b(>tb4O**)astYk#U~ZBax?Q5Qr=h2bxMx5Mf876m)pTUU z!rh~28;PyqrE3$_5%iQ1(Xfse3ku_4(X9N4Bq;AyexA$FCt?VF+KDGddDg*Jh72pB z9vrBe#hUOmEj+aJ^k9Ma33tgMlX8FKxv;OS#j`dO7NG}z0Y@joBvcng(F1F@OrMbz zU*B()2hZNS%2+^_Zrp*=skuz1LTFnCpc0x_gkKy1{3~9lrn7Rj!e=B`hBGM{!+eN^ zNV@bl5QB$RaKsY4XD3R#Ip@wA!H~aAdJJX%^u3oCBgWtDxOzJ}OGFv&?LJLJcWO?; zhNa0-xye0hGT?}6;%@O9kCSW;sJB z*L#Vj^wl)XN)`5lQ%X}NXM6L=am4_HwpF!u_aMe~q%JeMfU%UgDtkNNrpA+4JHo5& zmaI`sZ5U%a(->-4(PqL1h4wQZgLeAeOa>YSSZ=VfBMKGvr2vI4Pm}P`7V~;qGsJW3 z@VnLw-7SHuk6xd;e9Mw#XPl#nH^iEE$T8~{h*4$Vwd>apSVrjKkHTGq$NzoFIB^`& zTHxc>Cefq*H-E=ae#P|rsGn-mK-qumK9a`YJwgQE?p}ztvR^S+|` zy3Yd)>GYO=%9WXc)h$G=+@xl^2?c|CT+dccEIGr`f zM(&$S8)qq*pk}Z1SOwS0i@4yiR@+D`lPt5HwT6<_j|bQk|CxX0@SjF0+el{y-jKHY zJEl{vynoU_w_)?7Lxc+9=&*asTyF{1TGWT0l;V~?uF702(y+?a=v2aSh4$)Nir06GHtCZg@PBx|$} zUun#x`|@AJZ~VS*g+^8-y>o=5gCliB0`WbrvpLH_*=whCj7LtPW-Hw*aLy0HHdp8U z@8_~lC9KNslZuZayk6d{coTA;_UNwX;&7k0*UX+1nrOy=AsAXE7E!?HPBn%LfG-0- zR+YV53mjkrYU3NxMZ)At&W~n}(ls!;YJ$|#WlZ&qN(uZ^)ujcjXBg6SeAlbBa6NUR zFCuV9P^{{t9HhfK7N~WLJriA6J4fNtOa7xP-kh0qJ-hIS8pSKNmz{duD`#8;Tzav8 zwS=s6;b5|X@m{}-MF7Ws9Qr<{eir%P9?suZeHn`r8Yy`ixuAdkfbLy!Y_dBIIf`9iGJLIVNC{(kDRyEd00-{rf#6ht3u|tp?VRD&TY*>X{3KiEGL{?yI5iM%;Jb`93 zi-~3nx6HB(--kk6zyv|*@W+`mxt5>r89eRtur0LGN9oV>Sev=8OK~$tgpAIyD;z&N z`-A`w&d*f8pKSoC7a-2a*ADhO$x+k}jFAv6M7hOwAS~}&_YH^$%NBo;m_`3k8>19xZ15D(rT8T1p*Qr3n$P6K?uZPmh zV`{q2Hda6#U1QBc74(?i97eT*PIiJaaZ`i9kG|8jy2rIRd?AsH*T*hrccV1iXSPrz(H78oBYbP8TDs766&Fy@jFa; z7QUUd1++jY>AiKiLHl)xIE%u@S%X{NHK^wPQ)0NG3vLLycTga2ZNc1a@xVyIPsb?S zpG3eExaiAeGIEpIfXZ)=#HIVAz7HQ2an4^A>U6Qtyl?7D62a_0Q5& zs1^cvmXymDF!xzqV2n!IV`v?|(RH@RnsVG>o zIwkzFF+^a*i;d(8T=8%aH=k4{q%C<{>QcyCE3_Z^d)ImV2^4yr6+)eWmr$R%ScSjE zJyZr<7zI`6Se;Hpi(85t;X-V%pgAeAeK0a&lhHKD`{ov(^gyt$)Zdd6UgddB3YspO zv;_MpkI0qNl_*uwGt0!1`Ez|LaN5|;W61P<`aPy zPA;t-!ZRoPymv|57GIP$=eLz5oj*e>xTqd2N5c3ZWcVs4aub;U)^WzoC7ZT=)h4Hw z9tWAIpIeTdOKOp{+#G%@7?ht6SV=-7%Ef2trJQW-!F{v6ba!i6Dlu~s7pH6VWASK+>|W!d7~u`~hjQI^9g1cHEgOL4 zYE8Y$F`6IRT!oG3%$-;U6AfLP8E3t3=AxxbG#xze5BV^aZ6=Gz)nw$-D*Akf3+b0k z3>YHw3b&_~ZqBnKN;(PQhJ-E6UFQldUQLjc$pgym$P+>`AO}cyG_#{#lI7M9Ab_V2prmR&qSzYQ(3TXqPe(QDh6a z;kAB2ZkP8ok!eBcxAVa#0gy?Ue&;f9>v^FhaGuOr&Kt&@H`DS>du7i)UOc~Pdm5Gx zrShOZ#}3hb2f$K}@{&opGy$jOQFGC6fII1%pn@?{*_d4s#pqC@h2{6M^`7j;HjFx zmG2hrOWIy8f;29cFUpBYcZu!5P!tUC7E;E$eA&wm*2)hs72He?seL$nt;+k9fi5Qu zYLhZed~#nl>?`(qBnCe&7VRTbej46u3e3ez`XY-)lSBLdJj?YjX5H=7&6&q7e_w?Y zeM^OKK^JQDluHyJH;SJa^)cjSBiJGab@XkM@yt2)LyzteYi z{f{kR5I{~kr`bWt5y<(?AZr&Ue6XaD%iZ#4+wX?1vG%U$>_D}t)jEs%o;qWi?HpWS z;Hdw_du%{Mc`Qh31ck!o*cxmK04cWX&xl;wzwpA{4%6OPJhj>UGJy1ZNv_lm82kfc z_2T;hmP&k*b?mGa~C%o1Wh3vG0W(D%`VD+&>^Ylo>GkcV&h)d@AgWnnzyq(}6nb z5dU+~U^XXp!k6RGh3HI*^ErVHLi0Nrfj=4z@3xX^+_T+Jm@ifO$Y%J=Kw+{Muo1eA zO82-J+NI~;wYg)J&=RJ0fUFUraf=Y04s(MzQBxHrp+>?hT=iy7Q7AHY^^W-l?)u+; z;N&NrH=>kTH~XpBwYwe4jM2&!7U!*ZMBXdjvs$%3P0eDm%QvEMZ+cPaJ_lU3!1)E2 zR+WIl%w&HMHx<Wq`YdFg|Cq&x}zmR)xR9Jt(=>0LeNwF)0bZ=PdLPuPNd`VlA zJ(a!{COpesPk&5F0ZRYvPGMhV7P*%F@0#);uykxwLL>>XI+o)k)yT3tYVHUau7tA~ z_Vhy!GVBX4ev_wLz|LQn32+wqg4f>c_9kELOIiL@b|8u++^5&HD#Q$8bB>nTF4g27 zQ0ij#{!H0)X=u_`%~o!rO^eP%#6ays7kq)p^>@UDC}1pM+DA=%4PW(ZG(xz%_t8eY6 znAYQhh-%;Zmd5?J4E|TW@^ajOrm6q6`!5~d_r7~De99f3KQVy5Db_3oJzS0i6`w$b zc5Pm`cb@AQz%9d(lXCA~#zef0v|Z9tr%DXL^+v&@oFdL4?JJ%H9nTF-PjTJoS^Cy# z78DxhQA>l00dmG>%WmoS6WrlSa56y1;De`<1MFIQRPT1Dg!bHabIROidFS*zu0uqr zz2Y+Nc5}Pyd#U)+-vb#faT!_Y{UOM{6+=D3ZTmIu`5Fp`eFy8b@eO^HPeqTBRmfg) zpSX98`poC$XJU-8QK-{IjyTfI%VMlt@Q@eoolJu!*C?pJ*#N;?;?Cga!2i zRCX}E2&@M@8Cc?Q1E^(GgfidRRg?@YZ#3lO+RZoQb81?Vo=YL5w{;J8|^X1L=Pd_+2Fr@Dmj&o*P4&PkA=K|l9 zD}C<0bkrDLR3(v{(|<{EtFw~25Oldn)Pj~|>7y|spy%v$DYO8cr}J5a)y3Rla!1RU zw$w3FUjT%AckUdF$qz! zy(@S9m$|h=qP^yWNrToRbwl8&hvuc`JWbE7_im_NvofwpkII^>3Q-#M{@3`#!UaM# zf^?tOwPj0ljkAzg-07Q{FA6ZHi$x>@xg)O_#U!nAk%)f4`#Vw(#o3 z*j{A*isNYLeBY{Dovz%8i+nj~+4280GQIj z->CVyhO!>c9bVXY#xPxUm&7i&m*Q4rX2wnuV^ix;Jq;|VRr}v!S7TFoJ`5U5d(6mp zE?y%ReA5Ja4xM>A=rW8Q;Yr%}ycRrgEl*I7lW%R*Q?6FIU)j6T4yu{6+n;&JWd4$5 zaP&6#z&a;wqTz(CuheGS52(V-25no$w@a!3%EuH!EFYx&Z?oG@1|M}rr54m-L+V+9 z2&H#fFTfdGbC-oxtSTwkP=!~Xa&u9avVgJXr9pdC+d30~V@#0WQeDPDy!Ud_^P@rZ zhEim;OCOq;4`?*7Yqd*aEJ;7QBj`K}lMxJAbt^OY@|fN~R-Wucyc^VwNOb=cgE2`V z%vrSN!(}Fh8oCK8D<foDlsH&@0%_B|isgni zmqQa$XM+~K)EKV5j_1f~=jDspV{M536FZc3r5=jx2$B+uL13|qn&0ur=^BS(oObl& z&D&jjSk%4jcoQtT6kK8${F z>m9kgb2!#VRkmwR80C+WUScjZsH9_2&4i=)7d-S6Hh@ZUJj!@1s8RM9pCgBLG>Eqo;0lB&+DF_EXz;VH%je@0~bZwK<%QtQ5FvE5!LJ6ljPxz+1_p-AU}@|Hk4_Wf<2BceXQ3`xMp7k87l zK$RMcNvKM0V?y0AoJxB?$~`IM$b5k19w)fDcuu~pm#3NKkBa#ePPtJAXwo`rp>uPk zxTOgha2xK2nm!%U8eV9%$zSFx4{&1v2$BT|$5y0rfw67vYyaT(*5fx` zd=k>1ssc`n_4*&=L;F%+ppCh;rr00IfpS_IT8som33N9~VF_Vw=+rL|if#?A)82lZ zoSeytxM`0yV!S5Z)#`yPY}Q>hLCA*)W18jcm3qDfO0K-8hgug<%7G3NHy)}aYy9#9 zskbs^wuGU-+kg;3rIybnYZX4Jz;+577fTTnM^(wQP%OVrZVC0uB>q#|cBV^nXp@LU zYj+6Ie>sj+S1RN%x~W$O2lm_&yS_b{UOn^&(c zJx-0ZkV6OD5z-VNipFeP`z+#!1c9+1+_#sa%$2??#IQMx?4U`=PxyV-~S4# z*TQ|w?!yfVOiSP$B4sf8%|CVZ#EPz&N{aAxbt8bwkM-IIx@rdA|F^{NjQ6PrhZxR) z@YH=0MO`MB=~j^kn=9AdI+`h9&;ms;^$6ytGe#@=X zI=}ub24V71!;0JqIk9nu=(CmZSh_yqWp1YVM#I_)CQG^Fp6aZ8AdSnd0w^^AhRjlW zXrU6t`S7-O>BDN}tKPU+1?o2&7`$~paDd%41r5cyaszJkn+_?lrzvARx*vpw^+>Z) z{9}OPfzZbr!S)ZYCRk^>U*)7B08Ihd%Ac}obr)lFcX}zmZ!5?IFrO_UU{uHKg-!>S zgyf@S`siQvBc2KJ8a^>C7NjY_&;-+K9w1TaGmQ_{Nk=RerYuIt>JVYb3$&0XeJ0%h zAp#?iu!|y49d_Wu4&92}A=sg)z-UbaR3)=sR_2!+0k4TQ*Y}`e=P|wT32Hxt>1nNRN2K0zG^K-uzdMXg zQvlD>be|3DE-dK2zqtDc?;J|{zuzVLQ(dR_<4LyuGujtSTpKqJxdvym^bF*<8imC- z1N7J%!s1JO9k42~ZCECH^;S%F755s=>=)03J@cArkdntGP`9w>PT|CidzZlUb+~sd1UBu|B`L`~`M?4wmxu4kzX3J;IJ*a+McR9kOuo=bCNB2fkc2?%B|QT_pwVUG6z#zr@VKbLC$UpRG=#V$d0& zUP~j`bfLs9UWw+zb}06w0D zeNnvj(Xg7p_``h6U$1QZ?)#i$1CTWg49Qo#7RE0MwbQ26FG~q6aw6(J5xr=7*a*x3 z0)H8_-egg3N^vjPDD4k~K-u)z(w6Lzyxfs34&O*4!!KeT0rE2sq9qo^??t(+LcOlD z{CuYNEQXklM!Ue^**?ptB=tXypnhJSUwx!)PHI$Kbkp4^*PbV{2zR}ZkTC1{7*Uc~ zP@>(Go0L>9x1<&xJRJPSR~w+%!ui=Oq7tHXk+>|%7nm6hGysM2bHI4Yh9~JCX40e7 z`mnK5zxRuNe{*z3z-N;nW+D|_cgL(*N4vf3Ll^xcSO^Rt$A3h)s#%#f|IHUR)_F=5;qQu=u42=C@&1Czh-Xs-H45^DW}3 z!d|l(b{nH!+AUpc*wyjL(?WiGQL6Oo4KZq#do6_`_#Aeey6k)fIvbxR9*Vi4KoeQ$ zY<~DGqN@PCW2EFkvDgG&?kfOZ3XFfzd1Rq7v)qA7quyt@WC9S66%Da4{h$sIVtFfu zbT^1A0*LJ}u}ZNpeumJ%_mH6s8x;gG*0n~o<9m){30z<1Y~f{J`J( z$kwlD*H?IZyvcc4jQP3U2GS9VLJi~r2fWw$!>BfkD#+RElP zJ=mTKXdGL{+vJcn)8B2FbiEBc3seY7lxn`)t~;&NN%p!i+}^yKel}#|{xpgqpYT;4 z z9e_-0kQu@U9NqV|N|{)5A9-LrCg#sjpl^bHq%=soWP!Q#>1IneY03-K4k6gDCTk z6*QA+tJ1&;Lt&~ImNY4Or!0_M?%|5ZDSkOtEj&ucCrsL)L;DBosr)kx1frXg8@d63 zLT6T}`#H1v&%<>egP`nbjoz3VWkcrp-3Y&_!Ap19I!wAbDxf^{D3sMJF6gyHsOvLc=BmH6bw|JkG|EB_ zW^L^|d>LZGcrk*`hEQ*jEe9`g&uE-o5+h3ShjP+pOy4&F*;3FYTyj@x-3+{2*F~xD zt26-{+-vD+cTeBMgjM9kt0GVei+D{>g*JWo(bbmKB3vTt{ALz}RUCPvsqw zKd6Dg|29D8v@{C^!C1c{E4^;SBIqxpPtf-s!rAV9W5L9#(}7v&lGuZXozdTRh*Ld3 zrm34s13yMiVy#v6Vy4neay8)sqV;*PAZh?W8FvUj~|VS|!I zt@RRa6@mbGIW9QQ=AyzhVbwc#PV?Q8yeRSS=5|WvAoy6}2g^}=09=}sN{l^l=h}5s z5$-M>dB2E`<mfoNN?Q-`t3-92XV5Z~5Q zbPaP6KjnkI>c?0&i!-thv1ALDXCRfJ=%(*JZuuFP7O~~TeNXO(1Y$u2NZ)cf%SRGr zLcP}OV1&HQXHh#hdhPXT`r1G)k>Rt<%Kcb?=p?Gx13fEOjdDBrRZMS~j0Rpur@7mX z^ZVdD-_{|_vjUtF3(T%%#rI!7AEB?CfCU_(59z?rf9Jv7>f@WWUw5^hhFSH{4h;qH z=jW-Da;fr(eUbz@wS1EhkZP?dUJ#K34HW62;j%h1vyg0wC8SqW#%o}U;d;w@hox6d z;Y%-@JPN^fB*edytff%?-0QFiP?uQrw}9$fma{q7T!Lx#fHXJ8^^t)A6#$-)=6fkj zPb=9qR79WHvvcb{i#^)Z{&WW)fIP%c)-NVa33V5yhmPs!XCc@mzM-}Be`pwpjnPJF z3g)u@ALKAN;5r3)@!Zz2RyRjhjXr}YS{d`b9@X-KFg6&Yw{d@Q&R^xPE#)l2hdT1& zPtf+>=2?-rTN=FA5S8Z3Ubn>|;*E`?-1v4vX650t3?#3KO*u{Fzd#dW_KyEgLF2;c zvn*vF9km~r-s|wbWE@8P!B+Pvs%*PYhpJsLIjHtq)MLaJ-a_GWnwMZNdbb>-js^t? z>6xB(ys+i?jq9frkCNfrVG2JC9|!;#ulL*-;OLBVEWZeKvW#k4x{YTBKmGn0`#kxG z7+w47*1-lv_R@dbt$L+PuG|*jc~=N`ISWV#j8rKs=etXp(p~8VU_c7GkhPPh`@&<3 zLuL}H_~92r#j8bk(|uRL4{%{>+xS{N<@^$`0|5X&07%Irw}_?3CI*zASk_Yb|6w}s zIy~mnqmq7e!FM7SrGi{dzDN+rao6VGU z7nPPNDSO$J5og~tWPI%9^Zm}$*2x}FM1-*V%!sWc2q(w>|}P=@X$0IrNA& zIp3&=Mov5I&l7Xz%qh;xGa(#9UBbF(g?j(UQ(9S|&ZK)cyT?>xR~m-O-3Qztm^3$~ z{Q%Avq6K()3{Sx(JYLTgh1M_ls)^Iw^|VKuzMrrkpDU&vYec(Nrri`bw}37;Slt_g zvAX$u5z%sxwQ23l$gvRH7Fjn&qsUH9C>idaSpCoM&m`wBGjaFK?73}7f;I~rSLLx{ z9z}}(*!2|!h(|PHTC5ak&3HEZghuo@##3|G%9uVl$yW{&T4GAH@q~nuVpm=Ef)Hh7 z!W;2*DCk1U$m}pJh{kevb#LB2Atw>f&w$?PBmPvvN?+JjEuB}83trJi4PnvC<>MXF zaMfLF{?#bF#N5{M5Ye(}Y{DL+#9J4dj9DQbTHB@)HE>=EIYmEz_CEjY+18=0=QjS7 zA5)_FF_x7J#da`ou_))T^Ubp_r&s?R-g#Ty&$cZgk_dNMsQZOB0XSZ^73QDZ7(EYk zc^87AL#BKzW7o=s+zw*)0u!rS3&QM*~SQp2ip!`-* zaV;Cx)bTavEHrs2$=%(dMD~bqI|V&v1i4Mcz@D27>C3mQ-0$7K6qCnrU0-#?6uLBv z{e~$GHIp!tT0Y%^^?XOsN_d8dt6wnr&yjV_*9z0ed{*Bn(};Mre2yD+i`PTGl1N>G z!`c>pox30(FWtDVLotGm@{3Q_yzEa_7os{Jh#!9?(u^8c>(=nL2Cy`! zu?@NA+i_#Fif8tA_5u3+7e_X(6K&pw(Hp1T<$uM5ouaPKzj^omS6PwChLVj`L`KfCv`zmZ}OqncM$Ys*PdF zBm@&V^eY*7N4KvMa<}+VOYp7?wGs`!zP`C0N+(Gbzv^oY`C=uYRuI*d>yY_#EU$>H>6i-cF(>b0IvmVK#Jb`3a6 zC9)Aw3x%aFr{bKGtPVyWGFg!;^98Em3ZqQ9CGp4e$ECc=(d;gAKxPrW8>qZi%ptl7 zHfvVF8hAtx4XMmZe%G2i};8w(2i?I^BR8|lZOU37CW$KG;rqFs@s2*CL2$eAD zj>pHy>4*6_>Ql8v1-yEfu`W-?w>wY0IQsH_jk+FPs#xA?AYq6V$-_jyI8}3W-Q7{- z+Mp5Qk95bFeE|zUV7Yof4$@^vE?cbU{pMHqQ@TRLCdaVi6#1wz0NP;Yt(PpAh8Z?J z`Rp@IDw=l>r-#e#kH(y!aY8q0OaK;RLU3oDdplEsTW`yv?*e*#0(N6-0y%~yOfYSX zDiKF?QBH*x40EjtonFOI91iAd${wJ#=u)KwcQNx#o9F(wyDqdm9{TJ0=bW&o0LF?z zny_xq7dQ2(Q|=6`o1Z2SmdseFU>2EPqvma>SSiTR?B3iKbc@ZZwbW+yByFCPOvO{} z$oQNmoqfRL-f}P_7FH{IXmrxdkos?xpKDZ7ue5t6M(Q@W!#9tb;kQLUwQv$7vxG6_ zUupGPr*8?cw9@5kWe5~%CEW*pw8uo5B)e%fj4v};uH+b`8=4P5_Mj+-l823>KOT&R z*5X~)ObSD`jvUh*VQsa^2RW21RQnGf?SEw+`JVAdVxMxu)PI=JTjXHUcHro}9Zyij zY=e}2F<#!R91=D_vf8AVa=-xETEuF!_5I>NnWU^qK3ag438PPtB6*cr&eQ4-CBBUi z+Cs>7o?lw}~tA#>hpRU3s zC;%l}B+uHiTYKB^w*4QAww!U%!#N;4{#9D2)-0>lRu)c9%N3DtiB>J1#5wN=2eTBA z#^&Z0HT7E#?tUPt^xSQF&9dx`C$&8GyZiAV^8eu(=u?_pyX{{zF~0omN}<{qRyRXq z!tTS*@NCpFTlX*(9+>G$J`-n}x_{7d@uAle{ zNq$i+rGGKU#6@LFrECvHQEfs!j3AECdF^E1xSEfL{%%~9W2rP-$}+mrnUODH1O5Ri zv2ZAz5xh-5T+q`uJ>Z4NJy!q$(K7fJ#^g4}55Fr?8{t}4fRrSb+cX`K7}m-}2_r0s zovDiD#q10ngO{Bo6=F=)e{~*!%TGr*< z0u#wjYklSg%CzORJz)6AFIXv@jZx!o*Hxfd z9+;?C_Ie05fX7UG2?WDfHJqV_`;M&(4!Xc*U6~e|QCI8D-{v}hY5up8f z1^NGACNE||958VKV`fLCvUm6(R3hIdY1w>|k4dvZ|8LOLcMLoif>NvBvE{Q9Mlapt z0Z_DkuTnw8pNmU-(~H*=HwBVqg}0BT>?$Ul`UeZ=Q-gReTNGH0GuY_~fGQI|+_J0G zdNsZlyN#t9xUi2T1<&)%Mh1`mHx60zcB76%&T!d-P-q>IKA@Fkfhh|ib8ZH}!L3(VwzndAu z+3$OSbkJ>eW{PQ2;FfPjL>Qn*3A+?jL_r;r5b9ro{k>?D`#>xb#gZllyl^_jB03wd zxBKFL`M7^ph}qZiqm7R|qo{hnA4IQ_LO?&{$b;+=$Ylf_U~pjGfcL=wFb2q}OC{>< zBfRJTDD9R4zeMOwa!f$6R$3h9Nj$c?H_PA(*C!TRT5pxa$HpVr|4Ny@pK)i$!FT>y ztJ`V!7De@;doi0z`XwdlRA03MHh~Z1J#z9dkE5`OU1HyKHfkHfG-=pbpiewGNvH!{ z%sGUZVACt^=)}{1x%%T%PUD-rYhSqSjvS5lhRdAg&^kV}7C7l7ke~;)EQatI0=w&H z4&=*t`T@#0ViHjS+`bCLAecz0>o!gFqd6E7qN905=j^fBgMc~@nkOp{>7Si>sy}!Ld$fX!ixvB(D+lr-5~=1P9`Ts5Ytk zEL-Vc_Tjfw`?4m?=8<|B1*Pz@RxABkth2r^?3cAzv8MHLJdR3n^;Rhs6^AwF&s3tJHkzraASqLnP&?4XFG`uA2j3ov-VpaV8TsSx#{=TyY#Cl$8TrknT z78^=cp)Y`X2;?ZBTpT%#6t?br6|Hjd1a*hxW0nL8fwp5dZZqNMC5G;`RiZpddV%o1 zF5p!WjYvK=g1?;%gIuKgfT~dv73;}b@?S|Uzfy*2b_Ta9OlG_z*ai{%3R2|1+AeDB z)mzhu-&EoGre>2-g1JATM@&;0B?M)dRx5C95Ig}Bqfc1d?!o9Qwvk!rWImQBK!18j zX|k@JJKIin-HrPGx2xubkB=c2_9Z(3wsCH^FV2rrTMy@tiJNrEx|tFyV73_YYO6;Rh*S>F}%3GF4VwH-mZ z68P%`5-GM*n@Bg%wnM8!k$cUxSir`s2Us-yzqcP=(RYJ}0a;RXqC-ziEGCh4lWAZY zB*K0i1lBZB?Mv3|0>DGpJG#v}-g>8VF73@KVApTbtT(u-9#(=ZG-V)!#xJOP*1@iH z!csl|T743(TCifY{@S@G*8*S(6Ct@CZCCRh*i;KqMP()m$Xak{k3(6$?WOK_==PuJ z4YJyxo!wR=C=CQeA*jp6>apwp+BHcM^HFH6Js~{I9$uExvIPtaZ8Pi;)ksy9-Dt#> z9IdCGide66yT%P$XgXNqYF`*o#Ky{jU>E0sEzSgI1CtQ&KhxV7-2tu`!djOJ5ivS*vyn!7u+?%a=JF}9y`$o;1t2%xmxC4Kjbex>4 zSt_M0qUAZ4*B7zkGIi6n9Z~T|h4Rr66jfaw zS~P2)uG1K~7Tlp9vDW^!>ic4P!Dx3luH$!&_FCsWCu0vFVP_qVwSeP!YM&UvR`UsF z<|*Y=qF2W<85R+ls)3`T%olLGUQrZ^S4(fGib;!1Q3wx|4tQ_4B+9T@JAy8Hj6U@Z zeF{rQ+Q!?w57-OPkte;N1w1cIxqYPW`ODCm5lo;w{<21UqToePKow^MduLOPj?D2T z!H^;kfBwSWC%9;i(ARDMuwA<%oT#g%RaE-B$w+zO)@XIFsOuz;=D=6qa0 zOt2?f9!ya!Cj5=Gl;hN}_gjj^z}E<`|-u)UD&a%^^vJkaYOYAxY|%)UCt4 z`?ue}a9!8u@wh(k_w)690oh=8z{COKY%oT5DkL{TpUk0LJOINUjIIDzI$2@R-xz9$ zZ)(eU^gJH@1A{)p1V!URVpq4Sn0|==Vd2>SdbkU7xQ~0V;M~l&51G5_f7=%7cPZYW z@Ry=~zi8d7Dz$SvBYg454^k#dlUcy4Nr+1r7_mC>H~>~HR{o_}E#9oOkOS5py-42y z%O6#n2cX}H(U0~@H{>e`^-lH@l{cS1@w1=$2j_Y)p9V`76J3&}wws~3PQ+3F8w|B) zd(`Gv8^6h6{jT-9na7jF&}x82>=w`tJY@e&Y@`HuA;BW*ZGvRxgZTFrN5y%Wo24A6 z<>__1Y!6&>yIU0#A^+xfK~(ebi(ANLcndRRQG0wRxwjY%!HIzScSuUc%4pB`T!vcQW+_ussovUp#F{-2^rC-a+5{5%LR zq9WL*>L?&T@|42%1<5P8<)0f6l2d~C&Oxc_w^(deC%UOA)0=& zT36F%An&||wqx4@9Hnn+5j;5YQes)>wpE~Lo_|gpgZk>3k(eR?2c(>IvI8Ebjy3Q6 zpvwTPKdp0%`v~hcyA^^DKHf79ulVppKdgG)tSe%@qa{SqxL&yXM(dLcp=O!Z$-Ctx z4b=R^F0kt1H(o>M%tKpaUasvQsc|~8`1^^wt)=Y9!m#SfX zCO6MAUDV}lnVl~aS=1&E!7W*0pel}$EOk7)rkHJO+P&C**(j%XOonv0LrOp~rg|Is z@T{L!R&~dzTRm5LuZXE?`V6^M+md9y#QjU#)~DyIcR#lN?`c`Tx&qYMryf8`VU&|$ zD#M)s;Fo4>I2HJ=Jal5IXsd&a9j}JpJ>BH(lb+IPrya2)V@K4UN}D|Gn0ritcC?U_ zXLwUuISUo;3G*i#@(hJ1Ca~0H%EN>A!0~5U=dDW^=AA@+PdW8wF=R zfN0$GDG%|x-h*Y>k2P!3%?KnRU9oqG$<5Seu&uz$OC*iGD>eQ`r(!aG?5|E}wNcfv zRR)oE?-5b*Vowa5-D#LQUpf7P8+)9VXHY16d7vfv_-@>8B3gizHTc&aO$%#oTKZ1# z*V@wU(pT=#zht6j9kdGIu4gsU@71q#UkT0{J5@l+R(8^&0soc%X?fXb%LY^M4PX{_ z&$gjobNgv~wYXf)+I(rBa+n8x>`QFmW2k_++$apiN24Zi+rR6P2Z@ISdg=9qJj3JP z8dVK1(QY|695i!#NKlyxF0^bEQVZjbijs5nZHATRXHmp~kNd869x%>?5pC>M|6PJ%*i&2OUoOnZI18FrWt&&uWs8F37w(tso3ZPlh;-GWr67?*d~B4 z&{rx7qpfJAM1%EzHbNbIfc}mWzb%>+w~74>p8iM>Dhk8X9>POiMHDnv(|u;l78yQD z8O~>?dDw`5+FKV)LaBIEAPBaY+4!91jsy&PF zBXKbg9JuIACI}r}z9IInxbr9_@!fO%|BZA%SYcfT#5VkIUU!P^vA{v6at!{R(!_U- zeu}bLA$Kzv1^-P0kk>IolAU6D6Mdtkcw@QTUgW21&3E~w;tG#QHt}iWGhLkBf#I0RLci6xK{ng}DW_tH!_xeFE!Y>qBU8PnGGkviNu? z9vtR2XLD=nX106|%o*YdQg3Uyd`a93#&?-S=IVkl=&M!S4quaa;U36-7T_JfU$Z?Clgl)22bw4FBQOUz@^9 zlOCFVezX(VXwvQagzw2}y3~BHpfI9>8+J-=8f8Z2+eClWIsj7$EX)WGMMJ?X;F>qy znNtvyNWeD3v~V)Xn=vNO=-$7Fieh8*jDq;Pi$|mpe}BLUl<@77)GCV6xQ*QRMCQI# z5V~nqWd(5r5t2Wp!=2*K_LK8x<#`pmU5m1-d6?WQ{n}TBf{YKx&U+9nLev8nTVAVK zhsCM0|M$yfXp*8;;ih6OOL^bDpQC94cv;hLiVyG^!8W%|Xj>EDsJV$Ldgu2AibICNM~qiS|(< zUf*CyV70C+*M-SoHsY#(M}ZiOno7&ha7p<3J7gS7hH_+qVpeo`m5YBKN$`jXvP``D zU

Ngl?DoybAF;5_QFc{518%#@>Ko)_JI zOF>`k;hXkxD;W%zaGj=#pXUa{v9}FX<8a5!mKrp3CiBNX;USX5{5khH;#F zQ(^2z?mBRSPQ1upp*g$1wH33NLPj5pmT{iyTCgH`d#+(<^wwD>q;EhC8(}b%=VuhvA>bbbFbAnMjJ`Dy()Ei;Swi1aZ-cI(kwvW4IRxq9|Tc-4! z|LstZ69S9y9tWrM{!E3W<>xY1AucC@&~CoN2Y&gff*+f2INw$$&1sdb5r1rGT|^Y^ zXtTL4cfGR8AB-!-OD=jb>~ebZ5DR%HdL@y`;2AAJJV`~}M(Pp`hR&&JZpJ%qaPbsQ zszlX4U#j=pr{*MRZuoM~M@P=9>r3;MpWJM7F4SFHuH$Bbw&J_Z4&Ds;P@xo=I?FX3 zBwW@N;Jj1@kU)oZ`Hf3}RAo)el_GK*cN3=2e2M+k{l@n~tud~*NT`ko&=rY!ER%{m z8&0bVjNX59;LP5kd2UIb>+U*6J8~(85Ngm8TvRyF+7a@&i3A`92Scw=>~Uy?UIz0s0%L%8kEwJVICz4N6HYAzkWg7sVns0$1H=Xt53 zJot(#qC$dn6l_Zd`x^)%V3hmOK8$M5`v8IC2FNydKucp6xy9Mxjd!xL)69%b!&aconaPMvcCvJ)V3Qzo_6olcYlKqt& zcMeN6l9(Gw5=68OM-ZWrY_;Ce)|U<(l?|&C#m?F3EtS`zL~Ia zVHaJ=Hes+u$u(RYCNMkM^L@-1R%5`BNIP|GU@4Gj{7P~4R91uh+<@r<$f4JLrJJ_a zPq3AbX(PZkOTPIM-~yIl%orPzt2)>ef`++paiIr5rHKaK%!ca{3*ne29c_NKT3^0Bv;z ze_Lo6K(g&c#hFX|P?F&Gs_W1Ao=q68<4btQFCNJ$0yx>eHY&ct!VYQhBieXD00`oC zlhggeFt$l25ol1&jf&uHW7Gc<4!=~Gs&pVDkD4ggISlGAHJAx+AD?%odhKw?ZfUsGEz#t=GHeTcH@R<(A0JIT_sZ4x|)K-Y2R=iXEt0 zyEW4LS&jFdhg!27pC(Cx$M<`7k63xi!~d+sjf^RVve_onaLj6`hD+(^ExS&B8Ih)v>>Qge zdXIvGc740eW5c@!pA_PWyaz&`a2L{HYXRA5CJdwE&-aYP2sC~dIgy^?+kwf^A(nzz zl`7Q^COAA_}fZLVYjt z_xAC{x+>yohbu#nO;CaR4F@_rmY(A8zpxKE+4|SC@0?wIO7aVpz4JrD*q2UMc`^Cz zjSZG;7x<#~r;EOk&l60`hxpvyD6KuVoL*U4)!d#SJ;v}ONpAQw|Bet4`v2&a_azZ` zb*ZFLK3O*ka$90=%hrk?@F1negvqTGFv}}=!GZMxbhWASXNK7U4ip!{tKUI4z@gDy zzfhNLZB^dfV<_&A{+9zjysYLhbsZa|*`NQR4tKoyr$9EO_ z(^~;Ng7=<1X*ZX_UwvM+{?@O>KaZgGyw=2H+ZaY6*utCKf3l& zCds}F7Dv2!*DI@m`{ay;WuF|z-<|HBhNjp4<;4#EF9MS=^9R`1Ab|xE&=SE`(+~9-i;7b&%T=v2M0Uzd zLB|5G;db`Wre(u}UQTE1CwWd_pKl-dpFSknX(pcD;lh4)iYO4T`h^PtZY)3=y)b08 zVDk{a5q2NC#D%UVx}>rPAKmlgS^d1OpM(&SX~|vk`}DR>D2ChHW);*6zH_V4^f22o z8GI!=^?L9B-u#X_jO)4V{^pNL9|<&2FFK{qD=l-!gE)e1P8RKRv-`nYNhCJtZePQ$ zl|Xyu*{wrN2k}r87@U7&==WY6z8~0%VBe`LK1@SA8;Evu0nfIA!F6#aB5(kC6e>L2 zlzdOI;?OC1R{qArVG_X@;{Hf!x3em$e*_HuslFH2Bge#Q6xoPK;mxYHU^uMiG1{CfH*eVnXrE zdCSM`FQOB+=sr99(bZe!+pH@j=k>&cWH*e;*!p0>16~MOWvm(eY=>aF$&>mA7;ON( z9}V7HtkZoLs`SQw@muq+eA9E6qD6-V&_TOi@BRz{<4pFPaoZajJpFsI%s%<%T-}Ok zqP<~)rrs*hzq0rsBOs8d@-vNXKDw-Q=uRa8Y!od#=hcF3+g)8J-#@NkH?AZ$v2Ftm zlE<_@_S{0;6vl~0`QS#dC%)&z)N*wfxcxKVy!vyo`6n?G^DS)I*7=P_G5!9Kzb#M) zHJf{iotL=t+ljNF`j%%!E9w2b@6FIpNrKdyIlg;}M*O3`j`0lZlV^cG zw&0|yCyyyx**s?k z?@#qKec>-pCd6+@aFUUiPE$QO`b)d=#U{gn>2}nqjhwP7oCPWAxG!mD; zG|dj-d7$hkAJHy@`A~C(`|>WU8%-l_cKe6ZOjGwibV5B9MLvRJ{oM{ur8h(bEL>2c zgF70*ZCJe98M{2_}p zE6Y_k4e89Zn;$GO_AVK5L6jQUADfVm%|9wJ^vqhxG?`JuZf(BL{<7v$D0nsP;;lm266UkUn$RQyWkrz7VG@#+wiKm$sFEoa@ZN6YyQ?ym4%(Xj=_l9C! z7sNcYYx4L01KWRY_@p#@#^JEn3ck;5O6u{0>c!k!6krqCVM<-9P0C=oEWpn9sFT5a z@9l!4@o?++AHs$i>B+!hdQG|%0DiT9Od}jWjqN|9{iQ;cXOlAVo^I6E9FcQoW>bXG z!F*~S#QfZ-1h(Z%MS%Xnr9Yv0c8C0jd0+*l(Bi}dXV~2CWH>zv6+|A^=Omhe_8e^E z43eFD#GJin7s^UJ&fJV{68CBD>Aa5gMSo^tdXa)xrQ4CZp@rv<2GmfxNyXM43+b1Uo7S8*39*C?TB^=dA7KKs4c#<0y>|Nng zXq+BhHfb!Xn0roaF_>xCf#Sy(Di|XJ2T+NAURv-7fy-R)k!W1vHcXCmnzNC~>>D{l3gT_kFjSXPE#II}-EbL%tP?jJNh=CUA4@yZ`qOT7dz>HClFPk>2H9{R4~Gi zXOT9J64OPLLF^tShV}7Kw3Mxd%o@j9olI0#>7++ihqX2TKBr-RsOLH)&~$XNAGIZs z1T#ImVjt?M94aXqWDOP?TLE*v$k)&S0DKhe3?oZcWd$ z63g5Rx`vE4t>BafGs6la4S=tzYfT&?B$EtEe+YE!Z^T>>h3aJb<%RKm)mw=J#>*mj zBwv6wG!dBDn;@2Ar4|O6T-1fuP5#LVzTxwEKZcVB9ds7qPLgwI1#C^vcvZfOjCl2H z`4A9~{sa%>p`V!{*0|h)ZO#3_LrdJcPJ0lY&c+gf zDuyHi&@Fk6Ro3WTNBa)rVlvomsGPQcPSgHee@FKy zr6#+q!m@aWzr|?o(M8)6GzI{qEW-d}@a+Mc2+81 zmseGHI0mVwrSJmZYYHrgHvqNy{U(_WCC48`)E}$6B1Uxk8BXI%{`q=t=JW*EctIoW z@K>PT+KZM+AHp`@j{lVn;ROQ3dw9qa5N%@$<^!&hxXOrk(9vON1qWrAEK!?b)>%h3 z0NK5GLocajvoLW#YN(Ot*icz%$A(liwV15~u0S(Qs%(DX4V&A`0<_~oQW-oDT?Bv; znQHxxWFU+IfUY-Sax+yu7QQGVb5{BcZ+OT0Q7H&)I2UWz4zW76*zXv#%5208Jkw=O znc^h?rDoW~w-Www9wsaj-W6Y2f5w;khLIXXYy{eUDtqLa!;-uZwiDI&1+g(^_S;RMVF z2-xv9#JkJNv|bqPw=A^lqS=~qmS{RRMNo%o@`-l_7U60lfEPYqNAT#O*XmKVaK}P) z>kyqy!)u2J4TC?u>F3FIU1AhdYmqcEC=CO4zSoDz$0NOvN~My6-&v>8u+mm0F6Wkd zfcEiV?9-}f#cSs7ZON=BT7%-(cQwSq;8hBm#oDD~Q%3rmIA~=**YJ1dg1aVRua0f+ zZnt6y5syDWpLgU;9UZ@E_N%(Dy9`m~l2`SvvNR%VhHd3vh`JsJz#Mz{etC+b^MMw$ zZCbJ;Jl$N)=Zbe;wCq}CaeRTE9>k z)~TArvo+& zPa4McrR{vmj=>FpI=>dup%4Tm-S_6HQJ-CjRQnns=_X`61bjz6jag?XB@bkq#p}8u z3J44x*&N+>Rh(P%sF0!)4Zh%Brm{o#98B4NrYFzi}bhT5Rf%frh3jcn1`SP_=vX7_5{E+8Dk#ZmRXcBwF=#)O?Xm2 z+Uy@S*ZTB?Tod|SOXx(UKYkRYRVL&IIher74DM4cUcgu4)Je4!ADHl+gI$-t8k5v& zd=c+!`Z)M-bqp6fzMl5Ao1J7aao~VKoCL&TL9qP<&3xT;rp3?ie{1PV-I!5?A9ui8 zhk%Z%d9wJAWe@M%^TUVB&&qesufD8Kaw^H#AhSld@oBs`xzt=TK+l%xD`>LWeqfGS zDON+>ibON;p`S>keq7MhUoBf8vB6?2I8kOSRHFInQOY$(aIwV%aBS7b(h*>}%U6}e z?g;=Qh=#ysw#}$_0+x#{km>7&`Zdc|eglUp&s#B`YZp)rYz7%PvQ_vpeg2*k?DESK9HOJTRkY0aolg_yjedR}j6|mA_&4baF0(YvCn!6E zs1^&HLryQv+04KUeqi&Izf#@Hl2QeL3=Iju1Eg@r;u2ni58S42s|0lxgNUQ5Lyszq zgjCif5VopDj0fraaPDc44Mx1phCp!}-a2$s+>ciq17X5@p{bF&=Qd!1V6~R887)Uj zyny1m=vOuUhFn0>y*znrja z|G(D9RrFN+gI+HE<`{P>bz|{Czoq7hVe~}R@&I!4P(gw@85p?<(M;az;OJxNr&41n+x&jPXT}mw-)c z05tyHkM`h{W~hJz{8cbW{UggH6w9XDD{D88i33qE}9I?4xVs3eZ>_YGG?!*4Y zVa2R*%d&6N`D7^jI8S>G;w}2goqNsgnUZ$`|9z!QuhH zL^9y_-T=kgEO9#Csx#3_gpUn}#1_ib7;kvifXB_sX9Kv@AW@E#P5Kw9HvWgWOV>Rp z`gTRAky72%`Cnvd;f(ra*LRx?3Mxj7b($%MNv{(=T{`G-`M*a1#P7c9L$ar6**g~CyqNd=chYzDZvnqb>SS1sj6c(Nz#bV#D2#NaChW~@ni8$}O0aJ+(gqFD0R2pmEid)SPH;0NAk`0M!4 zo07}I9O;%pdOQO?-UMg&C?}{4X*p|S=mIl$0jLNg&aa+re4 zQ*R&Zy22mb6DdtTPV@JJm~v+5gx=w!^4~3Yb-3CQZtkupEdE8(Qd^(F~8_ShQ1u zd+`m~{jdd!Aq%qXe9;ga1p60$V2sn+YJB3i)g3y)jr;X zV({=RkkyK{lst<`R}kiI2s#RyOryqSPIM=?{wH();v@#)e8~b3d>% zU5aD)SXM`Y^MQ|D*+dNDeLE0&mC_u;u)qXgsi`+slNsWDn`qCPM}eO;N`rC-7(Ra| zQ)=e%0}yP`rfO;KOH`sS#UQcIsh8)@>~j^FCeuAw#~W5~}gT<>qegj(dw z^hk$5e2K;gz!rvkWx?3`+%b-k`!lBY2BW%1d`bBsBm)kUk9PFI>&ZbY6&0rKZqfn0 zwEv08h1!Eo8w%0wn?PBQ;7|bvVuU=-A2z-hGahBN@2XU7f@A%fVjf+77v37B0`hf1 zTRv(w8uhO*QSlcuKaCwEZdC6xQUNo8`mp6(0nmHTxO=-F=Cty1psFSDlUmVkZ zB2lrrr;?KT5O{Hwx`Pcg06?2!8YjIo_El6NB5BD3;JBo~wvrs^@!*CVYs$qlP!zdL=SKHVQI0zR4k%*Y%z zPj1ZGCAgtk#}kGG;{{<$@GFi09o9p7Gvx6A92`^dh9za5kXm<3aT5I;RoJ%kSFCGg zlZvX3dqzTxdZc?;f86Fg$7L5==W?_}fQ&bs<0#y#Z(yh5TgiX;@pE!t1U)9tes}3U zdv0A~zkTM2pY$*}MleReA}0uOf9MG{9{7US92s@V!zYs085j;x%NQOqYG<07u7LEIMCo6VluQ!Y0AC!&09m#m)}oP?92sOnDw}{?IlY270TAu`>s;6wE+jhfQ(u38 z9*M1)jbpw-wI!`rKmU^`rqo>QCc;qrPneA!+|)ABW{yHiN9Er}XYo zRGyp&iJ^bdO}6OdT;Nhw>wx=?OHZWvU-tN+a{G}vGJifD!2fy2rYJN@(nT+EtcRFd^!S(NfA)>~ErJ`XZ(U~I7}n~3Pm)s&TFy{#S97&t5G=-Lu;!?v zPOj4e=}RqePx5g8bKIhcG=aUe*bi7x$T1^uD3CX z{`A{$jo!=POxd}X3QTSM#d4XRCB4 zeLdm!_o3_aooFME3yxpxS{_zdde&!N-}54{)XXz0^Q7iGHC)CPgw9Zt2#HOJ8CODS7yZ992yPFg3mfnuc@4`@Tm?OHBeRP4rYFpM*7q zbnM=hhW#DkxVhC6tN~wr3f%WM*tK3eQd96@}*m93` z$uf0F32H8-euNKD*BkQsH|RD#ckj`P#UzA75W==s7+)wI63PlJSk28H<*^t*?~klA17+Ux`BZET|JjDEhQng zdL?BVRag2zpz8mBc{Gv3R zjY|ouMclu3Z>`WO*Md&5erF-_8h->_Z%gDM?HltYY!G9M&t%j$*UQxh551{*U!QYz zxxgS@{?Xg;9Thnc|AB6YAWB#oepV8;h8?j!d2X3_Oqojsv`Pyvd6Dc?Dj7?}__L11 zr@T>im{f4CLRs?Z4dTP@n7kgnL%NGvArY1Ye2<2O(15B}=-_Y#qnl%G!wCU7+#j&;$^7m%f5Q?gAZ26kY8Z>X{#DT2gS>+m523R z{y1x*lzuit$OvmL>F*Jlf|2jJb(xWqh1};=dqRXOf8^yZlYNy zxBWKJ&NjSw4fn@Qi_E|Mx38&2$vK4qV-zi=r&Gf#TC+{04*U?UE`S&-1n0j zZp9{Nk`V(Zs03nY!!e6C#)s^cd19INyp~-`pOrT);(1EY@%SYgZhBS4YEBMKWBdQz zajf*3xmJ5XUFD{97I-MTEhYT7TH$JUhS2wpL(s1_XukG+7smN{#-ubVOnFGzJBj~fpx=ReMnZw0mpMfuak!_ zrKK9{w1N?ufIM_1F~Zx1&=$15#j`u6;8e&5O@Ci&MU~e{Y;agyci`<~>2LnOB(GPX z*UvHXF^t!!oZ0g~`jCxlb)b6fNnOh!!IrS0z}xotC{j+U>hlqSqJH==8pPhsO3&^oS6Q~zWM&iEA`$Fbe zP^g5A!eD^CI>Ux`719`R6`2aHd+AIf!;ZMTPEA$$}^%i7nTZMAKbTd|J}_( zU|uc2R2fG{JdVZbuEgtJJ@&k4pTuJPYE_fP1`%op0~mBuOPt<}!BA~Jq03dd&XTX1 zaUdWO;tSH=20*=w2k0k07dSHHp>PcWyJyufaET9t@A9?6vA6Mi522n}`M!TJ5Ac1a z@6pl*KDCU2g-AAJUo{<+Q>5n@mqgz!8m{wV6Kl& zsOr~qiy;iU6_ka%eqx~2)_{6Oi4@(G036#IAcwbs!9ilE291q6n#8Nq99JnQ=DWc4 zo*dQjFMQfXP=9z-V*X(i{@Sq{t@S}-9&XpV4I@naP8rzZl4N)GiO)SR_-xDJEc=~r z5ByI_*|IONczZTXUwA6MJWaVaQUA*Wupj2ODbi=MDZ;^SuWpd;pwQ-u(@V8r*n6#s zx&3&-%e&4E3SM3S;o`SK>ZhY`&}WuN-2c{ZAa$zA2GgSf&V2W`>97q5og}AxSU~PI z894IU1vAkp1^+f1pv*8IIZacvK)FFHKJG|$mugcj2F;uipdCqXiD}2a9>Rtbs$zz{ z{QkCJ+6>ZBv3KAwqy&&8*I@;}s0A4%UHcxsS{)7eXAzI?Wg>dnFWW2;`AI3i8#~IF zS%4n!HzQnM?Sfe$*2iYIi|&RSQK-I=?FD>HgioX zgQ(p#McJsHp;10P;9-lw|Gge|=QB;)B+~E9*{Z%Y8n8a`ecJa>%{h4qt>I=QNIOWO zs{LDRVJ6l!@HJ=TSJJyItNGg}m`Je%uJl>LMA#*uF`Z@n8W}H~>$N`#3C_h3&H5hTX&tu9AQw2UF zYev1bJ5*wNdeQU-Bd&qQ8JS}{rpg?au4BVzQF9WTk4+gtN5Vr2!oGh2ZOuKs^d31P zL3RS#NNhA>7ITMV9X)^xnI))wJ&UNR4|d30xYh4B~7z@Wm=& zHosYQE#H=y$DmNI#YWS1`Fq491tSLLK zU#DL4lRCi*>8u+_sC5`|wk)$uym|oDJC7t&f@L?9?k`Y!feUmQxrkI=N8ACkE}F`2 z0)Jn-**@$2t`Kt!eO8@F8DM%JwVpLiTA~LKv?Hz2K7?HaaRTz_O2}fx=sT@(Hu0M# zOj#l0A;IuJY+8&nTBaC9H*EiajkQc9=SaNsEmYHlTZz~Y%^}(<<0&Pg6nlHKu0vbK z^HolhmC9RO)x7%79jLus(x;Me_m=HmI}ia9UjZJW2hj40e>)|Cd387|*oQzzf?^zV z*xn2`QGmjS6ZJ}RFTY#q9tM%)-2a+K4fBJH@+_8={#&5Z**8(U zWzZ}wLI^891gvb8v2KaaSb~nPtK*~?lLn)!&c+L~3FDOqEf?VI!&|c?-p57QukpTR zXHN<(F7{fztWdYRI+WsaW9M*z{TzPt`Yd{-&kQFKAMUyInvDI;29B^1mJ-x!{O7sg zoJO%U#33*%KFEh~TE;^_Wjh6Hp+4+D&BlM-1{xb79-8r?Hq78#kim`bsJ*7RXJqWL zTOMX-y~gbW!AD&KA6C(&3rv&NELr?dQ`G4bW+UvW5&)P)4%TbXI6j;DG0tcqPNDtu z=E0^Ho2zJBF0i)_-P#(S=!;G7P*78QUZj=f48jiETk8*X43d(~G z!k81P@Q461a6*IxprCUoQ;VrJO|c`G%rzNjxUYNX)YsPB1&YDeS2v^)Pt=Bm(J5 zHEt2MUyCw|1ZK7D%)cR1bxBNyrth4o+}a6EDGS{|H>FS)Hj2$nufP!{0DE!pt2=6& zUlRmJz1h=;b_@VMxsg9Niy@=TTUY>UT!NaEpgNgvCq%yy?XYyk8p=bi(s&d^i!(UI zMVk@Mvl}n<@)Fe+9ba5__|3+SSYSu_nsiRUkTs=jvZnY&q~5kpcj1G|64KiLT~qz21;~*j$_%g9%;bR9Ex`@Ci7TiOkT&&6xMKDpQj_POD#5J*jo0FgHyZSxHdH;D zjB!dof1>8cab|Lb?e0Zx+Ww=D;~|BeR(4tK@Xo=GA;6t}a>vs)ol?Z+&e_*Ne|+*| zM(#H~Hh~YkDrZ?r^eWlFVG+vKMD9FYe?G$5F*+ylA+Uoje8zUS%@0lND>Wz~pcUdTbc)MQzlJA%veq&|d{kBKq=m^q1yd%_(J-3=W04<`$A(l{c=W2YJL9bJ z>js?jMO^)f*6sSq5AwDg7ugy8k&>C!AuITR*HXPcTq6av*U5W>?3d(ntwZk);4(VK$#O2*i^UoO#VRP2EG%e=1p6}h4L>WP!!{4q|I$wC;3k?fN3gW%U zO2y-B_Ox7+8P4D%d}bvY3XiNNrgyreHG^Hl*|qg*a+?NN4Gl&dCvQ0a;VT@hxpuHK zo~gnBpu0Kxa^RmCi$+Ty9Cte07|$(V{DicP2cdl#Z$l6oGURLV$OmR440Omg9^QtD zSwVin$;)!HQMlr(#rBP<&X_4Vw#t-XAa#!j-0`7kZD26wMH^%W)-Be=(}CB&DPkGwq8`Re(H_f9`eIV$u3lN9{ovsyg~ z=r#UW zwxXb@sDLBfIKw?NaBB|4J;S}rm6@3b+&i4%C~>BxrDkPi9Z*v4!0u+96|DDin*RlT-PuV;N+dEHko!q5g9!|O)C3|iOa;G8`!+#naRv}tcM6J z?g_o)T5J^tmbk)-AZet5RpRrXpYYl5uote3as3H*DDDMjDLXtB$MR||?`~HwHuw_y z{NXOUlJO&2%;{$x4vX(lEh{bNDK70gKYGwQ8{IBdvmRE*n@!@DT+%>}(+au2h|Pr} z!>iLiJudT#UiZd+ecf693*LMUc2>*df=wFE_uk`Q{&m?kSC8I1r%9nlIAN%y#X1S+ z9d-KvUazkUIJ3*pjc`3h^J!dCmmv_GG&&RrPhvA*;P}A^C$M@eP%M}|NVWqDA5lnT znqu)3PMMgBg&ZVI(M6J?xunz!j3*>;*J8~BTz9)aT&bhp&Q*y`CN>k)Oa$wR%D>vN z+U`?7UDJO}TiHXDwT-XD1d)USrJ_q(a35yfcg&y@ls>CxI_$)oLEqRPlz zBR9PAx9d()$jq8{6r!|dsuVH0F;$AM=fdO^k2yI@rJ1swBM}hY&gw)HV*Vf!vau?j z61^Lw;CL@hJpmc&9oXNIJ^qZ)EL{I;Qfd`KLwet36%(SG_d;~KN7~(*dwQEf!jo@c z&!Yv4cn{m3I~lds_t9#U?2GlP7uqp#{kv1z45_0s)?1u{(_iif_@W&ioP3Q|$txoh5N0bdYAJh_I!t2Dj5oyKPI2ZOB&a1j365K=* z&&M4j0)QiNm_CPMByng;7TFuIdNU_?jjl1`2b!fd)9oUTwZ}x3hewtgiPd+GK7ng@ zk8!pBPU%;nCVMyAiE$BC5mWM>0v-hWjlX<$LgTx!NA>|(v@~1s+_B&9-qoblbu^pZ zCiLvxH*b@uyQIjMr}Tbw^!5I^a{7|hCyG77kjFpkw%jX>tUes5aRuwZET3jL-)M3g z`8$})kxf9r4iVx-vJS~rhqc3SuiiJ@x7)tbJ{fkrlq?dj8sD>i;MS+9XeBz~DMvbG zALR(PAvIgAa4oV*&uKW-DKap}+%E>UHgoC}Zudu|d&iGUCDN;Mw+b>eZaHO-O=$VD z1d+W*+QkA&Yma;aXj$%%C77W4%afiljV)f%wSZz}IVd80M`b)GPPU6Dh(%E0TGd@; zUdcT`If8ovs0J4C{e6HIbt2e}c%4gAC1ag&>{cnwWtU4rIYhfgH1)X-PwV4iXHf8}4UQCeW zEbU@()0VQ7y~_^8yPV3bF6wpHct0g5bh7Lgu_ku-6ocB<5@rwIT;E@iDyOokYa+JQ zvt(o<6O4WiP}cT#P^wl}5jDXZu<_%eD^7(pxHwGxy*QYJ$52RDiJ84Ep*C!odAA2L z&}ALhFL>i*JsR{_ccyRi= zllm_siFk)aCXwb9HYS0wjhP#%!d`>ji zuJ_Y8>Gmc1IFL zk?}798oaUM3v!e=vaz>ViB)xVb@Dv6-KT-D1CYqt6cIJul(1;Ei&R$+g}CM{Ej9nJ zIhq|tDa;=Zl+cKA^ltJKgTS=6zD3_~EJyy6QCE{z1T&<`I{&jMd8!MnSQ=07tyaev z(@D-zOmU^c6L;^}Xbq^?b)rCD)vY9Ak;hXfYE~gYi9X=zq#0`J>TQ^*FBeqyFGOh^ zCaPYRf0m68Rl4L7m!&pWV!g1F_|qi=?o;{h-6IsT@F_$uZprzFaMpd zd1U;y9ooB2&O6oe;CZ&aoN`=q`qGB<*=yAF%xla$FlU+0U!sYKr>zVrb$fQ|GNyw9 zjt|TpZLMNWx)V@mDwj!x5Uf(g%AvPFW|`w}QqM(b@D^{q>FD2?aRiAc zJjC*Nrqb+<98zL|@%lc!SS&CDp7(R|`Hleox9krYx6U|lB^x&Wz8!gyAC(+h2fc0z z0C824@7sJ-7=sG`yu0qOrGTP`kb=Yw3FKzOGTg$jDx$@7NwJMHT z-uMEF1jx;?i{X?z!KFcO&C@c^iJRdOp(#hPXgM9A*PW*kx`eO@wW}gr$rEf1~S)*CJ>@uazuzk z^V#o;N#|gZG$2B7GBy?JnURb{0sSUn2oxliuUeRfovVl01273Fm^u|B#s}@cy5Vuh z+2mma&dCmvsV?`+4<2kM_Fh_kNtU!HYexU34|0$LWuziw17h)(KB*84kGz^Dt?Y*o z@fPc?QH<#jyC}#;td{70JD{^oZR`yB-F`~#CRp#EV3m?6R-~*}XQK2E!>V4eSt{6^ zlhZHA(I!Oi4I)oO0i|jc4zfd2?ELT~SZL81uL39DNn1~_e(*3V699f&7idU55fcp) z<6+*O&`-d_Ybk&Ir3O>#FadtEN#kPKcoK_uD7RjrKm{(&D3H(;`%B;sR&zbIs9EL& z^D~56(1WtlrN0OcN)_M^IJrgV<5Kt~pGWOzJg_ssXvp_eh4jAlP*;c@FseL0PAkU53qlQ-OearOcUIrF0~GEFUKR{?#( z`Nd7tqYNyPtP?y)-Wv4Qs>d6z*Am>1iTMJj+Ll# z&U$Fex{Hdxtr1bXRBS>4>+?VuUJifo9D$YbBUR#|iATz=uF)!BG(Z&%zyvv~MloS> zLScJaxX!qy)Dr5+UJ8m0&~R0)9)b)2MVIz>d{^GELVQdfJ_X#^g=LYQb2dZ}-umX7 z&Oe_5YU#L#WG~q*SmR_Ov=Mqt;GNL-?)M0;){m4*Fbeq+t=d zA&%+I@o@t>T#%0P2SOw8un0bb%17JsA!Vu=C!2sOgUB;*i8p}Oe>oy^MY+f{7@2sK zT4Zab>K79QTbKgaqtw)>7{np~?We!~ra+N@qC!e7J;H!35D`w7QtVPv@NhNWq3$8| zB$Vi107dADzb;7C$G(NR)7Wekxl9w{tu*pq&gesn5CO4Tb5U}U)G7s0E)$`u7)sCm z>MY(gv~NG)!3psM;$6tb`xZBR8q?F=hODV7(3jb=5kx=HD7<4m-i$3{!n|>vdc%RHLNgKyVE0XHkZ#snlR!`@ym%#r%*;Ub_pwPkKYMef7_V?46(r1Vpg z*d>yiRJ7)OLq*^gWftBwY^AJx4g9;tdhwT?RKx+t$>4w64`|67AAiTV?w1�{yp! zV8sMGr$QP_&mrLwKPcHxP-b(FQ5B0A>NY@Hps3ZM=HCT)TYx2Xm>u5K>?C@`vjJWi zHD&Gc?v_A2Z~qX;!7B->-pf`v0up;!dlE^3)aSq?8Z{V>fv{k)r%ujCv@L*u;-5{sAr)gVl9iGK2vZ_u^3w)Itc^q$8V58=epqfz#8H6DjpR@UihxQ{b z>~28(=~3iG`+rq(^nWxSDukw`AFu&xTae4lNJ275F_sV0Srl=$^F}x5`{lswhKu8f z7oFZ>kJrK${XG|+0HW}!CajuQwJ?9ql|*|Cqg~`Lif6hvbOoa3_*LXDrb-DpjNu@^ z16F&h3XyRX0YEg*#02mRb&4uLt&@@mqNShmVH1X}-768r%dqy>7W)d98?8B7yHHo= zS-~#)OGM5gm8kAL^xrz@f63aSU|1mS8lltYkczfdJGfEQ7n2J7A5*#vtSIxUOY%(>dEIK?Wm11F}(=eZK}3zl&xac-lE{ z{d_pU1h9N{0O9MS0&~fbTRVGjxi+kdUFB=hG&{3)17qn(6Ri@Pb7Pax#4@N4AL6}e|C@`ZaP|`~UQTRCH?mDN8tR-e^#L2>!G@_w z?M39r9GIV$U!!mG@pLmf+4~AY=|T-O8n4RumJ-DVcmmE`oo8RfG+ zZk>bG`Xx}cX_ z*0CVIH$!Nb?B%gKRQwW1en;NGUP2B{XJMwZU|%|63r4cV+5ray%bUYN)rK$)=1}E_cEt*jQDg zS7n;=fR>}+dX+fNvBu`SECsPu3tdV+uAX+-whR_Wf^|tx*`kJu-bzZTtsL-2;O@jF zNh@}34c&OL@h{)7OtsW}1MCu!vl0P~NC`O`FU#sc_sfRd_zp$PKX>BZwo#GN)tyQT z%f=2NZ)o9Mr`-43_^?`mJDbuj0XP%Ou2VHqZQCsr!&^SJhn!Q9C$pW?Qggq)fE{PU zQk=aWZvq)(eln%*RUOPmI@^C%0w&)*8K@=OdmA~mKOGx`VXyiMJPhj zR_eB-rWavWuQxoZTr)PQR|}^F8xW=eb1X{MnwfaV=eAa7$Pw?5q5DSqP(0-fICKcF z7ApM%6GY`Zo5iLzE7c`!oOg-?fw-Fi7>6+Jy9Vw^UdR9qY$D`ggxs(%?3- zMnk0e&Ii~b?N6X*TH*gJoynv?yG<~Sw2}_G?)FFw5|6)Y4~{_%G5<)Yf0HWx$3;bo z2-(yg;r|8T0%w+O8?8_Y0$W+^uMQEbT^@u2#FW^u_1@?BWVkYV1JUX)j z4|z45wY`#+^#UeGf=KkpKUeD$mRdkr38_+(+miqTqLxJ}c#9^*9Fttai#5n8gUBe) z|9v~{B9=zN9jB}d=37hc4v->b3{J@Q1Wc!h2#5?Z5e5> zWR=_(BS&8tzj}5v=46-r+f0}}dn}6H>-d%?+{beb#ngDtA7El>sRoWHOd=ZqCq`5~ zag_vf^7e&=I@0OYK-sAJ|2n>hd}-JnJxd-MwoT2s+nMM|(joZ{>tFQISIaR7x&0;d z$Bj-Sr%cFPu5mUTx|J$%=6}LN{AYU**@D7=?~i0kIklmbz8LFK>agVuSV;{gp0Wqn zfK_2p$d&#e`yybAS;`8L#B$2#ns!*3q8eb2Ah39w@Cg3Yql@x+ysormHn-VZIO#-P zo6kRaRed55-XS#QS~prIxP#a-4>agtqr_ z7g>9p|Hr`Lm`4{JTl_x--$;3J&rdwo`K+>c&PUez>j!n(o~Y#rkM=)WoH8v7B2|%Q3IK z&{Opg#(2^t<#-VoV5Yu9H!6U->%`O)t1i9aY_~qOOue z^+pXQiS|hItwH-+)u=D*>z;5IQF+r`$kYx7&X^P+B-!*m{ z#E;cuD4iCP2%HO2@WcXq$K<6mAG#9Vk;0M&HY%;{MbSIsVT-z{eEt=$6fmF*hq_@+(1=iWiZ|gWCCMq=-U!GSKuX z2l&=B^H)6Sp6;ctiE1xfxMa`f>>&HLP(m%UdDnzQATOEVcIe3WR(piXx9=;_?S>ys zC&bP?MSVU*wT9Rv2D8c{$qe`u@-M8YkOR+veXk-`zMhs(V$F=vYIqS=HN(qq9lEwlYZS7pB6tD~VsgmojsIlvAVa5+#{4_(zYLbK1c!m3zbrus$LI`M zd|BRiU1!_h?fYfrBV-NisW7l6K+z;s%Vr=1e0PZ?Vkp>((DFW;VG{|{80=G3FbPw` za%6;lC2FNlS^GSX0UM1#CZZ(3N*V`T2N+ae+C(>+O;>(S5-%f7T9Gv5PMWCuyIWGe zR zhPzD8;N8sOPomDF+)*MOm%`ImBH5H%>lh7cj0q6fucEj@o|~LRvMqL_8bhzsB7U4? zB=40<4`;wk-PMtCq=|`nlGX-OwJeI(t?(?h*rsViJ%wHHE?Sh~vN6q27oF%!*!AS0ux@BN1 zESu9E%k*jbj4tQAcqgNS1s`iPE;gzpM-oYJ9F3x6+zLDqe%k|lMWDP<%1xCzVV^OX zT4xF&s)BVv@G`umfpGB%wSXMIueuUB%GESG_D0I@8Pl6JuE{wQt8ih}SKIUHjI)z? zROw@r+pLkFWWagj8FiAQ+G7(h(YNd6^paGKQgVSef@~a|S_s6FnL6rMFV`QlPk(k4BpQ&(P zF+Vi+!QZeSwwO+%yQNg@a)MnSgTO-S;4R15hZ!K@J3!C9eKCW6(Fe+KhC|U?Yvmz5h~nT6|D1PTlkFJx z#8-ipg{M1YqSYD4UR%TE;2WMN$c)lK$^B|dB;*mZoGe+_$42DKpk@X=M8_4VAKyD@ zIq!HdOz(|Gj&(rRdY4(JmO9yRN8LS|ck|Gih?8?7v<2Nyg7ro@8T&1#D=mkDH?Ica zVirYS+U_2Pl>(5r&=T`pm{)YYRk0~DL<&@50+x!pX+yoh{W$ti9AQiB_^B0pHINPcLPqI=-FYTJXH z;YAi1ZDBh+TH+-TO6#jzsURqzT0qFJ7L|Z9Tg5&M!mQB#2qnu!J&FaiIp-`Y3Lwf8 zH5Sc>?e7%oU<*WPb<6}h6fS9ROn^}Ud%&AeJe>qU0e8!(@tQs^&=S&>o>}a9Ls^UX z@?$2@0JWk%)MQq_s@)tztW`W&OisW>qg?a5EiV&RNh9rd6W1#5@eqk+ozLskZk7)Z zrx^}x0Q!~rt_K?GD6*tbGL#R(#*ZS52{J0Z3LygQ1!#an`Dqs@6;QNksX8}=bv7iO z2P#KzHudwHsG^5XuFQ5eks|syniI~Syyc`9fl54*@(dywSn#f?xzA8)e_f%#@Uq(A zsf$E_@z)$9d9{1EQXrO9Jj^cECD@_(aAN@gHV9BwFF1_VFmnMDnXM9+^!|1QL+Nz0 zUjzql^xJruat6SEOpleyvSC=4=u`^;P2&hKR1|1jdJxoG;5b+Uz*Zy$8eEPSHD^^_ z=8I+B5%b}Cs97;tAr1Y{XJ2p0YOgZXUGjHoE?{i(FFmXjI@qNb#ZTo(-DT;?)5WHqQvuaIZ?L)xOhQTE~|F8wge;Uno;dsyI+SkE-;|5q<>Z@xB%?=MY+V; zPE>_+hbIxioTY17bJkQn=D_Xrb?))3FvQ}om z%oimBBAXbAg8IDDrtRQ@I2~Ej9h-hYb9Zh-U|%UXlf$xyDs3VCpQ?qL4#gJC79mc9*frA@}Seue@Y_~WBU2D{}r z9cnCVN?_B&sPsRb{XvlGZDK)Hw7W@az0FX*!+$awKYL3`&mR=56kHlS+W~e($?%0> zA;6$9rF52=Z%hY5QQ%7n`I4-a{jccfQsTfaY$NT8Xqp>42!%l!)ms-~o6B3dZvNY= zNENWKA)Z~yH3ikwKIV+`#3Q}el7E}IB@bL(}!Jrrqe+8g|(k^g^3&e4B z5%hxWpT#L`h16A;YA-+?W2!}Ql4pVRdh2FZN^{e|7nq=jHsAoOURVzAup!9MLX-rC z&e@=Yg|Aqq-u^dlfCQkH$N_o#C}|B!F6tgB3%D(IzGiVV z&F!VH?8_R<*B@7>!zxCW7(4YBO~uRy;8j}7z#Z?P9TlnhK`DGwzH%x^w-hAwy_nS^ z_86cR4es1b4F_YaZ!D*bw^e%p2ox0OU1~{>FH#!JzX2>)^6&^_BdhDKpj zJnC}%q6k-UGpB2Gd2)L7un>%Y1cFxiflH0UQ}rqXFn<>eq+sNF7QYlbBz;jMmfjOy^Z_>dH0|%dS<4Zw(QPB8o5d{xN3B4;En{cON&hYEQp$H?;+o2x7$V#o{vCk~73|Ux^CaQbi4m*o4Z~|A@;FfK>Zr2$;jrc!Gw~LE`);cn;`x zgX5%y&)D7hFc8qfW!9eqO(MWN`GxjGh)X;q5Tkj9Un2cN#CvT@Zb0_c^Oemqyv=8^ zjo`CX{M)v&f@I2DY>U@0`NQqO~9fWfM3NBy5yk1$+KT0k7LVtN1k{$X zYi?nm`C6NB(y!Qn_5Awr(0D=A$x@gv>GNw%hs`@$fawagKs9A{oXi6qWdB9UN|4b` z1>W_^EUUjw9c;A9R{|a&oK;IIYrb(SPRjzMg^@?nivFfnoFr9pIUrs37p{xhfzqoc zA|SjdNE*)|1s3_-6G@V&$cX=BeH`MPT9i$y$aC2^F(`71RWisgiKK&1W=|xG@ezQ$SF=_ zLCCb!cDeWMFW>tbykE&mK`f*q-+sNuE6F63WCoU`GewM@#1bqRx1qSTO8ja51*Z3q~6xA;0=#84FE8d#KsFY%cw$+Jl5nt?tEPjRND zh+f?po+(Kuol8$0%Ow7jL#jv%i0B9?$s~$&mBP$d?WrzB;C|74C8#f{lr+@TFM463 zVNq^6kxDDre<@`7{V&Q+z3Kt9W*8k5QS-Uy)W6>?EBiW|6R%a?z{MN)N(}{blY!uA z!h!P|T!TSp-PPy0dIjUQ;(2svz^I_Y_LJ|_&Y4n?>1jbIPmr=&oT^pPcC=(cK4&^a zq*MN6x>iodK@o{pA_=2SbGnbeqe8QmvCi$aEeuU;6-+wm%>CL$U*c)f116qgq1&J3PAPUa9l%Y~nN zjVQ8;%E@pk$sme6J|LcF@!v14oF#MdGpv$KiU?WjB%mJl6Hsc}^{ij&aZeT3o9$9Y zRZDE&@AW$7P=*ucNBgKro3z&_^^v_6$r9z|QK?mZXLJIFli%%W%(0B(miiOEYR

z#W*dtzn-blJbcPzZODGwTgjotM8#^`Ri@Xy$*E}%eW_k6{GQ9Z-|Awk1h2uYPw$~~ z@&xZ@7nN%#%CXvkw-XtgTOZH_i=Gz+eP@pzK79-JW!Ty0rBy2bNkdZT{NSt1cW)lF zTs)@yCdcUeC+nw=0&X4~y&Z8UwyL?$?3kEx=yEZ-&y*c|(YsUA16Q8nR5Ls?_-N#$ z&c99NGPP)j$`s0{eg%TdvBg?7*^gtH$t7XeFrrAUnn(j(a+DzLh2>js$QzfWG!?8Y4f%0{mcfrxhf27G$+k@pVVj!O1!o0b|}IbEot*H^(AXfiR>%sUG(&2 zVAQ}r_09k75*-6ho;cwbOsR*$FqEByslRB2Dg?Q&4dz8Mn-88&%9*oK_OR8~uSkn3 z!zY1Oe-yLcS=BudasdsSu2miE{+%zbJJ4V2VYW;Hi)bf0s5piNwnj{0kFhqKaPg!2 zS(IZ?u9H~*;N8V31s~~2Sbax*zMFPW;PQgoKY{k;+PxHq?)t942O6Ur<<bW69m|VU6HfJclz{i4yaN=;AL8lyN&e1rWTW>US$((=QOIow^3LVH9jEsCHOTmv z$`Vg`tdb@Wm{7F^%WalgQ};U}cDZaP({0WCRpBLR+CO7pNwWb|L?PNGFam<|rHs9j zkEU~>*l2dzI(8I$9(MIIR(lqA+~Pl{+qDRZdl#yV0ZN7xBC8W zJA-Elmys`IY}eRm$@dyHlQK`&h>rtLnzoz!rrcgDkpJ>qyfIkfFw{Tj=sqHGO8%PJ zOXJ{Jx{71lsUTBbbVy*eJ<{Siz3Py1Uhc-U+C;R3#jE76ScBFPyQ+jGhdMFE7}laA z255ySmW`;tUxX!}^M>K#ThnY@*!>aT>Tg_6lXCjo_IP{SK}4H zt8IhY%?o8P{4K>B2Xx)JVu6F@VZ7)~}VarQKTDTXRZ=cN}EvX^?NE2-3C+ zQ?83PXyC#SH>)4VjN@U(fDl&T6r>v%O3&myIqx{F3+E2T7+Ij z_o3v{U24kXdt;qN%L;xKLvNVpK0Fg^^Ln&!>6T()S(Wt+gVH>BMUzke>-W0E$^Db~ z+X>qdiS5fWUHqb;sv@sEvGBaE!NH<36@*1CTecqnH9+(h$*zEq1E{K;?0&^dY7GYi z8CCKTY6?qqC!LpU*um^}ctfREz)C(e#BxwP*&Bv9$x8)psKW6PL{%gTiXtN{ZUI>MHfpzQ3n>OMsS}B*YI;73myS19<_i<0gy$p_Bd|uLC;N%j zgwB(<4k}@09P;xk*RFhY*B}7SB;D;&Mfc%RVtGlRdv7u*Mc?6Kzu&EK5t^%pg1#D& z*AbyJsobC`O06dbgre6HPLd77clIxAG8fJ@S@Nh%}G)R=&XX zpVo~vd`ueK?2B-->c%bQ`n3#eOD1~k-?@-$FK8(Zz;z=3)NVV8MniJ{xuPB#T>O!7ov-&LBwD_ z8*N@3G`sBy>}ZGS666oPIEUb>*<(%CWheJi4PX@y6TK^*HE&iU%so=pR{0a*vJ2VM zJ`=lB^cJ({oHs%9wZ&m+gBZC#(5Xf9Y*JnRZnDmZ z`9Fvu8eYG~r6t(>)n4|r{bq_4VrNrZ(wy6$l2UcD#T4yTw%Yp0?g>Q<^QH5^TB^bF zGm5&J-|@>g!jz5HQ_Z}MbNi{O>nAdae`nv*hrg+L9SG8T>fiwsarIou>!>_<-DX4d zlTvT+&$ZESPKw{8i9)b+?6c#;%?_3~R*7uKchzGR+Qp zy7Vo(jblfw>zmU)F^VMVhoc&r9HN}Qn(;y}_$b*q4%Lh+{mU=0?odJbGF5{#86Mwu zkYbv4UmI_vJsMZI@=xXuhdaGD*1hZ!7c_YT+h^XA_b2V0_ncHbc239#yf?Na(xC`1 zz8m_+I47Z^Jpu*>4;|mWW@KY=@_1u@T-j&Rt6d^XCQN|+jOe|ul#M|2Xha@ycMlx` zs>flT;pUjf`bE5dg5Kt|U-Z<52>+%XE$i3_gq+qw@v^G^KU=e-wyZyB|5Oo95Go~xglu#)~TNw_sPpJr>cWeZcu9vS6rjv6uVk zlN&ZW>?#Ymyj8q6Q(R82v*Y3G=U_t7cRvT{$X|b)Tve{(>_c8gG2}{3H+#sHtoY&H8srVD&*)s z*&S|VdE^fCXv!krbO@*&z5JLNmW(NJ6;y609^**eBwX3;a0<|yBJ^U13$bFGx@LfmXb#b=Fu0aW%11^4V|<4hu|8qU>%gJ z$$x7KW9Q`zAslTfF0x@bInrf}D_QhP*DQL}MCJE@`0eLaiqImNLD`%YDW8u%)*7>6 zB*#FD$}qntIWbU`Tjx|&!UXI!@UKd?yXP0aVjEGy?nL9f(vycnPxSrR?$G@@{a*;& zs>JKn`2tzVf-=lgCFGSZuE=f1u}{7b31sAhVplyGLMu?7RFFCbUTqjBL`#lu2TCkW zRZ|M#)u2_sO#-FR-L%U7-gcwVK=G`~L7Dpk097`GIvN!@f$Fobw>h}h2LF`(E1Th> zQ~6q5x&Vp9v7tMb6t(sud6QMW2EJZGqr`@2X?Np?pcY~nZI=!dULa5&8w^|!uVp+r z&wZ}aSo(O1$MIe1=CZYAGP@bBnG8ZGxXuBrkiBM4KVR*=n1r4T7Hd6LzkKXb@nGq= zT`efo>1~5esB~}eAD8GXntI58ljvl|!S`_QZ%E&r3J#|H&i>r=#7O9C`u%O>3y>0q z_JF6XgHn>434PXcF_w&} zlZt$dO9c{WVB3C&!=d8o7LTu1Lh3nAg#H+R(<8V~x{mU6V5$aRDD#8AQHj`NIxI#Sf8B{# z=<@Alr=Np19ds2BxvTwnjFBJE5p#2{MCM|N;gTum2zo~w_2Pc>SMCY+hdV+o`cPZ9?5}`CSf0*YB$tW zdLZ^bN#%vDQ5>`t_1}(9qFpw!?mqgH{4|Sy`M%zL-;bM&P^ga!@YGz1@EBx%asqbB z`g*nkgbYrH5Hv(oe$MfxD_O0Y%NJ8f3dTpK^lfAMVm_tT`>B zACu5^hS%9%vUQ&_8A5sk*Mw=u?^(BtcPQFxY|T?j+H-M4I6S%nOA4>k_%VR!@Ok_B ziyMjIaN)?#C2^bkNs9VV@9eiL)lkv{-07hEe}al6ZCWnW$9=Npk=Ird53O8yQU0u& zi_K*$$a>`cO#JW*J@^^hyt`(h8kn!K>g93O@UCXbf65B}?7dd5*7L!#Tildy^|(of zSHlZiS^<3ibtOaU+N!_i%hWZ9EAFG-8Yc8GRp=9u>y*>~UxzMwa#& zedUHp<;ETgF&vOHHfM#3&JMIDM2Q`R+Ft$O>Pv)v_zHV;e&7-m=TWjtNpXLX?5^Ym zlx>ypz&_7k8<@0C9cGHQ`RMa!pUEBLIsL$SNEAS-Tz3~X`z6NH^`;5vEdrqPh!5v- zSh~*Rj$>mWG)~Q>V^voYUE1%BJ?+0Xp!(6_kuS{7(OFr;5g!?Vhl_Cu*+|wM=K22B)>+5#ihTkvXdY4x8`F^ub1a`a11_t6IU|Lrb^8|E9-_4xbXns)2C2CbpfG^;eJk~mgUsC> zQ)Zk@+!zz2XZ0S*PHumxIO{ueU07uP^fLG_7vIehXyJo!B>4rvHYCQ(=&!7hbNk_a zgIJjtIVa2R)?0$l6L0wn&{ZiUnHnblN?_8}<`>ou;QE~rqLd5~sFS2q_m}ZotG!0V zYcWTbgUgIl>+o^QQ{PjpqrLhYBnB6c|NY@bpvlF^EniOADUI2Wwp?DsyzVc!FQ7i+ zy=mSvCO4IAT+*0N)?B=$KOW!s=mF*CnGBWVc#k};=LO})-}N7VF%zK38%p2z5JtO> z-?3f!ru_{41lFf-FR3?ZCA%i>LvQ?^m6HNYmx$e%mBxQIS^}zv|MQQ*B_Auen3Vr> z?}Q+|=Dv*2w<9c@fwVY_Q;&~?>WXz>uF3VcmELqM`xnj~4MIL<(%LdjpSkVFN&HT{ ztL5`#DE5^0UoS^<-=LnteHNh}$^T(X{~H1YU)~#QQVYj_0s2TT`mPa{^%>(@__N81 z7hlaQDAZ5RT^c`k`asHu^`?tSGD}sH-Os%F+gX9xtZ($Rr&1kwH`^5TQxB%!`&Y`i zOR#U&`U$&0+Z%bIn8=2r0d~{*clEFJa;|&yF^ay9{!7t+hl(`Z{_OE(Q~^_=S%(WO zFhO0pbw5flvvOXxF7JOSpCeX}&%?f$KGZ7ghky39tU<1=zDZWM$b9p=(}`U3%K_Qd z9F}KzXXl8|$Ft05HGdu*@JZ!5y}3{4p9}n163CqX0J9PRIvh3>7ftc{clR5ueoM#^ z&Gul84nSR>-)V6_PMX9jz=Bs9Sd5Wln3?GGq3qS&-hRp@te`%`GsMc^#ZvuN>Sy2p z&l7&-Pf&jdGL!7Ew(_FB_434#IP`PQ36mnG1~lB?qGzg#7-@4}NPt)S7Yz1&f18@y z|LTP6TD{UN`7tW;bu08CRBk3balMmNh-a zFcF=0a|g@+JZX@2TmU%b*_lH|+-NrkUZNY8rf-4*;3d@fEk_pVto&NiGS>H<(e%}cgxn08jc24&B z{52(2qW8NI_>(P)wj@yU?vQ^X{8f)k9Yt;!-UBidv^o%ijl7v_ zGD+g4szenddl|{1SAft&51cVn6X*kQP5kBvniK8v@{7jt7*elO)R?m0wmN>MQUgo5HvIeL=9E2AYFwJA9sT4$S=Y>{r>UUx^ZDRWehmmgQw4 z#gNmlX`?^WB_N<9a?hoIVlpfz+yvf?B}^`y?-lU4rLs~!nWoHCJ@S}+d05y~>I0t| z_n&mp@5km1msb#bb)3KqP_v_M236<&SxH_-ZSbL6Ms2f`+(U18i{6Qnm(UW@BWn3qP4o)g`z<~trE8Ovm zkay~Cx36;@h@Q{*bo-&yE11-+i9@jX$E?W4Kb`k8np*BN`^G{2^3StWW`xi3cGPU% z$m|#tbIi~{)-Gs5p5i%#=ZAC%B4aBfDys+9^xRCtGj7vm65T!Qp?!`TRu$0=7Zh>G zr>&1nV&h0UuUNr%F|$#RUyc-)e3{G2F{**frH$db*P|A~gM4nVM*sUn0RZIwK;T&b z06_il1~7o9+5r%Fz{mGXSolC#ct=w5KuYTC@#8y+ ziU(NiFEzCTb@gw$x*I1?ZtLnE=<4nm8y^@OZVS z8?LS&{QNe2eSf;T9=Nz{`}!XE`o2AX{#|_hyQ^2%0s}WfLRKRqzeYv<3<^333i=rp zb#V6VYC^)-goM?rS2wO)`57O75Fh{Z%9VpFS5i_^va+%Y3JS{0%d4xa8yg$j+S(pI zeE5b!d6%92EedY z<=X`X2Ze<{%gPSQ%Es#I-qqGlG&HFC&^ZEJd z>FKxA(^HF!Zxi)(8WpFS;q`7*P!^Y+J&xBvaOy1M#xZEfYtmyL~$pKEIe zYirvZ8wVR3t3Q5x+1_5;+uQi}Z+m+_(ErI<^wya$CuuN?(zkv&-P=l7|(Z>1l=CWI%z#W(2|eMDZ|7T z4uD(2m?j&Vw|Zh-FgfMK_^Sy?wRJO+C(K57**`xnNSU8+H#hnfl~v*TFs))s@54KB z!&UzrC#_Zcr!su6ciES=NaGR0!4Y|M%#CX54f-PiCw^+3$2yw59Ylkn_~r{~;wsWTSujxxTY(u)0rO5oFD>oZpkxvd=vSeW|7E>JTOR8dVo z`q`@He;WD`x3eO<*KcJeKSL;&VGm&d`?pFzH#D|fURe*iAy69LRDS()Lp3euCJvi7 zmhrji$*ofL>JoaR3WsCQ+jx)5Yk1oczddFyRk@D$23Br6QlxUxVzq#^`Rcpf47L>M z;rF`_&tZPdZw>qB4xByxkb&)^0s&Ry-yVMxls=D%?`+ZNflR6$?}watb5Dl%72g&Y z)_;=ILw$3S=ixR%T;DUV`nZ4dU9IRE4;R*nNAlaWU+*N2Ox`!%{-pJI z=j}v#$FFmu-7ys4btDl1byo{MX|a4o<3mBF`0pO`P8-=k_UVcVfdQmOIKeE2lJfk& zdvbsJU+qdy81tDh<;I0so-;g^3SP;e!_!F~b2{^%9WlPLjBKtNE+h;?T$7Z}SU=}s zWbSzvF|R-p)-FPdTS8LzQ3GX`sH0M?x;D6R>j})k=WfSku6Bfy}PAs8C_$$7gd9hq5w|LVXUcz_{2(< z^hu}gLthx8if8;Ik*;cabF@%tWdJ?}0j0nibFx7<&-@2jNmebN$`b&p!5)kl*LhFY zgA7+(;%kT*>VcSY7KLQ8)vG2LjDXAdJKX%N-=eXW^X#YOmGbVHl07H+LIZ*%tk30Q zMs=x^E7tAdYg~KevwQuzXUz&#g&w=-b5gHa;k5!0a6nWH?ByM0%cW^56WCfgwjUYt zH3id3aA;HRX!17qDd;DxT?S+-D2rGl&Bu;ZLiN~guM$|(OBXTuW6dGQMi$;i77EJ% z(8ujAy`e5KF$7ULk(&?m?DwMWF2&pZ;U*rg+jY&TWr(CNdHUg7)ZGCY`0s=gl~*;W zHiVULY~{&?%x-bz&7xs>{pA)2oE*WTU}B@5DYG|_t()~rN`N%5`G{s zLXd`Zl%@-O{=!gs^PpIxGbRbBPS7SzI`fQG%2_*tgxh}JPktm5ekv=!)EkQ|lmlBK zv{NtTFhKb-cS(0T)AwKI%e!%aa_Y+furvj!$vrBk570cZ!UY~?gY7HFaA?hfldb!D z@C%H+e765uv+K)xIcg&;otGwX{TD>SfD)EXYR9CN5cY22J5@8SAY6bq7>l}M zfCF;Rc|rMDI#rNg!~{bWLvFGQYiVB~4ig$&8!84V{ZetX8Jl;A2JoXT>2kANgbkMa z{5o8RJ4K#{3><+uiY0)gxiEA7I7CqzKyGFoVM@|(uFi=!3rzU@_SuAd|IUw#*-~d6 zjA!D0W_H9ruzua16s9+303k|wrQ&I}V zWqy5Tdm?&KY($BImoyBQ6D-@bnIdc;mqO1M+8iYz_Br!`%2z-<)GT}+E#?Od&zk}%T)O0{01s2BiB5iDxFWS&AP9-82fhFT z@SHc{$DO??U6Qc9TW4E&w7>H%bO`&wlb$0$#$ZRx1Z+%2v1vD~Lamh-zL+E#AI=bj z@bNUo1G(Doc_MPU<43ggrlcm)WOo5@!%d=~_se7Fnf+UUr#y2@al`- zn>WNaS7rZKsd9ab&uZ2`PBVSvOd6m7i1U<3`lJhGbIC}UHFDF+%>u~-bx3VTNzZEtsN^l{&Ma7(%4GGjb?U51;EI~$U4$AI|qk?{F zoueQ;oi$9xq@*udR%o7jtpuZrdAKN9+;TD8X)%&;LWBXV;U5u^T=RanQyPwr#mG1h zPaEtkP!5s^l7kr&5!b^U8&doLDd19OboYh->2(Sj$M}m@2W#MY3eDoreE8X~lS`_ro1@8TkC1hQzN4cZ*YfI8uipi(HfSr2;I5+UaST7ZJtZjAidz{ScV;w^f?85dj&e+rQUkHN zzI<*TZ!JKHNyIU^QLzoN$_u^3jh-eSc*)c$08&Cp~jBHE%V!;QJ8 z@3C!xv_YP}bNB)!q{6oOlTbiC76QMJWg_7^O-$>J%lb1L=)RNh-9;_-JY~ROG{5Iz zLc#ta;8`7y3OzrohC&gcJVc8dRTGF9=27{jBF2rA0t9?<$DsfLC)bby^;rY=0cm51 z^T@cOaHf}A+Uwyg&^V;Jopwx$O7!y#;3Kh{xA$_``l1JtX zK!}kOXsz&6JaECy<_6j|J;E0YIg#oNs}b>dpN1@Vj5vp7FgT?N4Mmxq$)NplVD7MG zT|@Deumb)a`wDu+P6|`#BJhS#g~k#OV;ykW%0Q4&#(*|bjN=}(5& zKGkdj$)JxQ1(wMlEokI#vwo}0$KbQ7X<+eCo7%PDqv=My>vj8{oxlPnykC^yV^mz! zS+C+*Z`fY{&I{^pk&Wi9Uote7+LY`M3A6(M4L0@p@Rxo>kfT&llm?^*0Gx@`y9x7G z9P-0XTAdD&gPA~C5Un_HHEiW~ z*!AKf{t#eDO|YxyVdHZ?44Hd{>*b@9E0>zgZZ}n8nxi14IV2C8;#68b+q53GV9hjp z??`$Ob0qK9Zp*Fr-AK(0WN9d%c@QDZ4V<;uk24?_DRN_E>+V`(;`)RgjJC7n!oX1j zWihOV-qzA8&t$fQPslLO?~Zzx&!AK+Lq4PFjCX1Y00GEkcuoVQC}1}LkTHO~-*8JI zv+;TeA_d|_bp$$&l-*UzjZrM$k&G)04b1k6rVf=2(Y?=fd)sp=G75`b{>GzhaM!~0 z4q^8JpeB6A%PQUF)1 zlCx~P<7Xm4fUSaC3Ql|*9%^f2=NNt~r2 z@8}}DEW_0@W9rN#T}|{Z^(H^8ZfK(=H;s{SXS(ZOcUO3bB#h-1zfxla{pp#xY$3M5 ztq}vtxq_gnPkf=kJAX|b|2QswdDI2WsRV%QX_h}%BR4zUg2!C67SgQ^sEa$^;9i>6 z3nLfJG@BWOIM?R20XIc0)o_4IS)kHd>p@m6l^jT6YR|!QIXw~5I=yT(s7fn6)9-(@}^&hwy zuz-)Kf&C1Ig%@b2qubOFHtS@uAnGq?8>dL|HukCiJqWc)yTp{NFDBvMNen-@IuJ!G zxE^x`q*C)PDNFnrLX;a>$$Ij&&^+GblmZ1D$mL1d9;unBDJqwWTSq4IX!>p-^c>6o zB}FT8&$|`+f+PcuZ1Vh*RPS8RNmv*VeSWV(^GQ!#CoS;RaA(B?5oQQU>$ku~AULBL z1$%oB6(l>Sm4N=iT?+_jn6Gpo6S3?Y_|$q=nxro+i%tbIdUI- z9WeLttR$Xoxbn!`1(HU*9+fhgJa6@!zTa8NLa5`tVnot@zdV1+jk)-qbvy>*5_1b9 z-|BvBg*U+5z_9~V4e_uqh&tyuX!SU2+V3iJG$4`jCpFG3awzV_SRk`~QD;goVxX!d z*HWFC;csn+wG)4~1b>)nW6R7(0+nWf?afbY?H=?xUqqY*+HHFFT8xnQZyc$61a^W3 zeMDp3yb^J}>{&5@qR8*LdgI^w_R_r(kN&nT#Gpr499KPY)!Glv(Sp zu=%PEHeXu-jcz%Mubd{rzPAS=I{Y+#1!JZ!im)URS1Nh-Vd$S%$nsqCub`B+ zg{$9O4mBG_?*f0PmitZgg39!kv%WCq%~p80x* z^s}F*A_mcD=jJ{g_NAP29ro1yiilBC1=OYoamA)QsZ@NQ7o5(Q=ILFT+s!FFWk3_; zxNQRcb(d!%XKQF%$?nBpHNvGf-&T@=uKn*`Axr}Q_fqkswF~Qz(>Jc~2=o~&b2R)X zr|ZifRst{^DNr^QQL^~aUN?ZZ7un@k9}i~nF)A(T66*~ROM;ZaAuDk}__jcrdaIm4 zpRi(Xxlv4<%2=wTgMMRTUu-TKq5%==TQ0q@!Ml_piV>}X z#aYS(u_ga<+=NTfE$q|t&sJjs7r?imuVu>599-Z3@4qka>k2?`aAaYJI2>2-MB-*I z&#>!irU0LMBK<+Wwl`LQH#~4S6{W5K*1fCV8NpKWmmE&3>a1ZMc}oK|HYkx30@{Vb zor7o=_VUBH4esUP)UD7TwBe7ae0G=O-O{^CS+s#qjjW-@3@r8XBr#v`Xt!N0YI@kd zkIGNQV;soqFAD6GxbP;hATA(7RsH9_4eH^3zm9{+@2OYmGU%ygJXkT-JpJf=Vla=x zXB5Eca6ZMHP;{vr_WU^GWd$ET&;DX3eXr-A<3KBF@ciPi($C9?EoM1!`Z zLYtN{E8>n&;si~Q*U>s$&fzaJy9Z$_rEn5moY+(#;261*TBOddQ~Ge%IjCCCwX_vc zdFzczmpvI?JG^C}NyFOc&vEnZnG@m0-!40U%I7!GepRCd^9ET;kzL_xLPcW$IfoMV z%L3?p4TT>)fxnCaUyxnb+6#u6CNA?7tfiM;+BZWvyg~jod&2obM)1xDvuQ#<5~Jir z9LfNnD|`BQLG4zJHNx%04SbWLyRWQz7EUD^qwSjfKQ(d9z{cCDo+|^W+C4|c*Wy;@ zxF7`2 zSWSoaG(fh^1kYSQVJtZ_mPY+#CjVC(D(}>w9UIXH_AL}@PRiv+(gPfNewkqfvHC%H zI$E8q$2$-MUX?>wx3-E(Zw6z;Fhph3n1Veo6$2l`9A$kxL+4k38~|b+R_X#O%;F*o zH8UJ2@`b8!#sB?Dsfvifpv-N@4Z>@O@%l)8z8JV&&@)?Qjb0u&{+L=62BO$FCI&8y zIexJ_0B2!nJuDr4Ja{P>6^pO#ELjHDZVd>H-xt{mp$XVwhf#>Pp5Fw4P`=_qx%Ti|Z@;x;De0q5^ zVM4;*mW&L`hnK(zMa{Nm(fXtUbYq`94{?5T7pfh;0wKKw=Q z6MuPpA|b6xSA~jQh8#^l%!1sdVp~L>86Hb6=aU<>o(DeT(G?=;nPM~57!9=h`J(J> zyh&jqAbr@mZmCeda=aQOsAU9e{~T2)0Yo%#AHjf5D}U;_UTV&xuCZ}4DnP$ zN$Vj^BIpwYMR+YLSbrWP(`jYS40@GE$xG0WAts(v=#tfA3h+hbxSZ)rtHMp^5TYky zDD&LKtG`nIy`f0xY7L_+ETaPggyL%YWbS<IkcYl-j~qP*=m1XD*qt@XfgbFtLRzDt9u z1Lq*xosi6VA{?GLaYW3s53Wug?;_UljHbqB?Z|uVKlU6#Y0TnLBW+YIrmcjBzNrZc%l6F3jx38VDV%q8d1oadFzw##)Ke9T#yYOH?3e{Tq}= z5KX=ISUlLihw@BfndYzP2ThIZGmqHD#lrpB;P zc90sdC}Kz5P^MpS?5S;n*SDJKm%ftwA5)K%)9P=>m*-h#Q9+^-!y+Q3HV*UTE6X1Q zGHRS_T1%^sIuZD6gspDk1*4Jhm#o4A_|+NcfeQDsO8>UT-om5yDs z9Hk0fF3(z6%n1f7mJ*`%oq#)zam9AC^VZU1V(>8)4VLevvE}*oo?U8z{4+QqmQ#dJ z=tC)>d%O6wO9`Q_XG1}W%C4;Yvn(1-EkeHFL7YW-f@NjJFv0D|jmd!ACAp%>RX7|- zmSV~ogh}>0-N3r$c!XFVW=9>YFN~V$20wZk9AcxqVj*5PD9PL;HzjIug=5^ zKh&{=(e&2Eq=57G>SGY2*nJSp_1wU>?PkB6zEoj_b=>W0u}Hm=Bd|yXt+?TB(UvNP zGA0Th8{SH%pQj-6PX?`ot~>#p&{WniERdvmUpl2u{1)UM`Tj>(=kL28!8biYCy!^R zj4~}SGWt#zadXpRw8XmUe~uTF?}@W6z1^>TEk~I}np=002jk3eVw){LIKbzdYTsL^ z&+=q_Qh?jnzMO=WU$Y}>`k`xDa{N>AhBbrS=9!t zY3I2PFm(ai$ZEfu~w2N3@TeBA0kNBP4qs z#)BFk>G0OYn1$K)n(i{#{XlJi=E=yDr2q$b6wet~l zza0z5TZ&|6wl^N>q4#;Y4x2RebtRfqDm?0B(NN@0>X_W*zrLb%3W}3!`vvfCI3ojB zcW0e;k}Y%N4&3yPdKU6wu?-f@q@xT#Hxy`#oA~S{u!$=06np?02Q=MGd8SF!$23Fd zt@e!?!Cx%fR0TpGc0?D#8<9%k|DLD}3*H0q9dD)HLZ&73!2qEswU- zUgK|hetCS%P(cgFZA=ubmeiC!l-{cApvho89QVestv1{AEQ<9^LVtgL9>sA!`kRn@ z+B#FsOGr^cMkK)84BqmJE_cnQMpziJpWog^8t%Z_|F=ZFU(WaI85?wmWZU0$bD({) ztVh_Tui-gd9N8%p4y0lDvetRC=)8M*+1GoX&acQh>;f39;~^&*I;yIGpY$qU;(Dgh zD=b)QvkIF3P{lL(VHx9+F@w#aS*hnM4ATrBa_ZR~j|*#>Nm>&P*($hfyG}@XiXx5x`MjNbw2H=65ogpbg||e2w5b`w2}_JjSx= zvMij%xErKW%c5Cp3udhYvN#k|O3H56$OQecC|=dh?~f?5L1R-6<`keQJ6Tbac1*-> z@}F(>COv-sUKQ8;`>>fghh|MM$VMWpjh^UdjqQG-iR_Z@t^=C#PUy4%;>}4&(Q*9y z%%g|#GAE6`8){1#JRqS{x(jvfH}8!6<7Zmq*?INVEtAdk>@tjSA-v;WBDO_=&jvj$ z5J}UJ6tagSd{*yi6`WLs+7Xb?ZudLumn5q!fzj;8doOIYaGdirB4N`!8ws|91M^6A z{6Q*z^N!F^aD-mAk|Wo4VLTv967!tyc3HT|%EoMG<}scB5tjU5mGvXF7w zQL_2wb95@7ap0iVHv31zSo55#(q(wqzFTdXK}E=goGK(08`EZ1qjzDY>KWBd3jPe1 z(JlINLWvF1<^uJ&z}UdYKp)huE<~^$uGg7uS^}`2WqCGcv{UZi2&%b9HlOqa-TXrN zDmPkFc2et**eP3({tT3~z$8 zJV9B_ymbc32C6{4*=!+nu28tNs?X%`r{_abd`_A5C4E3af|ix4xu&#svC&8=g_47^ z$M1MmLFb=vAkDo%4G3$Wm%~QRJx^-1>BPZzSniXonP!6;-Zp@M{6zF~MH|O^{U%xt zhbgPOY8OCbdMmG@;}8eEwW2TXuwJ;CvS$@BM7@#)AAx~AX&0?chYK%i;U&$ZlztQv zaY8z83$06?eb)RJr}u|Kk`j);P$M)vR=bVT! zc7+rBkImXTO>|b$x(4B0K<`&YnWFAT2Hz{?Qi)7n$gv}w{hpFOL7f!gU7pw;OR+uHFKS7-hM!p8;cvMqlBJjvEx3)gPRgpiE~CADx`e-J}8 z#~$3@#CD3zh;yh6H{lZNp5=SHKFBt&^jzV%LDTl~D2UkBdCDX03^_!VR z9tLr7p0fGg+bQUyTsA`cvLa#z>UoD7_*z+iq@p7U@^4V^D4`1-W^$~Q@Z<(BDRh!3hbJ# zyAN;e(S#iDd4DAN-AHZ5gO~13J-8iB3-x4^mIi#NZ}LF{7S#sPW@p^cmU6fQ$_?S& zfaly^#arW4AN=!qrGDEqkQeX+(eub{JsL#7rYLczNooSCUlxVv$vT=xw(RuwC&(;s zNgz6wP%`H9k3;3vM1;muMf<#TM%w@UH`)Bn*S(mJKmveClzP28k34B+29H!YSt5Q; z0&X4)vw(~bypL3Awm59FD_+Kgx035eTRHq7%d3PtI&5P6VF@tbcxF${noyPqrd?}>Nlm(uLy zuicX)J14@`I{!y}GUi|RcCi25Y`=)~GN{%zBlYc*dWCN#d0e?;&n@?ZAE-4xu~<9S zB;CNwu#SS;Xey07(E#vE&_IAUPzs0j z{xU(nbKZP3@3X=HxK@FsQK3cJC}-6^>0l_5PIqN*ykp0)KBU08G=qSTcf&uD73#Jh zxt4R(^%5x=oFAgO;SSz`=b+&yo}Njr%v93_z?ppZiF(5|1-G7mMR5S1wY(kvJ|AaR z&fC!3{_=jo@-cS#3((Y2+;4d=BVH$P%Aq|Tu@SkK{gJcrai0}Yc{xY<uf8 zvqN*)$s9dZhO|!Z+a+$=7+BJienX*}s=zqWG3SxHQ|6;UopP=+05pQ!lUqrR&9Krg)OUfff&YK>)C@w8mThZ=r55 z^Yg-CkDMz&CH(UQm0jyTS+uK@gqUxmk81w2oKW4LoYp?ILI1Ht`vkZT;pJ=oD5%>o zaNFb7Cl-C;)1|A8M8FDH;Ic_(bh32BZPTS?)DmO+PumWT&-*FfnZu1ZTC zBU4G=*Ot1>fefPDqR=7+$#w`W?Cnj7<**bvzCvqhtsv^8rGrdyOsnJIWWGT89v-HjX0(YrWq$i5~>l(jpZ@EFZVx3P=R0(cD~|2`sum$$k(mWUw$2X(;4@1 zqWSD=7a+#aD5-Q+>8Ui})U#iSbu+JkV4l6Y_t;Qkx{}NDnwAzIkKBW+)(MWaqUotB zu3;Bv3lMDRE1LSOXCyFPSx;owbAD`~fDdglf~+Br3<~KvA4AS_pLUKhBOxEeTnGwT ziUv{YbF+C^ezcvjy~?;yIvO2p$rS4Dbx401Y$SFWAMp(CAa=}4lULy}nm23CarfrC za5phhY^kIa7te5a>G@Eoe7%#2_q1+SM0j8FN|Z~Ji0oYUKDEhBIbxKU->>A_F>bCL zy}p#DoVTrcsKhiz4QDZog^E4*t=3vdSOyj~BJWd2HbXd#30Yxd)j>}YqFG1_`Ap+{ zx{S8{ACi!G!q}jEPEQ^c>ZCp~j1;DAo>uZ9IubCMSINCHnRKohCd`;ilo#z;3gwG2 z23U%Vu4w_$s&6O|ggu=}Be^ z|KcgwqS==IeR4UewO_g-swRd}a0vE=1kaMGa978^8_HLsYtp*(xAW*qt`}N;p?0=} z={~-o7eg?~#2Lip`lMC{udrj@7U~F7>j&65QTx!Kj}10gR&1w~@fF%~PK!!LRlkEp z&t~xSMVJI7+i~sn1eB*rQLN>*m+-nO7Db<03Nrfxzcc$P++0#WBaU^T%e% za7g6Xg8?OJoEu}QoTJr?l6a>Hl+e*p^H#24E@S1cHfs^C>D&u2s*&VwdIy$=E_;xI64PfYAp7A0J%Si;m3f1(nT z0`RrOXe8P-@l&jB9VF zog#0j*sXKn1Dhuawi`83h)`K+En$bt$wdWcXzjKq}KhR5Gy)DnLM>-6%@q$wV*{;1I)>JMfsuR_UZ_})|4 zx9sM_ET5yEPyV`%s*C4>cO?0TBqq$?q1G60 z8|fB^$bV#nDjYmWPiy&WqEo7c_3Cuo1X%gNZEv%TeKZCiz^pl2FUx)@E#?%B zouG2^!z^PJdxUy#A^!>LwJSUQsEIbJ=Gc-U&()xWl;@A$6yCmma?PJdpF_Q8nF^NS zaM^PGz9$8B8$b6rc+V;2m)Nt8bnP!6k>Whf=jAP}PP_HY-+Y7dC<7p{)!gu7&3pdH z(IvoFJHFHj^{)|6Q=b@0Ybx(}XvwUsd+OE8mro8geQ zD4LQVaLvWD3jM6VN5K_RDLRsK>kItm7PnC6(E^~cHhGinNr~4K(2F}wX1xi%pbQcr zyPlx%2&&7K77o8+%<&WvpI{?|F7&$Ad;$@|S5Q}DsL)a_E9t{TZyJROR42b1a(?)6 z^8T+>b?V@^3_M*}olg;+mGTSrJ(qvpR)f#%Bjmyu>WP<{eU>@mo5YIg1@leV05?|r z!B)9<@Le%c$fS@XW=cSOe`nzYo|+bKKlP|h%e~j@RO9{T=;J1W!b2*7$Ld&2JAN2M<<66&zXy$@8>Rr|P3` zMBI~AUj=12%j2+#_pwsZU>i;`GV@66^oJrA~*Fm8B~irad(cQZtL$7#rOJ$k0A(;95gb z>YKTkfC#(ONtFO=srBi>tEo_aBmqOVy>C$(yXrY zQDm4(bP+{^j_!BR1X#srI@dJ>61(iwYbDa>HLzp#4i;YZ%ZUQ^qzKqo3C_qgT6nth z7s^0Ac;1{&!ofvF=rgSH%0C6v@K=J@X2s_K$8OUvo>KU|GSHB@mt~7$*xsmlH+H6>hmKK%nSh3Lv%O%{nS< zX>`EWv38l_!tY@c!mlwc>NfC}JtE?j@EXox2Kp9zZI(+2uBuiq`|b9^od;!@W`88a z_a*jF*7g3udvkwgmxFtJp|gOX#5|;l)PHVce^@oKhIB6rOE_)vyikBMzGk~ahTl~l z>RJOf06@lqK)L{kG~VP}P=AE%2iClDvgB{#{55{@!L8od2%l>)1f3Bt$IXE*Eg?Gz zxFp2ez;gQd78R_q_zO*;v7r*ETGD-IVBoMkf8SWeGVoqSePMUoNvcG05OFX+i6AFU)r;I8{Fdb{yn#}7 zqyz#;-fv!$1eF9Ng3>5vp6liANW!JmhuLxF^>;57=nl61#k|bUzw!6d_@j0d}&y$A(f1}l~|e+5J(D4 zJ=~{L;EAkj9Jv|hWf_dil^v!K-OSX#F`;o@->=?0GY3-%5r1Gug-LrDb$EX#SG|b{ zH0cXP7y#UqxS**}kgiXlu1|De2+f;o{1&t5gwOd3LGC-B_A0KD)XYs(zpV&Q$75w| z>!qwO5MeY1#O={Cs}~@(3H*)^yZ?1eOdl>74tUUULk>O0 zJ_Z!aOBFy9-(-f~6LeYz1ZQzkZ0bcpB6|*S%rC6?Q;lrl8H90A zk)*ino6l6mvJl(TF(H6iX6gCBD#5p(_REe^pj?&I(up?jby}l}`#ClkBMo7@^jA!t zXW%b`=3?D|hmR26q-Nytd>`>gwNOK{D5!N{XmurV~Ho%opdO zAh(HzG9zxAs%0RC^2}7Nf`E(i4{5zVy(1d_pJp%Lp1TYKIOGoe{FNq)k8n<`R@|)e z3b9bUdN_gMGD9~c*`E&^>?zHSrhI(-OKqlmP~fGFe7lHZiStBBu^h=ZN5jmt1WJ*MF0rZBd+wslqJ)@SNp-?&m5}}b`KZwINS^(sG03p+{LZDQDCRtt zAs8^4Jt07-f~}H3egC(gm{Q%4H&wm%gh0I z!nyeuWJ)9Dmqs}%<1qrqe=OVIshFvS;)iw`TxdyOh~W?tvzNqn`Ie>`Jaz}0^n*PO zK<}Y^dkcuE1(HjGZo0sMk{L8=Q#|O{MjU;kHC0VYMd%LDH!`)$Iw&T!S0V2{$8P{&NQ5h#6hrwkW8+j+3OoK zLWz69GzO2aWU@8UqObJ_w!}>I&FLw3&Q~OePloH@`Bj}q*NxVahST)Hq*)f>{#lEV z*6yY)3hLOm88PnE6n%?Wxht79@R~XBdd-0vhtIiyl*L85TH{j1G)~-Z7x2K*B;y1# zynkm?;E7*&?TI??PUlM|-w(Jw=L}j%(-g}D2sXt9aic|h@&-)!L9KW3S7MKyr*n@c zXcwPOI|h}d1C1>P&)b#D@&Cit zc?LDnetkH-P(wm58hQ&zmrm#%Lhl%QM|u&|1VZn!I5-d#AYkuwug}I)CL%%e$Xmox347e`u5;>Y2(jW3NOQbZ`i+>$)oZavhD0wt_ zA=0EfjHJE&$sut-6qWQi*CpXzSxLoPgfn1NaX-qg+aHw&JxC&*8Co>j&o+CRy7;~G zo1z#wOh@$+ZBmZDETyS~)fZ^GpU zuQP)`kdiwc8rNbheCi&ar!Ox1DTgHgRKJ-8U}F4z^Oz55)SCcWPV`QYNdC5!a@tK% zfNg@mk@hb^jk!snBtZVSdC;vmBQ$GH32 zW(=oJqPNHEaaRi?Z2Do>63o;q5T2g?cw&f{y> zbb3-HPxVtCD59G&svbLE_XbmM-}rQU?lU!VLG0&^%m0v{oJcZ{oL| zxt54LM2)T+e2#1{UL)QZ7pQl zhCPp^4P2xOV4-vTva@f-_;!VpjGklKGxGPzeEHERU6Yy4 zzg~fE{ViFz{broZv5$ZL6VJIrKS#=yNCa^LaOb!ktf7}Z6O3F-2m3+_CCZ>*yS5v%lPvQAxw)3$6hb{UdGgj(noWm(mv1XI(?~zFS#m(J4}_9(H#L`7o%}w5XL|iG&5i!m?&8y3DYuM<^0=j3Ygf`URNn~5bMR{dB)gjM zB~N6Q#_AIz9$)hdflRgKlu+;q$NW7{oJ!0Gk^0(4^)?mkMhZ3_8DKaYzarJVM)9`E z;X85d$W0}(Q8EIBrs$*e)qK9i@DXUVNe~o{d{zA5>ZQLh4)NY;njd(MSuW+&i!x?Y zSwCr&gSRXW=-@|K@j_`xUu(XsOk-=FRP{VzTGA}Wx-k3H7sMEsC2nHyh{~90!@p;}T5)L-#a&Vv5KA^XPH*6ryI)*ZG8awbpW=|=a875-}S}< zbv|g%yFS(Q+rNeso_XCSYRO-;{w#h~WH1LGDXger6&dp$0Pj3Wept)=s^V1d#edau zIDC4>Qp$XV?gIZh^?m^w-c&UJ>Ga0?uJ%!g5aD%fpr~!|2lba1i-h^TqHAh13YBE* zcFtxa4qcYi+pp7%Tl52ES`uQHJwghkM81?+o44kV`VIK$ajmst=zVy6v zmoW=y)Ywn~Ngk-~g^+-`8Oqu@IDV*SHs9>KfiT8nt%c~ttewAm}l^69JC-M z55(@CbT*FDE!i|tRhJ7#$?!;GQG}y?a%3GKRpUc(EScPSFbw1)MCyJ$UIv}Gm10vf zP*w~)vVqXYks>2rMet`vMoZb|IXYfI&AyTnH_ZEr2f&=@O_J-xg@UaTw&n~&l4GvO z#RVer#fP9TU!_Nh8j;o_n<1&?BVSRUQJOSjpU2Tm>l0TDlZ4^2f?0qP z;OPOiQO)28JrTmx6T}pZ-@-->J~IzfmJ#bw+(_lgvW1yf(q-otq5i1K)75}3siR3w zr*6CQ4;oneDm?i0;se;%Rw=|tNP>b(0d?|>Qqt$i1_&RZNY{-r`PWd5%~HfK6$kOm%bLg5}rfP1m=xx?EA zUzgF;jo#+ySkh_6uCsGF$;=pL88SH6Lm_N7Vv_YkuoW4duMWG!?#$D;v#&m;UcJURui2uOZOaG=H(JtzlNj8*c%*)MS9BIGQOF$MQc#ruCeP$bu-zAwkgwn3 zwMjB-6yAEtpprBYK|K1BFe6(aT?|4yJwpgPb;=&RIPPBa&GLHk)LK_^*_#WyJtXyO zLC8kxaIf^oJUJYoJRGFds7=TeN-44oWc)y{qwoyRnfU>aq+wB}pqY;6lV2ZeghkF2~#rStyVH721DcH+i#PiMJ%$Z>LTgqC3cZs246>vh?)q zC#!?b#eOR`4SvI1({3jNwU#8o2E>phWk1*cqB`cmPKBOB25939ZF3OU9fcpa&l8>z zsU<*XlB{0z^oO@pXF zCf1rB$-4LJ5OURSsdIMy-j!eT&NUiSZ=kNvV(>xHHTXE2Im3hEyE(so-JCCxiZL2k z7{}mqr|9p&y)Jr^?)i$@E#E@yFKUDA)%+5+wCmIKO|l`mS6O)R7>vnEKSwwDDL2dY zA_c%R+ho!TM~iMmdvWR)bCYi+yXj?@owDrF`X8#X>6j;@I!x9xqCf7+mO`hLvYu+^ z829Q5iu&a0bwauitP|Fk`ja^QVnS@OboUJk`w6K5Tgr*Ul4?oDos8+xKJ$J1oLY{t zV|qg`^*qa~Kd#eX@1B7QOug%UcTcmWgpCeloSDM`n7Edl@-u%n=@D$(5eT6681{>M zPsdVNI^NW4B;cZNkIs`hy=Rs``B9+KP?oQ)(WSk5YT4{)Vz*2S*pmU4!>xZP;nV=Y zQ$oR;^yQ%kZWltgtq!(S#EzX~IMUiy8{gNnO)3ycXd+gtn+-0*_>5?YJ_ekKOFhC@ zIP>pwO5xd#uHDp+j4v*IF!Z{q9n#%Q(^**pA(&Ygbvuxe`Ffxn&idSiUh&~0s{1-4 zMaJ+Sz1=cq?t2{kGN=%1qa;o!<#3`M`%c%(eLBxU{I8dU)h{K0=J5&nm}e3Q(P4xkxYD>=oAi{XU|$ZiU1u?PVdC}980l0l)L*c`VtIu~ZBV(Y9YaC!5?Ry? zF*C$db2+GDX^1s3N3Il|goZN_K>|hS18qE*j>jS$`FfBV>9MhjlNB5Q_n2MM{0dYC zC@3VGx=BJ0*^hbCQ8)(DGoSrcSu*#>mwolMfKmjZJ2w-KVq!IT;_RIsUkFn;!Jx-(7 zu4edygf}SJZKqGWPB@_8BRV=^0VRWHcc(*RtQ8(H#BbU-YbM6U1PRYx*F-eyU5WyaLN&2rR5vs0~CFl`mRYs_2nVsLqu%V{c6$T#5?g zhWg52Kgd1Mec-gpkBdE3MC&YMZ#-YwS3pRb^W8)qG?uZ;kWfo+*>NOxy2Z*=j&sIG ze_d0H*PwIWS+`zU!6upi1H zqmtvGV9g-O8N%e896s1wk@zgOb70n0%;ysz*WV>~Hp_A$;UM@SCY?L)!#CsVG8qLX z17=M{OOe=11L5(iAFIWs43l_Gzy`B&!Flc3 zBc~3-OWnk#Jk2%g_lO(_BlHtM#B-7*~zIPO3XPJeS+@L=lk^BYAs)#Pimiht68OBhOYo)vX|#kGf*iqn)zO36vx zl+?_S{y@*UI3}5&l3O$;Jw^rI4S-#mLdwt)f@BU&5_pfw6-oqs!lLBxFkUi5pUCBm zhoDO2_f5M~-C4?!zzO>(2Udun>bT z5#fqqCLaJnUegt9bWY952DNNXP#KnaHA;$FW)gHjxu(^Ivtu0v`)^$8IuEh3(vn-W zc0SwU?`Yslg=%MMb#fK{u6f#6jQ_9TZJ?VXqy)=0c%H3=End;`u*lASBuQ@4<2F)X ze3%k3n!*z_=A0s0&sWzKib)~C_vq}Gu<&$}cM>21nE~xsOH=k|H_8;5Tf@+Yf`Nrp z?33v1k|gGX8H@%Uxn7Q8j9iML8!heJ+$0_ThQihqqct9%pd17P%BvRkyRE4#Y~PKC zKiw>x*NY{wY|v3nx!8Tq=o{k@O)@){Vazt!88c%#ho$uu)B*-Y7k~c!@KDR`sMb)s z7j?MOSEr5x_77#6mPo}wzJE?)2c-(G|1L{vIGHA8h)s7xX4Ya6>zvwHNR@Hjg}_|r zWR_ABq$j|5z}ld&XFrBs8#heQY+!%U3I@S3ia@bKaCH1K=u?M+?KKug>N*2FlYTS?PRng%EU4RQhKd0!n2=o+S{;Xlt7|g)6 zsvAClC8c(9p~;GdEjxw9vap9tWFS28&B|_x3VblD;M=SjrO&2p^$gMOzeT^F83UY& z6Rr^x7ldoKRQz~I@u6BGGw?b@>X4;O_TaUahAoiLG4YAmI$eP|z%te_CQ>iVxj#Ll zk%Fb85I_*N0-{U4^V^t9B%~!(cUtv$;x{;SQYO6?d$qy%PQfQ@xf|f>3p}i1S1GOI z?A~JNbkX1O{IdX1_Ck;}o^yTG-+q09&6>T@o)A}Xqv6dorYOy$t=@cQqUMYN5+t7N z&{DSWzA2@N3959jHyLP~hln+bem{1rTegV_|G#WMeI8s=Jt zXOHkR2ovq}7IVMlmcNdBUdeWfDk}akFTVk+Nfx$-mDc_oe{`#S?VGCkGcmbI);J7I zWup`EDk5fPcG$e(A#dFF1A%MQj5_Z-3ZhQ3agdaGuBL>Z`w2Zk=fj9t78Ax=_1(3m z=Ub13Ru`pd{CN*Kb;YQwZ=IVKV|Mci zYubja{}>0gR#;G@NY$n&ek-T!X|w9x8}sN*Du`E9if`kuMnRGmSLMo{flRwih&rHwjaiCQkuO>}MhU`ab>7GNAw^lS-Asd_JFcq5-F^?z09PvR`P%IlHutHZ zi52Mp1Bh`cGb{~E93HzH^fUGHMc`Bgo?LA7@T zPl-H6sIVHC>Mvet=N^>9 zUgJbQ3mgOqS#fJBg!zYNc5z*r-#l=dT7y}Ou%HEFH&zhWLnKNi*9~8JSOuM3k=)6! z$K;AhTKb1Mv!BdJ08-;Lvxs>d7J7LtD<)LILKx(7`p#hI-u*_MG-l+GdFz8Djnqzw zU>oS2bSz?TgnS;^Rf#?LqSlcq%~TiC92_LwG+C3Y#>HfaW|wYorB^%qfu{*M)P#XmTU_Wz7jh;$?{TXu$sB(AQzI$*7<+Z|hlyJkT~1$oVv`<|2Nl*aNP@5vNgxgx zB4<+ikKC|Ek5>RQ>yI#?G40E41}om<0CSq#{ejy`8exhGso9b) z+q9WdrPS&o2$uO(wb4huq<5HS$=BW_;j& zquwIq#2FEKFNe(|<|*V7_najUXEMXwbsznT$HVfiOO{)9C5ju%Bh1&#pFXDJa zsP}ma%Ppoy?6Q<@=_L!18-@Wy%v27TLpa^zuE@3f8g(IJ-Fv}}G5+A`B~M1=5a0RK zLH^q<7Vn#z)%>=(r?vnNn+tjo1FnkQUq-sBNuH*dQW%d#hh}N)=bI15=`bPf!_L;! zzfn7nGX_(q4)Ft?Qm`~o)Z6c9*WX=9PbWSz>&RhA8m1s*C?Px+etx{q!9w7A-$_`+ z+GPoIi%U#8Jb^W{GRb9o-Q5j(y-HM3U!)StNBAn9O5?J$;K|Y+$UgnN7=QILI6|XE z>NM;6!%51Av#1GSy88{G+<}xFI%H!ed8*ZN15GMpQJYF(*J4S3Aui+j>!Z;PS#o7H zfC)DD?gyvym!D2>0_j`KVPx9{Cp63W4igz%g47vqoV0L{WS1AWLuS?oBN*$JeV};C zq$FOfItLh}ycow8M97+WCL5FQ%zf{vE=Fa1YXP7@%bbMxSLRa@uHw0cqBt4N7xWNN zbxLOJ$ZnpT`#j9a{bh@8l`0dLgYsuQU{fdN>RVB=dvT`7lfzJJJG!pZxVluvBB3p7r6)o5hSQSta z1Flhx5My=e7UC}jI_?koVOYK*IQXaJ8Sfu^j2dZdE5Q|QVtLI!&DAk&z43Y2!S*UO zZUMWa?S!UEf0+mObXJe;0(prU_-bbZenc7D-7gy>p?m!~Ww{vWFh%r5w~$7{A~ewb z^v@~t>?V&67Btxeh7i@(t!7Qv><&23u~0kP!qL#MWg_9N)LYUG1lh`2`1TU;#kH6w zoX=Akp?QIqCtVgtO)(eZ>`=BLRczBg->Eub&|9SgX1`id>5a`k`~pmaHrZj&_qdfU zB+vo}naBA8tAi5XYxYt%94*EiR$|y;N#J|`j;6Q^g-N1e5j|dsU3R#;{gSgP01oXz z1b0igwT@w#8DzFJ_hTT$z(HJ63ZIh^3kos*%_p`Rl*_}+uu`yh$n=z$Bsa5j*IGIl zyEPoR7#-Po`~9_f|L$ZUJ7x;2!!?aj{;{!{#OD6KFYmMrIMYs|6};@&jIR_cRf!{5 zPmtOBBS~O$oS&>y3cmoQ;&%Tt8+k9&f&ix!HOq7oXC}AQ(GSO^kdt~%7yMY=&?&EE z8|x|Bf|kVj$-~tK8;AO@T^rb}^V==~34ED>o=Pxt9qKE8{#BMBL*PL zT~GAF(<_o9tVSqAILaSZULPq>9R1h8nf=9KB)@Bv$M!| zQ5poUyM5QLdR-LG?ztN_IkVfF9Ju^DU1~*BAGg-K*B$KnG2H!ppbEcoxm6VV`3H;| zRb;uBk-$ct^-iaO20=_mpT17o+coWATNr0hv@&FG!~ zm$VkBA4*hPIrYpDFCYC(>FlgQ9nDp0Amd8Al1w9Y&(K!nxk?RQTn?7nVE(GNya8f^ zJ9E?811o}eae|1A^&hui!S!W`ZxXzlqjohcE-u*rHnr#t zcm}NtowV=ssW$d~R8x6_P}SBKJ~Bs{l@JKCvV3JZTyRH%?Sl>Ws1MCgq-b&iz=pxQ zR%A%}l^iYmihuX=%((UMGY@`wdFy6z57dr3xk=i;?vStv<*mRSuUokZEQTih0%Grjk13q5+rz{&-s9L06W@Tg@D&<(`8!Xk z$flUrcDw>%(o!PvPP}iv+9*~M>gXWHjIhk)@KPu_!`xt+ETlw5KH|eX=0iswoRXTn z_&g^hz7(vb1aDpeLm03sr3}0h>f5M5NvWs0G6+SM(!>UGufUy*B3!K;0U{|TCnXe4rsgCua#B-r$fYL-B5fZQPspX@ z=A>`tkT-LZN)hQth=LW+X&NFP3wI#7=anKP=qGIi*a>AWuN2N1125AA2I2ED0C*l2 zEJs5mDFH)D5$BW=QVGB|84!Vnz~RAp0H_$C@NzXofrhZhgYpQ4IW&+O4WUK{-QF)$ z!-5O2V3ksY`2i?z1uA@i2q6H|+=0n7goF|}j*y#%$Sa-C%{sc6R$H8Ua$`#HXnbzr ze(u*X#JK~24-N5lKId(2P82aDnBU9b0E`FZfE)k@G;k6X+`NKppfkZqE6BgGWoS!G z;|h|mu1s*NOsA|&^mUn-#|aU$Ovn;*y3VO@8j2xGx~u>@Cy|a{yvkOQ6mgVQwismv z8MdP0;}%q<#M`7qetqI=ABQx>$TZRQ>hR#>WJ1mmvh@`*fB|Y!3ODgUHmv})#x6In zz|mM_XG^)1Y`JhrewYfeBE zj6@lNfPmMoHCq>t|8}JBF0wX9EDaSW_r+eMG<<})QFE~;Q3U^O3o3C_@DSp^6oa%RLot=!@&A%8xPf8U#77 zuB=H(s*-Su0eovG$R6gOc{_rUMg*-p`D`VON z4Fv+Nw^0=&sc?e*FK({*IU_ixi6mCGGKx4I65d(CEvOv61SjA7>0C#LSR2}MkMhh( zO5TA8-K*xm)rAxQ$TywTxT4t-JZNS*vJE#E&{$>~0YA;UiY!}+k9&MtGDhji5GK7Q zSSMC5MH0qoOu6~Rs<13;eMFy=zr&H(;^|PIn@r$4$wy0FtOvlLQk`G4(8^=MXX-ms zq}u9R&K+SQ`!LAVIO?IQ)8AEK^$GZuB!`|rU{YKJ&yoadV)^9KMXQna3~oCsu1qjj z8!xv-EWs;0p&o@aP41zRJDUXCltkScfnck3q_UD+O)9l-B$A8k;#e0|XA=5`T=}6# z(#Sb1S?%h7o(^?*C@EY;^5nCV&=O>3YxxD^A&RVDfqWhpX#6PoP*NgH|{eB zmmW;nij(AKSNT`ByvrSkg1gNrKQXTFtWgMGz9(nu0Is6S-YlWG+$$A3bVJLZ%#16fixTi?pjx7>J z9#&~3eZcIMbV(BuSsZz@dIQ(awe!TGx&eK^eq3uWqds<6)(^<>%?%9yR2t=<#(y5zGlLeImSCRF^a7@8s(b8h`#FcvG zd+MSD&LLm`L2j1Uybaxy{zf5Pw4oUf-_lx~`bjcer5b&A=B`Kf;RF)Onduy%^U%>I z>nvm~t?5Pm^6#6=$-MWJflE!I+T&SLxk*&l)(4A;R9llNHv-Wrykp()zi)<-Ul)05 zsqm!XCi}>g1ZlIx$VDM4yp}lP^$g8?C!o-{s&IW(A@)M!AcTK4B6JOC`xWEeHe`Ux03m2(bBTDfrZ^z>`$3ZV7K}Xe=7Dfh|vJf%Y34HH(2`i{}0KJKmVL za{{17Kt&8vpC6AG)T>gvao9Fh7%2Hhc*CV|re$wrg@Pmz&xQ|T$nWpJ#{D;G4HE#2 zzK$5dDR+i@Jx(gZr-)!wme8|d0FPgA7ZsEe(RS7H*23!P9j3+|gMdlVB|g3%n-hOj zYm^X4@hyswWa!4Ah}ShyF~s4VtL6cgs`psJZ@pc_%JM!s{D#0KynGV_xUqike4k{s zV0D6C--mmC#ru38m0c_v{Ujj~(+;V!@~{V)pyh9x1LTVP~JLv%7ul z8wIdE;Ee&?n7*r%=PE)lkXbYFXz6u}d1U2$ZLDaU(wn{=kIW#R?burT@68(h&5ds@ zCg@Y%pQ_RSo}7B%5&$cDYAxuuzB&qb#0|s)Xf8?#q*(`+Lg$7poJh{~|_Da#@VGN=a}ly~Ry_*Mgrb+-#-e4lP_{SI(;e z>RK;Zhzuc4n7mv1tB1y2dYDD)}odNzuC6$J>!41hJ>rkRK9FM*TEybZ$b{A z&K<#`YA&-Eh&8S^+>i9lqcxeNOMZ|%d1MYtDk7I!wr`1yy;WFr(M`ele3t~se{9}8 zd)id}+;d2Cl3y|UlqtfNZWS8+g(wl=`I(wB`&7JnQhZ>8yqJz`-QM#44$@n`o^Qcd z`{JaM4|s40gM9KmC-r&&t!3~Y$bE6??~_pQQOjNA;DQxjal#pc|E?^5Z$u$$soUMh zc0oKJMOeuX2ju*lUW`QTk3=5{K7`@+k?~AYX*mF5prmwT06pGp+u$|v;P!m-Fzv^? zPoOU_6|)6@pYO^4uzLc?`qHm2(m&j~|I?5|h;+b5GPn=BjDAu4KI`Rg<;iRvdPX?| z1|q_N4Ddwu(cJrky;HbA{1w)lds6x+SM85rQ3&$GrqHMRrgrz6K&Wz!BJ9pR%oQ|D zE0Gph%Ep$(#_l@lx8j6Us@3&)a?-+W;NqPfqq(oO&)SyQ4FrxmqD!ikgO=Mp9`4yT zY9%gz*ggrQW=4@lx4ukQNSp>egIrku&h@a9P{(3ray_iI+y3Y1yhZyY29RSx!60f$-T7I~jS zQ`EXRa#Zrf>b3!A%d=J87encSd6@#Y+8WHXL7>%bPKN_nFHv*#3i86OPaHZS%h9yJ zrtH7(V0(5u_o~i>ytpNSI;ESg`_7r+V0BtaNAHPW*F&j;hC2oDf43`s9c(`+xZz}Z zG4<%x>Y}~Dr3wih#vci#mC1{FatmGoncvMUGHc)hCsXP%Yw zKkUo4Yj?ixy`L$5-5CGXQl^dh>}}55XN-1sdyTh~IkvcWh8=si;#DLIWWG#et#FJP zG5%he_)K*@(Liv4{zz^SML1)g%Ej)ODUs<-n8q4wAM8w^kMP5pnhJ%v<#~~`ZhL#p z9wN$UTP>HHWR zRRSCa=1JnFT98?RY8Gt1XZ)wJMr>6k73k*Yxel4t`059$T5rWAGK;UzLzSgm)~W0) zD!Jf@AoTTdb1Rob-wW?uK3Tu{n)ygV`AB|)D*HpNJ2PJIEyE_$DrTxReC~QRI#Ms} z)w#?^MH>}DKC~oJ3ufZqM;QKjrQ9~nf83VDa|&V`t#Xti%X0U+g2%q~5u+Ybu09{v z#*^7I@cqzNHY=@KuaA}N?9>=y9wnMvbdimAC5s7E_c7sRL5;tsT`Cc?N6f|JY=_Iv; zCz#r=w)*gSxDs_0>Qfvkd|z`*N~788Qj9w8>U!mi9GYNIF?=^32ODGwCGPG;|4lon zNo&%&n7Ze?!Mt&{>i34`87pygX8Yso9>1y%A+IzuOH43A3$~k{2oFQ%7?N1)5z)yBeFcSV;wvLm#mG((*ZoUMum6GDMK881A zA2%75YaT0~C%VZyH!AK)m)o$y$J(B>o1D#fl_(*`UPh6SfvP;?i4J@lfLuByb4Gkm zIpejp&xcyfSBz&{WY@$oD!@VXUyYHy|B*|^a@0S@nGr7dwaWwWZN_mnRMEz&PE zGeT^wy_mcnI}LGwUX?av4m1)6zLl*fG_qCFylr+|2k) zeJQ!jQMglDyDazeUVPo{R(|~&N!fR5h83q9=jX)6do1fe%9L*g>O$|9d4KGcOiJK6 z#dqOhDjB0i9>bc1`P=qcMulIW*yqEHj)&N>Cp+zTxBobM%SWZWy?OuD{IaXE4NWcR z9W(MAkNF;eTD?Qn$)niDUT}T@XrXvKGlw~*`hwzQF)+rRmxaVyHgh#@LW;HsT_n8%KG4?O%j z)+@jtIH%DbRi~OOf|GXlGK~~Xp+#~kRKSzT&aR+FSd zKMo^ow}Uoz_L8Ob=(t~MSB00CP1xW{^lO3IivJQ{vF{yrH;%}2%^|P3KMZHa0ED)b zP0AhJS%DDi&$3Egd3NMbf6LhTIPbrm?$XDP>f!_Zb5%zpZZz>{Ebh#0{vpfxL4{s0 z1wW|4^6l6_!+w9P7|+^Id12#z?%p->L8y)Z<4 zRn+KjdDiOP=HXQ8?T02JS~!8wR|8_ay{za`#Yk=07U#WTTX(i=%}lNZX@NM)I}v4U z^GEmJwzn_d*|4z)eI+V6KH$gKwV5$^;-2!28X5>jO8{bF5Tc-RjtNk6dij>0%u zdp*&m{;=tO?O#`jFRf{dqC?D;u{xM!Z&%H`8bEuw=;g=ccY(w$ZkSaCN9Wn`WLrYt zdFQigS{pBL*RN7}S!VL?IeXXkH@KBQz4NSY_sL5ZYcYd@9P2t>CXF#Ayz%il*N*Yy z9u1G%6~#_*Ec}-Oq_t^KEBnFPcZ#a2;!*Jdvcm*P2h}k><(6_A)n=jn9h(n}jU}8- z55&xiaY2u_8kM}8noOe}e9qr~4&4B z^n8&km>cKPq|Z2SaVuSZFf-TKyQeVHf9-V+IZ31l`vH)>-Gk(%{Q7=H9bX&Zh}>F~ zczOMb%F`l_mFt?DPB^B^aE|?0iXn~w$1~{nTx<%b>q^gZSzv=j-@X}Pu@7feO@<2G& z5(Qy#C!HIlT+sqBuOh_@k+RlCSr;f8V^~W-hGJNzmJAYDs4~Bpr)5&{V;f>TCX*9W zcamIL@T<*8f!GjwbSwcEu2!OBNWC72$MOgRtP=PDY+DN4{*5pco35wpw+tJfuLlD| zt8C}V`v8#0JbAgE!!5P^V+vX+j~*zOXVRkf>)caP8*AoKct0jVRTO;m<%YnYE#nJXw^@#vJAEA zWm_EJUKFj%w5$byyGcfLid87!`U%I%9c<{BVJib6Gy-h*!G>~VGfl8zIp_cdhEqxU zn-oiaAe;{Txk+K_(}5~63szXj&(Qo|7Uf-)R!cS|L-RJvAC_!u!4lu^eXh$C-Y08p zvWU!=v;t0e@p(CGdT(+mN+^l5qLkam+J;8FT@_}TG%`2_U^GU_5d!A-a92>T)d0;m zO>VAm-;e&S`VaIU&I_V1V`_&QgY4H!QAxi9>tvN${&-ZF6YR!CAAr0~->WMv5t@Y6RYHWD1 zWGb4Bn%qcN`Rh$sWHD*9p!|T)PPTS@aVt%lEASvYHkT>R=RJlqc}9UqU=@K&eSlwY zkj00Y_fco{jm>Hkg8+Gyhqy@Pxs600_QW_7grBzws^{SmYhpHz6-N$kbq-F7 zrp;Nnpi{|fr+Q7Dapg6wAQ5&2^|S0enl8Bp+>^%YItCyAn-yAr<9xmB{mOAdu^rVp z=Yn$`)$wPatmVaJlU?WG0_2YFqYCUJ=Wyp_zelzE5ElhyLw1*mw?L8H;{8pa_x(pc zyFj1kkIoep3nN_5eSG8(btOt}h{%w9C0zq9ZUhIp2C%z^^l$jyCwn!yhF;(BnRWGL zMr}l8xt{7a4ZP?YqPO9D+r=|V(mhH%`J!7&kz4A0;MGdEwA*gUl2+*#A6t+fUn+9b znI~TqaZh;;Idufgu-&vhAfFm5p@_J*rnqMml_rWzXv93Kv$ATQL`zT375g}+0Jri* zJjxY3D(>gm@w;(~vz%ne*VOW1#HptV1A&;Z<94hNJ|81eI04H(jc5d>C>wenFm&0?@nmU6ge{fB15W<%Cn_$ zT=QAzu;Ccyaktx~XyDCvh*q87DOy;-Y2uUbJH;YLUf5DdLW1eq64LV-`RLTalR;Z^ z5d_IxGQah^=R>yqQ+PYA@1ECAT97Ni#p`(>3-hW?ib(gWu*Fup1PLSqXx#PES@#qP z&D217pJH_Wbu`y~mJg)6+aHlVXQnj(0R3mk#AoD(Gp@DI^I|1^-TFLt7(OB^8CnR4 zSC9`|f1z>SQ!V%B^#E(7yhrsxJzpBZXIEah-S@3JTG$P>BClBP(yVM&az9gje>I)^ z-GA=S?Q_TX&;5OVj`{K2zrW`I97NzLB1n-4)+a*jh)`c5ESdN{RNTZ6OofiL~;0Wo$^B~`eF3_xb6ISIIfWXKPS1au9mE<3`~V52F@O(sOrIY z8elF0@R9`h%7I)Y5H8XHKLtRL956@~7^VS<&}NO)MTTf_Md|T`>q6u8_=A;|B9wJq z^o@=52&wAC%bING@tE^?foLO+SR>>GBTSsBV7w`BqJ?0Rl}M^BPny-~G=g}looKSP z#6>5$OU}4tCzTjGD=Tw%cUK1|J3^eNzrS}_sCRn0cT%Eje6UYgSa3>eNOE%W`M98H zU)KnIqb2}%GeDq(g`*W9+y&sH0r(0O_}hWvJuul}gv?EDsa|%KK7P#+KJ9B9N&{kg z)zYdnLei6*I*XFh>+&*B&dTkcl|RwP*F>D%wNicOq4mK|{foc;3q!@BQ-(F_W+OQ3 z5h=4#726xCj^pZ1<65p0x}Kw2E(3~IHw}o>8gBDvoXhRpZW{S?ntR^12pDh+Es2fk z4@;^(Pxu~g^fTFF$~t7)IdaxBe(hY^e9(pau}M>QKEWBf?3t$M0xRAMJE1xUp-g8v zlAA(?r&N}QN|uji_Bpj|Pl7sXif?HvvD=i}Uc0g2DYFKen z%H5!-=^&rUpwdE@s>;yH_VC{|uD^2Zk2`(-j)nal@Y^W5kh>I8vmTc7FtT$iV(3NO z#OvgqSLd1YNzB!YGjA>qre-e1WcXYm`BKU5otXh`Ss@*{VV(Jr-G#wd^Hclt5^E`W zd3iN8HRXjl1!H9$9lhP%eVqfekv>}Y(9n$=V?({yItmINmlW@e)a;ISy=bW(TE1>Sb1UoJT>bjT-1Sd+%>A03!@9q_B`;od+A~Ro-u2zx?hijZ{`~0O z-yi+4H^F4yU@~w1KDz$vQ`gkg?1>Qm@#Dw$)>eMLn`1I(n9RkWhj*FGhfL=GSUaz% zCcgLUPkKTPO^S#i^df{RO$?!hYA7NiO?np;X#yr8KQb=bY#4y*~@T4yLz$j2=_mSB??x`#+CS?FR>k2L~H# zpGKcOV;nQd5B|S0$*0SYW8VK?CV8Fx)tfE4kVv4n{(F<|I1Q*uAsgCU5D6D zE>?1?s}jG$W_CbA$En3H24e(T_k~{q7)@+mi%NM7#e{Fqy!n}5%+p7~U1bbD-dBOSVpI^I^9fvV0URGSMrd-c+s=k`XHv8jr~M6uNUCFu(~n%_Ic&Yg#ExTg^2#Kbd|TYNmU zynH}Vep6o1N~Von)duLX%Tmqy>^A~idcsym*& zK5J=?2^(w0s!WY9_q8QAB<@9hrhBjnYE?`CdT0=o(~!3hg3d4+(?>((#n4xOFX7qF z?{t>GWc}K_Oei}ok&vOC!{@~YFxLcR#O@lc9lABNfql0cyMO)0X8r`^w(AGSgaRJ5 zj;UNwxIxxS6!zaPtWRZF`q#IOe*eAI{x)oD>(P>(+1JiD*cAD5UDy9KWId14ZfsZ` zPC3)v;Z@Z5Yw$xYAbMuQW8A$m`rOP@`TR&JpB8^Q&V9>6G_X(gGf3~syE zvc_i7CRi0z_0i|mqxCOnZQK)f*OKdy=Nwmj!lp95SMgYEQvFTzk8#a|rz&HzKiE99 zeC3q}1x7M(NFj+sjMe7DMMO{u35UQA#}1Hg9Vdc=L^qc7yti zddAnV1)FR4e~kqWShUZA^jm$HeFoBt2WX_Cxd9iKihzyop@8l6scVU8mWvwx_f@pA zFNxfIDfQ;m3)Kc1#emai8xOqEEuVP2QlJvlv5@sJF!EjVgAZ*RR!tm{Lk7xpda$@iQq-|F|Nrw^F0Di=Pq33A)z5KLzT zsNrrOsk{LY`8tMN^;Sj#!uy9tP%$>wC|#L?DKEQ@k4|TdhWzjEIC^Wn9pdl|J+{Ag zmc)xRGdOui7Iqvp`nka`!DUoup9hx(LU1X9h5EsY+sn>Ec>f0^;_Z_M5*V?Fs^IWZX=A` zW}F!BMDD3nTP`vQ@FcyAdUSp1U+PQ~#Bz%K7R=xN8NqPS(`R$Te-yxHB^d@#xl)%- zclG{!<~qGqu=M)lnZ360-JdOmllSISrRK4>doDP?e0t*FciMQM>5aS=T1jK;2-<^< zk-IBTfZGVlaBfygsWb8JtlFrK2wYZjmid*nsA@T_{UwAG5sZe5f}ub^1ViRp{S~Pt zV!dDXPp5d%_V6)(R4DDj;Ad3bua~Fp&$ z9c?6yt6KDbAFvCW`yBEgnf9i<}mcwE#3FblL2%(CQ*#-DvUxWW3162 z!%PM!1>JW#2wvWj&2BX2x$G$Tbnd*YvM26}$3m{GO6A+mzH0qC@r&>_Ua7Xev9^$j z!<5YTVEd+LrxcLk-1GKxzeaz_1@x9gJ4E7_S$&%a1YV(8EZE%m3j_=laiVl*b1Ki{ zh6hYmzQ*o%~_W>yCn3-uM88^h;j|oL(1SW*9% zkdS=T{gP!Q&oJtyN6(`aQMTtrHN3;HOBKoQ+g*8@_CLF%EDyYn84U6MzRdTqj><$t z`oyu-qonzR+Rx>)ZT5_f#vd=_jQ!tvzKV2yei(uuH z0ev;;I=jQhrhg45=M`&!R-&Fu?2F5i|=94WI-4-7c} z31vjSwTRmGfr`EJe64%sgQieh(%4x6wi3LU&=O#XBZFkneIVPC!}DZD=}A0*72ZvB z5_|V1WcFKy zoGxwtdVggA_Q5D*BE4|$y4>Hx3pU|vpz8V@*u=I?b_e(XC05U)n$KAzg_fTqtL?1D9jv(|uN*wG2teMOQnwq z&Zs8RBf`J7MW$p%@EAia`DR4h-)73b^(*iBDirV z84M^ZI4u_gzSE5Dl6L=#NMGl7hpeX*@QTInUu1Sf>rhj))ziO@q^yVCM$M)&=h_Y8-#^afSrB`loeas!Y+6r#w4NOD{MO@6o{WTq z`y)wR>H%FRlC$!Y{uqdbGa%=2@Up7J=*|cX{w~EQh7E&c-$f+O`=_hssk`UhJ&ei| z2nd!=sy0rh2KX9^~6;H>D8kvhv4Qfm@As$2%w2&XFpZat5(lR-luF!sp8 zN9%Xafn*sEGrk=LeypOwMkUrG(oKhM_X=dl@@2dtBW}1Nh-7HsE?AL_!l1z^WTY?y zNo9bt(8w1xU}0C(TOwF0nC%`uc8{qM4be>PlF4W@Df(PcBz&oOC!+YB$?f${;_^|( zr-j%*8n>Ze3fGU)6|bkS`V>*X>fmZ(>uCBmzgT$}XJt}h_2?}^+p%|+?F>50kD41^ zrJ!3a)@fj=rzw#<3kzF=M^xSt` z2}BGAk1BlnP$oSrVQV(YZ8QJgsAKFU6~)k~y-e0H4fuI96gLI1laXv>Aa*@bmUNfW z3_@U#oKp`u7(g7uj~R31C_R|}P%OW6gYH$3U(}gjJW?IBo=_mbc`q+7=cu|xJg#UF%je|lT|Sr9T@iJo<>t*foQ z;M$D%Q_D+dJ5z$?Jt{%J6AM=_<*ThgYq2};!a_42i6~~4z_go`EaZ7<*r4&3`?hd!Vw0@L5 z@w0@Xw4|9I{?c*qnmS;$3%!)mhPYMhSXZcfHKB;5#zQl|e6yxIuV&LQ@jMP1#PaZZ zGLn@HNR>oHc1MT=0~7#+aE&1s-etujLHtz`s#Uqe%3l8MXXdPYp#jN}$pQB5ccQAi zuN2TDs{QRdJx(S^J@nPSUQ-3hzdKq}#A*s&hFDFtRgbq>FF{dIP znLb#QZQ3(=b`bUCm&23KNp(v{O}75m?Z(^ei@He|7|(h)o7@xH_15_BlD58*y4`(R zDdMweB!$6x8;yJdAhQjTvY3`a*Oq&(Ek$UQ&q6wC=dWb@SCDq7cp0o&butortGXm+3XEBsZ* za^i>-sjgfwKA(Hs7iuQp z-Oqk?dC3+Ao1-tkt(^;)w8B3}FLs|T<;>RW``}Q=AN{NqjLqggiVQBs-U z9UX8E13B@eURD!q$PX?6kkXkbSv;6&4lcxl?*((Nm2iAmfA-n2?_X5!7Axl$Id;e3 z)M7D&b2HR`7xsJvX0Qlzz#&k4LuU0bv9v+r(xCNU=G3zG3lHlTU4MrDXgB@G+8Fh{ z=W~>#!q+vCRtTLz$+$m}(9ryk=`CcV?3oNU9)$*`1bPp(JW4 z8c8l;l`R41;ZSm!D9Iv}ay?4<-es8*)`Rv?DLJHM39AHoKxbk&9?SVkqN$OR8Sc}tfRU>xeI8#VbPM1TwD{K84%-4?T+^~o{@xnzk<&f-)B6j z?sR%DVmR?fZSs;Pa1nUNz4O)@1D!xOtCn)kOo4gpX%>@Hif6<%dlour zn^7`ka4s4p?TSi4FQ){93&=>R5)_pT)=CE#m4G!H!7|M#Dd2JY_>5O{?w*~o-)&w| zW0%4PN$!+CiAXP6XZg$wjeQN6OMUwLX{G+{W!xv8-bwv7Hq)3DYWiEzSjlkakP>0` zi`Y;p&>~+9&I6Y77%@Y+%W9UFrJ7ME?c($~kW#n6{kswrk#$u+MASc6)G7FNVATwR zFnkS9!-MaZAY-StVlz=`uHZs6GM2O*%U~UT!5X`S=yu)ip4u*2LWr7w4I<5A*x@5c zxRKmjlEvpgtQBdxJ8Sg|UW7N@S}!1`>}ZaeMyK@!$MwsZu$F&3UJ-ORmYT$qOGUS= zD*453YCw-k8^Lc!?xzCMq(xNl@iiK`MVg!(y_X8Sxk66U6rtuU^ClhKmwPyl+ z*J*}D?J^U?uUun)wn&jhasbtI`Mn#m4-?)1R5HK`+%;H&ox?*N84x1gdRnLZ{(^dL zO%06MRUng((j77W@1sXbGKXcMZYInc^Udz`x68pWuEoho^b@mlI~UUWJ~loM5#g|H zfO!?qk~24QaVTjrDs}2*X(Ljz5vlLINeUq3wa>zX_c5)Atx0{g-I^X%InmaT55CTwc@4p9I5o`qDF?nWOI z^~xK~@~Rjt83mTYp>UQcm2_0{)Ju&I%Y}@WRm|n`MsQy*=z7fC@4*PyV5l28_1iOO zz!dTp19@y9Obh-mXX@YLwdK$UsN>lBcuBkrvUt7%8{fz)DWIU5t3W>d5Vylp#DeQ+KUa&m8OA=JMvCFv6I-!g-Sahb-N}NdJHc}Ovhd&pJyylRX4#lr-%mwR)_yG2=mO$H`**tICOv~m`F7Svq7f_;)SkPx+S;@IGhMD*<&`O4r9WZn{ zc;YCyrfNk~>R#}+eR+ziu4!D_nYWz=Fw^Kk+N6oKfHllQpoS@(CGp?!5is6%s?x~G zcF6{I@;_kZr5?BGVA`3P68#C>n|0-T<%Eha(q;CoCJ*^kPCc?g8!qlkn4SHXYhWV< z^V4HHRZmEk72h_M7tI}Qw!1R8tU68?W4MH#`^j$($;)IzzDX z;o)Y}x_W%eHM#np*PwF+M9P+URHZ$PzmP65 z%z&WOgci!PObB%GY_#NMacJN(_C9WdehG2MP!*Ji)6Fy4BT$|Sb^{)6+Yt}ic~wD> z*m>|}cbAwRbR1oEy&!S^YR0*}Di^cvg-iFsIqbY1q%rwUc)L0Y{kAW)?a34rZH#E! zkav#hu6vZ-)#g`s<1nG;$&%P^)6-3`{5E8{=-Zhi4((fw5hWX?iHcFk&yV1|dSqoN z8Y4=ZP`9}XStmdOyI)&hv1r?NDAERzTIZUo7sIwJk`&1J{tSo#<`cl3ssd7(RQ|!H zI&JwlJ^1y-x+iTTCwyGdaN*q-AOZ*7RcAD2tAX|2N9&~RKb`9GUwMG)1rcA?f`!^T*^&>=f8>YDX8raQ2c-&53?Gpm+UQ9JMC(0gNO|~^RNrLNLl(91O zl&$0L|25M&EQ@PM(9m3ShSuvuU@mBsyUkd}l$n~1JPBq_r7IOEqA%4PXU&5p=Zu&iA^Bx$fQ_%-uC2xi3KQfSJmSW32jY*3w&Mw!p?VyrOZ7F%L}jcc;**OTuvEUM zdK0n9shsU)6#mo&rLu}=I*$%y%Gh{>C{r}eXaF>oXfF=!qnLOoqo4eRAmp>C2})fBCBh(SL&hk#>k^y3 zM!!%3nWoI9$J(&3$n9|i(le(*=&n#Cv=50Qwm?$xPy~&Qial!%3)^928H1up0ad*zZ*WW9H*Z3(1AFRN%xdFwV(izSe=BYk52yZxssl$Ks7A2NnNE}1s=Mn^`E#1!-0@qSdyb6>|L zg)_l~KPf$rP0?v1b@e8l!v2%;eP9sb`S8l@HNOvC5wl+}SyelM*|F%W><$_P>HS@b z85s}FTT(&;l%88Edh28&5~{hZzF@7)Gor!`fR1mQ2~ZL!73R{E6PXY%-%3R@FuxCt zb2skt_c+r`08gi>xIfmjhoW}RphmP&o!XiZD9pBnm!!-+e=H-RAdj{Gf6f!Z1Tz4{ zjUkAwka#SR2MIt>*};2D}yle7Q(e06YwU zPv)}?)@XF=0TfmlD6aEmCP%h)+I5vvU+tlAX|kLc7>CKgA;D}&8f?82(p(E!su}-u z*5{Ql+5c{j9uQPFRM9_JS;khCT{|+8zLl?0Us#lK658~t6R}>)-h38)2)U#KoCpSI zt7zsHL83M?K4(?`rEBK1$QMBdd%y;TBmlJs2M|a#DCPH`Dyz&ZDJg%8#0pg z_jIy&N%Bh0t2mX{f3#<9Kt}e&g_F<)eHxK?#*}zw@zzrdx(Q*OroPmpxeM0Hj8j7Q z`eyPry6djgbvI9RuWyybs+!$~j^lnmk6r0rdEI-X743-uH0+JFo>H}=wZdD4exy)z z9M0dT)by$9AIeRX(I0)-ICZZeK@3l2x22M#DM((t**y6_2#90p3_lxG(3YZZ142gd zph}?JOXOF!%1ka&%Y--qT>?c*Q_K#@+{iv|SK2}ajh#p_$t3d<`^sqKnIb?B4@K^3 z^F!IS_RKZSDCz@!CO8XI0m>;}&>LRLsi)@H!HNHJ0B(B%&(h@kT=Myd{`0Q1Wv-Utua_u&9*#8F59r-Hdb!T&T z2VR4m@#J1HH|2pFXlV-k9s?2I1!>!N^+(hN&KRAas9TqLe(z7+5uo*yTZ{i@^=6hC zJc-11pH!7Ib)jc~WpC>7(*Mp%Jc21P%@nub#1kWlwG4ziK#rWiwj1EKZkfdxjK|oX zzMY@oOHR0U9a1L@$NY&mw5Pd{phk!B26(7b^{B-NO>Z9dqRx(4K>Ij0m(12!qH5;> zOYr;&Q{5UN3S7Ezie?gF>J;%*augbV$JC-)$CnT4#DE%9&l#-4%$fEemtcYEf#b+? zI#s6MN!A^Eb`{(8ZH9^GuTz2^y){^en?vd$-3i6W(NNw)|Kt z%JxCFXY-dEx*a;>Z7Ua}DiR%fo_DNtBZiVa(O~vUeG+UoOnCOO5B%hOB0mFhk#9C; zDlwWNrfmD{(v_)$xVIoR{X=|`FMiO@nksw?U_5k^eI7tjfs=)R7KKbC zf~Lhm9q|B=`fe-QVte0#vqS}nrYyGRu?tX$WHPTS4TWA@(s?<xjE*D_;VYm;BY=r(YTcha++JRX48#Ow2&ucC|cAS6jB z8ML$x&J}}5EK%%SGZylvKR8VnZZQXjlctY6i+i)DS4%a49`?h(63%C0HPpEKLD zBn=Gfjv8w?+Nw5~5;mWx)|ecPNw|FGa_;-?g1`lBk<0nPy1oK&O3iVq0L0xDYKZCa zFr0JuoHHaseHz}FAD&6vfFpJB?%WgbT+5LMZo^pD^~7EBa-ZHu&>@76g6j* zh8sdHTum(IY5LPNy(ySQgq?Bv%E^A3!C`z*--;msrya$cudR4^(ue>&?&6$@z-oHv ze5e!gZoPd{+q_=zYGSIVrB9rY4@8Fu$zYFj1m>D1PzCqhue5b5I9x6qa^LXp4be>s zb^fBg_PKVXS)=3wirMyId(vB3fmNlQB^F6Ofk|+iPxOkQ2rwvhjKpV)_n}VCiC&~H zo^BsXt^U|1`&K_w)1YEIDV+1<#lJo+_i5}HWhCweo(^aykqv#W7-1;Ld>WVi6)v6A`N*6F|hYLevlr(Znz6!A%mnC@6R|^ijWiR z${mE4b8L zX*cNvW?7nixDO&sU^)g9__&#J&3@WjY@7d|93y}F?vwRDLw60M$<=SIP82WA_}q11 zb5(-Tz$a)B5h!wA8tx2TjdlGmkjx(obj!SBF#?Jm0FJdK5ladW5X2?2!wsiYS%0e7 zEJ{#GGn@}ZBm`;nsLT8W*nV|3_FKa-6t4g}Q5XcT-a3xc7e53kYJf%N{pCf94K5Z9 z`?{E^ePC9zngogn{Y)vb3H}v7eRg7|jZ~=7{DJ+;F8j;vuS1Fa(g_zUSz?1JZh#f# zvvV}v-9gR!rq_Z%;@*|jWu=jLHKYedtjEBM=DxFMVDDjJzvBD;&1?&Ft{gfGVXis; zUj6wh#AqqR^2DkEdX@Am-XM6?0KaN5LUSfUEvDiX-^A-ju3ol-`ows|tgec6ta$Kw zxyN5OF!FdM=9zdAY8o-`o#*BIfo3pIyTtqv6|?H>0})*BQS97PA}1K~d$-AZ=iltT zk>D+u;oYISVDezEb0RZpCwOZ%n3Esu*O^>m_|?|X;iN0V`oKGODsk31;Nhul`}5Af z@4p?idp0Z%R+{%|h#{Ml0Mj&JEC%4jIL%vu5O^9d9Wd0O+!3LS@KHu!6eO|l)XZk1 z7qkVom=OzT#sO$L4FMb=rMKW1P>mMF0JAv@yBY zv=@o|Xlb_y$_b3m?JAa&&G2EXYNNnu<4Tu>s+)z)Z$*6yFwGzqvTM!t<9T;y`!J9P z4priVaw`PwdHvxF+W7+iV^A$yll^Mr1SoCb6@1AxnLZe8Ls_aa_^hy`N0c>ml^t+- z{oeAM`sx9U9wgAKjuN23$nRk!6*!X8_&fj1WCxRX_ZByvd|ny^r-P&pDOuqsvmd}| ze(Q#Jey{#3oX_|w&4KQ&o`F6L?xAkSxF*OPh87>}%3u=0T-|H!;iYPiCe?qQK!4@C zwnw}jl5cU@^dYn15BgRnT&a0a6%Enb36V^^u62ISFyAwV@4NE|bk6;T*?I^K1UJL2 znSa4n;JHC7J^mCQFk>vWo~_9dTT4fCI`u^Vk+KdJw*_kT?C zv~hEyutv!Do!Pp(O=z#sy&h?=a{I>~znw91zraE7N3x}C^6Fj=pN-sjHJZYI;m4QI zQsX#=`JHOZbpo-NW6qa#Yj)NHSiWo#Smma{4IIz{EX*?+z9!Jz5sbZ;E zF0K<4ABN9Bg2_oCgZ|im9p8u?)IVM`0PP5!B9uv-S%Q|qWT0v!P<3wzew0h%l1IND zR!pOrj_itT?!zKt-#7)&-$YO%MD`P$p;+8^ay)zLk~0fk73UIj0Lyk^;ljKjW1~oz zxD)y`3N6K8A4o`@o*xi8$1GbV7W!1}9hUo5cS(w8ofA3|)G99>UbZdkxp>*>#nRAS zm*~ra_D(zKxCz~_s*f}B23H^w1)fF;3+aU+UMq$8Jq{fqLYK!)a7fLdq6cSpx(WF#emlgWmXsvG5KH^778!2VeeHbWT#!Tj%Dl zCk{S=V>XJ+zT#6|D>+^}}n)R=!t?dQ8=GiyCsv5bVyAy;CAwuRy5!VRC#q;$@&#G_pqNX z(JRk=6Ptf%&0|rx-a^Mao@`A~pzjWnBz3R!BMo@1zylMqp%tyK`0vkHnaG-0j4CE; zoI{!?P1wFxhzrQh(L)}skQDO)zGSve-a9G6XYO((SX*AKw6hmUX`5a1FOa`}#V2d^ zXw*|8KymFTl2w95b?2p1m_{2h*V+H(wOcn(%BH6{c!O3rK zWd4J^^?VrWZ2c6LGh0{xH*Tq0FBs~4+sagtEgHoPfjznuP;HHP5U1bfZ2oa*@ z+kd}^ARs=sZ5iId^C`>nlB6e6l&{X_J#Q!P6G6KP_}pO$1HUe&v6>RDdv8qjJ2U~y zTM94G`hbN>2tz|mVar%O2%77eQ|SmKwk7x1-+f?9I*YV+$i>0o4EY!dr-j{3tvTr z)PXanPv{GM=Qb65m%m1Qb0=!BJhbGG<7j^tt2W-9-7UgMDqvSV^J!X;z+NFXDo-Q9 zm5R+H>Ag*Erx&E%5Sw)@G$ECBxR`(Swe?T>81;y5z76JzvoX*MZBGjD!xnk^(-)?U z9v8%jbMrqcAmXUpMkO9W7Vh3Nyn7wbe6f-a+9PkG$|i3+V7Ug6Fg7~K`gwexrwe&l z`I8l2Qv}-?hf-su4Bv_D*=6~{9N$Z}M9G9M++B_>8HISvfHU_+rn35k6$d1&{~d_! zjy`n~9km-T1}%km9=#@KBCEd%ZgNhSSMc!Thny@BDbaso@D^wI{W~a0 z!A32ky{6N2yqNS7*?hR#$%;J@VNx(txhAKoEB;D0a^NpIi){&1=6$ z-Aa~S?3&m)sqxgw+6pz!rT$a(JDnY#frFk5XtIt~J%--Deux)OM3W4lygXK?HVsOe zFF#E`edESciP)Dq!f4kc9UA_cnlhU8FfQafOV4uj-B{+#UJf53#c&UW0Ote)0(zKY z&MU=7J{KK$syqU31HGF@+#b~DJJ@wmn0wFsb>7(@J?N(#B*h-mAdGF8ybdQ78mUj6gwx_hJ6esIatp6D}&3~ zK3$ePF`bfxAM`eOH=;OE&{{M-DIVePt<5u?ZMZ)vsnJ)BMPJX11&5CN6wx(?Hdy0y z1ILJRDE)84mQVN6BzaDaoLiOm4z#Qg{a_2#OS}pZ&?#p-<1VPW?TWb5-8#~*dW^MJ ze=Yv7GW3ChQ<}^T_ma;M9p~OxX2e9>&W?@eS~6EJ?L;5MDG7s+Y9+wwJK^=71z#H5 zu7Cb`kQ)w!iiRh%vUeL>#3}}42;ke$e`Xdt*Jk+9*s7>B5~!?)9-xA6I%1S zzRB}6<%;SP7?3j66+QF$mt&XVWqYR+pw{mPUUw$zJQcy<+_wO13hkyeBFT1cos#7L ze(dz5yUQ8fG+B^3PCO)fSwzY{=X2KPsB|3AsH-^^{%+Zx|IX>VN;_VeV-CE%>Tezu zSOn6(karFr={+;~5WIim-amW@*GtiDkW=01de-(BP!&nM3J&$F(+$$%W% z`~ub7r)B}5Jsms<%|jV9u-8vAzHEMqN+Q-K+3XOjt9akEFW-E7I3n?QGq+rLPX3!j zW3KOS;e!6Dz#$laW#TNM@rztw9FID4$x#%qt@Ya;jNPqe7C zC{>jE)*%fgOX*ib!SGJBzR6XgQ&XUaZM+-z-e%oQ&kV5yCpbIpLX^!xvY8@drPPi4 z&WcwP1|OMxxhf+6zHn%I)E_#HX70Y_oMD_eWyT%I;zk)uq>Z0mVQJKP$@piA#RJJp zODsFCEvk6dbkmvueDpmQFqvH2%mV6RDWhFs5x!EMnNp$ivI#@&`)Bgd@lzD$LeoI;j(7+%wn8A#vjOkLgC1lj;=Hw-f0XbHwGZE0mj$>E<2ffDM%|$HjrP# zTp#o^!ug(mz;L1Xo1*zVgqEvQstBx#3X_Duxo5{iL{_JT8_!)-9WfGG5e^DPT+^US zQxlV_@z7mF=sgA*XDrT3l-m(T;z!^kpRc8U7N5jg+!pF3D5~d2tYWN z>Bk_cEIPn#s56s=jZUsOb*~?*gH`_pN6g%Z*c0Q;oo;CW(b2^Af1ntEfYAVs ziI1T=Vw^-s!mrH`DB(AQ_NG*CN?m1ea!EJXl1k)XN&8J?&lD3!ecftH~i9{}AC?qN(istZU2AL9*t=xfpvc!oNGe60P>Fd{(n88Zb8ESozP zjldeNU`yRey-{}K`U;bYg8ATF zg9t&aE$wA}<%B$Sv2#;Vyr1amiOoHYB@xV_66Zt-Oi6neYpmymU4vhv9*U0r<{aS0 zoy*wz+6fP+_9KsuH4E{>W2D?^Ghu)8DIR-jC5Csf+mB!lKW!0~dpY)U9o689DOiEr zM@%^G5XC*@xLoa4VR45IvRS!7tWC4>GfimUJ7ZNP$cN;Bnuzh>u@a;(fQev$ko|tvrHwkkt+5LaG6Oi(6FC*YV3K!GEenEl z0vRxlbR9=lFhKVJlrWhk(+f#^h!7uxx7PQ~ibe%-VQ02Syc$N-pM#;rp`Rt8)njmE zKM492^mh#e{Q|1MziMeX`TJxOK#i1SdN+;KV^zPfs8cy>^`c*VLC<^{eETqadwi&o z`x|s8wLzdCBkyTYBC9IDQbv_^l^rZZonO(9>z`SPfzt>+84->CR?_hf&N`0L=OroJ zGk8>h43q>$E>@>G^ux*IZ7PFq{ZK}M%JTOD%Wfm3fK2%$BSB}R^#-K{;lGXrA$*=^ z{9aGW1~LnQ%ql<(Pi7I`_$gBE$3h*K?cdql`ENT&e1Aur;UmXPNOkDns#W|xyt6&0 zAVDM}x7U%t2Fm=~jFlqvFXgyeW8`HH2ncPeqS*ey&Xh@?z$u zRkYs3q4}M2X&eWeO|djA@`b$vbqT$vfDTbKKQ2`L`n!T1-(|I}piRHQSejh3bK0Yz zRXY}{1Z}c~gj^JlsG{Be+Wr;OG8UH!cWZgMf&6=p0scS75rjLoTp;v102>V84M|RjXsX6*JgblF zm&fXm?L(4p{Z$?f3k+2*4^956=FW;ZlngFrfb#M0){-^;6bX-=nHjEc)BqsTR0uI+ zu1pWzYIeF`-{bnd>pd;rybAYAj6B+t48~io$G149en%O5pv)9jtFC)GHnOJ1t@-Wv zGiLCyJ7s>moOcwsh4qAdKwPbQ$10D#T1A9C6}hj9oKiqc1nnBJHQgfm)&DX(c)^*JK*MgXY~+ zf1;L^%`jBacbS~l{(xge*M#?CWytg3wG~fE{sZSIL!FtK8~TPCv_AfMJ)sD_3Fv9D z#Z7GRfxa}@u)d-b>nVxum$dKib^wcRgC#I6+y?}4`A6Yq7V4s4Lkw7q^dRrk*`J2s zpBDWJ)p-6NN)$*7#-AE_x<#SnAW}>@YTzu^m>TwRGwgM^_*RD^6A6CH20q4sitkes zzfmy)a;JHy63`ZkKh->lAX$x%Q|!Ejct9KI2)nX{osY1U?HAwjSBU5nIF!qZH#BFD z9E*mz2t{V!Yza9Iebzo$TU3WyQ?8jQ5N*1y*??pr9R)g76Vrv*?_X~FsSZ=%Uf%)! zd1VEDRh5I5QgVRerH44VGsux65EKlp-ah`}CyH-0?T;2|tAL3rY6z`)a6c%5q0@A1 z6(pm?fme-zW7HdE&GLAu$M_$SiccZ~vbmCl86`G9KmmYfBpxH&%_0ueRRq4uX6TN0 zJv-OH5`YH-s#V`2A(+!=)T)#B{zY=tyRgkrRI=;uwA5u@|a|mQVHdkk~C|VqdetiRwu>EybuLmU@{Z#I+_q8@8U7g!U z&-a0Pa*cXdM$h`3I^xHRfLq!*4Ca2|H;6Jxuhr(sqDy3+yY?{eK(L~wv)gwwL3wk% zp&K{iFA*UE5tN%Z`f|9aIxv^;*9NSyDAO9SfXhdSDk zy*u3o>N14gb72V&V`J-dMRENKXo5IYLt-6_u?JJ#36cPK=RYOM>SO0;KQ-mQHT}ac zV%MLI=U{X`>f>X3g@*Y5b~-7CXWgE-u6^|J!H`og?~Rj!_>pqs3mCmfrTwoq|6`KJ zk5x5Wt7W+jCDm6+-{@p!xf^Gk*8AKnspzDYEjeA9D#hvaG-AWCJyj~F$}C^ey*rgZ zkjSZEKwS?$)_p?CjCj<1NTD0lN+h}horQtXAru{901E1}E7MOAIrkRh8)sC}l7XsAxpy zWd$cZN*zrA+!X1&C}PQ>8KIdDk*%uTo#Io%3{x4(3f-<9t1!PBVF0@m--EK zU$2c7PJ|d48!NAxVqz@;qOM>9A2KaTD*EXnr$1NaTz z2sjz;6(a71Gq~Oq50~ z1r)Hu_2uD@daez~)j4`&X9=ZT;~YWeJ?mZ`b+CV&SSqY43;8m3ea+r|Jf2o`H5 z*EcR?Bu!_!nsgGFV&{0ht>S8sz7Y|ygv_wvk@0Axlt*nc+8pTMa|Zl6C=&aUra;t* zmbd}Tf+IBD6veE!{sSEp|x|YMJC(TcVQ4iGA<#fxZxGak`9AML3WVT)Q?wjcX)T^^qIg~NgFYz z{ds{v2wBn=KLwj`1FFdRB&|_0%+2taB+3o(nu)PpzjOFa;Pz{u0Q*7Z^8xYRh~aUrj=&3zNS0!8sV;ZMwc9v&Z>`~2^j_IFmBUfmP1 zYvJ8a_cu$+8aa`P+vx}#muU;!t4WBW?XTCmsG;$^DN$Rq4X}yU>*x>7P#>*GY|;ja zU$a_CsIJU5F%+Ut*Wk#-C+#mp%xUab@n@*?+bHV8dm~bjB=$RlflUCh^b*JBv)Fxm zuGbfP`{(3Qr558s)YOxPHA(hkh#^C^wQDHEY|C^gKdPrL{>GUeLc#9-p1O~K*T9qGQqZz zWuXnt$f9r$@v@-BFfNNQ2~x+x9VCv0x)tN-0+Xw^(Nrx^T+pW6 zmW@z5qzC3w$@^|gA;~NnhC%d#8{V}Os3WFC8G6=slGL?*1w0E2mS9F*#sYaK7$png zO_=@)r~)r-6)+^0*GGc4PAly?ItV7h_JW}1^?Y`7x& zfCA#;t60`@(ZLMVHG_+BI;nplSmzlsVM(pcjkqG(?K?Q#`$3z;n~pw>e$flibx3Nq zk{=7^pLi{`i<6;|5}puC`XJt=y`l7l)=PpO4AK~)9O?AvZ zupJKe67S1UIH#$m|9F_)GwUP*5Ce=WLS!4>3__v)%NZvr2c+j3m9<-4#*eKWdbm;e z4op&yP8ErTPWr8h`c*aiu&zBHTldy}dPZRri~~M+d>dI zA5H~zCp~&&vg!Url_J6p;ET(e`FCTMN%%32jQ_H~{O_;NP3lukG2C2%JP(~h@yBOd zTTVc{8{MBBN$iAUq zW-%Ed1sQTA#rX^^gfo*f zfRl(LP>AXF7LlWxBC$wF+zrVHe4mT~UBz{BNvs%mD6rB?QfugS^<{l83mEF4k&%mD zjI;IV-x0O)-wS*?XT_)MTD`vSIG@?}dT`>$SNBn_igD%2X@%uoTgi1?s*cc^pyih- zxC|uAQOOflaKn(jT8QNBWMFq+g5y>XJ5S@|k53d7*D0qW(mOn1EkR6sX?nk7Wc0Jx z>H29c#Wr?7I=H;z`TqSKEHSoB)qt@Pu1Err@VBq(aZv+as|g`C{JUCpWF4s%_Yu2k zhP^)g&N%Jwlkkl0+5AO&T&wYnPVDlHD~qi!XicLDIlo?;d*3dzycO_%;=-GAy|=yW z4|%^9k)s_k>T>HHOV*X6pB6RYtWnD>o+$RKUlJeWZK=->%A|IjeLXgidF}A*PT^|X zM?i&geBcx^Pk^tzL&A8#fJsn-3i+hfc~4&4hlqDLmenk zSXMD8;2^a3XAwvgTpwlJ5=sfP9mKf5aO?B;8=$)fH|-Yxgy#>po=A8{fS%L0MV8}1O% z28cXr$zjE0zLgNfh^27_KV5c-OJKme0kwEq3(yA zi;1_V-nI;fw)v|X=zP?^@jlVwBVbbb!Bq+3pxHrs-+B2!5+YeIVN3eF#~IqGGYK`f zG@93;QHejG(5xLp=S=VheuERi7sRKRFtL$}|47Y*sI@|Rx8SKY@DX?H%_eM)Ce19a z>)iNeR#Y=4&0Gde*sY@B^)R2daDQ)N{yOX{g+MPUqyOZf1c{5pSdo6}4l5mt6XvQt zt#+n_Ucd3{^wqDvs4wp*BA>@aAoSi9T|xUi_)(#tL$n`BY@xcFLLp4_sTfScQ&sQB z!mo)UnFl4gpklAeQ-OSpAYX{6H}EGiPX$)>J(UQP=tD>^_ZJX_^P@2@*c^cNqw zFWov$*1IvN&-%bmyB_?gkc2J@_j#vQ^t+bxc;!>@=E>bu-M{aMSpF(~mo{aOgP|*# z->EU*->rdG@4!e=7-Jj6^dbIj`p@Asf#62BVQ9~3BT`=!JGg}bEW$>DYbQ=PzL{#;<(bqA!W=%@ij+!_Tk$n%FR4?Pz)JU2XH2U!g?beR7 z(<{0Xnymy}tA&Vo$3zRkeZ?OxacN2$QMHZ%*1C3ppzQM~7meC%jmeG;kpXE@rAv%# zwb@W!3D5;8Qlhb-j%%lsDAi3U(>5YoF8JF!1snvo)iNCcF@`HdMJbFfWNmGEV*cuXuGX~Ny{%YY1?yGBtD2MX4RzX##dl$M@%V``lhE!L7I^;=xcB;^RngUyc!E)7L zm$c`LQnm8a1%AbQOY@`lCIx}q*QYgn-yL#)|3m>;byLM$`w^zQA1ZCQr2A;r^(4e{ z`diGmzHWSb{`?uVU|ap5rcDn?@FkALyusnz9^+Q_ZGOx$eg_(g+Dkw<7`kni0hTrM zSLXAOt7yvOb+90&cOxpy5r^8&d_)woMbQVM4}!f1LEDxb$IYBc(IIC?&g{Xl$B2-7 z(cc|8ebJAHaT1RlXrV9&)&V!*fJ3LYj5tJt4q2&YIT)*_7%smAIub(A$ zgKwVtcqyYfmRnCc&anQXdin9Wd#6K9g>>XQ?gTq;IO z;2$7?_VYu{v-4rj&Xocu7Ffci0OUr&oM3Tb)an=i^s&TGw}8gOlUr_uoBS6_u3Z>7 z`}z7kOB~{XR-^T^O|OO`>y19YhCWf}B}@WqEE2p!ab)QX+VU1yziDQkK-jwvj>bEN zNqlfU_86ScOqp08bKajm@0bqQxan(wsF0Cb)(Ceb<9Fm}JHnnn#2%rTmN+uhD>Yu* zWvjEAbuAKXPzTo|ufE-NthNX;lAs2 zMKfe%I2#Hyi2Ky3JMJs`_4=g|wyKBk^w;0PX`Zon*S8Rp2$|C6W*G2C8TxOnnGhg8 zvl>kdqFg4Q|Gl$ehb7J5YiZQ1qCyTxO6m{*o#;o`1zp~bbnwkfL;PLJ6i=xYM66t2 z`Pe^k?xIWae{m;ocQ(8CtDKT-{*rsy=Yrz935mS(;_WtR=M#!#@%sV*AXXaAt%7Zb zC~k)w4s~ka|LhkmwRqY|VQ^WJv@8{kCeH>lw^l7v+%UaE&~IfW8UBA@w&5g}NsV~y8R8#~gESD2M_rZj~ds}fNO zi5xzrFvd{rYu4U~fF`sV^|fG4=>Hr$!txL3N1~zp=mkKib6Aj5nevZ!kwAa_?7RBz zj~z94o^WQB3YLZQ?n$(VTzDuUicakbC#-K0s!6v?YGJHKoa}rdKUVf+{7Rl9Y+y9H zMjS8g+*f1$>URF~ny5aB_A0T#qS~KTQn4KQAkJqD6#ipNKAIy2Q02hZPkXAx>AyZP zqe%53h*h*&I8c?`s;*HJV}0PPcXNC-`KQ&d0T-t=)|PM=Xejtwh8?dDyI``}?uB>lJ}&fvOjX;*pW$l^khmC)&V8tfZ~mS`sGm){EpS5n3o?S5`-d6QXf@cI__I5 zxnaKuTMn9BdwJ*ek+GClWq)4@r=t4hm-eZIA|S7m-z~jJK~=mCEE*=qS2^!02Y15A zJ@%;5*DJ6p^a8Ep(~@AfgF?a3t@p?L2xWd+vi0HJiDzD08D845czxSaw$?^w*1k;I z@si@VWf*r?Q91yCM{`ntE#IO0G8n$mS`7s@N!Ap5YY~DCn}j@72@;kt&ZMltIJ+JY zj0ZuMD{7aFB9rY4Qu&52V-8X6@yr2^n(ZW*MXqFa_8y3@m9ln)Wv^Cj;V~w(1!Vxe zM@EY+_xuNLmc2{$qHTKOTrm4=%{W&{v}3QiJ8v(4xmV$~wc-f1`MhK0#3nmQC~nu0 zgSjAzJovEinEix;ZTRX=8`oh0uu+jisvY+-4EUg@KA_vM{$|FD*uXFh^o@H9hIB_F5b0{|Uj@u`yuY6+wiI7l-l z#w;lv~f?Qm5X6(ZKjq2obOP%)N<=;J5Beem0rP#cyQ++otyhVehS3e~W* zjiTey7;>)B#3=~hRY5~D3ST&)Six?h&PDa}iDwC4CPVBWiAP&>gufkfiMYGz*W&;1 z*xwTppI&suhpoR#+uyeMFd^Tg@0g(MU2jGd`fiGpta$j|uGwWF(_7&qyBQ(G!v`yR z9)DRsKH>WG%z8qV(Tvii#Lg2_jeg^T@SAgnk&{L8=02{eLfo+KG^0bSE>rm6WbpVc zLS(+O?HKHn?V@I0<@$`0;>HldWBVg3_59E8mrzP8xrs;(-H|*U(gy74OR{7Bjoq(C zN1d|+B;!BK)&xIY9LK-Zu6ERYa~7V38%TdIsJL!lEvQ(unOC8s(Q|E4MPpv_&7~(s z&jpoPn^4@9ETNT5S|6mIh3}#%rpgC1AqOKW&Zf$oxbdN@^lEL1O6jrkl4DA_&1=3g zmgn5=9@ei*2y@Y9xS1Xet-}q37x|wmk>nYq+rpNS>v#u%byPM{hAXUTOVa9AP~(I&UsO>ZmUo=Cs(;aH-UtTV1-812Y0 zP(2>D_(!EIpznT+S^bBo7*05^{;iDv(e2fu5z4Y~p@`tI%>6Oc(W65W*5{IqLaS%y z4o7!*69c|9*gX$W8CQ-Ni@BL4VQ9Ta9Y&EkOEgEp@J;}#E>z1vAod_$cD6PIw7s4@ns3Dg)(nb=J zU8h~}+x7RxaoFyANN)1T{*mvD_0#+Qy28y09GSYD^PKJ681z60HFkc#0&msW1S?0r zu*vI_TNSmFnkIAi;9Smsek*20h<&Fq38YU%TQnzj2`{r#O}(x(s!fq*S!U?C2AQMAPg`1~?C5QnQ|g{k1P&sZoUuU~K$+s-Zg@P$LLSfX=n zF3^MznArAYliKvfwSwP%s~(#*tS>+cxvf54@kuRKJ}R}tV$k#UAA3Yr-N<(`MtC04 zsV}4*+lp5+5L~C6Q^|&T9o2qoBic)3DrAKq?AYWd{2esd=4OQXFS~dm4O&_eA$5Eg(y+F9yWYrHWZ8(hNzm*Cmfcr|ELqx?EK`MJU8yv-Y=*_ z&>G>9W;4x0;ZbG})0dK_vEoVJqRE~|JT>w<`AIq&o{i3>5--KOYrlt=%DUKMWh8TQ zMYN*U0!CY*2UXN-#J(r_4siW5k~Wm3b=o0T+xAVHntuDfr7pM2bp09pU;d6!z38TZMbgI*`g>!fp-X!!MRQEg7T# z^$od@-0c5duR7(U_aM0TT+rUPU-H9;l)u-TGsy|DS6X3I{JD<6ZN~Gv{9;p(Ge5$>bIwqN4-6e_`zm_~;Hjnmh}F zX!@yfV&f(QMI4M^0Rni|v)nr+vrDSlyBzu0*s@XKF$8blheYyhQKU5mnsa#I4+GXf z1Y4+eXGox2ZphRv4O`}X z`W_y}HzYM;BYPq%OY;3&*wwfLz!!Rs#H`e-{Ju0jfX2hHy86vF|A_t<^gDI`F(wvJCN0)X^wgzM@IVd|X??mE0qXw}=ljS>#_T>x)Z<`_VP~E~#w(3HWGp z9$O~GymB!&eZ+22a`Dq*f?m!N41WF+SNl5ovnLrD%nsUpB0u=y>OaA5>(y6U9|rB} zS22R9{meJo%etrjWRAZ-m-NwFTgP26L~oWoa821Q?c=iF#XU<_(f94&_BG!}a5W!= z-ww~`|2-@gd~x4qY@bzW2;UQl^Sd0;(+AGGPDh)a)7_zp_P(Q8or}7EPQ~7V9uzK7 zcou%)5WhVM)LMee$3c;gA~K0k`j4YoIH)K}yB>s!Rz^15g*5yC(tiLsKL8%Rho&X( zA3=yxp};jL8qE}`gqGJr6W=+=_eHQsC$2mLvQSW!uA{*cNWEP~Mp2|J36j4JJo^SH zqL3oAWV0>=n%Dom1gKXcxVg*-UONPB8?L+q7iJ?g+aVcL=s`rJTGvr+DWpQIvrlA- z7zq-MatK8^-2OrP_eT`Q_tZwGcqo*fFQwWyto-%;*&h*Ce*Qc==3t)KCz|;kxE#X4E`ySLlOn&` zMRzG-TT3F%BZS}E$|0c=hi3BwXY+qoOaHMg`1M7XFHGVG$G+!XJ`cF!VWDA6kaYlv zrtyO)ByIA4Qm7&kxqcdY#TI&npry}KnYttB{e5JF~JK}@~l{Sfl!4vXB8f9 zmx$>jw{4JR90i#?WNEA-&mDZ!C-*yo!^g50ZcP{4qsp_Xhrl&&5yw-BJ7h5GZV$s3NdPNn6qyI#w13A z4alOf#ohZ&m7yxsGkhK>I6Wr(EmkDNSdfHviW9rqZK$BvD73^@wP{q214`lnF%(vg zgiXo^OuVstaZs6SP`@<@62-e6Y;agcH#Zq7#>HC${MJ+-Idy#thf`-x)K}b=aIF{L zph=uMp?`F_E_<195FBQ0Ltu^jIpP@ufq93D4Fk#_&~ zQpNE?+sWp(-s2K~WZF(-w%JSbUF}d_lezJsw3VK6Z}WutE=@?AU2e&&TS>2T4DG6* z6Fhz^Rh(7H(!9TF>i5r4coa{@q`?C@{KvLo3Qhk^NjmR{UwRdan}Hyn=XN6!<(cgW zo)Vf#RYX;5+-_DZz*QA-flI}-suEgN8K<<2qgGj_Ha}HUBkMeARM})M&#dfj`vadG zN0e>D1)DVPl|8_WJ-D*;Kw73pR-?yKKhO)QCp-wkEl7>Xw9P4-T5NpFBBsEIb>1=@5(deI#RRo&M z^;)bvT8_H1grvZNm!B_?)hjz)9C1ha7JBni2WO6C z;zZW>-`f*ti^&|Zf03U%K63h1+kqeXJhpThC48FJ9!26uX7amI3(aGZ=I~1-^A3|L zWN;1A*keq+vP1Hgk$iLKkD1PV6m)Cu78Q|lAC}5mY9D3E75LpYPey8zprxd-+MbTO zXsApXRO+Il(l(sO{L+9Y&dmY0A0O3vbtLFMBB%r*qKRNkw@b;CRAyn#%pV8ab*PZ; z@+8u(62T}U{42XFW%KS?^Md?8`6igQ^o6@`$0R2x0`HtT3$#ZcIgkFle-ywFotWf8 z^S(>(xwN5$r_w*#iMbK1^$Ai}pXQI3zuPZ*j?I5v6COx}ADe{5$MT1B1T!XUPKD#9 z9vw#rAU>imY0wZ7)d&gv15T}CF0LwnduH+g(!v=jbpk0{id-sFt7;Y;(d@QNWIl{# zKA_G>=*!cIhzHy7jLNy0Kk%SHq^0~Ue!QlLid3Z`3)*?4tlF|{cNwKe>!zUANd-D? zM*kE4|EysYFP{Sj5=9SbO#N-{%6TyL+kEP~dEMT}rx*3EKm#XXS6h>kILMRcFC9eJ zIeMq)KFWTX4SX-(^Ph!y_lalqUB7hdBd5=z5+*OyZ^?m?i2$LcX`FlFl}6SpLCNNW zt{5hznH~!$v^QT08qJ^A7%5HON7C&`Kw9u(&hh3-@IHgB=epG4~d;_ z51Ky05oFNT7{DCGa^^s!;sdU=cc7Ee1Og+2G&{1XNqweCLKd(~@_BeG#krKNHr@NU z^4Y9!D^wE*oX`G5kw}-DLXnWagQWz7Kcb#3$CbA(oDHh;#_QB5zY}$s@+P8=|p1(h}2Q*7)$# zpy8d@vZSG&myL(z7DsME_pwnZ>LSJl5uhdZ>FTTfF|Tu+8{MLtQQL4h4&rBx^$#0T zYsXqVSlIPhj9VQN3hCdlMC=DsK*J#?*%^9zIEzz()U!w}`$$ zTRJcIB0u|)RNIcwqELm^)AYsly{L^$g))ogzy99-Ikt`XXFf)DCqeJZ27p?7h7347Ni}8Gu|I{)PcGZB z(8}($2#?^~5^pz#@(<+HJj&i@pGrVtYI_pCQJP%uPahpG*jbq?lQal-y{@%ZwP2dR zc;7U*XmUsY+v6fv4X^b>xr`6fVifOaX9!E9+D#R8+&Pz}spO){sbGa8hiaYFwCe5* zu7fJ}>iXJd9mpx98`rtS>|}RiV`~GA&jU8-jhY+qHz=nRAYr~@xoWw>nG&!%C)Jk~ z#hQ{H0&XlyG^U_mH+V(^s`vNp&zv%yfOV~%(3slMT#JLJlScFE+!hEIHd57fQ+qQ| z`6aep*<~aKe7wZJc;WZiO-!6`{xzMzpPv`|#_c4n0xizUO^pWZYx{fg$L50?S>46n zU%!`M{gdVl#WC}w z6h0HjWg5y|j?M%fQOh(jlF5=NQiK9wfY1v#h>b$*Bm|T=PVHAzC)}d*m`5g^Uw?2L zK$vj9E#>f$Ogxxa5fq)t=eYC*L}OTb5OHJD(l7`>@=$OQ6zFJ^5sk`)sT5FzajCmd z1b$+t)w+bcpi8lZ7{yaQZ$EfS;qEDY>)QNbb3-hiACKr}pfnCtIhubr#9t~p-giCm zoWR!XD_5SwpXmGPlXr2F!CYOQ)oCN2f+f0YX=Qh1vY`ILZYVqm@N?FkD~5vY1BW;o zDfYMgS2bM@seNQR_4~Wr?$l2Qbsb19gPl)}(_OATtvIybZ*C77e$86s51;0+p=pSJ zheRfbjUMRFdUdb&2_e8uLhodNoAZo)$U~^#Mvk>_@)JR`(BuPi{szas`}lD)?YzTs z{nrrFn<_WGW?bMh2zk%E<@cV&mTUDTlD#_!lM<`No2nHdpXTpfKRk9}-T#7t%zDWx zGD29Vv$*ECStsrphy~7!fiu<9gUm(>FsMgvvd3n-jpqVn9Dv^eu6{DD)j=!H_&>UY7~zBH`g; z_+Uo@gt;LU15=v*t4_qW+;{G~s@z>Xu##&Gz5jlNI`r#D`31c6gEjYTk)v)$vVZNm zpV>Xu^JUfJz|?1cOGB%l4Oe1%_u3Dp_5RsNZc8K$WvZ6xX7Bc8a-ol;s%iG9*mg&x zQs+#+fI6rLK{R~Bkx{o6zR=K>fP-!ZI?IBpgpeb-A=al#6xsoCLn7DN4yMehD04kx_qpnAtXZRPs0sI6OM5r{ReBH1QW&#|v+qSLPi&r>6 zKbUCO8B|#buiye5lGlo(AdXTyU&891qw@E-b<1w{2mJb$i^RIKqYqL%XK?2#EEGIjkyUoYXS~ z)T(Zd`r5yPRP~+|B+I$LxDQB0xO2+~Y&KRzr~K=JF^vqz$WU0m z?_;IIr1Vj0e_kOd+(&E_wC{94p=AfXfSt5JM5qxh;rTvbnO}#JB^X?MKivo63@6l)TuI;z&fVF~i0e4`x*Iw4?nD``S88KEj3| zg@!uwR#J;dWQ6aSsZAD6J?YH4fFmzyIVomHm_NR(V#a8@AdFQ+F&#_=rkz@}F_D>M zght$SLAMxM|70WY+70TuM?a&^*tAqJpf!t5T&#Y}l(F2V62Ia9wmTJotm)oEBZ2fg&eL=rDKMdz5 z2-#dB0d{Bs9=nPoUH@qDM;h(qAhixD*T`{9LFcN9%JJ2@y<7PY*K2hoc19_`ZDFkSA%#Edp;7~x z=(1hA><63IoFZ35%ZvG>pKI3FDrxI&(i51Jccd+K}EzHNoS>ok*Ipq|^Pk>B}N zZ}lqCAaT*4(pvMZyZ_aVU)*5ge7Zl8;%PE1Um{|{L(}G;EVpdq{A0TZ ze3DiM=PYU-op)c^=?aoDhiw_w|8vis@}CiW;X}~ZX9E@ki}xrWM%&D!G6#q5?y-LS zTKpNk_|MLul1!i)ihdbL#fep-rNhlqQQN>wBAbt{mMehb75=1iKsX5k39f}oA3ywn zwvEO=W+LE#WEb{U2*@5JD4Bk+dt7%YLu8Up03b-Gr9KHOHh@m3>^5=k%jSAfci~b? zQj$4ZmvFKlQgWtBhH%x(WG7Zrlsk#dm1A{=jn&@+%jj=?L|M|Negd zv^Pt$@96fQUN;=5{}pOlEWh7`pJKuf3+KS1Ng=4zFcd!pfFItm6e>tH@8XM`=a4fE z^X3tW^N5S{Qp?Sqf-_f%rG~FOm1fEivtbXvBvhz<$^J&V|9qT_zZ?sfY?t;_D!r)R zlD(Uq>3PT34(XSlUa`$0tRj??j4H=fRl$bT{8W7sG{C$e@BtIUR=5rF5&(T~2Rk#}_*8jKxCpa=^z%K~lI0cQ$bL`omkAaN}N?LvgKoJPB%=sds} z1K7E==Q*r)pq4rsqcn_!=;A~^!Y)*g0yR@B^g&w*wZIE2jnrIaE^L#%#-;IwGKvCnG%AAfrIv1h^5k>LZQ_8(b&WOXOEKiIcuht>3lF9t}WUoC~q`>xGemh4%2UUzb8 z9$mx^Ek+f_7AF&T839x)b0Xim9n*drMrP@esmvf0SWn;qrz$R!Fx!T)=5K;uHM3lC zpj$g=>-g`{7j{3Dn1NK#)7Irz%`JP5wLRzGKc3FKkK1(hb|;NBtXee&6gP=6DL4UB zYO-<{pV#K7$DZXi@?*oXQEmx1RJ=zXksCVV^ms7qae0DGx^MR175n^xG^*F=!54iB zd-a}5{a@Ejj<~w{d%4YQN{?rxs}S70uMgo3-3k-jd^1xu$xu^HzmYFANRwU&rQ2@; z81_9eRNHC+;Hz)vuteL;2WkswWDfJ@dx=CKwgO^V<*+H#h^hgQ-oHBL@*uMG#4+1o+F=9CEu*q9o6eYT%7&kD2kt! z+p~DLx%mDg7IzM1PQG+?dz^)M0#@eF0Z*wfHFAfCAM4_>|`vF(8N~0TdI8K>7T<){xir{w>!1w6nf< z?QIEJ_u&tF?jH5Me2KNTo^w%6G=I+?tvtVp8y*?!$#Ko;JnG@#hv#1ZY9XC6EPY4e z9<2KlM6{4ItRTfhO8szWX^0De*##Owefo^t-LqZ?Dr^CuJ>n}D zmGBGW7w-dQrh{uEn^TL&3+{KHWl7cc1tlpI#C!ewFngYl<`j6C$Z++#E}mHU*t>7` zkMJCY;C=qi^MhjcyD;wyCh+6MsR1J?L?AhU=p5t=IwU-Ury2*dmuxCQ$}ML7AQ(Tj zL>>VHrNCg}apqJ?&j(nMeuz~yxK{@5WirXzDJFZ|6npkFsmpe}g8}#9{kpt^8>s$w zcn6~aH_S9{pc|{L7*hoTeWgMwQ^SbQ!${9PT@Q1W=Z0In4qkt=TX@(NHl!=Cq>+8N zL~dy3BqGo54d3{y_YjBhgp%)93zAs$nS!Rp)z1>y@vVsOhDE z&OpiqRw^LPFd{LOe3J=MFYT*De_NtGU?cJ+s`o~xX#`pQc-tPY) z#<85b#`mVvZTN{`!M&7#p_@~zmYHFr1xty2mOU27XMqN#4THBXDX#?hv!!vYCM1%(Fu`)3eE-8pN6y zh#>)3HOSRx>mZ6hyJL!TXC{)V#r^I0Bp+E?^(AR_?Th z-Z}S}do%ds;BDRd+*tEVJsME78n}2ANzoOh=oNaB)HMBr@5#6M?VfTNTk5IOUtYFKvGWAb?`R zD$m3R9B9VAo_-QpHoea8_}U%*fveu=Y{GWW&vitp!RXSWx3vcx0O3y+lT z`zmj}`bCkUPhsTFtvMyogjrzi)77mc+EzT!`61@j*&_bR-Sr~F`2fscQK3WhYxJTyhgDO%$4utRG?mXgR}%1t@L5Sm(`(~YdYmUDZ45T_j zdJ?co{w=Jyn&FIflx@7)q0mQJDyGAe_hOXCi*ycaXclJ6nV#L?Mo#x!z?Q3r>t2Bh zYluZ=hkoAvblXGdP3AeRU*de!)(VS6uQiXl1D}_Cn&FKv$6ua}_P*uceAzA2`=sSX z-+Mt16VK@c+>3ZSEf}HdRvd6_a@&6pQB0*~s6fJ)zPZZ5Sr@hYXEi-;jFz5Lp016W zRB=m=Kk47;;#nP3LipZauzsy>E??qTMyHxyO>mafukMrPm}RGb`91Ip3AuGaIg;KJ zS$+o9Ze^Gc_}4CpH|!s3^$l+cnzuV;Wz*Zvxz1a5dB1J?q;XH{V)v&fw}U?_+?-<` z8Mu4U^qaE2r$O8X6YI8KurhNQj^E9sF$Ew{{Mha`;p(V%kZ`tr2H%6tG9zO-BD%rZ@ zSFbB*tpIs0?@Sp51ffu6oJa%h=(T{E<78wGgJx>TOXG@vY>8=Deiq6T5vy z8levVWSi79C^o8LI*HZ09$Aww*I{TomJK;a*o4F-)CpTm62J^C0NRbi-3otzr#dkN z5Ve*4P>tHyHY5VHg+dv{=?FwoQ#z|Ov**G#Uz9N?_P(&t3jmg>)!vtn0|gj3K@M;7 zPfM_f5%|@#)Fz;02oRyrD<2>w0{`~#YBceK%Z=s#N723bGxh&*0N)Lp>o#|WnVCCt zzl3Jye!u2gbHDoviBips=9;?*xh0`;zgIItQpvqiAtK!<6{Ypt@A23_aJKU}JD>OE z`C9iw<~^e(cHMeBE9TU~^=;JY(l%6a)c_=t+&V|xn{%H(T&CF1e`;?O&~y#Ss5$Yy zLip$T&!;&=y-zmuEiNaN{$2E4n{lx`b%~?lRm?qv2rB44e9Mkap;r6FU)!#yCuCDH zClhakxK>8KQe*nW+&!Z&DOa|X^b31Zh~Z`-Z|0w5rn?+(%GQm(-sLaPgUY=>MueP79Tmt!x8A{3cN>}PeeeFE@%J5( zR~Y#bq^Z6aG^)=nf8OQL^k(yip66u`wCNk=;h&!>F~#ykt$1BHub8_22HfB$)Y>FR zQn(tipu{XRf=A43$dMv1yliL31E9hBb#NqzDul;ti~;X$qFva%^!Lx(g6w%LOvlEb z4{BCw*{*rqU5Ue&x_Zw#iCR*+YA1zu<1(9UGK{IU368vK5I^1~us7{3Qc?D-M7Z$1 z6y4+bsEt0ry>`c6BS&S#>aJ(~74<<<>O|2Z!c3>-hhdHn)>TfNwa`3vxS%NEzwFs} zPDe>TPlW<^n+14?QIqljc5=I}_r3^^TmUjp(V-*dpvBRve|Ldv->w%iHz}9v;(*Ds z!Ez$bRL31NIPb1G8nw!$@f;7w%8lFuh2ktoQ|Z!GbCuW%9G6a@>w2?z4w1&cpD~5~ z_EEfxvWRfMMe>-!b2zjZScH`k#eJ&YU)=5Jxdr%7JrMC`c}H{jPAZ3Ka-q`_Wx}EN z){|@Jyhm4N;JKE(nTX*Reu1f7P}|+xnwPFkuO_8I{e|++Jo83qKI774_OVk8-!&v-Usb#u{ zrJ1Rs*%^vNBzZUZJaddNP}9zN8$N# z{A(uf?pK?d;cIN_bS>|8ZM)04H!X8K$CbqTrBF`84j$vI^ev zX5Ipf@7Rp2XrNg7sg;yIIV+~#&#|z#NEg(Um*p9n@9P8txO&HrOYh1kX~X9`&&mbE z8+>ZHf$`=rzveVP@sM;WCi=4814G`#T63{wGK%@vO>nW$F{)E_=%q(&U6uA^ZH$e3Q?D>;oNK zYr5yc26HfPhA7v&VL+2kRJlY_WCzA)PT)* zlC|oZhSFv`u5NBJH*2gljvd`v$2~`D6&Yq1{IL{%BqwRGE|U0*D~$^Rvp$|ptD(OE z%4^;NUW}x`UY1gmSi;JnwB6Y{NFj*JItd|1Csbec zd}hVNh}!9&b7pLL)Xh()#I5V$@;>*4f-T)HF*bhfEtx;}{`Wrb-I$&3QHimF9IaZQ zm|+2_?(AqERs(}PoZi~PrlT&}il2F!#(zfa=H@3fv$4Xic~gwdQaDhbM}>c{pTKh+ zOO`oGq)Zqx3$u(bSsKkEl*+qOolmXA>UGNI+6un@t2L&hcB(<=MOpcix$ASAe<723 zen3mXZB~U(oWtY8HW8aD$i!>ZU)5DHhg!TWWPHI|FK(nacZ6lYfNSQ4W$=JXc-ZbF z=4velbq$SrHOxEf^W-tCkTCHWixJgMtsi(j zWobqfQi~zl3SE3#aa4}BG8r?fSF-FPTPw1cZaPVbE2QQ0uUMeQo<@6}J`K%V&Xw(i zHZ!X7=w{D;(AmpbSgiDOAPkaN4~4)KEdj+O08Et#X{2CkF>H2@n~h8ooLP`W*y1e$ zgaTWNk&=t{$JWB2xvz1cAehFF?3rMaHps``#PxV2OVb5(WcLKEA&Ca>Zijk(hs*U}3e{7k~c05sesZh4JP% z*1+;Kd?MJIGeq^WI+U8g%M3>|)ra|${H#7XgD_*6pW8B{g(_<~-m-@p4sHMs9sv(W z(w&R08yLtVG6CU^2HNG@9_4?Q^oXh z;WjX+Yc80#PU46%I^z4gy~>b60MRHiC%Wpy_%bu=m!l>qA6hpGrklueqoG=ULrZ8%-zGlH6eD>B7RKvDR)^d?xa31_JH@XU4Qz-^AI~W zSej~X(rv9_R)0BS>Y{C+iA4F6=&2?^vpMTP;c1Au7*hJCiBD%VR+sW**6%W64DdDZQIM*;O)kNC(Rlo+EQRRdWE|Jav#} z7SG|!tNbA&?*e+qPl%>}MzGGbG4~P2zgvP*^byewDoRYePK~$$9p8eU!cZF7La7Ft zcpA!NyWAKum7PAs3XS93Ax)GjG1d1g#s#GS~PW-5kjcBq1g=HB7*R5J8t)De1Vb? zl{gH6A&Lu|SXWJ`&k0hefQ=Qzb{Poc)iJ}`!gF;nKUoDuhyfJBzM(`r>z`ZMhh+5$313LnLtH*+?M+(;v(JWMM#`F&{9^jDihyxkf;qr;MgU79tENNr$omR;Z1sM`6;LS_X@aVfAqDN_MCC2}kk{@B% zrG{zFX&z{BC^wccbrE;ZK7iXkU>Zq0ZF-x4-kQH3FV1`q^5WK!yar|yxDR_ z1dB1S0o#RaB*apwKlK=07ZT<>*UNRLi}5$%)vw@_Qe%amm(HnK?%sHMw0WlT8+b>f z>LpQjsa0)-dAv1DYnZ0p4|rn)ZvSMiX<&i-4(^y&*bu3&RF1tQF?KODF>m=lbFtV2 z?{11uw@Ew7imTb;KMTE*G!eycWb_>s+1%)9aoofDVU9TFJZ=NQ|z0GJn* ztM(4$2uMUha%SYLPW%TY5z+P({N$*yvpFo0B7bBCwI_Ne=zhzlaLp&$KkJ6J-$kK; z>>jA^^?i%JAHL}%Igzoo-pP;$P*!AO@UQQ3V)1@dy>QWQdTn92)@)PzU4u3*lF^PA zwk0YjuAX0+eY-^+SB`#{kF#nOMvx*XBy**+0)dZSYGNGUM7#mFVgSp zoR6;>;6bv{`m!u{^Ar6Xx@aasn~L6jf`*Ky$Pps|`fPU@btz3sAkt$vsV+1wqx_-t zTpx$RM#lL#^t*uJNbtFF`E$rl%=M}WIVisuc+3{H6!?Adsci0pgWOl&M`sU4vuTP} zpY$$$ZVNFNY&G2%)Y{5K|WNf8p?-Tc* zN0r^IpmHN?1zP2zU-RWe>#j4u6Lrj|&2`#F0w1Rd4(|sf=sM;A9MdVVs{gp>ySbf- zT+M7*lz=9IT(m)4WBOcJD#n`9L)1klGW@>kdboi+e5tTcy0BdJ{)8Xf*?@s-y3nd2 z@5_|-)*m)jKSPft>AStc9+`32w;C;v8aJEkdezAn0KQR=;Y!XsPlUEQVw+)gdQPttBA$0&T zv6X-e?mP3VUA~!tBmYg}I*o-h)$t(oK9ka*AB^h2C^~)y{S}ux^ZXalMdJb%EpXwx zm^XbClc;}ByMx<#)YCb=sPbM=<1fULx_YXa*vx4$gUYD~!;c^IM&C`9aqBm0PbK0= z$IC&J#Rg5q$!5jFEzw#^t(D-XDUI(A$W7__eT6&bkSk$ZALYiba2a0w3lQs$2a7F7 z-ob%VVPBmRbpIo$Kg&_~P2jd4*eeFW;s!*{4RBrk&S(008cp5*XqwP;Sa^)m@k9$` z0FXrixb~A9a~@bYk50F51CK_)Sc0z3m?oMrrOE)h!)nbFqV8)ivLZiwl-{q`=lOKZ z=sAcsocIAUo^x5f#+b&%r*1FGp3b}=sN~sgfOydm^D_4Ir-Re4Zu`EHmLEz+hS-*> zcE!nZ%+DpQdd|-5BR$w z3j(trP%0-kH0GeNKCANb7f|8fZrJC&viI^yWYSgDaOYWLh#~7wvR0-JRnCjw0RY5aq*{#n0~lThDPdjf4-JMhG{L6xBqs<8 zR5KDne^`udb&j`Nnf$p^;&xoQu0>0sV)^_PlVe{STx&jzJ)Ug1!Yh1h=vn%hbu+l6B-O5|Xu(m+En)vS!44WUtL2!WR-f^AxVBXKt_YVAz$; zG!CIh!iAg?1W4McbdE(JS%z)VLJM9KIN0Z;H2~bzfB-=vS9bu9_^p97Fl%>}o%~Gz z6!5_b8$bx;^s3*f^9!XXP6>;P0J$KBj5lCKG&T((^m4w=K}Lc;=QwvOG!4v|f=-LH zJa2s!GB34wLYE@8o+F)Uu;uC|&mk6^>9>%Gc6GX;E)V-GExcot~0~hDnGvYO}waZvO9b4?-duMa9NHg_-Ufj9*PcKuN6rG#+v-SbQ9C#lS@4T>R9@pBJGf=r0kDX+`v8s)BY!A<5-Y z@w)9n8rV9k#r@xG;FRm)trLc0xJG7uYiGEUdQ+rp`wj>Z?m+_`jQD>mYG|i^E+nHZ+@aNHzH<>qYQG(O;Ugf8Lg=5Brzgr%{qOzuK)qT3m_ef8ypv1dFC1yd zv1rJ@ZzWTM2TGo$EfP>`#vnf-@A3_>5Uf48T~!aFu}g;TG6I`O-cv4AW!FH|@=beT ztui%D+1dDgX{+dwu=!PtVr1F{g_JPDkjC(v~CX(F&S#%}glu zDazm$r^6*psAYfJnM5y;XrO3!RAkrLl}{CjF2iHhNBKq?Ll0G(l(kzV1S-96(@m>J zhWF8XmG);M_4_{D`#XQj#ExUjd*HC!kQM;jY^eNAOq3hs1i?Qvp#N-dJ++|G5r1+> zxSH;I8!rs4#2`%`*8#F8t;ZeHBIm&isSb+u)d-=nJTI>$IFOl6#TSPEBfR8qA+wNy zY5|lf+k2{i(-JNMfCk~;7S2s7i25IZq!K@l%4O>|&1$P$w{G@XC6>xRngmZbD;Ie? z{}||-G#Bb=@nG+c>)^~wM#ECsA=P3b1sP{FC20EKOlzG03#$5oN=yy#%8l9CPiZ#J-Oe&ZgB z08Ra%St6h`sdz!WJ-uW{jLU$+4o9-BrbqJk?=uDBUv$`B;2t)RexYHK*?IY(XlT;k zMk{=GWm_VpWhNu=Oi#;|P-izM>%$nY2?@6@X^ZoVsaL+-Ngar858z?>#*K<4F?fV2 z?i?qBwk)GcsCr9K4(beq8?G5f+DJh720-kT(x}$)cady(0;ktkM|6}-7fKT zK7C%jcp+?DN>}ejy8Wu!+~kNzZ{n@T!Ak25;#-ATJ~vlBJt`gSSvQt|+uSxeM}LQ; z?xy2FYg~daeptrpxuA(c^t^06j(QWbYNvL(eH8_9xbhu_3CJQi1$Iz+A#y_Z=%XH< zf~6VcW0L-HHkYp@C;`S6pmkY-yv((1`T_QLeN^}W#{IbTAsN$%DHDFdF z0Q_F%k^l2Ors()x>Ayo0EJqcH0(>Kl$Hv-Rn!q6m_``{WuR)qu3x!Tn<~GAM9QZL_ z)ER7N$r%6?dH|6#l~X#yYj5{ZE^x!RdtT+R$Dyq-%s;-e^PP5S5_dPQkV$Qt$L zup9EV=84b3^-_tFT9U@BJ>TheBZV0+u=JPqOvBpyFZ$%dqN=NZ-~4UVQf4P&@O1!M z@ZI3+cjAB9mUmNJW0UIJrtBU5b*jE>i!iiqxXlR>c#4K4NAc)!H{xQR*sngh6S}sp zdL1HrJzIc7Xynb$>1V&&ko=KI{%jA0gMe;?0;#9g=fI{s4@xfj*9+KD3Mew-zkMS= zce5z};g`yX;3f;7&WAph42FGef!HTsB%$!>Q$OY%|3!6#nkqtk@5Cpb2VXLZ`3Xq* z)#7hYb09c@C#_`V8y*0szyf)ovAS%MlGyR_J^MD1lsmyk&iq+f+jK`>C*nY8n#j`` zUV&ZS?|}W4_RxOY7yXx~`kfP7CU9O~7kjzddOsa)$f3qAr#@XxjScSFvAs*A{c*3A z79JrvsM;Qv$J3vX-HHQMJoV_d0ZnzM`)>Z#bT-3EnTTjq98N)Y}kQ2K*pms z-IancScBlr&P{5(9JJ3cNE6H-!LmloPz>NdTmJqjO@)(RdBV2DH82v7+a(fazqh+c z7Fx+Hr|p-F1Eccd&sjA!Pk=Hyc@*H0&4K)bWGX1x zdNXf{;Lb*HE7z?z)onN7m2K-$wjAp3)b3_N8jF+-l^X^*^*?1nKqD$YKd3C=da~pD z??m6u2PxM(i=i1{ipxt{eONTtQtagy6e9LoJ+4(wAkI~x^|VNGr$S6q_8seO&ha4B zSFwSp?SldVtGNk6W-iV`Ixquzah2x{4?>c_vHq|~;&j=!oSps2E5@q=%^^NIn!c8+ z0O@xh-5FrQ=|bpQq4Woq(7W)WZRnTKTR<(PQ#)V2AXRm8VPs0a?u4SWfh>@JRhnBv z*73cojzvlSp2zO)*vSO`zwJTF0u$<8m;zbtCwLLg-Q!ORM2xg0k0%(H-Q0irTs~xi z*4EgzKYA`Y3ZPBQpr2wZ5oRWI$YM7Vtc_M#4!#IlvMA+`U! zjQqWIiHsEl&06ZQ_p!cN3enTf)mhohOBX_jEHc~xVy=U|RHQ@kEb2XaXR17ZL`G)C zQzZ<5LJTwWuK6Dno^ulOJ>yxX{q1(AiN}>N5marOeG*wkLyn`L^UUyi+}OB^`>HBPHs(!W?Q$q$ zB@?lVLn37%M;P`n8e%uoU9ds3J+plfqmK$w*WHVf_HdQFtU8?u=Zv&LQ4rgS;Xm)* zE}BKxxASKLU{e%meyu^~Y*IZ~x#Wz~gAXYboQ|p>z?*vf#@_L}!i0_m?N=o(cRs$4 z{j#_EUF6TMuDpd*C*8zFdpNL|XL*|^A8>y<(3($#r$}I(c21t}EwD@h5IikAl}$hHX-97y zLpec---C(2#(I%V;@w~c=4k?VBTxJYZ*vo(|E?Vdg1DG=L2=BQPO~th!N1%jK?9JH zqe$0a3#|Z)lZ}?aG|M=eRXo-zsZq4olbE^|r2&a93^p%ow2739`G<~)ki!ODL8%C3 zd^1OF0wq?)_=gF+sX3;Nv~bC8$9gPIO5gElBjJ%ys0VSNsW8-ODfDisNK;hUM7qoy z*)Y{^T&|qY12-p*;_&$Tr2AQC|N8~HW_fmWJ7Sl@Q$XfxdXE$f(np(XDF(5$S~9fk z8At|B4eO!y6a-gfA6R7BBZlf&0{f>(Wxc)mK()0B<_1i*^it2QXe+hEOCrBz2Ip4IA=_!%s*$9 ztAF(#D9v9a&A%p}o|16#6TKK$=3QmMVBmZKiv}H>pNwnC5AXQRTQFbVD9Y{!(wFad zYa>6X!+%;|f%3vFbBC;zzJ(v;Bo?~*^rHjYxP-0*VVy$sSr(>g_8!ro{I7zt=aeRl zl4VQ{XjWddkP(`Tf$?sgm=7TQZ;C zNHnEYtLZ1Ic^AnY+AO6P*NM=_QWPME=@tjVyaTi|o`o({nH3-|^+bBi66K7(*x4Sc zpjdsid3{AtU5J5;uFH@#VO15Hh!82A&k%y8lh`I)>?pI83sjU4a2{8ja=QVyUop_}7V;Mce< zW=_z9Gvb@T{C~@1w$s6f2CS>8_TmnUA{^r4T4>td@9TR;BKt;#f6mE^9fs*2R=GhF z>dJ~#gdCeUdd2#RCk(6a`9`>HS4B`In(HKz>N-*bDDEkUivb$--fWLjR7my#A`OAU zBAW&nF%^GR(}+nGaD0HEgrlH@I$KcbRs~k5$s)ETiDd(#M@-SFU!&K>*&#^`sbB<( zy_{oq4Ur0u^@b}3h|XAw+ADAiboIufik}}NzB)g#G<2^6TVr-&(r~Hj*og=w@ziWR z+XF*^@HOF@VK%ez=cf9yIIw_D12WQ@0^Ugl&l2$@fF^-F@AUGSni&XG4S|{Nz3qE*Bcrn5m z&A{#gx%_JRRG6Hk;(>n$Ix%~D`?~@m{eBO0w_`P>$7SJqWT5o1PPy|ycM5YbIbSFM zh@x~AZx+Q#QW7M6#yEkNWFJQcL#%;pQA@scRp_pmzu!>Na;$LJkk^}hpqLa;j{;}K zOM2JH16gRFoR0QO>Pr)I!JZHM`I-SuVfT(T{ov z)1$FH&;y%P#%TGNT)=0!;J?2kL^(&0>!yNw!1Yfj1u?1Yrvp6EtUd`idfu%5TmW+X zzS|{Pq+YPb#Q?<7d4vd1jH&-^uI96EYNbLz<<`kB^5KFTf9x1Ty~%#}ZrAL;mg9bK zez-w;n1fdQ)i49^{Ugt_pmpSZ!keG}QeJWmip5cW{Tku;79bOc&fW(;4kEH1$4J!; zRn>(_J#o5NueppK8}wH2nZ6V#HBI2j2K=d@AnaG?ELP{tR_9E}V8sA1{N0gS0GLEU zq6v`pN(jbmM)0o?LN&_cH;jBs+J5CW4&f!mB_+VHETEfZig zE<0&s=Wl?(B3eF@|uSGGMrRY?kMe$vKRSgI;$&mIN9X$-!a&} zf=R=Nbt#X^l2Df>iuZZOb>g^6p_FeJn==>bL3c$xkIV4_@du-0d(usI_y-aChu1fs7 zQ=*R9%~r!o+=sa)x0`d*zr*^~Nf#+fTD6D_4!X3e^L#DvD`(C*u3z_7)9TmhaAWKH zW^fR{rp1vN`Y#|$h|96Spdb(e62{z5CjjVR5J~dsO{e`@AcpJyn!u@U#>nY+ywV1j z@KCewU`YTK098ggzeYR8WQsdh{V0)ex?w@Dq&YhL6m#AIEW8ZijvZg6qFg6ELawJQ z2Dk=&E-lkenHDZrNeCgAXX`8`mz%2Xc0J?yvOF_ws($1p!cL7xJDTXp+6WYVQ?$8a zyl*TnU*hU%vsr3A?)I$MSMO0s5m`?hR~&rtMX<@%Mki}rbYN05Qz>S0)ef6;#I&wH z%j$&6J-{N_N${lg$C%=SBD#F0&+Oy69AzVG+%?|%M>uM9{Uh|XXewR30zI1}pOq@n zB2PckvcV+azVTEiEe@OP%qg5f;5u_I7*)!2uacfH#$t#f${ml*=b)R)O%pM$a8 zC!S6o2KDz#GtSI8nsR(XJ3-tm=3PFl=G=7#O$g?T`S2EUB1u;ZA%b}ZLXSwr$-6V0 zGMA@ap{iL7BrKOiafK+UBGb6(!&TR~DI^w}&W%u|e#b!7;)#%4)y5f4b0<*zgsf!s zJ}2fXDITI|ULDV!Jy`{3kP$0!qlf&Z#mqmMpTC~)iZY3FJ^0p|v>aI26Qd>GZ=v45 zejgOe`Lwb1*U6*)xqR=#?glv@y%iNqR#b6wPnPfX+w8+kT_%4R&(tWNxcUC>Lxc&X zZVZqXy;>932wtLqM@$N=!IJoissuDc+MgR*ML5shSG-#d<${2iAWH7#nsXZe?NYeM z<^DSd&TYR#1W#DCr*ZQV@KEp*KE+z-tJVSr1{V6>fCkDjSfkPPEyN$lQkRn*8*gYF z|D!k?yNw_u@WfBz=Qp6HYjSi-CQoQD)l6s6D5)RBcs(vdBq z3*$gJIsnx3kHbXnQV~$Rc_T+r9z>sh?sJh>)oBc67xIW`NbPi zJWcJPS@=7f7bV0ir>_EG=8E8l({YeoDZb!bfH#(4nZ*U?1EJ|82!TQ8%B3Lq2_qO3 zfl4v}gif@wD!AR*C3<54gi`wzSiB`@J_{|2NoMDv?gH2w=@q0u*yo<&SzK4AE8C6D zzPrM;g`xGpQpQWn#4pnpA+1w%Az#ds-u|(HF69{Wa;d|~3Dci@SJI|$W=E6rCT=xp z?KQ}}Bg~_}9cmK`&!gUn1s6vbq(M!fqlk<6ObncW_?G7M-TCa`yc+X3JsbcjdY4u} zMH^z0PeKE!#~|JA960n9s009tP$j^b-vP0t%fs))|3iF^sQG}J8Ll$?4~R6#=lTr> z5yJ(5a*8vU-r3>|iTT?1f40mJefJSPSE|ckUWA1cn3Ujct+kx3-U5Wa$>5LMcP9ZX zt$mvl!@TX3$P#4neq^zJc8A?1-QuFBVmQNDu=LtYZRJ=2k9MuBSmCN5x4epqFF8d?A{(d8DY02`{##-rIt`zKIz)UiojD1lX9qQl2ox00>v4`S5lt} zFt>+2=F_=S%ASOdvt(Qor0HD9VoHPYxLG@I|*tGdBm}Ob9&Zi10 zY0Dvjy$;!)8AV?XsswwJzQ(!w1+dn}Z8#Cuem8Gi^J|sH-^^UkLtM(RPG>{P4@K@1 z?uJ)9#>39PvYUh|4Ybx&*k?hT^8fsX=)j5J5Bbl93f>Y|c(F}<&m>&4q&qezo4&S8 ze;2q|A#~%deFWGN4uxDLaPT+-Ka*{xzd|v_^aH7L5(Uub_rwg&@+*IIT^cqWN(M?B z@I!@000?v-5EG{i3ycp(&w-zWgl=7Xf~z}d`mar*NXDymr|xIOLTi8rDx33!6_5Q3 zw%pu#F06ZV@J(s^;yu@-zshRSW(CwB_n?aQdBRv`kVKN#s8|gvEfWQi%joY>6I6>* zP*rBWrrSdJL{Iz8>;xhPm+RE+qi#7zU=YI$c15xWx?GvT%%Nn= zQ01#dhKO6Euw}BSmshY_Yo6eWLC@{i*bjP9cW0$jx@z0%zj+>RPTucSnLoA^+Ep&& z@7bAp?UO0)zbDdvv^LUb?Dx~eRV0CW>4MN1I+tSc2)|bc7=?N#uK#r$vADP6xH~Ll z?DSlRPZRBk4*WHph(ME1zBI2`7kO}XN4@6UO*wYk4YD=P(;Nb}-gQ92nG$7ap`TOkO8$J`7AUNH zucn8wQOKu`GGmDJbZIs4+l3JCra&S9TqLO~IOKOq>(9OVh+mh509POr6An;#E%dwJ z@7ZX9kn5!p!;WVwO_NR$J~^vFzsOM_6fZ^{0-tsI%kLIgLxC*f>jqg+x((ofdUhzB zat}Sa?7^ay-aU$+_NBbICTjic{pqDZ0p+ulC0EPSI$jrU#M`(EtP!}P;GB8F#BgWu zmZ$f}ByX>7Xi2TYUM4IDL#@s5JJt<5*3DzK{~ytvG#COKl=qc)_r8O)*dCA7pY)Y! z_8w_xFV`sk@cd7a4wYD9fA=wAST9Jp*WQdJD^u6(`A-^;`=yk%_`hdU%74Mi`=Wtf zCypSA+wYS9e!CdvnS3M7qi;OwuP`4F$4SCNLgDB63GRIguKi09tqHDBIOtJfQ2OE- zf6>58aiEFIfGeR%LxoA%n81Av!_aoi6H{nNi+%>F{g{Yc3QE{q}@5MWW?UnRq0(%yI%{XGojg? z(1!~=`=O_QmHl@hqNLmmRa>Us5l%ltROk&!PhOAvWT}`QsG=NUf!Qv)R|}oE0aX-J zo?yTh(DBbW3T?$=xOBW;=@zQ(&Nat#k{F4VKLOJ6uKSv7cVq%daU(DW@d)JE(Da}lS2-2 zZt9osm0!sgHI3}g@#zXBk0)@0Qi5#c;u2EAD>68}Lqytn<6zdmXHxpFW>XGLlT)sJ zSkjG1zL+N`ka3t9MIa}MXx%31Xybw~ac54HL!A=>-tKdKJ>a^u8o&n#EYS;;1L!F9 z+LJr_IuLf-t&^-JD4CA@!Y%Dg$iB8+c3+%@6&k?u+;lxNv z+F92UJcOFw>CLjSVPpSFH*}%R!pdzKFbi67nX^J|r!x0tg*!}zyF^7we34YY_h6vk zy&@&2bG(vEloy?V`$jG{W5yzX-cucPWEJQ{Xfm(5`J2cj;$XdX7qKDChb zrR!Qm|CN^HD&<*Tj*9y0l-mlGw_hl8i`1r2E7jA34V+Ks80qVg_cUrdtn)W?^SVz7 z)aQhPSv4mK5Rx-z){8`eJphVad&@m&K?gK)8bq*YH`Rmok)Q|w^eYs4iM{V81Vju$ zAC5sMy6sgsK`@sKvpTjyWTZ46)*6glD#`EGv2#zb`?}_EZ=Z{YT=$JT+ds{KxODM@ za`3J~W)>u6%(H&kh&x)mJM6`6wR0k0c11%+1SWSyO(d(qVpge}{@OmJPh7pI^8VJK z`12kylru5Gt^zLzTpz1s*9D~Cg4++3Su13l{G?N+MyH#V0o_7gX`Ej8;0i;<98XRr8Z!Y~#7WyGg`j|xo zQ&y&Nba=c20AEGPWdNkn=vm3O#!3)x0Z4&OkMdN79Ax<}Jec0O_##E`z&iVL!$7!8 z8R5^s^_(&hG&Zz@_xn1(Iz{9OUSn-afO=Zvq&a45Bl+*uI=}DMmYPgkO=hdY-4h5t zava2}ozseuC<*UuCUwd;*kWsK6&OfmiVME0oeBrioVDo`ZBU^$3pxVD65uu~aNad| zF&-1J&CHW4pTl6bPsjq7QdLmjv%L=Kux78eT+(sz|^PfuCXpdG`?3W-Gj zsknY)C{+uZQEzc?_3^h}bNv$Y!g^R0Md==O*(AK{>)PY`c{5s+92OdmD)RYkvS+&!uH8 z?mrepZJ&?)*)hYCg>voQht2>qL_E0Q&sXY>DWO4}Y<4RB*;LC=yWLQ%UTE8%?C#uy z61QhBqD4YdCd_zX*FVBuNDPL_ihW$?eN5r~4FG7i^Jb_vAGJT-7{u?kIPT7m$N1q* zp5Iv+5DHhbF?g&S@>iFo%NG;}u|{)k*Z}3pFgPBh5QJ2$L#lQ>RCCd#IP22UP&p3v z%ZWCj7{oiWTv#wxOaKYVf>2}_0;q*#nIR+rpb|Jz+69T-Te?(@R3^O40stu#=*K^! zS#T&~m8Up3kr*(}<%aLNfH#{MC*l@8T|Bmg>W}#z-!9@6iJP#mp11w{q>&8#mo9Qx zF!*Ox|F<*m{AY%G_8jK6Ywa!qChG!6oUTW^y~;!q`Im+ zu%8;}~y<<=~R5}hoX$Nuv?(d{Y^0xy<(j;$~%ZvrcOr=4G zcQ!%mK(_q~2}E zYXC4?hn?%>oyPkss}dVJn31>60@i7c^3y_kr-g@NK6(e?b!3@cCtvv>Y!s?Kx)v@T z5{CuTA@2sjzNJ8nV!vx1m%#Fo&|tAq!l)2uH@j{~Cc% z1ejbq3s}Yn`mB!l!VlV02PK<;%FsaEDq`Uds1OZ2QU_8BKGO@_!PlX>U~bV$yutIu zdk)OZtzGzA-JXkGg2xxbPA) zd|lpgodRD4-sdSMuNI=A){P*z!sA?uat>TMJB~zmjuWY|7?g)fI_?jlp(VRN%Lqyd zPEco!AFP;lzmNSzyl>RsuH)Z+vqF6LSbx3dU_(D{72n3zihS?xQx z2co;G&x~(th{k^~RXaCw{#@?V(C?#-TNBPZTr&c*-0`8e%qT#~#Z3V;8aO)xCLY63 zqz3+z3cug-t`3BTZ+!?@7QY~UM%p#`zVS^<6knVPKV|m!=~)&+a0b|-5d&J(1m)&G zDBhDDQjxfL>$i8$v!YRt>(6A5n@ALmJljk6v~jF=d4GVB`PO`A-tofW`L&&~n!SGi zJ-5O;0EE-Y;lytn!YBi0@^Hr9wx)aYZk>7N{w&NMx<@9_g<-by2Df>U*!bK}{SYQi zo?pqU>FT_hg}rdD5jqeX;OuCTja5bJq#@A!g>*~Tkr7w!8#sa&W>1Huj6*nC&>0Xa zO&%_%nz77{;gE-Ghd8bS6p>tJIR@zXA!`IztswQaTbRZgBkO{RYhvZG8Nj7>S(?wY&TEClM7>QDiV=!As3vHXi6AF@dWCqeTW2%xB0qbTIO8FqwI+jrga3AwH=M#j&(Vt`+TUsEX#n_Q!M%82yjkri&Y>2zD(e- zloFQB09zUaxC-%G%R=nU*tV(w+&KUY0i*zcBotoQ!$Jbzlg8;8Lq?q7JHxJ@!!HmD zz(OJWSHNSxJzQ-Sq}C{cBm)8m90>?W}`bu#7Hy9p`L`%0hgvhuLXlbA=W*F1G&l!Wct%d_IDYY+HC z?X{?q@1xc-HY+Ui)w{_-S)%H&ksJAHAJFjb<&T5{>sTZ4o7Y7ODF_k~il^BCK2VUA zYA);x(eme35hP90AhqUjGeLIj6r{}_v$Ak>1-R zLAsI5>9ITH4_Ji*i*1Rs!`~*=PHFa?YgxNd2!XjYmhUBw#EA-P`Mtg;uqFo)w0EC` zgdMpr2P0R`XgFuQIUhjEI4OjHvkKP*-Rly~Y`KC9d8$wF{NVj}b?k>di}F>#{?1*g z0_Ul1YQ9bxCA9y&;^o5c>k^4_x-Fi@?dfGOAc^veY zZ|g@q^Ud0BW+|Z~iHBqb;bMap-~Z;|d3q6&bI+Yc?_7|AG8i-wIPB*P-Re>!t5|u5 z_LPooJ0l5Y*4I;k4C5p)mq|6f#!4rI)_IhgwiUrDIQo8h1eDf+s4gggv`lC5RnB?0+T2RS19=01&r;!b*>20m@m13*JEK$z%RueY z^Q0e?QTVS;IhGOv%GW2{Djc93ZuKV z&Pk(ZRiR}cbk7B=thCQ8cqT5Skp(5?aLD9@;uE^WDM~?AP)uej zAKMI`0I!>)?Cs(|1{jY5Sn{zzw{3mSwBu)4Rti@OS6D%>$S#Uwuev_RJ?Ld2dq#X` zRhzd32!Qur-v{NHCyTb~u6+l^Q=Cq!vU+)S1^Uc~dwb-WKZzLreop$wpPEOZ-{Z+! zNI{C|!-`P)2qi_(&)^@@>F2XTy)$WMl?ay1${X?%0fZvCV3{Us-s;Il78_1p?a z?eZ|unuMU5`I{tWg79VoY~?48LQ>@avYQ0=Pvl{Nw3@lwyyP+3I|^S^PH8s@k&7b{ zKWIHZ6~D~hI7@K%#~8f$Q!;!}FzkO+^MUQy>zv0?fLiD6R%FC$SSUig%i06XgAQ!{K{m>Tp#LMKagYz{Jq${ zK|={d#Bmlmuqb=`-w{YS>#e zwRby0zR-6%#1|)Kt#{>|Xb!g!+f!pAdha!xGq=$bYsTY(S?(Dw~GvbYF**%H+RncfVR z3u9tvlolIYh{7s?nq24fre;&vYRTOV6A}CPk-yJTU_=wvaBlq&ZIpd$Xx$F`v9D*CEKby-(ezFgA?wpw_D_`cFmTmBd0F-?LX%We z9=!Zm_r=9uWKd%0jv?KYIQ7jd13qWVW>-IbzcH0IC4@5uKJk-4?aiNqw>tgR)P= zX(ET$+$mY>%E=p_)SfmES3lP=7zf734jiQm7YE6F8%NN`6+RzqjSNC?waRc?;k9-X z1J zY#)@Wz^E$laX**{kkG`5@C}G;;zW;ywBa=x9}$Yy7&EX9qsUbpb%Y7s>a4?-o2Q|^%B+Z5CL<{%>++wT&ba2r7^~2axVaUXN2xX@Ik8%#C zutGR~JY}~{w%XOT(!gDx7_!CU_=sQ;61d$`+Uj(Yu6Od|pYAO%!7_N5o7-sK1xjT$ zX^5IMj+{0e)iI;1e0LXU!KVA#oj1G|A3rphz26~IifVKa2Td6L?2@qa0Lfz%xUrqR zhEIBerjBYLjHO!r(kPQP8qZ0Half&Vixfs$`|}N;37{=vxYZ*0M`#z;{(Nm4WL*oBDktBtO_SxNLjV#SknZgSY9Ii z`rrJnLWHxw1qlhWR0)RzjNpdG%!UcRf}BD~elw6-KKR*w;X$>9&Z~j&PXpiFTHF09 zr6gGcKfX{NoK+^^^es54G$5v7v-Mw-jFV>@^Eng3pec)^)nAQnTdBcSbOr`TH-dF9 z356acuv%D>BoXIksoj#-yE4WdK&NMOH^+vS-*%$RXtc~hS=I5!71VJVilpaC3vqSt zb$_C2V+QnaFY`@LE~D-fbwMpmWWD`6osmAbS&ACkpW(Z$yS^+fVP~?Af(yrZP-lFc9ySZn=K``VC8JO{9?vcxiy_{gE*?vBmUFv}?+dkiwk*~V z3oal%FVI{8EMk`QkWOc#)^;55Oa`pnV5x(PT#)v(U3=3aW^TH)eHB2puq=}d^h^b@ z^YL{;Gdc}v3|Nm!SZ_9s$$l>+pH67^j&a62wDZAj6@d3Gs}_U|7>R6XYTS}ro3u~c zT6!D32EZN(&_}VS2NhU)vP=K9lpkUrlVO8aVi)qTi<<2g<}XAqF}kDRsq`A>!==v1 zmFY06*4`J>CxtX6R@ctj3!cDhm+9)hCZQ?p&Pw#F$~ssTr=^%zFh2}VBT4!l)|tAu zM{mifDG5dGA#i(WHD|;5OG~O{nv@qDVzQZ{he-|}hUAwdqpOn-#*$gPdh`GG+WIEz z?MfOGA60Eo8Nrj!6r@mSsd^t3loIlP)pY|iYfyoyeq5em^R(0wXIvmJG)u&~xk0*Tp=xOT zPPdY!8v_On7DFUeUU94P1dCyDCTXG}d7|zmb!PAeGqYr-%H*P%94`>0;~ZRR*X64u z#_FQTim8`W;yL973jRyVl-!_HU%BiLRz-tU$umeU-WZo*tKwiF8Qh;(Mr!ZREf05NqvsX+y+=wXB8vq`D;)zU$_QD zv`!S=#Hk!}7CJnTyFJj>D;M!( z!mVy)F@-~e`<*Pck>Yo!mt3yTo_#=DW2draqft=60_wG`?N$g@^ zZ7xaV`CwV^=Kgsjqq9KhBW7aV=E3gTpRZf7QJbs0MaZI$ts-dNiHdJ*Yzp3RPsiq;ncb=G~3xF>Bti-VvDjU1dEz& zv>>^S(GZ67dL}GTKJAS>I?+J-hLXl-2NRImZle7vNQ}&tsqdtQN)#n?xtoBLG~7H* zKysA+DLL|tmFDwaX8r8c#rOyngcf}zsR8q5U*!t>jCh2ba z--3R*c%UHU~0x+7K87Bw@XgqxErpDvi_)~>pm&_-7gnstjhi)X7UhL}=f9Y5zZ~0>emii>I z(61c+qNG8Hbz0dvHI;Y`IAZpzxFvZ0o|5AESNTrxLLXRx3#@exdZp{Fb)2~56(SD@ zYi)v*(TD6uiK>-gDl2bk|CeK4%=B`;qa#6Q0~OPXN0?H+Kf&35Tq}5rTYkTT-892? z)`xb9-86dv<6{DNkn!G~IPiPCPa1HR-8yRiQ#`UX15SE8!245dI~Cn9wplc_3kSD+ zJ8!?$+Xagv;bS*%#h%}a3QJN%C$9P@`sjjG5n&6uiSwbyIl2^SQH_>MMy^~QSXM$j zj|9#mZRa5fK{5p41rYK)AZGK{f8{Vh1x$Va8|(F&1l+f*M%%ydKSede&&o>^x^_xd z8dAwcPpUGz*Z0TI_V+3Kx?BgKIlLbx)o&D^fJu#+&%E!Fda{~%d*bGN<_9E?{ENt% z$cW0ty8XI)E6@Erwf}jjD)<9M0Ewb#L%N)H;rqwUp}(olSqot7p0j*n>O1hEmYMRP>GK^mweZ`z--F%AAj!N#D~Q=f3oc>Ght8P-dTB zXAI5^c7H){e}a&eNs8oPOa(Xq2G$~iUwI`3UQb$@zav4L9Q7|5aLS<(>rUmsp-{UUblTcQR`+Wfm|&S~|vOufR>+LyNyHMmYqF8)m2 zHpA}_zre>T&sDGTX8u={SaIZdEvDmoj4tMkg2(6aqQ=10bgI|BHT2E4W(qGKIvfVx zjWvv*wz#Wk*J{qcFUJ*l>Q>^WQ7e7{{yO-S_F&iBY4Jplyw>Jk;lF;tZY@XQSD< z_i~swIFH`F{P(#$>Lc9ydlk5ym$Fo!q@d9E?)U(AGvP+iJ?zcUwW52Q{**Ug60VE? z^!^I@JMw#{XV#;^WhRI{xCV4foYdJ<9>RgCrYs*X z_?hFSxTS)TUDZZ+6|@ptFTU50<%&o286jWQO*~{t+RAKH^m~;9vzu4h?+sXtQ9M0t z2|SZpZGKL7{Ho^W%kmEIvAEB^XxG)=z}MX&2WoiLbkNe=ip#I2>7nln%-imZpHPuF zVH%rjF>+gJ1p0$B>HgX+a-^tyyG*gza?O49Kkv@hPPP{+Iek|T20Hd~Ma{G8zw*?h zBBQUAwhv!B+kYMPYokzOMRv6lMAcpj^K>*%eNt}o!l3azUrzs|v0&(ibk z1g-O*%Wkf4ZKx z#w^>A+PYW6$ybu-e56CMtIlg7343zVf z4LOq@i|aI#84um_1!pO*NG!E^^)&^OuC$pqdD@#a@7rk9gS#FIPV|175>pAC zymFsDM};DH1vJYMUmAlNz4wScBgDAB1l{VFbN_~?Hw{?5P8U*z+fTQ=DzBilceS?wXR6n#XyhLTzIYSQ#$#-qj%@{6f!kJ_J8rZ}1}E{ivz)2H#h@WI z;gt`k`nazGCF78^>@-!WP3-9lp-r<{8wMPYMjqWjj|uZo=`sy%{bR&ZJMcwuiEFLo zT3&ywRhDcK-8RE4LDBhf!Vyni>5tEqj_hyoz&U>@4@hXqIMnos7863!J+n#kRPh;l zUm*Bq44)c&QOXZe@8vtn!Qhn3841rA>u=w>>1+5Qq+Oho_))_5^(U^mP$PB1oK%8% z@*B&e#px5IQi9?V3sp)tId@&kKC<)!dG{Be27}FgO_>|V$E0a*YNnJ}+K;(bE|2<| z_i<&(ymIVmB&*q5VvlQGAk%D5tqXUEytHD#vmMi}u^dw6iwxe^TXevO-6f67h7`!c zgwt?YC?U@MBp*W=6qIglxWNoH8_RN+ zQ~0%;TEv>hJ#>~xh34jOQ7))H+=)Z^P^LrmszKB8RWt}IVJlfVOX$Po%<_ua;Md0? z)%oJJf)($iB;Sbb4+V4FiUZD%4mOaBT_IZfUBgijcy*;m<%v_ zWWMYTwDbIz_l5ZzwZM(ThH&qATNYZQCvod5xBmqDU`-wiuGz^|xSR?hT}_dqcN#Q3 zlB>Oi-yq)ID2xi6oBhYX4|v=c6=qo065-ZlMf={u%E1zCb@M`^XU9I?ylvAWp~<~o zw>yxFa<@QPIeo>~U{O_yDpYtbwYF>Lw7FX5)m6z&=f%Rld=QE@@K64bQdGeMMo6v6 z^;zBhT&otbH}7LqT^9$=&U@?Pi z#31MM+|92(b?xy5TN>Y+WkFOwyVz#0p)1S=$Lkq7)(yVkxigGp8NO$3v(@;04|vUT z^>%b#28S@yrScj(3ts?Hl{kSn0=e% zyYy=}_XB)l2SEqZ{=wQ8XpH#B)>AbhmxQ)R+X>g@W?NM`3*}-j$=IU_$S)0RL zkn^X(wMMU~&V;su>jyk*FVs|#nQi;N4qEH;p=y0?I@zwT-8SCeiRx094fM$2UHR<% zh!*g!&<_p(!pu-0Ccv%O=UVUKOen=;9AgUt4EqxXtNZnef%B`Ofc)Cyy4%bEz#0Nd zmji_I@ZaXN8lpnR=+g#cZ)ZJ5L3wYD(FOxf_|T(NN*Eli8UJ?P8vsBbilWfD$t4v& z0RWhzVKaL^LE1b^b?UpP#=B24_ zINi|Zw%E;q=LG(U+5_!9%a_Ov!O*0VjFvG2Tyj>m~3m$7VnFDji=xm>a~XtHt)=JE7vF;KNDX_21?Ke>|`MocVA#cm3$I z*WqWdlFS6XjOl;>KIme>ZgiXH+z2HE`t&eK@hh*Q0^)DoCivdNxy>t3R%@Tl{iUMIrUD^9)p$Fu)3Ruy1iK4 znDRm96|GIcIKAus!26N!6GUt8u|r<&ys8mV2B*ylo<8p_2^ZZ_K|bdc&aEV^H5BLK z$C?2_-VyKpnJR&}D#ZRr&U;mtF&aWA6IZ6pxYdMsPCoKTxd=>oQv?}&L|J^eQa^I- zgO#>Rg^%2M_Q4{QDuFF9!c9nuWeYK7ru1-Ae56{Uxk|>S`X$}Epwbq1b`^I?6|X<1 z+~_Fn>4!t$IxSm8-7~WvqI9f6nYt3!zdkZn)~#{x2cMdMa@#gkb*oX4s@6R=l&R+* z52(?|7Dg73YVrFZ@6;UF`DpEc$J>OF_Ek=szM4NjNyV1aYFBD- zOl++1>$aA$WeaOTM)hQ@h&Ke2=Dg@=9_CWls(@VS-tv!9)#}~Z{@#yL9`aIi^W{64 zsAf-k`l?)G>yq3zs#nR+kX)f6XQkK)c3MN3jR5j4Wg`2OB=!w}(s2^4MvW=Q=gy(` zBOg)6xt~T4?SQ{aRZqZ*{ou73t?RdfMFZEH^$F!UZE;9@#URY?ID<9x!kV( zbH>nn;zz8JPK_4ilkTR-#f{I(-CzJ;2K}0-@-|j2^fPe)Fe>`lUbjYf8+GywyHC%p zm?r9O;vXmq*6kfNv#4P`60wk@^V1d9RY_9r1t>C!SO?aOJu=kgdq{6vf5Xl9#*{bh zwxOHBhK)sih)qpyQ=JA&8T~d^$K(owOpOZ5gx;~C-!Depc*co6#L03Mm#XV*D0+bO1E4*uD&6zUHooe!`%___^F2YdGUnR zhJ^Rx_jVfY9f{xn*>ImCj)gX286r6-qAWluHi#@YtqdQv7#Fh)KZiIUl_DRl zB0mtx#iYnDE5^qlhhUQv;+7MkR~Dq#5Wb97EzC^ZZ4BJ3tewnFz3dI$9W6XSt{p>TMP5V;13S72|K^~`m-b3&vmCdwwn%loE>ces~#sJBl*fPaLqUz~qHd|+_2KPKi*Kx|}` zO|UDUgzW<;V*`vMOPafpO00)Px=Tu}5FzzihHH{nVo6S7M@{sBjZB4)(u%3#o~_EU zpH7dGb)lkJubDG0)EyV1w(RtD>GQiec*8fxE$Z0~&#@aGiCV-=r~K^T#)sj*i>_UyUH#kO z{;$*NUw^=PN9cNyf6fA?rt6yqgUM~5!o_h8wcln6$ z?^DLV-J)+li{8Gee>LB9xYWA6)AaRc!=GQxU%vEFD32+WC%=C6ogH?pf9ZJkZ2I-< z*RzWY6v`xp^8Dw|DGFtYLRmjOU-*7BwYRr-dV2QXfB*ft_<8*8X#2xV*_$ai1@McS z&#bd@ED6pk#do?xUz*Cq3kv@vW;>~eRZ{!=L!8MpgIBnl+gxd03Oza$@WVM<;3@7K zh+T@U(O3@m7(quLv3qmhI?2-%5f^QXuSkwxh{nh65(YeRO#Ztj zd|`+wXi(EXatbGU`R7!6WvbMEWAzAgX^7nFj!;%()f69sg7gaH<@Lf&xf1)Q?4C)D zTv_K;D9!JAscQSv2+oHCCXxzXnAeJ$&W8V*5+H>8y|4D$n0|GI`^tDZf)M!!_E2AS zw&BsSWJIxAeZ1{kyc*8!jmU&y5ef~inkyXGi4SKNiN}hM1W2; z)SAeApJd}aHAyQS>u(O`)l;$O^74pN;1zy9Ys}HV#Y8PHab+M+s&Ev1HC5*@@~yYZ zP44#sDMqHb#!R}JWmW7f_L$@?b|tgN??jpYQB`rQ%tQ%2t8no{?f zBkt2U*On(HpHq8p+_Mpp97`)x%zLZ)o*b6RbglIl<$b)bb9iRwvt8k=qVRKLuGZq) zZrOb}oKm|7Q*~Cy(|{U+*oMd=p+FC2!pzIAf3e@PFsPW@4HnoDNTB3~gj9WOnrSG} zb{{UpxvO)Dms#jo!v!|Fio_p6Xi}rfaoQSHyz!&1f{*S|bh(VroHRP8(>`NTxf_0R z33COX%2Lj^1^k*f`xr*{>l$ywNpd|3=W!!SJcqy3J#TazkSgh1q%Oi!zqpMmA}u3> zFz<@9quz!=K~+H*_=~hV%Qf}o-bPGz>sL1VOfJ>sle(?C@;uue1dH^*YHJEn`ok9xuccEWwo@W-_=J+~D&5`(mWWHEn8kp%|SSMg*NAe|SQe zrmZTkD}8%d6~)m5qp{Q^vn@vJ-Ty&frh#BXgepAwoAkvVFPMgb zSS+&88N+i0DML52{v>iJz7j6mJKhUOT0_L!eys3j2rRiFRW*WD>g(!iPl|8keS#Hi#%8?y}nt)AFEHRe?q7A!F;(|DmlRn^6=x)fYkXO6P*(o6m|qx5?%B+ewqi1Rt-O+a?-*k`{2q2S z8RTa=@`*X6j(KjXT8f*{|T^K-ft1+0%%b4WM3^ldV*XIFKf7gemg;P_Gb z>kpCOILFe)61C=sv3P@7W@-z4Na3`;bCe&FnU4E`*2B9i>McJWRatYQYg%Srr)Qwz ztsAw;$%T@i5_6nf^sf3j+*P!L)%M#0FN4}@_b)+UJVo0Z)jFu zYR&{o`VM>qU4|j;+v42>QqDmLs~SGj-_L|yOO)jG69@J0x;_W|*@-+(X)i-ISX`kZ zA>P~085H02pyXA06_uGb14S+3Nvlbgrey)v%cIny!bVn{X^xE|>}g2)Y@f-LU-xFG zA>68s5pP9s=Ni*Uih9#Oo#XhNs{(|uaNTZVPRftFj+d4Q?f1Y`{MEl#xL)>8sn6fe zx~5MhFb!m&bR)uvEhs7xSnN!VTZ+ggic0kU1&vpGBD+Z9r|;z0`3@X!;jf|h`WxeS z@w!gGyWUnv^mGJV{rTR;ZdEz^Q>Nopu@$LfhZ&_K@ns#u_gq?`2iJ@CTX-M892?f$ z^?K=ITe^0Y{I0peqW{+LzhWBCRv`x0FyxG7dCG&1N}4N-Lz}RxF=Nv;O1~Edwm3V^ zGk=r{tdOTrTR=qxc)sIz4SBusQQsJk8&vmD5LpZ^P4^VXQO}tmU~%>La>aYL2E7#c zCI6b*3JZAjc=#wn?+NrtU|@rEWnJ8!-zO~&;m#vkfeAHQZ`FckN|ic(=}pm{jsIDfiix1#CVy> zQp_1>xW5sbkITOM{lV zWW-=$(`K+IWY~Hmbear{0>ENzVU+-yC?YHdkAm=q%(&!3h_lltwtdh3V4eJ$n8$N11aSPg7M5Y#hy&0l}tH3CNjpRxW(kUl5*+x zhzv-$%sJO<1UN?_PuQF~3y>yEotBRP+c`4*C5HV*P?Y~6pj@0#Z3!vb*Nn#qC~}o? zr4qDg+Do=$1Ll&6LCd7>i21H&K8)~C~591oJV9ieIkp=ogK*|pk<6I}r!%i9%6!_^HG^al;urm$QnRbI%6wsOWUmEo0Ce=-a z9HLo{9|Gp70P9Z^xI0i3Xq%NYP}H)U84?DK?u2cuWu)w8ufVe+Ml&OiGfQV+(b(c> zVo4vVWD=A40-iBNg5|nqt@USIrl-aNXm&`j*v-tl0U6on>G?6Rw=u3 zXq5H|ipEj_YSjtx=!C2eK-`G=R+NE!%UDK>rhEs9d~5FV?U}NTnX(V&DR+)@vvKtD zC~A@7yex&h9~W@qF=#F9fnG7>HI}~Nl))PfD-%%GU`#_eiy`?T(z_Znv*E>&C|C;e(k+<#H70!;lNFB6dSRAvFD!FTBdawg(@_)ZfJQ%vUkZcfR?^NkJ&5*z_s?_8@;;xX0Z5AO^kO~;}xbwGX3Jw00@gmFVFY?34RBqTZ+r1QS z9x4n8>VBzX55v1HKy1;iq)uAd4cg&N+F}58*>RyJ5rjAf-npo~8w(9sfCgfU9?bN4 zZWbgXA3I2qNQCqTWM+66^v*goWFg}@S8)`v1Ow<_jLF1V!tO{ChDjyM5+%Oru==Kw z7W0z6{(j(}%%R<^zO<~5Rw9Yz+LSy zO672QI;54Gl$MViJTZ8VcRYVG^}I|~np=>%0!f=T_aqM%=h``2sbty0K#^kfLlDJy z@!r&U0Ujzr9^y45)uaVpQ=w4365QOG^L(F{v;fZ>rOrbDcscx+1-NWwbKx___{vIak7322 z7GOZxQa~AoT(u=V$z_3GErwVUAE|d%KmYv*{RW;jO0BX0qHv&q)I^9mfC@`J>RH?t zCz->`OXX>sDW! z#v(SehIZ@hnqi;e4ZTC-Cxg%*G&B`2(jyS#3Uu`ijWv!IIqZLm{6Iu-k3AP1NAsC17kK^;T+BoTV(ACG{`cai3~F2Fm;| z&EGc1d#wP?1>1fzwHg2&y}N46JG3`bXgZJ|oUm&0d=4QA77M8Gd@&>*`%Id8s<7a) z1d}#@D{&!H_6Q=E#Yj+Ql^daoU$ZQ{6=H^kObu4g47N_&QfH3B)z$z^XaM&pfUXi+ zA4B*_O7|Zv2-bqu{v)65LilJKd-`k3$)q0|&|DYjK}qHf?BLKqUAcCBxB}r2lhFYu zjBC`}Z9r$tGX4x^3`vZ`g0dqifX=Y}_7k^;D7V3ff79NQ8nRt-1cz&iT%aE{p+9#a zn|BL7^5Tij483l1$88KGnl%%Tsw17ba;evc=C3`!4iS$(Lw;1c@R3MdhoIs)5J0%?Q#v9<3P4p9+vbOQ zb!E8A6A5dbd-Xs&XF!&8Ww_5Rt1i)%5cGRl!lN!9nZc2n#e9&_Y1R?2-|<>Dv&#zB zn+fY}&46ijth&H@WeDAAZ#o*E7qmWYaH(}jPv0IU?dVYXF;(yCK*hAEEKtx_R&(as zUue9({BC1%qN4`3f1!vGo+Xqwx9;0~q3fLp>irU1em0uoh7?(IedMVDbzP@2^nrR} z%dCzemZg^ya;flzA8yiqEv3%hgg;n-%iDrPDuEJ25DyU~Vha>T1BJti|C4w!xjV>} z0QFQLJ!#*_2`EZ%PoIjN(YjaM){+?mfZ?^4=FihrWtXmoWG-qf`O#z-1P#2zEUUL= z&66{RnlcRMO2cfkcXpR|%(lt0S*wkiIj-qlW~3sk+K4v=-dwF$Hd+GUuLBc?^tF1Y zTfSMuUP^)(pIcHNbI;#pmP*HAwYEAgRtE%cpcDfjfD^s z!1kl`JC&4=L+FKg8L;dofEEp4UpQf}1i)>9m08e+cPqvgb)M8SZ8|U?jnw|KH0P(rb6JGVp0NWAudY8ySZ&b-&ZoM_gu25<0)6W%R-`=P~cNzh+g1b$+MmwByMR ziyKShs%zTKw&icY6W)B*y!2sHwU_PWW)k%2rkTrAU$=H2WlhQl%_%&eOiUQIr8@`Z zFjfElK%-ZYKslEocwL}jeth4fbgKfe@4cx%VjACjalz~=3o@mqBPG`TnrKC?)7^bB zE!%lQj|OmT0^n#Mt?d@=0sx~>AYcuR_(M>(f!3`3A-UA1kv~0{A^A~eG`upN$`IHn z!4o~ZXc=^xj0_1L5DC;?re4%t*RcP-k^N?!?|9q@w?9Z_3^%+IV{-@dINvU)^>X_wC^S3*hd@7j5-dyDix)QCNH;xqOKhD!D z$mpZqu?ZMs*>dZv1^qdEPQX%(?WeH_(>wcG5$D^lmVPtv>omK5nt#w>!>`)9NB&qN z##p`+PR<9G71MoCyh$bk-%{QBplJ6{;dXWY44c^PJD@Y}>$`s|Q3o%d7grz>F3t`- zGYP`MD5)k93)?^=5$<;CPJNibHk>(hzZg?VBW(Xgkp8n^IzcQGl-sOPAHFqIUDDW0 zXzd-WGDfbBHC(yl>|LA7<%SspLg_G<1jy)C01*13pH^Oc3Lz~2oqT-oWQYinr=OK_ z@MTZ|v}9&~ncY3ooL+8Z$x@mnebRciO>U)|?X2--kZsFPV$hX1pd8ApKgzFR(79Oa zVfeCr+QXptcPN5hM}Mp)TdTr-Vh-6U>|mujBV(BUZA5y4AToC#lrFv+lrvntND`m0 zSNAh3r(^YD7mQ-#Nh`z47(J?Tx^@FT3e(dh=9!qBoS|~rJg5zPa}Lug;=gj?4e06P zoXc-YR%4`^)7{1;MAH|A7*6X;_8k~Y7ijPtRh#~0A^tNd96V?e0t=G5w4FnF&?qpJ zX`u+nZXr=ctCa0$-#J#RStGAJGC`|#toDFaMQP{QM^W(=YSBhpj^n`$a?s&N$BUi* zq-@n?^aF;4h0)+_g}2*=IhqzW)>maeFP|_NUrat=P+g?}s5G`hM_jXJ-x@6`nmzA7 z)s%dJcGLb&I`1{AS>rXV4xp}f7Hl8ZH7k#+T^an^E<3(E2E1$BbVx)L`|10AF}Wkg z9{hVx>~GvG;b~VCPZF(cw`w4DW3R2ju*PC%P*_Xv#_U@y_$-vxrQA+1nS}@20--gr zm2P`!irH*qKJRYnc^Z4R$(E%0pBD;q^D#*(8>tT> zRNuTIzMz-4dQhYB?wr`8vF`UgDSK<5n00qC%mK`x+KRWfT;6t}Pf(F?Sl^ZIP!`Tw z%l#@8STmpDn|?}C_%uB7?}vNB=??3kzw)|Z2>L1|@-xC~Ad4kC=8Z_2u{sTpG&8H4 zX)8vQNMApjv?w&e(##<=j+3DAZ1y(C9ZmLXCk)6&(`OfW&JC%>9X+wjRiEpL)El3g>uJb&l zYhp@m`1lZhL65|hLi>Ktz6PUpdvDfC%BWDpyHVEBV-vZ^$|Q$fEI`u-OT~i)&^iJD z94;u8*v1YjCLr4WAj5NULFJ+f7`T}`JH9GnGLHV@V=rUK*$%I}ZPSVj5#lb1yrZO2 z?adGZVDvX~#v9E68GW}|_2&UCA#d`kKLXq(8~V)WhOL&;gOXi(9Mw<` z@W8vX4&zOOcK~q~cDL1r1yP$LI0xJ!!B-j+IY(@bMKoT~*_atXxEDs@7J#C_W-2+J zMywm(aUo0Z7;UuZi|byTl&5MUCU@?CALlhnx-z;UsF3Jd#wj62!dt(f^;{eO&7#I7 zM#M2Tkg0^ib7?0m1nE4;;~X5EQ1$$J6{LgpulmP2>$~2JiV?E>c@unZYwP>!>%ajn zYIV2cOtXdyDxy!r$4_K#&^eGla3@zULq^1P{|J)bUkY8$Uzi3PxT2Gwj?@-r#E=hl z$#hsL$CE$^^V}=~CTh@9{GKM+Qjs~W@2rZEU6e*L*gJ!GJZ^bD{`><$o@i@KlaNdYL2UxWkO{FE1r(0-y4SrQ{g-V&25-StQNnM#Up`q*UxPP!gJ|E zGlj2wMZC?2Hbf(p2;Lx8#LAh5WADs5t%v?LD#!lG%@WxR z8Puz4|L_9cKf$fuoaXTMV}4$;hzyY0?NF*#ota?P3S!B{8mJn>2Ky}>Wa*C|g4Lom zaqI+zO7jWsOp{unM{){zf{S-p4md{{cBs8HG&!4vpvG%lJio}iHoLbO@0$tpIGf(- ze&_9&xC!3S^_nwi=;2urfmzLb%<|nJ4!zx1Q_f?i$8;{eA&Obm+M7?@e#Dd_Svy88 zozfoPeo*lbVmo+`cgTh%=bariP2kPvBb?9&Pu#Uc=GUm0@tGiaXrub@-eGOrJ6iwP zWXiFFXC;r*zWX>+8`0z05Kzn!7ywWfV#z`qQ3J4O1PBYF;THnYq358ak7o8kT=|;N zN61LvB#1V1luzd6m-{m2^WPF#TpAPWwUT&Vg{3M}a=n~l`ArtWpywSn^xqsl3Dj-* z{oPZ{=1)pgeKQX>-8=6gwBs->%)-bRHsnIJseY2`CCau3dB|bu!s>7r4%#)L2E!@_;y6jTzd0a%s=^#UYwSnD&x#*Q>`aK9agY zY3cAPBQWzBR;1yCh;VTA9Q6Bc^cw)8eoyNccht> z0KExXrF@Z1E<8qYTGPlt2r+C zP}q*fXbIGm-YmMHE5TIHo0jZ(oMMfEn3ExSrHRx;qzx~Sfh5g<87M534mf$Z7yw|A z$dfl~I6BXeTevdX-!eG}9zV`VuOh`jWc0X_Z<^`poSNRJJcQn7D)kzo?wT>w(N+sI z>$`s}kS3gV7YoJ2q#DJ5|N9?B=i<-Q|M>B<``FB#VVL{-BoRUZ;wW#nCIz4{zIh5d}~E-rZ>6LhS@ zm$~B2#XAPX#q`3knrF=Qend>NpET>k8r6gv|MClqY4EGmL9fR{brZE7s>0_C5}}2E+&?xU;wY%I zl>OFQk4Ksr$2crO{~O2ZkP&ob%=W{WV2_jJyr85>!97%N6(hfcvCjo&Zz08W6}#*s z%7r>qe#9$5vYHG|miTMYP4G{7TAXt>Db-z3+3rfJ=%@+ZZAQl0$S8lTcz?^@&1J%^ z%UOKmGX1m*IpSiIuH89J4sQ73JgZxSq%FQc<$MC%JDa5vzg)vNB{5>qaDAt&1Fx#y z%}7*d99n?8Qgb}O949snMgi1zj4}DD|62v)|MpUcBu`7x%vl&kDVV{ZqJ~d*;U#?r zoT43}bNATU+S{EDY`sT^yJ>-T zt~pRC6IHTCEScH8$x$G=w@ zgc87Pb@cO0Dyp&x?%fLKZL9aSf(SI^g~7$!e|yEq7PWMY9|rcI|KfdPx}LhpH~r$1 zS=y@j;=#niFd>)G>v^ZT@15Oo-oJ-B+waP(yB8hIIFQOXaF7vl8u>qn)B2UXi2Ifi zKZfHnkYqsA9Dm=6<0JP}$9PcS#iDFYPw_)THI2$bC53Zd6POS8bT6(34!)nLUlP2C zeR;|M#W5A8&N04t3VeNU=3|G|CuKkWdqn;u5B5GUKPhWN^KujJfPB+BbZBByg{q(q zLPf_BxT?GW)`Qn^a2azD)>MZC%S6U5a4r2}MOsaE(zL#$3lhj~Duc{fAr z^h{9oA+Z`&`hnaNk^|!ThJh@ZA^tRBDy` zX%i6s%yDE8H8;8&ib6vYR>!DHm<2#S9VNl122tyXVlJD{>eYy98Fbh`kixpYTyV&xZ#cFO9sZ$u$ z0;nahl57%i!GDz&xr(rfOb}Rkba&>?=X^*{&i^{$9%GS^qj0D$1ywGzYUOn*;MGiM zAz$&0UH&1_Z~dw+*<*c-Tc;Uv>yY4eTHK;FX2DwS`vduGcMRy>D|WO$1&B4In=|P@ zOz7(QFe6~@toXThd_$`*R6m1Zvy&H4E}pl*carod3Js{>q9qm}JdaUY2;fDnA$Wi{ zlAUtsqn0k1c7`_;4Uyum=Qw4+v&MV+wg(9tSGy(axk(89Pk=*vy$a#3Mm$F) z1N2VOkOy>e91E(=L}=IXq+gl`j2yqRq}IDB z%rpD&5EK>oUqjL4-}gghWHIQgLD#YNV2C66whjFGC3T;(_(NyaQ4JU8l#fEREfb6MS~ClC?0%JN|Pn#B~wxF|9w1gn(-|z?}+;P5i~Lv ziP%&)&wbnf{^iK~$>68^Sa*%{FB>Q04TI~-Rw{nTs-2sUQAc+M1A}> zQ7bSw*Cm6-Q_&=kF4vyW>SKZ;$b+c5>-_2$9ZELug|ImaBCRfhk261LXCO_!*#Cy{ zXKlk>w&8*KIbOkVo!cw-b+^*nXz7i#foa;UR@yC29DY1bvOf_I#7nxwOA-P60u91m zY54r=6!|4Y75e}X|qT*$sh+*QpMbo)QJ+4a8tADJy ztBFrHT+TRhOA2(YzpU6Kq&t3DWt3rJCr=>;eRb*a;exY8dcS}nRTf0z9<6I@V5$Li zz-Pgk1D8sq2?0RtVif0nRQTHm`Ht=f$36&;D;C=pEBo-bCPv8s+cvZI`->Sd87R7X z-hZob7fOz-I*@i00!gGv2m$yEngj?T@coo%g?QybAXJ(ZXGe;Z8sMEu&`6auPlfa! zQL%X&HI6*)f|UH2N@2k*0mS}bPpc~F1h`dW|%!A0_!6w0z4{K7zqG@90M;wE5-PREioS)gI3<};*8g+Q4PRfjLA7TGf z1%xQPw|IE`u5Fs40_w=SmUn*+MhgE6J@vn1nV9qv7DJYu<8J!Jz3aRC!-4elvNJ5C zZryLy8|fDl3iml0H=6PvKM$piLb~)NWdUSbKPq#)Ap0Yn>)lHGaR}_6jGaCR3bVnP z-`;(|L89jJpXuFVXGrNWy29zgTW`a4x*0LSJ73*R^@CS5*Lj~2f%poS#)H!1al+%V zxN(4=a;9^vMVQJJ8{fRc1Vvl99bPmH6A)_UV#Wb!p`>qzx3msHs0}%;>xe{ibEKy5~u-Vq0z=|S> zE<7i}2ZSD+Ju5ux*nP4O!9s^UIa(H;h5*nGAxl_BKI6>=b`OhL>L>E2Ll<|rmMwq2zW#c) zm+Is3>dw0}u*vt&y_60r4ZG{~jEHz>-CZ3w;S0%7U?_Z}3rK!h7_PD>L>XVnN0$ud ziujNEi2H}|F66k-(^10$^;x ziOMj4IoH8*KTEP*#KG=xWL-qcV4aBT`pWeFs)K9AMilMuN5#uhoLE>R_5>8GMdbh} zaeUigl{C4`4naRkg78a4CPpIF$okZBB`eJsgeeQ43+T>Tu&@VTk;0N5f=x?$kMQq3 zbu+-5DEX8npU1LU;|h;u-}KRB39;+#TGCNW+5$eBm5!9!>MUn;Bg$LLZAC3Yg&m)` zg&w&jdpbwK6nnGR*WEDnI$!Qyq`B^0b_63=UQ3G9fUPhQT^1 zYD&^gk+8%{FUyJmRj26VH@ow3CR4x=ln~E}93i@Asi5*oiRz6E-M>`+bC&gkf-aJL zP=w?ZC%Z+LtpPwRK+6f;G3DRx25;H+=X6uIXpd#7k1bK@k5+u%bj5ZwI?3e!JIRpx z&}iT!{h-2(aZ{)q-N||8w9n`MtZwhFlb}L=r&4|E4#!>Zz?A~k8n(ag$BRmaxYPDh z0q@S*@wLkP1y~3_F8pO<8zAaRq&XCG3lm*g4~nY;mCB6255aFuHA5Rxjz2B84) zIB>YjfC3_KMKJ-WxxNfUk$Dy?M1)y_021GQ`hLtHkYxlw%aDBgfB=<~vKCy>3d3McmK3wb+iLB$BBqvz0p`N5`AOUhd8^jonpOu4p;7buX!gg z4{pis)2-5(i29PO8zbb#3aFg+`DXWzoI)0M7KsuU5NUG!zNu3cN<@Gbl7N6FoM zZy-&QEHXlwD9q=|rXbF^)tB$VdsJ*UqQ$8!G*fK6FaRWHhLQMruAH7Ww-IxgZ6`Uv z#;flR%5Ee+Ht#M!?>JSA2)*WGg+u?#I^TpE^6Ne6udIr7T z6E{2kQ|r6((L?DOLDu?5%&AUAAwtVX>)t+t|;{khG9hdh|IqWz@mF{^OC=$%?V-9ZdxcSUmFV$N4p1v*|R#!VoCRY`U; zz=6eXDx4?PH&e2IN5#OuiZaL79B+Jn!xXIXK&VaL$^X%IoQsrYl91XYn(_xMS^J_d z5~>m)LYS-#z6T%(sR8^Xo$Ed)W)T%Nkk$iCq(Q5w!D$$*Q(R4yg+^J!)y!}9(FC(v zhYvnFpkvG+~R3V zPCvko4qox;gJt5YEcaB)DKVl_t#A|(O+}5Iaj!Z`Xn^} zqvV_I54xEex`%gP4zTpob^o0>#J50xpsTNt=AuuN9V_Q|t$S9v8ArpAf3(gn=;@^% zxWp^grome!!8;n9cuN-WdMX_T3*#KanajWyYoT0y>L7;uIvZa$#%F0hq1@Xjc5=N; z{X5lJcZZ3xqUM&Oss=P9` zMB|zx`j68~K^kT&czmBt>^Y$#5uy$_Y2_3%m7rRMC~eL*nu^1`dSNG$NP&u`42fz} z29KhNP-r(;RUu7ls`ICbW>9bm606(}>t6+g44Du+UKm^! zJ%ddKVA39)eirOS&8b07id=%+7Pl2C&s#{hT7?Ll8in2P3cho=+9T++lJ|{YPK*p4rXH~J zZx|lUopb@SbqAh1nQ|5JCDal9;VD3SE(#9wj=79O`#n?+a}Cfm|88}3Tf=~a$h;t# z>aCg$5n}?TLIMyZ3yQ5e03mQ#kPADrm3m;i4(hy~WMX!!Y6&OI+J8nD%*GU(#O`Oc zH%XMtidqq2#`%NoFEoJ;gCWsfeN2SFP29=VY+TkjEVt*-9kK6j4e9Q5>29NG!CG2y z7CHXCbg21|0le|W6|Q#Ftp}BHTfm9>YC?2Cc7(Hs&l1Tg$9ujJHzO?92g&Y<>)W=x zP7OcxH`zndqFMnu|F7`jRz=shTSh=BC_Ap_cX!dhhU|3_x>&6;uXsG@g)~C!)mjCN89y30; zKP73sVV>Jqy0kH3;!ye~^#atb{N2C0vZ!)vk^_8t7#_%k%Z*5wI9M0cRy-Z?2Iq^| z7ml3=6uFUb2e$pb9J*?voIqG1-;xg^nB^|ThiN{bz$a3b15`D$aBrXEhAMO?D2O^% z;W~-H0dZ7_TR zpe`*084n0iNvNE9)PMqt2_k13k;SC41yBGTf@_%D`T&|xVHP8EmQU?1nL}Nl-DG+P zyEu@W0|Mra?5-+jX}0aFa)?}x3vzz=o&)pN1JPceoN~_#8iz*8uZr3kKarX8%O-H3 zH?yO|r&YH|R1?nr4STB$ngxC~j{v_1iLi&~l076)ZepV3pa_rIK++)h!FkZcYThzu ze65eAKMJDNN!3%egBHcGe&i^L&+S{TZ%NZofa{2YAYXF?gbieTLtZNz+e%_!a)3$e z;$h~}glt*X=O$DlIPuSWsvJ0EUI=w53{q(hw0(-$1!qX4CT$jCYIazggv=s6e_Da) ze}9!CfYrCt+=b2diTX9e@;(&)O+|I*9?Tr@l=6Sf7k)*hCJ$2%kr!)n6nbyBuI#Yh zZ115I=^FU@-$o5aDIY}QKSVgZeUJ*V zLCc*s9?={pVYV5e=yTf(qbvvrQx`n(8L@d_Gh$ngS%k+dhPY&@wpev7|Vm`W!t~YEq^-)Gk06wO+lnq<>M~m3V%8mZLm2i zxxRpl(9^o4FJwUl6)%eYo0uU@{ir+N-uOZN_eavjo9PH&Cj1Z)QP0$DdBMA5qTXUo z*}V;1Kd-2b2ked3S(sH8^HsU@7*hdJQBL3!ynTQsw_cgQeBm<%nM1!IjMWLpJ;S#itfFLNtJX}Wv8U{UCIP%ly4_LF^U{-27Gz=K$DA|Mn<5UnCeEAtX zjy)dcFMb^*w#02psSboFH%A71eJa*_6co&9K?PqPi~=Tk@op=Y(>)S~G3MN5XGuCp z?xq`v(O<&tkF?r$g*z_+7p^zUFU$?Pb;-+B(c}o5UJ_B>ffA3_^6c))vR0a-UbT6t zN8S0XF}w+w=0CX{D9kx85g-vAu!usL$~|lz4>Y#LZ9NevqaDB^{EX>WZ#ss|N5!+p zzB9){-{!`$t{x6jBxbriFz^5r0KhPHNCos^)>V(S9DJbK{Wv9AH(skw7V zW$?SeyYEkfeq^?1oo|RvSo;~%8SQo1@!mN&9)wk`VG`f{&9IB-M_Xr)X~W zenMw*MH3i#gyzEu*?H1o3o4AEq)C`{D?Yg;_lt*jH5J?b7TL zRxP7O(n@XoVYvM0%!+FoXRh#hT{v0#yt3!xFDoRj`HR3f?IR=Kv>U3H0u>kla63$C z)z-^sDp6;maD{W(pTtM4*RF27@trAcs$Rav5?ut*IUv3!1W^VwHUMq1d{=Z9`F4DN zU19yo26?}o>^)H83JEnbQyd$2buQfZ01c5sItR5y&9;`lZIrEG$yAW8aBd*0fFFx2 z`eFf5M3LS%Y=EajWVQ{uR znKtx|4UMiCYw}0WFuJm~3g(64@UIP>Ltpy0VOH3oyRx%n>GtB!+mEJ)@!Fe#nzSkt z+tj(zps*o>96HO;@v2QW4?f34zK7&)W@T#fZcc6WN~27FaV76c4}(^(o(T=0eMPf1 zTl0pmhwm$fG)k+xp77!qA3>fBBb42gi)^uz#b6>lep zEBBI%T;JHDwRHp|1n(G@80dNtII26zt2Yz%P(M^%?A}dmb6t4!7#3=^WpATwhZi$) z0S*DaA8{8aJqoURahNpjw__jHmf^)1rj-m{&9 z;Ij}?jEHDV$1|14A>~Lr-kTVRZR>RmEqS04Hf`lPY-O{)r);Te)*8xgU8i*{2roM) z+gvLynfAQK!<~{Dbvc?2x@mS@dd^+vq<*->yVy|d@ms@0f0$L|pdsDC#-GlgsM~Nx z7j<@9bL@!-GhfJiaAO60w9e8^p_?U2>BH%!#$5ZY?~UkIKuTJ#K}sassX*G!gI2@B zby2^*Wop^pkc6%eXVw4wE3)I(Sf0Q9^9)tnQ+l^l`s%+3{G~Ad6j1U~gHRTL=B$^j zwF>3mMwYQk>(gS26!`X7C@~0s7ARgC^1qvlEi9mwYG;sRe=p7cUh;X}I;hF3YM9>k zoJC^Im->Zoi)!qTJYo^`qD}o~o0{}_&B89UyV=Dn-Ja@K^)W_1$FntqyL>C*rr05y zd|R6>d&QlD%%d+^H*f0K<9t?DC67e~W0C^n&js-gZEes4t)Dclph^yQYU8XH&39s= zg5u|tB${St=94V4ry!Y0;(43R{<~7#CPJ&_M7u8*u@#G4KpxItv}jR>Wv~#e9;otl zSuIfRQAWF4VNvBbKKM;2iBw{?3JYWP9i>vC&B!e97?Yqa8;K28`prkekcXTlVdkK{ z8PVAwg>Kb9tX@~5cJ@2;rK(4Zvh*rV8iaa%->!Ri^Zf6!ESYxPvt;j^cQ>eJuG@zC z>38&terM!4Sb-2;6^KNZgW|5A)q<^JD@l*Pd?TmS#QvI98EqgbJ~aj*{nRBmV^%MP z{^;klQgespBjmb*WZ0NCcdIt!t_)c}7TZ=Ajxk65Xx+s6EQmrc=n=!CU3LfIA)~Yi0W=wl> z-LU$SxZD;*ef*fmb!FcA%~Jkd+A7=g#{K^(jA{#(3;r_}i5iErXKS)E)AN3tkhU&< zr85Il@gu`FIfMIhMgpRLW}GxZhyK>Ahn!D@;5g}z-vTA^JZnNsKZ9=SV5dYL!m(Ha zRMuziM}gAC%3?s!ZTa(C&S&4-e`*#BW3}48QMA8ND|XZcPXdCvX_L`6@>^KH+ErK?UJZmsCkY(&&=Dm1VhZjEQr~1TZ3xg5L9pbHJesBdd zSw5V8a_El>`sai9_w^6kVYN*5caS9f?M=7nelR=5eE9xV`l*-Sy~BPq2L5O?IvGfk z3XF8zJeeyHHk9OXHv~ohy61)I0DxoPB-}G1{}#k$HTjN?eswfA^EHPB^vf0*OrBqA zxBS!@Yd*T(9#?FBm?Z+68}&hu4^D}++br2u^q{m^FnnZ*9)M2V{BwiXYX~5>foqmG zZ!=oTwA`pRo&WM!<$^Dc_kvh46e-?NqV$bb=J(BsP_r(hmbUZx#ofwi?~4nBVOOfPPS*wfNE8l(;P?y|mK24W;g!&#Fzx{n&-$$|5 zwNll5Yo$NQ-a+;7XlbTaV0=K6Q$-@n3;x9(( z26BasNy{)?4j_hb_2GapEpq^Z#@Xce1>vmnf5H`P%)|2qv$zWZ{(@e-R&o)L%|Zp8 zHDC4-w(AaONKwIX5U*SiDXvtloqj3F4T8Xxd>@Ai+I(Ru3EFIvh6k;ya(v&Z{kb@E zSnYFC@`TF&KBpf(n*>e17DsTM9F++5m=tdHSVCQ}{Y6v55PXxB1$an6WD}y}tF;dOLm#O-HfmO)L#g@m_G zv~g_^iUdj%iAD`Sr#vlOZiOVYzNqg>B_+=KfT-J|mk^0Wo_w%!q#8Q-hP5_Z&>#3fEl5X3I;97LBD;pg1jywS4C&$d=zu4%)v9x%rk4E>Gp4u7=Ri3GB{e0vv(G;9S$a4M9+)K<=Ik zEStkdT9G3gv5v#sFPC!4=$^ghe$sWS;+Z0air7+{lZRw&+piS-RF70TbWX5fx_x**N! zMI68~ZhTE!MN$_X9J5IXp!qUX#H zmWLRgO9Pa|4=m+N-VYWo%n`n3D)pB9gzC5YbYAs1;Xt7s|BO57s+!kbhK*HCPg@3} zW%TMs2zSOg)NEQw*Xa7Ir#s(sQdqa;u9w+jkga(BgxVM}IQYuyge^NK$fTM^@vE+x zyZNw%F6$w4d_HY{*NI_1eiukiJ^_(Xq*&BfYK57x>Hs5BGPboLEn(rpS9NCcJ_nZ2 zDXKL3ux`)gCtxnUlBPW5Yy$;pz#(>lvz46;+3tzuy>Kk0>y70N~#QgUOU5V-96)n?~ztzd|IFlim^nmXVm*6W9!5rOiZ z5z?`b1JF-8BvAgm(L@e2)T9mqY3J~HQJbXRFGiXV2$v?7{la3dO3Lq&Q8xXbM2nWz zZ=F-tkB;u8%q3hJvZ=395VUA^_xXP3tiMf_M(vWydBcCJGjQcdDU<_yH10op!DC^y z1v=#R*n1a_-za$+vr_Gu6sB(0lIq0yViHQ7U90OTpUaCVIUe#Y?(Q_Z1R~$Bhgv*g zRx)gI;|yIZ9HnMX(BpnPTb>#m3Pfn5|fi%p>$(OR_;!c9YG8`dO z^D~1-kPqq<8xs%2<)T8Hi^kKfb)S#p$1n+Tq2hiw{+173OzpsC%N#u*m0xjcr_9{e z-DS7!-_DW!3G9egubD9noCMp|c4{yA(}hs?>qF|3jf5OLlUm38uj}+(cZUrw)F2Q4 zoeBCTA9i7h+$y&h^0YJO>HriSM?o$LeY>~;9+bq&P948wsUfH>paCu@s?O&l+1nAX zn`l^+Gd%H{?GYPom>1Sl#zr#DjOEjEq&XWaZu@I%o1BMUp55@sGuw{*^nT6ke~YBa zw7F{usY;JsKD~L#S1FqLyx8XM;?MQ$>Zb`4ZiTjmtW@vHx@xCYLym2(6FqTs)t`8HhjOGeZmDtHENys*0JYfSRjOg!()srLBbBgAIg z0B8x`!ZZ0iqisgH6P7p%Ye2v|DDV`OAS(g5oX&x%wm_$+u!>xmZwZWA#tuGqiOfP? z)0nrTAl!(di^@221rb7{NMIu&M_^$pa#W08a0fiJI4X7pyV&m8)ZBTcU&yWft21b~ zSy=pfD)GO8;{vHGkq;A8SzSx_Sl8~s`4U+;PZHuU$v)Oju6J2j+7`vJhX>NzHoG3k zH5m~jctd*I-R)nx){Z??y*|b;qr5lKe%`U}E-K5_P4IVFQN7Wr{w%gs>4!)8j!i!6^fqTnWLy{72Tl*`7f-By-|-59$m2m4>UF5yn+=0J(Seeb0Kuae1QcN+i{bd{%7!4#_(a7Y{$_@<9ZE+Hh`&#C;%K?@26wlo0`2a{Gnt z_>OP-rRxraF!3gXzq8KmUmuj-Bnfg0XVgn{x0YNsE_o|lIlhtAA>+N8Ic6a6oV?jR zO&IianX+{oNZ!*g+}pW|siIWO-l%Y3NnhG>-E1TT(?r|B&_E_^OS^hHp8N|=-Wl-{ zB2S0$P5Y0+F7bJ3tAu1tz*ci0;yxjPnDqxxenRz#|J$LpqL#`qvkOGUEi zL!hyw-j1VDuh?S-BD*K0%nylISQw(o&F0H?*h*I(|5KOXa{gxVe3Fab%0`3p_{c5I z3n~9i{jiFNZJC7XWJFu{^{C$C=qeUq9*)3MNa9eX-J!usZkh0^mw|72yMAjncAN)x z#&ySf30B1>H@&w?`9YYm9X|SCHBM2A168ztBu0Yi63L(4-kT>w^q>78^c~0DSXM2+ zp-xOn%=ZoACa4&(jKwgL;()3dC4or1DMC>)@U|ovLL7kK85P1|0pddnk6Y0S^#(4t zcG3%Hi)Yqd?)EgbRJdL?4o+9lx+>PfI#-Tf)4G1kbqvG|%*sA;fHTz=PL`f!hl`sx ziYAkEEjT`VUqfMJ@?Vi><0f9*@7@`%u#nL}tK3>kpl&3_IPSxqos*#7qz zsl?u7FJXK4ld%Tj8*@vm%#4PhRZH`D5E`QAV zENMs+4r9Lk<##>s{g>GH1_Z!}KOru=DOUSjoT{*?(DAI{76xnc2766GvWp8<##)AW zss4#uv7GJvwZ_1UuLhPUdIdlv@>c(9cJIYP0)3&%YOwE`u=u18&<;Nn0IKj6eddBP-a*YnaNl3-;kr~_Q%8zm>G+e@5UvhQO>1)ckmFOEQ`$k36591l>chXDx zq#3JP>9?azCMg2|>L!s-J4P>_Bzkh$V|wJWVxtHif=mXvZ&!6cHvf-_2mDA+H7Ua8 zoN4arG@9+V&dZ=6YFDwvQQHUOuGZ;xL-k%DGyTrXjfU_`7+L&)xU}r{Q zLmMXN9S`J31$zh_nA|``{ny7i>%dt@x z=7`+tpmfWz17>c~2!`eH`NgcceaCAh6N4BB|Kyg`Fh=vVrxZ&rRm4nu$@mTRFl&^Y zQYNr$sd$J;m)3p$@d1L85lQK*X_JvOm1NRnh~A0y7`D*9CNy00aM7J^Lxm*R=On&Q zFpw;mIv}YdnC$Ycb7iv=dCf9WeNbr1nBPQY7-miQJxFkeDieDa?Ilx_VC24Bxla}% zETHSv2^4G1k|yj>`*}T_&`%@uhZELqH41j5LnTW(gk9g{=XNTNr-e6PEp0yhsye!^ z=JB=2rNq>upE3>|mAgcFqd9>)&VmzcGyh$a8M2k(5+N2kn6?lQ0ljhk-huXpH6#Ag zeA=?%75pafJ zQArCSiSyD>iI31de(3jh32`Qr811K)*KNu&wgGy~Imh_#ue=?D@t)eiyYr9g4KaYO z7uRSVKC-7EJ4GW*Dah*oNB7%pIiu!!_=!r0R+LSsDoNTg%3`Xuf`X_^k6gATb3=ztV2o(tA?DCedOI6Oppbe$R91$W{%~3>g zOIuVjjj-1^k!Xs|l&DUxt2(dTcWNc`BqW_4-W-)R=4W}^nISKtkTEA(+xJapQCM%~ z8?u6k&n~%^D}XO7S33Zln!tQz)fhK4ymN_|l%)#0!yrP7pxpaov!;x$SDel3 zzF?r5teo%jKZ&HL!l3G(B8%n-p4*n}7GNo6X60rA5drcBlvK_}zz8paZK)w;%F|c$ zr_cXD-Yz}Df_W_wCo;LzZ9Iw2YYp;5 z@NhW_B#TEUbKvS6DE1>XivwA=BuhHqPyt^nM8p36h53slFRd+gDp^>umYi8juP>gJ zGFf@Kcvb^w(>w^IF$vSQfgcA69?R=?p&8gCy`e_}L!mAE|5FaksHXiAAzRNy4@m0M z=0g8D{2gR)g<~kam6*?s7;V0MtpbT%70TA2e44ii8bHRAU=MeTJSTJou6i#Nd+#(u z0ui4MPHZ@Tn0{zp+kZj-XYoN9_Q3l-sPzZ<8D>C5f!SFmTG|4(u&=&mqf}l8mNgp0 zc18ZIWBr$b4y$A}MX`KtK|dB8NlLufl6%S0bm-0fAQxhAu;UA;RmGiZ0L=uDEa_>Q z>=y;)rDYt4H4?CNWvF6jl>Om`;`ot6YtDcBGC!?}GqfEZ*gHk0Ip<_F7TrmurDo0w z3MlRG!x%pNWjY`c|E=r(!#JbemiTvLfHKLr9oaJqNQ4^`!wr8*#hN^Cv zMy?EA5cTr(MXOVr18Hq9yAD2N@V`;%t(|dynPqvJ-=uxEb&r!P733WmnEBK0=tVPc zWtT2_+w7<-ihN=ObC0_2z}xZG$I6tSCobE;5pW5-K8N!Xia;tMe@7+u+aX4ZbhPJ* z%U_{LX^LI-Nm#WL;XM$SN|J z1%bidVQj*JNmq;t-m9r=Z3s90RL3xR?(1Q8b2k*3W(thR%@>`{3=qu8re-h4| zFvlIV<>M2~B9R^fkDyQa3H(GN2@*#!oKRh1zVI@CQ#U6boMeG+3|7ijIY$>SMEEhp zhx{8499=dJ@P0|TGD}vKjyj^}kvo2*NcT&#w~1?WgkbQ`1!_dD+5D}DK&!_QJU{}A>J?`(Ri zRP6EE4vh@}0N}Jjcim%P+vFxfb{~oa!{W&_DBxcPLhjP00H{$YOK2Kp0Iz#0qr@U1 zm4ZM3;Xr4APzSv-8brwWUoS+2L^PU{vMS?};`v(D%Aow2Pi^fw6xcKU<=tMAe#FuR{#^ zwMJ)1qir9JosY9U+s#5Yl%SSSi{E(I&ake2D=$)GAxUQO)!EZ9dqf(lV;cJZVX!bY zm{mqdvMC8VP(m_&%_j&Sd%>0YiFMy6MN~*W^B#sJaX`SzEBO~pTBe_~U!-TgkKKq% zWhxQmHre!(=o;J~wq0l=nXbOtD1QciNJrY|0SMW5YR>)e?dw;H{_-&2{wAl7n@8?E z%vVY^fbhi|(D*&T{FJDxPQQaIaLFVXeu3yw=xQsg#R2vm*(g2q-52JxeO1_{4IZ!p zB3G+gOieIeX^TpiG(okO!4ojGRuHwf3NbC`;S=grNTJ;9@Z9gP#^PDDDW%Qj&zj$r z%~?T9HpE>+tETpdijXB)Gw2KmzoR)QXc^P0xHpNi;gFg{`mRUv(NL^OK*)&=QOF=2 zNHJ9A@2Y}v@nS#-j0*q29u$F}{ucV#SJGl|VN|!>pqSz>8C*B6$n2d?^@TI^TB)O1 z47Bijp#^v2bjx?A6PWz;Apw5?p}2a4xd}Y6()FuqG7wxr8eUxCz$l}Y^3ph9VQfsu7A(=-ZZz8Ih zX;lfl>L^K&b7@C5%=g~2@PwN6orlLGAs7A#B+6v4Y^PfKdU`seWfQ|dMPEQBP&W^4 zcyYt+d*EzAq>Hm*s?)szZWoE zMAFT0J~^r5iS*mS@3pL(pI|QSK!t-_^y?IgV}OVdeu5LMs9Yo}k`EZ@1h z%D-FS)fFDeZwR!0$MO4QTh4ZS5hugHZI&@SKC~##T?!R>Vs&%K9~E*y69-cKiMvr3 zpM>UM(LZ30{o)2mAL!UU3VGl!sj=uML~%CR^zvVz-JzO>T?GL+XKj@~rxepOEVsI| zVsUs&iF{4;;^)1>wr8&4ZN=-754)o&XP;vZtACK}eVdqPVU>U8{}6kxIhPBx4*E>cDSDmz<(yu&N3uOBy^>?uE41p)9_V6Vb3A@l-upAk5{b=&A> zxc@Qz+_ss*qj%sEpP_^|PY}NhZ}G>Ax7tLNK*rXN->%l-CdpDjU+c==mfMV`G(XZ( z2yCw1t1~vVN%}Z{x_L)#C-I2rYd464JtXX;=me?Ed?YF84)ngV_HTk)u%Tr(#JKB} z=bNIy&zploAsP?IUz+%*$Bk^hmkmnN|62S-XF_p-&zuUy;g3R-Irf9QtUOcYWvKLC zkRFDO4IlsgbJpve!P!R7lW15dvW)ajjr?jcXuUyn^_s=KIS=a8V`D*hr~Zj6Q_+9V zXmHpq*6f4fC*1MWy{@wRk}NPyq5q(**`fQK(K%G*51NSBwFi#t0?`t=gg4T*FmGVrigl*&iP3BJp26WM96Qu zKYb68`?D`CoB`~(WI)*^!w#j_KZsN&XJc2NLvg!3|B3%l z;csS9v*RB{IBi>tEdB2k-OUf#JP>(iD6;&hv)3=zfEq{+)HN+f?b@;$k?cw=lVh&R zR1QTFIUaK0Q7Lum!*KO0-;dszg(Qo3)+)L;tw0`CW%EW_ANfNwouH+P9z2kK!x@^H z2Hj9ly`|_T&x$;p90gnVxc$vtngWA&duAlX)C=MCUgGAiDOo@x{P3}1-;Us_PYvoEph>l~|dhds2 zI{`MiM%ocRublE_n~dhyj>)SenAjT|(g8zJBekCpY?ALPBf}Pn( zFL>CG*Eod)i$h-+2(X0KZwsM;WFuwZ77Dk{!tFB_-0BX}`j~v;gLhiB0x+6v+88u~ z62ETBIMSc>3y!tPW7z%19pT`3|1b;Ja)rm>82SM-5-^#VY~G9!Hh}31!4%76RG7z= zn1;1Rhs9w$gEsj42s=~o~basXj+ zv_g(0l?^BTHPYbUk$a>}{S&1={~-fU%(QAdSeB-KJ&Ba13Tak`v?)TANl;hU{nEt4 zJ15GWobVz<5+M;$NVd&H+FEW9wDp14V!{;^oeM&^rB>WBD`vN!ax62qe2&6@JC`r* z^!l!tQZn{yf7Yk*+GzYa?u_6<8RA2C&4KY6&K0EycFI3>sDBxDWxH;fjN`?>cnK9OoouV2`lBEVMl4?kHvLz}SB}vOirIO0` zH^1vT|DAu%cAfY8d7k@z-P&ytUT>?}ZEry16*zJFlGg=r<2{g*pz}GLb%ssEQHZ#4 zz(GL5-UFz_XyW)jV|sz{IQjws`$6EetK$5EX*%~nI{bxUSV#IbWaRM=>1Rbm`wLQ| zXc<4(#ri3tx4xGLa?r2FW!_lX#04EwTSP>eXZDq0HAOGH8IR2+z~SRCL;;}tJ!|HG z>1>A2-0~6CwAynzSpYM;gq9ssY>DPs*hK=tk$?l-6uB0M=K#NCbG$qKd=8oIZ3i*c z$|B*GiU$d?Q~nqp;oz}zm^A&~&&(kVZDiRe6V%@l z3<0=gwb&y6igKZ~dH?P-z1_yzQb)3OUn-V7@j+VM7n_Q?K6VA-thrO})l~VC*FV<}wd{YN9}V&24qCV0G#YZalO-mEb(@SX#!vdhcvhdD)StlZz?B56hCVP<;ePQ zG)0~Qj>dzQ#)ji>U`vcG+%o_A|E$a5ohe5LQ!WmbVT4eCRjDNT>$iS3JfdS|Y_12? z;e{De6^*SZz0~i*6dGpmka6SrQ`kZRriqU+CBr`LhKY|~a9h40Lq5wjIqRp^B<-%r z=??jyljhmF3!B=vwzN6afs4&^l?nY|sk6?F?t+pichvO$?n!rbX0k(&7kfD^p(iRv zHikmDad#fa{bP^P##N*BU0)8 z(;6@aT0aQd6c4u&o9U^tgNqA$Hc1M&+q4MdwQ}>m^6DhtHJzN;4c2@op<5> zl=hm7SUw+}yG6j9A4gjQKw>hW`W8rw&U)f`WZo6r_V@_-s<2g(mA}zdo>X@t+4o{r zHmRNI>EZY50PyNh{cgW_znrUnAy$ZP%Pj&Sn21}_g35z$dXMbx;B~t%g6^faZugy{^!eV&PDv&~ zHxB=~v$dF0ETXU9AbpcnrXvH~)Xf47i8n=qZ(;?2pOcQKe6$N6-ae_kgV%qztwXTt zdW;qiVC z%-4TX=Fc6q-ESc#jEnEQN*Rg|pTD{%$5NCYc*m;V!^6)_6o}b8mr@*{8D+Nj>W(z0 zhgruS9w>f3xj{(L170!tu-e^`-F(hwb;eM}g9G{aFiF`5Qp9=jOP>ZcQn2-htJOx; zbSp(dOVovYOS?%C8W-WsMMN#hY5`M&0x_#fjFqkMxr?+xB0t|hw%+O+zWe!1{RNs* zaIZK|r}DS`Mmg^!VsvyQYByFRXc^h#UOw&q7$%H|DS7CFcvyI+wyopJ8?Puk zWygXsMMktDAMRWLDiNaXfV<2QP?OSsnhK+mK~h2gV|LY%Vb+j*AE{x!78XMyAjSuI zMYg~aZ~XkHIkX;E@<=P{#hg(nH~*iM{ND!UJy8LO#!E#@_C1Q)lR3sS zTH9yD9sjVFqOr5Q^hS!*rR!x2Ws(o^>NOLxV-qra7nQy&8rEcFpPo!|=}xnkY8*lA zl*<&0gl{(nZ3^yN&ZB(`rf!VG?IDqEjg~{v!1F$nRFh9`;&FPlxi*KkBk2zua(qAC zA)GBVFW<-(Ke&Cmo4Io|Iq3MK-Rfp+CuO7nJW%^^dDzU|BAayZTzDSg*s<*>KA=ec z?+hH={o_Hr((}DPl%w7Tw9HzBw_HUms+f@_pwnBpp%XSuUjom4UK4aknwBRRFIMM{ zN>=4hTv1-F+1WM^43+O$_4yiJx#u)~Yy9=3h^LSj%op(#BpT)gOA+AZTx-+U>N()1yO5FiWrUm&+VrCt7{j|$ntbzd^KG|!B*Yhx8*uivjSR$q6QFnWrSenuID&$E&mZ^68Um9eikj24{x_F(VX*1#SMI~F)qATO z6uI-?N4S-kHslykkixbCv#dHWS zk`^QSAaG_fUQ9M_!S2NO)xoKbFKYd#$S!9zU*gurRAJ8zDheExaFGM(fRRE8i+yy{(vzNWQ!uP214t8Hw?%XH;=Aj zu|V-mGtyWt_t<+}m4xwZ6(x;@I4cvocTJ9sfD=r6GYrF7EG&WfdTb5oMxxP4IJ3Xk)4;$(FNSSGZdZmM$F9#>%Xp(keXJHqc+6dSg&cDaFVpMpJovW4~L9)r(f;Z6)J9G@~(( znwC3)i+oV8Wb57&v9Ja%TXr|EK%`9FE1Jue)@$G*OguLdI1&mvRJetqkQpv+N@k5( zbT4sX(r>&})3Edg3S8P0Sbs_ZpFwFVIHhQgvpc$kBe}Fr9kV`7u72uymb?h}wk5Ms zJE{M=)9@VfvuQlEK@PzA?vcsD+My%hc+NN|!hxh{z)cH7sA3Me^t&adPwUL9_!SZwrO7#<)YDk}w;$f~@MHmkjbR*k=EjJ9(9 z*4V<*B`V?@0p& z#^0kwWd%Z--A*VO(cl-o$q}ikC#Ols78ILHMk$6{;AF?ivG^p2l7`oqm4^AMl0hpK z=q)Qwu$;k|e6WoVps~gq-AB`n*Qj??_Ugmf;t6HPKJ%>Um2f;+pc*S_7sQ9-$N(5a zaLBUR9wjGuiQ>>73Akbj(a}gy6n(PDd&qEiRn9&IjMf4*@dPcW?Uu0wdRY6+&4!ugM0EAa=+nm#ukXn>S$ZW}sOsqO$)c-a%Vc&mH z%NB}_+1c7F``Fo9+?CgZumMP-FxpwYfx%JlaNKrd1%w&UE9S_q#wGDykqTUB(7Z1i z7@)wIkAbIIeXJ@~9Lja-!d!)x?b%cOSXrR*D-FmXSP9XJ3_$P+nMvfF2Xl`>?-B)8 z>#V0KHGY>qB=N0ZUKoWtKJGv;7;sbv1+|Sp!h{L7Km6dG)DhIPp+U+1v513xYrnEJ zvQughjj|cAki~VkQWbsOXv;)dv6fx=Yn}v>T**!8ubzylV+*^Iebqi|PU<`-_L3b7 zvW)qWD&Yk~4(s6gLk)o2_aeCms}gmmgzbYZB~QtLk^&K}swW2Sd{9#02*GXvQl$+D zqp-!CU^-ZSSAz{VXRt+s_+CAA#YhrQ%VNSk^ms@yvL~v+0i#D(f}~LN@kTq<)mXS{ zH~v+bw&aGW$U{AC-+smw1s?3Ze}LYRcL36i3u4h+*Mzy9 zC7&FhcZR(%I(6Ms-KK4~=h<5~N&rchzj}S!fS+COy>BWy`$YM~*Wis;-YSICddWq1 z@n>kc5e9=w0WFiCldJtF?AwKc6UJ& zf>{rVEaif-yj)~%J@~RNCb~o-_BrzoB*Mr8gQh~JWtkws?v9Wj#ClF6v-;dAJ0~$O zQAs=~Ko{~COR8Kj+HXDi4tbowm|xtyWAmtbj7cC=#nRRwQ7ei~<{z0?Hh;j5(*juh z%V`*e3BEl5!A2vFAZ57(QEdM0>$QB5SOF~a76r)XAwDCeaq&S>C-3X;J+;HP^*s7% zqoMoFK%<&xIQ!$*>Q<0HHbwlolFu6cn&l!HOI`0Nk&cWtX>N) zHl<#4NByHf8it<$R5Z94HkzZtMyhc^3F&Gi<9e%7VRxBu=OT?f5^gqi^Hdvu%c5lt zq{LI;6su`Bsq~gZ!!cKKMWbs(H=8&fC4R>yOOUg{apVz9i1LR2^*|TIkOa&B$2!IB zv@r)?#klf%hL6VO9ECP1XeA1@1NAM9BO2~I;^^PrJkIhxWuCav7ueMNghlG*h8jaG zjoz!-ahzJEcSX;=4~qJoxUjTG?!&rg=8{p>!Y$?8tpW=gh+|=z6>VPs9_wa_9rh1d zvCdxY9rt`D60F%o3NA>ww2_fmw(>^fcjKI*2P0QUFDINQK+hTS(k-_zhucV9aoFbUP5R2uUZE9*(y>SbIkT zayfKZC&XWd^H%!oCU|V}$uWiPJHN`P4pa#jR~!+>SR$o1ZBOahep*Z?^*bx+5I`1y z(Mtg58xZ{$%II|AOlhm|%MM4BiEr^>gcTtDBcN}^!ml*oXf6RCfH+lMB2ex%i-=>O zk}FV&4AicV{dOhRXGuj$G52iD?+LH#qF>Hoe!9hywS_cs{qg1POE*(_@EmuWGJZjA zrNcG-%O(^tt%}Zn^7?-jn+l_fHmNX@F(`$GWTO$gAcT;5MdNbrnZk@%5RwU1x9am( z-K$s-7dzDD3yAO)rWS2$NtLx4U2QDraWSBMOcBZTxGT|u=b5U)WRL}2Bj;>K)xo7V zEU~pNeaB0+<`19hJ4~iP&*UFG?S$0m!2J~9c^U+hi_8cB9{ccgYGO zG?w7;{WRd=Ruynrs9z~6J1QS-L}ur^vs+Dz8j5+^yiTJHZ%q4@J6xV3boH|yd8ZCJ zWCc{GBOcIN#Z51w{2^(C>M$Bl_(q-Lo!5Lpu`#Ru;@tj(Sv^X`&r!^zy&PY9imRsq z=IZ%;=~@(_MLVT!lVke6!St1q#h)l}JPSRF@=X*Kpno`??4P)$wKGyhi> zUS2)ljI9LnGLBiHl8H_>>?`))9G^=2VCH(}q#t8-&8M7m(i0uB{6`CpIaLKUQY*F! zFAikZ7Y#h`%}yQAutD6mMNE1-m7CFu&QGw7W???U#q;GABPQF3cJ*e2Ij0p*Q5hah8jZJEq3J9cdr@;lW*l?oS*pW9O}XbBlnKAixdC&U$ccqeU$^FbWLjxgoiJG4 z=ee<+pA_K>&7GQ09{o+3ykXk=_i?AzqK)V<&x>&(G)w=YJ9&2&v@M=IQw$)8VD&Wc zz^r+w)2?gvetoWOSAyw1iLQo{AnjpbV;0!hfR>;;h!seD94E+;otU&!UJ<|b*G?q~ zcp5oZy5|yVwzA@q=RF?)YXz#jWyvb!2NmWo2FZ+1c0F1LusXpLozSq;i?k$Q(Q~-Z z+^9cQNp4^~k(PpXOJU;JlaL96-5)|{TzW)ePS3ng3B0XY{&6w$T4zRV zX~jh-Q<{jNjQcPjWP|NFVy&Yux<*BYcibXd7#cfkC$YD*4c(ncO(qqvR=qL3&vw7@nK;fr7FMuj24c}JH(vy^8->}^#WyGw?G z9wYYgMd(0!SPu_aBhkk2m455qQ2Is$+Zb z^=m3w+T^TjDv&IBO`A+%9d~BoW=lf~-zIjwNw#H$1iO;<%EVQJiUKPkT=`6*AnFLi zWvq}PeziDyDatSq`Ln;+mbPDHM|$q-TgL-`m(DQJ*3VNjjb~A@%*HcBLFzb4-h@#l z$UKwf{ZMIlqS8LzCDid}JK9$o3otu1@?bl>t`?G-tcXpxna;ZvfY-qD3#kZKI;V?{ z_UK0WiNly-)Oum#eR zIx-H;W*$PPQDE_zhd%#U#b`q)6llBwD+^EDqs=$ zomv!jTPLVk0Vy#!t_>Vl2ErgZUAY6+X#bn=m-9-CbUH5K!%?!RZo;fD9_{Ys#(5XZ3Nc zY_#JOStFE8Ey}+A_549ATf1iu#<#}lxF6#Qx4o@5d$vVg2?;dEE*6wt_Gv%;khzBZ ztr@p?AhatlQ(i)Fue6T)FuUehW~1-6yorjRFpO!%s`~FnjSr22PcXBAFPeF59b%fv z+Wz8Zl@{9zk%3JW9E8^jLWwN$J72`00C<>Vo1$!qHV(q9C`>vw51AS@gex^yH}^Lh zSjUJ|eEzg^}a02i;!bq8Czb{_#nXlneW97qBEsqPKDNho+DDSa^^m0(}p}Fc>~1758%+_L~B-QP)RY%isk&(pZVBzpKd_(Z<%9~?E8gxDGw9_UPC^ZY23eAES=kxMKte|)A zK%oI=RJ3Q5SN+7b{iAnYzk?a(>iNfJHSbsU+J3|fV=Qs+M3b$|Q~ui|wA5nmiT;%T z>8hOca30fLm_yCaYk zgCq$kzKme@eK*7iz}tgWv#1-BHI?G8E3t&H`g&|EA5ue;$lMn4hN;SU^OFhp5ywk1 z|2sY$OiF1Z5mDfboS>}dtgP7WsAKfZ)UK4b!Dlu9Q(B$5 zq^Xkq`eAmubLO3sF)!nP9TuQEo|m8DNkGO2k1lj2BR&pRZl{O$q@%@@!`SK=$sErz zyTuxp;iA0Au0+gSdbYe-OkcEoepJTD_lYC`0)xK#d@noGz#UF{~?Eylf?i0bb1 zc!e|319WqE0aoFn@+g1N4T*O&O$FLmaDNqfn)we(DF-j^GPJq&wcD)_8?*iIS^*1< z5qC_ACBLaoBj6)`iGJXhyJf1{HJ@0c)Cv1mDtaXX@Pt!=s!Gn^l{Kf2con8S+~=jW zezv$Hh54i4MOrCd#lY+zzx!AQ$rwGtG$EHadR)k5iOJoVcT5pKFIRGqzG!y}hquhs z`KNmP9r~l;zBsqn55FutO8f6jp0v&4^3yB*$Mg1W{QUCz@p%;$iMyvh&dl}S-1+Ft zsc+Mo2*KHJ%}yMQ7Nw9Zz03KlGtG-ad_s(L)(PKIh-#KjmyfcVNSE@``8p|Sx@hbN zni@;GtLr-Spk-ax1s-@z6a)!J%@Bmd5P6X>TeUS1wnM7`LSb~6Q7{!Emyh&*vq8xt zL@@w_WDo{~$wv>qE5nm{V1>L61ffKU!Aq#B>Wzc?1pefdafi@BvixPKCOQPGjS2z!*)2)Qi0$22J`B%~tLHTw1*X zH8nOKI<~rWP4CRFOEw>E5Z~Mw(AIqCrBuP5G|y8j66f-hAE{L~w=I15zLWTtc&+N} zGxtgo6=P9efRW-b$!y{9aBI>vhGQO1@(H8$$xG$O7s(PH{*jdOGccJ#NO=`vc3x(x zx$BiDI(leZZ_q)6CXGzR$Qw{#3F>f)_?aCh|*=;=C*63@X8r!*Grz%SKWS z#-V?9#Cmi_^_M5<6|jzIP0QCRtfTH+#B^zQ1bW zj_Z>FEG-5rC5DlRzL+Lu|LGK2Oke4FQ|+Fff(~fPeO-Og(bj( z-@<^UJ$~oWm}|T0b-j?R1d|akL-;{#dpv%-$*}y+^72`h)O!x zc2N__Lf}-{wc&{k?Je31O^8}`wo0I!q_!9OxLm}%d|=Ow;>2z-rAf8)vT=^&JO#0x zjg};Q8F8k>Nt34>EO2aIH3m5v5iPpsbd`{6cOL zi6)QH;N89yKU%BIi$O|ju|#sY;J(3Ge6p+gU0@ZZNC<{q?rW>HH-y^(3V2JKfTr+K z6q%i z>>GNJfHcEPUa^WVGHYF%Kv}ji@;{L{H;Zo1*mW>q6Z3~*nv`)RM`7Ggmb0d|_2cMy z3)O;#s68QBjwG^l@r5O*x=G-?Gy2c{odarU=Rpe6gTWHD!s~i09tm!~E89%jmJ;xF z2xB*O0V`c?t{2G&6ZQo~mDf(I2LW&re+xpEP#UPSlyFO^3x`;QH^#pp)Vu9aL3Brd zP2Uz)vMIa1r`d3&-6-tPGI1)2Z~obD6?t*;CAPtPdwgZ6>FP{gW)(9-*K4Qf_syP% zJ7v=?5e97u1CNyz$};nunj<`4T~?h*3)IVBmN=R2rA-D=D246^UTcUQ{u54KM2y1) z0jC&yODul&jjX0KGBMsn+&Ac3=CqZRRDoK)!6Ah9%8IDEGuOkWt+1fXyl%%Eoss}w zN~u8^a84B%mAAcGX31pPdQbY8PSwHUdexBt07zz05XlrBk}iZg zDc=39BRuoiV#hZ@GB58>b#}_AK`g||G7EceqkGQKP-78EZy01{t#O`aXlO3!J?{vT zJTh~&TWr;I(0#l#W2V!RD#hn)?^?v1wok0_qaz+0>#?o^s&!-Ehd?uic{6uC`Y;PZ z@s?SIebed~?*aRAYnqfP?F+*VkV9)}j{`R`zYOM8PFd=X?~)xkym z>jxJSWLL`YkN$|Tg|DdWhxkTwS80&Q0Wxq`a;l<_&ujg>diTmctH-HkmJ8AUnn-UH zls+5BPClbX?At1@P|0&SD4xFecp4K#nO=6!E#?&#RCJ3qAI9AGg-IG_&13X^cHf^l zgEXyE72i*U%Nv=d?>`4f4F)}VXa#1^y^$3Y3!42-6ScqU4;Tei5B-#V>ihY^`s;lk z7KUg*U>EOQ(|=n~4~YN)02dy#Ld8pi@djaG#{P>ef(9RW>Q!pued@*V3)2J@X$$n& zJJ#%y;|^@YO}N1}CdznR4r_3LJ!obu1S>P-dc9=?(fvHj{xNRoY|oQr>pd;|6MrMl zReByJ{m3*sbIl32O5f#tID_WB8Iy+-nh%m&a+vc9;u> zA*J*|UGHoJdZ;qkx58ht;!_rAPPzOp7~w@ilE5oJ7_cr3;mjOJ2K4PImE;f@X%XZW zal0@`f+*5hRNB?ImgI323`dYCReN{gBG2qiXjkDRk|j*|Fp;K!pj8>Dut?Ia&P`$RG^Fld-de za)i!hT6p^7RKPU`7-#aQy-E=UKtJ$qEENcxD|svpzQ4UC0?!35TZHu%Uhe$?$lCda z(p_nq*bQdYREc=1dqAjHssGoJV|%>+o7*2ofi{8HL%ni-xzE1s#}ep#SaY6OFU!9E zu`2G;zTdCJK9ojC?nzADm&&;k?z2xNq~2!5k?c?xG2xce8Wi2zHT@_k5+VIh*6=#2crNu5hxP~F`*!Gh5SK@r7fax9=KS9ej)h{ zBc=wG@VFpxsLVL0hEZM1STqz-mFqcJxV2IUaxMZZkbHew)Aevgo0Y%a;Wus(n_GvX zdfa%;PL4+Nj+={9$F&GQoFc<I3q!m(PMy89bk2blecf}_i?$jY z@#^+cdPVnYmC%&hE#EcIshA+f%zNp;jo0=ZiSKc4={9S|{y|@Puy`JYVEOywe?>zH zh3TPmk!Q3X(jR70 z59rwN9=DY0*>d%4n&IR#(OVG~Vnn+@8xXg!5wMWRa;-lgRe=*8o)F?z9#v=WfP7-j zj!V?Igi3dGj2x$C6&>U7d71cN=1Umt$g{GYCtwD-3vNgJ-P23l(_{Lp_>-|E`x3EU z&q{`7r@fR&m}t%S)>wFhE*w$@gc!Qqt3zv--7J7XuH@5bVK7^>K-8VU2oq?`i~2X{v#@LB@)s02R zjG99u^?KJE^_uP+iV&apQdf_lNYY|RH5lIH~z6$p zcRqZBf~dnH?D&24BXAu)y2QOfoWgeKVe3gq-XkiSPBks{uewf|PE>3|sfc()=z8;-{++sf2 z-{4YyB4(pPM3hv3Cwhm5<@pl&@L_Zx9WQv|bC?x$^q$DkfL*EJcsQMaH*l4p7XUK! z)KUs=oR8!3#G~Hfjn^>r3>cmTn|g}M>Q?^5(pjhKRIzndK$Rtya;l@UFc_(XBaQ_? z+G^c$?T_Hb___l7jmV!8&fk39q747rClh5f03WSy94T70Nm^OcJ7d0ii*QRfEP<6(J?|H)Uo-~0^LMG?q%46c3E|t+^~V| z%9rb_?RK*U@^FdMYt3U?&gZUP)K!>vU3o3pg?m}3p_{?^U+XZ3B)`g0i@QuMSfD;b z#t5yrpa(V1gZe5@LcP(a!NgI-0VdqN1JWVo*4hMR=%pH^Xj=Pn?~$F)vk+lL<$}+e zPq-t%BKNn?wSN}S>>Pe*sTNE)SU5vmlAc18M27-R_!F4{I1fifG zQUXVvR7V}gcb!~ED`9*i)D!x=n>b6krlF%==OpPfmDYJfvCoLQ%kQ&qbknQ26h^}r z1Ioq3d;-O0H!oaKQ{6hCJ=Cf?+6Fh1T!u7MlhB0psfg>i-(c0}B9=#l6Od z_)`W~L+YM{bme~eT5er~-&dh4vGiX=B0oaMRpf_@CEGai(^2$C-9OT-y?^;QvY9v^ z5*O-~?VKz}94+nAjA!qv*|B7{uq>h-C@~AFrGD3r{jQtZqmBN`ddpLN3yF^add)q0 zS)Z28TN5Z>k25wzzrKy?r&9v;GNgJLnVHlfxUI&|Z2dc57KV1%o{;Z%BKGPjs3Ytf zq>lHhoWbTx@q1m_Ww%dd-APAej_;AHI&nTYt(99}1$%6L@ z{S2?fn2y??_}DH!7C}WsH9w;Ov-E6t>hnI5Du%Q;w5~WfoBQr+uKCox;UM48PuTKT zrsGTZE*v!2UuEsHGjD<>uIHVH)G#wW>S3|c6Ilp%sDs-J9^2=p=>~OPJ==42-?7k- zU`QrRC#&b$S(tLcn=SQFc;iA^bEg@V7e9E%rm21N^+1wMYkbS&&Zs*E`xCyNp%iDo z&b;~Od-AQ0CG@%tUv%%=<9`i{^LJ2PqkHXDTQXls>7JlTBdq14D?1H7x0W5%>HN8| zw?)VVR%oWmk9Xf|qAHlnOE(mvs|GyoW@&U$K@cFA_rri|H7t1JI+7*VKI! zY8fx;NB~rpU4*DE`c(8HN77GaP*0WOt6$Bno)m5_vA2MiXaHR5F|J6ntAN{AIN9dH zZ7Uw@a&Lzgvn}ub4gF6D#$hRscj+vF!b8dUh%|*|RQ1?;91c|}{B2QSJRUmBH!^?l z`ivmw24Ty7;+z$aX=3j4;O4c(1GqnJloOIP%VTyX!m&0rtm8Ph*LAivEvf9_`3P6k zG{>q*=?d%41=L#-Sg{Pf@duykN> z%U>Lvn%?R^PQmcDi{c@40epKMJPY4z#dWmYXQNluqg&yK`vv08_9&A&Lcg~YD}?zZ*Y_fCCNI?WQO)5j8o zcJ&FbJaRt#uca820uXYB@cW5h9W%VBW_t#btep;cb(`()tg<%it9hIqJv34n`E`tx zEA?UAr?$Rsu=tRqX*e5^odwz`x4uCPO4X65YGE7kprZs@GLd7kg{7p(kFJD*mNS)ID>Q}6g$;x=mfGQEKMVIs}7u2}o{$ff&tcP?}t|L)(u z)Be97t26EU`fq6CEn-jIJvsc+P|@n6K*(G*J3~5^@b-Dab=L{{_y#*VsY^z$c!$_4%=F4DXF1w;D5c3)W} z^?|R3O12a}TP{S{4+YWV!j*bC2BmUrR^ClH&P#s3^x)cGPKn>o@mkX{tEn`6{$xc& zwsuFM+1(!lk-HwO*A-v0U!7)s_I(v7b>8ng`Rcmgbk;{B>*cK#UA)c8N_D=?$Bo6z z>7f0Wj$b*`rYcm!22CAT-g~O$;N@gU+%kxf{=-phTY=KRIm=FTq-tg-+I`Nfix5+1 zR&{$u&3wF|R=i-@3Z7@Svi6fA`jzsbj?>9h!|25Et1l#5hhLQs^yl?7s@knl(D)p3 zkFJoE3TEMRXtO9)o3+JEd@4|rrjoir&Qdcrs)4KJtnuICI6CZ1RT^#su9l>8>YZxf z^4%zW(9iDu7wtDxvnn%_lCto=;~-KY0b)VHZF3n_M_ygeR1QC8@~*^z@In2lUvmal zVsvvuL)vF`HVtn#W(z(M2BVQe0#+;=`&WZ z&c->f;jHrrx!UW5t|iYSX^31E$wbskMI{VzFq%x8%Lq3`8GQVNUPCEdUUGu*3pIQ zN+*+8$p58*_+%(ue;tzDpt;#JSEGEgBFw5Qa-+PuZ=>QqOK~?i2iM3b^EwvRd(9~Z zvAyzDud9`Aop@|un&NyIE<;Ot?47?(j2)|ib@wxBq z-Y@!Nm0T_vX*6PB6YLLFbOP`|OcnisEiL*6F&$o~{=AdG(K0nM&27RWSJ7--3DQPT zjSEYJNpT?rX^onsrZxfGiqe$N!?>Dm^1+6awNfqbT!p+%gm7elW$UdvldTRsE$z#N2!Fb;wO2vK9`fH>w;t&Kk%3~l{t%&RF~294evlGE#GF~ zLSsT(txcBV8=J^dp~7{Gy!-I?XY;FzP4lyFFYgufNVf4swk1tqXTGuJ(IGZ*F(1j1 zhh=F&@4GFNn#5J&vq&QXy6Ek2%|jIUnKD31iVrIOh!A;b6AnLf95}G`4U~vFz{@xd zAwYe0cMhRdx&FPWO``vr#O=sqHiN-X1ILuIX zK;c1m-q9qnSjK0Q=6#DTyVnu1uj7bgq@v=?!T^*l_c|^aQF!UXJKThSaT)ax@et=PoFEMVa4RND$Hy0YZ8kTu z!*aK{T7=oT35L!(4~4JqK6%YJ)7oQ2alNV|K{qk{aM*0b#O8rpMdwCicIn`meR_)4 zb)WK2b-i7Ua%!h8&V4@$#w;|BAH0?2Dly${ zIuMTA3i!!&vkS^Fuj?M!pT(A~;2|`7Ia(GhBlV39U{{2@tKPTE0eGdR5 zW56_8}Cv7jR^f*fN&~cI!2Q87`z!lQscH>%-3C2F3_yjzwez7w4!cO0=pk-j~rcdhI><$PMIE)bn9*8_Wru=4Dt>&0s zM3^iG>-dI38lq4h9~Y*a2VTRj@#zC(QLEMO>jP5C;V1@px~{Iv)!o&K{8W+wT6udV zIu~jH(;5OGiA%es=0WDVYhVm6_X=Hl2nXF_(<7d)*NgoTusZ~|#3g4-pvaO^SfmX) zP()Q@MCH7(&f%tl0@F@cGuLXIFHFtSS?*Q!Rs{`~z4iIx&s~0W>|kT|Tx?e04Ny)? z?2F)w@McKk)GtKdmj&I+9Y-$nkMJJ0D3@slJD~0yI6U9S4S{)ZclN9Ga6<=NI`|?B zO9EVkgskmK^*C2{6yU7EF+~8XgCS$rEfvU;@mQ2k5Yn2@00F<$4|tuMQ@j@4oV&tb4{U^}$c zU_*&UY{UbAGBltzAgI>Z)v?SEjq5)y{Nh6TLz&{e!lZ#B0OJLT$GwpVT$D(pNT>^UG-_l;_zD zP=>G(n3YJo*td^!< zh>oke=3pbn9v5$6?W+{^T_SP{h$+@MTI_$qOxgDvp^>V>7bq3fDlo~H`G&3LUq8xz z#5$N9`-=%idIX~n#g0JY1MkEQYINR;%ieSe-4fqon1n@`$f}6mb6CMnQa-+UqQLQ4 z%qWx<)GXU=@mDt1}xV5YtWoiq}OtWETWy|l&`zL?$930%& zbKRfw{A9@#YOVM`LpyUIBV6{Qsc5X-Sy4H~8M}~fgUnLX9U>GSgs-Vp7y{&ffW+EBUOcLyJ6HB(z0vX6o>gKz zd}wkhKVg<@eE2;p^!Vw!jsEgOf|8-wYv25Ja8th1Bx5k;^m|kl0aZgw<_HKcxPRY& z*in2(v-~~8{|j1$V0UlR!jNl&{|4-t5o`?@yJp-04=)gf5ca-!_e1-=rsD_HZ+=(g zq-b%@Ttgh}KA_oUZF%a+Pi4YDXK0v=ZiwGJx^@KnfreEMg*O8>{Y)8-n*QIyT(=Uv zTjl@l;Q~F~eS58hj_dk8^pcAhH0akizT4|RNRaAJA#>j9-4|b& zpb;t<0ynsmX2&tJyo3oLaqHQ!f1cQT`AVM&7c7UACZ?4BUKN|+z+`S=W^>F;l~ErF z!SC|T1HJ^GCp_7I*k(-^v^GcWaw;>?v=kydEw(OpF%bMWH#pIG_hU50Q0U}!f2JkwjmoooJBxdnpTZ0EW0|^cA3qSIyIH>7z0bEL2==aY~ z9Ku*)Lz8+q^>nUu4^xa#yKkQt(*OD$7YAE=ie28tgp!mZiyziH1Y5kWO`TM+1$WRx zJoRB=DzQ8G`!9wOe7IrfeiJ zAUp+C#eYa+(#CtcRHFmUwO@|VR|il1j5MwUNC(J@Jv8drK0ysdLHYfHcf+s~W8wkL`IcaD z!=G=8Z}d6S2Lm=7P#Ipw*bC)hgQB}^$@ZUm2h5pMD5AJ?0{7Y8D#7{r9UPSeUmMgpV znYU5w%N-P?Hd9o|TeN-dE2YkfI`n#p`+DmzD`e))X9jkcre<6hzovv50u+2Dm$w`D z&^H+FS0vwiJZR*|XkGi-RQy#s>4a>rWb?zkcA}Gco15sM{?T zieO`bI%4V#O4jVnRn5LZ%+%*cta+FyWf}XhBes3Lj2(4Ki?x0vrF5QIRd1VX7Ra0~O<4UO&;s+HETd6S7x!*mcF(w0 z)NFNSh=S-zZEm*xQ3*gPKqv(+86+Y3CvAYb@7XOIpT@IqE{+~Jb57T^`g0QJpiIw` z+UFFR75>4WY^A3k5SuS*fEU%l3qQnLFy_*g&Nxftj`9-5sh%k+~EQC4BK}buU(~LTr zug4!wf0RE3kw=`uy48Po8~>4Yc{%6M*mLXZu)4*^DT0qzdpx|&c<=12sDvUvxQ%I> zBFeW3yr%gNaTCdXho8{`{yt(oP>FwOgevF3Ee10KyqArL2=-UE17+FGeRA#E$LVVj z`aaL|dk9XZuBz636zT>N77pyA_K(0L+bn|>i?n_&lo%mIW;}8 z1!(P{9y%4*DbC(d?J$hg`1&!`Z`CG(_h|IZqhFQ)oO1xquNIYqDDsfLwFtc)$a>Y% zmnDQEk5}WU0A#hc4;_K41*&e~+m&4xFf_>aI;y=!Ctm7CN(rmDW#K z<4ihbO_gXlRgoOhSt1Q~HS*@cy)2**Az*Ko%-f?t@Mcg{)UhzX5aFSj+m=f83mi~tMe{A z|2=3G#-+Gw3M#srE}#!!bUqlLc?*30L!hcSAqz%WLaO94PyA2}@L zR{rkO@RkcvK-2p#u#UGOFGbaxd3UwrEDn7b#1mvU2fGyL48C-AfqPLLpJU$yOiItF6u1a%7B zWMfKQ2A#E43Plb>!&Rh$%9h2CdYxu^`UOn6X8Fdqs382qlyhyR(xzj@rQBDvvt>`L z>t~C4n-k-O9b5JoXw|$f@FdndLt-f!?NSazqs(YkU2+g8b=)5j6muh9q!b0+-3#NK;~KiL--}tKQ6em|KR>5TdYQYh!!jA#q^E zo>Y72_w2~2BfxVk-2%Kh;B1cmTC?>9RfP2RFevDHCK*#PGrAq%^U>2U9<=yu;&d%> z{CmPvqPA25uNF}n9CK()($&8*Ox!_l*g^F?wGN^oNn-?_DmnW|D*Ox8B?ByxjAug2 z_M{Gj9pkGS&T=5#+Jd;i`pb*<978;VkTN#R`a1O`>VD?T>wq2%u_(-qDF$w<5Y7&ArzlD_ivUBWLuNnTB3;5ADe&=P2*8hguue80u zZ|;Z@&ry3e<9g&%DW|lDJ?Y9_w>Z?0 z`Fe<4aYNRCvP1BJQHY$SfsSrYW8u-%^zvPfV0CZd@#r(MvG;WK=5}l&FD-M!4Y)n? z6pp?GrwU4@GX!ax5bry_^I(Jl&upKezxs9IJAD|w^kKJ4oWI(75 zvlGR$Ra%J{Hu%H1t0sSyOL;&~3-tf5vg%$_xoA3ArbU=X#&0*l5`u}5Ub z228kMm>Q)9`I`dz&F@4=>jWP2FN$hG9Iy_)3hNOLQJ^d#AWX<4@ecq zUm;+5u#YUL#afYdN`sZ!Xk%S*qvYs5)pwKL$|twdFS-cML>}XffN7?4S*lyLxYHC5{OLXY4qBtG+l2IYR0j8u43~p`x;Y~%ICq8n?>*IN zB>dE`I~=;fx>?&x!aR{xYsh3Z>DeZmQT6lytxCXN6M~!op53hit}8M&WoXeW7`xNAyt1x3I5FUSQby>2 z9q_~=%TnigX?9=zb#p5U-cl&fIOo%s^SUn=MXCYeKK&b0wH@!4g2<;a`8_qTS9TX) zhE5fq+;037ZQV1mM~r&9+3R=is!>D{GWxEP)t^3F#UCJC&KE0%T!x*#R>9ZWk2h}( zp3V7kE=ovEAp(=wAo*?UqxgrF6iku<%lG$+c+LeJzeL39aPz@A(qs=d%HB%hZKqik zaT)uKlE-hmIoPS$tz?XlWPDB=&~oXQNwKVs0!{g17-^dm~#NDX+$a+0g+4>(MyN!0;(>I zp23h&ZJ)~ol;w}mRj##rxsAIAtLzs3wxPeh0jov-KszjzqiWknLp);(V(L==uyH{g z;V+%wy<84Bh>h!gPB_tI>t(Naa_z`*7o~?GN{R4@k)r`oOt{gCI0dXdlC6~05TPGt zuT!R+W8f~LB<9cwHDU|=phwoQBRe>d%ljM$hxSF)?b}s#YD+kA-Rnde7^* zxk2RsD65W?o9;Xwcj#fAGmCWMTEadBGWa0(kO~bXP6mN^Km`MHvcV9Zi2F&wedfkk zabtq%Xx`~VYkH0&w$U6fCs{5?jRxX#+$NpqYWk5kmRR+byx%_*f89K_Z`O9>#wqxB zTd1KZnV3qMaKU7!?g!y~0NfJ>dJB*HO)m&?5p?e(ijSH~e~*FO7-wa7lf`2!Ue2i_$F_X-)B3373{}q)62`eljSCsLibU56m6XuM z(3*N7SV_60XZfY)EZJhgE6*>~jf?PFgctDeTn=u5Td?0%Fl4^K8iYH=^Sg}*8%U~f za`pF%P*OP>7XY#kD}w*e1O9+@+*?RIsT@w!l>l1dDQv`vJpf_W>wZQkken1KmJ2;j z4qeIC&2@!PT|%e~se`m2JOLzi^VlsPr~rj_)J8@DsFo71zE71YUXTg20R!I9z|rc} zu4-6v&~4+(vku_j`d~Bxq{ILOctG@X=z}f690$cS@2s~u0&n0{VC-$m9n| zVhcj^ls7pI`k8X22xM*912LLI*+Km`DcHMn*7uGw4`s2?`}sbDGg>PkMVI zopZeQwY@3B!Sx?o(3*xlx)AO?aRiYF_hb9}){2=b+S?Q>Goi{cR74ikKKW)=nu|M~ z;%<_O2({1JZ)j%EKz?t^uAatRc7cTHoY<2iKnHyebDfTlftm|>>)>^k^n&f zKyE=@7^t_??VPvx9ku|6jIQS;H4A}IThJylx{r*mCBRX1z#!Miq!NUAD67LOqxEAi zCb|+Yro=>+L*0aAYRhGhCLP}}UL=V=rwd%m#N0rq-s05u`r2+t!ZT3*F6C#yRiVl^ zDiTArt!Bj{na7FsY2&E@da3XgPxqN5$8x*Serd$PrU6xJ&Ke ze_@w@HC__t9+RM5mZ1j?_5;j6AO!+w5G8%gs^w3jz8U+vK+m!7J`5X|D}go)N%p0K zg#KF&V1YdXhz}It$zTit8a}JEx|o!K;Gi(G%f2?>e{}O5&nH<`?HUSNk+!dJ7!=3`#rOwDeiyH zNSx>tXX%|iZ=ijYsp6{$U+P5HxHLSQ#h5Z0GNhpjbPf1Er`+N}YYxZ-ooD0HcyR01 zL9$cNkH&!8ASxl(ngUiJK$l!ez1CnkK-Dn+e;0*^qfazRO*JTN4a!okC=n2QuXGXd zG`_(E|LBk6DqG;qd`&$a?KX*!IMkAN0~E+Wp2fp6J~*-;Xv8f6f`lXE-kM<8g?VoC z-dg^)z=6N3dCIe6e|zv8=?hnWcTTDo8EhS=H9xWsdToh*mA6*b~hnRtRN*o zI7ED@Id1%c*z_~Icvm=2OeZ+DgE-f5u{y#$DUf^A;_x)og@Rb6dDuQf9pHfvhIBe7 zl{CdlN0;bfy!1REAdhd?gc*r1czzOrVen1a~6(F9FQqsiN+^(*XBI;AAokGSJ{z zs7y5Zl}0u>Prl>Z9n(5ap&noyy0?60`VGB@)zR~n+jD=kc|o8T)@Hcspm=f7Y&!nF z=Fj{8MTx;N_2rQ_&3;dW^0IV2-5(epkL!UR;eZ!iupPXr|9W6wq#rzuNF%^yxOd|J-Fb$x9(VHLNprr#2ZSCBhzTyd z{NuOq;*6-~!v6;F;C~`VZF|o7Pa{+(1RfFp(FMIak8JO8$EpPHCuy_=y4)A-7TXoL zIcaFG|GPK*PFBj6_DP1aVs~%A1k?u%bD%|D@@VLoMtOH?cun)uH!rk5HuZ=P!{?g{ z6<-cITwxB)kr+e%A0WMJ5GhJ76*C-Q@`{|+L>C@uAv!rNY2>%;lO~VQt3Yv%eJZrq z*bVzM0y?!5v89QwW4APMT5g@Wlj}Ijk{%IAfZsAjZ)-k3RRvO;2CxJ$l%bFuZ>=(m zy-jO7snPbju1!3)?LV*an0)@n+HY|J$WIIZ!>pjq7jKpzgHtB@tJ+0s@lqp)MS7JOTIS0lKgg5^5+Lsakw8 zQBRI*;Gs`LZUHhh;P%uz3GO?O5)cdG6#xVMJ+T(}QyRfOjePp}(DyY5_s)~wL1z7@ z%_{*)KakJ~H#v&n0O(W>g2P7q56f$yqZ|tX@wghiEV+sZ~-w+m+ zUlV?B(bu-7aiAH|vmZ}ae^k|hAK@HV4bv8n572(!Yh#&~M9(s4u7viBPn+lj)`~fI zLVfA0{Vuq7_(3)!-(-5vNz&yOlyuij5VWlXDkOovtAeE2LDIC#?WIyuYoPf_h*XxE zLizRLmV@x?AUp&7UG2+G|1Fx$l@G_CnFd_?HvVk)albV0ZK8`#0)2ziiO9RR-b6vW z|GnL~g}VOdcFeQ}mFF2ajfkVo*Ad_s{4Ui#yaML%*z{6?WnT8>1?J@i64*bx^&|D* zj^lw%Ev8@(<=)+Un+U^|`>%<=>4H8y?4?)X_HVu)*k17`*ggI%hF6j(&sPdtC=6@K zI*zYegek{y(voJ}&o+ozmO-s)f@=l&)twHWgkd=#N|u`=OM%9JQp>Fy&bk5WE(Ix5 zt|X*ivgiaU?~(gexzz_b)dj_%10A3<#h`SzsJ}^SGQ3vuKoyM@IJ-{<%Ux$8}N$68Qg=cidVL4xB_K8V~9M=u9J3 zlwDMXv8~*(iJG=%lQxmpnoD>7tsEPlo>-Pm7nIlf{y||;((U_y!LF#-iS0KZB7Z%> zX~+3)LCLRSZZs8Vx)`v$dZxm?=7eP#LHQIo{U@rq1f(ZF&GX5zShC~=p$ZXKw zhb#nA$INJJnVOE%7b9?`+@qgYY95s3r7+af5po#&mU_EuFI`eCGo|%Eh_v2KKFIvN zv++5=z1}j{fx)%PfCgG;3aebq0YSt7fZxjmSF*jZ)EZ*=*<^8ZzU*F%-|Nl!HoyN2V(i{ntc+ezP%Zd0Zy5UM^1-BYo6-kYpItpRUi0tv zy(HSpXQqPZ#WT=3DwZsBL}wQ&(IBcIF?>5c_}rC|A&2ochqARsXYB+GQcJ;#?^ z1j=NKZ&r0-@K}ljLahzXp076(PKF9+;*?2s5M-XwECR<)`+!h6yTCt7T{N^=>V`XA8hocS4BbKIPE-?XKG*6KG);xGJ->-Tk+cE4aikG58P z^_EDT7qX}AkzBCgp^$u1kBeol^2v#&n$!myY%AQ^b;d)S1)#{ObQ$V@-@GwnCH6cjBFOoox8DVQuY=bndr#iEE|YO-=|_0BLE_0j zcW%B;mI=v4-pNVN*Iru>#{OAX55fFVMoe>9k4YhZIfVUISOm_uo}y+{Tz8(YN3r}; z?CiKv1WIn1>{uB6K+(KmL2Lhk&>?f18+-qSCoXdwkrvqPqtwf2sIlI0oy#tLBx$aH@!MZx`ZP#g;nJI*z z_t83~mE^xl%^gA;-U~Vm4w|c4AR;~74&cHd3a-XtXk-s-{T+`Br?aGQ ze#f7>(5@J2Z}qNj1BxP2Vf~y&Q`&N#x>-HK3~4!@-pRDsMaSEYaGApJ6C=o-89OZzg_a+j^(qe~f<&6fxW?S}y3u*`I zNmEV`mcw8tuE|7ZNo|Cove%R!hYhC>iAIwF2m2M*BIzd)H7RO-kA*!3-Im?7Bh=qP zMJk46;a59i4_#YA3%y;q6f-0}_+~3hKa?yhQp4`hZXm|VrpRKYiXX>`k>Z6GgRG}p z`vz=l1tN2Xo>p{buqlJmJw*s(T2O{Ojj3%=RCBaX@lJ2@Db5RlHY$6XECos9N{nP1TWr9&7CV?pU<2!d#9(lNXdIsH0 zs(94udGwv%W#PRaCt97t3U5^LhHiQ(AH-~|{g10ciyvb8o#2&QVKUe`f8SR*d#B&# zBScC0&GMg<3}2l+#j6R*agOFf^qx#JvyEqPL$aN zS#94&q31};>8d&yeTE_3hC~agJK^E z6Tbzfy`@298iK`YykQnql?DDUFP5Kr{Z6Ak^718q19>Ee} zu5!#Rra-AZn9Anbj+UxKJ&ZUe33zvwHPvf+bvW126#lFzPu32g$nQ_P2T^8L$1CcJ zOh*|waSovA9gjLk&o(Wu7)tG2jJ|oO&|RqDjcXVCV&8sZ`|m^fL4CJa6I>f@#6Ya| z`UUl z!t-Y9o8TKmq|D_dh{l|VJN*XqFVt>{b!01Dft0Si%M_;fBy6za38+J{d)Wq7=1r-( znM&p1zqy@6nWxmo^LKaS?XmeWH}Xf(>VdfQ6}+W zmmVmRb#uQy^p3ec7xGG`^BIWJJfyVxd$8JUE zQF#hTv~FaP&SVjBnIRseB)`mGrvNx_hT;}Og;;t1Mlmh|*pDjF)+} z7?z+%6=5TUM5jxPi%MLRDZJn3U!!5}>kwXDi4!=#5}oN3t!$pmb>;s5_yx63x1b}2 zA>x>?6#UCZ-vlF<-0s5;dI52LzE4#|?_wXF859p4%-j2;8_gc1ZuUWh+qpA>-@vjv zv`C|KvjNA{X^BZdE zn^Xo8DX>gEB3)1n%KsZWYRIK<2%^^Ln7nei8^EGraV& z6YK?Fa1bY5%wWYA(3S@#UI;EBZzHPAkSo_vHwd&IY)~3iLSw9>>QZRw^>ck$8nmXb z1Zt<5Op+^349~<@FjSMlsue6_5`Hggqe(YHTo=ju$0ZtUiObCr4e)qF`{oRCudR}X zEEyEFRhmf3j+@R3Ul@{YVd6W%XS>p|fEre^tD;ho*)JhBcTYHoB)G-UHmR4mQ=Gx9 zmzm>7U8STU=^sSWe~L&E7b@mQE(-QdUHl5jvmcf5j|$Qa?DUjkAHE}0I6`*Zx^&z`=A6>Q3;`Jts8c7i+h$YR z_l9U|2iELc_b)x$-^y8j3;VBD4<;d5v4q0^M9XAl3t!NPA{Bs81wh(jo!pUi?$(W2iG3S|%d` z6sFjs5N2IilR6^RDkRMW3{nAka{k+$%EJjdKUzg99-QaPj#s0(h-w{|30Axw1j%Gd zuro>+(1y0`t1~u%F9$6j*|=8f?vOopt+DS~9Dip#{gY4qCtFJe+QX*=BNHCn|D`og zNEhaNa9yU2C0RNZkn?P(`{3~hT{*|CCBW2`U_blMn@5zqb%U5*W$D{PJQNw? z_NdLe?B|{E*<`^tl5)(xNA0*?WCvi(J_JNjr{-d#osr-k9r&mt@*HUfN$3?j^qe+Elwz9*? zGoI@i?;*^ytrBVum5=f(pYJdVRv6D$8N$Xo87L_QKvZEDWO=(qv9Dz>JEcg`{_wus z3cf*B-d>7WcK`N229Y8~_qAea{oia+wrd-0pck#aGaBfrX02u7u00XKSH zbq0BO_Gj9`7W3}FLS+|)X0wxb!STTKcJhTo)WDWvK__N9M3bqy#nSQ4k^a#1kHY%5 zj$@H?YHV0;PO46S0;6(sm=QhvlEXx1y0RqVFjL=|k>SbCkR~;#1!Rc8lc$PH{CQXXl- zB6A-8o8D&}fdmCXoZsr{Z3Vs(V7ob$&wX`~)D*~W2A-Bbh4IJa% zT{#`aiNnA6;I5JKfF`&?+ut5jN#u=qe1_B$t31}Ec&R%3l=8wg`7@@DWU zXR&jP?7beu(U4%`&C+c13;RCv*|eVFdxe`SzAs81J{+6|YeN$D>+5pL|FehGXR-$$ zcq)^oQoRvLMXDNoVDEL1P)Z&q+;#7&EAAdc+EensfBFZnNnRl^LFaf_NnyDzt5&uo z|3*BQSkEiZ(+YNLG6Jox9n-INLrxg}mv~ZP;j-LvjGXp!3-ais`D0r!%(}(!P4M!O zX;wWoMiG5Yw+EWGEpX;lJhsUka`4jUUv->jVIe9LeykfUbJTiw*4HhDd&0ptG^ zW$%IPDl#0lV6mK2!DE>rO=e$a_9*@!fY3WSlqiX}hk?N%BkLzr;^g>jmVQ@>&0Er+ODeQfi5hP4t zoUVTChxOhtEsebY9r!hzIQ(eCs_I3^e~Q1E_=a;Pd&y^k)6uYGo)rYM|D9iUr znfKWzT#UZxKMB<2GG#hJKg;72Do!OtAg&NMzmcN^LUy}^oI3rJyH7`TO5q>}3Zl0b z`p3epk8Pa{-#Lra`@qYl=wi>VNAa2V>A=@@8jjQRUxt=wkjOG{Kl;hGHK-Dau56Gx%(2+y5BP0|B%V2-Z0a z>jUJ0Gkd~(ceC0bAxRqSGazq7`;tP#O*6F5qNUv#;wcQFKJ+m^;Mf`9Soa%#{uSX} ze4^|m23VF`2HjM+(R|C$oFsZ!qtu*;xl6wS`Fq~>_j4{s;VWvvNRl!@p2)3|s^LF6Yg`+!#2MUrTGpLlYbM_fz z?}U|!l|q>VJDh)Yf3 z!f7rHj^b#pg0S)ycV^hS5S6U#!u!g!gUJb-tg4Ir7gbZy+9r>BDznW-ql%~sygsZ z)h`4_bU@8)ZVG$mK9 z9Dh)4%o;PQG6&R1*6=A5_(YG=2Y6RJ%d zojkRsoZttlhrNC|xVAJXK9J|M6xm6QUKq^K|JWJ-#B3+xt)R&V4h!qkJU#Dw^5&wC zYE9Sjnr}?+GvgPRZ@-dS2+vkC@Cjj?i!YKr{M|_nMd4nD6?4sok4QGFY?Fe2uZoNr zednlr2#k0X@}VVW=3P~5z|L5PcmUmSOfoRKHZ#dr)($Qm(y$igdDi^5arL*P}5PA&@P4-A1NsySSk zyaq6cM2EUqgQb$UxNyQ*ml^IpPwRARWqS^Qk|J@f-~wzqs9%D@8;0RZ&vf;_3H%Gd zSK|0P8hplIV3J$}P!VPX?l9?Wj&SMJVZI?#-cDTQfvT$@3_b0}1ZPW!<~ul8)B>}2%y^7R18m{*d%MqQgyw#}|^ zspHCskCG2-nefCDEv~lR_e{QKi1c`u6qvoEZ`@Q}8 zsbqWkMpO%00x(k#C9xWwwXPWzBHKZMZg1dFdb}%pTg?`#l3*qS01NMCv!w}CR^C?q zZ(tcA?XrpxHBMLH@E|feu0j@DEX4!{QdW2<&z`L)DmVx+;}#*dL=@yjsTMlvE^1NM z^={%IB!9PgHjCEaUXgwgu(olod)h#%tizpIuqtyDDyvxr2_Eye)LP)@Sb;W!ZNj*G zYOXSMIrq|QOlefaw?`+_yX7_WpOQ~%TLqCqvI>TXW(U6IAH)RX|0W|O0o97ZEhPmO zQf%>%(an(ykM#EY%L3W5fMBY!#N(+5w)gxQK-Nr8anVX zMCswsS;r639^UUUbCb7{i^aA7<&2xUe8WB#Ub`Z!R~-`KXOO~XqMVY;#nWuENcn>% z<9iOyaTA^WftgzIVN?F^ACM8B?TOgOXdJehi^V@4mgznNRV57ONZ;*&7+ghyQ=bbJ zy7iEm_4j;|z=XYR)^Yb@;7gE(@ub7k z&7z+sryw&gxDQWziTcx9NhXWAd$wOu<~yO+6I+H==P6>U%2Wx*5QOd(7s_R!dI>gLU)@|zQvq=JQpTSF=T)N+|8SoE6Y%PUn( zK{qoi*$H6mfY+i?;7G7^&$srhbK^H1Cx#5TUbwVUE14zlOjU1JnDjIUZP2#|D%fEu z{uP~os8T=(^au#Q`yQGpZiz?(9w_9rluJ{X>7-T%9ICdM1Tb@rRvoOYI2?;93=yp6R6Vp_+Qgt@PQt%lPyvKOuZ50xbL+KgbvR%5U_|E17&vm*{&6 zGqXQ>c(M_=uvprR_NLf;Nc1YS=O{`>oPwt&;j<}6AX4`G_eM?V%!28JHcu4^=dPt| z9c$M*q5~MX&-z~7!HlcQa~JMQ>Ap$BQLccu zzyF2E8~}a4vFAvh20=xGHqI`zJO8FXzkDIM()l?Hws(KzvRVXD6kmOf@|;>wSFQNJ zCbH>r*rB)B;=M8E|6=@BuN>=m75+%@g_-T^t0nb2hu?e+IDw}YYgZb{66T?A zYG;Bpn3F#(t#P@wZU(7DtYTxB5_FWa9;z5AB6kj~@R8b;h?4K2CXqpg)syBgSwfRm z`qh?Ng!G<4PE5;UufAdoS?Xl8%*}zUy_b>j7YhO4`5_IYmFB9PIMfxgec7TxruA<5 z3!%~|54*vEya99ht9ZM(XD{xZEfUp!EtN31b{Q*eEibY)U!e@bDi0bZA3iyORldvk z;Nx$<;4$_n@JMS0*abk60a*0NCo01(6nGFbLM3w_Tzv_js&-f7o(mXp4-!Lil)Q>4 zpZ%*HqF;KC;-I2~J{O*S54hsm=n3~{fVLfs^u}%OWWX93rkWVoR#)@41u@PJQ!tc~4Fv=6^>T??!@WlnN`Fn9- ztKjgXn!qKGBj#LW1MW}sOWV8WzYB){xHdj>jipV?VA+sept-LB_~nqpLo~ zJ(bvLAM7eaZZSJ&Z%2xF0YG|#5R%fu=s}`XPC-6H*`XHxm%(%?X2>pQc)O{fn7DjE zs2Vt%P$jlYX{lY3Nadz(GupmRNYxZyDVxPj+2eT#Ej2g%L{5>lgMu}x)WhKb?1lCW zGa=bd#2aGXv0ly1GWTYcY|W|>f}Kf<%0HS;l7mY$XO!b!L2A(D@Q!oMO5m9?*)u**+#DDzSKOEBqej?5qqssu{=<*4 zl-nL7d#2%@GcG?rH`+3qrx=M6#bTH=+x~cR|oZ zxj6zhn0nbcG}O5oY`&`C@cWIOm$<`HDD}H!6xFd$FfwN8)oWs85$JW`dRs|drugUs zD|07_Ew7Vuh{_*hRi(`R|tlzPA0jsD_q&P5)vG7__Kp$xdSIW(NtJ?a1D>Bet-_(`N=5!r-~JH^i_FGVq3L z={R5p6Am9>&ve{gdBV@8x5~bDE!6@cZh}z#W=%wLh@5u&J?ss}1I4TQ3l;bRvW?|L z5%|dMvC)yX9p5aoH9d+9$HT&}n9)XVWH#`|gCN@K2`^iXAw7_U4s)qxsUh z*=b+x6~?(x#*v~lX*_*gToStKt1<-gnBF8yqcRR@|)_)d_lnX=x$Wot|so6Lk=?%t8Ol<_z2MhXn9zjBlI z_16S)eaD&S@+-U8GIk0OQ_|`WoJI21=uC|}xD>Ls&=*23S3%Dsd;T*yI;EK)rB_RXDL+8fchcErxW2pO!A%j)1TEx&Mc& zi;>-ywY$mNUTYAyiaQ28nj5Y!Jsq96$0P&Uk`4daS;~s`sff+UFoAnYRy<3+%}pnD zxsMCefDWx!+tB z;()KS!mtt^(ZCO7S1X~N7u?5q2u9}#`~#qkx4n0=KzQP>{5RdMjeXJ!;Z6_Wo*yn5 zxPZu1kB}_vLi~(rg7Ajn{gR{MdRnp^O$m3;Z!JMXa71n+*jB;x@#evkBA@@QHaPuh z4tNY%6#TlR*yNz~jm@OZ@li(ZMAbEey?3Rw^IhjC4CIFT*u|u_7gzE(UL$!<1Z)Cx z9-Wetoar*soW@$b{W@=MX#wISH#Gj&%mvwEg`}S^Qze!aeRR7@73FEyWapxWuR}!@ z%8i^N44Yv@)ox$c!*`A^T!O3TE5FaqLg-kT%OVyLelKH)RsSzsS~fX7`k#3zz$br4pE|0|o8@o)9c?q1<>7)oO`qVNOWojI;#gv!w~5NLx30wX z3wnYuU#Lsd3?x8IWQXlPz@mW&JDrUkMl6DsFsQtt5q#(@qbAIi|<*n`aH>XlJgoHV)4LQ_%(d1Z_#-FZlZvC^Rog4%L z-d=UT?|o5;=)P6As3T+FVgTAL z2o}-%nk+GxzK$TO>KZU&FK9yFu(F^^tCavXQ2=nVAk>TSB^z%_T)j|KF%W5rg+N7Fz$L_xc zaSO`n1t8tG`!xcPUnO?HX7oIj7IqEoAfwrt%p1WcvF0=Wy^1#dbPN_6iha z@{?AAB4~VqWrgjx-aU_wdK9VE8mBpMBVqzzgk6Qf>!6%)qOT~>q#qG0L!uDARWh@% zX9YpOdVz2xnoIky=rHQkIlK$WaSsv=RqxfuYZRHx^?~cb-txC(9OL+iH&E-tookf>1;03b^G(2$d4f`H_o zKOpsw>m0C;Iz!0!dQh`r^;;>+?>oopS3-zT!nxl=zv%@Ucv<$#DYu)hKk7o zfk;AU_5jLui8+8$J(WDsyvIxsl)!rohQnVlf$T~oCQHKk2*xV6p$n15#!VIV2ovd~ z!XQffhCqbHzSba$KxVo@47Q0hj4g`?Cn*(aDyOqeibJgzO-hx9Y(JaPvVV*S;lxjU zs>G_;0KHE*9VU&O<{G*m^S^nNpwu?&Ic*HXv*B$)Ek5 z%mch_-sSX&p^0LRDMyQIXLeY;cl)Ltg(!O&3?=DJtXnzgm_ReBG z!|ly6S4QnL**HUeasTE#`PC$7kwEvZxFi&|Q&al5z3){KA(T!_TrwqFfW-}%fCMa* zUACMvil0VbyEP4fhz6%_vus&*)ZR|;?#X+((e@VHtbUiDHTg7nJ(4Dmt%J5qxvk@uwn61Jhif>1;gz3T1)z5llPG) zZUBc)24he-WMq^H-MZIFro;vD%`R}S^Kz|t*rofeveg5z5hYN8umy8HC9WcTw{f7p zE4uE;MBshr$oZb~JiSp$*|m!@&O>~0%@rG^vI=RaOLcSGPaL4Cba%}7T4qEjcS5Ol zxw9=fmb-!xe|-ml&=O71@#T0GS>=iRxB7+^x({R#r4v~XD&rKYR9P(GK&<=*1V;g4 zy#Xfae{moSuL@X!g(<>CkB?FUMG=?cU4~S4GXkNk~z!N~#*V1zSVN!~3^Oi({s=f_^)wofH>VpB=F~9~HHE zlWtkd5nLaTVOOlcU9D*@1QfXS-u!GIDFc5RGAy*~6>aP_7MWgpepVi_{)%p5P4k5xSaV7wSWuZtUzY)vPPWkofvTBb>(OZPF0e8|Q@%)mzJ7 zOK`1qc>;-zN}-CP-U?0t$hk0DZn?GhX@PC80kQE;5FG^Cy$^#90THrP7M!R&%YwI~ zh#nazW+zFP_abbGr%9v% zjBe>U+xhJ{+1MQ^mCwCCoidRZ{x)f@(QKDtF%?o4qXzrTUcmEi4Wb;JV;q!fEaipzXCp<)_woLG~&Op@aG7(lJ&o&Afy|`N)w>Z4~C5#*w zPl^X~PBGvLu~*mG-oW@oX{NT6Sky5?T(<7(A(aBkbbKlyV)5at8Pg5ZumL`!jj(yK z1!M%xb!g8KV*8MToguUE>Z zrLldx;4r?xnM{B%ZB6S@qf)Qlzh(`;cKM`F=#6)Av3&709w}Bzdt=L8?LG|`fsajM zpa-*@6*uoi4yc;Y#u`Fmxkio!RkO=c-Y&-cvyD*I0{8LdXSQL!4;56D9(CAR+di(! zGdohJy_s$9zx{>N{>CRdL=pG)KODZoas(V9~JUY(2iL{x!g*dhbS{;k8872j!^i#QxBU zNr>Am_t)cgp8WSG<0VhC$yLp-E!uh!Jl&$O^>e+TmFnr*Oop3Usa%(H4UOYEHAfJz zFiMzw%66E>!cJyPyt}(oajEU0MTVcFWp-1AQQJp$dB4+IyGphJ*#_`c7u%2wsP-ut z>k|snTFA-l!(<3OOa7K-{teN?ZOR$*&%~~xNBZ${@t5S!*XHz2f_iw`n?zpz@p|PW z`^q=0rF}9$Ve|%Ta98oSl%3NTl$rVR^-*B^R1h=Zk&fa(xpQm1Q&_xr=~k4v%e8_! zKAoTYlgGb;Y~$|@l~Z6W)7)o{8L#9*8{>o~PlackVH9Ew7+c39 zJET??y{g-DZ2wh!W@gyfBAX^sS0(fQI~8gVIswH6!h0)6jtr>mw8??n0{CHAYU4lF zKMdGtU?BUUDC{w7$F-k$GIOnuzpw8Mqe8(qfHSv`^9aD^Y|TkBT!~On3T}86_UV-` zYkcRPqeU_(#X6vK2aZzaHrd}d$zJku|HiKjL4(;k#gZGn3L6o{4L5{Gsa*}SNOet(>R|@wEB+gT*I8$T!hwl<SRg4Ti9*^vN(L z1PPcsl$}#QVF3P0P5asyp~&;H@$<6e9DX@tivfVTC{W1+==VAo$&$NI!E#Vx3fGDD zucr)%`Q*p>n$#IpCg90AV+tC3cs{L+j9GGDm;`FpQ-r30JZ3cDoNdA3xdH<*%Ok3+ zs{-eIRq~3LZTIU%mv8JJ>lPXiMIJa(Uk0h`;RxpI67FdWi3H)x5>Xfw)SFlzy7_fq z(W==9oxZLYjIXTO*4<8biT$YKG58FR?5e8lI6AM>TDgYWouK28C!d-U*?5DuARbhx z2NfU>trwQuS=uusXMR+tg1PAoZss4Bc$45vU~{0mCJ~rQ220Z6ymEi4&TT6J>Q7W( zKa^y^%0?d=Z5rN_2isE3Q~kiH_2AT9a0C%_8snOfs-*(3G2W;$CL(lIaQYP1w-a6v z6EIULn0;b3v~k^c^K&Y~#=sB@A8W!`HN`i7nWyol_r+;SgM;@ zxUi!!Io}Re`5TA_EHFS%E_jL>EMM!~O%2ZOPciu#l4u$<&SbqB=#t9%V-(;_!X9Oh z9eO}+37-3YkBrD=D(hm}7kdS|dO1=9!+punC~+AAfaP>2d5$U?zxC@JL-fN~PYhjj zgB8+@g@k=M#l*nLR9MM1M%UNBQGF_7dw+S;#e|JEai}OC&KcSMMj@V_&}A>K%L#}QI-yTtobHQk2B&h45=K!! z+I?Nt##7>}Q99=7Wy9rRiKrSfs-_x|4M5})F<;`4?|KC?S9#LKIK1ePqkdMQ$6%Zn z%1L^fUlA?Cg1(S4qZyw=_&fuM&r;nm!2$9p>ZaB#SPnGK4n3#f1tdQ<6StYiOy%RL z^H*oL0Cbkwe*RF)C-sd;f#E@uUg?B~*Cz)!dQMC@cj>Yv($EJFxt_i*^f9)r9~pf@ zf3o)2eN$s=0b<-72t?V}<4s<0(|gztKqRu5vc0Exu2U9Qy~_{r6mw9rxp|ar zZ=K(+Q7)OE3Oq+;HCw$l0i>m>T7Bx}Z$1s3NONAX23Ehe>XTeNBz`_(4khL~CO1Dw zWY=WIp3kv!+@81^ci_L~sIi%ETRUxg@-@Hg_bPubBk-W_K=?>Et^wW7P~b}n>JmM@ zBUIk)8CvF{pzP-?Sg&Mv9wRuhxdaHSysz33AOJ z>ApKlUt#LO5o=jmYAtZ+w3-@`#YYtCLxxKB@_(TTeOe{7u!wZBuzitN$OYNhx?>MT zugn=;H!8=b$147H1atLS8o#eT))Q^qk%Yp~zxeALsF2W@v!9r3v;I9Lq(` zn!k|6`8gLiV6ytw?MZm{rB>6x8*H!M0$qs!=>JiOTnz*4;l@I#KAgXa*uUp!zjm#O zhS*6S9+)EpqcdZNEHqhQ1dV`Pk+{)v%-o~5a+zmUDj#q{Hh`hgM zuL8q@a+(r9(vKP}SVvX0`SZv5CsxA}o#z!gY9xYrZz_JUe%1-@@=4Gwvq+U}eUnXu zMTlK4(7N^<$Xj$mXOU-s>`&PvQOF$@$O;>XCDu7FGvbTNj-I&4=ccHzyY=eS`q;M2 za(QsN1{e>3b2ndqaWpf9tVk-)KJpHi>qcKAm6U4}w~}-2Tk2_;p@QVh^!14mlqouYDom z0wIuF^MITd`#UKR)9Uwh9UG^d!q!jenf>XlWZ1}QT#t+ltBD9FrKf)!V~*1&8qlKw z&r-eZ!hI%EwKDRFK7pdVlg}dGyyJDIP1=r{jNwgpv`o?0ffJL_YM+e>H)eh(%=M!?Sj!%>N6`;;gz#U@=Tox6C`dGn0MSYZk~the)onfg-fv1p-~IoMHq{mbWLd zS)d@Wf2;(d5x!^h^hW(_PFtTi8_yiBAOTy`1#ZiQcyvsD{G!5c0mIb1j;mSr zBedk0?y?Nn?*dTzkBiE5QFvjsE%B0wS&liq?i`&(kj|n&2O7}%sH#IIsJ zJ_=R>3wghYv^P(%*=wK6hMu0T&i@tN{rdXu<#&!TQTOteYU3{1C%&(HeDZfRJo4dP z-N3_D{$@ttU-d5ksPT_$1&=G8LyuFm=DT|;gLvD#+vtZnwc!aJ%ulWpwM{AA5`>z; zOTnVNpMID0i1F&VA0NMm9ez|v*m8@ZgE&EI%VVl7Us){ZAU%&4dgK=@I$Mb{U|$cv z|9y0c%mc}biV^iCNYWL2i{P*s@P@ybLUV-_oyC`&>%R>B%MjY9$y?}H4ZCyxsvn{c z735Y}8LU2`n{oQ7T8)YO{ml<9)LRUS8W+$Sy%i-~^B0dAtjl`e`K%{CGIC67@ZnoW zgLT;se-dlF#5u<;L(`|QN)~=kZ$eomAyFa-F!8z`+{urTzxpxdBvB%@6SYwH5qgu! zZge-Yw^!4d#^J?;bTtCvB@Ksh(c00`muI8p08QF2Fdru|f2uK30ze(2NpLFp1lKI{ z9K{8g-@Y(ykuonxW|g`KAd}CblC>HrLhT#Y3cQ@`1y2u&*u!(xc^lS48?u=xjZ6!h zkoWCb7VpVZp{rGzcXUb3%lO7#cvsI}+MkfY<@+CisHN4QSFYog-A=N#DNBD-_-)hT zNvoUe{FZ@A=3yTi`*nWncY1wXrAoYsb1`~OMdXVFzVlG$SHqwzqL?p0U;MkfX+E5ab)WO0Y==~=!tr%bxK6FZ6|v-+$5%#b zZ@ZPhudRK4FYdiu7GtkR_)~wG!*8HKGqbI(^v~O~x8CF`Jj&_0`!Q+RI^w}t$i_df zIZ^M=FLk%cM}W0-KJ{yp*(!O7DcsV?Vs#b6b64~uze`WFT*J;`_|?O@ajWZ~Bo21M z@h}6Jz=D-A&mJbONg*(3A0>j}_xMEASye|u&Z{-^^93&Z1WaYVxLu+feKOAXKIcM}Rk7xc4gT%9hRe_I zpmqO$@BLK!l|M&%w>bUB))fOwy;QGu5q3NTBlA_RSD0M4t+6iJ@vBjLaMNe}`;Kqb z`SX=EC_YusVY*!<)Fxd0`Y3O{t3S=S_cNO3cMTut9Ku}-0I}{nXx7_xXOf|Bh4LilEjf>@<}8R=?9 z02&a}DGJC^jp)PZ_I_*6)cNjm!Z9jW883cLB!b3%nl7aVUl4h~bn=#UzGJi?S5?wn z?8QL*EcWusl#{+;vRRXPJIoWIf$ax96 zMZeRg$0Q36}0uks4B72+UxDZGC z*&qtgmXlYimy{4fiGXsJkbsc0RcS_$UGZD&=j}=XhAXl;1HEw8bfPgzox$uw%{LmK z-;)^2Lz8O`*+ylemmvkRwK3u@`7L{G7w#v0TjCuRGxkySl#F&Q9F0BbKPapEmBO#7 z?v|x5-tuus|K`ccUSf@&mv8xC&=q|7_1|Mxl9q2xv|YOzJ>PRJF|@O9aXHj~m^Q@k zo3ADGJ--}P!ym_ek4ls!it#KPkIAph#{wc{fl#AtkUSXx<%OGLM(rT-hg7(e#VNCl zLufE7*xZv%6y&E;E}0ne>(gVA_M}WfTpV{N9Rg|u>P`e@ikCwOOE`$TFHfr7w!2bP z-4)q_x@vu1Huta`5B8pXR>ChRVO5u-bbh1e>x~@Ss|_9E{LM@cO!xS@hW{q#TH2#|m6ZWW6Z@SL?gF_z7dA+@N} z3va*sIPi2psSE6b&EFcQaCysE(5Lr z&1Q{7+Vf5NIej=Qi1A--r(g+E>3G*QUhm|)_fmM3Ri8SH=^esJw|zF#<5Gox%rD5C z9Sq1s-OhN;U}mNe&Q%OZ@Xd4*4HPMc*~7nVYa2r3;*(PyA?kN$1{^HoIlUY|7v7Cp zihFdi{2D4XwC_o7<0+T2F3j1KbT*d>ga;5q!&~0NMJZbF7-AqlZW-?D!NDGLLYL;} zz2bC!8ZZDcG$M+hgRn;XaL%Oq3U&dT%eaPh-O~Kq|aMEw{$h)22>K zvj7?QBL+-Axi6VoIL2{9W-t}#QyR~gp#Q&%g;|#O9^?rvm`FJ^j~Hosvv4^c{;nFj z-`iAPbt@y_NWyHj(X#Dk?l^BgBRgFjc6)KEFXF`fasq&&2iLX;?J^#gEx4v9^KSxB zt;X0jsYRWnWra;MXbE7Ig9FI(Zgi4u1h6C5daiP$05|>0qA&2tO$h- zwlvm<&G0pqEK*M6WK{5p4Vx`5+hsxbD@CU&t=lYL$)U!oNKEgOl=JGJTS}TyU#o?2?NXq?zZP_w#SnjdT-hTGT^1c4{$n*)1#egzdOw;K7Bj? z-xq~f**bCDFX&U{g}tn02afz}xP;y0dID82j;BTfr{3s}QhqG?uxci;o;F&|RN;~` zc6ykguo}Sly;UJ^k2T#VgGFSG9Pg0WwW5_M|Mg2D6tc&j=MWnNnQG^A3l%*NBnuWK zH&wOwIct4Ii=>}XVfB%@FK?KhkyzjXhKio}$)^up;(x zEU7Tn-be@*93xRjTwnpJx7+CjNU%DS1{t^o6l5|$0c*4p#~=4`#9k;jDHi3ZCo9`Y zy%5+8KxQ*Ryu{vE3(7piR}`i~?cK57I=KB$_ZA+(ZFyW@McUi?l|!}gMc;ax*d-Tr#;B(*OL-9+oL=On)_ z(P#U$U~a&!k{l6ZCb9_r@N;FL7{7D7-|HmVIDjWuPKK9aV29J=n7=P)EH0y4!G1m( z3O|$A{7Qesrk@{QC~S168C9k_!CSB&FLNl*6M;2X$!tmyYNbQ81AwT|<0zOq9E9Bc z0^)B4oFZ?=dt5nRts*M0Jsl=Wj&@LMb#cff9ip7v``f;+=xMr?jhBhLZlQ zahP`p|Nj5EV|?xu^gBHKZ#I1Hlq4pSevv(QsGco}G@d%oXZLsw;_R$(>bJdaco;ia zlf3d(<?bWq#Oid`w12Xa9s8ECE|RUeWymC??Ak--8XC7 zZ`$Zr!H+o;YSshQ_5+t%k;e?oV4mj&1zE@7L4tYhVpS-H$*%Ui(M+DU@7(l86^e?U zV8MA`?i2xwi=CSO14jNi$+VM!|DN<>-!^)XlSm3jWw0M?zs=iZoF><;_N z!|SNvxx1Ib%mqUF+=I!)1?Pz6O_mZ>NNMxwFJvk9 zFeqaenzs`MY^X1}%Wtm=`4c18or%k0LLoTF6(aPIJ6@XtE}%rcV%#r0tpR05fhIv} zC!z)a6N^@DHiU|cA;>^wM$Dt1A`M#wV_F57zeJRYh4ouekA6nco)tc@EG(5P((jW1 z;lSwt$@f16=9w-lN$zcNJhW=qxm+?PF?4g*#DYiaN-XQe{BRjFGp{P?j-3A@WMrbX zWYpjB(=Ae8zccfn1;3xnd(xZw4*>l`$C9(Li_frR(eMQXc8| ziEi-@YLPmiZex7!!##s!&cG+Z79yq^RnyQKP{!o8x}B!wt_uAcQ_iggXSBegg@?Rk z+#e*PdYK4o0$7lCy)+wHA_{$Xpfxqkaj^h+hNPp-VAEuF6aq<}(hzI)Hgd z(h-~j39^B?cB973lgKokI?oU#V)k~Y@fHERIo$9kS4T(v1bm7@Y5=(Ni|+Q_g*pJ9 zIN*@avRUV|F`J^2!u@Ft?~2wh_+0?GQ>#O308$6>$&opCE`;(PGxTKNJ$0vphiFo-#Lm${ z8;Jw{l>?+RVp_p%)l{2xaglP3ItdGoHxnIuWv zjeY3u6f~G=FSZxZ25UDW2XUD(JLu2Zyq)u?Qd~&??m4}4U}ZnB*106*-+}6v z%FkO=e6y;w+0IfI1@kTEZXr*47EQaB=&6uirueBwh*jXKRzUrj2l%)v zp#qy2m6ptZ_eZ1qbJ@KA9Y(^`A%k_7FFv$TNQ>}z*OL}{wxssvze;E%6=uSE_Q$$V zTc6M}us%doPSe}L0SCdTKweOywjOn)>+n5_Zy44ocxnzF=Y?1W#Md$$Z-~X%4=p6xC(&To)mb@CG$V^a=ljLsaH{N7S&gZ>CAet z109@6JY5b#wz8jGw?naxGcXNPMI=n1$CU#rCI*2S0bo`criWD4WFp2emo+Mv-7vv!lrtQQs#qT>xYz*ImJR)82Pu<~Oc{Z*@!y%GB)fJxCrO8TVk@ zZya}({U!Rm^-rJA(44AkjVG08qo(OmX~*!NH?8STu9}A%o^kMm=7mBXTI9EBFh43R zhKOsKhJsIW)P3kskR3f#+p=t}hd_s_bkA9&dY+=V8k6UiOiq=uiXbZTqaV79g2 z&!t|NL~bmXG>l=N_|Lt`!-nB8oNey8Vgsgvc@V49IP?IXH3Awh=W_8hnIren(Be~z zg=3gJbG7?F8{C=-&cxro*o2u@*4>Fn>qgKY-R|whNONQE zr!Uqov%a99nEUyARE$>U`UrJ>dGd|Kkn{l&%cQOw-9&xH$#hMg;4Q;#&uK|n9g=U+ z$=erZ*z?F?G*TEw$`hWSb%(sf(+PJZ@X)_mgXYOLp zT-&3sDLuwL1nPyY@0@TY(>tV*y{o`>>z?t@NGrI(Qq*9@u;^MsHujZ(rPL zX35%CdL#%~y?b2zi2GNHRC=M*M?#36LKUswaa>(>Z5QW6>w;k?mXT%|Me5geh6F=YY&fN3C_B^M zuNON#R=WB2=3ny?sy=Nz%PhUGE6n+f*#=u)Xs3*6IL_;{x~c0_9U{ zv*-Prg4#FdLqA?>f!bWrxHaGHmTyzrb;+4ULQkB|LFqi*fZU%psbc17Swujb*!_fs8jeg-moZ+oUu zs-4cPU&s{+^gb1({rjrV*Ir$Y`VlkdSkX`0eB5sW@j8+X}Hhfd+I_d?z!BhY%HCY2eQ zlcdUw0_)W41F5^7;-|)E<4`fZ%P>`z(p_Gw8$I#po36lnL*zqB6l$yWAmDJK*ezCN zde{jsCRH2|JOW{JIL^jps2=ozF@)m<39P~K@j(9hBUz~|eFHWrP7{M2@VI`3o^_Uv zLC#FRgPF=8e+=XMD}IM3+;tZ&Ry_E)6=N%|tt?+y6M=~AG{@<0*(gn$~80psSSVYp0ukza>+|pC& z^w#W$Y4Ogg#udO3dazjPByY|+>@R!IlipPBfc5Hv(SjXmRS)C^q;x(J1oKa|zh5uZ zmU~O%-6jH764`4gQ{vV=QeQT=?fyzIc(^GsUrs5<0~udkV7w?dK|0P%*vaP2*I>Df z%2NE!Fvh+#K$yPPKY~MA`wdp@z4Q&58Yb+H8hwPEA8UJi+4*r-H%=l266R(+e%PLg zc>Y^^<*o1DFW>U(e=e3;*+_lq{FrWhbJy8K|A${g?Yg;>^YZ6+d$VNyOTwxwqit!) zEAQU~#3|KZXUGY5C5tCbPkK~cWv!@tA3s5ilMJl30b{jG{yj%)b5~W4vN`cLq2xS@ zVpF7Qh*~8#H*ZauR=LFOo|((%KdI*>XAZFBm2Hj=<{NC#jg>V(*DR3TqXlu9+MCo) z%&T3}x-#ibl4nLnf*R zpy!n}aS=`K!rc)|Td@-fPmw-ORl|f&K4Zq7<<@rk4lyXU3YROx)>A|MhrQ{EMkXQ{ zDPp8vy?rJ-J&FZh21Jr_VnaFqT1cHef2&^GNnq|o;kx|oI;4W0r^xiBkMWlj-7mC( zq@GeWa598)>5#lPrn{Brx&~>YEXcQJI%|*BvNw#_<&6a>9rQefZ7F}il;t#YKqJ35 zWu-o?V>&xc$bL|Ov2BXaZ$kRRt(9y+oFY1{B775G%8?iQ_c$x>>x>&>A|kE`ANIjg zw4vCZeq*8C{rjm-U&CYY*7v{sLXfP@umb+$zD8yReRKs*2CJzsAc~j4On)#r<0)%9 zHB!}<%dS$J-QoNrH_0vY5v!Vf$0AoZEB&3R+3a%X^YjwguZa(2|E40E zP38?zs!$nMNhI5dg^hR}yP8*(#Dut|g}AKZbtgHB5}UN!BF?m1Pbs)HL|Qo3FxAo3 zr~w`~{NE-8s@zz0)|<|5?a`blH))s}5n;K%4UkcMva0gTA#Nb%e!<(hkkZo!?RmJb z%bdF#9$HZ6zNX&1rQMEA06HoS*HyHw7NU;e?d!Dixil4 z`cF)_3r@Fbc*TDe$j1NOO4zxM_ay^}zBJI!?_39sT%k3EGuJ$b?o55gDo2i39#4m( zG)XkJ*+(*8*t8cmKJF_#@9QwUdAO=}=h)gya#lnJvSg@wV3uDCCSID`71coO#^6SDm$&>BhQ2c*xIgLKvni(h#T9k+Bv|Hc zOl$={?FK52%i(-R#`nJ4gJ5CF*DCo54N;Yi4kDpBn25H1{=nby?$*xwBr5@?zO|vEO zTt&@nZ8GtH1(Fi#IVqhw!y<+8RT5txkMZ*#KR+*7gc;I9eD-+z7}EPi^7dTCzy`oK zWe_v1Y}az7!Rx%vtm#y=Sb+Zbi%ACiPiFWlH0(U+tjk+#jL( zUd9-^ZbU_3Zfn&~GHJ*pCbF8Xc-rwy@j~7FTe~pD#zzt_J>G}q4%>#^j67jwSp3Vf z&o?p#wKWd728mq&{mP2bTsY&J(RkMD_zlaMKEpgp<5{%P&wSB=-akc#J@PS#dyWOr z+s*puz(($GoSa){>KoA!3-j?G8E$$ThJDdVD1O=T2~F7|2G8a63Z5zzOn9f&_YLs< zV>(n@ar1zljC%EKb~W;gp_MlhvS+f2{l+xr2?=dVd)Yc^lrLAF&>Kg`x5EUsTz*=a zX9Wt({aIP()ioz^UD zIFJr;z|lOW>CJX>ahC&0d`7BJWY0kOk-oHbEKd^FhAr&-&wHv#J14r&a(TO^OP}vQ zx|8=vl_K;kRV_NWHUudg9rf(PuTs6vNBTI%TUzZDIUTuF0CGrYFnLwo(=W83NTNx% z$Vs2d!FG-5`5{eNDYC36wEm=cv}$@dILiZv!tYi*yOL4PVu z1)~&WIbg1+xC#`3roo{HxjCG`UYwo-L~lM6o@C0T#B%VTu;d$TS5@rvX7oMtQRDxv z%`cXZaepr2I$-)yLPx5#s*;snb-C(0-0XnR} zjwS|8N#SM}Q{#R5%?M2Bj2rORgGj(nQw^FHq2X8YtjWJ z*cUVuJ*&j?Nqh_{8zP_#jw_k(^;hHa-A$^hFOOW}#E4637B!5VVGdqxm3*?Qojr=4 zR5ANh+;yoiR<?&c)A4U81_bjCS z0XKHbw*Fkyx)Y5ubYLLIOVwOzU)VF^CCY-jT3-#b4${E{*EozaB>exUZ3dPu0*t{qk7sD}hoR-9{Um|At%Ek2O$au+&#_XD<=db3>9peu zF!@EvlE|H5NtrmlH?!lXZ^U|PJEZ98gVfk`BDeoKSMD&}g}DsrabZ+LClpo2RbS9MAg;e; zwf>M0ZdAzM5NBtRzBrTM(0S%1F8$-hlRULm1*$zNZAq9^Ie?4jc!h(=Y*<4Q2H$=v ztp3%ukoo{F`dWO}R079!2adTjOhVh(>>itXIChzrvwfEZ`&vKwjenvZF;sxVB{8r} zg*YWy9KsI=(>~j%mZF)AgQ+uEi2Te-3$>Ivpie`K^lLG+rF! zB3Lf_9wkWn*x~H0?*hy2XYLfsyvVbCk^D0L5j!dd!CPcy`rIo1utom2)=;zY3r}4E zSK`oge>AeJQx~sX-~GA!(Q(Y11Qd!prf{w^$(8r*OW*V%d+QOwLPastK{y1*B5WUk z((lW7>TY`YE;a7Ppva*m)Vm0Ny9!Y~Iel6@M|^!d8KyFv3UVHk#|CWXVn7%3-a zBlxBTECdhBcY2q9`g*3f{-t&U4cUFLfeKEUq1F{+kSsBO#VhJZbRz^{-pv=vfrG4)x=?L~`=e(vb=43(? zzjT;t>!9J-fT(bEEZ8k-`t8n{_YWDNgF^bmi$zWsCm&y&vRRtG0h_eBc+UowZ@PTX z>0P1JmA5uY_=trZ9jfr~mF3fqKGlCXDTX=eZxMewD#8y>M!@54PbQ^Hy<=LiaEZnm zHiEf$c;E32gYhlj@Eu<<;DSK_gYnG*F(_g&5Ck_a;xL$A?%iJPy<_ebU-Cuc z@nvH=9$8X}2QUx=Ll%QDIOIe=WHA5(I~asSh^^t>2aolQcd!HBXkO?24R{!YYVeIu z{?><2?uSp#j^d3Dc!-X8h>mx_hBrt89QXnpP=PN{fmmLFEck*IsDd!SWj0s=F8Jjw z(B)wkfiHLi5vT$eeuFny0XEQOH*kY2$bvVBWjCk-PE~;|sOB#K1ZNHe8~}trz=1#b zgB1|x75IZdsDVHTgcWFK6$k`CumN}ugg1!iUtWPPNP<5AgDNNlHV%Yo7HBZ|gDe1p zLWt!<$bv8k1Qifx6>tM^eglUNghE&WLICGNCdE&%34 zc!Ml3gdsMBY#0@6z=n7LgfB3JU@iqN00cv*0yi*(ED(fJ$bvxVX+uDTDnJGPLr?)j zNCX@(goNJc8h~mXC1cBay6+q=|xL8&ml~&#da**kF*oSKv)oXx@AmqI!*-rLUO5O*4@YKd;Y{&Lg z!QO{{=!fOa2RHENFBsy@{(>#wf-eYd(GG3UW`iwY1Jg!rE&zit7~&8(?Ke2)*hX#H zW`j3ygJb@K+_vpMU;~M^ZF>#`L3o35{(^Rv=-`&;cBbe+Q0G4Y1VYel5ol+71_XHq zghR0BKX?OiW&?2s1nX93lg4g9*l2ZD?n1Ec=5A*|C8@mjQ)c|I0Qi$1n~az z?0#-R5QIWFghH_BKPQAmPjp2u1rP^uLJ#yq7z9H9bK6Gn3jVin|3-y;zy|k5g+%CZ zQ=P$*R9xg@+I$V(WY%F zkMc0b@-BY^+irF@VCFE;a_?s5K!|2$CUa{)ZsNZ7<9_aPmUQZVbLw{QjE?W@u5aoV zgz{eWKQIJ!j&F9aZ~LxqKyP$Kr}skm0}i)nsE+WB{_sQ(^g#D-2Oot0ruAw_ga@B* zhj;Z3KLk{#a1j6ZT1RyRPXwi&??F)YT90r-NCXc5@KQj9U_W`3H_Wi-_(O&W@ z5be`OcGRBsX=ekqduGmd_Gk8TH(-NM?ecCW?q~)C{@?a;=Dv1uzINn}bBi8#r!Q(X zKkq+R?|n~iiSM;yn=;mJZRp0P>FZDkcbU{dj=stw9#)fyF z@1pK-tM+(XkMIp&byfdxkH`B|kM)cu1oy56Ur%|(Uwq$4-Z1!NOL_xrX7Vftb1SFv zDF^dsM&b!@W-y3h-bQU^j&f{w_S<%YE_VYs2!z!y=Q(fs^-gf8kLGq>^yU@>FbIHx zM&c0QcdNH(`2O#%KXm&p{^ovnJ8y77aC8v&cTPv}|K{@tfAD4&fh-^dT^0k#M+FXt z^rmiVfv0s_ulT+PcvQ#u@0ak5_jE3BVHH6B1wu$<$Y*@|5B4y?27LenBiEnU9&P{s z0)U7Uhs~QW1`WOe!-ma3He9x_2>@n=2sR;bym`YW3_*=>o+QLF%nBAhKdhv^!YFV)90|O5psz8Yh1v+GCZy~IG`(nik7I4&@oLo5IpVo_?vHGW{;?aQorGw05pKZ6b}dNk?MrcaO7Cnn#%MA%SwE?9*Pm?{Ss z#`(hLHW=Lo7XsIvg#{ZH7;&sv$Pxa~n=l{WxM7|V&=)|~XEL9ObLL6BfdGZ%en{nt zFDoWy3B+YZA(ic|o3##Tkjg_Bq9bp3}UlF z7KHp4m7PeDC74%YF~(t7Vg7aKVJV9JCFov;5VFD+Ux*;c3alk^O^vU@8mp|O4RTFC za?P00Z$0X^8*V&W2S$&;Ib&HEyWcl)h%|N29i1_!Rjh5q|zy2|zz8lcIdM5Z;@MG#{73J_qBjvI&-h&WtpI)4z!(lX)(mOSSTcZipEpo285c_kx%7!%pP7A`v- zLJ)u03frXq0uyne1u6aE*Hr?Op=(q_dxa{{cn;B&{^Ue?QURW*1SJ+QVF)W_0TW_lBG8rZ>ZiC3UEEkk~N|4!F!n7!(2s zf_wpj9*JPJq(mjBeFS_?b0K%u7zjAbBqnfR-gu@0GOA&-TY1^oSpxS$kWKFpcBmfo z_Cx-NYe-Tv)j%4DauT*p7Ag^cI*V4!mMQmbENv9y%UDnWqOjbBZDgrpD+_ASS#5D6 zGwV(2QpY1O&jb%U$-9h=YPPtTJ*#=L`}CnRyON30a6*&&ZIs3bSUYdxJoZmL;b-D}y7f zyL- zg)l~hSXQjUJiK_wa8uPPfv$SE4P6yN_92T{YinE5?1)#wLWo3XMx>n~P^2QEl3Ihg z%VCbNbsvG|9rHs7K49=8f8EYh_z>AbK$C;Vlghl@Bd=~oGp8q+N}Vc8lTt`-AN|0F zQROzVtZ-#2fVq%(@?tipYNasZf(gJ1bJem`DwPi+1VL|W-~(r7i=XRJ=-7HjT>*C? zaER*}!7!2o9`Gd^3B*E-M$$hd4J06e11PVSG!sXbgDxbSN^}Aq{(uJ#C}Ag<0y9~e z90CrUdIx)t`mptJWu-0z9*5MnH~5P0KBWz%YWMkg?!LzP%-v zf5e6cLl8F_70Hm+xXXsL^^VVpLn#Qt94ftJrH~!dP3RnF!>-UvT%yT)lG!d5Mo7l> zb(14kSdG;}>=WE$BE7y+6&Y6Vh=Z%Ch6)jttbnXAEMbgl*X3HSmU6a;@Rus9Z0h~- z 0: + if pmap[nx - 1, ny] == 0.5: + pmap[nx - 1, ny] = 0.0 + fringe.appendleft((nx - 1, ny)) + # East + if nx < sx - 1: + if pmap[nx + 1, ny] == 0.5: + pmap[nx + 1, ny] = 0.0 + fringe.appendleft((nx + 1, ny)) + # North + if ny > 0: + if pmap[nx, ny - 1] == 0.5: + pmap[nx, ny - 1] = 0.0 + fringe.appendleft((nx, ny - 1)) + # South + if ny < sy - 1: + if pmap[nx, ny + 1] == 0.5: + pmap[nx, ny + 1] = 0.0 + fringe.appendleft((nx, ny + 1)) + +This algotihm will fill the area bounded by the yellow lines starting +from a center point (e.g. (10, 20)) with zeros: + +.. code:: ipython3 + + flood_fill((10, 20), map1) + map_float = np.array(map1)/10.0 + plt.imshow(map1) + plt.colorbar() + plt.show() + + + +.. image:: lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_12_0.png + + +Let’s use this flood fill on real data: + +.. code:: ipython3 + + xyreso = 0.02 # x-y grid resolution + yawreso = math.radians(3.1) # yaw angle resolution [rad] + ang, dist = file_read("lidar01.csv") + ox = np.sin(ang) * dist + oy = np.cos(ang) * dist + pmap, minx, maxx, miny, maxy, xyreso = lg.generate_ray_casting_grid_map(ox, oy, xyreso, False) + xyres = np.array(pmap).shape + plt.figure(figsize=(20,8)) + plt.subplot(122) + plt.imshow(pmap, cmap = "PiYG_r") + plt.clim(-0.4, 1.4) + plt.gca().set_xticks(np.arange(-.5, xyres[1], 1), minor = True) + plt.gca().set_yticks(np.arange(-.5, xyres[0], 1), minor = True) + plt.grid(True, which="minor", color="w", linewidth = .6, alpha = 0.5) + plt.colorbar() + plt.show() + + +.. parsed-literal:: + + The grid map is 150 x 100 . + + + +.. image:: lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_14_1.png + diff --git a/Mapping/lidar_to_grid_map/grid_map_example.png b/docs/modules/mapping/lidar_to_grid_map_tutorial_files/grid_map_example.png similarity index 100% rename from Mapping/lidar_to_grid_map/grid_map_example.png rename to docs/modules/mapping/lidar_to_grid_map_tutorial_files/grid_map_example.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_12_0.png b/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_12_0.png new file mode 100644 index 0000000000000000000000000000000000000000..0a03f61c8653f52a6d95aa43c33b5f55e2c2e974 GIT binary patch literal 5053 zcmZ{o2{@E%|Hp@6WQjA$lC_437K4&4OUp!qXv$J!%@UItON=nZs8go0oQ7zzgsCBG zOhXvvh-qB{Vg*u@3Ju&U^mv|NURr-*w^f%>CT={dhj#@9+D2?w)nD-7cjf z1p%P6uO+}?8g;LCWluT-M$S! z$-40A>?TXHc6;XKk2?l@#^@i!A9Cdg=sypM*2#;i*#54$%Y^#EZ(BG5jFC7rcxQ3Y z>`ky=i@rkAv7dtPsS)oRm`lXQ(TMnkxQ?#17`V=o)gc<@DcZrW@z>%hxM_$w zX3+E9vRgVBhLk&`r=%s2A4?Xc#kl6Qboivb)7)%Z#z%ezw6i5IFgIZRw$hPI^O3b5 zY3m=VCX&kp8x#6m(YS%|EB$<)Oi1;P=$8c+uDM4IhUGq((@Bf0LhcO^g>mlrS9%^{ zy)vMF@k#O5ur~6yfK8>)tO)fEi=*vYoYCHIgLw+Xcr0;PEu>G+huGk5n)zuut~-6v;z`%g*ceE=R+y2M|aQ6EZ2Y)Ji;({w?ppqX^6#8eu%Y;XV|NNt+r=@eAX0w zRKuVKQtP72x8exxaC#IdSUVfCE*G|s_t~sl399GwVc7zIF<`CIDpz&6-(fn75Hw(= zJtgIH)IeTJXm_7YLmWeEXGfkK*7dw|F0*Ja4*GFORP&U1$h z|EfnGn2Zg($pTFZ&R3qpx--@Ke7D?or%FUdo7lB7^dhRu>fr(MVq)i&{?FeTs zl?ER4j~Le-XxMyp++@!ScynC?k1bm&T}oCixdOAwQ-Izs?8U+XVs^_65S@(`! zb9Rm^a;HDc5@7Gt5$NbhP*7;wi%xu1P3yeJgt*aXpQL7Po)u#@~T;G=IwZqAJu|4wRP3v%l@}&AumSldmcYZEp(QjO`fD@*bfe% zH5isdXfH{N9<&Cy{fTo+ASs@*(85Bo#F-)eCUji98@njYF;uL*w6PH!{aZ$&E7Hj1 zmcpzP$E$B*K4fYV^`(u(!N;T7p`zXo7aTeA!~3(iS-tK!O;E*+W9+9i{44sdei?&E zJDUekyh+D_@s=%dIH+&nMU6rI8zv|n(YAzJ!}~3!o#gOx9Irs)@F#X!3ZDz})o=*& zC@4r!XQ`lQD2%9wRFXsO*A~_ah~g;WD7JB}Rw|IwwR)GTK+q2s@6z^t8Zf~k|G-5D z_{OasX2_vxMf+uCM5+fy;8U?aG%j>ZW$Y(hu&?LSYym?@Zjbj7&LK|0PYY|KG;y&_ z+`k`=^a%ll+cvo%;^#dFNhx4ZzeN0}J~q z8$O^V-gk>Sn!Mw6O~EPRgb@rd=pwi`V3@kpZ@D`wrqlOwFxEHg%K+QL^a0-uXTVf3a%P{iq-^_5nQ4(uBg zey_LF<2HRIDAzF6vUJOp8Qu_vsH%?Vd?M=%Be(bm_ZD+M?vRCrn1|n5!`M%n3|}K|JKvc&~%a` zK>{x>S!dE|4O2E_L#vfXNfHT8{9=6=rv2DF0rPLh70zf}*N`j8d!OdQYCIiF<4)GO zm=@fPM$tqAMdiSuMPP1N#iCjw;2Ga9+k*XA(>Xq0eEiu*Hn-KQ9%Em9`FXry zYCmo#hT`~4s-%2i!}Z3h4#l-Qw;WXKm@}ZkV7BvX^PcM*dE<$cajrrw@0Fir$ceat zI0=@lVa7F7trz>Cv@|Z3?z7|3r~J7HXDtGfBr9@Zy{u!uA~x})52SH4vAjagWXmmS@X*UX^*{FeCCXo#JVIe ztkHb!P6kyTZV8)`phTfoaW^)MP;&Nz2c{4x`_)Y;DEikJDLo%cgDb>bZe~I$s~OQJ zfb+!1G6ewgw8b4^Ib0>}Y|wQlc6CB=f+{ZbVWf10WX+q-awz!0uwy~du7fcb5ZFN5 zn0|hkZOj(?GNv#EUth@7*Ukan<@M{Xl{Sq8X0zmxNyVh5wj z%?d+QBbb;v>I6xZlxobpRA8ouI!Vz0%Ze_ESc~OU-zaSGPuh>J6MVmnItu5i#eaVH zf_smAJbZDX0;o&M6}1KRQvIXoICY-m*m0D#XgkCv_Dr*hlpbe-(NP#$qhZSA1az%` zuiz3GecSaci&_D*|MWG~F<7GFMGn|o==Alms%tbxCdaCWU&K1eddIjHRUUE&C=u3j z7N;NH(XltTsL#sEfubu`Fmq>9o6A59Fp*S;|4E5tQtttZbHalKN=S;1ZY3s->FlysqM z16~Y8X8;bIt}RS8_Ckz5*Eh>U#aqowO<(v=uui?@o+;fbD?*yJ?%QkS8$Bkc`eBS^ zE%?IRtp->DFo!U`Tojg%dj}E8r)aGqv`*hB0Cw_Qx=EF=0=Nj5k_8LpfgXH%QO)EV z1c_Yx^J9t)0i~*Kxex2i&OqdP>jA#r0w30&;{MI|&L?371)-MgU&7?W_Ead=IIss% znU+!|RRYAADoZK0XTX%My&V1ASkPB)9jskF3k2 zyz`FO=sL18b=LxYbr;z6TDqIa8g0m_7PP#R$6pAQ6q&THrY(uuDpZ|NDg7FkK8|-m#3O0s(X;!M5 zkOo)xUSia~2t=j_ZH!pbZ=7Z;u%djn)qLb5P<`N|_|&u8B{D_5%P;3FzvAAf6<37@ z4Kyg$C>~?KVYT4nk?g(%`@$TEhwRYdOmBo@W=Pt6Cv3h(@);M;VxT6=W|lW@KJGTj zBw%vI$})`Xju7YQ)xS;x3t@oJ9aGPcI>-lJot6ynpY~7Pkx4_<45L#uhx2faa{>8f9?e#*Vd@wZd!#0u$0a99t`;6zMqg zh1Q(2(dnYO8R}!kTR1U7l(oBZAiZaVGAI>5U*blTj!jxr3vva?U$*O8qyI1Cy;O5A zW;1^e%36HnPovFJB_lenQSunuku#$>H&W$t&ONV$pV95ATh6QsAU0XJ_La66#T+VW zJyQN2cnT>m41EZ;F$xv&wZYoza`ht7QMFQAefWO|5G~f1#idNp=qs8x#k!DyX%gsT zlZ88cT}@@2h~cW&#HLLD(@mW)jCcuxn#gLDHN_04;I6z(d}doUvcRlDS<8 zRSBs*o0goxkxbG&ZqqyrQgNI;;9QOyI$OPD_R`IKaNN$v$@a}hyr+?3C9TKbZ1dQ_ z2I72QVq}AFm;^6D9N%q()2tBu1QH@`H8&W}#h2q7&nh_;%7G`*%vuq>E9F!d)*4B_ zFQAjnKp0E!!VG83mwT|*I)vR1X}>PXM6Sm2e0S)(TuBRu`y6+<>i;UC)H9oVL&U5^ z)Zz{-C)2A-@4r8Br#C5M+V(IdLv&QEtWr>QyqcyYESb+R3e2sVDb0CVq|MYc4O&~v zrqy|v^B4#l={Gg>)~g%F!aj&0cN%lN$393LrE^xiw+|OzY&AT{*SHMSK)G`t-(?@1 zTCSDo%7~Yr1S#3qZZm~OTe@@~-oeC&-19{n*>Np=+n`JCN^p*J6i7*A6LlnWw&-^K zwI=?sq#DR8Z+cfq{*$&E&3^ZIPvdV+QQnT!{Y z7E=~)kgdP`37_5lBO-xlA2j1@HmBkQC>?02{=b(@f4_H{i^rr`24q5<4*{>*K&VrW K$g&eYH~$4O2#G=f literal 0 HcmV?d00001 diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_14_1.png b/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_14_1.png new file mode 100644 index 0000000000000000000000000000000000000000..6a89b3e0fa2739b3b52d0572a78e0ff536e75012 GIT binary patch literal 14082 zcmZ|02{@GP8#X?672!>G%4i`H#=aJV7Ac7cCCk|Noop#4Yojbi9P-Tb+|PYq>v>++HMh^3oAT}y+X;a{cu$>#Uw}YZ za>36aHz&Aq+N03EahQ1Hh8d?c2RcJM=R5h$;0>vYJ3E2>zH zxk)QFnVbAQbDR?eXmurQ1g;}~RWLUm?GR z>(`ly<5$KE#d4n?Y~~#1ZvLm?J>iP&%`@E6Zyj?J+t~M+0!wbB}ygZa2yOH zo=XyP+=a_HdikxvW}5*-Nmcc2e}Dh+5GneT8_OggoroCS`6@*b{o8XLeEuKlLmE`g znS0osM2-%LwD*_>|c$R45Zm{MqD*kQ!32E zwOJ3C*$r95z3>|HY(Fav|E!!UEkDuqHg4-iBfZPo2cZGED)~Gheo8ENhokZA_drKK zx=9t%d!XEkhxcG>u((*>D<#z-?TqM)ueG-J?kbDDR2Av&{v@D7uB^byUtJVNXRVR4 z@kZ>yCB^4J8ltL)958|dI0_`O$NS)tNR4QC6y1cnc?oy5%AslXQdv_a?g8_ZL4k{} z=aD=UYv0)1_jJRQ6LK%ON{|$M zV;{cO>Tm%u)A{c0CnNhdUH-|@(;%+3|9BX>9B% z-CtLmvMh;L3a`n!ABr`$fLpV;mD%t(ZsmQKajIQyT+zE|Z(ToLRS_!4;s0z?qGK?G5lW=?Phm1A_Y{z7}%6~KDb)rxj`3>3%#l#Vt zooc$_9U9C327Tk_PG5GiJGtxJ?6SI?dn0O1=O38F!LRt-mrWs<~{go%4>MqJ} z?2?S1zK1-6%fu zSgsobq&Xo6|I4mKX{`lGRC^+G3)x?K2ZJ_VzI^9e98*;Ft7an#-?$QeZTAPKV1#6RUbX`We$4l{&3NX2qGu{?6@-4u^8Fo1uh z3vNF5oZ!rgxNl*TV!l%7$xG{Mi zKDdso9G9)MTD%ha>-&t}@9Lb!l?|Zk1Rz*FKj(l%Xz638KYjwtv<9|#@HaN(ih!+w zOxNr`DKB#8e~m0y72Kx>5Ld!irvys_J#H7>ph9vwy!Jju%%J-y0IKacyFSy7?UK!)_7}Pl6q!cG2SrMC1VkGQbIgm)?#rsU}0 zbb2FugIW^p5wgS z39)tSQT$qOLhC_ems>guVyLv#XL^(k#KQSn8{}t&Pg-`t*=gO|Lc3vckq_ZWpr}r0 zJC-yVpgZ*UqIO8bl`1P!)?rSFGRRfVu}SJy_E5}T)ZPh&z=&LL2N(FgmdQ)2nvo9F zgT1s1Nl5Q%nI24l?U;tr!ed3c-{aH7L(Yh+kion56=;Y)Pcu7?Y`|u}qgmqDo-^4P zt$U`^rN~N%+lN}4Iz<>%ek$B>pWDef@BeFs{r3b>FX^|i&6|o74iQn#?#;mI@5Mne ztOdsD65WHwCU9rr(I7ZwV1D+h@tTpO+etThMV)0Gah>}z5#zYZoJLA())6hEJ7&-O zJ-e_@2>FwUTZ$~DC*L_-^+6nlXt0#AW!!5Rk13HxMv7m7L0h%lB9ONI+bzm&yuW}?}!SH70NvpSoGFW2QOl1U*Xi*&p=l9@z1z4>U|@k=ckjMfypfdJjtRN@utcQrTY&9-hJ33%?FUAY3W}V* zKx;M=$KuC>X|eTEeq4FgcVRngLcd+!_cI#6sTnyxwV4YdPvVuaId@bQi^6Ef%FY@1 zBF^-Ubzhjk@feKfA{F}aAVxm_B5MMSshhqV-O_KBRv{*iGJdze1kdwJVJWU@%VPGi z56&28HBWmMJYss+1SJQ(8}wd#QO9NV!X>q8Pj9&OsApG}%N;4gLR=VRTp1f{UPPD7 zOq@Z$n%Khy!@C{*ECASxFGf}#9^Ke?GUjUG@cV9kK@_jGhL(2n2hyUX$}+OMTAqF38tv;8(GjVwvf-<--v)7PYK+xDlYXHP{g)Y(=d-Wj{ z0xX^If|MX?#kRiV8i^r%tB~~6 zXB-H9KcE8(Qy2G#kNFL`m6ek5zbmn|BI~lA+%Gn5>U>Y9%D8q-iG zc{;$#Sw_VnVF$zf?*IqSwj{zXR4JrOBr`L9Nhf_Qeh0UgBu+Dddf@ z6D^D*F@zRY2F1u8zB~rGF80elXGnv!ZGK1;_hOzFk1YN!WQcqcK=Xr~>#6BHGy%e_ za1EZ2z5A;be9)~5$g@#rFDgqEWwk0sP;opr`yKv!^wo*ba%5#MLzp39ARTBx<=u0C zIKjlbb)^_gAm&wH{tuS%yOBy8gI{0c!TTeX(wgyGH=8nemX`P6k_n$@aAU8>G9#7r zhI)Y=3bbVB55^`k;HU4%>+(5sKgw44jCZ!BUT)yr>x-(;5l(wggxx7c>b_uF{FL&0 zUBIo}brGu^j(Vr=sk2-c3EvUd6w5hmt^$t`?o^ryo1FyvcP7gT*@e8Bw}2lBRPTO@ ztZYUSDhuomH8Daj71y-9dIY*qdw(=)35f(Kxy?DP)MWckpi$X>)Bd0{Lk^{yKn|M8 zW)*Tt|Eot|xX>OkV*nOkKcSdy8Ujf1-`(PXxAZ8X&y4 ziNPoXZeZ3GGxvfNUqCVc$YAjQ*V7^>^a=RTUzBbE7H;`+qt8ZDt^HD1?2UsRyRor7 zniT-3x@~}kyHfB9A@APccvI0mZ13VaMmKa}c00T|%pp_`kmT+b#?+Y$*jC(^>vH#e z1a-qQ9!bSdiIo;~pk4`w?_d7)8CNzMEfOx)aDXd`-w>Ine4g(eA)Bq0`#Mi}5n9w= zXlXV0u6TR~WGHlP?GxOk>UT@ocq%XNq@|?<11{1HiK9&czjbiG5 z1koP3f&12#mqu^_^Ph9rdK>7)KfklrRQB=ZF{vRV9Z+u6oAOjG0xF|%eMg zap}TDc&1bj6sB|JTe||+YUs!bNg0ec`KYJ+<-cbybQkS2-qg}iqHdm;NPr;fq<(>X zkco~K2#0l^#H7SMBh+MkN`rO}g0NayVhK<>=DeUX-)x{`1$sk&$!7w~p$Xm|lbgM; zC?3|z)*w^0k9Bb6M^H!xKHEN2NL}^qo2O6b7a?JUfJ-tIk{pp5i5s-iXqLf1|ZgpRu{l)6^U*{vitCC#Z`D(&3f zl^AMX%xu3C5+C`L3oYNb{koo1JdYp%R5$q(K>A}PUYYHB{t&A(G%9ACDg#2!ArlwQ z12orEHe;8){;MjNN*ORa{NBgyr_)mLP@^;LAoQPvHgc9Q7Vs_UzTXcG6;V|4*r5V$Miv3gzj zLE|w(r5(Bdi>#1aJyO9=SQLDl=qqcquyuj6ial|hk54JRJA!!Zf%6GSUS_rwS{kjT%}u$Ndz;w`zpAAwfXV!!00 zLn`vcB-_8}1}&NxyTqHKvQ+QJO4f9f_njVZvv%Bb$H!4ZQ@=`>HHs_CQxL=%)go8i zeZuD*6RCAR`mF0|=oYSUQUBEk7mQuhLJ^1E0VK?m01Fl@77o4k`ZRv}F%;vZ_~V#5 zwwCbOB5YreF7?1lU57BMMg#qD59I}}D4*mRRum+BPQccvK>9OAQbGyw@Z5dQh-P5uu~2lR5ATM=$tO5O-s=%Ja#9i+KxLcdP@ z(9C?ltO_8?r{Kbe0RDP!>tZi-CRi{9u>Kt-c&MR(Z5!ZhuF7!JS`hJXrQr!vms89b zG5aRGdnF0@$af-O_%;tqnpcPBvv-D7zf=>R19g(m^KM>7MnUC8G~yhbG*<=1ARZtU zpl(+JY>LJKv-Uqn{4l+t_+yte{P^k1)vbbpDC21WF4BKHL-9@^qT5gmvY>@<+au84DhugNZ!2;EScnqqdp(j4Dmg)$ zOEXypNqH2W1P~o$K?!7zB9tQsmG_e}L&?-P4ut6Vr37-CPeBz3lM zv7|wF%}5xy3e$&N9@eORu6(!*@2>6e(}JqA?Mx$n^&eB0hqCod^WB81q(K*6q?1HH zKk5LW7gc;a8~EZs4%2)IP)rTcw|4lK7hgueW!0nAQnD(DW% znbdgXg9U}C`w**LP=7WVPYC8^lw>X7{jL`nw^TEDOcvlVg%NPK5KX_msDYe#F%g&@ zyFFJWr^K(l6DKAPO2~~fJDwA?fHz2MaMC^yj zJRcL#kVB&zcJrT)p;VPJ@<|_`(=dXX?|ry{J8SPnwJ-D^Wj*o_iY2deoQ?WwoUocp zI@d@~z;Qad{SFcExB9&y52F~B;90@Voun%ZLM#X2E&|G5baQEtA`R>s&IqS-N*|lw zL-}XIV&W*9Hh8UaxUOXGYcY|qEjPzUZD+(I*CLEvt`#QZe}wpk2g2N_WbOlD)df{j z2CkQ8(y<#tyQ?BUaFkiiHv3$JBjA9~cri^j`x&;6e8jE1B3%BaZ%0iH?n`BPtUNUK zxe(J)h1c3Z?K9j>Dy)_;2-rt*aA?|_#&!LL;QIG#V{0wh(PQfB&=ejJXu@VgguA^R z+8fGGy0u!^)L#~`eX(T?-+aQ==kF%9g(VKU(hha`htjXUid5?PZ6~l+B4yTANRCtj zo}Wd|UiS+f2r3&Y)v!nm0yGiSP-ee8b%ju3e+_m?0^oZsN+~^2j#&Z(faAO@RDKL? zs*qjPonBEch&tLhp(<3mMSoFToE}2&dS|7>%Mi`3diS7jOBQgWEYH;Zr3&?S& z8}L^zaJ?fCrC%lu=}u^ewU)Q3`*G+SX3lP;G_^+amq9^nbJs+u^EGgWvvnG_>kz#2 zn-&S)FrMrD;e|~GOj9W}49 z)nBrXA~t*qTvS!;0CkgKKYkC2Nd)|Zm-;7C`1WTF0z9Qx*82^B&rxN??sUyvdl@n3 znxL(6+r1)xnz{T)eJ;e>Md}y;e#5hhVX-XX!vv`V9{!<9rhm4p=_aMI;29S3DGU_= zaNR#9sI0c#j>80N)(n>X_*DU?dI-pPxg@7dJf--=qit+)&>qx7j1Zx6{^Ff0SqtQi z7#LkvX_h+jaVX|BA(ZtPYtBph-GuPH+adw)D7pqJ4<^^hQ<%ZJDj!ZgAW~PjOYyB8 z)K`+jW2>WC=uh#q$5&teQO7_!9urb8TbX}2;|m}lssgrvI_zOov>OJYyFjpWDu@_& zQLqDriE=M^c2!fFgxA$xgjB8EK{6OnDJG|%5ds^}QQV3@3;nY8uddFZ*nV<;oZPit?r+ zwm#@R0kIMKFlC*Q(=Wn>OyTN74GMN)I>72~>oP0!(znal0Cc=fT-}kCU|vla3_(_O z`OhlP2i^&Cs%xM$TjhkTlY9d_6=LNdgWv>kYCI9T7-#c#GjFy4yl!ai!~Am5Wm3cz zQ-&ZHCqyc>YgYU;poMCPN=4?DG-7YeeC}YYas2gY zK9X`H>fyrKdy@)HT(H0&`MKK4PwNfVPlX!1NT?`^l&>(?EF_=%HlgQLZ|>LXNZy%# z|8h3P+1KfNg!smbz;2Fh-ePB;M<~ z_sbCpw`eG)fuX^&+1GC+Q9agf8PD*tm6XqvAyLkAty9PU)iM7ZARN~M7fBh zfl(gUo)|&&p57;F#x8#dg3)$`G9(39h4qHSM|igiqiVM622{n^^y|ta**+pt324q1oG7HAS1@GScj9mh!vmy7lW?^JNir;k;idio( ze)gcCYC-H$)?{TQ{16}!Pzy#Urr4h=qwItw+}hbK)bJ{qfjO-VlBN}$1#NYC`axgR zk7W@m8b*_xD8yZGl=o-#Ken_xtcdb+nZdA)-Z_yj1Lr#%4C?t_NH^A;y7f} zGtODy@EL4HfgoLbOl0bgJ>fU(FLZgD`*gImyz7Ag$pXg;i(=8_9Of$EXx59~Fqx3S zy(o;a5g<9PBp%iXnjK4n5NNmhRsidDw-{h>2ZM#o_P{ag0l6P;M9|VRKp6u@HP`7OAm1z=}j9O<`<^Bjws{6Xz$T zOviZsL2ZcC?6BF<%o;9QQ`=T5$z~e1FN7u#w$JwZ)a{^XaiE$bT>vhSaBb902Y{nh zmV$8q!+ztTnAcx@7f!mCU>Uus4l7rkityc?qWaL3dFa-DUP1}Zi$D>{M0&F+abB1F zOMrt%;(@E~LAiPX5-JIF;i+T1$rH#sYlm1pm|2WZit}SD!Chsu>!Hy4=JfMB#P=E^ z51pT}xEcX_FRK!^rL;6zSH>j8Of_H^PU^+dq%I4J=BOR4z5ogrQIhF_P!*UCS3{o5 z>CO;pj8)FJF`nxJnq+bZXMpEXV3J1fT+cFm8W>g`wlkNcJ0Ui~d!QsLESIDnHcqM| z2OL;VTj^7QK!hwAvjF0)SxFk#nM`BK_3U$dX7c)&WmT7%%IZ5ui!*@4-0AqhTpAQp z%K@31@;=+B3y@cqZjw`&dcj}5MBzlNdOF@}iX9;6-$}a2jECoN-iG#8r9qyqbG_B4 z=gy}R`460F7YyV@)S_LV<)k*!-DhhkQV^?c62NIr^VkiGLpgZ5Ztx}T-pe5j@2AyF|Y`>0I znKBw4_Th4{HS)$Cw8PF(6BV60fDj`Y>UCIa%dr?+>q~OtLotlj2>UNZZSe$#a9U;THhkwiH=^zI|g{>CaH6xPmuuosD8>_7)A)3trm zPO`rOKPXZK?fxf6O%1FLV1_p6mobZNCvG#MfzZ>S>V+&dtv??U`2`z>T@Qk$?Ng9& z)Br0j|17vx!mOK4=5_AdY3wqiyXq%US_~nl{>~P=UdPEhmxKzt{Qx;U6o$c$Q zY-zbqo&rBKFUl+brq$2xrnyZRSY(+o%2QJ(O_otr{J_}m!u8#1uNmh=gV!CI0$Iuk zK5Mp?!V*36@SPo?8PbepKO-?I`UM(R7Tx;K2CF7@p5^*vMufd1QHH|q93W?jo z6@jYwPkA^Rsx#^_fQzCFk_ND8vMC3_5w%u-9R=J=V*l`??$Uz#klT2tCj2u%McO=# zT?YIaOg?aIb`qSJNsze1Kr*`p#eCJWlj(ZZNZ->bX6yCN7F^*EStUN~rAr;6NwH`4 zJ~E#>@4%#jouu0Pa)*+SR`0YbdKu>2VJEAgprq*aDMAMc<00Pb*wguxOUA9^@|pIV zVMH2HBferm>!OAmw?uBTdoBia;X^A;Uo~fgmTv9!_3*gu%=iUl#*2K15~a-Szd&0- z;j=AZo4I|}7Un7H4=^`V2(UuY^+9i|EN7CXbb*qo$H)r~9YIfgnSJVMicS3#dKHfV z;{mc$J_+6B=T6z?ln^jz#g%WiD$ykx;Oq&(D;5j-C93!*x;yb9BT zF(1tLOqJgu&W8v5GHva+<#$<6(pY^>qC5d62r87^#x5%$ICYm%RZ%}02y?^JK~HuQ z`NLh79St>@T08-?h#e#exH@Nyzu8plJX`x!0^~Q!^TFZw@6QWvzn0M~R?(uD(+tXP zXM-}}yx`iNI!0|CkNzPXwDpw(rqe-?QpGwTLXDG##@!G)J(R0Glu#I*FF~q;`6zbJ zQJt!?fh%*$qS(^{wyhnpHsov5B5%WXTMdw02;Nfuyi1&pti#t3Bcsu72&^BQ40SUa zMqkA3gZPQR)$w9;Mhvmdv2cw>hx{Jhfjf(Pij%?FkvBYGunErz`w2R(of_j;A1x29 zC}K>sq@U>ut5_EEu+BnOj%5Dc=N zi1QxD(rCOmEuUTomQgCT4fk!{IW7(7|N8|;L+E=A*_-@lost=cj%UW=+dp6W+Ov*o z5yhhD!#Gm!$3+IvhfK+7^R?}diMGCH)K;p zcr>dGDxz6pc;podUC4W#JG`Z7%m2MbR@i59ko^3AEL?ex!NQ^2tRs(f-4RxEv?(6l zBKE5YCr;ito)rDF$399aqyFJBnBC6jV`k^7Ty_Cd3nB&&wVN}lvr!pO5_L>ZN4&kT zF-X3$Nc#oI@KQvVs5*2x^U&o+x-_gwuz@$1%YKnc%O{z}D~FA9UT4)5`sJi@CB>Ay zk(LlX_X+3CrpQ`-x;6IT^7`X>?pv_91aft2oC&IZf}(L@!TQocsC?k54ejgq&xR&G ztVFN>%Upg_nhRTaEH_ze?oUHMvM*ixuP1t@aV<1cx~u7AqFgI%Q3EuSA4>gHNv6C} zJm&MIriyKmYE_M_TqDLfJvHCMZ`VCMxA)A-W!fH}td*uLY^eY`dx25fnbo1+#;Z1- zCW?S!j_eCCK!+TD@7Wa(@bC3GdlQF&@0v4}tuSt>A>Iz)tYD%hFxl`tp9vU(x(DNT z?MaZ^wcNYd|a* zGfm9wg$A=ma&EGt5dlX4L>BV{I=cmE&Gsug)pEl*_iisZ!;=Vm%*Zr1MLs1M9wi&)ae1e;#ArYDqjF zZolU!bADm}^NWl|D&xdf0mTfT1A98Lhw&Q-1;q$Oaq*C?JtBRkeK?usv>R*2&$VxDKM- z_SI|tAd27mdx}zL#2n-j+j88(=tge%{ zze$)M8~M4taZBRw<^L^N*VK2b??HqL*6@dW-q8TsWU6`p!J|X1Y$EE|ESxhAG4ai3 zgyA!!74+WY8P^c|PZc;WbQf7(dnH@iR2mEnu7h%Ji81%0|tw{v{aRK&S1zH|Zt zi#phePuRM*Nho^cH39I+&ja;lG0L=OHVa?~Hh8$x!8sw^SP^y|o4}F|V#}Vovc91K%1*s2rDKb20NR&OS zw3IWi$wr>j6KvlICq1!TRi^Dd_`M$eXQ1O#c+6)*r28o-CcJu$@DdDkq?}aT^usG0 ze%~FbL5kk?E_r}zU}c<#T40}MaG>%+N9WYBY;_Yhxx+b>ct*)S3{=Q;T2TP!@!lB{6u`ur~ zd0_UR1OE*_)hX+f z+p&o0`o5aL2Uu=<2r_5=fI~XE*LFMpjYWSzD(hsrwdL-=PPL7F7~zZUp_dZaYG8*2 z+n(*{U>r9e;bN22xg!f=s*8H^uZ~o_K3dR}d)4KfllTj9lOM%a5w> zi+Bd1Dq}}RH_+%%iRSEY53D(gJ|EMkL{9xm>2kTF!v3FWiesA z`LE0CZBja^ulR6e8k%$p=Hrc6h+D%^Nuib7&W+vF1tg3NhOS%LvV+6tjW$jayyceW zaK==uTQnG5U?i2qH@g;I6DmUtnnt`3s}1O*XQPgtIW_gnd_Xvh~DVd`b_c zsP9=3`oEK0co6}*(+6sb+m@YiO&@ms&9aSCFuN0& z=gTGNGUn`w(8QE!j0Xy_&gy`bJ3 z^w>T%NMj(MdJ6%9jB}=L9y@hJz31;t%Kweh{22z?2n;k@LkSVevm`wstlcs?`7(V& zBWxds3Cm!$gB@A_KEL5K=oYWdeN3?BsARv~k~4#ALDZ!`>cBv;-@tfyy(E|iW5NZ& zwZ1U6&(v`ib5A{WtZ5u7SdgSXaRH>K0u~8M=*B^EjtNt4S^kNyOY%AmygvJYDZy7e z)*qqI=8_J=ykAL%a}RT@%PlRuY-WrtyJpRMuNa2_HVwEHh;U>2a`-uB<$7Q~F;zwk#eof*^&d6NHz8BH*F z{cn6KM!Jicy=QK_T?xB~K=JGG*4@~2hIvOdqxBGoBC6|OQ#P7B|5`kq$ptQQ_S^8s!KeS^l5(49!QY<{zi8&)O1JD6g+*!k!~A!i zIyQ5Zx_J+s25Ft8E_#k^I%RUsek83rWJ#H&d?0Cfuxk?$#h(RVw3CY-wcUye+s8IG zFu5ikCmu-(dmPEgBY8&ewM@Y8sp5YCvng~&fGM2n;6olVO4z-OQHCfSfvSO}mG;t_ zRgDV4*G~|uJ}|oH@9@XyXn8$iKEXSNv>0%n!MCD237dYuU%sllT~vnNu#O~-xgoA9 zVRO{KFAKI`hy=P?j`IT4PCkBD4<&2nRmG?#d-FIsRxF%%iTZQ+@);NpTYXtZJ}xSr zOC`f#_w^%s#IpD^rz0+{1*$Eng>A`ASRLpXdD7cQ$YyCh5hxv|ro=aF1~WKkvH!7# z5>DGOr^#TNdKYJ%`FNLSM$=*tEvoOgZDwq0HcDbVjWMq3cVtd-HVJ){D@LF}G1?nv zi_7_V)-$#M5vseijB{fdjs8e3DvmEY+zENW0l=R>PfbQ*^!)>PGk%-9ruz>{WHuIut$GrAJ?m0>$YMXSKJWCO0E@^H5qWO zOLyKGh&})#FBV4>mC5EFQB^7&lyvWZuMX1@0$ds_i+e%c^qh$5*WJAUkL2~(Q}a(a$C64WcT-_w?EQz1U~^^=d6kSDwx~0a$6h)k zj!Api>n~ETnis{460%F59pl)2Z)G!ZDg-CqLlMYCE-Qe6sE4Xf@rdiydvG_KV&$XP z4`y=!5-t1d1Ja#-HtL~tn;q@PEh3serU>s*u*{&f#kpvUVWR`1SRipLeIQkD09_2m`=`gY%|~sFyL)gZ1O zm3nhsy)%{S3f>G%@HX??SIbWf864zc{QvK_u;BlnU(j0GVi_H=xs%-ya2|YL4RXrZ L9A0hcc;o*7(A6r# literal 0 HcmV?d00001 diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_5_0.png b/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_5_0.png new file mode 100644 index 0000000000000000000000000000000000000000..1272a77a5eb3a95ecbeb7b2f9d135fdd4ed6cac9 GIT binary patch literal 121806 zcmbq)bx>Tvvu_yao*w9 z{nf2{|GoQ$f-TOTIWyDK{Z04ReWE@n%VJ}aV!n9s0$W}V^6|wBgzy(H5T(#jfhz-G zqeb8Y*;Ptj9UW-C=w^|?{}@hk+O98NVBtUiB22FM-vbwg+}?e1Q**R%^E7rbe_?Oz z=49vSW@l|e?P2cXYVGJi&Bw{j$;VD@<>uxj%*FLTH*h+-SaQLzDhgh_pnf3_kyQ7} zI?(s@di8xyJX1LW8NCyp@0Q4jI9Y_w{1Mq2krq8acM|!aRN~=)0?L(3%c|FdNLzZr zI$0>q9F*uW4j;<=0fWI-G7;r_ymPk2gEAIYfFIW_x0s9{J-eaU zfEIE<*N)%MNZXbaso92I!_Jlxnaz}61yPTPbf{&oP}YH)LM~qOX))ys(vl|qy3t$k zIu^@U_!224bpr2%yFg`7QBk$1>%J4Gd$aL5;_`kY0Uw%dt&Cj$w~)?yz8p5v<4)PvKCdTMJ0YXjB0deqIKUH#D1?knncqY1ik_(CY-4Eh)kd@O z8_0G}dXOO7<4a3pIkN45_tx+GlzlFTu(_^w8%BO7+3H$nV5a_5UyB&#NU9s4~gztn$A=!3>*qVyXq z+FPk9|HQ~P`KPDU$gY{#C8ZM`-eGi9Y)tN8>#0b}fGn#i#(bYk7f*xdEqtl??|d^F zdd$G89%(iEZ89IWlD}ATgct_+S#Oye8J*+=J@;#yCQ3@`RWk%pD5y8Gil*E@z88=H zbe)YdoaY~ZX&F~vUu5(vy0%@$I3J=Hs z1$*CMpILTb0YIBM@nGVdu{K0S?48@~YxQ@%ze{lIs>ZUFQc~Q0lvo-WIc@fGhmRm! z?i0k3zPsqdf-Hrk%r~*;d!I)>-bC#D5^%Nfe-`0OK!o;YuOGf=37u$uLT1JDZK%(;O$tZlnqjU7F(O=59GNCYCmkI^Tkr4&sU3u}@G1cqMSCp_+?H+{IdLDje4~ z+7e(>DqbwRLeOvxI&S`>1JAmC`ZXd&pS=#D>M=DTeE=^|yHx%#H<@d@leq85qy>gT79(C5YCJTG>dc{>p=f3heK@l0wc9)g4x%!AA}$!AZhTK2K#J$HLT zOgyUV_1XLUMq9oBu4jFJ4XBp9!iYWNLr6im7XBsXm16QzNDIRZmmCn11 z3E9={EWspZM$~Ktpc5)S(1~N&jlhNY*Vk8ib5vwlQN|0ra7;(U{%{(J$?39HkEp&d z8e?|tV0H564%W{mb9#S{ZbkMcmRV>4dayGgm%-!BtE!iE*Yf*AOZCxGM7II408V+y z?o=lO_*v_pO;IU@S@Pm<%y7)h(H3(2U|txL3MyRGW-h+e(=lI`Qqnhs>}(rN?NjUL zogpedF~4WSBM9fwW0l+G(g6|wsY2XaBAOU+-NJjgOoI!Ny$-bhvzcZrd(uasLj9IA z9ozVyT+68VNnjEwfVYvu+~Mz$06UvbqC48WR7ij9I-VVezP02C*Obtx zka63FK^(i}FSc`zHfZULx33>O^WVh;uVg%L#0y|}Of$v@6mWXq2p2)6;W5SBTjcQq z%bc*@+Xc(cp|Ny?x#=Itokc;qjwo~)Jak^En$PnFP!s6*2I#0-Z2*xD59C3v`2M?H zz(#2N>!#mW{=2+Sorzm_3N8fvyLzBPX~bj(jr4!x??6m6pY*vD|`*>HfPB@I#GHfA85 zIRC_{Fc-bJ|9BO))3o%b>-O$=)s#tzwp^D;#-dsWq~G>Oz>{;L*7Rt@2hM1-Ol(tR zB;)iveE=)}Ys)nKZdp9`CGG>K=X(LfD%}-zW1a}ZIs%Rl@KQ}cfD^{X52jwxj!Ao6 z!jCow3(^<2`@P%N0KC8J;||a2D^-;XI_*K~t*2v2f#D>iu7-?favoX5P+gG+AT0O&>gY@fY#xdyDdgb4N}D$s=EWs>lXoAVH~ zda*0w1A^wYqssEHVwt5zl7-t>U$;BF0T`oYU7|kz(+S68-__(3rQ`pO4dQ+Aj8*Sq zXe;)*{N_8+VqRxUX>>Z~{gxZ&@bv@4KH4Bx z(AhgVugfe?1v3`JlTXZna5dGIxv@h=12eeV4L1hkZd`)Lx9bH&FYx%l=lj)Y64ygi zJRXzu$Iku|=Z$l`L~Mh;|03^N1|VBDGwHT-7Rm}PRPZIomZJ{uTWAX?iRoy4#WRCV z)2xa8-Vd%1HGI7HI{KR?5%7n&RsWt3ft9)oztk|(&fEI_*PIA04`O=AdR6d5)j=b5`PQJ{AM!m{ zCBO9tBCKZ1LTYFL{S%mV-CiD=sfzm))x5@dcC$Qmc_8n$;?8XcEjr2OLu*Q8%DKqS zk$hpmnrT$_v4eIi1Vzc`5(*QT&x*y|>yCHPDxTuVw8_C72V>pu;SMdwkaFnVUHXdK*+MN+G0F z%NY-_U6;XlA5t2d>KEtM)evJ)Yt-mL1E-#m!+fHU@K^6A|Ksz)p?)X5GW_#}`c>0A z_z;fEwlbV20*8l)eR#Pd4c;1#y^#`$zJ-L=F|_Hdmy)oszk-^K&RfT6;5(rl_=VrK zOPytlM*6}P`s7F6Y#!skYHU1qZm@SZ@yCUsoEHe<{>#-#f~CeDE@fc74AfFph=#WY z++t8|&DXAOJU*ngexTV>hW)Ai7al=1xSY!2N>vXPC!u46-J{msIhJk)h$AQdIX zIPia5xVt~!0?(8NsS{g{wIq-U;K-jIwT*~P3bSGwsO--bEM{U|;ZTwf_xKd`kEjjp zuSEZgGErRbyMD@*ysDj;xQ6}>Jr^}LKGAVKS3kc4!>U3~KCylJz2JE-_?XJRd$80^ zMc--i4%*&A<=h$l>JXkhb8&|1O}StW>Ws9KT|pR%SAp!Q))4X4(RafyJb2(nd#vKqzcF%E%xmM)xW;im@W%UES`B8= zN48FDM|~qBBQtQdQ;W3S-+-v|OH!I5*hjv~TjQhg*;f4cl*<1#QicHheQ+=xY zHUb3Na+fJ3_4OGoYrjUDmvi4T_FHT^p=t};IVBQ%GX?ehwtLkgUfleY0`XVzB+^f@ zq?g&*drXQPTvN zoGI+`6`P*Wf9ORr?Pl16!coI8!S;)g0P9)ne-i~jv}*r!sU=Kbh=#!- zExkLx7BHp!tCr*5U)b%M+kWmsW2p;fQjotxq+|#<*t<5gx92?w!j%_kw?`u7?;sVp z6!};RhPC{*PRn6f@f)Rf+BRScrS%dOH8~fT+w+1--LkFwo0qJZ(uXVW%jjf&UsdYv zS`Ec7!kt>z6;6A6$8`SbmEkdl;IXUc6BCCE@Dvz~Q*B=cu#=h4x~N4D`L z;+NOHU4hL%Ml*VG(5?k>=He< zZ?$xtyv0NL?sKKIV6ut{xkxH}JTo&3&#M>g_J2;e# zolL9nHyGUX!F8*(1C1^xW$at~8-gdmBXtS{;GzeyJ?HYw$Q>*T<Eqh*^~9~*(1lHV*Dz);HQ^F3wgSuvXSpT3BGHQ zr3`w__sf_S)9B~RtYh93VsfW?2H!jT+~4@%J%b%P6n@*biWydQ>RY&B{^Uu_oirglLFr`8WhUMDrWsUc1YZJ$Dg6 z9_i4vAX0BLRSZ!p>2tdOC2+KH3zua*-kp-Habwns-^qqXir+>8e8Pok^eZIS>pix7 ze%s}0PobWez$mHrQzaqSD_#YzdcVHb5TN&0#hz`dis%-6rX2}}(O|s^zu0gW^o%ck zi{Q6bYg!}ml4I{+sa?y_kQ&jnR9`pXSEKD|v$H9*okzj&YM9g1D}6zO>brAyZf@S#OM0(dS=?l zqN^kM$#Q_8z~o&%t^{%~l{h(78=0_2=vD+WM9BsAKxF$#|AMYl>}sB@An{ z(S}E>3bc`jQ&u*r^tC6Eglc@0)O6|QoZG6|dV@k6wlpl~pU-Rln~>u0HTT^^sWXpH z!};=$AERLKD13GQK*Skw+xJZVq2u<#xJp-RZLXDXwG~x942y5gIpVQJr!f)pT?8RV zx`>Bc)A3S-ch`Mgz2m0B1&6`GK}hUg$^mSmKZV8+**bO*UAW!!joQn~mx#1Vx zPx-uAI5%gKx7WK&ayZ_vdO>+1s5F%HZ&FKj1xkVz>P{5h@ufczt2WyBMCE+rY}w~vp78q{BpV(Qhj2?;(Tb@OSZuEsoBkW_*maZMxEH(PtU*#?k>XF}sOw#R zomf}PzI-2zM9(6dL!B>YxMc#aX(mc?+7h6DF^E}*;@z3{62wqVb_i=Jz(FPwwsU>& zSp?QK&s%hx|9BwN=4)0`zoQV{5%ug3_YzoY61uaQrC)4(&-LRA*YOx}e!=Ogdsy1p zrmLqGHUMoTIRyB46IIE?R|ma@E4M3kC}cz{m$Q|0ton=AUW~LlNn56q#c`c0G4h#m zyP_xnElTJXu1I@u)#)+CZ%g}YV6hS6xx6lRm0`*4e`0j-VujnC)x*Vf2=#tWBZVEq z+GtauWpM995oSm7s(&VC>&-qcNpOb}pG6ClXA?R2JH2}8Tg6b%!Wen07199rkJ8*o zZVH&`(a~p{E1vxZ);x9j3JS`o1rzchlggGdz_s~Zy<$WuZ*w2q^YhCm_+If&UPSKC z6o5%hZ;me`+e);37OW&adBrE5KT#7EL=(}k)E^5HIuZ_Nu=dggR(ph&KjgkJ0V!wG zlfD^+MTJI47rAYL&d6Hh$i&HoJ{K!Gd%`-N{PRCEl>wCchdlq?3JHqv6FcITGDou7xPpOT4Tu|Akcu z2+wE^cZj8ZMGKi=q){ZXk{Wd2buqVHL{ttao8Mh!t=K;vfLZ3D3C_Rwzkj%Q&Chf! zX07fB4uBd1{A!iHG1;fiMZaYYtvuB8<~6BcC+SWf>iHZ$nTyk*TOJx3xjN6imxUk- zOd`gwB5BbM%R5zH0h)I}b@Xe|T>myQuhDzKg$9nfm?8KlL7DZ0vQUZ44Uq zAyXn`K%Jxap=Fd|;z5q_nOz_XT~r(*e!M4u7bO!n*@tX|!~?G2;hIXx{v56^T?i`4 zk~C!~z%<~~&^$9QmNs+Yx3aQ{$Wqc#tA0cSg^q@P1K)aDoD+GEI*F_~m$}U`BUf6S z*cDrO_bFW!7oWxd?-_VCz9qB<_yC0hFd;t}^-2n~I4`AfnF}%On zwqGG#ebd&{FBA8>L_uj{0{v>lj$N8NiiUp%_G8cO(EvZh2vj~mJ^d!*QckBCC%_#) zB+_<*Cmi6fAFo4{%Q2{w3f;1SkZs`|cY$`7Z-e!!Xp8jK!EPs3bbPoOm?%QOCDXRt zJScH!5FeZP&sWyWzP{X#!k+O~qr{$HCckN4qYuSSRESAQ?;bmE)bzV1fAqP6_{5`8 z(JM?d4tEMV@$nKYoRdY#IsQmZ{8)(Y(duy2Sg8|4{dARCUu`TcN7na=t^XIFJl-1$ zQ*=fiyxk(yW{gdo zAAd`ai7GMrc~$|m%0W+@97~Kq>nEOnJPLBudlUWbEn_oU1f936;x*7?cPb)+kp24y zfr;zWqYaxm8RMMlE|&x|&JTe*t=o}r92tFXtq&7h2IHa}S`erzbRToP&wH*7puZLZ zYX59vajAQ+`NzQXrpi2zKz&q1+XwAiq{|V?F8HWcuu#p4+3#t@kqwjDK)xk&0FMNN zOOT{jPoqLBB3dad(o3@!lu+1Yf9a~%kzT6K60Mc-D_64SG&FSH9v3pm40{hmup+~X zJ<2fQ-xH1t!TMckoc_P53!ARjo|dD8z~Vh5e7RlTaD6!7F9hwZc$chFB%?#RJsl6O z-P=uQk=q&QTP!s@AAMSw$1=BJ*IXjQk>YKBP`qBQE~ohYWs>%zqW3VrchPSfi|hHO zt8v|PGGXgGs&X%RF<-vT&2$(`O4=F!Ht;ruKT0x0%5zfEx4`BC%@LxJp)JuV|P=bRC-v`3c;WAie$Z(KsZ1R#we;ttwutt#aD3bmnyW-lJ% z#mhO7JMo8?<9`=z4-Wwa0pOcPGTK^Q>DFIr5}bbLW(|?b za_EHw{6>|wT5>oJdxZ~omm>E@K@Jf(LiX$$<$;pzB)MG0fK~_`R2u%L7Qowc#&n2x zyPR~Cu1rtpo6;*bEfc?8`mf((^2XRTM_04cBl|Qup&KMWx%rD+fh@imn#~8@iG1qS z3Qg~dC@Co;0;_qvtMKke7pkRv6#AIsu6~DA>`rJu$K?;E6*ZfZ*71)nyz1%>2)10E z$hrgHv~SO2DPr``QdoR2imcUIrp9ur1OLgpQBAs8qlPa!5E1<%P*imv7S8fjuav7x2`ua0D#XFNm2Mm$(<+ z9&ifn4uiR00v{1nH3+IRa*&|YFiesHH=KR|U!-tsVq&CG8i))|ls#laVJrFX<|Qw8 z)*W6l_T>YPb1fnkQCmW$1eMHWo^);fOrDKKVc(}ZWX@{g2CE=j@$*;%cYI15)CN;D zJ4Rt3+jY#=eDJMz8kt0u&Ta1{vsIyVjyN?b>qey>38jF6M|e(v2X6{0_Q{+QECo15 zV|KroX(JTVIvtS{$LdbkXAXR*%~!h>bVWVZE0MX~WxAi?K|RfKk6oWq$@^)uwz>eH zke#=x{A3(EDFgz1lsA-65X5(kJl`_sl2W(r^)ye3NM&Y_F~vfraDm9dtHQ*Jv24J+#h z!Uh#8cwKIzZ3xZ7H61+?1)zb+Mlyq%Fom*DJkw^M>Sc1ef7JaB*otkB-tR?|T&DD! zUMMMF@9Xc4bZGs)z*Pl5s8`nQOQfOZZo~9sP*Ak zT!Wv;U!`yy_tk13;B*0S>J>7dZ&(=3W3C@G-?*RIVutnj+UR1Oot~V=GO*YEmHWByQSUsGFCAn2+0{2z9I`2*7xf4IjQqmN9mMRjw8LU zG4zsjJV>2!0x-h;s~r{iq5B~mI%8v*>|Hx#&7`oCCyI+OGH(8dvHy2^B^lPlf zmZ(sa#DTNIeB`gAMeuU4Jjmfq_$d8vS67XdcA~i%Z^BCb82-}i{Q(S7QvrdQWTurF zITWltu`h(|f$Q2U=y;Mg>N!EflQy79A~X_~^VB*2R-HvYzDFBmeYM2=Ck_ zkQ;OA5f_oWUvE=woj7grm@aSsjKweB{K?a7Tasg0ATxTozdsTwe$Sm9aYT7_ARnL^ z?-F~s$YbdK#a|pIynEMmgSxF-+qdd}!MvE`zv!)4_HmR>MsSIUbAYG&$-z;=1^IAX z!qHJhLF#U~bqq+N7Udl8S8otEvLEn`=RWMHK0G|!*PrXnR20ycMRRoz@JKxTJILfg zVtA{PCFgi{PtzWHdF5x6*WI%WC0++Tv7C z{3vl3<}2FUD_w=yxUiswk-JFrUFJ4V*}x2~*3tH3#=W&1tHsxT$Xwuy_2cdYSh?

nDE;(^Re&8^q zJo%EgEo1>Q!E&3N>j}E9SfbJVhF;bOY_@U8>IdN5sw$D;Yxib+#f5XJ3+#CvD-RH0 z@Fu@?JT}lP@p6W?m+q95e^$n43;=+cHh2N!?qcixyd z?flZ&_K*+0jCFF`T|VHVjndYKSK~8SJ>1`%bnGlIhzVz)=bxid;muTH^>te(`)BD8 zPX7w@{l$NRbGt(qJC`Sg!dD<=n zM2?}+G&6)j;-;|P@z2|f-Hu#VO^DO9$ng$|QI0sILQ^$VAyCAZljfOcW6@~F@2DLyl#7Dc9r)35z?g4_R9}-Z?@3l5Lpww$&v~r8KFA(W8I1#Q3 z`MgwIRf& z(b4%Z&lQy7Vm^9VnZDnh-u2=^1{u6^MWr`T-;b#1XYC(u64Y${(2d_2I z9Xa%E&c*#ABTHLs6diuQ5V3~A^1NNSZ3IN5E%Y_vhf^g7j4leG_4O7H3p)@H9q7uB zk9yI!z7x$6LMl!o5tx})|E911@@}Di*IjXvq%c-sZ9u1c0|#Kj z8@VnFz+LU_wKL!{uy97cl_TWnbEwwhf}7d!+XT*6>24d8anK{1ViH2QVevtq2zlGW zBl=4#Raw6CTO%gq$x=?VkF0vpMfQ(oDEG62)0H3ZdpATF6?=T$RHtY;u5}%S?rtxU zXeLPV_NQse4Pen&hR~oyJZ_ub2J@H9F9z4QG8)Wd_&U9Qef{vh%s^&y#8kGrya?I! zcV$>9^EQ;ob@ban;>1t;(W6-76=80CjmwMu>h!dD9(DszG5xfoHFKRe-&#|rH?Vrl-(n{(A5c#Z;>aswm)9R&<)mI zMg)6U9CxBs$LC3}nBoIrPxy?$nj4&xRiE_lO*nR>=4_sx5Z(rGgeP=+?Xm0>xhoFW z<$f0SU(RTbL?76#YOmRV*EOba;i6vcRgBGtwz*5bH1PRxBO3j(xBmJ>+L8imgm!N# zBKq;Br5)VNHWs4r|Z<{tZ7qHDn@=;G?*vY|UqEA6mJ zMAbjSw5b3M=qrFln2x^tjhc>duj6V&qncj8ZsjLAS)qL(t>h zaUMJ3tyZ$9$-@d18ymCQ8pc+x+1-fZ)IIX|pke;Gic z`6V?qp*#qNmulI3C)v{3rHR`=!au#u&L4@TwcZ^7--~I9~!~T&-iry7oU4+4aw+wEj@bqp{w@1EEt@L4|gJWAJuN86l47jv$_O)?xaIf!i z=hc;Cw|V9Ja-&-`ocX1Id)0C7v78~sw_*}}Tlp7O2k6>|32sm|wd`p5rXL zrJ=8=t0L$PKQH_Haborn?|8+(3YH+5FDa^K^qHoIi;$62$zRSZ?mp6mJtylQB>nDr zAf_G|n)U4JTJ4WMk-g$M{(7}0+&kW1P~sv3=hR$yJA~a-XU%_7Td$RC+}b$g<$c&B zm#7;5r&A0%z{m-RCl_F4R1DOy9t1u3p(|z}`aL{vARXQ50U@Uw>1ls|Ubs%nZ|iMz zjJ%CX9Z8D3y(1CNa1O~|jJn03GuASX@I<_MD)mb>Gy1`b<4$#!Qr%_IwTAn1!!6#o3F!`e}2d%Eze zZRj6_W1)fXJac6sD;@N4f+wp`!L@;?BhyuXGERinu~jk`Yr2w)@sgim=5Db z-r68n_pJBhjc2|wS624$N4Fe%8{l_26KSGBLp+`7D10}T6Y;Y`gUye=zDL(_oqWx2 z`(S?(W&1<*A)IfnG*1JY<7piYFFjBCkb;Oa(5SSWX6uFXLaUlYGl%ZMVKO5RkOwx4 ztkl_^(ePaEC8s#Fb6lDgGT6DD*|9M`{}8pu)t&2iY689EXnuQGn(t=4U2i-%@Bff> zNFmHEVD-l?V4GrA#;sa^L~%g(xOK>TbU5jQWVYD;0rZf6Rwi>~4#?Oo2-uU}Dx@{> z1&%sgyaob&+((xz9y1NCR%bfb)4#rXUd~L$NlBmkmYb^|H#BQ)UU{5V>W1X*CZ-_w zedeM%Hw@Sv$`T5J*|fTh4khdl`Cfpr3JR{IuMhZU_x@x^=4J{+biRYvc3I-1iR-IdpjqJz<@P z(=4;3_uu(vt_C3Asxb(%;6Spzko}9$swb7J74uV}g5CCbzeRzmg1A=8FHU%Xv-h&HErxZ_5B!S#{yvAorDY7S+aObAsZN6BY%HgF!j9=>e&*sN1KO+J7@@_kQ2pK&H0q;YKaUl zgKM|Hp|zWN+q~FltoGp$~neb7zW6^ej>h6OTblcNfY4a)>qcc>VIsJ+JK)#?Ld%t3PE1{ z#NjQ<-@oZtgl3el0X4M5v7Hee9kpNNo+~$BGQaf|_o{)s<4K@$r0TXO8@ueo8gq3& z9@A@Ys_%3*Embok7mYj@z5CYr@brj#7=gRA6vk>cgaf?`MEDT(125_ps0}_iTnk9> z;E#fRqQk%lY8rra`fbGtT%3FT12>(z5vPGG z+M`#BN0{;Vyt;4uTyi-f9%qa^o&pKXs*bKrzw!qzeKA|cXV!7gJE)j*z^4=c9n;D;<5mH9VPU7de;PcLcLg`=uCP3 zlkMAH>y*TnL1(U1vIc>_#A?M@w}F|XhK2*3>|a>Dl7LST2R!Wd$eyh zt{leG*3w{nyxF#TI#+?-gb^M;B^H9jo6;=TcwM^_q3bYgykdU6}Qa&Rcme>gD~ zQGI|LHtf%CulI9*-X~}Af6QpK;kOXItKo*n_7X4&XGnPo9!Z3FpaG@lf4Ig6c)sbP znL0(`XG28&zz;V}9nq}nPKFJmiBhcUJ>H$^$|kg+6fpSq^^Z|%bvl`vSu)u_!{B*D zo4LVwosfQ@WX@DADj{7KCY)Y>bd5&&n?PbKkfJ}P^>6_RH5cm-P^Ky(=B+gflBc8X zlTn{s3rSR;{Z>oGXY(?$tqn=P_2c-pffvGI`RnP1vMJ6w2Z}-etBg+lgPQJ}!Bue& z_SNp#{s?WhnHG79=4C`#6p}t9+XY@IG=cK>Tt%t+k6rAP&wYA@=zne1U)x6$6Tfob zD=blO25ZoGm%3Ww%tyPe^8#kdAE(5-S#tEG><6{$ZT_4mRxiby-}ycum=PAS zvJUtjg8=3G+9p(|SydHsxQMd1+LkAYRQN+2O85qiUp4D(t4mO9&YWR2my0wq#r<}U zwBd4l^J+NFUuuZ<2YtJDKR%bfZnh_z)U>JrYUQq%amlvW(+R*q^WlDX7bNN>N+DcN zh4RW!sc!#aD4%Vr_*F1E+;d7v?p^*MQ!E7*)s>1wV>1y)^kg=b@1N0YpMLC`{nD}) z5zoPPRlf2!)`;zKHkMBBdn?};Z>JLWvt4?~*n{%F=6uDMPQ&T1bOHR1vA?2B%0?YF zhVw1pW64G?a*^Wk;x>0Sm-m;4wvLwJo!`vg7xpG5eGcZIDI;(R{xRP{(mHU|G37me zzO{bSQnUmBbbi32WLIS;6v?`M#U<@Q_7Et-_M)MavCK?8#CI zwW&qFl;kYF+`nv1Tx3nqbOKY^`>y^5== ztHaZ8ZZbPG(r?LUguxRNa#NMO;W!jM+|zayH)laYr9lo_`e8Tw#Ql#CS9+hm$83m| z#`Zo-$d#d$BqxD#X3n^V-A)`CAO9`8Mt?oJoti5>Mt|o|;#Brta*e^01uB z<3hfGaKPm&L}GXEB+3ACjI+Un=H{md0hjO8}b|akZq{_TSC>N!T|BUr^;uox zabd6D3qv3c<4@@Z{0zZVd{&+-oJu01o_xCL^%b2I>+6b?r2q-%l5}*Qt2bBFc5pt3-yd) zJWKZzzu5g;h%rt&vmq1CJzb6v!lWEX9ZRtw%^T{jjUZwKOcJ~Jz4q5rM& z=hAI9nJRFF7@;ONu?zB+p4^@4oo)8Fj|Q#)FY1V1KMP_ex9NO41A6t(jf=8-4GON* zMv~GiiiVnqYz6i<7)m(eW|QzOOR!q_A`7g9ChSB|U6>BU!@KS#Gwt9fmvcLF=DwGA zU_By=!*5KZpypXbl&p5)ZYsq_b(X@nziIei$&6N1d+>JUNw3eAD`?PKFOfM4u1QZ7 zU+)f9K=fOp%f~hFoHCNKBof^7i^(SrXEP*yrwYHiiNeXp*d+Qpp_huD2cPhGNNBm0 z;yzdDE$q@TiiWFOmzum|T3>C`kU%qr1U&gc?+Oy?Y;xf@z6dJiKm>?37#~KT$Gg2T zRBNi0fzP+4og3)?3!{&Upg`rGxvMhGpspGE8>k}(jvg(B@DnFT#4*t6)2uGfV^#Zn zvs)Sbdd)xNw%A7FxCI>yP*ExEkU#K#varaTWR(lkvFxxIE5%qoDJ_7#^Cgye93CYt z+iqHVtEfIsY4J}B6KhJg?r1s6va~qZ0_WezM9~*QJZ)=@Vn+0~Tj#rn59@lKuye}L za)|#H3(E=l)J@M^>AE^ut2t%mrwI~w5kKMVj6M9t4xx`VBY4)-{~DVtaTg5&R>ZGn zbzz^sQU9sa;bTBKerIw$3e@V9!zXJ^1s|iB4i5VswBsl;__5%{Z5MB>{|0jascMB4yrWo!qG}XXQ|~`wqF~>wAS|OGOa9kOs<@43de7AkCXMBi^Yl zz&jphM8ag!X7v8%KX=>@ct5JG%PJ2<2z$6TWg?>NZ~U zo=A?YL}h>5ZyoVtrst8JBT*TF+a%i6c?SD}4gbeUq&%$)9PM36$s6}XAYy&p`KU|C(UIngdq=m2}|w2s(S zChUH(_6P8PILY1!-XYWd%w1V`2?UZhNNu24GJ(E8o!mfi=QL2a#D}+qT3liXUw{DT zey2hMIPU!=d>h=`g-B!*r0juOY|dBgdXeWKvf{M2Z|q*s9V}{aT>?Ja$WXu$IVh#k zMkwyPvvX;t(_!P-{^O&_*zT(d4jbW8VP{FN8IyO`lKSm#{_sW{NjR7E!K{V}P2nqk zXM-?IWsTpV81pwj;oF*M#wSLWS09ri6uM+phh=^(O}Ezbv6Z7Mq_~=6L@6pOq-TMo zN*J36RHsUmQ5Nt0iJvqsKMxm|ck!*i%zbIU$m1`%xS22f_rB3)m#;(o929@ENd$%J zn266^(yIHl^(l{}6*%sxTduXbCgQ#OU_-b;arRt^l_KbcC(@CKXSs)j?NKO?f*~rXzeFUJHlS$HaB9w+qYj;3oKETvwAp{Gz7B5Vk}FhB%AGioB{4_~wn4m+WA!Mfp9J8|6QHF*Da>~TJQwQX3?8dtAAN-0i9vJtv`gxDO;R>Fqd z_P02VDaE3<7dzYQkNZ%#^Ax^Zyx~a76IA;0HU9mldnP6$;{GBTpdRQ2?E#J$s82ix zmrBKo*{#Zer9PvUjr9|r2%*4MVmi9}JGn?`nX(1@K@Il-t9!m%OhfsAES-lwE%sN(Ouj`J7 zriW`(>?~HoJk+Fd7J7~wu_*RNUL=!2PVL4dbh^s6DXQ1#5a-Yl1I64leCri5@qdf#1dUwV@aN7=|3xq5yAh|0+{hf zIB{r9X}#nG6*EeEQUAc$4du~Se$VLvFK>6a+*8(=rSR;DyrRhTdCDp{@4Lz3e7NY&Nr5R%B<&P1p}o_k`^ILK-5`-PR2iZbYdUA z^os2*Id7tG0`N9SQ>;$o^1fh>U=VJJk)&nt8xo)Z_wK_A5z1`!kXVyL<*)qPA-?fH zlo}H5LCzZ|s^9c>5AN2UoDLHtJg(diqqp<$qbWqFjlDJU+jkksE6Tw-jfl1C9g6Wy z)<~H#tU_^AxZxZG!QW$Gp&3HC^{HzSMu>IbrQ@M?wQa-Zs$`7LCvg!wqJYOAI2xHB z%*(us6w+kG*+~EjcSaW`EVSb4*!e2lgG4H>$l|(E^OumPDvt_GZK{di~`L%5rf7a2A2s`>1$_jP^&Y)@`NtEI-jpWgyBTgwTbzd0Y((*F*G z#7r-_D2)(Jhb-DpRFnb7<$#*)@83DY5WEzwV{RQ`Q6JuP--HZFD->6!B{3?&7y8zx ze|>5*NFZl}WVPw;+8;8IkQLN?zi*$TOcRu|hAco!zGRIq*U+G+D-1N-At3!;;09i5 zef^J7AA>(pfjo3f*V%f7c^ZwimMCiTAF}86n6Xxw0#TTn>^qF8(v;99jo%36!U;DN{lWp5g)@0kR$+m4x zwr$(EvnSg&rzRUyz1Q=@_x%Ujw$`=ob?P|w^Zlc}jn(Xd$W0_@5mGh^ROq6Ic|E`& zWxvIRbxys>>4#gH4tO?^nyd}q4w30sL_%%zh&K!~E;k$Z;IUV(o6Kr70|}*ad9J36 zMv)?xk0-m(7hFya4*`WjE~$LhP$yy5>}l|Mjhzlb{bU$TH=mk1EL%jo+1dL@{HVS1 zvR<@YCXWMIV5?nj$l)L)$~nG6i=x9gT7|~afAvSE7mVs|QloJSoO45BQrNV=+dsXT z!EnK$xKt(oEO8H_%hqw%Mr*A#g%Xa~^byZ0Jnq-4j{1N33!X4oRAAB!E^lD;cypJ= zA`1?I)GJ%OTr5htjb@d1Pp3KABqa~|$57UdmNilK#Y=fSVZiFhuOcH8uxwV{WqPR< z_SQLVPFi50T>7x|^{wQ7Kgk(yi`k*%pn&oeG8A9PgvsLn9%z*i|rNkBY0J>kjB^A(hKlUx5lZKzh3& z6NWTQU}{XZBtctjx4Ckr;&t6)XxwCTRij0MbXWKDV#Mr#yxY%omZb1BJ#zPC+A`S% zkCLK5Uj9c4+o?t1p3GZr+#V^Do9LX^!Vb@HTfTDr- z%F!QrIy)G(@|!uo_nv?$uVO>DHW`eX2CMs#R1K`&`Aebbd^!9YhLv#^yKF#TtIv0x zpNdQ&wWP@FME|=ut{hO4gV&iB-SBH{!GB!;h8CPk3z&hr!yfGh#A)JaPEv-c_NMI7UnT=@#S-!2SV|z-#G@@2_C2W z)!Gnr?FuE33_Ks2Z%WBSDqAg$ed>qUl$W&Ly!r-$F;&Tyv{QSn(ju%|zl8%Y!Fv*H z+88GVI$>c}vU>Djvt%3r)?=EPN&Sss(q>3kwQV&j>V)$Eo}RIQ5qv@^T4KJ8yDkcX znELE;^{HBPBncmP#2s)*aa5=#P3EzF46s(x4DICI>1v?lHJCrnPK3NrU^}4dW<@Dt z9`?kWsRc~RN~qx54>1sJmbKp z^o|$w!{ad`dq&F!lT8oeUaCHwA;4lB8U?1RK1$ndyT;G{zY)DPbV}(fOwy@?Qq)9d zV&dnT9^Ao&h15UlmA)-i9jkql%M7}=+o|cpR<4zQoH}2EMPRf`|9k)1&sU}9gtfpO zAaKJ1|MJlg{c!C-On1O`WI<*N=BztT98e&yAYVk6a`?;}X{CZTGJcg8q&$AQSeX;j zLMmvI_$7msfi7&)M5?#78HE|xdN?}&G$;CW%IwMP{&1&Y00CW9HIc?pSf=a}j))Jn zT!Lr8W(u=m)^@n0)_(G{wu*_3*PbA+81L5~b*b|gCrhxpUhVu;&vP|uHghWmM7$7? z*Ymc*I0^Cwk#h(Oit-QC4X}ja_PswiDUOnEQMmC2 zocuT7xA%?OL`tfERIR&RV8!^(l%V?L$KAVd13acP5w*KL?IM>uf;GajBkgRdskD?8 zt5{r4%Y@t6GqVeofT4P-`(dmh1ZyEa4~9EzrdJ+cNRlmu|-p&z-%9z#EN>xhLS^jKE zZAzC_E3o_7S}{DykgB`Rqx5Y@N|`1&~_{0w6xhMGDovh z4w7>h0keRBl##?17Y{#u_7q;Kj9@ zEszG~U58*iB*@Qqt3IE=$R%0PZzZ-5b~`byp-cvYycjW7<`jO)L!%{Im!J$fG_5rK=UJg;s_Vnxe#h$lc#$Pbz zYdDG<9N*(|&;vmAFuN4g)G)Gs&5_!2oG&lRyax!pQe#cf$oD*P$1OPXCrWlwc?31k9dOhM8I4Y%W`rA``9!i zxeIudV)Lg+8c0cRhLrbDc-~eG3@6U*Ss0Osdl`Gav1OR_`YNO=?;Cg7r0bnq&4Zz( z$0Sn=CmdN&BGgpXy+3U>awkMCz1$|?nTpI81}`e<6@|E9Z#0#%S*Xe(ERlnewF<|% zu8K>+Ba>xHKm7@m4~a>l%)Lc6o8anc&ie5UJ+ZJ_r_t~muPxvdS|gBJH(BK0qE&a! z)999D@6=smTM~gF-K$V0NcM#QT#Oyi0u3=T0}{ z@G_HAK_Hr-5M0)RfCBvrbW8s5|WdR0y@uWPp|lBVEUS4Y&H_O zqM8j0`TqxfVq9(oRrF6mGfY;Ah)vQ@Zb*q){5V`QAu5iv{DG=$YfH}nm@(1QXL0Jb z+v4fvd9ODm>9*=TMhVqOd9rBxp73&Yn!`AzGexl{(m;rj@$riJ4u6W{RkqigX}n(? zH@a+bKiGWRo5Pq;m9sh2%m*Q=ZZDcKR+}j8085F=^5ChM7%Hlo?F>PcpdU{z;0e$c z3=k;AV6-J(Y-3v9X^k~5S17$4jhipL+9oWI1RONhfU4GMH11&(o=GX`y9(3Wbw{}N zREF@V&qKjK2x7?ujlgIBT<2| z^C2Un#YYoaR?IIm=zAgi$XuCBk1uMqD+VoORi&ngi6ax0EUW0Sne%j6Alu2?(6#&V zvXd6YW^>F(l8FN{wxjDlRYEfDW-qqf_;_lvA{m<%CGp83OnlCwFm_bXPER(HMzuuO z!i>7Zzy}fmHo*|%B>gK9t{29Yl z%TGZXSm*U-#RK4T?0CE}*sCKemJWv1Y)%z6et0kvVn3EGDm^VKR=&j%wg9Z4vl6vr zUV4GNtXO=>NOtSF&Q7<;l2g1cQ`lww_5}A>LRsiI0%3+fKQMOM6Y*v;ge5oI%4^lD z*5b&`s~*S5G2T}V9!6tuT|f7Pi-Mu;?rC}~QI~zsY2Ml_6gSpOV0)9>cF4$zu)v{| z)Krq}_;Ljmv9Efwf71ORUj+uo`%lFPRY@r(J7h)vDcI`L_GqH(O#|_I-8fZoMdF0# zsNwrS>Q2Uoik9jn4MFy*e>ifbFLm&SinU8lrLe-U3@8bVx>DAjC!M`Ok)mZ=0 zHZ@%ZZ#J8!lsk4_5DeYemCZ&yM`evaHY@K*KmPd{8QG4_9oswxODvfVlxW%DA$)J~HQ$(vusK@Mm{dL*Oa8Sj|KDxLDz$+Ct zz643TZoPCR>avSDpveBj216FG{GNTSs=f&#_UH0zw8l={B_{E&)$y^=owmH|ap;3| zvE0%$XrT}ws!Sj!%Q*{y?EQy!f4#X%)mq+l3cx%BxY%VgBu;SaeIldm zgl%1F`5+{{pVJS2_G2FGw>NOt`AlJ!$nJd3HdoK)DQ%HtOuu^lKl+8tIM+)kP>wn5 zE>^wID04*9A=SmEsxh~R@RTmq2FV!%{4M%RcHtz~wc}*$b^$ zOIU<^DNE!SkP}PxB;|R6jp&hGoV)hUupS&5IgkvFI-kV&9I>&*SS2RT+5BCQgNZou zIiB>P-hDs8NBN|ZZ%|cpI)LC~fWumn^kRjEtC7lNT)ZX~AQ~MV`t@gANsi*W+ae z#^C@}m==3KWyt*a_qRYXnq{NCYvqp+J&E)bK$9(H2(m6^bJ^tV0j3CAbvXjrLe{hg z>>;=7(KHavHsLOK)(^=t3D(rzc2G(G3% zcf686U&s@DXRBNO6p3s8lFvTR{N498xXMQ*;oy7!P8x+?3azj%5JJc+q~vBMj7&KA z?|jt*ATfl;Ydv~P%MXtlbhqbPy?l_|QOa(3tV&ChZ~=9%9;Eocpo;Nbrrs_wh4nqR)+-ugDVZwW&}v^vs^i(B@a0CX^ux#z($paxc5w68jZ* z_@lquW;(9aSb6wi2HG~!s?1X(ztRq$!2)$j+2fQZTLayI<@3bs{vvCZI!= zm5HcS8tnQL8}IOdjM5o3gR4pyN?1S=}Lk<3@NN5fwWTunAz8RNKtIOe8nRcgGBQQ5Ng~FY-xO+WS^1+}znwl>Dy-+$e z9BmSgQG@WOPVc3FoUD6Tiu*N>Ah*hRUxYc_eEMN|)BP&s9q38S;0;ZY^ycye{-M`9 zPw@`X7zb4H@zNzVKO=z*-8koMzs>-;jK#U6N3TM0iSNTWoCewl7U=s&1D>bNEhK=x zw3AySYS6JD{U?KTyTuOwrBAAnw7McGS=jc7!Zqm6Qk`DN%7Rlj+aH_( z`JW)H$gDRhP#r#t2B}=~GL544X??l&B4HDF3Zs;HS>HbGb6b>Z`sEr z%#?c7l`DYAT6+ES;5m40A|{nP7uF&99`p5stGwzB{hV(-gW;;)-7d%A=ij%F2wx_p zeyebFTEX1tmju#whixiZDf%q$gAL72OK*b$b!`%uqslT(@(#_6oC6o34FlSKLIo5`whl9&Z2f=hHozX165UNPxTwn{%9vE!5ze+H^6n?3#;B&|+wG0~ z-|{lzZK2P1w)HisSx{$n>!yKM`%1m8ndAbSwHYlbHm5HVHx6Dr`VLO(02M7e2kLkV zw}N}Q#Bb`G&M$3Mu^LGAsI^u^{O`G0Qc}5igR=s}8D91J+C{yx%#h2A@_VtIbGvQz zJECXh`Ta`O8l(KjN_muk!awTbi0$=O(iA>6Y7lAJEIj{e{{EtwWP#n=HJBB%%LvaftL>@tFif!&LA-|LpgtU0L%9}Is5grIiPj~a=#&2Su2rt2bn%!%`9z* zAW}*yu?4e;Oa4|M39u%6)yV zF~Gfiw5R370o>Xtb)g~Ev6xCd-md6!Lp2e0GMu=arV>SBAJRNPG;bt`Dxv$jU148^ z%_xLPGg?kT(T`M4wTj;Pl*d`XnXqL4XYGUa$?@a>Mz?hbTkto$NK$Ov z;F%E=)WCFXOvw4ANyh$|&rxFN`3lYXypULSCxrLs-{0xQlyl>B4Ts?_JY`ZGb2tgd z$4OkpcE+Cp*D&ue@HeM~BhG$@aYyt4J+qP$C0PzuX!qpKi!{;jgW#VwFb-Q07Taz0 zAKt)6&aF7;L-{acV(KIA8gxE>AU?lr6OH$IaoppN!43AH^AUn|AX}%CLNQ+Ns)$P8ND38nn%lK~o9v%0HSs9>^%+X{#imX=8rbJFtmMQ`A}Hh$52`-s#7$X- zvSv5BywI%3$F|*v)NjKZ=c}_FiKs+jRb9=y#7eIdZgddt7yp^m=;sC`EhfSI`^QF6 z3WfNv^J_BANN=_7Qvdh%HL{c(DXDv>sVxHc7*59H%9m)kP)39h!j}65>(AOCR0ev4 zuGAl3wXr7cj->o9G#+OMb&SSgYdRoWn8++02@-ZpUR|>5BcFUq?P_I<{+WNL% z+hwqfMmTJM?KT)@Wvlx0R9y${#eSp`*?A>SaLgC?(!G~neu8lvqm@qLBQiA z4Dt3#t!vF9A9AG)u8|uMKxW?NRjCK3kjnCd1$^Q<9?hw1Vz{YwPu!Q41r4AES}|%G zb|A)n=_QGn{~FPT z6o(kcrW8%t^tw3a0Ck;SuJik4yW}_Ff}_)=)>{6}3d6XAPw_-ztvgzS9mYtQ_rL_a zP1=o`(8U zO7mK2Y)M)rn2ERyE+i@ zOjS)ErHRe7&F5m7qk_X7KPPHzPF)O*NSPt4pl8SIlE@^9+8B4YHNDta&CNYj@*b3*d#g zwl`q=n%!{=msBskW=oclA}3*gKtqXC6VGz}_AQl6UI;=M<(oK$ctGdhbJ}Vfoz1F< zPLiKXm>3wM=%vL4u4p7eQX~{53al=(*MM84*Tv!rqNeMek9#&5x@?R08Gy)Y>|TGg z+Wr1`!&Xj9*(3U=?P^`?lrP8eP7dWKK+>1e^o?@j`S*OW(hR!|4;xyIHl;i$$SL>u zSh((c=vJJUpdhwFK%jCZ4x_tn4M!`z(0|264ebDVui^RTH?nq{btsbk^ES3_f=#R# z27gf3H4+ir-D`+Pg+brm+$yDPgD@@GuFol92ufWqj}muE3JLw5v(?Avd!YX8K(G=5 zgEmCi0Ea`E_FF5x?NLO8P^XRd=;ytl8!bl0>j$}{qkjNxbRc+Q{B1t^&1=Cg&lM3U3wEiLrORV}5bwX_}Qr`L98pv_(H zdyC0fQw7ZaxZ${Y>(dX6>=m;pQgZOWf{ZgA;9IBpCbb$%a&&a?E?8&>x)!(izkkwU z{vM7oD2fHlfiPkFS%%USaY0~y05aqDgHeyx9{T)N>N-TgkCtl1=fe%=bCS`ePIm=w z+dwxpDQMx51kC(}hjb=ngtW|T2X!>zCZg$~Q%!FVz!7A}{EAZ|D_9Lp(!s#Hm@ zUjsfUWHNftYe}Dw7Cfi$QvrSR`kpk!81B*MDv)HKJK|3f=c+7Qx1#9&Y!AJXyQZm_GWT=vLtll2}BXmbe3E#GspJ1pVQ9y z3Tq52w^j$b&MxfyU*VEAxhoDDSpE90&+P0fcdgE$f39Yj;5$M-$mUcou%7+y`{TLM z7u2C7d7EbG=nXVom_cp z4j3Y zhf37ixoI1XdLeRlqG|6VBj|iVcHhid*ALVq*%IIY8J1s>FfJ@!IPnIad_YbmQI*P1 zGzH23JsL2OacpsQ6yoq@NkgyI^}@I9IRY=;I8Km#z7)!@tBofrZ!_G^ORcR=7M z3Lf5C6zke|2JtNpdV~s`FBQMb^!7*35XtY{9S3Bci{+ubRx34o+)*(IFox;yLCZAH z!goCx8GA=Q4n3hR5107;F>jYil$v91f1v<^cN#_Y$9{|41<2NFx23c+3E>BWcs_Dr zXFHdVv)8Twj0GF_*`qNMU<{>O2lRvp{|0^k{;V64VEc{JG9j<=+52u-nJHtrCq!by z)drX{GF2Ttd)m{j7LPJ^dW>KkU$E1*U6Z%(4nZit6+LN{r9PvAFgG#K#Kk?QPo5AA z05+d~dD#YLq#0?Vy|?}0$N>1U-&=8muRskr`p?NIN0&>s3p2O|&Yd}JnvWh>lng%H zoyON1kOUGb)yO9T0O!1A_3QlTQhPD?3tv(3IGiSHD zrGyk{vdRcUQ@YoQ4?lxi*J%vNVWx(`A=e=0E*&}d^z;Xn09;Q=sn_!HvW=IzKAsr+ zuE)@}-k~=Va;-jJp1TBSZ*@k-LyHW3@kB+TtT@4OH;#`t7(Knq$%lfq18?mDuP4gA z^ECU@b@R)(7$Rz=NthcF(a`lPCVy#3$uI2jU$w=DuzvEfrapQY%ENM zS|}0bSHEs72I(U)*x-SrIQWh;e}AsfGoINXADJC{e0;BFK|3#be6$2au`chOu%Mz8 zuvBNqL{xnDz~l%topXGaD*B<6a(M>GZ_0CKr-zB+B4JyOrt{!t`Ow?T$LSr1F=vMD zv`riu@r%)Imk$Gze!|W6=eK@x;-p6H8;2)zFfu~*h>1Z!tOC$6-Q21DTN1GYcaz}M zVdCHwmXdP#)%kX(ndLD8hd#tY9iYD#ju1XejZhj4#ho92k2zz{zi%|iU~p3XFL z=ks!cUwQS=*2>C;%2}_)Hit)cvPG;gQPR){Ir36(b%}{Z7Piyfu`PmD|rz7Ps)w%8}+ zv@$j*P7Bq|;Fctyq+}M$`QE}H3zQ*){F`~7d*I(g4e3X;;m_+7iBJ8!o@&N|po!X< zHwT#rfU|AGfkxUBriGO4?~@Z;1DsN69V*(2`E{$jAj+c~??76ouEu^k>;7gF=oAf4 zPZF0>ZXoT3@3zx9jZ*=FfIwYJF7YTqG?tMI!2Dei7k`Sqc|Bc&;rE8nX7_m>thU_d zaa4^Xy4=D_kxM;!7a*=A2-xK29MMYmNiFmn{?4~l~jy%J0E-bL<&Y5=3Fts4dh;)3CGeiXA|Bq;v z03vzu>p8$POe{t|)A$-vegctJOC?Sz5w%Rl+i^0epO8;;W*`gK#bL{bDbA!Wq=nLK zX@iD_CIdfxa)(gChGvZI@Od=;_aHHIzx{_|ZqzP|vT#}`vxcT7i3eI?J=HdMJgL%P zq)0Y*3-2|8?dqiQydgwtTBuJ6_MTW(TY%t-vS+)CKqG6)12k<|zG~l1eZT-5609)T zLZr-K00!1U7b7-W8>XB2BHoIDF&Wka+bje!gPECh)10IPR2+LHxuw%0SovK+ zxw4XBdG?L><@nBpt#3ZFELF`JDYN9wpJGpWQ}o-*mQE|axy>Sya>LVZxg5*uiG;whuW<-3d>-lDydodLi6{UMrLc4I& z(<33L*XJ*wBRf@mHm?l(Mu$a9i(XmE{$ybJ{oL|jty9qeaCak%I*-$YqHwSxp$>`Y z7*cN*foD>ZP(_9Ll-(NQDQ~W`ssHly--q?^jVu)}uMRzcpbjSg^>6g;Q3-(&8$(>& z={K822#woV!rsg2f=YpXN>DX%OzG|Wb)hYw2!1EehW7yI49}pNvGb`^4Jd71gwPmb zVo&|3tD8dun^tP$aq#QCsCTH zGPKj5-5Xeo>4u_`mCrcu4{S*A;+Kru`5BD+)tuK)xYcLBCa52A^CIzu$Q!GFfd?NwZ+3UEG>sG z##15f0}6~^*pok|IUBrFgNFS`y%B0rWwHbaM_X)h`6LV2vF4g*jRRM!HJsjOJa$7# zDpf~2#w2V)s5d~r$=t1j?31oziLYaPjSn6-Y`{~&BX@GNv72C~cfC!}+y)`uSrEuG zFv!v%A(cQ?+r}kkmT=BV1(`6#K36oSyNxtZRNgd8ega2Ka)rIFG`%K79M9YB9!ycXutFLuKJY`A^XhR2D; zu>{y2^cLKi^MyhuHxNG4W}%VeAcE3DGkUbZovwQV|I{kvCYYYE&(V>o$k^mAgXjQ= z%M}41jKjK`+5jGBEOGoUdq?Hn-7nTEoz<&Qpib11l!Sf~T5tH4XYqU$2uv)V8!hTO zsBW4mW&hK-od3=3osb*Le&D>0h=-J~h|uN#5ky@Ls-t&&=ML!8W`W4IEe%pt&L}Q{ zh=`lxY=AYC*V!>=I9w&(C~LyC?xgkpGc`pwBwzrW<3Fe&c^Lmx&h1F zkY(A-{P6z6{)$~HpMfHEX|EM@cgxfS_%U{rfNU(!OPn8b;@q!kv(=5tR!%XT3?3QT zR-}|YuH(~NchRm*T`sxVT%P379VjJ;Z*WpXYIrqG9KI5>qGAg%j6uSD-?D{xJQM~w z(+#c&zD|Kb6uvA?2zd_LxVFh6B0UtKro`TwKep%mgrWl_tPl<5V+^TPC9T-E#?V+3r>+I)MbeTO@s$E z83^)n>(%SK#}8emB}4}(><>WSc2}&`^)hnXNb`ZiU@G1KS^tv@6D7oD+t(^Yk@wTm3_@k1!|kE zpnAcRpZ_YAJZC>itEc2@>hai>{u&{*cDkKc3bp9h>sLhH62CtQw+;=hiCPhyoe6bz zY-66H`Uy;hZXzD*Xze{g(}WpvhjF_!7~*iiN{|{MO$I#<^9{z}eoJ7NY(J;Y@83X# z|4oH(;-ra%WvYgO)wGT=OrT${h7MqdHJOJ1p_ry4AurFWB{1)m>ecW^-m(=9-{7>6 zhK1;v#FSEVKgTeBbo;we|96YqQygToc~61Qv4=Mrn>=lzB~&UVzK*M>1uI)>t0h%6 zG8#>pkzDKsvK~v$C~m>PU#}4$;zWw-&p*$49!ikWTExxGwUfNEjP)@_)l)_dAxF=S z$wZfSon&z5SOP$SQTr9z>JW7Ac+Ht}xgG~DaSFK9_BRtP)o`;Av%>sTcjNf6l z7Ij(;1E5T>*Ln&63i9y05Ut?(1bK}p7dIf$DN6?=7|-#%m||o9-iVGJ9?atB^|b2Z zc6Lbws>8;400kG)`WjzDUpRlYRCz%Ar^l!C*Hv9tP9nUsI2QY?>k-=Fnc(9os05{YkOzvc6n1A6v0A@Es z%i}}_0TJq$&7mUH7SQ+6i<5QGqnK-r%&uO~IGEP5hu|ik3wIb)tV~{*ZH@@JsU4t8EBgZ@m5||*-=}37e`-2Z-EJkQVIS@A#kSfyY~TBFq0?Nx3pA~ijq7fN z7_B8H*-M-3URnV&+vDxl#R>F(ysTEH>>uBKg+x1a1NjM_F5!1n_a9fmqXg{UjUKJP zmrKNgts8-`yrbV9>8?7OT&NKi=ag_9sWOdAjbDQK!rZ-wIQ zHVv(4Agk|g_M`A0EfFb26jI9b;PMo|(3}shFG_kIw#si5C&O{*MM9j2h;0W8=^!E%uybaHFlBuC41xbY_yb$K+>)yrIwk)twg8VJc;i z`noaK;*!vJwU-=@^8PlBCk#eGKy+ig0Jbk>A1BFz9o}oh!&$B|cR7!Z{Q~{0 z)h>`6R7zR@A!)N8Z``D6qv^j~O@1_>*={D>C?+vM)k?2cg&Jr7ZVS zmD~@(!sJ!gq3ydJ!Njq{S4)X1VXXj7d`x=BWN#fCO>ZM3w5IXt;eXj5-!@u7)RE;1 zp=7kQgP_sTXtP7+XTVvE zp=d5^|Mp=EJ?r*ri0aXAe8A5Pbs^|bt9f@3BT5e@eb8b6wv3NS=O3MlgY zI|r4Nfv<{1Mki^r)b41bG#La5EU)E|6i28r@Q<96Fg0~#GWqg{k!r)=hx@wLOw(M` z(8HWVay=X+hJVdl45D`HA4`0izPoH|4+r8~*QS@(TFw0YQ%H`g&Rh{0fkAPY5~&VW z4JZQUc88A$CM^t+vQ^>YE1Ky57&QrLwb{0CknC_p_KoDO1jAJ9g$$BN)e{D(SrJbUV90ky|=_9;Ibk^ z9ZE}I=mqo*3y$*0P>C_W8C6|w$|^$UBa6G3hqr4rlO(+QdGnculoqkI_qZ=4F!vzc z!2<1gERHPo0b3iJFeSyDU+If2l|7bMFHWAdpBNiv{Fp7kL5E3(BO$86iHjd2j939X zHm(Zc=XES&+2xP3atPMg^lZM{v6{>;zp zmm>@OQnFeYa<>EeDqOuD4g}X?y`wKL70T|%0N3lJ9cb#H7d*JyZoNHTM)JZbB$r$6 z3h=e*_lOypn)bt=FG>5yck|t!9)iqB<4Kl8&H!$IXY-P$Hzvy4U%EA;e1=i=_WJ2 z0{;M{jhBFay})h_Zql;3os?8W&v|AcL9_GABonEUG))nE2w>$^A~6@B!wGGjS1s&T zgoMUid0d6Y^X}+CBXTa(iHJz~>GhE$x+8uT;$Da=+QW}RR@J)}c=5HX_IW?$qvlbc-STU&|~{~D)b9~dr4 zIhY|ZZy^VxTIu93hny^v??wttP<&$X&_;M&VS;wVsLV|J>3Sbj-g!vrs$c~vL)|Sc zNlfbJRR=i!+`fU+ylh@>?E9LbY}|b~0)bJdRR}jM+~oTG8owUfhU*8$?)@{DKl!mz zC652u*mz)BTwK^n9v2I<*ZB{CCQzte9d>BnRm&HHf>D>1NSZo5ofXMTY@1Ol=FrXJ z>3_KCfLe}>7+T~gKSSV$*-Ra3h zK<2ky&Hr%$ULoN9*O45Ctg&lu-Di6^iI?Zvl4lRsS{AmLe7~;NIeh6C8 zl$3!r8>&!Fs=lF~X4|iHIVC$P0KpvTbrlp$5e#;Fp(qd`*Rk>G;>dUrh*oLn({#Wr z1SgD+H|>R@tk`J1_#cjVp6D~JC|3V0@^x_m)v3dOB+=kh>P{g!ZFl`fHzN9d8hna@ zYxNAb7Pj<2&j3#ps`Avkj09BZ(6P8*1eq&JgYwzNb+LXbL`1zPJ)ves+u`A&1-y^u zK*Z}##CJeYW9%a}1*x$7+epleoW{b1EoAfaHmnvbcY30S5VQP_^}PF8wyGatd^pJj zdHciN_J$Fd3oP=#RkWb7!yZmKT@he)s;sFgobvhNT(wSyy1ePIoX(_%$Eke4Ui%6N zL8dxW?G{7wy4P&emLL0$5379WYqbv?~__)j}}G$k$UuZ9d)@JM`m2nFPJhs(mhaCU6-F6E+9 z&-!Gl0VQTplaTfWoua^g6Yf6WX)-SVU4+%tL|S_j&p%5vQ>Eh(vXk3@azUGwbP=G8 zbr3T5_x5U9T5!NFY&4b!t!T$&00*i2o7clQo{|E>mGa+7&vQr)D^8ENaNrRf6oMmE zuI~$JOnjC4t#9tkJ-*2QL;()$3yVgGAz>oYTYk^tq=^qZJ;!`9p>BT%r|Z72>#Bvw z6A{Htzurw^dN^%>;7OrM!L%dOkhSR&6QyRjy(nH^VczFrpUP35JWKvAw>t$wcpoj{ zvQnT-ivw{Vs2Sn(Kr@7nt z-q)1Z9Gmr$RMfnEm;5;@P8a|l--%LL_`J)q5!;*1feow%g~S0WQ{CZV>EXNlFN9(e zUi|#!O7b04Om;f2_s8Z_4T-p+t-DNQoL_T4jYu(Mo6VVd`ojP$98n#gf7_C}0guX{EU!3fX;~?>8U^5S4_P^08b)G(D zayhrzJnSp5Hi!K7R3J+s2&!Tac>+f^JOq$v)L-xW(CrV5*h#UUX^Cc}R_E@AKA+J` zO-d!@7+bypli^1`8U}=1)DI{l@z}?E_oQMLBMYFB69VS{M0P`#olUYSY+4@V3I)vn zA5CAuRz=sgtq9WH-Q6M}Qqn0Mn{JShlrDiyOSg1)cXucy-Hmig_qXonJ-#2n!Jb(& zv(|McO5|UX(}jRJv!QHf5JeiXT0vUTU&ApN8hTBFo?UE8c02{I(K^RmmSg&9bfhjf z;r{aVY4ofpclYBU*m4iQuqJ-Bt)OuxM7LYhN4fwRF^8Y6i;F;NVU=cp`^b8?%I!eO z-yTuugna)}W92q`NKa0_txGAt56Q0K2PQ#M>&Uw}y;ge`Wl6Qf0$zS&*dFrzeI*p= zLyeY-C8KCCBI0JcnT5$JF)vJ7Z%@LN5cMby=B*lJk%I;^L=-lp-66N>a1HDI+L^H@aQK6(`+9Z&YJ zvc;K<52V;i#6e9V_qWOleL*6$5`nr(Qlp^!#}6A{M!FmomD`3g!Njj*=82z!N-4&ocx z@oEc28j1QuC~LE)c0HD#_sf%8hJ?hVj?tk;c99{Zz(Dxd=V&T1Yrj4+VYWRgB*)q) zu~eR_mihs~Xr2JPtFd$rw45A_$tmr!-5)3veY$Mt9YuY&BMa~1WzINFpxR4YeqG>D zRd#W8Sie77{_yC8@PNlE9y0Zv;}=peYHxdLS$|#4D8|h5(|ov$jEjD)p&;&1ubD>; zNo7Zv$w$`);!i%8cx$)4y7djbe-7q3?V~WoL1oM7NO3_3m~ZWcWxLn!BPdD%nRr9C z)X?3cj%0f*{EVq~k<>c2J4QKzf%ldf5Mkv65#M%xAY25Yz6q}xQHF%1g$%=qVEp)G zx3BW(;^jpVq+`vpbA9aG%&oZtleE?wgsNmeQwl%pT?WDY)S)TVL}=HcwS166#d7~g z$unC=n+VoxYaqw;-v#9v78cE&#{o_cez}gEbigIbk9HtodJiTOeIP~WaoZhpGgr$3 z^*aIu|3EG*3>7!7Xq^Hn=2_lqK_ig1yS4jvLdMkuR0|9%yoHoGbQ)!a_k5p_4+s8Y z9lB35?9-0A118G!FcjMnmE7yQXIMxyjiXH&!sE6n<*PJ){557qk&$JTQ0G%N4s{j( z$6M;Lm707dKTiQS9s!V4noRG34o#UGxl4#9`n%A}70k`doY&YeEL!JF`VGileXOl>n3_7DAV zu9wP;jDjGar*kO}5f6Z#AD!w*KEj4eGTIN`GJ}0h<|is)jB3vyzd$hWGJSn)gqad%eqqj#!lt)<541YbUzar6-e1FUqzEl+gh!9mY*zO6 zb^1QAMjG7)>q?myF$wC;JJ%LP$CF?8m)5&cxV!tW^SNW;(ZX>wM?YWl5|HB*>9ga!4s;pM=z$r&FgJzmQS-dQ zI=)AUoQ8ry$k?QND4Mr2!kmKV3}44Rk_Ly# z4P8p|%bDBy3Fxf&>bsM&&QbLew|jJRk5aGgtFf>! z$<=pBf!Ov2S=zZZ2|i+igH;7L%Q`?0mAVnJF^0#+g5bAZkl)7+k<(f5f5VXAH1fZc zHP?Oln?!pz%(PqZxnK5V8Zn!*Jey_Nb_89^rnaV!NZ466cAc1K$gb_Kz>Vd!ll`>w z`QsQaHg%`>as3%=T|=*03RiZ|PtG?NeFVO96-~C8ibeIse}+=~Tfi8{AmFHa=cVm> z940BK27@jXVj_(klN8LYQyA$MPOrG>97l)6^zSa3_pI=b%Rw|Kr8(CPSa~ zSD8oOvB3SK1Jp3}OF@KtA=;3SH9n*x_AL?bWJ(;!2nKw$n5EYKo zYbS4T2u7g|LhYNcOIA+{79RtN`z_tt?PJ)RVZ$GHQkjGL$%I%a%RqdE!vu*9?eFa( z)uO}Naf+_ooHR?`+43oXD(h+I%Np(#H$e_K=swqEcK+~E9PEQ_(8=RSekZ|WtW8ul zx>$cK;R$x67|7C|8PddPr9`lA_j(rk7iu z44o7yaQA$ju==CAwTyW|A@a8KFy14;EdAfL+*>JA1iY2;cb(_JoEC>o7qnLVz||HT zL)mZ2?-DXt>zEInY_P#pn=bh5U*YlOT-Mz5A-kW$sAR^Y-GU;*)l07%xW^> z%kdidg|04(G!dQj!&Ps+cH%Y)NMTMaQR!)YZ$t2pR@>x4v)G@n?U3zpZMXM9y>wF- zXx+BZ$>Ke}zk!D?vvR3YRKTN!yqjjvcOX_r-3u{E+$Z+UA9{oY;qucv3>bTc0R0j`*-JAj_MHo*mjF7jHw0@J zGby=&%Iv?d4q}PLfm*A|&~H)5=yAjO2g`DHc{|`q``9V+hUDRP>-s_)Z}yWZP5dfY@!((OIu`C6UWMtR|Z$V{yk+Mq8)iC>;i!z*bKaqRUq$sgq=y1Nso4#)W z{WMOFpLTW~UyEufS8PrxGTYJ~Tv1KzyNGez27aHd(56Lp?|Q}Wqic_!(&cnZ?5F)kl_;e$BmY6`RzD=(XlHd!XKZyawIQmuul>Zp1t5E$0 z20mph(AR}d`yQu9&3ZfOV7hy8Xl%eerI3<+c4sts_+TawPQ!W|Qlb{)HQ(gm=Hq!o zh0=RQ&i{107PSjPo6A0X$eB-Uh2cVS=>i)7S~e_dE5XQsuj&TmNcQTcd88_b7r&h0 zavLEH@`okr6PLe)v7!@b1(g8L|Dkdr3|A?{miL4;`L)|oG6e-Qz$@oXl#u#W4`HC&D*!IZSwSL}t8D`($bKa+t z**UVY*@41_9-gkE8cpVhL#qkG)~{j(FEc#t(bv3#$5YhIxjC1lBgxVI%sp6s{X#(3 zPJ}l2JYt5?GRYRPg1S|IZhqnnb!minUhJmRcKU>&m-{3&>8`MkJ@KNOu_L`g%8`m&=f$vUOJJC#K_pjmJnF>cl+3Ws#S<98Ia6 z$!DUNWw!|ZjDbsQgd5rJX{0VCx#)z|J#-`Q>U;mqleTs#BJEY+bGDdL#b~M=R%}AM zO-=8%*-8r*R?C$}`HF3OI#91oIh-6X1ri0={}v0Tz!>GpML90hW&C{lE9$*1iSa~# zKg?_ILsrcD;iN4-wPKiV6%~K?On%KT?=n0U;=3&}WrWs`8w2OYIl!oa9%;9zMp4Q_q*IUN z&&Q^K^z0=>v5JMwnHd;(_9>OSmuP5w4({qegpe4)a|9k(sZ_}x6G(WV(1 z8#{Xy_+rUWGx#nh*mZQ*mZ%QeP6P2}d!Q=w^5r+nFm8*;Sz6i}ase_1#Ux}TKFI6C ze}B(bMMW`sQ0Po%%lv{%ajuag+GN!xPxA=s(1e=d;Oqx=8VBO1%R-xg)I-~M0O1pD zx*)P#vn(!4ypA2}>JKSvo2-Y^;7`RWaQ@s7<&|m^s_*QrELB{%gT<MNuUNxTKZ3s&`y|;ttK zc6P(1{%r&|4YW9K_<0Cm3_vHYj~JofNcoY3F#=sZK8{^X%BgTZ9o5D{o;Q&(XLrYB zYRUD{!{@E0yRJac=IQem`6R9F1l8S(btR(w)$_x~0yGdYU23Vpv3;bRMK8=#Ue=$2 z+erdtgF|hgy?le7ua%qr26f%jkF+L0q`bPJw1k6dN#g66x0m5SJR9T?v0JxR6+i#-BLak zRXD_$WQ6c{1eudS^U}tA?-Iyw(M*jl>!y`+9ByFtvwM zgBf+KEKuZ;&tm->7on+k#sj0tXCo<&q$n%NNCC~zQ0#MH?CK$kiTPJX;9|6QFwB1b zQ_x@Q^=Ec}(td@s?~bVGjW_TVC%z9Z#oOM;+>b8Di<2A{11Jbt{xA#$0}&G6gP>i% z+pjbr6^Vh-`fDA@bAOa%PFi)Pd$3sRy_&Zv9UYJA(Yzl-F;iF8-8!vjrC}a|$!RJb z*1vc8@!CY6+APw1VYzl{y4Ge;iIQS!NMh~1h>XM=`l?R`WpUyWeu4`2!G24*aq_yg zZ!-@cLnH0;r!&A4oQTDO#)*naG{+~3-u)c-Ze|p5MwohdTi(cVL;7+4Mw75T(Dn}n z2g|`lc18bj5WQiL9;@6b7)A%_XhMwN1)FVsm25|N@xyqxv=Ar#0q z9h?>s_*4uC+P@Oz|EQg$GXuI4mXoevsEdr(rRCmqEFK5hx4b-eZCCK|*hItBGgn}! zMZ63Riwyzq*+xL)n#)+OZc)PC-NnaTI|HxPS__IamkBDCgCNvn+3DRllAiCc{nL=Z zD>4vdF^cukf(Zq?yhjP?&ix%%HUcpZwEwHt2Uj<@=7dBAq{yqobN985DpAFZc(T5{ zgk(YDivcf51+*S+nlIKX+R}%RQJ?EFgzdk>a1!6vze83GylIPm*1bmSw?ep^OFG$E1dQoWVuWFt`rw!q`*>MX3N zskevXHi`r@gJ!tL!+H{SkOSI-<^iR&Tco*Mm?;q0+&g z3Za_^)4#^{O(UHT*JqgF{t}mUE7Iy-xvHRaN^b3JQ@E@(aYkDId9@J}2HUvSlx4g= z-)XS?>(&iHkbafAyqa*;3mcE9mz8DqA9<@wci7fj2V+MXZ0l%^97Y4*h?|@oL%6%v z7M+H!@X#MPw%(DN27%FErv@s%>3ea4pphErSn9?rBu-TV2p+V^QqOh)W@ELIyzHcm zWkfL?PkZ<8{uQ(4CLhmNq{I8J*9`ABF988FSL@9m&8DoZ1WV$&68P}JLk(%X!4}ta zT#mgPrc49XKNZgWnFpx5?Zo9ZSGCGm*1eiZkdG& zA`40}cXNRp=psEGjH-sWHjB`wE+Tjhao?Ntrv*#a&~tdQXp1o~=&zh%pT9TDCgXaX z0(_2nZZv3@cn#Io_&Y-H-*c>iG>dEBFGWILhvk0Fe4-Jh>b)%yxp7#_UJI zv+uR<&OInYwl=F?ll#o`y>_|fz+kD{87?dS=Q-bsk5{6C5pS-%v_JJuxYm3@Z+E6N z+x}p>+7nk{+cS|CA)3#LMz?Pn(WtV&AEN*hbCY}GfF^Tn&cNgi7(YA>h5U3yF9m>i z`m93v&5dGT{4g!v+C(l!ELe+ENeRRRr^8ukB`ehEPxV$!FJP4U!^TJGUzzo(B%E*z zNLfS^n*Et8K4C4GDw};^7ADVhK7j2W!oU&4uT|Af^mzJiAI3QC zDPjXe>Ym3nP)OE%m^sG##A!?dC?g`t`sq}VdR)(qcOQGf#+^|21v8|7mS|A$={*k+ zJIKG_mZ7?~M^J-fLG7V0WO)=Clt!Hkqzf)tW^e0TB zL=b|4!wu=}un(o^Ou#-; z39uenzrd)QHFnRaX43qly+))x)^Ex&WhwgYN7f+OVShr%!Pp&A>?I7r`w=q_Sr+3c z`Dxb?^UOG>OHCGqI}=YQbWJ~BP}L+C)n0UFh@)f5W73Mttfchs|7Ro-n}z) zn5~Go02S2To0_xF;ka)Ge{xqn$HN@i{fb?e+5MbKV>6u{02r!SB0NVevj#HZRlfap zS9TW7{LB3e!8e4I!jBk~mC4DU-n9dyG#r%dd7=*diogP?=Y5rc&;U^NYP!$% zWF9!%)yD7KHbmWoQ0%HLUSpc5mwa-MZK0x-h~43Lp_nzOB#Xz4GI0xIHAsE$x2}f7 zM~HOMBZ?5-9pG>(Yt*stU}`bUjb#NMAXv+KD+s@!2LhqdOo@`=!U9Gb)V;wjs=11V z0GpFDd2Pv73=M$7yDghYkOg;lQ4pQPXo4#g~1 z+c_Ii8n+u6HSK5`psIZ^D;M|9&PJfVZ3N0M>~O1prVnk$^RM$s$ZStLQ#09*YHH0x z1I=Pjl`&Gk#JOLbedNOSr{>YH-va3;K~MMH)CN_MHYYD?Qz_B`Zzo?276*F6vHaXu(-Sp1=h6NDYXQV4 z2$=RSEp0R$Vfy=Cp({|;g%c*ig`4&vuucYGd)T%rG-CW&OBN3wB zxI$;d?+C{TH<#&-N&io97;88d5ezclcZ${JHkVPn<aDjQ!5+vnJ?1_h`#124{hcV7$h0`nkt`d_V7|&L=z=$8G6X zggkZwd=Ho1cKpg;e4qK^of~Z-!}^s7Hnprr&rcApiHT&*lQ_dmyf%#_yY`(gYt{Q?3nXG@S#t!@;Y08@%d)oXST7yT;DY<*nykpOwefiUJ}Cg)%seBEa`E zG+i(pc(?KWeD2?OXjW$6R0}?TXe-$Jf}om@QD_cfg`5wG9acn&=qhNkBa|PkP4(ts$gcZh))w0RS|J# zLHEow#O)k*epF#ACR121AA+*q_c({$!mx)|#;oeaInKHy2Lz81)m#?Qu2ilIHD=wY zJzN&wJCM-_`Ls;;-ar5Ey?l}_{%H16nH#_8i#h0J#}Kxr$oYt;%|j30lcP#cLX7!3 z$#?YUI;YP|OlIZHcnWm}C^mr1KOeLE?lZ6jO;UXw$P(!;W#+X@oO}j_1%w8*H8eg; zO%Cp2csd_!hVdAeZtQ4*KuB$XT56HC9+;rA02ETur&0FZP+mS>G#A*a^8E}?D= zw7kO8n&5{3nC2Y|$}Tb2+YQ7h_*r`utetT8S4fX_@5}m?bD;_kw+;v!%}%uB)voN& zJ=R79dS#hVHI^x4<5>3zs_&F+og^9Lf~iY(Qf%3Iu)D;ZFgQ4}-S0YIe3lP?#pMiL zpY%Vl;m7yPSG)NT5;n~;soOs#!u8Uyp{>8w=O@PJRC`!))%Fy)*L8dsX+{v8D7fF& zXcxRG2lfJ1)`SeiGMx#cajK6*NI}1r!}eGkZ2bP9qf2Fz3-i0kw|xgH6`Jv-R?X|t z`Z?J(E3{1Xu4pK%KvJ_)x}Z~e^)slRbNcHd##oD5_A*~9RZ{RWC=f)_Ik(Gp_QV{o z;+ddg%Nl0ns}-_unXlH@|9B$77!+1#!@<)VHc+95fphul=lgD|@*-E!h5v#WHt!yt zsx_#n))VPuepWesZzzK{pI z<@r@G1dH7QJUMmtsN$*@J)}1{uzT_E4uFMVnCT?HWTX$>cnR%4v>LvSG^l->nm*GR z7$_~ISq#JcPT1gZ+f)w=`^}v9I2pqF^OJ*+2NzIU>|$d1uYuUai-k(^lSUtJ=m`rl z5(t;{lC*xP9?X(X5bgL5XWQ!9dq6I%-y*`ARWLvDkqa)4Z7&v}o+PP{R(3{48|tPlFMWTF(Gwbq@bY(ObGbLz zWNf}o-+KLwnksAkmY==z$CFa|&rfFi6QC+;OFFdMlr0s#x+Yzp!jmaJG0fiU(LqZJ zrpN&uJhH_QkCRo{b7CaB#w zQ|FLP2`+r*^obu^)ezY5Pt5lI2)FIlBCnwe>9Wmf$`&u8k+Ukvwink&@^*MCSnIJ4 zxgRj(&obrHS(SHktqv>61~TVA7sr1rtABQi-YR6uFJQ`7E7z|7$fDCw)^m6w;87PQ z;JtXxWv3SZajHD^_tBJ8y7ij={+~Zc<7Q}$gSl2V^H~RFy2T~O%f)p|LlM^`1W->?y0C=0>T3qHlF+hw6`W4dt@rLb~bg2Tb`SkuQAI z?}ZI$J8m*$AJ^aDZk`wYcz&9h2*p-+`1(No%~OEs{OLx$msT!*cvls~h!yAZuH<=-i2lsV|l{mS6)F`GKwfaeyLpa;-6Zn6uJ5guboEWTQoKJ-4SICx2CY6-zr~E zS{2nle^!S#AJ-@hLQ_A9#hN)__f<{;*FH(7pk|3p&y-(pb$-)X+QO_+RCm6mzL+Od zGB6NP0v_m6r{ks4l_N7|E`05F9^fNo)uQemcK!InSGQ7o@nx1W&GHHr{ z)_>PD<8lIQKQ|c%9xKiV-#UFtXedRvwc8+Hwb~$hd=5DuIXoL$OrJddvN0+Ln~$lH z7AR`Al6$Lh`y6wt$0rvd{d}(+vFfGzRkuUexpm{Mv;B@dZlgt1n2;BQl$cAhUbji< zD`26Ve+p>je@-jvadc8o9~ahKW78{XK_xDTl+P&pCLLmRKki#%m&B${TBz{93jq~G zr46oYGPb1CCPj9>Mco^8`;|CuLJ#a8 zjt}-e^A>MWOBOMMm5~Sywc4#6FX2JPE4tNdoo>)H_}}Uo-G6hg(BrRvsPt8@*R0fF z&2$qb?RfTZ_PVx7I9qWo8TE%dI7-kgAt!ei5412VcBwUIY@91~5xPlZs?gJ^zaKVG z8+AUM-msjSKA*@(J%)eRfY+Du`IT*vtJ*Oj>Sbvs|PN#VO^rY-PPSJLiL|NCTG=Bdum@83W_qpNbvf2&$@5{7%=r4qaN(DkN-fwS66PZO+? zjG{oc@y)5G)=Fz>fYVMf7zOq`b+h*r0lo-;S*%t&(jh?vGFR^vc;sb z#WA>PrG+X7wc&Rw1_>rjH~LL~9UR;$B~hVbv*oR~XBdOs0U?&y721Vp#=m`j6pJX! zEG$&z4Ovd-A#Nsj|2%n21A^3TD{)wsQbMkyYVXK6`ibjjsiG0hcvi*{#P_p77;ne{!bZoBXcu zJ)oQwLnyS?^xAP;VC-o9CbD@Qr?~A}(LrQH=RuR{6LuIC9#A;b%3F5j4^sxH(EK33 zKYzy3t9LH`RV9gvZ6G>6XL{pZ%+}D3Io!YB;iVEi6!QLq9{?g}mbL^436pgiTv-`o zoO``u%zlyRx{_ARVc!nHQ%x2BXgvslX+S92B+>X& z1aBR^5LtGXR;~Z;+Xg$S4>6ve3-2rl!EDzi?tuURk3b)i7daXa+2T${&wuXOy{kaay`4u9>J3@%|ji{P-su<06;|iN+VGgjA5N z48e2Hz(D+<(!@jD>)UBj60|*T2<$_mN08lp$|Y#jgmB9F5ZK zA481S_%3#!h%}8Q_57OA43j_{7?z?53c(wQaPk(l%F@Xx-{DW^3+olU??Y@ivj035JxB}BI*yN0|sCV2!W`AkG1aUJmpa9MDCl5@2xHgrxR(j zazg`_E#VcgRt+WPyd6z8u=iV2qLc3jlkDTR!H~Z)*Qnq;R_p@)DN{JdG zO+86sN&LMwW4#Vzy%ggWd%oHwINsTfRs2i}M&)+nz>83+!Xo!N+r@8B|KJxfQ^z=l zO%S?*s&xP$8hz0^%aHz-7~^*{A0M>sDU?Yw zjA&%)3$O7pDLW!^&Hhb?uqguUb`WaFMlh73SxXJJPC5PKWE>R}l4zwOIYLSq3&K_& zjjpd%iQ(hI8$NE_n}zb!ZSo9HwB3^x9Y-W)O;JjPpU^eCY3ZVYsY!c1WW27agJrEl zc(PZ+tnL259yX|$N|(|523@)mF&_i}bRIJUCcE5v79^2zNeZMy5NH4B?KN_4{NhK$ z=AQoi51(Q0{wli<33&svs#5fH6~k64GUT7vnFzxfnP66)%h8{Y^isRrwkX-{p00+9 za8XiLy2+YMOjxHI9S>D#@*d&vx+yQ_s^t-zSk3_rg^}708ze=)3Uax9DhTso)N!{)q2YgSorIf;pI! zVBm0cgibgN;Lj6J>D^V=H9DU<@SjE+K2?<2Dt&zGG(1bqcfj~F;( z#CD&uf}o%H3iCxc!B?w?_%fcsQ07j+3I}#2L-2OYA5P_m%Qiwhhz38C?Cs6op0CRH z^`+FG{UbQmXU`AW1Q5N)8BLYP*(Oe`>E2+mBGq-f6{a?M)q?epT3t6A z!59^zKaCV}ayf6>I>BIwuiE|*D%@UvbqM#d)i{u5!N46ZNc>w}-Ja>+`&e2ftfzZR z18Iad$(IbI{(e!5^T&(irDffb^gEV-2^~|@A=kps*gn? zA4h*1?zyv`>8VZO%uN&E`c7pIkWzJ9-ZldIS#?#)zCK+DB_t90nD+dvvr+O=+_|RC znY^_vWB6N!Q^e@{@xnzY0r>}NrkB47gLJ7{H`Q|0Mo-2kWlSDEz2$=$qfpp@CcUHi z7TnZ~<`{f^gm11~?|wTh&{kL9g77AGMv)>~CL~{E{Ke)pCM(*OZ;U)rUTtR!4_+8T zZ1`pB8fmsGNR(vw^d~R;r(Fkjb7-74wYU51zTMW^DRv#j^>d}QEiU~7detzZXiJId`bu;|!%-A7_^dkm-{53W)_tPmtoyJl%+4MswKpBjJ3y zIzl|;VUcGF(F%PW<3E$NZNm(sXOua7I0;ZP`w|ZGoMMsJaz81TJ!C!x{Z8k%axjCy zjY^JY9sopx+(`23oK!^ho2KXOKJavc>Mb1;#M*%4XsJoi&Ol4 zhfa!>@pH+pQOC`};X_au1uJTz-j^c#i%MNY+NB&g0rX1Ey&vSBD8zs;Mfj^IGyxLa zpjn}jk|E)UTZCK`w<0YYPIo;ceZ~vCM`r)@ zYa}!3kLt~dl582J5>j@_Vm)Qi-s?Z5`}4|eF-ZmkpwbI2%CQGlptCnPKdQgl1i_%c zzgv`!`UF&eq)Ul+U9jb<8_m<3jS_h(2If$`Cb1VnCl7KA3yUT3!v?;jP-B}#HPNJ2 z*I|92WgJszbD+)$S5dkyfcJfFyX26O?(*WJ`Qgf{%P>H+JL>zW8)(0Sf`T|pLrZTW z$f8e@Y{Idx>oZUU{2jaVweYqSGJ8F}M)|BdJ43;n$zEgQ!4myYr!Nd;%?Zru3xuN% zw;W|v^AM7yW-cFof{TN|ATy(jdb_BLdK<*U*?A1W45OB&G=l@gkuz2zoOPqVAj{&C zZ7uW250p^S)N*k_GQ8hKUl4z~DNEbA)d&|fPxC8Nmrr10CYD)p3OTS;T=0l9s zpvf+??sG#LKM+k>RTdX3&NvZHk?{iFR;P46Y|0jwV~!+lYb)>5b_BV9ZNrKCj!}N1 z28@u@m>3B4N=x@v{%$YF1pg@obh@^XA)r4TbFoBS?u&4Sw+7CV_f06(!=Nzqbbpjr zLZ%wo$e1c#%e;W5Z!ltNaaXJ&I73!BX8IZk-!h&m^px}w5tCa1dh714vc>U@VYQKk zVQ5HtL`%!B0EA)KUfaCRO{PGYy_qf#AJ-b(6m~hn2um7>;EZ|>+uCJ~)Qx`m-dnnV+3_#R%k=S20AACv znB)-qAYu2U7myOed0{?kuiNf{5ro^%%1k6LR9n)l$KN!cNPDBCi{ghtj9h9p%kq#T z>`R9Ca|!iz?YH7~_uo2pGRzbB`q7`S7A&gfb93_kgrHi+`@b3*5B^6D|FSoM!2%TM zjnW;vS4iGH*oqVr^CbyvKzK&%xvL;hh(?-a<8c$@-0Iy5Y0vawa=5%%lkyUxfgNvE zrWUbfgxmfx9_(&Cr%<-VszZ@wJ|-?rO(m)%D^DSOM|;rv+$5EXEH$~N`<}s8BMuVbzh{fwS}S}Yz&Y;G~w2B#$Rdaj16FO8*lgN zM;ez<&5kcN_@E4=i+qQE>zx-uNQAK(oJD?VS%+^!ZQm?&52#m;nPx2iv z`m@&ZDE~fo;{fr!j)kU3L#*>UFWzgQuyrr0oY<&>r6}3{LWAshS+xW0Uq#2Mz6JJkw?m$jzz1H z_~!1Y)+Ng9!37cf>d+#16&Pv|VmiEOU#DlVO~dl8!1fzzO_t?-CUzrAq)qgktH3~@ zyVI9NfM#i`Der#eZQAd^;dV1hAu;qm+NCwrx(dLVSQ|}1r$4?toR5vB1eJZ|x zadls4lRo|V6YKlp?M7T{K`o_}8-%dg`J$Jka}z-<#^8Dw^su+2X@$4g7~G9XiYh0_ zB7fL=I=dQzpe&$VP5ytIZ8tZ$=oLtq< z*~?2K^oW!48%It~IXq2FxV=4cKEGb_`=13|0gVXOZ>^C%<1k0U?HPEb7V4}5In+5k z!oiuuxKc}1^aHTW>uR}uh@F1_VJs8hrwk++;ojff#cqX04Yu8#P62u4dkn(R=CNPZ z#GVDBAra*e%J}#$$mS~OUSF$ZuxR#dtW`0T-naPi-`ge0Q9hEH35ef%kMBIjEDTwb2t37#nIEXzj581W&1oC!liBn zlZ#W*(rz@m`RcRBo^W!`pZPvJ8Ge1E6UwFyy=l|$QdqHd6J;rQ*hFT?x^)ZX>%1Ww zTdHG(wu8^0OySvf+S|8gR6Q9%qdbL@E*s=$lCJ*+E#0O7C#MR#2%JdZ`TgN-`uP@|ajQ#tmo5Ld@0#&( z0apNJoMstGXU>@RJe7&rjHQhwPvN4E7G2sat~#k5hrJpUKQFD^yy15Z8f^WlL(v{M zNKK}f#OAh276nbwuCM9M)hzG1YSrD$wmL!9T<+n@HHj%vv6=8<6`Kq z{V*}JhfU&cRxAn&(Re@@OFy8t2R2JetC|C@0%nOcE={6BmF!kY<_sn{yCsdXg+6$H zgiTecs`-2wXa;5gQSkb;HUiYE>r%TRUX-W&xLh0_J@MeE-Wrn#86DsH{LHA>)caDo zttgCBtf9M8DZeNUzvp&_-PJr+&iczEeZ}bjv9cW|KK)CqK-8`Uxv3+svV-#NSX!}MshXc3 zCO*7elO*bh>tH0t-qSs0q5ahiq!#pjNnjHrZ+zKd0B0CS;&-sSNa#s?kUHrTvnwl_ z=fgRv6)8xvQn2b5+oiWAc@~P0{dE4VE7!FJPbO1~H$$HS&1MTw2wpKi=SHoMzW+ku zNh7Eia%4Up^cOhC{^-QPX<7@w<8{>AFn%?t57HESzxp=`p6BHJ&R*~R5Qr98E^Kw# zm&XeLRI>y8;p@!Ax8qTUaT$V`1t{i4$4kMdTn7OC!TBx6{zNBX3#@cWKMcvlY|1cx zJBSG0Qk0E^SM?3AjHQwEeXDGiWXjWN3_5e5s<|LfNwFVHc@q*jP_Wj<*MzU40^=t+ z^i`Jx7OJ|HfxPmj`lz~keja3Ji;0t=_Yj|-H+2GdD^Q$Svj8dZedss9ELorYs{>8?7YYl?AAL+2i(FML+{|JLQ*qM~WBr^8#8=}^LVCTp>3IsuS z#v7U6b_jnZYWcI`h>Y`mwgEwwk-7B+x{Pm_n3Gw-&EZD995(@PMPAKSvS;-1pROk} zs$x`Fuab~i&y;+KrVwg)jFNIbh4}OH4Kml@ zw|xKquLWq(#$#!eiQD#As`JArV>o|2ZbSe|`ptX0rq`mURH8Z!|MhPrIwmmnh+E-Z zrt!V;!@+`)xSUp1p;lI+Xb;84s_MRbc(@LQA?Cvh^Rw@(;y`F}K0I4hRoo!cuJ3VJ zSg5IfzN8mG&M_eKkhYGJvY6y@-yx(Z1F_jg7Uss!o14+eC(DGgt{3LeVxsq5%bW|c z-3mkil0BCS3r*q5uTo@0tZuudf-d!iHeJ6w2s2E`#GQGo2rawQKkGFqB?Y&{Pu?f$ zP(({c_`A-wx2oZCQ7WGLE2&Wh-#*7FBANYC*Azh<$wW6AN$ZcLot%0+tjw+oM#YZW z*^0{6rJ|xZ^0^48u-{F0(|^9i8=-ApQThZVxV!SS zYo$rk7r;UBYh#!V`>pzL&(-7}vGD3xVIFq|--IpLXZ=#&u8pPFB>onFe)m@_-&kQc zVDtRQgEt;2VEDZChw_LTubRgSmiEZk`^7q*;J?K~QkzWSnm?kf_J~vLy_YzT? z1TsFDGF^1X8OAwmq#i%VSGUcQfMbF?BM5N^7*)8sDc?0vTc8j}nQL2&lZ=+-21c=>kRp z-KFK``LnXv$S_f~ED2<&YY_V2sjfRM&Yvt1fAfPSeE;}4c}0JXD=4B8%A9`qDLrkd zR6m_0ikNZ=fe`~K77VS-p#kGQDu>qx=xKfulCjmQfLkMwP^^L18fC0kj(vm7{RJgr zG%a+uKLaTkT?`Tg{nBoeqTdNDX-Fg^kqndwVrm7FGTD|Y3>je+7+@`k_-j|ahs@A8t%ktWNc`KO8^#m0 z_jdx;^TCwV&+}Wa+b64;EQFIzgII?(Uv}FkDB_2;y9<@vKehA%rFHL%JKgpu5sqR6n+0%4*68g(x9izVyHLVVyrVEflr*%2cwZE9ka?0 zrOBh`+PxW!OS)NQlwpv)^>z}oj+z;#C5jg5}{`ElIW{%fV?BMp~@|NF^FL)$Gr-ZDhc$2nq2hb`|@syX}< z31E}FhCEw~@aQEyc&zqE%#{RFI#n1Aj!1lUn>Geu$ZloU_Q~n>tLPe=< z9L&XkcD|+j0o?!ylJSEZ+G2_5vu_DoL$}=Tcz~S`;gCLU!yc=+hgN{%xaQ6+v`|y~ zkDM4nw^hAMdj1yYHR|&RD!_Q1vXZ%T*7Rk@5zVKTS+TKf3oA zn9+X!06q;|?loV4kyP$ucp6EHmY(wKPaLVQJ3uX$1#laD*Y*;~>6Dc-+n%L{lh%t?{L0>n}8c{b`23A*sswDsY2PiUWhXOzpm_Oe9C84eLGyxF<=k(xFop-CY@6=}{Qoa%fA+q#;0qCM*@n}o} zy*EL`ePo2Vf!1EvTF2=&Q*^J$<(NW4qodsz`?_k3-lXM|m@gGZsa)((nmKz9|NATY zPM`f#P$-Kq`3`(IoU_{zr}A3oqY72(Km_)vL}&aS_uMOz+48t$Re-}1)mm(|jQ$i+ z0W&CuvR9jmTvEwZ<0{jy8#I#WJnwNK=If_H@+7UEn`I{(Ev2jLr7x`-<=Zb>wHRL= z$M{}t$KyzEYB1Lo0p{!f(R2>(adq$4pV)5H*o{50r;XXhwvEPaGO=wmYS1`oY}sF z9^qHTy#>3)1cGQ5!oL}zGu^8^M z91H!53a8)XB;+jdzBW7HzBal4`sX;)d&GbDnD6XbJoDSQu#pJ?rjku^JJf@hKHny{ zg^0<@Y>BObvt}_h8$Bq$2|9S?g3Vr&q8RG`vK?|{86z6T9ZD42M`Z?;^S;*)1hM1T zG)qN#UJiJ(;#E{sPzuzK1R|R`zur>DIeCm$Fv+wX<}%}`TIT$K!DCAOlMf=Rvq;p{ zHle27by6iN7@hr@c*Z3{M%hPu_k0fPARs{Wq225+z%_AllCgAmzfddm^73>rpe&Oo zM4xr+gdzS6+0Hy&f~)-J(fHK)96fUH@n3RA9dJmq_slgi9*cyA@G67-&||YJvq0Z( z$>~*ES6#On+D$3kKe>*7o2C}UB4R??Zh$oVxqcqEyA`KGdODP#7}9bkVRBHme;E5= zibQsocg_6q!AV9);YqgYqUX0Bl1Uqbh5O%o*y6Y;Fcm_Hh>dt2T-{ zP-mHiapEA(18-Dex$@ryfVw6da$Q+m3Ky8liWcyeD+0|qY?mg-YDfS|U(qJ|S?atA z6E;H7-u>38U7@M@40Qx}bb|MbpHs9j9==%L)2#{W>7pV*?E9UraC1q)nVdZ5Ltzn> ze&;nNC~s*e2aGYxAoPdA@55h2rOsyK5bXJEfp}y^`p{pPq{vP_Kqb=U=aW!vIrT*s zog6)ek`bl*pPM8XUq=4I#UI3f+Xuf@3~WObKZCRQ%ObWlBO`+$6K5P|&jKV=^X;2y|*C$L+PXr$t+)UY~wh5t3sSKZ{H9dtw(;q))SPOiXn8QOc9|p`cJU zul7!9)_mzQ!x%h}gs9uEzB5KD*wBWF{h0?7|JQy^8B}fPIL`f{`r-A6B~I8x;W8%$ z!Sbr`vpd5uGm|6(F(+(D3i93U^EnpQt|&!uCy>uG@;yh8s*=lS0y+>y2$xOVuSNI% zul{Lb|Lz&)L-u8zy>5hBMTKOjysz-;ZN)F6FT1`EC@As04s95CH<3~1CLh`9{@7<%*VH=_KvAWuDshzZZRd?slz zkvY=OPLEfk`DO_s75rvl&OjG54uD=^?vH8cIbv;0Fpg>h23+ash>Kz$G7NojrtG<3 z_=Vgh-ygQ#vCGZCrdyHtL$kVe52uDyP8T0PWD8#wggg0Klq~-<^hOCicagBYd=v*| z7gt+){BQjaLym?ziUfi~40j$05ohQe5jA!6ySZ7JNMD!)HCna@MfJZ8 zwE8gsl(yQt2lJ`p)g#BcbD;p(lEWb)2f6=4_7Od#LuGkdT zR?KK{`o~-z}ZZ0Y{_rX~hVZi_F5W!9NR$#L0*9M9XZ zK32MeqnR*36ny8@+nbW>iMVJuLq>gg9-Aa zKl{~K(FoA9t8@xtsx-76lKimk1WjkNcu>y$mN^=1um8fZcXe}-BtlPX4B2nVga}@Z#t1Ts`Hes?*!cL!U)@_Tvav*H^YilJ z#4*~))^ff_uDGsn&HPTEzBPq@U5)$r<4>IiVY>g{ZHe^XE$6_LLkoq$6Q7{>Wk8@{ znfl^p&b{VPO$U|XHbqm;WkN;Qw7MAa3wmR@hrgHwyx4oY8lhf3(@KJTXpigjnMw$p zrV^UEoE%6=Q=cx@G72H&?{VqrWcME*zQ9;T=E_(g*uonFIkw`@ozA5(k8KH9F_&~b zgPDnP##JXcod|u{X}^eFU0r6P8%GlkQRW0tBqKNhVK1;p_fnDj1M-t1go&mSL4kH_ zP1806Z163Dq{GtnW)W&5BTht}uV4il0yG6JFR$rwYMM(WqTfK9^SrlbELXQir5#5a z;krWW+J}*-$ta+0f%yF#lS}Mg4`#MnUp23Ve?|o$Xbtn)qp}7g?~ng&>7t==j-EoY zc6|Z0pk+8Bb zRqSmst?*tn@gRCNp?>lFANPtt*@L?^3375Qao-+T+0Oe-9}W@gkDF0TXjhpcx@1XK zS>OS$y}^i@5XEo4=n2a&glzD#wKV?y$S)2XI-3A-nCrb*8cUc24=(HRk2{{p(VX<| z;aW4{^!~m-P~tJ#uN9IN6`7mh<53%1oJA=C(fTfN_>AU{-omEUE znII|CnhuS+U5|6jE{%yt^N5IDH@aYDlRiXb_(}nEV%Wf~4&A~!7Z=)s+$n~=xVS?v zbaxzJi9#DdAeYI9rDT`O|R6`P-II z!R;`c#-e=R?7>L%T~Fbw>mjPcg+(LyiReZ*geuHCm6AfrnUk6bfa3+msn2nmas+z* zs8}5h!vGD|PvRbP3J|MuQv~Qe>xFOmOA#>(P1u2DOaR}gTGHd??NUKS{bFJ&BI73& z)0HNSA?M`JX>8L>y({fW9^Ixf|JnG)~3u@GECd|d4DOb#JlK*OJt5Jir^=)X?6gm6w`t- z$9{a@@d&Y+orA#!bWr)aRaRp3I*9DQ)Gc5c=te?Cl4QpfAad>}wEfeq^?`*;%=E>@ zw9XBDj%*(Zk`@AC;`>caF7#GbJQw%PB7$u;K9&q+He5ym(e3nzXWcXEz_7#B(;rD_ zu2h*Ym`I4={D-2gR9KmzdsOL)XrIpO??|gh?F~8dz@B6TJN?IuaFDG5-+0t^P*u+r)TX%o)2)y>ZdAwJ6%t+eoR7L0O+@BAo_oUB0Yx z{t(OaO_NCeQ*vZ?Qk|~Z1EuqyU+3j9+}1&d(9?)unM(ZibS#Bmyww^3}6if`?f$HDz&KKNB4#g(da{w zD0pyt*=EpXz{LSH(clUUK zK377VV8e@O9`iJ-QYcfGm0?|jg3?ag(Uq^-(_Qn?eVziMf^;D`?MoT=Pk@<2W zl}2m0g9GS%%bRzE%M1@_&@}Exv%7{SO{m8#EvIe&AQP`wosOuj#_w|5XOHEA);XZP z;J9UM7U;}UBqZIdnaZN5__xLG3RtjZo_y}alT3zeyanz05fDHEif}L;*O;Ua|4NTG zbj!`hXd^b`sjTuEcmf~9-Wjivs$0L%q?y^BR%nBT9@d)^*xpic}TrnB47{Qox0 zB{Dkwob@La#-@6e3>?G|RjFkP(c^hbN=^IY6N9f?91r%PUYv}wlh@v#LynfPXbFfT z?s14211Ha=4GBx}Ad6Kbo!pGk9})1P=1_1Q<`9?sP8dzSqaLpdVEPAlzsC@tisy;q z{h1T`iMMRmqqen56{HCFy_LH^%=8qEGeIiQpIZ!6NYznU8zSevX~h0c~$8^B73J^5-$@&6HV zwro&h=FT`YO70#624$1VV$77rv849zBm!!xe47>Ax5O6y2Wnusn2`|V<0=RwpwYIP zUjOwBe}Ch9a)yNR2k!0dOk39L9!?%1U0zzH5gMq7yyVJ9RNCit1af7Xvd|=zvkc%_n%6PB8|7mtzLgyuT5} zK#b3;mPyY0Fd=l8b3l*&IsH_SSo~?rBZ+psVmr{0&1VVph{f-mrINXhG8> z=GPMOigIQ*MZ?HQ&@$haotroVt@xNh~DOkb$NxiBzbbK7w* z32P~2nM6<2{e<9?96SO@CcK)U$TH?nDW_N05>~=J3=BvKUw6Ja{{&s7>4)7#M<&Mi zX&T~lblj*tkmq`%-n;YXS2%96&_jdZ3RnRovh9X@8jCdGs>vO*OKrf0{7%9m0)2&- zZ!jGMCA+v5comnx7T4E_Lxc@O4k>Brc6_FCag%^Fze?quOCncWI)Zh&dda0{rpwU$Bml&%nGrb~PP2>*_ ze6)bT_C{#(y+1>Hh23RAJ@Id$pARwzmN4k6nk4LaAb_#xK*9<;E^jB*k+7=_U2@nm z5Tg3GiGdLp!Oc;yF`80WM}`B0B)LY@GY}Lybf`Zi57As3xb-e^ng9)`pVN&M%=xlb z`j5k@8lfwvHE<}Jp<9Bm5E{z&&4~Dab#;R%4!0|lpG=TTIe&lX?*iP<+I)GXef3# zyYjSaoB1Z{RJ=tVa#Ak>VZOdj^B0O3Xt&V5Pra-6g^|oMBO_=S(6qWPvNq?l&o5ux zV~`@Z2?~|X%~D!xYWA7+nF)Au4DXlb(YEu&V*@K-l_F)UW;2vGX4cQ&$eua=c|<4C z$w#mDq_VcqchUU9mju`r1&U2;P30JT>qh8L!^7fRuP47&UDNOhOiT_j_@IUnjh85R zMjtT_!-4P|9N2M-7tzUC8FY-F^M6f0u@41$y*LNPkRuC|2hKzjUog&F$|~hbyzVD~ zzH0<|v2GmC83&`_bE>K%lpihX4!}#m%eoGtm%RsJ*7-f>H`SMi(lwUmCejI}^cr~{ z)4?!iVW>S28Y08IU7;beVqK^f1zTpHj46xB^4rLv2Kx6QMsxyrpQpE-@FAY0|7&&4 zu7OmM>0D|Wm}F&P7?rveBX4>6q{j3W={~R*=JS61x75y7RzVMVY%gJxMHyKbEwD9p zC&e#yY9FF@pf0;Z7lcf6&CVq-%WkFZ?p=<*RI?K3WsOi#Nq~kO_`-e*l2VQ=R>gem zhvFoHMVU~ivT|5YWpu0f!(VZi4A59-OeD541o4;dyl39NZ(&f%D`}jBV9h`2I!O5F zvQUl!c^uU%=*tCg3Q698zU0RR0EHF3JT8^AaNtu2`d4hwM(~k0$qKj)fT3Swx+GiI zi`GXZ_k$Fo`Lk8oEDjV7&sww9Iy%IvAsSi$B0*1^nml1K@?|tcgc+^4JCO>{+N2QZ zQG5E0xON_H+-AgiF}l3$CDm`n=T_!S7K?&6?bwoogboU<(PM;9N(dVM1MJlmkevm8-doi$bmqJ9RXrASDL-0N``HQ7a+B8BN|YSLtTjeel=@IU0Xtf1KRqDFYCy1}}Lo~RiTFt;=9`#nYC~jw*F3h{i9J`uS0QT7G$qhsxA66M0 zM}{`E!QM4r-Fwye_Pk}p3uZ+5TO9Dp?3O&R*QARpnatZc&lv6~46T#NsOv~&m&E^fSs5H{(!1-7+L=8SMg5)HgvW8@$K1-sIj zMwPg*f}R0;Cj-M?%Z;0`P}auNZC?NmPJD}QQ*!dAtZd7oXj zu~n8y`yRWiJ9QM?Wo11(4Fh;lKOY<%;Q?dh2;C~mYC=OE79(?_IRpeE%_T$jUoDpp z?I#s`^5I1va{bEAV2fyX4m z_sM!gAO$e)C;<94Xy|0O_ncyS*;l*?=SoZcBG)OsmSTX+-8ib23N_7GHit6!Pls_$8dqbH3x6S6@*@?vA(neDywB=;3It3 zW&xRkkuLVZi`!ZzShNU;uc7ciO-vIE=$s1i9Lc9@_hQeYqTsr9SwNmmTWxyOD9u*R zEP2V1(7=6i{2zxgk+_BvE0*%!Q5oFMcE0WDb2?3-;6d1){gIS1+OV-ArIPR99a_oyyx~S)Q_ar&jB-Xzd_41 z5rU=`@;14U#;_0iAle4dE)j$E*&lYuG3uYKSJjxYIVlmiEJ2= zt7Qj9=4#$@AkB;U*!PZO!ms_j6H5l&=(_w8NcH`jVhE$fm6^;G318TGr6|Q;g7It= zSCB0tL6lmD&o5Rydhy0ZORw8UYIAJC?-il3-V=#oA|K_)rYI1?IS z@I^%hN4ZkoT&JO!OgJ4KWxTFqO8hvvh{}2Qc>Tgc8GDFPo~T^MeeUWI__&xhJ3O*1Rpy0)fAplqT=eEn&qQd?UMqELGv$Gr*MMalF z*#D|D+Cu;u69vhy$x%S|_*Yt@8F*<~$zn^1><|i!X7moX{ zy@g>rfyQUOTAwcEb2uihpZo2CXLDwlx7dBQmFeq~gm^lyeEG80!4gmU@!u&d`p{lU znFnDpiM(ltF@hW3)W6)^J3JNvi$L+O;aQlu5`BNas5=NB=W`DW^`fFB_(HE3JcvCy zUT=-(l9v|3JEt2A!r=Q`c6X_@uI(!l)gXzl3 zKA{Jjk5MX$UPr&AWuod{7f1~Xe)|T>w<*5w)Bhu0Xbu40QRvY-CzoqEIMXLUQ)6s! z4;Geas^}l#M>qtC@7>!F+&T;z+##XP1H#p&Zan{9(SdM4G*9k$?JCg7kySP!K0<^L zlUz9zS^dCc?jaROh56DYP>%iB|xpp#q#nnSC{!BPJ5!(f&xh zUgvwK|B7}BuKVo|!hEHAlpwmg&5i<(sXU5Bf~T`^3Tof;Oxx(g(h}J1!%5!BAt0&Y znXOZ+d-xz2a&z*F%W7sq;>Y(`G8{#>2admPzv;K#V3TjS zYf@mTCbAjt9#<|tqPF>*I-3tBQiaL!4u#+>=I~>?>sLq zjcTxNlSEAdvtAsQ3LsD*e8ty0!HoFRjv?`|r&$E_loj zAS$M3-iYgIqXf5{i^fyHc>>An1uON&s}%wa`{{rVCG}-L$rJ4V4)HXEL)v}H^V4X~ z&@^OX=Jda1ZaHq=<6z*$m4ahpsN^&=%a?k2-ikLvLg!El=FH%50!Z8;wmXs;G%A`a z%~*H$j9)phZ%U#|6nBVxkLk)TL=BzD_^);gqoToQP4<_SdA`&qK3)PQ>y9lF-RU&K zZ*SjghX@D?tNX&EXg3NGXlF4oH-#= z#gZ`m<(f3|IY`<4)b-+GooCQt^lk|&ql{$ay05C2y((;t`_w2}un`CY@=+Qbx+Mmq z!=l06yD!NGM8$=tKK5bNZO`ovP}1cJTXRuC?#oM~6Qupcp62VPsO2Jl5GJ9V`#-s* zi}ta^H+o*0SfNw+g~}B9zed+5)z`)I8Ud<*{@aCzsL1#jqdU9wL&5LW8;|3!MY%tL zVV8;kohYJTog23&y6qfOYhUT7tjYT&(Hwg!^Vg_t{O$BUE#|7-9<;Ced z%HKdTAxaE`?>Xt#nP7yG3pr1gDqj0Y35{>G=R4C>R92;W_AR6UxUZ~5=qXlaeep`x?ES`wd?nGN&&aEyJyKbL3_ zuR2RtcWI!VTHOR|LkmAupA!klTdhJgYsw$&X(oVhm zBPOf6-!(MrP94MN7cH*>XWUgO%UfBFakOZNj2_u!GI#V!dC z^5h{)JxD+(QF4U{Q@Lor^AR>R7}zF-RH-u;xz6sv{02m@y=t1(m42-%T@h75n#fW5CHshEb29{N?%?2Jqe!W*6?U2Lv5g zlp!w#?4o33iNkjTgV1Fs!vKBIxLsJe)thevRu<5q&&NiwaeYxdTY+N@Qv|o$G00ze zm#6i_yCPd>F8>uk4WA$fSYMdn369#{IJ&|I7z*1m_|{`Onv(?GwgZg?1<1q zsJbAHN0DBeIteDVacWrRGN!+O7{W_0;C~N?6iIAzV+G=8AMhSyEi8xz3gOche(c-z z)}a?3z?k?1M2k`HM#$Q3i-S&M$>J|ohK#wW%pPu+W+<+%3$zWKg60_nKf;SS=7vHv zH6%~+M9E$Q*I2o5d#CEBUP63-{`~C)tYWjRfQp|n2sxzX zD??djy`_{XGIyW%`L0fYRSS@Y$MIm5DD}FP*ph?o0HLmc_=a7u_ zs}{0R%Zm#q;j$fvl<>PS;@DtJJeyZy(n|FE`z^Z_>-SAY&xU{N55j{|b#InBDtHbLMeLbF`Mg zSHEKAQnBJ2q-5ct6@K+~#jYi;&zKfPM51M5`p@#QB79c+T*RSAt5dswE~2eBPz{Wk z%K8msXBZI>BGqr~#gX8xiag}6x*Vhw{umevp-p8U+HV3Zdfh_q!Q#Jt_^4z5j>C94 zkrWqG7C%I>i^H;v1My<6AF|3l|GxX(BSd#*2skPj=T zn4D~vsMU63g(y3Ya&$5gQ66@qsE+-f%GI9lepE}D)6EhH-+udD&q@uu)OjxYK*&#? zZQnK}Vu}7r6YSwUL^chMj5N~7XJ4K>?IHIv?QTUdTfi1jPDIw83y` zU7XLkQ1xhdGK}Nq?YSp*b5sr)M_DXJra{Fu=)YDZ)5xV5%ui7O={)rIa>#QqimkV0 zrrFDm1!_0?Vg9yx%VufzlqsNaFn?#6`wKIsSD&WZYc+YDuH(&U}*>*Ad6BpObZ3^{jN0!w9YT?0HZIzZpgZpW%6qAYR z$YzI-YB=WqTt#CeR9qR+ODnY@RwKBDKjkl5ZSWJel#8t)_G`Ge|0&M@A{4E!gZhdV znvX#VSgD_O(Xutwe|X;+%ScEWnVUhF2eN8n)_Q+H78ZJjEG=+>P@Woj+sq~f#)Y4g zdmkfq;@BA!(H%QwdA#b}ET{tkG_WxTxoEV+&GUI(m7#KjS3QoA+Sd@2A}`m%hK6af zmi$1g13BOkvEC}pQ=9Gd1EKzxosa-ITO%1MRA&wpOe>^DhtNlzcOfC;z?j{J)R{^b zj>;7}b`9hkHb9S>x18+kSPP$HQ84p>>tp6zTA!#tBD$_~0o7%@(7K1xFwX=$=9Nhw+H>Em zQ=5_+tdfFjQc(%KN@Z1T{wXg}Y`{KqvcT_gV}*?4<#m+S7gn(4_r$3B z89{X_7ec5P*m?0^n-zN&Mko+|mb;Urd|`0+uc!Xz9E*!c z-LF<(2z&qXLl*`7FQhjNl8aVzv`sj|G_+T{gVE`w-Fw}*|4o?7vUxbMgGhm^A`$Wh zai$L|ACNCgp*a8H%At4@60P zc)o`NJ>7=5onCHtVTr*{|15#EBgF(wWb&5115MqeWnKZB-xD@a&cp(`+lEVJv7m8Z zQJFs(8CLg4R`KTA#N8w3(raxSppS}h+8P>*qJfGf-dGp$KiQ~_?fY#8e0Z`VsHvf- zXb0L~)usm-8Ow^sKF|N*orx1GWCwOS-MhP>P20tMLpr)3D?SIvdt@~2M{dNkl(g`B z1&G_Cc0+-mkIiB&&F0|{#on93r^6iS`68qSZ2Ax&f6l>y4L$^T)ezCU+gO=H7Q6kd zkJXUnAe40m9cHJi__zCYj(G_n;7{6U!7w!mZVV(~g;p*;#aRD@-u;J>`oiZxyV@Yz zz(;*Ew5}K3+RZ9Je9o4AkgsYg{wOAkULdER327<(0OE<~@P8*GQ)aifFvn@Mk`UT( zkfY#{8SXp9FJC&BmR?F4xH@P-O3NlC)_ciF47UBZ!EE!ENC)Y9W73h0BKT6(drnw5 zJQi|SU=0C2=tVNh(qy8K@VKlvf%eNBt1b^52S8xg1yFFe-ke1N5^CbW1X2LdSnIcM z`FIxa_BdVG`55++7ob#9!88N@5)0{i{Y!$~Q`5EkSXA^`Uigso20%y_*Rbf@{9^_p zF~p7+(7IMwnyr&=6gO{PxrKCP0-JAcewXB%n(8oOTk&78GbSY2f#-u@fXv;;+)Nvu zu`s43L*<*7>z?PDw%DWALmRPsEx!Mi7GK{uOpqBQXc?puqhdwHf$4~tba z^#;8Wv6x`lMk|=#<|JpE9X)2X)=2;xnJS$HXh)o0U+Qr{SJ%!;dfDhN|7~z`tlR)J z1`tds-bbmSSWt}l7)Vf*qTA=fNccUImy)oHVtb)opdsyG3?_f0P0B~B6}Q`c0G~1< zg*oECHZ1o`Z!CmC5kXWbuB{Vf2j5PrYuf15?zd=H2Fh>9l>M}FZ7VDE2=7y{LQK|JepE~{@d z#oIi}4DAmtjNy(b9{v-$0vhHw@3S=%n32%L7jCX%tZW%$4Bq*-FEIrPM6vj(n0+Zw zWVbJyvvV(oDJZ0-if`dh z$8J#u*aw#St+?VD+310K^@x;WZl91%rpODCC_>#x$uJm&sA0`|^Xzm?klGE#o{FM! zKipv2-#I_{O6~&9aPSxcc61B^v5zq5(f!oPE{PsgI;$qrPE2f-*5RXi7zF2xxpo|p z?}bk8TbaX5z(V<4AoWnA&CQABeiZn8;q!JW&8b>aOaw=`+AQsJihu=1a9;Z&jbsbM zsvCBGjet-<_Z~wsgXLzgotg}pY_bpO5##1w_R`N&(?iee`)`9I=f@KeZ~bt;eq;(f zkEV3lgV+?xJnl>&+ab)An;Ch?kxE3wmpWux0C`ER_^Si+^JmbBc<*w{%n{_;TMF-s z3m0O8C^cX%Oz0oCK)33!NXU)#;efup)GyoB*Taxk=}Jkyy?#&6yF2T9SIpY=URVJA z)^D38AQRjsZnl@w=fPOIcm!!>A_`sfgn$wVSo1g2Qg8sC>s^~3NU@C!w>6gt+MDJ5 zHjFzeJP_*;4tEB01(HURQPH9FfC>8!7+E+phm^&U1|=oubaQe#T{&z-KHna}1Z$$6 zTRgg~^U;T4HrPsUUhYYtK7DH9wRLJAf!|)Tg-c1HwCSMFM;aX;HwqB{^5yrS?~Rq` zg=O6?SY8GQoQNI5<5x$6cOv1R~PatBHQ-pQ`S+JQuE z)>bVMr6Z>guR91k8dII9s|JZCWJkX*e^@R=Shd^xf?c?P3R0GnBze6E;otMQ4X)?s zO#y0AOg1fX6cTVZSQ&oycm)pv$QZ2bZ}VfOi5mT{{5yLZZRT*3Zj=RtcX5WmPj|5pUO825{R z^J$p9^q~Gp$%~jc5KH#0#hcd)6>Vk)?pZ-k?~MLeak0^wO&RtYu%!4<(cDw|lNg1D z69>-zaMHA(AxtK5Sqmn5{u^nVJM+x_R+3IfCQqu&TGI~;3HYnsM*<}V-u$xT|~ z$j^5LWQmCv)y?*BDs3B9(pebifxKLpL^2BS$1hiC<379~?ab6K)xf*z@a;nb)*_<+ zyFM}t6O$I2)e7#Jp#f$v7Tx3drhR3Anwsauk~HJ7ysE0_vHucV#d^~Oe_T-1oHpM! z1AU>ra}II`1SAYE_d`zKqY2M z3aDRY717b#k`xC~!p7!zQvm}GrX>cx$(U{n_S!!?^x;{xz_|)_CvlB$+gjlvW%jzO zBqZ`9z+2eDs%x}sB+DZ}yu_JNOb&_9G&Pk#rK5vQeS8E4fFPo%$Y@oWvo*N*&L_DS zhSDe^*r?6yfl23A+P1P!zNsk^MbMZ5p_=M1K4xa1i)Oo?TN9IQWQ)V|(Uhya4NTU2 zcUw|TRf+I`hoD`63B33Q`wGLzNO`NW-Q`+Z%euEGmF4H+8iObF>Tku=7$|zS$=ZqG z7ZD|d_@56?jM^V}G{jdtl!r1$K-UJzUpgV-MP!WWSBX>0GS#7A#M9Daqfwo=%ZiFD zlby=#3ElNT!V2x}oeu4J2BdMhJ;eC<27AN9AesHcaC&qR7#FC0y+v8b04!*$BdbEA znwA;MGYMroAqBySoe6f^X}rA;X02)^+D}2w**Sg@74r6TEL(7L0(WzXqI1lZ%X$rXdaI4E<(zY6iT=2> zm`FjMLAWGEGGKfvyu@uEdg)`|CBVi0o9Bs0s& ztU_{xVwA>q{K#Y^tN!$P%m0b-)_$hY19s*d&CSHs z_}TXp?96*C6g2$z5UyPcM}|^cAm>XA4J*d>{xuGnh@6i`b#e0S>^8P;J#q2gB?y2S zi*pGt1NR~x&dHGdiCdv)rN|LYycRVBDxxW-y*=`0Wh1sU?2s|KRcz^Aeo{*0D1`IR z%A45^bc`s6Pp=$Z_NyO~cY6+<;#<93Yp;DeJhuqYpbW|L6cu7#9be+H5S~<3cTNpd zjp5J5K{XibeJFAetFfb_X%GeSUC{eyNGRXu*9h)Bt{ zv$Y6%MOZC;5A6qA>yM9mZ2ab~E+^mL6BD0shM#U9=BKb12(u<+$Ri@0bOwjybMqom z=gWaQccT{0%NusL^DERTCK`R*^BR!;&3WPPeplmW~lLmC@C1a{9hu0%hd{uEP6 z*3?E(Gom)yi4x2B0P9Ngs{L8{+mjVz)Mw-vhU}Fy+*ut1Owi~!d_F*$yv8EyePi!R z_TeWzVm>~e{0FF8YE1=MOMJ ze^p~5-iII=M^>P%-%5Th!^Jm;2ebyUubXNr;sQBB;fOwQhb_GE-YGkMQd7RFMxc>^TcNW)P!*V9Ur5pcQW(S%KoF!c8$rIRv{hh?tmTAiGY1 zWjEHJKb{cH;U$fPTCy`I9h#rTzS4zbk<@zjdj*L{RxW^) zTRbl@_|Btkro>-txL!0-_!-=b-wY&dimV6B%rt(%e5Ep7J(m_rOB-Ww#K(sm=8}*) z$j_H?@}wrQ6qL-l*6L6_0xsXrmOd^Ro`WtYyNQW=X)a{3t0Od|J+ySPGRE5$;1GqY zYg>l+v$e~PGAOR3NY)5EB@_w*)%63Z_fLc$0O_DoY1s>XQUcNFSWN7Dm>g=Rg>M{~ zBru*P2@3k+b2pqFlTOs&XG|4aUQNJFfzu#RL-@b;dboE7JFu#no{6m_l2v!u?tob%;QyjmSJqv_`bXVaf2|X{IXu}S99Ao0ILXa?PtyW zCcnxRtG=1JVmKZgT$NMoo10&0tAM&qw%HjAqW9>?vJ?@^79uV8@2;LNeF@O+5Cmy# zql5)EKEHPYn~yH4b#6_~5Ed^SYDC92vi#h5%CkQEVn+t0Pg>WV|0)l1C_ja>5Xf(c zli;iKIW1k^V=-%}#J#;91hl>OGgK`!k7we0zr4YShJ95{a)30*GB*Bz%FH!ArzzR zecMFH#hBsg$u_Y9F8j!ImX>)RI7s~8iStQSMghc}PaZ`7;h&mB?FKjA`O7}cw+b*OL#7XH0cZLiO(@XhepbKxk`Q_CqR6t}mx zf4w*gP-0|bbKsxK%8WE;vz3c;-W$e|e65L&q<+s8F%xqNWNJ5fdaWBPv)Uhi+A2kK z7vk`_2ZLvtd;3DkV8ye@z{H z@{X09y!$TH32H1Er+it8<96*~4HNY8;dP8NHgr{kwN=_I4X)<~a#N$d?%Jj^wuV7# zNUZHIF{oEd!htsWxkCppHSJc`dy=;kbs zJweaodNR~s5MgRwE4Eb6yId6ynNJ|R508f0XwD9B!ozD5mMz`ojlhRH8&i=EKe4WN zZnVWb_Xg_W25@HW@WjL-{?BgintiGbs2}*fKP-(;5h{u^QhkWcr9xGVFZCgZvn zt4weR)L&K34+5#do+06#Jn)6}Qkigmr{b^p6>$_c2rWibv2m5dGyd)W%sK;5r?OI$ z6CVOZ;;(nXw=ge%ij}ey1H*enL_|FE`d}D;Syh6G?p|UQ&FbWghJ*xUinArGU%z9> zS&hqse$0i1(%{kq*yqbvVAv#JagwK+hx&ui<;vS!UPkpxWR=V)cq zVXvQZv9{`g3`F9&)0Zss)L{QL+80<1{Mq1I1A{e+Un5av%Ym}pnLMNfCfjo&I2hJ+ z%~O~%2$(kohjGPGapJho#<}{DGk`ZP+tK|1i0Nun{Z#5_x82>?cVhna#xRb>zXz(n z9v&`qWQ|rm*gV=2IBwu^Z30-)&f?W5Z}F%AH;Z7ME#ZKZ1H)!4xrpd{BCv^#dP<)I zdLr)w{GyR7elE=>OENTMxeF#i^W|9n-{i6UdxR71qESVv^rb>N~xQnq8stto`%?zu(76Ub?yuW=fj(E|i;m!Sgw zcWIA@&ipJV8swcP7@?wIqMcq#Nys;%_Jt^B*9gzOM@>~3eVyh8En z2VV4Se3O=S6F-{+1HHPH&COqb+@p&ePoY1NxqPpINlvEXWom13~ba@7v(ydEbyu+{AtI%Vc}sT}?Y77`QV#mmoQ z!WMm7#-Qs%HFURD=5k=jEqAzrbN?-zS^3BdJZs_bhW`2%3fC`NH8?o0M9uTQS7RXm z3WvT%;f|KD@8Pp&$(%xyXRmv_JQ!T(!|#m*nTldW7Ov zBNzr>7Xx^+oI1bJqeJJPIEjw}{iNVwn#Pm}jr{SO z_Ou!fmeoD4g}6-Hre>$AXi#rd?IQ5`*)PjO~FJ% z!`$wl7!>mv@JB72CkY4}`}aqyQ8&TRU({>VV&#noF(E{l&vWyFAk8oWeD{`EzHAp znK1;A?5zh3xD%a+wOnpt4nQNdr{$T(l{j}F6qXd^8h6GI5_Ys!7K=HX*7MA z%$2~MnHjR0f9^Q$Xq_W7=!>^eCNuuj%65*1*SvojMjH$CrW*mP4@M5WMW2ivsQ>%? zH7DZG^*9j6d(fP3zCrK}|A4DKzLUkFrS_mci7~1IvqXv+vKHCZh2w5tV|3o)&JcYr z5V7Y)uUL-tR8s>*2TqeWt#9{BdwVCt3W|`tqYy`lHd-J7d%E8@G-y~w6%aF(SdH!~eeQAeUhF2WKi$pa`S!7qiVwaB%Z5=DT32an+QE}|$^jnd?ZBIH@FERBnF`tS#7bg4DT z`q9N;c1L0jXpv#p7mY(>nQ`SBfJO0u!)pE1Ng9n9fPJ}e++a3I+S^O~iADlRo{bOhhasg$D92jQ&Ok#)^r>-2UdJac7$Gcw)jneCFkT4EsMkfTH=zGnqVY>K z$jgqfsX7D_9y%1Rcw)jb@#>RtH0%O!5EMu>jh>Wx0Pqc+hf7&|fFafgTTWKtAo|h3 z;G%si&{TlMY~=uofmbkJD&wEu`$tt0oldlJ0c%3);Z*D_m`dz%q+sZJlTf)>Wjcs3 z`5?Y{$fqN^ppoCD5TvlVht`?wK6ldir4teFcq}0T#ov=(w3)Je?g43IGva$jdI=wgED{M8 z#aN}2i6A;zxn>$k9vm_(u$!8yE*@ITJ3F7XNo$lB`BzmngdGrlMt{BUw(bA|h+WAc z+s;y~%s`?b8Ij|x=l?TC`g7EvO=)=SAGXPH8 zvYG$F%Vwycv``19_V5Y;NS{F=V;NX1MzOEU%MhctC!jO`C-DwoTdJ9x1ac^=Mkbv8 z;lR%-N*dM+9#d~!jy*|BBhc`5HHdXE`ESI~clqHRr5KaO1$^gOGcEcxzr`DgYO zp3X3S-sH@n)PVJM6uS3o89|`z2Zs5M7WGBL^116Nre=Ub5gtB7L@ZJ{mto9!J1wOU zhhL~^kdt$MNzda|uYSK-H)oa4;JzCLXr>r$_rEF_dY7sn9l6+BmZ<|NP`3;E{2nXZ zrFzZD@2kxk$7daBJ}=ItL$PY3+dXeh+@(HunvA@--5Tmnrx;YJoL?K7ZA(*Uqo11X z$~DcYyMUYtm2!<^J5B~142r3#d%mw}-*rM(56xS)`}aD2g*{)0tTZM0px_szuEtrB z_mxjXoUiRCB|XH(Ycq0SY-(uiy?dNaqg7V!zMgK>%weg}&liTyxjs0RT2Ax{oi1N5 zU8j|m(DPV)QQ!10pX&`(0HC(&i^g@Djh5<>1Jb2K2^m&MYinm>6$g>5||8_G#`Rm|-G1Wz|{6>!_1LRd7=&)0laM-%-v7fHt0>|UiF(0yqd z(5+6yOMm-xqG0G-qYez^#~%n;^cmgfwG;p!twN1aP3jcfpN9vtQow{+@xx(nX-Nm- z1&NKm*%BqbZJ)3-IR&Nw7FqQeNVhsZnoR@pqbf4-U+~E4<^&Gt=NpQNg>11$N*o zvtX{{obh(e^;osVu@x;z9r!7~>?EWyGHKWjqm~-^Dph=B!%;_U9vpnV%z<4|VNkQbL9-{!?Yf3=2;`vPDcvdBCbZS^2Ep3|l z?T)YX=?=%q0s;_kr#n_h3334=tea&Bs>ZwUMccXabmNxpbh16bercpNk717I^W(bC{xd6N$>tpf7$u$=XDN1 zVHSZvs@386!4Cgthti>V9MdmRs>gp~3Quvc#e=@pbmtEJzb98OAL_x(0Y02ErGEtC zk=&EX3>f3ApNuNzKC(%CudYqMUZ_?(2E40!$hg_C(f-GprMN8Wl}*@sBN{3aSX*{< zG!jJr{7`@$RfQ~BI6^p2aBt}R83vUTOZvueJPiDLKu4x;yPKNr2zpS_V9{LL0pomm zLgHY(31kTX=N9GF;&?16`;&+KjWr`POOZA)Z2pT`Cb=!um#4(=GKTqPro41(j_WC zZyLqh%_CaolLe?A_kbSQ0I?N>j^{?joJB@7@630azZ=GWg>!&I>>a!-7gRa_#o@)P zbW)5A0)VZ|%BW)o9PC$`S*Fct&UM;oc+*mXCZphI2>*IO82WQVie$MwM^GZX22eKX zZZ&6SF5TCIK|y)&w*eOtI3+CX%b3B$KaJK}EI!(#xK81m))|W>(mt!!wn9pi75Uw7 zzK0aFduBW#6PC<%zrnoE05+NvAWXJJg^D9b^Qyge}5HC%yS)mEU z3IlT?wB}WuX%Qt(yEDXado?xxr=`q>@pZ$S|NS$kCRu$iOIoU7_2SJcPaAL#UC6;M-m*V3uQJCSAc=Bt9V3?!!ApapHE1?B3EdT+iOx_ z`e$xX!zygmOr(5jC>*8609B{cE z)C+LTrDr|Ly5IVwak(r0yJ57Y`;8|>VjH9A!Vgi|9}$f(Xbu^roL{SHl&8M8=Tegk zO!Mw^!-`!>6eJ<3Zvm36_SQXA6A)QwKTVpT{>ivz?)jYQHX$&IMVJ%Q@|(pNxH4Pt z7M~s$$W!M8#GgSKfDH}+EJrsH2x1e;+g1u%QeJvN0JMr7UukGXGU@t;^3uW$0s@Hj zR(^<*30m6H5xJbPActnt{8g5HAU1FTLdOo_1Eq(r^(pWX-fuv)x#%!&rby)fD)aoD z$PxM+1X6I=WK}aoK=6vMHM|UTWX)SX8o1T8cvnEQPz=eAfi zlMExoB1_)@AaD=|rx#k9x&+_|%26;X{3D-O34-6{_u)P}@CZ%(+>S71)(|vcHGzo* zT)FUVt^9uFRZ3hU6MKpzvw&J4Xf$gj`iABks_Q`nSyS-cW+h`7%Z6Vg1PatyaROtr zN6ol9K&XZ2n~};co9hWy=)6MA$>Oq%8p6bb`zko)4k*5*$Jrq^U67(GV0SCm95b77 z*>E98Mnke}k2N7`hC{7sT8LIpTS7CrQOr{kgI)oLe2?7R1CFS7z1YKo2k_qfE(qu~BH+|y&2L~N6bq|>(; zl@)I#3l!J`VQr|0>$=}lGT_SZ*eX$zD~NM&E#$WaDn%thJagOTo}IOqQ9mC4-$ynl zu_bDiO_2N!xRn|RR!=jfE`EPhI9+F2WMIa&$)(v<&Sg*Wc=iZ-j>5RwT(;^z0(M!^ z*KG&TbH8UzSoK=b_n9dnE@BCe0qjIX*f_a>9j+gt{eJ5fWFij6$l;_AsM^M+-v8?a zyRK4Blv%rHzDsCgQ=2T{xB9EALx=7B8Q4$>dj(MSp27iH~0gq{(~#D#k$CgsCY4zb+L$pXcX*Ru|qSRR0E3AjZkH#>>mxsCvH zf8zTw6Tdn^7{JC%Qf^r<^V4Pu@;cU3j5quB1L)G50Vsy+zT%AVq?qwI<3Vm@9DLBe zM<{$Ivfht@Tc8L(kAkNlS)jyUOHPTykgAp#7$oU-&E|pYAX$u#3#Z+^HW}iuLlHjc zGl#TkFeaw}ZN0C1lEbCH0eKO+Y-}ncG5!J>hOnGXdJ@^7Tg3Zg6aai_> zVp2!PG<+kGd%0TIy~_V7w~gOI4w`f>{BLc49;C>(N1a#o~kFf^*ZxGNAaYwW9+b@AP+dP1)~#Kxc5M zJsgHRH|tz(^d*M?<6yoBEVPLQCa!r|ogZ=36fLU6mNa?2$x~!oq>A0n^o!`$y#P|C_JaU~p z`{Bv+0cp8s-mlj1iUwc#LXlUR``=JWE_`=n<`!+krSjlUMNFZ)?oa5R;gEyMdM*1K z%uJH2vbbCP*Z4~V-Uv|b7YsWR%4F<0KHzXRdt_$n$AqdO$|d)!>@b0 zKTWSqy~gK|0}uwiB1 z6jg>F?ehiKc+~%+1voe?&LN(`U2}X{cqRlivNRMDMPDVGU8SL^z3cGueON-NB2y(h zb?l;Iu{ptFNU{`{fwJ*I$V=FBKUe||4#oufBevT(ImvH@a=kW)J`cE4QnJUq=J^hI z0)WA3QeASdH*fS;7(942(Wh_ft3QJ2Tg7h9P#Uo!dH90}*C$4p@&myx*Mxf#lxQw4<>W3*Q0RLjDA7`Po7Z#KD|q z*7Hm`T0F3JY4=@D5(2{??h*p75~aF!L_H{s+S|Ph z$z#LzZ#=VQ2;M&&<2<|UvziPgAzwbeCv={~SADmCUo;7YN1zOWukC?3>*S+kom->g zX%QeyU$C>W$Xcmd*0<5kvaqzU++&cu@omGKx9(s7)1p0p@+P$it^9xkV?Nr-!<=~T2I7i68-xnIlk`r6Od z!x01p}^nYxN$OJ&s82Ke%K&o8bBDJW=>d#%1LIy3h{$0UUUjOAftg=U za(*C0P)ZNpQvFVucbX4zA*lQWXWz5OlAKIVe7rE|frlq9zxspVqYIfp2&8Yd77(H8 z@8Z(aB%t}-#UiZE(t^SLO}Hsw=ocPq7{ueHECSByrg6o2_b1O~3}HWhN%Q3l44m-M z+PzT;jrSXk2hu1AtT@uR_vhQt(B%mwNdYP<3ToSV$TdJB=L`+^5y6GBhjXnwc&ZmU zwb{$lbB#zA5krDsyV@E+zf+DIplx2>dK-#EGyEeHYK8*NP>&i z&pVyg*qIjvu7YadW`z@CQ%b2G)qE>n4}c|at}?N4uX zr@K2Rp}UpJhQ^ez$y9fL6>?!xx(+RiKN=?ms`2Heos?i?eU z9Bl_bza2Aqm#e9P-)I!*wZ4}K-i~wO1M0}tA6mAHtOWUyaLjEtZa>)~keRd~Q-M6D zD*|Gc{rw2@_NApj7exGTt&=ui!Ss@v24a*Vx@)04g+19PKpd#W+&YP()wxlzdt!P7 zJo(1dCRzOOYD+J`<}>g^ny-R7nfevHxgEzR{Y=UMS<1%A*;6mz`cTtSFr)n~hy#cj z{}FhfYyIwi(s%hQR*VyKubqge@6B~zF7_3PEoi2rmHu{82>gOV2sZYR!;0<>meN~o zhAKuvfid%Rf{L9gMpc`~tH3zKjIIDqkdHsSOAj+YV^6B9jrtUg0e&|fBCfF)_V=_OUr z9s~jJeJ28}<|y9Yo?8QDW#Iv3+2EpT1Ldf%(*;PVUrN%ccFmwiMJn>o^2+LtKdHdg zlrpTA-~Sv=%nGJ!Y_Z?fsIZ%74_N78XgOWW*t=GmO<>F|A&Yc=C^{X~vzs6b2m~dx zMyM^;VxDxFgj$aQ6WbUP4#_=zg4Gr#_rpX53%Y&RDUbppQosLrUYr^K)!`UhcyQ+< z?G`B>-UFAgNN-ra7vw5{{Z?cbCVp9@HeI;&NyBU7~m_ zaFdzoZx$rd7>AHgfT=!?dIxV9J)c^(Fu~64RkB?ySwc5pw!Ce&-6k|R?w?ZeVYVjB z6x65j+qiL)C;hvq5@tS?2d@_J;%wkKgzWC~M;e|S4b6|r*%`A&vk)?@r%VY`dirM@ zJ?>@z6Rx>6Ju_j%D6I#^LJT>v7YNw%J($Ap-i^|v4jagJJsYGLYQVQK4lvJ8L7*rDQ_#){QrV{} zTzs3^GO(BXanH6v8|TpeF11NB@I#ALRz}Cn$z3Z5#-6Uy`uKwQmubt2n2=Eb^6YG> z>|VG2qFPVuPQQzIikTI4(R5RGA{$-X|M^e*^?}*zbRoYd@U+Q#&FHY>1A6{#E`OjG zxQ|Y!n;0n5{+>F&``+(AQzYBY^$3|;GYS(I{?czjj9n;(dy)N^9<>uNP5w6{1!{Xj zr08VfLuz(e@1Go=kI4uCs+aGQFR~qXQNRHU`9su~6WNk-$&B@dlrn~9=VI&3+S(u< z<=noz8#hgDi*l#_h{w{bG<7g7F^y*F7j=LR8e%?4%s_fSL{XC7y`Bl9X9i?B-IR+QM|6+Tzz#EOk z_GPt(2;V%7vFMaj)Tkm^oVwYLXqzh{^k-)r44iI#z4)$cIx|C(YF=K*b_QF*g=(2q zemF#>4o2V7hEX<6c!Yw?^UYCT>**;4@{I`Z1L@04tmMu~-K7zuW{~UhB3|~(Cu4?Y z7aCh_Z!dC%qjk?qWDyY)7EAN3broBQ_n_b7! z5y-&^suz!n#`rcg42P9Nce6jyC+vF%?P}bHNmx`&)igM+r~^~_F*L~!7{c>?u3R0b zk3@sp$>deq(-(k4GX)%ilv$Ml{_x@RRlTW(hDn~=`>>g@u7pN@YEOJ#UOkK#m%XB0 zT@NRJC@C`6JIvnGS!h6YX0kSTqZq;#V}!-6ncG}VeOWtkL}T8zi?}R6ng7>}6M@-d zA34v&PZ*!)0P}+9U=k;|2X}f_#f+o{BA5HugGv41{z**sC&lMG32-Vi!eNp>x<=Wz zP2l)Fvsz-O7QfN~=t^AeP7=^6afFBK{@Wq&fns9t$!iAUiDUuvQ-xYgf9tS+0I7xb zn&J>I();KK###US(%d$`uR1z9QFlF6X1>~ZSrdC>l+28uBFr9-wMI1vgB_zJ3HMud|nIQX(?n!gD~R{`qcD0FR9~fY^tkmaQS+k#i$Bmjn`%R#Ekf9L+){%>Mh;*l%d- zDbg@P*Um~6u|dxUkD3Rg2-HEo?{*o|jPn(to@LnB$sb~=dHe66B#NVSnGV3@Gtg*#26?-P_7GYgY=>U<*bSe=y#P#h}pKE<% z%5RKLA9<);PK%zND(!Ie?VRW+c=&HFdjoaqb$JhDf*z?(nm>{uA$N7T?PzBV4Az_E zvDUs87qcIb1tcDfy`_)H!RMAKaYO)Nle#&iFS| z8ItKza*zurlwSbtNwN}yUzLg|!}>KWYM9F<`E_At(tkUqtMfwgcS-S}zkbiWf_2Vq z5svExaa=Zp_}F&$afAr8)!0qala{qQYKY%h^q^7J)=9GF+S=+NTKzm0YlC1-%?5Ra z%wU_wCcbXpFze$!+yjaNin&^pe3?c|Fe-58C-F=PL+y`bb4T_B++g6F#o+dAkPxFU zC_s-5&tTL?MnV;T!88YiyS0grK?dNFqsdJiu*1OD0Xpf)_0c_0Ic^#rTPbQ z#)vV!mWVyIGGuOxvM}h_1`Rs+S^yMwXVMR?zS2cSBWaf}Dnnn}EhThlw$NQ!H zP-e@5)fQ@y%7D7QuGM}IemOO zQ9n5tC!h+OsYrP`9VVl>q7^1y_%N0ZPOsAL)vIspzxDjv*i~*)o?iBWN6WU#nz|)%(k7saC9%M9duV- z{ZARq@J@<&yfUOHe{QCVnBoNB^Tql2GH;#$av8t#C@hSGl-WeWcELA#6KL54#MvBS z0!3;LHST>7RDngdEGdvnpkoP8b^m1YI*`L_*GjvjHF7l#Xq1;^DJde?`vwN`8=Rh+ z;KUNal|9UVg6symBK#e(_g?ph^BjSPu>gdKlqH`nPLlqJU;*tK#z(vys+q=e;L>Lt z9{f=6hq@jc8wTOziY3t}fTJQB&Ea_h8@%>YfSgf8@oL3x=(3*OuoeCO_z+&W+f0^y z)?u~8l>|w_e*kN?M1D#8dr9!6jI8X=V`Jd%<3S<6lTt+%7ln1ell+%U{|gXyxc7Al z$uXYsmZ*yh`tQHn6zP^eg4hWkVoEgDN0MZa_K&rM>11Vlys_vAYbyTQ^S27Lv6Dlb zvkSB>{ZDJVzG!-J&qtb=jo1jBd9gM()?@N5PKDe>SsYN=dX}{Km7!4h%g6Ie#6Ft(0SQI~3ME`*#~njf#7SuDGXWu@4g9gqs^O<^)gTlN7LcIx&v=pzuP z5gRy5Ye2`2jvND{5sA9wd25RSS^7~5s!j_@vfA@AdwGUYU#3hfgewqIIz`8cxdJ!~ zr_XY82Z#H1&XzSQ7`3+OI3oRle{o%HOx73g%Ze3^mCNH~`R0?a?7}&;Sb-I$E*G`7 z*kI;`=6(X{aeW((ZW>eRpdTDB`nGh{Zz5MC9sNS-`M9aBolZ}<-q9bj<9obDFbz2U z;eX|cG@Q*bFu-gS!)>&vKXg5`Y1PJVL6$-Y0sJ!1)*0#;CyUY$K2glUAi?33s2#G| zo@4?swrXW+JG<9KKB~Kas`)<+%9~cmc7WmP_r~B^*T(}=k?DS26(JA!__c;&e#ra3 zNz5A(p+N{tFjb*aqEwUv6>X+4wBPgdn}UP`i2KGSP?BV`vK}-2{sw{2fe;0=pJN%t z(Ft{IO}$Gxu^Igwn*sWJc286?TbW8iqFjlBBD6Nm@L#M$f;2Fy0{X=*%srkyF zT1IW?@qtG)i_xgY>>5z~H&Z!UfZ%95uUS@J&hPce#61G;D&z`T<)ATN zoc;xK7_^7^;mgVjmrF&0MaI9<`EwN&o6wBsB5m*Pg?sjDPw!78A1-$A73HKtjt^ky z12AQ?)DU+dmg=TBPjp=eL5JaC#OE%oZg?ICH*!NoZQvIz{ulJuDrhMQTq!U)n4EQd zp(NU(dxMB?pqCJxJpQ1=vs6*4&7~(R3lM+pczD1X^w4nVU^yP94@B=Gz?M7kk5h zOCKgpNv8Ap^X%pxp3s|f(@Ao7_Mtz|WzXpx=-B=5&LdTMv%n^n7TcZ9-}N<9=~13+ zJI>CWz^f%#sWeELaeViQ>_6jOK3bzpin)xa z_O;&FgkMIA2c)ehX|ejqXJ_YGSc&g1hcge|kGG6G&T&sY$MMB6Eyh9+as^>})#^y^ z8e8DZEZ%$fC(v0wNb$W7qD4kxGi@WKkD{pwFmMwIUC zhFO~y*)@>iT(U}A$;An`tsytG492sCIXrf=8$rEAQ?et{)LKqIC9KlEU?Uqz553bn8T~#P^Wpgr1OphL9Z|E|57|mDurBx>!5Y zv+EsRT{ZeXjPt{8%SFX_!iX(1=PW#so3z|pFYJN zh2t?-Lp29>`-xeM(l>*HSBBn@fI1c)?Emc~noV)6x3|oZ>JJV}5Qo3aA>E4DR$n%Jr}6#$ws!Y!ulIvZBEsZ6nnbUx|LR!BH#AJ& z7#f14EG+kBnRBxRak44N8vO*gl^qAO63Gdlt@5L_-+SST-0O6yykX0ggVg|$aN)?s zm#;*`1EH|N&aYQ7qb-Pvv|)kiOmJ)6CQ|0tcR+s!h(+-24<@H4`}=$Ut~9Atdb?6b z0)**apvjuN-c6}*&+~!|u{%^{?|pmS=5}1hJg6`rI3HLy^h4M;8MMExHb9UOutv`` z{gqr#=yM;DDBywo%uf8n4lm5ktM$PM7Ug@Tz%V=X{$G2NfL|ktZ^%$^eLe=AggdMn zGPYE}e0^bOx=@w(d!tFXfWUTVz-x03AI*o+bT3~iFxO6(pKh&gS#0Y1^lYu+qe(A8 z>Bk*?9=re>8@aCCFLhc~l+^d1E03Q({reEGgYJK=tYi%Tb<+zstw=(=CA4)hx7tE; zT%yNA^@E6vjiP*e`wyR-a{5c;H~N|VnnpF^?~@s*bonanrEU$n7vNU2 zP%B5p_Zs{%{ey($!-#Xy#&?TWx@+4C8yoc9iLWs^vXuf*=EcRf7hLz7 zZFS9nXo_xQb>K&2eF1@9NG>`hER(e+hFaf0(AZGEzQlDl`2B%zRD%!v{clSg2%cxN z!}t;a5I~1!BAXz5r^`QCk$~_E7;212HQJzthaJ6(#`U9s5K%~ql+##Rf97rBN- z-Ox<84Eq`zrOmm~k@7-&GX^7o(%HJZy8{#ZDA~=@+Pk`h42|lo{YpV6_wa}kH#xmt z;xOAyQfI&am;s9ou$pKYWeaw-phTwPfk5y6fzvgDzLP~`P@I>KWWTZ^bn)G7c#!Q1 zHvaWs3|O?cH%LVx6=K%J^7-{13;|>UX#UOoPx&^ zIo|u2f!_`I%ju&fH5#!uerOqU>P+Ru+IrHVgyDyLZ&<|~7RZI;<#P@z)HC19TqR-Vjo!Jro zZA?beVIKmNZ_-(!rcJxG_D1W)Cu)$DLc_;Pl}LS&H@gAdc;vrkApe{WXIgYXP0FBB zfClw5z>xcGr8$m%Iug{Z{;DW!I9-bMZ zNRyL)ZnP|~gKOx4HH(^E$@ytd?#ljTc%N!bHve}lOlVsBO`|Kzcv75`!q3LVW-kjY z7?vOqy7kMcr8&9zazE6$k02JM)_=4BFApzf*XO|}0Sy+aHH3NPJez%aB3_QPSa|^B zSXGXc^50ik92j3{;kT`mOUSwWIwB# z=Vq@SA_7P{9nQF7yT5muALO_rBb;K=U(f&t)9YEhc%~~3 z1h(S;-ThUM*zWmB-oXCzizYD+aSM9D20AX3HkTG;$h`sUrcNtyWVsy*<$mT#9!7D0?o%8R5S2X7J zji&8}aI^c4%+6(7+rwllySYxL`Q_Ky3XO|fe!)KhPxpL`AKuCT{eDBi{Gw(N?!#Od z_z4@)UXR~zpdEh?SV!0q;)6cT%w+_31+3%ejiAdq)(%X%0*3Phcm%&wstT z{d9*O?^eC));o}xn;eMp01sOb^vAS55o%h!d^Bd{)4vezS&Ee0S?U@ze%y8A(d};X zTRAqf)StF@<<*2~mBX~YVRvc7C!cH@7p0{3H2@6mT-S3nk#Ua~uYg0l?C$QFcJS!0 zVD}LR-IGPx-LE_#=Uc{9a#q3R3M}H2cks8We=*f$d;qp)q4*(9sj{uD;7=_Y$Gq$--4<@Q-3`rD$ zRlgVcc9@L9DbGvtdj%S?>Z7)jG;|n}kp8EdK4Z&WBwX>6vrXgmT4OSFv}bfL?*@v+YtEJ&?;%T~PuXk%EkS3lZkm<;zRm8}mM3Hc84J_zYiqH66nvj3hgX`R{8E!B zN~KnQ;K;hlL{K9~M0}Y7gj7?%dO?y=ubPUVYNO@}h-2>y%29|k8S$3vmVdVgQVS7@ zB5%~mWBJK0&~sq0(|C&7FQF^+ilHCd{;RJ=36bc?-+5dUIHH^WQA6YLG{)8wotslI zaV=YC1MZ5Cce*>G(yabKYLh+i0?as+*y)D9yI3p6rse~cN<|p7dkZjxVmO$TVAre& z;V|rGB|Q1*4L&PXkY^6KJ?>dN-x%z4MjFfJG2zG&K~e%_Trg!T%}6wiKRZDh=)t|= zkvsT5U_H)<@ZnIQ|L&gH3Bx7rN+1&yIr7*-e+=5ra6bw2hJ)_eUIhv_%zgtn)TltS zT{-x%^^S(q;so*%C@2<^a$Q|7x@J47`XKo9(Q4g?z-voyZKdq32Zz-QW>~bL4nl7D z^YiljtEwrZ)8B*b+6I~5_{x56pfXZJPZ=|?n_5{3!*zCtV4WKnfK4u&(a3PCOt-|% z4g^ZK%>L}lzCIISXVrASgm`Z4ggz4qYPvArq-I6Gj;3LKuzdCydrgJRd3t;PbAyV| z``nO@c13qohzLuGNLMr~jV&e3rn4-X7Nv|ngF*R}78T;Q>JokEv~eEUXD~&JPb!LI z%>fN7dE)LGS_%OEoPS$c_8IVI^`PIzzMmOZRIilAG_b~rUL8K4Hz?0aLlFz(>**>3 zPzdqH6 zo5p`-qDi0i+zj?^Z{70Nszr7Xq>>_Mk2v>w8OzuqS*(ES9msvkoXMVjO+|BE`GIo2 zG=_v5t&Sdo!??8^@KDGBAM&hmb4Y=%Zb@5B0|%$0vDP2Tz=9$Hp{)GSg~y`KNGH4R zrjAL@Oh@-~^^;N3PhyeM^8S!N-g6Ziy_0u;?SC3a{Cs&evB{>}ct!BB4hfF>8+}NO zp+!kaNBI;QRr&RFHX>^6>W%E9bd}qxI@wJ&Z|}v$ugZkp!4IRlZbznW*i0}(qs>>c z3B0^+(b1sLoiMh}<)1bw7P|m%UK1ymALIF8U*WWLxv{}m9kU6TPXf^NbmRS}fhL=! z$l~CQ03yj^2`KB%47QJkB?7KJBOlYDYjaXU*FwJF^dg_k^>%J{#rXsKjA^P6*VN1V z8hwx%aF9_9DE_ec$nV(ldAL14Af!yli#<>4==b;c{fTL>;aD|3y=F-5?f{V=4y&}P z(@_{;;qe#GzYsgb9Fhg)t_K$zw93+PG(tlB3!R-Hv@8t|-ixbgRcU(xA+uP&R{__H z*beu8Z4#lmNi9XtBi_53I=o$}UU)U3cDCMI5GHl(9%yxt%+>M~b@)awwJoRS1R^7_s9 zp7&0Oue{Tj27B?v>MXJiPDHVH`YVuzz=B3wGighjDm$`6|?YN!50nYrTs_@u#7X*?nyevB`k@3E>zH9=3OCGUfU&Ko`B7VK!wP zpgTFSxF`QTK!p3x*?QXOgqBd(D=rqG#@E4JZ83XJQ85j4v~|58r{%|Zfh8aSmjF{G zK@=ju4vRvlAA>s$-4r>kH|Dw!xW04(z$pUpS?{$y2Mox53n^ObfI9T7t*)=?0(Mr%eFeq z%bTF^`-LKpKofR)yyBPD#NO!U zQBWM<`+FAeOUjR~ASt1l2xB>cW)_afgim}}m-1^=(866d#ReT?o~}r{eLh&B!j3kj z0u#f5BTG>>P5q#nSm;ZX3byFMsg?R7b)s+2SX(pGn;RG+P^T!dXCCaG!F z{V4_S`q4B+*%RmDN!*+-z?G%gub02*c8wcp+um=mND$G=%cR``wk3;X;=cVJCYwD= zp{tOYuQYFQqBuoEqT(bdZ&t|{)ik@a7rdMl+U0j57wNLbATex9RzN0}OA~#HiXYGY zi0XN!$|EGiNkjW~^jV39diuxbE{eI(zn#{?bG}*Ro+cu^qPquALwwr9%ecs=__fP2CIs4gX@3lUQ?s!L74U4&~ zqse+>oJozutAR>;)m?<0}#g9{r{B4K7nCpN1o4S}s%c z=3*TkHPQ0Z2M$21!~Lue`s4SRsi2rE11q0(pik$z!qUD~fezVohvbQXD=K|=ypTDT zOj|7qdA@U{=q8({^zyfo_IiSO3}7X@aMDFFArZ-aySyBBY_XM%d-$jPQrlhRwCyMB zMz1md5Jz~rH(QvZ++1b2tnTQzgnL;k+jwzxz#5uJ^z^DsT1Y`=r6^7vSw1N+{XmQQ z(7nxRi!~rt_Vx{uogI`lL(V~ph{u56@5|4ELqQ>J`m~iNlHco?aMkUBjs&Gfo_NDQau;AnxnKQFLIbidg*du3v_bXKu(C9MoMA#IaqeapNbGf+FcG(&*RqT;A%Y zV)eUG;9?1JCX|*--HIBK$fnA?(Z8oLiI9uotM&a`ZZ^Qq_2bBN^&@*pl zE~^{0`w{jbOi$PGj>NFOUJ_9_O~B2Gg(ML~obaQnQ8)@Nv#kF@>J#~BU42y%KgfCV zw*6*ql);9sqTxIrd+%qlmlB^uR593cu_sSIh0$U=#Ke;~Mn zI$B`gB92bI=V!ms+b$8^YeGOs z>Tx^l-Da*Bqqxu;q3@%dwCUuu(@4ZA6S7_^>!2?AeViwqNrFJ=jql&`$kjAqXS8y0 zl|S@`4ZwgHoAdbcz2U=9!6|ur6~)PdX5RpW(a{54t?gJj=)ErQJYbMIIwc3t?$OQ; zAUWmCdFi>aSAEk+qPkzzW+qZ5T5V1;fa2*eCoVo+IHG`L;)JRcHT$ zF`d}+TbZf1$^5}9;Ei?jOey;lxovW42!~!HYBs`0_tmK|O{*t%ie+)o#L>zNx9A-h4peLb`&4R5yH|DDn1qnBLjC)Yia}I=^7w zBkjFrx5>ah4hS%U*^BvH>KJ@$e!*iK*g6RPJI+Jb$3gv!BlNyHE+`JC!y$V7-|LAm zpH+;?Q8*xl)M86T0NdJKnkUyjs-EFtk`cjp#?mgV(!ExWg{<3D0(TBmC>NujiDiA z568jqyB^ZoS89PofKmfBL>!W=_d+oTJt#=nDh~5Fo@`^II-vngK+1dC<3g){eGoqC z_ge9Q9LN|7Q+a3Xf08b`xC@ISr>tzEiG!gt|F+Nz> zq!$|^;l#wk#b{=_scEE{nNGua6`tjdwpMoyjZW}8KZMN80A$(Jpj0-i6jPG$yy?8u zoP1IK{h-nR_Oh7XeZYEu(jVBV4o%2%&^ed&Sfb;UhKHjPslZJ}z#q6?+6)5x&aemN zwm;(ZmRa|Ney^6OaL`BrZOc`(sN_I2iw_WQls00Dc02is!_;;?M!hnPs&clx4~TCZ z{H3Kw`|4Vt2a7R^LS)jRlKnnC<&IV~153GV0^CL>GbWU(w8+~~`P`(g0#Yzo=%#tx zocbHIni1ae_`)|(n7|cE7K0$^+-6A#YB7pR+FcSS|KG33)_Ni=q*+vUI10|%krR94SI8OvXQooW&UQL~^+euRjRPdHd{5D^FV+V(T zQZDm27-s9iYN={1lTecX`3b5ZgE{4rljrYKvZG_PlVK5t`41HI?<_WWDm+UtaDFAD zi$ZuhS!IRP#t}1%?w)J)VvC5V1npcK!lb@F40-L$jveQZ+u_*8F59MDUWgDF2Vp?=u929sy7h+Jm&r48Ywd+}l+5Ar5k~eFPAmT}6CZL7Z zdJ^KdaBKa)qA4Rr95{5y#0;9vWhjKY!C&xE{3>t=tJ6qX1lC_!P`~I<8-H$nt#R^T z$fl>^y*oN)q#TY%j`<(J;0RZ$qX@fS(P5$mxy7{D8|!v?p|G^r83N0R2)6O5R9;br zci?r0E~kLS@4w6>t+)Tt-yd*ejW@hn3cnN{(kr@0Q!-afO2HEqS{)6j|IV)O2OSFw z1H5YVrmzW)c^(DH!I92ql~`!Pf_QEKUDgc(A%R2nQg!KwbEymumjEG{F|e(iJLiax z4sM>qxsraHTU@uK)1OWn>L(C?jXg-BW&@nN7;8f zA&WDW*KN`Rx#tT>DhbAq(|T!Ovm-!_kPws=$gwPKs>UFh|Jn4T+toO4MMI}3iD>A* znn$*&C^n~9E)mVpMBsan=ve|~j_7`FasD=$C|oQF&j92n!KxO8h{u%t3P$Z{la4sg z<#RYsWu(6l0mcX8CMw~rX~=J6t;E+0iu-;@M1v37jUXk!D^KAk)4FmgTulW=Mtd%y z4+FtXg9GVhCd|rbD*dzn7Jmw{IZZVBc=xj?+;grFa^-I;wHzT9lxc%z8o^J^ow~&z zHuU;LZ-7Ra<7b=|V2d=U5&G=aBqS)fi6emBP0mH^Lq`dCv)d+m8lhzJ@r6gKJh)yL z>MQwtd`U=wpt7>JKflpI(QO0cnVg<3FQ=f4T(Xnz)9MlI!P&O#>XD`OiJlP%cZPxz z9n~&Qrlw@8Fch1ZwJRlI5&Xp2WB-Zah65pc=}4k*ySB8;y?>lgMWYC;DKyDO;Qvp zYxI5tO~o$h#v<3>~(_57Xj!M76Js(Cr-4ixZw_~Sx_wMJ}O_im`cR-+TMkQBAw40I>;|b`mx9?9i zx!tN5>BiRncZ@Jg3LR{-(ikP!msLd)CEMC&Z6Z;^esTY5qdUIdCBtxXG66fI=1<=` ziux@hjlA2k)qneN77$^ztWHNRCh_%3KYVryt0}WkcYc8wK}!v-)VCiWtn9#82&leZ z0F5hGMlR!DH9!>V`TIv;j|i3rv|A#PO_tgS#Qk*(z2pD_n8E_7T8Bt{*p~Esp<@euCZ>w0b04lWI?(L zoo|tSdAxtotXee=l-1KLUI4{d4#eb1I3oL_)s9X?D7>kD4J?O6LXPnW(kafcFFqMr zf#o44HQ$tBtxjk%eSzOIY1-W@WclC9`i)xRx)be|5~qLb_Qu-B(*|&>t11O{rz(bx z1l+_ZAoSm9Va614ul>`RW~EZWs^%)tAKe{6Rizcu&REYIy_$H3o*W*29}ok`Yh;U3 zhpruicl}B%4xQ4v+}tBhYtdGENQ)RqEfb0zS}eWC$6*V?vYs7?56NROE4q-9F^W0! zr(#8+P+O({s&=Z4-sJ$1ztxQ~#Cu z?P4`J04h7a52!=m4k<}334Z_E1_Ql(e**zr2g(ju8zkOz#Vh z#ex`+U-&iA?)wI!&uL3%=*w*vAnl9`S4uH{wCP^&bDA`Mln0*$HGFmz51W}BeBB z=?(bfLfXC5;GQm4NcZ#EM{ae$AgND;1c?C^|15hZNfo@Ylaw5@%=m`>2CTm$jS$*g zuHtTh?#x)w_a|BWQY|(pi+P-h=uAHI^eJ->##irewR!5-U-^r$VS>|np{8OGLa=tV+~C?_U;(9}D4P~ws8L?97zm#BROiKM0QlXi2Q=4PWUrDO_u-m}_Vy?etBoX5 zre>3Y`t#r6!F(j|1n!X!e*qdaG>^c;;AE@6f3fS$Ukwzp&5nuJ4tGZ)cXwk1UTsYN zM0Pfi{O9M0EAp8+Z(yCskk1eMede$k9j$=Y?K0*t14o!92UNfqY8V|IT;xZ0XD`co z^X@A!k~KT{M<>_hZXfw5LCcgYfCl~?V8rq^usc+Dh1dH)6z8q`dh4laN?iwKy!F4{c>wS z*YjbvF-%$ZcFzhI>icGZ8WM&#LDrzw>j@(RN=2&%w*(5Gpzl9qg3JE>@obxT^7`4a z6FQE{$o%neBEw_y*~r*%vuksAUG0SQSM%ys5(2i$&#{?_GdsXO(gp_>crSj6HIXB12qQck4k9}Ul%RpC>tBvTUZ!b$vV~lK1s?VW@pFw zvIolIA*NN2eZdAHf`ZTbisyVMe<*Cfw8BxP^LD$yE?24}qNJ7e1=Y2Ls}-eSbONQc zLTB7J`J2(nIHtj}S5=3n^Lt8A-SyqTmulJ0i&fVB_f{{ps+4Vi4S$E#*lqvxx`m-= z%BaW>p})ULCpBn8R=KP~zViL>mPe<*qhX;|B~Qx1aAH9PLy_vRv#S=>On!*@ClQVL zjE*PudjN2b=Y1}lUiYIj>rv5Z4K|sykcG9MxYvW?r{J5-)hP~h3(dAD2;v^xkXp!D zVeQ&W;|VJT6u@}vq$FMj4o);l{lDAP$9sJp&}5)z9Zn9Ul(N8uR%(!<$fR=-HCSVF zY^ztt{H1Nviti2trna-wIMXsRLB+fr9A7K&I;P3>o5mvsw~Dz@hx8gG6s^Rd?0#;5 zs5@W)HXI@FC_j<34oMLhY>@(uvq|$nI3-+UauVP_Bb}=yCV?vL-H9xia&}q^1pmjP zjS192T7>CC8f7q?W|di%f&S|+!1btYS0k(ujwBMm`wdi91FjoVNa%bd(r<&Egh5X9 z=NFm4pO=JOMEE3_Loqnn*DWM{-_n%%%>h7o*6-%#VSc3GB|nfus|=Qw-6V)uQ4w$( zas4^PXd{66V{hZg2OuU$iU2;Br#Rrs$PErbBFt@c9>L_=ZN|t6vZ79|ZxUwFs@gD& zBmbzenPf7B4{CBNMG03hL8v6)giB7HFwf!phTF%NW4;=jH2}= zt_=3*YlQe8iX@ifO7WJtQfXB0&t&TTtSl;J8CF&mhxn$irE2BUAGD4fSDVq^OlmSD zT$j32ei=Q&@h*Z6FwCfEbnsRw#tOhBgj-yu>-BfkQh07zNdzYliqfS%f4We|A9<~- z2`>SJj)AacUIYGszsZa`e}VA^+J$a2LPkZ?D0yi>Bp=VtetbN)opFvJ+dK`%{Coi` zA1|Ku1Q0B!325}ljd|S=mhI<68B(2(Nq+onPJuy-8=r%Zx7$Ri89(BegzCD1O55Kf zSzJNx)tae_{kn~2(?p)E;DaF?X%cBK?0`44NG9|}qA$fCv)yu9 z@8PrmO2Mc=xPIPGD>bv({SAC&q@;;ol*(epcklhJC3?2}iQk%REKds#D5@f0j3Ff5 zxQZm?%6#s0XhWs(aU)^Nn2mFC5M&3JHP{>*8kC{>7gTeC-LLw`%T**eYWQOW!*I*X zNJXZ%^&dSSwOAykeF#~>kTja9ULPfLc&)vF_f(&mxh$=Vkq(CPDj}im%V_Ou7tH`=%4u zhT-AbRvJ2jS?tM~JR3iV-D@ljyxiP|t9~GDE*?u>-*oDKhYAsQs9PIf`^e&432!j6 z--0-2b0A3r#@Z!^CuP~(v1_-ve8UthOM6=7jW)0o(zJ%1Ix%*=AQchg(qL^kAq&dj2uFA*~HvJC#l)E0{eO9Sy|0ts{CS*cU&Y zN#rDzmRubH9`4R31-gWco!H5_G&9*VGVN`4PD8(GYh8p^v-CgP_0)%h%r5@fhSuRg zu-4$el)t6w%?X$nH&ZIrnwn_H8^~|zPL2(n{WF#_x{7+ z5+rpID{FW46Y2RDVx`e6iB^j{bI8ca+@Cne<>6Ql~g6oXnFJ#v-uKH`0$gHlOS(Cn$Y8!W82L&FJ~h8;M%xqN9#m+8PH)9k?TozrB<7u z{~j#7n=^f>$>ex|WHOC)E#E)RcfF;hkt}0O=pn@s&2AGeY^^X@c>vHSDakF@IOQIg z@C3EB)T?Afa9Wd@q%P~WLrhRJ+pzQU{v@cca@_7lgb8oji$TbEnd}5+)*%A|sX=Af zI1x7#l!iV!s+RlTbMn1WpH9gWl+>{<6Aepm_8o2Ill3ML^8eN_nsTk^qY&5nnM2=T z>l*-85E#m>;WXKys6Cr}fReL!smm{v42zYnGCccJ9vovt9p=sG*^7aLSx3n~Eo#GO zmc#O<;tI z|9vBAT$rPQjvzr?B(8(GyO+XpeTnUNkQk-+Jqz1c2F{>)cnA*q`rf{>N|BL-vGf6T z{vhYQEl#H4sVs%i4Fr`b5&C*FAOHZo1tuFhPbcw0b(5IttGLrKiL!PZov7%RARIVb86PJ-v>i9+%t(|~G9Otbf zQ$VDUX0@%?4)k9+hB$ag=LbcC;kzLbH#|G;PV37eRGSY?%! zd_dr2eM#^kh0<8a1tuz{n4E#tI*6JRQv^a>Dl0m&-fx%96fQ6O{|#v=sQbG{qvAv^XbR9bVEXw7!NX0-f9kd|ATw4vc13)7X_9Du? z9#9BNQe5o!RS+0(GGCyfg9~XWS9i|OA8*m5V&Qj7OUiW_A~cl%OWGHV5Hy+NQ9N$& z9Sx;mxamaQ`=Y7?g>{zc3sT&_*GoQzv&s>=P`cv732l3MEf~5#cY*W^Xt?+iTBOn5 zqf?j>jkemFMP4#e0hlr&$2N>QYP3GvPjtiouiVL)A=McPUJahJUoQWYlVr zs|2XwpU+EobN3@T$55tlrN?G7}5k{umtaL%8++2O~o5>sOMIv7w;Y0k&I7 zAS0gy3N+`N_>*~86AP-B(d_vzZ4N>J+M6gL>fUG89h-owN_baeM}R>;?&%r$+`;An zYgm0MbOwp(bXH)H!xA5Xf>JmWT^Cxp1|gPM*vgZtQh_Gufn>e7@b9mI3FA-AG;~2% zxHXHRs5C@xoqQ@53`g7n%)6ymC2huN%%DW&~yHrSR`0GNgg=Qdtm) zxMW>uJfe}Z+<@E#P|xtdXORy+f7)*kH#oUr84k>8@P9%fUL&NUoduE7A_bd%iTC&! z!PajF(vJhgkX6T&1#p%64CMF8DesVjIe{yY?e)H&U!j0hOjP+dMt@YbvI3Hm-1!Bl zSiO_s|2}hMBF8iIYHe&u13Vk5iraqhjICPi6Is$4H36$H&p3R>w3IOs6Ur<@!(g8< z@a+A{1e?X!WXIEnD&pUxKq8}qai_a*o^uow{^6znRhQYpb%Svd;Wc~B3UioSYdYlT zhr*ImEek+xU?C79+TW$<#$rTi9>u_+aljVS-FU1QgLZV#?!5|S0GV}(vtz|FXFc(Bs12LHMWF(4%M z8b3Y5tl#kMddoZQtwt*txmg;0f(--~b~bKvlX1e)ehostTo${SD=iUpBs)A@Ie|bB zVX8wC*>FA!>Y~L&`iGP$9vj5lzj$IcaawHbrs$68%`W%}VPdy$ZVVax?1Ev6_fMMz zfd|xeSk)~&ztzyg?bOpy+ofgtUw9U>?ofH!f0@bOxSn|N)0aY+sdyr}baD2n!(r3g zY-m=2HS@PJp}ev3&{q0-(}ovXM&#_CRE0p0=M2R;`w`hVGH4bMr9}Pp*)eGr^hHoO z6x|e4L3?KvPwOH~>31JJ{MPQm3Z;1h3@@<=5>;&1NMxq|_dYC4-5 zslceBSlV(WTu)J{`+Z9=sr~KN;?c%tf%{1ruCVQI<%I9^OJr@plj%hK8DG6AmkA6B z%95UT3)YD&ZK>5F%1FD4#}lU&zmidg%8-R1OMNXB9o;q_!@YosIlKuTuBD}#HC{+{ zF*yl&TpZv53U)m?F!?5AtCS?q@?PwMJd(Ccv{XG14)BglVPnp1Lb$Tz(kMagHbtRo z;^R#T_{Fe~X3-Ssd_7};x1i3?CN!$FWbhSglHQYdAPO@rJ0ZXuNMHA$UglJhX%vma zl93K99Z=?#fvxH-<$lJg>AHV8);xmw{j@c}mVS3c7Ubh|wWZQcMh?E-YKC?!>HxMm z7+JTGB6`C`28+GfLp+hAC197csHp-MlauM`)5+GWgdkfVa9|XoLla-f?x*pNup(+) zDX9_H&ho?NC^&B=eW9yE1s50D5BaK#x=R+YkY>1D^t+$_vl76I9NX^c{q_^*&;NLM zW@H=W7))P8ey^}UWj|hrVaQ7h{yOZtIG@n6qvMq)Cz~49?T-{baM;_$fSRwE%v0=h zw!2IE1raeB<%jCw)I0MiM#lp?y^ocovB^P`g#j6x*lQjjq?AWPPz~-nvm4=|&T#fs zO9_!E<`bbxJ|3TX$}=3jFWxnwwgfBdN;-R4re_1V z?+VM9vl5)KQQ%0B(WMT9^PxsqIL}}z;b!M#&>^7XXh|gh8?02HiF`EJ2LtdIZM`H) z>lz)4|860@xP0(pV3DP0&td17{Q0kJ4~YGG(?Y=K0tv6xUgjlw?S~&Pm}0ZU+dGP+ zh>W78gxt+H9mm1H9~?0T`&(r>>1|LpHYrCdEC>v1N(~U}W`t>BFzt#fEDca{e)V=`;F|57 z+c4=08i@-!13y@p(m@hFx4n`6rPPRMY}5O)-T>Qx1ducVbg$3SMMW|Dm-7;7Vxlpk z4SE97S*mbBlKIEVFmzmZeRzjjel2)h@6JOI@x;(32j@0jM?c)Ss?5kRycTC*OM$1_ z)Bh@$_!CShAHO@3;L%zWW3qb+nyUA`h3sTz%W1uTX`OzLUxeFS_=6?hEn-eiOvYKY zHVVnZ8Gf<&_t+pT-}lxk?Jm6K_k-kjwO_5hMBy-2csROJ5f-lu5cdjyvGpMkdgCma ztVR;x--tCGHrhi?-B6sJiF}m>KR8zcCs{Dk%MFMp6G&gsg@Au8lDnIgxhX9;!qDax zPgaDiTf@W6B)doa`#T_CCJx$O&0saSw`l{o;09tu@cS1znG@aU3OV!;nAtB%D2%#M zMM;Fb7&+x`%mnSJf{T>eWH|W6R4cj|*5efE^(|q$;%Eb}Q!3dXp7y_R&ea z;c<@V!H}X*;LX#yC2rCPXF%&QDEgB+{_9ih>0UK&A;37df4Q?$3LKI;Z7TglyYn#%=`Y1}<8ObY^gli3DTJAQ{5Jw)bK~3E zU~UN5#N$q9MWXg;DG%#bwS=s((zIj=SivT9Emv4hR|_zFFg;^WTYstNnQShVUYyup?%+JeRa#nnp$wJN`a7_QJb#I*jAERqmMLK5E}nW&ddM^mejTWoKNas5kI6amxLL+nRFrtrZ0l+E`9pTtPwn;UDV9XUF+=4dGmk zuK4Mx=H*)I$)jx%u-n?`;7-gX%tJ)2!N!%oUo{_g{O~XM{D@Sq8EiORjHLPY(l-MT z-{;~8pWU*!D1Ww0w{DvBw{$y_&kaS3&j?2M$n0K~D~s#<+&pb460Jf6#|rEFhyWNz zDxcLq;)J{?kWgs0tD-;3VjQ>WH6nQ3AkfzuVc*zkLy=vN6_TI0=~)uOA_ zDsXEz_O|o6lb8T$DxfZ}9K$S56nUVibHK>j?&EEuZK;|Z4jCKt;jH#~y@v2Jj~DXD zfC&eu+}snIO-y0wZd;NHZsDw*j)B$pX4okcWoWOOupj zKzo8qfXeZ3I1#Dmi;4bS5ue-WW2di`NL2-G2{=9gl5G4n27%=t9A@uEW*kAFFb;cI zxtp!l*P8XL6Tlu_s@4(%#F%rk%&-GrC*(zoKZF9K_W9TlaOME;~p)O&thVc zM#d5ywi`GzS)l+g3FVdHo?pO_^ptbe?;~P5kCN8~W@2}@^%9V4f64y)3y*c(7p(Lf z4UOoX;PX>S!Rvv{>j-xe)z2K5_-F||&X+>>YzY90I2#CCa>l7v1=^yPZLS(wS@0?p zbnu9B1;YJDPHT|2`!mV=+lgV@bS6;I-^#%!!N}qh)L=Qz4|H=;mOm#;+)De0dp0E@T5P~zldP~B)F{iB6x$<(y3{d7&OD!+=M z$i64^5x~{D0`Si;T-3nBa~n-e8%7inmJ~XP`{#X4L0`PLdIKq0@CCEJglu^Ew_0K8 zcmX&6XpsdHf(Qdv6jVaKupWlN$Me4JB+5uUu8>*de`}aaDB48I$|&lCaO+(u?JZRYD#pb+gyI z876Y{8en=^?BSymvP(VhY&b{swWIB>XAz&z!4|JBEG}d)wX*3EWeTYuK;j?5!=maR zy9KJELGi%E2of9sTyb`}4m}b40WXe%5Q`V-+OH`HA9iFFVI|4Z#l`KHo@Ihhqy#Q2U&gW{Alc&KUpo1jFqYGFb^}|CryFdzvU) zC`C@M;2SI)EW)Fn^d2iSeOWC)Y$NMi$Nbyo-8Bc1XvI;$vW%?v84nn!Oclf zB_FtDJgKO|jX7@QNYXBHkcr-reXKkv1MrY}RbW(Vb*Sbz)dTIz#g^W;6TyhIe8{Un z(Eobbacd)!CZ35@mM5S*5*2C9cB);vR32DoLKU~S*IWkl5{Ki+OCMD@^S)Px``=B< z0TE|pqJNm%dBPSF0pkqqqm04Zl@%U>IwS)9SDYct4L zYxAW6CdS5wxkJN7FIQ##Qt?HP4O$3aAebeg2Wl&w^IaXL|GLXaPlrv|tUBeW6-cUk zELA6O zZn?O;)~_%l9^ z#e@&n7cf8(BQxXa@~*VF>xPq&eiN&KEdka_EF8qdfgBl+7vRZP>&rAYPR@yH+P_m+ z;eRZEg3CR?CV<*C})EK<_U--IvsHv@etVv5*%#)H( z{(vljn`bakQbJ)M$6GIeat%{7Uo<2Ta?LSX&M%JPW%ny6AP*`iM}-%KiIT!7jSAo> z4b>Bs5?%ZJsCVl8b?!SY?WCH}l}D|(bM8DNa7^X7?6>`Z<$ZR@r0Z8RJUu#EU|7ff z$NS5-dl+xmvT3JoI80_t3HUfAerfBPF^W!(8Sbu&AxlhqzB}d_`yNS1ynC)iPXCiO zWrlmdu*d!G=)TQ3B>nbeAeNc8dpEP{|63N@zTR9*NfQV6U3IK0NseYrI5u9$%!Be< zW+9RH2~@$!^KuW^{s{Qf=CMvPTI)WNS^Z=VY@;2a7N1{EjeVv1B-x+n#jj89q2}X! z_oeThZ%hDCQ%w3XD{8fYRz>L5qNE1IfJ?Pfz0)6_xwH4meG~KBx;<#~yHSM~LBn;*~nqi^weLvn21JeK_sVS`&f=ukUXqwg;W)QE&X zKNsg)c|PUa4FBOE{D#QPTm<)eEKzR8*9~Bu$+kBOo1S3ii{%pr|2oR%n0@@A5U?to z&BeOkUqk$UkKPoNNUpVDK+2u|043lJ*7IR|;2{F~h2!-ERnsHrKECsy=aBN*TeKSaKC>Q zQdTr5H+1KaE(>L#lJQ0(t&WMteD3q?t%q2@=5oKGpRBN|)az=(_&k#?pfDoujiO?8 zv@QGqt-anT5DAHKJ16-jo{dwbjxQo%CtQM5XehRo-T}tT$M=UmHo6$KVVOM!M`X_t zy900&)=rCB(RH<{RT?No1%gZek&L@`Zc<5~08{6Tg_6^|| zfzWhJ^wCuA88kB3{&0QJUC);*-noD`j?u~bvQ`Gv^~TGcG?=t>;=XosUE1#JnO1@s zDPQ)MloK0bYG`fuUX9IsiBy`JBP)w18;b`^oa+_QH}^G;%NSKv@{z~OLt;A_nUI_` zrbFUC0x^vqtomn6HkBIjkUm&IKj3vAp)--22$2$xv$yvy041z@VAcaIoSSJP5FNTZ z@Pb##Q{(6BcS-DnV!6s<1Ti*7qyR*?+2O@3?}&eWz7tN2k$zjzP7M*k{L6}C#PfI8 zE?ik>G9lnE%ao`ztQf!bl9GNMzVO>?o`4Oa0ka@It>MY(vtxHYrXsXO%vE=`CBRzb zt@WG{;E1?{J2%fSmHj+OR=CLR;T`_eU0TN8$pO@m^nJmOqX=3 zi(2mA3Bx~erKY@b7ov^)igz0SO&X?3_}dNV<%Ni~a)7?}8u@G0JW!VTLGQSJ1jozk z)AKUw+~Y>V3t~nP-sS8_r{jzXZFsRl0eOD_xsBfU+0Z<=O~BhD*Sf}$>*VcGyZb25 zJI9tY&pXba|8dv{9xDOnqKLhhMJ1l-9n7M2Vcvq^Vp&e{SAhkpjvf(x&xLrsHMRg^ zV0ijO(v*@vG{3&=U~wpPw~u-a4F&jJX9GRWa6qkL z&G`pIZr1h5n*==C@`kSbuLRutz?vIdccJV-H{7?CVY<)Ru7FfDFz2J|Cf$zjamUAZ zzSH~*Z+`LoqNsl_c!geR25{ZCaKAMhL57}mTsmF0{*o&+cO1f;KGtndftv0QL*yuV zENZT*lIj452aJ!s?GKQ>XRIzKD06gGgk2pCR$X4xZ-``20W+6NI8jkKA6~q!w_XSV z8s-2<3ePj3WB$P8(xG}*xx(5Hbm z6Kwqnow__X{3V}#!nN%vNnwUGTi5kOBt1wJ!ny*Mipm7f75}fLdPnjB5w|(dZ9&0o0eoqh z;Wg&YS*`11CL8e1{=3hQN%0CRqq?UnzIgvFEj&;z9wrZK~zD66jAa+F|{Jv7q6@1%ofq=O$(580t8Z=ooa zGCfo)OT+M_T&aGs@xvcDDX4a=^pv6Bod%%rbX(@2HC_2V*{Cbqpl=EIN0sE4YqnyF z_D5)6^Bkc%m1s7Y6Ur73!sgOBwj><&cF$YQqlw7w$j9^_vY1w92sdH93o zm0_Rm1jsd!`-RivJ26iJSfi^i=?N!;9s%nmD=R|1@2xaNB`sAL5g=F)$GZTTYz~hK$6sV>8k%1F}QV*gB=0F>82~vYD>Y|bJnwIiM@pO4{ewhpO8XE*0 z6anNKn^fF*$QtoCn*Tew7zA_oNlvJN;Q-WUJu=Zb=ev46&_`DJxrJ8{c|{zsyIPqX zu?ib|E$ea|*i9LJ`rws@6T6w6*{q2df39!yTGIja1Uz0oEf5P%dm_a0u8GQ&&f(cY z1ymm3kmhxHOU6~)L(&J2C?E*E?+{Fbmq!{t+1Yci)e(X3$Z5GEpH--aFV~}sg(Gp? z+Qoxj|3mP8`fh~{lC--!FwHWO!HOX7`>1uGDFb)4nit7ohTt#wJp}1{IMTbW{YHkr zx7$oL94cbGAxOZK%6PTPI2cF+hz`+h6FDeDf(lWR3K3KtNH3*wD|PU#(Ktp_v-{@Z z6d73Se$T5_b9RQnIxP}70&eFWlKbr?tbJzYJsXum%stMZ>wfqRQ=u=Pl2k}x<|9S_ zA`#cC`+Sd}D2vM4H2 zd#(tSPs(it>pIuPRPm{)!F=v&J7Bkf?nd<868&(_zt9Wm7-b|4G%=@!(ltwZu)$(r z9;;#3aY6N0e{@jk@q5==9gx1csdDuE@(nvdc%SPQ7;E-){%0ebuKvO}2$_!-u>|6_ z^4Wua53=!`in0d=A_USZDbpr)x3(0uEDGbu7qAXW!pe#ojm=#1oU4KA9c0$S$rn!G8eFq}z74 z=4LIiyI?7R^*r%^yNIyeBAAej|6Xs)__-s3@O+o==&~bRRjt2$(>|yuB+koXN$3hn9_|eSh=*mC5I>-K)o}^|+|CN^JvB}j|2_n5a-k<$;Y!H0W?t3&7ezJi} zZwnbncr+!pzM{#n+VONeQ+GCBYOz>_%Vs<5w$p4odbx&qX8Yv)xjV3uni~t)+|U5< zi2(?HvrS*#P;_E)a`4o8OEG%@B`z)v6XyFmA%8?%Xz26%f}*lYmhImT1;Rm_m4MXd zvnRVX3|4w|@i^&7XMB#{&zHL!FUiMnglN}p#-fSO3c*}`S#!!3Y?(*i=Zd%7aa&geia?4=9?i!U2FOQ$_fi3z!!t|hUF$0H&+q%zyWX{2%YPK^``r8NxUOsOZ5CMJ zl9uUTd&;aNzHv|Yye(b`CQ&O8ISzOs0+a|+NFt$xaD)hJH+TS57m*Bd52=RHT7jdK z&CQ=>MvZ!-7DyE=^3>;hkvMe}TZdcSZ+9uW z@r(;b)A5eEep2!syj{U1>G$DC9_OSp6!p6P^__|cu9uF4S|#-QQ`QVHU$CG1SDK@x zO(7}SnaE_5)Xf)842p+PcJsR^30c1;`j&U>%i>HO3jrkK#uGdKBpd!D1sIn^Eqz%f zQrL@k!(V>GI`zCg4*z<4BkxD9nG!B;1KjVwQ2FdK>ZlZ*byAjBu&+LRpn(28xp#R` znC`WwuwxB)M=%joh+uoECMU(hVn|0*EX>k;XfTXnNB!+wb=ZKAcSFTTV;A9sYeQGM z;H`AWr*~5xhg~`D4vWFlI+zur8ubh(%&(TG~uSl4o9; zQ@G9_1<3*1lo1;mn@2E+%3(oCV%vV@#6Fny7-5!^1bykrt7zE}>p(C^H~F$-*+4*0ljSG|ugb6ipFT7ANvm5A``YPxykz{M=@ zVe!P^AVJL%Vfp&?V zbzP41&4BYyO=YRV-#x^(NY9OiC`kGm(A)G4Dp7jMI&;l<2CjhgGg z`^oCC0P6|komnqXE=ehd9aH{!64ypo)=0()YCk`yM&F;Dl-1UncI9WQf7=L{yNK>B z78@Y27$l`HNhu|<_oVV+4Tk#I`w>Mt z4gIEB>M9yZc-Ks&fDqxbEX5OBEOoUI9Ws+_nXTy`v)2LxuRp_(2MrS2smg2HhS;U3 zt%`xk`!hzO&_O-*r0)E+?PC3(gtTu2A8I)LyTpQtEibzt1&J)Mysg2X1_KV7ZR-2n zZ_ds}b&4B?UkI2`3x91I%pvYF*Vm$`!iabVKR%f$4={my_Iv>q-re|se7px3EEx4= zP`80?s0|iwIoy6{{%6@i|DTH)XDAaJ=&TzU828N*0Ye`C%oYx1Oxa{|6=f6Vzw@Ad z74&=b@gR9_o80x&m4D@WeUCmvQbqW@B?mnJ5ZXF6CP~DZM<@37GM!lOG(;grnlFEN z+7e5)&=q>toVEIG`Z)Co^;6DiYj=T`o&pRo(WiZ9`}xf;)=~ORh4+x7fMUa>si*Gl zl#@B@R^zGZBfmYGZZt>yJQP4CLU#pm z)5nmj(9fQ0_B^_I^NG7p{@iG7qrxR>nSDWT~x#b2d;I+D_0 zCeNyAvHB~CBOzJC?8C`i|4DiFk5Jl`**q*5vykm}uZy@xbbzys?e8Amxbn6BknY}0 zMCIpy^)85`YOan~f##!IDQbFQOb^i|6=Z%S^XrzVlXAx#$8!CFWR~}y9BWgSBdGdz zmG;09vWgRVRgLTj?SQE9V&`5Ows*6!DF+)RO6OeE*crju)fk}mG+fP=X}l610lV%; z;udU8mQ}a^fmN^oW7|0|eDO}^WYX*l)CKZJdAm8K{wJ-iQ}M51MR#t4;h!`1hiodV zpawl4gv?u;-gm~8uo$rT_qje)QG+OSqQ<`8@bvOb@cVI^B;*q-PybXK2nqFXknlTp zr1Bz_2^7P2(5XjS@Ll5eT`$d1jcOEV78(nfg zNOUH9Zv14p9K^G1zMX}E1H!fp{Qq78wt4y+7wrut%6z`4Xv5=kH$mk22GPZdjtHC& zwJ>+uV+<$NCcKOj33J~8^|greQ2^B&!MS;WUc5UNu}`mn6Q))VR~A$lleTzExw{(; zUo2u}j}XysN+u`wuaxC{x0#d~z9SE&n?@e!BK2b>XFgh zJ>td7fTIm+B8LeU$m|+}RCoUCiv~;-bR{bWZc#3hi1o$^9DGsDTzp5F*&#kpeeX=P z?fz?0-}r%(}Mg3?n~il*Prt=awg*36 zG&VZ1x4*RU0>r>tc|lN`y_qdRSfzCm9r7a{VzS*TUl%E}h46p>31jus?@5Fe4`saY za;*t}lx~0xL^|qdBPlZ~R(YqpNZ_S2#m>Uq{XgRdXJ;BIM1Ju&;JF1eOPc%R10t9k zH!hCT0Ej!XDs^4sDkYIne@rjc@SX#*JsiVjlJL$G309c)w-Y;BdW<3aEB|y+57UV8 z^E(W;_3$24+DP4(PHBt*o|5^M$jzlAjXqKs(5tS|Z#=}?Ic)}7;wLRm6m{F(Av6pA z*p`|(EAj_e>FhIinkQGqG(NDeT3>4)HeKZz#9x!_Z*TV*^vJSyyb` zbaS(aI<}VWWNlOt@2pA6&4n}#$B7pO`K~jS@g_yaN`F@1Z^|T$DpQb9QAb8b)`3-z z^WSF=ovg@RuI@`DB!5ld5`Mqrl^2vIkDC*y{h}lF0KU2N7Nkj)T@cYmDAQ>bDS@T8dj)hZk3XY{Psm3-jp#}N9yJ60~BcrYFgpz7vZ(wIU- z*Wip>@0u}`k36K@#QtuAMVKiO^4*g7P79r)epBM>^z~ePe@!F~M9hBV|gAcUY1p^@PXNG+mpF!|2sBoC2ddzbt3B(P`A}t9pnl`WHXFMH169 z{Sl{z^>5y6AsZ=$-+{f*5zJ*hbpJ5e(&t@hd%h`q`C}$%lz2PW=+W~b6>i% zGtF5tC|ci$!|vW^GuL2J@+3i7m+YaNL`#1h7E_jZ2=?P?C4*A@N~gAp1ni08tTHF6 zh4*v$579NEB`Ah(a9tc5h_S)T%~7&TNp$*sONoGgeQ^qz`KWKh5`J!{cG*kQBSrzK z6Q!>{R_GPWV%b0}23#ye$MV|Mt6k^q#}(kZoB-O*cUx!2?;LovF?WRt`#fuhrK6Pd zW0V@;*C>q3vkfOGvU=?D!_Hnb`Kuix!Sb96 z%vsSy(N?W2*-#X)?K{WRFk(p=xtarwqgrBVbu3Bee38ExTCYAFzwm$^|8t<6_ll8M zpm*;u_yK!7ZIUY)I$@Nty}R3PBrD$K}o{_{CLYu zzo0&sF!d>|a4+?BB>#QM`ZVhR4F3X?QVT>)L2FO^S8V?R?`LEDkPm3*jl_B7b~KB; z2*PQr+q&KvohJX{FoY0h1qBDrVK?v!q8F4ooyBd`dwTu8 zS`0wAY;39Fv*iyA3~C}0dQN>xjOJ;uPyz%-o}u&s5<*p_;q;v-jQQ`AV5B7Z%|8*C z?Brf6uHYg5&{VMXjw9Km5(5}2vq1pB-|KB6=J#{m#rZa-qAnpTN`7#Td<5jT6*VZ> zdX1M6iK4%yZ0-!YNXg=P5Pqf<3+w6<=oPU|7MRJkFk0S?=4UBVdMquyPOmHzop)|AN}!4iLOE|tWfOk`{i92DHaPO*pUfdt1#)}_ zRf98tyRh_OB2fEg=X%q8vr+Vxjl(o7tI3O9ciR3h-Z-MG|Nqwl9L(uxH`H%2_+US} ziZ%+7ICwiJ9vN%k)IVTZHZxgfgsG~z;#qSP)T{3OaC?&r$q7THC?p7L%%!EGi~@^4 zCI`c36?|knQuEF2$gon2%~!`mQ_?sD?%28L;~a{&=RRd&aHTj5y31B*ypWJIT7%%+ zvFx=IJ`u>J1PLONBs=DU*0vOH&DQ6Ds0xEEJUg48=#hK*xyQ+@eEZSi$h;8yi-WM(pl4@{$Edj2*2e7)c@Iey(RK`aVtH7mNZr|@}Iwzgea+ksnb%9A)Q z4rZS>?Nt+aaLY;*xE1mT$qE&Ad6f9!Qr|DnaI{2sZT?Q4uAGYR*g`n%^gqU|?hlXd zuyophf|1qoXg6o{soTApMa;#2`cCq!L7;odeqv^bdvO)tyJ{n;qx{r zxAVD|R}KJFS1W31w|TA&VcBVZ=HxJCZZv6ccp;~tz=Bre z*^5kxWFrQbup`b*kfS2#Ow7{V@TcQzw1M!8$R9g=HcTGMWiKwNUD zvE6xfUP6~7zE?Xt@6RE?F8nP4M+5=6{6NKfoIUV`x_zKmNbQ5M1HW@zn6yi>v=f_7 z$`jGNX_KJex*v^sPtxyOoZ+>)kOs?DPrrCE3RMiksJ)-MV<{-W7@T+d znWSw1bo)7%-s5KiTHKXK-iX8Yca)~y=QPr!7~YjHlXQw4>`WgG9X?fa7EqAdTk;j@ zwOZPd`PqmLl$o)_29x@An?c-qpTL|q_AQ@(Tep-c5_mV$X<2GE$Ou;8X!xAk1+Umh zwc-oa>02|bjRevXxQYTC{&!0VY)6V(mmQe6s@;hLZfui&0VVCPIXgd*dzcXIr4T@) z4xJ77j0zFnoZ{ZZ-kfPVTaLdSL50$Ssgd&-G0_l!H;JPPN{*Y3YggWM%qqNrD6Dim zKAJ9k(Lm*DKOao7x%`KS8G{9_k<^glSE=JdwZ1i9MBiWG%-LN3sdb%6_o->n=Y#FR zfW?jWL$&gS1YplWLF<%I!X?kTJ1yPE4jVAT`hBUFzgehhdj{tl+>Q2Y&n!s&Dd+|N zXVxZ~#+AF%){@(uhih;4x2i`8r>l;NZ5K4!uM3RxBueO|`*(+HSMqT-z6*AKXZSF< zQN(4Sm~nZr;3@TKuAaK7Zke)VkBcYU!hS7l-t_x-K_lx?ww1l~`~7(?ff0~-0PD|( zN2lz$Sk0y4@{ zUOpPSpZWTmPL9TWII)av+EeCjmbqBrP;5REU)T4)NJ#^&@D258RJ!LPmu76KNr&$G zX&6Jg6=B@^ZjIR)N{v6>%S?Te9aAn*ARtXk0F1mck6K_cT({H5LwX)%f|t=7}EcVF&L!&bD*nJC8|Nf1y$cF z=9nv;+opv}6i&j^JUas;PKAJVdd54#-=wb|Z~d;CX-LvkQ)SbB$m$u&D>GDUV^|Vc z?j=ER;bg+nV(_cck+s>W12`FxBbOdZdPh&r{3T%-sZ89(;@b2M5?VC}t*pZQxFMQFeoX^+0EdlkuL%f$X`W(o7v!$^`3#3I8Z?BV&3SK8$Ii<>ST zY`M|qsoWX%-cjt!mq^(3@jn5m0L5oAFe77+yE&P;`BQcIH+ILx?;Dv+pd~1jxscm z2qE#f(yXuB)OBnqV~koBlCb!rV^@;m`q~w3qC2OR^Tfr@y&FC4L)B8 zP?1{RH`v_!qaL8^PGIc)3zLryk?2(=GNUSzm{S_g#3_Oxr*g!78P}1D{{W+qbI2Wr z5=ne*{ty&+kGxLBR@bSUuBQ{;I;~~FENcr=L8=*^tg%#@Vf}oaL?_3ikvlM#YdcLfvAODrB7&ACc+>Fb|v3gCADeU{Mnj~|C}XxLNY z8}}_C8U-YrT_h%RufW*7c;@w)Lz4!TVsNOra>ti8IhRQ8&%1yj`2ZC`Y%UB8)Ro_s zbheY(NKP8#3odL%?Vd%-)S_Q*Hc3oO9~ICX7#^o~+xszG_Vj?f3y88w0^}6nqYqaU ztvGZNn=gm!Ewu9ZI$p`-)|G%!q2gX3pIKeH*$cbdzSMbj;y6)Ukna8Wu0?Hb$OSG# zDUr-FxAHH;zraPc>o9mdej#p?T`zj z-;~P2XEk&rj3NrbGhDuXL~y^kdH%rytKN^zJ;msZlRon=akgBB6h2YbWG$;PFoSS? zQ&Ziq>V(wL&ec49!Ukzq<~Hy!FeIl)du#EqkSaZwZkizk~BvF~$*Ha6hu5u|=LB+1DO?x6ZK%BOEk%Gp;UG@O#GgEsOVwM5SyZe*koJ zj+{94XBMHF4|#6%S)#4NNikz79w2 zD%haJ%_&m*OHKS-U3?WH#gk0NII`JihO!7$bQNF|Mm;+fmYx&ZIxiT{#tr6${8asb zitN7n`TF(MAtsvG5@sAwy3))BUnE1pIFsCQ!lgwYKA z)GE6r|Ek=g%xBzTjD)CpAegl(Y2kS1NcE3SqSNUG9l~jIwdkTWq}-FoznBiHCDf5> z)l9fM6&$QgD2-V8kFd@4>y@czVZVwON zDpqXM?zIedxv#i?+HAp~QKvA`^YZVG&!5ixByyOUFb{nk2It~0_Yj&Isuifnntjjd z6sICL_^JSV_4?|Jy1)rtX7;g7?jc4^L}c3&zx+uap|31|>7lQ+-rgD*c4kR(l?j%@ z!op3mgeXO}dKweZ0hk9qD>Ukh{!zd4Ebxhu$0sH_r0X+w_p9rx#v^PKJ-LnuddTNmmeHiP)kyi)z-P1>Y(}l zYcw&vx8Bus;=TSCaPesO4Gzh3wmY)sr;d(!#xLyyT*)7{T%J~1AI-PT*y_M1C@L|4 zyaN`iVH^}{9@`#TX39}T9XX~34>ells!rt=1d76Z2$TY4xH6Nl~g zc^tBSt0AC>`m=<3nlT6{k%qSwThoXUbqWou`9$RA%~i?s9ll(0@PvbAoiMb8soBsg zpze4-rooU3Z?t8QD9vwE-xx3Z(P`+KC-BwCC#hZ&8O#Cl1S6@+-?(r^u-TbzT15@3 z{}CH@2#y*CI6Q#BcV01@fRw{=w z)_t1JIakjKRaG|elbsTq?;!ZPMzXWdi({c0J-=}=y{%Dsd*e;1oL3$Jp(z1rd0NSm zDLPWugateegiVkHFgr9^0S5`zeQTm;$-ugw7g_ zStj zqBDiF=y#A% z$G&l&)xD@_DES;}zHxMRAeA9Um=5Y*sFi<_^<;T~&K#gOW@7u>05MCpLhPeeB7Ji2 zbD?hK9pF}_Jl7i|;sn;-=jNA=3{RdIKhQIfnBFI^0-4C0nemzD?78b=!q1X?H&zg< z(5X|QVNNb=BKpJPGk_gmnsISz4P7K@|tGu>KTY-KT`xSN%^E5r$s2b&!JyNbWbx&#zRpcsOEJ@APy*K6q z=pVt2oV zMF>X-_Nsx&YfAyg?81)JjVKoLsSzZGPiU(*uM4*M!y?0iaZ)IeF5pcr-wE)KLcM$8 zRrl>RZL#1Q(@ln6bDSlAcYN=rao!%)Vd;CvTJQJG2+ z^RPp!xv6ene+8jOBlqG{tEO4$_76fsZY-Iw->3E^A{gQD@#5t=+F!p$1$0ev%go}= zj()MOS58-s{buR${BUAun;k7X`YNb3^<6B&&!{8lF1flhQ}|qcZ2L>pnaeS8nIqJ}pQ)cYwcj^HPFl7=nsPW2M^iCyW%`o0 zxc#wKKPHQ&X(R~;;lmJc|3Ku-EAxjGR0252Bi!>|f!V!zpXO`*i<1q4>86|H3}IGv zt**1IzhCy3K98}NzI_XG4xw2#1lU282q1-C?IEjetjy@5fv&lzhLBAfp`0h2NJ#5| zThgsRJjRcgHlQxP!BxDW{S3o-GUo|xWK(`Jlkm6Bn?GS=*fEi9S__sb?h_s-7DDHo zC9!KZU$KFC{k~gOWwK+GT{`c^?7D2D{EK{SzHw~N2jvxKHHO(4_Pm7GpmRyW@PU&) z&F5v^%raA)(6V57W(eK@$F1~EFuyN8Pu_Z&37x7%s@1e^iDZ_NG49c7e&q9oBP{KO z0BLYA9OB)X;#1r-fH2Dq;4)k{q!kL@DZppNIHY-2@^4_6aUHk;5_%JB+GMY9)2&#< zxdX;E;Y-EEsaqX)p1m-($7v_z=#Bs3R$&!8aJ;4NI2I65NLLsfUG>i7Y8UP`}FqIzlE`&@1yS>`k4yijwSuuMt>_J2GK+C{e`JV8zVWwI7& zDiKw{T1;kvHxHNYbIOxV6|V=p1NFjoj3sL}@wktFKF<;Wkm}OuBG%CrAP`;|)eP2; z=iaT%5?MI(C2Oi;gFJe`@{%Y*ZAYKVZxqwClMxNf}-D!l^Po7uMX1NM9^=mB?V zX6F6u%Mbm9(Vln~j~9mmjO`OKNXsB&n6O z%_&8l(EILu$FKbmzQphD0tRmN2vh7kGE^Gzd>;qEcA9l(KZkY_KUp{I-ghm(+gk{D z?doP;Smu==-1+aw3XPMcKGpvogm~?`qD>%RS^jBeb!fhF^WDGxjRvrnK$*z9gYOl} zBiVoKNJjzotbTu=y!yY0FAqEREN9OBhM~0qYxF=A{>c&eaF*p^=`&@1S=_A=9JaDE z?75RC^_75!F)l71oqPKbQ>h745W8{%7vY)Lxps>Xf_a-dl@dDjB-M-$J>2U@WUQ!K z$2{)Qyg!Cug(Z!ev=_Jria$bUU*gAmo3NyQ$je7H)er{p0P*P23XD{D2%-0>Yb4r?@@|2(}EtDb%{4;2XA*T%Om22kyJSthl>4TN_2HE%6t)? z(xzI3D;V9HFj;vIh?g3Sv5sC|9VYL_!Awi5#;dgqaJ}B9t7qKg#&#Gft-Oifo$~5x z7fMY=eLgpDd)4kj0*=1)Q!Kms(m$sNv29gcEA$Sh-NJf<&`-EK%>zB2uO)f6!3x9VnL z43-IRn)ygce)YM^izMPQB1Vg7vWf=(^IEv9j0+G*Ok#=T2VLFZ}p3+Bz8hgK&09QEC`YxOPb- zZE3SA>^l+K$KVgfE+(qBYFX0yiE7^74WSi_Zu^Ji588&i$KwWqigmuisC37T@sWH|yZiak zsP3aMj@j2*JdfMW;E-1p(GCUC<&YLGNX$i|4;?D*shhFiy5gj-NI`0mr>jMLZmE~V z#lKmP0&yqIaB>I7t9IqRz3G!T-%W88w8u6rTbfJzY(9!&X=PNYBxHbQT-sbnY#TulWHKK1*@TdMws zuqFAlfebZFMJ30Au?lI~))}Xi`+${-*Ak`OeIi)WNY}Cj36G5p`th0S`DK3ro|u>z z>)2I(ss}o4rdqxX7d_iVmonA=zQ&5;y!hp(P@hw*a$RmB$oG^-bSe=3de^QyeU@W? zeo)!#S6Jvhd)XU}>`G9D#R?I)d!4^3%C{v(Re(*8f#4rn1?;JU#gBfjTWw%lZJFBM zb!hW7O(RAj2T$kS6AzU;{R<7$^#kGr2IM7DV5jZhD(gV!;L78I=gca2ACCJ(l1Y$% zY?~EqA)L(@L`rHCg(>n;JIzYG5YDD+nkg}{`IABUc?))errs z*_Vfyr4Ie~?m0)iD%yOPNbu@lwsta)ai>DuS?($X_93gLn2oK){mz}A9$P|xXB|GT zxaPgRI9_$%ggLmtydW2l z_5q#A!oEf<+8h~~xDraoXxt&k4bKyYtG%wV4aa|WR~scD^^|Ns!oqC;LNbS~teDY~_oK?)H)jk-(>va*=I!Y9 z$}s7F&N18^GpI=wC z?9Gkvl~buBDnR+L<#~B}@Q7p7S!&+&vOrGPIgdOX_;=@AbF-{s46Av_@STu@SLb^N zV*ye9l4PJ6VnmNu_5TrV()eh)M35}0LqajQD(I}a{FT|RTm>L2m|D@#XhxN>DH<@i z-hBRSM)iyipaF{#79rP(aRP7QPA@bWK0pq)dfa;rHYH#3`;JwRi|`Rr|J*uRX9%{m~@j{ z)SPDJYNYg&58oj>T&mWy;;0+LYsAoIv|0Vcyy}K zKXz}M>-2*# z>GHiK4M4Z%xJkJbiuYodE(s&aHBG2u7oSPNrI3cP!U z6f4*5NFbGnb*#9rxY8ShVB-PE>2q1NU-&K*#f{$nX<+>Ss-#U+rYT~8~u~5>G?`#rJDNV12`$! zQIaWVkJ&Em_{ewmU!4PHknWhc(JX?&nldBQ_BJb(0y2=vT_$s z_U`#c$x(8?EaPo%L}ilGKquPrQBq_sQ@DoGqAz`Ddr-D9`CF%vWZm7gjR~EG@vOY< z1x>760%nZscK0fq<&%9~sg)I-QyyZ3o{@jCba+Y^30XTOxwvU*XW980Y^EyDlj=@u zld^c2EZ)8CnHYLMjv`$=5GuX92b2Keq2WJrcOq0|UqHY}zSbnDm9Y*_V3}}nwci)> zhHv=%=$&5?SyC1YBII5k!?{@ims99LVN%f-FfQcHWlvN-esnW{J?()4mEPubj33BP zou$Jt26ukq5-!CDi)!T`flHrKf^XJ2NbucCbGGImjknJR_mM}1#k-#C^9`%eAB-fR zJWl`2r(mniA0p^h+BCu;GbHv9{WgfBP_GrA>K%s)D;n@awYS8VG*QQK|}~_ ziW;Op{L+frsRN=bDWIZylxWEqNtZoB9T{~dkwE}=J%zdAq&uu%$!_17xH(+}H81A}jR;5Kb3U`{$_L*S z#!N_^o&v2l#c}Nw_e!gYy>A}g1O(@VaroZUD$fFkg8}x|<}4_uf=iTJABXuNd#-+L zY)CGg&6!^QPv^U*X=JGwkw;5E);(}hMvGtQU=Q*^@^|^t={Jit{-Q5Vf7LED?Y8W< z0ul#;@Z#oV=<`6}!!Mnv)g)XXoX^jnOBkf#(;*6t2SkAzxvg6%N=zV^pFmFNT%}8b z(EFX2dS3+T`JOQ{?)9e)8@)J{I=ZV=*+aO~#;;$OhJzIKq4a$#z|i%pUbnRtzBoTA z?QGXbDK--M?-PufcEW_e9S|^ojkaSIbzm8Jfh>h7%Fx0NS6iK)QuyM}WF8JEi`)BR zBd0o2<=(yfdvDI;>YSp$8+z%CW>!KO){k!ZLCch%JpXACQK*Y`!kmN#9CSYPnb2X9>+s|nzcys?Ggui;L#`d~JsPjg}2;*Q9(oix=HNM2Wlomite?S*^CoS&^7^@sp>wfpzQ+ zseIb%Fg~YTkE_+EF6xBCRH$GuhrqU&0qJqbmNJA-Q2SIj(}%l7$nYcWq9)*U=YgB{t-=PfLM)jos3SO`JYnnTExZFHiJssnNTyOEAx{v@pM+he$F7{w}W#yd6X}6I57k z=oot*Ej?^icO@VM=+DH59;hiZ%AU(r+g$%Jzl}jR zx=54>jkM`5?J$;ZaTf$A#CX_;CNK`ye++=J)ko(oA1~=M1zuZ}XZ;B!n>d^v-!}!Py@rr)LnYt+9M#k{{jBR`j=| z6Sh5O=-1J1yXQj(Xxb6IF@LQ{o0xlOIBMVWVUo9aqnxyn#!psz!w?4 zq8AGO`LAu;2wt@OhJKy72PK16*K&-NZF{4B;;#({s?uyWYo!GjsWc5Dz8k6 zD}71Y2sH#9RbH<5t5|NXu4Op}Yo{TD*cxE&$p!+J>y2c7DIn^kS}+3nY@7X`!|B$} z(0j+*REpEhDeuXB+mvPa5FH(>Ih_H&0B^dDI5mF|Fa(%LeRL$Lw*?0n@RU(-05}>` zQH>P<1BCcoMhG!+j288SbZ9u^sOID!9oZ zXsx)vTi{EN@O`{Wr6GRv!6JOl9`{qWm!}tZA3G5^P9dxc3k3aEjBot6&f5O>GwTB? znwHtBH`nKm`~q>InFS1xO9K-K3wlz|s}o6rAg9!RSAvJ=_<;<87Y1)KCdvNyE-u@; z1A)-fgM1{Xo@F?{+&V`HHCCbi4@wq}jxMa`bBYa${r%CEhO>viRyyu9Eoe%gQRyeQ z-5O3KfOOH<8Da4KSTP;1`Rl8e7~^xGhaqhrOgkr0x8ae00xUQ29!)!=sj})Y?RN07 z3TB%-OcuxH_{4$vrx_$y;N4t4mA9XTz-V5(ebOx?1=*0jbb@ZIJhDx`PK+jh$ot{4 z%;TyRxAAd4=Xc2;x8L#nRb@Aj4&My)kMAskoy?uTctgH>NwkA0s%^m(g4y03B!Y>! zcp69`Q+Oj!6^w5ci1C;=I&%cBUllT2K$IkIA6R7ljVd}0TMK2>^pe-%R+tEIE+DD& z+#8`r6PoS&@+9hhlk3p|W)90IHh=py;#=onpwN|CKq?|x=Jkrz@?-%CzSuu=+i=wqLJ#!(*H%=vMq-r?xBoH04BfEqC-hn5YirUix+aN0$JQp9tl;~-vIZ6 z(Us_|!F}>T03@!6Vzn*I!0T#r+} zX5i>1kQ8{y^HANUQGe-!_nI=~Rq=(OUoG!e4G!N%38DL& zL^gY-+oD&8IDm}!_3QfYUEN8jKW#sjZc~@mQ`21IloSPppxf~knpzgat_y3vr0ca%xz>2*-j-C2GD4ZZBTpF9_RYemoeW zB0b)*ESwF4`+|_(+QDev$B2%FTft?oA}_@YJAWXG1lR=FS(T)tm4bdg7HRfu+?9*0 zFV?Pq#=SVKHpQu?B!@t>R8DB4o|&r#uzwf4wX{&Y3cskx4nBuWqn|kU+p@x%1{W`O z&WNQ=C+lO7JtjeEW=cor5zH`mU7)`krS_FXOL<-<^f+(d+XSwdVsK;PB5HK^H;j3` z^AjeFb!(>U;V1FT%w0$K9jPlZXw!e@j5pm{^zxUXcdX#p@zzl%O%`bO5C&=5wfM6_ z$)MZx``~^dott3CN-(K>tfB`F&iN8Q5PzgHhgI}1o$!gb?=PP_a@h{>N~{g5y^vm_ z(paAeYsU5dVe`M=Pyvi+wk0G!dL1Z+ke6zQD*eH`ewF+=T03WqI_0u;6 zc_(O}24N4t5XV{bGSeX~v>!y#nl$7i%yuM5H;=nBqIhXwajpQC-oP z+l0?bczBqN4TNB6%P|f#+vTt>0lwXIXXtPLm2cea-_}XEO?M9{QNdI-7(-0ZjTZn| zlZ{g$q%Ft!#DKt)buj*}T*3r_v3i{(8I6Doo(YM?UvaoiYWsfN=6Pp;+Kw3XOX&hj z!c6fA+VA?MREMVw3_cSKYApc>ZgM9H%Oflx0=~pvHEKjXNjThMLj^&$ax7sC{T!~% z@wl9Yxdg0Ir>WH$g?V;7WS}Y;eW|xa+_p+!nM9HI7s;fqG`3_)v{KfgOHuVc!-U{I z+T-Zbz)z{iEH_w7JCJC$57!;ct+>2&f{T)Xu1;qs6Nk zsc0cg@{5bvn!-Ckrf-LruDlz!mV$p3{s z(sq3>1b(b9@M_@4b_6;)yg8I#B?$W5UdCg1IY7{@jOnX`baXgfR)YQbA-VGUKDrci znjDvTybSz^byw$QVaft*kalB?GqK-pm$CF++>JZb{FZI`@5h0*mwV#=O{n?Cr%Mys ze@^YIOm~^VTU$H`P(g+&S|SNxy z9RhL#|1pplSa`^8Re!XLQ~C7ir}bEO^B^JP)XK_*Cl=uTcuu6RO*j%W{%3$%pDdonqWhBFuaTPYEVFGJ{$yWVxv2@IL}S)Nc4~jy*acrE9Q3%u^X> z6*e_jheOtmL#0)CJVI^J`|7FT(}+B~FZ{qH5)(z;!i)IY{3B3y9sd=pj}W6QK!V6B zbKwqyd>R`tlX*+p(w`I&QOqIursZ1ITih@1_sd(wjh(}NX1|4Y68Vwr>&|v>fMw`Oaup0>%Dob9(VDGuK0oU(H4h9J0)jmK zlso3&t`P#KqoI+RBhX;qFLu51f^6n;Sgjqlf}srCnz;ycEia#pZ{NAfA2uWL-T9M) z5VU&CPw)q^IlHz%ocEm93hNPeY5sdlz3)NxZ={*M z{^ALtL9G${TT;d@pM#_ci~yrCh4=;@;XSR29(zA?xT2Sm7S_-B=g-HA0itmr>v?Fh z<^Dw5@^xq5Pt<Ajl!2OA~Y?J>l$ zpoExBXPr0m8>1$jaT=C<6#ZXsiGNlqi{8aWH;CImYA}zb!3*9J(20_z zG@EpiKW{9}^G3*u4!F!}%y8{4w%(N4rJdJ}+tD{)E1B>|?jMMun$kf%vkKxuD-BkQ zZv&(0o9XB&xu-wX&!;{U=nOzgqw;0H0&mp%%deF1Sa8KTQ5@+tSK1~3$}Z32T~Fj) z`R{^I)X9gxLCvLHk579uiwv$f^JajUQ$8Fr*DM_cyIiM+rQfEOti)~EtXBPMlhp&B zr8Ti@Urj!N0DC27Vg(Kg7;Qe`1B|;4BTVnOu@5dD zmynz*w(}Seuzn`Dq%^un-@W1$n6z=ruc1~y4|IJw8+gj2#@!w!eI8hH3p2I)T@kv= zVMgIy!mdN8S>QTzFSBm#b)WH_NBX~pBG9r_LapcqZ3EidYcTsKpZI~$JLQb^34RGK zAk5Tcrei1({wH7|D(@*S|Hurwdwp?Pozf~Y);H$+-@F_oQ^zBw4%c{RCjZkM64MG2 z(@>J7cQey&OdZ+7C3{0P41UIJ|GoN*E1=)3iw%3|tOpCx+yM@dr@P5-FbO5ar+BW5LmH-?E5~=bDrUdl2oFIF{ zRQ~ahGBOE)rB@T~7<>i0-l|r*E}3au@RlH0hxDTcsXv^MB<#~1yxE@T%*Ar=7XTjv zlj#cjDP~zt?mI4@rs|Y@*)bD}H8a{c`dXT<#S0RN!J^F0z%6xc38~fYwxpP-p@YdY zArNH?g)b`79Tt!u6BF-^mKZnJ*=ER{W=Y9^4j>p>TewkdOOt1NGf9%L)1Z?l`(3Yw z#PFe}Vo~C~zaq9@imDg3#Y%p(1&AKpTuFCKw{iWrb7xZYZRDR>S$6i^BDiN#u3em@?A!_NVJ8&|-IzNhHCFAGk z&%dDL2r(WNXxKwXJ8!7|%9UtdA78eYXiJWX{wvvauBz&g%<6wG$t0I@a3J9CHNZDO zax7Nl7!~Ozt)jB-h`Iau+)(@%WRaG-E%`Z;jh(QiM6DtUiXqC8)r$$ZivK$Y1Iw>l z9)~lx2aF$lNKUpj=^3k~{-RANTV#m+(B=}p?Pfw9_yaVoGQi>lZw+&ZA#AL$EE?jP>*EQ6iq&jY{&|ukU z-QoK>0L`J#7jWzZgYz{o0Xi>wq}7UVW!6jRy%wa(_N!&_|I~7}F-=`z96z@xz1mVQ z3={+%7e!YnSnM2%MWJ*t-VMSilp>qFL{eTfq6wfv@nSDzvQ0L;NK}Rj?W6@2nQpv$ zdHuku_y*`ESjj{&NGqbPP+|AZxDWff?3eTLkq?5`e~;am_c9$9vzq=ll~L^{~-vnq1klKfJi3TW?9z5 zZEiQYRKc_Mql-JmVb}44MW+gmzj7AiZGp;)P?mSz++LqeyZ! zBblT5J%^4UqZe+!x|Dv~bgU5R&)hq1db=EzHX~lTpvgN+Li-apo6=FjSz_~AU&alH z=1sD{_t#FaJlm${eOh@&H-1VWumcmdRkIv*eLnytz*>h*>UYC0xlJJ7Pb=n7-k@@s zqZ*O}La>vow1x}K@m#4< z1aPG4LtF~Z$Zx6278dk-YHgudlWzK9OXz-{0O)sdL46$76obWq#HCh2_PsOD_kgZK zq-wD#0A{uu>fhc_vQlL|7FR;Jm5sYspNIa8eSAG;4U+>WEg1(QXW9x!D@4G8>gkN`xK3`z|f!x0>YmdCz%pJ_y0a@4KFQWQNQy;`HJUb&C9#<#b z&_xjKThZ?Cz>J;i4qZ-kww1mzy-zopO|O^HZN0|?IpsBc3Q4|%RF#qIYwsFsuBd+m za*Y4$iT1HzppGo;Mhca#Tw@;EEd{TjZVtL%L*^fnMmrWN>6}CO5=gvSYpB!2`*E^a zsTs3}-9gKSClk(+ZYUKtMh-mK`4Mr@9!C9H+w*G3DXGhFykbFcR~k436kj$6q%ZOe zhXdr;oA9#X6mNY~rLVE=%;G~|Pk3)G03oT2RGL>o##qLL7_g7M@ z!KGMlJ`rN1Fa0Rg${Crh@M#U)`p#eI-1J-&rM%oVw>#EOu{uNkMU+uQ7A5Vp7s|1? z<4)@Y)-7sss)lShNj9j)ABL>43f6Am1E3+teESj->jGC$KixKkV6IAI`TM5f-SCb=F&_m*9A3^xo=ZrKJWW|f9J+UJEWMfv@iq$5kpxa zEq0`0RiwA&i?Wm{Nsx`hjKgseo_ux#ew@mkye*uAP|v*+%J?moAwnvcp78j ziupOh9~18r?FR|-!9<2eU_yg@kHz^##{@-$AJf%3simuNED(cpc$$01E89(j z)!FbZs;h4-X2f(UIenvIb!l!=ap!%-$QGxya&-y+Wq4`*ds)1t-sHgimS$?3Ct619PI=uO{h7SQZFgsbX*6 zu5d$v`f&9I9`TLcYtw&{gDtF3rOLV1(x!jBy*#4@f1jy?H1S+1=2Zj~oa|xRkhH7G zgAadv8BTCgKj*wo_rd-gYe^}@sR8b}WTjcCJD*08oW<&2NbqK zVhqefjy5_|r5PMR5@-(?^+f1lb>790{qC?Xq&|{q@iz_|HVT|JJHbSI3!dZ)ecG8^ z1I{wWc4PRO#G6n{^wgYPNWxK=$gdfnuSt{PzCP$iMbaUk=NZU+_3p)^BXSq*;YU4!C#thad}tLylC$+9Xmb(4trAp1dVOCnsUxeCDVALJ*+^ zBU0b}d-B7s-F-E)%ZT2ON-zajUt?d3E;SqXi|ti{BTI!X4obx=QUWswz-P?M6Gd%9XWxSzy zj2-f6H?-?2M+~?Cs3tv~HVj13PB3o~RB6NIKQhfw_D*N*SLqy_8X_cr+ZZXfPb57} zXi6aTUyJU7(PLGJVb0m>fyCI?a!jEtQ!byJhJ(R4v*s6rv; zy`!XZn1BJV#=9l|gmzr9c1#C6P1JSP*^^(^=u;XS%GiP^bqXhBu@o+hGlcAW>GG7$ zVRoBxS#(vzQCN)kFW{}z|Hw08jaCdg9?5@_>S<1mMm?8qm!F~$pWVwNryUEj&>uuY zWlMa{@D}9qDz-JfebGCU6A-F!2cy}@E5$>h&1o`Kyx*`7kQ~QUmF`V!td)3%4eJHw zLR@$%>(l0Rd*a|#KIpNY*3w_6=fp!-jpEPKm)bMhS16O4IXF z6sb0ANBA-L@F;G1xP_}puGo)p(xdoVP%mXBra3s@sf9rB>O!Tlo^yWh0M{J+ST=3} z)Br-~i5+N@1+i!mgn@WYA8@@ohAhOmaSQa#f~!eVus$p9`FC7bMI8h|6g_hq+{~65 z;UbQT2DO#bk=%mic6w`OFht*Je^T6mMO8s9+#lG8gbnm(JpRw0OdrJI9y?H+e_S0n z585-gpX;zgiAgO9e$8WQ4w-^zJ;O4~UT?=6Ab@gs1FNJO4sXBjfGQQu%`ijK;MZl!}F2cd1UJH9mT3h z0TmU;706v1>98{f@p}LGcSyYAnjpR(%K|t_n+*~0Ikq{&dvnJEl}s!R=hLdIn-w>K zq>#OmVWW`(%MD{m{p>dR$#(rWrytMo&G>U7l)tI0<>S-F*@$L=+RY763_v1q9ta^~ zud_1o!)11Euu=Dz7Q2vrs{8(A&W{7vCsMy@qK2@G!0+K=6L!5eNs?<$jBk{5liYcF zO6Z4#UwdNHHQ@q5c?UlOTHYjrKK?G%nw*b$vm?Kz0zn1v4q+AS#=S}4T@oT;H~r{d zM7zD8sM*WA!Zo;TN>*4yQ)jqP?VDB)gs5YuQc5|ZgH;VY1;o9zNwvSWE6*x1ztqvP zuv^wiqAk2FgB3~jlkrJvD1Zcb(ksK;^?2NcQl9K4+Rt|%dqNK?^bvO{qRrW62csg`MM3Z6yCbk~c4AdYRe24(8&WTL2#DE1p}RCKm0}dI-R&*$miADEfYOu;hZd+wegY z0rH5s$R)R!TLRQP;-3Ux=OYOW8gBRgNdDNr`i z#U1^JVAr@tZH;I8ylkys%szDDpImYOmM(Y=l?!&Ek|Id64LH_eMK0HNT(Kdh`A*uA zI~?V1T5v^imn#6p8{7M5MbC8?)fK$UKCTRE@HnEWQra|2uqW&kuh8$?e+~bZIlVY1PVxdI}|BlVnQ` zM=3N6H{9O1MW|JpJs!jq-Ft)!l%6!%b(8qm)H%<#0Svsa7~W3Z%N6(d-AaY4J@22UIoE$bBgerehUuYFZ!j=H%bW z#@1m=c-L0!cmLN~y&bvJ-^LmTZH=d;6CDwCkYttE zKrjUiQ0ZbOJTvI68rZ1!W^Ed;!xHoDJIv*ee#vJ^U!4&e$KdTI2!zi;a@B26G`7e8 z!L0Aa@O{w6`ABLOac9H=*(z8t(deMKStyTsw8*j-Uih2j{lWf>oA%DVNJNz0=*)vV zpdg;xfX;1Qz@?KLg{|=*J^NePZ@E$~048tRDU0&?A~F(WbMFnY6I7%xzBMUHE$BcCe+!=! zZyZYcac3=Q7|lpxoTHD}7&p0;K1HJO*Ofr~pR4Pzq@KrD;4!s?`?@>TU{y8At?u3g z%;=o3ZoW`ngSa<|+L1R|OJF!y9%o=I(UZ{RjGu{LYO$qZ5d|Ckj9|w4SfKWi8=nSWDUGO?qCTx%HXjrdL#gl~-)YtmzG#I{&Pj!PVfWAVOgz*)fcI9Q6;x%rL@RIu$$>vJ}Yz9(jaQpd%PgW(`aCh`TlnQkBd zkhZDaXquuSto^nyt@$R-yp&!xq2(QRhu2Hk9hw7LdjKOBg1$}#`1a^I^-nW_xFLgA#kzwzP}z! z7R9!QUVSsJ0Jn@PcBZpm3UFz9hogxg1>syQZNS~C{jkD~E&GOhxR;yV&271kThrRq z!|g?bo4_@=abHxXzx2#m+kGa%??kf+@Qw31=)-=^1o1zsL)b8&DB=Md7Usf(V64Na78{tRB z5ynAp(JAGiUUo%ZT|BLeVpqzQ_<*d+!Xz&zbXD*cS#0V6Mu0?nuOHa?VtpiKHhxc{ zQ8vNfY}Hgmc~f$5IRce>?bI%3ciLbLKC-&qw(9BGw0jCw9k%F0?+IJH1B`_&>M*`) zu{zFEBY5YbX5Jj8RxCDA98K}!Jr?wa-L})QWqaq1iyE<;+u_Qp?eyHqtXB`|n#O~B zJTpF=M#5SCa6zq#x@SrYiVFzoznP_}Po+(;-_~tQ01+F(C&9;MNALj9s1PMh{zni? znz|Kw)VV`;icWlHuDp=NaS6)7?+W{EHWRweC4Q4Lq9c_(L_R{UV@Z^Fn>Hb-r=~n# z?-7PFs(~25sgqVH^EJ-_fvB|wYxH01`$RGHx4Y{SC4a5yt5`Gto$k!ppQTVlAe(*x%;q6+Errt& z7c5MXpnV@%UcX8HzJx}_a6;&3A7K~w;A2`Vwl`0hML`d1OvW6t-2)&qGyC!41KinUU8 zs?wY|9R0mm1=YaQCEPL3&KI1m^bF0Xn-xveeb@x1XX{=?G^iA87%*4US3zn8jcP2%t~}L)lJ~O)4Jx^C+GpAyYahX^wr-pQauVoN9a&@%aD~Dt32ta zE4Lm^cb~y#0x+~<4>4%*R2&buiXD-{oF#UBKSE*-yaTGoqb_H1I0B5@b=~$5L&v3b zp#-TZ!4!TYzt^d(4_g*Mr}9SZW7))9Rq$OAccK0Nyg#x){o_9l-xcy}b`zCvWPbo( Pr$JB_c8Evkynp#GVN97$ literal 0 HcmV?d00001 diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_8_0.png b/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_8_0.png new file mode 100644 index 0000000000000000000000000000000000000000..49c588de350722c337303f3dbd9d5ac0507350b9 GIT binary patch literal 5035 zcmZ{o2|Sef>c1~3?{u5`ocLAl&|2$ zqtO6&sFY}SyXone^A zsjB%JZDpyIX>K8+9dpH)G)T^WDid5 zO0XVy-=4vxqD=33OWkE=KL>cC!-h4t)dSNQduucw`Wb{;bpCc$WIp{++1UW$9od@# ztHKleYo6!$kL|#p1hfEkK(Wr2Llc;uS?~L)c*d_ava&IYW=84x_K7YRY!KQyd!=@% z{>7EyYLTE@Zb5=F78^7oT+|P1+#27^G$9ll8xHC`GYo*wrzW#kkk(_C2ZHQ(ux@^| z=^HLOf1#K5Zg$VYt(cuJ%#QSR7<;+Ye0Z5rMF~orI2bmp1qhQGBMi)I+YaVTDv&<2P??J8egP-#YV~Wx7Tjt+G=mpbgfLh=JSylK*iYs ztplT+OYHe|&$BRw^MMnD&s-nsnHWoUE=?2gxWd9tz&*qc=IKi$$+#j&B55FY`bUz= zVhW(L5*%e<9;{GD;3!Rt0C}Lrzuya|Pt|=B#qzr$IF)>FXVZD3&_2U}QM3JgB1!U) zSV%)#VkJ1rD7&S;i*m0*EQuqN_QCNAXz5>4KVDQ~srmX4>oCl1KHaHSk`osdsf}M} z9;SUb;Uu#waM9rX6=@<`*R`ua*%D_i^XB;#H*l^mv<_vgz76ttIrl6y`fU?kNDFwGQMZV5Ft3OUCsi}w(khEz&U0qhA$3VVFN5Wu~4hJ zS@BO#rhVwj1xcDQWIm}VQ0{Ym^rUiP4%hh}i&jBDse96-$H}1mYDir)a&_UC*n7_yuV{Y3oeH!yN8*TMT$pM%9 zn?|NBrVQIN!=Y)WKeaxfCbe0)L$e5Gi91U4-ZM1*^5uAmMJM%-ULw!at2#UXXpa0x zv}3-;RaW6ndyKDYi0N+@R6g zb$zjMgoo5EWC%Ul-m2jdy#1UA1)Ku*k{d>k1mMT^^RF@Xj`bDq;hW(doR2vya78pt zT=3OZBP-MerG|^5(mL%^7G$tsY#gU`M%Ai`mEAP%CVh3bTI* zSW5iW=<*lZO@dl`tbOo9MnC&go!~Y5lg%`r{Yf!`Vzu)sd;zv0yXra3Q*Rp+)=z|u z90?euoaVUgt~!EHa4rp(RKEQh9R6HUSH`M;NbUTEHut3{t1lgZzq+Tm$#+RAhDOe5 zddcKfB3BX~qLLf^)=6GHRKfsx@D1;Ld5vx|_LmcRMSoF*2q-@B7VcbbBuO+o*o;?iCLUS4c z>!BSev#Q7>#pE$+QWxM0)rlRnfOd^qTJ7hhh=J{SlltAsmuV9DZ|Ug?d2w=>vW{_k zIUW%-J3G4R45mzxS(W}p>OMGmZ1-&1%sH|v^?j^TKfNj)?Rd+?G>hgtG7|un&czON zobY=CxMtA@GH5fP25`C$>_NB8i6Khk3}myO0GG<6SX-tqUjywk=NwrP{lpr&{{}Kw z{8kV|8RMhiVTR%h2yuKQsI9El#3m}#=(X{l;KRdR{KKX~Y%4Q9uLFi*^znnAYa<;4ZMz`N8v3pqIzUi?7&> zY4MxqzV4uZ$XRk){=Br2asro2lC>iKce-15M+7Z@QJ^B*l` zIO094?S~P!8K5(uuLUJ|6y`)=90qx(Ign(Tu&sebYYe`*l8G?cuqh3}=#0{;p_4cT|v zlI0hjr`OpjCRe7oNg?mzf9Z%x(NdEL%-;GD&?Ye%hv_#tHms}Buf8ZRYQXUR$X=?7 z{UC`6KBX;8>ari#yT<<8aZbkEnp7n%gPk5)Ti+J8rRvo~Pn?WX8#bvJ*D5Fn8UR_6 z4zuc)7WD}%|5No?I(5Z{EYpN+>M0@L9gZVw;sGY$#VrkM(MNb}NqVrB;4t+_^#M09 z*GJYRZ*0>3z~f2EhfC}iiB#!%w#(kCm_3W>KnmVSm@@4BQi>3VZ!R2K{NNcAu7pON zU&KAuvEy!NOq9ZoAC|j9yI465BAIzQ&D+fGWe|k-l^pQGll;jUPD0)$t=j;artMP) zIgIZ|M@tCIwc2+wIFQHa(-67&&=R2O8TTOQk{DB>=g4a3alc|v6B=NRvV$mD;--RZ zEQ#X3ccto1{Rqk?GQYKJ8~P$-)HZa!&$EYjXEV0#|2tk(T+;)~a3HXAu^5nMTd=R~ z7>H|oNNl)Ku|xK(R;S&W7LX`zLIS{CUfsMabK+56bf+jAE9;<>P|P1zNhR6dLnNoa8;C_l;PIi;s&rpCGO!X?A7<_COz?x?Uz?zi3R zUJlzCb!u=;9++TvCr;E6)Vw&?7*?q#fn*>qRUt%$S)J9Nac6=OSI=<7ms=Tn@M6)r z)?ucmccWe%`YYhrIj%^p*`fY*{^bMHFwywjrTNtQ7U!awxPO2edm9un2fWA>-^ouUEgGnv|Z4t#b9~$R^|wd4dUg7(F_{ zeee{(-oJbB%+#%$jA58n$Rkz0JW!PC0AE2aFqZYFZKg{gPuUI<-pT#T+pWHIH46qo zTSGLp5yLNRWm+fHGE4yjd zoX=KP*>zAfcKiOu?8)za6`+laF*Pk>jZpzY4Jw#ubn%s-#b$F9@+>>ma&OC5^mL_W zIuJUoa2NFZ$M4(#1<`E_I=4*@L?@JpZRj99n@1V1A*#in8Zli@Ke#Zh*8k1+f`kTG zL<0i7=lT<{yF%>DS@YhmRA~o@f)Ow&?UGe)2$2EEm)FA4-KcqUlsI!E> z5zp;74h=2$ZP!72rD#dDvV=d#R!lYnMK8%^IdE?7oBP_%Fr~-Zu2p#n{J=z&^K9^c z5*->dgcwFDj8VKe1#M$@O*wRZEFX3zV)k7!$XDT z4NWYe_5Ybw9?7Wkr&9M!TXMe{45EU;NX$e`N+sRjFWscr)KVR3yeKpZwZOqOf|M7t z1TmrA5mvTy9I`*oWQVJ?hgb-rU6arHwV4n{UfnT`(TUsUg=!^<0-Tl0WtP3pU-fvB2;o&R|(nkLvAd2^eM+=x8UNl-&Zy?y%Hh;NkGzvvACQ!IH`CKnwfC8CDccU8=vSlF$x4Q|RTHwL(;ESyS0elLj4;o~@Kj%Zy z#4gG|9a4qc5SZ}Ypgp0YLDrEtNHo#P_HZqI=_LLtp}TY`NC&KKSi%e2cKn}qzT0_$ zl^j}Z0PbIW=|}B4YazVlR0DU`q2I|68=eQhBwy#1eraCVP$3;%e3mqs_=C;df!x6< z`kIvA(#mpu=(I)2)W?{qw$}5@e*fF8#}d*RQxfgSBmjhJ4)%E$E98;Han2n<%;$uK zg8jeNo+hN&f(;H&6+CG3ku5sY=pLQ>O}wc?=z~v@8khAjaZbZ`T6JF5|I3eAE_Lg7 z1s%>GRj5<%21(#^yk*@&ZJ-ZX6Qw-hSuB@ptTJZ&(Yi*Lv@~#IvQo=YR9}|wnG44! zU;MOY9KpV7)BM8-Tn6qQx^Odk+o7ODu~j{M9?~k6N39_@>^ri$yPQU|hc;`Do7?@* zN~|?4o{B!+U41uw3CDe?hn?8V|8yctRrjp5y4>`LAeN zb8!#XAE^KvcKT*oG&a=%JYlDx3>8LH`H1N=z;ox6QptPDBo$-N?vD-+3de^n&YD>f zb#!=*>sup2j;5R)p{s1WbT9EF`S?cy z6}jePZ6nH!$=Xck{y*2yDX&u+{7_&IcPi}IM8zB+YF2#Co8h$ge%U!ENhge$xiZI1 z_20?v#{4Ha9$`P~9-)|XkgUiHRd}O^N{{ttr#deJvvh6bO?VYYDdF(_+RVPBY}T4K zFZ>RAx@Ye54ZsxnzPGn}SMOhu@ztx1c1up+AkPIBUU?(EMJ3+fnTcL+NNy82vtN`g zFD&h3Pn|@Hnl(pD8j(#|Lqpr9#5W?%7Ch@y;$V`g7?$NFmw_I?_hKd0loH){6atu$ zi32&{ONE*@457o)7N=5YC7LD~UWKt7t-_83Th4$y$)enHX jssHbF(x!)$eLW^m7j? Date: Sun, 21 Nov 2021 22:39:18 +0900 Subject: [PATCH 419/940] clean up SLAM docs (#572) * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs --- .../lidar_to_grid_map_tutorial.ipynb | 318 --- SLAM/EKFSLAM/ekf_slam.ipynb | 1784 ----------------- SLAM/FastSLAM1/FastSLAM1.ipynb | 676 ------- SLAM/FastSLAM1/animation.png | Bin 44443 -> 0 bytes SLAM/GraphBasedSLAM/LaTeX/.gitignore | 3 - SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib | 30 - .../LaTeX/graphSLAM_formulation.tex | 175 -- .../graphSLAM_SE2_example.ipynb | 332 --- SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf | Bin 276368 -> 0 bytes docs/_static/custom.css | 23 + docs/conf.py | 5 +- ...g_started.rst => getting_started_main.rst} | 0 docs/{index.rst => index_main.rst} | 0 ...igation.rst => aerial_navigation_main.rst} | 0 .../{appendix.rst => appendix_main.rst} | 0 ...navigation.rst => arm_navigation_main.rst} | 0 ...introduction.rst => introduction_main.rst} | 0 ...localization.rst => localization_main.rst} | 0 .../mapping/{mapping.rst => mapping_main.rst} | 0 ...th_planning.rst => path_planning_main.rst} | 0 ...th_tracking.rst => path_tracking_main.rst} | 0 docs/modules/slam/FastSLAM1.rst | 17 +- docs/modules/slam/ekf_slam.rst | 593 ++++++ .../slam/ekf_slam_files/ekf_slam_1_0.png | Bin docs/modules/slam/graphSLAM_SE2_example.rst | 209 ++ .../Graph_SLAM_optimization.gif | Bin .../graphSLAM_SE2_example_13_0.png | Bin 0 -> 32748 bytes .../graphSLAM_SE2_example_15_0.png | Bin 0 -> 30123 bytes .../graphSLAM_SE2_example_16_0.png | Bin 0 -> 29350 bytes .../graphSLAM_SE2_example_4_0.png | Bin 0 -> 52368 bytes .../graphSLAM_SE2_example_8_0.png | Bin 0 -> 31076 bytes .../graphSLAM_SE2_example_9_0.png | Bin 0 -> 49650 bytes docs/modules/slam/graphSLAM_doc.rst | 557 +++++ docs/modules/slam/graphSLAM_formulation.rst | 216 ++ docs/modules/slam/{slam.rst => slam_main.rst} | 34 +- 35 files changed, 1617 insertions(+), 3355 deletions(-) delete mode 100644 Mapping/lidar_to_grid_map/lidar_to_grid_map_tutorial.ipynb delete mode 100644 SLAM/EKFSLAM/ekf_slam.ipynb delete mode 100644 SLAM/FastSLAM1/FastSLAM1.ipynb delete mode 100644 SLAM/FastSLAM1/animation.png delete mode 100644 SLAM/GraphBasedSLAM/LaTeX/.gitignore delete mode 100644 SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib delete mode 100644 SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex delete mode 100644 SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb delete mode 100644 SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf create mode 100644 docs/_static/custom.css rename docs/{getting_started.rst => getting_started_main.rst} (100%) rename docs/{index.rst => index_main.rst} (100%) rename docs/modules/aerial_navigation/{aerial_navigation.rst => aerial_navigation_main.rst} (100%) rename docs/modules/appendix/{appendix.rst => appendix_main.rst} (100%) rename docs/modules/arm_navigation/{arm_navigation.rst => arm_navigation_main.rst} (100%) rename docs/modules/{introduction.rst => introduction_main.rst} (100%) rename docs/modules/localization/{localization.rst => localization_main.rst} (100%) rename docs/modules/mapping/{mapping.rst => mapping_main.rst} (100%) rename docs/modules/path_planning/{path_planning.rst => path_planning_main.rst} (100%) rename docs/modules/path_tracking/{path_tracking.rst => path_tracking_main.rst} (100%) create mode 100644 docs/modules/slam/ekf_slam.rst rename SLAM/EKFSLAM/animation.png => docs/modules/slam/ekf_slam_files/ekf_slam_1_0.png (100%) create mode 100644 docs/modules/slam/graphSLAM_SE2_example.rst rename {SLAM/GraphBasedSLAM/images => docs/modules/slam/graphSLAM_SE2_example_files}/Graph_SLAM_optimization.gif (100%) create mode 100644 docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png create mode 100644 docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png create mode 100644 docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png create mode 100644 docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png create mode 100644 docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png create mode 100644 docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png create mode 100644 docs/modules/slam/graphSLAM_doc.rst create mode 100644 docs/modules/slam/graphSLAM_formulation.rst rename docs/modules/slam/{slam.rst => slam_main.rst} (75%) diff --git a/Mapping/lidar_to_grid_map/lidar_to_grid_map_tutorial.ipynb b/Mapping/lidar_to_grid_map/lidar_to_grid_map_tutorial.ipynb deleted file mode 100644 index 9e8a00f009..0000000000 --- a/Mapping/lidar_to_grid_map/lidar_to_grid_map_tutorial.ipynb +++ /dev/null @@ -1,318 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## LIDAR to 2D grid map example\n", - "\n", - "This simple tutorial shows how to read LIDAR (range) measurements from a file and convert it to occupancy grid.\n", - "\n", - "Occupancy grid maps (_Hans Moravec, A.E. Elfes: High resolution maps from wide angle sonar, Proc. IEEE Int. Conf. Robotics Autom. (1985)_) are a popular, probabilistic approach to represent the environment. The grid is basically discrete representation of the environment, which shows if a grid cell is occupied or not. Here the map is represented as a `numpy array`, and numbers close to 1 means the cell is occupied (_marked with red on the next image_), numbers close to 0 means they are free (_marked with green_). The grid has the ability to represent unknown (unobserved) areas, which are close to 0.5.\n", - "\n", - "![Example](grid_map_example.png)\n", - "\n", - "\n", - "In order to construct the grid map from the measurement we need to discretise the values. But, first let's need to `import` some necessary packages." - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [], - "source": [ - "import math\n", - "import numpy as np\n", - "import matplotlib.pyplot as plt\n", - "from math import cos, sin, radians, pi" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The measurement file contains the distances and the corresponding angles in a `csv` (comma separated values) format. Let's write the `file_read` method:" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "def file_read(f):\n", - " \"\"\"\n", - " Reading LIDAR laser beams (angles and corresponding distance data)\n", - " \"\"\"\n", - " measures = [line.split(\",\") for line in open(f)]\n", - " angles = []\n", - " distances = []\n", - " for measure in measures:\n", - " angles.append(float(measure[0]))\n", - " distances.append(float(measure[1]))\n", - " angles = np.array(angles)\n", - " distances = np.array(distances)\n", - " return angles, distances" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "From the distances and the angles it is easy to determine the `x` and `y` coordinates with `sin` and `cos`. \n", - "In order to display it `matplotlib.pyplot` (`plt`) is used." - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "

" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "ang, dist = file_read(\"lidar01.csv\")\n", - "ox = np.sin(ang) * dist\n", - "oy = np.cos(ang) * dist\n", - "plt.figure(figsize=(6,10))\n", - "plt.plot([oy, np.zeros(np.size(oy))], [ox, np.zeros(np.size(oy))], \"ro-\") # lines from 0,0 to the \n", - "plt.axis(\"equal\")\n", - "bottom, top = plt.ylim() # return the current ylim\n", - "plt.ylim((top, bottom)) # rescale y axis, to match the grid orientation\n", - "plt.grid(True)\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The `lidar_to_grid_map.py` contains handy functions which can used to convert a 2D range measurement to a grid map. For example the `bresenham` gives the a straight line between two points in a grid map. Let's see how this works." - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "import lidar_to_grid_map as lg\n", - "map1 = np.ones((50, 50)) * 0.5\n", - "line = lg.bresenham((2, 2), (40, 30))\n", - "for l in line:\n", - " map1[l[0]][l[1]] = 1\n", - "plt.imshow(map1)\n", - "plt.colorbar()\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "line = lg.bresenham((2, 30), (40, 30))\n", - "for l in line:\n", - " map1[l[0]][l[1]] = 1\n", - "line = lg.bresenham((2, 30), (2, 2))\n", - "for l in line:\n", - " map1[l[0]][l[1]] = 1\n", - "plt.imshow(map1)\n", - "plt.colorbar()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "To fill empty areas, a queue-based algorithm can be used that can be used on an initialized occupancy map. The center point is given: the algorithm checks for neighbour elements in each iteration, and stops expansion on obstacles and free boundaries." - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [], - "source": [ - "from collections import deque\n", - "def flood_fill(cpoint, pmap):\n", - " \"\"\"\n", - " cpoint: starting point (x,y) of fill\n", - " pmap: occupancy map generated from Bresenham ray-tracing\n", - " \"\"\"\n", - " # Fill empty areas with queue method\n", - " sx, sy = pmap.shape\n", - " fringe = deque()\n", - " fringe.appendleft(cpoint)\n", - " while fringe:\n", - " n = fringe.pop()\n", - " nx, ny = n\n", - " # West\n", - " if nx > 0:\n", - " if pmap[nx - 1, ny] == 0.5:\n", - " pmap[nx - 1, ny] = 0.0\n", - " fringe.appendleft((nx - 1, ny))\n", - " # East\n", - " if nx < sx - 1:\n", - " if pmap[nx + 1, ny] == 0.5:\n", - " pmap[nx + 1, ny] = 0.0\n", - " fringe.appendleft((nx + 1, ny))\n", - " # North\n", - " if ny > 0:\n", - " if pmap[nx, ny - 1] == 0.5:\n", - " pmap[nx, ny - 1] = 0.0\n", - " fringe.appendleft((nx, ny - 1))\n", - " # South\n", - " if ny < sy - 1:\n", - " if pmap[nx, ny + 1] == 0.5:\n", - " pmap[nx, ny + 1] = 0.0\n", - " fringe.appendleft((nx, ny + 1))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "This algotihm will fill the area bounded by the yellow lines starting from a center point (e.g. (10, 20)) with zeros:" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "flood_fill((10, 20), map1)\n", - "map_float = np.array(map1)/10.0\n", - "plt.imshow(map1)\n", - "plt.colorbar()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Let's use this flood fill on real data:" - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "The grid map is 150 x 100 .\n" - ] - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "xyreso = 0.02 # x-y grid resolution\n", - "yawreso = math.radians(3.1) # yaw angle resolution [rad]\n", - "ang, dist = file_read(\"lidar01.csv\")\n", - "ox = np.sin(ang) * dist\n", - "oy = np.cos(ang) * dist\n", - "pmap, minx, maxx, miny, maxy, xyreso = lg.generate_ray_casting_grid_map(ox, oy, xyreso, False)\n", - "xyres = np.array(pmap).shape\n", - "plt.figure(figsize=(20,8))\n", - "plt.subplot(122)\n", - "plt.imshow(pmap, cmap = \"PiYG_r\") \n", - "plt.clim(-0.4, 1.4)\n", - "plt.gca().set_xticks(np.arange(-.5, xyres[1], 1), minor = True)\n", - "plt.gca().set_yticks(np.arange(-.5, xyres[0], 1), minor = True)\n", - "plt.grid(True, which=\"minor\", color=\"w\", linewidth = .6, alpha = 0.5)\n", - "plt.colorbar()\n", - "plt.show()" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.7.3" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/SLAM/EKFSLAM/ekf_slam.ipynb b/SLAM/EKFSLAM/ekf_slam.ipynb deleted file mode 100644 index 7634bfde9e..0000000000 --- a/SLAM/EKFSLAM/ekf_slam.ipynb +++ /dev/null @@ -1,1784 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# EKF SLAM" - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "" - ] - }, - "execution_count": 1, - "metadata": { - "image/png": { - "width": 600 - } - }, - "output_type": "execute_result" - } - ], - "source": [ - "from IPython.display import Image\n", - "Image(filename=\"animation.png\",width=600)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Simulation\n", - "\n", - "This is a simulation of EKF SLAM. \n", - "\n", - "- Black stars: landmarks\n", - "- Green crosses: estimates of landmark positions\n", - "- Black line: dead reckoning \n", - "- Blue line: ground truth\n", - "- Red line: EKF SLAM position estimation" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Introduction\n", - "\n", - "EKF SLAM models the SLAM problem in a single EKF where the modeled state is both the pose $(x, y, \\theta)$ and \n", - "an array of landmarks $[(x_1, y_1), (x_2, x_y), ... , (x_n, y_n)]$ for $n$ landmarks. The covariance between each of the positions and landmarks are also tracked. " - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "$\\begin{equation}\n", - "X = \\begin{bmatrix} x \\\\ y \\\\ \\theta \\\\ x_1 \\\\ y_1 \\\\ x_2 \\\\ y_2 \\\\ \\dots \\\\ x_n \\\\ y_n \\end{bmatrix}\n", - "\\end{equation}$\n", - "\n", - "$\\begin{equation}\n", - "P = \\begin{bmatrix} \n", - "\\sigma_{xx} & \\sigma_{xy} & \\sigma_{x\\theta} & \\sigma_{xx_1} & \\sigma_{xy_1} & \\sigma_{xx_2} & \\sigma_{xy_2} & \\dots & \\sigma_{xx_n} & \\sigma_{xy_n} \\\\\n", - "\\sigma_{yx} & \\sigma_{yy} & \\sigma_{y\\theta} & \\sigma_{yx_1} & \\sigma_{yy_1} & \\sigma_{yx_2} & \\sigma_{yy_2} & \\dots & \\sigma_{yx_n} & \\sigma_{yy_n} \\\\\n", - " & & & & \\vdots & & & & & \\\\\n", - "\\sigma_{x_nx} & \\sigma_{x_ny} & \\sigma_{x_n\\theta} & \\sigma_{x_nx_1} & \\sigma_{x_ny_1} & \\sigma_{x_nx_2} & \\sigma_{x_ny_2} & \\dots & \\sigma_{x_nx_n} & \\sigma_{x_ny_n}\n", - "\\end{bmatrix}\n", - "\\end{equation}$" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "A single estimate of the pose is tracked over time, while the confidence in the pose is tracked by the \n", - "covariance matrix $P$. $P$ is a symmetric square matrix whith each element in the matrix corresponding to the \n", - "covariance between two parts of the system. For example, $\\sigma_{xy}$ represents the covariance between the \n", - "belief of $x$ and $y$ and is equal to $\\sigma_{yx}$. \n", - "\n", - "The state can be represented more concisely as follows. " - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "$\\begin{equation}\n", - "X = \\begin{bmatrix} x \\\\ m \\end{bmatrix}\n", - "\\end{equation}$\n", - "$\\begin{equation}\n", - "P = \\begin{bmatrix} \n", - "\\Sigma_{xx} & \\Sigma_{xm}\\\\\n", - "\\Sigma_{mx} & \\Sigma_{mm}\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation}$" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Here the state simplifies to a combination of pose ($x$) and map ($m$). The covariance matrix becomes easier to \n", - "understand and simply reads as the uncertainty of the robots pose ($\\Sigma_{xx}$), the uncertainty of the \n", - "map ($\\Sigma_{mm}$), and the uncertainty of the robots pose with respect to the map and vice versa \n", - "($\\Sigma_{xm}$, $\\Sigma_{mx}$).\n", - "\n", - "Take care to note the difference between $X$ (state) and $x$ (pose). " - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "\"\"\"\n", - "Extended Kalman Filter SLAM example\n", - "original author: Atsushi Sakai (@Atsushi_twi)\n", - "notebook author: Andrew Tu (drewtu2)\n", - "\"\"\"\n", - "\n", - "import math\n", - "import numpy as np\n", - "%matplotlib notebook\n", - "import matplotlib.pyplot as plt\n", - "\n", - "\n", - "# EKF state covariance\n", - "Cx = np.diag([0.5, 0.5, np.deg2rad(30.0)])**2 # Change in covariance\n", - "\n", - "# Simulation parameter\n", - "Qsim = np.diag([0.2, np.deg2rad(1.0)])**2 # Sensor Noise\n", - "Rsim = np.diag([1.0, np.deg2rad(10.0)])**2 # Process Noise\n", - "\n", - "DT = 0.1 # time tick [s]\n", - "SIM_TIME = 50.0 # simulation time [s]\n", - "MAX_RANGE = 20.0 # maximum observation range\n", - "M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association.\n", - "STATE_SIZE = 3 # State size [x,y,yaw]\n", - "LM_SIZE = 2 # LM state size [x,y]\n", - "\n", - "show_animation = True" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Algorithm Walkthrough\n", - "\n", - "At each time step, the following is done. \n", - "- predict the new state using the control functions\n", - "- update the belief in landmark positions based on the estimated state and measurements" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [], - "source": [ - "def ekf_slam(xEst, PEst, u, z):\n", - " \"\"\"\n", - " Performs an iteration of EKF SLAM from the available information. \n", - " \n", - " :param xEst: the belief in last position\n", - " :param PEst: the uncertainty in last position\n", - " :param u: the control function applied to the last position \n", - " :param z: measurements at this step\n", - " :returns: the next estimated position and associated covariance\n", - " \"\"\"\n", - " S = STATE_SIZE\n", - "\n", - " # Predict\n", - " xEst, PEst, G, Fx = predict(xEst, PEst, u)\n", - " initP = np.eye(2)\n", - "\n", - " # Update\n", - " xEst, PEst = update(xEst, PEst, u, z, initP)\n", - "\n", - " return xEst, PEst\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## 1- Predict\n", - "**Predict State update:** The following equations describe the predicted motion model of the robot in case we provide only the control $(v,w)$, which are the linear and angular velocity repsectively. \n", - "\n", - "$\\begin{equation*}\n", - "F=\n", - "\\begin{bmatrix}\n", - "1 & 0 & 0 \\\\\n", - "0 & 1 & 0 \\\\\n", - "0 & 0 & 1 \n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "$\\begin{equation*}\n", - "B=\n", - "\\begin{bmatrix}\n", - "\\Delta t cos(\\theta) & 0\\\\\n", - "\\Delta t sin(\\theta) & 0\\\\\n", - "0 & \\Delta t\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "$\\begin{equation*}\n", - "U=\n", - "\\begin{bmatrix}\n", - "v_t\\\\\n", - "w_t\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "$\\begin{equation*}\n", - "X = FX + BU \n", - "\\end{equation*}$\n", - "\n", - "\n", - "$\\begin{equation*}\n", - "\\begin{bmatrix}\n", - "x_{t+1} \\\\\n", - "y_{t+1} \\\\\n", - "\\theta_{t+1}\n", - "\\end{bmatrix}=\n", - "\\begin{bmatrix}\n", - "1 & 0 & 0 \\\\\n", - "0 & 1 & 0 \\\\\n", - "0 & 0 & 1 \n", - "\\end{bmatrix}\\begin{bmatrix}\n", - "x_{t} \\\\\n", - "y_{t} \\\\\n", - "\\theta_{t}\n", - "\\end{bmatrix}+\n", - "\\begin{bmatrix}\n", - "\\Delta t cos(\\theta) & 0\\\\\n", - "\\Delta t sin(\\theta) & 0\\\\\n", - "0 & \\Delta t\n", - "\\end{bmatrix}\n", - "\\begin{bmatrix}\n", - "v_{t} + \\sigma_v\\\\\n", - "w_{t} + \\sigma_w\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "Notice that while $U$ is only defined by $v_t$ and $w_t$, in the actual calcuations, a $+\\sigma_v$ and \n", - "$+\\sigma_w$ appear. These values represent the error bewteen the given control inputs and the actual control \n", - "inputs. \n", - "\n", - "As a result, the simulation is set up as the following. $R$ represents the process noise which is added to the \n", - "control inputs to simulate noise experienced in the real world. A set of truth values are computed from the raw \n", - "control values while the values dead reckoning values incorporate the error into the estimation. \n", - "\n", - "$\\begin{equation*}\n", - "R=\n", - "\\begin{bmatrix}\n", - "\\sigma_v\\\\\n", - "\\sigma_w\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "$\\begin{equation*}\n", - "X_{true} = FX + B(U)\n", - "\\end{equation*}$\n", - "\n", - "$\\begin{equation*}\n", - "X_{DR} = FX + B(U + R)\n", - "\\end{equation*}$\n", - "\n", - "The implementation of the motion model prediciton code is shown in `motion_model`. The `observation` function \n", - "shows how the simulation uses (or doesn't use) the process noise `Rsim` to the find the ground truth and dead reckoning estimtates of the pose.\n", - "\n", - "**Predict covariance:** Add the state covariance to the the current uncertainty of the EKF. At each time step, the uncertainty in the system grows by the covariance of the pose, $Cx$. \n", - "\n", - "$\n", - "P = G^TPG + Cx\n", - "$\n", - "\n", - "Notice this uncertainty is only growing with respect to the pose, not the landmarks. " - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [], - "source": [ - "def predict(xEst, PEst, u):\n", - " \"\"\"\n", - " Performs the prediction step of EKF SLAM\n", - " \n", - " :param xEst: nx1 state vector\n", - " :param PEst: nxn covariacne matrix\n", - " :param u: 2x1 control vector\n", - " :returns: predicted state vector, predicted covariance, jacobian of control vector, transition fx\n", - " \"\"\"\n", - " S = STATE_SIZE\n", - " G, Fx = jacob_motion(xEst[0:S], u)\n", - " xEst[0:S] = motion_model(xEst[0:S], u)\n", - " # Fx is an an identity matrix of size (STATE_SIZE)\n", - " # sigma = G*sigma*G.T + Noise\n", - " PEst[0:S, 0:S] = G.T @ PEst[0:S, 0:S] @ G + Fx.T @ Cx @ Fx\n", - " return xEst, PEst, G, Fx" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [], - "source": [ - "def motion_model(x, u):\n", - " \"\"\"\n", - " Computes the motion model based on current state and input function. \n", - " \n", - " :param x: 3x1 pose estimation\n", - " :param u: 2x1 control input [v; w]\n", - " :returns: the resutling state after the control function is applied\n", - " \"\"\"\n", - " F = np.array([[1.0, 0, 0],\n", - " [0, 1.0, 0],\n", - " [0, 0, 1.0]])\n", - "\n", - " B = np.array([[DT * math.cos(x[2, 0]), 0],\n", - " [DT * math.sin(x[2, 0]), 0],\n", - " [0.0, DT]])\n", - "\n", - " x = (F @ x) + (B @ u)\n", - " return x" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## 2 - Update\n", - "In the update phase, the observations of nearby landmarks are used to correct the location estimate. \n", - "\n", - "For every landmark observed, it is associated to a particular landmark in the known map. If no landmark exists \n", - "in the position surrounding the landmark, it is taken as a NEW landmark. The distance threshold for how far a \n", - "landmark must be from the next known landmark before its considered to be a new landmark is set by `M_DIST_TH`.\n", - "\n", - "With an observation associated to the appropriate landmark, the **innovation** can be calculated. Innovation \n", - "($y$) is the difference between the observation and the observation that *should* have been made if the \n", - "observation were made from the pose predicted in the predict stage.\n", - "\n", - "$\n", - "y = z_t - h(X)\n", - "$\n", - "\n", - "With the innovation calculated, the question becomes which to trust more - the observations or the predictions? \n", - "To determine this, we calculate the Kalman Gain - a percent of how much of the innovation to add to the \n", - "prediction based on the uncertainty in the predict step and the update step. \n", - "\n", - "$\n", - "K = \\bar{P_t}H_t^T(H_t\\bar{P_t}H_t^T + Q_t)^{-1}\n", - "$\n", - "In these equations, $H$ is the jacobian of the measurement function. The multiplications by $H^T$ and $H$ \n", - "represent the application of the delta to the measurement covariance. \n", - "Intuitively, this equation is applying the following from the single variate Kalman equation but in the \n", - "multivariate form, i.e. finding the ratio of the uncertianty of the process compared the measurment. \n", - "\n", - "$\n", - "K = \\frac{\\bar{P_t}}{\\bar{P_t} + Q_t}\n", - "$\n", - "\n", - "If $Q_t << \\bar{P_t}$, (i.e. the measurement covariance is low relative to the current estimate), then the \n", - "Kalman gain will be $~1$. This results in adding all of the innovation to the estimate -- and therefore \n", - "completely believing the measurement. \n", - "\n", - "However, if $Q_t >> \\bar{P_t}$ then the Kalman gain will go to 0, signaling a high trust in the process \n", - "and little trust in the measurement.\n", - "\n", - "The update is captured in the following. \n", - "\n", - "$\n", - "xUpdate = xEst + (K * y)\n", - "$\n", - "\n", - "Of course, the covariance must also be updated as well to account for the changing uncertainty. \n", - "\n", - "$\n", - "P_{t} = (I-K_tH_t)\\bar{P_t}\n", - "$" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [], - "source": [ - "def update(xEst, PEst, u, z, initP):\n", - " \"\"\"\n", - " Performs the update step of EKF SLAM\n", - " \n", - " :param xEst: nx1 the predicted pose of the system and the pose of the landmarks\n", - " :param PEst: nxn the predicted covariance\n", - " :param u: 2x1 the control function \n", - " :param z: the measurements read at new position\n", - " :param initP: 2x2 an identity matrix acting as the initial covariance\n", - " :returns: the updated state and covariance for the system\n", - " \"\"\"\n", - " for iz in range(len(z[:, 0])): # for each observation\n", - " minid = search_correspond_LM_ID(xEst, PEst, z[iz, 0:2]) # associate to a known landmark\n", - "\n", - " nLM = calc_n_LM(xEst) # number of landmarks we currently know about\n", - " \n", - " if minid == nLM: # Landmark is a NEW landmark\n", - " print(\"New LM\")\n", - " # Extend state and covariance matrix\n", - " xAug = np.vstack((xEst, calc_LM_Pos(xEst, z[iz, :])))\n", - " PAug = np.vstack((np.hstack((PEst, np.zeros((len(xEst), LM_SIZE)))),\n", - " np.hstack((np.zeros((LM_SIZE, len(xEst))), initP))))\n", - " xEst = xAug\n", - " PEst = PAug\n", - " \n", - " lm = get_LM_Pos_from_state(xEst, minid)\n", - " y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], minid)\n", - "\n", - " K = (PEst @ H.T) @ np.linalg.inv(S) # Calculate Kalman Gain\n", - " xEst = xEst + (K @ y)\n", - " PEst = (np.eye(len(xEst)) - (K @ H)) @ PEst\n", - " \n", - " xEst[2] = pi_2_pi(xEst[2])\n", - " return xEst, PEst\n" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [], - "source": [ - "def calc_innovation(lm, xEst, PEst, z, LMid):\n", - " \"\"\"\n", - " Calculates the innovation based on expected position and landmark position\n", - " \n", - " :param lm: landmark position\n", - " :param xEst: estimated position/state\n", - " :param PEst: estimated covariance\n", - " :param z: read measurements\n", - " :param LMid: landmark id\n", - " :returns: returns the innovation y, and the jacobian H, and S, used to calculate the Kalman Gain\n", - " \"\"\"\n", - " delta = lm - xEst[0:2]\n", - " q = (delta.T @ delta)[0, 0]\n", - " zangle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0]\n", - " zp = np.array([[math.sqrt(q), pi_2_pi(zangle)]])\n", - " # zp is the expected measurement based on xEst and the expected landmark position\n", - " \n", - " y = (z - zp).T # y = innovation\n", - " y[1] = pi_2_pi(y[1])\n", - " \n", - " H = jacobH(q, delta, xEst, LMid + 1)\n", - " S = H @ PEst @ H.T + Cx[0:2, 0:2]\n", - "\n", - " return y, S, H\n", - "\n", - "def jacobH(q, delta, x, i):\n", - " \"\"\"\n", - " Calculates the jacobian of the measurement function\n", - " \n", - " :param q: the range from the system pose to the landmark\n", - " :param delta: the difference between a landmark position and the estimated system position\n", - " :param x: the state, including the estimated system position\n", - " :param i: landmark id + 1\n", - " :returns: the jacobian H\n", - " \"\"\"\n", - " sq = math.sqrt(q)\n", - " G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]],\n", - " [delta[1, 0], - delta[0, 0], - q, - delta[1, 0], delta[0, 0]]])\n", - "\n", - " G = G / q\n", - " nLM = calc_n_LM(x)\n", - " F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM))))\n", - " F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))),\n", - " np.eye(2), np.zeros((2, 2 * nLM - 2 * i))))\n", - "\n", - " F = np.vstack((F1, F2))\n", - "\n", - " H = G @ F\n", - "\n", - " return H" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Observation Step\n", - "The observation step described here is outside the main EKF SLAM process and is primarily used as a method of\n", - "driving the simulation. The observations funciton is in charge of calcualting how the poses of the robots change \n", - "and accumulate error over time, and the theoretical measuremnts that are expected as a result of each \n", - "measurement. \n", - "\n", - "Observations are based on the TRUE position of the robot. Error in dead reckoning and control functions are \n", - "passed along here as well. " - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "metadata": {}, - "outputs": [], - "source": [ - "def observation(xTrue, xd, u, RFID):\n", - " \"\"\"\n", - " :param xTrue: the true pose of the system\n", - " :param xd: the current noisy estimate of the system\n", - " :param u: the current control input\n", - " :param RFID: the true position of the landmarks\n", - " \n", - " :returns: Computes the true position, observations, dead reckoning (noisy) position, \n", - " and noisy control function\n", - " \"\"\"\n", - " xTrue = motion_model(xTrue, u)\n", - "\n", - " # add noise to gps x-y\n", - " z = np.zeros((0, 3))\n", - "\n", - " for i in range(len(RFID[:, 0])): # Test all beacons, only add the ones we can see (within MAX_RANGE)\n", - "\n", - " dx = RFID[i, 0] - xTrue[0, 0]\n", - " dy = RFID[i, 1] - xTrue[1, 0]\n", - " d = math.sqrt(dx**2 + dy**2)\n", - " angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])\n", - " if d <= MAX_RANGE:\n", - " dn = d + np.random.randn() * Qsim[0, 0] # add noise\n", - " anglen = angle + np.random.randn() * Qsim[1, 1] # add noise\n", - " zi = np.array([dn, anglen, i])\n", - " z = np.vstack((z, zi))\n", - "\n", - " # add noise to input\n", - " ud = np.array([[\n", - " u[0, 0] + np.random.randn() * Rsim[0, 0],\n", - " u[1, 0] + np.random.randn() * Rsim[1, 1]]]).T\n", - "\n", - " xd = motion_model(xd, ud)\n", - " return xTrue, z, xd, ud" - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": {}, - "outputs": [], - "source": [ - "def calc_n_LM(x):\n", - " \"\"\"\n", - " Calculates the number of landmarks currently tracked in the state\n", - " :param x: the state\n", - " :returns: the number of landmarks n\n", - " \"\"\"\n", - " n = int((len(x) - STATE_SIZE) / LM_SIZE)\n", - " return n\n", - "\n", - "\n", - "def jacob_motion(x, u):\n", - " \"\"\"\n", - " Calculates the jacobian of motion model. \n", - " \n", - " :param x: The state, including the estimated position of the system\n", - " :param u: The control function\n", - " :returns: G: Jacobian\n", - " Fx: STATE_SIZE x (STATE_SIZE + 2 * num_landmarks) matrix where the left side is an identity matrix\n", - " \"\"\"\n", - " \n", - " # [eye(3) [0 x y; 0 x y; 0 x y]]\n", - " Fx = np.hstack((np.eye(STATE_SIZE), np.zeros(\n", - " (STATE_SIZE, LM_SIZE * calc_n_LM(x)))))\n", - "\n", - " jF = np.array([[0.0, 0.0, -DT * u[0] * math.sin(x[2, 0])],\n", - " [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])],\n", - " [0.0, 0.0, 0.0]],dtype=object)\n", - "\n", - " G = np.eye(STATE_SIZE) + Fx.T @ jF @ Fx\n", - " if calc_n_LM(x) > 0:\n", - " print(Fx.shape)\n", - " return G, Fx,\n", - "\n", - "\n" - ] - }, - { - "cell_type": "code", - "execution_count": 10, - "metadata": {}, - "outputs": [], - "source": [ - "def calc_LM_Pos(x, z):\n", - " \"\"\"\n", - " Calcualtes the pose in the world coordinate frame of a landmark at the given measurement. \n", - "\n", - " :param x: [x; y; theta]\n", - " :param z: [range; bearing]\n", - " :returns: [x; y] for given measurement\n", - " \"\"\"\n", - " zp = np.zeros((2, 1))\n", - "\n", - " zp[0, 0] = x[0, 0] + z[0] * math.cos(x[2, 0] + z[1])\n", - " zp[1, 0] = x[1, 0] + z[0] * math.sin(x[2, 0] + z[1])\n", - " #zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1])\n", - " #zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1])\n", - "\n", - " return zp\n", - "\n", - "\n", - "def get_LM_Pos_from_state(x, ind):\n", - " \"\"\"\n", - " Returns the position of a given landmark\n", - " \n", - " :param x: The state containing all landmark positions\n", - " :param ind: landmark id\n", - " :returns: The position of the landmark\n", - " \"\"\"\n", - " lm = x[STATE_SIZE + LM_SIZE * ind: STATE_SIZE + LM_SIZE * (ind + 1), :]\n", - "\n", - " return lm\n", - "\n", - "\n", - "def search_correspond_LM_ID(xAug, PAug, zi):\n", - " \"\"\"\n", - " Landmark association with Mahalanobis distance.\n", - " \n", - " If this landmark is at least M_DIST_TH units away from all known landmarks, \n", - " it is a NEW landmark.\n", - " \n", - " :param xAug: The estimated state\n", - " :param PAug: The estimated covariance\n", - " :param zi: the read measurements of specific landmark\n", - " :returns: landmark id\n", - " \"\"\"\n", - "\n", - " nLM = calc_n_LM(xAug)\n", - "\n", - " mdist = []\n", - "\n", - " for i in range(nLM):\n", - " lm = get_LM_Pos_from_state(xAug, i)\n", - " y, S, H = calc_innovation(lm, xAug, PAug, zi, i)\n", - " mdist.append(y.T @ np.linalg.inv(S) @ y)\n", - "\n", - " mdist.append(M_DIST_TH) # new landmark\n", - "\n", - " minid = mdist.index(min(mdist))\n", - "\n", - " return minid\n", - "\n", - "def calc_input():\n", - " v = 1.0 # [m/s]\n", - " yawrate = 0.1 # [rad/s]\n", - " u = np.array([[v, yawrate]]).T\n", - " return u\n", - "\n", - "def pi_2_pi(angle):\n", - " return (angle + math.pi) % (2 * math.pi) - math.pi" - ] - }, - { - "cell_type": "code", - "execution_count": 11, - "metadata": {}, - "outputs": [], - "source": [ - "def main():\n", - " print(\" start!!\")\n", - "\n", - " time = 0.0\n", - "\n", - " # RFID positions [x, y]\n", - " RFID = np.array([[10.0, -2.0],\n", - " [15.0, 10.0],\n", - " [3.0, 15.0],\n", - " [-5.0, 20.0]])\n", - "\n", - " # State Vector [x y yaw v]'\n", - " xEst = np.zeros((STATE_SIZE, 1))\n", - " xTrue = np.zeros((STATE_SIZE, 1))\n", - " PEst = np.eye(STATE_SIZE)\n", - "\n", - " xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning\n", - "\n", - " # history\n", - " hxEst = xEst\n", - " hxTrue = xTrue\n", - " hxDR = xTrue\n", - "\n", - " while SIM_TIME >= time:\n", - " time += DT\n", - " u = calc_input()\n", - "\n", - " xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)\n", - "\n", - " xEst, PEst = ekf_slam(xEst, PEst, ud, z)\n", - "\n", - " x_state = xEst[0:STATE_SIZE]\n", - "\n", - " # store data history\n", - " hxEst = np.hstack((hxEst, x_state))\n", - " hxDR = np.hstack((hxDR, xDR))\n", - " hxTrue = np.hstack((hxTrue, xTrue))\n", - "\n", - " if show_animation: # pragma: no cover\n", - " plt.cla()\n", - "\n", - " plt.plot(RFID[:, 0], RFID[:, 1], \"*k\")\n", - " plt.plot(xEst[0], xEst[1], \".r\")\n", - "\n", - " # plot landmark\n", - " for i in range(calc_n_LM(xEst)):\n", - " plt.plot(xEst[STATE_SIZE + i * 2],\n", - " xEst[STATE_SIZE + i * 2 + 1], \"xg\")\n", - "\n", - " plt.plot(hxTrue[0, :],\n", - " hxTrue[1, :], \"-b\")\n", - " plt.plot(hxDR[0, :],\n", - " hxDR[1, :], \"-k\")\n", - " plt.plot(hxEst[0, :],\n", - " hxEst[1, :], \"-r\")\n", - " plt.axis(\"equal\")\n", - " plt.grid(True)\n", - " plt.pause(0.001)" - ] - }, - { - "cell_type": "code", - "execution_count": 12, - "metadata": { - "scrolled": false - }, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - " start!!\n", - "New LM\n", - "New LM\n", - "New LM\n" - ] - }, - { - "data": { - "application/javascript": [ - "/* Put everything inside the global mpl namespace */\n", - "/* global mpl */\n", - "window.mpl = {};\n", - "\n", - "mpl.get_websocket_type = function () {\n", - " if (typeof WebSocket !== 'undefined') {\n", - " return WebSocket;\n", - " } else if (typeof MozWebSocket !== 'undefined') {\n", - " return MozWebSocket;\n", - " } else {\n", - " alert(\n", - " 'Your browser does not have WebSocket support. ' +\n", - " 'Please try Chrome, Safari or Firefox ≥ 6. ' +\n", - " 'Firefox 4 and 5 are also supported but you ' +\n", - " 'have to enable WebSockets in about:config.'\n", - " );\n", - " }\n", - "};\n", - "\n", - "mpl.figure = function (figure_id, websocket, ondownload, parent_element) {\n", - " this.id = figure_id;\n", - "\n", - " this.ws = websocket;\n", - "\n", - " this.supports_binary = this.ws.binaryType !== undefined;\n", - "\n", - " if (!this.supports_binary) {\n", - " var warnings = document.getElementById('mpl-warnings');\n", - " if (warnings) {\n", - " warnings.style.display = 'block';\n", - " warnings.textContent =\n", - " 'This browser does not support binary websocket messages. ' +\n", - " 'Performance may be slow.';\n", - " }\n", - " }\n", - "\n", - " this.imageObj = new Image();\n", - "\n", - " this.context = undefined;\n", - " this.message = undefined;\n", - " this.canvas = undefined;\n", - " this.rubberband_canvas = undefined;\n", - " this.rubberband_context = undefined;\n", - " this.format_dropdown = undefined;\n", - "\n", - " this.image_mode = 'full';\n", - "\n", - " this.root = document.createElement('div');\n", - " this.root.setAttribute('style', 'display: inline-block');\n", - " this._root_extra_style(this.root);\n", - "\n", - " parent_element.appendChild(this.root);\n", - "\n", - " this._init_header(this);\n", - " this._init_canvas(this);\n", - " this._init_toolbar(this);\n", - "\n", - " var fig = this;\n", - "\n", - " this.waiting = false;\n", - "\n", - " this.ws.onopen = function () {\n", - " fig.send_message('supports_binary', { value: fig.supports_binary });\n", - " fig.send_message('send_image_mode', {});\n", - " if (fig.ratio !== 1) {\n", - " fig.send_message('set_dpi_ratio', { dpi_ratio: fig.ratio });\n", - " }\n", - " fig.send_message('refresh', {});\n", - " };\n", - "\n", - " this.imageObj.onload = function () {\n", - " if (fig.image_mode === 'full') {\n", - " // Full images could contain transparency (where diff images\n", - " // almost always do), so we need to clear the canvas so that\n", - " // there is no ghosting.\n", - " fig.context.clearRect(0, 0, fig.canvas.width, fig.canvas.height);\n", - " }\n", - " fig.context.drawImage(fig.imageObj, 0, 0);\n", - " };\n", - "\n", - " this.imageObj.onunload = function () {\n", - " fig.ws.close();\n", - " };\n", - "\n", - " this.ws.onmessage = this._make_on_message_function(this);\n", - "\n", - " this.ondownload = ondownload;\n", - "};\n", - "\n", - "mpl.figure.prototype._init_header = function () {\n", - " var titlebar = document.createElement('div');\n", - " titlebar.classList =\n", - " 'ui-dialog-titlebar ui-widget-header ui-corner-all ui-helper-clearfix';\n", - " var titletext = document.createElement('div');\n", - " titletext.classList = 'ui-dialog-title';\n", - " titletext.setAttribute(\n", - " 'style',\n", - " 'width: 100%; text-align: center; padding: 3px;'\n", - " );\n", - " titlebar.appendChild(titletext);\n", - " this.root.appendChild(titlebar);\n", - " this.header = titletext;\n", - "};\n", - "\n", - "mpl.figure.prototype._canvas_extra_style = function (_canvas_div) {};\n", - "\n", - "mpl.figure.prototype._root_extra_style = function (_canvas_div) {};\n", - "\n", - "mpl.figure.prototype._init_canvas = function () {\n", - " var fig = this;\n", - "\n", - " var canvas_div = (this.canvas_div = document.createElement('div'));\n", - " canvas_div.setAttribute(\n", - " 'style',\n", - " 'border: 1px solid #ddd;' +\n", - " 'box-sizing: content-box;' +\n", - " 'clear: both;' +\n", - " 'min-height: 1px;' +\n", - " 'min-width: 1px;' +\n", - " 'outline: 0;' +\n", - " 'overflow: hidden;' +\n", - " 'position: relative;' +\n", - " 'resize: both;'\n", - " );\n", - "\n", - " function on_keyboard_event_closure(name) {\n", - " return function (event) {\n", - " return fig.key_event(event, name);\n", - " };\n", - " }\n", - "\n", - " canvas_div.addEventListener(\n", - " 'keydown',\n", - " on_keyboard_event_closure('key_press')\n", - " );\n", - " canvas_div.addEventListener(\n", - " 'keyup',\n", - " on_keyboard_event_closure('key_release')\n", - " );\n", - "\n", - " this._canvas_extra_style(canvas_div);\n", - " this.root.appendChild(canvas_div);\n", - "\n", - " var canvas = (this.canvas = document.createElement('canvas'));\n", - " canvas.classList.add('mpl-canvas');\n", - " canvas.setAttribute('style', 'box-sizing: content-box;');\n", - "\n", - " this.context = canvas.getContext('2d');\n", - "\n", - " var backingStore =\n", - " this.context.backingStorePixelRatio ||\n", - " this.context.webkitBackingStorePixelRatio ||\n", - " this.context.mozBackingStorePixelRatio ||\n", - " this.context.msBackingStorePixelRatio ||\n", - " this.context.oBackingStorePixelRatio ||\n", - " this.context.backingStorePixelRatio ||\n", - " 1;\n", - "\n", - " this.ratio = (window.devicePixelRatio || 1) / backingStore;\n", - "\n", - " var rubberband_canvas = (this.rubberband_canvas = document.createElement(\n", - " 'canvas'\n", - " ));\n", - " rubberband_canvas.setAttribute(\n", - " 'style',\n", - " 'box-sizing: content-box; position: absolute; left: 0; top: 0; z-index: 1;'\n", - " );\n", - "\n", - " // Apply a ponyfill if ResizeObserver is not implemented by browser.\n", - " if (this.ResizeObserver === undefined) {\n", - " if (window.ResizeObserver !== undefined) {\n", - " this.ResizeObserver = window.ResizeObserver;\n", - " } else {\n", - " var obs = _JSXTOOLS_RESIZE_OBSERVER({});\n", - " this.ResizeObserver = obs.ResizeObserver;\n", - " }\n", - " }\n", - "\n", - " this.resizeObserverInstance = new this.ResizeObserver(function (entries) {\n", - " var nentries = entries.length;\n", - " for (var i = 0; i < nentries; i++) {\n", - " var entry = entries[i];\n", - " var width, height;\n", - " if (entry.contentBoxSize) {\n", - " if (entry.contentBoxSize instanceof Array) {\n", - " // Chrome 84 implements new version of spec.\n", - " width = entry.contentBoxSize[0].inlineSize;\n", - " height = entry.contentBoxSize[0].blockSize;\n", - " } else {\n", - " // Firefox implements old version of spec.\n", - " width = entry.contentBoxSize.inlineSize;\n", - " height = entry.contentBoxSize.blockSize;\n", - " }\n", - " } else {\n", - " // Chrome <84 implements even older version of spec.\n", - " width = entry.contentRect.width;\n", - " height = entry.contentRect.height;\n", - " }\n", - "\n", - " // Keep the size of the canvas and rubber band canvas in sync with\n", - " // the canvas container.\n", - " if (entry.devicePixelContentBoxSize) {\n", - " // Chrome 84 implements new version of spec.\n", - " canvas.setAttribute(\n", - " 'width',\n", - " entry.devicePixelContentBoxSize[0].inlineSize\n", - " );\n", - " canvas.setAttribute(\n", - " 'height',\n", - " entry.devicePixelContentBoxSize[0].blockSize\n", - " );\n", - " } else {\n", - " canvas.setAttribute('width', width * fig.ratio);\n", - " canvas.setAttribute('height', height * fig.ratio);\n", - " }\n", - " canvas.setAttribute(\n", - " 'style',\n", - " 'width: ' + width + 'px; height: ' + height + 'px;'\n", - " );\n", - "\n", - " rubberband_canvas.setAttribute('width', width);\n", - " rubberband_canvas.setAttribute('height', height);\n", - "\n", - " // And update the size in Python. We ignore the initial 0/0 size\n", - " // that occurs as the element is placed into the DOM, which should\n", - " // otherwise not happen due to the minimum size styling.\n", - " if (fig.ws.readyState == 1 && width != 0 && height != 0) {\n", - " fig.request_resize(width, height);\n", - " }\n", - " }\n", - " });\n", - " this.resizeObserverInstance.observe(canvas_div);\n", - "\n", - " function on_mouse_event_closure(name) {\n", - " return function (event) {\n", - " return fig.mouse_event(event, name);\n", - " };\n", - " }\n", - "\n", - " rubberband_canvas.addEventListener(\n", - " 'mousedown',\n", - " on_mouse_event_closure('button_press')\n", - " );\n", - " rubberband_canvas.addEventListener(\n", - " 'mouseup',\n", - " on_mouse_event_closure('button_release')\n", - " );\n", - " rubberband_canvas.addEventListener(\n", - " 'dblclick',\n", - " on_mouse_event_closure('dblclick')\n", - " );\n", - " // Throttle sequential mouse events to 1 every 20ms.\n", - " rubberband_canvas.addEventListener(\n", - " 'mousemove',\n", - " on_mouse_event_closure('motion_notify')\n", - " );\n", - "\n", - " rubberband_canvas.addEventListener(\n", - " 'mouseenter',\n", - " on_mouse_event_closure('figure_enter')\n", - " );\n", - " rubberband_canvas.addEventListener(\n", - " 'mouseleave',\n", - " on_mouse_event_closure('figure_leave')\n", - " );\n", - "\n", - " canvas_div.addEventListener('wheel', function (event) {\n", - " if (event.deltaY < 0) {\n", - " event.step = 1;\n", - " } else {\n", - " event.step = -1;\n", - " }\n", - " on_mouse_event_closure('scroll')(event);\n", - " });\n", - "\n", - " canvas_div.appendChild(canvas);\n", - " canvas_div.appendChild(rubberband_canvas);\n", - "\n", - " this.rubberband_context = rubberband_canvas.getContext('2d');\n", - " this.rubberband_context.strokeStyle = '#000000';\n", - "\n", - " this._resize_canvas = function (width, height, forward) {\n", - " if (forward) {\n", - " canvas_div.style.width = width + 'px';\n", - " canvas_div.style.height = height + 'px';\n", - " }\n", - " };\n", - "\n", - " // Disable right mouse context menu.\n", - " this.rubberband_canvas.addEventListener('contextmenu', function (_e) {\n", - " event.preventDefault();\n", - " return false;\n", - " });\n", - "\n", - " function set_focus() {\n", - " canvas.focus();\n", - " canvas_div.focus();\n", - " }\n", - "\n", - " window.setTimeout(set_focus, 100);\n", - "};\n", - "\n", - "mpl.figure.prototype._init_toolbar = function () {\n", - " var fig = this;\n", - "\n", - " var toolbar = document.createElement('div');\n", - " toolbar.classList = 'mpl-toolbar';\n", - " this.root.appendChild(toolbar);\n", - "\n", - " function on_click_closure(name) {\n", - " return function (_event) {\n", - " return fig.toolbar_button_onclick(name);\n", - " };\n", - " }\n", - "\n", - " function on_mouseover_closure(tooltip) {\n", - " return function (event) {\n", - " if (!event.currentTarget.disabled) {\n", - " return fig.toolbar_button_onmouseover(tooltip);\n", - " }\n", - " };\n", - " }\n", - "\n", - " fig.buttons = {};\n", - " var buttonGroup = document.createElement('div');\n", - " buttonGroup.classList = 'mpl-button-group';\n", - " for (var toolbar_ind in mpl.toolbar_items) {\n", - " var name = mpl.toolbar_items[toolbar_ind][0];\n", - " var tooltip = mpl.toolbar_items[toolbar_ind][1];\n", - " var image = mpl.toolbar_items[toolbar_ind][2];\n", - " var method_name = mpl.toolbar_items[toolbar_ind][3];\n", - "\n", - " if (!name) {\n", - " /* Instead of a spacer, we start a new button group. */\n", - " if (buttonGroup.hasChildNodes()) {\n", - " toolbar.appendChild(buttonGroup);\n", - " }\n", - " buttonGroup = document.createElement('div');\n", - " buttonGroup.classList = 'mpl-button-group';\n", - " continue;\n", - " }\n", - "\n", - " var button = (fig.buttons[name] = document.createElement('button'));\n", - " button.classList = 'mpl-widget';\n", - " button.setAttribute('role', 'button');\n", - " button.setAttribute('aria-disabled', 'false');\n", - " button.addEventListener('click', on_click_closure(method_name));\n", - " button.addEventListener('mouseover', on_mouseover_closure(tooltip));\n", - "\n", - " var icon_img = document.createElement('img');\n", - " icon_img.src = '_images/' + image + '.png';\n", - " icon_img.srcset = '_images/' + image + '_large.png 2x';\n", - " icon_img.alt = tooltip;\n", - " button.appendChild(icon_img);\n", - "\n", - " buttonGroup.appendChild(button);\n", - " }\n", - "\n", - " if (buttonGroup.hasChildNodes()) {\n", - " toolbar.appendChild(buttonGroup);\n", - " }\n", - "\n", - " var fmt_picker = document.createElement('select');\n", - " fmt_picker.classList = 'mpl-widget';\n", - " toolbar.appendChild(fmt_picker);\n", - " this.format_dropdown = fmt_picker;\n", - "\n", - " for (var ind in mpl.extensions) {\n", - " var fmt = mpl.extensions[ind];\n", - " var option = document.createElement('option');\n", - " option.selected = fmt === mpl.default_extension;\n", - " option.innerHTML = fmt;\n", - " fmt_picker.appendChild(option);\n", - " }\n", - "\n", - " var status_bar = document.createElement('span');\n", - " status_bar.classList = 'mpl-message';\n", - " toolbar.appendChild(status_bar);\n", - " this.message = status_bar;\n", - "};\n", - "\n", - "mpl.figure.prototype.request_resize = function (x_pixels, y_pixels) {\n", - " // Request matplotlib to resize the figure. Matplotlib will then trigger a resize in the client,\n", - " // which will in turn request a refresh of the image.\n", - " this.send_message('resize', { width: x_pixels, height: y_pixels });\n", - "};\n", - "\n", - "mpl.figure.prototype.send_message = function (type, properties) {\n", - " properties['type'] = type;\n", - " properties['figure_id'] = this.id;\n", - " this.ws.send(JSON.stringify(properties));\n", - "};\n", - "\n", - "mpl.figure.prototype.send_draw_message = function () {\n", - " if (!this.waiting) {\n", - " this.waiting = true;\n", - " this.ws.send(JSON.stringify({ type: 'draw', figure_id: this.id }));\n", - " }\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_save = function (fig, _msg) {\n", - " var format_dropdown = fig.format_dropdown;\n", - " var format = format_dropdown.options[format_dropdown.selectedIndex].value;\n", - " fig.ondownload(fig, format);\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_resize = function (fig, msg) {\n", - " var size = msg['size'];\n", - " if (size[0] !== fig.canvas.width || size[1] !== fig.canvas.height) {\n", - " fig._resize_canvas(size[0], size[1], msg['forward']);\n", - " fig.send_message('refresh', {});\n", - " }\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_rubberband = function (fig, msg) {\n", - " var x0 = msg['x0'] / fig.ratio;\n", - " var y0 = (fig.canvas.height - msg['y0']) / fig.ratio;\n", - " var x1 = msg['x1'] / fig.ratio;\n", - " var y1 = (fig.canvas.height - msg['y1']) / fig.ratio;\n", - " x0 = Math.floor(x0) + 0.5;\n", - " y0 = Math.floor(y0) + 0.5;\n", - " x1 = Math.floor(x1) + 0.5;\n", - " y1 = Math.floor(y1) + 0.5;\n", - " var min_x = Math.min(x0, x1);\n", - " var min_y = Math.min(y0, y1);\n", - " var width = Math.abs(x1 - x0);\n", - " var height = Math.abs(y1 - y0);\n", - "\n", - " fig.rubberband_context.clearRect(\n", - " 0,\n", - " 0,\n", - " fig.canvas.width / fig.ratio,\n", - " fig.canvas.height / fig.ratio\n", - " );\n", - "\n", - " fig.rubberband_context.strokeRect(min_x, min_y, width, height);\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_figure_label = function (fig, msg) {\n", - " // Updates the figure title.\n", - " fig.header.textContent = msg['label'];\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_cursor = function (fig, msg) {\n", - " var cursor = msg['cursor'];\n", - " switch (cursor) {\n", - " case 0:\n", - " cursor = 'pointer';\n", - " break;\n", - " case 1:\n", - " cursor = 'default';\n", - " break;\n", - " case 2:\n", - " cursor = 'crosshair';\n", - " break;\n", - " case 3:\n", - " cursor = 'move';\n", - " break;\n", - " }\n", - " fig.rubberband_canvas.style.cursor = cursor;\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_message = function (fig, msg) {\n", - " fig.message.textContent = msg['message'];\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_draw = function (fig, _msg) {\n", - " // Request the server to send over a new figure.\n", - " fig.send_draw_message();\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_image_mode = function (fig, msg) {\n", - " fig.image_mode = msg['mode'];\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_history_buttons = function (fig, msg) {\n", - " for (var key in msg) {\n", - " if (!(key in fig.buttons)) {\n", - " continue;\n", - " }\n", - " fig.buttons[key].disabled = !msg[key];\n", - " fig.buttons[key].setAttribute('aria-disabled', !msg[key]);\n", - " }\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_navigate_mode = function (fig, msg) {\n", - " if (msg['mode'] === 'PAN') {\n", - " fig.buttons['Pan'].classList.add('active');\n", - " fig.buttons['Zoom'].classList.remove('active');\n", - " } else if (msg['mode'] === 'ZOOM') {\n", - " fig.buttons['Pan'].classList.remove('active');\n", - " fig.buttons['Zoom'].classList.add('active');\n", - " } else {\n", - " fig.buttons['Pan'].classList.remove('active');\n", - " fig.buttons['Zoom'].classList.remove('active');\n", - " }\n", - "};\n", - "\n", - "mpl.figure.prototype.updated_canvas_event = function () {\n", - " // Called whenever the canvas gets updated.\n", - " this.send_message('ack', {});\n", - "};\n", - "\n", - "// A function to construct a web socket function for onmessage handling.\n", - "// Called in the figure constructor.\n", - "mpl.figure.prototype._make_on_message_function = function (fig) {\n", - " return function socket_on_message(evt) {\n", - " if (evt.data instanceof Blob) {\n", - " var img = evt.data;\n", - " if (img.type !== 'image/png') {\n", - " /* FIXME: We get \"Resource interpreted as Image but\n", - " * transferred with MIME type text/plain:\" errors on\n", - " * Chrome. But how to set the MIME type? It doesn't seem\n", - " * to be part of the websocket stream */\n", - " img.type = 'image/png';\n", - " }\n", - "\n", - " /* Free the memory for the previous frames */\n", - " if (fig.imageObj.src) {\n", - " (window.URL || window.webkitURL).revokeObjectURL(\n", - " fig.imageObj.src\n", - " );\n", - " }\n", - "\n", - " fig.imageObj.src = (window.URL || window.webkitURL).createObjectURL(\n", - " img\n", - " );\n", - " fig.updated_canvas_event();\n", - " fig.waiting = false;\n", - " return;\n", - " } else if (\n", - " typeof evt.data === 'string' &&\n", - " evt.data.slice(0, 21) === 'data:image/png;base64'\n", - " ) {\n", - " fig.imageObj.src = evt.data;\n", - " fig.updated_canvas_event();\n", - " fig.waiting = false;\n", - " return;\n", - " }\n", - "\n", - " var msg = JSON.parse(evt.data);\n", - " var msg_type = msg['type'];\n", - "\n", - " // Call the \"handle_{type}\" callback, which takes\n", - " // the figure and JSON message as its only arguments.\n", - " try {\n", - " var callback = fig['handle_' + msg_type];\n", - " } catch (e) {\n", - " console.log(\n", - " \"No handler for the '\" + msg_type + \"' message type: \",\n", - " msg\n", - " );\n", - " return;\n", - " }\n", - "\n", - " if (callback) {\n", - " try {\n", - " // console.log(\"Handling '\" + msg_type + \"' message: \", msg);\n", - " callback(fig, msg);\n", - " } catch (e) {\n", - " console.log(\n", - " \"Exception inside the 'handler_\" + msg_type + \"' callback:\",\n", - " e,\n", - " e.stack,\n", - " msg\n", - " );\n", - " }\n", - " }\n", - " };\n", - "};\n", - "\n", - "// from http://stackoverflow.com/questions/1114465/getting-mouse-location-in-canvas\n", - "mpl.findpos = function (e) {\n", - " //this section is from http://www.quirksmode.org/js/events_properties.html\n", - " var targ;\n", - " if (!e) {\n", - " e = window.event;\n", - " }\n", - " if (e.target) {\n", - " targ = e.target;\n", - " } else if (e.srcElement) {\n", - " targ = e.srcElement;\n", - " }\n", - " if (targ.nodeType === 3) {\n", - " // defeat Safari bug\n", - " targ = targ.parentNode;\n", - " }\n", - "\n", - " // pageX,Y are the mouse positions relative to the document\n", - " var boundingRect = targ.getBoundingClientRect();\n", - " var x = e.pageX - (boundingRect.left + document.body.scrollLeft);\n", - " var y = e.pageY - (boundingRect.top + document.body.scrollTop);\n", - "\n", - " return { x: x, y: y };\n", - "};\n", - "\n", - "/*\n", - " * return a copy of an object with only non-object keys\n", - " * we need this to avoid circular references\n", - " * http://stackoverflow.com/a/24161582/3208463\n", - " */\n", - "function simpleKeys(original) {\n", - " return Object.keys(original).reduce(function (obj, key) {\n", - " if (typeof original[key] !== 'object') {\n", - " obj[key] = original[key];\n", - " }\n", - " return obj;\n", - " }, {});\n", - "}\n", - "\n", - "mpl.figure.prototype.mouse_event = function (event, name) {\n", - " var canvas_pos = mpl.findpos(event);\n", - "\n", - " if (name === 'button_press') {\n", - " this.canvas.focus();\n", - " this.canvas_div.focus();\n", - " }\n", - "\n", - " var x = canvas_pos.x * this.ratio;\n", - " var y = canvas_pos.y * this.ratio;\n", - "\n", - " this.send_message(name, {\n", - " x: x,\n", - " y: y,\n", - " button: event.button,\n", - " step: event.step,\n", - " guiEvent: simpleKeys(event),\n", - " });\n", - "\n", - " /* This prevents the web browser from automatically changing to\n", - " * the text insertion cursor when the button is pressed. We want\n", - " * to control all of the cursor setting manually through the\n", - " * 'cursor' event from matplotlib */\n", - " event.preventDefault();\n", - " return false;\n", - "};\n", - "\n", - "mpl.figure.prototype._key_event_extra = function (_event, _name) {\n", - " // Handle any extra behaviour associated with a key event\n", - "};\n", - "\n", - "mpl.figure.prototype.key_event = function (event, name) {\n", - " // Prevent repeat events\n", - " if (name === 'key_press') {\n", - " if (event.key === this._key) {\n", - " return;\n", - " } else {\n", - " this._key = event.key;\n", - " }\n", - " }\n", - " if (name === 'key_release') {\n", - " this._key = null;\n", - " }\n", - "\n", - " var value = '';\n", - " if (event.ctrlKey && event.key !== 'Control') {\n", - " value += 'ctrl+';\n", - " }\n", - " else if (event.altKey && event.key !== 'Alt') {\n", - " value += 'alt+';\n", - " }\n", - " else if (event.shiftKey && event.key !== 'Shift') {\n", - " value += 'shift+';\n", - " }\n", - "\n", - " value += 'k' + event.key;\n", - "\n", - " this._key_event_extra(event, name);\n", - "\n", - " this.send_message(name, { key: value, guiEvent: simpleKeys(event) });\n", - " return false;\n", - "};\n", - "\n", - "mpl.figure.prototype.toolbar_button_onclick = function (name) {\n", - " if (name === 'download') {\n", - " this.handle_save(this, null);\n", - " } else {\n", - " this.send_message('toolbar_button', { name: name });\n", - " }\n", - "};\n", - "\n", - "mpl.figure.prototype.toolbar_button_onmouseover = function (tooltip) {\n", - " this.message.textContent = tooltip;\n", - "};\n", - "\n", - "///////////////// REMAINING CONTENT GENERATED BY embed_js.py /////////////////\n", - "// prettier-ignore\n", - "var _JSXTOOLS_RESIZE_OBSERVER=function(A){var t,i=new WeakMap,n=new WeakMap,a=new WeakMap,r=new WeakMap,o=new Set;function s(e){if(!(this instanceof s))throw new TypeError(\"Constructor requires 'new' operator\");i.set(this,e)}function h(){throw new TypeError(\"Function is not a constructor\")}function c(e,t,i,n){e=0 in arguments?Number(arguments[0]):0,t=1 in arguments?Number(arguments[1]):0,i=2 in arguments?Number(arguments[2]):0,n=3 in arguments?Number(arguments[3]):0,this.right=(this.x=this.left=e)+(this.width=i),this.bottom=(this.y=this.top=t)+(this.height=n),Object.freeze(this)}function d(){t=requestAnimationFrame(d);var s=new WeakMap,p=new Set;o.forEach((function(t){r.get(t).forEach((function(i){var r=t instanceof window.SVGElement,o=a.get(t),d=r?0:parseFloat(o.paddingTop),f=r?0:parseFloat(o.paddingRight),l=r?0:parseFloat(o.paddingBottom),u=r?0:parseFloat(o.paddingLeft),g=r?0:parseFloat(o.borderTopWidth),m=r?0:parseFloat(o.borderRightWidth),w=r?0:parseFloat(o.borderBottomWidth),b=u+f,F=d+l,v=(r?0:parseFloat(o.borderLeftWidth))+m,W=g+w,y=r?0:t.offsetHeight-W-t.clientHeight,E=r?0:t.offsetWidth-v-t.clientWidth,R=b+v,z=F+W,M=r?t.width:parseFloat(o.width)-R-E,O=r?t.height:parseFloat(o.height)-z-y;if(n.has(t)){var k=n.get(t);if(k[0]===M&&k[1]===O)return}n.set(t,[M,O]);var S=Object.create(h.prototype);S.target=t,S.contentRect=new c(u,d,M,O),s.has(i)||(s.set(i,[]),p.add(i)),s.get(i).push(S)}))})),p.forEach((function(e){i.get(e).call(e,s.get(e),e)}))}return s.prototype.observe=function(i){if(i instanceof window.Element){r.has(i)||(r.set(i,new Set),o.add(i),a.set(i,window.getComputedStyle(i)));var n=r.get(i);n.has(this)||n.add(this),cancelAnimationFrame(t),t=requestAnimationFrame(d)}},s.prototype.unobserve=function(i){if(i instanceof window.Element&&r.has(i)){var n=r.get(i);n.has(this)&&(n.delete(this),n.size||(r.delete(i),o.delete(i))),n.size||r.delete(i),o.size||cancelAnimationFrame(t)}},A.DOMRectReadOnly=c,A.ResizeObserver=s,A.ResizeObserverEntry=h,A}; // eslint-disable-line\n", - "mpl.toolbar_items = [[\"Home\", \"Reset original view\", \"fa fa-home icon-home\", \"home\"], [\"Back\", \"Back to previous view\", \"fa fa-arrow-left icon-arrow-left\", \"back\"], [\"Forward\", \"Forward to next view\", \"fa fa-arrow-right icon-arrow-right\", \"forward\"], [\"\", \"\", \"\", \"\"], [\"Pan\", \"Left button pans, Right button zooms\\nx/y fixes axis, CTRL fixes aspect\", \"fa fa-arrows icon-move\", \"pan\"], [\"Zoom\", \"Zoom to rectangle\\nx/y fixes axis, CTRL fixes aspect\", \"fa fa-square-o icon-check-empty\", \"zoom\"], [\"\", \"\", \"\", \"\"], [\"Download\", \"Download plot\", \"fa fa-floppy-o icon-save\", \"download\"]];\n", - "\n", - "mpl.extensions = [\"eps\", \"jpeg\", \"pgf\", \"pdf\", \"png\", \"ps\", \"raw\", \"svg\", \"tif\"];\n", - "\n", - "mpl.default_extension = \"png\";/* global mpl */\n", - "\n", - "var comm_websocket_adapter = function (comm) {\n", - " // Create a \"websocket\"-like object which calls the given IPython comm\n", - " // object with the appropriate methods. Currently this is a non binary\n", - " // socket, so there is still some room for performance tuning.\n", - " var ws = {};\n", - "\n", - " ws.binaryType = comm.kernel.ws.binaryType;\n", - " ws.readyState = comm.kernel.ws.readyState;\n", - " function updateReadyState(_event) {\n", - " if (comm.kernel.ws) {\n", - " ws.readyState = comm.kernel.ws.readyState;\n", - " } else {\n", - " ws.readyState = 3; // Closed state.\n", - " }\n", - " }\n", - " comm.kernel.ws.addEventListener('open', updateReadyState);\n", - " comm.kernel.ws.addEventListener('close', updateReadyState);\n", - " comm.kernel.ws.addEventListener('error', updateReadyState);\n", - "\n", - " ws.close = function () {\n", - " comm.close();\n", - " };\n", - " ws.send = function (m) {\n", - " //console.log('sending', m);\n", - " comm.send(m);\n", - " };\n", - " // Register the callback with on_msg.\n", - " comm.on_msg(function (msg) {\n", - " //console.log('receiving', msg['content']['data'], msg);\n", - " var data = msg['content']['data'];\n", - " if (data['blob'] !== undefined) {\n", - " data = {\n", - " data: new Blob(msg['buffers'], { type: data['blob'] }),\n", - " };\n", - " }\n", - " // Pass the mpl event to the overridden (by mpl) onmessage function.\n", - " ws.onmessage(data);\n", - " });\n", - " return ws;\n", - "};\n", - "\n", - "mpl.mpl_figure_comm = function (comm, msg) {\n", - " // This is the function which gets called when the mpl process\n", - " // starts-up an IPython Comm through the \"matplotlib\" channel.\n", - "\n", - " var id = msg.content.data.id;\n", - " // Get hold of the div created by the display call when the Comm\n", - " // socket was opened in Python.\n", - " var element = document.getElementById(id);\n", - " var ws_proxy = comm_websocket_adapter(comm);\n", - "\n", - " function ondownload(figure, _format) {\n", - " window.open(figure.canvas.toDataURL());\n", - " }\n", - "\n", - " var fig = new mpl.figure(id, ws_proxy, ondownload, element);\n", - "\n", - " // Call onopen now - mpl needs it, as it is assuming we've passed it a real\n", - " // web socket which is closed, not our websocket->open comm proxy.\n", - " ws_proxy.onopen();\n", - "\n", - " fig.parent_element = element;\n", - " fig.cell_info = mpl.find_output_cell(\"
\");\n", - " if (!fig.cell_info) {\n", - " console.error('Failed to find cell for figure', id, fig);\n", - " return;\n", - " }\n", - " fig.cell_info[0].output_area.element.on(\n", - " 'cleared',\n", - " { fig: fig },\n", - " fig._remove_fig_handler\n", - " );\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_close = function (fig, msg) {\n", - " var width = fig.canvas.width / fig.ratio;\n", - " fig.cell_info[0].output_area.element.off(\n", - " 'cleared',\n", - " fig._remove_fig_handler\n", - " );\n", - " fig.resizeObserverInstance.unobserve(fig.canvas_div);\n", - "\n", - " // Update the output cell to use the data from the current canvas.\n", - " fig.push_to_output();\n", - " var dataURL = fig.canvas.toDataURL();\n", - " // Re-enable the keyboard manager in IPython - without this line, in FF,\n", - " // the notebook keyboard shortcuts fail.\n", - " IPython.keyboard_manager.enable();\n", - " fig.parent_element.innerHTML =\n", - " '';\n", - " fig.close_ws(fig, msg);\n", - "};\n", - "\n", - "mpl.figure.prototype.close_ws = function (fig, msg) {\n", - " fig.send_message('closing', msg);\n", - " // fig.ws.close()\n", - "};\n", - "\n", - "mpl.figure.prototype.push_to_output = function (_remove_interactive) {\n", - " // Turn the data on the canvas into data in the output cell.\n", - " var width = this.canvas.width / this.ratio;\n", - " var dataURL = this.canvas.toDataURL();\n", - " this.cell_info[1]['text/html'] =\n", - " '';\n", - "};\n", - "\n", - "mpl.figure.prototype.updated_canvas_event = function () {\n", - " // Tell IPython that the notebook contents must change.\n", - " IPython.notebook.set_dirty(true);\n", - " this.send_message('ack', {});\n", - " var fig = this;\n", - " // Wait a second, then push the new image to the DOM so\n", - " // that it is saved nicely (might be nice to debounce this).\n", - " setTimeout(function () {\n", - " fig.push_to_output();\n", - " }, 1000);\n", - "};\n", - "\n", - "mpl.figure.prototype._init_toolbar = function () {\n", - " var fig = this;\n", - "\n", - " var toolbar = document.createElement('div');\n", - " toolbar.classList = 'btn-toolbar';\n", - " this.root.appendChild(toolbar);\n", - "\n", - " function on_click_closure(name) {\n", - " return function (_event) {\n", - " return fig.toolbar_button_onclick(name);\n", - " };\n", - " }\n", - "\n", - " function on_mouseover_closure(tooltip) {\n", - " return function (event) {\n", - " if (!event.currentTarget.disabled) {\n", - " return fig.toolbar_button_onmouseover(tooltip);\n", - " }\n", - " };\n", - " }\n", - "\n", - " fig.buttons = {};\n", - " var buttonGroup = document.createElement('div');\n", - " buttonGroup.classList = 'btn-group';\n", - " var button;\n", - " for (var toolbar_ind in mpl.toolbar_items) {\n", - " var name = mpl.toolbar_items[toolbar_ind][0];\n", - " var tooltip = mpl.toolbar_items[toolbar_ind][1];\n", - " var image = mpl.toolbar_items[toolbar_ind][2];\n", - " var method_name = mpl.toolbar_items[toolbar_ind][3];\n", - "\n", - " if (!name) {\n", - " /* Instead of a spacer, we start a new button group. */\n", - " if (buttonGroup.hasChildNodes()) {\n", - " toolbar.appendChild(buttonGroup);\n", - " }\n", - " buttonGroup = document.createElement('div');\n", - " buttonGroup.classList = 'btn-group';\n", - " continue;\n", - " }\n", - "\n", - " button = fig.buttons[name] = document.createElement('button');\n", - " button.classList = 'btn btn-default';\n", - " button.href = '#';\n", - " button.title = name;\n", - " button.innerHTML = '';\n", - " button.addEventListener('click', on_click_closure(method_name));\n", - " button.addEventListener('mouseover', on_mouseover_closure(tooltip));\n", - " buttonGroup.appendChild(button);\n", - " }\n", - "\n", - " if (buttonGroup.hasChildNodes()) {\n", - " toolbar.appendChild(buttonGroup);\n", - " }\n", - "\n", - " // Add the status bar.\n", - " var status_bar = document.createElement('span');\n", - " status_bar.classList = 'mpl-message pull-right';\n", - " toolbar.appendChild(status_bar);\n", - " this.message = status_bar;\n", - "\n", - " // Add the close button to the window.\n", - " var buttongrp = document.createElement('div');\n", - " buttongrp.classList = 'btn-group inline pull-right';\n", - " button = document.createElement('button');\n", - " button.classList = 'btn btn-mini btn-primary';\n", - " button.href = '#';\n", - " button.title = 'Stop Interaction';\n", - " button.innerHTML = '';\n", - " button.addEventListener('click', function (_evt) {\n", - " fig.handle_close(fig, {});\n", - " });\n", - " button.addEventListener(\n", - " 'mouseover',\n", - " on_mouseover_closure('Stop Interaction')\n", - " );\n", - " buttongrp.appendChild(button);\n", - " var titlebar = this.root.querySelector('.ui-dialog-titlebar');\n", - " titlebar.insertBefore(buttongrp, titlebar.firstChild);\n", - "};\n", - "\n", - "mpl.figure.prototype._remove_fig_handler = function (event) {\n", - " var fig = event.data.fig;\n", - " if (event.target !== this) {\n", - " // Ignore bubbled events from children.\n", - " return;\n", - " }\n", - " fig.close_ws(fig, {});\n", - "};\n", - "\n", - "mpl.figure.prototype._root_extra_style = function (el) {\n", - " el.style.boxSizing = 'content-box'; // override notebook setting of border-box.\n", - "};\n", - "\n", - "mpl.figure.prototype._canvas_extra_style = function (el) {\n", - " // this is important to make the div 'focusable\n", - " el.setAttribute('tabindex', 0);\n", - " // reach out to IPython and tell the keyboard manager to turn it's self\n", - " // off when our div gets focus\n", - "\n", - " // location in version 3\n", - " if (IPython.notebook.keyboard_manager) {\n", - " IPython.notebook.keyboard_manager.register_events(el);\n", - " } else {\n", - " // location in version 2\n", - " IPython.keyboard_manager.register_events(el);\n", - " }\n", - "};\n", - "\n", - "mpl.figure.prototype._key_event_extra = function (event, _name) {\n", - " var manager = IPython.notebook.keyboard_manager;\n", - " if (!manager) {\n", - " manager = IPython.keyboard_manager;\n", - " }\n", - "\n", - " // Check for shift+enter\n", - " if (event.shiftKey && event.which === 13) {\n", - " this.canvas_div.blur();\n", - " // select the cell after this one\n", - " var index = IPython.notebook.find_cell_index(this.cell_info[0]);\n", - " IPython.notebook.select(index + 1);\n", - " }\n", - "};\n", - "\n", - "mpl.figure.prototype.handle_save = function (fig, _msg) {\n", - " fig.ondownload(fig, null);\n", - "};\n", - "\n", - "mpl.find_output_cell = function (html_output) {\n", - " // Return the cell and output element which can be found *uniquely* in the notebook.\n", - " // Note - this is a bit hacky, but it is done because the \"notebook_saving.Notebook\"\n", - " // IPython event is triggered only after the cells have been serialised, which for\n", - " // our purposes (turning an active figure into a static one), is too late.\n", - " var cells = IPython.notebook.get_cells();\n", - " var ncells = cells.length;\n", - " for (var i = 0; i < ncells; i++) {\n", - " var cell = cells[i];\n", - " if (cell.cell_type === 'code') {\n", - " for (var j = 0; j < cell.output_area.outputs.length; j++) {\n", - " var data = cell.output_area.outputs[j];\n", - " if (data.data) {\n", - " // IPython >= 3 moved mimebundle to data attribute of output\n", - " data = data.data;\n", - " }\n", - " if (data['text/html'] === html_output) {\n", - " return [cell, data, j];\n", - " }\n", - " }\n", - " }\n", - " }\n", - "};\n", - "\n", - "// Register the function which deals with the matplotlib target/channel.\n", - "// The kernel may be null if the page has been refreshed.\n", - "if (IPython.notebook.kernel !== null) {\n", - " IPython.notebook.kernel.comm_manager.register_target(\n", - " 'matplotlib',\n", - " mpl.mpl_figure_comm\n", - " );\n", - "}\n" - ], - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - }, - { - "data": { - "text/html": [ - "" - ], - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - }, - { - "name": "stdout", - "output_type": "stream", - "text": [ - "New LM\n" - ] - } - ], - "source": [ - "%matplotlib notebook\n", - "%matplotlib notebook\n", - "main()" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.9.7" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/SLAM/FastSLAM1/FastSLAM1.ipynb b/SLAM/FastSLAM1/FastSLAM1.ipynb deleted file mode 100644 index 60faed6e88..0000000000 --- a/SLAM/FastSLAM1/FastSLAM1.ipynb +++ /dev/null @@ -1,676 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## FastSLAM1.0" - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "" - ] - }, - "execution_count": 1, - "metadata": { - "image/png": { - "width": 600 - } - }, - "output_type": "execute_result" - } - ], - "source": [ - "from IPython.display import Image\n", - "Image(filename=\"animation.png\",width=600)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Simulation\n", - "\n", - "This is a feature based SLAM example using FastSLAM 1.0.\n", - "\n", - "The blue line is ground truth, the black line is dead reckoning, the red\n", - "line is the estimated trajectory with FastSLAM.\n", - "\n", - "The red points are particles of FastSLAM.\n", - "\n", - "Black points are landmarks, blue crosses are estimated landmark\n", - "positions by FastSLAM.\n", - "\n", - "\n", - "![gif](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM1/animation.gif)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Introduction\n", - "\n", - "FastSLAM algorithm implementation is based on particle filters and belongs to the family of probabilistic SLAM approaches. It is used with feature-based maps (see gif above) or with occupancy grid maps.\n", - "\n", - "As it is shown, the particle filter differs from EKF by representing the robot's estimation through a set of particles. Each single particle has an independent belief, as it holds the pose $(x, y, \\theta)$ and an array of landmark locations $[(x_1, y_1), (x_2, y_2), ... (x_n, y_n)]$ for n landmarks.\n", - "\n", - "* The blue line is the true trajectory\n", - "* The red line is the estimated trajectory\n", - "* The red dots represent the distribution of particles\n", - "* The black line represent dead reckoning tracjectory\n", - "* The blue x is the observed and estimated landmarks\n", - "* The black x is the true landmark\n", - "\n", - "I.e. Each particle maintains a deterministic pose and n-EKFs for each landmark and update it with each measurement." - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Algorithm walkthrough\n", - "\n", - "The particles are initially drawn from a uniform distribution the represent the initial uncertainty.\n", - "At each time step we do:\n", - "\n", - "* Predict the pose for each particle by using $u$ and the motion model (the landmarks are not updated). \n", - "* Update the particles with observations $z$, where the weights are adjusted based on how likely the particle to have the correct pose given the sensor measurement\n", - "* Resampling such that the particles with the largest weights survive and the unlikely ones with the lowest weights die out.\n", - "\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### 1- Predict\n", - "The following equations and code snippets we can see how the particles distribution evolves in case we provide only the control $(v,w)$, which are the linear and angular velocity respectively. \n", - "\n", - "$\\begin{equation*}\n", - "F=\n", - "\\begin{bmatrix}\n", - "1 & 0 & 0 \\\\\n", - "0 & 1 & 0 \\\\\n", - "0 & 0 & 1 \n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "$\\begin{equation*}\n", - "B=\n", - "\\begin{bmatrix}\n", - "\\Delta t cos(\\theta) & 0\\\\\n", - "\\Delta t sin(\\theta) & 0\\\\\n", - "0 & \\Delta t\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n", - "$\\begin{equation*}\n", - "X = FX + BU \n", - "\\end{equation*}$\n", - "\n", - "\n", - "$\\begin{equation*}\n", - "\\begin{bmatrix}\n", - "x_{t+1} \\\\\n", - "y_{t+1} \\\\\n", - "\\theta_{t+1}\n", - "\\end{bmatrix}=\n", - "\\begin{bmatrix}\n", - "1 & 0 & 0 \\\\\n", - "0 & 1 & 0 \\\\\n", - "0 & 0 & 1 \n", - "\\end{bmatrix}\\begin{bmatrix}\n", - "x_{t} \\\\\n", - "y_{t} \\\\\n", - "\\theta_{t}\n", - "\\end{bmatrix}+\n", - "\\begin{bmatrix}\n", - "\\Delta t cos(\\theta) & 0\\\\\n", - "\\Delta t sin(\\theta) & 0\\\\\n", - "0 & \\Delta t\n", - "\\end{bmatrix}\n", - "\\begin{bmatrix}\n", - "v_{t} + \\sigma_v\\\\\n", - "w_{t} + \\sigma_w\\\\\n", - "\\end{bmatrix}\n", - "\\end{equation*}$\n", - "\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The following snippets playsback the recorded trajectory of each particle.\n", - "\n", - "To get the insight of the motion model change the value of $R$ and re-run the cells again. As R is the parameters that indicates how much we trust that the robot executed the motion commands.\n", - "\n", - "It is interesting to notice also that only motion will increase the uncertainty in the system as the particles start to spread out more. If observations are included the uncertainty will decrease and particles will converge to the correct estimate." - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "# CODE SNIPPET #\n", - "import numpy as np\n", - "import math\n", - "from copy import deepcopy\n", - "# Fast SLAM covariance\n", - "Q = np.diag([3.0, np.deg2rad(10.0)])**2\n", - "R = np.diag([1.0, np.deg2rad(20.0)])**2\n", - "\n", - "# Simulation parameter\n", - "Qsim = np.diag([0.3, np.deg2rad(2.0)])**2\n", - "Rsim = np.diag([0.5, np.deg2rad(10.0)])**2\n", - "OFFSET_YAWRATE_NOISE = 0.01\n", - "\n", - "DT = 0.1 # time tick [s]\n", - "SIM_TIME = 50.0 # simulation time [s]\n", - "MAX_RANGE = 20.0 # maximum observation range\n", - "M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association.\n", - "STATE_SIZE = 3 # State size [x,y,yaw]\n", - "LM_SIZE = 2 # LM srate size [x,y]\n", - "N_PARTICLE = 100 # number of particle\n", - "NTH = N_PARTICLE / 1.5 # Number of particle for re-sampling\n", - "\n", - "class Particle:\n", - "\n", - " def __init__(self, N_LM):\n", - " self.w = 1.0 / N_PARTICLE\n", - " self.x = 0.0\n", - " self.y = 0.0\n", - " self.yaw = 0.0\n", - " # landmark x-y positions\n", - " self.lm = np.zeros((N_LM, LM_SIZE))\n", - " # landmark position covariance\n", - " self.lmP = np.zeros((N_LM * LM_SIZE, LM_SIZE))\n", - "\n", - "def motion_model(x, u):\n", - " F = np.array([[1.0, 0, 0],\n", - " [0, 1.0, 0],\n", - " [0, 0, 1.0]])\n", - "\n", - " B = np.array([[DT * math.cos(x[2, 0]), 0],\n", - " [DT * math.sin(x[2, 0]), 0],\n", - " [0.0, DT]])\n", - " x = F @ x + B @ u\n", - " \n", - " x[2, 0] = pi_2_pi(x[2, 0])\n", - " return x\n", - " \n", - "def predict_particles(particles, u):\n", - " for i in range(N_PARTICLE):\n", - " px = np.zeros((STATE_SIZE, 1))\n", - " px[0, 0] = particles[i].x\n", - " px[1, 0] = particles[i].y\n", - " px[2, 0] = particles[i].yaw\n", - " ud = u + (np.random.randn(1, 2) @ R).T # add noise\n", - " px = motion_model(px, ud)\n", - " particles[i].x = px[0, 0]\n", - " particles[i].y = px[1, 0]\n", - " particles[i].yaw = px[2, 0]\n", - "\n", - " return particles\n", - "\n", - "def pi_2_pi(angle):\n", - " return (angle + math.pi) % (2 * math.pi) - math.pi\n", - "\n", - "# END OF SNIPPET\n", - "\n", - "N_LM = 0 \n", - "particles = [Particle(N_LM) for i in range(N_PARTICLE)]\n", - "time= 0.0\n", - "v = 1.0 # [m/s]\n", - "yawrate = 0.1 # [rad/s]\n", - "u = np.array([v, yawrate]).reshape(2, 1)\n", - "history = []\n", - "while SIM_TIME >= time:\n", - " time += DT\n", - " particles = predict_particles(particles, u)\n", - " history.append(deepcopy(particles))\n" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "data": { - "application/vnd.jupyter.widget-view+json": { - "model_id": "3f279cf1dcaf4ec886c01942c36e601d", - "version_major": 2, - "version_minor": 0 - }, - "text/plain": [ - "interactive(children=(IntSlider(value=0, description='t', max=499), Output()), _dom_classes=('widget-interact'…" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "# from IPython.html.widgets import *\n", - "from ipywidgets import *\n", - "import numpy as np\n", - "import matplotlib.pyplot as plt\n", - "%matplotlib inline\n", - "\n", - "# playback the recorded motion of the particles\n", - "def plot_particles(t=0):\n", - " x = []\n", - " y = []\n", - " for i in range(len(history[t])):\n", - " x.append(history[t][i].x)\n", - " y.append(history[t][i].y)\n", - " plt.figtext(0.15,0.82,'t = ' + str(t))\n", - " plt.plot(x, y, '.r')\n", - " plt.axis([-20,20, -5,25])\n", - "\n", - "interact(plot_particles, t=(0,len(history)-1,1));" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### 2- Update\n", - "\n", - "For the update step it is useful to observe a single particle and the effect of getting a new measurements on the weight of the particle.\n", - "\n", - "As mentioned earlier, each particle maintains $N$ $2x2$ EKFs to estimate the landmarks, which includes the EKF process described in the EKF notebook. The difference is the change in the weight of the particle according to how likely the measurement is.\n", - "\n", - "The weight is updated according to the following equation: \n", - "\n", - "$\\begin{equation*}\n", - "w_i = |2\\pi Q|^{\\frac{-1}{2}} exp\\{\\frac{-1}{2}(z_t - \\hat z_i)^T Q^{-1}(z_t-\\hat z_i)\\}\n", - "\\end{equation*}$\n", - "\n", - "Where, $w_i$ is the computed weight, $Q$ is the measurement covariance, $z_t$ is the actual measurment and $\\hat z_i$ is the predicted measurement of particle $i$.\n", - "\n", - "To experiment this, a single particle is initialized then passed an initial measurement, which results in a relatively average weight. However, setting the particle coordinate to a wrong value to simulate wrong estimation will result in a very low weight. The lower the weight the less likely that this particle will be drawn during resampling and probably will die out." - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "initial weight 1.0\n", - "weight after landmark intialization 1.0\n", - "weight after update 0.023098460073039763\n", - "weight after wrong prediction 7.951154575772496e-07\n" - ] - } - ], - "source": [ - "# CODE SNIPPET #\n", - "def observation(xTrue, xd, u, RFID):\n", - "\n", - " # calc true state\n", - " xTrue = motion_model(xTrue, u)\n", - "\n", - " # add noise to range observation\n", - " z = np.zeros((3, 0))\n", - " for i in range(len(RFID[:, 0])):\n", - "\n", - " dx = RFID[i, 0] - xTrue[0, 0]\n", - " dy = RFID[i, 1] - xTrue[1, 0]\n", - " d = math.sqrt(dx**2 + dy**2)\n", - " angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])\n", - " if d <= MAX_RANGE:\n", - " dn = d + np.random.randn() * Qsim[0, 0] # add noise\n", - " anglen = angle + np.random.randn() * Qsim[1, 1] # add noise\n", - " zi = np.array([dn, pi_2_pi(anglen), i]).reshape(3, 1)\n", - " z = np.hstack((z, zi))\n", - "\n", - " # add noise to input\n", - " ud1 = u[0, 0] + np.random.randn() * Rsim[0, 0]\n", - " ud2 = u[1, 0] + np.random.randn() * Rsim[1, 1] + OFFSET_YAWRATE_NOISE\n", - " ud = np.array([ud1, ud2]).reshape(2, 1)\n", - "\n", - " xd = motion_model(xd, ud)\n", - "\n", - " return xTrue, z, xd, ud\n", - "\n", - "def update_with_observation(particles, z):\n", - " for iz in range(len(z[0, :])):\n", - "\n", - " lmid = int(z[2, iz])\n", - "\n", - " for ip in range(N_PARTICLE):\n", - " # new landmark\n", - " if abs(particles[ip].lm[lmid, 0]) <= 0.01:\n", - " particles[ip] = add_new_lm(particles[ip], z[:, iz], Q)\n", - " # known landmark\n", - " else:\n", - " w = compute_weight(particles[ip], z[:, iz], Q)\n", - " particles[ip].w *= w\n", - " particles[ip] = update_landmark(particles[ip], z[:, iz], Q)\n", - "\n", - " return particles\n", - "\n", - "def compute_weight(particle, z, Q):\n", - " lm_id = int(z[2])\n", - " xf = np.array(particle.lm[lm_id, :]).reshape(2, 1)\n", - " Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2])\n", - " zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q)\n", - " dx = z[0:2].reshape(2, 1) - zp\n", - " dx[1, 0] = pi_2_pi(dx[1, 0])\n", - "\n", - " try:\n", - " invS = np.linalg.inv(Sf)\n", - " except np.linalg.linalg.LinAlgError:\n", - " print(\"singuler\")\n", - " return 1.0\n", - "\n", - " num = math.exp(-0.5 * dx.T @ invS @ dx)\n", - " den = 2.0 * math.pi * math.sqrt(np.linalg.det(Sf))\n", - " w = num / den\n", - "\n", - " return w\n", - "\n", - "def compute_jacobians(particle, xf, Pf, Q):\n", - " dx = xf[0, 0] - particle.x\n", - " dy = xf[1, 0] - particle.y\n", - " d2 = dx**2 + dy**2\n", - " d = math.sqrt(d2)\n", - "\n", - " zp = np.array(\n", - " [d, pi_2_pi(math.atan2(dy, dx) - particle.yaw)]).reshape(2, 1)\n", - "\n", - " Hv = np.array([[-dx / d, -dy / d, 0.0],\n", - " [dy / d2, -dx / d2, -1.0]])\n", - "\n", - " Hf = np.array([[dx / d, dy / d],\n", - " [-dy / d2, dx / d2]])\n", - "\n", - " Sf = Hf @ Pf @ Hf.T + Q\n", - "\n", - " return zp, Hv, Hf, Sf\n", - "\n", - "def add_new_lm(particle, z, Q):\n", - "\n", - " r = z[0]\n", - " b = z[1]\n", - " lm_id = int(z[2])\n", - "\n", - " s = math.sin(pi_2_pi(particle.yaw + b))\n", - " c = math.cos(pi_2_pi(particle.yaw + b))\n", - "\n", - " particle.lm[lm_id, 0] = particle.x + r * c\n", - " particle.lm[lm_id, 1] = particle.y + r * s\n", - "\n", - " # covariance\n", - " Gz = np.array([[c, -r * s],\n", - " [s, r * c]])\n", - "\n", - " particle.lmP[2 * lm_id:2 * lm_id + 2] = Gz @ Q @ Gz.T\n", - "\n", - " return particle\n", - "\n", - "def update_KF_with_cholesky(xf, Pf, v, Q, Hf):\n", - " PHt = Pf @ Hf.T\n", - " S = Hf @ PHt + Q\n", - "\n", - " S = (S + S.T) * 0.5\n", - " SChol = np.linalg.cholesky(S).T\n", - " SCholInv = np.linalg.inv(SChol)\n", - " W1 = PHt @ SCholInv\n", - " W = W1 @ SCholInv.T\n", - "\n", - " x = xf + W @ v\n", - " P = Pf - W1 @ W1.T\n", - "\n", - " return x, P\n", - "\n", - "def update_landmark(particle, z, Q):\n", - "\n", - " lm_id = int(z[2])\n", - " xf = np.array(particle.lm[lm_id, :]).reshape(2, 1)\n", - " Pf = np.array(particle.lmP[2 * lm_id:2 * lm_id + 2, :])\n", - "\n", - " zp, Hv, Hf, Sf = compute_jacobians(particle, xf, Pf, Q)\n", - "\n", - " dz = z[0:2].reshape(2, 1) - zp\n", - " dz[1, 0] = pi_2_pi(dz[1, 0])\n", - "\n", - " xf, Pf = update_KF_with_cholesky(xf, Pf, dz, Q, Hf)\n", - "\n", - " particle.lm[lm_id, :] = xf.T\n", - " particle.lmP[2 * lm_id:2 * lm_id + 2, :] = Pf\n", - "\n", - " return particle\n", - "\n", - "# END OF CODE SNIPPET #\n", - "\n", - "\n", - "\n", - "# Setting up the landmarks\n", - "RFID = np.array([[10.0, -2.0],\n", - " [15.0, 10.0]])\n", - "N_LM = RFID.shape[0]\n", - "\n", - "# Initialize 1 particle\n", - "N_PARTICLE = 1\n", - "particles = [Particle(N_LM) for i in range(N_PARTICLE)]\n", - "\n", - "xTrue = np.zeros((STATE_SIZE, 1))\n", - "xDR = np.zeros((STATE_SIZE, 1))\n", - "\n", - "print(\"initial weight\", particles[0].w)\n", - "\n", - "xTrue, z, _, ud = observation(xTrue, xDR, u, RFID)\n", - "# Initialize landmarks\n", - "particles = update_with_observation(particles, z)\n", - "print(\"weight after landmark intialization\", particles[0].w)\n", - "particles = update_with_observation(particles, z)\n", - "print(\"weight after update \", particles[0].w)\n", - "\n", - "particles[0].x = -10\n", - "particles = update_with_observation(particles, z)\n", - "print(\"weight after wrong prediction\", particles[0].w)\n", - " " - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### 3- Resampling\n", - "\n", - "In the reseampling steps a new set of particles are chosen from the old set. This is done according to the weight of each particle. \n", - "\n", - "The figure shows 100 particles distributed uniformly between [-0.5, 0.5] with the weights of each particle distributed according to a Gaussian funciton. \n", - "\n", - "The resampling picks \n", - "\n", - "$i \\in 1,...,N$ particles with probability to pick particle with index $i ∝ \\omega_i$, where $\\omega_i$ is the weight of that particle\n", - "\n", - "\n", - "To get the intuition of the resampling step we will look at a set of particles which are initialized with a given x location and weight. After the resampling the particles are more concetrated in the location where they had the highest weights. This is also indicated by the indices \n" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - }, - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "# CODE SNIPPET #\n", - "def normalize_weight(particles):\n", - "\n", - " sumw = sum([p.w for p in particles])\n", - "\n", - " try:\n", - " for i in range(N_PARTICLE):\n", - " particles[i].w /= sumw\n", - " except ZeroDivisionError:\n", - " for i in range(N_PARTICLE):\n", - " particles[i].w = 1.0 / N_PARTICLE\n", - "\n", - " return particles\n", - "\n", - " return particles\n", - "\n", - "\n", - "def resampling(particles):\n", - " \"\"\"\n", - " low variance re-sampling\n", - " \"\"\"\n", - "\n", - " particles = normalize_weight(particles)\n", - "\n", - " pw = []\n", - " for i in range(N_PARTICLE):\n", - " pw.append(particles[i].w)\n", - "\n", - " pw = np.array(pw)\n", - "\n", - " Neff = 1.0 / (pw @ pw.T) # Effective particle number\n", - " # print(Neff)\n", - "\n", - " if Neff < NTH: # resampling\n", - " wcum = np.cumsum(pw)\n", - " base = np.cumsum(pw * 0.0 + 1 / N_PARTICLE) - 1 / N_PARTICLE\n", - " resampleid = base + np.random.rand(base.shape[0]) / N_PARTICLE\n", - "\n", - " inds = []\n", - " ind = 0\n", - " for ip in range(N_PARTICLE):\n", - " while ((ind < wcum.shape[0] - 1) and (resampleid[ip] > wcum[ind])):\n", - " ind += 1\n", - " inds.append(ind)\n", - "\n", - " tparticles = particles[:]\n", - " for i in range(len(inds)):\n", - " particles[i].x = tparticles[inds[i]].x\n", - " particles[i].y = tparticles[inds[i]].y\n", - " particles[i].yaw = tparticles[inds[i]].yaw\n", - " particles[i].w = 1.0 / N_PARTICLE\n", - "\n", - " return particles, inds\n", - "# END OF SNIPPET #\n", - "\n", - "\n", - "\n", - "def gaussian(x, mu, sig):\n", - " return np.exp(-np.power(x - mu, 2.) / (2 * np.power(sig, 2.)))\n", - "N_PARTICLE = 100\n", - "particles = [Particle(N_LM) for i in range(N_PARTICLE)]\n", - "x_pos = []\n", - "w = []\n", - "for i in range(N_PARTICLE):\n", - " particles[i].x = np.linspace(-0.5,0.5,N_PARTICLE)[i]\n", - " x_pos.append(particles[i].x)\n", - " particles[i].w = gaussian(i, N_PARTICLE/2, N_PARTICLE/20)\n", - " w.append(particles[i].w)\n", - " \n", - "\n", - "# Normalize weights\n", - "sw = sum(w)\n", - "for i in range(N_PARTICLE):\n", - " w[i] /= sw\n", - "\n", - "particles, new_indices = resampling(particles)\n", - "x_pos2 = []\n", - "for i in range(N_PARTICLE):\n", - " x_pos2.append(particles[i].x)\n", - " \n", - "# Plot results\n", - "fig, ((ax1,ax2,ax3)) = plt.subplots(nrows=3, ncols=1)\n", - "fig.tight_layout()\n", - "ax1.plot(x_pos,np.ones((N_PARTICLE,1)), '.r', markersize=2)\n", - "ax1.set_title(\"Particles before resampling\")\n", - "ax1.axis((-1, 1, 0, 2))\n", - "ax2.plot(w)\n", - "ax2.set_title(\"Weights distribution\")\n", - "ax3.plot(x_pos2,np.ones((N_PARTICLE,1)), '.r')\n", - "ax3.set_title(\"Particles after resampling\")\n", - "ax3.axis((-1, 1, 0, 2))\n", - "fig.subplots_adjust(hspace=0.8)\n", - "plt.show()\n", - "\n", - "plt.figure()\n", - "plt.hist(new_indices)\n", - "plt.xlabel(\"Particles indices to be resampled\")\n", - "plt.ylabel(\"# of time index is used\")\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### References\n", - "\n", - "http://www.probabilistic-robotics.org/\n", - "\n", - "http://ais.informatik.uni-freiburg.de/teaching/ws12/mapping/pdf/slam10-fastslam.pdf" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.7.5" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/SLAM/FastSLAM1/animation.png b/SLAM/FastSLAM1/animation.png deleted file mode 100644 index 86c2950f709e3a0b97fa7b5509ae9951b7f8e883..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 44443 zcmeFZ^;=uf(l(5f;uLplX>lkHh2Ru-mp~~_aEIWoZGqzMZowT|C@#UBQrz9?m!5N; zbI$W!*ZU8=*P9=*c2;K1nl*dx$?SXXl}J@(S!@h)3Ieu(0SE|)>i{%( z5AWpiZ+L^~qAn|exG>1-4?mu<*3@;?RZAA-$Y zO=&&BcJ?kpo+9-BkPw0&|Lx|Wr~QYBtE~vVu97OPq=U0LEiXF{J14y;1}!b^d*@FU zLh4d7{~8YeBtmcH>gp)O!QtWI!S2D$?%-_6!6hgt$iexJ5c)Y;7iI?`rN0 zAM9%S*E-R6{~G;&miYhcQgOC6hp+k{qyJ~_|L*&j{CkeS3;!=i{L{<-=!Lsk6yrU| zzfYMchM;Ss4FZA~f}E7NrYGVdfiZu9U735f`i0DeI~2?zkR4kbO<9F}1kwFOY%)XlVg}e>R`c0{K!mG)ak2 zP!Pq%@bLcGOaLMf-cpJG&qsJ~U<@5Cl1V?g;r#!SL=oFV{$J{_5b+VXXV-hH{xbyt zi5@|o=3kos(a@T~^{3RLk+`G&*Q9ues`vk8832h)QVgX#hPSzf<$tXGYcwEW3jM!r z{YeVfZ&A?`YV;rb@ld1?5=H;LNcb?Zemp!xPBU!wLyZ4kKT^)+e_Md^E)1@p%+}FV z=fBntUs56Nzx?%&<}(*u|A=ldX4`+S9quy7zdiW>T=xH5_U~KZ|GultqO~fU|j*~x{0&xL4(c#feD4RODil=2(Aq3{UW%lyJC6=Qb$WobG-_)x9s^o zR#VEELTXL+D?>`(uxhb=!f+h2T z#y#OzT_`+QE!a40G=>3wV)DM9&sLWO*M|lgWB`%y5~T@te;(uqHji;%px8Z&~B2 zXOnuWuk#Ien<2U;A>tpPg+01~5?LLN0+DE(q;K{VdPo=K>5y_N*(kU{=RfAj*A2($ z9@{fO86*(mK2Gc(`Y_gWns1ituY#0xp&{%5#8f04iJz;U_y|YfrFnq_4jF$dJ-{ch zcKTRdO%DwhGwbtbY1-!xgY`S{xC0o=KpP2~=^ z7|SR%xc)4O!&H|Uc*^f}{>l6I7g?Us?a}nT2!^-0g16 zFM6h{=Mm6ukO6)l{qSR8hYR(4Q7l!ox4$0oKgYlD_qB^#S=8Rn@;PpypFM8bq26EZ z5bikZr{MYY6VJxVD#yT~BZ=DgRGeJYx4Ed};kd0-C0mrotUpFVSB=p*AOAB+n7?d5 zjU|Tv<^U+?t)_P%$sZ83}?*wE6qAUv{w>EE3xxc1$Lz(gyVC8``3r z+MT&v@8-wbAl*`0!0PAH9`+@rZp*3rpj#%DXcH@VB*va}*i=G^_g4qS`K$haAp6TL z+-?W6l@UWPAUCY}FWek9Z8{)N5@H!0GLLE+*}M-z*Fh770gycumVHBZBt zvjwT%_TaxTRuB}p!N26e>`jr^zin$JN8MScCz1*btvM6wZNv! zo{g`Z=6)1xG*>X$k2L-|Py__jTp2Vw<~E{#>fhk!<4bD_J%FD(qN>s8gQ~W;s@8pG z?hhc9biUZdCI=9JziUEIqu;df7&Fp{(J@-rq! zyXwzzMF->b%M6lVEy|SJ9^+0Qk_o-5!Uv;U))_b+=^CX0A)FC=>u<6=k?=$Lu=}#p zSId1T9GitzZaPx4y^e~wPv$CZB~QA#kSq08Qbj$R*sf9@7~O6^vAI3iv0Xhn6J0rJ zPwMQ72t{aXSPo_HwY4Z2*sNU&M*VDaj=$fMb(ItKVsOh#f|fIzzwzd8;;vjN!>wGN z`jTZ^Px4f_C!jQ~SJ}Gil8k$GrSs6KB7FQPc(uRs0rF5)?0%#lvqHv#7o@VB{^y!n3ArxUGG=Y4N#KWnh{sHb7y#zHW+wQIlu?wxZMW2KIl1>7H&WQjVI zdo6Y_kBgq0&4Kti3lYXjFUZ*s5*XB4g*YgM2BrCq_vDV;)sQ&cYsJM-*Lxz#`6s4% z&A6*!n9f}e*XAAhhP`)4ZTdTN`CL{U7g%zurFYZ#l|}Yui*n&PH~f3+^1_|-FSvHk z+$V{Ay*9Q_8DQUBarOfXrczuJ*Sh?F%)g!F^p?<=S4` zft~_Q4q?_o+rXkt&I@Bm?f!aEzf5@bM*0n7hu6_q{N_9d5e=guTh`fcT_cTQnA5@dlqbBk>sYDjMUt`<~A4Y={U{?Kqyk!OhrwSUI9_!j6RfaCID zk-=#9>;gN3;EC**PPtI^K|!j|85|Fa@jlfzg0R~0OGB0GQBQs)w*B!dlk9`d>yjcMDBpJ(dyf=0gx9(^Y(>4`+cBJFOvx&msF*Xe*>dvB91 zK2EKbK2cn_Lf~Fg#^gJe%eL>JI_lawna(7apS^fG1{EJ&FT{$jIFamMWAk1;B~{}c z)nW1;wR3MJGKKm?HGGm`MuJICjGfl+%0&zHz298>!>C^$whQ`0?|oxLs^|T+4LNz| ze#&4h>vDVcPx$KcId9tBcKW3SY;}k*#A*!^iH6JA;HIgZ8imJ1{PG}2{Q3t|EpL3+ z$I9%E_80w+chwEv*Ynys+PefB5WmYw*?~2&7tDbJ4zCd`+$rnbF-UvYI&M}KG>VnA zV4_EtWot_5eE7uP-94h{8fd`hv-k$uh#z#x#@?mID81!Deb+PK#sx;!QeIcp+;l$W zSx#a^2H_(p0aGRS)!{+{8aBC<%g$IK5sNln@4*(dgP>8;`Gs$ZO7t0$T6pY%)!Ryj z#VK{zDC9av=?Pu6?de`);OY9+qK|`mKh)+W-$|mL@t5*X<_pOnKlPMG=An`Hy+tju z+fq^=Ww?~Wv#)ffA3P1>p&UR>@e^m~f!nY~y;cx24eQ5g!ti_$s3>mPOP&N+- z#Y9Cv9n^8wkH=${_FgIdsX?`QfLf{#hmQR0=r?8vD&=nppxOM9>70>=mc&!1>rSSZ zDjG9|p~g&4Z?@RCKesO_>muPv5pAPqU|%mTY^8J+V43Om4X1TG%@zu@7$F7Ya@x&v z@`{R@eI0I~Rpmpv{pooz%I_vLZ?lqzLg)*g)i;?%`ckK|a`}C&q%X!IS9T@}wX?}e z#ar-(E$xU>3OhKipabVvnZc(+Ztd|SF?dd^gS_*a*ZF!ad$C-aFr&zhQ-TqJ@3zFG z@9gtn)Xzn+;rO*4bdp|74go7%kbkDtp1OLhs_yg|o;)_{3 zUp#9mGi7gjFQ<4pBWuUmW(aQmNa9V>tDQ1;w|tFP2n=x_L`CAr^FNo+FqWWgr+ zg5P9H?az1JhKl=bOCj&B#p|kWKfg-rn({nzmzl9zQ`lkWl9PeMPOqBcrrBlyr?iBa z1QVB~3AT#4xG?Cv`_^7j{;nK(WrMG5#%$)8)?(Q=Ue!V0-(=;jn0yn2Wn_UF_e9WO zj!vn#y4Pcs##$-tGU;W7pi9MLfcJh<{vJs^t`6Ui%;{fT^yX?31C)|Brn>Kg8s^u~ zfNHF7>s8Hco%5=BA^?CKSPQ3#uN8Gc$t1y@+(BV9O(H9V`3QNKaksd-ua#=J8iGUjKALOn zbt~&GxVx{-iuf3lN8R+-zMpZXKzoF!+4BdJ8t{mAt}kJ~mt8ovsQnc! zd%O!}UCeePmz^&65W^=XEj@~Xg^If_n}OnQ2bD2Hb~0rJuVBYp$+iAyg7R-e#6&Z) z=DH#;CDWt^CKD25U_a%GRmZ7up4Jt^$KIF6=0;X#Xsi?74M=az$bFKZecPm#9#n6Z z4#Y7A!OfKmyTHqJbMRufKyTCf`IkNOBJ>E;NaEuQScTT?qPW{MY3>uJ z2+$Nsu;XEu;jCYfz*>|_EP9UudH`#ha?0l`r*fyfhh0cl08TeyHf%5R1l8X6Bf zX>Oup#owY@e{tfn?XN>cFA#}8L%J$xJOid%oTS33inQ?+=MH-s9U>OvZhPr2cA>=s z6TMAsR$!1}xqLzp6PjH=E0bGUEA_n3Y3IWSD(Qmw3YYtvIel?Emii#~d>?X^9Gxm3 z=}gMaiMvfI_3+eNA%I`EoS^_p#evGkJbUy|RD4yP0P#n7I1rPOc&x(N$~?7(0bo(Wf+U^r;0Z3YO3i10j54= zth8#^L6_4SQhly zGM{zq?roB|5lr!-S*L#rGXqM$dG?f{Mpqa{BBUgJiwjio8|?qwK%{r>nn{eJcN#3B zTfgoRslQljV2=uMT{Y)%_~Ad1J=0RiM!{!*C~n0#k^HV$E39(;J8-8sd?pWHAVVPr zl_4JXLLcw@kf|be*MmK^{N-y!#Ck?f8sgox;(CA?AIoYiDmycdOR%}`(|AYT=!^Y6RO!1mc5w~2L0cxXV+5;#G zqXRr^S)+oQAxuXt#rY)BzRh}LVC*FY?i+D@Vp0+##%w_nG`$WYM9y+H5bD}_At};( zH_ddHX*Hh9^WiJT9)ZeWUO$$&HeF0Vz1iC&2~HTK+{2;6MCycTzTMfAP((=~?S3+w zFG~g&^oJcHsf0bA@~pK`m#>L#gF}+bh(OCA1RKu?lqBYW185)1F~`s70m+zK*t5($2y@I3Y7Nw#?n!}Nx>Rt-J>_Vl>R|sSh8c4?%pt! zwFfd0ZvzLR-*|Zo^&KQpD5e>qp7=JsP4BV<_4KHzInv)sBS1@eLzD06bF{C8e0-H0 zZUUp$1vo4ApEjxaVcFD2RXSIT?cpH8^=NQmh{!cbp4SCNc~~uE!~jZyZS2T` zO_c_E+j|`-Bi}-ZBEir-p0ShHFwp`qCC7(XPhu;zcZAHmQ9&{9MyHnX1PF+I?n;w7 zT5u_*-MgN4ms<8*Wp)O3PhEhyp_q}Kf1ZT+_2r|Ik@rN%F(8=bVKYTj^RhLHctS464u~q&TD#)QR)|56S%gzYh;rt z>XyAK=FN4bJj4;;Q!FnA=N8-=X2v*_@ zv(cf7%GGZxX|!*)$3$dRZhp0|2J*!F?JkSIF>2@T=*YO-qp~9K%N?4Qcf>Vk3o+S> zC)$KMg&RvXEq`sorQ{S-!32t#SqsJHpg$jgY#JOj24PZ<3N;Mhc>Pm-Ws?>{JXLxM zWV1Tn1=a@`qKILV*HW`~TZDk>uHJUBn~Od{XYWnjPPX~LGmERhDKSfGNc#Xn8gKM2 zuK!OWs>vT5n$Nve3Yi+}Z_U2@$(I>j*qqBuumXCor@hXk^A4(D5N81qmFOh=-u2fW z*5Gv-zicD03FDd?(dCEs;(#Ppq*8?T#5eeeoLkts@%xrX<@#NuD#Ec=(zbpA0Tx*XzqCo~Z=z48=* zaF`VF)^+}MeReVA#%;F;y}sUo7L%9J!uco`VO8Vy_T^CrE7)E6qHbIG1-^6ZJBBSt8@qzsP=`xQ%~!0euOt zM^@U+dZvEtVO&+;PiYex?GqFSFMBMQx4w+G^WnRC`USrC&&16`r&b;6MvnqN$Yt`P{mg?wrBC`K~o=dj}`S^2AUs7+o+i zl*#nHk8#>mop{sxKwnqA)o#(lNQ7PFI4LiN?nQJK5am7==zg1@>E_mKvBZz^DOLIY z_c-)mPI$`Kjkb@e_;%!wP2CnlM)6WLf^?v9oP8-qDNcZ$)c`pafd`36ev}sm0%kN5J$mf5A6ElfA~T z3ML6grJsL)-`l@775PT!vOaskn&fBDyNBlzc~-p7@im86$oL5LbK6=jc3aUBnVaQ0 zclOI4s_lVa?;+1b&8-YFEM)zb6@TuHM`*v^Es+_b#^|%mZ6&*110;0)xp+v~=zMCK!7d z<_sn)(ZAq7KZ2bIzn+&%T_?gUOTh8=JZ{WE!?62Qlk;f~I6h<8B-1Tl>1@kaj#E0+ zh@CFG=JiIMq9tE)(E4v)$=SoJd>MH(jXaWghNA#deVB3O+U_*3_k}^*~Po?z=I)rmrVlw7$eV&L}hIWPn zr(r5t#<#7eYwhlck+{**>u!tE?LfO_J05YX6vTpJZo$k*6NJrUkjHj~o>I)$;&7+& z@V!i{_x}CH1_RV+UBgD`RyOvJ(%M~IK4HjSHjWHX!vAYLN4Dq$<&SY=&O+7szvcSI zhLTf)m;j-1omf{X?jl%`^2&_nJZNurd@OJ6&)B3vJBp<$wR9Qk*12wFN*XFTSxuif z>7cCiT$R+kK&w}I%E9i-)>J>m&FL|&t|xG7sMxXWmvzD_Idz2}`s#PL@?ZjOLnnL$ zmN53V7ia1}=G<(ItMG1(Jp(`7Da|8*=Q;CGF|DZF@`L$B^I3D_3epGKC4jJ*4fr#^&0X~SnVhMeyaCskcE*(NqQj@O?(fh}js*zb+-hLts{P{p)MtU(}T8sE7c{=S+LPNQ5Z zBFavj@zHM0`_pJpwy*CD^3(k{CL|NcnTp$9q<>52lRJyA-tEDBK7*1+m zEPtycbE~DVZgc6|gqT-f#Y@`5;wn{2f6!gtbPo6gpRT&pR?#x4cxs z?olBgdDR;Eu{;A1P%Cch(H}WqKU#BiA@$HO7Zn7D^=wAhu3NA#hZaSk-|`~@9ICoR zU$W(3iDFsRj4z^3BHWvW#z)N`$$L5doUd(t7tfa|7EH1%&mdc*0l1Xa{8(#(_V*F< zYe#2|+qEunT)A`ruffc=hPyYwcVhpj7JV{5{-u$#oC2|pi-Gz>IuWH+?Cng;s!g2- zM(;Kb*j1X&?npD!`{iK8IDs zY{)fPC8*07v`Gzg|69sV{@@e6SkkPJ%s!nfiQX}hTmDjJu@PK;g5TMPBRs+0c9>`F zuA`Bp=fe9`(tIMS9xLX0P-$cR6V>%D=!)m?GiVBG=>okN8 z_eJbg;J+T{BS_GU>%QQADEe%PVWOL{QMbeL3(HAW&5_*fo}?Ut>tvyhtFHjFDp>8?7EE z$|ByE6I~)V%L(pFVE+B3CJt=Xoz?5@PE{E{Yud^^SyW{lH3@z`g@H4tqh!0hFKaDP z7M-M{#;HylRChj1RZ)zzAY)Es@y{e7uX6O&L&^VMx!7Wjl>on%IvO&6d%E}rZ#;~r z5MWinOL+{Wb%*N7TsSx)lu}WuRWsn)I0?n#>vX+=>m%!kWpl ziaJ1m7Sh{628nKkpTQGNlZ$1KBg% z)Hd@E2A92G|C~161?Rj#JY5eq*fEd>aM+d5N6&v{SEVooUW{u?C2b|cTYzX@ky3HlP5C1lZ4%^o!BwPW2*i}LI{?5~!Nnhi_Y z=*p3`a8;>b{CqZ~WBA;GhZobXIw+F@=V(~%=r+fE!gE%6(AL*5&qon{?fw^d+BhDV zT&vEOG@^dA-xvYKIc&*7cl$SQ|^YS8nckohx1_$TkuYWUj3!(`DQ#&`L>4+JEX@fPB08dm4;T1g7)l8t4WAV zV*RzNNG0f&#`RYuFuyoUUK_Wkjp=%3YVc#r{-V^mXmu;`S8+D@b6(9iD+6uqnc&ZJ zPzMxJBUuty!jf;cvEeiCzVq$5qhNo{ZZOzp9#`kfZb=TJ&+SIIHJq!1B0k_+GZ$Qg zE{@*itrA?<@hW6n*+QD3vpgPuip5r~L=~^dCSoWK3di%|Mcfg<0W_^_o8BFzICgsvkij8R9)3ae|3AC6JY`N5pR@ z+h6oAd4Lw{mkviRSz2W)?kpbCT-A*J4IHWzI`enWSv&ToG;-H-4(V>SkvD_r=Z(Iv zyYYg~d|kE)fafQ?2n&t$^c24Iv#o4uJKh=MHxr*4F8eM*aP0ww3%Mr{j&o_643UQk z3sbz08)1F<*Ibn^0#ClkQd>8yn@*Rg>Gz@ca4;>ha6EG<;Z*F47{ztQGMQ!Z8P|P^ z%z8I)DF`ijY?G=a4;K@Gmq>&*W4NJgc_bjU@Ygmq{rl@Tt8;u!H&aYJz7i@8=MS_E zCO|<6lj+-~6ws#=7mA+RjAFiT7jF)KM2O7<<6m3b@_pyfQ!;m??l-OOVn}*Ep?-}- zoOyJRMCw&$t=6%N>=rTjqjVJM8du~J5Av|IHXF@N``P3N%W?!h!zB{BUH1807aR>a zj8}o4h6^FHST+9ojv{J6;6OE#TBSp*uRj~uCw?os(+@W;GB8=3Qp z-C=xpe;dx%w~hiG$SjVvB-zP*j8MAevrB=@>M<5lX_fFC?N_>Y!)}0NdVEdY?tsz{ zioh)AA*Rrd6HeY28z|+5*%}O|dKhz2i^XGxj50N6-H7Cx09ZGP0J6h6PB_y?DEcDm z5%Q>M2D=*AXM6>^)t&2|UT8h`q4jY0N5RP3AB8B0tCayt+Un}yQVSIL#Yu`7p*ND3 z$01X3tM%|>vZ*ua#t9dljZ!)N#xX9<8`C)%rUgasP|{7({npp%?`WUPL!*BM3`vc0 zJb!z~9!jKL@Np48nt(RIWDAawgQ|EnCRD`*dK%wayII#QAdPiXG;@GD4V#cdfKbdu zbRTT$ibkR+eK>0?JE|p*lOIDFoh8Mz!cZ7`YBR-4qysy)xzD72xf5OcC9a0v> z`cV#pjhRsI1 zQSDNquKC@&n!X5Sf!t3kLKDRINl|W?fjbVcBx?2G(JxE4iVx2ZYXxJkZNaub8^ety ztWl78xiuoSZLbd(FyaWH;I*qc5NP7ssJLj*srQGOd`nPUALe6S?ErQ zw~}3L(v($%gT=6iE*~$vXd1)cqaG?7%ImtpP?wX-XVTu8M`iJa7?C;1$DpF?24WoH z6EhTeMa|)|&rT;sr-HJsVuCwp8)3eA|tlwS;12f)` zPxX{6yB6U^C^6DvWmOdULqdVv$g`KFBB#(%x?i`4CJ8umT7Ys3?e~CGQ{y?6_h%uE zCw;5V?WWvCzP0f*#FVE+Ka8!x80At1X=u;2g;;i|wKgfm;apl+;(to=3?4M5!5BTbx`XteOTH-i`OzaVcE!Hb>zmLAC>Hnj z<904`vsEnJ&*)Wt7$3PR0>@6E&s;hPjmB+&Ze1a!=>re^2yJN$O+0t)(TE z4SnpldFSvk%yOM6H|mR_?j8TlY(>-K_=A7`y7sciGY(*($3fWg4G72&X6$Y zZ%wbN;h8+S$I)!|)EgNzn+T@iEovQ12~}KUNX&F`)}psfbA@4WBpFB1_i36U1g;Lu zN<3nB6JCzP2a}!T-`MG?;Uy62kh+}E?mT?JEgs51994Pl_e3CyxE)=vOZt?}y>4;%N5EP3A>`W0lEm8%uj#lpxX9NUiXoK9B?m@Z0^6@dgR+@wE5UZQ}L} z%0f_vik)@b)OCf$hfH@^JGzE$1KVMl>98iSnnE+qH!h(Owt5^XHN}blX(>)N02PM? zmjV?Ld&M`=dvMD?fE!LQkr}F`M!pgw1+7DFR*H-7ojzhxHhx~Pt?q!HJUenaT}E^7 z?R&2@ux#0PDd}wN7(7Q?{25pGKJ8g##RxP?2k>q+hysJR3SaK?Fu)W1Gy{%7H;&rR zNX2M`f{HDEN4C=9#}oj6yldLap6zO3-ifWz8zRiW*ZakFu_LCR`!xl5gyzT0*C01+ ztjFDiv_;;zXTx>tJ7~hu`hX0+AOeF^H3T+VZEQ(`h>OS$;;0;zGucpzuJ0=}Uatg4 zdygPv)~;iMn)OO~fe96M*vI&#w=R4zV${wsDDGZv!lD{r*POcdvt84yng}xfrmy$bFHwE^8Iuf-1G(3K!NQ@Ji!|a zEaD!E0Ac=2`*fWUp`gB>m=+&dfMB5}B831g;j$f!DyI5seG&fjG)66(z68ChB340X zz;3iTbDArGAguJ#Brs5(nYWO$UUs{396ox|02Oacg-I&*L;Gb7xscuiHZ+4Ogef;~ zW(^#Oh@(vOZx29!giI_HyhK9C0teW&+W>uA-UC%1UeQ-RU=tr6O?=_QQ#RfOt& z^&$tdvj%qB+rjfQ{#}?s%}#Xh@b<}Af&f;a;UsnSdlXWkHU zH8b7huojd_!-wd1)G+t1K2zcK#JO0eId)DY#RyW)>wYMwDD`ZGUVg(sai%*t1kS5r zv=*wG(d6{sU6Hh$P)e@SD$m-4p`7=k?Wt_Eq5Fq~s?a4`%fe3;w8?~O|Ku+3ZA0mK zk&@J#tX-qwrIS;f8;sCzs^C<$27{KmeO7t%8j~I*a8oEzhokORbgX|ZUCkSd!goU^ z0=V<<%ypJ;Q;7QqkjJRP+CX3f*S*4I8?XtNImWSlOXvr1C^E(BQYOu03c)4;0vYz? zTke;Ika67msoyWn@Zk|te>$b%Q{jwgKp~$NJ5k)w*w5+^Ha&;e0+reK@~hg8T~85d zv4aXz<)!Z+$JJ|LFdHtJNsRTcsYxV(^~UHplqE-vCS9R08qSqyTc;kt=`}~i3oPX? zR2aVRm-9m2*uBI7(-KFnZz4h1-HuluHBaGi;I-a4p3<#(yGBnQBGxh8xf6NJmr6o7 z<9e}<>-veIex^0g7!wx&cT`Dx$!o7IAX zn#V+L;*`WRZ}!5<%OP%Btn?e|oI@(EQOxiJ>VFufoAQO@5CJbe|4fYzUb)mIdhc;; z$o3eB0Xbd|#+@A)O;S#(A)W8yb9ivYj4k%5GNKqRGilGC$d<~dTz-BO-MP_n#K^5d zg@fB*>p}AKz+`5u$-5tFZ^;|o@Y>;YDDzMb`X}w>GHV!p@$nKrWc4LV4{l?SX@(vS z%9OgsxS#$Y=N1pFTfqNxy~mr|((3*%s~Iwd>~PTgU_~~tIdwxJ3lsqL*7^l(q3(so#J=7^~@q+c;z@iMdB(SnTPG_6<`l>H% zY(6Wv$z8A6kuKBsd{A1j;pOM(k6Zmx0bm4FZUUkc+xI@Zw$a3FQx@pE!2-&7K1xOX zyegBX;I7EjHx;= zWey)}iWRbNQ}V5Q602sp1ELRy8uJrmje0d#7mKj?2K~HHz>6w+vytB765QAKh>drF zAlz_KRG)4*g0Khsq>64Q7$Ss9^;#$XzLA+gqi3j}LA@$trrl=7Og!D{TcfM>^Vl?B+Szu40gH8il2a@qF{Vh(YjiYF z#^!K2cSoHmvg@RTXRZcizrJ~Yg#e$IhsPSEX*CaZT!M|tUoi!OQ9RiFh@jCs&u1}_ zBW@F&^tz!!+uWRqLS_WXMC()<^qA#$cJVEKWayn;X4IJt6$4!iLf80Y@egw>#5c&w zyruaeZS=}BYKHRoyk&1Imea8*_|{{$x|>$;d6|qafaWLK%`z!3Lnz&9AY3Tpz>~Lm zvt0*Owp82VO{Gc(1F8HR**j%gg|L#A{N~L24-*hnaO~QAt(jzlmzkMHxgUv#5iHGL z!_4egtptrMXn^An*5_+MMTpcaieE$Tay_M+b40$VqAQJ7Z%%%QxJs)OD)~ud^^~*a zY(>$BvT%>OhfEr|{%@axI)|Pbvmh;5j=wsxlFr%)$7XF1wEFH_$3-7v;9Cyl{^shd zP!D(xo2v~oh1YkJ9wq5OzGtEA!;gzR)h+bLoXe6Ih;45gAs?5Bl>0=B&9nP#zleg0 zzg5-QXL`9BP*f82^$$22{wb>V4K3F_WWhEuO>%Hj+`u_Ive!y8sMrm?FlZ4LYbAM|kYSU%m}4_FFlNFxz3rygBA93OyMs*VI)dkCUYdMLz0oDVmg`A!X_brQhcofa+j4ZTii{{*a&)|4xHj%uyy($F2j0BXk&w{iBMs5<3Q7I6=2X{=nqK$NcQjW@ zi(gh#DH|Ca7YJD=&6_wPDIb$gs{Nl1v>W{thpnG{6TTg&T0b>s*uY#w54ow6rsH9b z#>SmG&x}T;?^9GJ(!5T2dld?$DTRwTqz#yd*U6fn?}3hL`m0{IqVx1z{vo!kG^?Y6S1F>Ue3bakBV7_L_j z#CwZIf3ge>W}3r)###Mkw%pi))Jg#RVV?(gg=XSSqRbDj;+qt-z4Z~F&ailzq62{u zrE-FDU=^mXdqx-}B)PSUuLHCivH3V^%RQp#FguBL)3z<3xZvb{jUR3qRlDIl%9$|R zE~D>m(d*LNZW4zPHimM75qSuw@p#DL8W2 zXX8JV_dW$pbO&tg6PkL~%xA>pJ<)t;PQ9^Nyz+zOz|xEB%EkNI%6YcZ){7Vq#QaCy zi(&bDsiybuQLk>xfy+aN_G!0L}A#V!_Z1=~TGN&SrXgq;`8Em>q+;Lx5%&Q@oIGOpZlTUl<8_5Pv~ zaEAouHugFh3NTAre}VW4`>FKhYMwl-m18HgJ8Er5O{+rY?vwQ+JF4|CWtO+X{9(K1 zAY)g}k&o=cS2#TzhV{)h6ruVVm9)cq3oP3o-<1`Lps z5!w!>(I$weS`u0spk`UMYvq+*pextX695MuJ=N5`WMM6L5`U^nYX{2@UyC2UNovY; zUz8I;?toSjj(JfFoTf`_xn&qmLMZunHB7;2Cf7lwCdPEW@aS#S6)`>4=AaO!k8uofgEp^%3!KMX_$Zvf1bFOl?uH&LjGY zO6UIoBxoN0qO>FrKff^4Po5JwM)rUg>a;FB%&p>{`lp}kX9VM8)0VQG>A}=IA-gqw zCD_E@mOb-5$UNofAW}F_D8=3-Nr|mACDrTN6v8_CiC7XnKTQn?=66$;(ou@bL{P7N zeBn&)t7jj}QW3_T@jpIluSenw^CBYbX>SpWog0VA;24ZjrjQoyv4G&G`5Mz);&y4x ztgkj*8ltby2 zKRF`6uVP_6sWPIQ_EWzWO0xGJKhuUG4NdW)-9>ObF>&nf<7F>FdkfYTdP3p$#e+>924{jj&aKjp<6=N916iAJ%W>Z( z2KF&ON<-n?64bw`)$P94#cHMBd@nM`Y1i{r^}Q`R&jb$r@&Qk{K99uW(0WgJS6z9f zKSe`nov5fitmxxLJhwK>R8+=Xt%Eemh6AAyM0(vK`}|&=0&!PUX~Y) zTlc+~7uSB{K$_AOn(GgJdFq;ym4KHFNjOv5V>&yU51J4+5MajbXfjTifvj zb~zhi*}8P6xObJVIjFwdJ!s~w8l89mQ#66IaOoBS^T5@^@_bo;6$l^(NXtj6J{#I1%}hG9t3j{zme75G4c2y=?*2L;2ydqU^Ifamq1P2D zagx-b)B_$@&Wjrxnjo@40^0m)Mhu1Ee!iOD)b{(va=cB4@~6(manLzU_meRL<2V%#ik0DTT8q z=G%b~9fGMI+M(mR?A4(-93cVgo0F-B@5d>GKQJhn5-RWtOax#y|S#;iiC{XGPy~w(=(>&Y=D_s-Fv}zcVY$9K3JeQZ} zaGM^dwnHpdOwGG_@tv5(&Q?)n29cXS@gj0w9j_>tsI7KaQp%G?r6Pwm6U*ff7!a zOm=UTI8&x&W= z^?0K$yV;>|WcL1PL*k%rR5?iM?B)SKhg^j$rH?Q*Ga>W_uKK#4&hes2Ryl)R ziRQ29ZH}WuTgh`GlYRQ9PgZC;hd;hJzt>2{M$aZmnY$}v+A+JD!+mGK06-f5MG-I| zZ1}2nbICnDGc2Ta#JtDa+LzcN6152)6}|IS`1f+@yuWPe6>>H4Yyr?_-qSs~Ae?y$ zD)M*X!EocN*tifu1VI21(h%bcT;U)yd}T6zS`;!A2js z<@jz|^(S*U7aM5}*0^>IinsS8$Q~6(yD*X|l%^o^>@Z4MP*c%%IW%}*&Y4SPA;Yjk zSK%OitZa9oDcw=ugDCYu_;EkCB@Bo(aOsX}h~=01MRPZub!a)3*Lu*`X{9o-@US-| zE?<6rSt-wN;JPIEzCJ-y@(tWq%1-VUj4dkfu2x$Z!B#+=CQDxi_@bv*ow))_P`2^HcymA1@5>Sea$i`6 zLnYtS$mqhy-S?OR?(JWcQd2FCN2VKHzHXJBZj?!%(hno0i!b3zzYW%5ROV+#JhQ(c z!why?p&#ew$<7f)CT@7sPV-)y1?Gtfk&BU_v11whM#DYQ9Lg7AX&2x>C&vjgYg??|m5(tyMTv;yIv0@ZQk`W zdW0P-&22CC{&WOTM)RtRZq>?X=%0HTrAMrZr@4PItyGk!@&mivHsbr&XvejQwU|=* z!=VV#qf&;b>AJd4X@rW_s19K{*G=<3<%?`!mgyU*Zgm+8doJ(Tb&F0!U=GqG|Ga9Gk&e_9zf)yW0o$b zr)Nn%j>}MU#_;$lnBL@RvH{z$Uc|;yrlSzJ=3|D#H~l`Ah?%(k9~?{P<$fJ-`Wna7 z{%oatTS03>7-vxerxOVQbDrIP@ZES(slQz*hU_>)@kdS1GZ3O$Oi8Y`w=aJb^z_f& z>`B9kdV5ecz`@+i%;_oCXw({;|J0KM+e&i%#-?MR=AGNE zYqBP(_tQm-n+a#u^pWcPLJyk2I*C0&LOO!vLxj4eV>P*G7FY|?E2rn1`6HUH-_fhHyH(PTF4f{i*yU>X_^}7}-eupLQm(t<;d>{ zdm6Zq%QQcfQW2-wj>4pW??O)cAY1}yE~=}Qw5M zlDub#p1{PzcSTf(V_-V^y+tZ<}E)rr@?~f3}E*q`yjfU+-ptAIWD_C%CV$sI}%s{ zk=F9^9Fn{6UC?7N=JN}pm2FeM;eWI?P;JJ~v}`;F05gudK5(lv3CZU|-@2HTAmYNTPjtwB})OjwgG z5>#njy&dn^?_2|qSQ;d84iSStNTd5UURP=RgcyT#&Vv-G22}EtH!ZaG23|^VQh(F( zZt`RC5<&*w3>EfYYJXAaR@im$5)%`n>^+I2@_O8#&p@Zmbn}Ob_Ae&I4%%=z%9Lb# zyzN&Fr=71aOBq<~mdVUltZu$*Uadv~gr+Zlo<3-^Y~QKyn&;FYzrp9`qr{i*8r$dc zlXOd>-Hs{?T+GeYaoK|GwsGwosatV@Wt#BG*VSh!oye)h*2T+W3s9C4Oh+ev<*BER z;3xkgpgTeCWVNY95$Z|raS~Yb4%lDI;OZj^Lm{8pBu-h+5A#&TP-|K*#n@)FqSn3Lmg-T3L8;&X|n%S%uVVREwJu#OUnNrzg301wx zQTbS&&*nN}D}76Wjg_+qD&j<&^PnGO5eRsb8L82AbL)tl?KzAQa7kR+nO-4A#W3`^&HKBCPjp>PvYk$FGa>HJJ*F%QQP$h*{xjl3I{O%OVy z&1&bJ@W($tt{tD#nD4>2J$k;IG`cD5tFxuRQ>g#al1++uyR-Y(Byo5^y?HP{OBb%| zx>0|WFJwD^h!~dfX@9;FJn9;j+r?`emYXR(6jzTeU7{R&7+WCRN9O)X1m z^^F|Rfo}m*YCxS;twAXS%2X?SE+nf+4SE~?O^K>KPpteonZKs*Vk53VtW|emm|TVI za;0%dR@L2n?zp#&a*o3<%>=z=Vqk{hu3`y;X1o+2daN+s+@wH)(Eqg}`77eG%!lH9 zoJ!@gKw9zx1lqINxAhDkP&~}lmmd?U!bOLAMVLHMcS$`Y&w*20jV#XSo50}=c@ssm zy4kN9SX=@O07R%dNc>E`d0rDL11FlMSu5FgzR~Nam*4l{8J%Y(JMMMQ`^6+LT!y|} zdFCLt&CF(|O)Uq$nB5zh4|ay~|(`S(g1CX4mynZlAy^{Iw8p)D%Dy{ZJ<%2FpW zzE17$?AabYo$`V@W8icXYrFSXr<$v#4`n9yL;-=#dJiHv#wMEj`O({6Us@u7oPfCw zscT@L{l#dBw4O0NSJ?BDCO#j?<*UMFf2aEn8i{ijg&R<6b~Zd8&6W}@mOLBg1Qm|R z!q8)DW@8KFZA3x2GYPs28j+=cAi`yY+Hz@H!1w30fU^7WWp71Nv!g8>7&<}YIXYCKf>XOZyD%@>z+%gJc*}5ZgZa0404*E;upVk6L-~Z2FyO^N=8ma;-=wO zS*Y8)0W0DOwCAW<+w!xdVCZPpztlB)zI5!HHRoFqiyjp#ON1ns!v5I;`c2GiI1t4| zY1Hz?H3okxw_Ql04_^#`Y-Wo=x>o4= z2!1ukRcC<;c7&*2Wt;R-2?CNnkaydCn`RdpQ0aoM_JXR`x=2$48lQ*NoDxh};D&xb zphCyyQvvsmr7F7`)dSSroE+c#;dQ4I(7B0z0kJRNn3LSMwFuSNL*S^-vm+twx4%E% zgj)t5BO_^T46Z5&956zr4LoUVCH!$*u^WsAZyOsfsGs281S71H;+wvr)XQC>_ZBK2 z>+jU1xBb6n_dpE&d97#~-O*>kvWHX}1BOu|w^(C{i5 z{dKW@Ry&oQ_Xyj-{^1{XbW2Nkj;c{{&DzUhs_M+amXKnZ4{7-{3Gbk*Xjqq3kuZfB zk%Bg@fij%a`^7_k$VpUxDnF%w)MIMI1lN(EtS845Rv{Uo-&{`)c05xEkY?9VCnU%KVe6#O}b44IAtEUDXXcmXw|jes^p{esxvU4#FzPJu5L^1 zSEGXzKM-ju>wh7h)l-|~BoVW7q^BVJv1|6;UbGpbr zuP@~D{JP>{SUwxUCW`pJxZSa#BtQ=7fy7k^-V7CRtTlT=D6UMTwQ|cyuw~E-G+SH@6n~*m3yMP6sgT}Lf~bFU&OS= zAZ>)RjX2;cz8Wh*1_m4hyXmNo=i)-~dpbiO410ov9lM|rO^xTvG$ep1yC{+Eoj*o|2+m>>U}YsYKWd~TJNWoiAd4U$otueuE%_R+Gipsn5?9f&txopzhqgs z6J1W=k+DUPBPI?Vghymr@I|9e4eAfZmDGDj+?&(YH2Y>!p^HB_5KcvU_v0NE#eKCQ{gh^}ro$xFkpj{^pCC>gB&j@1%FJB5}y6!LB zp-C-c3Z)3$i-1K#snm3nwa4Y7HJM0TQ!9)~D_haDh0C=QWeG@>c~IJAI4 zila@El)xWza6yVGOfp)W-YbA+KW0<{pGosix9Woq|1Nwdi`h}hC#+lxr6+j{3 zto9vWI1Rf>4a%Xhs<^smo<~gX+r8TgffAm5Dq^8`9?`?b0T?s+R4bX#&FS@wANCzBFZ3}$IIUmKJ z?TDKmd=su+4dl z+nsMdU5+T%O*EN}UXu<87jl`6SQHqphkF466MjO_x;1}?N!IjL`||vSR#>4I5lI2p zm0nwN(3x1Te$%bYFsCt?iAU&CZvco^+dStRIdPv1$T?eXtP~D~FRa!pK)?__y*QdK zjK=5%B^`7a!~99(G;V^V9xRx&5n6Oe0T0bJy-hsU##6a!=XED&?N3w6%)xJehihAm zV6)!lH^T7Ja#WF9TG3LXipwqFR4Cy(!Cx~T+C*0N>z{knoop}X`Rc*yom}rj>-KQF z^Ioure6JOUh&G_5crVS#tXv>BIe#xfI@NNJ(xn3qNYme~7Z__B;7aP7H*VALN_Hur zEA+_og~d1K*G}8H;xd)zU+GQx@24E8pMH|1&y|sEt&Hh_{!o^!T&JI1AH1rA?cFf; z+-zNuc+B210rRE+qMV4QBj~ITv1im|Jg=8)uUELok94|b{JJUlssyn|rY|^OY7OLh zjV;)N%X-g#HH%H=oqvgV;NA8>gU&T2mv)j!;06Om>g_91%1y5}9Ka83wgGH98|OB& zC93?On;jK$iS(px+uM|a>gvB{=9V*!P26XzoFPCE-^v5U+I!=*wE65nj^2?Y4@*12 z=~BE7c+%u3PwI11ZJ@ra@LzFlIpb5D-fL^?8M)r&Dzpnux!bKL@ci1=D(rO~Vwm2< z=nT9*kA*#37Pq+mwq4Fs)~mHPW4GGZ3ogjYUNZOLH7%mi24Y#0&Ch1to#x&V_p26_ z40%ANKz2RyaftiKKo`(Icn(=IbQrIXtY<{e3-xR?dE8#*Ja{`NyV~gf{ExonOtCHc z;>s;4^?KK__$gyA%UQ*E?AwyE>qCcXtlH<~@4(lI-BW<$5-S%mWzPCAFaO!zV)u{z z=NF1y6TT8UPw&}Hj)Ye(?zI6z9N;lhr<;1^%I;I2$)9)?orPA6STl&mp2yG(TgvX^ z;Uy=Vfh|u5z;Q_PCpr8{>-D+;7DFqn=gE4)F2)&O01NK$n+FijyF;7=_@3416cK;hT8!(6BKiS7ybB?)X$rgr6h?M zC{xftAE}Y+lQC6U227BS&(s9oOq(kH2i)imMuwZr|Qx@6`{GbQRLVr*A7tg*UJzc1+&vE&z z2g=>$qo`?qbhYx`2xkp9bRGe{YEB1J`MGX1kt$vp1)1QQ3C|$z*h@aJwP^7o7+t2MoK#6NkR(7&UE38lj z&H0FXtAP6qHcNN4m0aICnwmKX^+mt}t}qF|R5iK%ZiCp9hNHuy;-=wNqBr&ck2Tb& z-5TGQA||9C_9TQ_#Fe@p=cv81U7H+2h?r#Bm50;?+8Zh|Ulru2alT>CK@BO{cBA_V z_l@hZI`Y%9q9ZpN^r4)n-^{n6qjCG4wppq2X=EhBi?N0Z8?9-LHnFO|3AABw?Uk5e zbp5f8zieO#o_E>T)<&(#iZ(?34I%W~#WaRL?}Mk*(^_9LO48w+_JUL)*vh-(;U3_3%YWMz)10^3;=33F=QN>Rs4J%OB09GaJR5CKv^#E=~j;>dl1sPFLTaa_o)%%PBf;90Atb$^6sWabZVVA=l3aViLv0m;YuPI=Bo*L8zlQ-g@S>i5q(2+P#(P#2ejiAa;2(iF4K*WujVhG>A+>ULMd(VKhD}t-p0pk_eDZlEp2wjvup5pMFRouE-Enm} zJGtF}5n+K`6*G(;O)4K5O*^L#?O!Ise&v>b=9Dn`kMWUhYQ1rzys855Peu}6*nLK%u_7$?ORki*LMHAwybLd(`_Y$b{8eI`|KEgro(EoZ;>arnP61E|q5a z9AUG>+qF{{ai2U$FCY~Ju}BrpQ^Z??KnFUI_=3#m6t*Ca=HD1{pEHE4A*sB?>b9*^#;_< z63HL{T_3Pepff8_Kc}<*9v69SdnA56dp#7KvwX%|vfCRs0{_Jd`3>+MtZ-lPV}W(3 zpF8JAJvkR3r2)62SLTBCjwwJytquG;(vO_w1)!;4zQl* zxl7!Mp$ zy??x{oli1by5m1pSZ(F`D_)N^_!sRnQVb(C5LrJJ6dA`fXIc$1(J&j+(kZkBE+(cC?t^RXpDZfNoYSGF! zcD+P(Bs#0OP(4sGdZ6UU2>?^OpdJ25#ajcO6ipCQSkM&lO?kj7o&~(17f&eVuKS`Y zrLQmhxlg|%Pgfac*4kfM5N!BP#9%RO9lYP=^mmF-B(5v}UqF9DN|$g`bhmpz(*M~O zDWK3G!g9tkP>Lcs7XC*j3WmZjvM>PG1gkdydEtR z&slLqHPbOYa9xhK269b-Ux`RWa(tEjo>`TORN;3-1>GB1D?rtORTnsUS!Cl3Iin4bG(AI2i-+WaUn#G-cl zTuhA*+aQ+)xr5cpY6kKr%=>{nBm!?JnLl2)jR*Y3b^~H{kW-Zjs6_H4Jy>Y`r+?eS zP}G!3fN?Z0CvbF$vWuJRc)kPSfKCY^=W=O?TYh6IUzQ6BXaJz)D(d6*;$c2tl~@Js z5NwDsfABCUxNJ)gO5eZ*c9{$6@L9j=nn-aVv`(`Q;b|kEK3vq#*LXP5n9XMVh>wCWzqBAh$xRD1VbZ|z_(Z% zQ}p}IBzg!JEqlUe(V|~wqqgz`{+O66o8OG0htxcPwEZ%YpHOJ`Lk?P*Zjyz`;!@L9 z5#K?E+wyEE@u2wFeq*D88*hBNFLu22$N@19`oB z+{NEN(6i-vnY5d}@)%IVWOF!{C^H* z(ztXB&U?D%>yfy-dBY1h2`Rr;QM8y^K3y1ej~5)Ygu#oFzBahwSy@jf+5=%1l>ap0 zMEj)+e4Zh3L=0y?aUw0X0f|neQ&gbrgZ*`|s&3KCeR4H7GA9jK3Cy9;fW-aQG=UkTJkT1z&jO8r-W?|;*>M-|cxJXc0bIYkl`hu+mSy(hyS->Y zwDx?#X6QN;#l`cM1Vs*&ZdqfcRi)=^T;cutvXjMl{RfAisll7?wrMLTqR=Z}r2abN zoBCyrCJGUxH$00N@_>gy3Dn1FNTTtKVOSf!sa)Ehf7vUGc5!#_M)Ispw4F4rd%=@Q z=+KT*aG^$@p%a%!dvi>SNrXkKOhTm=xqycuDra!-5luH^NYi>)D&BsKby`4{-_x_&gsZdn9YS^)G`$lGWFYHD(=*cTlGwI&kle$QY- zL&{CKn3^ab<>^k3$AJ+q6I_K?*2%5U?A#kaF7XDqMp({|t0zdMh+<9H-{|?2lh}RD z%~E0(G{ADFSB1~?iB-W*iB&SY3b_!7O))J9MkgtFuJRsJRHToMZ59AqMP!f0PWxM`oD7EYuVY~>O$9Hffr&`@~v9jIM zojWK#;I%s+e8>y<(sfGHU_?)%$lv3yoUO$rq1hw83R$YIydJheay5(*N z3%C#gZNrlNx3d{?a{sSQ1%Ae|RhI)OARKN}nIu{7}v^J=>;L9+opSDwmDG z;SN#OK!O5lSwzsi28jw+TMauD%2f5|Toh5Y6>7gGr*}6Y@@H41g%9Ka<5(pqCc5aL z=mkj%7RdaZE0xr*kl8-9&}0bsqBY>QB>P_g1?-8<_8{NCB#Q+C=YM!#q=UMo&?bAi z@G->!+gbl`kT4gJelohh84MyDvE}%D`b(;)x8Jdje?F}x)1&E3H{{Y91--N%+cV4x zy0;K_sP2vUS<C)B4bC0o#;g2<%k;@sH9v4b<3t=D);dgrm$A(1&YpB1Z4PJG;TMJ zVc>XbJSp8G<)*v@daT62i==2?3?NspB)Mz=Wra>yorrtf$GvDfl9R@;UduI1kvt6N z9r&(R{?`BnzCJJ{IL~F*vMPa7KLo-*3c|B9G_-j6uXvN1CCqlChFcb&8*aO=husiA z{lhY@nI}T^^RNI=gpt_%3BleZzPMfHdav-Z@ajjgImM}*k5^ce91)T%((_?Rp+*|| z?S*Ck0stUar2q?TVM7j5$A;qXhLpeo2!S3!nR-MM282$j-2g%(jEi~CYFqJYld*f( zEPK#))r+oS2{4c8e(qupxF4vbf{m8!QSLbNBN>Wqj*&vp^;rL4nft`aSs)k!Ic#%q z2!(?*pO+Aiq(Gx*+XPNGHic3z!9YyeemS_|wcF13qql8kj7iilq}$J5F#eBtgPJ8u zFGfH3dM7Ch4hJQW918~8Yj=v4*6`68Ad^yut8Ts1D%zE%*Y~x*bT)A=+>WDDczvkXfj0fAz#f_J~6Vk z{^uDpnN2#WB`YiexAXs`=6<>&z)<;5Z>%j~uyeZF&wuZ$vhYs<*|j*(_9pjqwRIZc z4@kbBjAyweHh4KE&b7z;%lwUDQr@bE$5r!pToIVcjY?bQw92WQ zsR4HH#8?Sg$O0BHf$4{0x<1YQT``qYnr9*OVw)<6wM zhTI9&o$f1}L5j|ICB=uufW=`y@ootQ#-%w-PuZvU%I`v7Y$EOp3>S=`>Oe==RwNYM z4?%acCFVka5(Z>XUZWGudznY0$wZI$+wscbpY^U`j{Om-}DSM*mE#I{U@LV)~RB@5x|6& z<~pj+d;QQme;CqH<)^d+c1`AXCVf*d*RnFDU`6`ta}q58_hTczp!kx+x=D<~5fCZg za|ACSl1(sp1DAhIkNa`@xtGoN)Z+52E7@JRRi;qA`bH$G#_*z?KVDy+%>W2_iI?aF zXwYP&1?lg>MD=1s>i_m-h}|(gQE2Ep(hpEs@&%n?InAumXjU1_ZEza=zq*ZpJ`jL( zPKJy0M?Cn7{G@l9w(%-7tH^)NL!MV{xSVIClJ~38IMW1&S7}@PiBnpe`&%S=VlmlZ zrKMwfw$^R|b{Uez?H+H1rubJqF(6Dk5Zx*IyuOw3MVt!;C`1CW02vEDT(8o6^x>Gm z*-T)T*W*FA=5XsNz3D5rw|7}8v-Lw!NdWBiM~|{0$Ph@V8v1%*V0U4}97+U$E;XwS z;KiVhf#A0c+aBaVi6JX%+f622IJI)kZTf8V&HGY#RQ&z*!`V`u3wu;JJ#RRsfU-~5 zXPAOIdx{AW-_xHiW|S2VhTxc9pulNf_QeIyuO}I($#{MBXY;i5mowSW@CqKbGo*tO zL~x&3h}rZi!iqwXh;Kro;S8>QLM1=LnosDR)59Sro1!7>QoaLyj0vwSdgwwUizsr5 z{}e3|&s+3K1=nc(<*w>>=5$qOmE*YGBO&%$PILb{Qjgwn$gq1YfgUV~n z2OcO!Mr6Oej5OKyCLfp!j;hxufv*;|V|QOQGdn!p)7E_5Et>kENH#9!-vSkCB%0cX zqXkW0HiIUQ@*ZdT%@eJEMeC-OZLOS7*Et}tDqtLZU>TCR%5UgbBDqXuUeP3L(jNhW zcel+2?@grFR$6J=w5mBqK^(Y-|s~0w%;-wl28=ZII4r0T07RMEdGfu9{fhGQNK%cPrD1* zogYa$;Jzw;F{d1HSgy#un{G?Cw7gIyW0yWP)g8GWVRcM9pxRM9LnM*h<_6bmQ!=6V z4ii-9*Xh>eRbFseEgTj$9GL8ax0CG)ET^8ivdk{Hbn4|@BbGbTTD0{%f_*M?eUCv; za}xl}OA|-Kl_iF^K*tf2B@hTCWc zvth`><$5WeYiHec?>&)-mj|JsVL#d;z~M^Veat#$e9!Np{q>xt4 zC&qA|F(p1%=er4)MbuYnHcg#8-*>dw;S%0Txtq6;SKQG|do>l5$K(d+sgbIpPFJfI zE{vx&%=lG6ANRLElH_@n1`0l=Af@Ykv-c+sjog<%*qrg{4+I{(Fgtt%>9$$X{9T8Dn)kM2Dhye2h_ z>|HB(xW2YC?-4|_e#GZ#h=*ZZc~Ps1i_BJ`jn zuUNrHr8@8H;(|#?ikG}$N2Er`3JyCb55T8o6+ftvT-sWAjHbDIbI9N43Kg^M$TbG_ z26=Nbx|Q1-3j#BQ=c>|G?V;#B!Fqh?F8n+<*(9VdACu_G%)8>wA53b49-Kk#sVvO= zI(g1XG$>`n8QFBX_>avxHOA1fhbtmD_sGiMYq22w?Hk4&L zI!#Ntw7lzcIKK2mGX%1WTg?2t4-4|s>jWjbYsp>7=}Gi*_?07a_Q6%<{RCINH@ptP z7DOo^R9r($KLt0)DWGMxn?Ga0LA0x9p^Y_S=7G3Dnyl9kQWE}y*$yrJ`V3s=K8nOwf8)G zPZug;7W&n`d~KE(7fTE8sXWr0NEv9mK3?PyyfpwaQGa#&BMyh*1rGtrb_yYPW}8q^ zb!h14ci2u(#$hmaXDlTtIFH|wDWiCMDxTok<=4|`?{ga6cW|5ksqf0-d^2qgJ$*2D zmpL7nVL4BWHrSfp^NMVYpU{FoubD>__lZ6tMC(68}$xU>c7p=MfE0ESz- zH1hm5a-WocZ~Pr2gE58iXe!<*TYgWv_VXk4@1?)7Ucq{R5v0g`2k0uOnIh!w^j*3H ziDq^IQC<6^ds~yZ?f%v9IwU3Ce&Y5$#9%FWJXN~)bPkiL#8GlF(>=%<6WRu^3&FHiTn?*#>=^xekfNCe}Xc%+Tbi7Kt= zKhB(+n^!LXlTvn4j5iW>MNST`QbuNEIWm`BT{hG!DgR(jCqn3+ZS|DKxf22j@N*`8+I7#3!|aB4rU;vU~>U)F2= zTQH0pZf&PnQn#|T5QkBLLUlc-r-UAx%k%HqfK}jJMA~=NS&VFABKZsXC*>AhNT)0yz|waG={ zCjvEp5S7G=a*fZakg%#+4l-(us*n@{T{d|~Tx?&!Tfq*z*8h6r`U7M;z4vX?(cI77 zr*fqZgr8XdRtu$Y9$V9TeNAkJv)ubZWo1@G1FE6-v>ap@k3JE%34W>v(&wnp*XS7FCET`kQxaz2VUSFTO zP*C_I!Ei-TkE-j`bmbVr=1EjaQaIgd^~}}0nxF7X{oqQX)j z-rE04Hw=mogTm|j_UoGUJu~z&!}}pLeznu`>Yw68UZG#qoYa;I;*)e*+H&sC4PTxf zHs!4WZ1hiByNFZU@uOFqAj|Vk*8JMLbjA42D}uNaGG%4rW8cP} zx~64vsL+OKQ0E<+_uEXX&xj+EQKN}8;KBVd0@ZLQN2mM3+_d4x>Yw}|%YRMOc{}+K zn(s#mwtjz)+PoEZ$>1%6p3V!Y;Ec8E82ngkClr8^eZ-|5bXnayh@je8v7P3~&tj!a zT6I$9fbbQ}d_1*-n!)c_vSG4*&XEcv`g%S^`gwY1RCKbVLBuKrehfYPZ|w|ilydwv zPuj#EqxwtWYEn`&3!ekCVE!Y*2Lsk-p5HX?iy-v-yk++W8e!+zol^f8_R@+KRYmJ~ zMfVOBLBP9fKP}G_`1KsVYEB25I{nUh>u(Oh?epfm@a62_J3(J;xtqw&~H zF&P2`CSf+0x63sTO_Q6h-qC-nY}dhj-Y2=du%qrW)$)NSbWsXzAjp*qGc)8Hv_rGg zunIRC%)YkSF`UD0Wjlg}`)LUSZW#I!Zi10}d$xT2-dcln9L-LWmkF?or7hkm5;MF9 zduz-M`m#I!+X_2{gd2Y`k;{E)v!>`u>BPtHXa?r4+BP*U%Q|kY*q;s9d`T0ln!Zcr zup#>fH+A@CA>6ceKp*!|>2=ltIla$c55>6xd1}wv?pY<0;Uk_8?{1er z`w987?w#5O%YiRnR+_4qyNlY|FPeJZ8jo!f9W_bBaO-1$t;Te!^nVi8xHjgv#X(D$07CqA;CK zi^DGANt5!dK_U2WgFvP{B{`sciu@|gs4<#9xlhYY)ZBK?AM3(%XceMoQm zeA;MUT}{?d2b6LZDfMsZsMO+%zB_$M%?C`?CtiqdK)-ABp_^vLz=2FlJH{C3p>TduKGhgE_eS-YL-nQ-g}< z$wSe-V3{KRgzh~*u1MR&&s(941dDenP&%bbiG}7!w&!L#stQS3qBA^!mH zIda`^1er6T;t~1@}-nu8>+G z3mCCf(#jc7@w($JrKVZNR zr*u1=ednDqo-gIJ-h);2Bk=HBK+AD<`mW7ccs$X{l2(Vn9j|hS#N+SNL`uJJ;LeW| zWb}2L?eo(C+3}_w%UgErNE%NixdbRGE9Q0S4w7N>YdWjB&e-@Rn|Aug$FC*a3C~gS zmNq~kvD}Jae*SVyTcb{lKw({>um^9{oDSm2+sk&MlHr0y+OhdJ_-oVViOlW~c8y-Q zpCBA5@+EK%No3l*n(ZU*oUN14%mrKqqa6(sKuSCk3i#tSO32~UDS+3OQc|WZwxIOG zu-qS$N8Mx_p3W#yD9AfD|7*PbPGv`jE|8g#(>4XSbLPLT@N3n(^DDQsNpsP>ko`;T z`Y%|_k{2OwV~Y*?KxxXwQ4{8r$Ri41MpkaJCt%iM9rGUBsw(Y5mpUmJ7qN3Z?^{!R z4Ku+QS_j&WCuBXmWo%y!WwkvwSQ0u!ICvSD6+Jy?&%fW~^Zu0uW&IaRhfC3CTzgbq zKMi#vXOxX-(j5jEQXVP{WK407BkQDq6ll;Zq;-(qaF^1H2>O28r`V>yIG_Fyx6$Zr z)CILjIVc%-9m9b5BK#B>J;*n4kdpUF9(%$++k$?2#8Mi`7NLrY@L4Vow-%c@4kF6m ztlbuyh#rO>Z*-a@H?TCf=uCPOTlB=m88DQ!_8e3x#LOe43wG>0&v_U&XiQK}tka3@ zwt?=o&F{(A996@o_gUmsq8ImpSbPvQV6HceMEjHN$Z9FXd;7{b2w%M*;5cut6vt8 znoWa!Uo~5?mfqk!rpW>ET65jo@m{l<%9Fkv2EVW~LM1|kNxeK?B05O~w3%05&b1!q z@^zLveW(Y0ZQt7RFuKFnu6NKwN@>CX3b=(3$9i^8@eEiM6dcliA^;#ORV1i%%R>HxFx z!~HfBvt#$Ypo?wMljFhEXMkf)SAP-qI>)@6ObQAZ0s}`uv+c&T{f#-TcfDgjn3(z` zcSa%Zj*m19q}y>FIBSC6k&uCsZNsJOcX_zcJ2s1fBil(>_P|vIlzKzlMpLv-g%{le zWPr!>SA93*`b+nwXSC35as)9Ky&Mwc*-2PG;H{i2DAZ; zAoq<3k*A6?pdZB#0FwI<8F@LU|8e&YGFmF2$Sv5UU6I_GMU-K!h@9;$E`m4z|JwWR zceuXxT{Suh5hY5RUPBC`OGNL3h~A?`?`4#P&qsn_)DVJEqm3@2eniYDQKF3&j5>Pn zXL;Z6`=0AM=TA7twSU^z9<$e;wb#0z`?;U{DUep0*Q_eW3)KJ3&rJrE3$I}+UlURY z@cK)EIkL9Vs`atXcAU)N%j@XQ-zyjwE))_(#3f2Nq-p|`497~Ukj-#tM^I(#K6 zgk>`rw1r(hIum$VDR1AKcI(BA`{~;Vj@gOj%Tx^$k6he$zu-y1Q=|-Hj5m4F`$f5$ z4!(D-J^H2K2K2Y!LYdQ3M{FlG(-f}$tnxCa5rKcK;i&fXw*X;nYEaHoM z8E~dOpg!D6mB2;;W9E$Em@R9)g8fOX5UQ4T(Vm#3%dg2su|+19-*ktuwk2m+OFAXu z9jT4l)*84Ld}*`l@dG99NRSZ|&VIRj@rMS+B1p0DEMCjYEhWxGjv6*_6xZ&xm>I3* zv-^z3griuGP)TPR5)dVJ#U^fi@|*VGk&u9Zl#!HHzvB2w+80Lu9RA^PvN!)%yLWa6Cd z0}SbtY`3uqXEvcS;W!`{ky|5 z6$yD;PmNkct^F#}tF~Raavaol#nG7lN<$mZ8ChGJ& za{n&Gg*4u`nEeTN#kp1EQJ2H#goW%7L&$-Qitp7$htA2j(oITZ&vm}t?=X!N1?XjN zA2+Nl#9$^e?g7E+C#bErrS1cYW9jY{XANC2DbR++@(%762dgw zxgW5%GqLx5vl#DmhG6n#XeebvXC=s0$j~gT&35gMr)pZ7Juic4EOZ6WddOT%EKQ&_HUs2B3h ze%VR6B=VzK%$IvP)i=w9o>~3aTKeSHpS>L2nF(kEX0Y+6HA`VRPkOx;7DX``L~%Z= zPu9Cd29J?OB#t=D?wNl2{&H0H*6N3Q;SgfObJ9n5g;Mju?L$A&^S21I%2-gHsBjmcUofqCgxb-~8xEhj?JJtX4&sj|*j&rXTuW^YvIulEdD ztwEW*Jg&AU&kJLarJ23RAu}d|*ZN?;p8+)1NrFrs%?iC<#RdrJpVAq- z+0(x@PKUEjWJ1$+zTuGQMOYa|_lD-TM?}?<;|tNVn+9EOwjbsTiF}GPMZ?q{%@`s$ zW#KKH_%%Gu!Hu$KZ&K1X?E&ao{7x4W= zLFa<9N3={QQ+!AaLR>xD)P^w%7Vjf#-lUQJ;9=_pqS+#m5be$Q)!>#!;@-4{1H5>| z){V?Xf5N!&fhzH@y#kDW*Pjq6;DTMDk1)!i10uT zM^{@kzicvduVcBzzsHssKNv`ITaHn1Y+}M{l_5&K4Zv3JGq0p5_BXs?p(9?#YO2Is ztbA~0YQ@#e8Ucg#dvAjUjCYkm4p)jWNVTDY1~DmmEESS1gc6^f<|QdVGjV^tH@_W8 z%^eDx`onl)xzFUe(r1Hp4k{G=`QS?oI|iP0N5V=SKQ(M4vsWkNhNfK8G$%mi8>a&5 ztHO-AUWh6>JT6AonvEgKvO1ZtB01c$Nwa^|bx|9!+N`lu$cz5f=K6h5U9aA4bd^}q zoIHI)#pcQlHDeT;Y7;-+xEQ@|O~xoh4|Uo7Sw=0GY_jt{BubSNAhHbf`p&`-KA|*C{Ocy(MR$C7U69nAeH{U%c zwvT1uhF#2ioN&y9W9H$VLo%*V7vvx!H?v>$tQc(l4KKpTa{%-U-<^xCGCXuPz*C+V z$T@Czuhe=Dr)f*%oP;8h?J|EyhXh}@PvAFedU8dibWxqHet;^b_Ml}f7qD1RfJjB(0zxoT;7^k8{PFL0AD`V=Q!RTU z)XZO|mEZp)X=ha52;pmZlgPH~c@%ikJ(y>^MbZ5;XU;DGEje6hn(Mpw;SP*K0>u$X zg@_7)!qv{j00D*dhm@ZMR^Y8^Ke=vjM*VapXB%$}klA%5Goa?C(6C2;oQB}(%e}s* zK_NCkLoXck)n7Hg*1k^^F!G+pwN3`FTk8UASr~gaS?{j+!BSk+*m6lw7O!*8iEofw zJR7sx9emu0=&p)JFKeIWvWyav9M@J1rp9>kp*BoV8?E2!?sK1;&e!aX)cq5R>hI~& zsi413i1dKQ4|agv6tVsJar;j$HwyZ-^ziRl~*e*MD|J}}9eRHyX5^+JT zWD?0}#-xjeZ!El@ls`WRV)-oxJ$_*r-cfj>Z(_l#R?O`@Sw69nS9A{G-6Sn#eMx?` zr)GyU@wT$uX@W+YutGm*pH^w^5hEAp-_~BPAIWZ0SVd>K?6jO0DK`6cBlG5@7~@x~ zUIo&#y_t|BvjAXPg3a=Spid9je@b2L&F&7(j{Wu3TqtWMSX0()jC;E7Tok%{DW!4uAGR+N zd08=0t73=Raj*^D~AN_ruYDwtXKtylFX4Gr!#NMwcA>}ped^IqcsI^}|zG}ZIyWDS34quOM#GRL(8M>~QxSGaf` zVzqkn4fm@eBkotan}0C~xb45PvvkuwXZ6D|3;yl=xu!p%+_7%?(%y8~wScDndc4%3 z!p10yM*dyZqsLqL5aCnYI|iPs#37|8qOO_+WxJ|7y+LUr1twc%*N>;qy`itBud)dA z={?gU45eM&s&#uGNBEabovNmkphZT@zpoJ!IEbD$3^0+NJ>2{x{d=Q~;I9QX%fLfi zF~8zBqYCqgzCRxJz&+v`apv9&mKm316t=8fj8?D^zt>rIS(!IxH3zwBXc+W{%Jy4a zKyUay5h~CyeL12%JmjANJ65K*OCFS{%v((t$w*mcU?2(QO}fLi8p=%L*#3N2^g=P* z6%657WxBm-U`9XE?x?i7DCBk6jI!&o@-#1n)Mn_K14?OF*e=(~UOGAQ1M|VK^DqQE z=Z5kP%u{`l(Q&Ju*Lyqa%w3d4xx8osQW}k>3P0;?3Pn~0DF>_%6WXq~Ts_!g9anw& zX7yogXFbY1XaiBTd$1p`J%*CIM2?~i9y(t3c@}4bX~jbVOBTEMJ@BFMjeh?J8u5-N z<*3zahJ&&F`Sah}cDatFu&IkDyVc-&QTB|{@OyL2kofSZKQFr`&E;C5NM)X5n#d<{H;B@O_p-EDMeAkY zafpRG(R2K8`F1q%*%kSD@B7%h;!FG5!>^s3M3g$*hY5F`G{nzy$9Ng2M6roegA(?y zJgii@HTYCR*9$bQK28F1xQ}=_A1j%*gUm17EpSP^i!|@sT1Wb#A=c24}IfG zJce=MKq|SPk#y%zOc&mDw70&_SaVAfT}az}%_3UXAT0Xkj-M%WV0`{D^K$n3*s`bJ zbTYaxI~(1XmVh?%GZPed)Dsl9Qrs*Xpy?;BuxX5%zOneZ#n%3E3mb5i-Z?9!etG*6 zYgo~bjaVMFEyn%U#uQDi#Rs>QU1qplYgq~~{HZBQ3mJ7hsf%ya&l@C8akbqSeaJ3s zS#5xmb6}ubb$QL@litPrBV7}_UT4uQ=JL=2(?ls|<%JU0AMa5aRs|SN2CCt+BG-bX zMZ?fZ?LV)mrUJ`c4wyyONc{9p%g7?XIwlTj>?)fAXKX$}$_3w?1LK9~!|oeR)Wo~` z2lT}haiI-BV21@&Tm28)l4O>=QE=1;j366l2iY+VqI89m;1X}yx?++hPsDU z_WYm3kSgOn9a{1*n%LgMkVzi8}7v{GzI zQ)-3%2S3X5kX6bFar8~9pfLc|um$6Rwq=DsK~_{Sl7uD&_%5JI+dXIj)(v$XF_*$7 zvMNEgb>MkHM#!#xZE|+AIfP=X=Rv%D9c}46L%pu733;fB)eB>KJ0x#mq>arv|T;&+7iCo3eKmQhTCL99i&z0{-qpe6{DtIC;! zqQpQ&9==`CK!RM=8LQfh%hA>`(Xb-lOv1n9GH^t{8a?Ycvl!q^?$#uqV(Igtj#}}5 zDu^)9!0Gi5o=uN9;CSY|<3>DGaxN7Pco#+UL#cYH5J?johfQm=w=NaOF_K?o5|XkK zqIT^RRgWG1lc;Vw5|Wk-{ig3Fj=$SuUJpG-R?S;x#nNG}@%B9WIbdZ}0V`AXf=`ES z+9FRhoW8+Mb4KyR{g+mS?8T|k#y(@H8p!Ok$=C4&T{yGbrCM{7uDI|x9xDUz2J`8s zHA=&qt*j<2v`&hp$3P)ka5b)+YD5zTIMqO0PjPE4e}`@r(1hFS5R$&0mLwP z2~04aT|L^Kx;F-cG*yWlO!Lh6;HmuPM(c|ad2fI5Oe#~8Fv*Cevv+=tBiin*l9^y~ zEV@pUf4!`kzD@;QJQXw{D;^&o|@d`kMS`vr3y6VCh7#bovC_-8Qf6E zzQKae1mW}vdbpbX)jJWl z9qtbq|3O5!^4{eNoyh3_TZnG;gK0AOp`7|ss!X4%cgA&6r$@$T#WR(-{@ts=+w}$u zWl>~L3Om$w`efzJKs$$iexD}09E5LB3xsB7k zRWsHq>*a(&Fp(3u=wH?nf?(|TiEnBecvIgt6~5STsXB)bg=dI{O{`haFS!g|s{Toj zycRZm-<&8wR(mQXlIQS=8Mk{@=KZ{3a->$0C6JP>_tes>r{Da_|D=OWKEs7bA}X`@~_u-H5qE-~;`h>Eh9*_+s_z7IHw>KWrTa@w5SOlp(VwST?c z^+XoDxPz#q!DBP2RqU7B(NA%VoD6&4ff{89R;2?g(z`n zDR!#gGGUBw8*Iy=iLSDKT`nN5vI7!(tF~#s*{u2jP<#Jty4pc|73hLIo)3gH7D$<3?BXIuAMADJXuLiLlf3QNitStjg#pBP>Adkm(5{xP?$pn$WuqGI4|*|V|v zQ=C1))AhKE`ZdnGa-{BL-k&Tr!+&hH+g*6XH!#MIpOES&OiiE}lym!V zM_B?Z^$1PHF;3F7hfFDtAPp~SW|gRDe4L4goq7`FRj|F!o<7u9#H6e)e+$BmR}BHh z*?as;(n20iye=9ci>W}}-XA{fg81LeJMDPcTb}1z+eE9&`pViDy^&w0tyJZh*l@;_ zlscPt^kLUx=AJ~e>Md&1Na1sbt_(C@f%Udahc`@c)F~bP&qOpXEWlP7Vt7t2ahJ=i z9L>2=ej6^MPX_I}$pN;jdK}O%iTH0@8iRto=A9pRBWUDb&y%ejQuO2f*z=f3CC@?E zn*2cS@Xd*I90)rK;yaXjyLVJaD`1rEbxxrZ`W!kH3YEq@E|l8b{=mEidu@%OrldBk zDAn=4q{5Y#IDWW&ig3mIAf?c~={(;zU{mj`*jiPI9y=+dX{XjUVJGEK!$UbL%L`NE zbX*$PA8S!{ja8RQ4;yghO^?BVl-G2*MM^m<*$R>qEHlY?T~S|gUn@1DQ^}`A9aDY9 zN1%r~s1>pEU!RW^@o9aZz3`P4jQ+Qr;U&bo9OT5M4cq&>DY5r#hg5vmDRWv(AE`I7 zS__`#<_|gx$XIa0pCdJ2^thPPd?8o~q)M#{W~te5_xZT=BSeaes;l=-Y*ttuPj>3M zhTTBs3E%c?-9?91(icwr!(~n?xhb%~6fGm+iEeSeU!SU!x~3jVK{2!>_k*N<)h({8 zD}^W4Z*ZqcaOlw6)o}#{i99=CdUCPi`w1*E_3QQg2%EwTs?yD2Jt-4@7@~nh`1|Hy zim?9L*&%`cDq-!4*loMI!u>-cvcu&GiAHX)RCc`*@Jc@}NTU+A2deR%;4+tH?qn@_ zOk%$~qT5}aAjTXzF-$wz0gdu~4DPW@BX|c4OkJ}&lb$OF?L*)C*lpzrelxVvRnn|$ zLr=n@p1y_x$J@w5-^N=^YTqeCVEW22BrDPQspw~c^nOy>MR;tI+71G2k2YX?{1>xG zIRp|B9-fXISqVJh5G8xg1nYXRuy)wym`?#95E-yht+(`XI7AQHdw)n%3_~GVZ)VGY zMMg<#UcF?f5)-_H3pS-j5UhA^AYC@pQ@x^aBkXKSgX{_TXBDN(8|(G@&$UnXl6RX@r9oPY(xD zJ`ma-^OV*{%F3*ae_tJ*82C#E{|VdM(WkZe2cY+RtuBu?!6W&99l!dCgyYVd)bvv+ zG^F+_RxxMCQGb)%P}^FsXx-e1OhODM>fcf86R}N>rI!ShBEbYA_>DeyP_}FcveQ!| zQ8Wx={6$urty%2kbZI2R{+ZT<<2A5Ye6BS?YMZ)SrTL{-_HHQAyw^rG?ti{hp1_sxd)xZ9GMwV`TC!_6{GR)3RCfv+-LaFY}G;cI}XhWMOowmGWEQ_Rwd00yT0V>9o zH~!J6f>zbb80loX?C%erD6yep2F!0UFUx?u=bk|?K_VX6$A2I4_wfbs8FuIB|8oM5 zOhOx=tpDpO-mrJl{!0IODDnjTbl?Vq>8r#3dxMX3RKmzD@6(tgZZ;fFI%9zsBfQ+~ zTNKP=-g&G%nNCaMKIJTM^0S-&=Wh?|nUg=iwws!oB3gkUHK_akt2w}atG9+;C<;d2 zph^S-li;1dH~=7-e3EMN)@Om)K7DN&`a`i(7lBtbMWkfojuNNk0E)M${P2l?q6HXS zbKSF!YLx{DKxc2p+fM^&}|_c)DOgB~B6$4x#3|-WLe(CUOA*h#9ZSa!4e@!#_R^0Xen<9BWY!*MhaXYqmfkj z=hYzyNK~R|*x3$MC&htv+9Tc{&SRu=^h@L8OhLfX6DZx5;^Z!mL3q@l9VQx9?zm6S zKd{vI>HX&6l-IyJQTipfM+>n*-~sI}%Uw09%y7~4;>}O_@K1;Qp|H5gUwHQBbMUU} z3CgHNFAQJwCm7o6>u*mBfF1lc>O^Spr-EKq77Q-6IXsWHf!F4eOq&BJcJv(4RmNV- zwH<&oG5L9LYn#=tmsJY0Zx7#b`~g01$8lXJyMFF1Z}}~aNpZkMt7^3c%%~wy%NtS2 zCKIS4OvnwK{DiiTHs(!cPg5wFL>`%vo7XxeoBB@J5t#2S_3cq9y)-vl+5nSE;lvN) zDju*9D}Mb|j1ulSQvu6ao549g0eYbD@CB6IeA#o&Si!6(jugfdwRwrnK zrzDB1>}+2CNQ6hOv3*OWp`NOG(PU99;&oUzv%tl>t&eBoF^79$T(2=;S-b+~iEQm|>|0a?pFWhY+}dhHuU z|DTSw$Plsdr2YM2ZHflV*;roG@6`3(Wzw?;-LZEW*s%Bzucclx%-G3tw#DVAv0tq2 z=8Hf&-+56hVNJ$PM{M!?{Z^)XCK@f&npvTWV^zw2>p(g1`yGQhBeG*hXk3o$&GFp* z<25n%ZW3iUoqe1KoAuG=bZ2P5+DP%q;X5WhoOaaihs(czSP^W(R(feu67k|FNZF!u zTS2M->lXRY(mfw9F0|cZKP|pFM>#GkD#|n@B*fpF`gm2BtA#x_k~8d~WE-Jr+fNsD zHnCgIx;s;U#yNyL204K^%t>%O&n|Z1ndLTpfUX76i#fy%<&`j|a}V6d_^BZYVh6k> zrf~Y>bmagZ^~pE4ik^8ykVHlisf7LKXrm(lVPaB@{bSYto|6YZHI%mIf1dysLGfgY zU*Adk&&R@u-~ga;D17?gC#0`MUH|_d{lD^z+O9}qn@)r3iho7mfj?Cxt>@*6mJ$C8 DdJ+3I diff --git a/SLAM/GraphBasedSLAM/LaTeX/.gitignore b/SLAM/GraphBasedSLAM/LaTeX/.gitignore deleted file mode 100644 index b0b343402c..0000000000 --- a/SLAM/GraphBasedSLAM/LaTeX/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -# Ignore LaTeX generated files -graphSLAM_formulation.* -!graphSLAM_formulation.tex diff --git a/SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib b/SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib deleted file mode 100644 index 4d3b71ae50..0000000000 --- a/SLAM/GraphBasedSLAM/LaTeX/graphSLAM.bib +++ /dev/null @@ -1,30 +0,0 @@ -@article{blanco2010tutorial, - title={A tutorial on ${SE}(3)$ transformation parameterizations and on-manifold optimization}, - author={Blanco, Jose-Luis}, - journal={University of Malaga, Tech. Rep}, - volume={3}, - year={2010}, - publisher={Citeseer} -} - -@article{grisetti2010tutorial, - title={A tutorial on graph-based {SLAM}}, - author={Grisetti, Giorgio and Kummerle, Rainer and Stachniss, Cyrill and Burgard, Wolfram}, - journal={IEEE Intelligent Transportation Systems Magazine}, - volume={2}, - number={4}, - pages={31--43}, - year={2010}, - publisher={IEEE} -} - -@article{thrun2006graph, - title={The graph {SLAM} algorithm with applications to large-scale mapping of urban structures}, - author={Thrun, Sebastian and Montemerlo, Michael}, - journal={The International Journal of Robotics Research}, - volume={25}, - number={5-6}, - pages={403--429}, - year={2006}, - publisher={SAGE Publications} -} diff --git a/SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex b/SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex deleted file mode 100644 index 25f02cd3bd..0000000000 --- a/SLAM/GraphBasedSLAM/LaTeX/graphSLAM_formulation.tex +++ /dev/null @@ -1,175 +0,0 @@ -\documentclass{article} - -\usepackage{amsfonts} -\usepackage{amsmath,amssymb,amsfonts} -\usepackage{textcomp} -\usepackage{fullpage} -\usepackage{setspace} -\usepackage{float} -\usepackage{cite} -\usepackage{graphicx} -\usepackage{caption} -\usepackage{subcaption} -\usepackage[pdfborder={0 0 0}, pdfpagemode=UseNone, pdfstartview=FitH]{hyperref} - -\DeclareMathOperator*{\argmax}{arg\,max} -\DeclareMathOperator*{\argmin}{arg\,min} - -\def\keyterm{\textit} - -\newcommand{\transp}{{\scriptstyle{\mathsf{T}}}} - - - -\begin{document} - -\title{Graph SLAM Formulation} -\author{Jeff Irion} -\date{} - -\maketitle -\vspace{3em} - - -\section{Problem Formulation} - -Let a robot's trajectory through its environment be represented by a sequence of $N$ poses: $\mathbf{p}_1, \mathbf{p}_2, \ldots, \mathbf{p}_N$. Each pose lies on a manifold: $\mathbf{p}_i \in \mathcal{M}$. Simple examples of manifolds used in Graph SLAM include 1-D, 2-D, and 3-D space, i.e., $\mathbb{R}$, $\mathbb{R}^2$, and $\mathbb{R}^3$. These environments are \keyterm{rectilinear}, meaning that there is no concept of orientation. By contrast, in $SE(2)$ problem settings a robot's pose consists of its location in $\mathbb{R}^2$ and its orientation $\theta$. Similarly, in $SE(3)$ a robot's pose consists of its location in $\mathbb{R}^3$ and its orientation, which can be represented via Euler angles, quaternions, or $SO(3)$ rotation matrices. - -As the robot explores its environment, it collects a set of $M$ measurements $\mathcal{Z} = \{\mathbf{z}_j\}$. Examples of such measurements include odometry, GPS, and IMU data. Given a set of poses $\mathbf{p}_1, \ldots, \mathbf{p}_N$, we can compute the estimated measurement $\hat{\mathbf{z}}_j(\mathbf{p}_1, \ldots, \mathbf{p}_N)$. We can then compute the \keyterm{residual} $\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j)$ for measurement $j$. The formula for the residual depends on the type of measurement. As an example, let $\mathbf{z}_1$ be an odometry measurement that was collected when the robot traveled from $\mathbf{p}_1$ to $\mathbf{p}_2$. The expected measurement and the residual are computed as -% -\begin{align*} - \hat{\mathbf{z}}_1(\mathbf{p}_1, \mathbf{p}_2) &= \mathbf{p}_2 \ominus \mathbf{p}_1 \\ - \mathbf{e}_1(\mathbf{z}_1, \hat{\mathbf{z}}_1) &= \mathbf{z}_1 \ominus \hat{\mathbf{z}}_1 = \mathbf{z}_1 \ominus (\mathbf{p}_2 \ominus \mathbf{p}_1), -\end{align*} -% -where the $\ominus$ operator indicates inverse pose composition. We model measurement $\mathbf{z}_j$ as having independent Gaussian noise with zero mean and covariance matrix $\Omega_j^{-1}$; we refer to $\Omega_j$ as the \keyterm{information matrix} for measurement $j$. That is, -\begin{equation} - p(\mathbf{z}_j \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) = \eta_j \exp \left( (-\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) \right), \label{eq:observation_probability} -\end{equation} -where $\eta_j$ is the normalization constant. - -The objective of Graph SLAM is to find the maximum likelihood set of poses given the measurements $\mathcal{Z} = \{\mathbf{z}_j\}$; in other words, we want to find -% -\begin{equation*} - \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) -\end{equation*} -% -Using Bayes' rule, we can write this probability as -% -\begin{align} - p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) &= \frac{p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) p(\mathbf{p}_1, \ldots, \mathbf{p}_N) }{ p(\mathcal{Z}) } \notag \\ - &\propto p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N), \label{eq:bayes} -\end{align} -% -since $p(\mathcal{Z})$ is a constant (albeit, an unknown constant) and we assume that $p(\mathbf{p}_1, \ldots, \mathbf{p}_N)$ is uniformly distributed \cite{thrun2006graph}. Therefore, we can use \eqref{eq:observation_probability} and \eqref{eq:bayes} to simplify the Graph SLAM optimization as follows: -% -\begin{align*} - \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) &= \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) \\ - &= \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \prod_{j=1}^M p(\mathbf{z}_j \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) \\ - &= \argmax_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \prod_{j=1}^M \exp \left( -(\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) \right) \\ - &= \argmin_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \sum_{j=1}^M (\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j). -\end{align*} -% -We define -% -\begin{equation*} - \chi^2 := \sum_{j=1}^M (\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^\transp \Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j), -\end{equation*} -% -and this is what we seek to minimize. - - -\section{Dimensionality and Pose Representation} - -Before proceeding further, it is helpful to discuss the dimensionality of the problem. We have: -\begin{itemize} - \item A set of $N$ poses $\mathbf{p}_1, \mathbf{p}_2, \ldots, \mathbf{p}_N$, where each pose lies on the manifold $\mathcal{M}$ - \begin{itemize} - \item Each pose $\mathbf{p}_i$ is represented as a vector in (a subset of) $\mathbb{R}^d$. For example: - \begin{itemize} - \item[$\circ$] An $SE(2)$ pose is typically represented as $(x, y, \theta)$, and thus $d = 3$. - \item[$\circ$] An $SE(3)$ pose is typically represented as $(x, y, z, q_x, q_y, q_z, q_w)$, where $(x, y, z)$ is a point in $\mathbb{R}^3$ and $(q_x, q_y, q_z, q_w)$ is a \keyterm{quaternion}, and so $d = 7$. For more information about $SE(3)$ parameterizations and pose transformations, see \cite{blanco2010tutorial}. - \end{itemize} - \item We also need to be able to represent each pose compactly as a vector in (a subset of) $\mathbb{R}^c$. - \begin{itemize} - \item[$\circ$] Since an $SE(2)$ pose has three degrees of freedom, the $(x, y, \theta)$ representation is again sufficient and $c=3$. - \item[$\circ$] An $SE(3)$ pose only has six degrees of freedom, and we can represent it compactly as $(x, y, z, q_x, q_y, q_z)$, and thus $c=6$. - \end{itemize} - \item We use the $\boxplus$ operator to indicate pose composition when one or both of the poses are represented compactly. The output can be a pose in $\mathcal{M}$ or a vector in $\mathbb{R}^c$, as required by context. - \end{itemize} - \item A set of $M$ measurements $\mathcal{Z} = \{\mathbf{z}_1, \mathbf{z}_2, \ldots, \mathbf{z}_M\}$ - \begin{itemize} - \item Each measurement's dimensionality can be unique, and we will use $\bullet$ to denote a ``wildcard'' variable. - \item Measurement $\mathbf{z}_j \in \mathbb{R}^\bullet$ has an associated information matrix $\Omega_j \in \mathbb{R}^{\bullet \times \bullet}$ and residual function $\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) = \mathbf{e}_j(\mathbf{z}_j, \mathbf{p}_1, \ldots, \mathbf{p}_N) \in \mathbb{R}^\bullet$. - \item A measurement could, in theory, constrain anywhere from 1 pose to all $N$ poses. In practice, each measurement usually constrains only 1 or 2 poses. - \end{itemize} -\end{itemize} - - -\section{Graph SLAM Algorithm} - -The ``Graph'' in Graph SLAM refers to the fact that we view the problem as a graph. The graph has a set $\mathcal{V}$ of $N$ vertices, where each vertex $v_i$ has an associated pose $\mathbf{p}_i$. Similarly, the graph has a set $\mathcal{E}$ of $M$ edges, where each edge $e_j$ has an associated measurement $\mathbf{z}_j$. In practice, the edges in this graph are either unary (i.e., a loop) or binary. (Note: $e_j$ refers to the edge in the graph associated with measurement $\mathbf{z}_j$, whereas $\mathbf{e}_j$ refers to the residual function associated with $\mathbf{z}_j$.) For more information about the Graph SLAM algorithm, see \cite{grisetti2010tutorial}. - -We want to optimize -% -\begin{equation*} - \chi^2 = \sum_{e_j \in \mathcal{E}} \mathbf{e}_j^\transp \Omega_j \mathbf{e}_j. -\end{equation*} -% -Let $\mathbf{x}_i \in \mathbb{R}^c$ be the compact representation of pose $\mathbf{p}_i \in \mathcal{M}$, and let -% -\begin{equation*} - \mathbf{x} := \begin{bmatrix} \mathbf{x}_1 \\ \mathbf{x}_2 \\ \vdots \\ \mathbf{x}_N \end{bmatrix} \in \mathbb{R}^{cN} -\end{equation*} -% -We will solve this optimization problem iteratively. Let -% -\begin{equation} - \mathbf{x}^{k+1} := \mathbf{x}^k \boxplus \Delta \mathbf{x}^k = \begin{bmatrix} \mathbf{x}_1 \boxplus \Delta \mathbf{x}_1 \\ \mathbf{x}_2 \boxplus \Delta \mathbf{x}_2 \\ \vdots \\ \mathbf{x}_N \boxplus \Delta \mathbf{x}_2 \end{bmatrix} \label{eq:update} -\end{equation} -% -The $\chi^2$ error at iteration $k+1$ is -\begin{equation} - \chi_{k+1}^2 = \sum_{e_j \in \mathcal{E}} \underbrace{\left[ \mathbf{e}_j(\mathbf{x}^{k+1}) \right]^\transp}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\mathbf{e}_j(\mathbf{x}^{k+1})}_{\bullet \times 1}. \label{eq:chisq_at_kplusone} -\end{equation} -% -We will linearize the residuals as: -% -\begin{align} - \mathbf{e}_j(\mathbf{x}^{k+1}) &= \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \notag \\ - &\approx \mathbf{e}_j(\mathbf{x}^{k}) + \frac{\partial}{\partial \Delta \mathbf{x}^k} \left[ \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \right] \Delta \mathbf{x}^k \notag \\ - &= \mathbf{e}_j(\mathbf{x}^{k}) + \left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right) \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \Delta \mathbf{x}^k. \label{eq:linearization} -\end{align} -% -Plugging \eqref{eq:linearization} into \eqref{eq:chisq_at_kplusone}, we get: -% -\small -\begin{align} - \chi_{k+1}^2 &\approx \ \ \ \ \ \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x}^k)]^\transp}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\mathbf{e}_j(\mathbf{x}^k)}_{\bullet \times 1} \notag \\ - &\hphantom{\approx} \ \ \ + \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x^k}) ]^\transp }_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \underbrace{\Delta \mathbf{x}^k}_{cN \times 1} \notag \\ - &\hphantom{\approx} \ \ \ + \sum_{e_j \in \mathcal{E}} \underbrace{(\Delta \mathbf{x}^k)^\transp}_{1 \times cN} \underbrace{ \left( \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \right)^\transp}_{cN \times dN} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)^\transp}_{dN \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \underbrace{\Delta \mathbf{x}^k}_{cN \times 1} \notag \\ - &= \chi_k^2 + 2 \mathbf{b}^\transp \Delta \mathbf{x}^k + (\Delta \mathbf{x}^k)^\transp H \Delta \mathbf{x}^k, \notag -\end{align} -\normalsize -% -where -% -\begin{align*} - \mathbf{b}^\transp &= \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x^k}) ]^\transp }_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \\ - H &= \sum_{e_j \in \mathcal{E}} \underbrace{ \left( \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \right)^\transp}_{cN \times dN} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)^\transp}_{dN \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN}. -\end{align*} -% -Using this notation, we obtain the optimal update as -% -\begin{equation} - \Delta \mathbf{x}^k = -H^{-1} \mathbf{b}. \label{eq:deltax} -\end{equation} -% -We apply this update to the poses via \eqref{eq:update} and repeat until convergence. - - - -\bibliographystyle{acm} -\bibliography{graphSLAM}{} - -\end{document} diff --git a/SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb b/SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb deleted file mode 100644 index cd3d9fd5db..0000000000 --- a/SLAM/GraphBasedSLAM/graphSLAM_SE2_example.ipynb +++ /dev/null @@ -1,332 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [], - "source": [ - "from graphslam.graph import Graph\n", - "from graphslam.load import load_g2o_se2" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Introduction\n", - "\n", - "For a complete derivation of the Graph SLAM algorithm, please see [graphSLAM_formulation.pdf](./graphSLAM_formulation.pdf). \n", - "\n", - "This notebook illustrates the iterative optimization of a real-world $SE(2)$ dataset. The code can be found in the `graphslam` folder. For simplicity, numerical differentiation is used in lieu of analytic Jacobians. This code originated from the [python-graphslam](https://github.com/JeffLIrion/python-graphslam) repo, which is a full-featured Graph SLAM solver. The dataset in this example is used with permission from Luca Carlone and was downloaded from his [website](https://lucacarlone.mit.edu/datasets/). " - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# The Dataset" - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Number of edges: 1483\n", - "Number of vertices: 1228\n" - ] - } - ], - "source": [ - "g = load_g2o_se2(\"data/input_INTEL.g2o\")\n", - "\n", - "print(\"Number of edges: {}\".format(len(g._edges)))\n", - "print(\"Number of vertices: {}\".format(len(g._vertices)))" - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEMCAYAAADHxQ0LAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\naDSaNoI2+BqNRtNG0AZfo9Fo2gj/D1KYU/J75gHUAAAAAElFTkSuQmCC\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "g.plot(title=r\"Original ($\\chi^2 = {:.0f}$)\".format(g.calc_chi2()))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Each edge in this dataset is a constraint that compares the measured $SE(2)$ transformation between two poses to the expected $SE(2)$ transformation between them, as computed using the current pose estimates. These edges can be classified into two categories:\n", - "\n", - "1. Odometry edges constrain two consecutive vertices, and the measurement for the $SE(2)$ transformation comes directly from odometry data.\n", - "2. Scan-matching edges constrain two non-consecutive vertices. These scan matches can be computed using, for example, 2-D LiDAR data or landmarks; the details of how these contstraints are determined is beyond the scope of this example. This is often referred to as *loop closure* in the Graph SLAM literature.\n", - "\n", - "We can easily parse out the two different types of edges present in this dataset and plot them." - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [], - "source": [ - "def parse_edges(g):\n", - " \"\"\"Split the graph `g` into two graphs, one with only odometry edges and the other with only scan-matching edges.\n", - "\n", - " Parameters\n", - " ----------\n", - " g : graphslam.graph.Graph\n", - " The input graph\n", - "\n", - " Returns\n", - " -------\n", - " g_odom : graphslam.graph.Graph\n", - " A graph consisting of the vertices and odometry edges from `g`\n", - " g_scan : graphslam.graph.Graph\n", - " A graph consisting of the vertices and scan-matching edges from `g`\n", - "\n", - " \"\"\"\n", - " edges_odom = []\n", - " edges_scan = []\n", - " \n", - " for e in g._edges:\n", - " if abs(e.vertex_ids[1] - e.vertex_ids[0]) == 1:\n", - " edges_odom.append(e)\n", - " else:\n", - " edges_scan.append(e)\n", - "\n", - " g_odom = Graph(edges_odom, g._vertices)\n", - " g_scan = Graph(edges_scan, g._vertices)\n", - "\n", - " return g_odom, g_scan" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "Number of odometry edges: 1227\n", - "Number of scan-matching edges: 256\n", - "\n", - "χ^2 error from odometry edges: 0.232\n", - "χ^2 error from scan-matching edges: 7191686.151\n" - ] - } - ], - "source": [ - "g_odom, g_scan = parse_edges(g)\n", - "\n", - "print(\"Number of odometry edges: {:4d}\".format(len(g_odom._edges)))\n", - "print(\"Number of scan-matching edges: {:4d}\".format(len(g_scan._edges)))\n", - "\n", - "print(\"\\nχ^2 error from odometry edges: {:11.3f}\".format(g_odom.calc_chi2()))\n", - "print(\"χ^2 error from scan-matching edges: {:11.3f}\".format(g_scan.calc_chi2()))" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nAAAASUVORK5CYII=\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "g_odom.plot(title=\"Odometry edges\")" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nQmCC\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "g_scan.plot(title=\"Scan-matching edges\")" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Optimization\n", - "\n", - "Initially, the pose estimates are consistent with the collected odometry measurements, and the odometry edges contribute almost zero towards the $\\chi^2$ error. However, there are large discrepancies between the scan-matching constraints and the initial pose estimates. This is not surprising, since small errors in odometry readings that are propagated over time can lead to large errors in the robot's trajectory. What makes Graph SLAM effective is that it allows incorporation of multiple different data sources into a single optimization problem." - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "\n", - "Iteration chi^2 rel. change\n", - "--------- ----- -----------\n", - " 0 7191686.3825\n", - " 1 320031728.8624 43.500234\n", - " 2 125083004.3299 -0.609154\n", - " 3 338155.9074 -0.997297\n", - " 4 735.1344 -0.997826\n", - " 5 215.8405 -0.706393\n", - " 6 215.8405 -0.000000\n" - ] - } - ], - "source": [ - "g.optimize()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![Graph_SLAM_optimization.gif](images/Graph_SLAM_optimization.gif)" - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nBL6Dg4NDK+H/A7aRY5b1tCw8AAAAAElFTkSuQmCC\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "g.plot(title=\"Optimized\")" - ] - }, - { - "cell_type": "code", - "execution_count": 10, - "metadata": {}, - "outputs": [ - { - "name": "stdout", - "output_type": "stream", - "text": [ - "\n", - "χ^2 error from odometry edges: 142.189\n", - "χ^2 error from scan-matching edges: 73.652\n" - ] - } - ], - "source": [ - "print(\"\\nχ^2 error from odometry edges: {:7.3f}\".format(g_odom.calc_chi2()))\n", - "print(\"χ^2 error from scan-matching edges: {:7.3f}\".format(g_scan.calc_chi2()))" - ] - }, - { - "cell_type": "code", - "execution_count": 11, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\nRqPRVAj/D0Fj/txvoohWAAAAAElFTkSuQmCC\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "g_odom.plot(title=\"Odometry edges\")" - ] - }, - { - "cell_type": "code", - "execution_count": 12, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXwAAAEICAYAAABcVE8dAAAABHNCSVQICAgIfAhkiAAAAAlwSFlz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\n", - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "g_scan.plot(title=\"Scan-matching edges\")" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.5.2" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf b/SLAM/GraphBasedSLAM/graphSLAM_formulation.pdf deleted file mode 100644 index 65c868246c0ca8b4c93122afa111070654a39624..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 276368 zcma&NQ?M{R(5<;`+qP}nwr$(CZQHhO+t#~nW4<#p=jxxTIk`x6Dp#qbs-LwwO{yRw zM$1UY3PrlGGP(i9#6ZA6U~gmv#lr(dFJo$F?qWf}%)rh_@P7{|dNE5I7gHw!dNCVA z7gG^aV|x=*C_X+YXBQ_^Lt7}1ts8C4Nf{<7WveXCQ^Puw?!QCBAGgXW!`STp; z+@FP3`fMvuXAM|w%9Q=6lLxh(8iPJ zivr2)>vk)~mfdXy&&}3s_4H>&_(JPezR*JdHQjDKMNSzxXEnpf%c|zRfjsq@T<5T0r_ z5-;VWagQwMD%^O)Dt2BffV4}89Rrhws2CVlx~y3ynVEC_T*cObBytw^ph}(55W4jW zozRJsZ)&P%_0yuDL8^AmSt>WQ2+mYWb%xRzj|TtJj9F;jwsJED1HIQVdC}}KX|s+v zlI_tTTk|K${02*&rNf{h2J0K!w3JCw!Spg~Am!MD%@5PirO0P#jE+35sX8d^X5~SU z_@Z~U`EKReL8zhpQ3dvwE%a%+M)b)MxxC>`b<~NuPt;m=owQ+%s;-7!E*rDmrMn`~ zCr{Rd2nh$Op$rWX1sc+gu(s-9&z|joWb4ur2-m97o8ScJ00X z08O1&7Q+-&1kdf8be(gcUk9ygtE;7fpqEvKflO~Js(WD{XR;X|tMyE4-zc3?T@K7Kv72xQUf12YaD#*NlO@jM_*f>zvC@ zLQ;t;WkTXbn(=yb z`BggLv?*}kVu;p-4sM4;~5A^0LhViqVD!N=_s~YjBx9J8I z0I7%5jN*QYClz~z<&@)&$hHkn0BV}4!t3-@eD6OaG@v`rWBNp#CUIs_QQejV_E)p3 z%WkR`Vke?k!^z%ku7&!e+bjXH!+uGBo>eVmkHi42ls9U1{qlHx>Du)WWbFI@Rprjg z3xE@(Z(D83M`8l%Zqf4gOUMB7vh3G+CW^$4&b9VQ58%u`3W+eBw~q)RY@ygeIqQ+e zj?Dpk76T5ohq44ViCoGixF9)zdpmdo`3dktAJ(vrTAP)l-G0KD1* zP0hOC2Nu=K2R8zC73e;OXtq>W&mveUibrOu2}_U|nW_CK1dkP4J~oVC-$nHMG0YEo zVIdH5#1tp~N#eNWHRG7&$#?aNH@K2)&{3{?nYSv%fTa}0LH9i~I_CXC_^gS8=yxkS zkJL3>_bVn-nWPZw5swG-7J}%A-|7ag-_MNO1%7-O+jXd8v?Y zQZ6+50l4i+dAz=Nw(lI9Bm{{49!EU`I!Ah!Kv#XI%Svbs3{m?bh{LXyw{tGBJ^s}dsh*j@M1C?gxJ@&Sxj^U?7+`m0HcT( z0BKD#C`WYq#uzo1VI>V!V(x=>+`+B>B{1?t{wvL7Iy-gQJ`U5mvtOt#%!9?~?13$7 z6(FcE>gk`K?4&S(cxgDHb&sqJ7K&{cKZkFarDlEMf3d)t?sn0$xRQb|XV_L_J>G!E zSO}z)$e@Vu7dgC5LXMVAaX~!5*iyj?2NqItmyGJf?x_cd$N@ozhvrD;Xf4)Fy2i6Z z;1##ez;44AkT=00?2I2N#oGPHq@o-%4(KX%^;91LV&8@zb}jB0lcFd8?rXHOPxxyZ zDet~4WrE76`X(yXK(My#KHWC9DF{5qua){V;-rz}UT8)G3O6K&PbpRAaw28BmCRRz zu_Ja8hZNj`PaF4C{I(w44Lws!;aD-P-<0p$H+_+j~qDh%u3UswkBVL}QkM$81Qs|JXrD*OHl0r|sFh@Lm< z;dWOh$DoPgKJ@J!WkBSj8z!uWBva(Vy=VZgU#>_8AUo&ue5s7{RYo``|{%)jn*Ru^5QRD zW9k!i@6S5#7C?I>-2|ciofMsN8`wAwy^!51z+6tOWNabqEW6G;!wE-~yzT3ZAe}EJ znB|5&8lq24)?KMW1FVKBUgp1oSPB192$H^^g3^y}BO7KvelxY(LYY#F8wNlnPv4So z$q*FYcTSl&$esI9vdrq1VK;tuw|E?Uvm3p68%H>$KWFm;nCV-wAQB{zue`?Sai`lq zPI*2%IQp;Bd_xMIi_0KaR&Z`4Hp`ffKCZ#)>?cF!iK6yapH+f$4~HlZ=xul9u8lom zX&(#zGy}UtTY_PaDaAHxN9?-QT+HU-re13?xb3UtWH_2}F6fMJUd+J76RPr4~ zJE8k|!(yxyOaUvnrYU$LfIDsnZe$_3*+`}Ukqf;z7dCGbA=iWeq5>u(uBc&s*g?TP zd@|6sd^{eH*DFUWnVI|ze-JhNYH-g9u`m-OAEK-S>`N)e9uE&lfzL$gp}4Te7uI2I zY+_A%N`7)3*heVWKt43MLsa_@BBPpNGM*PSlVLGA32(5d=`BAr91Xi`ZX;Q{t9^8; z4lhU(hfZ8NQodp;-Bo!xbczMCciu*CAPvU`636fMcm59i=B|e_ z7a1g4hYS&mPXGnpan<&ZjD7d)fQcnnc3U3h7Wo}8IX0i+P%bYo|JyOBDSMtHfMXCR z0<#?nD8#5uBlr8;nonEkxcwlIgyU?z?`n$wr3EQ+V@5CM`{^X|4?QXZ5~`VwAv5v! zt#7H$&O`h3^-O}a=zNYL##can*TRQi-qIq(B`!TLo6V=$>rsBoV(;A_V4T8&ijFbP zvKn3=0)LEj&^!=bm*f~J_dP$(+vy47A)7k;D*(`6`ZIHkLM3=QRn~(;;kaAurg>nc zOA|QZ$9K1A+rO7D$G9EgG`5g|@8&Vpw_h`~$zLeJKo|}N`SDnDN}er~-SiynFSuBn z^^g#}y}}p4I8fzGNk%SW?4=*TXPg_#)XwDpRRaG-|4T)%u>Vgv!NkeI@P95RwC%Si zQ2plX5k8e5BRX=v76kE{ERW`!Wsx0<@)M zOZIE}B9yO#AV-Nv`|-R{>bp0j4B1taVo1ZgoCO>L#ZDmR@$wYnP(E3R2_1i%EQCDW z9LatL%9tB{meK9#gmCvnBm_22FkmYnKDZ|&jHCbMD!5XD$WQXe%>DRC;Du-zJBG8M zL38?C((!tUtd5gW2$L`8-n7`|jJ>=MuY|*@f^&8D149r5>F}k{CP9i?{A-N^O~_(E zv&dM(1r>G%(Key15eOL9$r>j{g&J%U%fGx!rm?1 zgaEEb=zt}sfxpCZhHNp!kw0VnB(#daf^F!L>rGh{7LFN(nFj+Ql!-%e7&(gr+lE|t zBPvmZ1XpG&Gyh>8f`{M$wZ{Bbwi{j5?Gcc}IMkQfUXTdWb69gl1eP5W*yWwf2M{M# zf!x3tttkG__QV(6aCsR*I}U*jlho!FHq_T*Aq+GySM0zrjtPz>5KjrJ!WE`snhGon zKoKb)uJY8PM65i(3Z%gUTqT)glqBG?Uwln!aQF~Wg4S--QUjFj!SNH4E#Ke?lC2-y zrpTCwBbtEBkbuvCQxE{!t+s!bBy&q^y$PUlxhjH`mL}Mk+GPrWI-xi?LW3*-a`97a zh6M+@iJ@S9C)?$fDa@4$)C`0y7!7i$bvR$>0ZW~ijdDRqQ zCJC6`KNpc__Yw^3+e`cUvWSw3wV72mEcmGuYm%f*;k(!_9z)8VH33Ro17)DP52h0|uNrtW#Osn}R#dpc%=iqL1w3wZfPbQar7AI)nHCpxD_yX*8Z4iXW$ORJL!k7T2vn z!A0e!*hnqyxsdtD@%{qBPj&Q2KS8*j^3Keeth~P1mm4qbrZ?`x3iYr5dP=lU z&mWVJt^O2M?1Bl<)YW@mBUp`^$$S@I2?uhF5mbEg+pU;Y=!#aAU1zbwo@kp1qFmGc z$aH3idF^2>&0GR06`dlE%60}3&~s88I%YZ?B1R+dfd(N%B6h&QgMz_h1zJWcaFBk`jP}(h)3hz83u)NHq5el$woooTrW;K90>ugSD1rQIjPs^HA_WHbpm*lDz;DK zriw^|iyY-zIv>@^E#0w?_xTe%LJBStxGoVvu{BVcD4r28F1VSlCQ=gU2;#HEuXuId zLE93T6aYc(Xvn-%#seNI|J74_MU@4(paJ-f1qCJBDOE9GS}*G~+x9wx;@@$KDU7D) z7*9u8j0~uU-eA+-Q4S>83a8EF^h9 zJj~PDKo0iuq{XPW+p_LzIG#3&y0h&#s^+RYxZuLw*tYAFM z+pJiizm~P?Vfk;S{&5M8)qC_x)RI`mI61@gOj+DEIWIgC0iJDTdz=W3rHlw0l?6#a zP{d}20uPf}2t@XM*jOwqliv5mS)1}p*n!g z8XK9b;fuqIjm*VkB1+#lVU$1uD}@F>M<})h49`_=s#ED&NzaAb3o-Nj0!opre+ZbLn*P6aqeJ`ta$_kQF#ro|@5!sIlwUxLul*j{g=yi%` zU(KyZ`(=s4-Jls$?`8aAt$j{EJ$l8-(-t3YncWsHA+OX2!SgK*n5Ow90{X3zV}!fg zm;0TH*X0sXT(*0HzeYANSUJ#NBO3~17Kw%%$DQxnL-BmU)H$c5mz*Pa-0v2h1_jA? zE4`K4Sm*M3GnArj#BrG{@sfT-3(05ojp8p)+>j4-H$*m({i|z3gVd6U=y;0WFj+!Q1f1tby=R%ZHVx%T4aW0lxXDtP7wXL=Lgs&ZZ%NKxK?4 z=G8BAQ1G!!Wm0;F-?DF)+>;A_6Z4A+lbq%>{tpHV$^PX0ibHK1?8N}Q)Rsv=<`&)P zCeYw)Fpy{N_(pvc`p{uD1NPU}A!M?^S zJGB~rV&-uf;xH1gNGpSihxJ(ols<+MT~Uz9eS%Y6QrdzX{BOCOi-^O?GWTnAMd zlYx^jTa%$N2Ss*s^6v8JL=|tA1I_!h?B(a|$dark-~aRZWPemXPd~4Ib$WJmdGYd~ z&;K(e>vI^(;DXPV38}|1cx)R-k0#E1`0f%o)7V!! zZ`7qZYMp&4Xa1Bd>uRaz=jBeag{&g6JYPTE-`;Mb!_KQY#~!`x@j#}dxl4D1 ztE%0blV}|&)sh`!QI;Tfha`)}gc=KDzw^9(y87tU*Z2J}F=?q#6tgEBlsYGXpPjmZ z&v*c%^C^U(D*0uq52tUTO6?T_@00uhsOm6V4H&)b+{7m~xQK!y^SH7|m7Y*4y>Wo_ zjPIA3xj!}Z&+Auo4LwH2_i*2rlD5y)S3jYYegY#dg6a```#l(Cxq9^b^~TGwwSx?N z@1zIFi%m*RsBa#k68dbEj<9f2MdA@EWKmxV(SA(;FJyh0Lc=9S$@SDK?Q~&w^pP#D zswXT>!y0d)Q)7JIzW)3Qzj!c2B@~^Db%VNWvq=L*9@5Q30KdE}ozYH>{XJ`0oKv^< zSlvGDFz#LC$QWVwaMY^VBh8tf5^8)$;_H(3)l^7M%h(De90zbv7gN%O@Lj6|r3nDG zlY(9)BHEhQrQmK~(DmVJ*N-rur4H~I*RQbsGt`!zZlfqf{oU5zj1+2qmaXY_nv>Yw^a@t`%~_^OpIouQ|1o0k5pwo^Z3MuS)PKbp2OxVkbp3|+-!Bv8<& z&?7q7s%_B-5l&x9J#<4HgB4+5N0rKd{)%W6;9xMe57!)!DF3V_!HPPT;gu zP!=RPP%3(XMx%{vlG+h|O6c_Akva*Gkb4VQ&pkOTryx7tItpbv*Y23dgEnK60;^O* z>U0Cb5O*ChmPjlHV^DXtMutAyJ5a$C#O%Q%>6|fPdW5V$hFqBlFlE?iwWxUJA>gAd z1{7`!S1yIE`2jeXn*Va5XJTnoOr10dVbAQeHW26k)gpykB$VJh(;z<&C9Nko>KHc0 zG2CB?vOQ^(idQhFV*X{8-yUlxTC>6~TV=mcj~SyMFws5`tPm7xleEp5kXZ;`m)*U(KFrhLC= zWWySt!!$%7xt}Gjd5qppp-KYe&FL`LTI(*l@K?f&>Qik;_f;Cemf*lj)Wr}vr!`?p zZ^o3`j45#)Pcjz3QY7`6uVe>oly=JNowV2=%mqQfHi^>p($Ui&mv66{*2qzdM2K|F zHM?Fb&pcVGE-wE~&l<(n8x!JKcO(tM7nHkA1d(A|V^X)Rz32C#Q&CjGO~`wcDFA~n z5S7_yj@g!H2_97G7UUs|mq|=_%9(kOV$7!&?5$v|!u%U)F)_lAR0@oFh!o&lF$xtk z^T1ePDpru*!EH6!dL=Mh#d6W;y#p*pTFpfII=&cqToKpVLo*21#_(o0Sl15F4VZMw zMFVmda?7k5+;W^kB2FQ7rAX zC@Zp3XN^7P3k-8jd5NtGlcL-_E8JA75*9|kda=@FYLQKnOR#0KWrV8C@-$zZWBa~F zRuCaX$a&~%?+i^WM>tnc(2J=?F||6Ei8N^|qwZwZopeKN?cGobr)HbYFj_7dC7WN# z>QJ%-5F~vp#Z|SfGkDFb&C)9l*5P3;h7laV%d#ej?Xr7a@2Rh%kZbn4kTjceT2j7v zSy6p+{L>S;WnrbLAl3aCo@cq8Odps3{R+uiu^A#C8qzPxmssgs>ztfiO}+;ensTg2 zsG4{&a(X?vlkY3=tzwa32(R$RDtrIu>kl_6u#mfJ4M!QEK31CSbD>SRa^3)3idUNS zz5SqR?+Lv-N2S!F+OqCe;70G0`oQZ&q@8^WkIUg?evp9}$Q;~RA_f;IF3EdwW$-;1UQ+6dqxwZC zEO6r_oFb#g#*h2zik)rsHFGF3*dlj6(FtML-db8ey(0N(HMY`JiRD?x47D_d1|=bI}gqmb(Z*r)n9-XMrHVdNNvbE0XyiKabexNUzmxRz?+2IM}Aq6 z%+t+`2X!uPpNZ%Nq4SZ9BVGm-wA>lw^lpynBv=5zMvMvnBOh=$y>8iB| z9;Rn#G021Y?eu618#n25+8a`?wa|WcZO6{xN-&P7Q7Da)#s*c}CeoF;Kvex{DV@S-NTdK$ z2Ujs1OG_nfSg5)}p)IhxFcz~3b~zSGS1}+_Kcc1}pK<=1u@3%%bJi-x+oAc1WXeE~ zND=NCfdazih^!rqsh%lj_|}BY%0=4Tln|t>F1?xeM3q~kP;FP!@+DK%AVzT3gRY&? zyizz+2hKY`H-f!j;`U*Y!yuQD$k8aj&4o-9J_vca zf#Gzw%K>P09=jWayfm8o%gFJdScK##hU>LyBaM^AyZ+YC#rLL;}C9h51Fa`DN(@0sm=!EpCR>kQ}XWQ-@ z*Tj1uZOMS`QBmWSM+ynh#S#oe#F@TEH))Ho3j3-)+NwrtIk2o4Dx)R4T;{gi#fsn> z`_clZ`-0v#9Rb496yuh|bJ4%QB(_d;52tARlG-C&u{LXj-^*HYS!}(i2MF%6IRQ8A zNIz{@M(bbLy~CKO6BzudW6hr_0~T%#YsEm92@8E~8&AIckBITkpUIhWLnO(0y6mC$ zNPVUBmWiY^uLdM;T8F$}x>4qJ${9Hw4EgKm>!?8mCvIgBG z2cL0CfPdb?>r8h?2~f>i{RZ$26}IDE=o{|)YdoOMJvMLw4ioa*3Fh9~Pz;#god`h5 zIy&r$al+n$zx(?^?Sx(KhBG?yREKFA;d%MkI$YQflpHhi`*UD|-kq@jmbhOacg(jv zJOx2f-(ic!+V<2h&C%k7#~dD+-^t{ALYFf{?%>_da$^UWjUd4?)+#DNgkq>l#x?^& z1ibxw7j%lWRiwZMI&!d9k=JP+3Y`5eEexT=j<8V(GA}JG(iJoq3qTWvYOAc&kVwbq z;LF4(~azg`=?lhw;&_xLfQj}{vUy8)FB|;fPD99 z1MC~xRag&NvZLY?`9SSPCNjuUS}B<8$FX5rnU6%x*X+?D{aksoi6vI<`j{5L<_q9h zN*QTf){Nt5z}Gj3!y{m!I8#sui=RGVz50xw3=5pkkO))zTF?;X=oF!()P^dV7 zSc|KredFiDS{vQD+q`B8XxpbtnoXE8mr9x~lXE%>`;4iaGXTKZ$RRfpl%LLSVek#Z zw^g^W7D0P8qe4?Rw@BvAoIq2(?4tzJ3T_hqI2EP^wgvp;S8MnVZ`OZ4astLSUQ>Jz zZ;O7|flRm<1aC;i%Kccr!h@pRkpAVa`Ys;y#;b7`FX74*zP)FN^oY9cHFLBIUrzv0 zCTTX&g{_a?o$?)=jfI6rZGOnP>GSdS`!SUNm7>CR5o688nXDd;od6h?@PM>_(FfP^iX6KJ; z!)v5Sa$l<98O!ND<*es*vasF(varpr%EEti8hSiQ8QlQEQmZ9}j6+Rg>R{~{F< zd0XXj!`tUOF75u2g~HG~8LU=ge3cTDJ#EH@&Q*538!fG|jqbsCj;BdT!f6*zz1VI> zL)ybS^}p-I>{K=Jo1eLarhEdZikn$FT`m1)corizM%^

h@}?sWJZXhc{G<|4(;= zo%R2tqRGt6@_+1ZXldK;tRecX*B>0yA>`$Jl?numg(i>1LanGJ0JY&$L?*TEMo*Pq zkH!6Y_d6d(?eMPDwMXfqdnQWUCNP_u_1T-jeVkmMT;16mMl9=~o2!Q&h8m_Q7)CWu zADy1u$nLHzuba>J{mM<{;T(rh>Za%%`zP_rJJl_WU>f%3kO@@_A&r@!a77FG=B7c| zMKzH>%c2-*L*@2MA9)I1+(|~fuB66TOdFyR??NTLz=?58homEoY!sD@aN?T&CgPEL z#Rnmri^@mv@3Q7H9vQU!i6?8)Gw&UZSST+93Icbd9!7ayl_moxe@>a)3&@|Ls-sm4O&y9Wr2PR6<9OPQC{wRdb-pR1nzf#1H--B zH%*}stT-E|T)e0I=2v(mq}zB#PIM+prIHGNA?t6jN#h*u(&#Np=`WhO77NC<5WNm$ zGv+oNW6m@Q`pA^Q3IVo$;h;iQl)PMjyW=ytHXa%1TRKu}UbGGigZl;+2E+!05=<(= z_As~5Ujo!`7(ftQj{41*GzF!9@|`#gCm6?xz-bN532ckN5oB2gK8XMf2ZGYjl!y8? z>Q?(8UX13Q)&Q|9`NoJ2n|Ak@SRfc>8gPh%Xy|GyunoZ-@c76=OMidB%upZz-UnM0 zEksT9z@R-FjfR!`JUm6QXc>qM4D>=U=tkYogNHk7j)CVG*%?-R0KL+);-UI>ENZe= zB%=ZjM%fNU2?%Nt6+M2NNY{e_0~nag_%`)kI3=`&OfeeJMYddt0}mq=nY1l=maY*Q z6&5P=dJF{q@5&_F{@0UGLxzq-1G%X4Mk$owiL)`r?n5*jG~lEW`7GETh$>bcAH6JP z^`R9}M<^kTo8|=#l*XgdcE7V&6$~U#!K)kz4ERV(!qH8qke89xcQZL(iECiCjAA0F zxXSVVScj3dhMF!RcUdg`XAf;WuXIV^q?(_gvr2eUg-4_wXmUbP1fEc>RJaqDOf4W4 zGhZ5Sygq)~WauC624NZFB-e@oij@>gajMP214on1FhF@IaU9M_&;hOM;(kZ55Yhk; z$s-pDv~aKx_+J(j9HxFy*#zDK;|~Ud>XCKrAD-^Yc#547g$pB9PqDBa9x2rzdf+!F zN2+E^@bgGW%6CsN>JCN`Kcjvy*tdv0qFZO*YHWLWGo#^)(1v8dHvg{h{wVfHQ#mUgp+&$oEh>*&j<-V6T=fB`5GT9Ap>ddN0N*q zf6qyVnT>rzPV}xD-8MYb27{H2y(;W{Jg&?Rf!K?zICe_tS`-^P0%U(LW;fBKq1RGz#^Ckt#)CT$wNKU$64l zo+@=)sq+1#R%I8yT!K6IFepO70AjjLdRQ>~-*?GCAuIdc#2NSxajFMwdYLom`3t!6 zcO!QW{zDvx0frxrYbw?=9#TA0aX~Gy7VZcge`YFfqhMt#@U44<0MobZZ}1ylDQG+u zC+9nkxtx7(9;xu5in9=mON{;fllYE)OT3-^lQ4hxDcXE^x8qZ9REu!jY2R%-WyC92#}o)j754`XhMz@|~hysPXEjwk+CW4ew>$9$WKhD?IsI zyK;k-Nz>Ib{c6{P?famW&Ia1c49}RBC;Pk+if5QbF5ghXFz&A4c*magPsRdF_-uya z<-xHBf}}Ww1b6w>pWvAdJy*NKBnf7Q4<7NZ!)^jDEK4v3iNddtYVNfM%YeF#5(bim zU!K;YXa`qs?mts*Vj+cDvWkeGDrCv_(Te)D7p}biOjX6DYIH$gpYKN|JQmlU(z>k_ zj%iAjmgW?3^yB9l`fhor`+{FT8ij7aon+6}9t}VU3s16ni4WpQ60DfU?B{p1rWLuZZnxDL9tsjy zepKRe@(xC zM&tMM%#Ks?aEDU>9)_38<%{e6HQHEN2ELv!?^j-lR^BrRlI?!}RF}(a9{c;>LCI>i zy&B`r%OP&NH=E+jd7gSvKjHo|)wK+%h#vD`yDZA|LA>LmP>82VCuSRKC!&55dAlur zQf`H2nH&%$!5M`(ICKp^pld(_U;A_p876bghDN^0VwK+J@;TRN76`4;8-v9NM#$a0|{XJ2~?| zJ4Tybw|8_~++};`NWqN@vcIIz(Nmg=G{L@vAjeD1tGRjFHgm*H$WQ9#hWFjv8uxTg zlf7^S^jHxuDLGZhxP7vTcGTP|l-{0**Q)89D?I2suNvlID)is$iGJ+Ve4?(gdj9~P z@Akj{Cv9;u{!iLsWa0dOV2j}Yza52{afO*xi9vw@RLGba)Yv%`MYv9g&KMXJfrSl7 zn&jMx)6?l+I5h^g!#{5T(avXHUsS0mDdo=RT%a6On9gTilp_(u#(cp01p%z|dXHUXQUO~@zg z=+x!w1n2<9oLx=+=OGyxnf}Kq83`C!SUCT83l0+j2O~Sv|6VZ@F#PY3fRmB+{}?@E zTR>G-w$a&OAeLx>l!T?+-Pt9Ap8J5R?;Ij|{^eoShw?oSlst znXCX4=Lr10H)6mFFmPZ%A^yOJ;J|>0@VuV{Mt~Q9p#UkkIs@I`1A2gndWMK}b^`Y7 z>=69{6f!6V@GRik052SXR0t6gaG(|Atc*f~wKa?LTtCet4cN>A9Uvki8vP~1B{+f& z4y*}42mnVkfOGO+Tfn*iT?o|<5`?V#ry8KOixcRGbawFY@NfjqIml7W$R&m19sr7M z0J{h{Ak5&J0KfAx2_Rp?xDD)w10Nioe5iN!H~XUl3ICD+*VY!!(FsJLV;F%qfN}={ z(4(w!BIZH30U#JXVMDkC3FAKo-U>7zFI)oNm%9=OD2ibN_+;GQeH^SYG(ZE*L4tGt z4-zD03ZFtn?i?eZ2aO4kIjZk z;{&<50#{D_#dC@X={o`-`pksp{AsUdI9xtf`9YjzA!t(woYcGF&;83!+xVJAlg7aAqE}O(DoNi=l}8I z4?PPB186CDc(5-I9S|Iz{pD{2f7#^bwp%A#Cec9rJb=7RZ3H z0DX0sgiiw)z&;<0V=Iv7uK{y#6e55KPZEZ@a6yI;Q^>a_Xl_g=HU4o{(<28GX7o9R=aD^0N(gZxFkI2f6Y%13~>V4 zG?tYerWM`mTH&?rqev)xIM~Qa!#LPsnlUqU$P4~;#=o6|WC?g#I|5^yiMM9SKn{F` zC=0OcoMi=bM=%CNy8X`d*#{KuBGvGBO3RySmxI^@yPfWK*%nOvqo$VMVZo%BH(@_K zx6)4%v97)J17c5y?~DpOp0cutWSf}w@0?Yi2N!>7_EmM^U$FSviC4DEuDP=x*SUko z3Bu76nXtcz|7)8)q9DSeM z#h11ls-BW&&+w7Uq2B5V>TMI=MWl!YxbJ{RbCFl)t5%8~Y zf?S6aN!z9fhIv$U|L6rm=}P#3>|rsC;zgZB?=N$^&WDFF@;Qogou0wX$WhxLi$9WB z?XvvuUPooQHiWAqKN;5WN&ynQYe58VBAQrt^-q?Yz@@|5G8_0?6JuI|F|$W$HQerv zg{M5ik1WhZMQjz{!z0?P#;m^d2MJnP2AN-7!Dr(omuifWYmD-;eLus1LD3MZux{$C z5zMe*kr^(uL)Jb7{(x>Q%p}nw986KE~A*7 z|Nis9-+b|mYK*lD<$yM7H=?3Cn!>Wxc?7#wTHJLhI(uqb!BOJL!)YjqLPTSY_`rW1 zmgxP$_U_eAkL4+mIhO zY(&UR1FJg^LF$9gWQ)K88)5ElsywpnY#tV6-H{eM-5EpSDg(KQ&q8J@*)L1rLY{$J z=J2L_WS?ad05`CL<==lY@D>ZXyo7o-E8H6u`%ZsQ{n5*niohLpC(nZ7*Ffv9^LCA5 z$178fvyDW-*xU-tB>QTEHBw?xd}EMtvkwFrRl{+o+*;mFF$u3u9~TXgJ}}rAyX#)b z@b1dX;@3%K=Aj8nPs-9%&9)Bh_akl(YUx?sAh;5RJ8DIOa%Z#T`Jh~DcM%E`e~tn$-AkgBf6ZijeR?Bio?~2PKaWuNpT6Z~iX(&a_ww$^X!+o* zO+}22<-Rj7F$^?C$@-nfRac{vE+%AF(9uzEGGq>v;=&ugP5Y?7UZ_HBe5;mJI2Y{i zNE=7%hXOmYxRGM4jjYGmeE84ETb?wkZkZi;eD+W95Z5i^Zx&VWVrd2qikb}H9e4`I zwozuF$!z25>FWD={l`(#iUw6kRfIPr-ti23oMNq@iXYz)B~~Wv5elmPX1A2$_N81I z`pNYW8FMJ`Q59$RO8l&@2GS6`7xo`ZT>(DU{mk^aa>?DtJ9&SKk5Ji>|9S4W=5luZ zW7qIyqiTez$+!jxU$bq#p>v;e3o$1KlO#NI%qbT7k}i)w&G)et;@}jh+Ssr1o;xu@ zTKwUcTtKO^<*7{_cMV9XUhw2)gen}+OsRkBG_ab3`|&!X=meItzs=w#5bzSZ)uZ20mhiTg~g%W>+R zEtYzj01{kzehZGMW5ZHT5p7m1uF)g!o)rJl$2p$SYmzA*I-6Sv$;bCk)6qm#nwzm| z61j~LvVZm8(;OFq82;?hW5-j?tz2Q(jZ1oaNNm*4+G!`LaqyK>(Ft|vEMx7HVcECz zMmX^`|Lp>Dw1K=aE!c^TJU>V<$1D+^OYKY3ga6J6au9w8jUy-)g|HreK1S*|p7k7J(i%-)LjzuAt zIkmy9CX{?NwV(#c2T{DlBPJ=x%V*}hvnBf?r+k{(=G_OuKUH1!<^IilJ{R~75WxVQ z>hrl5m8vYzsc#YlBD=DFX!f`{Ur_@3j=Ri9##L#Z zngkR`l{jJ_y=3@e&XEW5YWk|zf*l72+|_F;L`b!P?)BO$(EHv@F1_&6H}KT1IAh8Y z#^&Ig3LRy z9BVAru}p~-imGo#Bo%4)v>rL2L8n+fc}ThTa{p$1t zIoLzH?c!F;mVOA7pUgCFhI=?K)XHB;I=E37FMLHM2=KJlzKXxZI?k^o#jd)6d{d&G zmOVig)A6_1N0e_XexHXg>?W(`%?D6JJpM}M@$r1X#9duh$)kFLJKGSQO>cfh-C znIl` zvwn!&5=ybGK~ESj=QXmC!$N3}f-z}*?75p0ZF8^zc^U1WXZOHv1fnXXc|cJ0mCn$1 z{?PZ?vhmN=d#&+frfbRoHX>n8>`qvl;@wi;H%pO`@fH@eG~7ndvJT6YV>0#Q)qj;^ z*{RO?X2VSg92HkilWs>E#fVfYvy0TvbGh{kb4cC>dpMx8T%!0W7FU=m)rbC6s6Yud z{}F*I4EQxMstA2I@~#)6vY&lr`hu{eM|buR`-tu(Od=E6(I!(Ux`i1#C#Qvq>NyIV z$xoi19-owa6Yo3Ft1n(ucPm_wJxiZ*A?YzetN)9TbBfW02^#d6XKdSNY}-6z+qP}n zwr$(CZQJwC%zpnSo9x9Vd(oA2Cw*J#>U!#dCgcgEpJth@J=BV3b<;(Vm!yUdb0ZJw z7_$g_=G-^iMdA~V=%SX!AT^k-hj$mr+d5Li3CclbyEnvvdqaXU0q9tdJMCxF$zR4H zDM0CW2_tR6Vc5c#l5Fk3K2|=28_1XY9EDN2C1RYl)h^+gZA{BKTnW5|+SIm*%rGLW zY570zg!!hhi^7Al!wl@zJgdjvPdzl969-k1S@F82ZP!(;d1Fd&e!LxOlu+y|!m95_ z%_CtHV^`I>C}ElwL*>dmtf?41NV~Nb{*0YmI%dg63|WIK!wym|$nPrYdWJZ8PR7i+ zm@)O(uFy+7=P;{mc%s7;N#6BcQmC{P^-J1mq3r0!rxAOpt|NpCo5_7WMAzp$eFLWm z6eqyPlC2G{q=DEuBTX?Ks2~H*?_Xv;M2S7fU)F;7(3RY>eaJK%Zu@&wc4|l&iF`%{ z#T&$NE;$+-Q^ldiwDn{{Vrc=JKuZcHc-yx`TqDUn!X$x_hdmZgWngTk{{av`)7tj84}m}hBgK=+e4NPxMK1Yr2>)O)fagsVB)@wuUE)b zk*ox2=kBsNGwbZ%6x1aKgr^`p6eD)kItKJ1wx`5rX0%QXG&;^Dm^l4>pa*GC1f(d@ zPi3lyX{bWj$Y}(lArc2ZMe&h&MqmexBA8F90ft%Lt)v?FlGU}7`3pejiO&_kd zY02sF?bk=aMyD~!V8`}O znrP%U9P`+AB9c*IXSPSZKQ3>RR+|=yCqJpRF!lD1rKz$!jSrWbh-LS`BUB@Huswix(7E-Q@ejjTZOiWcI7IGXF3iST$=%&=E!sSZc?qzl3+yJf2@ny+H+}Lukp1gnn{bw3D~-&G4{yF;%c}WygYCK zkE;~?LnbIu5$}O|deQOUtY!(C%kDO?ka{1Mr=y*@96K$F@UGsrG|LL;%4v(*dHLIm z5;v*r#(I4|iUn31+^5yNjy5&mabg*=zOu;tP{vfu5SkS#uHM*+BK(o&P@M|OcyoGGF2knj0mfiD4a4tAI+ z++#~J(-b+DArh{ZxSM0(eMMyoSf{4DZO|n=piE%^m>ZQm+X38~Bqc~mM#ktf{oRnoUPjd*x z&#|}2*=XbvwC~-A#h|v)lw-dmWQ8|#okbJ`r*x-$VCL!5r|fTB}oTmruqUuYp#>;K&lj-i=Wy<8*;N3Kv4pZf&yf6B-@0^Sx(5Bu6i`d`)0&)EX96XgMnVTu?)5!36h`D;as-LW?fOjnPtxtH!Uqs}&rb`mS{+}(DCOulFw;yykCH2i|X|1=t zTKoqNgW(HRU4PDYIQix>^6vUAn-fax+wK=QvhFWAp)oVGOA?kVl%BGN1ws9Uaq3FI zfmHzMmkoGhBR;p^4Y1ZbbF#0U(v~q<34h^8&4HJJnbkz+cF9(`Sk-F=o1vnpXDA`L#l)fq!#`7K=d6${`j zlSg-9-2Ix3c!=oJTfeG9+mi-4zsxH76DBUKAH=`0S^t)ut9fIP~X50Q|wz<9;v#-V>;z-X3RJWj;;TsDU6oTq?G%uIu*eri5jjnV_Y@HRQi=`P3^}zBw2vVDj z`_xnTAd>DOR_QQb9#J}pSL5m*$>T*))?`;{<79>gWA?iHtPuV3>MPa+j&_;u?c7~|g*_41?I-kT8qES6j=n6Vb{uJ@Yr*QHxX{S7 z7B$i7a3t^R2E@&u{&lNFPOT}g?_Y{V@>Qtwi>A9**ti0%P@%1hRR@R{j1M3v*wvO+ zsI?5yj#{a9EUpkDXa62(K_9P36&l~wi6p@y#5fB%Ne(A^<{8>x!_TUK*qmExQKiIg zhU>*apeEgREUFxIvDE{yhy^1wE6ta93I{eesY8&6^^VDCqL8F&4*%GUC$rhJF;qwY zc7APt^<>dfY}vF#zpI*!Ie^ho%Hg~QE(Tyn-AX*0zqrNI4F{&l_K90qNp{7YoU zc5<`FuxrhDnyo&pn8>B4Sq8NY$}1gL?od^QvO6+zrsd+{Md8wNFdE8%Z55<<$WdZu_gUydj{q>PTdWqCu-DrCEQD-raIg5*CX=H#(wi4D%fuG z*+qcsHE*JxPz#LKY$~R5;Fx0dXwVcHZ~hY>q=ePl<2*SiVy`1-{GM+uE%KmjfR`Wwvd4JjKzmK{52Ri_L5<{G4oPv%2YcRHSWlHd0S|@f(MTB(DSdA6j>aIj8ZH ztp}(;LD&*V$sa`d5iF|a{cPpiDRK5NW%&_iKyN!_=KhDLPV_im>DF1@hWep>_Crbz z!1jnm&Ph*y#A{+DW497La0q}_BrCC87MwXc7)5o`_0ZPR&%I#E>XPPyz0iStf*XbJ z*Djl+g|#m$&psUC9?Y^TGb4Z|%Ux5LhRgp&O&r}CTAq2ML)7!v?Z_&eRp*R__XRJ& zN-X+!K;G_{$yJu-x22zYQd{)?wKdJ&{^tARkHei3YcM)J6bzGW7C&55{7Q zYgEw-jxE8|0uEgVLocesbkCtK0FH*~NkYWd!2I=5*u{Vp0e>~(>87r|@V6yGh5;+K z4t5=9SJP7@ZxHtre;89P$g4T!a>e;UGDz`u2_J6kD?0L%_1=6ISU4|GYFvBZ`*T01 zLTm8Txc3lw?TbH0*s|ySmDXib$|!~xB;kq+&%b((Far-mMd@Q4J?B>v62PE0 z7V7z*V;TzS=?DWqaFvZ)cXJ82feQWIiXyVX>TA(FjYcxd)$diOlj zWkxsG;8!zE(`B09Z@4^Qm{|R0GdHZRa(cCfc5f{Mm17oz>E%^w@ zyd>-SFcbC}fl?Kgcz@xN)^;HrS)nA7XOEWengQ7XYSCxl?=6?HV<5r28iK9P@%6Mx z##Keg_F*x2C7jw5u!^+l1D<~g-FM=pQ|@iKcx%>X&tre=w_0(-Dy&;3&|OPRS@)W_ z3<5CR{qhk+inv-*V79mEve%Yfn*H-;4-sXJ>mUqC+%9(5M0Fs#8BYE_0Yn@@DbUD& zw+)H>QDS~p3b}I|r9N5ndnshCwc3FE+FsQFX~vSyOGhZ!K|0S-QvS1NJ%%&* zgiW~_5h%ttNpg6VaRqG5Acu_!iv(i9xiDpOeXD(42Mk72Zv?OmpVO(%=5LuSk6!UH zUdJ8Kz)QT94HZw`d5Nk!MFeFZ9&05d^q)bas&0A4>S5G8@^2-$`R#WTru8d2J|oY@ zQBsCpD}cd=DalYyKa8@`O^ zYkVBzc@CfY50JJ7WQd4&l(r@*~YOhL0>4QY9wJK6jy+d=9LCYPh`Kqs# z8vI<)t!@-?QC`2-BOQbs$?2yCqy zfO~eOoM7|6n`MW&I z-{II{qXaN(4%pm-m$bEK(a0Lg6UPxa6L5mRF(;WJ53CFJCM2m%eBQUbq{Hlf+f4+= z#w0}!=kBnSeAWX6L(NN1E#FMkf!#*X9VvBiyIt%S^f7oum3k&@ZB7XlhM%$dV$-yH z^4{!}vrsey9?!mzJy$$35M%tuwY5o@`ST!rUKk1&0;9|be3gMJ~hg}H>BYc{Aq%hG*! z9-cF-WQ|(fp9Kf%gzv-x$C4ETp^oHv2`5^bqCIo0WyXb}%G92k#`0OYQy1VBqkW%; z($B2y?Pv;AKbl%bi$O&|d==y&0mu6+BgIjPJ~MkYH`Df~8nCqAy0yK#$c1~T-=pc& ztqap|V78NYG;%NoQb~Sk&WpY-bJav|1JN0LRvCGK_rZ|%f?_fO$(Y#CY^L7~e_7jq ztxt)O(TqjTk%tzv$81SN#ioH%BvjQplLS$s6)ryvEXm(lYC1lkOk%&Tf2!ZAJSU9h z@4I^ob-g0^H=a0ZGU$^;Ez2Pni_&_JOrDEY?>N^slSvg}ThPfsWSDkUEamr9I~6Tr z@av%9H!D5ouJRqhh^Zm-Ot8@xT>7{J%?QbqM(?Ue5R%;>h0`CWTvwQo_ zm^oXpY@S04#<9kesCNY|APzA)~K4 zw>Q>C?UvpaO^^f%0<&5=k7a~{&2$gGw=9~4ok z8u5Gt@Rpc?d!UKx>O@@oVNRC8;75S_R$oc{6Tr>nn`(Al5sO}>4&euCrU1(U`2w+k1*YZxf z)S*GuBi~>|byu&rE_@5=$!{cxKQff^b$9LZ&Ju*?WOgsA#1BtB%^co$tJrL+(OS+% z(6TuLW>g}OUjr%+glCny467%jT0f6>&J$Pw9*d>Obl6O>PUQmvQyHBoDO|o)f=?A@ zW4qkjv2dj4S23`mDg763dEpfNqI^Z*#i8=N*lE2)UchONI1yIt^F8!U#0xFN$o@y0 z;crNV`SV%O8&MZGZNIsgDAK7@Zg&A%aLyOP@PB0&{S*Z~V9B&o5YO3|#kr#~0392L4MR zkm2)ve@P4U39lu|!Gn3RsJR7zVCYC7M;;NTw`KlYH}TR{b@r~i>dSWrzMTl^+0 zkek3PxYIQQ3~|3O1B8a)L7XrRO=6c!h>*zulS7(;D9v%wxGv{IxJKK@pZXmJ<;`annvwMeS_}<;Pc(}mm@;3fH)wKQc zdgi*b0%{CE5H7%9?%!Gud%>d<&_Ehl|Mj)>rLCYg`4{qr^`rPdE`ADDZ-GE#%N~xv z>;XT3@2PW(K>>I~?l`~c-*!V+&XYE#Or~kS7C@V#(BJ^x{>bDMoc_t-37Ea3BP__f z2PY8UFP=D@`L`M#?(h4g@Lyb@K)=*4XSrXhjh8ws{dX%tOyFNU>5&5q#{r;FKZu?9 zptK>t1;W|yQ~U41<1hP3UlBkL^4pIl(V?N~OL*?SY~WWMp}DQ~>3!hU=Yrr6vYzHw7DV3H@)r@qU+0_P5Tf1+AR8#}+wXTy)wRJ-3Z>8f zo8_Aa$9=B%t_=6C_ntg__+J=#)EfuYZ~MgHd$Ine_m;AHqxYV)`bBW$I|%{6<~?!& zVtC|R<>$WomgQYIeqi&Eg?~fjBXa%=W>8-^d9Fctrr_YeC^r|g8wR%UzmD!)bZLI^ zR}(`=2!Of-2DbpAJp57q)K?4LpCP~QLH&B}bzB?Y(E)9a@lvkxmrlj(?HCuQ;}_EJ zQaNOjsx_YGnGe{T_svab0@%7D)*gN62j$C z7OlCHkw{Nbhu0yi9@Rf8b=Ey=4}K00tFJ9$mH{`)c{8pKDE$hPBfYMd@y<1G+8;ht zrvF+BRe|zI-@WdEFFmTs1%3mlKB*d;EYNVs(J9Cw(0A*2UYCcC$n-|f2~r23%$ajP zUbj5--zv4|Sr&68in4TPa*AAvKFCtRu-yd@X}ZYV5ir9|x*;EoFhmI-=*gqZaD_JO z0u;H_m$4oRhXV^Of{8jPeiMe*F%R*WPi-W*jP8D?is8Aa1?}Wa!&JEyR9~Y za2}GWQa)kO5lzuRfShx$epsuV=3(gV?FR zu%`DTu;;NJ^FPtQpTlO(%IJZKw)V9ZZiJPb5aNsiuz*nu(Hx>^W6${7r9G|KH**>o zdEIAUKt|z=!b+r27{#hlo788nNB(+X!}#h9PPAE7lU!yNouE^`A?Urkb7V~XAjbHU z;7AvgCSA<6R8X9k-V*8b{cxyM$^j^DVC4r5OhEtk@cp%#aZEw#8MvBdvJgqjktmA6 zc~?FRv_keUa1@ll+>VrW+n2xczSMl1HMES^=7`^)5#*WSAHy~dh`&iuH`JN>YNJ33$V4$ZP_aeyYq8fn5 z&7~iNaOSKGt~l9>OR;p9Ja8|>mlq|fo1U2nyg;EU!*58CW4Ie(<$WP&TYPOcrpG;8XXZ@Dbmdt4;yqEBJNSO&T zE;Q7F95Hk?@J*>LolxJoi@DT=Cfy5Dy~OZ`&@;S{@ypxpvl%Ym9*T^q8KT=KuUgrS@#uc-DDBs6K=F1+C~X07^?YGWw`*urBUbjq$}YGjcI^GOgIl= z5f(67ISpnQXF*PIo757N3U|*tmZUQm;3g8Vc6_&0ncNKZR`pFYKbWS-{)1H;dZ?fU zlNDLU0rXaE_ydQ2;gmDkdvnXJoiN__}jo&;>Gz<@K9REng zNqZi$icoz&Jf!_%;=>@7OPt`8+j#0nu*k()rC>d%oC`S1OM7{lI6ONw(@1f6i5xOMoX3o=s> zp~e6kW4N0bsh37t8D>KWMjqEGrmz|lT7}|g$e@X{q!(!H!FF|@+Wy4M zkbHz1n}stU^wlk-QzK(RTN`=-ufhKWCd^)qCoV5n=>YrXLFKu9-t6?XRw+3K3RFuJ z!0;PlfFFzvf{U!%o??~h|$Qv+-bitWI_`v#Dv0^Ut1 zv=ERBJc5ZfIxR)OIhL27AT}x5AODKwVT__vUljQdt2;%W$ZJBVE!vz!_p*BLfNJKqviK= z%93te2c%F9tln%A>cL>K-EZ`v9jY~D`P2c7vmdc`eqAN3Eo#s6vX_WMBWveW4p4TJ z>L~u19p>LJEZ*dL+?=*sf4ko`mIQtgWD?Mo34S9*K+-`OTI$Gu?H?1JVEN~9tK+~8 z=htcYMangJu;My(5f@JejG!V=ymnz>UF%j_MRgQK$5w#|19MybQ3EF038omBjkkQP z3IyAx=OT4Doap41iRv(QS^R0_?yZ|fZu;Ft^hAA(T>Fg>@ci?JuNXSn(vBVI=rm@x z*CtmcNIPo+8+`}o;USD-&VH%`4Hx(#W`zaa7J=$#evGBG{3(=~IF&r%e5VekdwLJb z=q2df$45(+k2AFHat}D;5#t7Mc}l=2%u0D+?@@a)&i3Jl!mcJ*f=9G+#0U7%otJUV zQp9UOHUu{8m5)&IW{$Y0=`L~+FW$RQ_KqnQDlXw^Kd=l<&dnn*=Cwb1JoD=pQ>bPt zH7lG9>QcYy>47tp%dA+AsMfCr5^UxBV*M+l!@MMu#s8Pt>MBw=Q>R*W0#DAE3O)v^ z&d;>#yxpN(;L^!}vc3{X=X<|=!{&*eLBkm~ilSphO^5|Wl-d~^zXNF}8gUU^r7cd4 z!o+H%T1lu$fJd#7tuZdsfDvAB)(_|7+>eFD1PrfaMrT+n4G6~4afiTcMJgjsrSnrZ zlMj77zP-6dqS`|zN0uEbnVoF^cp(Vz&=bYU`CPeltAy*bzYdGb&8e9SQw@Kq8UYD{ zs25K@)N3G)_Y=ior5L7-)$Tq_eVJGarr7aKX^ck$y(qq6NB2QzPT+i^PGW6&_~<%u zi(*>4v7M~UZ1|5(gpmxgo5-@V>jU#7D*6x9wxDZc&vr_&O7f*tbI{EQ@8uqOwJJ-4 z(you>`j!)CoN9C>|L>xd>uG(}yG4K)olP@{6%04Zy!s$3aez`e>-4WwL1e*Cc}OF@ z3!r&ATS?ZJ%Jn94hVJPGwR^_@PmiovfhH~XnL$(;)|!Av%50a3$$wg*(EQR}K3Mcj zQCHi&>|B_Gt|^fpYu6uolR8K|^|qCZJyGi#A!I64(o3pcf!2M3k6}*Nu4*pmWfL$O zW)?GsZbPg_J#xII8nCfXXt-Q0mv|js-C;`pO=nvY3{(B-guA7&Ngk3_cu#GpB%M1q z8z=!}<`qQE9TY_%?#eg#6$E{~uNv6W)P7MDc)Eyl9V~%Q{*|SX%9SU`OMyawzFlF%Ip@xAxC_|xp)XT%H|Trhl*rj`yG*$ zaMP8Ys1E2>C?(nqUJb{8Q>yy&nOTj0MXr)@1{FOf6EFz`o5HQJqj0Wvz1VJ{;5Q@W zCy$xw1c?)IJkRc_dMm*p^|K$WC5io65QjAv$|@76J=Jb-0E~#%?N86ZZA51{C$p~z z^=P=3wCUvpXn}A)-89aiY$Bo4p24)&Xhhw3c?dt=6PL<{EmRwZVTcV@n|X;yH1c6P z)BEpYs#(EfHodgc)x~ZrI^a|DdAtuz0Aye^U9W3TJO$@b_l`*Bnzg0>5^+*r5~UVe zG6BV{Pd-84>6-HvOv-q2D{WDRH~9*Ey^ltd#gi*92!?_hqr;L~?Na#QPO7)=C$QpE zx5OCTZ{FggYl;X<)_%2E55uUMr!$jCW3s&Ep_5ckwi7gBw>z4S;!M0owcoH-ILXQ0 zt(23?Z50>;55n+PA5_VWhUNEVo?FSAv`gO6Iy^ExrjqEH(tJ((&|ja;#y8%yG5Oe~ z1G@l6)Mi8JX|P8mWi=Coq7-tDr$6k&6VRa}X_fm{~=NIwz zA9rEBeYylY>NWQ0>e^8rc^0(P2}kTc%-$l#?BXr-H@d={5w3^Mu_MSM`$XC&kkies zugW!kj)Qi2B;+1qpdDfI7VDa6o;Fc);|4IvHHv5K0Szp--evSEZ3!-bq_lXu*7NK5 zh92jeQYU%oKd2RT9o~qHI#FN!ad*dz^R+Bw`|thnZQ9=VO1d2ezS8CX>vn=s6P;?m z+Lt*mccGC-W&UD{t*&f&`6%DelmMO;hAjG7WX_9V)X{jzkE}3ziuElSaM?jZ+03Zi zWcoCPf9aV}>54BKMTMOfVfZ@x-E1;+TuJ7qP|?*u0lHH}TFk*$|LC2J;idfz*OfN1 zt2Kd=hdkdVm;AFKz1IO}K11gM4kAA#JnDWeDxDmn87n+A&;@@YX?mpgS5iI9oBVpu zrMvnx6fzcKeP~R{7kACX@Bi`2koBpj{Tu6=ZsQF(kqY714y zXCOL;Np)ONSdia*ENEbqz5CQaAKM7e*P3<+eiVF~ewSXz7szo?gAHjY1C$tuoj@N{ zUbp`_b=z&SMt?OL$3htpeiLm|(Am9pTvvmrOb+5t&Ed2n`h3TUv}UHAz=1)lGt#>E zaKCc@HKpTAxLNe$qFUzob3a1vrIQlYSRbR`yJLOfz}$Ah%kx+Ibot1+%Jk{*_#|O1 zV@nIv^cyOq-MUPS<+QYg{ahU96)_bJ$0WQtgeR2Ov!L^@NyzF`qb6@POh9e2Rf_)M zVD=b`Xf_m)V^OX)^yOjQFty!Za%wO-3x+7 zP_rVx8O%0^>;y6?A!2yGrt*L*z*}2&aYU{5#I-<*gxBj#oYU32^G%byRI50R8pUhdpL{(h2ngQo2$=Un zXm5&U-{)ICMQ8b%-oeDa@tN09B6ircBM-0*#&cGh9~5W z_k?afjrn71&*6}qu9wCJdydyllw8}0{o8%$I2tW>D|2T3|7(q(M$aD4w3ij$}i&sGt+bSWf zltgcM|4g6)f%uo(_p{^l_{OdETKn;(^`LGNW*c!@B$O2Sp04LB_+^zpKh163Wzu~H ztqD=rcXtv+WXNxX7~8x}JfZ0B__=g3nKC3=qIVrwCA)9DUJdfUjDPZeY;u+n zAa0xTr6pgBmK@Rau5v9tU)QcKQf9$blkNe>T3phK)%EW^b)f zd3V4Qn*|Kx{BmN&`n?%d6pldM0fOd8(&>PjWm|g-Mc-; z>a5};0#Kmix?u;GJVw?E33c5mybAh#gXPX>B(Y?5x^9yqIv#F28V%t(-Gh4PO~@_2 zFs2a*aJ`{ICrx%uX<Y`ms3?v+D%A<0JWh}4g%zOypjm%w3& z`gUb24kc!bTx)VKiq-5>|JKU;vDPSR!||w|lQqAHd_%Y@U4(aHdZ1hi(Tjlb zb~QSwgM#nYm|qG@774<4Y59o}ITc$)psvV97^@eqOZjmr!RW>92YNC7n4;!oPn?y4 zNO<)~NIiL~vh<4k7-#1s-y{@aZ_jr>FTfx^jDj|M`Y@h=yjl(wvf+JTRE%170EvMI z^87Rw?6f_-J*W8=4pMO!)akr_gVNdS@|@_GsB3c)jE96If!u{%;2=&dPr!`xq%#wv zt5M=-Q&zijpQNXbp*#>r)l>Z9YJQd ztMdKOQ9FTO=3*VkJroh3k&+18bI(If>G7KFK)({cPq&T5%$Uf2!O6o`l$ep@7unbl zfM;;jbS<76LJW~z%;CBk{6>?2@nJW@#@jzVR#_ii9~ z^Cwx+J*L#g!NThj#ZGyR|5rkv6(42J#RE--R%XF)VM9h-7iJx9Dppt63S3OLBi(k* zqCGGd0ecn)deU3A5EgAjR*_+l!udiZQc3ecnjdg1=jwmw!9bMmtKCpsqC(C4sDA+_IFMxupbJB~+tH+}Z+Y8Hm0l=4K%>dQ?%qA??U-sVHU8!mu*7 z=d{|*=2z?{tSy3<``0uN5DFF+Jl2e8Z{5w4f`y9F>SW}k?JZT*Pg0aUhtKqJ_#Cm_ zr=X1_B|mKuQXSmd;D8{Z)8=}5)){8|iaIbjXl4m(1TWnHsn%Prt+^JrnU;W5@v(hB z4%9IM~^8UlDU1;lFbz_+-J+}SfIdwE9U49 z$EnWhdnu4TZ69QO)!Sn__>c94x6e=Bdhef`#R;8b@Hs<*L-M5|gybzS!#uS~&(_4K zU|HijajrYdh zr^^*Hil!dQg9s!h_8jeoM3u`Xap zhDvl!+Oj>4=)NZiq|X)A|EJP5^SKycyKN*o_%B6h>d~es^e?YTN_`LK^QxV@>SRyq zu*I!1?_Ft+yOBz;E8K@!a=mZQy00#{Xa4A#;N1o0_VK)W zu~6eJ`d#O09MGNPyNq@wM)$0beZDm5mJp}Z^K18p&^CMfTbO<6s;7ZU{+o1fe?3bM zRczap*v~FzovK0V411e_HlKalbC%EJdBS4!U3A0Xm@vmZhusl7dW3A-;$Len9a!H# zN~)g?KLTV#YyuVV`uYE55A}%5Kb=bRZz-VV_Lou%94BK4jO}aSe!mff<5W5^(|xo{ zfzU}7JGSs>a)wjhMZbdCZXW)U3(7ekA!|6=blYGLxB$5umn;mtwsoJO4CrK z-3cT#BzrMb{8+`g{ipB3BC;pt<%`8d^5+kLXavdaeIIkZGG9ql}IbZiv2;_5YY>Aw12!r9~ zL{>`9tS8Z)@NKQ5#zs#f(7I*B8w>3>jm!i=IYTdq^vm@D~Hm4YeKtdYqOCU|^j4|8KXOEgnwYTHPz zgWQ*%okSPI+^eIH@`jQ26#;KPqJJyDI?#Z=o ze~pO1P4)5aGf-`FFb^Q8R*FOiUQOYw|Kj5`@J;6C#4!bi zd^c@BkvgtBui05PkS-F~(<-ab$yKGwT#%+nOOOj6hzgMyJ%Trz$rps7UoerH#a{md zX`FLo$kh4A&&u6>v44P+eZfxU3;xxi#&6nab%rJygT$qCb050g!~UU`93IQ2-9B?N zE*nbruf&}F)(u+^l^EE|!{Y%zdF!mf{W}R;&4pA4t|>zy7U9L?%2}?Iz9CV6H!u_d z;lX^oS8^bWql}VWJKAP$F)D4iKqVXAR z2(w*18;dGi<2G(FmP4Vs?Z&M1XdrWR4%;>cWp}7x&tClI7D#V5W5wWg5DQ*B2KP^j zUTJUVYGuK&REvuP2cPjFD;kFm*H4KuPD3^?zAnUyK5sj#>LZP$M$VqfWl zg7}9m(cB`8@jcwvaPj+YMBn#C9_DT1EA&(gmSH0d=H-b-aJsd`qoiQ0HVzF2euX8G z^}{l3BLR}5MbL<}$)r<@PQk-<@6~P^3OdnmL@U4?PfJ14bz99_pKafz!CRk5q&P>| z0L%9x)Houm|LtBF0XYYC^AZ{c11*oGN!qSa>rY@Nofe2fLHiNSik&~3?p0?I={9~Y z%?Vp|!Y*utR~qwwCMkZ51$x8f^}Rorv=FA45T|5Rin()b(q-@c+M^BP5#mv?Y7ETc z@V(fsTio=1&eYQRRWrB`k}_5H0(VCJG(R2(ss)=^7mn!@e~H`rb0jN{P(=ls4C+w} zH1qHsXlDC*r1#G41pPx{C0{i|4hrA>9TVBC_+*Py>lbaU;5J!|3P0YJIj~L z-v7@Eqsox8ky?AhMb`DIrgKA``Bl_?jY0fLOLCfbo45I}@lkSStZ?G))mxhUBSD8V z{X-=ro6`y> z8$a3Upis3clcoxopB%M{icc)7RLHIzhCvZjJkl zFaT{hz~uA6HEoYR`{cIla%0KI%;q9~$?%5z9`*@`C0;6RS`R+fq{FLpR`@gR6Bd;bvM2~NWLhNO~cdp37c8b#e zoiK?0D+p#-_Ml9f_o+9H#oTBksejEzd0+AQu1;xp{sBeV7(eC$j)hi{+Ohm5R3&Pw z2r78pEI8g$1SVy~>GTu10*Odk``zPhU=y$a>UGptr{q}=M4kk z;7FJLO*k=JYsOC@0Uv5fJBCV}hhP}G3)cB5hFP*^|ESf{-|9&E?uH6qy6Ij%(BQh zK}w6I_Q~8-4=+ueU+Gw$&yrUF)u@p<;p6xv7K2q2!+Jhs#Y@;(l0EPTde%ZvtmR0t z;(AP3N?L$85x~O=Z&72GO-trdM$cN4`kE?X4+C#a z90XLJsOS58E;UI=PQ^5^M2ThV&bLB-VrH{eIXDxnh@6h>{O*5l!QnB*ksdB~Bg6OQ zyPMDpkGT=#MDr+Aqe=`b(yU z?hBRQ%meHW$8V#Tl;d6qOzvtVm&!*QCpHa7tg3bDo|sKrRnHO!7;g0@WwU($4Snr1 z#)OyGUyE2DmcG=8Q>1pc9aP0j!_pS=*86Z=rl=fR3Y_FMOT;O;%vs0bj`#Uhg=$hv z|D#3o#M%)^8s9Rgbh(!hOwRo)M}+xh(PZazKI)t++3Z)iGN2 zKv0ImPOR!;?({@JEayTo9?CP43Lh9L=+8lRdSb;fH_cI;^0Z5)Pp_6(Y63%(<>4I@ zJ#=4Hj*E>)lBQ?_S8E|IDOgqR+{cERVw~aP+JBL^C$ zsAzMds>(BSO5^$=-aWFhmUoaj(+;+$mE~hm1BKnl9m2F5zH9Vl358TB}7w-|bRiTVz;~VDl{j;qqaHQ?Iz1W!w=r50T zrCLkfdODc)dF5A`LOnQ4U%OiPMzv`_j}Rr=N+kbG2Fu#>eE%M~b20~BQ*nEP)xG8Cq5s>^#SIUAkZUYV zV;+4StW3;8b^fqyOyuVFb@j*!_ZZ;jT2iFXWh0YM;L47W`G?3!{esXN0i$l_l0V1} zlXhmKvg4Tmktl+Q!($&^X>!ry)}|lPl0GIl+wc&zCE3k@yHw1RGXj5Xt^C)Uu_6d7dH zI$oUC#s3E|XS!n9S$J$d&&{<@*bx4csVfnY3?ROGz)&t;32) z6;XHXIl)QD2g7v_32tyA;@nVOPi%=6``i9@z|-&ycLVK z+ozs>mxj}`Y9^LA7Vo!M)A&(~p?skgKug*=SO>o%w3wAMN8B429aM!9uetng+OE&2 zm707s0y86gQlC3fS^O?0;IC2f&yA+=&;kvhjxLq9nEKP?a-`x);f-Ln-K6lT&%gA5 zcCZ~Vame-Y2{zQkBjqQpC^9j%VoIVpBy*y{Y(Q924QK^ZDcE$V8S(`Zy#8eSb?3!9 zvyTa(V#h6_emOK;!gfVPNd~0n7gQqP2p*qLmVT)fTIei0@~sbemZjUFxCbMrgob7f)x zlugJDYXf1Y9p!fC9qhSDA!YXEL$|%o*mfv+!IGg zVDXJteSDJ)Bav2yd5@jk$zkrpbODs!`JLn6I1(?zG6IwtXHW$PoYg{{uMusC)r{ps zsN2m(+t9QWlqf-vuwzRf6ejn!JKP5If$A7NXO_KvKao4%f=Ftl(O^s+< zi%YkgN8rM%{c> z?8q0_m=k*o+Im(U@Iz9_h=kH~J1#oUV~-xi*Vr8{P<`v@Q$kIeDF#vm#j!|ZN||nG z``xSQcUSnBwl7hYEUYUQ_Q<|yAb$t5C39TP6l4~^hzQni2*z@5FkSLeHJZDl)L)$t;I2;-q8&UlUUc{*=q^+EgPJix8 zERW#LLmq9G^LP=cb+v^ ztjgT`77ntK?iGJ5#1m$Eh?%cxJ?+-}o2;*)@nW^8Zeh4oxT&D?rlEVKE@y(Yp-FS>*>QS>0 zxnkO6HKJqDKXb)}2Ay^_#d)3zB&}8OaD>;^Da`_J3chin5AB}zM_)#y;-L7oJBKuM z7fAhZ#}5fztzgMSY*g`G{eLJIWs5P)+a`d0aOmoa*A!2Ix#Ap#6Hzm)y7`jP$Y5%+g( z9UTsVduBGo6QU7;$a_$OYd|^t^YTg1C_rz`^!(5up+DqhVa$o6U*0q-0hf3$CEuXKa;!gj|A z=rJH&K?t|>A+Y^erU0SlR2KF|+Vt502|$ki^{4uY>YN5@@zaCHEwk*s9ufE@RM7%B zb?@n3=J%7Q{Q;Yf4&nIHh(A?Lzf@8Y=0A$JV@L59K>p5<0}KfWsEysuKAoN3_!CzH zG207ci2-ErZ3!9H_-9rLWNI9VU5r*Cr+@f@PAM+fKvwlPHK7ty^yfL0y=>=@?xUwk5%Y7oaj zK_@+ox@-KJuY11lVg_&wpo&1@K_BnG09sxAd%nXp!JsX@KX!Swknda|-7C|*nv_I+ z;$w9F_mEJ4{NyNO*=HXSwKM{LWVg*ogz~MsC}4MXf8x?EQTm=8b^t7iBhFU6AAo`Z zxnFv{e5H8_{6?>BmH0vW4gp07eYt*?(XXNewV`j>=xRbgV!t(y<;$>9q?x&bK_bC7 zltEd)tKy2Ck2SF4v-Gr?q)+x9vP4+8auW{79FlsW)P!*-Nnc#!XsXB?@W-bZblhyZ zEBoQi!&a@iA30mYyct_o#F?2qT2H-qQmmZWcnEP*d#2E9p~>igeLb^W*Qzb5)MaOg zia0q?__RBdwktX#PeKDqSDbp2pv#eS(W4zjc)j&cem{UMTa-VDS(xxbB6Ic--*Yyv z;l)OgkJ4{zF_sPRk=<>@9!@aid<|r z8tVwENIwUUEKy&#N0x6by9<-!z&ut*hOF6JJ6_v(vyaZ4^j}-zve}gMd}Q0aWA><@ zh1-7RK_JEyE7zCZ`Sn+UcQFLCtz`XqrlIj}om!vdcD;{1rdU{-f4%Ttlji?A61Tfl zq}O6g*UXv7pQ#5iY0p%uSF5t0t3Ttk@zlt+b&0q)B_(}Pg@maT2>3i30qcv$6|;J&v^{UQS{BK_N=7Lp;VNB?|{9g9tIc{~+5S?E~E zA>*fPHHNPM-Z`lpyMBHeX#sAVzB!?*LFAqR%~q4IoDj#zN$p_A7FJ zMc;4s*Qfbzy&?zsOB8YP`HhBGQxe4C@uInIQsHXlNZ?EVV3G9O^h$XyBzMPfzhNh#v&bGl5ymLHB>Q1rdxGpk~ zNjs1imE_O)^DT6dV2 zBE@(gNv?#E8E=;@iq9Q5qb)gzX)5S+zd)07zfCSM^wRR~I;Es4Rwtm!v3_rUJ^48& z55L7xa$|1`YWLn#$|D%CKG?Zln}gz%R`K>6<+SFI^7W}ZQ zubXvds(!Yiim$~Q1a+7v{v+OHKJghD-SzEW=D}F*!6~~IXh|1j2w){@{@rwb^RM9+ zO=^?Zc+&YAsuTC4YV_7qX;H5ItH|W)>Z53`db6*^g=I5wq#^mEMsBAkoMW+6UMm1y zDK?cXOc>ZavoweZw?;pUYK!}2O3rk`kP6aKJ{ zZLVV@ZyU3GNk*rB%xsstdhZ5pb*!gUGJf6Tt2}dn+E{Y>%OhIi%$o{Pn$p<7HN=Ao zhb-Wtqi_q7?PQv)nELgdGr+w^$_Tvz%xXF+8r9O3EmV4u&O{n)En|DW69q*UU351G~}fr@?{- zN8rkViI6fCXJKRU{a0`vptQA1))!`dOaYX<)(gK@>q$c z?ULpYY9nniZyv914z~L*=uX9WS3N`n`3tVph2BjM^uJdC*&6anR;e=La4^)EX16!3 zxKEAuv@gW9>0r(q2YG8H%EjC_g{)G-2bf$W9>;1v)YDsHK`Mx3aS&A%5C}C8)mDk=ZzzFZt zd6I&*n>9Jb&c5%@!XmCoJV?IUN9`qxzH(hE~1wz%TRMOw7mScZ~`dwOavjz&QKXF%XVtE z75MB}-QcD{2WE*t5JPtCGU>uS=5;Z?YAHgh+iZSFjZwK0YP58roLY676aXTOu~Xq~ z)9tmr9QnV>_oDb$8WAvaYBIKTB-C~^&0+Sc@2`m&^~diZ514&(meHdlhm2g^W6Ero zuGQM@?2OaPQHkpmlf?^nDUjKf&Yva%$LwCF&$%H2T++ zQ(%hqG+Px{8C$=>*yEw0~B!02Hen2 zdN$l0)&YQdQjaDBp%no26l$*ix12A?OUAqpm*)YDpITx=EsC$8?q2@zBH;(4wZ$zD7#vi>zp(Qs6#CO#!J4We1d-X$E5E7{Qv3+?bb{OK|WnxMrN4kWTC!no97u zUb2(6>6cK82zf08($ZR7eMr!xKK2C(MXUQ0%i5BjvRp1Bbdi7maFekV`F&a{e0W&F zd;)c!+DrJ5L&mjSh;%~^i8Od>O%gb)(Rm8%G)SF+20F|qZ(E?6Z%`37+Mif-pfHXn z2c-76URNkMXt`5zV90DpB&Lch`HVs-%qy&5GP>+Ax@@&fYKeqe!HPiiE()>0?b4;! zLz?Rz3>gvl`$V`lvr)p3?>)4Vm|4=Cki#h|D8(KjzXS!2r^6FRfy@F%Y<61ds&_J` zWLq<}96U!xMRS2w(h@*0G)T)jC z9nKf`&R9mVo-i>~)Ox*-NrEufiseS)elsKQT2G~s(tHz%X1$ZvqpPYVr@5eUF=#_*8kAWgUeZCcgu$se-6Qf_UgXn zz@{6kUy_1{ShR;~)jPu(o~Dcq5<{~-BcpXn4!bL};G*7B;RP$hDS(N+eW3>fg~pfe zU{m{x`&n4Ph6i1?Ry`kiJU1ycMTdP(J;l{zSW_W{Z#Ik4263p*x-{zY96}oe7bjA+ zgmo~-jVoOjwmmH*E&$6GOmo^Le5)wfuEF_6#FM#DxW>QLe{Q$LR9V`S}`y?7a{sEdR)bT`;{`ero1JF4@$@ge^7o?BYicrHYLf(KZ_$ldaVIW9`6twUb!Y6_sud8% z8c2?FuE`C91#4ODoU=BwV#m;+2{&I)9zD9p zy@WiRHVWWFr*{c@g?Ai$#84FNrrM_AKakxT)`VR$U{z`A@-VWso(+q+xcQB!nsdlZ zou);;e5#l!rooG3={xtpuKv?yUTU^2kyZf*3)!Vnittl&I+gr$o82qI=X-cbuE_~C zd$UyN-y*D55re^iq!saYj(-)XhK-PP852C~dQO*3@i#Kwkn`IX31h z;+wI1NX|d{+kNi8<5pa*6Pu|{X zS3~YF+c|dCFcovn;Ngg{`Kb`c$?XG zIJJ#U{P3C4LMOY^(UY8!hc@ww8pTc#SBL1*o<VE^|`B=?yAz00G$&Idc+qQD~ZSb zW}sNCS;dG+p?2vtOTu|GWa3b{q-hqI{5+b*i{H4KJ$Bk65C?DeZIc&koUL5apfn~7 ze{=pQLrvI}509bMSQ7Uw8Lk7S_l56_l>{fbzO?IWLKl&6Zts!jKHJ&LQRY=vI}}ODqtqJH z{rs~(XmntEexC&}oDTFVd1_KAtR5SqzD7VO6UigKtcaQ!r#b=yCEO9EE824?F=z!) z;;uN_7}t^^rn=bfTgzzcYaf{sQ+#p9sTZ%z>Oj*SDg^B^o7tc?K-2qz777#V7{(P+ z_9cSd19H=lNB^T1t#qWgARC=ui_CAOtz~dTAu_zC@uI;k2UhA*{+9V}H_x8}iY%Gh*XML7k_@J+fXZ8pFZY#!T{%v!I)a|VOzHXA{h{6_i^-l{ zi$y`SR{)zmvtL>rbRB%LAr>75GpkMbSw`HA z?DMW3-FIj=4&l5bgkI+Je~RpOhTe5}%Ry**t(%)X>fAoqlivJzd!CT^I~kgA<7-<= zR|_k&`HGCjd36O&75?oP|3zYs9*m*+E>=F=GxSL3?%C_wualL%9H*>)GQ9VHU=lTN zN17$m<}*&d!rzWp_83S;R6^7_f?rhU91N>|mf}X76=06=x??d-jN+nug!M78T=2W_ z9<;Jn258rp6CK=3?r2EqhLmPVF~KaR!D0U5g#zlv>`L12AF;mg7M~K4hkc=u z%KnS<%-ZN^{vF>X?bu;jFG=?7McfIN`&(U8RbDI!U(f@&E}bB!%fQairPH_W z3zM%D$rP`82)@2l%F73$KOZD5q3AN${D6WFte`?XbfzY7aTkVv5h(ULel`{f!3vcC z6?ON)I&yE3#!GemsgU&aq(Z`V3=1ue>mj_QJe6MLdm%q!p@rb!G+*ux(~M>Y3(DR6 zi}(F9Z#Hx029-s=!!>}2_J(jLe0I$wyBEBDu>ra$efxEd)-vB}$#}Eo(NKkJ@f^h4 zd902zxqxE@q%7>va9gShx09+;l}$5Cx<qT7J{5-3&>-fcgla$mRH~STyAD2%`2D zy}g48dC%b&}=gQR$*-d{RD5L-Ge`?Uryfoxcq~7kYlz`B=n<$p8 z#Dw*sUT{s+x_KISGaDJbiD%Gg-CsFn2tQ#3;L`1LK98Sm@ukVedv|(ZeAw?)+$EkJ zxqi`{GVUxnb1xIVeGYG1$78sHF6z z{nVtR%85~CL5Ae#+`LcOyv-}40072cx&w!-xdT@XvrmD2+=^ZILEdrC)E-q%%*N-M zsGaJ#_tJh@H5R>b9tZKUt)H4ni!z1W0-x2u$+yHf%<1;JZ6$X--xRuW*=0GYpy9P2 zvIP4Xa-!R*R4*v|yC7QUMFxGIsw76@XRMW|zY=EK3bmqxItR}}szo>_wcY?HUM-7tu!5A-4NW+n?r16y*2*8VYmLUR?Ub2%19X5q1{K>=@)Ij3#&Sja;Qx@_1i z(u=q`M6Z}S`|7=*hL2nFV6S$2%r9Q9w7VLsOpJq1qESh`BU>E4g?#ZhgWY!HftW&# z%GC>p*v7u#N;+@Wj{!15wyPG*8_ zYmm|lhOMXzOYpt|HD$5(tQ>3!YP$IWKbG~8x!rJommcNi@U$19wgOqlgA(i|1Gmy` z;L^N6zn$Mn%R*CG)Lkei>Svr>NQ-&Pzq`6QSGa?uraq?k%O@9>CxxLJiDi&LHFO z>xoXhroro0m|f8W1<4U|&Pax2FZ*gx+m=#yT>8D|ia;{6O)Q8%;sBNFtl1*0aDPc~ir=k?TZH0$hp@hMb<~_>QpDG?Inf z7G5r5;c!vYi8{r3X>xtQFdT~DJFKP#AoTtZ_Xm;po-4S-Q~QH)+^!Pb65%eor4y#m?4I^36>Qrm(GphY zNa*b!{F2t-?EeI8+5Z!;Wv2h%yp^nMjQ{KOe*jxn4yON4U|SOqBrd@w{ht3ZN z2S#w~^GG1fGm8@jO5Wb}|JGIl4(t^GxW|DHf#uCW%KHoS+hD*r(4*V356$4&@1F40 z0+?8$0mO!dA$;CC`9(2dz}15Z0A3IT@vOb~6tav#=0P`x_#y86gSFH)vHWde4)*RI z9u5In+wA&wToPz5eqW|&F9@xCKH6zC1IQrY zz&E(E2$u9q*Sv$c7Qi9EH<`dr$;$v4w0dXwbsP8qT>q2S+C6;z7p*0j`$uanEz=sI zAueG3Hvp{&W%c|><)e}JgZ04u@>qNQ2*}vhym`lfLF|Flw}E}+;D7*(n*j4ZL4P%7 zr?KGd1={R81hRap$DS*vzA32qt&j9(X7tDhU=LTl9uU~qK7Q7^+kdvI{-B&dK7UWv z1@l{5`O@eg{`*412e)+uCLjL>Y<1HA+^_p10sz|B*boW;0<56|yfn0&ekkkAZi0Ss zjXh3!_xktNLQjF}dG>;=;Tu5r{0`nZ1H1bHLbP$M?Y{bg|5)qa-2qq;tU&mouE7Bf zzmVn^PBN~j}Pv}v}7SPtpD}2tcZN;zbdoRP6YVt4o_^&5HUT5OsE&b!|+b<#* zhfr46FVI%v3a&jJfb&{6Ox`c7H`vb~4fV9dY2VQ##5_;TG5+hUA70@wY=i^QmiYjJ zs_S37<5=C_)R8O#`8u>I*oVtPpnsS6D1l|NRT4uShL8CY0TE;vcNO(S;-)ePI7ug! zu3Q~@RChx6@k)(cj_`@SQha}*UJ|-TcA(C*0 z5(*G+P#B4lFRa5@$FpEH&<8zWdZ)k?a3V1wxb)w+*x(E@q+G1y<41+h02;w*>>zVF zI<>~}H^KY~X+pR%KgZmO7rt_!*yHFyy&)k@Rj#{3uBIBBjb&>UE_u$TCVNeb9Rv_ zrWdBZjYS~jkEu_ss#oaF2C~~H$jA{rBzs!n9s1-wEcB#9z=^mUa;UqqU2cAFHEPIp#!Je76JCDi_m!0;kHw-D&PexLD$mV(?IRl4N{p(y)ma(cGpMk))|Q zGr7h?pno>N5k-H@bd;QhpxjCUu3C3_5vK`xl1UNZU2{Ki!pz5J%bnfyfP53mf{*Lm z=na+`YN@sgsd%c&BQb+64&_KimCi2Xl%EkSUsyf+I&QRgi8YWG6fGzft_!gzk5-M7 z-z3JcMKwsB*7%feFB%_%VLLq39ICy)M3zhI zvyGqKeZzz8*_kw)_RhHg200-pRPN1hd)*jE>D}_<68K}7`@MMTQmZ(gXiUr~N`c}; zBj96PwPy^QE-+Ga>DJTMtOz9bO+${Aebb_4Ihq#FpGr3^DEr0jSuE~;C1Ncyhbm>~ z1?1bBru4U>{_<6D87y}BOIW-}+cid8uJjBU1C9ku^?MFvlpyLkMD=uzM<&7%;!}{E z@Lp>E#n964;A9dgP|~4t6Vfg8%*oTR6*;?EGpWZkl0EK=$eelrYDXnp(}yVCLXXsB z9^#>4D^71D8rko5YnuVQ%|kr&9U{3K*qj}uhg$ytw+Lr#xP8<+YB%1mt5gq(7&#~m zH$N&?9PuYvtu4UU!jpy=VcV}?qE5Uc2alXfOQlc(0_WgI|h>&Zsng~UScsOVvp zy0(Sxr&G==+AdR_dRF2tg&FUJ0qp^@mja>X%DOJoi(^Eub%DBxcn8!*y~?^!k;Wr) zyjdM#?dGhe$$b(~=>1FcWkbz@tv6%Yh4Wz2@$QaE>YQ66Kj}iapr_~Pi5}b%Hz446 zdPQR~sNxkeaRVREi&Zc6M_EiJH=>H7f+^AU*)$ogUCt7Cl;pfsIv&MPvNy)78Io~@ zK58XOM&sU-2XQ;x*e8vWrHb6D>!LnoVSU7_xh;~1@>DIm={R{qEm>4Uu5?pF8g(2o zg0`~f_)W`hKhpThsQK5aJtM_ti)%^cr&cHoDx&_0NCPz$O7iL2Fw4M)WGSfaDD=|S zPNG6ux)UlSQ!60S&%8nGVq8T0tTTEiMluYdFe`$~kV#w-l~$s@{}|oth=VjSso)vC zx;E68;4P@rAtHM5`^APhs;7zLkh1aU`952K*E01G(XKN$mdjt%Lh0MldDhm}(RRY0 zVrto6MU4xCi+1xF25VhLfUw?{3BQH8cj^i^pGFEhr4On4&zt`9drTs;7L0^(F$HZ6 z&y-7|om_?dQ`wPfZe?+Go5b;=O7_FZ`j-=HS-6(2qG?@kWpN=%IVMUckmWHgk+w&k z9H?qx^efBbM<-Z<%hout$_fZCZVjX(G!Uy&9J$Aw;vRH%=L^hvc#vWKj}lSxKT#Ex ziBG3`0FjRS8mdOfH>qW?$`y1HTxpIPr^w<;1s$8M!C|8_@M_XROJRs^`<@hqgd&Qh zJ`3#`)w&vRH2$CPvVY>N3$^5Erzy#>I)U-gg=Q4Nd5?5Xi%`;2u4cSSk25BX3y-=2 zM_kBLS%aH}a1ZP65<^K1)In(-h`AvWOGtEClnamCh+DEypFi2H*8agB-^F}WoVGqF z;-x0sQ1cteAl{pc2VeJo@xZZ17e#8Ztp4uBXV^nM*@>zLr2|L`$!H1wO5<))9on4P z9!)7bBkM1qWWe%}HD#cO4W$l2RVY zOOW2+Isiq^*p*{;towKDtiyX`2`voSx2{${kmB+8|ec|*|x z?NL|=Ez)5qaWwLd@;4s!$W6M5?u!167=B9nwlO`S=fC25U^bVnN_2(wBvG$3!cr`< zd~x!$1AF$@k7t{!O%cu`zAkLyTv#*!dB;B8u47n;2ph(1qGKb0`v8aJ!U^Wg9Cu-K zi-FR&KiF9ocljbhf)7h?y7YKXPQxsE<+F`!b2a`a*_mqXMbI{#D2g*J&tJKATYV-3 zvM`fM)f?`5L=2D-x_9Y4t8X}5c_qV@xkmMuJF-}NNs2s{rUE~lSG>8 zub0s8)G$}6SSq>3qrQD2-r&l$nwXEw*geLyc;I>Q#KBG0K?U?huZCRJG+vAJ4Ra_+IUsAHn^(wN zBLJySfiH~nvG2}6!Zzry?11HHrcDUw2RNL{*iLj#&_EaE-O|X`%-r81k`nz8ipNVG zC0}c#nH>wrXyajnzV}!lkaGQ}b0MUq0uoo5pn5__(PPHhvN6TmA565}gt2gr!NEN) z=RP=02=Tgb?u=c0O^dlKFX0!LX1n;5Ye}CchbR^9xwh$QFUgO66EBDg9K*tfESz@{ zeBt%}sBLc3{LUr8%8AZ};fZG|QDRo^< z&R9c)9}){G5uUEAcLi{`(Bkwu7w9LbruvzQuf_q|!7DutRbd__nTAy@FCv+m_|-S! z60G)4$0HrFQ5s*Z7A~R9#RXy6@WIQG6bgFK8oCo=YYbjZxy-aw<8aIq4_Difb9l26 zNmEum0_v#wCMBn;1H~YuG2ESOo|@NU?0>qCr#4L8}Q3`l% zx5IG^B&9#fhLpT|_GiFDN^6($%FnLhD;Tn7==?wwNws4_m=R*F`>;RvM!ENr z?zgiYhaXTGrsbO*;ga}ZAt`E?=ERO(saU1MN*RElA6ZNmN-ag%EtFzn8S(YxVjtyb zW5+yd%!c>!djS%P6Y{hOxs|q(X!-DafiON!i%AHEDM%PyID)03mIMh!Alm(w7iUpt zHYZ61`kU`cCESF#aA`7@L5q?U%|;pt>;A7Mf~OTyUW_vC!y?%Qw*$WQPhT{6YPv@_ z%3HU&K=_=z@|Y)MG0~e!nv?3TN!8S*#%Uly(uc5acf!5MInFckC=YC>lB7z+?T?eT zZ47&v+^xp$X_C*ui&i{ZLAMP^m@)B1qxAXG`?CwB@Q4K{o3Ul8?*@pL+1UawFCqSv zn2-SjB4QP>hCB}%ZF9HufY0M~H+ym?H6d%r!JBy4(B+T%sXHr42Mbl7JCsHZUXpCk zBx1D{`_67jMlH(a&HCh)H?|NZmIluD;9hk0$L*Witk`p|vMy)u3>;d;Q$#~Y#S&bu zna0t8rqi(@->ywYIqCg~CY%mZ)#fO(s;{##V6)FSLIj7eu;`m!UzvsP&M9Kr4#M(L zy}h(cQ0qM~>B39Gjgg z@8dNU-9NVzFpp;psZdpCeC%TvWCGcKU>jLhmKPaFC@RG! zW~bExL57&Py*xjIwCq!Pcb81dTo^DuxrH!~47YTLJXCX!AjjsM{MmFeI6j_5f?Zdp z(Q)c5bvd$M>mj6-Mi}CPB-`fcNMlWBVEUyi6$2s zh9{czl%;c{j^>Xa!re*`#3l1Y!~VE4Ds~<{esA$PSEvR*jHeR;lUHxbbk`W{{Ro2? zEYd+bk-~hIU^bJ?b|fN50l7KYK!_&JT{(pGgl3JMNID}4pN-!b$3rJg3$I7jlB>ON zg;tJN^-z~XLS95r-hzE5tP(_)7<&sptm{i+6&EtXmn@a$9g_t!Ra;G62y2eK@)l$CWLYrlMovhooEOpEI~~>R&k-0A18^HOFy0 zxNgQIumr>h%8}8zsk$g*qoA3v4a#7ZRq@PHsXl6oVxN<#Xuy%HNiC*%&f|3 zQ<*D;W?w1hX5_PpPybTlm)gweOnULIplU(^6~*QzbqqK)&t>LVzzV!s%E);-UC9N* zklORg!1)-8I->v`v}61}9m$l>dmPHSUz5pO+{utBfz{BxO?UK^#iBViqEZ?*Y>6V< z^X~KKUF`z9nN_51Sia**EpnOsCwu7l@~f^5-8(@2m$#$KF(Phu?pQ5uJ7S~U$MZmF z5z@?`qFC518s5Y)v+d`yfyWIAyB=x521kT(JmC=9{NeQoltFmZ64#k*0h#Gmk41Et zX5k{29Qn0uNRcm)15$%@bM`-$ZAr z=Meq~ ziuQ)vp3vZQ&%FpF*mGe$Va1EvQiG^wB^q-R#F;EPjcqS#@@eaIMDTXfECltbMQ7#5 z5o3_-SE6^ymWEUeBw{T4fXR`v{ADDHjmtD?IdTQ95)2`p{a0;JW-unN_{U4_YC;51 z0$B8jj*d+0>jPmTPnapLPKFO~77%HI!ujQK{d&AA{GJkP)`?u(8);B_IQySU>rIW` zl`OKqtdE0Owj*VVg(E}A&$L&22vnZU{g3H*Wss(kV{>PH9WNdqCr=DP-*b0ec1^}Y zWNqsiN6SiMrNCWI7wX125;5-^fDlrlCYdy<<*IZm70zn45ReVn?x-jzj}4Vlk?DK+ z0w;q2&EK!%oKa@ESmeoOXmRFI$Bjt$2izp&D3~}9pk2M1WYe9qO?&siQHh4nSeUem zCn?YdFmF*M?ld6j;*A3P%&`l6NX zd!_hHBY5LhYTr$#{ml)_0Qb@9Yx(9oItMN)O?uWyS}b1(mB?pX$Sj#`u|?pin-}SnIgH1U~X{u2mf= z>nJk;*vWtFg*}S7TwS^?d?+=>2=bNk%6zQ9e~=~-bSE;5ZvUro~5#T7i=n3-3}a&f0d zurU)b<8MjN6X3$GCjCo8r&MGofVvy6#P&3$_3bncd%Gg?&Y`HLS9f5ie$_Pz>~d%i z7cW~9dpvoM=0BON>LFXPOMk9AGn5(`YiBZ#6~y|W7(_^2BnSr`@d(~C8EZDugTvhm z3O|p}t;3*OfGH|972S-IPD(T@4)jjX zC11caM*A+q&n>E^M5dQPBEHBUD__&?k;xOZkt2enaF^oiG=CA<-rN4(hL)`bfya@TuZSgJ?NGb%#rTa38RbiB0g zBu%@7c_10OtwJNlZwT8w<$4GbSVrE0g!yl^g<3b7jr43(NF&jhJ)$RvOu5R7bjbc= z>8{skRMJ$R=Lu1n^>Ju|)?KQ&sN240DK`4UKP5ql%OCNH7}DL6W#p-Az@>yKjB|R0Kpp#Z&xspYT3J-IXT7RX%rPGv(W;^yX!Cq)Env z<(I&iCpTcltT`53>zLq&DwKoUB5V4lWzg)CfIY!Hx@D~Am4f9rd7gom9dG7Wtq5d6 zK(^I4&k)Ta^nZZR^nd>ogl1r)`=6fhzt%7V>)-$R`(F^6fu806453xP6&JobN|0lv zi-Mv22Zc)_hhi@?AN+ZeuoUb=rgX4+mZ zGp{}#|0y$PPF%bXbQhKn5<&>7@+d_Esd9jLL{V}}i*5x$fIy({0(kugad6)Ms<1xB zq^Axbh4T-@LXG_#=Z5pcJu**@B;zMi2>7zAwdy9frx!hAcw_+ zk^61wA^Bqb6Um49=7+JN#Z7CIr)G6g6;Jj=1JPnz`}zh3V%^l(`gWqCfj0mX0jcY% zc$A_R=fh(m%nGdc=2mO}i1v|K-JG9OLxZ`yy50t4&3=j|X2G!ldO?rP5od$)^T=Ju z!EPONdx>gMA72bV2XTPBJh0wdv=PlN&VhybfU&@Fj6sER>5#3VpwPg3(I8LD%s}us z1dw~On0z>HLB2QPd3|+uch0^AeRtd5)`=9_={Rq0S0Rq4=N{nw>Tv~3x zx?qPTL|Dz`tQFgCOY*@L3HK0HS5T6Wq>k!}$&O#3bdbc@5AU?%?oAvY{ z`Js;X{)C!ygFGJ!{&~5~sTMCF-`kZ$AZLEJZ$zv8NJtww0=%11>3x^dC~a*rzB53%{aaP%zoWr1_v)B>kW|+#OWm?2LXYC5)B3V2Mc?A zisv8(z8itxIh5h`BEUpHuQ42?e$H3F5P@31V*{{nXEbACu@?D(HGKj$;fO)%`#hmP zd-A@i4t)e(XQ+QLM}HdrptG=krleh@eEFpIN&jtK!H0x1-O{83o8{Lx^?j95Av(30 zrzF^m{b?*~^QU8s6PX z{m~mhnixiY*yS|zIXhPCe+lP6^GotTRr}2 zf$T*6v%jSg{-$J9P1MG=ERj>S;uN?y6~<0;(v6us<2b_If;1C3{}hd8Ikxir7nSbr zY@+HzyZ!Yy1lxZ1u(is`sGS`u*}`-I_uZ-TQ{@%K7b_O?mzqhJxMILzzGEg}m|&gy z^oUrb+UXc=02f4s`xyJB?3r_nEGC+)v|glIZ7Jst>BDLS3jIBm8hSWe+6|C+0h`ZZ zz13yZ-y7*6$izB)R&Yxqmh~MVV<(sCuBsSE(=g;%AW6lxD%2WW<)z&I_%(X(5nPkZ z7hZH&VW4Nn%ua;^bJN}bRKI~$YHvQI9jybSdW>4&w9ZU>)>)u^9X_fkh%r821s6l!$@0Y?-f6YI=;Hn+9D^3Ph3L8tGiwC<8LDv4RrruqD z$AsSZNKckdroGNckco=Yd1X6xps9Vw&-~6(D6y?PYp!QH`}toB4}Lly>wQVRLe;={ZdWV2}j#2c=R++neNK`IzUb!>k;Gg0Oa6*FZIdm^`LLiA{sx&#E<6A-Nb{vv*-dB(Q2jI_ zIxEX18W*4UA|e&R-&tFq&%N`N0uL4qyo`9-i9?u;UvlNU)IIT7==fsmMUK|I8fP># zQ$g5OLMIWny6GKm!$kSXM+sGAc2Q_N1j+mgidN}JQOT2jTSZH?=t$|feP=LTmPz{{wV_-dKn^s3bHr}&c zs7xr%Qb(n?ZrMJ0HzpWiH=Pyh{a3tf`t4RGmKy_)JoL{K{?s5jIL7pRk^~narZj@@ z%)TK&aPa5>Z0;^De}8nK#Xr+bYz?u_vo(~UMc!ZJDJ>*m!{xOp#GA@L4$LnHZMR2s?iUEA%W+s?irK_Y% ziWD$uxJZ!UbH35Q%E#SVSfwgD>vEpf@BV>DaO?JF%1KlGw~pgLLpFeKl*?(;~jp9i%wsk+SbVGh0T}{|l`Go@@r(6XNu`09@ z4VzwKfXIK0m#FlP-MmTaEuX`qE3|3idm&xz@|6;j$Z9bED?p@ZL_lI22KI+Gg`Q#A zDEWkmAGDauR@%;}N1URfN*5-fjo$irQT={+FoZO5M}0Ke&(QD6oJFLgFpx9!%4hJO zcf}FNJ%kYeO5;kSrdq#UE4?i*Ic5H`<4Oa-*g9&xpKH6L%$HulOW9Nph@~JUi_U{e z^uprc3tQ$ZE2@(C1xa26+d;GYAZE-qlkMqhuuA*)WXMg(gMjPyG-Dks7DM<`&XQqY z;)1MR;knfWKK%)VdjC#mqzCqr>Sk=o{z65Kf;xNEp3#1qUsyX>W41A8U3Y3m7H5M> z^gY5X&JBUxoT35hwF1AWlH=F#%A-IMlux7dsRW{8K;Rf9f0Zg}K%<93&*rk=ZR7!) zGJE+Uwum7x|G3F^7>7w>gvfGO$U#NvzenKY;#qPcdf=lFM8oH#5ykoK+6(@7Y~+(> zk_)aF>pgUe7xxWwdsz5c_w~6EXm5;tQs-)A=Hl!F*RNAC_vHtb`wp_UnxjZZ$L>dk zIOj&Lw(jl-!l2MSK`b=3BR5?OxbXW%*m(41`e}c%4ws1TlTOtl&2r<>10hCnEOksR zu)uK%QqO%144&y^8HDc|`gS;)S4LB4& z-dVCtXd5-m(pby4K6?!O65l*w+)kuaS|ZJ;0j6e5!4@t%5|p5u&9_9CEZ(mr`9l!# zMaud)wlE_T`YM}qtDV1x0*}LspTK&PLZC_DhYMY5W%np-cTzZ-nhwV&6Auc~Fnq{P z0alZf0-!F5lsP00jB_~4Jwt%=pdoa5ql3G*!P)s@j8^yU7j>7S_~evjgJan5N%rw3 zyak1h zAIg}jgx%c?&oj4}MxrV3o#P0%!g|HSVGNe#Zfo)uaV|y>q81oQ%ueY4!aOrmoDj#? zHy^fMc2EHqr!FlH00c@r;7rmURZXDmjxFykydM~;J^ki=8AMR_BNQqYd!|`e)W3VYRO+MaB z7H)O@t2)0`N?=te(TAY~qh$rM%^Te|)1WKrjIa2!s0oa@JDak=HzGoebn zsi~JRq~8hy8LPSD<*P+fjf<9xE&8z$Srbg~t+MI|2 zL45w6kZ|c!Kkz9(tIE;)MZwF$oTlP%18X8bdg4SLB#njA%`_+xl_9F|K5|!tF=Dkgt`+#kqG#^)LVEblqx;O9Lx?CQU8B`A zIg}C4vL=TwIgNFSr4B_8n~$2*NyA14>XW122sQ<`NR*h0TC5l9sJ5Y&^vUXU&`s>B z$D(G~|F+tV1f=gk;g871>k*Uy446La;Ke@Sor50(!NsGidYvMy3db8vR$WmkClg&8yv84jxLWM<|{+gL-ULp`pZd8P{ikF578UeSj0s z+<0X+WzgpD98}^TQSluEmk&~dF<8hgHB{}H$lzcJ5WV)@C%XIomF4xJ?#W{2&^$l~5P9Kvi z%i508AN|c5i*W~m$f!erVAeWGx5z;&Yo9m8oUgKE)Hqi^tnOHP68TO>t-ENophQyK zMTk(28Zp0lU)y3LyDNfs2Srn3gVGSJB+RpWw!~{sMyWGPH9l8Lu11qD@OFvy8;B;F zjJXYhId*<05lt{q!7>r1BV(}^yIP+h`?05rbad>fu$Aw?Y)b*|$l`zl^GCPNsII2~ z=0_H+DnHG+7{c{q#TkbV5aO+2gf&OOg~9Yg5W?0Z9xon(1F639A4}|gPSTz2Ntot6 z)!RlWgQB8tV*RIS!=t|dFBNXpsl@w2ZiKtGybb#wMeqYByNBYm7+=r$6A>nqf z|4X7;(Dg?9W*O%$$$w1~9X>n6)QqbNc(v8Tx~Nh9f$!w$?AC+Tl0-bRr6{)_BzFjm z1sXM{5;r9~%h~2mCe3mnN#8KjELNK0WtW^}@dNBz@fyLyf^%^ozA79-6m4QIy=1YK z!4zJnK2d8(P#!#dB=VTYPwO3x_guwl^Q3h)ET0v{)Fj+a2-cRqiw_5}>( zzH{nSIT4;RFeP&vM5%m&RmAI(X!94f;fZxNqXnHumC`N5qqkw;&<;0pjt|lL5pPdurymNOos!ij0KP zHoY1F?IGQK#M86yo8%}<8^3x1)O^r4r_8ymgN@63Z|W{w$|bX&!eP|juW$V>YKr8< z+!+eTV>CJp&0xMyHi-ao)hr(@{KRG($Ut*OY(~{s$emui3Bu(h3xkQww!|^Su%x+= zp{?ZYP>NKMYaFhqJjX4^L))DdiTqlMv*2GNXJwO;VYm6XA7-YUo3poPQ!%Q*nbPN` z9al<1(uiJN;7h3Bm>4)`lTygFbJYaC?1~|@r=pgcV_bBnsuc9FJ8!CKV#fb zYyyEBeT!bNYSsyRWG~dRM}=UwO0%aC7pC6RU@Fb)rieGYpV9fyt&V+2L(UB2V!OQ* zvQ38HD6VZrE&1B_jt-;DLV+}5JDnC`vsbu+SZB9SIlnh~Jby_ZEcYI6b_EiBGS4?c zF|R*N-RuPn@>6jIP~cb@*UBhdAe?TuN*}e)MGCp4TAXb>>Hiuo)%Onj5`lh&8!6kq zb-`vX^36@`O}?_+Jl0yzL&a&*I4;q3)t;b#%f$+y{Rp>BdOTphW&>>N zg_l9fy9V%uJrB{yh&-#sG@glV{?R{k%jB}yRMyHS|8Wm@7y4cSXhD`}bCP@1Qd!cN z?t)Px$gOx5OgUL7kY>b=|15o#7m+0KI=}MSD znC*_sKj7Q_F1{QjRynNOIL8<)%?5qR$Y7fj+8W8XEoO2r8+C8X2iMX|}Y$~q(=ld>{~c&(UmtT2w}9^2O>RQs-oH-?YZ zSMJafXEPR5n#kvR_y{?kT@`k-K@S&WI^EUx49j%BEQug8_vDg0Bzzjhrhm<#Y|{P_ z>v1NYES+OfxKwbySaG(EL!~~_+5K|I)cWs|8$5)cB`8(bInQ3lD)I%$wp8l5a`(*S z$&FXMDDE49K&pHGGeZq;h~!LepU+j`4mLou3Y_=t5S^`maU3 zg^A~bVhWTTyYnQ!RKIe}fK{6&l?>Q9yLj~9awE2pPxBxsxYDUv*P0<)`br4Yzduh% zx?anrGY0Ki4B=Y3_Wp~EgHG~~y;G7!MyQ&R+b>6vyPvQp~*z%$cO$Ur<{fm*lJ99i7*XDqSq-^;v&X zO*H!iG^rRfet~l1E+3w+hbE*O)f|NIT(+EuchdHqErWsibdCuaDa_(t)oU`-opbf* z$O5-h0ps9Cdr0-;nw#=-C)RA&rzRQ!pr$Nv- z5gSmhFS7Qs$#h4p9C!|wvzE%q#%^TjaNz54%)FJtII5X{3pQ)>#LThDe-z)%+Bx#t zV%Mxx1lwRQx&68`0N(63glIxtrfF@gKnQesp0}L1Oo}4dLa1I#{utWd6I7YfOXxO+ z#O!n8GaJ5(8LrOzBbI=^P{ByJ;dc~eAjc>Vq^Eb_3v}uw~rkXtgJo5dxPHnSWbei3)2Qu@hvJ8)Ioqm(RpM&=My8DXZdpC0d+u zL|t0bV=Ri2;lQOA5?h)lchERm_qi~SjhPSoap~RcH@hu4bpH6h-V+FkQ)I%PL+hl( ztEr9V3&@p`XC09&e01z+ob9WGB$3p3rk9&%#n`}B`$TDAyWoe4gSafkLO5>iQ$xWs z5SD_>A{xekaN8RR-W#a5Dpf>)m@4dy<(zRbn7P?-^0T~PysN<3^`0^sE9sB{ftA>e zpWqTFn5d@tHrK0EIovbB#k=xcmbO$?$X1`5n311kYYRl9svgdsZD1FCgp@eaTybbm zS9p$WHS*p;g2u#;zHugCF-qV0-8*BS?u7@MG!YNq|ou@Niwz9EHjIk_el* zrKsI~p1HKOh`*wRT4x20ey@3X=f>pO$xRhIi_194D>|4kM_mz}%`;^zs`H58D}03E zt(U%<52~Py0EReI*H3My7ype^KP05ID&r63YNkG!M6GS89gy=#uP`GC^vOvY@`od% zuWklrg!iUqOttByMfjWoF}`{}i=;c~*G-A`4#gd~_HeVi0vC-y&@9LB?mBl`km{1N zh_XeO@o8=~qlEh=^Kv?oE5%CBeJH%agn6vxsqe!i zXq^gaz_)mwsU)8s~qL4^VSYabt%o-krZR`t=?mfC!{O7wL z#nZivN$Jv)e}6^|JXkHUm`oo@Ur;7|__AWhs%^|)OVj`CdPJp_#mZ*`p`69|++QVG zGDp}2khfc&s>&p;50;6`L0@xH7$yi>aTQ7-x!n_m4$E*H98`nMSa;_TOlKSx8AW67 zMgxaUPX^2kM&38wC>`wF>a|eMhhq(TYL#K#bF5foes<&jB%w_tG$|2in%m>2iE1yr|So(pY7Sx zqKLyWj@W=<&&O&^={;v}>{=d6{PlXPyHG<-7zS*@$^zvwxVK0U#Yz1PE3TP^ zg!mc|RP#jj&$cEzZpmk4PJq__VxyU6J=J(IcIbEcfh{IMxBpLAl>R?qQC7PDZ<#V3 z9TPpnf8wHa^vulvZ=Es>K-kRE(a4?vAZ)4UXe4N4U}Iu3GhO6{Yfr;I{zF>Pq_Pcg3<)M{E z4M;S-)qfH=oEnG?3hOjbk_Nc$#THCWovjDwF-HU_>lc@AR!&aJ8KR4CD()<@p)m*q zc{-~G@RhbSBSRf{slX&JuSv`g3?G@{(WNDzcl`YLcvxTmWDvxz5v|w+q}4C83do$7 zEVqDa7U#CZ)Hgm1_m-!rjz9sFv65HX$9(Y*#Gq>_kM;JhO=wq17YXZcAjSs-Yh6FkV0&34ttNZ5W9~i)U4T=A1c`bs$2Y7^X z_3jrT~9vSY#fU$D419^3RSH0QC5i-ZJ|ZSP4A#Jk<;OC$hX zf`goX|LFk6X31Ea!2I}OIQp@D`!RUGA^&ly|FIFDr)_Tb!J7Rty8EH~TL-%4{%Lg2 zuY-A#q9hyGNe%YuBh}>RLt9HYi*u;|(xa|sl8};w1gf$Ay(JNwz&MI)S`A{)-0+^j z;4{wTbCW>>1*ho8>gTOP2W0Hb-25}wMV*#5HNmw1$Un)WL@EuyKKUF$^D)?+kp6Ok zk=JDieY-h2*gXbLWo1uyCFqg-2Dj@$+B1@v^1Jqt#qJ#k31;nS1=1dW0#@b4iSv<3 z3xVvV{ML9R+Xt@||BP~71Foe1A)p1S*yIVt?xp-ebPvnF{qN5!%l-jSZTVLKD{$rc zPi{);@1I;uo~s_@A6WV~$U9Kgsc&ITfH&YJdW+|Mr^}G(2h(#5_Z9GJUwPEC8_~1G zGpB7{cVFA$-Ujkh=Njkt4gLmH+5F=VSX=!9)maXH(&+|h%)q>ny-V0!>Wm`3sW=0$ z$It)!gw%z9Cxkro>`D-6e*69~xiMghj9{97*3|$SUlG3#5FkLd{ESB<9FQ3LbT8U> zn={nu^jVIt=>D`OG-Bf-9M|=~gid?OD+pslpR3`g98MHrdaM=gXtq?F+h%9P9^PM-5Q; zWjQDC&}~n8X=Ouz>&s^$WpS(Bo2wGYElBxQ`mbf3{9J{{ylohMq*O{~4PIGh?$A#O z>ICyo>acm%qE&%p#`UwM6$4jnd^wRhG*0fo(mij*0{m;uX_50&R|XiDmc7)*RVt!Z zZdbT2!IPf^tIx$!S>Gwv_v>?Ii2wst|NR258&oKPZ@x*3HeOrqIKOHC;lWGiot9Hj z26bhmFl;8MNN{3#UWX;UaI5+j4m=yZF!FDFurnCsy|eJd{_pz9z*Ad?M$R6G7Vrqq z4hhVA`IWyszq;HQe)wj<>g@9;i?1o!J3IKYlTBq<73MK~&bSH)$5RhSqTF~EQE3F4~~e})mT|v803MWKBbP5=zZ%#7sk!<6LTjB|xL#xM*J)nK!$lo3^EvB6RIr$kg(5+=k{b2Ni__25Z`$Az z_r`=X40hP+bc^mtOPT(gXS{H+5H&GOTG}Rx>^`i4JmtD}hyWgHPn!hj=0-q^63r5Y zQKgaeJJqRlk3lA$2bIPe52fmT^z zj@X+upuq5T+B1jVXgXb^L!&jY%4M~OQQ6L_ydnLJUBtxOWaiB@+sA5rFxb#*Y)OsY zp+1qbtpTZ>a*u8hN4P6jA-76##BaB_z4H0+PaZY8W%;Q&no+S$_Vsn9j+6g8DVp4^ z0i-mxyeT;TI}6<0U1@*g8y^Ml+rhJHDj7tPa93VeLp1V%bIcUtTcGdjVl>xqKU7KP zQ6T!2U*aA5+V7zTR!yrcfVs}I_>uqD|nDUdyJ5#f@Trl>Z_l^gF$WJzu;t|`ae z(#CDxy5B5t?mwFY-2@%g&Qe~kPm@cLP>1uxbA&_<;|B@_PuUmX+re^T$U;3B^}naL z3@0MPt|1E(klIVYLUoVUIw(-4A65V>lfn34{`^J5Ly+=Xt+RIIqu|ai`g`sP3(C;} zQSxnZ*Ni>Ec$8YGdzRfv6Z}eL!g|N74b%rP>m-_X>TsKGw~^3nyt!O$*^@6yhvjKu zE=l_tif21Zva{rI9+Xw+f9~0P@9-#0rHCUr!37f7D`R5Yceh!& z#cd;`+A(!go>FZ);``cOX}T?c(})k>mQRk}2^7pNBdcx7b$u66{T8RbI&xV0J8FO` zwUB{^L?r!(+u4r4_;v|27xvW}^%)rXZ$lS(RZb>)6;khp0&JX%mvV zm49f+MrBxUP?&3sKXg_>h#gx*r1Q-1Hp?6xm%Gv)RnzU+LN6ekV&1rV&R!pTOLZhA zg3#429ft3#fkX`7`J~XfLT%FIFOAsM1HQj}L*}3#&*Hv*GK#CC)l4L1fvGquwPo~d zixq!l1(7*FJp*@4vo)gRAq{Xz(1;VvbS*FhjRV58-u_4X#*;+q)y|( z&7Ko!@s5v(!%6G56;;No=A4Dk8@r#X^sD*FF1(^&a5}U1Y>z~s;NO-Jy}_=$;*3Z) zOD2*>m>-6Z96cjA&guzE_6QT{>e>UMg)R3gU6pX0wEWuFJ;Fmsw>o>HVafx3dE@Vp zK2&NnM_JUYrr(+*pbM`?oZlMv?&KzN`E!7Qb3;g^U2P*D2W8P|^mE_hx)x~h2zKQBv)(<*_hTjqQfFMNCvn((%Ol0YER#3k%VYTbiB?mKm?HVD@=U=S5{`3KcaUr02%?l#0|3MUky za*9yN8}mFvYUFp7r>m~Y1H@m`_?@#uLQU{``lFs!5^1uFn7Dh1qwfrAi+eAuRcQ-k zROC^32C_L0z?+~tAz^H$CNwICOcajQr;eUDw$*ddG3L(O6D!SSwCR35kP{FXV3b15 zCa-AWiL1kmKU@Ff7k-_L&ff*hlSh5y$7E$vr6Y9xG_>2H9w zmDT|{IhUgKj7y5YMCuUDxiq&iMd{?cY5TPWhi8k1SyJf;7FW_tz-asLfMEaTJXWdj* zkL8uy5h{M=5#O|oS!w|RWe>+eM#h7%_m7)r)!_mA$VBdxu@!hYhce64^ zxh6@L<%TllP3sN$aAeYB|HWIAH~`5xwgS!_Qxzp+5G@pQ`_mnEINus*N4;f!1y-AL z9GqtoAMSuK24bZNJ}bIiGg;iPQS@@EN!NMzjS8>c1}DYy!ZE*pozwIZm3yL6VF{$n zG1>7l8h@!(Yr_JyRTb6Rn(Q%hQhf$8$3faXg(-+}1pxq$ag`w0?j1+$Llne%AgR8l zsMeNHL=0V5@&-eLlF(Fz<{TWY46}t@Jb8I(ymC=#5rbJYWRvLTL%YvEk`$7!WC`a( z+E*m?8FMXTalq0WQS?sk0yukOmz?$Y;Sh1l6xgJS%QhZ+{;6>hPqbq145gLeD)Vya zLb9i@?DlK{nibIlkz0r=v&^Cz+B?!xd8I0H6_E(UcwZRgo4qTrr`~yqH#t~tJZo{S z6Sk%NC@QhwDThNFUHc0jnu!jOCKs8k7OG;qB3H(|a7r7W5zPe33nzBotEtdNO-y3y-F7 z(MF%#D=BzFsr+S~bt0qBo5C-M-Ar`20%I~VJgky>pOnQD*UvUX>&y+q^9fvil z8dLTT7FZl(e-}u%V!t>Wj7LgNcpmvudSxSbvXzey7O~& zBt5!hHOAyfj=;p=63Te`ah*D+uus%bi|PG;Rh_t+RgqiA={eE$!f+s)xv`M+F4N;A zTVZUW<$teMu{XR`OS3+0ajeNP<0>N!4aUDNIZV9!~59ccGG{UpHHR;p1aHWg0Go#l3DEJg`FnC|6Y?Hc;AEMFLzu%%1R2fYTvwHvNnP*tBw6KGI;2*HeTSW zst9g!$*Q%5xMwiXNUOzlqb`u9xmVFYVfY}!%*6UD6%y9{F;tKCyFzfl(Cl3;R|J|_ zJn}66FM@{Vl2G8g}7?T zWc@Zpn^lWD+96L3{-1&eIBKB%D9hvC)@jQjD^Z@9XFhO%xy-OC!jjCSLE+ zDgqb~TNTPwtYDG~)9L8_fm#pPk>xI-+=Q+WgKzb|v>q4i9NH zZX6XWiz`b?QjJgoSF-}nOLj>yjwo#%EUL1JP#xt&n?<|b58G#N@AqQh9qI=lzZ0^8 z^eqbWCjSO(#a~T|@HE1=J`q0!Ze6O>W&$LKjb~tzf|e1`~^IP`)9zw zm^`}67B}TuZIfs_)oNTvV%jVD(sfH$Hic}`eJ5X*yWBn}Ox1+I&lsHb)7_I8E^pgK^oug0WzRXn=Bc47h=bXM(QsDf(j8{*V1orAF$skz5o^ zYCsZ}^7p@dXT{H#5xNPInIKWvm0~~=TdcA) zdN~ica`Z0Fh{2Z^u&umzTP0Qk6c|DGC+wVD~kATVazt8#{ z-b|17et`VFk>#8o@(U~s{x+z?Ii1X-18_xQiu{2f0%9$@P9YZ7jY_PcCMfm06DC$o z_;2V}VMPbio%r+Nl5Lk`>SE(SWmoNCzsibpBv+Mtwd!^~vrf&%Y(())N`}GLgw&VZ z*mOM@csLWYk^VI_qlse2R&J!ODmNsP?lR3Ev4amtCyPTpVs}LT2&soB6D@nc=YLgK z3(ey?E#f2l7XQUwt*mtczy#4sXX5?{;(iwyIyjnegxz%XZB|lQv8=N5c{RF@Fs+J< zNqtDx7Qoedjj^4bbZ7Vjt7yIp+zMJ`?&Qx<0m3MhDI9jWN08`_Cx5m>$d90NFOfRR zxgF3#j)>v)l5C{1l-sJ}*sX8%l6kz(;gZvqa$Me=gg|k}%HVbd#c*LVs{2Q%3vWf9 z0Y+}f!8@`U=B<`!2V{HU&07Psv*5tpH$;L7fOH2tAySxiNaIM%DK6KlGhQc0isoY- zgW7{z(DCw#Gcc6cD?mP~g3nkcpQc-MR3}lecK|TypOn!|u~H?C?mW{YvMc;N?qhUM z3hyGGNhGYcM=FpSvZBq<9B~kpo69%Yw=rcL={g8~3UOtuyrBQXoR0AaCkMvIG*O3| zDz!15qTKanO|xdl#)m84WI$82GGR!oVN3IU5V~m&HH%2PEo@=Gn`OgKXcJ41U9hl( z{rPO^HQXAmrZ45g(cebtkNEtH8#?YU3d(>GZCX7Y0rf8GgSjo)2Gw9&g5f+2m*=$a zjsDr|un4u=w=ud z0*nsoM)i>~wr8j%gIj(D5pQvB!gNSh8m3+xGHy0(>#2>m1^kPbHnJZxXez zU8d~8g)b$yX7V#Tuy+*rr4TK8jVcT0Mj0qd^Ck5mbtL3kBX!+_j}7`5>hI2vjc@j! z#wwDum>7@N-MZ%(Z*q{c>zsu;^0Qa)Zy4%A0`_Kt9(?QsJ|OILROH-Ax94?cSQCXS z6njM+DOk?PFV|oQyMhpaOWOXq2THWTy*mM0m2gz5d}vo<=iWbF@=xatP4an?*Rg!@ zEhO1|VS5=mQsrOCgJJf;QMQ=DJkZ6}hV|2~;n;~S*Q(pcn%BcNLUJ<7Ih9gJ{CAP| zGd_t;_*f7;v+~fo)%rx~>v1X0UO_k3Inl3fNXo~-+G^%9%;sjCP%bn>)5%GY8Zp0UX9%1K|nTq-TnuQR_Z$wjDiPUra* zf@=qskJeoHjm%u|EH(jadii1l<)RC5SawzFRq7(L_e~tBtb*2VsLi;?rZlz!#$+jl zL~%{v!AQq)uFPx&{zopOYlVAtu{nBLq@PR*(Jz8C^(oMjs-R89?X2*{*{k#|_pmEE zFYJDw5V3u1ueMtucpOS*lFv)-Pwws>B?7o9X${7QbbCVhbXx1@!KaCSBoCUdBAW$l zH)3t<3J&uY=L`Ms32BkBG1NxY5l#}nplsbSxDO+K@+Y*a&E?rb6B2qlOgDn3uEA-w z1S7=U9CdwE(T78rpkueGkf9{%Cu6+l5x!iL3y+oK*$RWQ_qE%YGD`=^z|dtFO62<@ zk|ZKC@HmsUoSyc}5r5p%yPkLQ=s_&E3fV|cvG9}EMV>M0+{NUc{+F{VZfvcR{@MO$ z6dhw5yq9k*KHL)r6`i!y-28L+AHE>N)D}?}S2Ytu0GEb?_6|1KH8WZG68D8dVSw{# zfmU11b9xFJsvgE*dfS{4L^_3`O~*19i4+F~PMi*d26)*lPrD6_LyBFzto?TVr5J`! zi281KN$V+g50>Ki=Bf+#H}Hp2pach1hORvq;k6Rg1U5wNN9W0UXmN=4T8 z8t(!EE4U7i5fDJr`hr^LJHr46MtE2%_c(z%J{7A2|hP-cgc8V|BGvL_@6tI1U+PVh#dH;n-WT`Ah4Q&=t zHUhYGyV$*J>cG^XFFU?4NItIy|J}fXQm{x!##q}oOc4B?PW*ANg{?!X!?}Y{6qKH< zA+jHWwTs?~HzdMU)vE@$Ci@Hngu%7SYN$vZi1-b*#tl11Et<-Dnw1xvMB@J;$Dk2sP5}(}Nwe`Cm}3&AT4A ziJ&G&`MoIJHNK5OcDrL*dVQwKaIQs1Lx&AawuCO^tGEv;)xfjcQ`Jv4iO#3S--f?> zrBs0kg?wna7xQ$E!c4@dD-kK1al+2E*}$JFTtg;1S8;K5gavtxaY;?Kw5 zRq=RutZ&SuzA_=^tz>~+cih;#=9!>JXd?>`b*}+9hKCpe^z^zcOE_>6x=~!Ce~ZDB z^62;hYrgi!=R4|c_NJ~GLwboZMOH#6JysRR?zhoN=d;J_Q+;s!Q#^12isupFoi2F} zXl?8Tp;t>z&*XZwgp?vFHdm?zSzC&oHq)S0{-nY#byX2G4fW}6ptUT@1|%43{9zy3 z63tK)u}+OB+4nH!Pl4Gav(i|Gj@Jo1qwH!cCU8<+3+*LfnyoJ-SoMg?hNC^DR?#!3 z)+8xWu@-W5#)S%4hR^b++&`hUwdgXHQv<hE|)YXiO%18B6MhN~N8cPc41>OJHd^>bHc@k^SVH z=HN?`>Q|^tx1-~}o4{k47uklfh}hG1j%~R4HU^CfqCxt<>ta~E$(4Hg5FXC+(%C-B zE|Zi6k0$us%Y19zn(H#9INRi6vz$gSUNZb!Q$o-2jP<%qo0xyEYFSk@PMmEabCU)^ z%Tl8ajv1N z!*!lNVwNXojV+Oq5Uh()#RYbbkR=d*B=LI7NRvOP;4u5@?F0S&b}5tum6DFWvLF|7 zN8Std(Ukh*aL05#P8s=kVnPxI0JR3EW`RUUpsb4DS`rPF*qjn79!=w_qGI@{-~C)q zOLWj2j;y>OR{vEx?5SF-hA1HEfi&pN^!sTT*c;mNYU$3p*dwV7Q+495T#mw8v@%{q zk3S_%6+95$DtG{x@K4z=36*B6i!al;KgP^Rh`q2p2_IcxJrV{Y! z)=|hy&)2Rq$uzo(-sJDxOIMtsskjVQrd(!^&V?TZ65|t*!@nG(yCaQp-7)7Si}_P! z4anwI(K+^19ertOIQFBj-+Bh_zrggcD?%(DplA3>8SAAe*BPIedW3O~5amLix2^D~ z^-85Wit-nOf;P%zbGDS|M#9eKaiXfebJtC9jM^EgC`gM|(?$hKa zlD^DHNzY`!mUuojyciljH>kozJgf7W<&a0b4`_S@?I%KRtALt|5hmaK>OziQ-kmhq zzlNFby*Z7!lQRx$#ej}yDv&^j;p~x}u(w+&sCpGh!mAy4aQNPo*WB}wwy$OS9PiHq zG_pTfTDUCUP9^bzsgQ~+c&Sp>CttGFNhK!jD*sZ=hQv9xsi%t|^Vg5U)Dm+W)DnN$ zXbC-x1#}<)lBQ!2*uHhW@KV)`y?=CDJTf-Qu00LG z^29}a%FXzQW$!zC<~boh3G8Wof9n$t^2mN@DVPc8oRdNiN_m5KiK8AXl+#$XrY> zq+G{b=}9Ot+90bL^0*s^f<@|71axWg_gpJqw{ym?adAP#_Bz`j!Xl6@>&o^8RMJYR z&`2~14>39C>h7f%#@^0!|22d4Ijm$~;crA%3j&r)gM1k|56072iqwLx-&@;Br99~? zv*+Eee@x`j85|U5=K{nEA%lGMBdP2trPa{EIPrb9VL6RO^v$-_>K8B~RsHSN*)b&g zNVAA))pU;d?c(EKKT(e?)?1{DJ1{TdNLfW4k%)ZhB;u83xW~zV>VH*|`FcNmbgM;2 zX;7A6vg#i<>3UXRotthI)^fdOA7PT%2pHvZovn@*3Do}_bUUlGiE?bOCL;cL)}^E5 z^bw4n<>eC=SjANx5X;=ck`YW$Yz0F@!uWh)?(jdSszt7tx~xkRij_JtV?lUG9cQl1 zS8ft0h!oA(oC&(6_zqLAVSr8%q#XyP>o#6bzT>~{hXfZQpP$#B%gzpiv8x*qkco%jikKczrP!%}e1P;9L zK%IP4>xj_`D}0R|Au;j77FH0mh|zd!7jdKsgrb~G#V{<0Eq0V+IySv8t4qtLeA8|Q z<6N=9S8{?<^XlM#q>^5a;B@nMePcPQk@%>_UnTC&ZJ_?CabzZ>$seQ4+-c9#496Z4 zSMHH3E=uz12?~=V(ER>njzbKge;DE<;yOJEThvi89jCCJ&q;k#8x6V=&r?PvRu=C! z`MziAOZm*m#4nDgLLC`^o*g-_hTm5YmJbaw5ipGRv{OtW5x9Fox`{|jU5k_+fGkhb;2OwqKk8TlB>!;!G33W` zlPD-N2R1*2jy|RT11o)bR^a408tZb);98Z6LFZ+5lt|rlg z2*c_qM*z!GR#fwgu7?Xk^)r@>r3K!pv%;(lC@q$KASN?aj3;@0smU93?SR*KZkVPo zVT(ZxF^EeH6x40|$dmZK6gwy+?c3Sn{C#Sh_2n*+?NA*CSUkNdN<;GGG%8s{BMpjs z{d_$r2XGPubUO~S4rUk0y>iY&9h_nz@!O^}%DEUx8Xlg7^N`o=SxRiSm^luAT7U*S zX<_u?_>VU4`<-DBtY?ln|1uE$#7v>;aHUQ~x9_kQ4W-bJ98qA$zrBA|=GvzO2mjOk zTyXE84NoGII*_$SSKdL!jHPCa56pYlp(aE!1oq2yJg}}!(p%b^4B)wC9Wsf3=r^2G zc*4buCL2ancE(HB;bBv?bKpCi2BUaG;jGq7ZTh<%_a!0xoRFuIoi(+7?5SCyj@)d| z2Ws`e2drKZg$elTpk%4ly9HDqSetk5ycX4d>;ievHeF#SZ@%`-D*K{J-Sw3J8cwIu z9wRGMPr@2i-aDp1ay9;Qs*j=cy>rS=G!vkW^IjmGuyDwUh(ZF;9n4ar;z#z5yjfIl zw57f8ek=b8RQ7p1yd{V1giWzJ%Lhn;T}MZD`^X=kXK;iWH8s-{$29&+jtC{yzGo5G56=S66{G4UX6PS!1cyzBC0yN@w9`rGRqLH)MJ zO4oF|S|2D0ZUSul%fdE5t{E)zYc^}71k+U`;y;#!xORPc0cYzO)+1$8QDcdkLZctF z4g5oHHS^G#v69RW$&qtsjq1+_tFS)-2_&QaR-E2-?_42+R7AH}<=&pU@xq}_{s0{i zW%2EE*v0)FsnVCkxGl5}VUUQUSon&OVIqty*z3nsm_I6{%Urwpy=jca;yaUz7A(xx zmetDO!rT(@=#W$bkt#e#O4jYvx$xf$Y^w3xIJ~-HQMhnq4xG#EE*96!7h5X+Y)q7%rA^aqU$A2x5~#Nxa~C61?D1~AH7YV-j+L>tDX&Bs zl8D|fbepL7uO$T9m(su``##NOs(D{*l9+(+mg9k(DNY<=PWl2uJQBqQO)pvUYtoM^ z%nct%!ar10;uXYoH?D9}CGQ!DF?)b8owb-vm;tW&2s=~5OlY} zsSN7(+ZJt2|A|>$dmkBzFtsW#irDt?wZ`<_#RmQ3F`w-BXgr=Q))jE1O29%lecvxO zFX^kIxjj@Q4Li|+;YHIhbz4H6j)=0j&sfKQh|Pmw7=;YJwQCzy1ilBITW@JC6&rs` zCt(AbMzoV?&}cs(e}rG+MG?Q;20~3&x^;5@@Vzqx_Ne)~Kx(kSvDJPmP2^}#v#u|G zvdH++6bHpxs6$i>*2EySX#*z2NmuZx<-gi`qD%@EP#^3!4u!jr73s5*O(161TAMQ3 z!))9-&u!Z{*?fabw4~X^J`Hv+`=6|0oT8Ctv(hNe@Cv1ck6mVyF19E`pNJIu$1x79 zYS3sJnkVm6GK@=O=qz5={pMHII!->jbhPMjeXw}jxHkfW(~+21=-}VUYT`JmnADHd zIk44`FNauaJtbc1s?2Is@D_b!{2k{aURhY)rXalq+~*v@WQ`xz@de%KRNL5uMp}(Z z!r}KEPE>!Jj{x?k<<=%fFeH@q8V>5#CZGHs5dJf#i^yyrm&qL2-J{0X%xjjVy+Lga zY$hz;$(FCB)8lfve?ijJ((>+>#N{uE??798lmh|8qP0b6pQ+zBRG(m8El2RgTdk19 z7w!sSwC+|}asZ~WD=Dji##WWRyjpWY8Q?j}I}=vp$ME>6E1Ye6FAFUeuattugQFqT zOr6RB=Rgy=+$nO<^dbGmuvf3ciR7?HZ%Jd;{Y~XP2`ZZ$+ICwMo?Y8hAE(vC+=8`7 z2E^Ngv(NvsLQ9Re;bRu-DpT7=5&_A-r>358cPXQI#}P`@CuU8%zz&hlCh!(Cx|gA- z&qEre_oiZeqrAmvnKpNL%|%7rS#tjPH~rXoHpdEoKu4kdbk1Jo@f4N` zTYF#f*cnDi$Z@Ee*@Lv^DW9v(@_ww!&oB?YUA%s0R6qKlV)`>>wYA`si^Rw9Q5;N4 z*D2St3p>>@xjt5;LY_fhcXxc*V_*zVxd3Ta;;cQ)k3H;WE<~vuiK;CVu57Dl2~AQ? z#HqDg{fOE*i*U9&%mc@Ll4;a@3DD(Ya>))9#NQGmo4LmCP?s{b#X*CPH}v|CVEn_P z@J^W$?^GUaj&9}IlqlL(*O>XhYJ$X@kqPt7Bx2M1A*&_kxgG1ZepEO6RszfFFoDf4=b= zvD7f+csxVo*tj;Lx*_+m-8N~933=e87B?#sV0#{M*(+>VL0?6wQzm)a^r#ARFpP2r9xM0*Madkp9kzJra}Rsiw!-zB zhawx7d)^4-y>h+S5Y>*qYqqKsGRVmwUaE9;627mHMoW*11SSsI7VpLsLGck2!=R)9 zC0iHCS+oanxDLV}O#f14^1T$RPJFsjwHFFgc|M#u5BMAeZOKM&oAQoJMQD9iQvG7* zE)SdCHSc@UVv&mSU(>u{acdcgND~$oNnZ%le0e}YJ@Q7m^cRYg?wfCeItot7o_f*S z9zMBVu%q2o0%16lqK2hU^cf;AMAh|>Sx}p6?pjM>4#g76PA#I zS>H2Qv^nI)uVHwzGUfE6%?wwnd2FslS9J?f8gZB04o@u=rn|vKF$yR5CfGsKMR;yc z*7-mQ1(^jNzY|Rrpay^g7wXPJ2S_&bTZGUw&CI3h1+Vdui-JjJqAwGS3`icxW?>H& zra8pNRrd{vB9Sws53Q;C$S5(=$|F0QTb6)!FA%uGHRCE~M%9Dcj!EVaSDK7eFezg2 zuD3U$Jn1nt&%jjK8TmMLSdtzd7EdfN89^5%qQJsqgBY4%inD7QZ@k z$ovg5W+NM=ozG9nQGE)2eYQ&XpAuW|MHkdYyeZ|(4ph4ML%S>+L-sAG!|%TIY_NxV ze>3`T=N3M*PPp<57;`aJ|DW0(EdR0X!Or&I^$sS2e}r$=|9<^%2p$I~3+MkCg4YJB zlDvt2CreDMy8uI!BV6XfzEA)&_5WRLM+DmoN>aoWN(&O~5K>am5Kt1(Qc}KW&;Ga1 zy}MesU1l{Ir&qf(&M$mTcx-6j-ab$WA+#!}fa3RoZ=fXsQe0GK1cLeb`3!ye`3M0q z(-2`!fj{za2F!s(yao{MOMNWK@d^wVTBR^zy3`j0djhiZ=mZiN5J*Wtk!ZLAHt?=M!#Vrnkl;J_-WFaQQtQGaS@hu|Qcg+1@Q`*r+Q zDDD=gpV_MV38f&^)hTd}0pBw6m|!4Vx^~?419!tOVZ=R#=6|)x(gop(A2qhT> z2_!^RKq%uArRnziS+~J9En~ z8RrCb;DNvTDof}3%+$f50zEr_(ya3PR}b?6+#TM%i4E~88Sp7Y@WUFNzp9LX60v`? zS$xk2;(C zBKPn?j$hajf3Uy){EFxQHu{SqeItK!qnyb<)oH9sw(IIw-u%G-Bzp+>zL?KDigRmx z6wwP8`Nn#;Zuzb8*F8`uhhKtY;0~=%f^)8fv*xT&$$vf3#!dB|ZMDiA7!J=BZT0#g z7?D5rNRHx^!e4({%YUEx{Sr*vU$bI1FiY;VFLsbF zC{0TU2%MGhoBkc#-X&SX>_TkPO`@IMRu0nW3pn`OB|cqN+IBS56;YuY+@fxz#Xc)N z@_rC)Toa@(Q-8c^Ccm&XB7D!dvq!f3NSMLF<0YTV{Vx!c@fX;m9hY1uq*Vjy4}Z>+ zHU%@%!&!chu(jY&gs;SpT{Lb@dv2+xHI}YU^P5c&>CVozlB! zJcuuL<58Ugj)Kg#ng~QG3}O$n;MSUQ5}e=5G`D-yPrZyJcwy*l0PcXDsa=TKGZnED zEYvS+dX{-!cGX3_DNPpBk>D0QgJgo+l<|ZtIUtwhu8)>5xl!?4Cjb zs^jeTa?wn_$+l7m_J0~&PWN6Z-&2UYsj!kDrVW~R_3Mj!CMY}h}9JhrTXDc9Ly(%QeOp$M)^ z)|=??t(Mh``()k7{IQf6LfSbrngllSbw zA*I!)`lagUPmEeh2yrB#{N4@SJZvlUb-7sAkR*$&M3TByam_HK5ZWoi^(5^*F>UTVJi)3H`1*n$!yAxASl7Ywj^YQQpMq?4DofZ zHOMHm=dn3Cil8jpXV3{WRvK}Te4Fh$5X*6ezPaULnBPuf(Ry)`rWSN9z{Tp=CWTn- zjnsi8Is~UpLE|zJKD4d85H)gArkkEH6df>~e|r+OU3L?5tADiPRrdTTgCC(<|Be z?IwaB7ws{XIo2q9sX}j)>)9EcjB&$_M!_|^-DD3v zS47K9-G(8zMPAWzcvAv?+|thTgz1s?cd6XO$mPiK64HCgeqZasU~!K7y;cE~7mC`; zIupn^K15%6zU_9RD%H8CjdhQD0E1xGXUrRK&CKM;OsdD$E1c8}0pg!(t9G_ICmO~8 zuSBvre8`5z4_TP%!TIztE_z7h`geww?kqT_jfH!s&{Du(ZgjxS^pF>~CS*Jtm|qWG z$78(N+4w_V?3t|A;PeVZVfXeU_EfKy;c>+zH{v36 z5Yv#Mog-GfU{AH$Ht9(tiiFzdY|K#Hy6b=r8ILwwr3m)NC_HPzaGTrCEDueN7EgPt zZAovNla_a*Yc?>JclDIXQyn|LZY&EDskz>ag)1sc1*tGZYI33vT|ea4gB0wpY??RQ zB=c025PGKS6LFAvZR+LX6WB7&JZ-I%UjmUN1V!D6P7HSdASf1@p$h8yKGn5ATgn=`M8wK~O| z=|f7I0}5#{F{}@dvPyJk=#sIW8Sf}eQlANPC6=Dd`T4k*3Bdoh^+Bv_$OJCJDH4k@ zkhq`tzK6);{ifT~%^CtNM-xqccL9-?1X+t-rCN;Cg+_wtunMU(n>eb+qc^ebrbKWmp zn~{zsR|#UDXO~6nuqQO=oR`{xj?T4=<%Vtau*Bk1>HT<$T#q?#!ibKRPLFeYNwvBa zj<#^?@YNTVn+5fTj~GEze7Lv689P`g)6aP0YpauGhb#^hY(qRxU0pLobx`uF&p0_W zW9#tQiRNw+EZd%68p*8mE4n=Ol#M0#Bqk3j zN-N=C{NWs_!w~thXsc~CI5J)-L&(=a=rSa-K}xh#T!p9Q<)<;-IlZD-Au(xU-z10L z+pY8;fYH0Zy{d4IR$GIW=2=bL9%zew#@L9>;QhUW_7#MLthhOhwl+PzM-E(& zH%Wp$GHU0q%MswC@~Cq)1Xt;#3If`jP#1+`O}UtCuk4!|uqUP88LU=fU%Nc951uOM z>X*w-`{_gNCiWX0LQ1}gr9um4V*|7Fy_@bFL@AyEos6i=W)q9w@G?R{;dw|b>V0Do z`n1vtBV+ZNdyG>HDsImP)joV_)ymUZ68VmF}kubebs(yZFkRaFpV2S5)X`MRIZzuhZo{YI<9o zqO4iVapldLF|{BhOJ7h1wv#^l%yxM~nQxjaKF|n06HR|3k?kdoB5iR8VbTr~zlYMu z&7{9IhO4*WKGYzS_K!-$hiB?`6(TEge^aH&C?i# z!0y&b%`k8n3v3X{^>8bJ*Yx#wQGCn0_d0Tsb*7+S0sN z9#aUGCWxvS`1)ipxiuV506swy5l^f*qYdla?NHeKC?cR&E6N!k=k`zHjw18AX+LBZ6a6#-46daF8Bb8*N?$7~-y zk6^1U<;D+HTkK4|xvPW{P-DU{Cd06=idr0Z9adgd!kFJ^KbhGTb4yPZUt zc|fu_EWx+?e6Wt2q8zn`lELl(qz8n;xx%8`8GSEt=X? z#yOI&6(+()`ZzGN&I4N#)jSzhY$EqF8FTO$QDWw*>&xT*a3;be8?MNcaNnO3Q(}I$ zxY?jz?_z&-NN?enleNFQ_8S}JThB649ahitP;yr(b+9_tyE>S(MlUIK%wnTc1-l1}hHvGCAZPTs#v&^M7=u_9~wQ)eyV3>Ch8A(iu{ zHS{A76c;hh&J73-KLutMrk=Uk8lQ^;g}=>HfWl*cZZma%+bIqp+m}(%5+T?thTEnY zPlnubtDJ@;9NDNwNmOSSQjBx+JH}+iLy58W{z1UhJ$e2^+}pwkC+$JFl_oWNkdeGI zaU7EE=p!Y$7xkCTkl#|3#N!_a=yZ5UBoJIA!$-Pkq5~(w3Jt6W6*yKrSaoAa`~fqB z-uz87+E=U(G+qEU$0WuyJSus6wX!+aU&d_qK6#5{2-9g6M=dqs1ESjdIl@MBvo%G( z-Sn4=Vao0pDb03fw9|!43#+WKy9qqY;a2UE%A<^LXpWsI?JRgWd&xwnOD%K9_J|q~)l8l5&tXe$22YU|rKC7`#1E z?CymwR_I(!Q}>q;<=v!%Z=DoRTQQA<3_gQ8fwxt`@`n`Qocew2Ua@YgH0RJp4r?-w z!HgTAgmWfs&7ntQVFjN53Thnw6u&d6Ir8A7v`lmPSK`p-A;+XZuHD1$ckv31t?VW0 zBa1+BUz5B}q7Qg9-7#z&c0495`A>R_i`P9RRFp93BQej^a(ia}h`U#gG^tWI4eU7j zNbqmmRf(wht2mh!q1&*OTiq6pMo&pRr~LAJ z^ymx}$|$QS7%$~@VgGWyj%PU(-}Jo{2H)n+6g~guk`0c+OziCY_Tbrkh2dsX70r?j zdzmHT@RVH$c}x*23XE0+Wi?V)H}ic$d5T2uqAeCu2J%M;c8h=D;a1+s39XW~N#NZ+ zZMjWMMO}H@sMvc++=JwZ7hu{vB|)Jse+iF6vgd0nM#wzPDgw) ztR33*iX(rU>GF3|(92YbUhIhq_EK(1O437F6REo*LIHWs?GP+x7hW&bJ+^pA^7LnH z(gAT#G=>y7=a6gm6sm#mhZ&h_M<3%3b+vv|?Z?5_8tsHptb)+m;PddWqi;68=3Ngn z3L!k`4sD5j4&Pd@-aw}10?V2us)U;)kL6b#!l*gptnKeDsC~UH6#Ih^YXFmARS0fy za^tN)d_Vr;{rs!c7*)gL8?f}ubcEIuOPX_R37dHkT%X?lUhW1I2;yv%f(BR8Ga_o2 z&>YZOK3p5@!_~G5HdGv}Lxc}J!ge;+IL0g2lj}iySl^=u6BZJO@OziQhP0AF9^P$w z=ZlxkD23&?nJ{7b3-WMv&&j+E4*DkEiMhLG(7d4|^Nk%npT1TM`6y4fn#R93((o)tB=MMfk$)FJ(1$Q`#q{PtLxFWSupe3S@vx zkw~CivlvFvKf*Zn-2+y6R4r`p0F^n}5SuedR0P>RRk(pEFh?dcc23l8;$j^RRcpW55#p{LM9}^`n}b?N^y_!gO9g zt>9|ZedvIGqXBi>^k^;=2mb}T`6{$DaYxtU^`2L!2xvBS zdKG<_IOX|Ws?avl{zg5SkLW+lt%V^JTLb2cU+7gjb!)4fAg=ofA9D5G>n~p025SIB ze%PNT2D*6Gx(_ccUs#?*cRZ*C7jOC*nP7~P56X)J?+4s+> z*ILq00R1PD-f_NWkBJa~ zWmt3C>E@f(Z^*#3y}4ygIP5d8@99&Y#gPnD>`qmxu==NgBs5ZXeo*d!gnb|}wAtFY z_po~>z9ZYH?t+8UU! zaxE0RC^kF1^2Mu5vgqD*xXmj*C3o-9O(@;fx!e{^SErp4w`8k;h^zj~R$((M!+NOr9foRP(+xU#O%f9Q| zI*SnR-!UU1lRIk=Xli+JvVE6$uq<5AeOS|4Q7Ny9kJL_}GW5Y1gH{d}7qwM$^!}bH zoTVp;WulWNM?F*ueE}6aX`e_6o?F9+LiV}7wl{sW)X4!R-RSKRc8ko+31p_OCX6Q0M6t?@JoQqo*Z4~ zXDce5_YqP;Ajh0qy%st{z%V$sA8HYNrXwALZI(~7pL?3=3(yn&0t8}7WvoLKM0$05 zpwKib2RDs9e`W6$xq-IqA8gQ!J}2YE`vDY(&{gn4Y(Pnk@}i^sqZ0H}qtt);H%S&l zw6PW$H^8q>%Vi>(c=%Lcv3Hlr{{#y6Be<7kGDITxQW~2Eucwa^O181MbVr7QMtF4Nzmc+%Yz5AnD^K>-7qaiS23pzb- z4*9_&0SQN&@*FjbSo~#r`aYz>kX5##tq&Y9J|w_ zGeQZ?>9Vzk+fxdvh2}kv0?D;w*66af%ksA0CRHYi$@l8|Ev^Zw99tKv2kmi^2kLU& zM5c-Ultb3(>FMP9N(|GGD`_Wvx;a>m9`zD(s~GQ1q#|9#WU>PvUy(Sfb6KnZALTmZ z=oJtb*7t8!G$o)6+-ukFP5jcP9j`tLUOhO1jn6t(f4|OIMa{nSMppB2Ak598Ixp5~ zvKowItOdk&NkTjV5yDDSez*Ol0NLOI9HI)NS#73^*C=h>vZHaqDoVU86GAlfH{V2` zOW!mP@p&bZ+t73g>E(^i2@Sy91al<4yl z_=nVn*dlbau>ylA7vYm`flvnoRFC2$vh>zo*?|^Cx4KMKNGlA(BU`nXb?UyCu~RG? zcpE{qQfB`7^26}Sy<#s}{b|}*Bp={&?}FE_VgQk4f`a&J?1HS?f$doq(f~-TGSYi& zVMP^`Wx!!bq)Z&xGZow{i~#?rA7V?m)*M_eYR{d_tiAH`)o}FG8dE`8c@zHVh^uw! zGizUc?*)`6*SP*N3(WE4L7g4~$ek?sBgl2qocu|HwgSJ=ldJS!7g`7xEad@;ztmj9 zqxR;$nLMb9ol;K0J+XTlL%0!?us61i%BcFDAQ#Q89V!_8B_N=?v)9qw7g?GyIO3wn{5 zb3`QnhzDx!tE1~FkQoxQvl%n`@E9`Uv!ioar+UYS-Kg+Z#rhYtH_1?Yjyd0lt)_Pv z*567SiH&gE9qbVxfvn7PDsLFx74+u`w6^4>7! zdfwsIjRFG+azvkAYNYNCG@!uhE%t!>acgA7`y$pNaTU-xe?PXY&`*xqLDoxTI8UuA zCJOOxqU=_@J+@R7gBTVVuA7NZCe0puTr_^q*6LH@IEQH>^D*3xHjf++F;7T6vCc?b zwDHy6*G}?H`yhr%p~rs9X!O#&dkxPle9wJc%(n;I zy{1|X+9HAWH6X48U#G3Fk%L_ixV>0$)Z>ZQu?2rQ}LU%TS?(ayktxshzYOcrg-Y zWH>S7NatO?wL8mkE_8=~b6cjN4o^Y9cR3%jQDV1{q6JC$JtP7wTj;akCPi=-4wZI}{j{S?-5 zmxWeJd#pKWZ?9e7?XehVp+^D%qj+*Q6Ti_!-2;$j;Amf|T6ZbM2R9B)FR}8qk1YF| z$-7f79T>Ba5hE$&lC*miemeD@3-9=nIG`fs7RdHy^j9q5-#VF@AF*Dz;-|);Vdyke zWg*l#Tt)7+3oAQLwD!_rwS8Q0M7FksBcJ`WGt9#Aee^8)^`{wNz!ES=F0s^oRQlz1 zSr04}A$exSyOYOIwA@~kf_ULQJmRJY5L=DrbgP31Jx^D8LyDk%?MC(0ZN;L5xYSaI zjkJEh?>*fh?L}J?(u5joRU&(zjViz<>7fIX^T&H)$fb{(2A+?0nm7b_1zGA&DcKLXxbY`Bq78>g1>IOI@>@Dl`mepIlV7VIA^^9i#TIp7Q!S z`ly3CvCEI4HtD$J)`Ai>LJ_Y2;|O4h3ixD4iAV13kzNO7Q?%NKz>r@2@LFnC# zom4bb%~pls#*TJh5hKZ|D;Z@Cu|%Ursjm>Uoe*4M`p^zxN4bAvsIuerT9|2b^a0?v|cjm}mbg%(tfh+HU!8GJVH zeani$9IR-Tj%oTYkV{x77DE7`ShR{j7;%p{HpMGa{^|u{Js?4sjKWCRCVxa}NpNvxi|GfCvLC>^YPlpbrZC z)PGaYp8}cS3@DSmf5z`-TueLy9vuYe0LIP%5+-oS(~Y2j0Tmz($FQ;lc;?-Y;6KLY z4*?X==LL*_i1cp%|M;q)LBxLC!Gs9KUEmmjp~Tq$u@3AQ0{XJz5QkBS00D?|`Xcq% zSdow5-og8J2H-gRuQLMxtfImI80vfa#|4BG?ciXvAz@wLRElrv7&>XHhzh2~UEDB% zf=Ry{c~Cf@!FwCAs6Wn)wGhSdgTHm5#5jPiU#cKWlfr8#fUi$MmX%+k0~uq#t(*f4 z0FL=65(l*$04IPJLG02DYufE@kVdk_zOMTb)iqx{xe`$c=b0M-O@-b4UKfZqDvJw8GkJf0qbMl}eF1-h2pj_lB&2kZ2#Cl?;o{=~0D*onM*(1d zt?~Q+SvwJ9B?6Z6t`9z*@@Tz(O8|EIN`v9=W;MJdvTY3iy;SXhQNV>9_=$dJwSKQ3 ze#!6k6@ToheqY0uy0^CchPwOif8k-=!n+KAiS|@3LkDC7=#bdKBm9-84gE{i(7{5z zJASd3{{}cF> zG=Vw}Z{u2IllcoXY@K~Emrwx(h5TeP#=q$TV1xo0j|Xy42L2re{2^*L3>ozCufiap z2@x=IpaanH3@)9$j|X7Nc0!xzcvxT5Ps|Uk-GqRYy8|^BRpba1?U3^5^-Azg~$G&$;@YQCV| z4?!ap{1<%ufA(S}(-%EP7}eBoM}iL~FQo=s7tW7S^bJ^rebbyOP~f>`H$DPdtxUtp z&WyErLq!6Ec(ofB;F?2Ftra`lmPT|@fgB9Ci1UGk+x62@*<5DM^Ht!t`~e(kC%Tlc$;!+oxWkUp1nvjg7eG8NK+oRrtj^ z(7SzT%j(NZ6}*k`jLTOg_08Kxi%obSvG&vr)$y@D6zdIQRx_yS)Ve+eA9iUkoESER zomVKt#18|+_{eeMk7~kG57*49V0ybEU)nQfV?WJ>lbIUu`qc(Gz+I1&LW!k}Ix^ZQ zQN%EExbZSNi!rxI7VRe1#!L}8sg~W2X&SPrTc3;bw5|mEP010MhPT$FnqD~1mS>@+ zU_H|mUz_RmHX<905(2}{;cpPGR|2ubGDId{UzIz#7!#r1c~QBL61U8Q>S@#99agsc za|3lC|q*jz~T}fxxviM~JooPHELvdUXmp#NuM=OEhpii4tkxhw((rk+wOn*oU zuX{3p_I+&!tPIZ+fQQmH=yj9KM>x>8GQ(UhPOCg65k-a*J?hp9`-*45UYp%KR@@iG zQpBs!!%8dqP|FBYRc$yn(&uPaob#ZW>U3bHTRg`?m<|k-ry!*T#_R^0Di=7(Gls>} zPbbvKaLbcxOZCvGEZ{#rPD}IrAWxT6agTVLK~=98vB}XH8^!M?GgVD^D5P0q!w!9$ zs60Ehl(vrg+|<7lW^!km8TZt-s#?VEX@hyE6?$-0X{+vV8{&nR#Qt2PZ0buXdtx$+iiJ@J5o)@}Zh2 zjHAx5QalsWu7gcIPcjevWnb&RnSo zFLNe4<{a55y7<+%l}cPho&U_~l0Y$~jV)7k4SD#+t7YjAfcThvIJF48Don5o>d7ll~--Q zxz0ah(vYiMEFhnnD#h55$CZz%hujgp(-P~H&fp;r*Ozg=kn?n3xXEM4{PDLc_xpP? zsRCp~I{6#+Jhk_Lo{~=$X=wBly9r5}68GB=o=NiiX{|(WvJSYCRGGgD#m%m1&$!`b zaNftSGRN2KnwS(F7|RIEM-YamQo~I5IjXJGSr0qTT{)eSgP0}C($*QOxk~uRXl$sG z8IE z(;MbWKk{lvxYN*92IN~+1B&FUYZj~S-yIZscwor7b^v`Ic9SkWuUK~qN44uXGxnIY zrgv1qU2N}IY& z&zlg2zRpu9ie6b6@^!~EgG|_=)ta($(E)7(r&A163DD$B6;XV>K$iaUTt6@n4AAoF?+jbK~Cw4e! zUbp5Zxx{T?k84i^{X27%^>Dq=-pV(|1bU7isYne0BNtqPBB)-!dF&}xy>5fE_Je`s z(XUybWcxhNw4G~dWGNnp*Xg9xz3xV2Z&BsXwyVt9vgRK=k;&=1&NxvYRcr86^<`22 zlpom{6);%w!m>f4o3m-yXN1a9%+{t@9-(+>(etJ1h)B4R?_cNLAW9@3^{GRsEhXww z;pm*M44umJx?#k2nBftfzeCh`YcbO87A+3h{SA0FHZXROl-9=+N5DLA?hqg`#_xKV zKAuLq8Um5*l;J`V)i!y!gy9s+kwkVL8O3gq!^>wkyur%Z>&Q~H@7Wn4e>3;LfR+r{ z{%IEz6g9^ae&z7vffEcTVQaNzOGhXn&wZFeqp4V`S-*VKDbO=YChstBGL!M~o}_m; zOG=5`#k0MLflx!=|C=_1ufhR*2%{5vTx`;-5ATkTUEXZ3qf6YYM5Jci%LvB|wjS*ofDm33r-v>UQ_Z)o*^Ug2)E# zAuzn+BR15#+6^?=?K@551U(>Iy5B(nRr%TSu$TG;`S@8oyXy0oTwmQ((p>uKBnj*? zh8JQ!3Ao9w*RQ~5waoARQ@KmMaNc6pXHm|lq_k)tO`u74=7dtIdXrk_Nf++Y07YC=S4rzJHO6Fn);j5~xq7-J!~ z`7U*-2*N{#z8zlkkd-X=gSk2yW%m(B){L}9np;bfMXA@Zb+NQ-5br4;8g>$%*sg5g z_HnQr*I%QA*pznB3L=iF4DDb(jlpd{yJ$qe4Fzp}ZMjkMFv8I!K3Km+#pGhmbRO<* zg5Q6++&2^Nk%qhPsf4I&pzZdx>!B#)?-k~0w`=IcX6rTZ?@xK^5ryfz1sN1%?ciXmY z+qP}nwr$(kZQHhO+xFeL$;HEY_#WyPR8mQ;HRl){t-Ua-IlG;>>GM&RFI9W(d>DAX z&y3DrDGr9e3Q4&XZG9PTn#=avWHAHXc=RuI{UA$;x6nEomz_Bo4#q*{;wqo>!*99= zEz`VRIZN?$klUO&TXAgt#T3cc)EI(GjgzeKz0&F>1M9JDmze+t|NPAy0zL*Z?k*NH z(`X4i2fs+dERwB#e$4Scx(-Q;+Z$jS{Q|9D@}~-qI5PigEZf^-R^8D*|IqdSdg9Z~ zR1vq=JvKOh^muU|wvj4VvVY-o@QF4i$xc!vGxL^M@w^LLBXWcrD-bo-u$E(HHL19q zvSY6kx>GY*Jed(D`ZP231()3V5FH424h!1wb6-SAp;ZjEg6d?`d3o_|63b1k#cGaT zq*%5&%|Pp(_s1tNzs~Jbp^>_>J3Q9uSc?8^af8*kj=G>R}wD`Dk zFJ$*gXd*^lVGyqrh^aYdBLnyzadgW-w6o)w8pO*(phL2ZRMgPskZ=vZRSLXF$DvQG z2erZ;a?1E(Yk6dj!`7H%Nga_LHMsKKpF?Vj&kLdc8m4d5X~PB7a9y7^q9X*2(c1^G z?o68CmXo^qac0@vLX49-|D8#X*qh-u>I*gUf^tysFE(Orhn8D}>CZcXM*jnun3e&~ zlPsg4M}pR(Ix2g5y9Bo=U(xJCyP3XLHe*}WMMhFKX&3x@*sayDe-+%a|D{$T`RKu^ zv6o?=|00fMJkePru}xcV0blDC_ctSZO(S%N6vbf~bNj z^z`nrO{qujh9BPr0!+8xf6y`_sL}X4qoGI0E#tKk69dC!bb9avOM>;7P5Dj>L+<6q zAr~8aVng^iM->zt(2U3>>p`Sg=Pgh9e2Y={QK-H0k$O;p#EitPFGnjlbYs@8ynZ*z zR6EA7F}p(|>TQPD+~m(@ZjnMhxp)JvYfp+IX``_yWXW2M@Q?8T9JO;W6_e_fPuKEs z9;n>)!Z6lrFLAHf*J6$;oeZ~ZMD*3)>!kEQeag2?c$?Ar??-3fTH`2RQU!7EJeDeK z)WclT=^S(hhJ{SgN2S#&0~y{|$lAp~Fwk|u7~r0nV2+Us zqm-N^sW&~0Itg4Y?jTmIrPf&~A@vVQ!UkKSW`J&`E4;6%BKF-Z4E3lz-zl!n)ux36 zuh{z*tq(Do0&29euB=f7E^Ih$&ogW-ehltKLOV#LcIJ8Yw0#arH0i&W6jBYN%cUM0 z^1r5Wt}k)8Ix#pIfq@Lt_rg+nL9^S}!{f%xWs#^EHQ-wSlJWx|zh%WEh;MQ1J zo7H-^l!B^icL3-yn%l(8&=k#&Ze(etSbz@cY8W#}K|9`)V50Q=vy6>2?z-0C?0@gU zt6|$2->MQqnqK2siA|{$EX}sM+2eikq*Xm%)M*GO+*Bp5co(kkwlyUW zDvn-NW;>($iiGm0?^iBEJnDQ|#nZOupO87YDV&EJdRx3=E~q)WX9RB7FRv7h7^@_? zQdZgFY)X!}0wYhe`0n_Sk$kMnC}i#0UZFX3RW7<2QS1q?aTn4`@unY~cXOC}6da!} z%31!sK3V=^9x*!J#aP=G=WP11)F&h)@GX$bgaq~a>8SawSatra-FZfyvlL;nkx5YL zIxxvh{yp}`b+OVd5yOc%u2#uR!qq$<78+aiE{!4Im3_0>#NxItcx}Ybmi2?l*~?3P zl4c8C_3)>P{L_+lJ3h<~9*uoEk*2%1qKiJE{oT!M5Y~d^gTR1!FDo3p%&JbIc(RS6 zsj1+(*%=gPzK``5S}qqJ>ET+SBSYuOpPL$&O0Yazd0O zcB{}}P?l~}XhAVhJuZUGUP3xJCZN+!+=K-dmHq%4F7k5biLz}xZ7)$va*AU4)o`eZ z_*#la^8J+C>_2NRFl`)o&I^3oC%iwsG6hJs=m`15(W91t03lmMau)Qbgs~V!vbpzz zlSV-U&ym~0Jr-da^*GpbVA+E-U=G>h&{e2h-?A@(PHnM!HR5k7~8b)Kd>P{;{K`dgT`a0v@~O{!r4j9v|mgHQi93gi=(6J>Mh) zmrTK1McKeI<-C8=QkBbzT?ieZ|EKq;gThoQ^!vT5@`l?Slo4gO1>E(Oe2IX=!z?z$ zWEHsC8L4R_Y0b8FOsrvG=1RdK)2;f(R+d$A#m;!m zN@3v6CGmxr-mAtfh>`LLlFo)9&FaCEa-I`)%8I%?&4fa~K!S8wuC<-?sU#Jc!t*K(1*hnseLYt$*)dlr zi<|qiNWRf2?>w+zbr>HG+XE0Osi() z(dQg-J_A&B@W=Q|peKj26&x7jho742zF-+HAzp0^t6~ivcCxW>3!mn& zBm4k3gaW{bmYUKCnj=}<`x?K@F?9@X!{dU37F`s~SytQw$%8Gth~0_<*gw$E-6#p& zWkvNeqfm zu^VRBY!Mh{^m`0xZcHkNed-`KtaBhU@w;3sbVjDzU}`|7+LW<*Z)eZu-h57wPg=T0T0C5`_RBE>;*zD@ z%(ftNxY=Ff^(@$RZc0|`Pw{xOLnzrsiU;ATNy4{beaRXJ+BL+g-F}`iPbpaRaGPSH zUHHe492EQ=eYO%+$u7~mH(i#TOf@srTB2yBGr*+{7nH=w6hzy+g>v2a@0!=LokP57 zMEWmBQ>fr!!i8&ovih8r+KfW8qE-D@ynnixYAR!LE8*J;sFe{+jTeYI#^XO=%`!%bjyuXKnHRcGc3 zZWI)2**0>Pj93PY^q*iBL7=mUwc$^?IgUO~>%`GGO)e7uev~}0I8d~ZJ3cX%=>OBX z^h79U$!3BD{cR!=e~fSo_$h-1246zJeB+-iSAVe@kH@Jbrv~T+4_5%+A0wM(SN+THr)$P^Svq75-mX1{hd*MZ# z%;Lk5?nP3gl5?H8XvsK?TXi`4=f^|zlk<;`36?~Ca z!(fIdIdpAzF@D3X_acdWE=Y+)gEALNb@V2l&eM2^gsHny;(5#+jm7EZV5XD()U<)6 zLFIQkzhz+~KpU8n%o-l+)26KU^d`|c;abwZ?v8jjq#G3q8iEw)Ih>b}NqZn$)U3eG zejX;%kd^^+2YEBe&E~KRQkc|zoywIfd#8|%EvDTs4#DAKL8hX|jqB$AboDQcPNiFP za_15so0gUPd82}ir&dVp*gHGH5#8{FxV|@tXk=(T9A#hZLJv#~E)8o&Ao*C+xZ^d( z*@SaU!7%GQ3*$9wAE2X(c5_j@_H2>`ENT;sAB`qY?rxJVxc6^#J+vCamxtG;OPs;t zNgTG~9C_+%YDdNw5yZLH+#ZVBVd;^W;JUc3!vvb=e?UiD%|_CDHRx#QMFuPF6e8+z zVBGl4&MF0y?4wOIr{2jj0y#*&T6wxjx070rRe% z`W`;CC+IO=tvHu^O1S38JJuAz9(j^!e z*w`8W_s08wsuD${jph;v0>NT#ccZ$azLKqnto}qw_S5;9tIsmbE ze5iABbTpbVEF51fp1 zU`R7E1ZfXEXbqr=Pd+w`V*KZAn~@*p4B(@Z#TDAqKNbf4qf7|P5Y!2{!yiBn%&QJ` z4B-R$VPzii2*{liC%?KJNZt*I<3~dEJ*f}!?a~oI`%2rd?33!ljj-+zub&?ZDm(~j zZXWo`9HtIvGYH_qk@AY(4V?<$%=|qIqA5%;_aLB#zm8|_E8(P55O^4fWdc_4A>P=gL}IZd{l3+*(tb0g!(NAigsMX7m==nLC@` zkGuQGQ7;N8EPUrrBQS3aK#0>H@w>f!#Q^{^KK3=ORh(HamqJ*cWb z7X8=Qk1?p~XGreR4X_h<$DVgQ4yy0{^YJz5K52lOAod0KckUORAuJ%ZBRQ0CQjg~M zIyo`04Y+H~y$#TM%R3u@R#sQQzi%;U*6(y4An^C^pF z+`#WBoHM|t*VnLn;*HkYB4)W@ZfgI%U&Tj0pPSmhEB3v->(v!Ozq7z0#;MLDo*o&V zoEiTt!+}l#?hK-4>7$3r;xll=a;kD)U1(+KKJqx&J{vsO!zdP{MRFaDS#Jd2q zuj3Nbmm}~m%k=?Jg-46t4LU&svLE|l{SE+W1H^{>#RmikyWkUt?<;tL^Ndvb#rpFA zz~1yLDk#Sr)r$bPiqru38}sh#mFJ52)_VNPW3T=L#Vg|f6CkJJum5ZM2+VH%3!3-k z`paKahMN5o`qd=|aRvkod`;7@s``t3zZAWgL{9MgPxC-CyZ;5}ZO9$*ybJ!z+WrIF zp7+=FpNRDD#-ZL_1?()}p5OH3L3PyRBLA;?Q<=dJ`0xD%NWhi=Dtgo-JXC`IX2)J^ z9!sLJtu@zSZM@uqFQ$EC3|dBhKbUcu3>#8&V`FOa7nWtpS`WLgJwpM|{e{!4z8mL{C};-PzQ z)#Yd6(FngfDOo=9Lcz+il2U4kpfGK*+mi~^iY0GVJGc@M0 znhqO!gza)0mJrb(mHRhxw*sJKO#oM!a{)cKMuLGOhVGJOcS@jHucMR>9MfI*)bSr; zSQ>E3l?+9{m5Q8o>pUDxB_`5Wh_!SQEfFUij~)3vj%s+xlJ+B%8&OT#(_jSxR=5Zf z9iiusg?>o9Rmxt)HHwfBaxd!X7a5x`&&n^^`{^NldZJ3p!n47!YodQG(;0NNO8MZH zG?ohY%?4^=4QX&*RRPc-=YJ_wwP=FIk1acpMQcvyAxYKXz|Ak1J9qawoqh|Ij#+lh zUYG(@EL{(e2VUfCHx~&8Y7R9qj*&evFWaSBcQfSU-CTPIZ_7II+L+WAXQ#EUhZ@&i zW>pMFf8mKeI=RtzBDPNss)u4>uy|CyVk}351rc1|~jRfY}#<+T;9-KhpiM#nq+vZ znf#IN-YjAS;!TDAZeuI<`Cpv|-9GiP`slOR0RikxXBk4ruRnTTT<6_#SmxL{E2WS4 z6aT%;K;Z6HLQ;I{znT^_lCBpz&rmGbsK1oYjc8-<HKsI5Sr zSOElN{F&I^d!t$XGr5Gg1I;~?;A@2Q8jeIPbwXQ72vk3*V?AUkQ1J5tlTsghrBZ7X zx?*2U2R?~&^1?a~h))FLwybNvxu{PvUvWdo#-tUXdFx5i*AUS$t~Zp}nlE35Zk8aI z?sB=362BtI5$j>18$9fE!0}hWnWcxU1;@Wl+{tv?h9CNj+kB>X5T(d{ld~pz5}pt? zGrLn39)_>Z(#F%pvhs_{HFTzC_{TD4=V>5d2AxgEJgSG`# zhOT}cJ+=#O`L+ZH|B@^F@CncRAtyD0rq^Q~{ytLVK&&vcZ9F+!(w~`*I`5eX7oa~i zREZP|aXaR~TvlBl7vZ4;pdvt30&;E}=Xh?I1oZ$}rleu`r-lM-BxJ2tuGbk~sZeC< z2!tk2)Q%_e3(X=2LjG*QWpq4%dJ-{jLHXh4uf+7ujm+)L=FozXN!^)l|)wqG*A z<2eSUf;^Ct7hx6}$!9d~Ri#a0=2%7MB6@6F)Vj8!NP@x%HsymJIekorx%L2yg897$ z^4nQ_O2wOfXypCsE>65ggk>9Y2@fRv%{OE*@lP3b9qL&oVug7)88d7Qe5HiiwPmI5 zbb#DRUD}Xh?mmpHcG#`{_1B((Ze7Xp?PMwk{8m&USJpl6WPxpJlr|nll(mO@eQ$9h zvEfCSK}E*jV)50b)D5$LlcSK}F@Z^sxV;Yfa~O%j+GTFqLU=1nP`__AL#3L{0SrAh z0MpNXFGm|yV}}~{dwk}pN00IK02er~kv6u5{o3h9g{y|R3HETH=nyo;d*XqTFII6kR6$>ET}(0BW=?UiHR zH~*?R)(@R{@>B)sOM<}V!Z>CcFdes!lk}xvu^cDMG}C4@L28B*WTiV|LiL}hT!w)? zI}M#x1$>t9{$^$uve{B7j5GZs%sTbT9Ho#zV#Z%=`=}I! zQhi?=Kta9S8Z%Gqt6ILYM&%j+q6Z?8ZlYRIMHpEkRE(x2rEc!^umm*GfWUp}5?C{tTq@>b$oa7a=W@sU8_TJC{$%}r^ z#BCC_`|@xZo3?D5P)!9y@I$|L@Xq|+3$zC3zNh9*olSZqE!~(dC=OI61mVP(bCL;f zO8(~d`?T_^LqN4z!)U7%EAwV8ep#W;RcLY3dqQqASx>gW+*9O9 z_QkJn0XD_udj$x5YpI`y7`Ia*p1@x8pcgTy<{n`d2{GDRL)p~7C~js5`QK8XTtwFr}-JnL5K`; z5G(Y;PP^kgZ?||##mbwN7$Ih*z`7$o30k$EpjxJE$*VsNkM-{k#6l@fHe80GvbJ=_ z9_>p=4}KzM}b4Kz_j-o)9dFD1Vw$j|%+=G1}PqaSU~` zW2KWI&$?cL_7BA$?~3zSTewbA}YiQg93So*Z(Dzc|`TnOyqBEFEq^&_$T|B*>&T$ zx$<^0_G@saz_ibSQz6>zXFd&LaH+%`ENrkFhnD01c0c zkRl|i3G*UDO%6=f*#o>Xml^YvZmxBX6w#tGcZaK3v-Sq>UjJ}-+3`+Iw4~w`^X)@@ znm|Zrbl8|Ma$BV!=jG6KC)Ncu#CIi)GSn3-kwcbv{I@-jBxMAqR2<;p$Po=#u6~6Mg}KzRH*Bt$ja| z3h~Gid&S`J>$#tKNbv;(>>Axv&m)iT`76-FN`18jTi#f(gKe>J$QiAIA2d$loCzb_ zBboLN>}K1Zwjy|eQUGuGRSfTA-U^;RUE@=Cs^4C+%qF&27?ozy-i9q@tONL}@I?xj z5lM8jvKq14!3>vABdubP+atYh9@~UwfFl=|w;%kh!LMS~ma`Yhfs04Q;sjPW)<)7N zLydCvo-wK$aLMG2ebKJtV7J=5sH!u0Idj(<`}`Vce$v`u(DsWC!`%&gl2=MoBx)x+ zG{yJ6{vM3yG*@)Ha8&CnZgqzypet7Ry&h7?_tEy7|<}xeF})jaQ8f z4!e81>&Qz*f4bACud({xzD3W z7hoKDMed|J3gox3iqveI<0&(3V-^44w14)<335b*_kk9YL61wn5Y30`i?$QrI}YYy z!4y@3=Vs4Kt1mVy^caA76wy^?8#S+K^-OiJ|DNagmqC4PhTakue|XC%@6f(2R4(j{IxDT9UC zEJWU6hQ*sDpJD`MEpO!H&J|^ni7De!W40J_2l~82(PFno_=$a<+rfDt*Oz5^)^9%t zM0)~8KlLo=-H#?>Bcp_xy}daA;_Ma3Fkx?hDosyAD-}zc{gN>U9@4yIxa*We^xjK4 zL^Ua-uJuEK^{&#+Z(&s#lCT!Rn;{b?*|3Ca+oTOKmszCv3J@L>MeD6lUirbXuW-de z{Q7yBF)%63Yf|&jxBHN)W9H&z_mr4S)mhhJ6AM3c4q3gjIc)2V`I-}5VoCGUZBHr#Mjl;q zbb^Ee_>VeLxz3Bo$u7eOJQ*Ga+KDc@kK6^{%(wl^jh?R~cwIY0Ms251*zMfHi{(-= zWbIIV1iCQF5H}eoHk+DqjNd2$V~`^dbk_d1{A~!5Hhs9`ly@0PRa+|V5mj0VcBqnY za#zyCuZFz5GW;63hmFr=1D*w-FgZv@VjRE~n!-+U>~bo_{@Q1q;f(bR0GT9G4JZ(hwK70p~}F zx4cr_mKQGsxe5|_jfmex)3b0%*{cd~O6R*#I>xRYcrM?+F3b&D6s5ER4+swWcU_I+ zH;wiX$99Kw-N%UOT#Go*($W`5GsOV$l)AUm?~tci?I}O|`19H9;Wx%dYLcrDg$J3a zDf;U!3FbYdpIk`efk8SGaP-#8AXSv=bQ`a4L+0}mqGueQ7Lct zvWSEC_^#W=-sY45KC!A0w6KmX$nHw$kFE<@eJsNtmvWV!foi2%u`kfQ{}If?99+50 zMLlmsTSl^$)(^&m^?baH##3fgY<;RO+8N|)i;i+!I&fyPA3uK^!~8wl8`q;-E+sRQ zx493eU{0o$6lLpOx1@+L5J+?Os?iR2*#3iGD?KJimwdciTDR)<$17yu^G?ZS=qaRL z*1h9)l6loKlFLB`4tg^temuKy+PGJDirKCO6ADGUcrOYJhq!C&Hn(Tc-5o+B&X}^5 zP7u^Iit1QH_ci)NQe?G8%oQ)ZC7*#Q8uSc88RFw3WO%Vu#tzzbv&7!# zu*i8;dm&3qx6d5w(Y$9+n)m`Hiqxn%UG`uIZ?DOYx5DBL+NWgo1nkuy+=}y`QY12i zQZ|

AjtuitFH26N|N26+TzqxqP5D6=HK8-2?VnqHuZVW zFP|e+DcvxPtghshkMEN?UA(HVbu+&V-6!TDx+g-N9)Tv$A|ed4#XXs&z@d6%gLa9o zsDm>+fh;{7wj5T>DFqA^gAy%Kulsz(8D;PXiKs*eEBXBUsNcW~6YPD0iD?o$pyMrw z&Ad{YKcbYEE~N@pBWR&NgRZ~%r?H*|%O#uN&K;(gOdCQs#eKT}N z<3dYAaMqJn)5{Ic_`5o!PLDs+tpzn5 z>P)qoUv6f`oImI=545P_w4pR-y-(PDvpVmsH_H%nZ-!tLzz{}UrE=k1t$)da@WZfl zJ0P@)+JiogKJHtC*cq8~KC{LT-XL^u?c!S#B(NSZ4eRQuMfoH~>P+qJwi1va;jZ!_M?EfM>OB+j&m&x2YF{(9clOxceq`A9OUn1V<7DM(V zFs74cS}U4lBm;@uyR=*vo02p^6wAV%C7$cCt)*o zopZEQbj5QxHPXIEp2RBt1^THxD>viCFVXZ$p2c%G8u#0jeyv$*l&^mI<3c>l+yD00D(|KfHtXY@Mp5PqYe;nobvPITn@u$z_xrUfR9Qd4vIdnfENapr+#m}~j z&@id5@@xaTP}0^?e!O^Zq_3LE*()C`h}fMzS;vqYn?Vz9plH^avOFtJ35}D~GIQgPT%|hZmpMRCnd+H*E{jT6O)%yF3K#X}fx~;^|}YOrDu= zQ0D*5sqsebSJ}}XjNt4f!>?LzGT$g=fL)-o zECrR5)>l2C2p@e|eG2IB7F+PMIZd=@?;_slJwmnnuC8&)fwq9CI+5HB{V$eMDc z{n~!ccB+cLMqEQ%;8<-)Z1E7(%eH~fI4cDT!dgvJ^ z>`$l)yQa;l7JUaW`W=o{wU3Ceet%=tdG6>Y)(Lpo9;{0X)6AsE_{0-656x%sQsYn* zk-1~DlO~r>ob^+S#B_|B$<(GT91rQb?7}ks#5*=K?gCl|rZ>nb<5%fbBACcP?slbV zx#vz2;TK24eH4BUVe(ccH`=PpUo}YuM>kHNKMeB#Ga-bohF-bvKwJJR^W)v#*H=We zo*9QJ1J%$`aQSGZiQ19>c-%Yp;*Hs7xtF%EZtAT(PX-#}G@T6r!&Sa%hvs4hgewF} z(mke_b9>we7)NqdfBTFVN`AbRlF@NXDTufxUDl z=MP%JEhH6_T`qT95S|h<|`Z6ygoj5@83!oyg7R!6copmTiG43$h5@YMw+F$@Ql* z`uUEw;|mF`aZNB|RNG*XMJEVW!-hT*RCd_z+7FHg;At->W@)3(lhdHlS0t4ymG*@Z zO_Sc-v`TO26RHX(ge!sX@|xuKw)3fAZ!>Y#5pezbFjkX3p*Lqvxifx_ae`!ZRew~$ zver`2B-DXE9y$3KhCmr5YwXDm2ApD%c03koA=~*qC|=Q<2xE$OVH?JAn;?i4xBDiN zHDX7eDnkqG+YoV53OE=R)&rl|)bFmK z%B)#R;>%H?ig){+H&y?@t68qxuW)tr5?UAGwMX&8qU-Bu=&c972G3k8T>l86+UdH- z8Hs35M5N#IRF4)qGNR92w!APwn2Be>xI_fnpegj>`rXrcMF!-gJ8eDbtnoi8$y8Fo zylQB(O?y+TJP{-H3>}uP}JBTHTZ zO$R*v@k(lrjj-57$$_kAPDNZ+Ml^s6~?9f9*mIIqYnV%LANlwJ0N#Mvl&#gj>srHChG*&1+53djC% z)Bclz*KVCBfc?tZQLA02#X0SvsIGogsS}(BZClsEk-B{O_@cpVPX*pjcV{t(PJ-;T9lU0&7(gZh? z?p~e2Bi_=~?&46#kHczu5V!M@jB;hA(-$deMcAyZ z=!Jdu>N_pUAzomC{n{+mjy_9@rhZr9`-r}LPrgtiKq?Q;<{2U5wdCJ(X*qhwg7rtl zk?dxCceJKU;v`BJOkGt=HGBsAs7z?{m`IYg0Nopu0z1^kVcAcK3KR z6;1nD^TQ)cF9N)e=(~}zoBAUUm7n6#hr;YKshNTL?)@cv`j%dZ zAh`&fj|mO7Hgl)dl+K>(c#^+$D`kn1npA>;5M=r(GFL)zL4zl|2?yQ%FJD+Wu;J`& zw-KEKjuF;H{vh*Sou~b2&YE0h=H86w;Hj}taTC9c;lGi$NM(4-CBr$kB2a5=s4;YK zq23e<4w*|*7$sDuHQ!&wBNBAcnbopWiZ6x~&0SVfU(TFT9x#%62p>g)qpYs4*bl*0jDqh$Cy7a@H!5l^ z8FDW^#AbcL*RPm&rG($AmgLB5kx;n(D7EFBo0O`J-EoIrd}d7a?siwqrseYcybVI= znA}RL_>wfzlE{ySy$z*)5k{JA#m>O>I}f?uf@FV34iIT(y*3V2?-ECZh7Pmk6<%$W zFM=on z!CkSvtY3z=V-oK8#_Y#)-eR!qyTzej=Y&@cp2*U-L8(R)Km9c3{JG=efGU%P)jv&D zu}T!A%a>Fm>$7qcXhufI{pG-kfs`bqVb5#1Q-h zF~G}oQHR3pD>*#E)X#(G#5%@;J+y{RM?rL`g5Zq#N>DGBL{BpRtmB#POCrP7W*ASj z@|hgLS|>D+=7gbWyIdu7mSSlYRNc9DPMD6V)r%5i*h8@*#K2!}+%L1Qzf`wsbStZXL|Y5U$Dl^Oy#JFL>`R^DazybJqA`Z3PB3ZxG0Pae+H9{WdMW=Wa~hSuBa|!Vw^?3j}>3;{dszW zBJ0Ev!Cpr;y;3O#Vg2lwTw{+2p8``YE9oKv$E#YFZC*-Vhi%#I(DBcg!#b3?LGHhx zbJQc6l_@1Hr^}Oxee?3f@nuQW3`CoeqeGuk1U?!QX;jE~_@@CEBFwO1Zw~RAdF{Sa zE}n|)06}7ZYlC$L{l98tiUg|(8=>A!fJZ4A#nN0qY0TmMK27sWl>+Y-Oj2!}K}w z`^MNJ2GE&k#ygC1yb^5Xa!>om#oJ!~ec&D5?n=8hA^oTjpi7gpn02>}oYAy5E1f@m zuVSmJ3d}fZFM$Yl*G6~;`~7|(Ks5b`iorR+`dB88o>E(w!V=gKszI0yc$Ac!%(PLF z9brOO3k2K5(rLT)MkmPND@O~wJCbL|otv{B(w7Gv9 z^FDbDeM)Gzv3}nT9Jx`xM5|7WU1-*V#gkl%FLX3Mwx+jV6}hv+sr2EV38Sl^m^9wyd^S|IG}c-9G>+CF^18-@D4`fxT{1aixx(_s?63M~W7%%2pkZbk3R+ z$b}EsnRfTb#?S@Kup2}5DWZR-8n zt4NOt{1e2)gP?SCvUp)3#bMix9vk^=5kvo{VFlfQm3qr13poc9U|hh?$7b9Em|16R z5p|(8tX6mT>0bc446{^yLFN$FpJdVqkIllAkxqvyx4SF-M-I)R1eF*&vF7^Mn~;$? zH$C(vPO(OVjO&aiMEAStaE}rKh`te)$V^p;b3zJxLWkph`}RJoCG}fd*!qGIPsD2C z)cH=l?V1?aO>1$|!=vk>j))XIvkOjLFYP$ZE`=Rb>-!|I7(C_YyL{^2M02#$?xxdzsY8BHmQpB*f~2nU6z!H zdZZbZg~c;5?>ToDmGCx^*g5?zM&E-RlB$zqn`DPI@VXc}|1c`&p7;ZV>rH*sGy30# z^$p6?YqTzU?5K?7;-z;j`}UV$_O8&+QMGg~meG5i(A}pp^QleuM&vtC7{k^^G~&0A zwaVfr#Bpd{AR1(PXf*Wed0#~Gvy5($=`^_YNjH+)338M0@$$E;GWt*tdK6+PAI+Fa znGB%mTV(hf?Kqft+T(MImK;3>aX1Zim<4>X%YcX(QC+-VTc^}iJYl1EHuoyXkDUV< z{p$jU@NqcsP&q#FKgL_v3;Y*TXB;B_uT7n>y-G%^RBVB!)Rh4Px`Lum_m`!fZ}+yxrNeWBNTD*%IYnqJb$>r<+!3ALz_8 zDasjA6b(7=O2IXh|K=WMTJ@!k%zM}GXVf_&d6Z%32dj}iP95?G)Hvsr`3wHY6r>QS zahO^DttNq(6qNMBu%cyp)CHh{#Ri|@aez5i2kkKr7tVkSI*;>ByB{l7XRIW`?taHs7H3n zbdIB_@h<%%sMyeGC+Kb^&u1$ijG>((8>SQB$Lk*AgOP%k1U3`9)?7PEQ*B!l(murm z%0S79iP1j;37=Qp_!EIq(6Id7PuPzDLnYs>o+8_Iy9r9{oS1x;^zJjub_~%ZFCK9$ zU|#?3W4aZ)A;_{fcCrh-uYdT;Qq)z`!a=Q)M52|{Wx)sXuq)f%k3h$H&4~YrN`je^ zi}WoapW&`;14^aM@Tu1jz}7BFB0!4s?k|#4JDQd|8g@)xt%6#^g+T-6lEQXjxi|S+_ zgReVqJ%(N4sfh;#0ouC<2%aw>Fh;5Y#2L4aYFNsw-J2wM3MVbD3Us?g|Agr4NXfG? zce5go?U-&V=*$;i)KU`7d(7k;*#Af_ojef;a3E{L^{_awo0^_`A7sf~G<9X^iU;2P z^yUoOsB58IkUIOYsOhEYhjnVU*9jBNs564}Rz-XO{LPfFdy^;ax@L*PLzLnNwS#h| zb#K*gg-z_3>sm<*_}8}XU`(l0WVz&|A!I%nT4-)w=gC40Xfx@m@FOX@gInf9SSS^( zn0H#_YkFnEkmf@D0IC`}&gVjg(v>PVe0~8HQvX*6=A7{OHZ8`V(T#tBa>A+5VNY*> zz$1pR7kQc)KI6{tZ&8nRp2kEjn}BY&Y9*8+-rvx`pX)sa|KAySL(wPhs;GW zDtN={jr-G{-qZ6^bxpG*G z7M(9#X>#TX-IHbaeJSa}wodj|t-MURBMKFKzR{q0D#SKchpPqPVOAEeWM=IF3!ZfK z-<0R-6p?H|Ukpt5q4?2j23x|nsz589OBd>%WqK{EX$v!Js_XfA9&1aj^GwqXir*J! zXsj?=0~FYbh6v)Cg;*z3BE@%bp9z==7DKiNxbw&>7r}!Jg~;yC$2~aPOKKLErVzv7 zH2Xze6nL3hqZ!$eb+mI*9dC%py?Qwv-Fftd{a+L;r3_bE z8$W8Ki$&Xk@2QsPYWmLK*is}8Of;#tp-oMV5G$C7SVndD!aHfQL4L^TrbIcsrSpI0 z(^CNpo;m?lwwTa)BF6Ij{FTv0zlw=?kkXpV-is924#Q|~gnHG;1(1<-J>2v?{E?j| zrG=P0ckt#S=%{nL)@G7Pc&*MUef^Kn$K)!y!x-_X6va*{T|#cj20bhLCw~FjR+e)7 zRJ~uHi`Q;mhV^;YF5mPs&&1prk_x=7zZo)FcBiyzW_zgCmIohQ#Of{8kINr`SCVxo zr*c?y@?>2U8gRAUOm@YZ>{zhuPi6aI53yZTYjy#U$`!1)klFL6Tyh1nII{QNs(A=O zm9;j3pzxyCbI8PT`WE~~u_8K*sn13si+FDr6e_=Gq^IGY@Uhb}z z-Ou%pUbwf)4mZ72@b-JJq=9v;&a<6@z?Gr zd8!+rt}h!`{*hGb99&Uc2-zgW23<1{T5l_~T*bwLf~&F?j+(oj<9x(e%j7)@;rKIJ zs`V4p%}?12IRb>|-PPl<1?M^SPtV|)4*(HKndk;}Z8;`jrW0ZfA5fMd*)a2u`D){p z`b&?{(54s(FTUsw*5w(&>5(HHTnTxG&xoJSuHN>-60s)~L@C0*(?-EJzXt66+6FjrgA2CqT0y;bCYkRwA}dU zGqT9;Ql61g13$;^br9llB5M{)C~~VoPlmzxsp(_n;!wI1m*2BMhbC2(vw)yKo_2M@ zGJ-#C#=~&F5teiX!~eAYi33lP6+LOiukaTGf9QW)eME|8=8;jDxKAIx7*820&yt! z4yFrC{VU6jM6kZ+yhMz}C6%O$KLngPzc!n#y8s6rYHWbi?l=WLk;)Sd0!`3AKmNvd zQ?(fUPvJb4{}j$+W@Z0x4-gXpD<><%f3N;`IFF5kgY*Av1yTc5LD6a})$T;Z5sXvrViRWI z&H?hzLSg@A?9KoY*hm?GK*27Hfs%i+4}*XJ1Q8(x6(I=}2p~wHaG)Q@;4T>eG>&Wp zJ%0pTK9Fy~0k~b*wK9PzH-GARr_ZbL!3^FbjGG*8nI8m`M-Gr$Ywx+gSrRU0@?+vU=IAG!U~{OYjB2d z9?K8M6VO)+M$k`wckALW`YQzz_yY&_cfDUnM^FJDVj0f>+z|}8`QP;vVFv;a0K)2X z3h@Xgyx>4Emmq?99P9Y5%KpZYnhZ<$QFM{ zN2gx_BzsTY7Yf0>9`<6@_su_k1rq8p=;K@SUvjS1txv1|+2NQyKxm7nzY@ydGhYV8 zfAeYpA^-vb0tFczJYXBZz#bd?M}OkkS7)G4Fi_u2GjugYYgm zm}dYWqzjy*|F#eKcMA~$0>Fll4I+Sb9S?}~jhlNCruDN)Ty_Wd0G0u?FoGNa;OFDZ z+cfSVl@{jW>ap$fcK^ZJ8WR(P@8oCuu8+{uGo8IZUL62p4;2NlupJ5oETRAn@OQcp zHt0(g^zK$ewHz0Q;J!>_nfANNV6Lxp?mdm69pHER86?bz2BZI-ePAYlNC0~|t^YUc zq)+&V-R*bs!5`s^|5EY6!R;s3=_lwH9Lgz>GLObOtLUpKbj|ELnO zHPoa1i@Y)lpn!z{yv6ybc^R01M%c zpW#oXO}0Wj7|zJpE&>K=raxWAo0{UkRJT{hPR?mD_k_wM+EZK*@E`F3$>Tpb4pDNKgOPlCRM^pxwj^hAofv$4Vrd`r0bmLEJ`gj91wcq z9pDH29g^fS^Sp`Oxa}R~=u^B?i5xkJvjK>CfzfQC3QJt+D} zRZ*9ewA-4^2VNw?pl>_Y@X?jOLmJRZG&%Drd&-2TG2&7sxDetQlz zwO*yLb!0D|i?U-kLiBOKTYo>^->;OH-6GzsQ@}`4ir|iI3U%M}Y7jj&M(ot~7^%_A z!z-tpN8fX11lOZ2OIgyhnCmX*$yrnSg(<42MD$`KD(W75Bz>!vyx+$d-l}^sIv!A{ z4HmzY5x;E2Z@gM0`4<|)(uO=T=<}I7ukHEo|UV z^s;w1c{Ok-^^MIA?25SQ7@&#qOGYi-Ma0_f8aEs?(GA6oQ}zI!TPrsj&0Jo>ht5D2 zT%3B?$DR!vZ#Nv~YNDTBKJa3~F(9B4&0;`Gn5vSX=and^J^7O}4m{Y{Z}0Zcvm7`@21`*hvg(r29ix{2=E?P=;rcFkAz;m~+V@M@mw!eIwry-NiC<@PM9M8h9T(V*KOpS%_cQG<1 zAG)Wp4DG>Yah@ok6t6A_{|bUcQ*MWrB2V4O5L}a6StO6r_dn9|{zF@yyUh1;1VXS| z!tA!TDwS7sjqsAT2Yrc$+nOpPIno>F1@Y*FMZKkz1X^q51k2i2*;8(o6bl~9ok^bsT9|(CHfMR@Ap;c=5B_k{J+fcw*ede%m zuvzR289Ar@2{o;<)lfbL(_nVVS|D_&NPMw1tx{Tr=q&0)5kSLfalmYiWOu z6i?{1pS$$;isMq(u4Ia~lXo4;W1Y3BQKq;0qufaJ%ffr4{c$EoGdke&`2YX zzrf}LMYPE8Kq;$&rrD1rb5p2k?Iq(EQ|IEcsHd+ZMT*TJ=vAh{I&~1XMwX=X!%qaM zw#%N}oty0R?BWcjuvwTiwHsb-?@_;=-EP3t#Lxo}bf^Ly*F-DX7FxNyvq(8KVp+#U zF4q!93R#8iPB^(lnNV$-Z6o&eO1PUBDkD){Ucqi84+H0L#flJC)7FOBLFUVXL9n;+eN;*B`H$aTUi}f>Kiyfrmrx|A;E^J!vVLg{MYMH@&zRu^81#y z-ds<#O+MPHQEcW_^i)QQbN7(^oHofoX`hPR~GWZG|(Ie z{-Z>=+5F9GnY?JI<>hR!*^vR4iHF&U$Ejy%=0~z95(#xHT4n#MpA8Ce287Sh8mFSq4+#e!ZJN9Fq;Z9n=PBN? z6iC9KHBDqFs}(KZ+WdTW4`EdJ$7L1obx|t(3FzJ$_QQFdN)W_L5g{FC<+>zKWG7yh zv*`8KbI4<&K@I%G71jK0fz+c{11&8m={vtp4)@OJ3)fN>4;f|I;JOp&%FNR;mcsWd z@)6D6bi>7hg)yTE9@yNY&{{Y>MV3gVbp1h}d-RI(S>|j~*|VGLlxL-^HBL1f3dIZh zYs<8eOU(L8YoZZ*zoc>qzklJb`=~w|Z!s`pzh7c&z?z>F#eWFMQZb*>88MlA@Hj~# zwu8)w#OsH}OY16@ZR(#3D&+Ib_&4S?cDR@=1MEmXZ~E|ox5vSts!IifJUl*Mxivw; z534Hfkfv+1r*=U}SK#-p9C~|$ze+$Xe$~a{$FF_DQYh0y*Od6=sM%sU3^*D;z(R;B z_p^po_8|9;b&VY!*OfiUJS`QNh8!Ksrokk8szt%cHRob&vc4$KO^Ha{z-5SuTCApY zE+QMYM($ZTLhfBnlrY{PATE=aA2pTmX@)u zgaage?6g^Df$ z;>ddPD#d)p46{EKMKx##S8cR6f@SVyD6MWEr*{5>G8Fd%(bENafEGch_QjwtOZw1* zEv2G6pYXT<6%*VwM1g%}871{XcY?w2x4?~ORs{m*!)1Ntvo~3*s54r~A0mxB`dqx! zQAvqWjMXf>NyK1r;A!nBBd51G*WOx~hdej54P!HT?7H-uQ1CA&!@=T3AbdR6p1$Vz z2KATSy)SbNk_jt@D>pChWJ4~e2(JoGRdJy-BSEZ9o_eYD)g_{})~<;54QVPe--$}b ziOE)Vo!bXyPK>-o-=36fFhU_RAyv0G>*;)uS;69x^+R0s4p&c%WgLWO!AMB%@xI9| z=Vb-T{r702Adf1^7`dvAhzz91M?>_*Uh3+z05jp|Or)S%Gwkm$`$8c8EcgX`gWV^; zIe*1VE|Ut~LPz(JY%HBx9o1sx;sR-lR<*em_$+EMHn($ao{=?_)XQ3*1GUEd< zKk^;)cx;lRE{~7w`*w|5(n4tVylddx&BVpNH}-kz7rDdlP(#JU=oL`gDy0_I)1Ri* z_)AGuG+@2UqOJ@1%kxZBz+!v1V?1VO{l7L-9`0w-e6WyFTWA=6CRapfK~r%N;8Ty= zQP9byh+x%Vk|{QlTCyOYWZPd~rr%Re?H6XSSva)3eH>P7n0>!(b4rk-K3r>hk!*h~TBoiwSL=r5O z%#h0(1uW73G^xpV`K?L%Tv-KDD*SDSlBUE%N6+136b;)yuR5lq$O|t;=1aVdOXjHJ z{{h*vkcr49WxHLS&6e#=J3D-1JweXIHBR3iJ)cKdb?K_tCS!I#wTnD?CGUSoZ z-TOv~Et8w99Fy2X-N7C6a-V2yI&#H4sF)e>*2ngSg@qnsJeU76Ppi-qIJUkXR_B;e znxhEKAlWzJxJ(|nNkZ*!zGWuU>SRk2t;fkC!Jm`ge=LHSgBV@X$R8dLO6 z;`Eb<8hcp*DC{VmyEAZIzrjVjFypR8fYic3N2XFht^{ItAqRz5Ix-Pzk zY_Z>_axAe(Ve|rOyVgeVJAiXsFRd&f{LGp1^Lfh?S(tXNoofwk6#Xv?4)EzE$j zr!zqO?<4T*Q#^Fm4dccb6ItoDSD-B%9&^11r-7wspYap(8beA#HfoPV@_1I}?YGu|!4i1=?pF$WTNs3fTPA_2MHgCHwvT}P&HyeJ@ zP-{H-U)QpLe|6UY{h?#{k|*X4c$4QCGke>aB+^no2CJM`^EGNBG)y$eB@8c?WoB#@ zNp2zFGp)68bz~F1Nwm_OwFc;B7%SV9?}LWdbf!aYvT2n?5`L|!pgKfH6^RocS*n;j zf?Y5Bq!b5TZ=YdgrRIsNJuJDDKYDpA6fK{g*>_6T9CM1BM z8#)e--C~UnA7vbqjf!3NbZzL8=d04%_`};u-p*yYN?p2>XZLM_rf1U&9z1IRjkm5R z>yr7rGt=51h4=5Ea+w|j$A+VvUeE8br$*hlax-+S#p@y$ZBINxfpc6o&8D+C$YAKG zJBZH^7|sdE7d?IJWVwD>hiyun2ObE7rOC@2$1pXdEjR0p)kAG*Dg}k=6E+!}q1upCIfi+v)pia148&q%})aSps|Yn5A-8o)LmeribNmN^mk zC#fK9s;m_aXdmC0juVqxB7HAK!yCYOw4GJ*)UL~wzBsjGe_29v&?p-X;&TcTpCa3& z5x6|@xb`Hep}%EsAGOr+HW8*pOV)h%F?Lrocx1_UT9HH?zGP<0+gjVD>Qrb?YHU2m zrCr?Ye47XHFzD*sR(}FydC0o0D6H)4gzH#4{X4CbcsCH~t;9}mB$I=A#{XuZa#XMc zGcdE_lW*3!ICojhbg|dblwr_@bS#uGR|G-90D1WI#^Ky^H)WEhkReDO8$gj z_J1DITn?btc)$`rs4|er(9yW&VR_@E3b`JJ?m2JmednL6!!i!#f_-EbW%;Fxc(~=k zy{Hs29`EF?l)AC{7^P9XqhYJ9-E%em7QoUCiFeu?t}_dV3oF%O_o3jm5ZA!FKpfzA z1D?Gb4wT8XdjLTro;w#X>A{o7T`kY2nh-~>D3%={1lrhnlAw?ezY)J|ouw6q zEU#d%;G-5qV!o>xbk5P030$1N%WpvH_y%Gu7u?40J6;Gql$M3NvsLv`T3DFXJu`I) zp7`!=I@N)-_7yVvyQ5Anl5KtY{T${N|C{&zv7?afo|mk!PyarcY0(JOY1!w@Y|u{| z{;@d~&c1!j;Bp@fPqq{Tm)}s)EXG%vqQ@GFcKC}gG7*waS|{53o2v7@VqbqtxvPqd zRx8-qd>n1NHDOh7Q5nnLFte_x=bR|mk38x(<#WA^9I|yHozIaIW?m?yc|BC5zBzok zdV4AZvird&!KL5FXmF{)88=g8p?~h;*eK~+1S{kw>^c~_jU5YLR|FMZDV2V1JQq!G zfqg!q5-W7^?QKI(xn0#QEH4O2drfI$<%4hTVcoEc_|j<2#eS;tUF;iS=E?s<8#3{Z zjcy4nt0TF-)#LrchC1mi`g(hoxn$$Ken@R@y3>pVMiR~9KZ8k^OMcErbsh2D$THtO zBwHrYlaAb-N9Hu1nm5ldM$a2lyRH~m05i%x;nAYAOn|qA=A|D>pne^AwUo}8R|=(<)QE68Sfm1Y`8|B_e%{Yt*N@NsB^$*kOckJ`qU zt6X_42~PIXbLS(AV@I!EnVD!P{l4dRh^OHGsKX6}zPlf-`wI;@E7&|_Ev{Mtu#Lqp z+a11m-^&tkN>XVDUB?c9RSQ0ZDia2)&6sGwbBj6<9oV{kxUdSehM5$Usg-fyDd+Gt zxT%{>eQFa82e&SJV^g>wm04V?qJkgN+r0%Ybfl6N&c_#utO-K9dF$eeethkpnan?W zo64;_23TdGoVmQRJA-wd3V?I6>LKb~=C0CGa^7~ntkW7>mehF2jV1<~0^e5K@zBj5 z3#8yURm?q|v){-C-pFPP2~KpecHS5EaRwi0XssPu8sEU0@cK+P3Rcfd$?+z6ZZd9g zaMD|Wd@0kmWRgMopvF4woIraf$U{#b3*(51yWb^W#;nFxCTAG^N9dJn;OT^mhc7>A z4cM5o#`KOY&r~^8r{c4}7{RA$hH`g<^`5Aq`XSlo9jB}YE?zR^*%b}p-if@Ln+1z#NhN*X2L+vl3NTHq2l`9~??o6AA?ma_Bpe<;tG%z#N1Dz$jQFfxDOab{_mKI2cHms8z=3q~gNC3CC zu@e#>5oI^@Y)^cCibC44^X3FwBwko)mTd2DU46 zsN2gsd%r-Q5B5#}39zyKC&0$S^gl%#OayGqoSgp&u(30(lqvdt%ZY<_?Q z1OYz-!wf)KtN)~bS8{Q#-*?!04xggfB*ym0Tm?y86*%Oh#&zZf9yfTBmmQT z@MXCC8SwdlA%dG>0n+v=bfAm9h~ce=SHyn9DM*Bb1cbx)Yd8gmK!W^M0}KJ|7?+TC z1G{EWZeW=GRt1Q~OMOC)V%$UtbxA)zd3kxh`e<%^oPC0+3E;aBB3wW)1b2u*U?cE1 zRXPFiE1-8>417iegChvnUtsLP>%?3G5Rd@C?1EN=bna0=(57Glfb=fFunR2!U3G}7 z_=Z({V7z|)8bF9U$S?9O{hdA_LBqbBf!0SRB09{pDJ`$`6V1S`3 zKg^(T zxin1M)gFU+o&U5ye475!vdVcP;_GeDZ;_HpND&}kcMt(UT|NZFzjH|lf-r>h^@A%4 z5A#h8JHQ`ex0@0r(qN0zAfm2DJAUzK2GDm_U0Xz4!m< zn(mMN)eq|Nui)M9tT^iN)tC0vz4W)g#Q>dxd0pQVMsHyP#*Ot5BR0UNy|VInp6g23 zx}YN6Z;h&W5F>X!fV0DoJaWNJr2@;a9DG!>>z8l}fBStMsB_pLftQ2(*+0D2PYnR{ zod(yW+A5bWK7>0owo3(JX8Ge=0yT|h_iEh*@~=O{00ihtGzODV3<>ZJ!eDhCF6jUB zHJG^Jb^wOscfhNChy(pc6o5Nw;q1gc{WE(3lwg4^g>=TRSO{r=H%9t3{zim=-4)E^ zAAEphZ2m>$AMGD?r&bCOpr*{eiQtJZ`}bFFfWUmh*5RdO2knY^a@7J^b5y8T9?vvz z)6sybQhH8L-%><;1%3(0WX`FjV01)ss0rTdw$t7U2b`%n2E7j(wq*o9Tc6tBpR(If z)u4g#2k(Qqq2(Omjx4AZ+$WJ&&)6e%ANp+{*`RC(?0RjM08KjzN2MN|DCRkNtFw!^ z!oNRv6Q^@XXYv{OKMZ#x zq>}xfu|wXPV|y?Ses}4x93&Hh(nImm6?nK!>u&@LB>|L)0vyKna>j@?e*Z)?hqFal z5Iw7|XjOyMm{aCj4F%nO!rvawj;6(C3GTw8sVe0FlqF&q#62{}-SqE?XEgF_4DW8U z=)!cm9q~xAn!?db`l(8BR5vEMBMfm{r#)U#zfB2y)5v?r0>p78$3GC9nsrGoOV@&- z)D-Hix0IG^O!rvvn~S41D#Az^+CHKjq>7Qy9T|-!8urG)wa9guE8QdNLwr$C^es=u zHEZH&l9v1TTrLOvIC{2_7szjtwf@sRJqMq{k-uEj)J>&%H>V!*L60?wr+G#xFDIZi z+Q5g+3PQk-CepVRDd6|^4vDf9uBcHAJ{Xd^Zus~MP>iLng^r#IKGG|;tK+?EF|OAZ zbuP>7u68AQ_4wC3%B7zutf6*tE(+R*uOnm$TSiNPpjQo6PvvKIS6;f+bRiJ>_;FKc zon8(8<_KPxPTwG0bL`%XVrwbC2zBy<{1=;h0kCIeR-{8>QY{kM!t&3EaknTXjf4yf z(kE0~fTP9uCNBr)cT;PqqMh??i2LN!CH9B-cOi8_Bh~Tx!?hY2lDEnnCRbT4I(Bd{ zTNRXEkc1l3(=ZU}<1lX0aeJ@i9)otZL=5sSbz@6`W!ge_T@~B?kIuweehW=_S+^7k#^ng&?Rs97V3CT$-VNN21bL5WJAxkEstx;zS3sPc6 zSm%f8rM(+43I~>aiOrM`9r(N*1Johrmn|cLI zX@7jNd5-0Lu7egAiHeP4dX&<8uvUU@|0Y*-ZtW>Hm}BX3xM-?#Kv5qRFSv`xWFe;^ z?*k8nU30*z?7JaIsp#9n9kcEfs1P>Mvd0Qj(TKE7j5W(*m^8SKD=SJZF#Fz)2p3kzIKFc` zt`L^nd4GbPkkrXob`_}!o4A+Wi}$tH=2Y>xG}t?pyN8p%R$cYSI4yvmvIjx!E{~-CJXku!6h^ znYfvO-$gq#5!=?+2-R5&hFKT%(2HOd4Tga5wY5LxtDER=WqN29W!(p7R~Dx16DGg6 z?VZnQdN}@TT*dQv0q^zGhw&RmhGZ63Mt*ZnLe4L5<+Y=&tj9txW78JtV@}zK@swq+ zgrw>r{m6A?sxu(v>Q$MOtTpbx>{)XSanK+RW%-%-8r0J-%!*0EqBgj_iT3jBI&YQw z;`$xJ0|oTGHvrY!9g)BWw7y-OB-aSYd_!+~M>j)jbAIbY=n8FX{OWV>Xe(ywYx>)6 zZMm0{nK>DDrUtg{_Fs(MQ?F=Im!RQo+qQAGb+&EWwr$(CZQHhO+qU|2cdAks-$ng| zm8{InI2!&5tXm7OmK708ReMELwSMk||!qCTh#ijx0^ z4Lqc)Wh-Vzd6AwWl*a3Bhf5!&W;oG&xFGB=yjZ)-jcOC{NFD^287q1t36QNBam*BYUceJkcLj7v4v*+m~~~`Nf;sP$3vZL&1|BrE$6$k z1|QpG-~Gr#6kM49Tv43x#F|MX!7;Tun0^xu$V+Y{$oXqJ2^VS~W)EFFSV?}tDf{i6 zBb$@?nD!sAQC{z|X$YPDO{CVut&y%n?hL#6OUA(|MJOynC>@hHi^e0?i)b|tIS3A%MTO|?Tb-|!Q(dq;L_YLeuy^x z??;TU1-?2SRF@rnS`Z-hX?ZDO?+ zAw!;MYK6UO?Y$8@nBv#`*IHUGBM2%6)ufSk%d4jC_7_3pklw;CSHGlR@$7?VnqM&~ zD~oo)Sa-Bdc?S?rwy`#sD%5qlmAU19%;CX399?}xmx~s_*TP4-O9O13E19z=J=7#$ z3-4D5?Nt*@B+E5y;k!F+`Qjr-GF|c@uD#q3=4^Vh1HglsuM>+KPWGt0bQHT*HxnX_ zxEPfpVp%0>v>GB)bZq$35Q)SV6dD?``f{%EaY2>cUR#aaQ@Bd!FI4;t#hN{haNkq^ zEn z4)JG4nKdpujY}LTf(}`Q&H(lR_?y+NjMawi6XaUE$fnywxSVRw!P4`YzQH8%ob>ln_C?0#wa@2a%)^VR z1?DBlCH{9F6Nti@)mAZxF7J8s+lC|MWpmP zr!c+9anj@6?2guanYrGc%g5$^@BuCIYMK?f=iI}Z~pD!p0F@Y*}Ay#Q6Ybq|_)OHIKY^ODm zKp~Sxf;U8kAYYVsWR>l69JYwWqXl#P*wK~3q5uw%-i^;_=6Q^|7_kZFnhMn4`i}1Q zJRJ4KO`27-!-Jk36=V8I78BDBm~*Jk<&O=$$~1$p%FNta?s8cIAkGq6N*&{qMj_}i zj6X_GGizUjt!gSIhvr|aF&S}nEY$5CQ7o)Zthd$na1;C4$dy`D{5wYdcTbk+g$|h~ z(dZOC-$|%wwG5ipO)|pQlijiJdWxjZrywfA)XL;Q9bnB{WpHXwcboD7*TTk)4o`1k zvy+V&;>^^6pMey3adIqGq)gd!U5O-d3~^tK*(>kjcK=VZDo(|K4Xy3d;vM*PgboBm z1>huF>`@uS=Wz_Pnla+QE(>02MT=Qe?K7n4)7KrSvDGNkL`a6|4MMsJ#2}1<)};Et zVay$r-9X#o8t?mb@7)fa)|4C9z`SAP5yOhsRAKd#Z>UpYsg5O*R(=r1DWkppAGUP= zOtiwXFOgxRftYJSLpah{87T`nVB%c`A?alWjA`sso0f zwTd~b{tmsF2E?1@; z$R;h&=w4`u3^`Zirt;S1cB)fkjUfC~zW-QORaNu-^rh{kS zrO&+H8J!Te8QvI1OR*&3<-o>Wjhrsgtj>GO5v}8sPTb$(m&Od2(tZ1Sas(cRkPVwG zYZ?WZpEnZMHa$^6^?P3Z6R8Ln7huH^lU^Z%Z{grBlsR4 zCu*}6onY9MX11*C64J=9m4>FD$Y8KNW3VYke$=_n*uE6S@{~NP)vp1P{w6g*=dVX- zCZeX=Pa($VX`gBx37o!4adIP=;b!#q^Vy&@yWDJD)Vg`yL?c8qtnI^@x^_9os34#B z;s?tE^Y4%H@f}dja}tHY;rBUmi2wtIoI|C6YRMrdP94~P1e72>{05MZLjwRqUZ?aK-!2>v_8H3%HoP_AUY8&bbb%MwLe9T#)Jm^GB0s*d zk8Dxu|Ikt;_yC{vZjg?6%xF&gFHxQko&Y9o~@Im|zsiU4nLshdo<9a(Bxk4Hd=Jk-=N_-b!)eUkjn8h16*<^0Lg_BfU=nXW#Jk{%n~ z_oxb%r6G+`(3XdQzwdi5pb?%)l;_$1eU|%$7laa;1Cty-y){P0e(~N4O;y^*C@+8i ze6Ty;(@_(n?JWs4_WWrhl>M`5w_Fka{oL^0#W$< zTxX>qR_wX$LNz95pGTCYDFPXY(tB^9MI4Aax+CN>qFKrXDu_*pO_EmHAFjG(QbZm6 z96G%@*u`zNVFNM18aCEB2jnWQCH+!rjNH^dy_+*%H{QVBDQgi$(-<*{N;RW)8uCY- zQtY7I=~Ufa3+NHUu+%*|)uCR54Sv#3n$NRH-7E+)6$3!J=S|_UbLsM|ZJ(r;C$`TB zQr=m{*@Q@?BuEzd%XW4*oDF{vnd8Z!3x;*WVoWd!c2_MiL7XW^k@0;_RN>A%VL`1+d}vJQsb9 zw3wY7ohBIb)s0p7wqUNMQezP+c`xpKRO(-aqex9TK72}@;$k(bwg>68=yUQ2mJ${^ zID-xN4P=O}{xqj7_m_U*yGmA|3g1C``0ekwWel-wa75*Esg)$;=fUDILOcW#m}r8Z zTw-66yJb$ZA$(9AqIcGO+U&tII3d;c$@=6rOy$NJ`}uVL9K$iKO+kR=6{u(hXvY{8 zAy~wY9@IJAq+Cxl_bj+m0;*wPl{6bjGDpD0pGV^eN!N%`4CZ}OOqnXoZC5Cbwjv_u z5bzveH7RA=21L09)SQN>pDG>V(tgw!(&x#0k+kvWt!sS_qxx;$nT|%@r-*v&x+r)Z z9q}l8?&nw+an1)Bx7OludEr7J4xo@tS?oWa8`++3C1%W~Alpxl~$uiXn^VA0hSsF%~_byuQf-0#cTSbTrvcu@U z3)lvdlBHY5Ex*a^P5T=#9-elE4^H>)p@ti?G>+zAg)(BvbOcUhD`Adt91yzthl8hd zKqXohl09RYWSeL(De1NeOm&%$M?0owyShN4TRdcX?1Hra3J3!eBt+(>4L!BBx+wTs z)#0&LX77!oJn7u&)9dXQL!P9WmlkfAcAG)R?${CvFM-|92$YS<24FZTLr3L{Sq_e4 zk-FkX(+C41Hei?OYqR|CYz|xcWJL4GFoKz{JgLbh$kZc2;jAw?R)hH7TdvS=Pi;yh z<5Q?|p?m3yQeB^Kl_WJXpYvDpIDpk8}B!SaFcS;JY zdjYmMfi(kGbkk}sEyNx5-CtVi=A)CwR(3Va)JD&SaPKSJAQxkLr$iYEF6bwhl*HtL zfy#~Wi?|3JSG4jH%-Nene-JCH{;qqAYUzQ<`P4xw%zpHV{h}McvAZnG0D*Mu#N^jY z&S+@0sGgM%HLrh9ts-SwCtp}Y3?6(Jp5G*WBesOUXGLb zQFU^89Z4VE5)!)gruij3VdB3>rbH-~n%{Zq4{=s+?ehMM{lun;MPalLkuw`yL(8HmAfi{0Qco(OGStFQ4w$ER(S*OqrA z$J}g}L2q_nZ6`mC=P6 zPCgQ}l578J?e0Bo8f*nSD1)gqzPQ?aUwFYI9YW}PJEj)%hTQD=x{U<+^;H%`noHOX zHtomu(2_53i$J9lBcC8fm(MEseR9CAOP@GlAA1>b%_%&aLZ4N=3Sn;%KE05)Jw~&% zAlD-)WD&n+UH}OPe1rxZsk=&~DX!NK_lL89b7f~C4cA8pGM@Mh^@VN~;m&3?@ZA9m z*n^ZC64EOMafz_~Je3I1{$Yx1!)iFIIz;kQXP)f}|^8TW8;Ql8@W&e+i%FOg%aQcr?S=j$$M1YNjmGytk zs4oAXQS*n)^5X?bA5D_3rNs365lms$< zmrmVte;<8zId)xLW?Xc8sc)!#R=r0Y2j_%@)*-JUR{09+h!EuKaO9L{)vzGIA|nI( z4FK@)6hT&if51WS(gqoJAebd?e9x5`>?qJ;%lYfwn7Emt%B~LqgTjCb6&w)EIp{Gc zz`!Pdtiwje0GIQ6AjtD_DCDrC13ZDqab0I z*Pe!julgQgA8#5o4s;SoVE;mc9>Eqg#A|4KfDb4e>|M~Wihxi5+gG4{j+ty8QxAw6 z{QzdnFW_ERevcgi+95Ff$hYlqFDU>Bkdr`P9iM0$G!W<;`Cq&c&foa^#8HATf7d>@ z1Af0f-Q3?StNSenfkG~zABJCUt+?>^`k3(Mx&Mc#^8BB`_Cy8?e25I<^awzR$iNbZ z@cq9r1`xtu$)Ioey0l45SQMY+>RzcoGHb83=a0Y57(oB>0Slssn9$%4zk>gGj|3y+ zH{i>6@vC+6H+s9b;ENaHXZPLg&CTs=<>6Q17hi({X&><}6>nA*|6g&(!|V$z?`Lxf z=*Lw1c~1rc|H#*}xlZm2j-pVD>t|6Ys19ZfufCY1N;7x zA25QiZ|`?uzZL2v#+SM4-s`J6;4t-MSGA&0&#Y8;la!1SG{}H{4gkPs$W0t6EO2ji z4)W$Vv!5@H0xEjA6X5k2X4IJ$Q`WsekAF(YJ-Ur5)7^#5|;pg~6 z6b(Fpi`%Q~7kJMUYM{el?>B9)5mf(suJ_ot82Yha?{4xVQ|3+MC&jlH#;%PQ2P_Ro zbkJtU(bMPlSU;MvGI#7D?+aqKK{&(@!UpMa;xsLTS$R)g<_+hBkE6LZ@#Qh$?{Cin z$|$By_dBS$l4OJYrTARAcfx(>u}a_2U306T>`L-w$NKoXkW{itz)V-b)ZkWlCgf(b z`$M;vQ5h^WCfxUq*~kBVBiS2^qsyw{PF5^vuW>I=vO_aNR^^mb+IN4CflLmm5|k|! z=QEmX;`FN*#AACFAjl~WfzX9WrxVqfgYN0ZjK;2LOm(u|KQ(PNJtWg5`}+e-Cu2-2 zoq3O3Q{~oTwlq>oBJ$-3?q6*(_D0nHR1F}MAXRNZcOQ+K8k~!LjUxR`p+9|gQQkyO zZ90(bTFD(wqN*a>|LNZCYTjyhc!l}|JIk>tn=4j{*E81DL4k@~G3^{EtmBhQ7iL5aPP;P`UqC=<&4Kiu9U#<-_UuM zv_+||wpr8g!$bW@x}QzBY1b*hw?{=xJSobr@__#=Fn?2XOe|yr=3`mQ<7tf$f7|v5 zMP9o`9b(eMdm9;|eJUkFiI)Tuqb@`aeMD9o&Aq30riW=n{)aHu^;SYNT-tdps?}#B zZ2@#cl0Lt*Knxj2PO6%`9U7YGJE6g9{yM-$azo-TwxPS~_trg&zzFJ%_nL~KP#}BH z>M9Xoo_w6s(B9_L4FUC1+=7>7`_+b!K`8kEclmg~wWrl-q@bwFx8<`06Cm^YN~=dC zE)*N8_bGU7DQ5-|%%{{LnV5zIkHB?%YwrS2@x`OOV+Rrk;m=&y6@hl}`o<7PpJ;#s zZR=F8V^5K>{!QS|eDz}&`xwaO=rGVE=&O?X2x9e>2`JvmV)I^nrypd`x$)u@wEsg~ z<(39lAiBw1>`)jWz7k_(zsV_@Rv%AeaonA~!ZgAR45Y{;WiIP5Hf z`dt&|#y30dI9Xf?nLrCdz?8HWrDhA@%OS>Rp85Qt*@w&VFD@73T0VmlT?Enq}EF9rj*vd=SIO?KtHnIJsQ zh7`lRwib5NQ>Or}u^Y?9wpxd6NdS%Re?h|B!huw4!^H;qN!|1^+tmZ%9pr_bLk7@a z%H^4e7w2*KR3e3!7TY(}s5Nit60Q!$`x3VSw%}a1+rXeYF?sf`$Ir?56(UCAIQyvu zk&Xkw=D&1ptCvkO9i#WjRz}W5pzp>;KNp#rd^g{-nD?tl(4fQfbm$dK1JxqIee8tZ z^M{Qeb2h>GXJ$O_Uv(pRwAaWjfBYJ+KPi-DY-N?)q9 zRR7Ar@ZDMIk_*kzRSDl`+1+j=Hq+KLp})tc8d0m++yLrmDfH098DsEC6XN22t=Hh4 z4_4GCGtCpb;AqAvC?DbnBwdiS8{3o~@=q~fnB^ecHGV*rdep;2lU?igOT4DCMcZyD z6>RIs*Y-qRGmhJdHPsjDw~zfrq-vQy4sp?Zz^v#fmNHME8Vm+#P}!P_AxDMH1q)SV zYAH8=;Hhrh*0Fy-@{(92CDG+auk%I>(Z2D`HO!>>dCnqQq;bRWR>(sU?ePrNa2#3b zEmKu^aaR$fA817B5cNp##Ta<6!DS!bTauPBwaxql%!#08mTr#Caltb(tjFIHr;0zg zu0zpZAE6muf-AwJ@+vRdkJ}?%yiyrL*#r?cPL(%(xq#~X{wtZ5z~gFM2B9yajHF+= z*#3U-s{0Aluy|_QRh9sJ=#}OSxY`L7np~SG(+PUmHAH)*1TpcBH+z@MK(CI9{M1p< zcZg;iwTdK#h63qz77J0bBbS3{U8L#ixWrr}LQaq%N0&0PGcMa>kuh;Qj-Vzxvh2y5 zs4KV;6dGLG@;T?eX5Mk}>L3+IkzF&TbBC=C zjBhV2-n!Iqkb3N_)al^E^oP8aEK#tH1sN%NQiV5c2LYGuMf5_FzO`+(`c9Yd&T!1; z1p)jLcU}dd^;Ei+W~~f)h;daP0NqlE?qrPdm3x*Iye<=v>4?VhOd2bg7=W^_aDolB1~1jAV>DyL4a?xC{x(pt!;Q zr{k&+wln7^LWA7aoqUpobZ2!JO+1N6yuF=jEPVa1l%-W{r#W#W?KyJ8zj8^8pqL_y zlFe;<2tp|jt)5%Z@r_54GgtzLHfE&}BTAD!eNt!^T0(6(z3-r1<`B`Yotw^==p3Yc z4>=?9)Vju&$q7mK#$9=I`)f?Q@r_G`8RW|{Q?#pfe_DNrpGjrhR{^@zjN)@`$f#S* ziwF*w!`1HUQYIS|X0or@T5mP$5&xaBZ0gKXB|Bjsbdqj)yi4@)(Vcl=EG`n z14nzk;hvtcjStMVMsIXcR#ovjc%CLry!}fSbm}#0e6XtbOpCLk`htR`*~+EQ(wJBe z)%{`fHNeakM#J-|jg|m+BzHG!`eECVe^Mu4c_nIj%V4b;44kA|$@kKJEZ6vytcz@b z-)w+PvsHC=g^FX}^Yd8?D!HSzP4PwEHTbHoFyn|kgb%f$`6S%kX1j}sq-c4fD3jBn z=spHZn}@abSKQjnwwYH=%bfN1G&Sm#Ua4+iRrQpFqp1q=^^}k4ci)$yGCKdyQH=83aoD zF8H=CtREcist*Gb;s8N)sUE>&G5gB1V@sJsvyOl4i2lj59~Y9Ct5a~n&xi8yE!R=L zBpp;>Ty^Lf9+uv%cO~m)Gs?k$Jb$(%TzG>(VwBCMzB=wf;3iA6V8E6szs{o}?zRjo=@YK1EH$0^XV$sTgQ*tsJ z=jB<{_wyZrC7Dx@|2@p=f}u@cSBadNQHDJUUKzG+Yec@5OZq#-ik|!nFzz%QB(y(a z89!=|ti>-5Pieb@tJP%)L#UHO3D~u|Gn;{>q`&K(tsiRsr~Z7)JM6c71Qf|nBLQ)W+qjVk zf%gE#nGoWg%BFx(-r11gd(`i>YD&@}zrQ$LtfEOtNM!LymF4`T$I_y-T6DQnYjXCb zlymNa+#_TUvCfpE;@}(DIkS!}ahY5I`D(%Z_KH#?+9v^21fw@RAIm_XEMFP#cntjb zw6N`8>ZUfs)wosN?#g;qmtp6AeY|1Qti_v40o6_z&Q=J~o)u+@4 zU~~sDzuT)sWb+ZKdy02(%~he(!c_LneHL}7u$HQ(w)9za@+B+E(9TqXP#k6yrN^9| z$MnOZm)xfb0%r5=VUH}0KK>NLcH*S6jJVuY-Y%Xu%t|c@Y^im#s&-9=QhPIn?s-Fv zAs;LtuAuJrS{EWq#?)=z_U{vNW0jdwti8OiIzZ4;bkk8MIF)wmP3d6$m)3X`4KF6ES5n)& zG^I2-f%Ofbgqcy_c*@9f`+NeQ-^w|EpazJ<_?rJNW`AuxiSEuJQ}>$;{mB$B#ts9oX^KJ*x1F=;Lm1&{EpC?kx-Bj6)C9 z(Cm15Zfs`me9D8xR$vQ8C&7~B_$6#9)P?#)gj-nw^5v!>xrRRVqt$UY?B~9b40Bix zt9V~i_xw*>#PO!~YXcf*=8VWjb;|-KXVK`@RG&Qe?laB?8Er86C)}KnKdJgr(&9%; zyzyzStXP?{vKwLYKqK@^UwKBfW15=y^mnv+RH9be! zFUecS%XoKfBr(z1sMNYYSfEOYc|{9#*gW3c{iZEBAFfH~M*;;gl3DGAvk>5)m?N_N zfkX$71y8tQ`AjxI31_qlrf=SD!=Wmh*~JnP3x`@u*`9TLX&JUM)j33{LIdQ5v>nvq zz4`Ypb+`L*gNP81i_5CuXX6Pae2h#)>;3Vx`$1~b@X8Wdg7#-wKPITnwC1qDtETC- zwoI(SRhCi7-pB0b`bqBFKXeWq9rn|V77(aK&knmTc~xV(&`lE{gpq%(??sZ%963Eo zf_x{OcS;7=|jsd}sHdmNQUS0B^oA{h47Z|m&Lefj4zEpG=nr6u2tG(Nc$bKiiv z6(#vW^c!rC#FJ+Kj3-1tL|6XR2oy7xoH3N^+Pc|JMhH>Ag}<*HkB9yNLS8-Rs%7RI zwOO-rv4iPsL1ev!Ey~oZL73GNR*X;lRFl1I)_zd-w$XKiV~iGp*F~;J7~Sp^)1KWIxv|sh{+L`;lmM$wUejMX>;3{@bI&VtIU@_8tOWXc<miga;x5wW4P^G?aXxQuofbrD7}`+jRIoT1E(z>P zsw{^`O`t3t^kU9*oH(s~w^(foAvh^(x2M{VwB-IeRfA3;zU^{*87b%C2{Sp+zHhgCgoI4*6OH-v4!M@OUqX?g}^W4;VPH4{VA=J z?j#mLPbId{QiN zSeP04BLN?VtBuA_uxPpKEt%Ta!Py=THiN!xCy*7IoCc#uWDlXWKv!-q;NeoFbu}yI z-l^*wanI(asr=G`W}jTXs?K1e6Y%w$<5+N@cI zv|031C&SSa-6KrMKa5NoUW4iP{HZawaSkvbMd&Si>eV24jOb^2~^{?UYKx7P-uswG)_ zQzkM>Q6i1AIJP7!{I-+XDy>?cQAW%_WPC30c5O}0f1VXf;yfi@kxeMJ0Vk+$i>n|V z1&92+SbjBjEo|4ZEF!EfnN$@Fcv|MlEy-+1mr#H7;>GNdhAZU09_dj2f!%&;y~+OSyUPZx8oDqLm7#eKyQM_C1rd;ZifaiK2hm$&bGB>i(_WW02oYX zVL%axfJ{DC@YY2^>$d0Yie5gJP)hN4O460darC|~?e*3aizc60{W~;3pfjH()uoxG zmMd`hBc>K}MNeqXvj;~`YHG<1rVctAE~7hpHYy#J6M5-SCq`b?al~~~F6rBD<2Bwd zCR&m*cw%R2NyV~+dDW4t3k}n)>`mxcyvL)=H#DT_XXVs8Ejid;2-`en(pk!lu&qA! z>B;)q4rykow8@Oq>dO5T1p$00%%Smt4(-xZl8d-B#?0}lpb{YkH-mgHb&Q4`6kV2< z!P_z9*6FnoAzwDA$hihWzxs-EzFsm-gQvb?>ii3%aVE`?xawZ6GdDCQ(JDMV_apOW z9VtomWE-WGrRoRAX>CPVbcQvt~hb@aF5+XT7M))?S)B+p|$_s^w{HrRI}_(r_0T(F|N+*yA#~Om$cm<-q^_# zkW*d-C0O4k#nyiiZ5|(I6vKpg&e*viI%#&BE6nV>f2R`|>0#5(jmRbzXE$lpGF7#P z?V}oJh@oA%_^jU%w7Z>8_SDvbh$)~&?AnF`c++#m5bBxMKu_?86lr)*o}*$6qlF1m zA6r(4LuBpSAeD_3t6`HXkJO?d)!Z-+q;}gxNFh)0LaoQD#{T<_-8w7R;k9i`@o6TN zwo&6xE5aWv;W*S@ocimxwJeg?`%{dXpXyaPn{q)6MbY?Hv60Yd;?qo#%9~FW{g;Vs z7w*ugV}W)UcPOzQM&g~q3Fxu|Wt@hcfTxn+_02Jo8vBoA@#`@jRoFM92U zzBqYh)esXDFUPu*oDzbQ59C zD*>(?23Ay_vlx%Zl_f+O#QWYC$spbOO0ppJU4*BTCsw(5GwX=*ch`Y}6E7y5 zmpV%Y0=rZTqRbUnSV)>Go@1+qV|!Stp4}AI_>+$%kDv1?J?eo9aIx&hkOHziU>q%~ zIZ5ie(6_^2F^(3tHhLRIqTE9wohkcUWF1oD(741dqcPdc_Ms@n54;*7ZkOjpFoTR3 z0#_<4QyOmu94;syV3V@jXgxe0eSmmAP8T|8V>{&oU=hFb{GY^DTSDg* z{kd94jnaH)GDdwJ%BatLH(`Z%;O=Ucn2hg^k^jbgGTL|ng}-X}8XJ*|>LO5PC^a<2 zE7b-Pakv2LX}_Yvz&Wv14(%y`RPoC^ter9>8GtZjWm~g86o#&OyCfR*D|2k_Z!98# zg;aom<1Mkun4iWWwjhS6J1!_mu}fOC*pJ$qh}}eQkxqGKG9$0!gbF%}7g2azPHE+R zN{hcv7=(nt_TNsa8ta!1Z? znDZEm>@5D#_%J#;eYtJ?YkgA7^tb(+iy{eUd#25D>al##w1@IRJz)t=iR=fAv~x*V zndPfK_sk1q(x80nyY^84a!e;GOw`QUoZ-j^MtsE#_}^y7MR;ZE&!9`H&3}VyM*Rqz zd^%aKwmM`5BH!22Xg+Hp@5PL1Q|!>jlYm}Pa7p57=)Cr0h# zG#o2l^wXLNqM_oKl7%YY`H#FJfHBVhL4jH5|C0i;$fqsJU1Ju}~}_uW^aZ~?(C!Ka2m0xUPrk^tt% zR}erD2f;vI3JG%z_a2Dkn86>nLl2^L;=8UKhd>V%Ssoy-#->w1;4ME;jYWd-<0Y7xo^Bc(cg+ot$!dpeziM;#ABLJY;g>ne&?W_Ud zw;_W-_T|9RuPgzcc?#_LW;y?`-vR%0VENVM-T9vVMEnSY1pdN-asDOZ;_ANxz`%jB z3uzYw__+8RK;etR3jpK#aSY+|Dx!DT-=mktxdwQ7$7xT`r#+4UFtYNh>bw&pmPS6I zIfs4nQz?+I%e*G363AIjz{N#im&A5o`=z8W7DoKC0vzPix(pk07YP2N&N;XzGt(#j$5;7d;d0*V0c&zG=31Q3P}aBzD@^c1;8(ue%8N$~|ea)OU@ z7Jdi9ZYb#oGMGiU#(ThLTSo`tC-A`+0Q}p!zsqT$ukVLEg$Qcr$ER<1;Ja2&KlDC} zx9LtYg|7!Y040k7@bUaPI{{WnOAfNdy@&t0JB_Nathh4Ia{Q@%=PNZa0pZJ+=U2we z$0vjXf&dmS0YFk8x#!!6;ivCw4ERB=f_xJNAoeSc<|*k*e)XyP>hB8+2EVtf9_>24CtN2Qn@*CRs%Zcxd@A|r{vPbv$s}Jhgw*~yuVEB9y zIAEcR?w<|t=G&Pe_!Cw6X9)7-@P1cC8U=$BSi-LC)AtYJNj2PKC_84KT+AQeq6cuc zZx+29diEiJeb~?EJOGd&{=DA?{nCkf*iSPz!{@h6kbb!7-dLqTPNFOy>C~_`5P&G5 z0N}8C+L4vX?2B(0xUln>jF@zXCeL;Y=hXBAC2$K6+A1Ff>V0%%2-+W&H1U|7{ zV4!dC_>m8Gg8mpAgsaK3s1I=TZ}^|mVP9;LIzR+Ed@J%_k)gVxoHcT=A37k0{oXm> z&`5oE?rraXXsl<6F7Qt1bNj2@RS1uS9sNNob2a_d{rf$`NAQCndXPQ~A-XQM+A-FW zh(!v<3;1-mZ7Q(aEnJfZnmAXsSDlN4yg^X_eR_x$Tn_0&d7u*0e+wQp2Cg#?!77ZaPP-BD2JbQy*DfG#51-tJgo z&hc61W^--TnJnAP+(m7(opm&)M`cVL##T*)T4@UZnRHEk#wp*k+|a4bI*Z14_@^h? z(I_JCmS(buL)0bS840Uwi{m->VXeeb+P`uwv^dUWhbhSBvMypj83Sfo;lF;Y;IcYp z!`9}oUoVrNE`buPtARIlN$ws?4s|TcG@Q~Q&8HfS8!=lkL3*cqpv?y%r2R8f)%aDn znloLz@^FoBK~u8(kiwGZ0%}S^Z$OE>pNol(cdS<6sJYXk?e|B_%Vj@XH@>n|6^v+~ z%qz^_v@FCu6}x-qKOz-#i8)R4Ye^9T;##?-BSfmAJ=M^I`kO_B^Ok^R_< zRVp0Bu_z#H*q@(~uA%f~c(u9|x^1=FoD(znN=(f$O$zX})QxOhPdIK`Q~{(t#x zDlJV=h^0Yy%!9QUhTaYHI1S`C&^nXZ5`j8R1gI}!6`2-oL~6us?6g?(;B(HYFLIL6 zskUaZhQJxmwj%mJ6;jf~-~5>1Z69Ji1?(kf!N89?z2@kYO+=NS;^^ z8rKX+uQfMM6urrw!=R&GX;FF~2Sz;K>AqP`8{D6R*A_U%Gs5Ht8gOp*fdy5w*ggTm zL33xh)}fQ$bwFgNd91iO^Y?vJHD4FT)>wPfT(}0n!9`5mp?^(mOl@$NxT6zS|9ensDHmMLGw#_KL3F<`$9BNKjm=T(P{=Dn+Vq^ zb~i^FQg#mmtkgLsls8stO`PErF?QqbWrw*b{`;1oi^|j~_DW;$siNb9G;L&M>h~1nVs!l6 zSZVNKtk&%W6Vz%5&+=2;&$xxJ$*{7X2A{a0Rk}5Mn4eq$_(fRB-xYCwEV^Sr^k#J^ z#?1h5%V0lP?owA!)^lcD@)F8}<=Tnc8?^DLeQBs91{x_YJ(G9>*_r&&z!^n*%$gN7 zbB*2E-TP^PZtLJzhBJ9dAX!B>Z#T{=wR|T*X~ER%1Dx%)!?4Bq42U9;~`!r9!-y&os`|o4@=DxKtMJ~zwffSwoM+Nn zc|X??#TZ&l@ce8KVZUR?V)zZ-`!e8cNz)X89C4NCMjYg9q?$3)N2g@KQu`3Gb6d<8 z#9^lm3HoL;idg1{vN=xEUdPz;AlBV)r8axopMoB?rh+$E`(AR+W{sc1>Y))f@pA|n zj4Q_L>Tncd{Z=|&a@D*c=1j6o|Jbf_&hs@%HW=H=>g|eY|ux* z_M=xT>p{oH911QY$vB0I>+k{bC|lj7o+5{O%QA-Cv{#MKHEwujy3HWt1Lj@C$;Y$B1eHv&U}W--|OYYmT3bkHD!d+9!=pbvL%Ax$o!kYYxiJ6l|>Gni}FCstYpI z?%)$E>w%sq4lT@b6Q_v&2?g0{NeP`U_t=SE!fPpr;G9Ezx*8-mSwvbhCU<($c#uy` z!w+@PYNb4A3HMS*R2o5yEn*JyT|^V*y|To}CkS3g9052b@%ekg4E5IjfvTV^_~-XAjq?o6MKH1W`emm)Q=Cs zrTJ$U{8$1_u5poYHBviR9M-WCL?|$~6t!V06JeL}1+gxF^l-bh0shDr7mC^PYw3eF z*Z7?Dx5`#fRF(vqdUwc_Ix|(Y50@4C%}|Za)OlzTY4S&~yR!n2w&3Nj6VF?Hfoq8d z*sQ50L;Y?AZmIFm;BF?sK#$ao17N3kh+j&8fD=X~Tw`7vJCAtr{GDFCL%>Mrkf|g# zZP6qPpf&B1qhUd*7T03s!J^eiNlrTdE%ya<(?#96Ee95la=K$eVhb)|gS)gN!*7sY zyp6mCqnnlMBh>A({k&#vfeHTLT37uWW>H+_%ox9Bm!HD4L2-b=kzL6ueaXqtl{LN{ za8&!qj|7$8`c+KU8aJL|3Ep%rr9!j~Y@m2Ie)J4Ie}m{C{N4MFF>ElJCX?DJkedD| z(S%?E|NB>)%WN*g(Qdv`K$*H?)52`X;ZM0cE<_ZE z8}$P%)ekXKofI3|YE7<`t;%@@z_RFVve`gEo`4Umg&S>8&x1FKmNGiVW+z}MtxUg3 z84C7oQLTiCl6jhq#}U}QC>|;jvd6paVn22k_cvz^(7xGUEEj|Y&nKiamTd7~hqP^? zV-JrV)fA>|t}*CB&84(s0o<^2gSX_1|I{Ew=&f30#I9aH&YoNzYUtCrGP+Z!#a$&l z{+X{n>&IOH?cG7^@jBRNHefUd>g7C`<<{&S0}sB$Y_&^I*47?trmx(yg6^U5?$2sh zpHIO=>)19+aca41m>9IJ5+Vi?S|sJSG)kB5u#c6*!a^3m6Zmlwaf2B7+UfdRD5|)x zEn=km-6x3{Qg+kiExGP@Z$}aE;#6`ZeXV}!yqcz2XFJV0oP1&$qPz|0f{WDJ{208u zPPwoJ-Si6oDH4C=t0rg#ULCk|yJ#gaeAQsIOg17M>G|Yv!jBOf$j6x-uTc$>MKUKGFX+JqV;E0_uz=pf{LFx#&+jerb({d$1urCt%BJH8qv0p-W^W^ z51#+im#deyz6L(uf_e09PYo5mZk!W?CY(>722wdz} z_!aJ6ey#g!q2Vlh;RBH2m<2`!-B za`HBDYDJ_=2vuBLWiSH2kSDBhoV-&-7S@8~tIXB+=Vl!V(BP`8hT+@js}`x3*Rxf^ zyuKZk-)A~1$+_&(>NkUauqgy2hd)7{*xVGygAA^x(_}MplJB{LCe(OBp471oJWi1bh3YJ2TS#8DPWS1o8{cN|P5<2y}$?}owi5^oL>Yk*#x62N61EZZ5 zR7sjjEuFrn;tmsfHS-yGQ2&Rra|p8p*w$>?c2(MywsF$7ZQHhOv(mP0+qP}%RZm{u z!5wrDV;-^Ni&%TFAIg_VR%%*BM&#Z9HHP7MyWG*y}6a^C0mDKn}H>#=zNY|ygV%+^>c-N*}BmPqa|Vv$~;>tiTuHPmr!A# zQU z!GyV7MXPEu;1JTnduRnd@z=rYnV6|0?x1#*Gn^89&WCH$GQvW9=OA`1*{v) zJF-gdN-w>q^EjI-cS|Km3#xL%S?eyQYpqS{}!wgnUvj@ju3b9n;fm4@1k{A z3TyF0BI6EU?_UoNFim5Rci2ICG%>Z-V?=+(Mp&qk33xxFS}5pQ4uFn!nE9^x9@;D? zzdR^Y*G>$8EOYlJqF)0cokJV%E4gRBsv2N1F$ddJxaiWa8>kZeCI8CW&2W?shH_{@ z5s4T98r-;vF1WK}K(QZr0^ zEXyUIOS%xiI%{5soib{;CF9BZBLuF{ofP41|XFC@m2Ho3I!isu{JNoVE4n!l9D1cODb(S&$8NY5rsR$yaOA-mk{)dhh#L zf1RGmiCAplG)NDt{4(S*a4)?H9%)uqqKh=f1s4EA^mW;|^{{s|Ih4HKg;r#}W@J|gej{dVpnWQp<1%HAhPUKN z#;2$8^PA3u6z>gQoX|Q{q97HOn~R)3Ll?9@QZSS87us2vE_a*4zSJmKpEhAoEcOwK zu<|df(TOpv{cA?^8`&gH@P|JGvzNdlF>V@Knl@Ctxolm6ba@NMY#7(2>J3;7b8mYJ zV=}jBb6?EzEm|fGf;CTIIlw2w~4 z@wh5VHn;4%ym{it!_bBQb7j&Cp41}>3Y`SDqZK(c0dli#ys&e? z{PM=m8X-*3X^=JGVkO0aTIQHu-3z998jvM`iFr-vpW_GMMarlcsx6e$$;iEFvt*n( z1ogRQMr^#FZVr?1dk!>I(xsQ1O1iyBk$?pXDiUo3jjv=;xOEcwLUO>W#;G3s6P(7d z3=yx%2X~NM<(yk|m~D&Ard+n-Rs=q9fD)sQB~t;$k383NJR4If(e%nSZ;cI)?N;r| z{m4tO+?O~;*Oen|kE>9}cXospMK-H{eI78D|3qo&^!k@*neL6TPHw?Q=VjTPo>t=9 z?A)Vz{BB+IP)qXa){;c6qM+m=N`cbmxIeD>Y7B|Vn>q8?W@$MvI+bo;KE{}8{2HB3 zqaz|fATK&TDgb@!H4pK|SlZWI&u{exi9#%GQ^w<23qO{1(KDtd?l`e3D`5WZu!nwk z#e{2SDl^N$Bo7v2FLXPi%#S%(5r4B*kl_nvE##pTIEV=iF=q%>MLe_Zc?U@eFAbH; zmw-!Fo-YZyr?);MMDIbHm}#R;r}nZ{NnkCAzgw#|dp00gCaQ;6BUf+!GKsOw?htJ6pT`qNgt703l8}+*hOaphxA{yCH2Tz!%49gxb+12q={m~~aam6s*z;#DP ztoDqTkMwwblEVCM^|a9BfLQRron`NA$(^!!2Tq-3MOetpOlt9syT`sp$MlyvHrf48g^RR1r)<~jHaUOVe*f7DpW1xWu zIRN|Y#rOA3^=E5fPM>7`;^P{^-%F9vaK;MD}2Uu6Ns$UEekqax*C)-L@g+Wu0#ww`d5#Eq5IA`!*{PW?Mmkt_gzL| z1NKElUxYEQtRe^gh)Ndr_&xGav%ZF(>UPn#Ye8GzT9GY;SuKqc_;28GUbl@(LWhOdGQR+;YOJSm^*y{VAd9MtH7L+j^Chk0MJ*$T zQ`&W(Xrh%9OF$VQTgjrQP?uzKCnB>?el(_SDVcKIT!NJkLk9feIR4t0Rx$>OpQs)w z2^KI;FJjUz22DhcAh8m3pz5O>$K`HIiR$8)74RGY=-v@>E=Ji{z=sPGIjR0J6AOSX z&;~lZg)DGHD#$tty}VV7t!cq{vaHsf7MlBT{y6)%J%7rLYtw#kjhb@zF;-!pBh|LA z*^n$3IrN@`Dmv|p+`HK+5g>1f(Gh|Q`DMEQ06$CN5Z@Cm-MzzQv5KFpC*#IkHFJs{-tKruYgIZBW7RTy_QdvP@j9`I~{$~z#BLvOO6}Cr5Qm5z1_|M2E z3n*=s5`klVXvCRQqE#Z{d4fL6NIT`SMOjwF{FAncU>s?69@a!}Mg&eYx{;AbD#9K5 zm*Nv46Qr(+g!wTI=_kZfO!LfOQCj=6+j5!4E+g`p%ch0iP7#`K-6popL$5@+IW|hiQ$isHC-JtHjvpqn&xle?s)%y1i^EByfLYbV%TCiq+x&SOmq2`vGI5`z_w}a-e;G+ri?#dV;A(GOKy+A??&WEdMhh;{oi5s^N5B zO`4lAw7WSXahU@_ST0p_t?n>5vRq(D3%7n}BkJy1%JZS6(amJTal?P5L(f?XGL~_~ zkjBSo)~M4a>^ar7g4OsiRpmK3;8?|);Ob<_m6km==iH>S{F)G-{*s1U?Fb+(?q2k^nD{U8+u*qx^Q%BtrQ176-4Q z@m3TEaFUQ`1Pu`dv9>XY#fC@N4|WF>T0TFiKH?eYDjyXC1W(r9lpZ~%O+Tsn zMu0Q>wfQN-AKH3Tg&DfB$ZtAh|L#qFm>Cm-(BM+U6kxob(A8 z*!r>dQF=Q4Bl<17-8%bekgSivO>)@76SxllvJ)^;iYSN0&AdTs{=-1IbFs39$U{qx z8|7#v>~WsH`zg2+yc#5Gr)O?iSFCw!n3m^!ea)E3!VvzO9# z+%R18KAm0y=Ci92(=zG`0c1lf0!5=DG6VyJY|D6hRNj`fADm(+6&!)8kpb2!zc#wC zQKhZn72=%G2{~0YgBH#(lXIY6TMIOSr;uBx5dpTs5%N$6o z?z=jsNHEOMpv+X0EZ2bBO(cIMu__B_b=%A@5QWdXLG%@h67e$t zkF027ZAB-sryfr+AEeA1vyLa+JSF5i%y@2aPw(8|A+!j4TV>NHZKSmDK5a|F*%yFa zm#y_T{s1x1GNss8HC_jH>JR9^6!FJ%<3h&MizgobkW0b0*gRrRD!8>6Ph!N&0`Xb5?fN{|^y0 zq+H_FGL4u#U%8)?j>k<`n84{gAsRnH9GHMO0d$u*YT=6xm@p@ia*|FV#lOL9VL46- z#X{)U5r^rw9><%>uEg|1?`NG39?vRQGHx7^Vxn@nBv2{T;K2y7um~y;0&hh{cRnpG z2_-G9grv|BIDhBBFP6mnw1HVHFqpE}9v}i{xPYOxMM5;#PXbL_76?p*} zc`ckcG)&c3Or&5Hutmacs6T({U{3Sn=;0_3p^o-KMc6qE?Tx>mpl-QffKXsy9Qu0( zfR$abe(yo?gS;bEGEL&D&LQtZq~+rv(^u{Q6mF@w4D0YB3=DXAdGnE6qyE5L6%rA^ zy%N+;`$5Bj3VIIw?XB?#1`Xr7oH5ETVO103+3YkwhO|B zqhDM^9eOti28Kd;hlR2q_-l8EWDC^~zwZb7d5r^NR{k3lY17YlWPm*%8BZShTwYzz!~iKaae~7pbn7fES&EZ2keVz2ZjRk!veNAAqW>G zhYnnx&`4C!(dLrK1Jn=MF-zD{5M&dp7mSt=E&?Gt~+m0KzSY2ZX~0 zMhyiVy5}PXN{?iVq@CaD5H^KUx`PJgZ+>cp{ zF=8(Zg7owB_OhUj)AjdHVdjqSZqExptUtOeh@uGiG@O(d~2 zWSGF$CkCp>Vxjd z4r554mwrs)O^IBL1Tw8Na@9yv`6Mq4unpcx=me;%3AcP|5gvs>=SDqy)TGeN8} z!J1~ypy>H=p^Q_vJ8>IaDW;-(6bx}8#E>npRkxNcG`l_2Oht`?k1%lfojl=HE7g^0 zH7Q|kD{VHFYQf-)L9s&9q|@;H+KJoXBf7`5i@?oMxId~lJY0d%=-Z8EIn?)s%w=RO zn9LX0Jbll&034g68zD@BQ`R)hkn>8TNp6HlLk)M>b^fpXYj|~>lvzD}Sw=N}x8r~h zP<%x>jk&i^VR7rQqzlTqD>wAZ7E*;gg;v~D!io}#RlKq2D*zT1y zl7e@v2Zp4aW3gCww(&i49VeLO6C9r@SJW8 z7bJ@=B(XpT&pa|0NSqgxa*g~gKrh5Gs-fQ4tGgr?RM=m?McUNgvkD?HqFwtZ3KvI(i9TdYG#DQ zl}TVMpW6PcR#c4B*DEJ<<0|>YT89N^5^{1m^IOyd)F139}JUm3sL!2bP*^RLOXm!7&<=G zsE7(<-1g!K#`x}wQ+`KE;UV_TUB0dGaj$|7*UdZJg)PN&0od7VBTvkEc&hC`0xG(~ zO_x8^{kW#>FS{nFX`2+@aq=d~{&@`=s1f)(Ws-gyAu71t7l~tOglE~p4GB|uRMZagP%mU_zn-l~diJjdWvr)^n9Il&2?coh>x zp^7;sstUy2i8YIwpWH6vR=?w(%zpJN0{op5W6TAu#caduNdkNWlAEC+JI`hE!9Csu zfGZmabS;^oxdd0&}u=@Hd0dj_t5;a!E^#197&{3n+rG$&6zaMs=U?>h>Dk!-fZY!YEI_d-EM5Sv_b!opFFqN&;RIeIntEZ4_ zJTO!a(m-`zo8E1_xG}r3`Zd~7u8^!Ls6=aUGSkZgiF~}CWDUQc3{8P^hjz}O=UA~)}nK|<94Pq z>?~EaJ4a@fkuqs9T4M*cTtJ%p=RiUEStd<*Qs&L~(oj?L%(#z^D#Lmz zr{m+C$ksXMZ{?7zg(mmuX&&>}V}9C_F1Byap+f$fH__`s(fhvY8yY(|;%KSE6j22n zU9y^4NE@_k+=CG&@6yaP&hupPhdP-h#Yk6pJ!>M5R^pzARI;QCHs!+eoUdx%T93op zD|Kl&YnhPSBS$S3n8Ha%0@1}@mnbj4vQu1#xf??q>7`d>5U<~tet`=evoXcl4$r>3(66i6NfEILvZ=?$I-e&41s{9|i7Fmj*9G2M;(=han3_zc zRa;UK{7^Pr4y~5=y~#}xHtU3|!b;mIt$}o(tE=>eaZ_yBDk0|;^ADlm%(xc(siRZ& z97T~S=7$tQ)dEB%m?ZFR<$9%T-jaBZdZtBI%OZS6cwK@~UR|j@n%jMp{ge1Y*alcG zlN~%aw~ADW=sHt&X?#w#%RD3e87m>5=({-~v(0N2sccL6qt27e&npdL?vH?1n)++B zLIs9BOwf<)T+b)VrZ5pg1q=(4oi~G=gTDLGv@*M}+^TO))Uy-aD2q-yN3`R#tT!M3 z!+wvLJ(WwR*i6=cB1C0L2X9TRh_r*XK=$d z@lc+a>wKLgz&kXz*H!P1s7v9=dG269ljyaif$(_TcK=mWWJ1yMmhK`6Z}YPkHpjet zz>W;GY`-7hV+0jSKbjO|5MViM^%}#9bB;>1hEq!SWpcPwIUTgs#TXfzYtt2c%g z4rjKcNJ;SAr#WC(r_$^I-p@s&QOjIRv|)1;UWecr?$%eoRnmWw>q7NJ5CKzvK*Hbt zIEg>1(k6_asxi8*!^Ca4-Vn0-Rx7GH@~B&nt{7$G8!J}7rbVH4$M1ElRCj{rwxtQ= z%>%7{!WE5P3p0Nw|Ip)qrE0l3jh*DIWoeMp>oOY;*I1Nm`eJfKWQn$<4wU-P zy82r^nOXGrsh|9V}3WD7A0n6J?4T2&#IUo7fpG!vrFcz z3gj47X=xUGKO-y2O!L4#ulu3b)*;CHSYO^{cT&zmcN`|IUa zmf-DzGneQ4^xd1LyqIhGgW;0#vWfCUd`Qr|;^ane;zn#*f9o2SLx;2_-q3VC)nj+n z+L%4Nc;fx|s%Tx+uzV^d3~5De!|I781f9w&yl-U^9IX*->vLoJoJ}V+aoM)=-fAKF zR{=j%ALbEh04XY$ZL;g82H>Ui7Dk|WlR^$p7vO4jYL~`^y;OIY(rz__$P{?vXpBj2 zo(MrcWXygU9V*y_HfbLFs3kExJiJ++eA7)9dt$X$`cPcqPxJ;KO!`nn!OGb#)QA#r zu3>T@^32Yy$i~#qZc4PCg8yggCZ}eUp4ZXFipi3iF--0(W@m>ZDk5vP3)|1aL-2em zb4-1tOGlVzh3cyxZot!(WcL$;T_Y)O+aJuVQ3l0)u?eR)QFdnX@SOx@8waAMPRWm^#`9u z>FFBqIxRXIB;+hdry1WlgZAcEovbgOBU5_$v%x$BbJ&yJB*@|nj~>eNK^uHHj?#as z9HX+&9w*!PQAn3Av)9%omv9q~C_IT=5sdUqHkyafK{ViZS=-(Fu}yFWFsI#$aDm4{ zq#PBtHe;Z5yC{3!Xt!0)+yiZ5cwvZn+cXV9b{5z`Iog(#wMO4S8FwG1c{_6q1fOQW z;TXZ-?Lv!Mo|f=Z{iiByG*9MVmpq@r)3{ZG)97+jIAF7N085`De+eVG&)TkPvIU!> zi>JTvY@KTGT@JTqFaCOJzt<1@&wt#}r*b|FRwcHHK;CBN;;9#qn450w;QOD$jEC*R z>x%IVgmJf!zEuYPNEc-bUAW}w_~tiIAX2#+ot;Fr)I}CIzL6MqwNo}X+Z>Wn2bm~; zWtNyosn*o%*WCVevR9x=+Mt_g@2Rxht3a=FJTk&GrDVmHCl*4_8ne=OBaw3LtOL`x zU7$=`E@84|&bf6>S&4$ClVw@wH9Sp72-sRXgw`Auws-%#T9+JI_}8Uv{oxu9zphP0 z4j2OZxFd@)e?NU+gskviMS$?0jvd#*7&9&K=;+jY-5)%jxaT}=L$(dAETToa*Za^? zXy;seGL@Qs=J%#MIcB(9*?2QVi&%^kl@^`81*(Bz=iPqujDstTFVdSF!nYv>1aEaP zCp1c{;qls_$1TbuTJ0(u&voK60DztQoY3zhCX23PS}2IEc%z<(&)Wgs9e|&|sAFKM z>}(`g^R)5wD#u2pI*eMvvykid$!(85UWbXhg>;I(_5DXRRbtew2z5g)8=adwQChAn zV`?3>EZhzqNn}kB8|Do%n`X&6o8vxnR5fR)-5(6U#}tVA9FUhIlngpEj8jeDMy+zy zYP6FdRv|iMvg=&)aOv~JTvnTMpzJimgte?a0e>I@IglhMV?*xcAEVIFgtfh9cv^3E zhxu)8bu3t^ehL^L4Hx%{a~xG^(gwg~R5!NiP|r_L^c6;Dpi~9iIs0CUKY?%?^P{y@ zwRggxp`{MNvuftO!HW&x$p3b?qPzH%X@ z$ci#exAAE5*4P;9O%bz?T~LCt&E}cal{6Q%6L-AcVsT04+!X=Hof8ON+d+~VU7|_0 z6dH*_4p<%SXHuAma))ods#WcHzr~OTxl#+kQq1o+-EF3bfMXlGW%$dLIn$rdL?p%I zmleB}5eCx>$7IIlkh(2&tiD4Cr6*KW&Q)gO2eh39r{@r1+8iRvT!d=3xVHMZD%ey8 zmd6YylFry)e@otilQAAsSK{Hz+<8_(V#zFv%W42TkEU2FHj!m??uuxhPsD}iu&W5J zR#^jZNZYxT$~^enWS+5;gd9VDDJAHJUe}Iu1lC^O^_f^AQk4dcwkJc1EHWFWD_It4 zq<3lriWh5QnM&!1c1LiPVKKi2xgayUy$qUrqFgDKM$!qh4zCI>{C#qKub2Xk>LfC@ z4n|%2PB5_wk{)%jO{;7p>@%re`p&z$$m>r{#Ls1xHD}bE#z$)%b?Jcg=xNO^56*I$NsAyh)yv zDbLsH)z6IJL)jQ}A?sM4h!-<6ChWJo|08lYWlhk>o(g>O8J2(C9tc_?Ay_R>{C>Lg z-1!$f0?AJAK&~UsXfkTs`>Df5vS3^P!tki-R5PF;?O3e*J`u3_&;$dqf?(aAw!qx7 zt!90?HQFNaltm%~8z=qDaOc&NtftuaLCHnF=RsjoZ1Di~2zrz6KIXHvQa2J+^%DR$CRo=}4zqB48%#H9}PXEP!#ipcvVfg8HL( zZ~iv;oGxv~s5l$1pz#{{LF5Q9KhUW$JF+6#UV-(VR%M5zam%80*=A;vquR9k$Wcu_ z(<8uZ+LUd&J~V_1zcqE4cOxE<+xS~?B-&Z?)#?(Qzw1E} zbX+iKhgJtZyvgw zOoaV7{jyTLZ0HB-M~K$VQ^)n@aN7-eB9^iibQ1RG5>7B0K7fNRp^OoWd^0+~%jXZ} z)U{lZ^0;)7?eJv^xzTCMbftRR6^0w$kzA?3J444!M{OHI@o>RNFa&Ywo&)wTBCz05 zk|uF^sK#acf;E%L1N_C)(@?y_ltyV1Z3@M!42?epeKuR9z*^xRRV@eMC2$yOFX7Iodu9ko4b1lCl=b8LO^`F1W@l$N=k8&lJ_P^QBGabt3=- zc2%2X{hGGeM%LmUCoA%JekcMaK82X;z#doFfggW?EX5m&&{6+h%rivkor_q#2g^ph zHEFX4pjldzho?g*%y=t5baNVALz8&9s6)C7Qo+z=ZZQ=peI&mPf1_~c+XK-{Z-K&Lx)2i|5Z%m2o>Lh4VWWJxvQW$tR68w}Q$Q5yt+3MPlF!8Z3kY+x! z%YOrD%>NCfu`>M!NMmRGzpMWQY5({d+yAqQxD{L}$r6(_$}dSQkXbObcb0T(i-rS^ zV-iWwwZtiqU~68Cn1G0oBAS4P0-k7;&4c^Id*qf3&kfQJrafu1q9;G;m?OhEh3`r$qx3(7Bf_e=;GWE$}jvq@lUU5 z1ud#qpJEr3_ZtpI&LtG6)g5>fglIE>h>ySz5(@2m1L>F&B(CYPwgsZp9wbR$t`-}k z0B&+^V`+OCA%^|rMidA(4850zn)>yzg^O<-`qBciJ_uxyde23Vd@!6q5{eHJq8@Uf z>jypHC>ft z3%K3o*~XW`NsrY|R#KH72$=7ZU#}Fqe+btC-UXaM2J-Yz83=P$-)v8m@(-gM%&glmq%SLrCU5&$PSY=%2MlgDPW33rvo9BfI&ZlLj)u^NKB%WC zw1{VL9!CF`%URN|GYO*?MSd^$eUq>HdD@OmhRt)d=69P$z=7k^6ZjyMu?fi~r0%}3NaV2p>^k}hq@A2~ikoTbcVQkkwrtLp2Z$E}_ zHGh6o^M7nb?yr$XZFweiA%5_?iV}GSKVrcH+OF*eF-rT8I)J`(6+v%xD=HwGn_XSs zb*oS|QR?6o{k?qmo^9@*b@VKyJ=sUE>6Sl(FTU2;fNGtbn;wS+CVvy&fqJzeYnsD9 zze}3{VUnXkh_(VDvAly?=~b)sKu{6D?IwJHf2Dwd18Z6QhzWoI(SG@o=o9!&yyAz4 z;`bV#U0%XGfONDHhrF;&!wa#itG9n+_67oJ(eUd*twMb3(%;~}(&c;x67Openm~Lb z28|*a-M|F+Wnbo9+x+x~#n=%Ve7D1V_aV*pM7O>HY0(dAKLZHgkerDeTtnKv&p&e? zf0k6^Ix47$?r*^Pn7{tz#zsRxc>43J!8XvxnWYH|s+~AzqXmZSHC>+y75M-0 zVPDv!(&bWqv5(TJs%G@^%fEKPtyU@TyViqbJEq;M|BqQW=GQI4}WGD6Oeaf z+SROQVTsjt)v71*2=U!QLPMzqi>icrj25`IVb{mIoxQR#Ff z1Q|PUXv5STNWeivK$;ZIStFF?1^K-s3sV^MSviE6V)mh?3ZFCdgD6%XPE=`7u`fJC zd+p=qIbr+Hovu&+ifJOM-%7<~pU0#+>OD#^Xw$=k91B-Fx==J}@Co@T%A>nItkd0z zld@|Z;}S!(P=8TC@tqwMZY*V~4xI{YR5uE&Il3e&3E$a= zJwN$^0TVGKUBaiOE?YRAvw<;-Zm!!HaQ9r%IHz=5w|gnk{V3bT=h%Pmck;$c=QF5# znZ@Qi!IoqZ#TX(~@+<{zlZF|s;QXs6wq(+a%YJreD69FPXw}Ox+(XKYrILVA3{wT9 z%tCzEHudc@hh1alu&c=8#GNX{a;H>!;?32{CXq_MdrHr=p=RoQC(Bo$}Iei1fNk1Ab8kfLYyPV6n@KgO|4yjAY!` zq~VG*8=_;DNc%;@yqLtL(si&#e`4;bw4eg4DD^P3@3YS$EW+G4vbk_3bG!oV>E-Qi z_*X`-D4QnLL&GC&DTO}T>pPIbnHW`o*jM(RTMivxeIw?BrO7L2N!)y@72rv7SU1^3 z@wd^aEEb$NYJR{30%P2UNhYJB*;j1g)E7MdFIZib&>Zek8n}h3ZKevRu+_eIJsqrK z*&UP`!eP598fKozw@td?{}wgW*^K&kcck zehovi2s2BIj+K%6r}^qfbba~tzYVpcIbWYEWr5H8IGZA#Nyk66l+ZLlG?1Rc?3=+R z#+VSfaU{lf-#-pfPh8|wWgeonmUh$@C#_~t#awuLFbdMX5C8NYFNVv6=Jl7UvZQR$ z?4W{CoPQ(M{ai&^BpPJwi+X4_3@yNvDr53)T$otW zA5WY~c87_1ZtX0&OgxM2TC%c;yEqD9+O|StO*{yf%b|ry2t0pP89qKgckILJxC?#PS0TIVXGV@?AtGZEs?oCKs?l z{WvwQkt&0|mig4<{^3J76Fm~5emv=E+%@fW`}Alju87nmC&81XH5<&4WcA@Mu}G6! z5VD#$kgJ@~;Nf?8Z#=p%lR@9MnoPbCGn!k!Y6r%kB`1YpK8H|kvmG_%o9%;e0mYDM z=r(}X;_PA(K?f!-x$1SWJdB31JdxbmZ8Mx9UD5GGJ9>Zj>t5q&u3zZjx42y@g0{a| z|4O5#D-%h!88yZC0yVHX!)K8I;;BN)HH3(?ioloKzY(27W$-)-%yrQiKHr_vu@}LF zw}rFIx}>#dcEoE+z7)gh*}S6Y;xjs??&R1dDuKA}HHLQYnoXW*P=cnZsxr*PAS)Z? z3p$$^_>gBc6{E}?-{ds+h-fc23vfEWLZkIPXp${UA@|4h)I9T>7*-habD&8%W<>L* ztQvYxREp|#E%0hiPhrX5(F;A#ojZ?dB^WM)&%?3g<|u_w%uU=yL`?L}?%82B+u%eJ;PDYgoETeN{^%h?&2iz4pM(4lCVp zL>m3Ha1#s4)$Yr*jo&^iNn=?aK(k3E!C%_naZR`Ky#lb_3h&ki< z@ULP5-nd;mefH}?sug*aqAY3d+P34clH*7h|1f`UB^R{wH_UAazP*|17JXqaxZ+}` zzR#&PA*y4T4o|rq|GM)VRcLXAl+ni(vo~z*KmwG=tv-eZ!tgRyRk`eE)Pmfk2Ki7x zN8&Mq?W}^LL_U=56pgb4?gLn;|B_U6?c^Smw-pkth0cT)Y*Gd^5MwYKXSnbz#=4xM zfqm9VBI4oaot&hzI%10PhTX)^5_Zf)$OO)0B9e1 zd?yoHV{9n;r4WCN&j_z%D`Hs$j#n^fKK$N!@FA~XSpIJ2IZDE{ z)lExZq%ZDj7_o>b9fY#fzp0c>EjDk{vKMyvNZnQUf{C-OPFPD-#ZhW8WmKJ^V`;_9 zStzbYAD*>hiA#7_jZRU9$>-?Fz8K{HXhMO;S$vz?DJu7L2YDj`^Eb|{#ms&H_vE11 zUwA^=Ze3#beNDZ~1aADYG@>;wXl5KR5;qm!Io@eD1t2}Uuhtb|lQy7?J|W=E<}k_-;I2VP?@@?(ua`BJ?tHbfM8W(fw6<4*0UzOMY*0_k~F(!B`e%P4scRSa2a%wR$ z^0Ac}m<2-{FN>{Fmu;qib%sTVm!PX^Q@)4Attb~U#NmZhK{t@&^XHYNMAuQQnrjv6 z5npYoq@P_keuT~>Q?@b7WTPgdyF3V{atGaU#+Kr$=i$-A2a0oW#)oXw8=}4*a|Wx9_oI zOf;?!{KJ(@XAen_lIUz8Pr26IBNJ>*w<=eJ=q}z9yk^?>YNZrm5s!}Q;l%M>YA@2l zgx&+7vKM!@LKk)a**L3Cuk?P)7C);C+h|CgsN(i+Bp0Ich-dTR5IcJ`+j)B$c(x{c zGI-Wv4*aUIDft|{KB!0TF@1k!`DFf>>uxuO%}tUY`LMMqs@0dT+u)Q0=c)2sr#e27 z8ybkEV?rZJb7Tn2{-o(@<}l1bp^I}&mF&(6FetSKQ%gfwnbx+91&@zd?Z(iu%fp;{teUC(vpYZtWsKUU# zyrJondLCqbgIgQMiYV?R0o3tsQhw5sVah9JWMGhqtInG8yzl)&tP3j=P@^qJP_MKb zo8`D75BmkInr95{TMYd0f>;=~mWz2UI^~V^Xpkw-YwvxJ|_E#=a1#)q6 zCrNm`j=i%huD@3q(Y3U(T0IoUI{rY(g6dQhBqf-WT%a~tZuVki_g{Gy zJc9pI1dPHmH&zDyDt2IPa4YX4Io6CLLAmBUqglu#>@lq{1ReUNy0w^i80rl6;t894 zSw@hR@i)a39C&+D2GVAx{?R2cINN-xBYvWh6O)cLU2@40Eu*`NXA*6MAMel4>vCUX zIFQG%<)3P;UE(?dPb`vRAKdT16EN>-=fO1-s8qxl_U+(=%{6sfg7~--UG6pd7Yr+6 z6Mlai%!Z=7N1*F-F05CIhxk{u(ZUBmmTSC@62e0z-wk;JG5=Z5ZaIF1J*~K0j_$Rk z^2Wf$#K0AMeKZZ0ju2!n2V`n=BK%ScbQ)WTZ@}-Qqhrc4C(vlBQD|&#$d|8L9uIHJ zn!#hv?aE)2wm(bBMH688;UEsq-2~ktUwjYp(LF6hxtTa5ezz(nN2FOja~c@bv2)5Q zGzYYt2Bk+IP7l$Gy#PO=eMcFPP2VNK3g!olgh#R18f_kTRz1^OTX)^AXXY3eEC<-n zwIqPlL^Uf$a;CzL9yXsZx!5!iYY*x09Q^)}wt32g_Hvk05e&W$RzV(s7YxKgeoKvO z(+cOY6xTtb%Av3&b?2PkhC6~oA%=f0Bjf3wg&cK7IDqOyR$AYGr)a?G&$6j*-$mC~Gyo;lVk(#5l<2P-Jgo>`Ir4=ylp`b6zwlY zBG~cAFa@1zqGCI{o@Zi>6TuT8;K}aN9m7CRWQi(DMfwk2r3AmC47E{mlPRz#aVJd| z&dTgt`VgsKk#@!%HXFt#vt2E7e^GxnG0fQs&SHY*rb6!3R6MY+qiN*yZ6<@e>q6{b zv1EHxUOi<&mQ(-wS4pL7ZY3s3J4@xbSiWct_{b!JZuk?iVp88`?X(~D)0m|hO`OsR z^+8IGGZIRLc&lve(fl6fu-OtolO%Z-rdIOC3=%^a0Qg&^4{Tl0&<^klfsvk(OCq(_ zV47opogmYAt^*L|#M+iI`O-A2Ate@UX7IQHJsC6j`AYC2+lVx?Qu-)C1NQNBTj*Xw z%2sdxBGYu`BD?KPi#Dv$y407&C2t;1e{*zq#X*}ToysFz?MkGSpw1ptf=1l@CCqK0 zt1y!e1s*#MDXAbEdJdG`bWueR?9v-AwscHxEXZjA`JK!0W%v-V`$6pg`8pE(enE^L zeYx~XYFlo(y{!N}%zWM!Y}Aue<#yB6!1758uFVFJ3Hed!TXNAxyu!u%`6DP`B!ZKu zt1aLt3n#+2ZW=s3<(}6W)ina%WM+YUEw!Eeh@sHIDoUjumDVRC=WVs z7yU+Z|A!oBx;6hb!%)gP@tPbpo&L!b;c){CkS^%5?d-6EG=0#C{#4S(gWy|@@ruGc zLBxnCQ<~Ze7rRQpJiT9_5?&uIRE71bv8h@YDEa4CYK3MtOqzakXQ822&Aw?~(f&`- z?Z9wZhn0|x1ar*KFU8p{E<*k3jK(QUH;N{sw;cM zHn`^6R{KMIo8Li4k|pk4l?#UfLh0);Ryq=Bnndj6at6I_c4xPhv>!k%Izc<6(H7Da zDh}`_JGNrFC?9xoOcPh|7j_y7_HlbDJ}57wh8-^oMw4KDRLsOMn94~h{)rfPLsD61 zJpTrZOmdUk9@MX=T>_LBQpxck?ssDAxG1gfu%IG03O`gkfp?{~dMr6kf<>E^wpuXR zl|+)BKjxBItaI^6rwxt}5z>)lD~4B(h)1xIk=W{|2VTK(!&QBYXPF@KsmK7L9vW9H z$FA2Z7st+O`DrgwI^e#BOb*|BBZ3|EqSnJ8sD*oC|HIfhMTru$S+;E3wr$(CZQC|) z*|u$0-Lh@lw)*zN%=E1FKlEe1M&`e{>sa5_S=ohozGTUZOadBPsH%Ask&B&8wUYI1c7CCNt!$3v=px)-F9=pAt`@2VoKwxdKo&l%wy?NVs={wwJZnPF zV89=z{qsrJf?11FC(e4Z*C`e^szPfDJqrwPLz9<9ySme@FB;`r7(FJV!&nBKELut;}nJ^1`_=ZYUpCS?t9xTU<| zMr7IZD0f;*OdoDniT^!Kp_W&1#QUgYcVl=vrq|qL-BE<~f-T81&d0F0sorgw z@#kmXqJ3uhg@bGw1*xPSa>_39SwVrwEsK4Y9Q;$m}x zj;ZfTL)4P>Pagj2xd6liE*KqPq{$KA8J>xR2esfOU`%!h72oV~B$Uyhn;m%K zo?XDRXX)MWQf@zlW+X>YieT`^ztM%#v1c?7GVS5;_M#KM;<^173(V#|sO9#qbeRL= z#k=?U8AvN$XMhqlOvde6y4l%yWHOwq$ZKe%Vypx+R$V=Rjva5RVR&3Mt(17l!-STfo=WVc)nCKi7R2-tI*^eH+IwpT57^8PU2q|=Qzgj#F=R&>H@?B>I z)8gPK1fG@_iVzor-tRG+)a0)2)aPY9^R7K+S4krn1emQWXN~WRVs~$j_zFu@xYi>1 zZ;u=HB2&o3R%uMH2}YRzK=(&l9z3R*MPn&8fIG$5eQkp|Z@u%qNA{lYTa@1D zo01j&#c5kOB=oShufp~>mv*hoxNcs@&=zGau3%REbE!)mHUCAxv$Sk#G_4vlo$+3| zfFVitvjGFV8DuM#auBV(G5Zu*l$zy;krY0}jy%g}XE`Ms=GS6~(_b|g>~MV6R+!4# zb;ikzSiRJRd``n$f~k8*E z@ej zwOboa$O};{!=1hctKye+@_tr*Zo$<6ReLvu8rei=DAmc`9)HN3ez`P>fr~yZ9swi` zu=wsc93YwLiuWu!P_y{Zd)ro=b@7LKVUOGILuJHxX_f&3`e;d#o7-k|ig&b=50P7t z4(cRq|FlmLw@$qU(s7iF2r`34_L1Z2nmCWWIb`^%1L#neuFLBU-JrJXGMx{Eky)wb z^-Cnf;lnNArug98k{0tVF48~7H#HPyL*99Fi~<6!DGI{HL;$CbzeT-bChHOL7Jqyc z@=Vkw8GK(5y%4}TWMzo4{z|qeMw0LfnF-rM%i(-8!E$)C8OLnf)_XTSGxey7{9xx0 zeZ(MZl^8nB_9=)fAEUZ1g$Xkt!YR9bW6$0{f?Rk^wJ|J>D4Pz^eTT|22 z;qG0ATosjL(N(5TVw1I%nmcB4pdNqUG&trqywDFZ@aYYut44~l&61Y0E0Hv0?BkNM zh9$Z%8NDn?n*3eT-OUSxrdja(kqA*>XpK|m0qIzH{ozWd>k_^2 zV9V4C>HZ!FfgD}*@k4o%lNg^#7cvP>0Q~Yxk8~itbn)jxdu|vpdj4#`$aT_hn*!9k zG-otOfBlMHKHCW>bmydaA<>RQKPi<^Ro{?~Pv)X_1zw?CiGhb(_Awq4b+p3m+i`i~ zBX&wSvyn(S!w)nE2u_1#uQBi1rZl)`4DHXrk7wX$dk5k)4S9=zRH{Ari;0=r$M5%W zV--kA$Mw87PB{arwz{#s>78{1U>s&rBU9ln1H!z1VNsBrfn+1n2&vPq*{*J;Z;%$( zhJk_xrpgq!wxQ%}ER)-`*IJ$Iq$56#74&v?kr%BB3VU#w+w_|HwY?_aP27WQQBj%m z(f62~U?uhJwMHXd@U$-KUE(o=ofwXj9)(yq#$!fZN+JCUb$yONh(E8at6 zf!|j8?G1`E;*3J5l2d3o* zT3f|zxKL&U>>7jD##QlzanIRb){MgXdD(w+?dj}ulxe%z_!^^mFslSsfT08G?B`r4$N}}-k_}$eFvx7tz z6z?jbJD+zZ&z@<(XEq`-xBo7f4Ttg&FMas&Otcz|sKS{i>+X~okHx@n*`vHlc(z8& zj)q93Q={F-p7Rt_1Um-H49+S)3!goE$_fPExJfq0poIkZ6mPf+t{2imaSWVFJzO~N zjYDRE1X2P+y=Pu1Gk!q9EdGrLA9v*e^Zuj!VYLU#HGGnSXXIGHb%K>g7+SFGQBUZ` z#nE`PnT~~2y!(gPZ6Cxw=E0h%lX(uI6Oc{$qssM=?eL8iBLjlT7VVH6dylqCCp#?V z_0-OhRY}8Ez6OC))0*ccr-Z_6NO-&I87Ae$nbS|t#s34DUhS${3Ou22khGxzKC;)LWEGP|f%k+zXpt6_T z;*)1w`31|$GB>L^H~)B{6Nm&h(tH1zeGa` zRoIuIPzflcZE!h|!4lUof=VV@3Ez!;u4pSg{wMp%kb_xqe;ub#_XZcltDr-XXUbY@ zD~he>88|_NIlm4B-5^e-!Ian}5R-5V&|K^a2A9>p=fY^wb?!Zo0!Au&Jv0qGQA6Fe5zFH!-u+0-0~f_~x>|hM=XF_eX?x34Q-u9(@Vqx2 z4EZEUR8jxrXm8f;dcN!X@ARS2>Mbkc&p?EGm`H&8sjxTgA1Pe-CiLgvsmhMF2#qd3 zV|aGkp==SawZX=$t+3W{Ww>akXKR~{X-><1SRN!EF|#LO63Ue2fE*+g?s6pDX-G~! zdS#;=-(m~=?gQ@^m8=eXh)0`c>50x_H`AiJmlE1On|hA6`WLBuk&JyOwz`l`P{+(srg&y06@_XnVqgW~>Aa1+~qf}2>F{%^DT zfA_5aKWD)Igqzq|S^oEy05@84L&%(&H1hFk>A9|AFGIQU-SxoY3TNeGpT342O~K!HsD$ci_O0I2okI8bw_U={^`7+5IVm?oA-ac}k_ z21?&Qk^7Tk6A!3tsv%1H9U!(h2tM@EBxM`Y1Fap75st!vG}!Oi4(GO8^+y0j97IC?2T0 z8{(<2+7O?hN8AwhPNSSa*Nn3QK>M!^*U&5Qv92J24Yqg<0R4V9?`}~kAwU8K2{8h2 zrvT$f{(((sVe7w|#_+qiH?Z|UMlIk#0RFtc?_L2Z=qRBs_wV69pFW~A$*L+cvYW^w1ojBY)*-1Aj9$bg)owf}hRGNI>IL0mSowT=LC5YX>r7%qJT^UH^TvFZCJ$dKG@ z-(w{aA;no8BXY_gkbv#&0ls2^>P!(*5&%DfD;^=koxV^Q1Vphy1`Tw8)=_`}-ie&2 z)dr~v01*{`!9H~Y$bbl3x1oBaU+h6Lw7`yjzv&Hs2E_n~!68s!_hGbq=udS~1bBCM zn)fz``s1ITA7AKxgB=El^D7i6qSwC_Cz6wvDMU?aa~BNz2Ts~1-JziaUtMLyJ1aSw@#spdPK+Fty!y#6ArGIkaNM{CZTaO{ zaJMB3M16BU(hLSAjV(m=ojE3Ku8362q^)`lFJFzYJ$95$umS*jILb|BOvXm2&Ks@w zg|urOsf@sAD@%^6+cgWkF|4vX`Uj#zhjPhUM(Hy?y&A)&FjKRyrahOE$lMfjH?_$$ z@I|JDkIP20m@-$Uh4NzyRsx526p}d9eNvI922?^J_cVLNR%8M+G&+v<837OijM0nv zL_9$3^SZ?H`zvwEp+eCUgNj1)!Ty_y*25bx$Et(ADp=)r^Fje zXhRF#tbZ#$oSeX;9r!fTh)6s4WBu!%f%xdhODQe<78Kv+TMmR%(h*~gx2xtPDGRH+ zQjwtQl&V`?7oV#qtn~6p_37-=CzV8FT6>crrm;+}d<#KqX*7yauh{P-60rd$gN zwH6E(H#c7|HJ17j6XDl*5?6q)!8ug#CAJ)Zw9|~d*e2>heXuP~IY*HVRx;Uw^1Iwd zaP(qq0e1hZu)1-r>wy%8SE8G22}oLgAE=ZvNAD}kcyt> zn7?^Pw6GkX>Knf$5-n&t6y))IN>LZ)P0#E++5X}gK${cd*P1QpuTF6 z^@8e^Gn(s?$>_1ySM^a8CnIN5ZP&#zm2zCpsT_}j@Ww0q zi+6Vo@*631@UCUv{Lfn6gazW|DO=fWqgSzFpk*ULcNcG2?ryowR2rlKizIT~P!+j<;VV$;>t*iDY4xqLF>`##nmT=pnpa5T zO6{KR(flYoH`rj}<5>4ZYOb1xBv;z;FQQ8m7=TD;(TX05^PXGG7t}wojC>@IAK2&* z)0_%@+QePargBC2+G9lBp*e6_B^V&*mM;s!*o|}XsWgU}MNi^s@T2{;n5RE!%u`V) zlnQdFyOYcRHGq(o_iyCdCeO)>oJ38e(%wOzi3dWaA~&v38+=3JEPMBkNxT=J+Rg67 z|F+0YFRGt->J=Z>S(c>IN_P@Aph#Ptsb)$g_DX%k99IL}Mo;7JKp}Aa`Z+)KgD}m7 zuR~oWIoP`)X@pGh@#{L>WrOnPU>UH*0C5?LgNeYWc&TcNr)cycx9wPGP5$1`lA1QS zA-B8_z{YWZkxIrRK4Q-=^Hv8OL^ITn)`bccoJZc6$e&Xlt_cO+`XiQFt$I)7m!9dV z@Q_3K*-qfdXKvY;d>@^B>E)=?s>H8XR>EH_MOV1o@SDN!OP7U{W2Swem6o#rh2{ZU^}v96 z*eg);Y+=PGL!@(JYQVR?R80Qch%4`ue`+zw-sEySF~k3d2tu8AekAy9dLY5Swh(ai zbX4y=q+AS_=#PT;P%I5??%M3N4)LzWo=aH!cHsNvB^DQQE^_SX{%8+xse5|OW*pm) zAjpb9kP{T*J3Jp2_fKN<@aq>-BmM5k7%QXS@b^`j*uapuFgyqxM1_O{?^VV5So#tE z=_=QrRdd1&AH@Mr2kD5^0th`^$&ICvfvy~joMNa?{ z$;6YkwVMO#jzebL!4?4@lzQ=LDZXC)%yqG8B)X{{#uwwH69qht*IqP|#X4U{x|M}3 z2%i7i-PtdtwX3S0Lu^R{pP;j(`>~EZWM5$;S7hs_>qU2`;A;Pg-A_{H2}Cqyy{2zS zR^Q8#b;Y49>jBe?^xja_9I9GJoFU#!Kx3XT@!!nh)bH7IxN>e|OlL~4P5Tg1H^F9e z7!_@4c<%_!iL77<6EtY>L2NY33Jy;r`R=hAcyM1}1*TW{Vt*Ko#=_;BqjJ~LiQ5nV ziSvlRteMQeB)z_@32uffvrePGE)FBcEZ@=R0}E&g&6t(twn`f`%N=eEU>iupMs`vHiV4@^70gN|P#Hw7%g5$!^M+XS5RU|wB4HG*3nuXa^miFIQ?9HS*ANy$z6x%l5(_aIs z7H7+WPY>shW}Imj7;H4c$qB@f?z&u@aYcUG2rKA2uN7CmKL@P5Hh7FCw0~f#h-mgJ z>r@rlsG+O7M+$UIzrLk+@x=7L&fGp(6dwYhQBH66_|9bYCk^mO&U4X=?pAl`=%z@I9pPa2StQ}p%>l*?@PLU zEJ)-+NZ~|{3 zuNc~FrTJfoH};|Bs98~h2;5jl;i}cA2x#K$xx;J$C1kZ@@gfy`jg@`?zUp9eXRZ4~ z)FktyWiGew9dybiMd6;^ZVXD4&Hl3MnwUo`s<{c_%8^n>*YX;7ccS^s^QUVYRmhE3 z)#K50cinJX>|cAZye*-g1RfEJ@{^En<&c}A;i@uV;p1WK%qPUtXG{!y9s>J;_MCb0 zV3@6w-)d2*()oE>W=4AFu`HRSsZuZ(BvAGsT{Q{OIzM?r8xQ@~H1g%n#7o?Ieq?Jq4fnMBl1oa& zxv1d)1jf)iyXtMDlzN? z?7@7^R%Y@~eo_znZo@vh2G5;ld2~hWrSL_{FR1-Tw_kg+8dx=p>aQsHvN(6(9sXQs zAjD(dnfwHMGbXW~ui9e+5!GsP_q0Q2O83pSlspI4-H-O|pHtxm=~aaTH{eHVXkS;8 zn=dxOK)KJoIVoSfpeL3RlHv5^69H$VxrF$}fUd87^E5*2h0Ev)P{56>FqeA1aeH0L z64JB`{8}|1cqJkU5_uWjD&4jVdwMZkr(Rv$6bx;Ms+Qhq{(l=c>BfUXv;+S+a%3+IhoxLF!J29SL;8ZH^ z9vhMQG`&9ysx7!m#n=OzhZacRwYJD|PS1dxud52kmfUI!jYdsVfQ#z&g`^CAYQi{U zcuE6|Tdh6@{p>q~mpHW(grXO6IRx6Lsz+R(I^8)7yIcwS-L?K9U)E+G)lwIoWtL3x zK#qsldLi`{&py#~fx$fIPN|~~+Ol(7Zcr9QGRed%UgUIx;%!t9p2P22>m72#l+W-| zlu1&sOhAHF>QpS*q<~1^X_P$W^7!4nU+ZzR2 zdWa-Vu*)q0=&xFtZSPf*aIVm}$tm6>!Q?~ykUbT2r;?kHUNVPbK!ia=Z!YLTpgO#7 z)Ma7uC2Mvb5q_zKkD(8}PJzB6knU zKWUK*+vOkwrcmN&$Lag9W$x-@Gqb#C^k_D8(^acUxhhuG@sNjhpQU%Yj3^u9R?@#} z`hRdF0>wI>A^ol*w3ZdcQOh5PMe(QrA5gW{En< zUV|5ee`J4=rt*I)N{pqx%8u<|{2$Wlo{csAY>@L^VA(E zO+C^LnJ_t+nxU_~q62BI!|1QJkzF&%+GYsN;I+6u9?z@#`>k|1dAE;PD9214!8}&i z8&B|SZ7{0v*M#zsufdEC$9hu@hM$>oDz2kkl98VPrp;Nk7iPE<;b;p>^0K*oXbMbc zfvv}gySQ{c-dLp%M1i8k`^~x9>5)n`A|A_dm|2&lWpzHbhY=E0_Me&2od4OX)`p^PG(e-_oPFFvB!A@_CH@nPHGxiZ08KlhV()g zt-~>TUVcEw3iApZq-g&-iaz~aX#Tmhs&KrwVPsf*CO=GtaHwB%My#bD#u4V`U#QVGf#eHfCTu#_n zE>34xWHoxbw2AUw7KLCiUqkjGu5?p5y7p#$vH6AgS%sPXeLVo%{%o1cDRFlN{mS5* zFvw!fjNry^OYCx!;fxcz#fL_a+Y+Dm+yUWvM0tGi`dEp!A;3B*EKI4qrf@9TF+=MY z(!?*L!7%Xs@Uc!Q6YwXy;YCf^a0l1-t+}f_EHnLVh-SgBE9Q{_mvSoC2N|9|XZVP9 zqLMN(5@XusX`I`Ot5REd&)4?Fm6Z|DtQh4B!JDJ&iu8+ve=AHf0U;o4NuGji>EJEe z_KH8Nr%`ls)MhNoxl(SjJA{S&dbT1^KSy7mc0@)4*5WC4G0xQmKWEw_YmukwYsyda%^O~G#oC(s z`Q^S_U&Ck6in_3Jaxjjpr|LM!?nVRpL)oM1fmtG4TaX7^VOoWU6At+SW=YDK0`ccd zu_r>3y_@1!S_9y#Z4qe>kD!bV!O$o@IG!m=+CK;GzWV5ni3#1R5+M=0V_P5Pgu_*Or?*)4*m=k0f=)#;+c<4<%Fz!sU{$Cg@CnrkayVAk2S8$Fgp z`YuM(2TBpfsY$;^O|}Q1ozogrNL%N{+X<%ZZZG$YWjCZGUHYBJVl-t8YzG|Mr>*63 zV{W}z%evy5`a0W`UQ?T1kJ;jrOZkdMG*|5rG>ck8$msHm1+ChGd+Vwh@E;D!FXLuu z_#`~oN5(lic@`do9NUwf6x<5vw$7L_E#*BgX2 zj&86@$zKHT++W>1;^E1mWXjd?k=(B2fL^b<_NHu~p}Zqj{wJ!ch_%eOEiNoOs7?`7|D6{Q1rr58S*xhP^aT$4rKF#$_RHJ%qZD_HchN5w`m1@$fLN$k%7-6v zM*6&jJum!&k%W-!4`pdpiBu2OR!bX+$S;z+4>W??T1l{Vq*Hucx+RUxpA}o2C+kIv zo{PwBZZ`TM7LkXN0p1Oy_1(T&R!{Bh0r@+piH---2_>24K#$Gw`xEB`+Tlv?3(u2f zrD3!0*9{1r5{xOy=3ClZVSRhK<-=4RM7S5*b1e!movdy%j{ecq5}o5QCS@nAnm5x( z6EUlRX}gdOFnv=7&FZI>ha)NDi{cbvi3q#++jS#iXZIQE5s*Q7n1V^5qLp*yG^wyl zGEz`qPhx$-2-Cw}K|k`ULA&zxN0TJRJhcxT%G`^%#wl_~^Y%zNF)T`!hAn9-r{jdm zKp%>lxUhKkZAhGWeM=ILsH&Z%E@?L@SyLE+$Z`x~QjuUrOHNu;`ideC7Ji*LT_QPr z#xO*9{18?<QgLD;&3*3J|IzojDBBN@{ds20Erdb3paf4NHm_ z(D3P*+7z-fXe@BK&!(7HE?BM~y5omyY``K2Bxgw;em>~vc9xjT=N@7G1IN5xoUNi5 z;)eD#5HQLTxApxDf^{26F@}YU!5fj3vY<&DsoV8XM^^=NFT|+Trme=%+M=W7rzLb& z?ZT%LxaOsAgb0R(P^L0!M}EPr$TIl2HX{WAAq+4~NxlpF0?-gcKLYdLIa(woAgMAXD%>Cm_cVg-oCOGqyI8Lo z&%Vc>U#;Ihvl{c<&yCfc*PT~iU3l=URJy!o)CHu{0FnGRfiEB=08Lk2V#R=f0EE7P z00Knta6Fu2fKO<$gSqgI_Q3>*$Y0Svu7QFI7BX-_LXS%c5CKtHzyKs50Fe>_BBUT7 z06{=N2mZ(jbVvZ45!_o)`7`hefuj+LU?YhCY2m*_Z~%C<+b{8T&@E#h0^0ilEcyZALJ4)|G3_9z z)1d)+I0e)-Ve`*Hgue)@z6rO$zg*b>5ctpXocv9HsX)ZPOVw7INFKk-x1s)wg8PH$^KgmukdFDOkfW9hc%aa3G^n!>DWD# z`wI*4tqSHN`4~~HQ9@iC1L#=lsfwSo9U3Nz&y9XBFRMkIfER(!pSF4*g8EWlSfhgz zFppqw#*V?XqmRNO;*38X76$a6^dmX~A{x+O1|Xe$3GJ<_J2wsa${pbeT1;`A_z51;McvC~pr+-3vicNf z^1mbRt3Ck`?{EH7d#AsP=8_uF?>{{E6SPs(hhJ-<`vW&H_wxSQ`v5_)aFI3(GVrgW zJ{tOOv;+VxxgZ0^9c6ik`4{wCuOJ1e zSp*+L>(XENEH;n8JGg*QoMUkM8D9Vaww*J7PwuSN&+yj@@#5qlXy&Je#O2q& z&fg#1fI%K3*}@73()Vtw_Q3PoGlQiFe0Kw2XHe-dTB9h=fg#G7XmeBzmS6Qgx+x}9 zl~GqeapmZ9F2PY>EZ6=tIJcDcT<|ecN|OTSJq|SkxR;$5eUz4s0gaj@c>0gULNw~b zH;3)XCK?$B*{dFA%r6Y0E$Rk^=4_9Z%QgerE+7Zc!|d1^5~kw(LPjjNMuM2lm2|lt zv2r5@6nc^gJMS^Mu)0RVUHUE4v*HuF9yJ*wWskG-_IVDjq>#A1>ZX)vlrZIaMYrl2 z)8|3gS;gUks+A5ShiSig<1Mn$?c6D6nA40gw^~eKdit92#yKbsAgGL+@4}tKln46s zCY7+N>of6pQ1&+bx}TT#zNxbW+*YOgy!2d%fncZT{;iJL0`W@>#C9!kXK#-h-Fmg>ki;o)i8fYd8e%jyEoFn8YvSENS@i~~K?mZY?*kuD!e-zL-2?x58zSVeTEy%f`jy};h23o zO+}VIRRw5$Un28*jE8;lm!? ziw+mr2+NGAS7G6EQqXJa%pG4Si2-6K&D?H@#twj(yu;f)4b?-)*ScHVv<_1Il5HNU zy^Znv!u*&|l@10kKoj>3*l~yJbXQC$^W~Ht0VlsgylWhaB*q)#^O%8X4V4Og!=+j7 zp6Qw;Wlz5g7)b*ezonS%4}+jTtYmDvH^^$kn?`I6=#)n_tgr3ey2T(0KQM;z4JIOe zI;LuQqNj9oFG2n zA7naDSqSsBp7pFWincUfrQLFKTZ?AESXM7`*HyROoCW1DE^UMmPi6(*xrd@K+iOj6 zbs?lvU?TQZ2>}Aqsx_sr%qu-K3zupzHlV8O+@QWv%KFdW|Lh^?xml| z1vg~aW(DDdU*hidbhQN>H*@k=kM7EL3nQ=i#X@82p>)`C&^|?!AxS*w^5|F+b{`CU z2&g>d{07@cK{{J{v0jX5%`rEM=Sd|oI88_yimuBmOXrd^R6H@0^xm-B2ko@8zSs`||j~c)AJi~z@}!&t%K)A~UsIIi_A|IqO0E&A1@ETdl$nD%n#H=>@_gI}BP)K#9i&ow)lfFS z2;Tv30OU#8)N%1tDl!s4%18Ucdyg;4YQ!s3(N$oPP+Hj&xSW40fTRxS?CdSVJ#4|u zoza4)B1GcBArtiEY(oU6@Px^4KB0X)>&rI^x1B1F(`=Y`QQwF!6KLaBZHDvbmmfik zyuqD1SgIYL;zv^LRfG8_o{6}_h41~h+MPHdEX6^p54=|}w4#Yh(NXhY8{jw;VcU7Y z1I?bsss5G{;V`3RzMsl|;rZz!_7LUNMyC!PDrTWSugp&>?#y%^ybC#$en}8)DKevAM>7?JAqz1`^K45z^@{b z&olXzb>-u*65-0lD3^)!%;KILy84^65T)3?tf;kkI7#aAC~ur~z3Q_y<&oOs8N`f$ zTujd^pmmw;M{E-1WH9NS3*XTF1}F@SlXb2c*CAUpa7Gx+OuKugkFJB%orXX&x+t&Q zpeTA>RN@~~zi2X^Wb;_>!{(LuJ%1#j0{b@yNN0BP?4KJ&s134Z8a z#ivHmcLEs>j!Dlh0<*uAJ#r|%Mj0N;=LSn|K{xG@$RiL2RqU7AE}6WV$d`W(D&$KtIl$n29#`R zHLtqLYzMNO>(tXNw+WYgtB(UuMTSxE@%z5W7GSZ~ZCPf0)fI(tqOZXgEe$#!3e!bh zk|ivDQjh+Ch4&bfz@!VQ!EcU94IVk|HB%@*&NX&p|L&3PeO5=b|9qv}w>3T}1A`Fi zXuf@Z1T8*eff!JBAh$SEZ}7FLz|JG!K>Ekkru7c4CW3JF*FlFpZe68kP3R}3zDFc9 zkKDifVB$O!J0kIe6^~Qk86VfdIo3Pgn8hZOg^@sLMw`ZR>)2_6{;I4>9&UEh-|6iG z1rE#P#5vBM$;=y@j9zPF=W@zF#U4{hmk`=TiZ>KDCp0akoC9ZMSH$@>R%$5a64I{1 zM&53Q&_=SxhU&dEV6TUvfpX+XB8E*pqjqfZNzSC&siBWGWBXtuUi8zmNaGT2i3KYW z4cTyq6<5joK6~TN-Z|1ncMFsTCAJx}M?-1n1RaK9LgDAdEY?gC2$LRPYUVs?4m9C3 z9)nfL+77kBjX&)W4_3u_W=n#EUM_JQemg1me|!f}yU{3=32bB%(UCzvN3O@+YaDzp zR|3^(wB0`6Z_3X+jF_MvJ**7cEeql@_ztmlLozRqxN8z!YrIiyj__s{v$4?LY+XY1 z9l8)^h~mh0G-_QQPp9&JfF+4k##$m<`kU2(C*d(1f42UH5QU-9=Z9y`#OkP#tTPo9 zx<$I~7W8GnJ>VjVcyP;lAdUd_{Cum-FIn(dI;p1A_bUA0zCTDlv%& z3mt3m5PAQl`_WdPd23vht?$HK3wqomvGKFIicvBVmKPASbMq03<=wckJ}?YmmpV# z4Cu&S;cAvCRBK8SJJFR(U)<_Q_v@Z1C1iD7MP zzF5a|Xw2vBG3^z22&5Hp_3QJG??7=*5B`?%O2wJ?7|>-rNJ}&*L_CGFo6V)s?8U!t zir+4V``~)n-DY%ViUgihT~Y`2?-VtdTk4^+L@5lk_*=lt{=6Kt-#k(s>|#K6DQbPa zo2?8ns$A9471o=b$=S+?`XCPR)y^kL!Z3`Or#u=}*|l&wocJI4Kd9lP^?aLiUs2UU zp2bA+i2sac`;m z^bp(Io2t9=y^usy`Bg*uN%H0wWFt-uiKz`8M3_$-g>06jlNrr zq13^FUs(~v(|(Ymf|yl~z^&lh{5dFfVVdy+6*rKh6$z-;~ThIp)sGVyfjmwjcjmLGnV z9`#sD>1$i4oo6KsOY~aFws^ z-sT%4+m5+|ddEK9okp)ehIolvDB2JGd*->)iXW~T$3xB+e4a>yaFDE$?3wmXA(s=- zWk9iz$AbKACYs!f>OEy$nQYLbqTz8sg{7MyTk0+tGBj3I8ijs-c{h7;CpAfTJwESv z11QN6MCAr9vG-VmV5o0hi0>C>y`F|kvH)#snGbG?7LN_e$?VJuQC|dDe^aav(W`z; ztzyLT>I#!jzXm5Vtm?N+xC^IkB3OKgvTa)MfH{sur8n`!xt!(cdvWw$=FV_|EZC+k z7!{^TUcbKK?AaKUwzuSaoy{xA#X_S-4X!%H!up@|{AJ zSbqp7S=SARHnXnDuZJ_~rn0Pk5PeQR?G;5b=H%ki1i{w0;ze4TDT6LoL+X_HF80Kb zD)l3HCT-J=Fds)C3ZQFon1}YgmKwhlgY`h=&JjC*n^;bu?}~0d&Ic=5?Z5`+LDsvF z3U!@+pW7F`HC1|}Ss}6ZxRXDBNVWk4y)NG3#iaxbmUxuW?bVD{AOc8!`mrbF#?=h? zf^j7#@}T5r%tESeL3Q=}G;=|(`nOX;Lc?%fDJXwQ53kR+Ucu{6nT@}4O8MWt7$;D{ z;UurJ);;P6ZcMU9GeA`G$}%Zfot#^^VyIQF{WCoc@&p|Nou!#}t=8!1OUq9S&c|E| zBUQXL9TA^b4)!bmqyj4#M6&bxTVI+M4_927uDDip_O!He@M_kSmNyyBSyhud#*Y=hsikQS|Cg)6Kr9vcsgR;r;?sk!T0$UDeItVz~!IwV#o0hYojBqWrS)@om(1KK4sK+ ztDe1F2^bA|*3Axz8c?_)MdIfbagrqK%G{SqQv)z7ny0>!VO%i)94#C2L3FUO)6z(< zH9%=3s971?x6RCoyrl)i;a(hB4of{b+#YjH%_RP+eW5RH z|1ZkUAx5-l-PYx*UAAr8wr$(CZQHhO+r}>2w*B_G$-Bu*PUm%2>(5$QotZi37~dG= z843+~=WUO8B%wnyY-R*cDJ8uKb5Rj}8>&m8({IwNso9lVoV9yd)mts@#~QVCuT9}d zR3n2HdFc_a==R=KJ>D4uvPp8l+Rgz{6?(P#Ywd{(@$=1II`QxWNco(PMLcBF%~QT9 zeb%?h&JpVbtM!U#od=hW--|~S>--OGcpKRUA_>+@@on3oB;^NBOQAwYY04_3Ir*AS z`xh0kIdsFk9Cd5zVI0BaC+2S!LEot1q;JNa9(k{AGi6)V-9HO|@_Hc+|Cm4iVrqZN z>pU6lDVw(qU9R*r5NHsrsz9qn`1VQng}N5_+R}mSNcF%O4!R_-iB$av;&>AN3s{A; z<;pIJ+d&joU2QbEPepXee)Qt^b2jSrBPwh zwsY2GIRG!cMNH;(U?6KD<@NAK{e&1q35c>x%I|DH6t8(>_xt|*&%Kg$l%Xu~HlSKx zk9-g^uJLpMFC<%r$*Z^U!w8c~HdrC(9$UfK^5Rf$ih5-CqbFm676#`fIMP6|VCG@i zA{ApEwx*c(iVn_=JS=WtZxoO!*tJ(5efrpds@NO3tznB0OC)mh5>VfwQ7J;tPpUio z46vPb+E(QNWUdPQ=5d9)P|G+$h3@oOILd~#BK_S7MXGtsVw3*fiaDDu0n(KV1APG) z=BuRd2 zF9!Oyr_~4@mGS+=0h3x`f6f8Lo4} z2wv~%xh5<{;m5S)Ywr9lFbkbVwdzDc4!57IzOTu^TE{-w$5kOO7K4fi<)a-?inYMu zIMS_m&|V(*pd61@hTA5ewSKEI;*Inl4qVpo?r&K8^=2<6uK4c#lOKUefth}yI0>mC z4kH-{-VK?%;Jc6KHmovmr-q$t;>na&kB-Ey$r;L&;b~!~F;2dvtff^L2MdoX3=4Wj zN%q1Cl#MYLezF}AVRsO{qfU}~^E4Yu!Z`2A=-98|+--Sr9bcsNyiI(98)X^J`Bokm z{O&y8DgSiJH_y$>POrV%S=BAF)?TW}!$ zf~vuwjq{{$Qx-K9P3|_{)}lt6@a@`k;gNGpq z2yk@K;}Vy)U?XuX(KfQV_id}K2n+1dm+>*$JrF$9^^b$Lyaz8%?g%sbs-y*BbY@}O zTo2;{Q&;YV9U4$>hsdZoV^;pQ`piPE$V?rhJuYVgC@3ojnSBC3=onjtYu&XHkLnhbH@FRhm$Rh@Eg z@J*|)u2xS;dP$sx*mJbH_|zgkjL4Q!zY;Rr;Nns|MJ1rJ>HH*x^0syuOEgjO&RjY* zi>Zu(XWl3zuory$>LIqz-ze6wCN{j9v7d(aU1MWwuwKtzWa08Z#bS*b&|;IXWv;zr z&Yq&y9zMv4Vpk8=W!75aIy9;$pgC{SgnR1Y343&J6aBrb$Q{Fm=ULsB&@RbIJZK?SvuuSq0y*iCNs#x zAM=c=lIQEnd4}ck8u4@FqOLv?ELrM@YVjj(x7+jYR|du4&4x7oHm&=vE2Xf?jdf-sB;A-c z*m2}$Di^JdP819fwt0CQ{yYhKUgMSpeIm84wdw21wI+$yQ0k__2W3re;2K34Pg30O zP5a_JydLABbu*a-+~W}TN=-MpB;;axIUr7^lAY=`@L-)igavgFnF)s$PtX8}i3BEW3%5`892y0<-)#{vp-6*YRZ7OmCb}^mI+SoYO#X{YE{W^Y zoH0Zf8SbTdtmWAhgFy4VU@w+*Yhu>vj9fZt$xX}R;fVE~$6d=4Qs=oKF14hkYKo!U z%r=dWOI9(4Ua|e*bXp=jos|6bpk=O1r>rwR_0gh0&1phQiZ+ja(VuI*(;fz`c^JWJ z3vC&)3)8~pLV$)xujtpZD%ty~Np9sI$osRhf%cX@LS;$rfIwf-$p7 z7A?N5uhFH35e!!u{s!@ZgY5@*Jt68G*eVEJqBf2$2= zrT=gGFcTa5|5b$l0m1a_|Em`NKl(5|)Bl$~ti1cdTC#_)xX4mmK0Ln-5$H@rFf`b}6ov(;Um|q+jzPKnZ4)uU{xbykDeXDi(xuS8I-L(7aVRd`D{ zq<{z-HY^Pt<;C$a36SepWIp}uN$5D=n*K7V}>RFQCSufTnXdLqEP zE+=|ob@qeR@WQ@Dc-MDS#L56iw=e<+_5Qja=6!VZ;QDLc z!hbX{%>U59I_v`p@@0BL{P*SxPQ+Wla7zncPz31!zYQEi_WTs_+0D(!5Ds#Z|E&7b6`SyIcSKF=daJXSbjQk$cVdlxUbju$V| zFQ)rGpNk7}yZpTRc5HcdSxHoKQc?<-gsb3!2Jio;G(6yspu7+#(l|9WDFsmC zmrip zvu!PL2*?j9vjfFNetIzA7eIdqXT-EbppOUykUt?Fzov}x${-Pg2!j5>7{LCrgcqm$dh8Aj+q4&Xdc; z9vV;FN&KRH`S(093*7cR< zD5oA^Y&1>HTleCYk!btu)G=`BV-d%3l;}#=OB?O)VjM}WPQ`Z6CgT~QKQ&Ov6C3)i zL|9+pd-eK?B6};Jlk8q}^SN=08Q^#5q|K))DKj|qiT$vOITc6iE-);>A#praff8gM;k1Qgtp<~ew2 z9$b{y>S~5&OqllUi>N#{4g__gX@}bVHFxckkZdm_`P}__D4bJB)ti2$gad$rtyt%^GTzLcmS0|0nqIw)%XZwxQ*xwItKR9C{*mi zv2RQ&Rw+||N3<7suYf8*m6;oX+B$ZS&b#<>RO^V$yh(+WEu7Xa^ zRcT%5v2QONtT-RtZ6}q-ImP^bx3unS+|=z#;5#&(8D1mGii-)$${DJ5b`L&~jTzuQ zKCCjyqpGSN8lSdYm=E9`z!$!NM=G4rWl+>qPQv;8xYFU(2Cs6yboB-x{_QR5)cZ0vD16$!$b4GPI zP`||%NrOohiwec#CMQz%H#d%CXVI6LKctW3Zw1%<0)(No>PpZ+a-A(3zfdi)E-=J` zyY-<-=?#w5A<06-pCT$@(W0ZS?H3^tS0^B(J@tgT4$h3r&^VUd0J01c7bv6{%g6RB zs$4q)?y!>G6t;>p#?W#UCm%JM7)w^3!$q{L8R`&_N}mwoSUe1~Q^5e1ug-nxGh06qy@qGe%%TGTdLFug;V!O3m^1wHF86PK*anrqP4R~>;WL*vaWUWUw#vr;F zI)V7O+@iPEl^sW&X{cY$_hq9BRvxlSd%g+R&pQk^DZqFZ@rk+ij+h1sAruAtB?Al+ zEM0R1H=+%Dq|00uwl4MKsbrtsQ+kSg`)I)dF{~Ae%Tko`tB9?b37_kC5l-Cef_e8< zywCEmTU;?on?`B2(~L)+b(fP{yK7UR?!6<7&0A^JygtJgSnZMd;WPP}rfXC%4^6o| zFsbXe=#A8?+362E=K@6%YaK2$j+tUy-gP8|&axjEsE`CS-0O zAamwbtcnKHYnz4D=)GB*=80uY``1p#IXzEJQsQDskHeW8;O*m-)c}+%RaJtM}{e9k&`(vBPpW2HK<( z&u@t(f-(!S5=}??Uz1chQ8^Ce1atTMnx7rzyX>`Nr;op|fAveQX|~9otu6gKFQ!~? zO03fIc>6?Nj~!iFrgt8nzE)RwJL9Wo5AMp)aE~r)_0$B@OH;UT(JC@Xp&5(+TnUax zCs)te4$)BN#Bzq7o2jMXwimh`Rd*&Pj@dd_`AcN$yPaQ&lM;XIoDYvzur8wGH1tR_ zQ!KgMG`kV?25r{>-&JRU5|X+xF}~pX@H&|GsMej~WJ^q$iD#oNE>wS7a7evyKD~g1 z1)GzaWF*%LN}>(XV8UL(gr0u9)~o)t%d4Qdgxr*3fCLAioTM=m9Cm!YWB6Wr7TRD|U62Ta;moC(1H1_IAv>O$PuxBF>fO&kxM3+|i&@hH1F6mm~+Vvsf zF|f~D&Eq%0HkW9B#O!UD@ zwdQRYOCBF?1@oYvy+`)}`6&OwzVN11iv@83E;hc@Br|o}z3Dn7>#1caU}LlEkHHb+ ze4XNBV=?VR5Ovw?mr)H()Jr5iY^nMxWGwHG{$PJLcT006$3OHqdIhR1%4ftIpvN{T zm@&W9!rNz5M5_~r{JI0JBU9?`y$u<35E^Nn4Ey>#9?E$_<)}DmTClYu(aZ>k!x`XG z3KV(Ow1(u#;`PFB%ZFtGBX_UreB?9X2c|U?TJJ6i`e9atiSCFRrA4 z;Y4m7EH8qcFR!(z#V-tUwa)Z0;v#uO{YDh7`L*cMb4p`Eq#^Y9`xr{xb@ULP((x&^ z4O<2s6>@t$@EU-bleQ{Jr=xEvBy}6s$F`(S2i4QmoqbZ%`MQ7>oQ>E zaK4aJAA&+lh6%>Xn_NOG60qKnmE0jnM^aCErU+$Kdc(2x|9#i`3 z%8H1#Du>ETw$3I-<$P6hTlVL>qsv9CyvQX=?@&4pa&jHRwT#^w=42@C zU*qw4nY3jBf+q44r_W|qS!oHVv)V1ZYlGbQKKO~hl_E;5jvlk9P$KlF8V)(qa~0B^ zD~8svkZt>P)ok?=IBd$T8(Lp9E-Ex=Yfhw(lTeT5%|;>*Hc zG2cs(`^f}(w2+TzlkBnt5vS!AL!<2h=G4{o<(CHYCgX)h+uh#!abgM|5%Ij@t|aUS z3`#P59`mu2?Kf3dHE0Cbd<35rYI0p#Tjpj0Ug~zo3mSF44q_p$;HATPjVgHEcgU>g zgCoAlZfx=r%PB`o#k|l793s?wZ}ARz;-M+*Lp=yKyM*a_+7xes28}GHnwy8y+$~sP zGW;236tWAE7IF?}6r8iIa#M-6AP&B9jYOE9{W_p7GouxPs)U!qtu-feE2PSLe$F!U z`38Kc0=hZ)N4QBO@jEf4!B(*;N5uI<(ruBo}V2T29F)f}W|FGn?!5nHy2) zXq1-D2raSmxa)B^iv%}nBFn2Jf2Bu@^%z?h_7Tbubj963FZ3;CcyvrlO59z?)QXWo za55%lM76X^up93mC9m-2>eZ5RyDX{^0juE?mG{589?WvCeGc?;%+TyHJ421uSx+U0 zUf@3m_VPQB9OK-S5<_cUqKBHucRqW;_eiax2F;w=>rx7-#Kyg((fG~*iyp*3od-I+ z!S3&2X)%%Wsb9aWvQ!nwN0_veYtCBbJc3&)O&5QVSKYjn819XWy~@7y?4U!hbQ_e8W6KPemDNu3OY3iV8WB10Gsw)*@6 z;yJ_|O4a*TIKpNs>KA|)b{iCwmg-Br9$ej|C~IMRJp&pS)KU>Q##CN(Le^M##LG}m zGIqz~wKioRD>#L%Rav2voJ*B;KIv950?#MQjD*E3acS@6E4W&UH9==Px=(6+RCzbZ zMLRvS_jNsQ-3!|kYXDXoy0-!>E69jzN|J=J>J=GT=uKWtRqwW73{hxfCTbn(%83{D!+0j($ots+SwSuW2 zGq}tzRVUPr-JPxtt{gW3)(xKIAn0;$LR=j#4jcL9JoC0sYP_G&3Hv?4+Bj*#*U>47 zx|XgsT>jg6*FKI@DGA zxjc8u^es&5c}X*UJBEeI`)O;jhvjG7BLZ))C6eqPERj4$McQ#OGG85>*Kplf;f+DX zZ)adTl-Z5o-IsSvLJEpnQ-SpYYf>q%`$XxegB-XHjRQT#T~P#!y0zI54aTKW*vivr zU*x```Sz$v;tm8B$rLY>d)X*L_lM!yPCuWuRp*EXLGA~WeVgP)C$>mB^`6jl_mDohH*B8!!{&D8 z48JbKR^++pONSrsuOV`89ipmcmN*MJ{{?I|^bINAoqtVdnJbdJvy^hF*W9f1#e|Nd zUp9YdU0yodnw6@tG3p@E~3N?zcgL+ zy!CD(h%p$g6m#meeOh@o?5nD+JmW2uWd2rrl59*ND9RlO#8C*4kLN(rB&7?%Mx`5? zI1$e_-*V-QB=e};iSW^y?aLKuxEnY{ME3lleY5?MQQ>*gfWXswtO8?uILj-0-CNCvkbXu$nf-&ZZY##7t51v z%*!x3(9=yrW54SO|AZ*mvCszeXJQziwJ!a2uPftNLj1)h1>^4QC`s7ny|8PRiaEIj z&7ekSv31#l73bN@Cv@!Y#M}9a-gfkq06OzLH^F)_THFE0t4Ie$hc9o*PbhVDGM_Wj#3R|Gz228U0*L)tgR_Etlvz6&> zDt$UAcwg1Lg}^I@%!O5$WEaFt3!h%IzXzNA0elL#zn<))lL zx!BCuxg^8pU)En&mdTaS!FR_CjPrb_M~TL)us+4|W=?+n__GY?hCf%rL=|@au~)6S zr*J^i)1em66Y)r1EHu|*1`{LaH8_8W8yU<7qYLMY9Yw>FU!0O8Js`mBmA%+e*j9M% zv2wHM-n$0M=C@?;&ku;-S;4cC)2ZO7Ki+COUB^N(JqbU@=*whku+x3krk8Ke1G2p> zWUtI`&W}NzsPUb@bP``%`~x%D#S9j5g@UJIXYZ9 z5q?ACq7m)6>Tz6bh~8h`9*!fKBG!?C!no=PCX<{}6TRy7-x;)EowlGNdJC`2C>fa*`Kl}N)T`3KiE$j^oO%rTq~qL)8{wBI06Y-gNy)5e`&NWsF0L5)>B@GI3*bA?6dKpn zwc4a;6s919o1k70RXBlSCV^fR$UtZczb;NAb4LTNCuLte5mD)yedV=AcKXn;LzmI<3^oN z%%%0+;NRrJ0<#?P%K%0d`}$HewmNRg^_@jI;{T!P-bdJk$``ba`CNPFVk2XKb(t6* zq<@}Hu$%aawp5%V-sx-t(@c2*BLAA%TuMB`ltO}WZJxHxrqmMtccD?hOoVLhurh8P zU7AC@u#V-2hI<%mg|m7+#gy$u+?HK~=4;H8(Ti~41@*B0P}xT0qOOp*D_@XI&M92a zdfG85oh!w-!CkPi^KO*G<x z#PnZ*PzDwj28RD3LLuoyEv%hQ9P#Nytqq(_giVa>j7=bUc_E#g9Zd{uAl)}&UO|;N zH(x*@i9j{Cdf>OV3);OJ1RbE@u@Sc-wH)YfZfTM~N*h&7hMTn?mRt7@8h{hf$VI*3|*4tFfo6tFOY9l`rtaS?>5; zg)8Ow#puUpQ-Adk4r2L<#;aroAs#Tx&CQ_Vof^UF9RSwa-`CyWG&BIOs;j+!|1>)t zfs3Pa1W5x%P6KdoY2l+MNN&yU%pe%s0($72^2GsYB5?v>;o-p@=A8p5VC55y509hf zn}aj}Y;@O}8ydsNH!%SM64?GK1-=AK)AE0|4WH!-CIQ_(^ASO+H-O7 z&#VUGU&l57RI4A<1B~|XV*~FWoqpMM^fUWafH3|vYfOlU$cgDmsKFXv!PW6@AMD$ zfan{X8i3Z;);IvU>)>>MwN8r=&g^i1CsSHjnt<=VMP6OlzWq`^^C*6Qm4C!ie$@(o^+XkAS62K!EPf&1e($l?{j0Zs zV%=40k&av-k*{^l23~$cErEV9bwu(h#wSjGJxvHi>z42>t$r%aNm*r0RcHII@avJs zQOrLOKo}a{q*(mcS$@*ltm0|zig3`M#$X;ZMq8^JOQV#un~UQ z)opnJqK@!N`4Hg7sxp5BvH?&#{NUmIMeh5;({TC=Kj1uPls>_GPAYzb+5xCBe?`3O zRHA#VyGsfG=JT=dD^%;*{Em9Rdf5728T&U+x#u^q3KZ}6;i&^l>=K_23K6*bm0-8_m1s z^o8zia{F8EjgOJZ!O_{f$LY5lPM75k@9Pv44x|%E20rcNS{ek1+6rjHwn{icJKc3` zokIbPcF?zPc`Jd~en;sZ>DS(EA_1$He1qka>B|=BF}&xjWI+-tZCTQ9h>0W{&#j^s zW_H>=YrzRo>Fx)jdT;ngskcdKGk$30FZOG*gv`h%>6BeSeqVJ4jz3*R%Sc{fSqmS7r^^3yIS`-SAEyCB7yM0GW2GGGyr&@@+H0Y~A3w@SDTWUs>$<;-~GSY#GY0VOe^ zB_0q=smBnNAHn+dt53XBwz=1i`EvgZ0{ooCcK^nii#8zEH3GJFAXKk;6DrE#`Nq8K z2-ct+7dlA}1o(60x!*lbD7WdAQ5SZdNWh~RKpC? z%rwvOEzNjBeA6xR{7X#=UGdk7aFalAH<&@bn0kPy*fqFo?DL;nOIo(3skFFm-f~GX7H`^u18LF97gP+}$NRC{SnGaP z@KQs_pFXc+H#}L)%03fnbO=j;VZ=wy6re)M2a0BYvJqe44N7-+=(EP|?jzg@67?7b z6s{3oo9^kgpCZ`C`XZJ`bRiC=&Ad|0tS@vc_=1C~Oe zk|@Evs(RdFac0UwDV2`C#1rEr&8OG*ifAO)FJ*1H*m_wkn>T0u+Fu~4 zsKixUrR#zb=xCAzIgRXQU-yc*ui>E}4FiFM6n=r^zQi^h>F^MOK8}RQ_qJ{xB9QP!(*t-s4<-@bW{_`=V|@uN z%o8{^wry*Eggi#&T;k3!EDz_-$nq(>)W-@Sc~pW!Z^fxL?Q$?%TiPFSgBH58Smdi1 zHTn5~TY5qa+UHoVk3O!$RM2JbZFbG8OWz;j^04ZF$gxWv&fX@J02uX-_G4($u+PC3 zvb!I|wkC~!M+dFh-;90NhIQH;YVW$@_*t4%jbGrE&5EJvGz}jol1sU-(=b3r@v7Hm zkG0ogrPSo<1vduu11k3+!KJp+ST1y(yryk0_Jc8Ei026j3%nJ{EyJh~DN41Qff9KE z{RjYWaZs{9Xbgee_t)1~ML`n2vioIUN25e_&jY=2R78!;bCrpxRWw2MaKytkdigdJ zS8|R${53gxH8{rR4~8Lw`fIm!@^?Z*&f9+v=uUk>^8qdgP(tQzye5;I@qZ7zZbvKET<}i|&p%y6pHFT`P_SG< zkS3A|2|T;SIZQGty z_Lz8YCAxqBy0w;kSQ!)|E@R9%7ekJBQJ0ML@XbGU&~*b}usKY{D$h4Y@H*O9 z`Nt{-=ISUGjdM~;x1#*jkm%IBKKazF@@#a<%PPT>)9)E`(SE3iT3i3Hj{Hq zS}+BlO1s(r{!~V;SxM(&kOAa}!f1MpT+|xUF8xv)Q&d1yAmEbmxMU8T4fy~;I`kwk z*c}4J)XF*h!ht1mQGge2z`b8tgG|EOkIR69(5V=sHrbY5PeNK5hjKk_H)$~s$LpK? zw8;-hmWd9ix;85TZ}$aV7Lm)u1GI}P*88wdk;J{{BL%xMlQH_v zgI#iS?z{LA7bOp%JNwBl@=A6H!_GL|%V zb2X)4cpDErYccMBCh=ZiF)&&x-`ibgEZo%e?VHh}f1=*P^7m-LWQV(^lD$v=uBY!! zK|D<@?#HAs>}bKz=9mUy{1qy`q38_S<#!jzy48B!{eIKS&0I4jnvcOUkSB(G%f0Is zErt#5g!~dK+ij zD=uy1s{R+EYf%0s0+#QFHP}NS*1SEY%CA*#^arZYA!1F)Q>#?2E+PfVPFX2A4;9gJ z)&2**^%<9i0C(miILE&>7Bk!>?r^SN9nF2o;3qo^Gw|sN(SA)p)krt&A!M{#ZLMIX zgax@Vo;0tB=M|u%qcAipaKiA5AMjcD_0Wm2$m>C;&+EMz^wK15xe4skC zas&TgU1C{;7=QPS9g&JyYhjGd*w`2)HNw5VCh_-^D6;s_N>nAUm4N(PIycDUU!z*2 z8SUzq0B_r(yA$QXt5j+Fq#Olx+kXNBacH?Iy(Mh=xC2#apBQmNDtmnQW-TB?V zH+_fivo&+-V36sUa`tFdY`PL@DXolXJ-ZzDqmsTyYGs>_AP+@4tzM|=B0ZPtN{A#rJKz{aB{0@%-y!s7ToG7F0mt91f2UE--e+C zyQ)(Fwlk^rbB5q~uR|z2Y}k&B&UkOm&cQbiP!Ss+Yr9oV({wBfRz1SAu%~q(7= zk>#J@knPEYJiEwqh{n0fDeZ7AGsw0Fve=!#r?xwTwHhOt5S?(jIvCem6X>%TiU%aR zPA>*qMFg_Jc7~JG5|?ES^ZYxOz2>|!K7LzRZiFX=Y&T&d{ij~a9}Lh~3SvB3=Pg^} z39`SgC=R)&yyEtB=_8N5y4-qEJl9iK;iR@`8Bykobc9s}2AD1*aDhgeo+1$W(*FaJNl`P*ba3;&k|1cfNX|h(b2iwMj!FW0f^l z2OF9gPXX44=o3WhW$gX|^J7O^uQpNJ!=AqlzD}oV4q1rX+a5lF zxZ8>m@$9(R6K=wV>bT6z9+1tH&P%}Ku<*9Gj z_L{}!^WKnRIgy z1PrIP45V|{L)enMZ`pPl2~D;wFqcXxz57FBn?0=E_d@9+S`pxnbIGvoaO%QLSy;Lg zt{b#A#CJ~Lt_np9FV1bhp6*n5&H?Vd4RJNna7gRE148^D(pH>`QX5ZZU*8?DO1XlbFElSmPVeMG(J9ZSIGX_9$yYlq1B8Oa!^R zouO0sb(ybM%*OTxvo~XKUk*f1BdbXMXICJ&R24UE?;Y8XsILUfO%bn$*lYy7p3h8E zG021osul%mRE!VCMk?JDRI zMe`@XvLp?NWo>9Wo3`-H5^g-7jVA?z?hjw%!lwJV3u_gV8mTImDma%c7tK7@g46OU zx8yQt42@g64Qz0&p1|GEjoP$%&&Jses#Y7I%;Vrm5`Ld{zAA+Mx4I!i*1U(^;xL)& zMS4NEU5HQfvcDw*I3{EH{4A}cZ^|xE>I%Gc<6RC(R7w#=L^mH0FjKH1?*dl! zGl8OCIgAp^SrR~hn~@gNG_@79aNa8Le`?doar-TDRRTFuujRDB6N`x3;}wOW7;cs{ zeWp%=Obl1+m;^@$eOVe!8YTm>UB@r`{K%(Ja<-3jR(Wql*hyz*#rs1az+oN|)miwO zpui8S%DOoWy45J&x?g2m-}mwJRiz&QWNU*q8e}%#aBf~HOXWXpv+h*f7TpBf&d6UG|mx;E6Pa%ZQuYMF!Nig zBT``if*5QV(z(odLq5b}i)9u|Xa=$%OjXXW(-;=;^<^Xg{_6Yf0D489c*zNS1Qc5a zA5idvM#5KHId226GcaK zeXD)z6z{LX#48%y2X4ffD!PZP?uzczFk<15Ek-8M*z!xEyXp0i;L3!gQM;08Hx_f+ zW`1~Y?K)A`y(3S#CSW$?wx`WJtV0qmCX7s<4!Jm-J`|{d0)z}37lK_LzGoktj>JN% zoEICwvsfzrUDcB17Z3@c=7Y_Ql?O&mbv+sX?EOvnQ;CX-_W&P=?w8r(0fY-#im={Pnv zWksb4PqHDtBfe>6GHt43XNCdMjCjM|GiDTkF7HOzvaEb&`$=L_0#(xEyjM2Lla*3TiEw!8XIt`!OtmnCSRBG{SG(8w{PmSAPX$B5Y9@;BfWKv8rx97joxF& zOG%4wQUH890|Mkd+7JgqEe|&GW%f^ePTZaOvZo)OOh8S#qIly2AT&H!S@f@ey&uZF zm1MlhQWhin!_J_{6p4OdMHM>I3Qk<<*33yXx;3Q}?#_>Jvjf)9OxM47OxR=-$3#Sh zyJ3P#Ybgvl)JZ1Ya|u6k!DAW7NzNL+_-CHTWiQjI!C;wD_N&HK>(Ov`WNbbgnkFZ> zri=yjviAFSAq{9pZqltAhS>nMuXhto{E&$;i9wrat_c5G47I0Chtz+hH-q&yo64C? zG)KgxFM6YNJotvl&PE$(!nXs9FZ%{<_0}vs3d^lmsd%weICD^~7!M+IbJ2v9fxq^T z@Vf1&{7UE?$bnMa37^AgGw- z7H8UmnMp^$=dGFm`jT8bva>!00qf|o?Im@S;(E7M!Cc?gA3r8M5M3AXIzQhHs-v^) zm5LZ6)!31V2DR#Eg573kQf5xG;0bp?dvuv-cCR*JfIb}hz)(NYD| z!S#PwLB=aB4%Z=nyN!S7k7O&16_sCW>ULlcu0$gqi6nk#L=rwvEaRea#hYt*vb@EC z55#@o+;_;5uu+Cdxh}=SK7Tgd1-WcrJn+NbY`%}56cm`K{EA63MTY_a)hMvonPxZk z#OQe)43(i~UN`^lpJUNTJY<7sPE9GbE$`QF(%Yt1>v@>tlsZOIfxCLsH>4oHx!d_jo9Op6k%3FQWSM^7iH8zIEriN#flHZ&D>sMIbkei*9TU41&uVA+}%)#@1DO76xD3gvD zO%9)vs`@`S`aAS@kmr*r@~v;%@G)gMn`5Y1`;nNhu!IFYysr||&3mc3PwDU|Uc@)3 zR7kQ$<=TV+rLw#Ko;FXHxcTa0B6xobW|-t}Nkh(b)J|bJF|?X!O!YhgM%YqP5L2pl zncH<3bi(mX?*SQ5;5ioWgYMaKN@)m96w3e$qP`@;1 z*Faa~cn^tb&+JtC+k}ZmQZ|DDSBC}MhD9Lt@fVkD${nx%lZy!3eJzYdlJ_pA=~DgF z*p=`FK-XW!1F>iVOWmpunf>j9+1Cl?H8SbYX)T@2sP*@BYga@K@1R8sy?cb&z@EYI zwEJCPJW}4$lUW@w-0Y)@qpJh5(!WCbro2--4=>}iV?aKWvbj#c)38y1`^vqgXr$Av zyufhcDv}JY5T6AbefHd4juUv8!9qjU%@Y~$ke$%7$ud+nz-wGz zSIcZdds9gi>L-yyqt`P}9s^XIGk6$zt^`%rTnL{j&OEa;&d8h&0`XbI8rl#>v!sNU z{BxzZe+h-QAJB;};AE`17C}tB!%-#G-w*wg#l5D|Sn8}{V6V)#;lh^=Wjs{kLOa@V zgt;yWWAb|Uobb8Nl?`_+S5+z;b#a^NUrtaNnfzbEH&TvKxv85bd?Io_ha>Htbkhes zQMQ_mSetNH(rB+}_&6xgv*2PqUL@Ntq^aLRz0-SP4^7Pk4+yIAG%QZOY?9V*l7@BRG0vAs)RO|ZY{$wCKr$`pG&r0CV|65(S zGyU5vQ9(x13bYtk$weQQ`w-rv~NPA(V314IM9T=XGA0>Ai zq8dP!rY<=6GkJCFBOG53kn;y#9{uNDxxiNPZ*OeS?73LOI5ao!8H;AqzbJu-4Bcw~dJD1k)wZK95XUNWHJ2S$yFT zsFLKI1P-N4b!nm9X&sF@MBN>6_U<*%23JR zQ%0{MacHrI1(>0`-%&*t2B*=j9+E_5`%N}`Ikr4OBm#g?3Eq5I>H~8LZ5$%4Gc_77 z{{p)Vv2?L61$zrAQkCua@Du@5^QBBeuB+v{d`wk`R;z>v`)*N(5g07-^fE{d)|h;v z-BMKq?Bks}s9llV^Cg)h{wZ8sfmOt0irB38fbOEgbRswv#v!zaJU7Zxj?Iqk{B*7h z(fK(|aq(AB%_wl@;3QGlgv`XIBBo|KY!n9fF;F$UFj`2$f@a=mqijOv%hrkBs9Ky8I(?ZWMX+D$<|l9^#<>Pp1X$Eg}dMLV63-Ry}p&XDa0QutgDee{a>u?%u_ zATRytu;#xsYj6`E=`J#WP@VQFe^LZt7&0uXM|YY6d-Z3_lB=qA-hqqtU*-ZTT%I+KI=^gPoE>@ghv&*Mx`*d!_Hzq4{|tQ z(r6IsZ%z=C8%)X;|BOW!^AMQWmEd>A_hn*PKB1PiGClYgN#;;)sd~kTjh*~yH}qLt zvf9#Vh_?STBk1AD)xO@#JX|^Qr22tvligHD33H^OdpoG4=u1mHf-nQB2 zE2-$$m?zQWr$GAi`WT%2FJRP{lPwVd1H+)qv4!9(UwvBbDYQ^=7ogMSCEuGKx`K=Y zL7viq%4B4f16KfL${$70o;Aa4D~bl&SwlbfLJftf2p;+ypxXy=1*|9EbDf*^w=AZo z`q%SLSUN|ZWyDmgSmDvU*#c&l_(ymrPAIqc{xL%)S|Cx1!29(mBI}%r2dV4Zu$I$! zUkG6Vj2^{R&wzGx%Wq0zSB<49KoXmG?=Rqu9!Fod(G*~E9OtLqeS0-9D39X9QZ&x} zTmAspl`R&cL(Snx({NV(&m8PbU$HA|>!Up*8Xi+`Y1^uR-?XZ1DnUZD9x>K^)xA%8%Kz)cfy42RU+N6Fi0Y^a#eILQRD`FyeX2ZVO z6iYe;z)>q;br4EJK?5V@7Ks+Tz*vWKg~I5cD^(uQ9?CpbEn(9$uMf&go1{TkF(fAk6>Z$X8ugy01YNfimd>wx8XnFqD?eAA@yM--^c)!a zXi`y9X)IhVFB3#b1+ojZ^=!Xmly#FaWP0KJAjHpSrwuad((fofOy!maTS+LJn%OqE zs%4N0d2G<1DAnYt(p?%U8=;*ccEqtnw<34@S9E~ybTz|3b1u>0I@=?t zzCe2mCzy?ance}j6kNo*-svxxYKmb_bR*x<;@v~oTWIE<*AXaqvR+U0*AP9Es}SO|RQNIA@FUa+zOO3B>eeh&^;N%H}%vf%ol$ zK~%vDb27Ka@Q(w*q)#Kq4Bqo}Z}}0eWFTA7L_MUI%e(3S_B!Ms{Tq#YY0p8@^L1W* zHxR$yoU)5&Yo9UnStEO)?AOXmR=Xz1fXeAdBKgoago!C(KA8<%a* z*(d3v^wvS19QoA4nPDY2(n7L*5!iq85*42jMN;79>HLu#%*!3hOT}q_XWHV{+5IkE z+L|=E0@U$8X#HxQA07nExB4fD6CjrIq4-PbFp&W4D)OUdMkbolG{ruQO)cwabM+>W zN%=9wAHaJTGT9JkpVwLPT_F)-6jLP#l+{|AKVDRUX0gb5MpK5x=SbRtdNqCCrI4K| z*X?`e7Hb@D;h|qa%Zh7GM5Q24kAE6wJFF0edCj(Ii0Ar8MQ(FRgeXF2H?RVY^qGmy z_gy+ck(h_?Waq0U2V6}{uk=nfr->=suRdbaonV0Os9U2{f+}Fby?VI#~dfx+Dc=hu*V!rVG=S`WG}sX*DV3J=iXFIMWK?5 zP+V%afe|rhQ@vIoV;5o=w=&Q_ID0uaVt(#n*|&H^_vcPpQ>Ug!b=tJ5SI!_@?VJ3Z zP8@!XMrgMkWa@?NcxJtKeoP?sjUhC3Kf@`$dePR;Z~h&Ay)8+=R#+_JnWktm)(yDbq-Cna z-zw+y*pQ*Sj2su(AIe4j`lI9T^~HQll8S+fFfs#q+mO}}#Ms`n<3PkaMQ_1zx3gGG z?EyjzeGFcv3fcF{$-~s`h3xaYA)~3i2dP#8b57a%M1Q$7ZGkthI8sV{dyCzvP*U;D zto225EbZC_Zmd1TzRAqiOjpOMbNK7b>lBMikwR=JKP1!JR>8*t&z+BB?se({vI8kV z1DWp%1mfrQPuEoZ+O+Fluy{vQ8j|u@kF2>ZPb`6x{NmMqb-JF}B~Q;V?Hc>=Ecd4u zxDJ)XfH!|?*2_BQmV8qRt;&r_S~g28p2aJ#Xm+3#={t8 zs2)NhYllpQgPe{Z%lV&>SOHsH11QuE)^hQ0ru?iBo1Yv;k>*@q@2(~R7=NmbymoG0 zGOsg8ymq$n#s?s56o6YF6G-}H%_tfAl~iZ5j{(fi0q`yf~1JIXUI^_ z)?&nFwPk$|Vwc76&e>g&WG_xtjK}VW(EXbxOtR!4_`>_ja$p)d7CaOC2Zof3IJ0!N z!a>v4!<^kt?2}f*P|zn^FUewM%l`0xOp;x?F`UqoXmdj|4rOUymY=3Z=LeIBV3!vX zy)cM2cVs=>wO}*-WpV#eHW)=sCG-JJNEWek5~MiS%6j|lA3>jajhuTa9@i}3G#z`W z!t)XkSmDjG&3HmM9kxv4A zIo!4#UohO~JsC7T-k>#&Ov&yPD+h03EU%)ssm^@*N}&eO`e~~D zj4ewKdm*ipQz2Q*QzSbQd98n#G1%{R`Ssv`JBM_Bj zF}&vmu|?WaTtu?VDvK{>{4CzQJ_+%h^y&Dc&3-Mt_98$6g`Jt-yTeuY&6^oTCu@i3(DFOG=;Ywd1LAAXTQ=yzi4^fPqgK!9-*%M z<69vjX*lxDF>SHoY2h;~0SRs`5O`)Z8M0V{I8JU9iR^r`f4X%q1U3|vkd$A;g3-VB z^9#qP^M(%&zRBZBV{EM7FF=`R8D?tpuzjX_ZXbFMe6mw|mYjpUiuzGN<>#otJ`` zjh#O>or5%`*&l2>lv135oS7`3C+R9=djYzm>jGlzNbZc7D@O9JDUNY$TSl1;lV^?@ zCvX%pO8>Q`7Rp*FrF#gK!47qWM)v+_kqI1?y(&5l#^}8PxZc^(A5N%0tTm>pbaT{N z{_>JOTdh;LF{SCa&dxBqv#hPJp9Qs=VGGp^Q|Z8>A&9Z_f#Q;z~R$s z9=fG>XB5?y<@L<+RBpSZJ7V{$S|q8Bbk}!d`Z!CA}j;D3j1>OgRhKf==yDJD?D8s={i@E5`Z}RfeV; zWeYFfeHLL!YxC&1!-+%88Sy{`ttBg|PdW1=MoU#>6BY6Y?bNHi-t9a*uh+4**5&LkjwsanYSnaiUY)O#iPJMh|lC%tC z97UFcJ?p+1mOps&Wve5Pv8B0gI_fOPu*W_$zl_zvLOB%o3Xit=^>Ma`{^0Ba5?RQ` zu{&gd*T49)POm$`fTE~YODeGzbsc;(Z%RX5dC_ldpxYKt6#Xvpw{1zjqTf^wq2>+5 z&Rd$v3PmS_eT~;XeS+oSL<`7F(8yL6tvCU$`=>V*oec~8JKa)E>TaO@}C%0}z zuib;53T3{DSJD7r)lexRuWxmdlz4}c_ajfyK=y2xHqmPF8Qn_>9m`04c>9V)WQvE` z>qhH2XW0yrq_6gNS5~`XMLDIOym)aTdPtaP8yHmkFwiR5!f(P$I6G zt}~`JtOQ&*;Nj=e8D6(65@4_4tszR%-`0StZ#rQydZOV?+b8`2m1dXi2c2D=1utJv z(>SqkKZ)#mSsfj7wRP6c2=C)~3LrE?ejVQO76g7*_a@o@{YXJOdiuUK1k z()a}Jmq)*28s!hV6ByLlYp=JdWn*6?MA=$A3-nn$N>9ur9XPD`H>`sWHfx`d9F;pg z(`k=$^VQN(oFaEz*@I3ef5skZOe0n}ZP1gRg5+EBC2Y~EQ*^u*Z!5^%-cgwb%9mRX zY78vaz1b~SOsS$&-`k~nMWT|X=+jEupxw5Uk;lmk>I-ZUB*nOj&LCbRxdlNlLex@H zQZ5roLJmA{AYlt*#I}FwngC-Ly?rT-H_+ ze1b`Mb53xYlyxa4RAQ4d!N;B+sC{)~kG(GIiAU#{<{CoBbK&KY$MnrX=8BA#^4MD446+Y&8^C9PaMC|LG)?w z?1}J{*cmKX>klZUA=n>+e?(fsSE(dmTvsX-NFR^2dWAByroC{KJuadZF$$Q$yykga zwMM+vM6liyII1q1bjNHGxGLbC(za11>Uwb}p^Ocx;9zmcRkr}rLr<3%Vtct zQK57nxp29LpX&S#T#xM=FipW8x(5+M3OB6+mFrV;tGK2luBe8mW@L zmbVkXT^3)p^~lL$p>2Rhm{UD2;swnHLR)K<<|Zl@h&>D&4*YBN@)?!dj4pD~$<-Zc zZ(x$9#*q}ow1_Uq%0 z!IrG6mv`joE>^_3pEt_4p8D2=pp88&K|IjnC z7$tndj>r=h2G<)^>zX*Dv+GoTV@h=KIPulWk_TA-uA-3_I;7~t-AlKhoEDyb4DF?5 z;UM2)>Bqz*Mq?ZHByQZ1i%EImRlYFEebTWiOMrNjNARp%QFj8*P8cHOch|&)BDpL~N4W1J{pq%iM#(N@r z9q+?j^HCMOZh5ArKYwv`b#?8Ha7LN#lsvvIzIwy|)R^zNH7)-Zb_GG!hjPk6zII%= zv0j8)OD>cws&KvL^O<4E)W}OSAd@>hFhqFXj$k4WyCkmN;4T-5@jRSQ!KpeL5e?+j zFu^MUD}&V5$YrMY-Vu#^wsB7a3*`*jCUjCAeI6l%^f31-XC-w%2M_GLEagw|P#R@O7`|d zZ0thjpI!XJQIt=ay;o1n;8PpIgxZfer%J>hKh>H;aD!Od=s!2)tx)Ysut@>eNa{6d zh#R1l6p29pGx@0lN(8t5<|O7nsVc~e^XD$XpXd(MYA%vnXLZ3y!^ERh;tlx_i1pv# zrVGXOv7!3!%bMX}TqU)<-7G5`=uUPY0?VGXb-IbPMob)y8T81x>X>_;6&h;ZB@3$i ziq3F+j_mxpmkEY0s?1qoNYT(@;|e&EKECR(MOsSG+E}i!22&h?5a*s1k4|KXYk>>S zmnzu^!+b#ja7 zAV?NHc-r0}m{RbhTel|9(S25LR@UlaouMczDJ>+Hm{ypng*AzWQjdmV4a1pELigWNt2KJ(LX2>%zBcK&RSt|?`#AzSIcMG(4yiC^ z-y5Djm{<)ig~K}l9pLkSz2Jd{V!~K?ddy<}MM%f>s+e{9;16u$Pk^^Ej;jNjqWou_ zHTjfZ_5%C@0`Rp%EJ! zum%?3XM1i&FJu2g>tO-GKfr|XAwdgkY@iGu=m>z|2o0tosI_%D1%{)mDE|H6T3YZBt*^gF;~Y=arVItKtXr?9*& z+*s%VV8FeDf^g>}tlb-^GfV^8c*4HraAD+=R6zsitG|`;C8Hvpgoxc28Nl^fp}dJY z@0f{lh~Vv?L4+154);AM2M`vht@*wpyfN!|a}2`XJikt0frV@QQUMBBY~Y89=rK4n+RW_}PYO{krz%@*|zVF@Wk# z$s+)KJ-@Fdy|)Y!K(q&s_3ihG)8xO2tY}E)oyt%AI!#UxZUgEe0q`L@XtgTH0(d0ECwcIa^pn5)xaphgV@HB=4c9`PlO?Xk1KCssZ_QPkWNN>+h2hUO*kkY- z898MQw{hkqCzkkIDFLk^lsiuL)Kl_SUpnsjWs!TlXx&zkN>I!x*LFPk87>;LyDkQO ze?=iXC$U>=Gs8_rB*qskp0%4cyBq&~?U+^1y}aI(txGcQ;#4lb)0whky^Bf@114{O zW~UZWvG=9OGmCDCVR)j?F_CMV!6)jDjz2RdGA{c(lH>F6W)ei@d=w>08y3E9POrqV zH)WzpabYv*+^{SFu_8GqW-l}r;w{6 zyXBX#opxk}i3cXja39A-5UVk=QHkvvC`%QKqckd(a@EJbVuT+yUQC-?=6aH?oFR|6 zi=sSrO;v*tRF76Z#|HA8-8_<*x>^)yG@B%>j#yCx& z+yWB@Eg+NU7|z`{l@Q}$x|+P@BVeyIHF5Z4LLABGiZ4zuxaMd(W_E``yeqo3BgB<^oGLeXock(T4}0D#5bXOStnRu*_f9W&N8;-awc7ehDZd*JTTVE^oo;05m1oMH`+w=<#NGW4Ni zy1CcZMMP-A4#21wr{Cl!@+AOpiuPSdzk}OaOPxPrR7L|WI@G3i?{~*DRTBcRSZ1puX(I6>xn!3oBOG@3T45P$TOve#zSc%hG zk_C2wlqbc*(Z=EL5N~jCf^GRYY~&O+D5D7n7Eu)}QDm@n#1D*`51Lditr>)@qL4cC za}S1#ZzlMclN?FCf+U&cj8>2Xyf3i-@r)XISs>rLMt2#iwA(|5AMIBDjH0jMP3uRB zrA*}sQ}|0T>@?P#@1A(gQaFoxq2l%el#mC|xFM0Nd~TgG8ckcUzE74zr?IrkE6Z!f z_4fSS+&1d8$*p>`0yObDFJvX_G)Bf)7TqUc`l&mI_qQo?mzyHuEzhY;iF=VJd*7u! z6X>5H*|p;Eksxu<7pbXA{pEElwo zzE*_p`#guAYm@)~rN6Q|*-j15A=H4=jN=aTjccGn^{u#KPUa9bn)3k;O7={dVleT6+}H zWT6!D5~N{#4YDfiH7ZR??LRQjeY8m*6Mi?s< z!4%boFZT?RfIu!XuP}vwkoJdp2bXgetTI!XK6FCh?BOSQ*bhR2P>^~kP>(Hl6Jgk0 zTYUT5nlXjdE|9Z)i)9D@j6`hPRUYc%leDiipakHbogmo=UoJY;sX4)>DdS3Y;)w;o z4?4StIm*h>e45EqJ}>d4SQA8Wu5dbqKO~6l5B5;e4W=Bi*O=w*FfPKQ(0;wcQfstP z-!r*Mq)7T`c98MdT18Or0b{eP+3{8gW(Y`3(QYQM$IF@!$pX7&T8iEN21k@czuR!K zvoKeB%!0etZVn~2V4!3_TqSZ*@SQ-V{CDe8{7Y}@LYY;%Gmx88#ODoaO$oY$I@!S|knU6$x3qWwk`k2F~Gkd&Ks3u{s? zFyffOY?3FWiG^MI86_;Pc?N& z(Up-IrI{*^8 z#8(ryP@-tQ84wp(Yr-U9co6*6An?;q?w4u>4`eRD=Fgd*zj(G>V@BCq1JIAZpBB$h55-qa>lp7@;l ziJY1;5ks)KTSe^k-Ae`f{a&A6#={TUE0>P7V)pidXD}pr4*0FZv2i6&M)_P+lyu?J zK7+{}h_ai+!EY@Z?EW>e7`pOxqkp+Q695ul^*;cXYJ8!gX$V$;O#lygW1FtfYAJE zmP(Dk0XBbK|G*2rD#>HCu@#vt$A9EODGif50j7wqxeJOw9Qalq!)wf8p~sinx?@lA z?@AU6M|XPciCbj0sl!G)-&ScD+2*Wjm@^n5s>EA_>)fC8kPdZs^L$D!0ViLJELfvY zoNlkJoZtKtnwr1ul@Ps7z$Q?gqQpJ7yB8{N1~kNp7sZ5F(^ilmqRhHFypcWpa!k-Dn^29cmY-1z*P(7+qwd<^kFq5O|LNnv1XI)elE6iB#Un zhY9=^k9DW-T?(N$f^@ow(>9t#A9 zErcgTtFN&|R)m|+m4yED4HVTl7TLGGvP*uk^F+_! zjUZH5q%QesOOHaP41@xXYGjjm+<1TdUea}8b7F1MMp;uf8}$AxiNd7rd}7fA`+|^z z1l=#&BuUS(6S!^uB}GX>|LbvXbcx(Ox(Hk6xX&}$o!TZM{4AYnyI^n^hMpYn*2-FO zkg!eCco&NNShETi+wXm~Lcqj(oz#`|&z;a&bdXNHYuNkIcaU8(u%Nar#3Q1Gh=VVO6$>bwy;eB#Wy_eC$fJ&eO%>4;> zFudIM+bS-{inbi#u9lbl*&shsrR3t|AA^YLJ_y67T~+FZeJq%`R9n9tD&s>)4kJ^_ zCi9IlvPhWPx(%-iMDDNo!{pSoIXMXP#a7t(e#=Tb7-BPsNmO;H-FG*AHq6E>hiwMV z#!Lq|;3eELH;pe2|2|RBZ`$fnnvkz1&Mqk_wKKW3 zS?9FYX7pFuZh;DWW^7~1Z?_}-;VqeUaMvcF^wU$Nk!xdvX|JvVZ1&WvqNrk11Ci)r z9i%Il)7R(SGbc#TRA|Mjq{Q6Qjel(9I_?wt&y|Fe$r|oQTiCI-#Dia%CbmM)(ucoJ zxfYpQBF0R}wl69xyQ2mfs}jt`11a@+ipm7;^j>_%SN5#H@pwj9c|4j%?J^=gC9j%HbmA zdCL~ddS@rc-LY-Lx&Ucre`QN3bHtfbVt$;Fj$I4tFs)CQU9v8GyFdq%md_y92#)l} zO{l(OQ>E7rsdmMkr!b@Bs65*Dw5Vv^G3@wqd0fkQ-1bY~=cgcH<%ALvrLU%Dv6|t=2Se@%3Z0K&SJeLGoO(5qX=LB@#=uF;wuZ zMj$)J(3rGDb}x>ny5vDO+?uG$@|$77dHzF-b@Z)R)2f9JLE>*+cuYwY)>?#Dl!jOuLYP>Kmn}UJ6LT+^gAp^?@llgOrQu{WT{l{%K5uJ4M33 z<%0F7+-Ewzl*yp{V!J@E$?@+(yt3+{!l-$95#Rjv<>KTA2cr!3Y~qM8ZGv3=meRXO4G`*G{%*l7iJ|5u=5`qGZOjsJ_5clp}caSa>GL1u>+CkN}* zw&AEv%S48tm-&{Q!z=h9XyGe!wZ&u>?L-GygIceN&j1zLAM zMkm`DvSsLAQIriSL)(9)JQB2b(YUxYbK2;Rq!HMTq{!2OiD`D=+1V_r-<|k;Bc{W>GE?>t+~?bCn9sbY;A$J~TT2!PdpeCNwwSG2>6 z=^$3`)7+T6yjs9J(}hQ6#Qw9A?<@7^3se=0<*Moi!7i+W3FuWZN_6+mgkis?!7zxh zYnSh{ay1di^EnQFTZ2VZBE0>^JFgQ=#R}|d%q~xR`z=GJ;H72x-w>{e#CW(EFy%4g zU1&xOiFOy@JwI$fH|(=+9F6J(oea1)<#THx+$m3ti%)~A3v#y-V~jc*#j!xnW08+V zLQU!YhY;~=U>-v8NX-xZ#X@WTAj#%-7Bbq%t7z^CCVf4ml8&v$uPDGPCCl9LulZI%3PI zbU+VoVBmp%hlSuD9>6=|Z$@SUO{8Ro{o{Mh#+n({y*d3B7I(g8PLlkT<86xdnQ<^* zQwmX@j}MMkpWEf50})}$0o)SOWmT;kb0)u-9|~cjvMDZb-JrIv*_A7XWcG%9 z$6avS{bF15MvOMZs24WC z4dm^kaCSLoQ(~C|Fcj~7s9G03qwF$T)KytHn?vHPk+(UuB=yJ9*7Z6a-($3X zq2+DNcGDGOp9X?s*Z$LNf6AjqWuv?{XA+2xNia_wreBC{qj2{`WKjT=vt7dUmD9an z=^XJTH+DHrHV%mDpnW3dL<|Btmsz{7LgFGXTftM)#?e9PEjnORZcmZP#%-_hNJ}+k z#Vs#3dmC>>2WL<%>xGEA{6f*V}p1D>6U#fEd^_fJ$t zU;d8J;g`$4@Mg7w8?v|7?tW_+**nvFZ$y%}eFib^QR+nsV#BXZG?!-E=x6k z{)myzr&0@A|H{o8pgb*D;d>H?cJ^SSoUnNd87O)jc9cjmcQt{_#anMTgnbw5LVW&V zC%d3i6fb62NHrC!ORPadrUCan*z->#L#+829&Jdjpfir)FN`$YdI)6d@^7p;-~T+1PkhdyqFj zPcS}-j06JUhiQUMn*}tEaw{geP22H(Ea{eVEX<=)%v&zINxdNLepj$dyTfcF zRseAi<|{1AA{#mKg|^r5a}0L|@QnE`muNquYPGxM!@iEIx3iCvd+-6{o|Tx0;B#(r zNejf}!hp=O(Y5hopTE9avU+Kv*lZiu>gbm8GWw z9rPCL3J4@`k5Qcw>lJ6*cWi^WM&*A027kcSlZCqQf=#&|UB?h-98RBT99m5EnIWk* zc7&(MDvwqZ)vRpws@wA_dpYj;{ED*ZD?-xSr>}fpV12#f6u()bSv{LW!%ieLgIQ9{884R`YRham*6mEW}ANzCNju6`ErAY_Dot4G_{K zmUbjpm3e$#Xe@wjR$IgbO^+E1N6{_i=CY8_U{uvYk@Dku{Tc}HUG=*KKHc3#eSne( z42ic^NnT*+A6w~~n@R-ud>e3)Sjt|i{d%?Bl#I4XyS<0a6um_{PL1q$SxJvk2|0Z? zDQ?Gj|3j^f|4Xx!aWZCvj?&?cb?T!`oTnCUR%o^erE%gD2@O~C8=*&4(#x=n_q&kB zNoC8z6yc=QSWcfao(pr15cB&26N_RWD%`Xy365@)5J_q(u{@dBlEOB8A3fH44}`0Q zn$g@@zLYli)|z5kVJfjHjsC0_7X`Sa9MZyYPnrj(>|*n{Kw=s3Cih*NpE0n!^PQ8Hs_vuh<_g5mm$Q;vyP*F0ss4Fxa^bH1Qi!Ow(EDK7TRbL{rz{sGzqAu4)yD-rdY3gzl2Z5%B+eF>9{rhP6thIhZU|Zd7;M1F z{3E+Nw3futDp5*?tF?zDN3a&>P3H7lqBB_)04PPhpHepjKT0&enM*e-jttU390ca- zl~0dT-$>1SVvovrvVeJfiteUX!MTv%__q1sbpe0l&d0*Z>ozY0 zqR9a$l;HIX+-2Xj_MX>SLf3p`1-j=S^BfWNdvygJxC(`W^2VfidPK z41rjL=G^-;dEc~E1=d0U4EZ3Hs=B$Us@ZW*h-(qnp2kYZXcig!1dA5y=DOGtzdZih z8AkaQMhbQjq#FAu%W4?y*1806uOrLY`KTw*Z0uBnV?iVvD;EnTQm=$YV5C?xxyGP1 zlHfuUvB=Y==yaJYL`vCnVVU`K{)i>E80H>=S5dH?Pa&?!U#pmw*865gY$aqB^LTstEn*?r7g;3{ zntRd(k5XBrrtFzY$<$Umr6iq0RNB;f)k3~dG7BRJMXcsX*+SaIAZuBduZ~J*8yC@FQkNM&l^9xYiHkO>OQd^Ji0=@iWmWEu1zh4C8 ztKi{DC3+-g7TImec+3#1m{%bp;@sh^^|`mZ2U5s+6%j56QCSs~dTe}D!~V0u9;!V8k#uG>m^EjG=YhBTM>EPossIkjZW z&56IIAM5;WzYm{%UXD$iHm{~n%F@V5H0Qet@?brvr zkj4Kj7>GwMH-dKx^H}yz;A%)}b4ZlVwJ(xa{Oi|DxP`)nT&d9bf@7leevwtvReXfxM6N}7csFs6ic9SRWSr{ZSz9Gh4IJoM1{CgbXLua zD~+D8xcBw*G)smWQy^ch&fAVZ3Af`vY85kCo^%_pjSFgG|BuGL0;Y~=>$*@1#ih6x zmjd@*oZ{|Qio?Y&aB+8vySo%A?(S~I-HW@s6qlcuPxA7=mwYdoWX?IWk4$DVdu7i) zYgw6G?(L|{$^eBw+oW5-ld#5l6}cfCv+lzJZa!#e$~LP z+6aT?`%ENQb80oUnFmH96b|KLR9kFHnht!TqZFX=rKHLa(pd;9C90cwsVj2Nj0t3l zdyDnt#zPJ29~XbAna^#~CahM_x4lZ`Iai~zEM1>|uH)Om^!+I)t%QFVE7B6`RlO`Nia&eOni-zIh@C@DeT)bPK}`)2?Eww| zwt#6bZ$zsVjT=z3RBDB$_8TsEN2;Ct1Nm!DKIUoXz7>z_pp!U3U0xNu_Mt{ z-S~tNs!6nED@ecK;e(@o&3|**(RqykM7VJQ^M{Dg>ErnGzH*qRxdwI)6+)(rh(SBU zlExQItc)%`Lap*XHt&YD-!UFG47Q*Volv>*=Zz50b1g?F2jqqpRuc^5wdx$XAG#}! zkaba&Nlj48zz@~Xpw?A~Uj2a*6sg9$fOqoylox3@fcA)>kUx%l>8xk;kCrptV4Vqr>RQ8aqaf#Hl$DbQO0R_KS7()zI8P zB(BoKRAf}sKB~>y+frNn*W=_{_^tEOw%iO zKl@Kj7CncHjU;?*08^rBiNzn@OFR!7BUY-i&H*Q7c$T~q4sa>K0{;aw9MPvQWCt9W ze(J$4Ox**7VsjJ;xK8cnJLPKzHz25(V`C0GXxG{2QRvDaC<8?=F5Gl zKPs!2)x3vQ5T3{4*V3#4a5kje+9j#3n?JSHsh8*BObhNVVavhg+$*_9;Tu#|#QNcf z)om8l)oEGR$pESY&`TiYP&g=R(eHJ{(7!Q@@z+$p%*^GTYARk0x*x#3i7Ir&<)x}* zSSo?~TNt0Wv42wLD^rb;3&dTT;!b@GLYUL4*TK>=t#DxvaA8h;2UCkVr?D|`SYMHu z(Z>G78H<}CG}vrxE=dt)PTkulD^_1NVYElpX@Dm^2AD2~LKll6O<5-!24RLB#5UCq zKS4)2>Z4!iBX#-o$aUot;NDdk8i5$^?sUt zbvO{%jo95_LHo*_`^w@5LJ5_v=C{WztEr28fo8^dJcnUiB@&L2_6u}`LY5f==by7l z_Zvm#)D7dja;zm%@Q^>dx$!#fi?P9)BylgZR(%W=3zEJug@(j$gg@6!(u*yAD;DfIWp z^`oxY)P0@4?=^UQbdgu3v#4X~|2y4sFyDKNygXt@y?L-Od3>6`7q z1MG=QFde{^fQtzE7+0G=f@xUZ8e|wzN%g%16MS?k)0Z8b#pT$45ij->jKynZMY%v= z>(`iW(jXfsGNIquO6ifEzWN$5{KA{Jr4f} zvO263JC%x>APnPg>47nv_XQ!B7z6*LHc1G`J)7u4uDN{quoolbNmI&)hHe zLG_(@%fswu9rTlpyFuMf#ufxqy6skO%DkVyjwNo*N_w@;Y9k&uPJmAXD?CQOaP9kA zdFIl})S;+Yj;f`&*U_6Eu{a5|6&(R}hAI>0q|d|KlN6oHypmMS6B$$L54OK%F@t-o z59=PS-M&2q`3iXmxbZ``g%sRR9fgZxR|J}+NNTwC!; zgKuzYR-F$aCy<>Us@h9_KM=|iKHj;^b5lPD@;@;S^5$#moHgG?=&7m!5>tgmhE_$l z(>k^Y>IG@n?FRVW1$kEtWnt4fhQ(9 z*3Aw_SJ^%HEavub0Y!?Lu(2;Hx!WN|KQ>%l5c?{YozzjDeh?!J)?lyjx)_)26JA%N zaW>a=UxeT;@5GgPAsR(P^T`r~R+25rm7A^)@@tPWqA={-GIUq9QQ@A&Qt7D-8#Nc+ z`u=T~$UQgK59$68vKp1s(pItTQzm5;lcwse@rg?kF~C@Zu&Bh4emi&mvco{Ph>Pw7vLf?X3MHkX0td{PBj5 zK@3eeX70B%%qsegX4U8wqMqcY_;|4gtVb#%F#xv@WUEiVX@Bv&p3g|H zox}zi{DC_BWvhE>f;D!kypaNt^i&fT94y>JKuP5BCZ|e!jNP%5XkUxfYOb>`Y-ndt zB&!`G+LjU#U2V~=p}>pu8ab+1#4E}#6Btg+=f>g1%*f%IvBfVX844bjt@N`(!JYuZexWM~A zwRO#A_pm7R9Sx~lCZl=IRUefT#Rz=8(7T1+l_DP6rYYGh@QKaIqh`uEQA!Ep?35XVG%N{R8Eequ^N!i)Vt znnUu;n>slpX`I=4l~{SX>U!M6t&QA_gWd57O)66>P2MPyr#~~7+lV@(lk7uP`lk|( z3Go+4e{eTqKjkZ%khpTUJO~^$#I+TK(4SVsOOGrIP}?IB6OG9&RVv}I-e+YN~< z;ujqPn1nki30kE|N5@Zh?wEMPisxJKxalTC0dfptO09Svpqh2#@pr3u%ih(6e~KzS z&X2iN;cneaXn)0QssBAR{Jno@+J;v86sR%Iny7dgxd8qlW5jJ*sa=ao42RGz#7lPb141R*-MBs>H{60;XfLlX^TSjPi*%e)(Co zg^%BhKZVq*pdY(l^NXKzhgs{gPPjt8MATTM0u5@GfV!;w+GeV2i6@vQrYTW|NE_if z=Xpwgad2V&qWAWu^?CB;jHNmuo&NJg^KFuJL(GlGnZVbeufnMWyVs1_^UgT>afNp7q%{S_%BZ1wy1VDDy8p(oex#2CR zpEGA`C&;QobnE($k@4q+e5vUfks6p;fore)ul(F4wHF?s%&~S{$JS$eL&~`8v)iCE zw9l0a2xVn3oOYe4;r%3q8dW_-sYJy*T0;l$e>OJBzqXI`OT?Xp9o)|^c#X@`tl>V# zaPO7|GLJu!C+#tM3(z39K7sg7`EGROf6OR^U7dzhsj%+2PP%K4?ntD1M0QB*&y|u5 zO=Fp#g^=#mR3u4+RZNFn#a*nOym69#eR2CmbZ35PD0I4KfW&-*?nbHgczp761wF`P z;=QJYUP`sX)9swv*n-86vB_tF%qvt`{?*_pB8|J-#|qMpRcijz6Eym8_Vjz316+Gk zYfw-}_n&1mk&OEBL8qtHc8Vh*r>)1@YLd9##%Hn{*xwnw4jz||4<}kCyf0J&Xx<$I zVo#pbt+QcBqE*2`QC>sc9vY?2f`?y-LW|7=1B|fQj6X1`54af0(Zfmo#?=kse^47*@X|nKRJn)J&IPW#v_C&@~?7+r>$wX z^`eYvYibsgrLY18D!yi2Z!a}KhhJZ^jUZ0kX9&{KG>C~~`SDE-_rp^rDlge_%~x^5 z$e>U!-7(y_3a~tWu{(y~k631kim<^06%JS6eVA%n@=IeZ@$+oRr5lPBXLaScZoAvf zA$R7D;HGIhRU~&_5cjdZU#$!#wNQ01`S5#G?JpC zVdwl|^oboyxuip6+awf9%xO15eH z&~ZBRES|VO`Lki1R7eONZR#%yqRx)^hjKM^R=6l<%%cs8e*MhY2-(rFlPHDEws+KI z@Za2cw8r+8RzoK%B(wZpn%4V^h(PgeHp=;Exs~`Gd zXt%-R`+A7G@pINYP$zzFMnV5m4-W9Tm&dHhA947To|`yY>orhM;865$<|hf`xpf5I z4VXVW*3$b(t}@Lm3UnuY2Wpzn;vAN*Cvht$A~d#i53~nkbi9Nn!hf=bYS93(8i zr)K-SV&feQ+mgET)6TXMX|6*`?}rC^M32zr^Y;fKADzlF9Wb=#=pk@fgBwFc6Skg z#YUwy+Y*k0>Kw&{?WOjf_VGDGc zC#1|UJVIELtYJP<3Zzjg|C*~4qkOn8pDXz%Kw3=dqmKV{qT&>DgANzE32L)x<{tN6 z%AUs6>)LJm+N;j0f>%gO5HKw0zQ+QkHv(!@{K4j`(l$p4CSi#DTaiO-dpoT!@`i#_ z>2rDqmWeHy7Yj@GeH4 zixD+VPODZakCO9AZywPbGuZ;|R}3_>N3J@-2g4x^ z#kMI~5+w@>4)vXf=tn-fh!A1w>>*t{xBq z-jw9c0E#ZqpFt}ukz`4*1q=W!Sp|M{IUH?W?_H4H2kf2q8Aw3h(_H#dQPd5616h6%eD2MRX<0CyA)V1~FMYW~_+t<$ae z*L*uj{44#nHLJm}f46N%7u>q_4@v)zIG;Ycr(h&{AfE@);?AM⪚i8=+Y8XIC%%a ze-vmykExDPOx}xJ*Y5I{?K=Tvy%cG?$A?|Sn+uzy!b(#3U{f( zdOu_b`(?h6G}%g^u87uTv*-)1Jmx+7MwkCps#g_xqnZm*(BLHe`YGro`EOtbw<>n6 zEh)R{(G>|a1otWxNjm@Pc`3qaW>k~!N&Ju@$GKU%qkS;S=Mr|ejd6E50lgFoNVCRX zUb>)ruJfB^>1`ro{UqM9&CVpxjgUL0 z=rlvZSZhJeoHgwy?5D-UQ_pP{X>QY(9|Dix&BNkfJ=m1BX0aDY_Z}h_(wfTT6I4jI z|J0TUVuDw}sk2UX)dx3iMk}p5$A^yvhBiI#(~l^KGx=VJmlSaNahLD*f4XY_Y5c%= zdmHM&O2%cVIc*QRV`kdip01*+$E9U&aeOzlboHon5?BvaqOjwz^<3{3kTW-10b8#6b39mQldZ-}f zVcW`{Gt#ActE_uq*VtU~a(Hu;A&s@>o2+jJykgnukJsjSoFYYQ6)J5YBA#>MhfYql z+ABv-Ph8?LV+)OMYD^6Bhpx~R7Syo)@I}uym(qjhn1$__XE%vc7gYqM?wX^Mz@=TD zsF%kJ)(WKNTUP|}m-g;7Zf0HUP=u_NzjGk7`?^s)9D6@rbEzgCW7-@_T-py3%?=Um zRACNbF69F0-vllTXAh%rZchccisN>8tZglv8~?7d%b<}Eq7)tMIz*TF=WJ*M86?3M zWH##IN<{rVOih^bG8_&yzRkYXkCw>kf{YKNS&C@VO7}kdon@R1*!)RVyC27sy79&0 z1AmXY?Js5Rc6wf9_fn$k1~#Ue?rt8mG}#cq;Z_xHh9$D*Ur zO!jqKv)q7;c{E38$YItCMfQP}*x@%6nIfFQ53~BuK0P6nZs$d0bStOC(B@ zZflorsPy2cAJRvLH8cPB#i>-}*>*WKNGw^dxuyr7RaFEFaN?J9ivAtGLE22h=C?+h zwcAOA58oRZD>tt0@s}LF0PLuxmO6$0XOA?2b2`vNxY$?=*~;i5{3E(r4eo7vD2LZl zv_{+KWDRH$U)pN)kFwoPpOb=JT<1!o>Xu80efu$RCNE3W$)nN6dD};U({RnPe}jEE{~7xTIXakH+tJaps6ZVoAaCbyjs|8BLx;DL z$eUuc!`n4keHDm0xii$kl-%?!SHjK?VoYwMZ)mP>0-G66Vg0RY-J zJ2`8k|I0+hPT$4`V)UkOt#4ruL1Ix<5mRRtceJoD(6_RB)4irsF@@Tbza9Uzo-gF8 z5Ig&~smWQHfowo_ZV(4M6Ns7Pf7bbC|8{S(P$vjE2moYf5rr5)^{wd1&297@Ozk21 z=bwP*TW;6kzfDQjY}v>xmQmauPA{-K`?lR=0uZrbA66u+}_M7Q#R(dz>T&FjUG$2-yW6MXd2_wUwS-6WA2}6(IeSBb- z9@F0s@%nVCfVYr{M}QukVLbWLZ+&7hSvp^?Cuy)NT&tcmRweEe1)&gL85IcEM&Ck| z*wD1z@S`7kDA#nK2mGX7KDvaqfsH!i-LJ*R>p}DI7k4?uoEi<26QhPd`4tPsM+=uC zPwzD|7IUBz&l6Fap1xW7I4sV=dwiN@qYBqMIT-tt1sI-v1ef$LhwP~>V%1~buzY@Z zf0?C{SO{VlZwcWI7xk(EVQL52O}gb+-@>c6`{9<)32UC;F%yJ)g)}I|W|j1v^Xxe( z;|uB`0twwR1v2koKDBucTTH58RZNCDhd_lQR-X=-J)SVGwOEhj1}#O&t&E4nX;)4` zJ!0)Qgtr&%f^^BOavdftUlkQlpLAY}SP!>d4m-oX@!ra~D0e<4ZTX#FG|e`+9Q-Ol zYCGorQ6RFZje<^=z3O4HF$8n_iho)%yiqoHweM=W@dHPG&^obgox6>A^Kr zTGt+W%W?CV8SMn`aT7p!OEB`q|aXVj*KJ_cBi@}4X!iM^9Qq= zbQjwjUT*0&@fiiO9|ilNiw;Uw&HIg8V^8=jaU`uL9M-!j`|NH9w&+OTD_O!XHgXQkW;YWIcqGWtHdrU)=t@2MSlzsEE-HTn>^ z9Bm%Iwj^D5O}I0UAUYn8k^r$N%UZM%usGDDOEfaM!N_I2pN+v{haoEiL zM6m@V-BPYO*W&tIl6WoV5K&y^=H$WxwFY6X1#*vq>;Ij<Py7$_U~@ zt_2_ma&qY)v3!HNLHkYNF&? zyxbshA#N@aEPg{bMg$o;4FEU zgf(Ghvd{?iaY_T-#MqiILF!{{tHynhp*{F>WX)X~IuT?Gf7A(Sp9Ctxow`mLT81ljlx#A=TNS=N^fN^Z{dzzbV;V#> zQai#A7^8mdbn+f|psi(We$;MyUoS-K=NY_GiR{!vy6@9Af$Uj{&M;9?*y_;s4EQKw z^A4^1Gkzc@7m9=)c4Rk@3ypT2D$RG=27Zj;fvjbcyLa1n+O@Z4PaY5ZEHIs!fuD&- zNBQaL)Ir1S;n+cpu$W6HfrcloTuMQgJ3^{rjVnTiZ0)N~(vMN@6~*GmUA8PXzD>5G z>wUjzxx9ut#+JNVt}_R%gMP9C`n-+}2MIAP%hTG>t^#>hhJ54n(_$B{QwN3KFa-JA z?<4c7fRat;lZ7> \bar{P_t}` then the Kalman gain will go to 0, +signaling a high trust in the process and little trust in the +measurement. + +The update is captured in the following. + +:math:`xUpdate = xEst + (K * y)` + +Of course, the covariance must also be updated as well to account for +the changing uncertainty. + +:math:`P_{t} = (I-K_tH_t)\bar{P_t}` + +.. code:: ipython3 + + def update(xEst, PEst, u, z, initP): + """ + Performs the update step of EKF SLAM + + :param xEst: nx1 the predicted pose of the system and the pose of the landmarks + :param PEst: nxn the predicted covariance + :param u: 2x1 the control function + :param z: the measurements read at new position + :param initP: 2x2 an identity matrix acting as the initial covariance + :returns: the updated state and covariance for the system + """ + for iz in range(len(z[:, 0])): # for each observation + minid = search_correspond_LM_ID(xEst, PEst, z[iz, 0:2]) # associate to a known landmark + + nLM = calc_n_LM(xEst) # number of landmarks we currently know about + + if minid == nLM: # Landmark is a NEW landmark + print("New LM") + # Extend state and covariance matrix + xAug = np.vstack((xEst, calc_LM_Pos(xEst, z[iz, :]))) + PAug = np.vstack((np.hstack((PEst, np.zeros((len(xEst), LM_SIZE)))), + np.hstack((np.zeros((LM_SIZE, len(xEst))), initP)))) + xEst = xAug + PEst = PAug + + lm = get_LM_Pos_from_state(xEst, minid) + y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], minid) + + K = (PEst @ H.T) @ np.linalg.inv(S) # Calculate Kalman Gain + xEst = xEst + (K @ y) + PEst = (np.eye(len(xEst)) - (K @ H)) @ PEst + + xEst[2] = pi_2_pi(xEst[2]) + return xEst, PEst + + +.. code:: ipython3 + + def calc_innovation(lm, xEst, PEst, z, LMid): + """ + Calculates the innovation based on expected position and landmark position + + :param lm: landmark position + :param xEst: estimated position/state + :param PEst: estimated covariance + :param z: read measurements + :param LMid: landmark id + :returns: returns the innovation y, and the jacobian H, and S, used to calculate the Kalman Gain + """ + delta = lm - xEst[0:2] + q = (delta.T @ delta)[0, 0] + zangle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0] + zp = np.array([[math.sqrt(q), pi_2_pi(zangle)]]) + # zp is the expected measurement based on xEst and the expected landmark position + + y = (z - zp).T # y = innovation + y[1] = pi_2_pi(y[1]) + + H = jacobH(q, delta, xEst, LMid + 1) + S = H @ PEst @ H.T + Cx[0:2, 0:2] + + return y, S, H + + def jacobH(q, delta, x, i): + """ + Calculates the jacobian of the measurement function + + :param q: the range from the system pose to the landmark + :param delta: the difference between a landmark position and the estimated system position + :param x: the state, including the estimated system position + :param i: landmark id + 1 + :returns: the jacobian H + """ + sq = math.sqrt(q) + G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]], + [delta[1, 0], - delta[0, 0], - q, - delta[1, 0], delta[0, 0]]]) + + G = G / q + nLM = calc_n_LM(x) + F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM)))) + F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))), + np.eye(2), np.zeros((2, 2 * nLM - 2 * i)))) + + F = np.vstack((F1, F2)) + + H = G @ F + + return H + +Observation Step +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The observation step described here is outside the main EKF SLAM process +and is primarily used as a method of driving the simulation. The +observations function is in charge of calculating how the poses of the +robots change and accumulate error over time, and the theoretical +measurements that are expected as a result of each measurement. + +Observations are based on the TRUE position of the robot. Error in dead +reckoning and control functions are passed along here as well. + +.. code:: ipython3 + + def observation(xTrue, xd, u, RFID): + """ + :param xTrue: the true pose of the system + :param xd: the current noisy estimate of the system + :param u: the current control input + :param RFID: the true position of the landmarks + + :returns: Computes the true position, observations, dead reckoning (noisy) position, + and noisy control function + """ + xTrue = motion_model(xTrue, u) + + # add noise to gps x-y + z = np.zeros((0, 3)) + + for i in range(len(RFID[:, 0])): # Test all beacons, only add the ones we can see (within MAX_RANGE) + + dx = RFID[i, 0] - xTrue[0, 0] + dy = RFID[i, 1] - xTrue[1, 0] + d = math.sqrt(dx**2 + dy**2) + angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) + if d <= MAX_RANGE: + dn = d + np.random.randn() * Qsim[0, 0] # add noise + anglen = angle + np.random.randn() * Qsim[1, 1] # add noise + zi = np.array([dn, anglen, i]) + z = np.vstack((z, zi)) + + # add noise to input + ud = np.array([[ + u[0, 0] + np.random.randn() * Rsim[0, 0], + u[1, 0] + np.random.randn() * Rsim[1, 1]]]).T + + xd = motion_model(xd, ud) + return xTrue, z, xd, ud + +.. code:: ipython3 + + def calc_n_LM(x): + """ + Calculates the number of landmarks currently tracked in the state + :param x: the state + :returns: the number of landmarks n + """ + n = int((len(x) - STATE_SIZE) / LM_SIZE) + return n + + + def jacob_motion(x, u): + """ + Calculates the jacobian of motion model. + + :param x: The state, including the estimated position of the system + :param u: The control function + :returns: G: Jacobian + Fx: STATE_SIZE x (STATE_SIZE + 2 * num_landmarks) matrix where the left side is an identity matrix + """ + + # [eye(3) [0 x y; 0 x y; 0 x y]] + Fx = np.hstack((np.eye(STATE_SIZE), np.zeros( + (STATE_SIZE, LM_SIZE * calc_n_LM(x))))) + + jF = np.array([[0.0, 0.0, -DT * u[0] * math.sin(x[2, 0])], + [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])], + [0.0, 0.0, 0.0]],dtype=object) + + G = np.eye(STATE_SIZE) + Fx.T @ jF @ Fx + if calc_n_LM(x) > 0: + print(Fx.shape) + return G, Fx, + + + + +.. code:: ipython3 + + def calc_LM_Pos(x, z): + """ + Calculates the pose in the world coordinate frame of a landmark at the given measurement. + + :param x: [x; y; theta] + :param z: [range; bearing] + :returns: [x; y] for given measurement + """ + zp = np.zeros((2, 1)) + + zp[0, 0] = x[0, 0] + z[0] * math.cos(x[2, 0] + z[1]) + zp[1, 0] = x[1, 0] + z[0] * math.sin(x[2, 0] + z[1]) + #zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1]) + #zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1]) + + return zp + + + def get_LM_Pos_from_state(x, ind): + """ + Returns the position of a given landmark + + :param x: The state containing all landmark positions + :param ind: landmark id + :returns: The position of the landmark + """ + lm = x[STATE_SIZE + LM_SIZE * ind: STATE_SIZE + LM_SIZE * (ind + 1), :] + + return lm + + + def search_correspond_LM_ID(xAug, PAug, zi): + """ + Landmark association with Mahalanobis distance. + + If this landmark is at least M_DIST_TH units away from all known landmarks, + it is a NEW landmark. + + :param xAug: The estimated state + :param PAug: The estimated covariance + :param zi: the read measurements of specific landmark + :returns: landmark id + """ + + nLM = calc_n_LM(xAug) + + mdist = [] + + for i in range(nLM): + lm = get_LM_Pos_from_state(xAug, i) + y, S, H = calc_innovation(lm, xAug, PAug, zi, i) + mdist.append(y.T @ np.linalg.inv(S) @ y) + + mdist.append(M_DIST_TH) # new landmark + + minid = mdist.index(min(mdist)) + + return minid + + def calc_input(): + v = 1.0 # [m/s] + yawrate = 0.1 # [rad/s] + u = np.array([[v, yawrate]]).T + return u + + def pi_2_pi(angle): + return (angle + math.pi) % (2 * math.pi) - math.pi + +.. code:: ipython3 + + def main(): + print(" start!!") + + time = 0.0 + + # RFID positions [x, y] + RFID = np.array([[10.0, -2.0], + [15.0, 10.0], + [3.0, 15.0], + [-5.0, 20.0]]) + + # State Vector [x y yaw v]' + xEst = np.zeros((STATE_SIZE, 1)) + xTrue = np.zeros((STATE_SIZE, 1)) + PEst = np.eye(STATE_SIZE) + + xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning + + # history + hxEst = xEst + hxTrue = xTrue + hxDR = xTrue + + while SIM_TIME >= time: + time += DT + u = calc_input() + + xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID) + + xEst, PEst = ekf_slam(xEst, PEst, ud, z) + + x_state = xEst[0:STATE_SIZE] + + # store data history + hxEst = np.hstack((hxEst, x_state)) + hxDR = np.hstack((hxDR, xDR)) + hxTrue = np.hstack((hxTrue, xTrue)) + + if show_animation: # pragma: no cover + plt.cla() + + plt.plot(RFID[:, 0], RFID[:, 1], "*k") + plt.plot(xEst[0], xEst[1], ".r") + + # plot landmark + for i in range(calc_n_LM(xEst)): + plt.plot(xEst[STATE_SIZE + i * 2], + xEst[STATE_SIZE + i * 2 + 1], "xg") + + plt.plot(hxTrue[0, :], + hxTrue[1, :], "-b") + plt.plot(hxDR[0, :], + hxDR[1, :], "-k") + plt.plot(hxEst[0, :], + hxEst[1, :], "-r") + plt.axis("equal") + plt.grid(True) + plt.pause(0.001) + +.. code:: ipython3 + + %matplotlib notebook + main() + + +.. parsed-literal:: + + start!! + New LM + New LM + New LM + +.. image:: ekf_slam_files/ekf_slam_1_0.png + +References: +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +- `PROBABILISTIC ROBOTICS`_ + +.. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/ + +.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/EKFSLAM/animation.gif diff --git a/SLAM/EKFSLAM/animation.png b/docs/modules/slam/ekf_slam_files/ekf_slam_1_0.png similarity index 100% rename from SLAM/EKFSLAM/animation.png rename to docs/modules/slam/ekf_slam_files/ekf_slam_1_0.png diff --git a/docs/modules/slam/graphSLAM_SE2_example.rst b/docs/modules/slam/graphSLAM_SE2_example.rst new file mode 100644 index 0000000000..bcc797ba3e --- /dev/null +++ b/docs/modules/slam/graphSLAM_SE2_example.rst @@ -0,0 +1,209 @@ +Graph SLAM for a real-world SE(2) dataset +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +.. code:: ipython3 + + from graphslam.graph import Graph + from graphslam.load import load_g2o_se2 + +Introduction +^^^^^^^^^^^^ + +For a complete derivation of the Graph SLAM algorithm, please see +`Graph SLAM Formulation`_. + +This notebook illustrates the iterative optimization of a real-world +:math:`SE(2)` dataset. The code can be found in the ``graphslam`` +folder. For simplicity, numerical differentiation is used in lieu of +analytic Jacobians. This code originated from the +`python-graphslam `__ +repo, which is a full-featured Graph SLAM solver. The dataset in this +example is used with permission from Luca Carlone and was downloaded +from his `website `__. + +The Dataset +^^^^^^^^^^^^ + +.. code:: ipython3 + + g = load_g2o_se2("data/input_INTEL.g2o") + + print("Number of edges: {}".format(len(g._edges))) + print("Number of vertices: {}".format(len(g._vertices))) + + +.. parsed-literal:: + + Number of edges: 1483 + Number of vertices: 1228 + + +.. code:: ipython3 + + g.plot(title=r"Original ($\chi^2 = {:.0f}$)".format(g.calc_chi2())) + + + +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png + + +Each edge in this dataset is a constraint that compares the measured +:math:`SE(2)` transformation between two poses to the expected +:math:`SE(2)` transformation between them, as computed using the current +pose estimates. These edges can be classified into two categories: + +1. Odometry edges constrain two consecutive vertices, and the + measurement for the :math:`SE(2)` transformation comes directly from + odometry data. +2. Scan-matching edges constrain two non-consecutive vertices. These + scan matches can be computed using, for example, 2-D LiDAR data or + landmarks; the details of how these constraints are determined is + beyond the scope of this example. This is often referred to as *loop + closure* in the Graph SLAM literature. + +We can easily parse out the two different types of edges present in this +dataset and plot them. + +.. code:: ipython3 + + def parse_edges(g): + """Split the graph `g` into two graphs, one with only odometry edges and the other with only scan-matching edges. + + Parameters + ---------- + g : graphslam.graph.Graph + The input graph + + Returns + ------- + g_odom : graphslam.graph.Graph + A graph consisting of the vertices and odometry edges from `g` + g_scan : graphslam.graph.Graph + A graph consisting of the vertices and scan-matching edges from `g` + + """ + edges_odom = [] + edges_scan = [] + + for e in g._edges: + if abs(e.vertex_ids[1] - e.vertex_ids[0]) == 1: + edges_odom.append(e) + else: + edges_scan.append(e) + + g_odom = Graph(edges_odom, g._vertices) + g_scan = Graph(edges_scan, g._vertices) + + return g_odom, g_scan + +.. code:: ipython3 + + g_odom, g_scan = parse_edges(g) + + print("Number of odometry edges: {:4d}".format(len(g_odom._edges))) + print("Number of scan-matching edges: {:4d}".format(len(g_scan._edges))) + + print("\nχ^2 error from odometry edges: {:11.3f}".format(g_odom.calc_chi2())) + print("χ^2 error from scan-matching edges: {:11.3f}".format(g_scan.calc_chi2())) + + +.. parsed-literal:: + + Number of odometry edges: 1227 + Number of scan-matching edges: 256 + + χ^2 error from odometry edges: 0.232 + χ^2 error from scan-matching edges: 7191686.151 + + +.. code:: ipython3 + + g_odom.plot(title="Odometry edges") + + + +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png + + +.. code:: ipython3 + + g_scan.plot(title="Scan-matching edges") + + + +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png + + +Optimization +^^^^^^^^^^^^ + +Initially, the pose estimates are consistent with the collected odometry +measurements, and the odometry edges contribute almost zero towards the +:math:`\chi^2` error. However, there are large discrepancies between the +scan-matching constraints and the initial pose estimates. This is not +surprising, since small errors in odometry readings that are propagated +over time can lead to large errors in the robot’s trajectory. What makes +Graph SLAM effective is that it allows incorporation of multiple +different data sources into a single optimization problem. + +.. code:: ipython3 + + g.optimize() + + +.. parsed-literal:: + + + Iteration chi^2 rel. change + --------- ----- ----------- + 0 7191686.3825 + 1 320031728.8624 43.500234 + 2 125083004.3299 -0.609154 + 3 338155.9074 -0.997297 + 4 735.1344 -0.997826 + 5 215.8405 -0.706393 + 6 215.8405 -0.000000 + + +.. figure:: graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif + :alt: Graph_SLAM_optimization.gif + +.. code:: ipython3 + + g.plot(title="Optimized") + + + +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png + + +.. code:: ipython3 + + print("\nχ^2 error from odometry edges: {:7.3f}".format(g_odom.calc_chi2())) + print("χ^2 error from scan-matching edges: {:7.3f}".format(g_scan.calc_chi2())) + + +.. parsed-literal:: + + + χ^2 error from odometry edges: 142.189 + χ^2 error from scan-matching edges: 73.652 + + +.. code:: ipython3 + + g_odom.plot(title="Odometry edges") + + + +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png + + +.. code:: ipython3 + + g_scan.plot(title="Scan-matching edges") + + + +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png + diff --git a/SLAM/GraphBasedSLAM/images/Graph_SLAM_optimization.gif b/docs/modules/slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif similarity index 100% rename from SLAM/GraphBasedSLAM/images/Graph_SLAM_optimization.gif rename to docs/modules/slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png b/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png new file mode 100644 index 0000000000000000000000000000000000000000..a3fca366e4ef37bceaac5cc1e45a987bbd2d8252 GIT binary patch literal 32748 zcmY(q1yEc~&@PMyhu{PWu((@rcZc8(!GkRBPVnIFkN}IjyZa)+-QC^o?)!c9-&_CG zp4!^8bI$Zg_jLF3OvHC3X*6U)WGE;oG+7x5RVXNEAIOD>_z7}HUtO65@&)HCCaaDJ zDL#m1;gH`*4l+8 zXP}s<{tF2Xl^|6ECr~pmWvZt+X1kQ(w=k~pSh=wTs*SCR&H&sudY`iK!a;ei^)Dr_+@$Q(0&Cmx2*csMqpu)Wf}a*J}(D?Q5Ej#r&01w|teng1(#LQ>A$ z-2;#UvT}g$jEszwXXwFw{O_*{IIYdL=H}*lEd9WX?d|Ppx&L2<0M*hk)nj*1QcJ|p zM`hA7C~yTwMK0QU*txad4)VmbiHh7?uBvs7s&%&Nu{UTI2Q)i>C*anidR%>LiK#;l zIFqDop##d2yv!96pKMR7H^XdzB=eG5ahh?Pi5HOx5O3iORpfNWm$>j##ReckF`1VFS_?Mq?^;ByDL_;j#fQ30I64HaYd+FbAx7MO5SF`e4wP=Q}-0r zV>Qrhm0St0TuBb^3c8k@Z()*dMN%vN_vkl+)_UgudWgk~_!CwjyG>QX55W)yUAck} z-2>|o?iIyDlWq?;ekKsNyM|6}40zHqLDzjG!u>;w40%i@`$BD#loR7~d~%6%BYymS zH%Ipllw8S9z*RSrh}Nd!X3cCPbID5!;USC<5^=kuQDh`I)DgZ@UcLb3vM!wRc=6uA zn!no{aGez1AISeNyT3cSc>)#lNmW7K`CEc0-P~6mEL!D?Wjf1DXcq*{LQPKH3~kWt*KYA{SwI3qeb=YK@ZovhNFxc` z+hNM44*G|>NO|#1WS>+#>Ct{CL5En?V?b;C@MWvRsL;>WdvH>Dk75C9+$H_pAePvGecB!F20?V;D)v zImP!i4Y3@0UCQR4BtSKL`HXkdY*XuY_XLUVg{PaTdyejA)EsTG{w+{2fZw^pRTb#> z=}hjqS=ActlFduvSNJRHD{dN;I#fsC6WSs(K7NuO)PT9X1f45Mb!K?h{3_7Vkq$>6 zZR0A0Ize^Ow!EBcxbSH52}?mi?{lPPWLGPi3Ai)2iCH3;j>^BDXsp)?aia zTHmMq;HfUX?~Vt0Lr^l?zWk?;Ovs?wkK;O{d=wwhtkWhp84{&Lfsv`v%>QUFmm+A3 zGy|FOzeXIbs8?n6{-;?nHAElieR|Nknq0Kquag#tJ~z*bs-?N0W5(MjtFGjMCw-{_ zH`7FF+1)<_z6yGM6Lr>y6kVF=%B{%ZrjjnjGfY=pNwEl7{uV<(Pmsac`oMsBq654i zG==!D{!8+Ldhb{SYK5Qsn*WKTt{-UB?eoUj-XG6s%rcM46zF+F_W9?z1t&_4ni9p) z)uEF8V)edV3}iO?aUVnEzKx<&pznF)n3D>DcJx>{-6J#5c+bAIfB4~0q)Q~onw{%w z9kw;w!c=y%r~@#^%uqub*UCKfz0c~Ua{RxN-55Y!?q`nAW&9GUZ2r|e6lR*i`a{H- zdk7S=iTo-?ML-#o+_2%@@fnrNJ~IQU0nD8K!I8Ka^odi;IU|>$GGN87FEQ#bF@om- z38bM}6s=8s+T>)`Y!1(LM$y3}>$A?}<%@KIbV}qf^@D{j;j#3Yv1n_l96!Qhwr$Uk zw|(nqd6c|A^oA`3;Zj%VDC`+LNJEj1QU!O&-emXhCODrq1I&90WXIPE_VFdR5v#mx2<#w1X&dlCr7vX)kvtcCJa1n_fX!ze%flB?ftiTc*GjvRzw zIi?5W@O(7BLY;~i2(c*0nKE#)d|!GB73$_D%y-$0VH_EO$LvfG{Ej8~kf9Puppa6H zj-^E2yXhH@|F7+QXG>yKEZY9t?v95>>l@9C4Sxh#ol8k;b3G@=5^PAf$x!gRQ73lq z)&{#zs+tU;@uL%(9T<@j5HKRz&YfrE3ew!g;V_UC;QFlgEQC|Nb|B+RK?vH|6P3cI zZuaqVZYuPQkRa2HMnFj9nIDSGXp@BRnH28p4-v)k_}ncbBgA8{pyc4V1O*ZBo5e)G znDSyq#C%1|n?2A{AuH)S>{pL&TpYG1|2)$&5*2Ja%v7soaG(!uO4SE** zyts(;C-&#aoSpB4cd)iZ0I|kJ7B#F{aE=9M|eMS%;@R2Mie#&ha}O{T=%B)RG!b9 zQ_${p!5xnkFY6AIf)&p%kEa}IY_P341eBGGSZTDmu}zJnN-rUp3#)tAVa@T4A^l_N z+IiT85tQkEQ-JrkZ>S{5l9Kbr zVr^E_jJEjw4DM4pAHxNiUdf^UW~6oJ^i93nv3`UPmU%z$y$}42{Fa9R^REP(*t>j! z@p4LflV^Npf|>%WhvKRnO&HInf$P(uPWJ7|yN@s28S2#KqOd>JzWk@E2yj z%jZ0bgrD?>r8vUO36w-`&Medd4oebH6x zyWX^dJ*x~1%O^Idq@fvW;G>oyl0j>?If67>7;X(IThtZaDksvA%~rpu2P4XyTo-BT z^A_?ejLE%iHBVw7?4OHl3J&p`N`tL}#9NqZlMuZ3BlOJ(n%n2Eg0=g(f5nZ5NHUM4 z2*XF;VD$S1754O_lDzj*W^?CKwT$MvZVF`oov$Gx(SW9gOuwu2fK!ui#+f+2I10Gf zo)5O-e3P?Y#>|NKdwU-FUrRpzYf+^X1AUt+#-rV*!zPYIi`ndKlj7-oUYZrvVPCrD z6cHGMh;@NK{PPB!a`e=?7b|)6E*YF!7Q{%_ecootAJDfVy=1K-VKdALY@aITf}d@u z5LzLMF#q^{-4|Yix|wauoIS0Y#ts@;{`1kL9x;zdtdFjN&4-$?dZbGt_)!tm@mge&rtZ zxd|g48y1HE#CX1T-;bG5q9C%y(eB|GW9~RH{-(9;nTC>2?L|<_CzixSGU>18aXfMA zTxJ#tLwEQA7$qUa+lnWUoiQ1`bfR}#SmARCuw%$0W~)Jr#fAlMH(8DzeJAdgnSB4I zY55tl+&_LFikkOj*TG-k&Qv@6y`Q*x+UzpwDa-2lCvLoU8L#i46VP+d^qNc%N*S+> zI+tNX(`-wCNtd=40E-@{Da*r%9-fce%J-rCLxz~bJ{wjwLiv-YZOa6H0#6~L3^CP* zM%xH)FucTIeA{>&?VC9}NOg8T1>ct{LBW6_lAtqs~S1RZiVLHmUmm0VT0~jE&)rmARNmDg{rh3vmd5Y2h)-6^N7Uc>t zyg%j{$ud_27BsWpZ8kp-$zx4R$y z2%O;OG;&tV-C43UzA`zh)lr?^Ei4+`{u{P=Gue>xF~NU1{)8E${PU$lCW^ubQ)>Oo zW_+c(s^BisyYs|G?p9i5!{&H~FCN)^wHP7eXV zR<(>(3C~w$3%%*E z`W&I@Q>Qcek+=7^8yWd%G@QSR`xD@ACy7a=Wd&Sg8XnD~FjE?SDmGx{suxNj*<8u1 z=;@)`+k?^GIR&6T+SH+V_j%yR+FqouXH)s(iG$uU)JBy(uSE_~|?~Y21J+t2ZjY(1i-eDIZR2RlMzp+N zuUGWfa?DgI1DKpK&_+5a>gWCUk`?FGQ(*$UtRKgjcb!u;87{@iBZ}Z^@{=>JE290Z97B6{^6uJKgd|$T;)aDhrY3R)_DoIeD8J7{M%H=U^8}5 zx-$=FWiFTCo*x=)4ab3j{5_w`1SI@eA<`6v~xu%D@` zU2r7jVI5niQ-8NyS9%86 zKgO!F{5yvO5q^7gJges;%A=|!(3bSms5LStg4%Gv%9g1Sk3KqdraHCfmDN5DPBMkW zar48`r#`=i5=uGb&F9XHWglM?)TNltgk#9TR^|n1U8T0UHZ#2s@DublAnQ*1@Cd90)LSnfA`%BflzrGz!t$B7>wSgR|BCe1&^uAJ~NZh3ET6*McG7;M@|7 z1{BB2)yjuOGGC!Bq#MZ;bGjaR-l?}jyYy+r5xB#BjJEF6l1uOQ?cO@vd~{D%{lJV@ zCcJ57ipE`o$zt475a8?Wwqv+dXd{K4a&rZJpAY3AuhcIAwjb@Sxl7ksjQ>o-I9oYM zLQU1rdwW_iPzx-b<(>7l_%&Tyu{Fy3EMb{yHp3Q693lMq$42B2qd$DpVW1fb#z%Y0 z&Zj@WmNZ0#p4|f|VuPo&?v1Ol|0*_36hGi^3Gl!sAeoprI-fe7YnooEpvl$P4YOrA znvohlcV-DG8x7fkjm8T^G`kx|E}+=qTW4+vZN_7K%+94h7JUR-t4SvviJ^vWYz;;2 zBMBZHzaDU;V=TkTP;V7^SjzYoeN9;Ho_n=$-S0Ca^`g{@>rPy*e4IKO%iz>K?Uafu zs}3NL?dwJT#A~m7*5k6+hUrr^z$*Kzf6-qt*t-+C+JXG^Q5=q=q-mhcRDlT77zXLid-G1C95&cvz4b6P3=qO&qjk#f>RBt`p`X`FH??5ZFCtC0_(UhKjZBI>96 zW%-2~v`^&4&L?DikD~;HX8U{97HCmlU`hCUM`-NN)sAZ=zvmhntKpMDjg36{P&w>9 z-`iIZzR#qtu*bwP`VObq=T7V9H)dug@KjPNW9xV57PRZ{rszq;2pg_=&Jg|`qHyYl z1{~xtu=}=O+5@UT7aG~#b2u$PPxe1TP3 zyTcTc=Uqm-srU__^zK@jVuhL6-2#{r>5}Dqmh*?oI1Md3D^}w2K?}F4qnwx;+lll7 zyczAv=&FsY)=B2`2Vae%=^(orS)=++g>(P+5b5o-k}j!zzM~z;65q`@>tio6h-kOJ zOLZ395bew8(ild6C6|sf71YAp)EVKTG-O=+O z(06!8MiG!ZEf@f%iicZWU5&O&yIIGX$SSUQEOib~hb#?`_r zQpcdr2#K`W6d>NFYTPR&AV=Jz_#1z%Oyd=}9BliAOJVmj$6Dvz0BP~q?v?KAmlyx% zoANWc6P*3@me~3Lc}0_1zOJMA0`|Ly#JV%!v!!2Z#todxbCHxWeO03DA9k*H{hsX3 zSp8^U;=fS{s$RJ+MR8XpLx~wUTAn0IicCha3de@IFWDfP-WiGtxjq(dQd96Ohi$|= z6{Y>U9T-8)_Q}OeCbrYMmfR9L)dKV#uG41v3D!bJ*DhcRSv>G|pKf+yU` z%MoHIobKkHep#B*_;aUD3gf4G5W;|=J;O1b z!mYsLB()Z?qF?n4nUF^&CyRnxh7ws0eTCwCf^0l%Wn^XD!p$<4U*qT9`iw~yK}qjK z=#h_i7YVn!Hjk6u^4Gzhm7)H#T#Z>>T}&J+$rj&U?>sRS3+q$5mHm~yZsX2^u?ViI zI@k>rBkmACGAIHFEa*L$Ur1Q?6 zU|ix>bNqlNg?TBr|Cpz~?DFePxuU0x#Sh^Svoz3cQxo!Z8&aGpC^c-_s}Z(=_Pk+h zoImC6v)K4tu1)Urum=ZXAszY_U+;m@g*gSY?oa?n;~ z$H=Kj(vsU}9KXG-K(kfA7u0MeTc8#pusP1XQ~-a-C|7{RU>}^&xMWion*&?in~-p3 zyJU(X$k*x}_TBJ+RLhXp-(QcJr#r==Dz1I{Z$V18QEsR|x^YQ=sk2_Cx6Swj+1kWi zw1q_@OR~9ilAM!^)!D=x=NC>oc=AhEeja3PWFI8`hQGcja+};qpO?CyI2vDO`&Uwp z5J^yBBFG){ysDUfi zRGsqpg4VQ%^EcU*?Zu6eme1TIk~|kp>An?AMgq3-uY-KHCvMhaE3CDm?wnQjI@`2V zNPS~369Ci{hDIc?hLoH7?Vsegm>mN4%_H}bVk{wCdlD@3DAVqf1oa+7ioU9XWVkD zN>ZMzIox45l1Ws2|7ad=4z_DM>N8sF_{M>0$l>%vE@dW_oveLbt^$CV{t>fS*;w@H z6KDUSTqQGY80X>iD;+N_q_s6l*-OHGavau89SXL4gj-TRVg|J$-KE=m()cuxNR+uS_K9_-o zj^Ef{RxNo=4`|m9d;?iFjUn!Ro|#ZcMLqdxN!?m!0Z=ovbXdQFjKH=@JiPmILUYNH zRQgDP%r2f@O6mGjVek7}=I*m%G{Yr#nBAH+(yRVMhs4CcWPd4 z22xu!+(ZH20l66K7dkVt5sJUP*51$IJ(C@{y2)u08)Q5klX{o85G@41io!JAO4Q5@ zvKR>)gTqLV4N`NyB$zGF$fmPD{EN$S&lw(}i46!LpH9R{dia7)M*0-v6y zZ#BQeja1FT`unSONTD_(0RTlWT&2{Aw@Nf>>NV|fyO=Zo?}7WQ8xd6ZW^ zcNzJ$QDh2{ZO!yvoHa?>tx&65O8=YI;brjs@S2{tifTqk_1YS1;y7w4OPWB#K@4Z~ zrS+%0JaW;a&b9>?oQbpdkLDtxo576M-e_|M^{sQhfccU)jB(tn&Asd^LhL(Sf#hd* z$1OptuAI&odlM=Ip-SiOmpy=kEDCnlQnxdMHqC45kupI)-uh@JxriuIYw!?-ZVt>I zBu%>apfw#IshfszZ;=Qb=T{Z}8AG8utLd%u`cSRvx$AR=u2s91V%m#|`2^YGP*`x% zORvXyC(#i{F1ongPjqSK9zr?NdCRUw{VQkfasahGQ@ge1d_gCFMEMwO?5dY|#I8+7 zjmbNLX%mBzl#aQ7JJ4sACUbjc;jNx6N4Q)tJDG52cYKShV{)Hv8NCGu<=3|zCr~Zh zSO)E`PAUsWD11rBrUE|hy;xeW9)x28viXj>;6ov!olH1DpAtLuKECshYj_WQXGh^} z*>}!RW48KP4!STu#gk+K8uT1Yv(lI;*6p6}A4iCL=p+S7J)L-6`u+t>lY%tY1NeXl zZlc3%#E^cr+We3*L2}RM;p+Y{Jb9nkj_bE46otb!n6B?Nb$(Mv0cEQQEyWc~WttHJ zZQ`9I!70^a{~s4%_RGvGW@IL~)wT81ut@27g#XDbo|I*zP*LfZjBG^vd#lW3j+cy( zpO4@-&eTwHb!oyQMVv>@r(=eA?%2}o=ayC}lA!uu92&`^!Vjq6-LJZsqw-h(wD-rd zkWS5rx&)fEbSj=26{HtS)cTD4IsSvpoZm1T6&B@eD9eV-Nq2eVgefc<3NbV|#9VL`9;Pmh@N7}y&<-Qwgo~Q=?p-{wUv76WXNwU~TDY)*V*hqe$ zrdk7MwMT86v`-ZtX)HI(t&LUUGI>O44{<;=^|33HYx7iwNklI?9=vFB^-4qSzvWB+ zEHhsLx<0j-VF|4W$)KVjghc$yWNGFW3f+i~QQzqkwL;j5r^swuB8uMWHjV9B_ZGLJ zyFG@tZ-=h46yNCd%C&bxX3eg1_|Df!9v>hR97D3zgV4}*H=69w4bAG9_dcOd7$Fi+ zsx~?CjwjcXCyD0er(qc5I1|0fQ;_v#LI$hkS2B`26iP zwNvwz)LT={>pmSRAL2fFa^RuvnTjQ&-*jz=& z+hacS0iu`cWm#3mp_DH9hHyTEt9kva)R+gaqlc0P>t14Yy3v?arbnFXC`*}Fm=fmOvL7wW>pq|Cc_SC3x8{ltU0|iXo=a6 zmddOeC+g9&@7e5exShIOvFFqFoC5Id6I8J7V@6*$Aw=?oy{J$=*$u(|m@d#=)?27# zwMmI7f4vlcyvc32XZa-$iyhmCf0{r?ugqSO?@bgaj}g8}9vJb5vPb2`KbKCIC4e2( zPoOf%*n(Hf0DdIX&T97I$CXK%I#$ol;lqp#UvUDKx+7Z@0rbGYXY{_qsp$DosUo2c zF*T+N$-Y?chL0N4C-%yp+YjKdmzcQ8B}J3eq>($Iu4cv#hR|o;=bvk3q34F zX8HI7tdy1Q>DvTHS&!+rBk;GIOkapnj$^VZtunASS`!ucSsDMVT~I5?z&FkY9SqK? zD3*N9)?=q*w@Q%7#M+)4j!>%Sp%2-(eZzN6mQ3|MKyF91oIiXcWjo4-qpjx54 z2V|GFnPl^~l5!V`bZ(AyU;m4D&)ZHULYc?-&$)|+WFu=H`) zFvC`r%uf$C@_hIleZ7N?ImjLXI}4al<+v<`(@t4;hb8!=?^E;DIM2@+3uOWVF)yv*gd+Vxwt9n%`*D(@Zx^i0;vL%UvUQeN6OGhC39 zzRP&$@4{v9_+^9NgGuU#$CY7tI@9KV0PJAuKB{X-QYf5g0#YSJ|IdYSO1T8XT!B>~{);`@WbUErO8p}A zt{Y1Js=|vkezW|RnTwg_2ELLEbC49oy@cTWtdqpJDGt%30FGRLLm%YX4Q0L%o*6y?C)2ZEf1p${rGHCl6~W!!z4{wadRyEWahkK z-1i?dW1tZtQPSFQ8BM#Y z0!hW%AmA>{pBtccnI|4UCWgALjWLy_xou=Al&rP@H6yDy7L<;4J`)b*(h^r&+JuTgu~!1!_3*dM=bZ(GnwOT z+z_{30aw#ysSKx0aH?H5txkG=>(s&kgCa++y&NH9M@FN@cNdb2=$*qnIx?r7=y3c^ zM6E_52j3Vcl2E=}0dlO;_~zB@)5?ZZq|k0J%8Am=R6F{6|FGKy~@B39y`X zfKWvU`m434sbn^~5F&_#un2fU@z2|;e!x@`CLCLPyuPTXeD5pQs@Cv*TxfdEGT~a~ zH9(G&{wf;M7jB#YS9(RB-L`*b(tb(I?k9lyMQk^P)^xBNQ~EG~A)iye;~5ne0!iXh zlVD=<^YiLOYe`|I$R^$vmNlY*ZGZ0x581Ue9>AmA{_`Sh^l^9WgOjPyrGf-2m7JTO z3>vU(^>S8?ye)k#&JDngxi;rWaAuLrnX=ABn&0IN5VBxjlXN)^B@C_0Pa0?em_F*J z+i_5>FZ4VI#AJl#ud${z#i95{L00vrV?HNaXHCXrDxrj!t*97W!?YIn4Jyo!g1xdd z@LOXH+%G=NOaUSR#!cO9edq(J<)4Plp2j#IPEYklP*_CT+{UMdd-H0Xk5=gb*hEi+ zOtBN$Y!08h`~O39>VYWNUT~4t0zBb6-SGG#xk7qbIz`(d|3Uh^Yyy4dX&Yyt;*)s_@^!wz(`eC_x>qb%IRQKp($R^mz@FS0+e*GCfO__TL<>8Y|U z{#(Y-6>UU3^6^MmW&0{Cao6P&fb}Vn%yCa?-tI_UtFPBPPn|?n!ld1gYw(?9eFsW} zLDov~V?i6i4bf<5V70G1wK6adpmkW6PE7)uE$hB_wQWUCgINtfcd&=k&hg*SG}S|nFSAO0r_<~aQvZ3Y7)|KcVv+$*H^y6H zkKV4qZ`1j_Ci-3?!IR5biXTrGyGv)2NeHa?VyXkIR1y6q#WDqR!bF)=5K>K109_FY$y-w18(FZ9=r*StQ z8-YU~hiRHSDRcm3SEghMdXNLLn&EoOw`BhHVP%Ye;gSU>eam(Y;!6xyBO)$WcXH+J zcln4174p*9CrQIn`vMKBSLY2{?;$|F1n#h1u(WMDpN3gKV*FRZdWHjCm$d*hyFr!D zOTec6rv!bjj18lyqpF=lVqOF~{>0~>#7_}dcGma_?{AVye6qXOVAp|WW$Dn}$S|Pi zgF!qj#_Z7eTEn*s&tkqh^)|b&pA&A{jdk3|Q%)-7o!iV|n&?3H;<59ou%=w?-X|ua zK!0Cf>$jf{m??^6G-wT6 zr7<`6vTXV%JM$S`zM%wVOx^v2Zo`M7)(IptfYSKtrXi!*Wh*}rT&<2ymqI$p3^ofj zh*W~M%V;GV`Sm7Gbzb9AINOS~1|(BE#y1Klb_y3dW$_-YR5(@pa=Ag!M*%mxLN)`3H4XKlEpvN_CM6e-g*l$?@Y6Io6At`P zFKcd%DLJ4$ayxD9)vIm8$jWH?a>FkhYEWYG*>mJ3zxU>!NjXpO>P8CheqQWk)(U8C zzMCJoCh+;z^WDX?xhATpkN3V*nBzIA2^yvi_v)mDupZ=FJ#Ed5V-h^4g?i*g0qu`A;a%$tMIaEJSJQO#Qv~M$bB73!b zxY)=eWW;q>ZY=AQV{pM&b21;{a~U{H5gQ&wNL71M=@pki(vt?^hSAqh{&jIo+%Q^V zKP%NE9(cNongKD{uTa}KE6=Cp%hHNtjV4*ouq>d}nGc@3Uc5*TSie6A$LHmpG8_3D zxMPDcQ1-@gHFn}@-tE9FEX(YY$-g`7kMOL9h7@D{%W#<&i2-6w9RM6>2su zWZcrECj(*NJl($}jklGMjt)dh#+>EZgwMO9Zx!WAeDzjXS!r{h>^y*=@&D0toF^m7 z4VfCS1}oa_z>4TilGx}cFcenCxzz4(1n4%LKE4B%PWQeSm+Vh5l~@<+@}!A5u{A&) zL1xNSxcY~QIC6lIZ?d3}rRbAgq0>G(}Q2@ppejM;|gz=XZE`1wA zMk`xSHy^Fdh186_dl9juk(QUG>z6sSszA+-oOuz25>27>bB5%wB|MeWpW^-{9FCPd`0d#0PTlmXM-tQaZ;Un@$nJkL1e9d{(|H;nKJVB&#| zn7mgK@m4buDNJR)5pygD%7qPSx*g2X(n>ALL*H)Jd$dc}Zy=HR?tJ5Ed);sh|8L@T zp)R*Gk<)f)>E(E`zy$jCRww<+2&97Lx;;T}2)XCH;H;u4509}sof`u-du9L9&t}ov z7;_$hEh_?V&<1U15I3@?od`gj@f*NNIWm0AiX`wwOA_1IDtAlZ4j8~PXc@caY00w* zb-19+@^XQ(@=c@`+0rj*aT9RwP`b!~i>T3V$87zBKq^)WPDlr)svXAppqI$LyVZ5` zs#_GH2aQ|AvBoabs`3CZMGO2;?RQi+CR+|+&%P;aXdP-1q5PGuAURGw0(LnfkAD^( z>?{L}MItO((eO0*!fi~e2ju;B1aD!k3o-@_<>!uweq==02Pzd>e6HGi*E4qAIj^YN zD|G1uY2LrKz>xmvg^S7qBxtae4w$4GbU);vpG9a5JZ?lG^4o6*UG2oOdUFZ9Fpj0e zzG!};8xjKr=SKV}h65nOilPQND-~~MF&NL$pQUy>kheeNyuZw)A)-bTYJ!y`mML3-5qb|Y^wblxm>>l1A=t(yx8)*I-HHo{uLLj!j1T2 zvSjloDf4DfQaURWkJ8jbfh>It`DZKwX3woIYBTNd!AFReQOKpes8Vk)Ak>4gQJ88N zWVwsO`2=SsdXL4aM%C5&hB#P75b5lS+P8r0dws%z`m+?I^L7b5lNKn?XZoAnx9!of zO%PhH=EvJ#zc(Up>uC3GiXFQX-u}@!jK&>~N)X5Cx%*C16UkJj%#;j)>`~Q9(d0|7 zFsGq zG!4SEv>B<{?Q@2c;u}}%OleIgj+Qk@uP^)fzLHryQU*eZvi)l4i0H$r7whaAz;vOf zX0BI7)BA=c9lt9Nv$KL~eJ_W3yTket;K$3Gd%R^XF7E*`&~hyM0xrH0C^^9=PxO%WEIj2`0pFHr1VR9;B^ z{)xTU&(!}@7QRV!K?H+wUQQ9%NG#r_uF6QRRD63-8*X0oz_ z8f>9-xoAwuzrkYHyHt&+L@BPiKWC)Ow56G55lp~aVK)A^4K|YfjcOQ1^Gu9FEW)Z9 z(_i_}{(`C4`(_OE713v5(-V4rYd)c*cEhk9&k|30!ISZMgR9o^{$Vn=$ zSHfcPAc7Qx2r6jNbx#@=mZ%^9ZW_LL7|J`~;8hjNCZ*#hm60jo3K)R$5lLbPoE7q3 zx)>fG56C)l+M_E~OMt)U<|r-4`fs|bzVps`!PT?XLffva*r7;&ElK^RA$^8er}mKE znp1Vl_$~y(1g5>5AvhmcoE7K#AK`CCPGah+0keppjmnL0`D+(yUgnFcog_**BF4W(Duc;~J6O@)YR>y$bNgODa)H=?J5ZMj#?Y}<8O?VtUvv5% zmu$6Bp`V!S$|RYakAk4X*}r#kojS}d(dLE_P={KXY;Tgw5>X7QNdNL+A~w&9I^|+P zBGZePwoF$j{QbpZZP4$V`#(-wqDT>_{qdk_)sAl=dSf?Qw^j_czy^uPZ4b z4~N4ux-AloWLh=4U-_b~DxIu!78}(Ivk10xl5DC~geTL@REwZn4!)jcWS#t->1Z3C z&3QtaB?j#-34$qYQ{))WkfXISEon|Huk&N;X)>*>(fs(J6!<9SP) zQx+7QwVJKJTYDWgH+rXj`x{58dSifOKKgN!D(58V$lLdqjNfMS-zQIl~5AWF`LS>c=Y2+ zct-YFD40QgeJ-n9(J5K}wHub?Jg=h{wa}f>7dAt_AU@Qv)>eS@DS`-ZTYV>7jN~7_ zX*<^)FFK=60_Rlw)hBiJ!#=Oufc)4{a`Ac!ibXN%Ge#<`} zWDoT=L1m)RKa>>~7-Z_@d69?M7luF}NVu;Ybv=`aIq~Km2aG{=*h_9T6#svLi~n_k z?f!5^4xe7a(oTw=%YN^`8dn_e6ljjU#gq?5Pqtx*<>RXj_-ZK9gGP9;5 zCIXB5H`K$$^F$BXnZ-y%YKqYQX#3Uw`(|uN#uA zk-y+Ab6nxyEo%2SjqCkC6t@FKeXb{YA!iQz48qMYj_lrP355w zFX_B%F>;}J?_b^?Seg;c)Kp5ixl9eS|L5f6m-$Uf zX!~TD)(P~bmXW!zmd2dWgNO?RDU=ehavVbwWkks-L^Cwu85K9u>4#bmwEshhG4rKw z>`?}9?B7MM)u+Xl8{gGSFg!s5rPX6GAM0@Lyx8sz8InTwHu2Vn*{4YsqLEuFXgtLT zCoDbB8yC+If{{fWj}HOKX$zEg)#P5=TbLutf;loDKdl0> z0x{X3uv^Z^vUyXD_eyfT@E?}37fKda2Fu(v;-)ED0X)))xv}xWHdh*31E)itBR-!a zv3s@7o5EE+`( zA4zmF#4xdj-Eq<{mpjbRp=d#n6IFE2Zqy|FFci{U9lx|l#r@Ton1It6sgx&n^+F}Yn;B6zeF z^BxzMclkrmmB61y?l1qB3s7KJF11$?xTu;f2TDkR-a*{c*pV~hwtF@^5^v0bx_`MF z;dfmw&>PII2l_;b2DyBpt;ahN_W6u&gdYq*F=0~x1B8sRG&a;fe>lM#6)q^1Ox_GsD7rA>=j)mIs?QPHd(gD7KhL_GJrW^)S>Z?4DO) zjG1J*(8JS6WxC>Kt)IER-=6_b3pAZJ1ug6Pkf7ZbyXh{vNDaM^DqEzqJe{+k{!d$P z85LL4MGfK>oIr4C+%32U8VIg|;KAM9A!tKz5AH6(U4pv?cXxN4`@G+*HEU)~{pufg zRo}jSZdILq_THznQ$=By5vyaJbC62_0lu#6Q6la@8CD6r16D27AOX}kAEB- zA?eX(Hrplsx;!G_Tud#=kLWAW_nlIHirj5e{$E)=scTI2CJ%3 z-PmT$Y&|3*s}AYJ8%>IkZnbs*YH`j&{wS8#Iy62q2b(53?EhOG;gn($10kSrwvV zA}d{XvD)`&aJqHd@S-qUuqnOI&Ne0q>FTg7X2xj^%D>{$2E-wJ3zIGkFbh{xQXn!? zo!{rl`dV819>78O)5oJl)t&t;qHKePimJrQC)4HnF>M)}8;fH=FB`9*ij8z}t2<$T ze5owS5ns{p6Sqvj5!r1^S^5`q_W1Eta?&I&1+=>$=_zbGd`gK9VTu&#lq{veBe^=7 zT?ewyoFoA_22n|#WugE8>Gi&q?1-tV)Rh>QA)Mfoxoh8UGEZ0V zocRALtqtyI`rx&;)g&3`u`$cGlC~9@xMB0l-S;eRFK8+66Jly+1rlgahAc?MkxInEF5YDK{ z_~ax!>Ckgo*LoH(hv}}Rr-s+yw)Lt)6X(LVowunXTGlJ^cV2#u;Uu`fTOOOkOIDYo z`kDBb%-zN0awv@>k96ZnFK7 zMGI-#CjNs735ksF}$2=&}6piGUTw(Ecyx(Z*EAeDXrv7i~zKRn{=r=p&@g(_C zP5pXRyO($0VhKh24p*my3eBD(0n&a2YU;67AQJ&p?Og){hS-#YL>INdS=gV4-m?@# zHVKXm5dorjZJ3|ylW0OA{xjW+#rp=U?EwTIkDf#ED2}F2e_N_@w9TKiO_&P};*bYF zLB4iY>b7$C(tk)cPnho8Hv%ngM9i*puQS_aa&vv0qI>Ub=ZucdZ6kYsPFx4H8R%nAc=E_lKO*$fOb&4u6d4_GK|Zu;UEF@QezK_nsQn(!zh=4! zQ#s=Pp_q+PT@C3dGygtEEy~(PSISmw(8)8F+pvy<^dpT_4Fu!w*c$QdP8|NJGpnyr z{c5Lx|BjSgG|VIewyj|(dIB+P6y3pGJ+`*pwk0M0{$M}|4{g-NVdMouE*`JYON;aBWcpnBGJIo5Ec9S$Ib}y`^7Bm_6|wq()61_VWHl(ZTM- zg_*>r(9jCo7Ej+;gJfBmZG+1)d0|8p%TG@BISQ}kIY=l3m{dj0JU`a@-#qi>sfHEd z4=t?)Zjim3;}XV;U-uGC7T|PP`a#Jajlyn9dDvKJHpyuEfj1p=gQ1j~& z?h?B@23$6kLj0SSlyN?!3Y(pVm~d+|G{;8U=Y4g;L$L2_hd@0s9+NrlFeGntKj6G@ zbT8#y2+jDj7ktW4XYY33>KfZevA#NSt!24y|C@2rm|P;SE#MTQa$mSDN?rdV;gH5X5;IA`y< znRPV$=w;$H*n*GYW9~A6FS-C~6ipCqs`D<5!u~O-)h&Eb$5yAFgXa=AnR>Z@JNwsW3!H<8XZ`AQ zVUY@d3=C$4NM6mvNvePaZqQQ`6_yK15#ProB{~u+X!1Y!vSuOpsDic4sGpRv>C{~w zs5_e;U(}r{_-Qf(H=gc^S9+&u1#aiT_R_>GEGk5X%+D?raLBLIWtr6_iIiuS_Cj1|x>{B{8-@_O+n;EboG0A(OpSup8M=mg_ zqofCUe&P(Al+KRl8Xn;z{UJC{w}SSfZ;@KY(ZebSx|Asc|}>7okwKsz#* z(*pbdMX>1A&D{T;-u4 zqfT09AqBG4vEjOko6EjXqbOo~%$`AAV8Yh!GK=SCUik33&?qm(#)e5_kC=CdinDO@ z*^1u8BuzYQqmNrF%W-Sr;yPe`0z>lCU3KS(2VX#d=IAFK-qFST1OrS7G@eH%IRora zWINtO4ic1btt(PfmE?Qu%_BROEv2=2qDJq&PW&;=dD5`^AknfG1rjt7vY;O4nt2!k z=5>UQ1s_od0Uq(x6jMslo{YNah6a-w@$0-&hWp30au^QAllYYRqaYz5nnZ%cENo!w zCVBjAt=3sLvIzr3{exs_wIRzHEZK8QNkiyk(X3Gl!D5Uc_wP;5RsO%;%PEgz4ec0P z{uhkBZp`w@=;LS3CQE;|=7L^*^+bI56B90X6FGT9;M=^861Mc}dFznWtLARcvNqM$ zEJc2DSuJ0(O4cSRAfdo^S4OG48WvBAk1_riLDp}EB(2%@)WO2}b>2kW)^t0Qgp$0Y z%1*Qgm0x&*@q0WH(ic1pf0O*C-((9Qa%uO%A>#h~M^w$D32e%if$aV*AY5ywKrtqermh2cLY$Nd z;f;;Z)4EkF*xSx~jyA1_DXK*mn$>aC!Xi>6@P5x}XX3Nd4sgDzIOsFaQL+wL1EPNt zUITtHJA5fp4kpqTM~16jO>Hv8=?>!q-e(w`$;-RTe0Nz~B~_$>OO%;X8c}l5&P(4U zrhxS~yvk0!)(rJ3mX+%30LqKB-+WH?)F6ESzlCHY(`kF`zoPZ^L%&OuVm-f(wim}O z>U@QxJsi$S-MHrrIQ&jMa0xz#jOM1B*dWGsbp=O`jMGt{F86f4!D9%)k$FRf0{O78 z*1{$abyU|n-X_~gBUwU17c%Ya8n?|7dMc}0WGC$f2aazG9$$m|7`b-CK_@F)I#&;i zJ#hm%{Qfd+kDM8dcqt=6^N}mM3H!twF?o10FHJ~eg9?Y|XC_S;L}DnjEHtBmzlHL_ z1b(Vpyf%%JymH=ySSj?|BeJZQ>d!bS?vviWx3AWf-(A=dkg-`<6<_~gZzGAUwsfzp z2OqvTAkCi@RNImOn<%o}sB^{WFTMd$C91FBh&qF>yrbu5A2w)8vqIbKbsZWkoz3~m zeaU;fj1|ISHtg{nc|UkW=G+LKLbd2v}hqlzHe`zVr{gRWz+MgjDAQ6*C}dVkodKnDsB8_o6Q-O;C}Ii`GOVv&=+>Q<5nl z5r+EH6TPLsA8a36(p!Xzv%LTnN`_wKG8l=@_Ge}{(CW7n)$t=v`grNHn7q~8A~Mdb zD-dP6XQO-M{&$f&6HeT;HZ)P@G{Q_z@9P`NYY#;{TG%$_c&v({by3UIAkMHYl*#I+OWEJ~(Eur_6 zMvXN?dubeaiD9N)V;cFDN@d_uUF~ENA5RxQfi2KD)6RH`=clVV^sKp_-aO^r)v#1D z{O)lC_jtMdOFVa%ohd&`M0GJEU{M0&XJswR zR@eX^c-YB4LwRYVUN=Im)JrBBH@Y4Y!FX*P^a@7)62n)2aVOx;kh!(Vg=q=od-N{ww{T z^OHeJ9Ge`3hy`MlUv>M5AW1#UQUPK6n<+oNja&4qdUSbAt(Ll{-hj`S!B3Z5!F#V+#geuZr&mPOZ7 zVPZCy%PR@z+l@y${ozS@)5#5i$nd*Zw&Cn=R0qE7erNP)pZlC8^gH#*_r@@-tOC5L!0PE56b^~(k8tufR|HaQQj{gb1}wEkK1{8pg$rWCS&M>o1OM6-b*RCjCR+qq^&mrrRC_k6a1#UJ&d zt5XOw($G^doyQL~aOun8LGy(JO*u2y88mKQQ{#uWCkDZ{o3E9o6bSsiY89HW{w=$B zukAeRZAJqd8`bgUJ|J+YaYA~eAqA{Q(fXr~<6TR-73t)=-Kj^X@4^Q$?={LU#PZc-yZ7OcV9h3rW2Mnm|zUyV@IM2VJ3;PGVy^PP@JT})0V0}}=odia! zT9A%c0F|H(up5*17@uV^Kb8q>e@{fh-r3pS`%~Ea8gZp@{z$(Ew*;hR~FolHps<)@?#oCm&=(6sNCqRCkz|UWQ z-nQ}ap9X*YT}5M8jk9Jj7$#wQ7dHewn9SF|FJf~)%LQgG_|snkvxm#an!Ch$OLc#g z;0pwp7liDSFI0pQ5V6I}72nnRn%Na)w8(R6Fv{|!are3B&_Dx9^c^%8Ajeo5@ zD0-IyVakuT_LuE8m+iW*ZBsswGWW-S7^*ZA_n1p6&`KtehNZORh zS~>DLA-4t_7sVhc=`Y!vKNWVW1K<(Ki`WrZhZNAcnJaz5&uGEfv5P1CjEYSgoj+28 zc{d3ai-cbl`hA{N)P?KjS(QLiFuX}fx_vxCM=^Zn&YLFl7V#EP-aMYLOHW9FMb(PH@G`b!a*55K#PWnCH1~#sT{J^wr#|2^ej0jyo zrF#@+V!Hk&^o4erlBl-CeJQo)e!-)-h~&G6CQy|gX#V2uWVS&e^Md!u22+R1JTw%M zV5A$&E{z!>`DnRB+(88ngL?0qFcxcyTc*Y;n3$&!7Ver@^Xk#e3cX;NT}GuG7T*sJ z)7>nx(lGD*?9V?QNCLsG6}mZW3z+fsCX6%Uz1@-W}ig?!0l&Lg=q5|+qg%1gT z47wSRmb3JDIek1^klwc;eY{*`gBAzE4qY0L6<(W$!}%)Y{)2m~R^>%0iLB4;FrJQO^^U?|H;o4ag39pC2hp}g9sk2~{b@TQDv#CdtAl}avgI<2cSnXSmLp)B* zk2fpf&P;X;xzteUHK7@+wV~XFC>G!Y4o_}^1c|Pc4xl@s2T(=8iZ)e`Y*_Es4&r7{nG$t zy$CZ>0KNilqQU9jH7pXO#tI(}p@WOv_S{GsJd zPT@2(A7Soce8>)m1T58Pv#zT5D)5#c=St?a+}NRc zwR~UF1gi=7ucxXH9aZ|yRfVDvWv}}cI^?=ka1$6@4Zf+mpLLbtKdf25wUr9$+KHg! z(|v62lo+Os?IMr*@Cn%(Rc`CBpUHJ@zh+FzvlD?E0YU5|hKbsiYj?yYM;o}By}5oq zqwOu?5`e(stM8r|Mp@S~#V0Z^9Ou~uU)!@VM1mM}wbDOCE~d|zvW#F5_dRj;&zx^c zCon&Xh_d-m7n`0r*_#{4rAclbSvhaO@;}=7BzLUr{_eWfk1n#&CSh~k47Oh|2qv|j z$w~0k03%r6M*{oy)vb9FL}Pg-q)~%!2FMC#X>w-ns&{H9z@;J4qx9cmbfs%eO+<)x z#Gm%49C~X$r_z~LOccZ^IIl*_F+3PE#3gcanx-ICI)5AcEiqSmF^CmH-FgD5+0O*= zoFrNmdcNmFEGifRN)r=yHzsGTJ%>tNFu?34C%#Fezo}~+jB=z>$monMg7GADk)>}} zGnve?#V9&X2si2(UjWb3Eaw-ReVfHGWfgv3R2&?l71GRACz$qmIba>i)}g}YPh9Tb zNffW#crf8)%hQ6dvRzMAoM^_Xw?@3maz0D;LB@)-+sh z0r$S!j{UnZDwTBl6iw?#JJbCITxniKbYWcO*>`N?(hXb3Ut|+|aXA2@P1eGeW)WA7 zn%^g&IksRupVmh(8v4QXSj3Qw=)LP$uK3|~JVS!CeH6PDUFsS=o(t>cA@6H6>C>M# zcv-;cOr2DpCGd~&%L8H7h-(xEQIa-UuZ90sjMN%IR++!|!C6(0omOh~CjcL*-5VIO za?2+Cm3Y_^NK5h>S5vSqFh0CMN%ZH$Qm}HjZh*4J-r%fZDE=0=hI!`Y6C!%N{KL*Z zC5gd#jQ-j&2a{QFs*+^c$2-vNrw24k!?S9q6IV(9rcH_v=^*Sqwh*Wigac%qUVE&W zz7(jca0k6}%+n=mw~hPbEwV^VG^f|wi)mT={R}qyA7>3jc0o7_{t>Kep6AyDlzXa2 zi$C4EUl5}Ex(%d|UaLf6ATp{T{;hF?GG3TY%!k(%{9O-xzB3AT$3Q3w_ zn>0}Z88oE0JVY2DK0mQ#dMSLky&j*j*yUoEci+Lvh!VE^=zT4Jde5Yd;Pd1^;_xo8 z6Kj`+%Gt!9fOiK&*Em9d_=kizK%cy{v}=Fnr|Yp{w*wRu8TEfX0>V(75OLVzVtJC; z0!18YW%>LSb$yys2vA$(lC^D_)GKFQz~};UR`)XhUON;rHV%snwk3JDQFTu#(o9CO z?biE=k^_5OkwX_xN1;M%*_cmkdS*Y>#KYFu92wmY&F6hvxL}qo_0`XeB8f5>^b@3X z+B)e$Ej8&O`(?|o_wC;Wh4mWKbXAtE$n)d=?enNnw1t;%15RV94C0fHmrc*W&W4iy zNeM2tVm+d~#IFp&n#mppI$rLVy@9_1f7M8oL-qqShZ@XVq zuaV7!$^BRv5|y5`Tl6rMLG$ApOFp2- zMV847j_r{cg6 z#pN$GW#!E}hafwwWX0SR?7o=D6VS*Zr4vD_9Lo@sflZ7996XgK3kA<8XT6nQr2Rx{ z!U%ngQGhpCZcf<~w>d5-AVl5t^LY%{)|uYq)1!*zU{!&E@p4Iek) z1nOjRt29-DX?1njbV+J)X|zoOaYFU+xotl-Kezpgso?Ow>Ss>s-5%n}hdbznfC3R9 zzlb#%Kiv5h)R*bcS!3GeeWIT-wQO}0Ag@m)aH_N*F~paUHp&3L!^ zD*d>=#cD!5%{nm>K++*5($+G;f_JpC{BCoEZi4j2)ZgBIFlNaj_htEFYd&Def(jL} zx!}ASoGh)P|2ZoP)YRxlZ;VfcO-nOqr-A{QzAzM*2u^p#I83H=v)Z{Wsf$+B*8=%L-`0}TeZmJd%5w!q3c*ZY(!HZcZd%&kc# zBER8~EZxtVa`CLL&(vPN?<{Be+Zz5X-cmu>ZE8g$EU+oP&B-62d9%D6aA3dsNsYw~ zqoiFoYq+h-xNgYXa7xb97ko>qf$g}q{ zj=pJ7i+3Dw)%ODs(0J>G?7VN-JRwaSSlz*qC7@A!T(Jy4+;3hQH70Y!u0B`7v*oRj z^;h!UXZ5RvWZwqsfT5rZT28B2x|xt*b54*y-y$r#?jMe+0!GDG=g-dzjJ&*03M~k} zRU?u$XAM~gb*?6!f|o*Gf4r}VTRH?oh4h*bDY52>bVy}bNqfRqUzj|J5jx3w2Q3RS zIa9Oka>X^}h&5_DnqtdKS@9Q8<@kryA}2EcI=zIOvH$rqBu7WXeY)5s$Fik!HlRx~ zb^{$I_1){4xT8s^_d215sO9gz%^jQ|SUQE&G(%b1Feb}()fx6^RXynN(IYGl2ez0( zlgEP>)oJhGec+e$2dL!`wClf3WEtW_WGVYmC9UTHoZX*^z&|#{GH&h<@-BKX_!W2T zk!OO>zh<)mtrg~vskBd#ZZ#2hj;BuK`Ma~N`7BceweS)eZ0ZY4EUQ*v6lOdT3uHf) z?8-$N4!1w64+bH(9FHS@kv)my56}L`=GJzbG#FdR9Sdfs-kUo|ds~y4&#kI2uXl#7 z(`pz~3uW!WbZ9od{F1jTjviyjf16m^6DlJ{-D*ov$RtpxQ?ANjJT8$mN@z8-OcJ^~ zJEfTa&Hypkvo0(1F_OPlY5|$mnEEl$QiP{+%lCbmn-n@tCzWDbM466Z5XAmGQcxaA z-LteicUjd>{iRkX>T?CZ)yw-7P6E9R!;VGMO?$(Q-tF2<4Zr?vV zbTZNk;<5N4aKPyW@HGY0k2?jOn%MV82z0KxiOk0qBX7^^E>3Y4r;Gr1I2&A96_ffJ zcr{q*f^>Tt`!WucZC9pg>9AHjw~D8pdFm(7h`{4~w2QQ#8nhcrO1iaC*3gRqBJP$+S3mfJCn<9Rzs1%8UXh zutvGX0k`GNS)-#)tij?Zv= #m|d%GRXgz6CYD^X=QtE)j=V`?zCYB>6{cZAMNh zeD&$n-&0|34PeKAWl7*T!gwn9-wDb4zqme5Q^(7z?o|2VLfZABTb>u=MdyskOCSKD zokT3zn$6BjFit78Qd8SW-S2M)AC8oz7pl0aN@iZ4ot?I&*GJXAsHM~w1^sSjc4dDV z#S^HZ?e-eK{um628^2nLfdG!Pwx9jh;ggs|3U%gQTXcl|dI7&RY>#)JShsatk5^M! zVc`~?xwjUb4&T3V=bfJ(AI$*s@~nY{m>jKX`ScVo-(#(M>P22ZL@&^1XKmPrO~lyN zGi<)A!O;>@!S6eEemH#3*3365K4;*vfUer+9p(Vp!Nz>N%Qo$>V(Tg6+$4m< zqWD|cmj_IfA>U_+pjOgy9aWL3J?ZE6+hYma!|$;;hRv&V*)}mLzn72L!nFaq#HEHt zgpNmndhXq-1{JaG#)eg9Rtw=MVxU%vNBf~*ur+l1!vh4{;n7kaMS11wS^ql#xF>m6 zkC00n+eFYet~i%cbNX5hC9gU*F4Fy%0UrF#?u~3&1_Q<`y~-{P;iGzxSrf@6EutYh z(XzCsJ9_Luc)!AHxuPXQP! zC`^dLP?<3N#x|`e-;upx(v`AaceOX9ShG@`oP5Oh2@9dAV~=ZtEL^XnVX9x=X2-1Z z$4~`U;reRwmu8>C(^v?kl=M2f&{k3>;kCjg&eCKW8sl0(>bIc$A2J|XQ zNIJgEf5oh)Sz{uT$XKqCS1Gy1LoJk7RQ{D7^Dl+Nu`-sS?QnATM6Z?nXr3Mw>#4^gp6L2t&tQy7wZyVwM{xv$RYi(^qR} zzH_dK^d{V4nyP)Nq;z_3SRtd%@v?Q@#8P0fVK5vQgppK)U12HLrSQH(d_{c`3SGJL z&I8Ls`z`|IPIdv~1)BxEcXyZUhUT~KV`bs`hY78Q&-7f#Avg-?5~HN~9`OaO<$|o^ z`?=M1ieq!3EL#P#Z8xpm%2HdDKqw8HvUR%MkkHxHO2|S;EPLKBV)`kE-I@m$*+O|7 zzBArfv(cry_hng{;rQoW2JA(g;LebcEbQs{c(InkkWT-cdUfo7Lo4C4cwXtg<< zi^r=orO~`RJv^QS`?vq|o!`%5oz4kdYg@Jj`8@;;l7Xir;TUIITFuQ*tev7k~$5=vgyHVs3E6|`J# z`}s!~lxCf|a^9~ZJ-OdOD~=yxzNxnQcs-oj-QJa7bnN~7ZjdVlcYz5n>e0@x0yNbUT>0suWYSM-cY%1^t+f|)j2*;cK6@UA9KN&~;ewlOqs^N`6;vim|Lpu-s#UMx#N^jX@>(2%X z$Cz71fv{~_yJnY$U#V_9NaRwWDCU%hMd%enFJ-O-)m8rvHYB1p^-fSHi_TZdI|+Tn zktuPLFz#|)|DL6pBaE@Zx8XMQelGW#hPPmHS`2rqz#4Tu*mn<_zQ< zp3ZLr)s$*#UqK^OlQHJO|8_Nnp?fB=1WE(i9V1c>%}nG>u~rv(lF zdT#K$W_JliQz!HIyrkmPD$Un5<2?F5Lc|>F5?O- ze^dZMSeT!XTC(?MID}M`aL6E_Du9bkG#xlwNnmXd8S{%2qMH!bQ{i~p#l zBd73Vpg;<@cw+q!v0Gb|Q&SZB)zoTIxd)#P#s#yCG9}SR z?&-g8GdrOiHa1DpQ!rx}K^&rB1n09A4=Ir~d*L@g+d7vaEEydVN;>?G?;0fP-xPZo z5^S~K`f|fd>)+&3))zD~^4i%JpXQeO^VQL$R(tU?SFBQs{6uidk_W#VXXgGrZx-&F zuk{-005NP;TTLQH6oL3C6Gapc!4$vuXM3P zY2Q)|4D#VY>7?TYz!=28cGYQS8`hqp34%@Di@&!aZ>oE2!%c&{wwtWExR~GA4B_C# z-rBgOSkYt_SOwe1c8Legq^1dTV_?}v>yD!7$Woj9TH>H>XV&H|=rGcFlLElKhwY2Q zqL$hF_h&!*$uDe%aBWYenH0ngVm_w9HbVaEum;)kb5Prm-=8>R1#dER_)7Ht~#D}X1NMsPeRjjT0`_eyD;D1>Ux} zV?UTIW+eY}W$*9>jX>)BoBeNRO^16}fB0e4Czwdh` z6(z4#43)<>v5(Xha18x0{9R+N7VQ6ZfBdOHv)0mkVVGCAZy$%ARq@k!tvqM^atw;V zSU9>?iyDx^*ER2^V9V}}&9wfKtnVUh&06Em&7)Q=I+~tcTwgAZI#z>Q>V?#co5$mX zow|;M)Q*^JiZB7XxY$OFk(AmkI!%ic#!pn@a;k;7C*wBs-9pK+hc+c_%d^`)Pjd_> z8l2!cgpAZg{v?AQFuzOOf}P}u(0$lRXXo2n``xs%==<}!f-atfLojyRVqtGXTV3Q#p zM6-XI!|EU7nlTo&y!k_fo0-2wQEF$;f8I2%99e;o3&gVA-Xro$?~j85{0HTWjtJH0 z_b*}#srS?KdK9z?qq^*JMzgBwle~c5TSsq^vkw$5MudfG+i@7n+)N#vDegPiHr$UF z(?9y7&MSl#`wT%v>ACe+@e0#!<9z!-@27Z;BcGRxUvHxaYe}O=sf-sk+B?hAV)oYSv_tJ9OaLymDg(d6YpOTA)|r= z)0Z#IqJIF0_QUR@6|<)N{b=OW_uowb6qDYtIlx|5QXKr@wSK}x49cdl)s~qnVk}Jp zT|_4t3SUHTU5GY|32-vg96$R(v%_|~?0x&K5I;o)wA~K@3)sBo61D*k}lFqj-5RawL{e$DhD@V8$95 zp0b=?`_o@juc7u;uyxd-bl&!Z$=c*EHW@nIem(>1WrNr4Xpqm7d8+fOixytN(ZAkA z`UXa~t%vgx+%4DREQ`if=U4nmEb4mVKN50GG&Rp>S_^B7%p=5iNy0pfG^|)Q>W8z^ z0_q~q)n&8JqmfoA-WQKJ;p{%Q8-XDh#NuJVQWg*rBB`F2H| ztyWUrI;kx|9#|`|K=44+)MjgpP(H80TWDf`OKoAAM#2&uO9WCezPX}fWnZ;C8ZE-9pM?V)L(r>>N%b)mUDM-LO?@L!KQxqxkUf zIzJ<@l#i{*i&B;I-HPfbDJzZ!9L)rPgOp0@QR&qT*XF50nyW(5AdOgK@O5@Ke*GP! zdiXg}h}h{l|LEVIlO2G|!(a96rpCxY+i081m6w0$C|Cjz?X65X=?&{NuM89a#_l$c zrQdAs)p!WCy1R$@6=M&*(bRd8xJ8t%Mb*yIyXIF98VV>fE*vtZ5m!TI7@9yGhNbK7 zuqc?s?9Nz8w}Rw=l_XxsfZz($^Iwsbr5U`Aa*j6sfSQ})7+EF;7&BE}bpYP!zSj`S z3vKdfk}NrOi?5nHHnBE6b|ri1gbKY`2xudbdF$Oq9q+!WzfHsnXTgMB(cZ zxMe3Q3=&BxXbMTnfc_eseTqj;xcJ_kO?TCmo^90Xz;EPtz zy5&HPr@iuf|1o$DJH^M=HbJhmcnR3~nY7gprffp_>u$`|b|NA;qBeMCNUc>f^~^B} zCGWf%{FoKRIy+$eTKi^*e3|ju)@KVDMk2q*F@z9vS(>02+$zmi>TsNMIC0Y85Qq?o8)u#YgZ>8X(u=gn$ZiHt z&LPf>cdwC&x93lu&dc5B^CsQ3z5G>j@jns-28sKbmfzJMd@>7pA20PBWZVVHrV`n z3jWk7O)p07>OVK;UlI?6ctr=pbrX zM9=fszCV`s9!|J1UMoZ+b|)vcSB9F|m+$;mBjUDT;6ZlO07w>Mv*#+rjzqA!^PPufX=d-f+HE*YFKPigK=go0}Zno+AqnV|Y<@W3S&%~xXW{pOM+hXL{ z^uC*OqWpgM6o^+2g^YNg$GDbtzRDw9?;p?UHmsif#{utjFE)~1qypwG|2}mUhy&VEtrie3CmWd-g;9V!|kQRjpKlF2@7)F-?;>ELe zy-gGQ!{aWS7pot|_K$1N`qvJMeV4;&9eH(QB0F1>g*aDj)A6yLAx}dWI((qCGg%te zPAtRopf1zhywB~9T^}!de-qx_pxrJ#;I(TaiiWrc7>^h;p%V}X02d#)Ye8vnv_-{X z<8u~vKYvyb5yA;UL_6YKF$8ud0k(KW+=I+1bof5@L*6ju?bJp;n|DSrk+JONtFh1h`pET`mZ9m1C7#Lc} zQC)8K_V(t~yfEwC-Q78f8%W-Wh=`%;z~4ji|GMCF89?Tnjqds_=yz({wIt|gMqwXS zyE~;7^^b4-bVe1-Z+9*~CbRJgreHSrskaJGVBDcWP;2B5|G=UlH#s&`kW9ekp|3SzVP^{fh&4OlYhBG@XkPN0D_)B~D5xjl$Y zmEL5}&s~1_6f`aJ=$1p;NkG6sBkB+2Me;6VCL4=Mvwp$LY* z36X>&VR?`|l=P1j!C=t5`(fgz&VS*8*5(_hDf));Vl#>Mz;XPjF$4f|pBM{-zp~Ir z_*$e(SUsGoAYH`$*B^ZLK@5Wi!x`w89RKcz=uE%!<97;8yNGsqmxfGxZo*S>lvKpr zQ-jmWJKP=g6YM&SAM3#n64xY3i5<4O$D?SOlAK^tr4CFIsWla&p|qDb>p$|N5<5*9 z4-4~MdYTihwEB#MM_wy3C9MJPpD*pNq^I6pZzaGT3U9B#gZ;Rae*4rQ@@>|;D&dF$ zw9Zh_0weO#Q&c`6%scC;v*c_7uWa+2Y67NHS;pf($*YflFg&ShUTmADN_vQ^UgO6# z=qI{@J9Qb4$?gx=ZZyjKmQk^-N35}j5=)Kh5moVZa3BgIxs5Wq&5Wpe=pd4hi!;8O1iCM R5`+SVw1fheb zOD3Kt$vNkVR#B2hK_oI~9v&`yEG+*w1GBT6H4DgbI~@Xo970w?RKq*(BHssyefV#5duHm2F}BEN z=!;5{-MJ(KPH=Nf)hyi-Wx7_?f=;uTUe#P74o>w$T#S|~wxNbb%%a|{)J@c{AB|$S zUx$4|X}u*d!YmTAudfrW9}yv;4pyk{1G=h8(bp(PUnRKSQcoBEx$*2F^G>u}p{Xk8h+qJlM-6b7 zpke~Z2k!?%_BnSwg{P}M(Sdq2<+@=mmQQ&6=sx44X*nfnIn`;e zM)VI2YIbm-1*&UrX9f@~URQ6Tnq9ft83Skm6ST0pbuJBo6@=Bb-*wtesx4;-O7kVq z`I1+a=G(0L_MuGwu)^09TAilmMGwlL2MMXm8CIsTcl(12@C7X_%T=NU7jnN|Fw0f? z$W>~}RUW6Qwc<{Tq^S+2tF=6JcU7jv;9k5{tDT8oH_E4}mFC_H-=7XeMfJYuS2^}! zh`_>g)?XX#1YAGa2jK-f2IU8RLKXVHh4j7Im^(m5LR1Bj`Mh02_P{>EbU@C0kq`RX z2VDbwW$FG2;97Gq|w%h5pecoZw!soJ0>svT{%^(iS)I38VoffF8q#)Ekqh zen&7dYOD${7xb+T1;B17LA+Ba@;$7V?2o<#^HahDg$vxxIf}ukAfQ1KAS@OE3}Aw3h&@tb`CovU5-sl2B*k@|Jv8OAoYwk<0To zgmUzlI$$qmtg%n*8VJE$*Q)lF5iluXaSK~BTamgCUV=+U_9p9|-uV|NmvARvfNFKu zr6JpI5QR}u>o$SgA-%nH&)q%Iy?)-kPjIi^m}7{b1;oEorf=ZZ(Z+xD;PJ@PgMw0n z;kpxw*#6COq*=lo#}-S!w%gl#7-C<%Nl7gIDkb?BY|Pb>@g;~v(t^tc$``g?fu2jA zzWMF{wt@zdDtI5!SVQgsLJF#ROMdcCgH%R7QotwiO69EC>2#lU?w^I-qV(=nw*7w90j6Zvr0zmdYZh3m#@8P}DgIcuZNUGA-pf-1bi5cF&4%Yu!0SOC$-nVwr?j#;EK|Usy zBvEGZNdoyluy@xmh04V!n=(z%oG?EylUuoqnNVG@>k_?cYJ>S_uSy_3?*f+SK}PF+ zyC0|*@!z`6OA)(IUU6@jZqR)fP<$8uao*6}5Z<_y&LqGBPKH+)X6@l*ul0l=6C?v$ zjf;Ed@Bhp+L%x&we*cT&f`0Rc(llR@S}O4lMJFVb8>03V8Hn(%A+cp&>i&V{tuOJh zhI@Q}YVb@6Br8-re(LMhpI>1BJ>FB155{8g;CeSTPan^>-`;yZKRZClRf2+`zUsed z@E2JYu>Z{&y_P(9&=RUprX9}o09)GsOl{f!tgs{ z&z1pme&W{*^r6BgeGs_J1}j^?Z~n8*Ds&*BwVTehz8$|<{VE8!v8b`6C83H$aF|(Z zT7>^J!Fcf5C0TGC#=bwh^%tDRoCCyf3ZG1Q zQ1^JoIA)%uw!y=3gA!1QnP|>OkFD3KecJT6b{Zpa3oUZh39&Pbw_e3X9h?^^bSeVB z%xSt(2d+RFuK&OCIpqi$YPaD+(c@d3bJq~KTuiQ>HUN*oa4p*IYlZhSkZ4cx_r`Eik7^O@m_x4U>D;sYUjZ@zBP2?x zg99c=o|l71$5iFWKJI5BkfJ~WkJEG={rp9PJ%OZwJBlqMlV^6uXZ|xM()La!`Si)x zlrR^SA1d%af39`PUP|i{FvAjHo5Aj6=yx=Ar4M_G3cwg!R6EEE2`TOoy<;AvYwtKI zSzgtcn_g|y*zaH>uv^EA@9treyU$k#=piI(Di0wf^-HjBFf+fsa1wzlA&iC=pN?gZ zz@G)puXS==$_t=YQb8Ih%;|jkgS(=^4s6j+LxzNAMbGOjKV3r*5<35HN=E*k>YTvn zbIdnOJCRj04-P%V5xN}b_o&|M^bl|D(6)!`AM$*dwamcYq69?m;y$l=dRl%bYDE=2 z{P)|xv|N^oXJ^hWq7EI#g4N|cT))t22i$&h+1h>!R#(+O!*~vUq$Jel&$A=;7>VW< zYS1qItWiXfZs#m^omYB^%8lS+>62yZ<~^-VcK{PXxz1N>Xs%QP{)0|dY<_h=w+mQ( z+?GFt8YD`~(j{TBa1d|jP)kqhS+6Dyg@}d{o0zD}m1$4T!fXMkU0cI=^jHW=zK4vA zYB%&QkE^UUDw*7`RgVcS(9H(lW%9(8>Gt2xT%oC94sjP=Dg6sQ_Y-gA;cp+_%=TQN zQl{;nE7NLszg%ymnuHCVx@usboz+oELX3U}0KY|nH&fITfNy7F`C70X2pQ^%og-@l|&6m+&>H^^Yi+D8t2VzRo~OQ0#SN3WT<|8Sf@eQ9xRf}EB#9n zDrB*Eh)QPc{0j&PRFZ4cNd0QCs1_mFTl&op72I4%?tiJLf z{f2xioZ8J;cTd7~qY^OG81Ret7;3;9sU;ix%a#u;g#D5~m9^j?wZXVz+#o>m=n6ua zErn$z_*CN-5hEhCD8r3Wt<0&3t|CMG51Rk15Tlf{@g)Dc#EKcx3QOuv1otF@4B}{0 zo1+Gkr*Pb#M%up@2>!xKE<+E8&>Pq~xK*T;AZtlzN`7vK>S^-iqHX8N)$G>{ekOWmWYurfo2MJ>Z*rj+lg;)wlz4IBmhPvucU}CpCvK`FP^~jUE4Pt3}*$ntAcAVz*_e zwGw-jUmH>V!)`I^sRDU4V^u?Djo%qjow-N~S^OZX+M&HyyP4BOmQYj&)tmPLCV}fZ+ z*r4GX|5*tH5{Tg264`Dh6o)m`%f?YVdjO0uioqN-{spr#XoJydnMCV?T zfwjpP6P1S@lzYT3u1)SnoyxIA5^~n`4r56a4KBL_k4{qS?jJ8>L(%QRpUb@=o5H@h zhfL~U|A@U;w+@`wQhIG6WFteEg=cx48f?K!!!s+mZ0u`Z)Sdk^IKDM&3&Cm)$m!Om z=5c-i5$_4b?vgB18`CI5;H9r;_DfJeyL8V{7IjV2y!9B|#zPS!6GJhwKbewQQ$W@> zj(sS1P%ZFsfYXpmNEW*!q4*JW!xdblk7K%aDZ8y7aE~> zVPeyQMcMiCoxm9M;M9vdQ&k{wv7Z-sDR+ZS*5JBp3*R@n=Op;zB%@D=B^Jfzc|s}k zvqEL^!^1EQ#76zC<1No!2#$VBxKZAVpO22E%5Oz!zM2vd4ma_?vtgSSmn^CCa|mTi zn}Ee>0uAEL0-N1x>~u_)bkvx!huhBUfW<{$djbE%VXBJpzO_Q6a5py<#8MejH$)z)KY7N_TsEkdISmeub6+vegc z&+q+aJa?L-@--zv?F@d0rVsiGJK0|EEsrF@CaviVHU(e;!(;Zs$vDT`4m}vu(eeI9 zne3Uk*YL7uJsqZ68goA?4e0WE{Eggpg_hNZ-%oy~eB4Lm+$Z!_V`ojV9q)kt3>y7Ko?>#1c1hAgdR~1i`*nT&p$Bj zr=ZD$olYZcOCfH>`d{n_9(<{oDzy0fsUD1;Pg1EaV%ldAUe`hS%5FXn8W7ub@#_yG zj8PBuES@rTdQt+s;~W~?!TE{3&j5qT21tyF2@@Cb5RQ**fCbVala zU3vIgI7+bfWDcc%-FJgrMi;)e5|qPcp2LWJH$uc}FGq4*>i%Qjsz{r~`_=Ye#KZ)U z@95`Gvr;yjq;FJ~mK|78Qf!nMEl|(80foMoo*SK4u(aZGj5TukqrdHlDN>5C?NRw+ z)TL1ODi52HeV^678@?Ja!!$s(xMx86d?`$i*UHsz7~6>ar^aHww^L?FdaMHx&|fM! zmr|zYazysL(?qWWC%F>fchc=g5P>Nn(vC`5(3uq~m0k>s67qMnjt9b)!h~+b&}f9` z`W%ZNF;Y+FYdAp@&u#?W;P(aN{u;Dlgx|CIkSTi=4EqWntOEn#e~x2$%J)67$FbF= z&l5_z{6c8Y9@Zkv^)>`MaJ_WG0{#^_8+SXt8HM!8-KhME^0MqK2UkWCd+>E3tChhk<}#jPf$TpMpTID%Z-r! zB*m^vGV%P1e5DHDCoL5UwAY=h0(B@kYWor_N{vq4A7s z*sI2jWao+J3RcTtHVyVIUums-mJ4V^;qxE^i-oc9pXE0GC2f@b`tmB0u%0yOyo37Q zK)eI5p#zBd4F1r?l&>qxLDaqfl9`gD#;%|0L89T{;gN%}yt-O+`$wnmB&6D@WtB#6 zJD<{ofelA(%R$u|*K$})@q$VbPd_iV$etV1ympP-^j7I&>6Dbjrl9L%1L9Oj!1+u> z`aHh8`Fyf91;=K zmmS!0crz%8%G!8o&-WpchKT@s&yk{|Kt+tZ%s*{Cs=;kL<-TpW)CUtP8NrUXZ2~)_ zTK*A$_{hW>arD8WR60YAe@39AxiD^_(muS0^n+ecW4g$K%QV`XBLTeRvNdo?ybu@L zF#;yeZT^1G@D%aTE9Civ^$8E zcC7T9%ZTV*I$70L{~Yw>MS5;x0GZwR%UXXia4ieyGn~gp!1WunP{|b-@G?w}Wnum% zkh|{V@J%s}@tkEGPKP%hIU{K7WY#{g=GKM_o$lM;;-s-C411pj8B5TWNW-=yV}`I6 zV@9SmV^y0u0(RofzP>gt!95T?kDB{^BEzrBQCFZuk3CprT3=R#eIo5G(14OsItH1H z*=<{E(VpP_*DsE6J6RkLF#_b5AV}WY@+rQ!z z)yWL950wKiztua5-ZL}ZUsZ7Z>GCULAJ>gsvJ!p}oG7IeB63urMUPL;`tcly_iqUpf7Yp`v}Ig~zInC+Mes>m1kPd8tV?;H_7`$G~EVF@OHY zA932Mr`+lYwXSiV`Z{{nSXVB zt>|0cOp;QG(}B|sRPG9(Up)1CTTC-vAdYY8Asq-Z8@@~ z=mjh28+Fl`IOYR)f=W^95y^UPrcdfCWAW&a>~k-1WN1GbX}vJ!BVr>7lG>7 zdEZLW)4xsp`sg@-X7E`ciW3)sEQ>kCzX-*P{NVGg(>!Ixoxd3>rBi%Lp>~l^PGr zb0x}^@qG3Wk~58QeNOrGd-!F~Z?{PWeJ?QrurB|dF(lV^*8a=GX6EedFWS&|oK&@Z zc?4CroK9&AmezLGN2Vi@9JjB)|8K&`3dweZmSn{#1np46Jw)Pd?J|X&sR~BYCOd2k zugf=X8!97^oO`an=pV(c$ERJ)_z$aGS&TO0N0(2#K#W@ z!h`GtoS*+d!j0K|=qVw)TCwG1~^pc*{u)d8Y zai}!yVnn(8iu8!jgkq&bY$->Bok9IscUV;`QLcco>T92T8plk!Ykpu=jw+Y;FCu28 zrHp09&kV$Bx#q-mSNPeqwfy|N58%?T>3&Q~FEFb7m8?+yFuhIs3>)Z9AZ%3Tyxrwz ztRBozaBfr#-0N|OU1$1*SKXD%7*C%WXF|E5Hr7f;(*8F*(WU%MVW&4%p>!9mOM$5cMq#pBmiEbwMD@XD9@O09@Gw~^`Cel3(t**aa=TbHFE zJq$+4M6ir-Z0Em{ZidQOTHeZZmjJjWS%}-01$7yB7X(+?NyR~Z@qR;8vLXhhmUFVt z4$$FGDvGziZUblS+DrW6H>5n7xgxU4N&jGbU_Z>P-);HvSL8KIr4C21MiAN(ErC`Dj&s08@w@Xd|wb4TE_s{oPZL-9k(&$(mi?>2vv zo>g9Dtfz+4whvXF7`yqMn^MKu7$5n#z8NoykgN)6Z(ZMScXO*$m~(^abgsMY{I4+< z`Gg~rVWEz?yrR9w;GwI0+Q?s~t}ipHvs7x53RqOO#wB5wpmH6wl1RZbn9(+l-q6y_ ztMquGj8EY5Z5sQweo{ys0mkXlbDE{8Qk5GH0i{wsf!_i{{om3^Z7o&Q5~=ZsEzb9L zz+*FRx}JiHJ!Vj>a@^jM5aC#xE>Qy#C^yiy_@LPLl$wE>X}05_vBmjY;`iXAp4IT4 z2dpsGre)us>S8l09k?6dYH4%o*<`v?SXhYCC+9FE{*fFhJwoL#6J8eBG`e>6lUl+Z zrN?-vt2$b093QvMs6M8FUFj{dCI_2`#<;>`v3h)E< zo(^_b6;x>j;Y|l&35bbh#p^;=r|nz0xbo=Zn-DyN()v>(uhFt4;3=$Ycr3if4c1 zdVe&3p=?>0|0e2EyYXWtT~wA2Jta%mU`k5*8ep%X(~~>@?I{dw=}^iuV@k-0Y*aTC z5QGvr)d!!XpB)tq@LExKistBjX9}iSCik*>1yIM7K^($ck-7MzK~MIk8*S6{?o^n0 z-qyUgfwc~Ot4({%9Al+0!SKnIZ)0#ZU%}Fz#5b4 z|K7D?!ZU=PPSZRpaWih^x8&9j&h!N> z%eG*MwDkUk%3P1UwK${RvDa{X_%gMgh;1WZI;?E*%1S&vnN~_>5Y&EWpf0ZkvT%5`tAE3ps-%Mj+-O_ zhPe0@%my;|;oIn`Om5fcQ&&c+Dcj5m`2RT)S5Tz}?YSl#%_BKmWfpi2lMHt7#iG<# z7M@RdmmXbwavf)^Mr>~{Igem)gt|d5kKgngx?Tz5Kyjb&7KNG-R_rN-avU3XtA1`% zf6CnKHt{?$#9g4@PnXaWe3_&TZ zzE&17AF%rtRdamz#W)UxABkZYuHIjDF-#tgm8@x(!V9KX$Y#BtF)biFb9fs&1iC_%5D@Z1c3#d4=iIsO=ivt>#(EAlp!x zvOc(i*V50?r!35*Hmlz0#7E~ELh<642-LIE#=)D^Rj*Qy-1hEb`T}?4#MJIHnzN@+ z2znG~hWO3(+*3BcBmtQEnKhK4yg6)QG$`T`6K<16CO|q02;V(TuTcZ>E)sKCIW9L% z$T1@@o$*r9dLRBDq>$C5l}bSF=;*b|-; zVa&Z!3wcJx)h#vb12eGSIe#PxY_)dK8TZsg+RGrS_tgHlxKaNNXei~b4YN?fRQq|V z`YeTg^&hf#_Jv`Ibn}h!Jt1CuZI-R+{HPmydE<8x5@@^4FaUeoVq{SXu=xuKC|e;> zIli4`i|peb8B>yb6a2AH9Zzuz<=Cr^89P2I_>|-Y<>%BP>hz928WTG-83fr=e~s+@ zdCb+^0_^s5mFQ5~cbGU3Wpk}o>G|-m_IFwm1>Yf9PMf%9>CAL3)MOP59`!zm(|UjS z2L!8Qm@y>>j<|v;m=_rn@+k4%&uJQJR8iiOs!?}1$)pX->`Esi4@F8B%T$?2K zLr|qs7;<3LIBjYmlVEJ`w0`*)fU}Fig^2e>o8Tq9%m$kq9}pUB552pj&wmO3P-*zJnwcqXE&h;yt3rRMP({iyZ1Be#jYS(dzQ5=I>2)49WNiLr6r#=YS6hI znP-r9UeUQHbPZDA`+hl-RR&))w6(BS4cGf%^>5PnieqY?qa(Kf*_gg;+>0x)9s*I& zIDX$3B!WcG`I@b+^wg~`0A7ZIKdJ_AehpZLXR zJo;pFnQ)ybSNYY1!lfn(xIS@wj-Qrp>O0$nI39naT^mus8)NPbg$`A$QeoiTR82Qn z$65&|V#yBHjocIpMRJ(`oqzZC3^Cr;O-Pi$6m(u|exW41cyiar(A{=5u&P@c%!(5AW|&o`uC-U*>FP#D~}OBpDMD z-D$Qm7nIb_jrkwGU2+w)HqO(+WTXN33H+!v-QQEu?)&4QC&{8X&WG8zj z941V?f3g4jC{4~)Su+pvtssHVPc+$y#cL}X z5=GoPI}f4cWXmZpLu+EwEy znKnESaq95DF;9RtO<&wr0*&&DPT;m=xmo{izWs$f>P3T#zrI8Bh%7NF&mhG#odskG zllAxl`U|Zy=ku}O%-H&W4U-V={%YKbYM>jj#4S_L${0=@k$U(PfSwMEWj*g%`Vyr8 zo53=AVwGH@OrfLmF;)AZ#sI;O`~E?@6O7_tE?=f~{*`h0Lz$^z$mKwRbm+}aT zFyJOTp;o=skW3gU%S4pM)-Idlbbs)hN!GTvFO0o7WXC7ck~fT!4$~TGU!{f+^VO&g zx4VDeY`*NlFZ{jtX6+~og$0%>{IEw9_H#hTr^#Rl2%855PHsj+JO*c}v<1*O#fQ6;Az-@~AeFGX_ zDF&w)VYFyv|*MpOS>@NCFtgd(j&|A3D|5{u_y4)$tFxRKToI&MuzEbou&7(@!W*yogaxizb|BO?D7!w&&M!DN zIBxb_oEIl4nONx#FYg?VDl12iA8y(oG?RRdv1ZFnoppQn7HoJz%5Orc&!SQ^G@)5- z?FGJ8jvW`q{)eIejI}%Hd_Uf2lNNcJN?0ZCa#I65X_!4luP8;qEXD2&8I=G} zUg;z;u&f`NO+mU-HGyoqWBFj7o%5$PW1oo7QCs!C&bIGxpR3z7h6p|A+GY@N-$*CT zJU*(>w&kj^@9rSw@lsPb%!Vk?ON_iQt_ckE!1)xg;}c#b>G+ZLMvm$)02d zV$4EM@M+`%2jc^~D?ASI0<0sQGioO;bWz_T%tb0uOItU@)Ik27p};nowhNiP4W=4 zfuBfNW~!t^fUp9@Dw8_PH8A`!B9<({y0Tx^?_zp9g|%Qip3pTTq%SS{aE&IPdA8gY z?opz;P$KDDCSD@UM7LSSv)QN%Mz&Pq>({mK#Y-)gx8q!H z{w7^h#bQopLPms2iLR)8Yjp0B?Yw^-vU}2CdI*>2ncI$ms(&ALoyL?hl7Xd`r{3&^>UpPgRHfHg zvaa5(JPpcWF8B$$#I%270s_G2=!2>2hrdmj2m}-)zU!xl7y^?lVOi`(AdZUl!{L!p zri-N(^QGBSq4N!7O*?F97jXrJq#7eEYS^DDJ}Umrq`lJ4{fjvOB5Tto#bXn{+*+n9gx0fLRT(enW)~s{kWM`$l^wQ z+QXLmasC1ZPFj-Yan5NC`d#&xFyEd`;(~(lVF@f%xtJ!zk7<%}eluie$n|@&NVWx7 zFxg$`5YGeRqoG4B1f@q!8`;}X;z&{Mk3`jDUst(;Jei)gHIv!I z)|5v%-IdTGCR?{s$(4%?jBz6uea>M`Up$ePmGk2BxD(y72jYjlvHzj7y-+)%7@n+LXs{G)%sIW z6-5kt4<%udiHacCL5KEchJ4smr_F7SKWX5SVRPhuwI4Q8daCw#K zMLD?MzjNP(>(k={pMC;K(eS9*J$~?{r|)_DIICsdJyI|;_(Y7xlM^MFV9&?4&pLHM-E~V zVW#4BXh!Xmtg|WjnAY00Q|VBi`s5F;#De!gZX6#^j44b~+86kSBA%HRlRuv?ovsBl zNm{ttPW;jNtv}3dKj{Sh20jHr>Q5bzvC^ffC(G5SjRF%vfr@3V3+IxR7MRCZr_e&L z=$b0k(h$g{i&P|~#$*=7Uiqtd%KX)ypmhJoVC#Z$dCAW=GKKs#TY2tR2k6@na>nJp zVF`t1ALj8}9?0d%*;Kjuhm>XAML+VhScvR2aoE_YXiWikHe#~aM(v;)YNl`hJL9pX zo&f+gLnfu*T5Y8d5!sO9c7mX3D1x!}D8=HAaeox(CAWVL=~Qv_)H8HoFgrg zP{A9X&9VgrIXQa*0!5aTh0HTv?gB3w*(vOdJ_0J)lP>M!V0Npzu8eiKUaTOtoE{T# z+|Xvxakv-`k4<6yIDK;35~akrn6z(C<@j;_gari_DU+v~wvr7f z#+A;bvWXSgduZ#oJy7SDM@e{48I?ktd?f@0Qb7rml^LQ;PMB=884xai1XhOhYMc`N za4A&dL;f?!s(2}yG#+$*gly`3>`uqxY>1Yjs36x|2_!KddP6SnOt$!wgq|1B!E*cz zar3c_B@vB^H z?sSC;^Zhl!4XSL%)$t1DOB^n1pCIl?z046ZKZJEY41;!vZOV5r_FLN#y87f?fpvmB zqsMWJ@^Lh`kwAf|JGoMA&=S#eU`Yy@X8XMWLt6B^LA2Nm?Q~@F(z~20lAFQ2cm0O!-9G*o)w;0iDYUBkMrT+bbq`$rtQ4z@O~H z)}O-C(Fiw8aaeuDH6QUyzyVtjNzem$xkW3_DYsUK&K=Ew*nDjghrq;v4^M`Zt0r#QMD8dY***AE3p_8&B{0Xy9)cH&0MII&mi~}(^b#|F_{Ph09 zxTjCm_#TT(U4b7OH6K!$ztl5@zxdzA_b4ZHMD9CWY69&~o2!hRhg@Y%_d=@NUb_VD ze;JKw#%Nm#XAt?H%o8o(iRSmQ+SDIgY8qrjytb=a)FfBQS?{Pgjp(lN4;UGbB3LYw zrJ!v1k9l0-|3a!mBS93;hZfeu9c4_+D8ODIw*J?$CP#B)NBQjZiRju94%*#8^tt3p z9wo){IWf?;BGaH$k36^!{YAm}Rt3DelDyExPC5t~`%`@B&&xF8_k|(mOU=6pLm|{w z8&htpQ3b!vY>+rV*`IWjUv5TUy_v96sQQ7v$s$FkYiRXZZNWut5fruzjNFAb@{-|W zs+Pm_s%Hq}$@=Sl_ufHYf_=Zze}QN(Ln1H2jkPeig=7wcBj>TS_Lf|4qNhw~Q+Tt6p=dNl6Yq6WjAd zm}OFmzzXx=FOmVDe#wzw4!$#0uca*s>}{|PO-sxyhuk6+ZaMeJ6+g!SO&w1E5Jn~G zs#(~&s+i~^GG|q!9_Aez#mN~(Y_fJIQKvSe2QVLm8nys=YZWx4K+dt<9yY2+vOmPG)?F~kfjPYhl#UgT+)n-c!R(O^PKWA;BZ5yT0 zIdX4Jg7j5tN-6#174O%f3;0dHHcykWk-*`G>v0=~DUX^zIux}faFPXXxQ#vm-`$ft zIjntQyotdg^Ru&Oi&q09ep>)PL1E+e!94dzyS+wkrc4+~5Xp3GpH}Mt*=H0FY6Q;S zv9`o&3FPZG8SS$c-!=U~nfF!N>BYdM#iVtWbI+{mYxQB*?Ee7Ygl_|Q7}biAgTsWL z>hmJ&xCpSZ)OjN*N^}di(l0GcvUilkw!n`%lP}D>E6SkvYngmLv&)+sV^({p|OT-=81J=9xNd*67*mmOJ@0^|O@u4g( zGHpfB)I0ju{EBd1x1ZFPbNp+XYY&$0RWL@o;Ron~^>ANNPQ9>Rz z$&e;LTAixLp2jCZLIp!?xXD)}RRZ<02sr*O$>~tYP(NH(70TD$N4m0CNUeVwIRJ2C z2?YtSI$1ske2$y9UUKIdz&i9(>1V(lSVFgem4YlcC#7;$PZf_TO+eD~zU@~!f+w$0 zD&6Xp3hV%c$F>wFl_?s|vEnd}`8%(tXizB6(L>UEzI%7ObVq*+Y8i{HO?ypOv#VE| z(3C^5ZMp{gW4_5%dZnpFI&0M~MAPMR<)h0gK+h}s;RH%#inZU4pyK^BlvzbW`vMc| zdVk!iuMhT|yyeMgwPC2lj!2~m67ORg^CydTnd#xacYZV<{-9iMZig`NW9oV;_*ji` zaIy>kgc^ms|IZWk65*Y21&IeLt0awm`NMlzyzKefpo}7D-{Zs#c?n?@5@y+b!}W5N zxUfc!Glr;1#yrGwH>-c+ns=Ntc_&SK#ta|n1Sb$1Rj5rIttDsDiU5f5QW(`WKU8BL z3@1TF50DRf3NFrdubCcbmDWCFKd~@m@1MNIK=iah`Rqhkc0<{JX)B*x? zs4)A50x+A?8u#vU+x=(88BbIbayaR03rF{%sq+J2J7o^5mh_q~k-F4wo+`HN?Tgb0 zzr;bV_#Ef!SMq`eJJDFo{H~t{`U3`)Ix#+uyDxixG!X~{YK9p7ItcVfwXB$!_|L;m zn>yL#6K=FvrkFV(m}5>19d4xihq)M-O+;c1rK5$Z^9i5lM<*iQWdIeZ%l&JOzFf($ z35rs{Nu~g>mw8=pF}aS-Q77*Nz0C|wQAM|4- zFf@s|P!Ac}&mySaB|62{`(vxo`wesV5Q~PRu=w5DgnBA}y%9cqxF zRmbm#IBg1Yi#cDW!IU5+jugerz^}8h$ZXTrXCV97@2gE$qW~>1_c`^2Xz^)B?gp+) z%VG@NeoUW5LUr7^Nf)R|m9~|q%ReZvuGH6#R_tR&->i8y8w}t~5eR37M&B<*YoBPq z!w~jlj~{m)Ck9?%a?JhqoO};gJ5wizno^S!L?H*n2Ezrn2J!Y~1NMIXKaG7=P+URR zZ34mF9fAi94nY&#-QC@tFbu(E&_RN0fZ*=#?(Po3-DUpy{`>OXms_`LUQX4V?$cc@ zd#}CM+Aq=uL5JC4R(x%LN0L6E(;Y)2825enP@zX&Sx~ z;W!q9Rz+(4?isLo{SRhbk%W>(S8;Yc<1PzMrRAImhVvp$qr^Qs*0C@8(hmrzam}rb z_9b(kP|i?s*+de-P*LyoR5O1UyRV34pxxnUvqyFc4bn00!M1Z)hmj4aiz)ly=3Kqp zg#=e%=i!hV9pKBD_}lB0!9p-*8E$fuI*%JycHPY zx6Whp)UUt1b!vaG%3iNV&>x3VM;-cJ+Nm>oX@qZju#nd|;M_mn#MpnP#sW4gWJvwp zI|&fmK1grv3m-1xLXx0{23`Oy`&rDE7#+=Z-U`JgiW#2`oFtE}M(wFHeq+lYFpK{C z9(#(o+0V4K)=l8h>Bra|?=kxgysRz9!RDwUJk&o}6n*rx`6=OB`qT)`+lS^`=J11y zK_#!~nb^DC)fs`M^>mMQe^vFP6iGU zYJ;<}0QZ?5ZJU9D^Z|gCH0fY9&#ci~XKsunjeO+%j$IddDFg$!;i;FI3M_ZHj&3KM zvX6cXKUpfbnKEf>OG+F_=0*9w(mpuz=G%^N7>f97D$YsyDr#KMdB3|L@q`h?X_BZ<8uY8-VS!$mdlNJEL9r^7{P zmY?!n-c+8A-4@d$i)G;WlQMgxoU*#I%g6q|z3v`bnGaGLPQ6{Iz4DVY4-bBKcdF|e zjSX&-LWgT^r2l4%ZheVxq`t_vs2YaIx4wH2wF$BG0f zVFX2S&$@3>C zO`hE@WUDemMxvt*KjH=wMY}&?6{{ZGU=dBPUDTm?i&9*#VJ!J1%pg%jK z3HpmKwk?BYvQM7v&}nu#vpp*g&L&{jU$jhN49KQ+B%EcW$xsYx!fIHbs4 z&Cj{VcpV!*yZ2NIPCB*=w5SlHm37z)cV4pYBYM#?8>B(r?-sXt0SW%-d z#SPoPKYG|l+5H^ftx*E@ZM0=(d*AU6)IJ2qllob-+1d6D)0kX^4T2SKg1o-=cLmv& zjtX>h8KkI3<~ACLhL=?i66_ZfzmD5>gao|=3@5ZJ9`4EbK4Q7zxmMbub&~#39eX$D z_vL1MuBX4)A|<(K;ng$loiq(JG2X$p)t6PwXW$*CDa6%C9>pV&rDI>~0)9oO_j46t z)?cc2VBv%gH^>}}h?delm?2~JiRs%x8fymrH+<@=eSXU@t9;;-94TJ6MiRI9g1hLB z%RekiP*3l#3m}0hI}gSKJ>pM1+fD?Q%Tckac);(eAVeb&ocdcI5 z#!5<#BZpZkj{fwSdW*CYb$_RH9%YG>y?VX#x1iRrU%PRh5x^dSvCgPIN#J|M;FSQHTtFp-3^Og)Kj>*?jF^eP%^|Gyq}Et|H>r0Wh?Ajl~x|9qAH+1vlwz%{hZz>d=g4 z8J21aE)73;o$2PV^^jXJ7xS55K&K?k9GjEk>16X4eAPqPq=#|-$}ewH-aVxTurpuw z_wt$0;k1dtbTil7DP$zQHrGqu7=4Sy@yRHf%vi6NVo7uCZoPPZI=?uS-{9MGH`HAOA-u>_t+sv*ERhal zu_giPJle0*dH%pc4i^5D7V2H)*_27lL(Ybc(VP9Uqfw!n2lsvtjo@tso zOJ{l>1SBI0TVgy*$G3y1FFyvT7z_M1_+7avd^d4n?UeD4D&Vbx&x91>#sRbFF|Hb& zcHaBqFI(fpMlbICEp*>`)iukQOKg%qI6zC&(KrDAag{0+^;1pkhh7mMY?*?l3{g7a z;X)k`IWUQ11bZZ|hdQjyCk%|BGGyLwQ6sdT*B`WWf?M+j;^ncgIp7fL@|g^5__OeY zc2RqJ`m+6!d>15ZQFpiToGqZk6R?<3k@eGIsMlrKXDE=w_3O-5wFRl#YE-Rt+$gYc zUh&Bm2lgTik-EWjwzJ8EL;JQ!A*ApBc0kBi8f&Dz=gjH6!Lx9gqjyiIEJ(q4#j*@IHW{1cg^H|W<67WdTD2N1r8`Yb;=mdzauDx5F^ zO#qg}<^@7qRsO2L@!$MEY9^~x2xK(a5#do}dXKEccA;zPH)4>cueBStav_qVGV!A|C+PY znn~E@ty36Un%sPTaC_PioxpPb>1PL$y$Mir#POJtNLS+U2vgUpk5Y z4Dz!OC8i;OgX%C387ff-%V&-R-C^U%PcJReY5M-uQ1)(bXoNn`OfpO8CWAS(%F|vv z{@P;$ORBRv$7fbteu?P9pe1jK@}}m);&{^}wK@($FdZ|I{8Q9lc}mJ`tR&PzE<%-N ze|^z+Kg062D+E0bBAX;Cbw~c7E(oeOzBde?i2x)Mx$KkXdF`a|nV%tl@H4-jqZaoy zYOe(>>|UlJ!fJyy&Cc z#QI_~7PYu!H1@Y=>-bjR#XSLX1htAnO>`mky*!Zkd7Ika-35K0kWZO36=fEEjc54~ zr%^?c{I1IA9~lS0Jy%+Ct$Q*HQ51OE9mp>4f~Hm@DP2SOY&b-0UIm<8DO^i{3j)0bYDhe&!2#xnRx zyxZoY$@Y{~6&(E_aT=4kAqA_8J_Rlt)nZLE!VdT>ET0>N_{PbyVLM?Ri;=Ggi?SL? z5VcORs%s3%mGGelr5ajtg61+S(JU+L;UG5~ns`X|>X10C-%G=K#H_Vv9LZ#jMLqG# zpC@%&Tjcx;>p2P)seEuV3#DVMbwXx0*ufqCj*(Go&>__;izU4hng16$DU$o&(9Zl5 zH#sl7$H|xyo0*sk{8ZO>zBWz8$d&6OZUL8G`81lD*2baBZ9OOILti#IKR62Dmzskf z-OVt}6aaRi({-w7p7_+^N_%j%kK5F!pHy<$Z@&jTA`Wr$fv8LY8{+X8(^b{VJTMy9 zYX-*-gP9#f+iY9kK9c39;<1xVILVbjkbM5c7LV=q3Iw0oMj309##W-=C$Ej{yHvXS zGpyz1`-d%u94EKcqY48RuR1pWVn1!fyhA2CHl`3H3ffFSY=yyWSL$ z_w?U3pP$i?Huy-@YMHtwPU*0`npZufC-b3g@N&IYYl_e))n!2Kuf|_om*iDkk3gy_ zVr@7<*o$9HB*ZO|bP<0nkaP-Nw0k4kb;$_vL?PpQX?4 z0z(vB-2K4xu^mzDOpeH|$6JH&B$55+;vKG9VA#p>9yC334s^?*o-ba4zRV4G!NtXD zZ;Sn)HyWqr$$tBlV3NHr42o}MA0~ub-&RVexputl%=iv$qTC?IR)c+J|Js~-wN|Ru zEO!t8RIozEn7-2{i0`;e!2LD+HN@8L<*@_g+K z(hzUF5r4O##&8VDGT$|ESwN4fHi5NY`miv|P`II|FyuD$1>_=h{C5+^L*0!BeFM2O z$5m#&bfdj_KmSNOR^U!j*3+dSZ1t*@$tS9Ymueyq;7Vl zNN9YD<7o5L*1t?P%Lj(|rI$>H z@jS{XNU1aL>9^0Wos68rgu=>f*xkg*8v2&nh(ZBzJ4zH9v#?Q1&)5Z{PH_zpnIf$`{Z! zTg2e)Hc7Zy7}Fm%ZrXJd`&1i+28%9Km!Do(jH}AX7>V#4}nQUu;m|M4#_a=4A%KevRstVtACBA#j$s7qlFQk###T4p(IZkiV)%zWw$V@@FPdx{N1`0nb!O_+@((JkLcJaK+R|?kTs3ohyndad ziA>L35myt-h6)cfeQ&U>6bERm(`fcy6*{4CX&v}z|;85A$U z_J1PvQer}ag8H?d7gRLhT)=JIG>V%YYGb-rotpTb&Drzt@<#)vRZt+WH^KtUm>oR^0YEx8lR59Kn!rOmT z&<6h1eGh_~QEf%p1B6_N73~X3<7*oleg|XStp^B%0cRWBqQURg@*?JGH8n@wxJnr= z)K=Gv0Od~~%m#aA3dojfu5%NA>WWKpz4RsrUnklv7gvpm_e}1CQAq4bh35kwZ`PjW zCHKl3#SOo8T8n}?EUvFL$_ptI#z%SEps`fR_Xiu%r?Rx@gffS2 z@NrhdX>*atq3wCxjEv@_pN(X^W&xvY{){`iuutE{F%jnMsr&Hw3W@ID?US^IaV${x zyq1%m-TKC}_SmAg)g=)_3^X#SLmKc!)WF?q9e{(lQx!MZ(kL&;#OCDJ zt-L@F6OJfZ`sJ#Rh5)RN%j2C_;0JVXYjXH+QmI`Ey!F>Kc3kDVl^6Zqzc{b6=VXC_C_RAkbO$g zOrfCP9V6fO-(Ta$ssPY9c^~JJ%9bggEY$C(&RVDKx1SukkzQ<>8p9_YB%-5i@URfU zC)yn)(q-OvHPGUqin+xsTEWNQHEL1L?vJrIyyhxJw~16sRuG@1>pwpbG#_&4wb6}< zm)rF6kS%j_zt7AyfHHT@2Jr>wa!_)tM@GWj{Z_|wGnP44ZHoy5jP%0K zuM)vlF~#v_N!cs&P#jV|2Ko2W41s+0ekTO&eKVEuGK%cPOHg;oZe&a^EXmT%BWe0u zRs?!Z0gO?)JAWV)->So0q+ILW3C~utoHmf@@!}`k+2JR*RN2T3A93FPDDw|5#XL>c zeL+QCI-|Dm=Bo16d15C%kV5{C-_3zLY~5@Fb$EY@P+^SE8}h{3EvrVjsyX`*CY>Cg z6Zypy;4`s;6-|=qMg4G3l*jiFvFC3#@GO@C;VgQuQ}61?to$_nz()B&Obm+@LH7|s z)@@BqH$(`T;9NF$Sv`LA0F-}3hGP}nD){wOs5e;8X?{|M(>g)1S*E}`r8AsF)$0+b zrh@Hpidg9rJ%t6^RX$vl)+9C+!Kp|8hBaA4>6Prvgr7dW^9l9) zcs+^o*lCxw<;E=Sv&$z0epqi?_Fs2X63KK^Oqs}zom=QhcXD*2XeRNa)(|f~+(g}# z*2F@(ezQWn`D|pG(2P)slt8v=v=vJXB?6$#!vVgurw#x-t=xd=N^EJBxBh`H8VnuD zI(`4@y|BQ{DezwnuH|MDie@S)ZZ9x|vhC=uGS0tnIYjZEna;hg-aM4n9(ITiWH0z2 zXS!qZ`{;hFb{HP3Nb>EplY_idaTX`pvsKH=yR9+=f#{U|9&?ATjh4VX`8zzaSqtjm z`hn4O)MR^=$o(~_udG)kJHz4|w<)zN?x2I3Dk>^W-7@b#6KsLo5Y>~s`Zpe46f7YF zo2>61&SEwgnc)^Qbhm52Y${F*VjyB-ECpJOws-(njs^zHr%w?tqSBO~?Fo|vmP-h4 z`%1631h3QwL&B*G6~Q9*_5pGMR)j1R-2!gxs=(SL|rtaFt4J_1l7OThaFL8m%L4Hos&$T}5Y#k51c1{i-9aXo#)NDiqWq7h0}5^4t1U4mkT!l7 zNc-@Lp}cC=_|#?-Z@jsHnbx@|1?7`0H~MIf^GcU%{K@VbznV6_oQtjl5taq;RXP8} z_%06qtqe=0iBS3SQ`pKLoK-Z)ZlxP{#i_|*jTuE0^pMRx6p82av5ZcBYnE5oyz#+k zym64YhT=R>q6vk-gt-N0*zyg}1O!`|Iwt35D%gq{1LO(7vPX~=NXRf2X?iEB2@ZVS zk&M$YV!PzycTOypga|cnf9zPgNWF{t=cqUby^t zBT@F^0}lI}N0I(G^moT9%gADko5fM22;Iv(s{K9?`UBdjp1%A9lNSxh^{T5eXx9z- z8*#Ng2rjkJNIYgq+(rfZ{J;_OcK{w^w|ROYyUn&X{q2#zl@?z;_XE3Q*%<$QLz8~CX2&2{_Qg*EW-22>)K67q&7Z_`%0wfvKH^XqFUB{Unk^nCYk2Z5uA;;jZI;*@@(fy?H5mCS!jTi>WzL2plmzs?tgp-|%2bIYfk zgra(~yE`fjC1$+S-;&sQiHW$l!^YC45Z&fW(fE@}D61>10Sa+l$<-`&C+7aSyIss%PevoNr@BJ%o{a75=Hh8o73lt=Km7U*fob_IJ zNUU%Rn&1s$fI?<3bHSDmnF7hNrS$ge0mlaL8uK@Y#`<`PFgqQd;MIxypp1*#yNR%hZ6}>gSGG#&@Cx^Ld2=wEjtG5c!ViUX%WjeP>;$`VnyO8IQ`m>>>?xuc?9Fm2qpX|U*fbjo<(;r=Lha_}nL z1-&Z;yki8z@b@ZdGvYWG7Sx%igS~~1=3mOx;<9h)_)x*3>}jvftUryU$M&a7&nvm+ zShk}K$cv0b9`BxQnZKeTbF`N(alONAbOKo85yLa{Ho+3&%u9kmj%;+$b_=kH$GUj> z!w1~G|I`S0w2CeG_wXQrN{Dz=DNpAv8fD;lb+SYVk&S=bkQa68fKQ<7UTX%5HJH?l z%<30UG#F}GX8AoDxKe(B`BG5FP{dvLN9)Vt3>NWwVKL`kFHo$HTu7{f*uhET^Q*SS zXg30AP0e8HvXL=PpH5-2z2i%{YX#XV2*%b^4{m&wlKEU@rT8s+Qb`T&00+r`4m0AB zu1J#jp3^9U66#j0NfuIuRb@cF>9Ibxu|PH~{xnIPa4<6SX4s6j-Pr4NY8~-o&_WM% zrXt!t?le{$9oP07I>veP;-Q^*X*J6~4oUIuY&UeJDoZ=K=`7!Y({7=FPNTd(KvCFa zdEuetUUVEN;@9t84t|J1-j z#FWh}9hlRVE3_rW6xqv#1i+%ksmOmgOuL(AV?T7i^P|wrE6CE?tMc7iwF3YtF zS98S@O_IQbxF}Q=js5j!cfTb)dlcB0#zA~f&hP9yUpg&WAi}lgBxQ}Uv_ps6aBBSd za=T+_awvuz!V z7lkI1|7IgyC5<_Z$jmT3D8n5*^a^V$xA6AY%AulieFWnER#ETzdPPN`|M@!Irr}R? zxVP*RnY-`C*9I1wUaHc zFpd}Fbk>rV)<&0!bMJHb5R62d+1KJhccHjbABOYj)v)!Oyi5_B&ya+(?c}*-Ac{%7gZ9fE7>d&1{**gRn(fCAJ=Qv1&?4N>GQ9M*9|4qP=wi*t2XaIA6P@>SOS&ReWs z{E%4i9vygQH5okconyk~Rb>sxQa}fvPLg42#m!rnqep~i?@LPKNSr=Jy4pURqa9`* zR$fHaKBzLx4E9&|WowjDVR^q^Y1Y@C4>Fi8YR>jLzpCzKNg+;tO&0cTFv@5TTmsCK zdbVF7Jn2g^;s#obHuyQJF+d5p!;fwx`WDXnL;lXs*E$)@v5AjVpCs;w^4VjBv3G~4 z0U`si7>`tAsH!iDna56U2lC!$+?$f?r37mpznxySke$|u0BdF#KOru{bmXkaDwK&$ z-YKua7uQ0-vnkolEh6e=aFh$|5^T$bNX6XdxpKi{I!Ht)nI^l&QnxW|`^ zd0ImiG2Iz?>CgM4lTnnysYii@{&vdt`-m(y9G!Bztye_c-T zFQ_QlzEf|EvYsvWQmS=!8*}W`t9R3RCV?^ZS&U0PY)}vFpAE#T)*jrt!O@S_jW~&F{CsiZ89upD4 z`sz(%y80)gsRChiPA67dds%1{2+(AAb<4XQaU%E_fPi=@r2X#3w&viJy zLEi^p(ok=vyF-XI44)rTa7aT#7I`2dBFIkZLBBXso?!npEDrGpdY>;GI^*~;UT@f= zuQ19=G29VWN#T@MV8y=#ZR*3C2W)b$_S&y+k0BfcRc>GWgLtJ87zJ1QuP-(!3ZR{L zw4N#~QSP|ZNTyT~SU=`2Xgw_-lDO2MFmn(g;MF|dRi!WAj?h^OlMeo6J7dU{ufCd; z0s1|TpWd(3LeUc=Ql7FW5ydR|gP4$%3W@>=!HJ^uEgwnFG>Z><5@aF6&d;neGiW*D zuPRB0RilwKO1Jk`W=bz?GTN`f-c)f!br?Z0(Jm4qd~eMPL)iYJ8AYfAnX6&H>Ga33 zy5hZ<0|$}EeZBgK^gSh_N+2IZxZ;dGdAg>ljgRBm?mGIbs;4F}1Gg~ghlR_i1J&v# z#GHN7@?~o@4(OJBcBW2JX+GqB&ZVe8K&1Pe%C(VAVD{;RCgGs3|F`KDJ2EH)kf6*) zS*=aDci%}uadT8ubrNG>s1TEUi@d7$>m~qqs`g)NX+SAR_$!?0xI<~}z_u3;K57c3 zPU3}rU0LRgH^-=bYNJ(oMn@}4L@)(I&G`;8h^5g%CJd&WgLHUxP>+8m)!$t-D;$2} zHP4|rx2p24G!KjDQE}H{X$rJDckB@#-Z?oS{8zjOqGSe9r&5^_R$_3WR`L0#tC#gG zdK6AcVhvG~mKNJ$zK>ie5L0=YH`l{ocs!&8QR-+MKLT(6649R2_*m6Z#**n%+w?Me zWbl&9XeWJxStm~%w((`Wq?+oSeh5=Nt}~Fca$oWMQKPg%t3qN(!dI2$Be}=dn;dpu z9?v4~DZS)@utq_U+MsU2p$!r>JQKCf7tg2S=6>q)$+CGyAK$5(EwmJA41@hCwYX0; zWjVIQAI$Ubdz-U1kAJyjGNdP2-~#t)F&@rM6Q8z{Sj@accJBq<-_ku-Z3yYSUw)`^ zG-UZ8`FF2aqwMJ-pZEf7d@sgV($S@AD!&&`pqssbDr*3Qv5H(9kGYYcycHg*kASyT zmu#@HfTYvRt5Fb`?=kNeMTiKzSI{nkK^&u0YFdwtg zpKRD#6pEV56{!eqngZan`!T-~CqY>2EyjuCA^OTEFTun}Cy-k*1~0O@yA15cc;m0p zS)2{n@BNf@%>}@nKgsp&=_>dEn+qWP$MKsP1GvGwd{GCSSbe<{6h34dq?YI^+fa91 z^UgQ%4xcKPBNV&680F|Syw!l$ZvjYyxokgHL+v>yy)XJ9cq|slFB=E5A8yM4Z-q`?c>lzpyD=P!L0O@b$; zg~@&(qA7dRljT~P92*VDhVZie0xvT9P}O5^#)T%~a){aop>eg8cYq!;ejyu3E5(Y3 zAhFrm^k5T3jQ(b%;4)XElVV5=8#{&{mYtPmzU;ytiWbz19`wWM58)YY^}qnrjv+!_ z=;pjPbcJsiJO6mGVH)pmpylju+_qu|sHyN~k2hTfh^~D6O6sU9=kO6jP+}} zEKvm<9=_D@x{Xqg9lKOxA~yXHtzbBwxhRu>eDA$_PqrreR2dNr4XWN`k{v4}o|L@7v{kMyD-kTOf_X`}VzgINe~=g`pPv?QN0`ZJe&^rn4nSUohv%1 zA_K(4f~wL0Onz=o7btE%Z>`mpz}ioIG{7z26S5dRsRWh1|IFRdhZjp`)0EtvG-=wp z>F6xsqgR7h>u{PopeXu^fqwA)%dC>g23%Ia|2iZ`vNQ>_^JUl7>kdiWY~+J#bfMns z9cfc97rhEhI~mrxDSUjU>~;_7&F|L=&Z>a07@y9?1Z}>Q9jdG?lPx0T{2pXGjHl22 z`Kk)mAwj-*Ay3|9cVUBn3u9Ii5;7ipA7eJ|eszT6NJr)ym*x0Z~KP zKuqg|qrZCt{AEplDs~{oh4rB5WVjn-?8XL0WBeg}9@Gh@jgF8i>^A9cmJ!atH(TQ) zythHV6R%M-$8^ABIl>#Mw?^wE!j34X!h>3)JnQ{EKR91=tDt-`z18FwsreC?P!^}x z?qq_&xgm$SAwR8#b8RDtALhPU3K&VkoE>Lx*6GwZGw}SoL%DZorH)mSNQ;hNk;v%7 z#bWZ4zCC@-5D0#8q;4;un;Sd!F;zZRqZxDcGu04VACkoW>m(jW<^sY&i##8r-h1VZ zzEPb_(aY8Qen_1B$M_(0+f}k930{C#{q`#Gu1a5a%QW5Bj{2LScQ*mNU57R`+Q>?= zgNF?ajvUVy*4ax?Fkf!quT!qWd=;yysn1~fNI_RqmwRO~a?7&+cnTMQL4VvVGL1_j zzLe`A<#NE09982cYYp&iVU>j*YS*p&nGKN^HtJ7J@kWj!$I@=9iuQ`@Lk_Lk*^yFo z=LO63T@{_D^8xCN+1p*~L&%CW=*mLjA>1t{EQRK8>PY2ln!oATs>>h>;FCkGtIkf{ zv8?4S;5GmBleIZrq`2`I;np*sx?cEh5wVVl4Zc%5*6t+A7Rnt1of`oo8(aj|&iZ7( zP6sLZPsBpD?A4}3<+u#R4`zGPkBgoBJBW=D_>Tr5>X9z73WHs6v(U01jyGY0M+Opn zL%0!#Pus5Rs6}3Q$gl+6b<99Lk$48d2pj&tnk#F(LMeGMwm;kAB;k^V#*k|_40?&e-6&tX0-b2s-#+d7m}L8h zX89Dp4px!XbzM-|FBgnZ5R0|iY_pl0c)GI)$O2P8jBZWwmU$B05)P{=rMEGs$ z!=vEW{j6;t931|FLI8`AU@)1z#2u{X3$3~$&Rp|IB!sX~d3Up4)S!o+@0I{UOcN5= zOno>-3L{4j(9P&hbfd?Py6wimwck^Lw$5rF;|%eXMjlY(1khJ{?Q?Ff2Zf5ikDs2>}g zuDY(*RR3#C$q_!%ez{`R#9Db;%uCMt}a}OLZKQm>i?B*i3)2I*vWb5ad)h$ zpgCgHR9?F+V>m}JaW|F<94t9vs|&3x{=yMUcLUdvr0U!aC$JvzvwKQN#B`|O&tGFI zEkk%NSL2R*-LN_dweKhZ1&Qhx9T(9b-ef{QyY_|!+7)(BYf%bOer5jUTysd_pZ79` zr@-s_BSW_I8O=H&rf|kO(YaJX-u#>Y-~|u?fgF){El0s=OMtDi1^K)c1DfLT@*L8F zDa#+QBO1qe@^OBIlo3Qrs?Yl%PeKIALXUJAez%#9@XReE~dx_F8( z?rYz3Y?x9%~fLG07II@s~uO1*qC4s~$TP%#|2_YtLVuOa4-zh*q&$DqEaNww`q_%5WE| zdi=CS>{$wc)=X?oRJ~v-F#PgdQK@Z>Cojy=(t)SW5*bd$ zV9rdom>^BNrG8;?%msqXhe?QT{{gs?8$Dl_yeqLM4Y-+ymbIKFThDQ&1d{rAMbkP# zXJi$hogh9z@2asepdBQPf!=Y#QFq&vr0VqnqruH>MCNy=CyRvm2D;&mFttgS0hKeLnHR#uaK+BJ_fbh28zMF=VR*mzQdc&K)+>%tW3g+Iseso= zU7c}E+i=QqyGX&D zUYAD~T35SlG3au($iHA$cZtV-mv8s%4RAb%{C~DfLJV|QsUzxc*>Mpogyg_={C_+` aFn*Z5uQ}y~YeEaFevpw+6t5694*VaA?;gDX literal 0 HcmV?d00001 diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png b/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png new file mode 100644 index 0000000000000000000000000000000000000000..3684e79652895657ee20aee18bdc5fb90d74ff23 GIT binary patch literal 29350 zcmYJa1ymc&|2+&8DO%jE!QHh;Deg4Io#I{y?o!-}I}{1-PH|{)r)Ypcad!>!=K224 z|GYV8v)SD_li87v+*XZ9A^gsv*nE3x4h_h<}Pw<-}ZnC;=U!1MnJk4A!5gg6jzBxF%IoN)s z^{{jW**ZJX@^bQUaLDP3vfEST62LNp{WQ6vqxBBrsY7qsA!qbxRocYjwkBu#3+W9Elmqr21h48O9pD8}-Ebd->5II)xIl%eCrfbAjX3Pod%=;(b&M0;J-Rb+F;Vw6y1)K*| zdj8CE0|p)%f&aGcl5d{8HUSUy!GG<*e?KUdzv;T6VFgQkQOezhy!tAYgO$o_yG}?R zaPErle(AH^!~t153y#j0bXaa0ghn4CfE6)!xskv_I;c1Fi_&w+Quq3;DEKdvQaO=Q z`N+D0xhdb`69@S3$@&Wo8<_Kp((<|>1a{J`q15%puXdxOgBhH6U9-aj{;R4~zTAC6 z*ZCO&Z;7%}xk8`wbNt`x4V)TZYp!y-KB7YC!=_UW!(He+M z`Y#vuq4zb2+!=!KG3X;^?UuM{y(dRk&|;82)LY_`%32ymjqZnWjO~VE<$FT9G%oOp z8HuzOYuPK>At-2+t+7^6GR5pZssq%0oXYL;CHi*ysd4i#<-JS?K z_bu2CY8!7Lg%eiu-R`ew?APm(c?SxeQ|7#j$k$gdr8V6rjs8fllp9C@fjcl@xbEvl>T{Wb0_ z=mMn*dgl*$I>S78r-_(>EyNkJ7le6yXt22I z-o$u^kemVx6*GH+?RpRsiEX9?I{fX8OZj(78Wp6A>tt9X(?69 zVm|5wH6qAt=lAZ|#Q9)T9|KSidE z&0B24x|iP-16;m8f3wlLKY1p-;n1W~7i3bzG_8YJG)-_Ajv*hFfy9g|?OTvS{{2); z8jxhS1$uttWhBGtFm^>cN>a2*fyE%l;$8)0-Oetg?mg1Dj*@t7N|t`e z)&D&Mb01K$1K{?q1(8}ysf!bkX(#QK+p8HA@cby?iS?gXad_`ovl%lyw0>m0e<(hH z*)m0#Xa?Y|a)!qF5dBw+8K3Q!;M$bKl9UzJD{7;}z0?*l>j*mPh&9iM3fBEK3ad$n zGh#BVa13y@swf2M6{uu6d832(piYtBxP_ZA(1#X!1O}KiW2lL1_2k=?NMoT6l+2VM znaHdo-rA0V+-$zq=hWTtS;zn9)y$H4oHBP*&es1dCeWCyc#vX+;{@Z~?~IS8sxDHw zM$VjKqYhY^AqR*MM15pVflEzSc=YeLPp%Bq5z_C%V5gyr#-R~3PG`i;G)#GKJ)zhKO~$)ZLZ6_f zOIWeJTsmKQ6zE;^lNGya_%3_js4jBoYd(6U5bWg?P58H9qft(;SMzATmD@;XOMHtQ z+CHVF|eZovKDS}qht|B%>{W1m!mUXOub%FrZDBWAv3hyvYp%}H z8+HTKG;s5>DQ=0nGra9wLsX>#ev%z$>k^JUnuLSJU*gBJz!67)NB0GI$nY74moRWp zdNiV+I4PcH{Rlm~(aJgpD`xjS(qZn~nw1Ms z03TMNaGd!(W~=@M848lke=%mo6m*d!miBtz?lL)Uhec=1fC{$8BwT)0?F^FKe6p&b)Qv= z9YuKTiM4ryk$$UQ?U}Ie(114U228JQNCj0sRJxJ>a}mB8H^gr@c|r=uI%xXz`gB!b zuOqw}&i&*XOnlkpYp-4+^C=-bw#0b}L2iJH?}>We_pEwiX)nJvf77^YBg5RyDmdMQ z)A+PS8ZXB7EC(w}rnGre@-Bzd@+lko5!(9i(KAx!8aqj0{~=E82}Y_fXFW?YmLElM zlOdk?5haw8Fn2h{?EVRK690O?r625jF4g4=?H09s*`M(ttb;gFv7<8K&v?LM!)e~S z=~KLT?@8rLoM(srdwe%#b3Ipjv^c(}_6V;y9KJpWixnT|)2SMrP3|ueZjjFV(Dd)E zMT2}#XO3VuW0`?CAFw=@3aD0~S>Fd%oB~&Db4`Wk#1h0yUiS{>3Lv0*zqo)MrLKCu zjx%!o*d&$FWnR;zI_N&Flhq6j8{0f?@21bON3|4+*a7rnH7ucs_M$RwgteEgln?8vN|l=nbU}3 zg$yqj`>}EA`jyhB;NyTvT~LBV$of!1NsQ9ZPlNGLvd>E5Tz~<=Uqz8A6AjP+n4&e9 z$1k$&@qxJ2RFCSA?T&^jRYt41n8RRJ>;1!F9l4$-u(~+kRYvBw|4L%BrZT?4Lb+XL zT_s(|2_rs6R4i?4HID|zg+1lNF2&jJcsigF$5+VXyvrrULek02jq0K^OXihNkD^C; zwd2}Vipbr1B^PY+Ll+Uer~%t)dGlqzYCNUa&*ApJ@VcQNTB={)NtYt&0yuuupKxwJ zE0+@8&)8_U!BDzi{V|l2bX7&a-+bRL%ZoSca6BzgFWly^|Ecnx^#>Pjk}ke=+p0=+ zPE!Qkm`CkMo-#&Q*j8jL8QoVs)mGmS`H;Sr1FXZN8<*#P2~vmWcyO#DqwMYK7mIV# zL`@|bO8M18J4Lp&@`PSIT(Z_?I&6<-`Z{o5%_J*g_@uNlN_YKc`Ww*hw)Y;Puk+@o zpBRev7wLL5^nKgGJbBgeKOV&*T`B7DJlvsx(ek&rbe}?Krz7LW5ZQMTh(VXxtw33F z1jHoUjKIyW+QvTQ9nUt*n}I3=O8kd4vMd_W;jh(<+zf(0{QHHJ0}*?S zIG9W%IyK{&VNX^78#~@nWFt#PhgK-Hn(%w5W}?WT|J?zAMLPVWs_KENy5nyn&prz0 zeI%V2k^%YBAz=^y5CmH!dSPBd^MB1|C2H8_T*e=d|B>!Z#Bg7qatl!{^)a4fS4%7V zgaJ8nwFhb|#}+MyV(~t+1{%@Q;>X!li{cJfzYBBKuic8oqRd#^4e=BB8atlPb(xPz z>97IkI+Y9$0?qx!UH>ohnA?#A|3914+KlD zoHyQ*p@G!q9P_R+p7H>^=Q*y&P`U%o`IQ$Vo2->2k=TiSWbRX3KAPz;) zeD@!8`Om+)mj!>#&%5rtYntwPJS5Iv(AZ3g>qU!4UPo9*np~Ui&eh(4g()!?JI)7S z2NE#-n{Ab`oRBi#K2ZED^6ZxQd`D7VF&mMkqKUthBsb#o$@OZ%{c^X)eEaIl;dQ(J z?WOyo?9QL9qn+L7!o0dB*DLhkpY)82hdAJ0qSkwNt&oQ6$blYCKHx>*5cIP{Yge20 zTzj-bsfCW>C;hsQ<9?Zi^WJ)OE^V0k6DVL?o#rHR^eJFrHSoUx<-;uk# z#&O`1hIL)NBMMdDqRCOd<^Hr`cI&d7#qYPz0n@aJ_W~1cv@Z`hkhE*d8`r0c$F1?q zY#%;y*2D(f`ylL2>|+e%;Pjxri4&+TO1FaA+rJCD>e{SYhK<)37ej#8$8_q!1Zs}i zBKgy!wT>7W0AMeNj@LSVxT5ihVLnHG2vrUT8D}ydX-biFAM~x^)^3K&2+7E*c1G43OUqhy zRP0goS3s_^dC_p2%j4|>3~F#CCy+w712`Y(6@%_w1zlx9dgd_vdIrwV0VnEz^M0Xw;A zudHYaYQND=)Otr`QqUV+;}aQu^}UoL&;jW^vJ$YkD7 zbp@;FR~uSdMTfKb(Re?(jp4VH?M?Pwh7z=_^~M61!1PU5ecCK*Mmt(&mK6H>of#VW zoq~vKzrLY6(IgyHhU%1JB&p26dO9H}`{lmbO%kv@aS+Q6zIt{{A$SlcJD<@ex;Z@o zvImQRF&jm1Y2){2}b$W`xk*AipLCydwhNuI|E~zHAJJ_?I9l2QfT9-q_F4 zfZ16HduPgsFIzZjEEQQbIqvdyh83A?!IREZ%l@8;=mat~9cuK{Bzmn*Z}yl8d#m}; zGu2|mo|}gCtfP(_Vk|gBisTMF{Lh11x5D|?{qNR-eonPc43TlNIR6ug;_!5@o;X6z zqAcn*=Asbs*p#`Zv}*`i4D=(}4ml}u{pS?Fx>h6znIX(df_IJ2r=(AcbXvTjD^=%{ zDxEb<%yF8Eql+Us2Btn)Qq^Mp8OLG~JtvtSlB8At*+HRpr?E?Mdy7r<&w7Fd#(C`v ziG886awt^Z))ngI%op@c1&-yU!Dl9-;P5k&?`aGyY(H|(uOa^}s_hJO8O|QY zR5k;zC++EdgXp7Zb|Y5!niQGBp9a14oIi}3VLVw1O3S}^JE}rm3)W{On7|ls)*O?5 zw#$Ay(Al048#Jc!m5?(yXno3B4kYy=Wa_oxrzxzCYu#1_7OhR5hOs>C1>9T~(L{}} zf+d`RB4ML;$7rk^OMJU!;}U#jsWV2+cb}D(lbVo{fF5~wnmimP2`bUGcdu5zt}v8} zFce3xuG`I{>F#p3hASnj(|1}$E>BIUynQcG84I#O#N176@bQgPv^Kv-an(vK_FLz+ zO`#8+Z}=KdSJRO>Q)m;Es&2FP2U%pv zWBaoDuyN&TIEXGGt|py}`uux4RF$adVE>17mRicAc)o){LJ9AR6Mt4V`#V$+=v@m3 z{_x^C$(d#{)A%#_%Sb3?)XR9Hug{{Dz|+@tX{D%D>WT@1jRdT+RPzL)hd(dz<7?W! z?|1mUmDjC4E>yD2$DVUhBGT9G;JF%qwms{G7+44 zeu&?5{XFu&KEa%ls3iDf88zfSy%s5oLsN}`{g=nw+wGDk@ zZ?l6j#W%v*z;-I3>P!V`I(AcjDg5F(?~Eeh=!km7Wcp#QOf?#9d^)7wPXNtCdRZbS z2b!%O|9-b4)MUw?ko+!x2|-SzHfcK) zIH1ysZF@rT=2F{8bGE?Fg~MQ#bH3r0N4`|*Tz!coyK}0ofjCc+lu(C7QO{%D znRp9Vq|{n7zHMQz`#}pOG8ScI_ZtopjaA0dH zz7dI&)FK*hhDZWglYMK7q(w5^1l?IEg3p9i*HDfQqa`!4m3h9zYz_Z{F4~(sR7^B= zv=*UTgLJ#}JKPzywDO_=c>4g8g@uugzQ@}AbtC!lG;xY7zUAq_xukd>>HMP4iZncO z>tY{Rt#iSl&AhEnTB+Nr#6qYQmYUOv{hR!%5y{FWcdCfNnnIa|L;2XDsmR= zRj8G3X~{DtXU@IZcb_3WQf1XBft-mT6*QwCn9li_h7%#XFz#v5RWXUW{qSME_05~c zb!jw+n#V5-hj&aLhJIwzw^+V^&@*X7>iJzX?xs)g5k_|w<}sBIC6(x;-{TVaucZNd zxBar^tH1LtZEwmmoZB6b;``2KG%{{`CGF0|&so?N%RY{M_ozoJA6F5k_ye1`cGroL zDT3RW_Wb*Th?S1u>fv2CR6w?bDD%>;ehYm?h2^ZVTC#yCfu9FovnvU~<@fs{i0Y4_ zp}%9wt^1}mwcWGb&$O2k9|SX*)$T=u|1 zp%%`4duPtWBX`jT6E~bOmZ{P8TaxVOtXp0e%MZY~gVxT;OTrv#9xc;3zilUK=%ArN z@cwT0tzIP-{1Ux`xyd;frd?xz^+)9fpoCd`<%G%%8YU)UUtRCd#Z*}X8gNovs^jR_ z51GlkBdbIugwQj3(;{$Az4Udn8|r7IFy(PZ$UZBgxNqo$&Y~aU%lchAzuRp{E#WXo z%h%=7F?@fyl}i=H*Xc$67AkXII}l&|X~Ke;qyMP(C?ozXpw-s6kM9;_@ep;BWNU`yx#8Tp!pFBK?ZckJNOMU>r(KTwqtBSX%*(0A?&xT|0dvcT#sXVYRht>oXw{SjJ@ex+W zoj#TZclODuJvl#>R$C%{xtn5lpY}0R;ucT8Sv+3Et3Ydv0@M&of z^r7eh1q>I;4I^B(TPYt-%;KNSp*{~2Qt=L5?qA*;X@Rr1O>{DRhx2b&8r)oaLUHgj zd1bfL44UlER+?37OZ65PF$%y)(4})osQ1-=odcQ_PkP22ap>3u#6X&3`OE@VfxHPq{h+@3cFtETqWa8 zVyIacQ*6y?I(NU$voneZpdrpus{Sa|?d7xS@M(3LZe)u6Aw19>bzwu>AL8y~P~&Hf zw20FHD}H-NjUI~H*BkuE!=h9#lIZ0(@c94^6eoxwZ4LGvFIV4Xrziby0*i))oBRa# zcvdX@m;@W+l)G+s-Ca8+-?|n{2^86C{Y3p|ePfq+HAQl;pt?;vmiRrD55#c%J9lkqdZdS-H)jZMyvnyQFeDs5`;Rt%i* zC7Ts>h&K2%4?nHhT|GyP(SCJN)@xNuUptytHkrK`it)QW@(~w_(^)Dikt60LJb;?K z8wrFNoR~N=BmS9HXr1-HoBRNXiMPvoY_IVD=|BgtnrOJq_0JI^jI;YUO>leKhX^{KH>1Dl9uvXhuX?d3W z-w%hVv8wmowD?`BU3O1XyBmEIm`@n<=hYr9%w)VC-e5Ssw8!ysJy9-p<@1gl{k@VD zb8(}UHfarJAdCWw8mqaP+Y~|U;=5od4%OiaAyh;A&k_{J@yx#uRD zs16!%J|wx@p-G{i`AyfFLQB%@AL9Sh0vM~QfK3l(wZ*&j>ky6_l-r+QiMgN0qKeUf z$R!Rkil4B5ni7v261RJRrTmYYP+6onYbs%IkM&@4sEuNIh(6YuitDPoMqvE z+BIZD!x^87npBnx%}NM%FJjZ0?+Eluc}8lBH7pXZ+0oR}a>8`K@u zwBH>xbxT5mwtW7S0m9-;lV{&I1+Xi>!zN*$&aZ7NoX8K|;rseSWuN?O4W@tqw-uI3 z#!r)?nTgs~4VRAVq;mqgd}CI9&(chiq@uGmS61|X za%(Bn|EyhEd74eB20z`4Cb=p24r7zkH#{beg8ZGzdxe5^PDZ8++CQ>_ug{m=Khy6I zCyNW1wMYc-+Xs-bh9|HV9+{Y>FM>)rEMpzM!wcf5shbA5Mnkd6G8YC)ANT-ZinG=<)me z1PIO?%r!RqW(s0g79`rsUg+JKH#Hfz^S=5BB~5&rrtKQrNguFG@9PhPQ!3xQTGcX8 zT$F7m)l5dAT*PCt4?gSqA14KrSu*$)dwTvwtHJ_f)|3<9I%(kwRp+ zwR^uM1mddJXW%u{k>@O{fal(+Gkh&%rk!r1g!xc$1b_md@3|-X;zez= z^%*u2n-cKqODdlA{KX}WGfeM8jxz09Spo}^j!E@|MmRPBPUzOY-^I_@#Z)$BX!zIe z+b|czOju!olyAFbe3s>Q`vhijz!iA7U{Q88Pzx!hh~RkemW7Rt|Op)mKAC$A-O4{WPP z!LgbspBT~Rv&`#Za$!-^s}e2(VuhsEXnr54b25Up_BofZ@LzqL%;PFNfn|D!@8ahZ zttyv?(mmY|{R-^ZqZWQT2O1f|;Jj^l)DS3y3wNW4j?v{wnqYaejr&~>(oh+#61n^K z$-DTO6%fNxL3ZWBwn;wTOQp`hypA0zUST&N`7GlV*+!HXN6L__zeEJ?wEk4|P|Gl{U^8iiDkZdy@M?EaX?!ZCNZ?VBb zYM%5#F;M=rT|Qftghrc5kzKLTCI4D!H}gwjL#$MT(_&vXO}lP}NK>7{QxKvh8IkRh z%+u>tZ?Nhfxr4#$RDnj#i(BH}pu23q4cl|7GM8h-k&QHWz`dms_F|i@@hvzWcSH|T3YT)lMP?y3{l6jvJ8o?KK|Sf%xCEh z*v-Xoa50{!4I{z?Y$S+W@}H_=b}g>yuH6)HizllbHeANzw(bn^ zrATJNcBiFp>gvfn(5pB4&{X3rY<#g__3<9eDe{Xh;hG0S5<~~XU&l+?HAYgzgJnr_ z4u%Tt-v-I_V-8HS4oA_p#A@WeJVziK>J;ln+uOuW~44c2xK3eB+30$Ys_H( zS#K_?TJL0dH1(%jSSf$>X`E=`MYb89Vb$uyN_hJ)B>7bNEApSKOyeG7rfHfFf`O&G zg^V%v^<{?AL;ZoyG62=sOQi7=(cmyGb6tVq-k1&L`*V_R8trDms&sZ!}JAFvOP(`XGeukCfpEUfe(Iao>%-ovR308oBYYWJS5! zvoDZzULO>=?U&J|h#3`dql{jofSsVlknEk@T7G4_&GQ!RQWv6=lr*3}PX#6*LWq{H zKWtcS0No;dSp#n|@tJF;;3dHv z*9IIit_X_j9FXa$p;78lMWx`Y@P)9+D*hJadiSbG?P~;@^8^>L!zM9+qof|jXY)vX zKUkCyYMsyEw(3%Mw{F$YQZ%hnqUmXdl{$Ue>0}-vOEPp{H^!nuYqFu91gRsLd-DIQ zXB*Y{lE&GKu#p;fvdDr|D+A{+XZth+zij)2G`Pt));uO#Mq$y^U`jT5o@*Exwd8Ut zd_D8evTClXo^Y-VG~%xa9qMF{U~%istkeu>QJr2E;Db6d()~+!ze#GjK1-3?u|DC? zWjI%A$uZB1B=2)eC{ih} zDN&$qY-CejZrh=xXNh`3WsB)>=KIRFaYg}CE5*A90GgXc{gD*#4PF|RtNBqY7!J^X z0|^tI@KFBD8~s2fN~*M@{ErAYFy&rc&``kicohv4;HvdA+PpxPfpZ{|wOb00mp;;wWEi>sTu{$&m)t*!cSEd8BVBclP zk|5VIgrJhXZ}Hu4uO|uNSPKswTa{^UU!3_7ix-~GeVuytS8C*MEZ*zdPwj`&70-mI&|P)G5ubzZ}mU+4EAA4D%{P>qSS zfpzdOv>%HU0agkqI|@-?m7*ox_PnBd;yk;3m#h|%DM1w=ME1)wBJk-={E|1IJkhgo z7JU|3x06&(O)4Maez#Nd`{612TSLVr zSfV)0DA%k)B<3^~-~@reo|TH`{CvZ|!m=FYF0t{9rxV)1RXW!B`G?WRVnu-G>if&x zY>HujpiZf$;BLBGB7;UoCo(BAoBPy1a-#>$ti~He0Os#} zUlylRYth@#a}DHKmh8Dm1uFa*owhCv&7z_R>YXzS0@G!XEFs8NJtTO%X69UV%c5sZ|wp*TSVfM=Qf_`VzF%u0~V?Yyf0)Emm6gn z)rprKh5RF9PsF1*j?fiDF_hqZ3x?L1P=bd_hh2m@e28Y4_T7GmS$@FWbABR!3BSEj zUnMzzfdPu-_dFiX2mYx(ZIj$Ae{R5>RrvVwU|-q>l0pl)&1+iA0UIF))Voy*2sj3= z!}&MPG=_51W)((OmvCz)SBT@jo=Lt*zTnlzR)j?&?;EYegE`smJMl!PHP>`kP|vDN zjy>eD@2EG~hAOGw=M7n7JhXDObl5_?^y#%R5UL_-{tDFS>2;TN>M??&Co;c07qf*@ zR=jTL^y?MalvgWQ+pRP-6dWp7+aBrsJf~ zH`HTv#qY3_>>Pggf5N6(d4GlMZo~V!$Q4jMo@@JI%53Ut z5Y%t|ZTIZm;ES?UYL(hya;@8*1~nFiph_CM9&jZ&4-`L{ds14%sZ-S4?D*K-`+gB; zDHd9c8P^QG*s7sVfvVp^lDB4^Y@Xt3-cu@JhjJFT?H+2e+)oG6^Z0I^gEX3{tD0i!& zyWJgQocibQC`!`L0(3B!IT)`H1o*cZr+23o9|lX+WRZ=HYMSpJt~R5X+;WdTBH)PO za<)hJgBvnZ zo0Ng{r$&u#W>g=O6bTtBA^e}m0Dlt?5B3(49o%#kEQ6@^mtXg zBI9HVR?j_dQv|Q~13= z4E5bQ;sHO413d?_g4u(^u7NXl1XW2oR;BiiClXvKB!0Kua@O5J{E``Oy05W6GqBhT zPtb26H&QaaEr}ly45w=Qw)!o%yf@5+pT2QyBnW@Xb`Xl0ue@nzSDr#w$hWDu@$rof6^YiHN8`LD$Sz!*rWv zMNG3-lOJ3t2=?s=I1#6w@3yEzy-zZ0$rO=xJZ7InIWm_y=7Ge)I%Hf(W3$G{GyABZ zj>t&AtGHqRyC{`RK*IozNJOYgcyNu8teS+L#Q~Q5>e!VyG4PAMWukv1r&V`muy%eR zC$Dqf@J@ORrEis*)P`rnGD!WzTl7_arqi@kML(jmYrd?%Yn9*-=n+U6$P6RV9pj75nXkHBYKtPgjfau~gY0gR@y#I71~5M^@oV06ck{ z!0Tpvuvh7(a1s{s6=+mfyRyyv2`0*&`CIx_wlIf=`1czH0dVSvkn;bl*5}g&)Rb0*fK-6<+9~^L>|9_ zNIi4LXN*~}lKe0~;V4|Z=4m1h$=+;UY|t=HHC`S##1G|9_zF9tg~jt*{Oe3F09aBkkEd}lHmAzt{OG) zRV8Pssk6&c3eNkCvgjIxm_o{eR6n*OD-h84wLl8rlsFi0)l@d8YgQbH%o?k3NVL|U zv@QxbK%&3tcH}QC9D)f6v=bxq%5L}q{2+OA8e|rXj-@IyS41|U#&m^ z-(tA6V9Xv}Q{VTbjk!wWM{N(qW&+6pE%b|en8_=-$7=n2ZHt)A2=`A-Fjp|!O6;@W1a2SI&?C$OeJUXK-7lU4jHN}behVFb7npHY z&^V_CcwK5Wo*mV3kY{Okt`&`1X-=xZP(m^wFHdTH#F|=9=IW^uU*?_26w@o+sUhSx z7TuXZXNnZFO0d=6t;M>8wvvZYiw=4?4{zLsLlk($dxB^rjf>UuS2>!mCIJLYhriIB zdrla%K{Yuky zyjJt9M%kbPPJxFN@qLP(B2#`pX%JzI=Y>LP^PvCp4Pc0hX|}`jl=yH_eY-fhDJXC+ z7u#a8s(hs94r4X3aViJ+3#7rSzWlgNkeIFJw%z~Jqn=s_PJc2%UaXf5;c{+sc+i#G zKd+@d_p6FZmD#F-#=Yr?*FnVH9gxOQ15Cov8j~y$aXqeoKnmzZ;Mh3p{Ib2~DYUsX zW1}{9CpLG9kpmkS2dZpdiqbDO&|9Kd=(m;y4NIX#!Ocb_%x&yYIwcy;*z(yLe3jYQ z>KS}HQzqL*Gd7z%KoyqBm#v;`zyH_o$|i?1unpC~kno3-gT=u$>C`DMBmT^R%wYWd zL!n@%m*EGMNSk-{6wZI|HlH5!(4zP^Dp)Jz!a-34&t6&wDMw$oTvfNou=4o7U(sNI zmSCJeoOYAK;bo4T4BfJ(-FD@iwCB0xZC(x2AS+u({wNAKkQ1l`z_ zpnjviWS>BmO^T;oHQnGnN!ev`cPjdRqlCQ!N?{HgL>_g=18cD90Ez&^PjG>VA))e8 z{`~w0?iLaat*~OCg4T~ezAD>b=C)ed3;?m9aYTyJ)nqP@1l{<^@3%?4jMa_flUeih zvY?SsuoHlh<|U2SgPmQ!IHrCwyL8d=}v; zf6MjaG%?(q)0lm*QaQcjA^qpFs(_rTK-)3_bLaDd)s_3*5H0T<)sDan9c*oEeD?8v z>-E}HDEy!wo-rcE#puhay%yC$`DhrjztVw@wAyC@w|LgmNGmOy$JN%Z2Nir8NrTwm zGXf`(y2&Yb<5^s&^+`rb%oqtn!Z4e^O%+o(JN(61RTWB=nc;ajR}MBQo5-(~G;#Y3 zm!kkh??>I=C(^n=*az3#1*{#rLVD{8hAC>Tntf4L~y<4G?Gj zKK4}Ap;6&~+ZinvTXcVG9>Qb1#@H`E_1*i0Q8yi<(d#T(#LJrychw>~!Rn9AF@aS? zgt^;|ic}kCj!SqvWW?t2!i%%JRGfFP<@dBn1^6GMV`b$PlV3&U)!GER^5XsYcW<^2 zQ_>riCm!jVyC9b6(scZxnLPY~h-`ENX$b;G{+pjqGr1W@(5*d_bcBe=lAW#{nUy9pF$}#~D%8B_en%iYXt}ibJjtuy6AB^cc z=^g35A?GS*cPUg!3vviF8-Z zOYpB4QRGl=|6h5L&l_)!4V*^!HXUvb0uj|a)JwBhkl0c)`I@bg)s8lu3`%0SHK`NC zX5H4%Xqwh9o)wqz(Yrexam3+bfm!rlRR$w09qblQ9Xg=nbE2{@YG$yleuti5>2)7A zu_x}Qm%Cr1*+=0IyE7l+VLt8zqYR@AEY9@&d?F zYa$C~M{=+f=&$(#$2i&vs`bIDeU3YwGfBn;n#zA{?*S`2b-zR<%gS`GtG6OGwFE9Y zreHY-7i^jR$d1)1r_0m9%q5$xRvN~^;eimu88Jt{)rEMqA{C8Qq*vHicH=5fGCnH; zI~jhuH>;+>;ZVcEK~?0f2$OK(_|AtDa=k%XMKrkFuZ6zu3Us3L>swXr)Q$j}<7~yX z+W7RN#U<&I2Smoy7s>N^E8gvh(N%>;ezM58U-rW5^j$-?jj3qI8SUm&B@Z-(^xLPFpf2bx%K)a@ddFouMVm>5+?oLsjzXQ%Hk*b5`$MK*Q}-c~N%{7$ejr@nbm z+6=agVM*)!){oo8_rQ=Q3@_tumXjIKZe}V6<&+51 z>!A3H*Osp{vpCt}uuRBjeAD-zg80!x+{CRAad!uXWjy@!fbv$V}kVuYL^ zQE_rNAb5D*h5~Qb9B48ZbBGE}$7tTFbfwS_jserKfYaE(hTy+-A&z@2;B}x<7ks;4 zhvmev@U@>Q@q6-mT%@F8C47B452LnQeg8&nR?yyV;3+c?O898Mkga_OdWC|Oy|%?H zPc4LLJkxOMS08LIJ?zTsT&nGuSNOpqL#!RyvHOtq{wxrpximnG;kQAwAxz69sK+8e zdXHWw^o^cdn#Iz2vt1O~esMQ&60=jO6!g%?mbeuUIkyfiAoR*}t+7m|S4d(_TB3h@ zc{_=R&=SZsiJhakxD&J44cnNOZX8{JI1fZI9rEG`tuFN*jWe(eNI+ z^VqX1`So9n%-|BFFNlvfM~iY3EOf?tX>m0ZF%4_}o<{4{NsjjyZSfJ3Pv6SQZO;}+ zMcFQdNBBy30GXzw>bUyM3ak_E>|d|Dq;Gq#Bg4m5Tv0PFY|)|uQ|10ski@FPRIFecj1$^$dA z!uJj_j`Gqcr}~SBk22u*)!-!Q=hMm}$dmzXed^q#|DP5Bi2QJdgZJY7F2~(8=O{xi z-IILtO^oL)`4HC&q1CD|l`7=3EnD(rPjC+_xCYS!!2^xBb*7y)LgD*&47`*ZUBaa^ z$Bu@RyUY~)xVT4GHS%{rmkqR~%i2ahp?v7f-cUsGp*g3lZa zjE700*naG{Lq^%PhU=6~HMj!QN#nIrUgJ&BQu0Us9t_{We1#xmA@c42E9|YJ;&{Gj z;lbU4JA)G>xJ!WG8VK&egS)#2cXtmmf#5nYxCghuKnM~bxD0yd_x)eKr+XiJt?5-= z)pe%#IeYI@c;|1=X`!A3N-p-6Vu)CXmgBMh7bK2G)gK$IoP?>Ok3lg55f*cF9Xrtz zeKfMxgt$L`N1~JB<_ufVPJh;PibU%}|KZ>2{j<19JUsr7N0Fij_ISPimqG==Unb%m8)WCNsrS9WXY^BAmj5?b)!I2Q$g%^TsT54M$LDC;dZ&)DD(=KUd zgKH~3ocfj%p6ZuZvyCE6D#2{m^Ox9g)%VdC5a{~!`)0)lGjUwA>V7|Cu|)dG`jt{R zz&WQ>)@uURH|Y_khbcN8yU3`)PJAIeIwhqIcO3*m)D?1CrZb!a_6Qne;Bqyy^=Wff zCb-RWT>{jk9d3Jhu!nEzue6=)(?_{ey@zJ1(=xau14p|A+s3{ECVWDqP=64nXVsK) zBWC8f`s!SYN@Bs!9Jrga1r5awsLMOvQp&@;MO_u(li~tZSGV!)*H}BNIbE;ra}Pj&3h=kw;OoZ!CFJcc^2exmBrm>on8llv1ge9Gt58ZnhBH=+zDIM#~v2%vsk z!Q2w|!hOd4tRBM6A8`L`c$et>om42(QN7-KiYN)Y|BBV_C>5Y){I&)$&?jZvXXEcB zyrA(po-xL&$sEsr9T73r!}>p%Rc9M^29^{&u<^{<2fkgm?B$0N+%w6rVfCE6v7eLv z1?q3C+r*|e%pLrxXMnzvA5FqT*cN?TZ9cD?rj#`s%Y%4-*Y)##IR96W&qnf=ZSlPQ zKOOkj8q;Qa&^>*PR_w7n-Y)Szf$uHfA%kUiyA!o%rk@M5BhG2!yK_uBC%p@(5JA#E z8i+bePg)F{f8Pz2YQApn?6wX39f-{_9)8nOq4dv;B9ky=Q8DVk=jvU|@xVUSU_SqH z@4895=o+|9Hj8fqRw9`9PHDL#GE}U_=t6{VM#xZH1(G!Hk<5=Rk*vyWua`B>SHC?6RsiawD#;5UwWvSbZ!il9lkq?Lu7X)~>1z;ZAGm|yurRo1> zO-B>+t`FdD*oV~tiPpK@s|uMH%$@2zV=X60EFgBvbOGHr~RRw8pP&^W%7qGQzidr5Wpf z*_!ISHCSUq=MB^I*azQVtS1o0dnr$kYnldL;Y@jJ*icGZ$DHn*Cb#VhFmop<98PEJ zqr>$%B(-(6P)UoaZ;WLc>mf9nQmrg_R{fF5jJuKg}>rZM3}P zl5T)ZjJ|G17c0K!H(YbBicXT|kk4d9_x1Y2Oa7(7GmXLr*8?v%DF{~CLu~?%U$T%- zij03ZGh**$mjHHg;B6JqX3Nmxuzg2ot75$B5ct^Yq%yvGp1Bg_CDU&sOa3M2iOXXmCe-B=Vq2nsG3t*1|N9KwTJtt4ncv=B#(cxq<6H5re=Fn?LUE@ss$blg|F% zHpsR-b?Mckz6|Ap>$Eilr1hdNfmHiX&I^8CF_6+m+%FD()wBP}DO^8FR#qtB-A|gC z-#YrjtXFMm?;p1}+F?#{1oxEmG%*slpyIM zHYsku%_lM@y!iw?(U+%^J;w9wPoBpS;W(3`*e@)gKQ@IflD|AdH3tCKI7Fa9UY}_T zJm1tCEJ&WZs7zHjc?|t_os;ey-25K{Z^}hzCfXoi)Soh$@pSylNMjk7`kTPEr)a>T zv567zeV%6}33lA*O+-2yKLMtWbFDml$1U}LK2bzenNLwA40Pl1;@D3-#kBzC4NQxY zoOIPCk@xJqfs1T?AMEds&AfskN#O+d(**Hsk;`6L_%bR#u>iJTu;T21#aBKV5 zYkI3qJ`_cKxGgqqx>cJ8UMYjVm96wPj>a9Hlwi1Kik5El=ViU`yuL`7dZCc5!hM=#Cn&S8N z4mU9mS2BjFzG`pfJ`iYtv0N_RTdYxC!JaRy(sCUIDgWz@wC~q%dZo;po-59m3zOVF zcnnM~P>!2qLV4MVLF$JkF2Y_eNzF&FYumlN*RAFWWT@Un>a$03N8wvK9><^qDI)Rf z(kGwVgj&b$pO3~B<0Ek0t#*;<&JZ1Z?fe?_HyVsZ1W&gli%PN@$?p{p8llb(cJ%I*b&rP11 zIZ)xGsi?zz+8<*gYj9e|A;wIlNtOlMZbf3`)?`*SP6ipuIyL;T{Mq997(U=R%79Fc zZsp=5St!#MRKMLKDi>Au2|1$npmt3TF3%MU0>#M81W2jao-fHs7d2%|hZYDXK3$B? z7uhgVOG8}{&fkU}0H`u7w?zT$2=!F_cA5cZ+4JUPT4PBx(<72nI~!ypH)MkiVtC9f zs^*)g7DS?!MS^zsL63sHO${>;?h0MYhCAQ97j-&1F{Jlf_qo&>tc)mKK_3XQ1)rza z*Oyz(N?8FLS(FLVDs0-gr=}}^cHJu#cDlIE98`c4Kgn~5iH*g1h78c%|2m`UHFDgn zRk7uO(ay0$g_=1=SNqc0&U*oG)6eeE&Ur$&IG=T^f1bCKLQ-UO(enV7bE^P6LT6A< zYLDsGf&};>V%=`WULC^Xf#q2jbPEKvy0Cu0rTr(~#&nHSUJE|kXumlq(QHY*BOy1A z*uf1e?h--@yRH$_E^n7S_({&lUuYzUGJ1^qPGk=1!w}WO)9Ei~P7_@y z8e(lem(vJ>S_R5^`tJxT5arWOv*0H8^xFCOCUgG2s${9Ac36>pSM4`EQcinph7Pmv3Li@Hi5u7Ct*R;L z3ikFhS_%m4LfWnh{15`zPEkb%-U7I>#}pM!s#bqkBdQWhAMtd&Q85$8E~+aBCpK^( z25$#VyZk8o{KNW3ix%UD^2;T6BcmSS$EK>)dFjPP0K0C5RLFg4VDCRsn5gZ{ZDEAW zPs2eAyCzot9B$zEkpRH$^9DaTUb^4xW8icMjmVq*OYSY&y-_}+!24ZjYK^Z*f=_?L z5N8gqP+9Ci1kEpmvt?FK#!&rvzU1+1`goFY|ITGTud8Wrj~_T12Mh`+d^B*)~Kzp z{k_vwn$~k_6Rp17Gsp`&-LLgonnmMs{u5!H$j8Pj?3l~j0!^R)PTp&_-XqpaA!JDt zJ4xwF47klO6$SX|`$Qze!UJE=qCFN1YIo2O)wNT`aum7FjY+?j?xY7IgBc8#-=WSW z_^(FAeE|Qlh?RX(V{m!b0qA(~S5Obc3>$0IJ|AMT@J0JX-}Ms-ST?7!Gh0-90eEjx z7}$FG%c%I&ah*|t?RFJ8emos(TRo~wBv6v$Ob}zqh&FSL#~!i&(PY^@pHgT-aXs4< z5nHxON0HI$a5|O%9EkzWHbbn_9p8LFqhZySr}inpBPMRMTvM11z3Q#pF{+e0qfn`y+`H8lNpb!P2= zC$|y}T4;gC-f92c*7TFJ;6h5&68R_HiKJ1I&^V=ZOpmP%6-h|wXU+z}qs0}m7?qnF zbwauQN8^|M&bD^$3vyEbFEX~w;l>Gh88Bwt0pUmpniT4Q@H`DdJ1+WVO}YO3+Ka9Q znLGW;zh9b;=^15#N|M=CRZ4d@hqbnj`RC_zm<&u5-oG*nL^FH-khuR*Zf;5qeDSll zXcEs3lDsSm7~?d;+#LB>K4#jxKI}zaShtT*6BQ;x`_|hSZLaJm5Fv($pZmJ~ zOc`}NiHN}MR2j|fCU<8W?0K%+&sr*%DW3{G{~NQj2%sZc2>fvSXDW7U6k z5=JJ;VqUQ&h#_@B!dLI@v*2165y104W$k#eJLdVa5wF^1uC4Nq>9N$)Ir(CZ^+aXW z75saN07SEp!WWJYhTQq&KMvlnGYtPpD}=8&htcw)Wo5J0e#ymSzVp>%A#;)SWJwf6 z|Iei*G-0iot=EB zy*?e^^`!1Nml46$6>uUR9y&wwq~@Pqyt?(MA2~Og84&5$*p8{-KZuk8%i@i9`x z46|koZi~WlnUAX25!=*;5MP@T9bVJD4VUr$=fq80+RiS$cd)~rhc9s(Chs+;z;!a5 zPVSRa*v~FA(Js|Y0eup5Z22Z#QKx6cn#C;(5g6=+VHR`sHRjke1)^>hCW2-IH5t9z z?%PkdLxAbJ{QdpX750ciUK9ET^K{3-5U~UFUAN2A_Hi^CI@@XbWO1!^nb84rhRr1J zw;R1>HH^hO!u%tAT5s#~33iXFs~02^$z`|P&|na}N@vd{{vi)tEHXZN3R{qlx?>)IH~VWAdVSQ)cYmG?JV@#6D_X4Q_D=OliI@4v zjUC~(6Np+i=eMqbGgGYLyk-0sl?09HTnuv@cjvSl=k}Cc4QQmGE8;x&fy81Py$}O^ z6k7`n6t%sBl)2fmT{= z1YJ+@%9cD81U{oM6{XI#G9Q@*MBZhqbA~*bQ@ng7uC3WX=18ViLe}XZ6Z-uPGI*|j z{kvJ}o_nt+RoL&nzI?)_Tg+1#Ao|}nT8A+8sou_&MaJ`;gTe$AL$K60&e_~w`xCs0 zRT#gHqh8&m{JX;9LFd02cfv;G0q=>NW6kb&nvw*pzt*2R5G1Z&A_A$W%QT7Ns;fD` zruRe`c5}d9&&U-ds@->93!==hYs_K8u8Qd5fqa*={%`!Nc38Ofq1hT`dD~?|W&?If z5d&`AzAkqF(i`;ip#fA%%5*e4wbC@lRn?DXL2|ehjM*;5X*BPTaq(QKu$PytPi%{+ zK#krrA~lGtU+FJzht)MYT%r@a{Tnk0G?@#NCiO@w2`h(z!gyL8&eABBbDcOv8F%p* z+*JYVd)Ddj3h;z|a*T1)V5if*s$a|=?{r9uk3h(Kln^RVWN%qVJ+1C3f0WH~C@aGy z@x9aA&y9A}&q-IZ$NSP$q7*-I;$7c9p+h2AjTOOBWX7@MJ8Xbo2}nxgbEI$4jiE%Jc(oU6BKvvBjEa2mffXNf^Gz zczQEmjpzD!3eG?v*bF}!AH)%z8Ep_I^=K;HK(D{U9`)-W)*-z=hrm1Doq8Qx(WE}# zrmy$nul29AzdJuH2k%dV-A2bbFuk|@vEW8;*HbN4L&i7KueHGm!(Tn6fhO5P&B{lq z`GF^r!-f-s(Jqy8--#9Maz6b&|B+lWVFB4j#Ty-f=I~g_%5LO;x5g52ui%h+e0hYO zUO^+8J8zXXqfyD{9;>BVd(|-I`f~JaJMfUK)YNM8b+k$x@2TW$(w+Hig^DtuowD-=+S+sJ8{p)zX)CB{sg!LsdKpbWjf7e%5XEk}kp?{Rg z2L#RtBVDu$0%j$UNL5FtHx-2>*A3&Wg|UlnHbOBF@9=t%Q!V$+PxQ@S?T`ZsvpHJQ zI4heu%MW^VBsYC%U5AOmLvd>D2NZA2yok^L*15m&*;9o6PX6Q1bWS{MHU7q2{8pA& zw?bgqcQd!qIJGb^8UY?S8A>eq#}$8MU5GK8NZ2PUfLEIzO8GDo^M6LTSdx*JM-zPF z$s$M$V7BVR&*cK1?sv{nLbn3aN2z4Dg1-&qh><%TU%K|8pYNKHsWLh`xpx+vj=9m~ z3#JB~NdIfb^7|>rn|rX_Fx**zDR(UrfpaeW6{9i@J*!rQIk#U)VeHHsdnADzlF6=@ z)kW^al2#rYSE&|qR~Sgm4X6QWxR`whf=s@CPd=Fqo{(KIVTp?fGKTXu8ASr2wnf%S6JrP7uv5|}k3XV0e zX+js{?8Gt@$NftY+_5hh+a+3W#NrT4QzPe^LnHsJ{qm$D{g%kd95Uqb{c#>v`?y3U zP6n4mgKMj^Zi1L2eWUhrNcwX$K$`WH3t#SY*8^4TGxIlQDG;pomMx-fik)BpByB>2 z+nYpJG5)ftCyCs+_1!sNW~+ZiQ$Z9v>T(FPvY{K$&s5!WoQf}1QM=oJKbTxFc-^!C z!&rOe;$#0a4>Vp6Doj z?QxstK_MT57=%54(_`PSnBd2KxP_q}uh;wxL!9UD5A5{h_Jtxqt40dl?A-HpDva0u zT`6EZwWZZpV=QEVcD^Tso3yDePxc;j<(`~u1r!c)8U+~}DF6YC-s>pIfgaqq{M(Sj z)evBsvyLoRjr2*9OX%H7Wgfw{7y7bE8+!Ls0KtQVH%rS0Dgd204b>yK)|Gk>$p+9N z#yE=Lnq}6qYj{@01odsj0A?pKeoYpindD3oTT2MNu2 z`W8DFHCnz^M#QMs2S&Wm_yX=PRmfR*vk2hJo*EkJ%qCz8!facoxgw}EA7SuhI=6I*5-}Qb-TETH%ur>`+sFicL6!Or|Z$K`477|cXpIcr|V~|gQ z#H154kCE%wHH3whe_pjM|3>Y1tzE?o+`HprF4NZeUc!^d|7xuJ2z6 z*M%BvM5TakZrtU&jD*~;56d#+KczUVq-C2h7a{`YPnmr-KlVx4#}3GM%-tDD zYLljq*?T_QsnrE(97*(Pg-N3fAuC%X-FK-=Zgz$b_XhjeZ}5}+VvMhdq!+~|*bL?L z+DgK&@a^8jE^M|TTZJW%S$)h?Xw4%D={7(p-=|-nLZeMtF;)53?edUy0UP^RzIR~a z!$iu(*k459O0qp(zofa(3P+!L3rT$OA^NqUSd5Dv7I|9B2`e}wy~H!PRjq7kr~h)6 zn@$WR#$ENRRN)QPWK}_SPa^RgKE>83;@g&3p_s2@Tl_ zVEt_%Pv&OV1JVoKaLnwgcjB=#Easz{?r_4WJ99dU5_PQe7j z4vt`@ZVzWyn3t}aM#o6a7+-^;2HsU6lZo-YzpCW8``}U7YBBb6xv_iVr@Z82%4QFL z@@rMf#yUK2PHX=qpF~^SxA=P`H3Wv`H?MT5yJ>-Tnde~jNm!|`B|WcxI_k|mOv~&Y zyTH=QBqi&Q_Z?o^e|UcpNiRI!8eMi#FTC8=GG&u$a-A>`Iy@CPzP35-(Z0}S)|ASQ zD^?^X&h95>7?^KSH2LWig;`t$U6pw$Eb$;Ws%)xFP(9|Qbo~2;UIO%tgw%+W@EFMp3 zDZZG6THu%*OH;OU4S<76`=E~+W z;A>qeG;f&{Vd=2r>o}_@`Plj46_`;J)jZoTrhM6 zK^(Cp*=d6Va17`{g2o0W>3N2knVk_KK0k_~DDQvg$;auB?Fnj6^~_$JH&i#`5A2qZ zB1&s}zzP?)uBmr3(o=Xjm))5yANDq&ey^5Dw77iJ)?%DIy7tfbAft2IIjz}i-)*|E zKz5FbtB$8s1lbj-hYBr%1>1dDs}(r}0xk_axGu2_LWG{8qP;16g?xx}enP;`~#3 z&{lcwqsxZip?>qxChHz5ZL0Q4@OsQ?~nX9@scoKRBmKfp55oRO&MPn4IrQZ)gk zZtz*?&j7qv=?8GXlyA5;SsQA8E*+25P>m6Z`Px^^KG&d8Q5UpR^Rm^RMQEWj8m{){4BQXk`pSZGg|z??$XUi`|&j%ZRzTn@Hjs&y2sQxa14sILYdIngS$f< zF_N1iBZ^ra-A_fBr95Eeh8=tLm+yTsyBTm`ukG+L~D8U2tPEq)yh{8!$ z4fvmR=aCNc_Sz}|HtAEjziJLs+xTn%D<%iVE8Rk_m*bZ~XbD^81kxvTQkzxRE2O3% z&ri;3VoptP05TQHc6EO!I+UrWd^gX#yB%X1A)EEelR3$XODYL_ydrbgx^+-tK%@!e z{$M;J$XK#N*AqL*L#Y5YJ6h}oup&?KpqVc?KUy^09UR{5zDanwcSFa=IE3Tq3q@<{ zr!91@hcC>iBg+ifQf(!qGhh=}Anto8h8w@+?-^k%ENFO~FfyGnzG|qR5mduOgCN7h)#-gJPQ zKj(0#jD6IJ@w{b*Fsq$hWhoquH;N{(&~)3WhTi*olrTT=aE9Cik@^zI3o1;aN!t%SEpNfg^?tS930t%k=a2V_Q@Cn0UvQ=4o5&D z+hPhPSr8)mpX|n6%=7J68hb3L8=zmQuh^kiBiIyujofMjgbP*%u%qEnEC!pHdtlT4 zTh#sH5WgLL3M8w@ojhqN9Bqz1t*YWF?JjIAwjR0Ds8+N2*x^Sav+1UA`6t`sga}=D z)1du@Z4CZDB*K3`B@z~G)ph(MrLEUR8fA1qQRDNvvZ)|Ae|`etQdQWY6ZK;;1#n6h ze9`^!P+XJGHV$U-KoP!W)}{5^Axin=aB@ES{Y1BjlT^ zq5fqwYNqC&1yT>&Y>g;^a^VKaCs+SFd|RezO>I;%$GN>W-w^@E_qRt7p?}=In{M_j z-}z?fwtdU(+LdCEqm+|5B7No2FXXfSkZt&IA>pIBzIuDB(shRJk)>Ha+@1CJcDEM_ zZ6kkiu&zvAH-z>*!s*V_fwLIb?geQLr`k(P6#pa9$Q3N7E#ulX+xXzqzaQuid*3Eh zvuq`x)IbzsG#~+6sjJN>!h878T-&_0vqkMN=U-NS+{tLf=}%;S^NO(;gj5ugDM?wk zbkS0@L?amyLeiv>Sj;{2U%&W}0p@ze&PS0Ths;*vD#;|H8hDh*E55Xz)Q2%@+@(wk zxD+GQTWCR`{HR)?hx7P^{?kGW1AF=(Vur(O5B?zKskXt@rJM&L?NHZisc0Y+| z;8D2!TE22+dWj?zkJ(wJB^j`uaPr>Cz8KUlef9tD+cfNnO^+lg0&?utyU8)a}>8~OkoCkwOw zN3!C{#%^0@LU%XHDnR4QZqGOs<=kFD|BIpj<4H^U=F?Si`rWpMd^t+LwkQYde8uSp zfD7VbaZ|91FpHB=34{8&w|p~fmXsba?BBsj3v=f^UX{>_RLqz3EM%`n*2Xmkh=c@> z^yU7Gzx`r!8~cYN%pH#Q6zWQeK^> z$_JQ1&gE0|K$l zz1(wMHoVCzd}hP|%zr$@na;21VqOF5nj*7I2%Q>2LTrb)T7G<>GV`nKVGQ`kW(Mjr z?7~TN{M$!{zISU@eXZ4bJ%9a2au5ILrOS`c?|0(77ePw+@r)Rj_Hwft|B4c$0+0>I z)T#qx;~>@%@%6`m&eLe$QBGRMof;Rgm{X8pqifxe`OO}oMhY4&$AOGZKt#`tRRnE_ z@in_1|5y5RtX|fzVzkb{X`^@(J8RsdNt6Ia2l*GO1;$xPBhx%2+!PS0DJzQ4GN6)* z;x-z`-o-pQrsvMo{kMFr{@M2kQ8NG_uo8mat1w$u9Mv9au*d)(SRt${}8#~{GB)ccKZS2sZkZn;b;sd@03DbSUpF?$yd0DK7Z<{7)`7aP$In;_meiAlNb^S3V(8wX_ftLd$!dX6|ldl zs0C?Hn*RIOlZM6Q;CDZIvjQHh6@tg|>X9ye^|z77tP(j`Z53~52gx0K(l8)y5{ z=lHLTlt=gyF9E;h%zASam6&c7pr$U}?0E^4#zf=cNku7Cl^%v6UF63s;#T(Ls5a!h zs`<3=j#0ym>wuE^pSiG#DXLRde!}s?-#RTIE&rJJOKYpUwUd+RQXKvfM|HWvWKv1n z^3fZtF{cU-BFEg|wAW#w?XkmO0dK96DkBdmFQ{QKTSBa+@k(kG`N(^+_;5vIKN+DyK`A|MRb7=s z9+!;HX@8c+nJ=c7vDd3??vH?Sqgk(^Ddd+o!wP8D4VuMV@*{DA_f?NQW2G%w;-lGC z?W7pDGSo*de4uKOhIJFio=jDV<=EnAg0MXo&%3DeYz4#;a!Hs=Vg3?$$vd63$hGE{ zLN z8Y6aB!oFc^Yc9`}AbolHZ%p3jN(6hCcZ@eTmo{hc0dHg4GOvK_dTA2=itIA?c`YR> zzCBNNsyMQF2??#JR)t^a+cJk5(M8|1@{sMZdsNmQ+=pGRHySV~h$5km?b)5mcftjLqgq?S8(@-ut_O!*z|Ur8Ess z=_JVtcq={BhuSb9=8K%uLPnYc$uC5oIdW4#(sj^>N9^0PcUWJ0AD!(ta$EVvtTE~H zD}LJXK5&-a7K6Zg0#0ItnVGziv?;CPXT9y;N848pP(s!6F$12G-rI2Q49Dj$lg#in z3=PGB3w;o63lKO~kyQnSz)`}++z1~o;N<3YZ(oAer~ANIPJ`(Fm$wNT<(WC&8=tXb z1!Q6{ay~x&KHoJfc&mx&I)2%J?f&ec3WU=J-&nVp9jxlc@ zIGHuHJ@HT0+wI$uZ-ZW+JEeTQ>(%*+rnY!pOHPFGgaN|G^|~yH`A1j~_Odw(89Ry= zNQglZ#$j3kKV5-plFeXbG|nm#pSaL(&^x$P&9u_l1nWMKm(zDY#8!nr77iKa#p7Lt z8(6KIzvu+Cw&=hUZUffn+g=OVf3t$U*g;qnmQj%YDZbRTGmVJ* zoR`QKR&5JBfJD+Y#M2Ky1{H_-7L2+%c0~4KGUHB0O{wxYo29mVmd(8Ec+zh6F)tfV z)cBAHI;A0^q<~IKcZ{OU@*X$WE*=*==yHcXH_O`LNYc8#z%GNtxfBRe)j2lTzs|;- zk-me7tzv!Pt#qefe>mRwXs7h|}AQO2?pGVqS&{9c{{7A_z4(4HPvX1pLVNV5_v4-OQ#V!eEkhwFo!w9b9x zp$+%(xvVBeL~I$++qrf#g{rAisp#j6+DEgdpqB0SKV6L`$4{y@ucjiv$ntqo1oM5> zwWhbq(evlTf8@CCx|Y-Is|BWKTtLq3q{aY1QrcJj{ys*vj};#g%|4p$xq}=y(^qpm9Aal2ZMl}Pp8v>7^p#f{BQQ#)l$9_8toMJp z6wNTI!rx^F(2~Gx9}(`m#`+B~7yY~?CjJ;N`L#`%r#%}zXvMs_uY8Z*#7q0SG?OGc z+o;f4P$xP&SgIW{w^1AC|f30$np3A6Zpaz>H7}WWy!Xo zkDezo>m4FFsRc#yMFLv^W;gUOf${)h0`L}q88L??axQ+m$NLX+T6y}UHfKn$N6J&N zGZHrj7#+aE^g7!(0UUq*UI(k*MuMHJ<*W^@FfO1JcjVP&Bm{ zc^LvU&f8g? z=ji&?q%Y-(5%y4tze}L#v3%8e_jfT67`Ym?XDbtH0thtti`t6D*#CX2edTJ+THs0d zk}Q-k3f~ks^bZh?p#O1KkT_uv^4X1JZ_i6_rymfF0rV!7@ug$gre$}_$4tU6i@`6; zzM*+9(6#)UlQ;?}$O;Uh2z_O@Fj`OiEM9D)3z?0=-_-}SBOc;Gm4HKE(iBpR*&}`N z!TEq)zzkC^tF;l*DR z6>s;a2X?iny`_?g4FQ}Z9kN8OqC?#QD~P_D=sY;QK@W@bt>3x%J&Im#gC%vop!_d* vloa5>HGvFgYcQkAR5cOJ{@<68uV~)tXZ@@G9Z2vqB>_ru>K__q%)|c=>Pr84 literal 0 HcmV?d00001 diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png b/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png new file mode 100644 index 0000000000000000000000000000000000000000..a24bd005d95a7f1743275b5ca79839e43f0afa14 GIT binary patch literal 52368 zcmZU)1yoy4)IA!c5Ikss;$FO1aS5TgySo*4cZUMSi(7GbcPLQYy|}wOy!^iZ``%k` zy{vUtZYGnPJ9EzLea@b9BNXJs(U1v|0RRA+qy$6>0D$p^9;iSBXv^RL8Vd9c-U%$J z0))Q2fhOV5&q($Xnoa-!3f6xI%=DV?3$&5PSxm!O+0M+_&Ct;lU}NZPZ*AvnZD~a2 zYU=1@X=h8u#{7kum66QC+1Z|#h2{V4z-;Ge&Qf5ro&*4p0VE+JD()F4x^C_`s`tL< zqsi7}iIcFo5x~G4?{EoWvTy_um6H#@>5NXUlqn6wOa>|s!v4fW68B3@S-_`ifIgAY z)A{B|u*5f-j-SWYxt))m(P&CZ1bbwgXRT#sI-0xQb?kTUuR6hF_5{Eoq7xClOnz^L zK_}w2-`MExCijLmadSg9K%M{dC51h3{l9MLnB2kV-O#fzAW^T|Mt4AvC_MTmpZ!L6 z4>@eu1u=KHFmOs4s7Mv8K^5$-3f!zb^U>3<=09p!|dVw=u54fS^|t z=ub|*0?E~YKXkTkh~KMOr$z< zYG1t%y&n-Uko+48xi1bl5lH@q2j(Xawoq6SggE11;?g+12rRkUL0e!AsQh09R;$qb zi2&!PVO%FMn!VugLB@4`reF>FV7iasc2J!iEqOmJI6M;^J_inGH}0&m*B{~f2qgE# z0^^{N&jZPyzRfq`g1za27fBv{NI!y`X#CmuoYi9d5%1a0vJVHF zBF z<{<{0(gj{Z=bDtfKOG#t5CU@39yeZdg|>Vn@5jKjx^p3iM4GN3VWM0^yZqIVZo)!E zxX>KEt%&@g!$y(a1{q)C0oPW+{E~qPosYei!I}q2y4L83K%BxYnEflhtdJn(eDDv8 zpp$`Q12kYawy5rsexYtKQ#=KR%TPQegungpcEk7o8eaS({0)JXv|DlbL>giW=!9Xl zs5%P_A`B9JKsTEDB#i9OGoJ*h|I{4@kZUaO1a+4H2tkSxl|O#K{zJHcUF7w_6;`G4 zA@Nu4hB$L9@}_9O<*>Nde<83wbjX4w zaKR>le1ngYXD9$67;ZC`sy-349_Yl^SfCn2C3Q0`f*$pZcrh!a$x?4%HzK`Bsq%OL zouymtGZ6{Of!4)2VqdTWKg&s zMcy|^BC)1ktNC@``*Y2GRR1?}44XP#p;)Dkj*%z{(fhpLfG+2~@tM z-deT$U-(ZE}Vp6MwZiYH5q6?PVpooJms)!JhTD!Vl}K==V7#Stli z3o7g+x@v6VPUlKbX3*`|`12W3{zXD*5aF5ViB?01 z?ds_ziz_r7L7URfD7h!%4ikKX@Ds_)Ip$>?*FoVJ;0#?yM7l`iF)`k9xZqVFiDAdj z(az-Kwr{{G72p)8+Z}K&&Um*Dql3xw4X)a6GpzJ3I^*ky?izsL^33yoju{j>gSbIc zJ^-44hErWYC%iNpTtqQ{#4FqeW^ciU;X9C3Q>Dc&(6|Erf~*;P2{`{Rg{tK_$^eP- z$QlQH10P0OiKtzI2%8TWCC~H2@^)j;0H*>v+b1728Rp9FOA1J{|^g-0-zA||Gnh@pAJ>{ zHpP`r-iSUYapks7?EgoN=vet$NJ2`VuDdpR2{K`H=z6J=x4bN8|P!@5}B=N0x0g$0M2JIKL*npz()c`&ajnHtR8uQ`REvNaNY_c~b z#~xor3%T`N(E4PSl=_3%_rW}hjV!N+Iq09x1s-L&Cn0$;&D;WFs`i|Ci$zYjec-ix zxKIE;@5UKNeGr>jm2eg3si*+5>P+B6Nw_Z@9RMb6*jPqVU=snrga2WB3DzVlAtcc* z%D)#(#`kIHZ)wEHf2IIOPt@arf55S#1GJiKb^9tDs;h=xvPN2wS!=S@-AEuvfP}7; z7R?WUDxkrrVaQ@Fu6-)Z0gw_OxRDx#a=A3nJ%|s)fMwMs@pjdQ(aK5>p(%?}aI+*= zk{fpAg+WBW1I;lVz94yB9wo=QD1xSxA+tf@o*b4+ru5-KSh=7Pve{xxR-^tdt$&m9 z#6%4{AN&*95&B#$*J#;sRfjL7+c-651&tl&??neTG;3AG1FS-!ygF#!YtW)}c zjlA!I`(5Z=jikYp?;1crj%J;~xF;HXx3h-=M*-kgez?~#4CYpy<|lXL_tcZitC1I8 zI}%p+>L+Vmw>i~I8)iCxI>z9k@o#c!cna{7!Wg4hfZmG@r?}{o>Ld7Y*oVDbFpeNR zjsY1MNcP*~Vv*p3{p}dIEn4iLz6NCT&9pCFceta}=6)g|=sTnVOAs?87^DuT0T4#K zAi}ID9(Q^>R!|9!!K_VT3lC+5_cx&Pf5b-lVq=8onG5`Y89@oXX!qw27PG+S9ozz+ zD!*L7ErRLh{>R8kV>fagTGIv88coU0JeL}qp}(-TwbjOm7vnM;V_)m4*%kb;N5L<% z9G_0*hQU)-!mJxG@51T=p>q5YU1XD`F720t7Iw>LS<6~ew@r{S=09~{?)(&+TDM7~m zBs-Js`&C8*N)W&e)^IGy%FKKlAs_Vl9zG}45Qy15P=Qk8^XVB$2kP<21_M99fbLX< z&Y-WA^!*&gBlG$nrnkOqhZhz$czL2TRM+1>mVp;va*(A$Z{4S!i(?BGJ3 z{3sLekg@#!e2_F?sV<;y0^v{e%K80tK#-IOq`{2mZqfKqp-(^Ix`fCU84dzaltYg* z1UP}I1WDs6ugeS-?BhfXt73c88<=_<^qle;;sJv4}^GV+YTb+K2#OfI+w2X+8=PFNb=i8a%*L(9!W&2^BzR?wC z)~?wsgOEgKe@nh_LK@c_qYobUBSKNh9ortKwVP;KHxcq!I?32%|4|ds@V+`zq(oUv zQRHdc?TV(;C`uwtP3A&63?NmKz`Qnj&Y>SI>Q`^6t#XAE;?y4yY~Ckx>?2$K^yR-E z92Q0VJE=TV2j#E|uP83KV%WJoAF8R(-QT`XUzI>E_8pst;PX&+cZrJ!M|(uj0n(q5 zVk#Wso0!9hHa{UG9YP0|Up*q0n61Bi7r`4iz4Ge3B8dQFLYa{>D6a0zo_7omj5w`Y zLa6BaD{t6if;;a_&pj-Eet)S7HF-GYA-$qKop}q{_%7rS^ZgnUje69|CLUSo_>v_wF}gcpYU+Kur_zAF zF%BR*+UGjh4)A45p*phV3jzB&ySwxP}HPA zfqAOo*+b?hAmqb8kYoRA>)g<{^XbHK=}aC-=)*rrdb&z<8zGkF||F$&wP6%~BLX=KBat&V1|7Z<;^BtwyDnO**f_2l2 z-@)&0t1fH>xPLFlqjF|s)uv*6#e2$;R}f3UA$dJB`AuqBLSh;dJ_u50j(vMRvGU{% zNzwgw(}&^Z4io1DFKB$M_5HAHDzq0=ugDRBRbC(3)zvNkCkSD#Y>+bkJo^W!Y9bE4 z3PrOMuxPPjCnv1RYwZ(1IL`5Jq&cb-p$@t2YJ~J)z)G_Ro_Em_@+H$z zhor}4%5s>ayCDy6^&p<+M+y3bGk0a=DMeJ4oy!R%S*-EqB{4)SH|=Bo^-54_lSw$} zMTw|2m}D{Ds@Mr^Yk_;b9E4vmb{I`=JGuI)>eUo)4dNBZIxOPjza;MC-&s8K15$jC zllHI_Ms~w10KXzk3pp%XLgZuE4)&*fpNhpvm`W2wjpOXP)YCeAjN|07L$WK+dd3|P z(c_^p-#ctMK54`xrdIFfODvO0gtrhtS-a|HYcu!bk%p5mz*tmoBR}Afg#X*E2w-3NfKfG@gRuoj1s-EaD zkfw|wM{v37C#*=Smm&h3D^`yWtAd{1%_4QJD$F*CP@*`O2_o_RbQ}xcSYtCT^HZRl2GZd0d=*yYtPjh}R|D(J8|9 zY&FV!tVaYR?81ugh5qk=4B5Un7q?*6+b}IQc5X|54j+GHyWoRAeIg$nR#@keN04v( z5J{*<(ZW9@C;?!Nz9dlA|Uq0)a zXu*Y}xiymU97i6uT=5GD5BJRm$k!&!P(k5d2^csEkI5TLnjjC;{23T66&$P9rQ&e& zO))OBo8I|Jbs7m``Xho~PzacLCKc`Gn5DCj!%#&1T(r`{k5Y|MbNIWqi- zED}Nli3em@1Z+QR=I$@cxeUR9rHu_NKa z+)}YJ2BY-)v_xI9phvmkH?y(X_P{WbNYbg77k0aQXc+IYz?{cEUY+pT8*;h- znVE+03)n`ziCM8P^e77kk}r;pMlwnaX2Dm1B@LmR=LzWhM%yiqAviS1__;<}rKH4L z=TQ?FGqyg*f2Il zZW8V9h%wUNqaSB0>cpaN))iWq75Wo4+)(za=SZ$H;p2!dD8%+5G9tv{P3ooC?UvS_ z7@=lEU3Lr-s6Dt>c0A0M^lhaaB&$+y$TydFO@tcp|MuI|4M}y8l$3F+0lXCgSu{_n zi2}z>Q=6{HVeV`{TiUcvpR%fs#(H?^#Qa)(!L)!?A=y(AdBzX_&Rg#cm6e|=!`cwH9VE_PE^8)JxD zP8rnf`KsDt4l0_OjgwCu+al)MttZz5&+(j#Sqby_Z28RuCyTq! zkBTK?S}!BXH5`ep>5FdU;@a1M0V&UsYog4}yC=ibGgdJ>N|N04?kNl*fKgAIWn>eICY;!pn&#H_c z2Fwy(_H(^k@3_5aWO(?RO{F`unX<9-+1r;^)7y(Uy67U~+J|hrMS2aV8WRQCJjin%nFyXV82S+3Vcw(1&FZpdr9Chq*cS zm;h(?-_6KSl~4eE&>&viY%O&xYba_&EVyUU%%v;<4$)>~Xa-uuNfK5)3OPxwkAo0ixcjF;;F^ zDq!^A&AhQU?-gG5RFz>9TBMQ>q(GU>((%-+akU-8Fw6!kacDxAF!pd6ai7T@U`N{;JlP}M9yN(W{e)ne?wnmpmdiq_R%X>XesK_3a?17Z69T`YO zHhy|pr&%_m1ah(bz4<^MD=jI5l9JUaMiF^0WUDdBnHRe-(T4_nQ@2H?rdYX~8Pb+# z=6w@0HNO>6a+-Lvu|&@0N@DEcJTW4Qqs!t09EQ&Ktd>%{b^NGBsouv&9eA2-zMh;g zq$+qp&r{x@!a4Q(&s5HyXFws@66Kbv9LU4L-*+nr^l1ZDlRPzN*PS#YeTfk$MZy=E6zy33!4! zQrR-VXfub$a((%f{&i`eRGeFNo1nJ&>dl=B!U@gsUlC+mtqwRiZPIK!TF<5p(iB&^ zA|$o$O*qQn7<-q4#&1zIH;&Z%IDO*SpY~@~@mf?OcPN~~!v!DvZ98Cyu=Up5&jke4 zrI430N*DAeVnnJ^L>Y~1Y(BZ6GHJ0QsfO79IvD3$TF#pKD{rOGSuBo`*U8-IDY@|Z zWS3(^%@L#M;b7q-+LPt)4$v^R&C5Lr!v3N8dePeA}S^}a@76<6J)2- z*H}&r9$bt$24U7AN4auiW<}rB*NAmrGAPH5W3K67SD{9!$|3-c7@M$ z{Q(_g{V!>@x3@?~$cV9wY~7AjEr_SVP98!;iBUYMmKv$aOiCs$#&RggTk)mIO3+co zm-P7B2;XFHM?u23$P&WCQ@d>_SUl!>><*n$zJ#r@uVu|{Jf-;jzq%3>d4=9A*3Hj! z^!$dYam~9EHR{8Q9gLHti<*B~bOQwUt*RVg8+lz+#J_spWQkMTtdH9?{`;zlr}%9{ z#~x;?(2XKfOfSo4yS<%G69G13q|m`wY?TuI>%sMeBxZ34nX#m!3Stz_?rqIEg^_?= zvz!b5-GwTXl8^MZ2hp~pO@3OAHnkOssKOU-XZbd7W-8?*9g9;kriKqtxx*(p4g2eI zZepT9+ar1@8gy9S@O8pe_l6W5W4^&O56MtK9dHJ>ZA~V4`tO~4Y15&psf_jMiZaJv zc!M?H1?FUraqhm(iBeS}#PxhcT9z`@$4Bqc7-A1RYs=45!?aHOSN+&Jc4}Eoa>Pl} zw3@+SNCM50xLA!Qdn|9Hs4n)VMp)|q)&g+J@y16u9mu4AQ>n^YZZe;MCt#!wfSQJT zO9idyVQ6%sNFH&CxW*yI)5>)Qhm`5Os1XgkjWc4eOjoF-br9jLEwvBgKwdjt=M(r> z8=IPCOL_?4e;yU7@P`5?rmt6Ugz7kwa1q*q8q+>JtTp_6*`W8&I1xpG4&EIY3BiNSZDlfvaFetMdyq~{65EdA>db#E4 z`>oYAPNW)7e8p*-t&+ca*j814T&@YS*n%W&Vs9{}t0srul%f7M1R{$Vlg8jp%`nuq zGt@K-U7*%!uJFyQOeX)3t6yG84Fvr~mY;V}`tY~*G+x=ce*6EdpYW?eo?QnZVUnfP zc-#~(yHnYl@p!s9ErX>gI*~?)jnF21(xeRYgur03`!@vj%6L}UERQlv{(xc%>!sd! zv~Ki$h42~D3}4==k#U;zDuWkyFN%iJ>hHKkoDz^Lr8L5?<5*gnFkH4fJQzxUumZ2& z%e9hBL@CCNtn^-r$Fn5lt9H1jY@D37iAL@Mj{~D44Ey3~UhID*%=o-~nfgJHac_QM zkmtlkIoEBn;v*P#VnqO@TbpW?X5{b8o)s1GPEgJrY4ARpDLU%=L68q*Rnw|uez}0l z7Ui`nP;7N!z=rEK%)`3>H*!qkp0j2A_CP5=f8`mW=N-53A&8z={7-3{&Pk5%`|Hk1 zo7KmumVFu;&(GT?rmDISlT)oMPDWEQ@?Sy=<&vFDiaRR>$;C+-zkhs0>?6DKJjH7= z)l6ARp#2{4FxA&+qf=$DCzGdbyXoa}Gj$giMKtDe{Eef^hFMx%La@5KCm;msDrm`u z9VN#%rlM^b?1~SPGxQUddV1rj1lsimBmdI8I(R9aE1LtYAB_n)jU@R%8}LS&nt#dL z?8&t!_A}LM5?s%8Y`w1cAo|`t$6)gDcZvwrczIXXElHgS5V})^j#cZ12DA12kBG|J zJaPs#)|!!5&gg@@DEgGb(%^OZLWQ}yysDNKFF%<+vg<1y?Kr&1A#OhA(T3qLJJ);V z^M8yrn&)AaP6C0-^1GO`*zy;})~`=P=l?00n!L%smeJ6^BmQRtR#aq*(%w1c=qu|f zUN*4Fe0d}WIf{GRS~(x7$M2`@vqeRLv40Iw!AF#8|8v^}&;3~(*xlL<{X`#Y@^mHbC4#NH ze~@Rwmm!5YwITXt7k%tCr^c?CA)8hwfVlPRZ-+SNW8hV&=i_XbkhBH{zwpgj8>8fa z87O+7)`^Kc6MUkLxSO;5U(ytmJ53&@TRHSYHX62944ZHlyLrzdmHO^tf*QE37?o`NCh_a zejc26VasNZFSthG30B=4GUWae9tPa)5i3Sl`U*g*gOA2Dz}yiQ4e z$(0Bvfx*Ee96Rduo0QAshNX>D)z%5R=GSJCg&05gxnFN~q;7FP)(MIJWmbFqhUJsaMUre1r_<$M*n|il&aY;Q#MR=9$3!ZEq3am+jl<7biht1PI$HofTFTBGMTjZ-eG;4Y z&$-`}7(INQB(`g!RA+G|keJ{LrDUFsHqD~C{;tb};7IV9qeI2KhWJ6<1RG3~T@_VQ zJXW4nWzDB%aiX5N^3vX|0eV0A6AI!*^UMK9aYiYr=KSi=yNjlEUZTVCA9ve8+DnMS;JAZ(EWrJ>s#%mRwN|;dC@H zLaf5|do3`!GOqB{l)oFITyppnb-J>oXibdCY0=$cUCL|MK+Y6xf=nF*KgL4^P1E=bAvFOJR7)H90LK8QE0Ww>|k>so)+JgA$;iSFokk{DBMT~c!PkG+l} zd_f(|k&>d)`}iSJ@1Mo;q+ALWk4}xYyOJ6JY&F)Q+KGBg84aaKhZYIdvQj`n0c1h1 zjF*IAY9xc#(sDIw^^Q*^X`+a?#+LZK5SkpswCV|D z-EerYO$8%ml!CF^ZmfpJZTf-e1?BOKo<@e1G2Jr5_Yo@cs z<`xX@PNxzOQLGkYx-H|1aq|=l*aN$`dRXa-%Y-sH3&4|ogonXMFIGD{)oOyybmv++ zqiUJ;X;4C3Q;lDGi<$f)+qg>IqUT*hF=iaIdB300SM~K@@txPX0L_8f7`JY%PVsS;9sVbsxCF8WuuRunTWlt+o!9&d9*tnImph(X5`h0t@Mb2VUJq2U73`L zCh5x!+dFO^9{fDAYE0OHd`dhNCCXv1Tu%FEhT_!QuOGxuygz$>^AQ(0;K1~qcDXYx zpI;spBH#w;qkr`A zqL!~n;gn@(<3?EBH$Huf{z_LGBHf{-wJ^Q)FWdc;)6@_)!%!*f_?Piw%EqlDdWONz z2%lvRn)0(X9(bo?wWQ@7QAE>{yF+D%z*^aKmEQWr0!eH^-~4aa7M7dP}838@m*tbNFDIa>;1)dG6+HtZQkprgSE;Gng_)fie}U$MHPhtwd1%hz~WK zY()8O$};mA1=*6>vl(0bh{Iaq#-ensHzhyN;u1SoS!2P{{5AQ;q>mrg-PvU~NvCy6 z{)?>Z)xS*d3WN!PxHR)FpJhUX)n~=D1f! zC!V3=y_WInd`M+~bgDCxc}n|}{Jx-HN3)iX=mzU6l+fXPK;nwemr^hwU?S0eXPs95 zPAjEdeoXKA+fH9~ik`^K=;WWS4PrI>b43&VL~LD`K^kP;yU*cmkfdyRwGb_qBNWZJ zOu+SZqlZ3OkTYpFqv>Diw}^gLx|6$p%?q~5PIZ>ZqZ^lF$8V#V*e^G?&OvfkqjkL% zbDiaLt&O(So;Qk|Fy(T@u55mnVsqDYL@F5QIGb*;lbFJ}Nf$8A2p0kX7XLm#IZTea zOM6h#g?bm&yD;Nnq8QS;D6~SM!kK_nz>PVfwZ2?D#-!F}CRDOT3`Hz4o$EB4>#z5{ z%kh$#q&%V& zkoS5K{GUZWG37qCfnI?Cb6b;>MXxE!{hrYaol04yz{vzajrSZ zn@?QTefKvrxT$j`eG7|K+0zFwXD5GRX+00f=bI`x{U&&$UMV=Su1V1l_kwN6|C4gV z#!X}Iz0Mu@D(>%xC?iO$jr{bQ$THP3)LLAdooI#Xu6Sf64a45^#A4?B$P{LR-?{xU zlP4x%xr+jQ24OUi4J?o6E6N@lXHox=j3!jd$mX+c)=2Vp82lU=P}?$&RaA-6s|j2m z8CI)h|0TF)i+0W+lOT@$`LlN=bYCO+?IDN{_mIwZ8Y0O>n>D1?A>%n;MVgSYGWKZW zoLPWxIg9|ypRcObGe2;wy2E1vq}5AEC@_JKa(=oypNJSQ4HA|~s5-1{JHcLMWBawk z=cd*f=y|JQHZoz3cznCSFn#0cfpd3M)*!mV?7`8wvkCujSkd(GEX}+*^%t!}Rd=1y zUeT3ZY0~>d@mqag6&r(<9!XN;clqnKU9sp8%Ge#$%x5c(BQlcb=nEKcR0EH|UDOdS zFWHCr-JJRhv>+*X`BrEx&cEY$^K>BP3W`_iS4U- zC1{JNo)Y9rbLLM3^Xe0cx7BrWe^Ze+3y70e@bdY;;x_&Ji+8*=pyR1{wtabV&Tcgi zBRBICl~M9p#=f?*#OAt0Pv8#sbXC&%o3g5mZs8HhTu)9dpL?MV>yRLduDPbe<<`T@ zFKJZz!=(utxTM&L{Qc~GI_gKSEH@IqJB;A2T?MeL_Cw5XY!UZT>g?vqnWH-%hetW* zOi8(;e*p1@A^VQKu_a8;y;SRHX8s# zcSC9zDJ1iLpsTPazcumsVo%Gw*NueCjcoc=V@U}_x#)_joS{;I5+Hda8e09WUFh0yYu8XKgk=Do@dF^cg&NI5EJ6mFdfu4>pQChO$K~YZ<f6XmscexU~K zT6uap_x4}y@`DpQi(F3^yC09M2wPbY3BIRY#6~(SzquCk+I*EY<)LNdpvaE>@#WEh zos@d`pp}BJNqd-^jp!P>8Xw`FlSKzPcpUrpx9NV>bLe^An<4#4!)h@UZT!d1z7$Bx z6Th20t1^Eh^b}t3e^HJ$QD(yGPaq*(y7rVDM)1IaTF)s%$~J6&3p`> zJ5`3}n6D-&ORvvw4N(>(@}N>&D$JG_LOqdl9Gm3i6w|T6t|w5OGo*!52{B4&ql-o&*i*>%JL;nolm8uQq-J>(4}`z z%zM#KX8Bs7C3bUI^pbrx9pdr?xpl3ufu7ZgWVxnMC^n@>JghpUX58bNnnF=efQq9+yAn-{cgK}t8Q;T*XrV} ztL0CDG@DqC9hkF(Z6wOxDoML=Lppf!U%6rO-dISVO;GLZD? z^@Jv#<(k&8OpWyRAM1g+s)>FoT4|3CnZjDVlStfW*RroRMpt~#)@>L$(0FN$Qj~_& zBbbk2X2*1iEe17yKtqT5-&xE4tVvaxzvY#8Skt}^9yA2&A(Ju^V1o%8&WLzvkZmpTN*p!BaV&M!{jYK zPxkP$#fprySw4-(Z67qyGkBB4wf$atGAnH04e&3Q_|byuy!ZC5o?pD#cB3ODMSZG! zp!o>2yv#9oCmq{4$oBhBc^GM5$H%ZsPffF*tsRwhrt1w1erN0JXVo@Kj^}A6X&HsN za>RL@RvMHkgYA21?kHao^GRGW zkx}hJjWz5203>7Clv`S~w*9Z+M1eg33P2yDX*V;c#>Z4<9@?-O9BBq;J4)xPYmavV_J`}C zIBTS1&vv4jTIwPhz+%mF*ZZYlwofv5zfyc8gaEI*bT7D}r;->s&pl8zpmx5NL9Ddn$_!B<>26n$j7Iw+g(U)J%cg05b#j34Fw$ugxk-JW&EZvOkD{t4pvgE*8aS#qvVStsfvrX-$ zaMoJl6$B4TWz>?j+&*S-MeFmqs(jh3rCd~gdE?U#gF~!EXg5W{j;f@sL|Z9D^Xok2 zl7rx(vm2^GZrFY(#vlMpOFTO=FwEs|mzcB{B|Xnt?xtcnUoUG09oz6&8uyRC$d1qX zt=M?K?+B1^|K#g@CHQEY=G{&$-3&+YHAbAo(HBf{HpS7YE}LE(@~^ojZATTe1B`onyP{vvOi5fN%f`JEyzV4Tequio#hH^E1~5)gdV}Uj$3`A$8m;-0Ou#?pV_`| zEn8j&6=q!RnT&rZ=owE5>VHrKPFj#STK^^v%!ze=Ze@ih7~D~ka4I>*B(&jYNa-b+ z`!bX@RdYeyD`e2z)Im6(+$(y1&{wSE9^out`>V{7=$-hP_IzbQ4%U&zIL~M^iJWLp zQDm*PH2Kiyejs~7N^UG2+vf_&uFWED`nn>j(y3_kmhEyx5u8BdEh|VWFY|Ogv9oNM zmf`pM&r5SZsWx=3)@C}`2bra7lsutEqcdZdMN?OL{K;o4qJM=J1sYNN8(zGGTy8%$ zS7;Bq&CU;OZ(_zIp3v7$@49eV{ZYFL$JALhouUx5QxZ(iAWAo7pia}s%nC)zH~1;; zIlaGmi#67|oFmV-`;EOd4U;W7*#!zUCD?9x>%QsDvZTI43zG|`lc5}5$a{;fV&X(; zQJr1%+2G_Cp`BaD3G0T)_J75K^0rN$L#ULwq4F`I=b*QMZvDEXaeRLga^K9q8@X4~ zj+O?chLrFOnt#<}!?Mi}58zdb$aa%V$Wfw&ZgKqnH8Sa46ALW+X33^6QV2cnxEsaW zB$|*HARV?>D2EY84}+}9x|5G?7gqAWQ!S08woON*SWJ)qP2%T~*t@|D6n%$kjXb9E z)h-Orbb6i<;^;+Lf3^I?FeR?M1xfYYOm|qS#AD|F{Malm5Q}o(S`wU~Xw-O^!ZtIR zB(=;u?N3ktv}U?5M-nGt>)l*Jn2L})6Zd|c$Baf;Jq3MGz-_B=_|c`(epfkw zFKqtqlU(7?e1yzV!@e!a)gC=4y%6>{v2&N^=u|6@-t_NJ#QDX4F;3({TO3|*l?cPH zHpk@MWKA&W@Z_i0Xl4~GKQFI)sMA@fFR5Lvh*}td&@|0(%sFsa4;4JoN2%&JM4J94 z5!gbSIo-oShE_hX+c6wX`o5($SZQ8p0~_Cp43a%ZMEan}p@ zX3jZiUVpb}j)kD!nn3$+ogIh8z<{sTTfK{fd?8`|m64qO%UK(Qbk$5D^(-Ic zOh4o8Y%3k)i9&P4Ev>a+BR6gzh@`02{y?GFn38Q+R*xO{%}`f!`*?m}LaUJwAqe3T z_2j%$S!oAao6dAf@Ohl#Mrvh~%mXSqi2?<3dzs-{!=R;cuW9BiR6bh9Vib;C6`Wdq zrI*ln{8S6cQJ%tiXQ#qEdv_LCbGhQULw2374)KrQ*e#pA{`A$1l3fu!)!-+snXZfK zR!q5#cCy3XL{??Pl_UVHm~fuoya&YU90QrTdJ#`YKv1JKeUoXPt=otV!bLkM2a8&jhmNXMkQ zUho^RwA8I>?vSq4RM~uLHE-{=?hf~Gr>(b;3uk{+BHT1hQLm#L-qK{c-FjRL0CXq> zTjOk*n;3ttokS6%>lStg2?Iz_Aus@{2Ify87i55sy=3tA;9^h~8)P8>_F-Zi+^plz zS1U*6kHY4j>1GAs?FCWzM`(tC2sfB^T!I1PaxDFpUrlnm6oKbqFb6oHg&!_P#X`KZ z%|7Ia%?o_Z13~=nO&iwITS9<$!=cUnaL6AvuH0E)4y`*S;RJ-q0LbY8AR!>oA4wQ7 zpnEQoLwBDvANF@4EM@lCH+O%;+$+Zeg+ca_zqz=0u$r1vr!K??O9?4$XIuLQo8Vg_ z@B2*NyH(<)W-JoGE(kRFiL>-U#J<`uPNvE}C)uwfYDr6Cvx&N&NSbdWF1B)(9 z>nG5~B%>BO@W=KmrZ3^D@NU#+x5tCsGE^=5A`xzFbzav+Ng%!iSy)Jv;E_eC>`!IZmB9V?m1&QInu zCaGtoWwS%}<)%hzi^oH}&&b^Ia%kPGL(VNsH3Q*8e7qlAFcfW>p_PoZUa3B8u5oD{ zv*{J_MYl&ebdBs%l7uKU8D5r5W5oTt8DifBikLQWzHPrqnjnQUb{4QTaG8QDY zYGUccC(Tt>>UFqu+WWs~x(2pNyS81EIoY;tH|;cOvTL$!d$Mb?ZQHhO+cj~AZ$IyG zd_Q30UiZRzT_+YwmvfP5gV&42rQ)B2{o5^HzK#$BppV_P*{pCPS|O}d5*JB$SkhLyZ5Lda$$S{n(4)-9~dA^M0Dy>Yd*>?b9i}zj=P`jG}{amJi5Z%^C9Uz2C>xJy0dtyW35lf)yfv#3n4}`4lOb|mvpNgq6kM|9By?Tl5 zut3K)=ly(n2?v1Y!uhUUH!0o6U~W&%^Mcs|V*8hG%&)e4VdyPgx0$Mc;jDa*mqfnl zJ_TFzTq&1rPy`*eC*DEb{5uNV&+OKyV#{8se}^H3ooV>}n7dOG%L#p)z32HaN=vQO zr+@OfGK5BN`*ys2MzO1O=d3k6&m2%w3u)eDEd}61&!khvn$1*N4uoY?;X}jjqAcWz zt+ilWRDkN}kI#MtUY9{_I|o=B`}j)$51RQ3ENBPSk7L+F*lu>sm5e27bUvF;w;k@z zD}^=bYS@ziOE+n{^$buDhN`c(U)Jp1uzT=q$>0Qz`~FG7$gPz1d2;t>)b?*|e6ex6 zfo5a#-#6U8XedD8fx{TDC zD~H-{%Ls_)#=o(h{_!>=?rs&T`+WuS7Inz#P}v?I$7iiF#G}pslKf|cxS5#K}LsOR7sG} zwwzLs5G8;AL~MUSApl+B(Cpm30Ty8@;8uyYvg1#lSSZ}yBOqsFTx8JZ>x?>gCM`Nn ztDf;~%e1fnw^>4XrDDW3K*+~`Ix9dv>xJmd6AFfzu74P)5BO-w2}K|Uxn6T~bH}-O z!$MK^@yX5=k6e-WZp=2FzW+$HjpTXnoz^DJ)%E4Q9YhCviOq@c%UG$Jpx7$Mto7mV zQGl#TkVdsl!8SBt;s05yHgYUY14dfcu<-M6rZGG4-=ALIogHXGgVgkxsTEn#b&IvzEG`r> zl;2p4zfWk92uAgcV_`D%8GE0|8~pRh+t!T&%J#hORAdl5P z9Za8f_5)0ac-PUv$;7PE!dqXv#q|DqH6E_UR`*(V)7ExmIJ#Gk+rg_-FV{~0_p9UX zj4*nRFr|3BpJ{OydtBrUjPu3t%nV2kzLRlfJG|Djg)KPEY#uvs$IqYbLYT@1mCAz( z=4NQM!d6$KGd7_he0M)1T+Wy=3maXF)FF80{@Go1x(H{!Lj;mkx-Q%9O#kWMa(iIc zpk(;MR$j>4s#-t%AAnJ&q5DyL17^PGXb#pti{g*H;>y$uAyYq_3vO3zVJ#?)01PAN zDIY#C=#LT45$a8#wC)2{Ly6P#MIz7F1kz3yRlS1Gx6L*i-?%ryqKNHcU%+|NO~Byq zXzRf#h?@*4@5{1jOO;`8da_nRLSisa6as`;@UyCMVNnr9G{Ok5$YQnZ#l=MoNHc=x z^JN-sg$Fp&a-SOuXlTJfF!40+>*M=sEjTRnYbq`6yI1f)r>)(mk{&ZLNO9-a@b=i| z)I!u!DcdxHCkS=x3fL@b)!D4`S+hrp+2}_31_rJXFn#K;zq>3OtgF|_Q4U6YHQhg+ z+&d$@AsIiFK~LZ1WcJuCofsjBztIBWE6n1<*RluFVj5Lww81NP8S&-X@`X-*J;v+*O~5z0$${Msf4fzyd6O`B>_1%=zn%v94k})Z2N&LyWWoN_4n>bfWmfK2UHya_# zIgTW_C%3Elfmt=gFz!qYCFB(5Z3m*OOHgt67PHMxD;rwl#_f6>%+Ddd+aD`v;;*!W zm{4&Y-?wn53j$vrVd{gCje*~CiOS-3JJZOsrc>@{8~)(l(+9C256En7kut34FP8K# zy#l!1_9mBe`{_LCL>|(ePg!&uoN@s(5Icm>_Cq5ADkNmsLnQNr&H{wNl|iTfxt=ya z3`_@yPw_7R_l~RpzmgWIGM>-z&b>7#OztOUgmTbuUr(Tnc_@#=Dxui8`TvOzPl+)E?Lu|QjZXNtE{yB%bq}f*brq(t;6kJ=sSb1 zpWq45?~KN;|NYi+?Q*6BRL7KN6A4~6bnrXxx(dEh%zYQW)UMK8pzu6E;>12oQs&{{ zMxL8hU`+7ScbaFq1P4jEXmOyE;l76)=E#_X9666z(1gD3-n1eWMa+>IqvFTiDUsC` z;ZowK76|c)n!HAg-WTl>(LC1opUzZY*@CLa!ykWVCjyX)$J&gqyE7KlM|b$y6UEd{ zCif6?($W}q7HeiWQ5>Ck5joVl&oUx-ONMb&Og$uwJH0eym<-Y^9OM6C>mOwu8BDfkpdqNzS9YNv(`pt6vo9YIRP_>1j$@7n#+|Mu`?^E_jdUcf<=E$+8p|t;NNT zqOlpa`|?H7i9QSFgqOr1@#u_12A8WvjWqi5!j8AH2}P6Za+jxr=V`HATdQ0O6Y3b` ztD>Ne=Ieik;Pf=B+0C|0OV5+(F6MSLMB>8TuW$?Kd?dydx5m$J`!l(^&JkJrnbch6`hITc z3Q1d!vZdpmucJ;Ti;n<$y@Pv#OxrDv7 zUxVppxZTF^UNo3lZl;hfCPw^>f7EGPg(?}ZIqR|TfoHUtipkq4ZVgiM_1ct$&-;*flfj`?ed&+$w0Z4#vyd`R{6?%@f4G zKU@!XSL@fHO-L6O-nLI=wAoMBn|Mb7&cwi`AsT;!m!z=7M{ARXC^@sC>b15YP|gEgHp&fgx6Sn?umrD;{I26z8^T&el~ zdDX&;8T4K~pB9U3iAYH)Fjp=H6Qe&fQ&I|9Zy2)9L?3B(DW6_w`7SSF$V&}dHE$-Z z^_-S=`677DBV>B9OlPeEoBwphE9mSi)M7G$b@cB$w1=^##^`6*SfYpFYB=@%<6!a9 z--1c=Sbnc827(*Qp5Z+mDhLPonjIQ8Fo$UCxK$aY!z%Tl#liLFYvU7KH1UPu`iW7(#(J4!LB^q_CMTPtMzM`X{cHDg+M8 z!I8v*(0|UpPkhe1&!AninGJQT*(Nji8e}#_?T-~6*8c2RXt>q7;E(U}WF0-^Sc?^0 zfj#+f_>Py872QZMGQWck+TsX7NjWk0h1oPHfBgObFt2a~qV%50Mc(@TjY?YCLxtQ0 z7r*cJ!y@&dpOZmxc-s>G+!Ze19P#{k>+STQJ95;*D>3+dRNswach6XBXdB?UV3@8v z&2=TChH2gX_AczTLP#Y3*fcX~J@zM<zdwn17#t@&K%|!@!W;#Iw(j{Cpm0=6 z7!#o$Hs4U)I*bMfjts&O90P-)l!WA-{9lsI3GiU6!_CxH`Pbmz2Z09)et!O=>8=~W z=cMP^N=>jmWqEKZJqM`nmW?|i$><+Qd-}fM=;w_8NKh41NfY6YGjs6@U6Gy^_Hynz zm~=&UE+0^RUMc6wRTBc(Y2j2RKHgAW&V#?S8^Pop9a!JCC5ihk8!XVD;I!;a!QQ5` zT6Z8|KxtnT>Cg)*j%=3jgG18nMkM~yCz0fu9G&u{P0URB`X96$z)<|LyP%ZL2ZBZJ z=D4RKGsOne-{F{kLtnJCOBIyAilT4=`Z#}s%{k3v`J;bwDnY#X1rjuu{6Z|lP)Wte zkPy|6OA_&S{Hr6$Ol6a+P(x{{9U#%8HB~&-R38?j;{8eNH>e*9;TQ7ca*D#i*%#`2 z2rD8ilnrvl=CW361{pDT-YVDx;=MxjBa+x`;@m7>40Tw~Lw@mRYc92X?#H;5SV~G^_xEAPGb4an1Bm8m{JL?Jq%l_3TLjSX zTy;K(j9obfuz9{Zf{+hvw63ZmPO-jl{&v?C`fvcmea)TUMRyR)5yd}DlR51qar86W z1@NY9qYf;vb z65HqpRAC*alOm&;Qu`6nAvUcNpF&D%(Ant~)rKGy(fZ_2N9PGquniX0_%jZ1EX&lY zhW%p{Y0?UZ#7VG%v2^P#(4ossScIiu zlTY!49J}eptEI?^F)S)&qlCr5`~_UNdVrkjT}%GdUM~s9HGA<1euLeN5dLq{%porP zhYh>0B_vhyo)74s0SHWSH~d^!ujtP^vA;Hm1b0Q`i? z&Zp^Ahih+kX5LqgCbRe_x?T1{q%a!)TtNrfPj=ryJMu$+=VA{;Gw8=-gRFav#A2OE zgV-i4NJz*={`}(JNx~gm!qPq2W#FEh;o+vH8AMzz1U39=h82QfM3< zaZ23#*UkgAOOrB-xzHcKMFFFXxTS(|7JAYa!9MjVv3j2q@va37=_$=Z=0Jqh+^b8z zO?de6jLW%-_hqLCn;suy^gy~FlFac~;%}6AMz@`49w%}qQ(qyl=0=Q>qeHOwo-ZOO zz@QfgmNw}(((UCcGE?2;h(D_wSFQCb+&16Z(oSWN@YxhHVe$Tq8}A62@8+M%Tr3}B z{&ZwhgH_iFAY<YTZJSMq{nlTd?(Etl(jxze2?BICitAg}7_@+1Rr=$exu#Y26%K@=KVv#e#;WzI6BJJC*qKLYO>v8 zc~xoYArOo>tmbvjIJ$<_z)89%*6dm1i#6d zd2NmOr%=$cExTM8xYDYblYQ^rVBx8=;qs%qF*r$`f{Hs3eziKJs&O-_tIoxZM9kp)T5FA&!lo(9==*L^Dy%#|Qo3<;CJrr=#Pz`K z9$IdeJd5mf7J__w#Nh}rYj{b~Ud;lW*NfN9m^3ic>Ck0xP-qBC^R|%hIP-k;dMj7J zd`pWCiCmJcMhDj?L__V*iADpo3POXKQ8J4oMSal1eEzd~fuo^{qmoi8@M#GC_lKu( zQKaCwX@eKT<+w%#5OSjg^T|Lyeuc;1L5cD`v zQ$fj9^cr|&9%q&pRwB+gZhO?%P*LUolBv;?TKy>>vu$?ex_ZmbURU1vq=jLl*^2UE zyT-N%2kMwrz*~U@#fLmJF7!UN`y^2R==hFux7^%ziN33+nl|kh{=bKs89LGC@Y-jq z*UbEp@Lp*!Amy82?oBz@+{nT6$Ysa1@s7{Yn`_@zyXnUBOOtjTEK`V(>wwr7tR%d= z9~$U&=J+ME{~R=1nJZ%14KN=WOEehgA^IA9-hp5V@6Bnj#w94`-U{~V@)}syFF_Xh zEXmnracN5>#-U?t!ffEB{%KNSzW-==uhBy!zsTzZ)>$AK6w)9T8bRI{^})%Bnf|g^ zMiW(UjqCjl`1B#9Keyd=Yc-h~AU(_n$54<7dzBr|GWHP(dPyqSw^sYN3c1c_KLGSc zCw8TbSwA=WGx@-k!Z4DNH!wgI%>ZL7c(d1Gq+^UFudv_*fjoED1gJ-;+NE}R# zW$llhuYPja5p`c|;_6TVq*~h^WFAT)T;ZNcyh_! zhk9eUx%nah@R=OE+|4e(qJ|1j0HtZT>ab6Lgo)f4Z*ydpH4fxMj2mdfmFMFxhWvh%3e| zkk*^Av&E69c5pRoHP!NF@vOAF0CIdJ{`J8~jax3kYhSIOS{)s^3*D`}_?hgeauH!I z{NfA!o8g44lAQDbM3vDWXhA3SgT2KRZ_5dTMvqSk^CiirPksG;+93^arbLAbJM}d6 z{rbLrv7=`=98GaE4rNSD{5mTCeF5nojjjSb6s;6q83swT&%fFmyn8gog)QKj?szf3 z{?vbuZF#$(bv|Uu7t-z$uJzu`6=<4QV#Db2jIB5~XRXx&2V|pl&J@mQww=oV=WHz4 zu9Nz!*%s>5ZY^+Z=tffFFpd-e0fRP`9eqQsK=pQvpU=Gma2)s3^!>yI>j4e&crsYc zp>g9%94VNID6YLgzbpt{rzW{wLqdsa;*QRObmikyP;pE;QqHeOfDa%#r?r&xQSz#= z51*nI-W(D)%9IaRNPFTBU$XhIez4Y2Kh|hGG&oPPhekFQ6X?CQZl957oxmrf2UBZT z{&i|fDEQ!o@Zi2w9OFOy1dch6b|yP}H$3Y~Qj0GiP%0N2NC1LD5-Ve%1&oE&$}*TQ zhGJ_wok=4x{ZC|6pV3KQam8y&GQ(rIi2O#%eC%+VpfEhNIT*lVL>dHUPIM_K*7SYN zEa&4I_*!w4qQ0V(WndOB2#9B4d__%H^CnyylLP?h95jINaX$cb9%G^qgdr*|Omho8 zQtcr^DpD6Tk!%)>mw-^(dZ8n%Q%3Y}fo_yDmyzH<{=CnND^T{k(`GCUg?t!A_(@q~(@-)A0A=t!9W0h zKAo(fJzj|+(|x}?h8)PfA?G()pnI!V!=j|zd!dqxbHT&cCKM4Qx*aOEa32;6?cHv( zCvEi0h(6tPy0eCW`GjjEvRav6LC-0|B4(t(f0cIPm7;yWskNkwxaVbeE4%MKU-c<( zK%IL9{PRBjk_K>$-EIK^Nvcb{pJ!a}(b)L=fvV9hTr;dDYg$)8+4@{*adG+ltD0*e zdIU47vrVzcO-YQgRS&y%>i0HTr#l$8v-eM6SmNitLzbKF#c=_>vohhlr8qxdo+hfsdhdT2y3{fc`bXU9MF4%+1N?%HPCZhK1Uq*X> z5Eu3i4uJLBY>@oCUe>XmT>k^~N)}&a6acLfg^e`V>wj8YvKP4+;G<&*8#J+sCFP zhG0{deV-@+kNP?)DxM?V1;oh`4QoQ%1ApTl(U~ZCx;-d8lL^Gc#ZD` zuSTk1dn4w0pP=tBi*yAqy%0vUN~2DdQiwJGC%$NA=Gsg{}Tw0r^Yi zT%#>UC{(9lA)O|VX*N9m7}-+ib4#U%5s~Mk{<*hI2!_1vX+=>D z66VX)(oSev^56TlH6EiH+GXxpMSYo`ZoW`?5XO_z>~XI0h?#PODPVmFnXD$o8W~2H zOE@DUGW^9G=GABRSQyb%xrY=m?u88h)_I7a)>*GvWvXoJjmnE`u#^W9`&j}|lTA#~ zw+?f2cVyBBL=(3s|1iGlz&M<)xAY{-jUQv=XP5vaH3q&{#Z}T1)ZL$f_U|6n$kFHp5@?`;N3=hi$IK!jbP?J@aKYZYGc-I{N z7N*saKxR5E3q@-9F~CgCSSkJ#88p1wd=)W`MA^k=+hi%) z5&0JzMegA0YSyFPa(jhZ?PLTGR9-Xjwb&qZxKo`8l$2%cwCSddNs)TB-;ifHIg-^l zHOriUL!{Q+Sn7rRb3NUx!haAOaNcH_oZ{D8E_%`oK=QMCARrPW@}<&0ar12DjdZqM zpmGdhZ|*|&%^*5f9iyOhAa&gZ5qvVBAy?c<8goKyXfKskBc z$EN__q+g*{n+NJPcbarh18rR&u7~*Sc8~)*WanR}*tY~4^QPh8CKrH_PU){{QJTd^ z#@`eDqe&GOpEHtzgUe9KbGw+ef+tt?{i3V;h=rm$gVq|-Kn<-a@AfKiUg3+-lfilnEOKgLBdh^F0Myv?MX!T^z83J||DM zjXR6g$+W8xAN#g4#!Y+%iU-~qtSopR%Y=n*;|ITiK_Ha>?VSzZ`4Q`DyI+H;F{k z>RN~5S+mV?fB)9Ex&s-vDT9l2tb(uJiJHv;ic?C50Eb)nvo)QHQrB#H%%CS%<0XaP zK>>a@=k$vB`-?3%pPIRU%2qgXvm>Qe`>CxtQLd@W&vZ3Ryu2-Bd{d4%f%uHN=F{1{ z+5G(j`V!;jjWh*8)o-qiHwB7fII&9{m3Vxv!LDh4v3TPbt0GTR=L#q*%o?i{h;fhh z9>8UfXJFjjt{Kuq!{dB5ix56%#sfbzMqln)VOUuO-bxEu?0J40UFU(DOExdQ=7pv{ z_Y}wkGNwejF)t5%q7hr{T5CdN{}qXf{D5!#l${r={M#dpCnNhU5QpK%Kud@F#@cJK zYIv(e-6+wUKq1E)wRee}`a57gBIhGsdhKKu0zv5^GR85oSfg?8yX{U}H zE^C8_g?>Ls)pW4U7JDu369~N*eSV9#{q}Ail2frBm3fwIBjJmt3iVyK%Tx7B9?Z*R zQ@F`8U{TJyS{EM!vPwI{B8wA=sw$H}R_G)vv=-0@gK^~>tsRM#JK1FEQ&g18?S6>L zl@>nu_b;?#!&u_o<%%w~pSE7i4+;tS%y(~Ii&g8%md9C-gCW~&w~%QjZ2yO{IzBJ6 zT|y?^aql_tNkN-b28qHn>PUb1s*iq&(omGCG~2Bd%=twi_31l+om+UL)PG{sfCalh znEj7{LBlkwqXW12iB=Qcwal<Gw=_{SGot@B27?GRD6-P=2RCj*OW6 z=I_a#g+^uF-Y>Cmb!x58vv73)V8b>`vgCcIsZi0MBPFr4HclQtQ5*@61ko1MjcgCU zmEiZF72zT?A7Adl@!i=@~O z=zIxe(HaHHDM*f*L}Jkpwwj~X8;HO5(pUF>RBDH=*8#WnWTf@6=3snz2DF<8n+&-s zi`YSlMA&z0jr%m2H+z>BGOS*tpk8viv|C*CH;i8#>+41gMLzF{Ypt0Wszvz-#3lJ^ z2mP82!k=MRyM58O$cn+5v41LZq#HC zr;;nzgLoG^ETq=U3cDh%*<*jmFdH}FvBJaN`E&Fy==(m1j!aCKWA2zJ%byRXd{-*UtH}JGBPK$+0A8R?CPX{87i`;(ZbOA=oI_ zJSOnj>Wv-wy_qft(IhyLkwG4GID_SfbCO4bH1LfU6?TI!)#6apb?_|J1U`j#6NFpd zJ3b_AAOk@g8XY54h!bf3wB&8+y#lc^NX{Fo`x6p=2l7713Yhiy{+$S+x^8(sZdcznj)$-(T+e60Khu4HKbUzB2OsHKuDn;Ccg)uF@DiuT zuzQH*yV-seBJ&fxuQP&GRcVVdT0xD>2pRbvqA_eiln?94h=!gtbqXIIHe6rioe7ky z4#fV*I^(gbr61R4*S~E>;FBlD>zcRC?sQfvj*+I9V!q`2B-QY<)=zoRF1Yv1 zIR2EJkm$ufiSDU{MwMGpW9qvP$0OSF1|O9)l`egYWh#DP{5RoSVy45r6W`olK~H~8 zc4`=^EIyaXp6KFVtvX=;uo%Iv3HbxJI}8R+6Lq`=rme0Z9xuq1UzfEN&BX_wHm=Mk z+_nv#d5`C5d*^^Sq2mF+VD7d`^G8Gx2A5IO7MS zUb}FyQNj|2OLK`oWx|e!oKtbCn(aV{xpY@a9*rc^Fm;y~Oq0*&D{u@0>;7gvB%&er zU2bQ2^xTCG2z=R+RF5}q3@SZF#o5c zob!pDo9fAYT)*PanA$CUu-`$@v(;6fDaCS%xkm{yxsQ>q;jt;Z%i(HJv|_jF`!$Zm6SE1BHY^mJGm&UY7X5uyjU^RFdT;4%g(2 zFtsH+S)@5A;fC#kL|55YKlPZ)_7tqv+@lM_7zPunA)JPdwT#UZ`k>qH+;m}kXA;<{ zxyDhUhRTc3Rahr0Ko(JGP z0qX}HAFE)4q}|l-!EHwc3M{>JYum*>+sdHf z&oH0FN&6=b2?S*flO%0);&SZh`kdTPnSuSZ5j|?CckODe^8(ZjXb%n8HfqXt}t*S3`98Ql06P|C#*x z6k&l=-oRWFGVNnXFI=tSayQTK3`(U@+4Sn3p788=?U(RW+4$G`#MiS~SDzd{t~dXJ z#F;V@7pi~m?-b5;TAjWjqMF8RQT?!?X{+ZMI<4JI;?0%l{8^imQFDRT^%1q+wYnpg zID#y-=%J`xDFP`cYB~yI#8IO&r*)#hZ0{sZItkyh8F*m3VxQISqPRJnDx#+L=hyJ} zEZ)5QtwHdq>Aqha8Z4vUmk_gFu!%8s#Djyq-wing%gT8@B^7@wS!`g%vomU^7gXg} zl?Uelyknw6pm&Oq-Wi5>=;4L9t;2AD3-V&Ec3ODD;-ED+jE-jC!?h7UC6@-;-Y^Se zKLzVvRnUu^98HGc^D_zZxwlCyAL^nOX{o7^YO&`fyDRM*WhJ2J-X38w%y+U+=VijV zYzIB~Tmck;svVs`TNK-&;U68+3X+BW#HbF!pxZTkfQ)l*YgT1z3gV5^X>$71#&dH8 z0Nsx;v{#l?xrz_0Z6C42u+rvq~g#keRzUJ+0`)h2CuL&QQ{LIg`nIFcJW*7ypi~%sDq}bj1n=DE%>R>MWY^Z!9cC4n{r$Hpfr z<#q_m0qpV$_x-@EDAV^#UQt%9%*^11VHES^liEw?8hSk7t|>Y;dizzoDI+>R%IeEO zTkvVf=y#=MZ(?Tlbqy@FO_Gn6K7kygugNufzEL>T?a5JrPmmC;PfTfljW{*pjP!gA zJQJ}m+ql}*bK?tNZyw?e>+Q0|FwGAo9{wVmWMpJSyFEBK5-E=f6J;|1-Ou;&hvDro zkzt)X=QI(!ck#tT2g|13L{Sr0@tQ=|`Xa_;jymG-l9bIJcuAfAfn$!OFq2>Nq51C! z2B2cd%S3T>1ok`>S!Yblhp{Vc@Gbu8iQ(<6grOV=9shxpzf{rpyfC8%2nn#BC!WmD zbk7fnkeC!jQ(=+?aKRI$SkPreNR{pLkTL7VDFJ9TH5dJiP~Y@#0zNvG2f?p z+=fti#~D@>!w49jL8JsKVVI*0*Ug2N65zue7ggGpDmhHeY7GOC#QOfekgWcL0G8DZ z`n0c4ywOAoYwgNC2cIjKY{_jWZAvdZ{L~E&4s3x@+gQU^3C+K;RUwnt{+eP%uq!`|)u;bB!KS!_rC4K%r4X-{o=#ck}huTn#;X4YolS z2v#o49#6T;lh)Pk(p&BbMZQHd7edo#7qRzfN(tOZD`opY*R}XToz7%P_T9Y}1}|b3 zX|k{4d@+O2!k+xE`k++Yb$d_E{L}M4*$Vna>vvfC%N*BB(5#h^ zbV@tk2M?c<(*S7=YN_~AtXKk|40Q-zG`@#^L2P|B-zuWwQgkcG zg_I4a5|q#!yQQRspAz2rG=>p&5ROCks0Ljwg&*;SG=2w2-bJgYbUr#6YNG z&)yjI9fQxCl+$0AD3L`@JEDh{o&8kM$H%0CrT)CQgWn**vfh+4;4Cqla&jLb0UZ6)0Y)L0#>S5y{ibjJ@N5 zo1k9n7kiX$+^aWQ+5`#GL}%Ms|JS#RG`sPn=C^hili5M-e9w+pC zc3Tl{)G-~o0n^0ZD3&@92AeHA`8NV?(bLS0Zces>X*PsY)DMV9cXmmWGr#l}UB!y4 z(qtr6?`(Cd4`#MONX_Z+h&7fV{Deaut*oqesKpW!S2Qs*s+$hJ5uLP>osrRVP#J_d z{iZl+5*&vxQ^5uWE9i!2rnt$2)Nh#yV=uQRK+2C>&G5<>t1Qz5UeqR)U;d-jNceOm z{$Uc!*r^wL16z(SK?X!bLYW>v>PI*jI;Z)E#g1-xNwugvel#iVd<-BK^}}pVWT9Y5w?s;LB6CX5F_xWYOfQuTLr)a%rEh zZCo|*Za7K7+aR!YjjMT<3Sj7TRjC5Ne*6eUj6bQlww$i)D({SPET{Md!t#1&XJFSL z^E>*gCUVg8y0D1Pfrp~v^QklTo#4xTEENH9)pwz;Y^JD+6k z{OuxM!_2!yb!)6Nc z;&Oq2fFz`=JV>%>{#C04cXK3;I-hFb^Di#JEC)KAUaMk^vL)CTg|r7R^i!##qyCu+ zM1cX#_H%*^3oM8<6a%n;qXt-?pDMm~M`t~)TbYc2LKQCQ83w!gTn_y$=lT(gOESrf zQY!EoF~R+3pF)v`JbYikb5asnqN!6+cZV()<6IniJ&NT1U0}D>y74GY zrbrl_4busUS>@jl>C<;T9}Pbb6U*0#WqzjWd%|_H?(3A~#84Du*bNuX=YnS>>;`L6 z<9zeUJENu|V=V(UEg~PcIT+tQ)RG+Vu|whVWv~Go6cq2DrRhl+sTb9qXg89X)Ld#3 zw>UQ-ZB_T%;}km3q9pID^Bx|f7=FlRIwBUU?f@utqHhPd-%X;Oe}()B8fJ>NOEyIBf`NzoiL{dqlTN!|Vw0`4QwZxj|D1VR zQbnm{C3<^lTj(?17l#eD?ajn%iOy zb;kLf*L?P=J5I5(b2XP*q^5g6Zw6Y2Mg}U`eE6tRB3?`|plIJ>g)B{V5TVn!ZH>Dh zbRLC{SCx(phq=G%?(tM!kaJcLa*2w-r7MV^`2Mh<0`Q4T z2((hjLDum+r+v>!f$?t|K2nz~Q25zDPDT#F_*@&%BKpMZ_$77D3C`ALGeFs;T7c6=DUx2>@TsUeb?eLXDhmf6K-tTYNbOd0K87IGIrxt$WNQdQ9Wy_E4zV9WP7hEXIXIr2yoNEN z90z8CeP+~$*eCcxV~sd^*AA+~Jg8Q=X$B)fn2rveN)C3`=LvO%5stuHL$-(BH9a;WKiW#oLqe4KS# zQUdycdncC=;GDdAzHE}Mj1TsScob4#z1}nc*<)NkeZg%1@Eqy<`C@b&>xGpnG9(8j z3wevjjhuek_1xdN)ZO(ebiO2}EteIcI#?`6gS=fw-kno%C<)e$(nI_ix?JUOX;IR5 zdAFnvcHh}K%7vLxo^LZ8Bffet9G&{^BXkUMIY6BC2E<#Z3^Q_Jp?{{Ck+GHNc0^1# zmD9y=(=m{tue_|C3ZE?_T|JFahb3q?KtukC6@(t5V^4g|RpS44`;j+FXn@S#r0;mI zk9<8>2z?u?9_&--`(gQYI4=WEHVn#~ECx46mSbB0>vV5-hQ;kWpJ1+2K#WSJzk3Zt zpfHC6p!!)=Zg^${{LElp0}S&Ep|PG=!%Vf3vKL;4i}%Glb-njpOZ}zJe-jq zUtA)%QWK&!GB!mh`U7YH%@SxTuBC2CH%T;%()o1dpwMJ>AXM2SEjvg-o~^x*Tc;H; z;3=m%WXxrQM|J)AQP<<;7FUFXOGZ5kIoY`5U;U3qe=@WBN@Ar9;# zZ}gYsoRw?%q9*u7p)+=kx;YNejb|;}fr+nklB|l&R%XkU7b}w4!!LJ}P=YQ@< z&|^;x5_>osi>3n|T$VTeI+}Bbq*TEX?*cC8zr|av)7IX{Jv{!ph5TScILE48x!xzy zWJ*s_w*lR<0+PIskUw5z=(RJG;sRX=@f3Y2{9L8s{+1ezq$?~nS&cH)$fO@CIo{$! z-9HXwg$2hKAGy|CLi%aB&Lc(aN+vg1a4y?1K>7ILTK;W6K6vbEkA&|E`bWlNJQ@eN+VtN&U6IKMU%**3+tWOPztT>+l|) z44^tkwt2|XhGp<}&QN5F?mI|OiLDb2*r*Bkm}6%IR}lTXJPp{;67vQExUyIw(60g@ zUiiJZ)Pjfe@5ssvbzJNf@cY?88-#Uk&nF#FnFNeD8tjwHruP2;Z$Xg00uaD&JnrkS zVb;3xN<=qR1mJOTZ~{-5!2H^4;EsCtUF4n^CvfAcr9lJSLwb626H`nK6z$6VI2BC{ z;``K8=8-K?ci{tj4j&;`I3_+QB6fr(pOb?N{!PK2xd!l$O9EtGwgrfIEP1$;q{GXn zIryjBJzRFDn}Y=fyr%<_s*H&=hbLp{{?u5VIX9R6q;eocV)gS&67YqYB|Sa-(=ZSP zgII=&&iUDA72o%?Y4SK#h4%OAt8(Aw&6rGtQ_mP-p=svp7{Rcz!IG2|>9iB)yyOxr zosS-sj^oQN!)oN%F{wq1<1f7w_Hbi3q;V4=pPf6)RgnlAJpX+2grTZt(1?k_q<6*{ z5;US|l2#kA@%wu9U{3k|dpyIt?_vTSkSG(e1}5oTZprc$*^|;lKwM5B(z{CYn7}fm1Qyc4UG zi4$SgiS`~+QlRuqngl;r=gt+c5Tp4I5))zWJMTQ^C+igOcS<_DsURY&dc)NoaO8_< zg1?curaDps_{Sp#4W9`tghkGru!o+*gVr7~m>+HL;dxy>>?J$o{96+C6 z=;lRN>wKWV%{lSVvT|~8d6AUWwJSag&HL=LE5Gg6UzZ)betjgb962I2pXt+a+*@zq zvv5X=P|uhcXjAFw@;tGz)vIz;QNeOm1t|XfGqg`44CdXt0VqR<%IgpT&<-C4NL4o3 zoN@}n9))dMOimYHjB|;>?sVdLj0sAbhEU6%J)=huiOJ9yiYR_BGF@})>3s3UU_%wf zT115@W45I6y$6W+2*t3E)Nm|3j#o^_mXpTiiUY?fHd9oG-;e%bjGRhOM=_OP5YFJ& zUV}~A=r2i41&zWR1z^t%kj2T!Nd77)kdtY0GBoe?>v8Tt01AXCD01qlFx7~pyvoG5 z3K%;UlZO%Xt=f6hrkHpxybvoHVXL><%t=<=x}je`^bn30{j^CF{H}B7=>5oQW?LWI zD>4TEZ)lsZuG9ej@rp4O(&fUSb4m^0uW0O#;>1}?8C)K!QiX{@i2wj$tA!I6P9ZlH z@bz7F-gmQ`AG`=0DTkfOyf;Ut%NsLpqsjE?@|GJlg60$qN?U2WcJf%^m=oq2VPX*j z#_g7%DVFqBFpmb5R_)E&tnCz4vVU~ahh;>b!=jT^%(bH*8wT7M>??Bu!0(F?#>Iaq$^kjnwZ ztOP{cm|)g<%9#&t9WpBfTa>o!B@Li&4{`GtXscJ4&p!ey7C zeT^m^uj=6Ur|Bj$4l~;Qz4wqwEGF_cZ4hGn%P#=$#fxQzc*~Z|&pul{;I}@*^5swj z1`IG4GPhDJ3lMMB%6y#B+*q$3?)kFIWW|E1C;G@Vgg#l7fR?VUXV#T1bHBf@~6KVRYv8^GAih^s5 z9gD#m69b!YAOMY&NP>u}N{Wef>&(Pl)~!}8)Xn|k3v*4@MvbJIN34?K;$Sk^vIT(I zqJ{ZBQ&Tbd_3Vin!$yEN)`u1R`xi8j#Al`C2$jrJ*-t9(p;X>ai4peuurp9Y<*)9l z6B00afAkT6Uzpd@(hy$!dx765hYmqGnK1)loyLW?(+NdDn1jZUnXl#zH8=b& zlakDlW#^p3yk$rM2a=P+W7A6-Zy)>LDuD8rgS>J3+XFtsM(%PU!!azn&hPew6YtO= z4o?F9koFb`jY_`-1OhfY2UXPs{y`$%t<1)GTH z79cZd5C-?mnQ}mirF;AKaPl%^0ux$YMH7vx0>Ea^mMa5e^{6^^Bx~gqo13rhr1LG^ z&24d3jLtnYLq)ET_U;eS47;fy!n|WVzFc#${(m~JzF%h_Y2is+g!v6`rblFt)~(At zYmm8O*GlRYF0_4&kj@|0X2)|ld5;;B=KT5QT#KY6^o?++ur5tH>~NU0*|IWB98;#i zu_-3qm>A?1xZQ|h_j)lATy~j!7cE-?l;_Wv%&je2KwCG4DgRLk2Jy@b7h)AKB2DK> zp-I|GMiw9nzZ*?s?xsklQLzf`TMKjw0Tr~^-4vat575~+^Pg$E7g7WGf0DfTB3jLA zUq9_Mvy(NrM&~uQUY6($*zdohHavzry!w8fw=~I#aN@1Ivg%Z9v8>*(fmx>v({;XZ zWQ4(}BKxzKG%lui(}3AQjhG0|7j=t=nL>jNRSi(`}dn|_Qp+7%rwUh8ZZxUR(0`pqjnzDG~RZ0K7W|w<_Ft&c&a^8 zdtagEL^X{Fo4*Kmyt}r6I4^XQensQ^lij9!HcnPXI%BV54{Q8h(s)wnI-(8&5po1p zt&&s=hYmrzH*(0Nr9lf1+~p3Rk5#qOl75E{!S;RQjnYvo-o<(6VIo<-9-uCKK#GEX zf8&i(<3HsTOavzq_?ek^zG88hCzw}L#&;9V|03R(;J-P)zRts%$m4?lU|W6-;QvXI zn+sdED9XVMvMVAmHwxLhl_L^r1h@#Wc=S?f%k_uszz^68Oy`a!B_$ZUNlEzZH8_of zMC?;EUfe|jk6+Pv*R^i`^$l= zgE&Ql2Jjo)doO4;1le3%91{9Ov{3Wr$in?Yz^@~+?fwgNzFl>jCTVuNnLQp3W@K={ zX5)a0l~!I0tO6>oe{Ah5YPjux8=C)*jMS+C{69es9fJMvh8xWLAAcMzX=r-BUOBvlV*%qAw9GjdNo6;UAqOqw-=IYDsqTfr|jRvs(#%!)qTDMJp->_q%Gj!y3K-^SMesk5fD$?NCw%my$EA?L`0y zv&o5HT+BTGN}c~N)y>@$b7636{I|HTXDBZelBsa1;^OD7(cwU3OkiJr2?fGzN^J^UIIYur%H(8IG0WJJD&6-K3PG;t!BDn&btVlo$R-xfnCEK?Hz=sbvPxR^OSaqCz zw!Ei$^`w)(Su;3-O&PA$5br9T%M9=Pxn3R)#8eO~Zwa_Kxf(NJk$pw@ zV~pdbj6y3co9(2Ko}DPE0sKEfo_h{0wq}ia|GDQv%Q4#BhYx3V$D6Y%Syg%Y83jBs zios9Rpfum=|Bn{KOLya9l2Fh7mSkD*zh7L44Pw3G;=GFbK1q5(L~w zu`%gLyc41ECnUhM^UE)=?=M)ud_$}!6b**SWA<>J_wTQMpRY*7geBtPMf8`V0N{=J z4&uAUjiCrt3H-XwJFar`OG!~C;^T>xHyj%bGVgdIWfE3AaE5_{KIJ?#; zHGuyo$l$>MDx=Azqyz)*y6fb=U=WVY|7-0DYm@@*K*|J7&Zjv{^-7IJR4NjmPjbry zgCOq`00SqZ!af@kY&LC@gKqY0d5-*iGu5nB^LeC!n}b2n9}8P;?b;GxMvQ>zz-E&f zn_at_L*}fd4|_Xwo@#f8%k4#5UR(FA4f!U-09>zTaKI@wysZmiv(F?<5@SPVm&(E_ zjT1zv>I$2Nx~n=bYU}0+z2NYRi9y)nu3eSCk6;ir5&HKx`!9?@A{>fqD8tkyg5c}v zr=gwu?=su}!&;}}?U1zSURhj5IRz~6CZ?2oBs3ZD+! ztp4Uw1NbLcgx&m;Pt5zTxdt8ASm5}HCoF@F%psY+5PRZFH|SyTxw37=_DJKtYdQnm z)~;oKe;R(fY^u%+(&hC6q=ad3Z@yV-@_Y8+RKXxXN!Zfk;}O&OL4Bb7qpxXS;M>Gsw-O+vs6a(uffQM9MF!dPa+AbKhUe(F0X(pSj$nqOQ9`2tYJ9~-Z;vuOz4@xob8{SOk zku7yDF${|Cs?O8<%j3K@7eAR{A$uc*{S6!Qj!O%|{q~6`w^VL^#*!fzS z967@LRpT7f1h~3ZPK8B6>~^fyrrOP>9X}~tZgX*OhaO%Hj2K}qso9zkZg4_?+{+cqG#Z*|iJ6keCRk^V+1Gs2aL8BY1gSZiMONcGb<})#w`j zLv1`^P41oqH;-ziM*v-Htl7-cT{Ua((M&)K9Qk2wJ`iKp1Q#xpCKIDwJv9}M?&ZrR zB}1b|0DeKmpeQhd8FL7P(>W#v95Vv=uez#w!2jDBIed&|3>qs+~a2&_PU=eur)xb8pT~fvC9i3ljk0_Z^1&-8z1E>~QZw^V-G%=2E|$ov80Iag>o;gHHq!u_PC z0=O5pl3{R9k2eGPIkl^1p!AZ)b12_ri+^aC&T(ob^5IX`aCc4uH(;mRsa1!Dd6!nhE#~g?RjS2jALV57#;tkyOG2)TWIr z9wTTjnl?o^a#hKI)e>Fj&3SHq(v}~g6xGNdlN!K3L9%Zj`sAcZ=KTi`V$e*O5Za;3 za5BH$AzAp`Zp6ih!0gkZZWBm7{x~L*9z6ga(X=#XfD;kI_+nxJ3d~?nY|;cIQ{zw9 zP0l_hV$RFsk`e%vs0AC16FwsYnx-H-+mW5eCFEp(6fJ*a{{sHxVE}bjX!4qTw%Pa4 zKOqvxCn;{eKiO=?TG|7NOh$mu3i%0)_WceW;4g7FB(;O8LMsXmp~h$!QEpLyyAk}wU-8}8v5`gRjq<<$$;hWO&X5!mMmf4dXRqdr zI^mX)jqP@<3f_DZCY>8@Fa!VCv7ut~?#LDAx8KTO1M#dzyMJ=BTyA6a78}b7Y@B7}!7kWCr^U z8<^LhZ;t&AYFcKw;b5=ktW-;X ztdW~vxt;Qzm@6cKCv*-SrdVRM7&-z$MeU=;`vvsK>rad8Jmsy-dsJj!c;kE zvzxLB1CT7b{iN4g}Ek^ zbW=P$hd|$N$S1fbAv#aVtXa&g>%6oFzF)P9dDbi>Io+4!=DUYTa34NgYP|wzji6>V z#}LWF?}Ag`TD_}TGiboZcUM?wt{!EaQ1bH3;kCLh%QA}ckWQxrMd1)W>nucS86Cai zucpCv|HBVaI+w2Vk;!hptp`>yB2-nB-P=CN!$F(bpTdnBb07c`vk4O-S1w6O=$pfb z%ljFpAX3LqYE+Hd>qY+%NpvokIdM)rPpw*#N@DzYjwqxOO%A=M^ApYBoGrJxq^Yw8 z=ufDebdwGdO(LQvLjQY+=n}(s+lZ(^Rp$!8UPX#bD3OyoXW^VU&u=A$H@LI!|-LY%*(BBtL#8>82QPFKIk8*3DPj zqla9I%u!<*y;5>;Cg~BRRO_eENs&NU6r<1@}M1D6qS zj5SMDRobp6On{k00H3kWtchT$gs;S()sbmZe9_e8(t;(NaLUK-Mo9chrJ47=1UY8FUS;xZ)Q7wL~OXh$-j3m zqQ}~{#kB-Mn6b`skceM8+k@H-70CAOV8Rq_-Jn4vZ;)uOh7G|28aAPY7%pE-tZ~ks zEIDC-PedPtz}&i>XE|;X5l!dg1bpN6yEXj0JXvl@R0cl*lAVpn1*g^f8E35`X=-w+BEUjQ42*B?AOH!K% zKrS9%z%RVO{NP2A;C^qS#i>eeKDZ1apg~O@*R310^c=jaNZ zxAe;AMe+Gzie(W=CAKof!8gUp@5;%}W5^R>!xty_CnfWbFX+5{IrH0-bS~Fq-x=3l z=TlEL(lp~eeoxIKR+$b5KwYqGMw3H_5YZ**kyBD4&21tbKW8 zXHSOw6(*ggM6@~d|H(7y27KELBICxHbF|A$YS zoXpIqH!BKmTzRD|O_!Jm=WCrh65OptS46^;aT_@jzLmp=VU9DhcwTY|&Z{W+|J!fT zmiOIfuF@s^0z@$XL<7YQ8zi|L5mpwS%XOX^EBzm(2H%cwejD4tPYTbs=kvl=Zdn^y zReAS$`CO(rBHCNTJFeCq6Q!{X1$F5yJO%>s;Qjf!X(wIe9DF zsl#Lu0{0a&LUad)Y~1p4ghJZwGE(K1+8*}RuMag?*pqdgy(*G>0uCp?KMnWhQ|%le zB$}0xBhoZsut%4aAnTI|bjvw8vYp0`m5D(jBh(1=@$r$SlOaQ7xaIEMn4raXy?ets zEkY^BjDe>A)mLUGX#4h3n~jTOQ*u`@$o%~xowts1^W!6QPDN7&UYOfWl-0 z;8w%HZJkV)I;GjqPYQod9eKZ+91fEWs2Xn{=jPpu5d{{ZMOzd2JRWm$fv)qfzrs;& zG=1H68z>{vveS$#czQn~ov8oT|;kdp=Yi$ms}FNtUg5j6_! zSBU6wBKm=dzN(Hnhkq~NhscghKoS}xR<^}^(mee1c%8SNozEqsDz8@GvnQO4R(a-` z5Z8H#Qq`+gV9H6iRJ#f>?rq#C0Y#9RF|#?@O4m6UBMW#erd%#12V0AGtXDF^T46xd zc*j+4_BNKFUru&jF~gj^wQ7KjZC|`tepOZm&~!M=;fyc8EbmuDYeZZ1?0r+`DVm#S z4#f2)Pewbf9*BY@nWXbW_1yfvn#23mWIl9Wbe{1y-oQ#GE)Lqhz^GQOV1Cdv>C|oB z+#C~c%`fQG$($+r?6YQYd+Mozxg2{Ji174S0330JhTR$f}#G@rep+N*x2i}O2#LR!@*kuDW+ z&sg_YaNO?Q2tW{R6B7epQDwltZ;V-?d4}?Mi9I)B-!XErpZ?k91OEx~-%7m7%Zo7R z2Axjcmu9vjucZw0092g3xW9+DUGC;X4@gbqmtO#GGiF3yYS=L5S#eRKDXe1A@clh{ zG3$DmnwZE;bHL2u0eN(V&P8|Y{9Jr~7*tG?2gxXzAdw^;4-KfZVgOFv6g|Sf_uY56 zc5Ez68b%RXwUO#M7=%4q*tKmofaUJRdbq@#Xt$eh#;tt)HOwTrx%mA0>(YMSsue6b z_3A|rKV=5!3d)1QgQaa;MD;Xj0^pB}!(U_hz4&;uBQ_zy%xVAIZ)Q_O>(*dG9X%TN zTB{cGoXd1xd5)}8YpgX;N={@H$K*%!EmIDJ-5#F2kM+;xeQ6o|_Fxb9?;mMj&+nk~ zi~-;e@+&g=Y-&H9_uh!M4FoVj^>*ky!{z4X)AbWhYy8VEa8`?nJthVd_tB%F19Y9s z?sW4LBX#~(F)K9i(P&&wcK$@k2v2CnVl%7S=Ktf1h5udUzXkY0bRF8Z(6}wpG21)l zMl7)flb~3FmfKwXbayz+iZ3>6?p`kdfGC*^ZYb7m#x(K$Pw7W`_|I= zt4k3bq^fW}4@!ZF>Wjytx1G-i=eVkZ)i zYoC*uwbx#It>3B`&z}XseGfjWtfs53BKqyoZsR_wzeP`t2=V8^>oCM8{9Vg=qL#Wg z=bo!Viywci!c%9Tox*8o2EP1~Xu@50Tdb=3y?LQ>pH98d`oq}OeVbaD+LW#J0LXf?xir=rQipcLzG;O}j zr?Pw^MM0`QRq4oI)h^7Qpkp~ddp0GyPQ89sh&~8gv~(%aV^>}v1_>4`2*@jHWFKm|RC@vdUM8%2o17p4hCX>vvz{B$^10pW0>gwh5$ zolF$DRsm56ng@3*)|F}EEwW1Self#zJ$Df%C3Pd(d{$NZ&9_G4v-@W&k1+z1o-y39 z)a8S#6X~M|4A$LmOvJ1KCOvvWi2iZ1`?W(Q&Z^pYdZA%ZtT;&9Cst8RsB?Pmry*K8 z%p;|2hEhuQddD-nM>wucl)S-tgXj4x%nH}vbNnHi?Nj}P8^EceUc)&8T@&>1nyo92jHg=suPo=SKeBaJKEr9i~OLQuowRezU_*Y#FDx3@ z)xEkI*VRgz0N?GQjCdl2QJ6H_4AIz*R-$#`egx^7lCYAQ7D1ZO(@N^#wF$jl|3e#~ zk9&?z^6;^zG%E~uR>~TbQA1GN93B5A>K&UJH?(;$;6yba!KhE~y@S=!rg zD%#*54Bou}%OcyKoD(fQ%G-)LCS30eQcR@CNbuAOEW#uLxR+aCob4X_9Ox_20d`O6H`8gl^ z)e$_NsJwoT)fWMYjp+?bEE+V3!#ejJ!7BsVa&bX_-e>61gXnwV?%?%309b3w+&spCDl_T!d|AIqEpjkzIoD) zUp=ETT2N#=A3|921H*`q`lkeoK=g$2nHa9%`M* zg-y=5bfhRqpFC{Qlh?BPWDUx4E(Xh$_uuFLaF;I0_cb)|@zPRGnap}ADk zNeLSmuij8P_U>h!myR8|V!3^L&OCYG0e&4>Q1#1SHr{RNi6=N~s(pJlw1&aP&oDT) zy&M(vy%D7Kr4>|E#H$f!18uKFK#v}5%$F}$gn8N({0P6IC|oGY*7 zJbszsGGs{O-LMXpUAs7}BNZ-3k5&a_)22DnDzjwY3eL1jsc`9>gk|!8NH+Y9CNy{^ zfFxB=d5hPtXfmS>em-z+r0yqLdvULpVM3rI&aD>Ck}<=IGI^@|lS*zECQeef#py zK7IIS|NeY_UAnNgj!b7f;RLsgf-K&WtCmww<-WIa@)PgZx` zrH;wR|Lt#TQuO&)x}jORMrC04Zcb&DhQEJ*H6EwlehN z0DGm`5{YmDRfi7B=mV@&nJueUu_2V*s;;<#kH7aG3&a%{^Zi4Hcq)?9jOWH1`E|N= z<1rm^1Wz8t#j1gF&?_kYks{T0$tz_vzDBv-9@tS%aR44eP8~{5Zd#`x9*1 z#Ku-mph9rv?u;4A+du9&C6C;a?A}du+igk?Lyqa{t23;cEQ>Z*g=kT`CMsM?!*7~N z@qOFx&(846u<3~>>KJ~GXoFuU#6QGQ)6;qos))xK`l&O6^!Qa4tzNAPvkqnwkbP@s z%}Tycwm$6Np9`^a@j#z?N*T)z9oX<4d1P))uVptenOZ2dYPM|Qc)4siGGIWO1|l9_ zd4-L*&&S5TT{|VpCPN&um7|nn9yrilq%D7!DUdyS@V1{v(S!FXr0j!fvWC1^D@=UmXGzI~aw_aG0p5 zC}n)#mRi=$sA#KUw81YRzMkl=%1ju1!=SI9VF9kFBW==~mtODV3f;(SxlaJ=*74ho z9GUw5i4&D4nC-Hkh{HFhoZ{{=3#68#$i$UbDnrz%lZtom-OJ760k%6mdn!reOzhmL zH0x!UrM#Rcj>8V)NuWaqZc+Kb102T>1l)29&Tx-h1sr#r3jLgWt~-47{`*8@$Et~C z$r7Fn#*9&~dHU&muJW~yK05bSflX!aUZUG?cgss(cp+zr?YTZg%X%rVzFFE2N^jrq zPm%>meE!SIn)f8zINIPB2ru7exr%ubafk8a-Kmg{w8@>zEPDUkmmP z$2%5dqx_>Er5@jsC6tI?Uv*V(=Vn>zl%z~>Ai%~hTN)bJ;q&>}7@u;A+CYv(Sjkd` zB|3CaJ%lr1+Z<~zDpDFi!-grz<1StJ=jE4kh(&h4>eb8L%v=86t()rdB-`b4PkPwh(N6)8#6Al?@%a%Nx(AN~{88b!tTkH(-gzbLscK zm^znUHvUefcfM;E8=`>&Ic%Ei#^S_@Y`Bg-nhl!}TnU;ByLYnzl^*C#H>vwf0 z`o+aW%a&#Ly6?P030g6{t+Yi{N(0t`}X`E zPGT|cq$NW*XPm(zaW~zhy!(<8);N+AO22;DXE`+otNviot3^uKti_v(TNY85E=g6* z_2m`X=r6LxkM4u>Qh%Yxj8Te|Z@!t^sebZ_GGx*)1KD}vPCosV4XtcW;>{s{^iejn#l^f3 zdg!6-UiZ82*sGQkhH3I@aOVyr(Tm?MvK=S+6)e+ru z51*6lXS-^ZDvpvX2N_C|&FLeN+^$T1FkR7_HKcD!v@_R_bcmiSS8zTHwT_h3k|3XoC=(Lj)vT+Y?2-nNAkdaC7nsxR1I|4NCF!*$o?KCG%Le*VcP zv&=BS-Jf#Zm|U?!HOKDRlbg*rdF?fx5Tu8F*In7a_M?yT>&oX=R&qtE3>V3`_P%{Y z|M-Ur??}Z;=fBc4S=PXr$M22nOLpzzWRpOEZ`WSS8AXPn#?ra7dXGMRh~9oXx9ip@ z7Vi^H=;@ZQXp$3hkmI1LDx$J7ip5tKy4P*7A;h9=`rs6)IVl(!Rg%zT8jeFMm;X;LJ0V zLrfoi#4&K01yfy}eg6N34XSEZ2oCqmpU;^zhQY@M4dU?1o;^gDUdoS^89Uw{y2l<% z^s8T~zkBscFKMuOGl!FeU;{sMrV2O7)r3>WfBJM@B^)fZ&nexa??sS4z9yWNQfG^j zPEbzMWVFH02ZoVs?6WOAX-?8q0mls9@V%{f*d815e>^2Tz>gpDj5qAojA@t` zPI{jkZs5}$JC;3l8A54_g5zbEDZ`h_i{HN8-FW<>i?ZMNtgq)uLe9g%Ag70(eKsW) zVu1i3vu&237%+hE^ZVU(2l6#$%ut)drpXn+>3H{D)o7-)RAu+{?CEZ=2=JarO-=6C zk1UH~cZBGf>n*yiI7PFbW)gEdC<Mv8leN?LUS6H>e9t*2_n}52T)8U*8&GfFI1%gVR8}hE zSXt?A=F%81y~HaK8A_Qxo%aP~7cGF>{_Wk%?{)39{8;IQJH2s$H-BZ38^C$~nI^lJ zUgGBf?CE#!&aeNAU$_gx0M-r4y1v1(DC$>Aq<=groUF>KIpoj=KVJ+Q#B2XSgYrF+ z^mvxkyPvmc<>~IQPq<%*{yxK^eX~QfquAa2;)8+X>Hbpp<6jdVso@#biBQPewYd+m zww6OThQV>|R1yo(D5sK2!+7ecjY}~&*}k2#W#seA%D9@gyqpqYpVCrp+D*h0kKA-M zP2TYJdi#?mxmyG-T$n!dDHh|+Vkre7D}qlvQ8hl1uid#b?_s1RE<^mr5O*UT`;G$f z=rt{hHu##%qzL;sHR`YH$YGzDcLQ1oC3xlNa#Y*Cm%Fmk=cA9uR};XYil(SWu3xV< zR3}VG{~B}Ws-c~50vqydiN!c(*9m8NlK6fs^e|%&CtUEs#^MDQL98 z*W}E+-&l$8&WisCanD}wCUo!K>IsfXV@tVPJ6+!Xr)xEx1a1o66yx*43(8}@|Niuk zd-`cMlF}>RxG}f)dFw6ZX&VL`+jZ;McuQk@)>%sXf89E@0W6Ka%({`@z7$WB63mxf z=II^ap|+L{yx*@jh)+G0D|wwOkwAdx#W{TK-w#_f??`tun-ONn=Dm0B zoShVdlf8R+&q1E**s-dwtekYZcPCoCnjasHvVM-7XoOJt{qokWo7?Dj?aF!knF`## z_<}=2P6NMiAx}!(yC?Vbz2-+@ilpkarD-#0gRjY%Sd8Pyg9j5$L0I*ym6m7Hq?FIw zd%jyM$oc#BV@D@RL?jBs{6VT;mAX3EiER^|cODO+cW>TAO~>b-E9ruE?Q+uxlJE8K z!z#`6h$DECS-o1t*o9!tAZfHe`^>#zTUzSQ(Kk&sVaN^Hks}+=w_m$fNk0Qbca(-{ z>);AnQKEY1Ho&C1IXX_?*3kxE(Jt|{@P#tJjx z;a3f@=(EpqKS#}>gEsh@+_5bB?4l4oiSZP58t@EN!ghtbl^_9GwYQU-y?;K(qPaan zE|2wuprE_LWzv;xF4K zdgKvRj1>s*%D^kpU>LkVAy)z;MyMt$NjN4}0w@a5JXBHGtfD&j6W;#s`-ExpSydEs zHWYWZCDdV`LlSN9H7;UhWkfz7MUEaso6oAEdLuy5c%|(Wgy{uTP|UkQ+ej#fh>{FZ zlbc&OCV}16p(JI{Uv%NL(U{=Ydndu7iV}+&e&4tOlPwtm4p}uNMRe;{m4hD$aG1!p zS(-uW~GS5(tJ^Dx?n04>5KI_)%fg|NKMoXHbJ&z^kAr%v^Rc`S=;VR$@z zK?e|U>CHF5NC@`X03CpzuJ0U<@0l3!MkEGB13}tyOPF^3XBF?iyrCz6A3ECLYZ5fX zD`oA3v4G1+)WerJ)+E8ViV6;1H&-Vkr!;hNke1(U(Zk2O3%wTlt1=40d0D<(rA=T06*En;5d+DGn`D5XOF5X{(r@15*r}f@23OzhRH4tk{#E1 zio!@aG1Q~Tm6c@!ymZk<{|A9K_!>o7S+e&o8%xX760a0wAvTcqZ2rcImG;l?jd-e50s8*8938Q685yOu!e+3bGaqVxM%G!Gnyj|sQ@ zfwNu!APSAM=-(r%Xe~~3O-3IMokZ&vSoF@XLo}`{8~%$g=Je2JC)*1zNdN!~rAb6V zR70~HO<|%9zD6T)#IWsPa;<^9J&EzI5XwK{mV8cU^gn;ZqQ^S2L63S2y5zARJ6a2- zXzTa#%S5NQv*-W`8B35>9OTMg=#D-&5kww4s3mlU}ptPb!oXD+;7fXS7&8q5%fkzM_=g zbHjgyT-h^Dga0}Dy0WS2QAAS^=IovLv4|+522n&Y2p)?z`fY}64ZZ=5rVa2}^#ZI9 zJp%$j00aPG7{G0}0o%4=#Db}~YxO9c>3apU>A$e__)aeenZCpr6YuTw z;jr6pfMFVmvHL^}GkQIVA~f*10Pt}z3I+(Gp&pCJEXI^6!1D165bN9(}U>>Sy3c^XDD>~{ZEwgZl zfh;|IU%n?Cjix2p|KpJ;U-xeS>;)45F?={MemqcKp5%=W7yvB0dKLV)v)6756S(|x z;D#F#k9qUXRT$pD_nRglF1mz0`xLL|qP!ebU=x^zi;$o9jBVgO7O88$>9 z0Ni@3dd;a*fx&};Rjbr{4IT_EUJL;MLx%#>rvnWQKv5BXHg7U2?z|P)z~_$m`P-j; z265@7AQ%vSAH+o$0h1?Z9=qnyAe&jCu^WJEz@MeA@xKLtdjV_!@Bx5f*}RVS@HNfJ z*Zs?qHbApUHGK2pFx8`ojrRL2G&VLWn*9Dgb=xI6M}>QSsYI0Q2KNHJVnV^QLzIDDM_R0QcX| zo^l#?KVO5v3unMU42I7D=FSC1jlx$;YtZ?e(=h=NRQmid@0$y;yS8z!-a}W^A_{^J zHmI%+V)0`2{8g*qvm-EJgGd0iwYi`4s8R0m#LrdScq6c94`ADT9c&vm_}UmCAQIt~ zgZA>(PzhjheDZk{Ku00O;mz<~8co*th7WTe7%?KFu?K(`XRV5D zU4Jyx+ZI3bv&mq_MW!)~?-2648o%;;Ow-jxKfG?DGE&{q<>Db?hAD$DqFYLH1m8>m{(Gia8-;u{qU#^DnlCg>#guf5m)oXLI8>8>JNZs53SZN zD=xBdNUX!P1GM8W&#c-+EAH+scO_eHMNhY3bWQO$_Lk0!U!Sh;s7#GI8LW-?@ln3< z^4vOYTO(dU-=iNRq4Qu`MH08~) zur;v<=WCM)(of#n7!}5L-tlD8vb_txfmxLFc4P9!$*Kr!;nU8PxY74j?UXHWBD{_o z|1-HL4c$k3%sh%zw+8=B#ezG)BI?IcK?0a2K=(l$u1_(e9-WDyhIAMdqk9@6bBk1v zsn&9NYXV{q$n(*ld;4?z^8R}4EySmgA$vZdzt*lXTPZ%`Gu(4Hl8*>uE&fLWfy z;79BIkoA$NF*p%V945!XdZzzyYnQG+cOlT|vq9bUd<)FjnzX=7f}AUJ&`*rpFNr-; z-m6sHiU^puCBwaDaIL2$BC!`#jDkXL*@MTv9VvezLs!0G}Eo{?hwpd z+s(f7wg<^Bd@0+mmh#@fZG zOMKB*^YJR@HgL-9y7r-ogmW#=VRpF8@t^dDei{~`mm}s2ZnNg60u*Sv;EFyiIarIA zcwXsW3GvvCD3UG}OTjPiYxfkk>)ySKF*!J#qjO(rqQin)3V7*K#hDTooxVd8GobQH*Abk`_4U2Y)kj!aRx4^1X=x^j>yGM9|VbXUT6uQG#yg~(%5*3WJP=*X)~?`vdM+*hm{MNus+ zM6NeU2RcT8d{bys4x(^Kq;b&x8ip!qyyx z+w?!>cWp1=QG|`4rmNE!M@)KtiyYH{n_p|hqT!W6U=utM`9_eNXcl&=VRu9H#mU%j z*fHhmraG|bp?z=WH~7aPuLF=A11i5CA3qd0TEE+g+&`#!WX6K8c3iH_ewFr@Aikr> zqXKU3Qnh={`dB!#KipcnOJ0dDWr?j)WPALZ8x^q!r|A7huHJdlEQGV22- z(MZ@b>uue-+Uh5u>`XZwzeTI3w1wDykccj8RZi`3AwVMv_g)JTk8}y0oAj>D0i%AV znQq6a!BgTNR@9`Hg(88+f_c;go=XzW!xN`80(aDH zg1=FlQ6`jtDYg`aqYvP}5{3Y$RJq+8$Ga}h2^h+9*eP2p^Ix(E{dC!r89xEgmQ8Qa zfy^;G^vmvlp~`6B5lBbN&T#LklVRJ0i#4&`;U(w=#EL8(Wh$7G{eBE2T6%<5&QFP> z`EM>8H(dTV3?R7ipLvg<;=eKvq27}ICIjR-?EitrGHI7MY&P>XY5*W3XiF%&p2a=+ EClb+IhyVZp literal 0 HcmV?d00001 diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png b/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png new file mode 100644 index 0000000000000000000000000000000000000000..018ca9d92bc93c8b9adca7902bc730b0bbe891e7 GIT binary patch literal 31076 zcmZ^Kbx@mK_$6+oP@LlKS|}2%IE3Qv?(W6i-CNv(ySvli?(Xgsx6Sw4+1dSPGxJW8 zH*fA-J@+~1IX6NW9h-a-&*AEG; zX%hRZXc`o!Ut+rKWM_7hF5TTiW#;B)%ON41?x(l>Z(~1Q<=tInC$&}WJHs$BP!WQ9 zrygqC+F>9c42}q*d${pYLwy4=9{>A6o(*QxfDQi{Sz?P26+u*}7s>m-r)cp5?2i)Y zKr_Hn>UG_?Dhc|=MkQdfQtd@mRNkc_Tvwiq0x&B-*;ARmQHlPpRO!SFH1~I1xB7q% zL_-I=%Be&-I=i|}yxoE52L zMY-j)WrN|NB<4hML+$`m^PPFtdv~3+*6d=(};vL=)ddI-?b`P1t^_lmb@x#HTOhJd+5cD z=z``{fu)B5DLqfXQuU1aOMcLtXk|k$6lhLASt*AOB&Y<`ElsW~@M%&y@dVA`0ZX5H zw#U2LW0X!bL32)^IVRBD-pto9*jKMFALNGiq;k)E^$c zJhos-=s*{bXvBP$fwG3x*-h{p78R}wxdWal;(jpTVY+V#8VxQLb~EDs1LqND3AO|( z8vz%p0GhA`^EWZEHFPyhn#AEVE*mKi)rt^wOTDImt^r03))!dJp0pk`YVa7mM8gaM zI#grNa}T$FnmA&y~28<^qFo9x#0&1Ed`_49>><-#M3OOpO^`Q6gSjtwR`QN1hU~ww!gkpd7{8Q-Qo(W)SVYoL1g?;rl$!8xT%B#;=<9Izql^R(#80U!i zs7x%&%{6;(1_rg^!Q=P#nm13~)R(8)j~&AQd>IWK3Spjr^mjO(2Q^Ow7sihDlga^* zk;cAK-s&o$w3tvk`Z_{Oy;v?D_b=n3a@j|*?otLra~UYm1QToT#`*%I9X^DzCH4<> z2MaW33@klgbchQTjD<|@37SuwFyIti1`roiDD0n-Bdi9kf}W|w2U6Hgn83kdQ4Pm5|p~{-p<5Hayh6nUjz?**#l%Mwa9YKJsOjUD2_!;)O{<@DJ45|vS zQe8>S^UP?=e*D7J2cs2Gwu_3vi@#pm6_q`V|I7|qs{kB~CsNPpdwF1~Xo`{}Xl|j$ zrw21K@J4Wp0yIYhEG6$*rY`ot=+poRKKl~zV79mum;J-6(V=%0Zcwmc1i7gJad0C( zKH02G$Yfgfjg(}hSw zq*rkk45`QGfK=Bbm4lEr{QIcc?El9fa=ohH+hx$hU4+4l)iI>Y( zNwQLPg_C5drIZM>NS1Tp=ECo70=q5?;MW}*P>yH}8p1o;(Oi-JDgD>;t$m=^Lb>qZ zA0_{36(@VzelC6?tl`kQs*0UH5?^%p2lWU|7uZb|Tzu_0?Xm888}H)7l*+?1t`@5% z=9GA-!{;GbZ^|iH{l|Uu(FmUzmQCz~e1@Lc8tO^#%mW;t`oWIB01r~Zd_;ZB4u36< zs(NzY(#2@4V5~Af(*BLn)mw9siQKXFr%#Xm?oA5bMBEof5*FQU;SSY@5UaZ1Km##Z zi4+EfrznZ_J5uFAsaUl~COw5S-&1<1V5H(P{{KK}i3i|)wG#z2*Y};&R0Z%KK->TS0UGk` zTd*A7qhj#DL$cB(BZx)kmivF;{;Nw_Puz{0oP;Fr8pdO-k`;KOqbM)TX^8wwRIlf0 zFFc-$yDelBkT#FIdVtx$OL$TYU-g>q%|Z1^HXSv%hAtSg)fuicmZ&v=u2}l`Vsh}4 z3Mu~Cb8p4^=@RXw{#z2WFMCEv1lC5&Xy2*fMNSt=ed6zt_JYoM zP=tamc<6#~La~WjrAPSCUDp@&bEGPR7_c0uUty9q$|y*l!*^@0Sid&CDn>@OYC7mj z6_cl&#ICaAKVz?7Se7Rfz(zyk16+;>V!8ggG@eVC>@S$5fCTG)HThfF>8G2|Nh)D#w z`*V$z&(v~EgVfjbmh})s)n}GrK1>bxKyzFc!hV>5?fSgn4;wF}Rn|;o|20>(=`WQbBhzWkM|8bl!n3#l=`Rj>(Y2MWDY6(EQXd* z3W%nCQdy|u_?wpdZ7vCck3OJ|I!9_G?BUnVej3I0ZMKwbO!#4nu6asbw%jeiD_iOt zz0oQrP14P>X!fhMOUz!a_z$NgCl7I1P3=lDdP%#J;jf!_g&Q-bzD)FfFCnxKZzEVj z*~uMs)Q432jludsG%$fzrAJy5@|GWD=O@1n`S1A@-7jQX4FP~V$J&A`RWH2`sbxk&=}Vx|2>84y`g zfCWvBCc~gv2J{Er1RTqsl!I5WE(6W8hM~Wbpb+s%-9MR5IRyobPM@StJ+;`2Xcv5= z`&LS4vZ<)5OOJE<7Y<_xUlXNU4xQJl0`?u&^S*MeApKoa7uWHoy0|*|{#6Q8qc?Kn zN7`=VVnWa;U)J%q;f+-!ABI6`F!sC3S|%ufq{d=(^NC7bn%YssX+@%`jezFo4{;cy z7nR6!=%$}(r93R&-(&^R7kbeQC%}=`>kk;L?L2Yf#6gc|U1O&E#e?G0Y=^tDOqckt zrD**_HF}sNrHiH>quc3095!{x(QoEBZn+^V+DYFA!az$VSd~UvAEwPq7}#*yw#-ag za2a+e=mK-K#9%7`^o*qn!{9SYi*R$wISavwOflxzqHQN9na1V zR(^QWqU#@Cth-)Bhw<;H3up-aZBwb1Kh$mCI<0yTaXHo3)ss}(^C`Sf4KvKSPpB@^y zPLi8QHnlXrX%-nVmMo_?TjMucDEeS*= zhOt#Sc4?1iU4PE%sisF!uC-Ec9?GNEe|Dm5tw8t zis>6t-#w{>0N6Y0e_3c)XvFL&b}UQjaaSpc@}yTL*FM>MSc9><^Fm%X16UN!@^rD` zu%oHGVe>=AFF1T*9d)J`+>u$*XxddI3Y2N;6)ORpm;ABBd&8D|zoy6fQ~zoxy*p;p ze!Lb--6O~!^Cl6}8>pjdV6v=9x^Z?f$JL_Fs_3mr z#Shs0q`}pnY01SAofejjwk>sj@{n0Z zr4M*|=4XLR@>(Qd|9q9-!`!76uz%S;KXkrY*=o#_+n0n9)LEn{7L=7Nl({!dDLJ2t z{GvdwdEK6VuPrPN4xNNFw8rQSrX1GXBh)tp^cP1 z3A80F)*t*pUpd=9ZO0Xt9!`pFHMj+`g6k349gq1#iPRLW<^_OQQdTA1&J#dPvAJN# z#9`68wdvrc=a#+6(R73A79nGn9aXa)?o8(3&b1j zL2Al(c2&<=>cKMcDdA3P>vm8`S8%u=S?nPFvtZig<;^9t!HJ|eRv&Mg>C#>ewzf~E z=@y~g1AydvbBASVMI|^{<188Aiu02fu}F#S%cIP6~qTy3d04DPPTMXjyAG6 z&MN8X&ROSS;#Gqw+D^Sp*60Ye0it-)BrPig_hm4`S)Zoa#J~f2Etp02uEE@VXwu1p zOnG>CGP?iIDVENm!Q=$KIh!bWCRH!5yvg@_-$TPZ5KRWgOZ8LMKF8gVfc_M*x;nRy zy=%eBm4|%l_!ZUV5k?oO{78vhh(#}dOX`_95EjMh5CWBf zy+_lY*3_JE$DEtephvWxBFkS30ig)VQjSGjzu4{*)ghbJ;*0mMjL~NJxqNXAM?z#M z8>Pz);j?xARzhMUI|)9=uc+reNUs+ZSrTXX!e5LAjmk@$H=YX?G9_y?dC2+WMvMv@_OG>ASqx z5T)bbr0|r`2r~mM<&T;g-191?zWUwaSZ(m*vj+;eFNa+9e1(e<(ARg~gvXsz2#Pri~uM0qbl8~b6i4-sJ z88zHU1p0a_;Xn(j%?O)D`)=0ULx4rMg+&ejXt0Bf4vUIa=iG@(Ydxrl zpCtfRqZiB)EA+Qja*M0sh|lh8!nrp~A=B?i(?5S-?7Rw9`i?HXFg?9-Hjy0Mce#Cc zVU*Z%$2;Z>h%}UL1)7`EjLvZ5Vra38)tb4=nb(BM<$g=aufzORwuFo-FS-+9bhPs_ z>B#%R{~JSPJAA_APS`dykG4o^;uJpX2SC=n?b~<_qVA4!Wbfd+XIYe&m7}7D5gO})$&#lv z{wpcoslQ8HBn^FDUnJ)vSH(B1Q^@Z8CczcOFPM_sTdYV#BVV~!oFi*8C2cumQlpc$ z6c)9mwoboC;PdXf7h;q2`1?+h*gUZIt6CJKQUiUZETYH_KO*3y@dJr*DZasohTWqY zZW4_11tg-8r2vH^jcCeSMDM6AL&qH)vzf~RH;9B{F4OD&n)ip6&m?)Jy2heSP?1FiYknUD z@|#molU065h7{1Nwu^?gW=HT1gBsls7~TD~kFx{OAp(tTD_KO-LTr&!)-vc_9T;4R zq6SBd5KWtT%o-<*7*&A2|Et&N$IIU4r0jaK;K(Fqe0o}p;58HSrarCb0B*-yTM#tNTT8$^F zs1>!SqhfL$GcLP{$;9R6!R80M;V0L@u20rGWVNFf}}dsy26Q2g-|ngN|uYnK+2k>lFQ?& zKZz68Oy^2&bb3O*CZ66bJ4fNawlt06Z7#~`m165Se?BRQi*LV>@Zaissht>U(gcJ7&Abvl1kD$zc3OM z1O^HqBimxpG)KEiUESnZDpsu~LRoU#t5SX^tmN$&P?byu_u2#1U=sTi5mGErRJiw5 z%_Oc-h<>V%!utV{5c$D?@%UDjfHswbp3H@i$=6UEjt?k=w%F%u{Zqib(?7hsw z$E6+ZShQ;e%tZ2rPum5|$Y@o1`%jvGuJ`Qu7KUV_ZBZ5#Tl7fEndmY}7p0v%ZE6Ji z84U7G?-hV^yoO9P-+aBXm5W1!>heriFnBqB;=umwF3d zam(+_C^@AWNzO23`+gGnn3WgrQrJ&W?5@J6o7C?<5fErkBEjFAFC*5=ttg3ATh86i z>c-}4%siL+Eyd|-_RS?{3Wz{9e#?RH2`91jpwL&I9wJs% zW%pbVqFYIMaav&v{vuc{`4m#=(!iQJ?_%Q{D>vM7r6=&r;zG4d$p6RP$T3tg^}F?| z?P%GN+&_~YiSIXsWh}GhLK3b?@pjSF`})nNp8MrxcPsL@hl96N6;-L;hB>AYD(a)r z$k{pvoL&ciV|8uy0&^+oogYZF7b4dA8zfTE*2?(FqcNTZ5Gb#_=t$+KPBO`q4qqSU zu1#~skGcpobir)C-ik|j5=YFXyjrJHKs?C|UW8%=VLTZAtmY z{16ivf@I1kcH_~iKT)*QVUZHgKuByJv00Xqo4;&hE_<$!PjkB~?P1n=qH4ycq&OWQ z6qqLf*>JF~T}T#+;)iy@GM)3D;U=Q!c}-3GkU%7#>_>Sy^^fC9k?Q3!L9x?WZCQWi z^cD~Wz5QoKl8pYuwDZowfJcVqnH%oK)DV{mW9j#ibk|vMnl~*GPmOmGECr!WjoZ25 z5$6iSRZNPU`c9ihK+^yQ_BVTyTDH0|OLDQgyf8Miu{MvlR4qz@l-@-Dn!JFkXpUvP zC2*u6*f`!?wL8izdyEfS#nPOSDGY}Y?eEhKwXO8t3zN_ecrWwr(W=ylk=Q|78-LK2 zhi%>JOLNnLQ1fc`Kn{!aU)ZZC{R*E9{5BlOM*qdH0EmqX9eB>uk+BwI&)z;CtsW{U z0*EPd7+O3XQ!kSyJ5(%=ohF%Q{v*<4&{d|BrU4j#pDiM9#&)-T+!y&ldkaHBY8bV& z9oF3azRa{UVL9?SH&L4B#b$SUmC$mOGq=1+uyTfe*de990Z=@q1uk)Z=4#w8OQpFR zYJ0!PrcIPe)`m*4iE3Vx;j=2e&v@d>1gPDVq^in?l0ZYa*zYM6-H=nG!^Y>oYJp=J zi+kQ6v1mYXwX%8`2v}z>UOkr8Zg(gHGPt+lF=l$AGqzLS3j38AgZ@gwegjB|xwI~> zaV5_Xm+dT|H?q*Y|1MhHkMvqaff7cPONMK#xNq0VXBTUDE>*0EgZ%cQj6HFa)?MMn zl%ay+Iyzp_a$h8ZFG!qmJn3f^#36~bgyz8{Mt@G;fi~7TJ&4j6C`AunoMqPG-~|zV z-N}VZJ`Na=mUb@vdMNy3$1F^bTE(JjK9x^~J6VW7U+JI~$yzU#a!)MgCHKMfiD<;C zM8Y4+Q4C1jkVg|XyAjK9jjmzQINb^{3^O9u+Ln||ZMS{y#I3hjRc&Fp?%U%-3YX@j z!Gd%^cRa8*CF5^CKDbC!s<@Vc=;lr^U}@-8e4tMAy}B+|VUjY+DvJx1X<&2*z1%3R z=P)i6Hi;&$tBQl&?HS4}cvIXvv3!7HZq{x(l>i2iKM#;={@jVa`jD}~eZ02HXBBI7 z}Cv*iX(9;gT~%n`*!7f_22OU!7cNBp#p;J7p& z0iTtNZbleal!_^x;RrnuAd?US#P!%NP+)tNQrpYz!kN(dQHLduh#kSL-%CNIAHJn* zRqDLvXiDh|zmzvQdib-zaFZc0idFc26}{_8wq+}jr3*vU+yKs3eXDH=lXH0s?{+yo z9wk(cEX6445|_zML?J-~Jwx*ZvSmk;qHEhlL=N^eMNkvplj80pr9uTlY1YBD-fL0* zdx1K~d<2&6rYPAnfS5MY+;_YsDB1C>| zt&-#w3?AeqWFG7mX?oMwhe)Y{a3-h?#CxmBMo$iz3zv)v zCl&l7x=;`<072B8&688OgCa7f8os$?9??~!0f{C@0rhvNQb_=8;|X}6`|{2u70pk^ zz;XDHT5*|y4)m7}q^Ah%ym>mzaaVF}O9QEyPBYMw(6TWQi>k*16S{qsX7M)>hW52c zOib!Kew~T=b}6Syrh<@-0S4)1CH|76w(T|DTQEy@d?+VbYAB?7$aLvM zmX*y6FU3qRSCDF92u`lMJ4}C^;RPjKUuF0s0b39>zREYHDNT9#E&r zmCaVgG(Efn-9Gg%?Y}X^tMLuGzoRR2g}V%pj|hnwKnj;JW)CsM@7o)Gj>6OV!DE8d z+trW6(iI%)Q~sOXilDXzAMkX+&eENcLX+y!)1=rWTk|fF;2M8alJ%D@4?IDuvAjM_N=0c@hL}s2T+*{c>^N|ddj;lhhw0+h@xaOj~d<4iI zPh9PeBs;`n$ap+}-JX@db7%h4$TevVh)IFOYuratS(n}Di+ZaKt8EurTv2BDC^a`R zHZOl&jP}ya$Q`|XiE`xl)tQ{HmTlD)?6suutyGgx@Ew^-BzHZ>pRiHaA{SYoA?FKd6aYM$yadD?l*ns%Q+({~J4B8(?Lv7(xUk5mx=b!^y6~ znWtZE>MEN{O?&4pdo_d2#0j;=;{4U^N}o9^@L}0=Ir&gy%p7YQIHkIC}spW>V#r))|K%su0chOuDX={gPNTo z%kJ>csIISy!e%fEbzb&L-~^5plQZf$XgTokX8+1+o#m`?+l(sBPfx`hl^D1$bL(#b zy-=sne!21NF>6^-DB86_%gTj=bEGhe2~jJwK8@BbvHrD~jX$0>tRIhWzZ9mT>iH}9 zEH#%ay#KW+o%y{d`gkjL72|C5-=-R3%)WVb%Wb5E#shAfP|FVz0*VCtP^ zc_J;cToMpBE|9Z)nNQM0=sujOaZfkp1C>;V$&(J%z4_^yXr!mK7uDE4ZbE+VEbr77 zS_Xu?Ii;4RGZ+QPZ#X?3Z=sUX}HC-@4uw#vSBx{#Hyu11GKjyTL^X!9yJo-%adLoCE zdz#O-VJleQ<`(-|Nh>H=1OxWjeB)5N(78MG#EEh;o$y;dLUqvI_0&Ux;^O+Reua|x z|H)(d?fdQo>>V<#D(*C^iJK6v&idoa6tK3W_r<83n6}lV-G7w z8>+GSs&i+gh)*hpkSF$g=W0~yHwiZKEZgPnvJZ<~ARUboRNmzMhik-O19ilN+L`kV znQm&y?566-VSaK{9ocpC1Q{rK@-D2k!&f6xm(*RFziO0u6p}q}fl^u9Hx@T-j&s5Y z7|0sjeP>^we(2{s;Y1vM86XNvXfASHRpHh89Y#)p$-H#ZgAAWygrre9ILJy}*MLk& zP)l9-C0&?+aFx2y7!fqAe;ofnsOXYtoSG*d-E%3WgC`T1zb}kG^SG?;eLwO|gt6#w z=`XWTUEm&r^k)QZxJ=e56zva%E-rihbI#s`TR{L_&&6{ z&6~1x{Mjgh?fng!B?3i?UlF_LgMXH~+n(SwIiKy#ho60L!WGU zDzWEXnW<0*&p5hr&xPeLtu*b}e!1@O*epG!RYMz<`$?nactuNQn`TS$eAB&a0vjFa zcf3OjNh;8fK1>;6)t_E1016pG>pr-?Kk_MI`oDP;wI3@!m13WuCm~I~QZpdMJMJo+ z0*u)za3Ik#)iEanuIP<;yWvY5_cs7)BmKc~aT=?_oq2l9jC$2vSqccfg=zi!_-HM5 zZCd@SS*TjUo&!EH@{IsR9&^Ctgno++ClqE>qeC-OjwNk-3G9r9F%i`vmOGK}n}wEs zv)C1hi>V4%JKfJ_qSDiTwaQPkXpGjli3V9+nacApDDdO+f?Dvw+4b9Gf z$E0g7bsp1Iob?sn$hrP!kHP7M=DdWNzi{pWQBv0a`fc^NEnd$W|EKo7@mGLiy7Q#8 z;ky)%T{x=6} z1TSQ~@DPz8-!KAke^i?5Hm#Nnh=@PUWgi)-gK8%hJa2#RvK?GBbeX9tN_IU(95>GD z5(;-sczgYEYhpOMgdHUpvjmsBekVCPdXzurblcm*3Fg}Nijp#`Kj6Nkf-H78D&R+a zztOOn*HtB>-@+5R10&^~X7B(Y?rrf)>;&1tV6S+7zkN8{7EA_O`+)U}D z4ExUO4tRb!oF|d_^CRLMGtaNopK><^XxlF2&h;HQT~K5AE)eV|Y|<^!9?yg{g6UR6 zrIS1*v?b;AKCx!}O_g64_CBc`@=;c#kx@IG!tIn-xAhST(^t-qLg=(um2MlZt}4g* z@V9z;J=`6PqouC4v4lvAJFo)0t}m*thuw`Mc*6SY))kM}ki0yzu(*=bq+1V6NuK$Z z$4p72VTd^WFisz$w%Q~InFVgQWLf#Rb0e;S3nYC4sI4@7L zN`cpl1{#HseC);MrfswtQ6w<`;&t1RC4(r5#!bpm<-JpSf0&7hgW{5}g{295JP3on ziZO)zAE$Y7(WAi1Fr&8>?m{Ln4XGWXF`O^$m*5#}1T_`De<0?B@kFl?)9X9*I@rNq z^r=eWb>Y-R6Mj@}Y7rOS^`s#6ZX~TpjJ-~hWg%G-LdKEjU{j1>5!C6Y6fZ57P?6W{ zD4HIQ`tVB8T(16fh|E&psJpX+XB^K6kkd~er%+Wb@yxN6QTj^vqb;I%+Lwuh01nt#es-o{2Lc0>f$Q1M~>tq(R=tq7{`?U)-91OqwseN<5^{q-o1 zOQu!cuvo4=J97!>6eLMu8P)s3F=VHaM%ns0H|t(8n(=3m$&mhlNxTmqFKdTe1(sI% zQYa40e(gP461`3nFDcuJ%Vt@r@DT?O|C*m3V@&Up-quBoE)sk;PYru-2Kd3_U?(M2)mI2z7&WrzD3F zoI<*i+}1evs_V#$Z;ENsZu#T1dh^Zz&i&Wo42-xu)xN{}XwPGtEN?^wAVzLDM!sjn z)!NA(XTW(pcqTSVz&4>Z&FH_P%ur8$8~YD!i^EL-%FkPWd@`wLA{I)xelh*SH*6bu zV-ez!#6DW1CHPS+!w*E*C{z=}Fu2RMs4T_4%;JssLO2`-K=@dB4?``7$Ry@$-aHC( zyWE34_LMPpsSs+nbk!#F`$`Ar7$ap#8cZd`-4Nj}WL-4@9iP4LFptostQjUAE-tk+ zg@i?epSLLoS%#=5CrFC2p08Z8()F5s=@I;nmZ{R{m;?AO9sxYQsNLd75W zDEC$~eGzHYIaMP2-uK|`#!8wz0-~W8aYA2XM`H^JnP6d$L{rzwGR9yCnO`*vOR(*7 zJ%;Pktas5{Mv+UAH9jEw?<#Ex*#GSR3@8l__Z}_Cc zS%l`*^mUqWAv?t0dp`M38F#sJI>amGD+JB>hpeYak;u*~H}P49Ha+1TU?B0B6>xeI zk8mWU>n~z>JXM$5Y5K58`Fy#3rLj*H&L>sUX~aurEAcP15z^)%Av>r@vtF2$b~Vp5 zKyh@RlwZ^6EUVhLlWoTV{p*C&tg26STvpip*TH%@?Y9#X-Fmc!kabwYq$dpz@n5Kn z(Ts(Zko5pwY);I^2X762RpBSxj5xY3sWSf>BtW$eI?bnIx`w7l@tsdC+!y$xf|3Gs z92kgzLzl$RBlNCVW+@BmSjzbLNF5)l`zM?ReXE1e!KO^=zNo9EyC4(N^&hNrje6o` z1yLZ5ND%w-ob*bD=NSjtyvAvvNocPj8StTDC;H$E+gl*!grwMDY93-MdJq75)P6t;NfShPt0M%Q2mX=UHpd(FW|}DRP(82^rI`y>^O~$ha)CSzl&HK2I3dA zU(6V|XFU7{=*VJ5u0it0G#?2gy{KC~w}4D2iz3 z%Qi(W>BBejzp(wJfuW*@wuY$c`7c$dw_w_I@A&}I(55jg!^jFQwI@1Z>+`9;k#!m? z_7{bp6tF$bUGty0H`pPJW*BZ#Fid1b4Xnyk^x-ctMF>Dy9Gu{`f`taE0Gj6c@T}D( z3paR~Gs8QGOpVH`!)nbjBPr~8UjbYZl&{A&qLl0+NQA9>%FIJJAr?(-&P)xO;Ub#2 z?8r4#R>Gi~UB@iUZ_$b1HE-wUbx$vLH30GW(R7KFF06s2zHqLI=eqLkDuE|!N{U7> z#DIbQZ)0%fy8&b$H7*BsgKbcdmMfvDI_=^e2iq}Dlv*P}Phm7iv|K{Gt*Y2L!qUaT>*}e^5uRy=fFbXlT zk-Go{QN$Vun(`TbXJ&)Z@KMZC9!aKOio$~#WTPQx^8-^p-M?_e|1fu3JtoC+AlatMm8SK+Ei=bI zkJOcv;1U{Bx!Jz+2-}8xrO}um8hx6r2fBY_`P9KV}7~c#Z0oea|y!5FRP)e zA~r6OI?$;6ZT-=qykrkojpGCgxo@BPv*(iHp{Nt3!six%1^ZGY)X+c?f#K9IRAGrk zO%*EAPs3cEG+SPD2SvV2w|j&f|%~V?(0yWE{pNmpdd`&=AAVS zTC!N0>@DJO@>Mi6eseh;-%Pp zBqx~s8TKgc1`lao`kw$wVSWTx4@YmQM`*b{i6u5T$x6ol>` z*5&%E3xL1ohhI23u?3#OZ9;7cr}A(l*3%dG%80IfjAHvWKct-1P=<;|N5DdQzBX%) zE#HzP;CP0Fy-E2l*lyx1Fj_tu)#2^jrA`&i;D$+5)=-WsZJl1d++IW8SEf&Px(ZBuJ{hP`%@frWvGRJn zneEO9;DFNuHH=TLlFqBrU)8+12h~W;dEM$*(pvgo>A#v>V&BVXa(RxMK9N`oZgPd( zDW&R8mQ&z92D679cMmD(qYHIaqVNF@FCQjrmW%D3F8IuknlgBkdLk_k(}U4^K=;y( zok7RKoOTKkBH#{IVhyC+o$Id3etS8HXy^hluI&vTY;xe%iUL-xeMhSdVqpH?jKb0H zr~rP4#g+dju>cVsH^P*ryJdS>+P@Ha5#0;4X~HSMB3PKm8pmp?wwP!k<>Iy`Rv&Aq zDizIGy2*hI%(n#B*_UGbd(}aA?&XoDl*NT#mqox%TZI@yExfYCLzDKh&I4RE$Cdk8 zLpX>noLqso-q@&UIg}7-Im8H&LNH9Fg^o;5>HZCe<;j$j+AE>wFv&}|s*Q0lq$Ros zOhLAIg6HJdtJeet$xr zM~Q77#wy_uf6nLq^_sa{$Z8P3tZ)0w17BIDSzUNWv6Y`V$>BejJ~6-Q`lzH#$!ml0 zrPj9cW5aFr+xpuF0&2om8OvN$b77c$9NOlsSfaF#AH0AiVrs~wSDkn3&}%#YFt0R3 zY=(GH_>klXhMUw=2O&rM zZM*!X>qU>NPfJeZ-(e_T2KhAu^t2&p<1{*)z2+1()OqN6GjT*v>NS@{rV-Y35x(iN z#D<*zG8_cK7Zqx2@euQxZbfCvJdocgQR*IA#l`Kj_ex2>eRYix_AkVx3e6|EWY(35 zVp67+$ioQxQ}LB4$A6++zTQbS=)w?5DGXPx^Pb$M+`w91Q)Zvp72n!0;~GqxBo~c4 zQ%j8}KQcBd;IW61U|xN_*SKrF_n%AnlsVyHV|I15+2iKPH+7`Wm#@%PV7s6?0Ogb5ncz(4U{eg3afDgeM z{NH%C&B{lFEr&-W2+N>;FuF|pqC{0U1)Bw&)H~Drty|f5Tv`~dhH@hMeQ@E=t^B@8V*N; zjyr8-E=r6G6Mpa2jPU(^4?ct#Vr2BH=cM%R&X?uVkX~aqJUe@;OQ+G*sF2h=dMLIr zR+>0Vg6DSsy-)l4TvIT7ztP7O$LOjyE|Es82!%1<@zfn%)%x7~EvN<9^V{+z z{+DJR;^xd(DEFL`_*66ET8qadvhG>l6li(%)M7>;dhh79(U)teT0PFiQV0ux*KdgL za%F(mhIKz0bR2bjyx_I$%7E!g3Dq3D5txuabrw`(T0KZU>e!5^x}8@K=9Ys{51-0k zL^QHSz1@Zxbh}zPXxU9P`QmG9$(AME8@;%3>yai!`PmoXs21B}oHnb|J4$bigcYsp zh||)&lcHI8fdW&Bm$%raD$RtF~jq$MMmpuLEEWFfrnyPS7vSIS#v3qNJ76vpL=5 z1w>D^bwK*UPDg`ESNd-@2%Dqcpnx&Os)qtYH~cA=MaqA6yJ~1klrvU6Y6$18)x7#g z(R5yY|Mb7>i$(bgQ6T9xP8zoPLZ*G?21i`#+?OdwaW7&?cZNy4!ZTYlno#J2)m!#W z1=qonNVZu%V&^)(|0JmV_By__S&KQnk^j%Ne3lLygC1NjsT@ zpo+QC-;nk9w(vc&u#97O1V_B&Se7<{p^Zuup6f~uHO)C{FE?K;b(DrJ3 zi_O=)jaiJZXSmHt?6f`bUoBZ2p_iJsdiGxUU9wqL3kFJ$7Zk_)*nYY!rJ zPg^x#`eod5GB^awb#OJs`;}`6s*Fa>@X)8Pr9Y{AVrmLX@?F@g=fF1X)5F-+ewxFr z-@hlgFyrAXn3ds^$iQ0_!2yY|?D)U_Td7)st3}^-x&PRuz*Sa9=R zgJyb8*XIsL$BQ|)Q-m9zo#>*wdzjh#Khvnrrg2frBz($NBaL>u# zfD&>Dz&<~UPthId;esE6S2b2MJE^Sl-X2z3+~!}bUu}XPsi0~4sXn9Q0+X@u=2X7c zWd-8W!fD13`Vm3qz7}v|-wIm&_W7u+vbx0OCcH_jel-j4gUqSSsUOS>9s3N+6Ef!*n!} zl!!7%SCw&;wQBmLWWu5xccfoo;6ePqLldW)mW@jzDHL~i6pUsbi7!52T|PgDMz{ob zTYUQioqdlP3l%^mhg*eRhG3I_RBivI;D$iA8bO52)GCpFTVIfyEm5)BEPcpu;aK}} z677AprBfBX?#qzjFiN7+oLP4CMistiTd&;6yrh>?|8+K}#^Cq((J(Kk-kQWO^9=N~ zA33x_>rEO>O4R#H!r7=KOioAsO}xPGtgDOnR9SSXm5>PidLcWr&Bx={*(S->u<5*> ziKDSh0pvJI+`qj>T?t&CI80@ zkcqqsaqIz$v6lKuXE8VyO-g5HEy`1*B-0uj1*z{Z8M4e4RU&oW;qRLhbe01QYRRurBH$M#a=Q|C@L0QV;ba6aRgYee2$BTP!<_ zQ@~{LLmMh`HWaW0`+zGD1-JQnW6M{Q5?$$tX zlHeBHAwZDe?iSqL8+UhU{PcJJaUSm5?T32lsv1?hwyibinv+9=r-VS0Ff_KfQM)Wc zNxmax-il+X0TV)BtHxX%%ZMh=Pr9X}liDPEn+-^T^wBlJ(~a6y6cAFb}p!_2is{ z_zCZbcf=KYbcUiSUGKA&C9bak@X&{?yn&D5zbacOzYswzCx@=dB;&G)aOa(K{7a_g z<1@}|H9RHSCxWM!&5c>XkzCBF`bv*AtfH^}qv5sXUhsjhJmo^}pL;_klVIb>J%hZ~ zkLrE-qZ+fJM6f;wT1wTW^Je&`%#NzOXGVmhOwQn!F}*(I_<&=Zdi@#Op0t~Hu*eN3 zQ>nXaS8-`uMuc*Z>%So7k9;MxPLc<5HJ~w~MDJ{cO2xj-P)@|ew7zI%m3;Af)#esN zRT4l*J4#qKuUvuohKogsC77I!>`9)cZ) z-$lnM8>mD+*9d9cvR#a~S~=XZfu>tMolpG(e`XC>MT#U-b%;*s>@Z%#PLwujm5M^V zSJOP1y&tV@hl3$h!5Rs5cnMh2z>D9V-dN969DVmG^=sH%qksn!j9SP=<;1to_$^p_ z7+yZa(Tc@^iYhrWv4XHl9E*td5&F^xf+ws?Af4By;*!6T{x=F#yllH}1MRy1&asSf zQm$cSs$U5l{LCfMtFz>EwSR29cUli{naf=LZ9z3CSPv+h=g;mp4MvFfLxSyGefbEe{|#b_ ztK3b!Wysb;yqzyFQ5B|@z2EGH;jB;qhRBt9|L&9KrS zo4(z$mKiT6nq3KF4vCH(*bKmJdv*_7qlZ{5>9HmT7w3GZiTim{b#V~y1;yKgO_#Yp zS_&Lmv!vx)xf6?jl0<`f(^|azw;X6L;~=DVqXaFr`l9Y@2_Hwy6CS@PP~9@k&sM8v zAsOn`m9{&~koOjc^fd-6Xe{mD)Recz$IYNxd}(=|o1UA`@^dPekMFFXBy4?aG)hDt zPFrfMJnmG$nv*~4Ca42X&Hx>=T!!~*qBZxw;cg+-_)jTd?oTCfmCtgp6 zV8(Yj6YPDqdu;R0uwD30pI+kjrbiS7$!5Y%;E{&Q_HGBj6sPPoWR*NY5e}c`7Yqvl zX+6uhb(~;S$H90v;y{P!k6h;K9o!-?{6?=a0_jM8R0q9)Dy18P&iA>1yGJ zjb*`z>xI|bU{G2DqZX1z8tPti+A{pV75y1UYUzO^>3Kkadsu5t$aQ7JWJBO#CGfjb z*)8$8H%>PzyP)5?9^G2^6^O9hkyA|%GO2-UEUA*+1Hq@E%*Z65Z%8xD>!l3-S+Uf; z!C#5i&%YeGT7-S_sd0>pz>^#&h8rL6Kf^^{I4?jk4#1$Lf*cX+0tfHYrf^UgQX{!A z={>)ld;a#=I0v%zM1u9(%H|FQEQNuG7iIEYgIi5nu}$q_%38_c8aND-krw`c0M3{O z0P~70PoYzV7bk4tFt?@F9Qoz@;A5hdIX$1Y%BlpcQG&_*yhHCvv(X-!uh%1dh57cK zI|@>Cg0AFwuI0Assg-!*VUZIRFEHa)*aPP z_07#3eL%&N0s@bySu}a;S>vmbXIm4MR0&W8YD~28)tQ}Kx=z2rP-i+WJa^@}#Ov@I z5X&IMwO+r~CmD*5Cre}E2+0>x!@bRm9``o^aepQYh-b&Aj0tGCy?(NNe4Wy?kovF2 zScHp?O*{@YWm~AK%DE1*LfST`$gW8QWu+y61h=ziq`wcXdHAmGTgjfx@4mOi01efE z1qi)igcqt<2J6D0*)*7#?hEA=+c_LvZLT@xq#5$akq`-hv7frkrn7?0VY91G53zun zjLdh5-5+4XZ#Q#E0Ixz8Xk>XES7)SWol0T{5G>7~J1?TW1(z5%Kf(F~oCMdB-LYc$ z=^wXjbSl&ShJLOL&B=Hb=YP^$E%+~W2xzH+z7s|r>z5DF0n?zB?x4C;88No58OL^D-luCI4g zmbiYTG*a!S5MaL+ofO>J#V!Ut6xKyFBEP6O;$+*%#hzvZr@_rn1IDgREH?*HtG9{Y zvF8Qurol38DiwK3Z;i5wB3KU4FHkN?QLa3!wKKyF)GbXGvYrkXX8YOuK&VQSjHk@3 z$1lppcIY-B2{4|4_;w@gm?SZuO+s<0#0lS~q|&L%JSC^qnwohf<}kLd zT8(%$;K?a-OTlzwoG>-TieJNU{M55pt>e{zP)jdgGvf{wmX8UL}M8HFOvgO*SO zAkt~vA>RlszMX7{xYtJF>Ez8mjPbPPM81yk#9t6+`eqDNStXD4ly9nHPwS>q=qMg<_@V$w(=?ES56) zQw^G+UdMQ&zM#_>&rltI0L69ZI3||y=)|rNcG%G{ed8;x%N1&u2h@`Spe*>Nx%4ss$NVFK);Gvy)dLrD| zxgsVG5Qop0%1i4bU+@Fs1_FeoFJ-(dGYlXO`(&j8dkWbTW2pXjOMiI%;>u6rYg3ba+6lDT4w5SLp#|ZK z>T1K+fytmqH?lJ-)#83i4Z6p`3uXVD?6Nu3SG@WBoXu|iOvJ_3R(@*#Ca<&0d%yB+YQEm( zn#Mn0{6TI*u{Vy*tnbD@ygl<7IZ;&^QNL()S}NZ-Yn(N4og$`3ffRpiBdo?(gN(jC4Q_>z{l3oLw(F$&^~(Z1}tvwp<~Kk%`=2UBGfz|Ty2sC2ON}B()EMX zMSbHS#SzGyivd{wo!3hDH5P$GHT zcwnz%!^0SkUh?oQ{RjH?eH<|jRy(fZ5`JzT1X+V-O^4C~-wk%p-1GNSuZ?pEohTaW z#C^;8mm$)(*TQbB%ncXUeHkufl&`(XnSmrROOSH~oi`6drgFEA!KNw~qbp#I4V<=? zR#@(EwCyiYo)9ClsygYP?6yh>O2yW*r=O`Eq>|-P<_M4@&dv5HGnuj23dQFO-5XHs zAg}DZqm-GE-GS_9BdjESb-2`xY>#f44vd$9;=*hUr`p_R zcSQiaaFY4CJnv_5Hv*Uy&#^EioybxDNg?Y4$}u=k9Jbg7r960UqzcYqUHr6Hv-jTI zxd9L92JMEKxh#xV%haxsqGmOy=pgQx;B=fQ`D_dsb&aa~ixBdd*aZHHgm*dZP?KD~{>T&F~vm@e1fAO^j9;vm`#R?UsRqVvcJ2mHNb_)Dyo|KJRp_p8% zS>Z}kp+;J`JQCGw1pFaLzPSWqTAwZUZTDX`6*ioHAG{ZQsVR*BHnCNBIDmJO@Tfc! z7uFpI&APtVf#N*1Q8K9}O7|d12}cf7cc;1DQUVI!Uar*6#X5K)9XJmP0lu0)%#_N zxSr@&uiK5=KS`~$y&_c*ePMVdt|*5SME<0#!N*NAhwf=6(evM;to>JTcGNvB0po{| z#YnB3q=DM}5kg9-zi>p#A`zAlB9NjaxSP3{2N#^o;_HmPHEuM8 zTH~0;@7Q|}dcD(~E!v{gSMKbG|HB(UmZf+ZnEE}Jp^EJIl)f`%v8Q9xS`f5|-cm)k zg^F|q(%n63qPy!H{n;kW+Y&(fPPG%ET*ulb)N47(kiMDQ_i?750=-|+Z^K`ttJeZI zLS)ySZD~Z`IU;PGIyX#Ya_BSVM2!HdsHRy{(pS$2UO=+QnW zb0IKZICt$}1Ye}cf?JrWa{kWj5a$q$v@^V%*|&wbQ0slVJIjSCj;Sz|xv&v0zHsfa zGkE0t4G)>IjeGIOEDsG$d%b#O#$}+1_<@~Rv2iyJ7GK{#pX$GZ3DDW~ny2&a6ukl? z(!-FICDZaulz4qfY#2CK{bHgQ@T8tiTj(N~P9HF;Kadn-^6-u?!*u!yGtBsx#h#Mx z^BP_?tFHeTtr)p+Z*4@K(B_X8bRj3HL924f&}O|CY5O}Rq_8rZ?Y8-J^V_fJaU4!H zWC3sP-``*1sbQ6v=01gaJhlxu)RAe0&)GUH#2a|6PNQ`(kCZ;w^>uw2wE(C^i1fV! z>JE2^PY=4f4jVB{m_Rt3C=hf(-c#hG1le8qX6Wu0ns?`tmTU&$8g^Pkf9`N$ zld!#JnyehN8W#Pvm5igfUsbua(^mW9lSgn~;F_j{2fC{L{AKSdb%z^$0|b|4g1XGQ zk|5jM^k`Z{iHN3v%OD>sC_kCrXFO)b|Md<`FtO8nn(5GX@_DWY9dI}I+i|b?DVVhi z8mVi|;*o8K&`SWEoQA5$)9mIrJ_bAE=wddFmFap&)@}a-7{Z^E?;prC@4M(t-(x%Nf2a!MF&w*yg3mS0mE*Qj5^}FytzYNqS$O1n ze<^Wj(;YZvv$OAIRxqb~1(!vA2hE>yS*et%EaHD9-5Vg4Wq-_F7}n^b)JOev$7b-~ zUigjXj8?I5mby2r33c%$e2Y8EM(~i8WY-nH;zy!9{z=luhno10MaKk{EHhJ7EOGX~ zx&kU(ata(V7MbJ&8owO{vh`VV+osD(|4Gx?YCZ_VNNsZVuv`bkw@tVf_Oly_d>v@5 zeLkmd$c@Um5LjZeBRMwrwl21H_-LY+AbljqE~?8hG9`8kDq^dKzchycFkXJ223Em> zLG^JMxDdxADyMZT&0Ir6mP!4<>6&DWn3;BIku&(w)1`m1Oxa?TD}C0}pWF3rBAD5J zfIxt^Bi>0dTt3GX@B#WBAnt+p8bSQTt6U&^o? zwjSgQr}WY{0*9o%G-j;qR_~Q&e|0;pnVzBOv>c7(h>oCmetODzKRfcUka|E-_9F^Z zt(s+kqg-k@eT)kR_Z)0cAJ_ZmLnk7t;Em7);vi_`F?;X1mr_-{SKxor*HvqM5)Msq zxNS_B>22}z5_R=_X(aHBE2F zQ<4De@b)W#Yza>=hhaLu>TVDDtQpX!EKMSXXK}`syV6T%vXp8$YVcK~*5cf!G*CMwCbnPcpnw6v#Zr8?H8SPLNCK5(Lg~}@ zPF#q)^v%Rgw|H>;mgfgU%yyLaDPs3n59!`iB}v?MTKB(kt1?|+I<~;<xVbPDp){ zH~2zV7&Ey;)0aoMsK6$x=cZM-V%gcECt%o6#~2_+x5(G*HpWH0K~l-1dy{vxU7r^F zlZot^EM>LJ{l~6Dv4nBVUe^~6h!~x5x=B}?0gBJ7@@?tTt$#^Mz2QC)6E~XwEp{sn359;;e*p@x? zd9$Qi3?sjA3$q*KVJBHiQbRW#_I4|v?K{Shi;~LqU22Z@5WSSuG_&a`S}%XY-eaWN zv2X96x4m~=(l{Mp2Or%9o#vC{?d=0|s0sF&vEvE|*bz+6-ZTHLET;Zi+xcjDNzs~tWQGLyRbht%VhYESUVQ0nAniSVFNv{q05eA49%tZ4VnA2EF`clB_x z>V$@0_xbr;+C?ED@ZBG$jXg&_Itak8+y!E$dACQ(wrPqmWP$%sI5$gO8yMz%I#xcV z6X!Iz6^2=xKR~{cg{FUR;JetQZ%&vgUqBk&)K|Kj9$H_XGdER<=Q&-k=80qHkTfYK zt^`fKqjh+$)K)mU?L{bqq<^^;A3JA9h7u`-tRzO-Byhx*Cq4wMNh=@l*LSO5xbAH* z6z)ch8bXWj4*s$2?*%{fn$oO@|Ocu^2Yy@Wc0XmKMv-U^o{gpF((Og?*?0y9Q_y zlA^KxY;-f9F}-*F{&4REjnw zwW#ELzjp6rZ?v_;3j*7(Y30!Nd$nEp=Y3K^E%08i`Mr6$Gy&M;WgzRTDUAA~mb7Da zxjmFw$RnIZ-uY{(LDxiSLex7rSzH~x&4|gsO)VMlYORwKXuMlNx~ehyua@gsr)V$H zowx(R7a`7HvhI*cUa~aom$|{PCdaLu!%M@!Gv! zv{_ui*qooq39|D1BMtA#?9ABqB?;1GI#z*PbdQZIw|6ee{p;p;^>TUui~4r!n8*yq z!8nfPO9nO8bgFFTmcrKd*)%$ii_Z*E4^@k5tC#wZC#f3O*YogR-@!}JB23W{9oP`L zjT9{p?mbOFE$UE#1wreg4NEbN$Er;qsK4oS$lAG@LGGs&RQ&Q>fV6eNr^?|u<3@?3 zAdKzZBfoJD>E50-G>+e(RZl_wJ0Ofr;50cQ@J+{d1G+#kbRjo9TsGt9E4_Tusy$6Z zywW-ncs==@wA$+IkxS^9lVGx3k*TPIdU(^Q8ir>+?EHo3AS6>ZZcVx1I8utQ%Hi8) zbrLUm4zsY}4V9PE;*^q0*J#O5%dKRNs!XpUniPvkO{s8Z(w}fOqW9=jvI=N&%IOJF zMhb(L84in@C8O`NUVxRz8?251-xZsGN48Zl$VD2WH|e>Hbv3ZPt9$!}h@S{rvZ=f! z#U_LIXEt6d$eLky-)!0@%8kKQ>^!N59^4kuv_$PzSFVJf8WyneV=rJdtNmNClJP2l zx!zc(fJW+}h@*J7GNXjb*_2qAncL|-4 z$fuTJ$276gfScBhlx#3(S`Ul;WlnFxsTfA>^=Zr{5e7CC2**tBgjt*)ec-Pr$1-3i zN=V2hKU9K7seXmhEHs2pvXv6FSvAE7k}Vh_bpif5ypxsDb#=MUqlg^Lg40)cSZHvW(L>7_ z&^|=rtAHJKWZ715HWRo?Z&%a|G*sH3#M;?-rXj1r<9~r=$XdbMCdD0H)3*ON64B03 z0+`4|Zpj*|crJ|eeE2=Z&@zUgPXYLy{h;K>Fnxbj!TG45mCXNP#r2z?g@0cvfsnJ@ zp;zPt>WeB3Yn^xrdfccL3TBzCzK1Bpxi3R^5l;2+QY1p8-Cql@?G*0*eLRRxc{Ay& zPgPC?Z0nN#)Nef=@zHS%VhZ27j8UL9b}GM=Y+2dXvh`MmJ+hlnk^--xpj82TSNrQp z+shlQ#f$gQK|zc!j9gskqRB-}Zi^z9U@!M`rkngRNqlh^>HHH~ydVyS72Yg52B`og zwBC39ep`#Yso0}+1qfT)P1#=${mh%_&@M?+-WOO2ezb;G1Siu$-T0;0P*Y4EcA4tC?Tgat=67GM`;7akTbs=A@^Tp zm2ewzv=(}5WT5Ne)<_5Wh%op4ZeZL$hTLw~K~RSQn5wXj1X{z=q3VtEtYZ|jcK|~T z_l|k|XhITIM7iPFd~-`L_o|Ko)UjT^PLEDUK<|ib)@#3NSn3Q@kM=gKhBIlRbT~Gz z3SF+-x}A+Tq$uIM(M83NIyzZSTk=VoK=qrQZEX7ccMBSWo7s!&*oo?P*9soq%iXur zNN)?TLEtuk(}l!V#-(TP-vHm!dX-c8YZi^M19^e;Fw&F1#;=#fxd9%p=CQYEs=L## zX#(}Hn^6A0C#&5A*=~mYWd|9-_YkUJs+?k9X^%XdwmhVx=(XZ13epaYE{uJnO{EkK z!}g$|1%oC`cvdvU7YMsf&U1kMbKobgzjWG#qo10zn7d665#DHoqXl)4BkHqroW*sk zFGM23jXEK#hIOKd^sII7EzdSa?!~_fi5UwMeO98hoEX?ep#!)n)`rn4k)ZbLN#his z7K71Myll&`yXLjb;-?qQ(&#Ao{!+Ot!;Tl_uJu0B8mL`-mj9{8~QOb zNvSG_iUuV0J?S$H@cHtOWuxKIr&-j*gyVZz{}nDxG3whv+^dEV@*1Lv%;F!0{N;#l+5Zyn%AX)v|&XSdOvK1 zLSO+oD5ae=%GfeQp>bi2TPsT?)QNocT<@`;GZcB1us#)oVoryS5a57J9fH?tO_#i8 z{%UBhlH%tD-d95{X7#K=C#_2UuE6@I{hjE<9WNCB4@%Fd?IBJl6vd&PgCM$#q!E?L zCBBNu1G&$>8`WE;4v^RGQI3N9C29MowhK&-uGI}1<}Wq4pHVu>sh`;COeFcg@gt2&KVk4#9nQxLC!C7( z-2YJDXi0O;SvX9-7QE@(E0K=jcbtOOYR#h4e%heGS3b_;N3#+LmzmM!fu~*tJ-%L=h?nZtUqw?le7SoH$eppH+GG7jd z1H1m75??^}ftTCFGF|{a$1xcOpJTmj^EIITz1 z6;>tTutr^d1QfcfzW|}eIjY8;cON|Q*m|OR0=E13Re8(apqrpSg`f&5s;k0m#r9TB z@RK`56B%C^-aJS!U;6sxo2p>gTv~Xp8ulOSI=_3vb^UvxdzQM{;(*R9@9dgcQsDt) zKWUbQu}SWyxY=ry`rkUJMQR}|l{Po8$LoQzCKnw7<;F3>`$UZuRbl!SF)LhQt|p<7 z#Jsx2o3sG$Q1veK_a+5~(7!(w(d`qL>%L%oT}E9(y-beLvf6N#n<>4<>U($P9ey3{ZpG*6@{Sg;tMPd>*ESs^%E$c-(6*GA!Gf zA&Oj9Uk(fS0&X+W+j3CBUFlpT_Q5Ug!3lrIaJQ0w6jk3iGjJhnZbyyRaC?N~Kz<~1 zLw-sQlQoEYKpX@r&t)?i+wl?r7M}3ur<9_ zmDp&C!FSO1pZvJOr4*OPYf1kXMA2-Ng^RL5xm<6)psT?cyomljuw!)l^Ejey4Q|3< z3X~o|pP1tN7q5%8MM>h%RI`tN{XDCmG@~;5b3NC5DfeMh87M!s>Qv)jMX)h;WzCnD zaREZ{_(S6xpT%Sez4+ZGfKrCyN0u5T-RLnE`@H378fy&ou>RZf>gi^>N15dIhs^qN zi180UPs1MwahOv()`z@lcIlyTEu3HZ8Bx)wrSd~`T@C&?1p?NE%=C4N>jVWfmvl6Y zNqiKNS6}UQ-ku6=ET_PYPQOxg`w=*Q**HX#-N5kc9#*|+DP5Q3S7S+NUkDgKM6=z- z$ttS#_hD@?Z2fWJ0QK)ItoK!`30*^W>+7>}XF4oNNrX3|7C5P(MkJs6;`*sq%w!aF zuQZHq-OQ>q-}!Z&3&bTpYteODMiG`JfaQ5*=!0$vzg}l;5XB)O&5)}!o;IdBWi#R61pw81Z*VD zbiY`#x)y#E&P*-N%~hX6>6|JL)qO};kV$c#ReqfZM9j-e*03(Wu84}*QnLfBx>K(+ z+Y%j2nhNrQBca3!rLwXNj6 zcB!154VJtJx+~LeX`}*&6Vzhnt6fbI-b~H>F$x40h|VKjq0-p6Z%vvX&lhhJcvmw% zx#}%ZiCsc2FNmF*aVYjpS^Z!vmbue}lMOMm{0E(MX+QHr6_BXMDUfjB!R(>+N>saU zV%RjD-Zcx&B1>M%XaM17x>$CbHBlph&g-nO#7>_hy5_CWnftG5M=ck;x8m6~&$siv zOP3gHR-zrjg{A*tTeaqfMsp@OE9I0x!;(FO9$*P~u850vQH1yf`u6}Y2% z1TC$?qHFv(LeGjg!S95eV#j?B@`qjDI#>iS=HW!ERtOHOat$-E`x@`OSBR{|Qo;kQ zAzn-dA&K#H6kIJw)%B}BWkZ8rEeV;11X?^((pnfD{~4!Ae<+(&R_tV@W@7xA6HAoW zu$YZIQMkj=xD$Kp(C7SKJ%AD&p9g1u%mY95lo(LAU4|NVz@d>AVE_ zgWn)qE^m(xU%$c|z!&FYcE%+uR3A9gcgOK;e)BP}E?2NQ%V_vrnKLfH^y--|fYktY za@kKW8tb9zL-y;XAJ5>Rl(-II2(E2?d%mdJ83p5b)>0MF_+R3ThEl#FPY4x5-UkCx z&E5@{h*l9nZVaTcw22Cc<&>jbPiM4-0t@}vj{R*0!`-@C45|O7SwmdgQ$?7q1 zK06H$`S7H_!t7TOG#VrjbP((>Qb!5w6}Y9PJO@-J!)yNTJxm-_Q&dKCy-LP+?XFC} z7-4(n#IYL^(9^``u8}1;XmJJ z$kZVE8Htr0>_=N|4-tfErhc*Kye014_=d=+Os#=h+3wbXqMf^*Xn8tsZMs$9fMzuT z-A%7|@r_;r?H@5IVY7FA|V!6ZEXaL7+oI+K0qeAXZ zv6qVDRdk-FdC(_7UNbx$dQs9NEe0yq&LMJ=jaiyJAfi#=Xvg1!{USkGv9CY;*UX(= z<$DqU2k`!EMnQ?bH&$2&2!D79q^rYk*6&l~>~J?pKkfDm3g7r{wBK&z-cPpez0#L3 z`4AIf31llXgT`9_DPnpXfRiAAA)^3q+B!4(tj3bR|1!A}`#6du*BLwqh+(1wAo{F-=4{8(bkRk} z5W$zSyB~0tTvQ#PH&^_sM>kQC)&*Y7s8j<@7@O=*`6M zSQ~*48BqR5%HGn4gNlQ#4PioM4@$GbBz7Z5UT0~nSp!$d1I&g@m}TV$wd2AIE}~Z1 zr#{xMfXmNhfbSAGzw4?p|Q7?T=1w$*QsGwamo{XnDIhyxn0pj&7q~G^?rY0 z)JfLHcs(65sS*MI|Nbp0i0sjV^*a!G6(sVg$CR<#OjLW=@J7$%mFpEiXNT&=zjr(s z3tkV+oV?{170vxBtUl{_SPAUm#O!w*7UCPxIHYw_f^tWKlJa(y$m?T# zg^15=5H93DSmG-bmI#b15Jh}~m~O^RM^`^5_@&COB>xozr1V#IYbWznlpgBrDbTZX8>(@9`bME{06iBfl8a5z zRE*f|UHL`HAF3E!;{bLkoP$^TyV%>+i?~UIG{y&&{5583kYKuV^QL^~T@|B>-SHV% zEFPR%x|IG;3IIj{-a2yV>(;$!P-c*8H(}6Yw-fdD!=i4lYc^InLA?0wfgsc)ak;xI zxC;IPUL8&xJ04c+6lzL}S=|+m9{z`{aL(J5k5gXe9<^y4Mmv1yq9?*VEj){_d%#-^ zewRd3$q~tcfqIg$uo3DDdK`>L3^V8|x+9Vz1_+hw#lnf#k=bqFe*^Kl)P>iF4}rT$ zZMK|k#sxPqaK0(a05+{|uXxIlaK0hyeyMr1*=)Uh1lep&IoI!1%V%b$cn!2O({>%0 zHW*)c<>2>|#eYtQWVF=JaPn}oQttghvh`~qsug3T)&JU@EDbH|6Ls0hy8w19kaXu{ z7J4h6mB^tj(#smGptDiqIMk*);cW6Mjbr9blMX=E#FX=3DNFbe($+>?l7`oB)h}3g z7bW^vc^Y;iIC>;2f#Sy(uv*mAlmt0gKkYv=;mf1VlFIDfyW9i`#X81RRmE-np1BnG z)fNQxPsCOF%K_I0r+#~rhN|`(ZUffX;iAKTD6zW|`Ui6%+2-@%j)3WBB}W3`ap)0o zj*Bzah|UX^;pe0}%-eJv&^9sH1B1EnqYK|gi;!>5HCOJ3GGXmNYI_TpaH!Ej3D@=E9Ki|JQz8{zTwCU8+;(MxC=vY^^d&*qmzVM3)_-@HnRWjc=$rhm656h64i>H+#?IydJ7ZTzTL)KLD-&{eb7vPT z2YYf37IqdkCi0)Iu8sn%tpEQ276)fb)*`#jWB`C1AS3=w-81vlz{3+~{>gt*u|5Mm z1WWf&I+;daoQfPnq973AWFA!ngVnm$pvxPx_E&XR9=<^h`dAaACcFgY@Q>c${QO|_ z8oI7fs*dGX|A0;(cZ+7Kyb$=bd#{7#^<{cX3(L)$tP9`GXL`&aRD2fw)`y#ZwN-S- z?Y>Y{d>UsBq_0{!>JQ(8xq&CqCT zQF=&{>hUnwCc28OUq{O-FrS13sG1KPEj?>)EzN)ql4!~W3dqx&GZZz`74a|>;V~9{ zEIV^QW4NQ@j~b@HJZh$0+3%B3=xc)4S4SyQhXd5W{DI%n0T=?r0Ki3yj{pAO#gW+; zfBu^m03)G9oQi^?h=RjN95h8tS2Uq1>sJ6=DF#02($BLt`$wr-C)>S7Hv3Je%XZZO z+ZE`WWauFUs@CG|k^{{~mB4m2`X(KE$S+lEW!qQlqB-57InUL*0-$OReNpousC&V^ zHMDN=pKRHgY}w0bHDwq`wv5%JAkz}4s#E9p0jS!&GVu&ubG`cNASkC2s9OMhQlRH% z=b1UoJV+;IC?burdlxC1gUHfT-eqBSc$_4wiU0_bYcF7A%R=jHy!7ZH4n=d=%@;_6 zl6D!%s$)P^1eE)y@FkE4L(yR2vw{Ap7zUrXJ03BcpU?c892K>ebiQx9U13trw z!W^RIcAa%-<~m(z0jL4GgCId{QG%Xj0GcEG6)_;Wn8Xsc6u|bS`4s~2hq-hB2m?X^ z%`l~8s~~{r#ZucR*h{3q>ADL600w|?zB4ul;EU6dq7T>v(A8&wwN{-NR__P^-EfB} z*k+cQf)e5&g&hR0PS#|I6XD&Gkyr7(MujT zfR}>wp~ufXD0TOiu-aD7EP|5SURHNsv3u^DC%a5nTWYIT0l5z8uNSb6mZyFUeM&wg z>{w(r&%UUE&!!h@nEvf{WQdLhXB`tq$Yi3ZQ+5X}Rf2Fm9d-8?hp|+5ZOYJzy4P*e zuim|4^YnFp?%72FXCVFXjk)B7<6HK(_gKEiUo6_q*TqP15Z{x>w1UgU|Jk*H``peP zs8M#OCi`1W){oSM*f#cTb*_2jqS@s%qN|E5+IN{$4^(gW9)9L$W!pXA1~CN-tJ6cO zRjspBtx{c`vl-xM`SNK1#JmnHML-=`iA62D`o~yRw zE?ag7c!S%51t^FYVg~N#b`+MoFkvM;)fItRcp%+d(uGwKT=0(FXKQ6^sg_+U-K{>cR%lTz+h%-GRU*Z{_n96MCYgH%Tg zfX9VEA`8I<3E46p*|I@E@zUKZVUH?ck)f!wPUdLWHaq~f$4R!Vz%;2_r)~rc9fT)a zh7DAO^nA1w^sLc8-Te=A+-lK#@&Ll>vdMws(ETm~kW);;w8Au&w!r*>Bi9lKAvy~3 zc|9N~60i3-k3(2(t|6IRR z@Ak+n*1*`pUJCtmgKKOD!)POJsR3ANP6ZJ~h52fnz6M&}dWoBH2Vw){;RL(q0dEM- z!ALzKy(qW80bxPd$Iz=thuH#%Ld9=FC{p*Ry}6B)mO#%rAp|gr@1>^;#YMNHF7|nB zo3M(}yXC8n;=A;(p>55lllv6SePPFsm!fw=`#C+iJPUTJyZ9eiz7w86sKtvxj>T&5pCD8&=1#yTR9D%2{Ti0VY9o*0elUizp8UWDlJ4eDqf$=25adf`299*gsO``Ed zkiNSC!zCaq>wZ{sMrE@ls5OghnoOkb`OPb^*alrrTz)Zjjc&h==9!kV*81NZT+<;~ zCE=0#C%4|H^k$TaHzZ2&vwbqL^@_7YI^tUD67L3y^xKs^4XLFdvX8refVNV z9_%QAyhvggqtXKV%34z__|vF00J<&Y&~1?@{7&x%qwO&ZxU7xv)kp%bfuR>x;*KZ* z*{I1!3|l)t8czD??%}eUn$J^@ogH4P5i}Ui@cB>71T}Ryr z2$zVyQn-Qr>?kjsB7`0yW{CV9xj&kB3{}}(h5czzAV_xo+q{9+$m@!b2MUp|CfejS zf_*sD7R7%*UrOwu103dVz3y~=2G{qqJ(RB#dv~b&pNF_@`oi6U%=iK^7^?5TGi&$s zYj~(O;#F?_%Lqy}Ld^Dw^)uo_YqUYiypHqDbhH+x@qqjI6=!LMkBk$Er6-m*%4wqk z;h~O>>;VorC`(kllkP+>P;$Ogi++*XwR#6)a^;4~1~&ikw6h&S0dMBD?PWwHv1LFP-2_1igBT72(eSAv5>9FGO3?OK*pfCzWF zPHb<lT0r`|(X~ZNH*%+awrXC5`?Ka#i&JbT|-shn`NW0!(hgrV1 zptesRU09B=JD2GNYC6HoPMq8Q=4cERs*a`?d1tbc!c~cLFC)MrwbvQJjQgU75znla zc>jDvujWn{OCh_Jy1iU%I#9suB5G!4s%Ak(5MRQ=v42uy%0e{@tha&XC}VBW`Q1r{ z`VL$uwq2#+_=%yEkzuobBkU)>;m!E>wLTzQC{6t0N_y@hRSNM6q(L4!HV&;5{%2R9 zE&)lr?Aq89dH%z$h{wu=b2S^PeDKAK#3OTf#z#Kw0A;vNfoW0FT+@_~>ADYYi#Q745Y!RS;;MCL^t za$~wS7Dfz@f~@6#I5k>(jkDs2^lHWQq|d{Y{Ib%aIsRB)S4PD`b7=+f19x2lbn*2K z?%Vksts&j4xeTeX>%KAU4b8q{YEKkc+&9*A43eH#=}#BCo$l z4Tc)qxGgnb$DeRE0rcWn3?W7v`9Z8CsIV7=QtazvA-ZuaqJy`<2#iD)xJVva21O!| zs^i9^K4sMVK30q9vfQ!$w=_|yLryc=}a zLu3?Eq$6&r`hAKAv4Ri$>#l<~HCNA{MC515XMt6-u+FkJHfBy{U)8E12xjrlinie< z*u%73EdpT?;rF!dOTaS^coLQ@479XR3aNqFW-FMsuC#d_bvm(XHrT{8tDF~&*j;&X zirL9rD(8uG> z%AkF!Tx18?rlZ+T0*?u!?U2G>cn@PE7F(&Yj|02z2TThyi{k5RNscZYWt`MrUbwh! z)6V|uKI=jo_lR|>S~MO-#)dR0yZBeq47nl724yPDoSW<_zvYAA>&N|>Z$ia>RK{fV zzG+{{g=ME$%JV5?h`fZ>Tj|b&%e9mWOQp@mQnCW(^j{vgvHT6BG|oS--hUx*HkTAV z?-t?4l*G?){=G<1vuKpscpjT|1W%#k-*)9WCPF3@h*#!*U#VlNbK!loVNlqaxw$F` z*O4sXkj?Fc#+LF{Ucq!ClJ%}C(|mj#t{cji(sL)cSC4!~rrO4pq;bQ>;TryN`lkVoDBaZsQOH@BmAUGk9MouWr^^01 zkDgD5zp3Ri;Zxja9PkB$m>oDa^gDBrzE2c~ z^iz1Oo45S}?ugRzY84ubCGc*_`=R6nOq>~c_UhtCvVDD|Tjx;Fs(7Zp+L4(fns zRxK>9?>>s*%o`v z%;&H7g(9zmzg_PS?^=Eu@8hmHNnJ-AtU9!Pr#&nNJ4{O=SukFX5TXC(4953R@Z-&KRR*X1hFh4c)h(_eL20k z;_()uDA4(AeiF+XBq&d%iV`jqu@ zX7FOQ^`8}*?98CUcs-gYd=bk8t(9ZdQ(#870uoQ{3y89M>Swc5nD5Id=s8<|$HpIR z=3JfUoy^eUe!T>&`c3dFl65FjWUzfn(ID<;?RI<(c%!VhPL{4Qq*5+=czQY+0Y5yL zK3z499oCQiiJxy}$M?aR?nR1bGGyYYsG5Bzg`wJkj2MT}C(+I#nCHZhatsKBy)Caa z<32*Pnzvhb#hslGK{IEUo`=@;QW_d&-bFaV7F7MT#EOivU#}S$678TMq>x81oHHK_ z1IMRwZt@;1_uxjto~o!$k7D_-*Vx>+1T{MI>O)9mv zt%7<=&*X@_-tgh>SN;#k=EZSnx^HBIb!2{x(h>;W-d7UfLdG7dlFb0{{mG)sIs(39 zN9O0~%O*h?%FlRh2Sj6`vsD?xqscGls}7ILY(LX@t<4fF`ok#5Cb_6>J&PzTwzU9Q zSKdWzL$1|h)BE0&2HM^d# z3~I99zSD+7R`$o7)15@`tc$JD@(8TR~*syN!UU26M@*Bf~+r|)5NfXRaI&#y(p4`#+_G#8&>Z}C3=|bP4;wq< zy!b^UrTj7nHF+xUM_n&`!)~UoA)p-VzFFHj&ZsdTMWDTEQjr#G;>(wC?R%IXNPG?( z+5TAia|o>=MnhLJD$1k1beVjFn#mE#f%hA7G|^|PHlVZa_X&%I3d^kfbQ>yrnfJ~2 zI&AG0Mb!x;pk;hzpP`5p`_UW~5?X{M{zdK478*RQ08$@NiY)oTsl^C0UJgkwDeV^` zJ5_^#=MIWoaa*pa*-_g!dMQbv!g|tOn;WmTc9**6 zr%A!d_S3=NX%3e|)DvEbXYX2O=2Waa=CgZ&wv%?d5m)bcS-V3DZgNelM>m?GP@_Id za)$Wac|q5cYMhRB$MK=$Ghsao#+p}|nNwoO9l{0rn&U6Gi8X!Q1fS*ZWi% zax5}k7fDKqwMHYKs4ARj%4Jq|=KI;q(uW91a3&h(xEXyl2d2o)M`H*naHA7<_Zepi zo}fT-fz%gsvLz)t&DEhqg3YD$D z8b)|A+3jTKeHU5wXyurHk`Fd}E^eTKjD->- zKBAtfr6qQW^E`8*$_8|Vi%XS=$IN8YXexy@(ie(`3GuEv#1Twkrqn_wO#FelD#J%m zSSZd$a6uqe=M@xZk?!n~%^6(wvJyDXKWByV?rBd%AIY#s&C_Wy8VEyiGBs?>ZG+m4 zBizQuNC(aB3ywK&UDw-j7Ju|x=IF>6c~9S;Ll!04-HU8W0s<1i^@Gw9yZVo<&wn0} zw+d5=nfQgt@0VZhWG09Hu)n|nWr+x@bttcAi`o(5y0vPOiscy(9G!d+!EQ22b)$V?is%8;GT)KS)^1m3x^o@s|G?e8?aRg`*& zw3nHZkXb#v|KnNct#Jh^epJlS@MHKg0cAzZME%Rs$o1AQERTxY!`_f8<9=}q)0o}N z6RFsQSdyw@MZvY}RV_0r`NP$kvE91z;$_SZT3j$r(c!od2j+rrP{A)(!9YJ)mhDB2 zpJy3=1Ze|DRD-qW3#}y&B9wp6u(kf&yxEADBIKWmdS1Ln&JtkvKBylX<`uYADaa2- zQAkUh--Y&tB@~6zhDb#W&CYZag5XR?(`#llZWO=#of0Cg4mi)L^w+S0)roS;$xN(F zOdIWMQQG)G*MQMdkBv2J|F5YdJ2NX>KAY)&!^ZFSQTmPew?5dttqsfY=V&La+^wB@ zH9a&bERuFSTUrlFzr~hfyE|lkmbcH~srO<*Jy2hg!jOCCAA-G`6<)%Jf2ph=7ue5n`p-!ayf zoefB-$pEr{Nr5ZqWu|R1lV3kzLFWjUjT_nyv09m%nW3l0@9vpLnx8vJQN+OPY>Yj>Q6b72)gZ~7PMkTTSb=$mbae!Hzlk5dVkMB6 zsry4-WQ>qqoxG-nFHz?H!+|5)AdXK6z~BxsfL=- z25b+CCi(?k0%mibhqlgnCYun}_b~Aa%rwgHZ6+jLWmUE{EfyJunvy0bYdSkBG=SGT zy%uQo)Q2+Rr&;;qv+w&G4r>KkFL~T@6>-B4IXQ_~fv8NkO}|Rsib=hi?4lwy19kNX z`HX|lxYXqqcc&xDi@@Kr*dyQ3voh?ltfqQaJbD6gKBT0JqM~LcmG|aKL)$%;8XTB< zk$*|Tq*8ta0>7wHNKcu3K+M7_?oi`h1Sy%YlLjtZvK+%h1ATO@jvemk(F96wJU70^ z*#t`H!=}wtpiq1&ty6%v!p;b-SN5rGhPhD0=DIhd$ZB+=?fR(9NU=g_lMQ2A_RS>t zZRoQYYG>v6Xy7YY#Orr@{}TlJ@$EUw<~f>G01}3k8ip=$-qmum`HFFCmveY@lqsv{>GZ!9$I7jQ+;=8 zZ`s64w3`nXOb$HYFfHqNLqe>P_UU` z*YpM#@Qp4%d)I3c7ZLNs69B>@t=D`x7uVhOo=p88sgs&~g%gHIciSD8q9&&6jtL1f zbN$bnj$1rVG!xX66efQG8VoBKD6VIf#)+DV!39!ksFo!Oht|__-0Pk)QxKdP%(p-o zE2&S!y!D2?r^^&t`n^7GQ{P6^J}xh_^M}PsxRQJ^&R>%FA2&otNpd9Pc5innE)Vn+ zO14Q)O;t;)(_qxSb3cQm$4sSh$$WldS4f{?CiyU(6rbauFg%f?WGHync$?Jda!`B5 ztQX~b3A3o7uKfO2c(JtVMO{X}3?s5uv)X`#F9Aufk$hT1lWVV{M*7q{09qA01XQeX zYf!@m&4n1LH=Yc|=sd}6>!zh)WozTGdK%@Sc~u*UBBJL<{{xj7*OK;@s(k*o?m;GH z-u*`O{E8)*60(BMa*PPIVw;f2;UUf{>&$0j9eW;{GoQS>I|5(MsgSxfq;ZA#31xF(!&Q@k$w;K=6&H zc(GCqsPp3GQIi-uH3p3()lk=qYBroq05zQeu^_s9bz42k)jsR%mg%OGhjQQLfEl@v zv(?Aw!jr&2XS3lV^k5EK0t4-qb(-r@MpqeXh6tK3PH)B@0(AJ?h^dz+M7Fqz029jp z(*jge5E9nKC`g{jTVde@E7_a^1Ir zToJ?zV)Ty|<4C4GHmS*=$#wnKP|Wrn1=Vey7;`W;T2!J&O9T|?spasOeyapd3mXMw zdB6Vz3fnxhb8ynbmT*7Z6EsSIkSbru0&vp!lNQ}WhthV6!ycFvnVeJ-`FA!LhacYLFvQwjo1UzCdtswB+3tpw`e_Qx_x5m{e9TC{?Hl%W zPblGVwZ$?-kzrAls_(-4w)XDk@ei~9Jk`1VH(q;Mlp0Gfz!_?DBe5y?Or(Q}XZVWa~4})f; z=cBp*VkP0?xH-?n&SD=g#8Jq4=?zpvQWhZyl0%$bn!sg(|Ii|%~?er4l*<& zN*3iRybs39lN$0>7?f6`b5^Cu)6!0bs=F45B$hBgL<&8XN{4@3@LyhL3I;jtp0C$f zf0Cs@Pc)b!?EVBsG7qm`6R`X>sguE@ z{`_)O5`t}AA*_*76)k`cH57vLpQN>_JIVE2I$H@d6;|8ey~}rQH|y)SfaeU{;N?m} zT3K$RIrWg(*gw-$(|K?xcV#85=Xv4MhlGTc^XYt;Pg7!4TN7E#siUzZ6!?aRdmStW z+W*QKm~_pK?x|S3VV?_=4$q|rVo6TvPVP#qmq`w~>svBno2kK|xyN0|S^v8I(%d+2ZhvJL(q1tJ7 zO%B1e+h_Xy2j1+!O`AtGMvhJ_)ihO@g$CT&7`@5JUWwf4W4`;lL zG$PaGix9IdTHhxe*nf`1!FS*;J3B7!QRTJc6OkNd52( zhhk#px*1JPyn;wWA7-9MBA377ILuE+cE4oov#dyo@V|Ob#V?W!K_GBAA+wsV6MIOl zrEdR~DHzX`$9WLuK{I-_N=srMf`ekt#dioRXhjTQ%~YD1Pp=-b9we&|_uUO@ z^LC4*DW|q?JT+Y@G$_m|Yxt2mw=Hg{0@k#jZql#v&vbMs$Vk|Anww6UP<7)Xqlc5d zUpOvwT}l$y^ymI_7`amMFPuAhako=qk2XKeN1&+V{(fS_>^3g!M~6Mt&MmdhotM{O z@ms@l?4qRGkk)|23En^!oY_A)DP($fKd%+DbLDN77B$tyVTRl?pQUSGJMtn&S3}d8*EH*AoLuy9DYewN$})?!S>Q##YQ3 z_UjBSwIXjzSU=_T8*PrZekFZHA4{FRZUXZ(*)d+{ysJ|#bRuFzUg}nZ(lKS*6-WeC zU+k~VXiARC&1LH-=P47tA$$&;mJ^EZ>dnX*5sQpuY{DjPee3mKu;Mss6W^*?jqWhqt+q$pJVEEbvE`(C-UH^9ngAJ&$Wf@G^ zAHEROZ%K!BN>E_k&x5YQ253!{_(K=8XNxt>CJJTntWHOevo-@-n65HECq7+nYYKo= zUBw#h6Nxz^_xge=?x=|>=AFzzhqMDbjcA~__H z$bxB)H~c}BG8%EDZ_k^@mf&-gmx}<`3^Jd}WV!gHei_KsEW?+*Y)giG8&y1+M-O$CHntezG?Z1u#|TVn{B%aM3; zB8S-^74G2%{W$xsgwQS7(es52yk(Apm|VEjM`FqMd#53tFX=wAVzf|7=}NqWY3y|Q zWi1~;#)$FB|ApOe=JmM&8yQ~u&ing)ARJ#?CG&X#Ws=|IG~MfanOQV?e-tSp$3Xc{ z+{k!>XGlXc9ADb&%T4mh?kT-^0Y#2)AK&}0Pt7Z9ps!Ly1yZxtO8O!uA-HlmSqdH# zHOwAr_u!NyNP)92zv=QJ0{8PE2CCS&mx;`3a=_B}JO&Bds^O zlKOr<#;wF5=+4G)u;x+~D^0I^LMi3ES7h)*N2l?awKLx3gZD=71^DOLvZV(|c9Er^ zlsm<(oV|5rmcUgxHBU2tu;&}#Ga6O?R@HshZD^m#ZzK>_PEojddL>zilv`0@NM_eT=z$3qx* z_f&lf=OL0?hgF-mY*#F>gf;bn(a^rw-^dPV18P@&!n6B{Vb!X;yUQmUs86^hO@7x| zEmiI7roRvBXV!ZdKL&F#Mq|IB;FGT1B?Ds-)yg{ z%GKfvs~CpMS(3|-4Cf|$PJYF@mk5C1Zl0Jit`m-D9yNw};7`*@VMF;~k)7aJ zh9B+F?@+i;h2O#1M8Dgm2T3V?0S<85*(UtG&Hq@iL4J>Fx(_I!N``0L%L&K@<_Rz# z;Tzp<2e5r>k{lHIg2WsRnDntP&cDljKG9uIZ*;3qHEc}ZL%^Tv%7;8C2_>X1v~e=) zuX|b5`|Kz0$?AAd%a~;eOt0uSgq=+#Wu_m-32`V?Ew77P(bEpnD%9)C$ku&DA~ADw z2Y?x?I}`Cv@+FwMO7E|{AD@LD_Y704NMH$haJ_3Q`*bgK#-(_A z@%u656{X2;yMu+~cSs*CqaZ$w%rX(8jN)?_jAYZHV^<0@Kc@FiWaD6yk*5cxtN&}V zv3od)q*jRi0d3Ay`mEi^=uQq~Lhvzs9=_Co&veKccIKqWt<#IMY2o=^N#XWihRf=y zZ340V53GeknFVA~?APIhTg(fYmp4K17srYMv#r613uCQB!cpC7{I$AYPuD17;zBRnBvK3mA> z5YJ(5_$}~B@F{x0SqH!j)b1O&-v9jNxUD3X&yQ}&A=PmJ1f6jNqoQ@y#= zG#-1i+9u4$4k-j~l`9N>6T2j?u|U{d>0}O*ln7QHuZDo_Qw+svX=vTPr*-WL*9pk$ zYS32pgr{Uju6mF2Nyv6W2@(F^4}}C+9KKj#QTWP_TZ)`4kB(bG6y_JYO|C87=CWy+ zNhX^9kNbqPR&z`E2JPc1)LOcuit09$NA(>w-5`&Ct9RQaJrx03*auuu{y-7Hc!QsZ z1d{+*4?tP&(kVi+P21{1MF1>$H>PQGt*@8P*7X);T`{U*)a!!a88vl#dQ=vKlh#jM z^}sFg=Xj5n%NF^~SZ4jbH|XGCm(~kl)QsqSW?`+PODUqL+ zwil+RM9qJ}GCC@L@UP%mCaI};#Vs7}vcqMvh|GTs&;6rZs_HK(k8(o7&sNaFO^v*| z88b4XQh&rn0cS&88g~V2tZk83QvB4!3`wk(Jp3{VDF_EIa z*BryzrYOy^?HvgRQ9=6Xk@+f(U&A5ZN3;ud7j125i|~hUBjan3k+GbB;!pldY`PkL z&)0vvyc*HYuHglC%ucl#6OQ{(t;)LIh1V(0R&?x(2a2rJHiE;@W#k2PM!}S6$KG{D zeoa0t-eU_d%gQ@)Su@ScH3T|<;)o9`1nSMoeKlTD#cN$8MoiZknTx{}dVd zt;6YETqP{692muD@^m$Pn7y7l6FhbViGrSNl(~a(C4yIbNmaFaf#*HM_FF$sz&Xpy z0+N8@w911r&Y0+^2VsInd-Y&6NDex*NJRKkEN+UTRdo3upIh@8ANVt@NU8drO_*#Q zZN<%HCI7fZ;k7>_w)zf@Q>}6gZ=3$m2TlxUdxYh zH@!$gk_^$RNfn@!?S5t%m?~#00;bc1^3Nu2HKvcwVR0Xc_Fjxu$3)#PCgMlDZYnWU zND?^h(u-D238?0f$SMgT)1%e9Et>>>T&9Tqd_It!E=7$Sefl>%yVdK*!{sFL<$Cj{ zO_SOoAlX!Jf;cYBj>aMu^NX}CPJC%YL5`MSTZsS}xib$FzvHt@b}JRB4Y~HPgw~m? zzDGz-q;Y$#oV59{-)pdQe_e41TFv~oBH8sf>?9C0vj;RpGucI?CP z8KB=uj8Ws`sTOPN<#iC{VWT;}>oh!gt?}vhg(aNETFr(fq5x>!10F-4JMRsTG2|55 z1qz_7(^%0=ZV(ZuEN{jceOEaP1tvy&WaHBQ2ZzZZIxwK!<>zE?|fj~>|tAa zgf?`!^%mHO_RX&PLO&bC5JDThIt_Ex4uSVAR%)@?0`643;Dh1=_71nriqzpQzhG7S zhr=X?1lpZ@TAeH0AM&8)IU}h&U=JDVc+wmS9d)+>F;GclfB3wrg&+tr&Ka|k&hszP z8>*d2(7I;!du0Pw-g%@*-O!9lEsO03ND{XR`qb-4G4xt<^mhOT9P{%3}222 zBH_t|{*%D{UOYa*5(REiZ-0@2YGFuv)R1(}Gd`HdH=&mZ4k>1~lefJ-b{^4y+)ph2 zhMdIyu)NxhYy24gspOOAt9M1MO8H9d+3L-WhL%bM6V?~wVoGn4!BQ!>K=ZOE-?{!} zo%hoxNG8=+h&uRih$X=Hve$MoUqZ1f`zKKMRmadYn-88GXt3MWufZ~GME~Qkrgc5KAmlYN;SLo{*2tf7ZBO$EaXyApqs?-2?=j{Pa6^*XSPI2OXTKdjOXJJq-CwpP zs|Vi~)?=0L4Hj2DRBaC?Q85}w({zwU2T+>7;n_m%dq4*FZe}005}O$ZCbar}Evm3N zs@!}&m+SI#!~E?`^&@@UsC5sEw8fxfFLnjw+4Xt*XR3h!qk)lSG+txkP^`IAYACAL zhV{Q?9K2#`pKz9m!)dIKE`=pvA!rYrmX&S)nKHUiUS&F2HiMKtl=a-=Xd^4@&@!jU zewNtbk|@mVPko)0CD@Cxp0pW>5#50q}a|48M*ml!sa0SC6( zyGjbeY&!wuUd5EB`IG&dN?HM!3bm>8L9?<)GlxnfE``TC30bZ}fRE*41HVAHT!TWx=*$v$((b7DXhVO45& zJKUz)$j^UZ(Q9@T&u_b$I0$Ohg|;np)~y49^bVbT-k^WVR_p1#2+{b00jW(kgpu5s zy?Yab{yR2u`O z@6RVtHeJI?&m$ODCw8|l1U%VBTo;(!tt+%HdYNWj6BxX)Bv|1Pr6r30t#4mx!`t+i zYmBoksPN!MRcF-@L-h$Kl0spfJbV})3CpRHzkhO#=S(UJ5fyqAB*GZVogUj*p=()TyYFaK_+g$MEt1YAkyGP4 zkR=A&}!DgDI(X%fVIZddL)Z;6qs2GHgOBJ&z@a|x*hJpYiYmu|Zk* z5F_skmVrL{OtrN^uvs`f>_q1$s-Z zu|3cEs~uMHw7XUW-p*R!v<%ZayNBS!3l=OfbG=-Coar`0npXq!DRK?J+GIcvAMkDf zNPW<>TQTUEn?Pfuupd4ICMlX^tTf4O-f2`UZCK_Y2tUW1w7Vln{)T-@VfmJk{P&NG z2F%-4oG)~~Oy6Llu9!d6;ye;WP-_QnUs8l%bP~iO0F;l~Kg8jC#OnTcgkv}zKbV#% z$T;M3#r&^rPwE#@3Q?+%=8C8^Dbf#D79rn7o$B1wuot{AgOM;pD8IZ|+OkVBk4l~F z>{wsqG*;&VF1;U@PxdXzL5dVA0N76eIt0ufxS&H~TY?2)`uHsL7@tx=LVs5&9cwrY z=_goeFMf3=_V^sK%?-9d7`RsXoC)xcH{TQfhZmQVB^Mt2tVPJm&j(QT!5g9zb z58nI{?%hKDq~1eNAmwJ(MVvUO2XN4-#*9`uSX$67l4xuKJFa0>jj`dM+vvzwi>WR7X)T16Bt&EFOd5tcU#uDQZ@-yrkqpDOi_}SATC8g52t1i7gQlyL z)$C}}(&oB#(Gn6Ipo*l^rYEzVe80PuOQ9W!_%eS)(3ne9IqE4HN!))_{gscV^!** zHWC32ZG>oEcdRfvTpZ+>an#0`w7pydgxqM64=>I)Kh+e+Ig<)ufmqP^_MZlq@Ic}0 z$!a0y>M|9b$9y6W#_LvJ&0_Lk;B-K{)9^@@{LqEZqq17F!YTrpKauU` zgjaG9+b)Wnd;WqGL~vg=lHOi&%N4y!qIxYLz`5?>H!)$;&DO8X2ay8;%UfJ>4h@}d z(>b@3QywUPzzqKj>x$s&Vc&B``ZVwD$p-vO#HDy&YO$~ys3x|-*7}>~!fBVmp)U$| zf+DIs93$wnu4e@ZL~J5s>C(DjlwCjtmE9lgLu+Uv@YZ-Zz` zmS%2F0*Q%FGn4(Hnts=APN%b3HMr}2IQhfr6nEFF3B8`kljcsVQE&kI@V=OW)Ij_z z>A_z7R@~Q=r0)0o02~d$!(6jz!ROLa4~OzZ#mwQ_>57_WkjOT?+yyuk|89J@1UsjA zML_a7f-|3W;$)q_VueeM6!k~MQQeTUJ-t&k4P*4%Gv`FE>%h$&TC;s_!24Uh>(R`L{ouLr2o?~XL6qkEZ4Rt5VCx3v0))B;-YrZDOf}r`NK3n2 z*1F>~GlwxZU$Csf*X|}A9+BB_e|9Hl{X|EorjGp=|tE;JuvxSD~n*p4eGp~Q4Q(ESrl&1^97tkH@ffp*9)lv$rt;6M4Rd& zF{G_2v9`~y7+_u=TYHw1bBVB~%oyldmdKUGKRxDzRw$|9PxAXfM5k5Kzl)lcLS&ii9x}-ZbpNSZ}0* zzj^abh$7`g>*E*@CfmTU_v=W30WY0G_J-ZUGVOMHKW1q_N(eb|g;V(m_pA(2WGu1N za)JGy!0uJLFq1-XFRvFp|8ea#I-H5Kfu$1JWaMORZ9VMhskt{bfB%rNL||8DFQGBA z#ty)W|K*4AHoixoyT#j`W33LBqQK}EU2Y`2e1_3?!_}E#3nb(W42B)P+*bDPbAtI! z%_R7LS^!!l^M}g^s=f9SydSeck3EUhmww7IA|IK0(my^f)&0s^jwO+P2Gw7jB@NGq z8pk_A%-U50H$Rz~)wZ>B-g$Z&tu|45d7Mc0RT$-D$ym^=UJa4;bie(*d+_av|I%~4 z-}C;K`t+isgZJ2Ce|Cy?yK@f*Z8ALSbZ0;N>3Z_NalGSg=m9qKI0d$)%zEzhO{->_{5+#Og*+sxtGJ&*)E5Dop3lbSMkrj=XYyoG;h z>clL9b3F@itgL$v=N0FOa%zJS{n=c7?0ZszgO zdeRnlmoAK|@p?(vi5NT>SiG1P+&k}(be1j!`t@TZ&6QX3zXOnDF1-}EWPQ2?Ows1?1g0L7RAc484_;N8P#ph**;?+aH!MV&+r8)<7IPg<8xB9BL#Xp1h@ zx;>0&lmxxA9mS3vz?LnH9{S}MV9gpJ9Of~zviN&MB3!pCe<`1j$0;e{Z`QCOJ9qnW z%gU_w*rTTaZYRP{B_o3!+ZU~lMz7!ILxF_<6?&i>zC(s5ib#eJkB?t~x3=fw>#u=t zzjclxTeh^U^d3E|_syE6A8l;f1Ox)W%$aP%WtXvIt6#s83tzItdOi#TIO{B6+&I_D z-$_)L@N3;~Z(sftK77*@@iOMV9EL2x0GWtj+($oS2BQ}2(JX!YTJJ}UNbL{Sktc3Y!j!29$l+P09Cnx_O)@H#>^q-@qNE6w8QIS0mY<3OvgwU#Mw964 z-^B^XeF>3>6?bm`{SG*Qb0#xqGRf?WGZ?*OpATr(j9T@1dDgs5&z{_G+&D|7|^jG0ojC^s;J|6^zibC68Na zH7hNh;3i}3GT=_y))EquUn-!IgwpczoP?j3XA!!tE>&6TzRsMTh@i|0R5jgf(r_RtxC$W&q4?i$8^|srn{Hbf>+Lu9tSj6RX)) zsS}@*OD=JS!A7H$ir%z|6QC_xFp2H(!+Fj_4;2~N*p#qMAHD)g!g2k3k4ypU*4C>> z&7o=2D9E=bWui^fD$m)wH?xq_!k$Rx@lXfEeXgnvm+)%~rYYj{IkFljFV}>M2I`^zZM??(W)^?YjSdkuSd3y;`%;sK~R=TDc&{9K+DuB-qP=YSMQt{c6J{ z{Mtgyr4#?7c|5WMei@`p>C`E?6rkPG*TqfrqP6e!Vi;B;(h>}C{DHM9XQG8~U)Q7w z!zORdCHW5+U@155F+ndE4n(8WlDYnR%2(*$yLD@ZtiJdn6+T8RUpLUNs4(2N<$$x8s;M-wM90dC+x zt7K*IjR{GB%8)X6tL-C?Mp-2NvBy}8xNl#lo3Td^k-z_)8ckn+U44UL!v>B*GBfE; znm(P^7>C`Z=*H()8!qA37A8-2{v(wV2?XTKGp#?&<(FGur^k0IMi5|Cr_4;t0=JXAj;u))ag(ld=+ea+8rz$3_0{}C z7Zfl`La%@O?OMD~E*ywP`TI0##Ja=%`_t9)#TT@MFTdPLpxwGT-FU->ar>7BI3si- zfK(`tM3hI$GyL*@olS?XQf6l5b#@b%di59vI%p8xGLt5e;Q#$^jzr#jkCy+24HQ=U z@=NmdnP-ZlQkG$GF6n{`Sb1#43QkBjY{>7P7#fslMy4CFQw_L;UzQO16)0!Uvo7QF?57XH0E-is3~l zrpFUPQ*4M!9B9oO0J!ct;F@cgZh!H`z)d#+2OPk{6TN%$9QEr1vu6W6djf|X!Yua7 zF5|gRKA9=-F6s^rJdnk1X3PL4OaNYZf%-@%pA0Np2K4U_+VqRB`RKlzVvQ z8K8H`5={8)!dSr)K%gK13=u>sqWIvI4Oo>$LAJ(?fm2Tf&N+wAgK6^FnKuvk-~+a& zeS4s=kjs!E)av>9XX@@GzW(~FB`l|rmBn@I*0FHTr=Ri|spLZd>Hy7~M|p`T3UCFy z0Lo!RqlnCZ8=i%Wpx$u>)^-`y=@s_Y@~5%zW64(z3qLj_?cF;$zJ6yddcB-+hVv9p zJmGZL0L;>S@=3mb=_N`r=#a%uaF`>@ z;$qH6Tz4H4!;UzD*OMr#tw)(%y3lsi!RUOaK@=78o(Y z*^K+|r{Go3p1|?PQ`iciIM?Ba*YG`Xu}kp#fmyRy2J+^csYVI#H~;7(itIi5D0RmG zisrR$&G!wk*-^?+0ZD=jP+- zcGsd{(1d5BDW7`-@f4Hg%lmd=#z6AfY zDN`^UrA4SZ~-6m^;^!T+Yd%4D*7%Ibj07&&=fSIDR~92><#kl~6Cm9ROlA7-BFW zP@X7ywcLQMKXbqS{VCrZ4g+6&0lfE~rNG&^F{PG|Ituv9U--UbN6I8`+{kBd;X=B7 zmM!BtE$b~pLSMa_?cKDAokcnr23=FRxvVKrzrN*Wj6~S!e7Y?kr#D@I-W!YYd$~UWn(Ke} zscAj*ZQDrtIXS?~FVkXNyqMdba!QTf0T;Ug5fW*eHvDZvA^w(a+w#57M~URdjafTH z7m+VOF+7OI<&f<>=gBZ|?o$OgqA5oQvuAU((4+}4W(@G)gM4H^`;5!ypL3LI>1WI!I{gjNJKcCAx@6clRcvu+bsH1>k!<-$)rcKtX{e9xP&6}-G=u70| zW#nTDZgh->2ZxJs#}D~fxsvxLQ4ZYa<0!awYjy&iJF}zf+?gGMmY}XwuDiIH7Y6`O zKFQa8mGrCQ_t{&^pTdW4_um_a$mr2lqyeZ}SPEat1S(zNxjKtoZPBiKVqdgy*YxQO znbS#J+1d0ByQn)TE2B=$q)8%e+gd(z{afC26T>zaEU^v$W!4gkiX0C| zbm&kiM}}0ush&9tMe&Eu{!Hnbs`@qE;`Q=RnD`v(_x9}DBaR?h=*i-Y43Sq}sqGu( zV(nT=3Y>J3^?PS$Gk@aNTN!G5*kPPNZPtwI?1ZZn6X?G9g2m8F;FkzgGTB!V!@gmI z$i4T9^y_CmTc@1DM8U+c-Ds2(voF2G+>Yapb1H%Y?68hMp0W9lKQ1zB7Ik;*MoQ<- z)c>C|$I2kCHnf^+FzAr--f?$O)?N~jrT4I){DXftrOfb41q|7t{PNG7po82?;gwSO zq{4R3q8<-tms7={>ZMPgo&Bk694_J477_?ws}$N}qD$dR8!b^>oLXNe)zYYu^K;Xt z>9>900V`g*QzwaA{;o>q-a|CX$d(&#WSqHOIkTvU1Y26l?FtJ?{wr6qfQbGb?Zs9A z3gWF;p<~u#kt}u#-!OJ6OLf^YiksO-FHmrdg>{vZeDt+$WsT|iuFK8BUzDd_UN84 zJQ7x!jt()Rltk@~REmERyWWW|_-v{vp+^P!Pm}1@N&IYg=WN`_1Q>wUWmQ5~E_NNE5Zy2rU+mP#>DN!>+H2{mNYt3o zNpja;Pj`uZ^rmGwF1kqM=%dL`efo%;>v7gca1j13gfW(vQ-1l_W36Xx&>(g`)qP&J zZ)bAXtXb6B>EGWOt?cvB_~_EbX{=;s^7+lnOBR*WOIDW1DXmQ@M@G^$N0djR8JQCG zF!?Ml&yb49wLqKC$6nVyYS8O+g||9fBf=&8+Cnf$%fUwU+N!9i!n#klBtG;*hw@dA z1hgMFaldinICQqJ8#08=j7CN7xP$+Jo;_(vy4W+=xRJRJr=M;Sw9iL{$@}l8CQUm0 z_#->Gn?<7-cMjM7x zeXy`_=ZL(HlY1(-gkKBTvB2cSkB#iZ@W_|wA>}Y)6Sm&8gl|tVuWV6@&+)i%&XEAX zNi;2=+rGWXXP;S83VInaf`3R64#RVE=^lFX&Dy+s`!>G+p00+10?Q(9-kga?FTF%- zw<<&;Om@;^8Lzj`%01;gNkZG|#+%bimd%F1{xC!AnCtBo45 zP|MJvOxViJP5sPfX3~d0a3DvO7hJ%iEss3H=Wgy?)(N=sN{%WL0~qWooIQI|?e&ML zLFashUPh0uewofc30%Uj1-#O_$U*ij9G&5q6bjqK&sw!go*SxcuE@T0>cmOC<;$Hu z|CTK+t*ML*j#|$-C-oojy6fmOUbTvvCLRxcu)8XkyFa0#f`Vp~CtH>;!239D8eJJX zGe5F&B?%Lte$L#voG`uQ60RFIjK2P+O-b@U{lp1VzhC6GlVhbTZF5C&cC3awClq4m z@zF<|M4dH@#Cz6RRN?H?Cw(NC{dsNHjF$M-SF;&ebFzNp$06V!qF}bHgbqU{%!{37#ISRl7*5|L$1Ksc~j9BJl6beutY|Ur_gc-vu z!eo=uQYM;+RPS7?R`GSMn;;#I8ux%T4US53_c>Q%sCS_(a&iuUdfa8v1toP2K zq=cEWx8BM)@~&N(2(@h+^CsST2e{}Wp5x?`nK}K>e^LYIFR5n@6KK`>raFoHcOs0dL(tdU{?%i8WwuLX5&sMr-dHbi4#us2Y_ zcD*1fc-(<0@vw--)1maLEvuMx9WSP+sF`oaMSd6HYnpaF5se|D zFcE!6M5i$GmiTwGi0CvTiV@M-%>2slyw^Xy7?VyWT5u0pkqAY|OaG!7bPJtL8d+qK zK|00A;0XOIau$V&sLM|q=|w7`%bqBrGtVSy|HE=BW;>lin>Iu}HY`t~Ss3P7PD7$q zRJEgo-u(>w3MqbEw1ifzDx#h}k@Xk|U_x273ZVbR7noe4QDj7p9ZPiBVMI6Ggzsn1 zCi?0tqGz5#a?0OX{_`II{PWKfz3~RXD>oPIHFhjOSx^QvMVN`6cmk91+O?n{sI3JV z+NxDVWn}=;1q+BKO(OcoKZrVXAUf?d?4LJ}C_kTQ#tfo+A8kcLNuwwc8AJ&HTo^r$ zCXP)8J&}1@ADA+O@a)%LoAz9S_G9HrY+f(gr&TK`5Pm-r2Gi1z8SeARea^r2eTTnO z=!>O9onE6Dy){7%A>Ww45$2t|IRtB~*585f#yLntx0c z^*FWUZ!>r-3!3Wl&l5fO9JFmBWM_^U1CTE&`h6^;D^@^juc`uV!O)>Zx84eH4+OB% z%FQKu>M3Z}-+hP7(7AK5Dw{Zw=z#~2CHnnC%Sk(AB>7m7&{zr3kC2y2=uP^(MG@uX z;P}p+k#(A$-WWh_3ix6(4BW-mtzhq5umIY>$3t}Z;dr*g4%-d19?O@bQ5GzKCgbyA z_WYalTTRnGV&;Jj9@rSWPh&PBI*N!MivK^0h-N9@y+TAq4V~k!Zo^-3qU7(6=?1Ur zR%*+#wMXvYe^JmRRgn{Qe@st(Y_MhWK3kg=EBr^8IhWF+ck(ih;LlC(Yl*#mxWwXTve* zjg`%tnWs;OFEKY4w(>8&fCKdK!(}<-!Gn>pD&&F-@SAn(m|uMr$DDK${=P6ozV`@e zjyQ9jUn~yts8M!js$szKdD2OU&5i3k{M^q6L*|r|VL9#n za}|BpxrEksDx&VcET<`tk0c`&rkLTQg%g*OrV*WV|41^TVTyTt^kl_S%3HsJMm|0j z_weeg6eSO7#1zqdRH`kdWmXXl^DL*z+$!2Iyo5Z%iYOxkhrj$X(UK+5UOk@V&FfA6 zY#8_}NY0*nj_Af4q4`dj0JB-ER^a0D`(d-c?mD8WQ^9B|c#>*r;Abf-g9&8nRM^Jv zyc55B?w(e32x$~0jf{Bj5;lC@=cUotl+frRK>gaa@ZpHqyRQqO+Fq3%oh1T!n@p0~Va0-!5GcY{I7 zT*vQ6hVHAcCTH3C7`DD`A8Gmd`Ssy+C-G8`$&t0DQx*Dw5o&-Ih;s)*+*6c zD;Tk|S!$KgY-Ppra!m;xn^{GEEldW-$S}gRVQmc&VTA2Pdwu(MHq=;I7vz*4=CRYm!Ct{`1 z{)gq%?T0G*reg_x-?oTiF`_Q(mQ()PD*CEz34PuI{*t`!meVLt75%hV32ok|h%5_E z&8=IB-gyV_&Fe+If{YCG196OH!Fe8w!S4S3_t1h5ZMmEV?x>=|tuIp=)sRj^Q6gf} zDMs)W=|mI>$LO}Bs>mE(L<0s8_2~mgZ?|r6ni7FNd-P~~9feJsBx|Nv4Ltj-bn>=s zD^~$xCD5%~(`bnE@=&F1#tfW)!2)pXKk^9t3==29S)HHX_;V5ww0SWOV=;vL%$INx#b18X}rUICePOG z`$ndld~3%bPaA0RzWc&1UPvb2)+NX<%rRv$Qrw;%dCTO|(&XzL958wGXy&sA*;gUM zeI^ec%zWdqCVz5lkk>qBO6@a+4S!X)Ql3m9zQ4lc7lsD8h)nL?J9&jOtHk8zo@0() z;j&UO&E&+M_&&>k&tqh|$wLj3>pa+}YMPIqYw|1&ZMFaYh=F&z=Z`}KWet^ z|G1`4dm{0Qh`uGFwM6u3e7i&WZVn+-b2Sl-Zp``qCjj5?XG;SG@+))E!6Fw_@;6#f z{;FMZVw8l*;5)PmzA6I)|9}HHv0UHXCIMYX%Kw{hVgT27Y<4yVvY^mSwFz1hb)P!s zoD)y4UdSY^tYp6TUNqgNO=!mFpLZva^ZS{vA7}EqX+eHvuF2<~ivry0vDw*3{+Tt4 z`KhPuGzQ{X&pZ>Lwr(Bnd+Jp1-Hd6C38sk5L?-EBIWC}`!dw;8Z|S`xhprdw&?ir(4sOk>!)P)dYSj$TaF#K@7<^&)ME_; ztA_slp18+8{dS)Kev^r`tAiq>S>2L;xmt-wp5{FhDYc5+VC|;6VIeR0R96 zkf~E~4`O1tw9j3IsT& z8(gCScxUSkM`P9Jix4Z3DCzDRzBj<%l~$nkE7>!<-L^mg8LYXvc4b4?@jl(&b;pk2 zWSTh9zB>5%XOOOa_89P2SXaQ0;@wsJ7P!R01kDb=pFksRuEyd(> zn)=X~EB6VL<+chHt6Xu8! zm>ivS25D(%kM`}8>A8t8Svpq-&pr!^g!}HpSUC9L+mm;rO@TX5PL%d3bH# zj@96>VY1(j9?kstcqEAeVq%U?b5iil|S1$R>S|C>f0Ek=5ppJ?e) z+HZ0ZwQr9wxQ!bT>LwDZycDJwd5DO~r^Sf;J{nTHlvd{yQOlNyEHexYjaa>DYpF#z zg&QOL?1NPMZQGK|#Wf@u8AupfyB7B=q+L5?46k1=Yw+geAiOX$6ZKG6uSRJ*A~-So z_JxzNZCgC|0}sg3jc#HXNMf2Wfv8_UJV(2B$SNK>l&F1slqCKBdr%UHZOs~aj^4fD z*BdklTf25}9*T(4{r3lD#oKQa-E)t;-<~}Ya@nH?N(U}nh-_FgPusjAnMMAq!T|BY?Smd3qPj|cCxb!%kIY8v|Rk3S-dTS#s$ z-f?<5-uUSxW>f4nd0twOKR!rm`!U_%H>jA`_92 zTR zR#svX895SW6I&KF`S~`gNW5=Rwy%c#JltoW&~tLo=4YPCeEaQig05HrMoK{~uht4t zC$mW|MC} zx&GtAo&f*+l*zSkm>l(?#;7<>(;V~>ae4qIS@iukLYU)WhaoKS^Am%7{$L4Y4QZgc zxd>N%>n%7K=gdLd@3&vF(>NmoE0ZZxuqs=;7`0@D*6nm|iit(_hqP}mL8)a+IEGEr zJ-Q?sh4$N~4Wg8O`bj=dt5yIlaqXfa=2u=pxZ}EMG67C?{tnSit|4Ed_Ck>|QG30( zw~if?{V!d*pg_wBCqU~L?UI=(!CxrJM3{663eb1=+Do3NMGI*0S6zk4WYZ>4IluD` zRxeYg;5R*bG+ejYIYEe;01ZWq5#iXpJUMaX6T2sO8=mW4nMPqrc9AGUy&%)sS|9NAALmBdqNS>tRi~+sx5R@-F1@YcJye{ zo_dNX9HtoisLCoK%W_aIq@ZVbgOm4t-?@a=tX1~KeDp${X5`F9cZ*@5JyHpi6E2c9B&_+h)h zW78(0%P%Lo@=Dm|FS`tElZF95#ScG#q4NCmVbhO9h@N~BzjMl_O`tTWtCRaI3w{#u z|Ia@Yb?E|I^7idWDhh>QlRo)mqLWU-_e8jdP>ATj1BqtNgxxqU~+nl-ZRbRF$uS?IIsa~lTHmtVsFLWFzl)eGlcxsqtk9PAGS;1?M_ z9LxukC(EQSBG~W0_yUA-D_4T%d&LU7k0B!i_nDD_cCjq@2LAhB{N7D!Yq1IW^;e?H ze=VUAWRRbbXKmfHfQ*w*{(B{4HD*@WQ`=uz!;eIuiCr>ECVj*V4^O5L&zhC2O%Y)U zx_UMKzx!_3RW*${NR=Gz(G%-3kW8-85j_(2 zrlw(N%)Uu`n>?yT{m0el0bYEG$y>L^i+kT~@=L>md~`?C)i!7_!5)9_yXaxg=F&UhXi^0 zK=<}jwR^FDs3DI%JlEuh`v&>Kp=QFzP#E{YsOFVZ_A&W`aY3$L3bVrb=i|6J2Cmbl z4T{^S$yl|u2xWZTU&=8;$;_DHWh)*HW?9U?y@nNLEN;?K`$1Y7{2;37N!RVsJDLWQ z%D(#|a%Qi+?9o|2_f*`t~I{@kF9eKgD_a_eUgxQ@gzSY7lOvr$f8x*%OfpzemLVEM83X z_18r2-?W^%{!m5l`b+4`tRmX6gJ@6`Q6jHfCG>XG!Mm?Sj);9LTb0l^t&3>&>iUlp z`}}^QBaQ%h*5QXki~Q;8pYKKkvppZyQlf-j^j7|{JZQl;fe*Jo)Uw*-A>X%>S^>iI8 z=Wg9V%h0nYNa4D4!Syp&E~jpjLExu*4bo0M70a$aQp;by9CQ#RB|Ci|jg8W2HtFml zdHiv7?0@`&h;H0SY+0m}MP3Ti;7Ap{qZd(eF-!-7OWo@Q_qyLtwC}z+2NAf}RbeLj z*T3+;2y@HNPX_$VOgWGmBVv$TbWxo5eMS+z_g)eGdNU;tLs; zo09_|-Ly%Xf;x5tP_J8uFinpK$L-jG>j+^+Rj+N^@VQ41gu0fMp)bGvHq2HZeFT$^ z#{;w5@Zs2o3_-uHPr_k@^{!kgO+zbJ;yHz+r-QGkZ{H$1Wa?5H^4$Z}X~_cOyY3?G z{`>zp?)*FNB&w*84coOVY>c~08nX=8Q`=wFq!SLqnKxlVe1~arEX{7tShNVs*yE3f zla7e_iYpKWQc!@O&76t-XPsp~|Ld=F!hx2PgJtd!M_`}dpE`=9DceB@*~1mLZ3Cx? zx)diuGSRGAO}nPZo^4EcpKuViZjDHicixelEWiB1eCM5r1`!b;fdKOvo)Cx0uw|S^ z<4H%ybTawDvp|pF=2Q;H`Tw1c=2|1bqqE&jSRN1av7Jq>GhhOXr3EnlkX=x`|4sUO)~Qd6PHND%FTs&rKAKQrqiaui9LO~ z%(7O`;q@Z#uRl9d{s;kqD6tnVA4KW^_n# zj4Fc%%f2voE}|#|_fB>;`iI(IUVL%qKtDYlQ6NHg>_Dhqj~)nU5YZ9o>99G^m;qa> zdJea6x>Pa!jRpTMUEt36X>a8YghfdJmiEhn1% z+3`VM`?$%gR^i==51&Vy&c{$JKsW?Q@YWbUVO-axs0Kb5<- z8!~O}TspdrcM}LSJ$pMN1J6-j&V2I8cusYa$jgH*zE`j02%6kn^i@%yod{u_`T6b< zPnnrG|5<0DNXjXvU;+^Ltm_y*=beWPUctZA6j{HX`NLaG4tqgS5!O6B&2J}}6H!Z* zm5A*6E50B#1k72sLpN77&xJs zp;d{=sk&NLS`t7$Y7~-QoMC?Th0dkAu3^YFa84NF|K7b3GycstvWXTRuA)#Z(%JVmNHD}jeb$*FT8zfNk`_W!KdjhySbZ{rIb8bE#C($;f zrQtp1}#pF<9@C%vidsA-rWh7Lsz!M^*->uDMitX&!X{Sw- zr@8P#>|44N`&ze_1FA<4wt;E)?lN|{p+TDp0ED(bemu_e-FNu>(o4|9($nR#zIAK) zT=i{@iMYtffQEP2VacGQ{(j&<=KuRYJBd~}3B{`YgZ!q zB~f9?@8=_0nSA{5_+GG1mXrWUBN65gKES@LEP0-2RBCj7Kaz5o0RTRqoti*3rDSDc zU5L2vMgdN%R$-ufy|4wBmAL~#DlM@wlab$#CH;N(K}$}RsH166 zmhQO2K3T?M7*7{mASXl>z{LOEyW<&Nc?IuLJ+@yz=1VR~Hk%PagB2@^E?t=a^)J|s zYickl&z=q6hyW?C7n-y4IRXKg^JdLrUbF~_N~tD+b?ca~yG~B7em^wi7hi<(v1Scy z;a86}d09p&M+g^>lE$}DMbb00Xn|)u<`~rUJ^5rzT5c;XK@yj00@E}A@TgI+#b0p+ zCZ+mF`5Iz|O;1OE7J#m4n5YU0aGgPe>?;G&&gyx)c7>ndkw@ehVrDyUzQ>bP>)5sK zK}AL4#1;{MRZ_vr_ICk%H*jZ8HuLNvX$Jf~BqyDOfv-9|Crx6$$5+8tTt%@AWI_tt zyrBK<*%Qt!X3)tJNe3=7xK2bTKjRGhb&HGb8mv%KG!287NCIjg;7&E1%IxCI2-Y;| zzVukTu74AplZ>Xw-av&y`Am|Rlv%V-)>^l!Pv&bVk< z%%6VBeA#98i84DI6R>Ejj0|wKoOho6xPb#vKj5N^><&z~Now3Udx7pPTVQWK`)vCv zNSz=B4TSjIx;5H-&K#I3)~vBl0+t0OVcImg+GyV%tH6~j;|Gb7n*yM`UcSG=Oz_jB zqCRNV3fG=D54d#iz4*Vp902Q#%WsTEpOb@?ML_{<`cAqFLBBn07$#t+pTXlvP1mgU zv78*VU3PZrW3#hiio5!1<_%Yc><^++FO-$pAFh9Y8{j9vT`6tKe!sNi?24r&n@D3f9Okbo0%? zv;X`DzNWkHhGTQg7)+4$Y5y4+Xp>ZqeP{nGE{4O_ZFS)B$RsWCTb~bofB*f_cAYvk ztW11F{ap*mu&%pztkP0GgJcAZ|`DMB9{r9o&rAy_kAJ$>g5gM8b za0?b-Ur7l*&!3Oa-+Utn!pSEmUt1JaQ3uQY_se~6y@l&I*&kK#cY>YUAUxmz_raKm zHi^r<_hNAM>)yu3WQO;tSX-5VyGyY9m3DH6fC-25c}`u&@v6ciGI7<=wQPy|aQ-Gc z8I4qwHFX`6+1$C9xc~7F>>n}&WNBl^$_cVnE0`Jv4^Gxj^Ybyeu380f z_W7W#s{kI06TlrDFnO3qI8-%`X*$$nQO7TS{A%i%IKOJUKJY*s{_L}GGT(9wCdxj2 z?AX+<9r84$PGznfW^yfgIYz{_mZ+znZa>waL2u?X-wgD*AbCs7%)0T7V-5c7zh;kFa zP6UuvClGbZ$dJ4&Vqc3E$&;AV^dg?UZ(kX!e%o!h?2a7BLnT;zrSqzLNfU+ zy_h$)=)~V2Tgh8mcCu^Lgyf!UvjtPB{W~rwu-(koBg^^l!|ecAT#U&`Ool!m+Vt|v zG0|?`jK4SCgcYG$G`@y>93zeEbRQ4%AUt#b{lNzM%P+D&#bWT$2;lGC8!G?-{OWOE zehIVIX{RB&DHVWcWWWi0(M8NpJ_+uq7hgo~i8_I+tCsfdaSuIvx|^8N(lA8p^W&tN z7{vE^dCcb(nY?;Z5M~;6>7W*?55~XG&HdAYJu^20ev`zlSA;_L9_904UogmAS;;^5 zLsFHRNV9D=mhShSZo(+4>ukkItp4+;1bks;>De>!(*zJ%7M7vnvLAk!`nKoJmB;CE zW$}q8`M&p+d_#1j+mxHoATI03?ihnb(Pc@N;A#GC73yplr?A&J`2tJ;DhVG?WdlSmuc4y z$t&Bp%Xw=N>#92*8z(E`46;DA`IrAegdG3 zA1|*%1VG!i4IowDWYfJn!XAZfT1-yI9fxy?!S46tdDH|Y!$7Fzuwm{IL}D^jyMg$< z$aF1hYw{_lFu!~mXfrGwNp%loRB%i=kqYK9BHlr193?$L^>7ItFlr~rn$M$yx)Hx z=Z?joK!}1Od+!ZXjY!I?Pt;Yw>8E4zP=}LKJI`eP8UO$w07*naRPWLS6VK5{Vn8K& z$=mDL5t@@_Nn2^3KJr-Mm=oq2VPX*jCK!~UDVFq3Fn0q=r}pOa$w7L~Ik4TPrvp?z z_yAyW^2s<>08M5loPNgyKPMH<=pG90JjdQ<{q8D(Dvmp z8JHY=ac&+(wrqh`uhIn<7c+nKk-bl>U5mVhlTJeW3X@KhG!E-Ner2v{GvhF$-Cuqg znZ#lu@7)_Awm<#|@Lse?W{B^#7xM!TG!FQk&+zK2Py|MgwihyYQY;G)@72qGoN8`t z+ZOkH(n&JnC=fvZdj5GtV%>Tx6svFbo_6PK%a-V@e^HIzDb0YtGvb`#RU5uo@;L^# zFx?1nkC2g=0OWCYGMU6u-+(GDG9txxKb70SI+ch{F0?Zu4EVe6mit$)#<5G5NN^Rm z-J*pIIXvJ140-|j6DKCyWm8cQh$Xf&BvI3FjnhxZ;7v<|O*j^VMoJ_>MAs$7#Jlg> ziMgCxix#Mx`|-#2nyei=N;8jGC1qs5Wbnlo0L&ge?Dv_Mhskf)FmUUr0I$}E6;-8< z@2Zw#^l=UOIYK(eNatyKl&i}XQva8@L@)&A*=l>+g%7OB<&DO8TuV#C%ljt zDN%;}1COaFkCyl6ZebTH=1K`d*I&(-rdr=Rc!?iWIA$Q1MarHJmN7E{}AkL;!^SocLI#qsU#AlQ{?thDku zuD$19+<1HMG9(Jy)8IKR!>$~!sF|>LcawgX5irij`G&&DhYs31T^hnBq%{Lt#u>pl z?AfWnh)G2g=()E&Eie9ZI~O5Hr_njw-Th$?`9zy&JxBr{rsfg=a~ZvtC`hMUw^EH0 zt392P&g^<;G|ZJ+!-kOCYpRh26D%-%d-jfTwunhYCE1h|k$<4VNQessOfYUNGYoG2 zHaMDAxzfEsy`5L@jd5KLjK8W1SfjtP7r<81VO1SLwAZ%HZGSa+Ca|PEv7C~e4n8fF zdWUKcTUk}3ptY{_VW}bBd!MZ;v}=2WX1MZVWJ3=KDLwje-mU6=q(b_s-+Fh3#=yZt z&-r7%Fw54H4CFnl;%@a_H{O2DuvXXP7~>kKumNZv9!V?GD}?)BFxFCiSc46BhT~ZL zGS}`2%*n^Mg#LS1Ub2w!H=c*H6O}kyS##WY95*uGhx?d z$O&nhg`$%;Gego{2AAD>V3XJaH3L#04GyzoE4KeYVIv{l-~dry4HNxZJ?}0dd??fm zE0PNb7&8kX@;^gR?|gC|UR^Fgs`uhkez=Ra+R7wi?PmTY)j3?Zo%~lxJF7lglj+wy zvyC}{a2Y~LE!%v`4N>D78W2;j(Z-90=z1(K+^tNWTQ;O+wvTD$q|BKe30Hkz7tNG< zzWqnTILrU(kGdRv z$jyCGHtkSRp(GrBCF<4(Po+Pa>6`ZGErRh`L$ftB%Bp}8ucRqNPB-l*@?!I}bDf@m zO5H5!!2wU6#9~K@Ujsc_$%dUaZ8W6L?2`^5`n5nRRgh~J<;G53w#T|MiwgGzG|I}v zkQ3+pvzL;=$B*?++C2A?z0NXMt{e3{8AL`1(?8+xeLb0CTV55 zl>LRO9sRKnGE9vh9eU>~Xf)u1Mzl@LhE{VGQe`ris6$ph@8+sUR&K_9Up7VwATv{X zOb_sB?E!TK3M28Zz^TEQMKB+}d?s)#xsnQ&Gb>r*5|6x#Mi}i#W8~JKFX6hc`|-}s zc7F1xLV`t8v~p z+XK$M*xg43{`ABzVd6M!a~1DvU4w}(%a@zpw^=dv>q^25ijv12>Dxu=K$elLH8_V+ zIG#|2ZIx$*gbTMhO3wt~UY!#vjLal*xcWMSUjyoYwyt*WV5({}XyQ<9CzIIBVSOm2 zlGw28w)S81!q^xLyxa23@BPzMaYoWfK(Ppv_usJ#UzXpDf!z|Mxbc!@!q7WcjCw49 zfBbgzZWN>Ox#++lpa%54^fK_^1-kH_fr@6$c2%X4QBXF&dvLL8bq$)oJ7d@zgBDcJ zn^}dE`1j1IVK&}s)i|cRFIJn~K4wKou`N~QG+*M;l@+b?2?ODLMO|eMTdcTah1vaNZ=|dgK)aCo6i!LMxMR0py{>2hrd0Z$~+TC1Z zh3B=;8LC`0TVDg$wq^M*4&8OLw51wwT$Q0%cVwgTISUWdP_f7}2uLKgb7@3xC)t5O z;r(t8(zN+#+R`0GkYGLO{CUvx)mYEicd|>bTvM^?BpXfatHsui8(-1b*$7lLx7K)x zw7lT&s!^XWGcc!GpLltGECErDMR|D*m`LLt(EoPu*Kw^d7x)izx)F>OS-cPf!^S%X z%yo6Xc%uk@f$;Vr?~S5Bm<6F1!ammGtu%;cQKqnm0Ehdx0wiDH(kkbu#`-<=OV{Su%H#? zQUr$uzJ2r0m>fk1E@`~vK>*L%?q;#`6u^vwmj;a_nl{Zsgy`Ln_50)sOXApL-y?k1 z)24O!t5Va%GH6J6lQpOucfVU!F;u#h{99w7eFPkQd}^rkpEDcE-~utv?`j&y!UzPm zuG$#5I<5;bTFOa~?afiUsjwgaTRKiHlhM{xprvlHVny3EhW%teG^sHoxGfnnZj(2x zwBea7Dkl@3Ywt~u;FLT$eirIz@LhtiaXF0*keSK=&3+lA;o(QZsEr&GQlh}T>oGHw zr+**8I{+ro`sy+KQd8A!?e4e12$7(!+^R5yaEAe}$&qZ?u(!RSB~qsh4;)J_pAivp zNYAk}_`j2uk(&U1T>zE<~SR z2V$n9nJxD9Oku*P*CA|`(=#>gM4-QGKL{HA3aPmPYPF??ok5FjVop%pl(f+Ze75jf z`joxjUx-sfv;Mc8H6J0f{Naf>H9|i~0V*d7Zqu@%0lP+S8>Se(;m0OtWUjxTGdPA& zuTDBOJM%^!teE%gUa_A7KE|JENAPy?iVhLIA2v&5zEml~#^O`w(Oq2XOGkRRo-Tr| zy}nc1*P$IVoHvBnP<+j*x6jq@xwOm9iP(7nlPw<2p6N6k*X+W)v%?|zbIU9H_C&Ks9K-Vteo7gqf($Nbpuwl+DqrKe`w>b|H zy;|Zz5{awp#al~Ode&-|o{>eXcp2|r+ln&nmSMBr&0^B=&*fVXBzVzm$~IRgvehfJ zR4z3}E-N6|55XwkFOCLLLY4$T0BwABbU*y*V8BO5dM1E+3FS?8*!YlP7KYvk3ln5x z4s{sf=;5EBs^0G(0e5x0c>BgLe5850A-3UkDTZKV9Lpcb$D|=Q$4SWbXFK}g>}T*j zrO~s6v*m+foPOA$QPN9+M_H}HrTazgT#~y)nTBkTKE+U+^Ej2mgge>sx5mk{=mwc_ThpBu(y&X2yn{?JERk~=Ayj5o3HX!+#5PmrtVgtxiE zrl>`Ta^+WJsD;-J4lccc|J*#OEP5V>a+}W#T-Ae4dE(wqh8Pd{ZZAEQ@}uxR37joo z-$z=Oi%|h7D$kCD5zFMG%~m}VM>@gI8|?ow`ZjHT=P*S2Xeipl^{6E!5J7$dAP)kMo@zwT1vfd{RY<^d_eSMZ%dgJB_%3mlyycxljvFGijETPry=Q|97Bdo##`YD2NG&$qWnqFm$-dt%nVEUD z#Zh~y7NH&oEN_o1BhQLvmSQouoV%XP)NdB?)%S^=ar4-oks`#ro0HSdX*nfe zt(7^MhFoHBn|G}*uqYN!eU61trwy2q?i^G81)KX(ybZkC%k~yha}i7rq$I|Sk>pvV z-osyQ!#V>~$wC}e*uqGg6sS=mKdYPsq2S5NBHnn(WjjEphgW3@_>G=p2eWb#djecPxNiWA zOTq|V;=%`{PftK8fseY|1mlO}tn8!3`e*61498i-xAF%#>B!}Av7;m092xSELAa;C zSQ2v^>ED7)R7ulKzmZ0?`SCHL??0YdlX*S07{R!#qjT5YOs1E^$0I2?@Nep&UV%Hr zJ3m1)OT1XAOT$nAdRPNd*{P47MHdWq@sD040r`f^^-0xXa-H?koy$^) zq{p<(6MFWDKmEy4ZOgY1p>n5_eufc3TNL>rbfc?l8_;L zU%eks>*g8^)Wmdthj%^DCq+Uxk#!2pz%4Q`=gjvpUE6K5YHIAlRU^S~EHrtTqUxIR zi~YPy*AL0`#_BLD=G6QqYkyG{ZgUA{dW#vPad4W_isTTEGF)3-~%*r`VEk@ zwbK+`j~UT3`730q?UH`u%sdoFrSf-|mi3zD1)-`7ov_|LVUH!!$eI6oz6>Qhm3Rny zcquro*+?^^MVze}92r{}&o=W9x;HbJmv@96o0-`RApAfY8;SB8x_JGtc>UzW@689# zsf^g=#>o4ULD5yk_d#7(KFQ=Ba3Y-XQMh~ zN~{(C#hgqJgG`N+_BG7>ryw($TVd|5o%?E|SaL}FgN*NLz1_P{6T{&K5$AR!HwZ+u zp<+BYzllzla?>=~)e<^!etZtcu5qW7+Wj3)6r!P?;ea|^KhTGEiSq%UKJ?;rYeLI? zUdJ|jK>F$>+lAZIiy$edaunry-h!?f$bshk5T?q$@AD2~5BFY#Xl)pDlso9zb|1GH zwa%G{Ddwt=jGk>Z6fuo*qmKQ3qGLpjyoBOF=QPPWwyVs#z2DY+*mFmDeVJ$3B5W( zx`M=n?*@og?gq`L&f`SbJEiAMc!}Zi5;XmXw%wVl7Xaz5SCwp#xpc&$AKvmh7n2PTZt249Ts5YnicPMlWNXa40z|2tfN1f!0MGaNOtcZorOID0y z+rOq+7Nr}+5k--OdZn_r1=Bvgt#&{+UcaYQ95)8qCzsN4 z>oY3l^yO-2k9nZt(Z-vSKC;>hF{}ulG2RtV~ZS6CLcWFT-7?gXBjX8ofn@bpL#U&iwxO3 ztV*-X?3WnIRz(De&T;ydIlqmUal0Z1w&^i>II}O18%@Yj#M+PuX)aG-z)kD`WI1r@ zsDk$6n#Sod1G!xiY^yNIx?!_8fA9fjY(C`%%($@q>3lWL zlT;uEy6=VuW4h*T*vG+0nAj~Bk{&+nFr#GGQy{X_u_G(TIYUhE!{z+lpskcaKR9=BV%=E+E| zKh}y3mnSHbivmJ}^fUrY<_u}sqmw?hk)i9d1noJeqJkPTxT17XFME3cxb*X1ekbfV zwo9`)MpZBk3WgzqUxRB)YpxgJA?5yL6A|L@P(t3|*Do~b#GUA7Ba|UaQs7-nE3U44 z^Xu~GLz>bnJjq#!Gu}3SQCsXWL6NkKXBjsHi5#88@A}?p^_F>RvK~jmau^(HH<953gyaqSl`+8`PVE@bitk|e!IFAN#jn`l1^_g znO!3MozysV@Y%U_{@_>SWK|++L*lpK$xP2x%^xCOk88Prl+?5hM;q%yTL|pWf;M`E zQcVMtg4+DVz&9~W4%%b^J!XUO5#K-Y()#Aw(wd2ejTJg9kU&<%*&!gdARP-+ki{5Q z2D!s9e{$o5qR?ZWW8I=GcjwCvdXf7<@$UXE3UMopoTSq2^|xd~{|odeT#%joq34#v6{?D1D1&R`rTg3!AL3 z+Qc|ObP88&Ox2?eI>~}(0P*Tjc%H_e&#v5xuU}}VHRnu5UQRqhBuHeaZhlDb?d7sm zq0&9DPbZ8|EQwM3kJz=PU%z=$`*FX%ZDAIlJ;e%bsKRs_{?%Ly+u^M=5J+8lOfz!L z;^?ftFzq6Lx&Jndk>L*R(XAPf44!9hVd)v&o||E|*0;U+;aP%q|YQ52unO z&$fxTi@%2@J(}SgZfSMW&O9TL>f^Y|<}~P+v>4uVYlWkG-&BeDBf+HVtF};=6_n;| zSrUWr)^c{Y8nb93V{)=;Y@kENlVcD$%DQ1!Y35SL-_wh)Ry^uM(?>(*m7~A2R^|yq z$U0xdd3csQxxIg(H$5LQC{Jy-ZS`&C5dKI>W{{pWt?507KU>kWuOlYTNm->^cAke# ze!ATYI|5I=0|H5uR%7~%Me0@tjYmyVJ^7*vaTYwT^i(?fLq@yj(m#0)hKww%^Y|H3 zeQLFN<--U?!vKs!uEqYb^-@Y*YL0;-0J33RpmS}1JS z1?ggRUVq4eeq+dwyLutP8E449fZEDfj0v^ZK`x56(9ZIIjdgOEfJ0fBNq*@{IKIpI zs@n1vWP89B3|B%p96NRKq)Wc*vK zx8GAWCB??PazaH%e)_enSb7ur(FD)y-&y@(OUn-{MDOOyiN>%ZsB&A^T9-oga~=?o zNIy;D1LSie&1c^;S$Q)N-uLo6Y%rbLcMLe#zYtmW;~4vI=pXEU3i!_WQ7 z8;cf#k4l4uI7v-Uc9+}uy+=mwJPk(!d<1j z>ncO0rZ&8H*h;KCoFK-ZG1|9vfsIXuqa#kc66$*U)Z?YvPw|A_PVq?Nx4;~E>Dq({ zR@3!fI%jf9>eh{xn!=NBm5F{zgVPCl&f;C)0zUnPO$^ghNcgyg(W@q)`b zR_y=B0?hmFvlsKdUdaiT%QPt}_4RjH$N^>MU}n@<=wft255TQ(S0BYF82aUH_vnB>D&UW0*2I{Rn)JW&#m=H5)gw;o0B2Bu=y6nVkcSSr3Ra_i5qoNnJ3u< z0NGw98D>j9#wuVhB_S zjwUO!m!6(qUGTI02D5#3ijy$OBGju$+Al4L_tqfs{_@M9FJMmNHrnuqLXq*XLQO5e zog}gHqjx_CV5}1LBJ@Q?OdM58iylg>r&>k^Ao+7F>o3#b2=7kalNB zgkbQ?5^mNa(zoM^R*9`Vf zVn;!ch7bDe_ezVsrvWZ;fP`Nn5liF+Yi_u+m6bhB5@l~sL7Y(ojao{$3tZR^9l?G5 z%1IoMiA6Oue*0ofGY-j9oYR4T6lJs;L`|{_*l_GNm2kMWlxyAFzQNx2HVP$^TK|ZS zo||ZjIIY7}H&`2VR$B9uEj(K-CtM`!WEPakjgp9)8h5Cj`?dU8I|0-j9o^4U+Lazk zF*o6XE|NFl$OaIdxVdrv-iUPtMT0r{B$=cT^$Js$1^t2Q)$jNp_gu&X7$T5tktIo1 z+5QVV1cm)NcBd0u0d)ah8@>Q)4JtAO0(p4zxa?m0U=CVqk>I6kC zBOxo&u9(g_&GXhj23laSRQdvEuW4Wi$rD;NDgOaL*nW<{s|9-u?O&u@cf0(8#+5B! z2Xd#d|1cdv(h9Ec+mwxXEorRNSv6;5aV%aEZ~=Ai}47NT$1 zjaJ1GlMy{$h|F5VhzuoBrV>=zRR+w7tA*0DoyW+@gY{_xz|Jnu#NW**f>_y=I_2Z< zhs4BE#!vjdKv-IS$fQ!>sX(|d@wV1PsG=xIcA{>A-lqpfC-Xj|)k%LW9+leGm=QWg zyA1Kh{cexp3S#@WT%fsL02}u?dsEvf|M{+K%wvD(-1G1B5DE~>va$+$x=y}dv~z+p(}u(*h>y#+ZHtq-#P~sfA-hi?xR@92^#Z3DAlOBq8;};T&a7M%36D_Q zE!k^fIX8fK4}IHvyiFMS>EE{XF8tm221sz=?&UFO7^v7FE!Tg6`=bjf__nd(PJOz6 z@NHC7pXXsZNV4-U_UZeLo_aaY=3kwH*qbgyS*vXVV;W7K-S*NcAKUAY4hvQqttz=r z3EInsC;1fnmC1Zt5&-c@8>r7;rp?7fE73s8bE{^olzD+WnfVH!pxyon=4OUPrLzX3 z5>S1(`Ss`4n~+qY$s7GT!p4Wf)oB&_3=8wT^ZN^$9QIbOH_1Y_%!;ks@=v zZ{5JC$g5Wl$0_( zJRVMZulw(#z}`DA5mL`U1N0UU%vJdC{QEsznEmgd~F?UZP9An+g$xy~X0w~<%wZ^lrill)G+ z8Yu1iHvZN}XO=_jDVG%BN1qcCAz3hcM6_NUDORho7sJM_P1jpi7me8DZDBOor#>6g zhP)WJQCrs5Bu_RvO`Xd8cCe=ZU6$;^nCiF|{Q#i-6QkJ-DX(`c+g!;L)%m;~`{vWg zgGn{C*bG6oUSylaC)G|IMVgg=;GV4(G;jTCNHoxFMVMfh8xb-%OaN7so!@5pe!Dm* z*9Ed)th5n6b8Y1W@^9ZGsNS9|xbpqlV9Dn1`9<@NJtoEqcFDko$t*RNz$;(H%3C`G ziM6;z3*0qNG_{!n%K7!(Jm#Q^SLp@lhXscTGQbdFUS`mb{^8O{=7D5W*JQv`H*7W} zC?xORsYVPv?l!LM(%?{;`1eD9JJbREf5Y?=6qKt~6ur`>z6f~ox`dns&F@(A{tb7% zu^Di;dG&2f}!8;w!Q{FF52P4|AFd^R-2Xhv(V=~2XH$6`4e(1N$aDQ z0U17iJUK(zcz7t`qokLKN1DTE`)RK&_TLnn0m9|oA=QQ4-cyxcj-sM8db;`E$sNN} z3z$>NLOJb+deUT(L7z)I@P_gvbIelLTIrrZ@C)PY?x#XBu6e8mNzZF_liMO)6oz&d zbfmJdI=X3rUxCr~okgHp@}Mk4lAs=gT^O zu2rB~Tn}RC=|4Ve=4WThxf)zZ$*x#``OoeOKo!5oWFb2(rw$LVJDNc7OcJRjSi(7H z4*q?|sZEAU1bWRv2Az9xL5bRgxDl*|YFxdK%UbmI75MYB_Ze-WTOd$xPO3A>Fi=#4 zSP&Cuz}MEQ=U-R0eHy%bI`c#;Ymxf}83~!S zcanKxt$aZ>4RsY|sWtUsgyrn-Ofo%_hPi6R>s^FAD&63L64?Z+ZsT~Z(ocXsgVj81 zI7i&qSF?_2kT)f0W3K;KbHDjJA2y@bjrHE}oNCj_jOo8}c=5EhAumA?V+%UmFTDp> zps$hWiI}^t@08PeSrbzW=ddf~SkW52tMuGK81E>V;*A=5H+Uw)qGYtYju*KyeWlyk zHTD$dXqNmhcBcjxOp@u#0O~+urzLJ7yU(H^!!3s?FEHcTA6qt=MrRrA_>IY^-Ik0_ zwE9Qw{N=l~4_!k0LFoXd_>H)~rJdk*OuJ^}pUev{xI=xCmJ&6%?JC!08J-dV<66%a z2@?*+!nyuCM))+#YZ<~X!|#F!LB;T#AbrTS+R_Ls%1itGyy_7vaxqBZ5u!JA5>6O= zJ$yR@eR=G;dOR!udB+cSnrk$?N`_tr^a?NJBUJuSWQ|ZX><#lc{6QI&%_C=jmzlXK zh`W~WfA?EX=nQqKrhj*GMajI*IDdYDp@_-Gz>9^=35XtP$02WW(b;fH2|0X)p~dog zF3f79DNIv`;u1Z9AL2>qhyj>SlU;nPUjsZh%osR!wqNJr(E(J!sJi`?D)^8Jq0wb}0Mk0s6vjjBOnS@nZ+OXUjdvT}L#|8@bRTT*R|%GBN~ zxt;Q9*C_4f>o|M6P&A;xijv$HPQ?Gx7#3p=XzrrpQ5n>h#tqXcS-PEipQ$^_rV4EI zhf(sLo>aL!w@~;Y9}skjUCUekMD<9lcDPvVd49f`X{UL|GOuU%?mM6Q&V8oio1E=1uT!;cmK#Vs=c~v}m&U_|M;twZMxOiL8qY zpUI2oiD6Bl(|b3YADYx#yPd$6irbh_3);>QvXE_!v3m=;`tp9ftbA1B^=(tqW}Y>% z+5b;vsyvBSL_@9SDobAQM7!&cfIr~Vd!kSiFM^wK0g)%^2uoGF%W1i7RchQXrj286 z0-41qP38W>xW0;l4k6peH$!tvg_cUv`S@X|L0rg&Xkmg=Hbl}Xsz=2(+v!^rulxwN99);(QbHIGnWB1z5W)^YIXQeDTuNB0`LWYMU1dLv16 z+#H|E0QR)oi(Q45Ki7MzW$)f>NfU-m>xM8A1m7HU0gk?FvJbM4aEL<>T@NZ3A)Fts z5%)SeslL+q6^?53a1f@Za?e!#Vr`_$MEU$vymKtuV%>1>m{d6qR5zZPyl$s_TS#JJ znC>2ax;*cOmz_P}g%<@i6=58Z@^1@EBB`TS8Oe?A8LzRxW!pI)^gc~!4&1pdElJ2< z8=JYxP*||lrVn^2c=5eyr-RM&rT5s?;$})7peG13z!CMU*Shb|X)~3`>>HAAOsy5p zI=?E}WLZLSeQNfYqj=3mWH?;yz(J71z#!gM$pn-(E)M3nC@Z6-YGuz?4wOqKaxek)#YMpQ1jG}r%EuYuUu(nu#IcjGNX`Y-@mv9rjZl&&W@us zD)xD-U;IR!qOAXH5zn>ZleZAd>*M^v?P}s9Q+ZA@un02iaZ~zxn52LUqoO}ZlM3i$ z#{oTSc8e{uFY}3iuqt;P5;jdY)EAL&Vg+(=fSQTb>#7om5Sj=Ja|RaK@uHXasjKXA zA`}YL1gO{d|G2bI55IKzRPn$#f;V!-Xb3&Xzbd2dw_V)MV_r_Lvcj60ob$f?RH#i_ zc%j9O=XtyS!OAYoMz87qzr{Rxt3IS07-tPh_?uBDy4yb~eQ3lY&&qmVjjD`ub-xn_ z1t=N4pHx=;yMi7H&0RgNe~t;gyRn(@JRZqXwdn@!JFV>AoSh{}40`f{?PT&b`J~65 zUY?XzgBlT>DFQYt#Bk$d9Bc*h~(!Hf2|JtXc0U~qt8%=7Zo zk!7QkN5CmKiDw9U`vqFwsKN_6XH}W)CeQq=Z}48u zT!4~@jL^|H7mXSY1?|h!5dC(2#pedf{jYN>4F$^g3|@e{|KV(GJkpg@cC(y_kHc74Qpp}ws}wCE+}gU6GSd@rdH)Z+$~Aw? zkwhd``eHD3)IY2;oln)Q`wJ!(omKHoIp*9XD&tLaCb^q%NWww!ij$HErbmKN@D%#$ zlkd4Albs7k8Wk7eQ`-dIY|vD2w%*r#6WqeT)32j{s>l(d@eNWA{x`-$<`TzalcO08 z!56i&OB9BsCsNB3$2GST3|P#j1K1-&iA?X#SXlglYvl9%V#eBda{Iawr2> zcV2qnz|@l{?;R{&hkSUw7iSk99aGC-0J>zk)GT(3WaY&Xj!qTY8Y~-J&Zs-aXqHGok2 z>}K_G47Z}zCVt2N?YDq%8gPB4u}$=rRRtSsGS)ZwugNj^VO)h38-m`LZf#2M4koEIkLHyO#J?(fcw`tDiVzIzc2~~Kf=ff0tRAMA}MHb|NW!BCf1~k#O>PLGr->8 zRWQ(RMAN$=f_kh#z96jCS#fOycNN5{t<&Gu2R7;2V=ac{d7?Q4iscFKsgytGUT_9q z_?zVBa!H>L)?O47XaqIuiB%b|C?HI&kx3V+QcNw^9UwE`D;`aMNl;@U`PbiI1VJ{1 zLCXlbdB4xpkuzVFmODvL9CdBi|G+zvyHlBXSEMolTk-lbptD<9-|%I>#;VOEsl)Fk zp9=-?r?ayhOY+{l_rHJZbe%;iDN_X@RVnljVF8H0$f`l&4-F_sWU|J&bpQ*q4SCt! zuOPk$$Je`m@EiQ1Jr3%l#ZWBEs*AG6zp8xCQpHKqH#+6p7vM|p zORLoGw9-?#utSaM`tF9@!9Zb8*gbn$}*g~4_nR>{ZxC2 zg6#OUNV~1>5>qh(B1UpC^M5H%IGO*|`KuHWfFJ=Y!-PQc{!6;)EqM$W5=ns=M?P@> zo8KYB@-Vpot3 zf$cy07He)4R%7M^SDb9aSa}2V(>G^UL?ANT;G<1`m$L|Uum1vCT3&`U@*m+E8us&h zT)aHN?d<{DU!LEmQ@+XmT0~@2OrKpuX8m}0`hM%{;Fsg$xh;n(1VGf6fbdo5GPJ3P zI!YH@pz&#naublVr+ASUUz~$i&SjROh=G|dA?4t>%i)OKx5lv;O}cPiJ3b>VD}#t! z!1M7A9Z=(ZTIT(@jH`p+NgeCjC}|5yb@@naVyV~FCT(~z-CBG;~0vwWC?_AtxB@D zE&X+^hQi@#gg6IP0dy}sK&u7G+<^Mnxu&WV2FPSj01-Bly|252Ut!W%6E%Vih&h8h z12!hVz|Ek5sb|dC^eOXnwk{rackYH8V4AT&aEC4zc#vRtSM2T!(AV(;(c?Zn;Z$WN zI(L~oUfyZ~mSjJWBwF)C(Wbm~=jypQS}E(3GZVqq&2#NN~t1^TlbOi=i=*s;>41~2+A^pAp=_tK zfU0i`DMvruw)Y9(2MauI0&jLd8JIhGc*tGoPwX`guAabQf%1aSb5_nC%`m;Wn8e~H zGU{KDKwc1=N;`hYKkoxT>4Tj%UozK~O=dW+#-ihCXV8Yozni6XEbg#%O|YWEJzyX@ z4$ac5p;-eY^j0@1oZK`&zdb>f)U~t^CoH9cad}kCUHW{x(v202%*zXEXxQeDmi3sF zU=$0fBiX{6b_B^~JV-0F%6=dxxf#2;+ zodw!NhQt_CP}oywrMPZ;FXSm{^l{kEL_o&|x=?>syN>Zt8$;6q*sc6@a_vfKic=vyv1qZxa1nH$Y?0S69mX;q~HQ^=>PQyDxLBx3i^uFEjQ2z_aPXRN4NrI4O>CM@KxSo@77Jn#2?&J}f@6VJYy%@=EMLBMJy= z8?mN}6m|GC(8z#H{g?o~T|T>2MLzXSgQ{Xr`&U}LKo9l6p53o20%80S`vUS{BE0FU zDBHZ3xBIHIogcP?thZhc@5`_@BB0DL`XCYztIfX8>5eJfB{c*Egb23?yNPP8N;s;! zQke=;<+|A*n#B|V<0D*dfGUwLQ6RY>XRCd6I)8?IESRqr`|7MCRQbaoRT%xrF`6@r zV5ChR>!7i7!6)vU7pgipI;rdTzmZ5EiX~9c#2DMyGYljY`$}&n6SPUmLt(zJ3zCSe&r3qEer1D921MGx>DzRfAmK#j zC-(fF>K>EJ^lf^1R0G|@y$eaGw;%)>;{?yE=rEg=%r7X>msqJ^{Go?Fw>#b%6c0|l ztGdqbx~-{~Wx#v`{Pb|9R{I6FCl;ViLuHFv?8XgB=pio10^}%%yfSS=F%|2iuNk5S zHi8~@K-f|Wrburq5jbJHZ9#G{q9)oFlWdh1`!yhISbfJf7Adrt4Zg3P3sWzMQHQXg z_b{wh`)?jyL=oQT)m26-)j#c*xo_%WJH6q%2P$8F+}5x&nEFQ@+JUOPYJ?ut>l=@e z#{&9a{X?K8Az##fs{sPRASr+)wPBlc zpb>Z)LJ$|}We#5K>4)2&#L&Y4&@4_|P`l+!(IwOd@>&ppE{6WSV2>mzWDwHwh_zN(`r=lU(h$D zL1@OEBl%{LsTGLW2$!rpRm`;tl%hrQ&61S4{y zCviU$TC*?zv_pJfj*|o|!5C?C1LiawyaEIG0tw&g6|R`Tru_FS>i^$)PLKP4&JxT2 ieGvcOWA?vCZ&*JR|6;x%v>AecKLr_8aHZ6zkpBa^u_M|5 literal 0 HcmV?d00001 diff --git a/docs/modules/slam/graphSLAM_doc.rst b/docs/modules/slam/graphSLAM_doc.rst new file mode 100644 index 0000000000..b17c3b18a2 --- /dev/null +++ b/docs/modules/slam/graphSLAM_doc.rst @@ -0,0 +1,557 @@ + +Graph SLAM +~~~~~~~~~~~~ + +.. code:: ipython3 + + import copy + import math + import itertools + import numpy as np + import matplotlib.pyplot as plt + from graph_based_slam import calc_rotational_matrix, calc_jacobian, cal_observation_sigma, \ + calc_input, observation, motion_model, Edge, pi_2_pi + + %matplotlib inline + np.set_printoptions(precision=3, suppress=True) + np.random.seed(0) + +Introduction +^^^^^^^^^^^^ + +In contrast to the probabilistic approaches for solving SLAM, such as +EKF, UKF, particle filters, and so on, the graph technique formulates +the SLAM as an optimization problem. It is mostly used to solve the full +SLAM problem in an offline fashion, i.e. optimize all the poses of the +robot after the path has been traversed. However, some variants are +available that uses graph-based approaches to perform online estimation +or to solve for a subset of the poses. + +GraphSLAM uses the motion information as well as the observations of the +environment to create least square problem that can be solved using +standard optimization techniques. + +Minimal Example +^^^^^^^^^^^^^^^ + +The following example illustrates the main idea behind graphSLAM. A +simple case of a 1D robot is considered that can only move in 1 +direction. The robot is commanded to move forward with a control input +:math:`u_t=1`, however, the motion is not perfect and the measured +odometry will deviate from the true path. At each time step the robot can +observe its environment, for this simple case as well, there is only a +single landmark at coordinates :math:`x=3`. The measured observations +are the range between the robot and landmark. These measurements are +also subjected to noise. No bearing information is required since this +is a 1D problem. + +To solve this, graphSLAM creates what is called as the system +information matrix :math:`\Omega` also referred to as :math:`H` and the +information vector :math:`\xi` also known as :math:`b`. The entries are +created based on the information of the motion and the observation. + +.. code:: ipython3 + + R = 0.2 + Q = 0.2 + N = 3 + graphics_radius = 0.1 + + odom = np.empty((N,1)) + obs = np.empty((N,1)) + x_true = np.empty((N,1)) + + landmark = 3 + # Simulated readings of odometry and observations + x_true[0], odom[0], obs[0] = 0.0, 0.0, 2.9 + x_true[1], odom[1], obs[1] = 1.0, 1.5, 2.0 + x_true[2], odom[2], obs[2] = 2.0, 2.4, 1.0 + + hxDR = copy.deepcopy(odom) + # Visualization + plt.plot(landmark,0, '*k', markersize=30) + for i in range(N): + plt.plot(odom[i], 0, '.', markersize=50, alpha=0.8, color='steelblue') + plt.plot([odom[i], odom[i] + graphics_radius], + [0,0], 'r') + plt.text(odom[i], 0.02, "X_{}".format(i), fontsize=12) + plt.plot(obs[i]+odom[i],0,'.', markersize=25, color='brown') + plt.plot(x_true[i],0,'.g', markersize=20) + plt.grid() + plt.show() + + + # Defined as a function to facilitate iteration + def get_H_b(odom, obs): + """ + Create the information matrix and information vector. This implementation is + based on the concept of virtual measurement i.e. the observations of the + landmarks are converted into constraints (edges) between the nodes that + have observed this landmark. + """ + measure_constraints = {} + omegas = {} + zids = list(itertools.combinations(range(N),2)) + H = np.zeros((N,N)) + b = np.zeros((N,1)) + for (t1, t2) in zids: + x1 = odom[t1] + x2 = odom[t2] + z1 = obs[t1] + z2 = obs[t2] + + # Adding virtual measurement constraint + measure_constraints[(t1,t2)] = (x2-x1-z1+z2) + omegas[(t1,t2)] = (1 / (2*Q)) + + # populate system's information matrix and vector + H[t1,t1] += omegas[(t1,t2)] + H[t2,t2] += omegas[(t1,t2)] + H[t2,t1] -= omegas[(t1,t2)] + H[t1,t2] -= omegas[(t1,t2)] + + b[t1] += omegas[(t1,t2)] * measure_constraints[(t1,t2)] + b[t2] -= omegas[(t1,t2)] * measure_constraints[(t1,t2)] + + return H, b + + + H, b = get_H_b(odom, obs) + print("The determinant of H: ", np.linalg.det(H)) + H[0,0] += 1 # np.inf ? + print("The determinant of H after anchoring constraint: ", np.linalg.det(H)) + + for i in range(5): + H, b = get_H_b(odom, obs) + H[(0,0)] += 1 + + # Recover the posterior over the path + dx = np.linalg.inv(H) @ b + odom += dx + # repeat till convergence + print("Running graphSLAM ...") + print("Odometry values after optimzation: \n", odom) + + plt.figure() + plt.plot(x_true, np.zeros(x_true.shape), '.', markersize=20, label='Ground truth') + plt.plot(odom, np.zeros(x_true.shape), '.', markersize=20, label='Estimation') + plt.plot(hxDR, np.zeros(x_true.shape), '.', markersize=20, label='Odom') + plt.legend() + plt.grid() + plt.show() + + + +.. image:: graphSLAM_doc_files/graphSLAM_doc_2_0.png + + +.. parsed-literal:: + + The determinant of H: 0.0 + The determinant of H after anchoring constraint: 18.750000000000007 + Running graphSLAM ... + Odometry values after optimzation: + [[-0. ] + [ 0.9] + [ 1.9]] + + + +.. image:: graphSLAM_doc_files/graphSLAM_doc_2_2.png + + +In particular, the tasks are split into 2 parts, graph construction, and +graph optimization. ### Graph Construction + +Firstly the nodes are defined +:math:`\boldsymbol{x} = \boldsymbol{x}_{1:n}` such that each node is the +pose of the robot at time :math:`t_i` Secondly, the edges i.e. the +constraints, are constructed according to the following conditions: + +- robot moves from :math:`\boldsymbol{x}_i` to + :math:`\boldsymbol{x}_j`. This edge corresponds to the odometry + measurement. Relative motion constraints (Not included in the + previous minimal example). +- Measurement constraints, this can be done in two ways: + + - The information matrix is set in such a way that it includes the + landmarks in the map as well. Then the constraints can be entered + in a straightforward fashion between a node + :math:`\boldsymbol{x}_i` and some landmark :math:`m_k` + - Through creating a virtual measurement among all the node that + have observed the same landmark. More concretely, robot observes + the same landmark from :math:`\boldsymbol{x}_i` and + :math:`\boldsymbol{x}_j`. Relative measurement constraint. The + “virtual measurement” :math:`\boldsymbol{z}_{ij}`, which is the + estimated pose of :math:`\boldsymbol{x}_j` as seen from the node + :math:`\boldsymbol{x}_i`. The virtual measurement can then be + entered in the information matrix and vector in a similar fashion + to the motion constraints. + +An edge is fully characterized by the values of the error (entry to +information vector) and the local information matrix (entry to the +system’s information vector). The larger the local information matrix +(lower :math:`Q` or :math:`R`) the values that this edge will contribute +with. + +Important Notes: + +- The addition to the information matrix and vector are added to the + earlier values. +- In the case of 2D robot, the constraints will be non-linear, + therefore, a Jacobian of the error w.r.t the states is needed when + updated :math:`H` and :math:`b`. +- The anchoring constraint is needed in order to avoid having a + singular information matri. + +Graph Optimization +^^^^^^^^^^^^^^^^^^ + +The result from this formulation yields an overdetermined system of +equations. The goal after constructing the graph is to find: +:math:`x^*=\underset{x}{\mathrm{argmin}}~\underset{ij}\Sigma~f(e_{ij})`, +where :math:`f` is some error function that depends on the edges between +to related nodes :math:`i` and :math:`j`. The derivation in the references +arrive at the solution for :math:`x^* = H^{-1}b` + +Planar Example: +^^^^^^^^^^^^^^^ + +Now we will go through an example with a more realistic case of a 2D +robot with 3DoF, namely, :math:`[x, y, \theta]^T` + +.. code:: ipython3 + + # Simulation parameter + Qsim = np.diag([0.01, np.deg2rad(0.010)])**2 # error added to range and bearing + Rsim = np.diag([0.1, np.deg2rad(1.0)])**2 # error added to [v, w] + + DT = 2.0 # time tick [s] + SIM_TIME = 100.0 # simulation time [s] + MAX_RANGE = 30.0 # maximum observation range + STATE_SIZE = 3 # State size [x,y,yaw] + + # TODO: Why not use Qsim ? + # Covariance parameter of Graph Based SLAM + C_SIGMA1 = 0.1 + C_SIGMA2 = 0.1 + C_SIGMA3 = np.deg2rad(1.0) + + MAX_ITR = 20 # Maximum iteration during optimization + timesteps = 1 + + # consider only 2 landmarks for simplicity + # RFID positions [x, y, yaw] + RFID = np.array([[10.0, -2.0, 0.0], + # [15.0, 10.0, 0.0], + # [3.0, 15.0, 0.0], + # [-5.0, 20.0, 0.0], + # [-5.0, 5.0, 0.0] + ]) + + # State Vector [x y yaw v]' + xTrue = np.zeros((STATE_SIZE, 1)) + xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning + xTrue[2] = np.deg2rad(45) + xDR[2] = np.deg2rad(45) + # history initial values + hxTrue = xTrue + hxDR = xTrue + _, z, _, _ = observation(xTrue, xDR, np.array([[0,0]]).T, RFID) + hz = [z] + + for i in range(timesteps): + u = calc_input() + xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID) + hxDR = np.hstack((hxDR, xDR)) + hxTrue = np.hstack((hxTrue, xTrue)) + hz.append(z) + + # visualize + graphics_radius = 0.3 + plt.plot(RFID[:, 0], RFID[:, 1], "*k", markersize=20) + plt.plot(hxDR[0, :], hxDR[1, :], '.', markersize=50, alpha=0.8, label='Odom') + plt.plot(hxTrue[0, :], hxTrue[1, :], '.', markersize=20, alpha=0.6, label='X_true') + + for i in range(hxDR.shape[1]): + x = hxDR[0, i] + y = hxDR[1, i] + yaw = hxDR[2, i] + plt.plot([x, x + graphics_radius * np.cos(yaw)], + [y, y + graphics_radius * np.sin(yaw)], 'r') + d = hz[i][:, 0] + angle = hz[i][:, 1] + plt.plot([x + d * np.cos(angle + yaw)], [y + d * np.sin(angle + yaw)], '.', + markersize=20, alpha=0.7) + plt.legend() + plt.grid() + plt.show() + + + +.. image:: graphSLAM_doc_files/graphSLAM_doc_4_0.png + + +.. code:: ipython3 + + # Copy the data to have a consistent naming with the .py file + zlist = copy.deepcopy(hz) + x_opt = copy.deepcopy(hxDR) + xlist = copy.deepcopy(hxDR) + number_of_nodes = x_opt.shape[1] + n = number_of_nodes * STATE_SIZE + +After the data has been saved, the graph will be constructed by looking +at each pair for nodes. The virtual measurement is only created if two +nodes have observed the same landmark at different points in time. The +next cells are a walk through for a single iteration of graph +construction -> optimization -> estimate update. + +.. code:: ipython3 + + # get all the possible combination of the different node + zids = list(itertools.combinations(range(len(zlist)), 2)) + print("Node combinations: \n", zids) + + for i in range(xlist.shape[1]): + print("Node {} observed landmark with ID {}".format(i, zlist[i][0, 3])) + + +.. parsed-literal:: + + Node combinations: + [(0, 1)] + Node 0 observed landmark with ID 0.0 + Node 1 observed landmark with ID 0.0 + + +In the following code snippet the error based on the virtual measurement +between node 0 and 1 will be created. The equations for the error is as follows: +:math:`e_{ij}^x = x_j + d_j cos(\psi_j +\theta_j) - x_i - d_i cos(\psi_i + \theta_i)` + +:math:`e_{ij}^y = y_j + d_j sin(\psi_j + \theta_j) - y_i - d_i sin(\psi_i + \theta_i)` + +:math:`e_{ij}^x = \psi_j + \theta_j - \psi_i - \theta_i` + +Where :math:`[x_i, y_i, \psi_i]` is the pose for node :math:`i` and +similarly for node :math:`j`, :math:`d` is the measured distance at +nodes :math:`i` and :math:`j`, and :math:`\theta` is the measured +bearing to the landmark. The difference is visualized with the figure in +the next cell. + +In case of perfect motion and perfect measurement the error shall be +zero since :math:`x_j + d_j cos(\psi_j + \theta_j)` should equal +:math:`x_i + d_i cos(\psi_i + \theta_i)` + +.. code:: ipython3 + + # Initialize edges list + edges = [] + + # Go through all the different combinations + for (t1, t2) in zids: + x1, y1, yaw1 = xlist[0, t1], xlist[1, t1], xlist[2, t1] + x2, y2, yaw2 = xlist[0, t2], xlist[1, t2], xlist[2, t2] + + # All nodes have valid observation with ID=0, therefore, no data association condition + iz1 = 0 + iz2 = 0 + + d1 = zlist[t1][iz1, 0] + angle1, phi1 = zlist[t1][iz1, 1], zlist[t1][iz1, 2] + d2 = zlist[t2][iz2, 0] + angle2, phi2 = zlist[t2][iz2, 1], zlist[t2][iz2, 2] + + # find angle between observation and horizontal + tangle1 = pi_2_pi(yaw1 + angle1) + tangle2 = pi_2_pi(yaw2 + angle2) + + # project the observations + tmp1 = d1 * math.cos(tangle1) + tmp2 = d2 * math.cos(tangle2) + tmp3 = d1 * math.sin(tangle1) + tmp4 = d2 * math.sin(tangle2) + + edge = Edge() + print(y1,y2, tmp3, tmp4) + # calculate the error of the virtual measurement + # node 1 as seen from node 2 throught the observations 1,2 + edge.e[0, 0] = x2 - x1 - tmp1 + tmp2 + edge.e[1, 0] = y2 - y1 - tmp3 + tmp4 + edge.e[2, 0] = pi_2_pi(yaw2 - yaw1 - tangle1 + tangle2) + + edge.d1, edge.d2 = d1, d2 + edge.yaw1, edge.yaw2 = yaw1, yaw2 + edge.angle1, edge.angle2 = angle1, angle2 + edge.id1, edge.id2 = t1, t2 + + edges.append(edge) + + print("For nodes",(t1,t2)) + print("Added edge with errors: \n", edge.e) + + # Visualize measurement projections + plt.plot(RFID[0, 0], RFID[0, 1], "*k", markersize=20) + plt.plot([x1,x2],[y1,y2], '.', markersize=50, alpha=0.8) + plt.plot([x1, x1 + graphics_radius * np.cos(yaw1)], + [y1, y1 + graphics_radius * np.sin(yaw1)], 'r') + plt.plot([x2, x2 + graphics_radius * np.cos(yaw2)], + [y2, y2 + graphics_radius * np.sin(yaw2)], 'r') + + plt.plot([x1,x1+tmp1], [y1,y1], label="obs 1 x") + plt.plot([x2,x2+tmp2], [y2,y2], label="obs 2 x") + plt.plot([x1,x1], [y1,y1+tmp3], label="obs 1 y") + plt.plot([x2,x2], [y2,y2+tmp4], label="obs 2 y") + plt.plot(x1+tmp1, y1+tmp3, 'o') + plt.plot(x2+tmp2, y2+tmp4, 'o') + plt.legend() + plt.grid() + plt.show() + + +.. parsed-literal:: + + 0.0 1.427649841628278 -2.0126109674819155 -3.524048014922737 + For nodes (0, 1) + Added edge with errors: + [[-0.02 ] + [-0.084] + [ 0. ]] + + + +.. image:: graphSLAM_doc_files/graphSLAM_doc_9_1.png + + +Since the constraints equations derived before are non-linear, +linearization is needed before we can insert them into the information +matrix and information vector. Two jacobians + +:math:`A = \frac{\partial e_{ij}}{\partial \boldsymbol{x}_i}` as +:math:`\boldsymbol{x}_i` holds the three variabls x, y, and theta. +Similarly, :math:`B = \frac{\partial e_{ij}}{\partial \boldsymbol{x}_j}` + +.. code:: ipython3 + + # Initialize the system information matrix and information vector + H = np.zeros((n, n)) + b = np.zeros((n, 1)) + x_opt = copy.deepcopy(hxDR) + + for edge in edges: + id1 = edge.id1 * STATE_SIZE + id2 = edge.id2 * STATE_SIZE + + t1 = edge.yaw1 + edge.angle1 + A = np.array([[-1.0, 0, edge.d1 * math.sin(t1)], + [0, -1.0, -edge.d1 * math.cos(t1)], + [0, 0, -1.0]]) + + t2 = edge.yaw2 + edge.angle2 + B = np.array([[1.0, 0, -edge.d2 * math.sin(t2)], + [0, 1.0, edge.d2 * math.cos(t2)], + [0, 0, 1.0]]) + + # TODO: use Qsim instead of sigma + sigma = np.diag([C_SIGMA1, C_SIGMA2, C_SIGMA3]) + Rt1 = calc_rotational_matrix(tangle1) + Rt2 = calc_rotational_matrix(tangle2) + edge.omega = np.linalg.inv(Rt1 @ sigma @ Rt1.T + Rt2 @ sigma @ Rt2.T) + + # Fill in entries in H and b + H[id1:id1 + STATE_SIZE, id1:id1 + STATE_SIZE] += A.T @ edge.omega @ A + H[id1:id1 + STATE_SIZE, id2:id2 + STATE_SIZE] += A.T @ edge.omega @ B + H[id2:id2 + STATE_SIZE, id1:id1 + STATE_SIZE] += B.T @ edge.omega @ A + H[id2:id2 + STATE_SIZE, id2:id2 + STATE_SIZE] += B.T @ edge.omega @ B + + b[id1:id1 + STATE_SIZE] += (A.T @ edge.omega @ edge.e) + b[id2:id2 + STATE_SIZE] += (B.T @ edge.omega @ edge.e) + + + print("The determinant of H: ", np.linalg.det(H)) + plt.figure() + plt.subplot(1,2,1) + plt.imshow(H, extent=[0, n, 0, n]) + plt.subplot(1,2,2) + plt.imshow(b, extent=[0, 1, 0, n]) + plt.show() + + # Fix the origin, multiply by large number gives same results but better visualization + H[0:STATE_SIZE, 0:STATE_SIZE] += np.identity(STATE_SIZE) + print("The determinant of H after origin constraint: ", np.linalg.det(H)) + plt.figure() + plt.subplot(1,2,1) + plt.imshow(H, extent=[0, n, 0, n]) + plt.subplot(1,2,2) + plt.imshow(b, extent=[0, 1, 0, n]) + plt.show() + + +.. parsed-literal:: + + The determinant of H: 0.0 + The determinant of H after origin constraint: 716.1972439134893 + + + +.. image:: graphSLAM_doc_files/graphSLAM_doc_11_1.png + + + +.. image:: graphSLAM_doc_files/graphSLAM_doc_11_2.png + + +.. code:: ipython3 + + # Find the solution (first iteration) + dx = - np.linalg.inv(H) @ b + for i in range(number_of_nodes): + x_opt[0:3, i] += dx[i * 3:i * 3 + 3, 0] + print("dx: \n",dx) + print("ground truth: \n ",hxTrue) + print("Odom: \n", hxDR) + print("SLAM: \n", x_opt) + + # performance will improve with more iterations, nodes and landmarks. + print("\ngraphSLAM localization error: ", np.sum((x_opt - hxTrue) ** 2)) + print("Odom localization error: ", np.sum((hxDR - hxTrue) ** 2)) + + +.. parsed-literal:: + + dx: + [[-0. ] + [-0. ] + [ 0. ] + [ 0.02 ] + [ 0.084] + [-0. ]] + ground truth: + [[0. 1.414] + [0. 1.414] + [0.785 0.985]] + Odom: + [[0. 1.428] + [0. 1.428] + [0.785 0.976]] + SLAM: + [[-0. 1.448] + [-0. 1.512] + [ 0.785 0.976]] + + graphSLAM localization error: 0.010729072751057656 + Odom localization error: 0.0004460978857535104 + + +The references: +^^^^^^^^^^^^^^^ + +- http://robots.stanford.edu/papers/thrun.graphslam.pdf + +- http://ais.informatik.uni-freiburg.de/teaching/ss13/robotics/slides/16-graph-slam.pdf + +- http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf + +N.B. An additional step is required that uses the estimated path to +update the belief regarding the map. + diff --git a/docs/modules/slam/graphSLAM_formulation.rst b/docs/modules/slam/graphSLAM_formulation.rst new file mode 100644 index 0000000000..c673bdcbfb --- /dev/null +++ b/docs/modules/slam/graphSLAM_formulation.rst @@ -0,0 +1,216 @@ +.. _Graph SLAM Formulation: + +Graph SLAM Formulation +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +Author Jeff Irion + +Problem Formulation +^^^^^^^^^^^^^^^^^^^ + +Let a robot’s trajectory through its environment be represented by a +sequence of :math:`N` poses: +:math:`\mathbf{p}_1, \mathbf{p}_2, \ldots, \mathbf{p}_N`. Each pose lies +on a manifold: :math:`\mathbf{p}_i \in \mathcal{M}`. Simple examples of +manifolds used in Graph SLAM include 1-D, 2-D, and 3-D space, i.e., +:math:`\mathbb{R}`, :math:`\mathbb{R}^2`, and :math:`\mathbb{R}^3`. +These environments are *rectilinear*, meaning that there is no concept +of orientation. By contrast, in :math:`SE(2)` problem settings a robot’s +pose consists of its location in :math:`\mathbb{R}^2` and its +orientation :math:`\theta`. Similarly, in :math:`SE(3)` a robot’s pose +consists of its location in :math:`\mathbb{R}^3` and its orientation, +which can be represented via Euler angles, quaternions, or :math:`SO(3)` +rotation matrices. + +As the robot explores its environment, it collects a set of :math:`M` +measurements :math:`\mathcal{Z} = \{\mathbf{z}_j\}`. Examples of such +measurements include odometry, GPS, and IMU data. Given a set of poses +:math:`\mathbf{p}_1, \ldots, \mathbf{p}_N`, we can compute the estimated +measurement +:math:`\hat{\mathbf{z}}_j(\mathbf{p}_1, \ldots, \mathbf{p}_N)`. We can +then compute the *residual* +:math:`\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j)` for measurement +:math:`j`. The formula for the residual depends on the type of +measurement. As an example, let :math:`\mathbf{z}_1` be an odometry +measurement that was collected when the robot traveled from +:math:`\mathbf{p}_1` to :math:`\mathbf{p}_2`. The expected measurement +and the residual are computed as + +.. math:: + + \begin{aligned} + \hat{\mathbf{z}}_1(\mathbf{p}_1, \mathbf{p}_2) &= \mathbf{p}_2 \ominus \mathbf{p}_1 \\ + \mathbf{e}_1(\mathbf{z}_1, \hat{\mathbf{z}}_1) &= \mathbf{z}_1 \ominus \hat{\mathbf{z}}_1 = \mathbf{z}_1 \ominus (\mathbf{p}_2 \ominus \mathbf{p}_1),\end{aligned} + +where the :math:`\ominus` operator indicates inverse pose composition. +We model measurement :math:`\mathbf{z}_j` as having independent Gaussian +noise with zero mean and covariance matrix :math:`\Omega_j^{-1}`; we +refer to :math:`\Omega_j` as the *information matrix* for measurement +:math:`j`. That is, + +.. math:: + p(\mathbf{z}_j \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) = \eta_j \exp (-\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^{\mathsf{T}}\Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) + :label: infomat + +where :math:`\eta_j` is the normalization constant. + +The objective of Graph SLAM is to find the maximum likelihood set of +poses given the measurements :math:`\mathcal{Z} = \{\mathbf{z}_j\}`; in +other words, we want to find + +.. math:: \mathop{\mathrm{arg\,max}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) + +Using Bayes’ rule, we can write this probability as + +.. math:: + \begin{aligned} + p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) &= \frac{p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) p(\mathbf{p}_1, \ldots, \mathbf{p}_N) }{ p(\mathcal{Z}) } \notag \\ + &\propto p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) + \end{aligned} + :label: bayes + +since :math:`p(\mathcal{Z})` is a constant (albeit, an unknown constant) +and we assume that :math:`p(\mathbf{p}_1, \ldots, \mathbf{p}_N)` is +uniformly distributed `PROBABILISTIC ROBOTICS`_. Therefore, we +can use Eq. :eq:`infomat` and and Eq. :eq:`bayes` to simplify the Graph SLAM +optimization as follows: + +.. math:: + + \begin{aligned} + \mathop{\mathrm{arg\,max}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p(\mathbf{p}_1, \ldots, \mathbf{p}_N \ | \ \mathcal{Z}) &= \mathop{\mathrm{arg\,max}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \ p( \mathcal{Z} \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) \\ + &= \mathop{\mathrm{arg\,max}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \prod_{j=1}^M p(\mathbf{z}_j \ | \ \mathbf{p}_1, \ldots, \mathbf{p}_N) \\ + &= \mathop{\mathrm{arg\,max}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \prod_{j=1}^M \exp \left( -(\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^{\scriptstyle{\mathsf{T}}}\Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) \right) \\ + &= \mathop{\mathrm{arg\,min}}_{\mathbf{p}_1, \ldots, \mathbf{p}_N} \sum_{j=1}^M (\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^{\scriptstyle{\mathsf{T}}}\Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j).\end{aligned} + +We define + +.. math:: \chi^2 := \sum_{j=1}^M (\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j))^{\scriptstyle{\mathsf{T}}}\Omega_j \mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j), + +and this is what we seek to minimize. + +Dimensionality and Pose Representation +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Before proceeding further, it is helpful to discuss the dimensionality +of the problem. We have: + +- A set of :math:`N` poses + :math:`\mathbf{p}_1, \mathbf{p}_2, \ldots, \mathbf{p}_N`, where each + pose lies on the manifold :math:`\mathcal{M}` + + - Each pose :math:`\mathbf{p}_i` is represented as a vector in (a + subset of) :math:`\mathbb{R}^d`. For example: + + - An :math:`SE(2)` pose is typically represented as + :math:`(x, y, \theta)`, and thus :math:`d = 3`. + + - An :math:`SE(3)` pose is typically represented as + :math:`(x, y, z, q_x, q_y, q_z, q_w)`, where :math:`(x, y, z)` + is a point in :math:`\mathbb{R}^3` and + :math:`(q_x, q_y, q_z, q_w)` is a *quaternion*, and so + :math:`d = 7`. For more information about :math:`SE(3)` + parameterization and pose transformations, see + [blanco2010tutorial]_. + + - We also need to be able to represent each pose compactly as a + vector in (a subset of) :math:`\mathbb{R}^c`. + + - Since an :math:`SE(2)` pose has three degrees of freedom, the + :math:`(x, y, \theta)` representation is again sufficient and + :math:`c=3`. + + - An :math:`SE(3)` pose only has six degrees of freedom, and we + can represent it compactly as :math:`(x, y, z, q_x, q_y, q_z)`, + and thus :math:`c=6`. + + - We use the :math:`\boxplus` operator to indicate pose composition + when one or both of the poses are represented compactly. The + output can be a pose in :math:`\mathcal{M}` or a vector in + :math:`\mathbb{R}^c`, as required by context. + +- A set of :math:`M` measurements + :math:`\mathcal{Z} = \{\mathbf{z}_1, \mathbf{z}_2, \ldots, \mathbf{z}_M\}` + + - Each measurement’s dimensionality can be unique, and we will use + :math:`\bullet` to denote a “wildcard” variable. + + - Measurement :math:`\mathbf{z}_j \in \mathbb{R}^\bullet` has an + associated information matrix + :math:`\Omega_j \in \mathbb{R}^{\bullet \times \bullet}` and + residual function + :math:`\mathbf{e}_j(\mathbf{z}_j, \hat{\mathbf{z}}_j) = \mathbf{e}_j(\mathbf{z}_j, \mathbf{p}_1, \ldots, \mathbf{p}_N) \in \mathbb{R}^\bullet`. + + - A measurement could, in theory, constrain anywhere from 1 pose to + all :math:`N` poses. In practice, each measurement usually + constrains only 1 or 2 poses. + +Graph SLAM Algorithm +^^^^^^^^^^^^^^^^^^^^ + +The “Graph” in Graph SLAM refers to the fact that we view the problem as +a graph. The graph has a set :math:`\mathcal{V}` of :math:`N` vertices, +where each vertex :math:`v_i` has an associated pose +:math:`\mathbf{p}_i`. Similarly, the graph has a set :math:`\mathcal{E}` +of :math:`M` edges, where each edge :math:`e_j` has an associated +measurement :math:`\mathbf{z}_j`. In practice, the edges in this graph +are either unary (i.e., a loop) or binary. (Note: :math:`e_j` refers to +the edge in the graph associated with measurement :math:`\mathbf{z}_j`, +whereas :math:`\mathbf{e}_j` refers to the residual function associated +with :math:`\mathbf{z}_j`.) For more information about the Graph SLAM +algorithm, see [grisetti2010tutorial]_. + +We want to optimize + +.. math:: \chi^2 = \sum_{e_j \in \mathcal{E}} \mathbf{e}_j^{\scriptstyle{\mathsf{T}}}\Omega_j \mathbf{e}_j. + +Let :math:`\mathbf{x}_i \in \mathbb{R}^c` be the compact representation +of pose :math:`\mathbf{p}_i \in \mathcal{M}`, and let + +.. math:: \mathbf{x} := \begin{bmatrix} \mathbf{x}_1 \\ \mathbf{x}_2 \\ \vdots \\ \mathbf{x}_N \end{bmatrix} \in \mathbb{R}^{cN} + +We will solve this optimization problem iteratively. Let + +.. math:: \mathbf{x}^{k+1} := \mathbf{x}^k \boxplus \Delta \mathbf{x}^k = \begin{bmatrix} \mathbf{x}_1 \boxplus \Delta \mathbf{x}_1 \\ \mathbf{x}_2 \boxplus \Delta \mathbf{x}_2 \\ \vdots \\ \mathbf{x}_N \boxplus \Delta \mathbf{x}_2 \end{bmatrix} + :label: update + +The :math:`\chi^2` error at iteration :math:`k+1` is + +.. math:: \chi_{k+1}^2 = \sum_{e_j \in \mathcal{E}} \underbrace{\left[ \mathbf{e}_j(\mathbf{x}^{k+1}) \right]^{\scriptstyle{\mathsf{T}}}}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\mathbf{e}_j(\mathbf{x}^{k+1})}_{\bullet \times 1}. + :label: chisq_at_kplusone + +We will linearize the residuals as: + +.. math:: + \begin{aligned} + \mathbf{e}_j(\mathbf{x}^{k+1}) &= \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \\ + &\approx \mathbf{e}_j(\mathbf{x}^{k}) + \frac{\partial}{\partial \Delta \mathbf{x}^k} \left[ \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k) \right] \Delta \mathbf{x}^k \\ + &= \mathbf{e}_j(\mathbf{x}^{k}) + \left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right) \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \Delta \mathbf{x}^k. + \end{aligned} + :label: linearization + +Plugging :eq:`linearization` into :eq:`chisq_at_kplusone`, we get: + +.. math:: + + \begin{aligned} + \chi_{k+1}^2 &\approx \ \ \ \ \ \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x}^k)]^{\scriptstyle{\mathsf{T}}}}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\mathbf{e}_j(\mathbf{x}^k)}_{\bullet \times 1} \notag \\ + &\hphantom{\approx} \ \ \ + \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x^k}) ]^{\scriptstyle{\mathsf{T}}}}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \underbrace{\Delta \mathbf{x}^k}_{cN \times 1} \notag \\ + &\hphantom{\approx} \ \ \ + \sum_{e_j \in \mathcal{E}} \underbrace{(\Delta \mathbf{x}^k)^{\scriptstyle{\mathsf{T}}}}_{1 \times cN} \underbrace{ \left( \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \right)^{\scriptstyle{\mathsf{T}}}}_{cN \times dN} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)^{\scriptstyle{\mathsf{T}}}}_{dN \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \underbrace{\Delta \mathbf{x}^k}_{cN \times 1} \notag \\ + &= \chi_k^2 + 2 \mathbf{b}^{\scriptstyle{\mathsf{T}}}\Delta \mathbf{x}^k + (\Delta \mathbf{x}^k)^{\scriptstyle{\mathsf{T}}}H \Delta \mathbf{x}^k, \notag\end{aligned} + +where + +.. math:: + + \begin{aligned} + \mathbf{b}^{\scriptstyle{\mathsf{T}}}&= \sum_{e_j \in \mathcal{E}} \underbrace{[ \mathbf{e}_j(\mathbf{x^k}) ]^{\scriptstyle{\mathsf{T}}}}_{1 \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN} \\ + H &= \sum_{e_j \in \mathcal{E}} \underbrace{ \left( \frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k} \right)^{\scriptstyle{\mathsf{T}}}}_{cN \times dN} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)^{\scriptstyle{\mathsf{T}}}}_{dN \times \bullet} \underbrace{\Omega_j}_{\bullet \times \bullet} \underbrace{\left( \left. \frac{\partial \mathbf{e}_j(\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)} \right|_{\Delta \mathbf{x}^k = \mathbf{0}} \right)}_{\bullet \times dN} \underbrace{\frac{\partial (\mathbf{x}^k \boxplus \Delta \mathbf{x}^k)}{\partial \Delta \mathbf{x}^k}}_{dN \times cN}.\end{aligned} + +Using this notation, we obtain the optimal update as + +.. math:: \Delta \mathbf{x}^k = -H^{-1} \mathbf{b}. \label{eq:deltax} + +We apply this update to the poses via :eq:`update` and repeat until convergence. + + +.. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/ diff --git a/docs/modules/slam/slam.rst b/docs/modules/slam/slam_main.rst similarity index 75% rename from docs/modules/slam/slam.rst rename to docs/modules/slam/slam_main.rst index 981c45ada5..41210fee4e 100644 --- a/docs/modules/slam/slam.rst +++ b/docs/modules/slam/slam_main.rst @@ -21,32 +21,12 @@ Ref: - `Introduction to Mobile Robotics: Iterative Closest Point Algorithm`_ -EKF SLAM --------- -This is an Extended Kalman Filter based SLAM example. +.. include:: ekf_slam.rst -The blue line is ground truth, the black line is dead reckoning, the red -line is the estimated trajectory with EKF SLAM. - -The green crosses are estimated landmarks. - -|4| - -Ref: - -- `PROBABILISTIC ROBOTICS`_ .. include:: FastSLAM1.rst -|5| - -Ref: - -- `PROBABILISTIC ROBOTICS`_ - -- `SLAM simulations by Tim Bailey`_ - FastSLAM 2.0 ------------ @@ -56,7 +36,8 @@ The animation has the same meanings as one of FastSLAM 1.0. |6| -Ref: +References +~~~~~~~~~~ - `PROBABILISTIC ROBOTICS`_ @@ -77,6 +58,10 @@ The black stars are landmarks for graph edge generation. |7| +.. include:: graphSLAM_doc.rst +.. include:: graphSLAM_formulation.rst +.. include:: graphSLAM_SE2_example.rst + Ref: - `A Tutorial on Graph-Based SLAM`_ @@ -85,9 +70,12 @@ Ref: .. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/ .. _SLAM simulations by Tim Bailey: http://www-personal.acfr.usyd.edu.au/tbailey/software/slam_simulations.htm .. _A Tutorial on Graph-Based SLAM: http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf +.. _FastSLAM Lecture: http://ais.informatik.uni-freiburg.de/teaching/ws12/mapping/pdf/slam10-fastslam.pdf + +.. [blanco2010tutorial] Blanco, J.-L.A tutorial onSE(3) transformation parameterization and on-manifold optimization.University of Malaga, Tech. Rep 3(2010) +.. [grisetti2010tutorial] Grisetti, G., Kummerle, R., Stachniss, C., and Burgard, W.A tutorial on graph-based SLAM.IEEE Intelligent Transportation Systems Magazine 2, 4 (2010), 31–43. .. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/iterative_closest_point/animation.gif -.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/EKFSLAM/animation.gif .. |5| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM1/animation.gif .. |6| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM2/animation.gif .. |7| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/GraphBasedSLAM/animation.gif From 413011ba9720f7ba9ff7f57653b7b28dd35d1643 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 23 Nov 2021 07:07:28 +0900 Subject: [PATCH 420/940] Bump matplotlib from 3.4.3 to 3.5.0 (#575) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.4.3 to 3.5.0. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.4.3...v3.5.0) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index e11ba13b8d..84f663cb83 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.21.4 scipy == 1.7.2 pandas == 1.3.4 -matplotlib == 3.4.3 +matplotlib == 3.5.0 cvxpy == 1.1.17 pytest == 6.2.5 # For unit test pytest-xdist == 2.4.0 # For unit test From 094a413dcd9ca7cbbc2db4b7c44f84294cd80714 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 25 Nov 2021 23:05:25 +0900 Subject: [PATCH 421/940] Add how to contribute docs (#573) * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * clean up SLAM docs * add contribution doc * add contribution doc * add contribution doc * add contribution doc * add contribution doc --- README.md | 20 ++--- docs/README.md | 3 + docs/_static/img/doc_ci.png | Bin 0 -> 51875 bytes docs/getting_started_main.rst | 53 +++++++++--- docs/how_to_contribute_main.rst | 129 +++++++++++++++++++++++++++++ docs/index_main.rst | 1 + docs/modules/introduction_main.rst | 3 +- 7 files changed, 187 insertions(+), 22 deletions(-) create mode 100644 docs/_static/img/doc_ci.png create mode 100644 docs/how_to_contribute_main.rst diff --git a/README.md b/README.md index 024c600cb1..195eb1bd4f 100644 --- a/README.md +++ b/README.md @@ -96,17 +96,17 @@ See this paper for more details: For running each sample code: -- Python 3.9.x - -- numpy - -- scipy - -- matplotlib - -- pandas +- [Python 3.9.x](https://www.python.org/) + +- [NumPy](https://numpy.org/) + +- [SciPy](https://scipy.org/) + +- [Matplotlib](https://matplotlib.org/) + +- [pandas](https://pandas.pydata.org/) -- [cvxpy](https://www.cvxpy.org/index.html) +- [cvxpy](https://www.cvxpy.org/) For development: diff --git a/docs/README.md b/docs/README.md index 728a81290e..5c4145e8e3 100644 --- a/docs/README.md +++ b/docs/README.md @@ -24,3 +24,6 @@ if you want to building each time a file is changed: sphinx-autobuild . _build/html ``` +#### Check the generated doc + +Open the index.html file under docs/_build/ diff --git a/docs/_static/img/doc_ci.png b/docs/_static/img/doc_ci.png new file mode 100644 index 0000000000000000000000000000000000000000..a9a73f7e927046bc7a759ae9339c3d7be521e04c GIT binary patch literal 51875 zcmeFZcUY54w>U}@M5HJR0#Z~2sgd3Zh=52Hq*s*|TId}Ds33wM(h0pIz1L8b-a908 z={2+vTEZ`W<$U{`yZ1i#{&}D07oNQDWMS>WNl2#wVx(Tkp%YC*nu_UyI- z3jzNRlb{`rM<4FW%H%FSWDWdq>)kUdCoSc>Mbx)CLUrW14T=Nq+U{ZEudyP8RVP<|3r8vIVo1#DtP8|yWqt*Qw{i0@d(`(eZ2*B%1~(sPxX@#%_wrl# zcb?MR!(*3OJ6P3pfA)+!fS(_$WwLAObLAX;dBu57kdaJ@$4~x?J22T4&xrx= z)Ux@t&UL(3pxRWeC)&R{s2IAlf%8)sz5{ke7yROUH>bOjQzmo?kbhPZ%$ybf>Dw4f zu8f@)tJ;_M2^8gpk^l~cWr2+6?V$_@Q5?5p&t_zjpTs=>Sa4RJX{T?V+1b)0BdrOj zF=k!s1np-$d*xi!0GtL%tH%P1t~EZ4DbrH${BX!o{;2x;hoxIvi1NH=N-w_!TWJ{F zi_13&)5<<0rH9PEOkmEbGL+qU40t(O)S*STwD$UF89w^sgSlI(rxGvtZIC##uh6G! z_o*oKWblQ^`U&b~W=E#RNq_}b5Ai9xWhkf!XunvP%O}|=5Tq%k6J3%gwf z2h^V)zFk=UMB!nDtAb?ct#-$^f_&dLK0z1TJXx5?(lRup9D%ct>-s9!Lt$EyEinR9)Q^E-n}AzJl?oRFbSY>2((9FbWQ+HX za@cEbN`$9$sJ&e;*C`?`E2GvEa3__>ZO>}l_L$hC4~@(3Wv4v+bagi}FSKAMd$xGK zcxo5sU8139lrQO-tUp@M?-Y^$wIle7;u($Z4-dw!L&qaW5}7m8EbN(g$7@UoOFvnf zU5*6)^&3n~Ob!_Huuc3$N1!AYEe*fFn3(HJip!?ZM!*bacg#+|0zj7iLwk`K3-v)cNwW2p+uX>zLY3Yk_?w9 zsXsAo+g(S-*}%p;5=lbLqR_o(R3APJQxU%n*JG*qB=9Tn^g-JTqT6At4>w=1eS80c z>KZ@u*^L63$%oLdj4v1u37zkVg(fSCN6mB-X486wHp%hDe5Oyg%x4s5Ldn6cZzhGS zDY^{9tw|g17>DX)Rd4uL-I5A5d0v_|w;|w)N0=bo+0M;J+fTV{cA!Tb_ob)oqn?<~ z$BDP(dSsWWrEll-m``Zff89*}*x1T=|4ZJYudi@3m1!XO2m05SQ_v+R77y74ylqXS z6(sN=p!KoJgB7YZs^06`ALc$h`XI2+jiNH44t>rxlDa`Q^j4fNUNo{UsP3a@z_h{+ ztMo&PuP<2NeG}mLbVvPH)D0zz>@V4vZ0c-YO-hi4vSHt|J~=K;E;;2)?eE$-)#}@I zI`Na##SbcY;c@q6BG}2gU3v<;8@qW{`c{|@spKQys*`52YB_T#KbeRj?xpKB?&Y$# zx975l?Dinu?sgz15G2(@AmFgS@uYY0-6*TSctg)WD`de(o`LA9o*`Zu zFz(*jmA3ynnBF*A?~3nt3l=>80+|V%daymcRpw^75wr1n^ZsOg(O91HWcAqU#-S_i z*5n4$1gtQ#s5RI45R?7hS55Yym#+sQrnw-I#WJ( zzQL#7H$M@d5F5QWdVk|Rl3e`eIXQ|Pc2kQyjNJBSB%QkeUoK;GU%yq!Tc)@3X3Y%m zgoC9NL@mz}g87W!&ENYXbVKMieJlgx(*}p*!32x@Z<4K=I_r8)Q%N0une)TVBYJeA z1=#%Fk#`bDtVZ%M`&jRk=H?efgEBWI$5L|RRY>~#2QvG!Eg1&X5>bf)19Af{16%`< zP_)5Q?jW9anphfkZmbzy#dMLcj?lJX;lk)RKSJ|O{m+V@&fUH9oE_iCw*n@lY(H10 zxz)JkxHY=9eEB%Q3Oy4>3AZ4=*<cNcVSRtRkEEOWch|C$wxcsdA4HaFU>gYv$n ztx=9rhV>EZ=Gqq77T88_9~}rU3v`y!LEJADMZmSbwZ;w}v#2@thWLisx|Ul|Fj|z=D>kc`4KxM!fO~gmVkMSWM&o>ma zpWA(|V+P$#q}FGKGp{lV0lxDjQ87}(*v{Fe!u!@Ioi5nV)r_7VxZV_EN?u4w9Pj6rSeO3yHLk_PlwBfQyYE$@9swy)Oo)Q}~_= zz1=!5kQ!^si&bspoAdWRI6e|kv0NDv71pw11FtQqJhL=dYwkxkd7AKmS;C;zVufi# zOW;Ky^@kgr*I++bmJF7nchYyN;p#3y&XcRhpPxO~&Xnd;Y*M;>C?f7*xCd=IZIbf( zc?LQoxlwh4pDg0#@nf%VW0n0@cZarO#FhK9=PC&;OVj26VNttrj}A8v*PaocYC@Ej z(oYQz(x24j=UO|eZ6*Kg@b38bOW7r5jW_Kgo3&!4(d$$a+jMdkcNE_bDGPv^bv-kG zGx_60eljeMcT4|%wI}j+@3*GMEinzTB|Mmm!m3h(xFjCqrsI*RSEf_(BYox;A}yqs zmNWdmiJtmh&O@sV@epp>7}I>m!u;=^EkP~6e$?(Q=s+Zz_85wx`^sq6b;at;*V| za;Y;TL2fq$Lm_f$eX+duDE!gtmlw;komjS4S{^RmF6$$qiZg};h7p%5=VPfleUnM= zg1dAW^X{8^`<_1U2@Mnm87}lBM@J&8Y8J$VR>!NyqSZZ;L&aS7*1OZxQ!LV?oOm~k zw$B2N6alBk)(smj-W#fC=?9DRwf^9tW@R6=x%HsW z=*1Rg1hav3r*D&l(Njt8)gI69y7)IalTyfA`=s!ONAb;CeHbjhpY!J5e(nd+ey|UG zgYtXzSQ<~TRrZX22t>HZ@>(KaFuzy#bVVb;+dJaB!U{Z<$%dD+iS!n6NQh}7zKjk2 z;(I$!PwT$@{Sf1)@EN?S0i6Ze*k>O+f_F_`j(2dI+-#;oVU8>5TkZ$)6HXjL!msf0 zl%fQz%_wGZ7mzp$Jta$3RXk2y`8wV;{M&ehxDr0@4-cOn@7h1gcz7@I8UCxRiT~tZ zeF*UILO^&#|LS9ad;k7?#eH$m|9TUC3&tbC{ko0&en=Y|U4s6f+ z#vJ_Cg4fgD@i!hkNl$TH(cZ%K4U4C}or8SJyi`B zIk2+@i!kp~-lq?xZ?LeiNIIKaifcYs_!l_tm()XRS64@I0Kmh;gV#fV7wl{W;1d%Q z13cvi@bmNFdhob-Ik>*@)CVEK*r&0DaWtJK4XzX$rS z&p+pB;R*WBNDeOlA`3?#;CBmvkM}9y&%j(kmVW{EyXBu?|Dfxi!%6-|CawYUw6N2A z4zkCw8aFj*K2d%_$$yOV|7iNpO#cb0?PB392e!vSx=Q~?SpNe4W8?n>{KuI3{~42? z|LGrx{6othAb-;!u4&-{wsZTp z*H*;?n=h^oG(0IZLt!??f~Wazk52VSWrSt%@QJ8o{`3*}={5@<-K+Tby&nwC7Uuml z&9SNpqDoAV!%au#l39!`V->Ffdojbczr=uR$loO(VzIrrn~lADySr~FIz0TQ6_nQ0 zTNUen^*&QIebRO0-Bx)ug+Y~?fyj-&rtdn7#>}3RZV=VT&tx~dW*4QPw0|9(nj1m$i^tfC}DoSf$8c}q~f14@gKYid_jZbWRGr0!$)lyLP(?g?zil0RwXqxcY^l_*6;Q-LPjJ*fbRJI zewCiy-WyX7rU8G)3CCfg>oQD&-W2ya2-zdOv9`0nurn%Z?`(hh+BIgQ<$KIS z`;F?d7lIoJY4HHDda-X%s9~&e1<&8%r5eG>>e2b3Mt#zq;Z~Nmwxm1jdVi^LIEm0+ z`##xbY z5%e45DH&D3G3^`re*^xxuHzGN^2p#-jJn!=`t$YmpLt_(lwjl&6#iP=|CISl+`vVG zj0_L|V#WR&V?YZY{tL*h+*^M&vw!jS|FZBeCG-D*h2^pHhaxp^j%axN-&yr<{=INc zZ`d8Am~*D%(S60&PYC_X@&DBjdy9pT|9SNQRQO{ZTj7JhmHW6-VDrk!M`z<#H{?Uz z{mQz~vIt0voBUe-m9lL8 zlwUwVtD>Uf`-S5U<=-i|=mt({DbF9L6Obsg@CvJK<&Ap~yf+A$EH>=@+D4cIPMaTX z_LBg`r1Fl8bQIsAy?eI@*JiQW8(ZPraRYwXM+1kJ>)yV7o0UgO6;Wf)#Yl-{EjFnA z*53Xc9dm<>%%W>BrNU;yCQ$<1tdb%uH(5NxQovC#=zVdr7u|Fz>EWmFrvm=hp%IAS z#T{QYrm|b69Qfq7b8~aWRf}vE4;l(fziFw_ZB+uu#d!^DR7|`NlqxRsF7HE z^zU`|XIn@0%XCp#p^kQ9??VkCd~#{w7xs%p%tK6G!7BIB?gfj>9+k}kiC_K9Wv;M? zyrvou_TxOU`SFR^7qm46Zt{y^kn?4;c}) z@k-Is`|wEN-S1tK;?^VLpt&c1M%KUUWbA2K@bqU&Sx}{415VEJ^+S^U@&_`!`^F2j zvTfseE6lJ2$Q{l|+p%I@Q@3g(*O8An!)v<|Sp0tA!+681|92u}u8`5x{MO#p5q5Is ziB3Zv!}rRsFzUSbT{7;_(46;|4u*21sYfkeprT@`8XyMLwc={48KVR?vZ`Bd-8 zx&Y$3DkBe+w)8*=b{%*X2f5l_5YkLTZBO+%bun>OuJ=cIqqfAl#@FBCQ!K zD=KWVc>^i<9fw)YmWyjciJMO>&AUHl0lsEtW@;ANq%eE#rYA=^8^f zL#|nj)Oq*M3X3C45Aozj^iP_v0wHzCFm-9HUi0N!1yRbL=36q0BAj36^P^mMbuKM3 zyj(1mE!VK(92qTerUATTwq}k(M@jJMjL&fS}}ROvawUa#v(w`C^vTMveW<%E|+| zmBP}NxM{*fdxN~+SD4@1hk@=@uEB225>te*e)>6{dKmF)@J&WeE$NG*@i#(TrM9&W zdzas(@yJkhd-#Q3&jk*|p=%!Y`ZYW2@0kLc_J4(?EM`qAF$~)f+JP6ZrZm5lf*#Z3Lslxl!NRK+=>R9)DYt2Mig;v$iCH z-#uEpRlgqTzSr{XXy5nODVmjCqVf1;su;{09rY+;XQ%&cDFkUz?)8f5w3rNc8CHmp zDoOiUW;xL-emB5wtS04{+3}m8!)QB3Kh|EF-5+BSM!HuV<>g`}VcLJtLeh{p$#Bl( z7cStl0$=YPQKifGyLs$BkMRX+dd&fU8&+&hKgEiUiv^v^%;7??_=eLNOjX97)Hl)2b^ymrQa zl>)5K^J?!A5no0z)IPx5{5}r5Mex-PndGd1Pjveib#lENF{NvKiE*QjLmigbqk&CP zCsCyaIO|&}d9V___omtb(0rU^ZA__y=e*qc#li6fSB*`_javWtsAUzcikc0P{dj<( zB|DeUO;lYh!i#6lx}G$M0=Rmo_QX~v1eo_UB&@nZlhDT6q5k0uJH#*m=>pKA%1rpkD(Y8B!Y*=Fq@Mxye z)x|WKg#Y36p;96!Kj<0FH%@ad90%>YeXE4zU5ai#fR~wR)^F=tew5B){|j+`>~NV#0N!lcdmckMc#Z|0HsK6yP~GVgkDIbp~kNK?h?9UdMgBiuwU9YIcded$6{ z%SDxQW~f>CLeHLYV^E2qA&u)MVxVV3a`Z^dyKI{&)J=Sv?S6~pHNl_AEnDzDsr1$m zDR~@E0&ohXHc?Zf(c=Hv$Zw8(v_ji9?IkbvfMjGSRH#t5=flBcRiBHZ*L`eN1#?^_ z&6Dfs{x1xZQ0`%|%=JQr8tb)<>Zyel;REn`yhv5aYH^qI9}ThVX)K;BJu(W6h3RaFyuR9T5De%4QCUroQ5ZHm7lKud9FSV8%2Wpa%wR zLU5O@>Sb|xa~>a~`Bw%fww#4|4snl>&)wbQgj>Gn_+7XU?iZK8lds%+#)HV7gfL@E zZ_*3u9UGovspqSB)g<^y=jsSJ9>{QZ=Tv{-OSU!2!4$pqfH}N+#Xm`b~Q0im~HHDJXj0tB;fw z0b;ZP!m|KP&*_C6b}r{#&l9cAeBC#YZv}GIQ4X5hT|;zk%`PS04-w*>%0oay&ZA2G zBN}Jy23ZQ*Xb)kjveEww_I{}W||e^RDEj38=^!X`5=W8k2-mx^n|uv%i*jg+v^P_jGe^Hs3rtC zi0J^oJAdO>O%+3;Or~^e{n4O=Tr;c4oNM&u835wMjCT#80gbksDoJTNKJ2S7@3~Fq zHL0JOXtEkR*XYp~63y15|48xkq-t2Pt=CL&L(_YZL1BE)rJZGx;0(+svOi5^YLoEE z@cUeaHRwt4OqG*+N?IBK=zHZ?@UzNpqIb7ZlXmdL+{s(Fq-0qbG&*iBcE{?)>UyF$ z=7)M^`mdarsl=3wEh-pP!IU9~eG_{YPG=X2G?ce|dtT=`Su;+$i7>hT22 z+9o41?pM_6F*vh8w2;@JuDhNI7eUAoo@kbVVMuu|&aB|z2-=d{?~=p%tY>yX2j~ALQ=+{h`w>r$0WsG}U6p!WD>WV<$jpeH5nwFZrv^Sj( z7q*}Id?JsibE00S?@y8H>Y3#MH*V?8m%T|kmS|49Z<$mzc5~5dO)5vVPbWJ&iS0=3 zzNiL;033qw$UdR1cU%hk3KgK3!Wc)n-^cfi@+^T9tCg> z1b049G+Ts6(q8qLdwv>>oL)GFn4JD)4G7_e6N(VxgWFrpZ}+{e1>oKI{t^Zfol6N{L{aMi&&^ zccys}cbuNcFOY4nolgm1P+M-}X1;E5=WCUc13N8cWv%rs&x+$~DMAu#X&9+_3?Uey z72CBrlkMR`4^xlHc!Av58`4|Pq|mf!kj@_eaZ4psrJO*%h&?w(pnFcA?$Ig?f@&UJ zwqA4z+k|K?C~NcFt)~Z=xZ0V5U_=MwoAk z`AAhLKHUcT*&Oh{IfW@wTT94+-SO%Xarjd$d%{!RD`g9Po!6Lq{G<8kirOFNyy$%p z0&S7aGDl8oe}mRbOn;9}VosZtp%(;do*?zW6~ZFAHq03gF|%cfN~?qGw5UivE${OSW3#F|Z zH@HS!BctsNB_#e3V^PpHETGz|xt-fFIboF-n;<$a8IGBPFbh)-jr!Iwx$V^tzQ4p- zx4jEUSeF&tLf43cJu&?g&w8?(WkJXp`!NzsD+Q{!cq*WKk#UY_gL^Z>});@zIte7 z@ZRU@91Y3NBAxZ><9MXz#wLX4(Z}rIo@7|v=X1Qn0fDWXNN@~EW2$_QGr$r^LK1T4 zb6;EazQ;DlK2xbOlYJ0AUnIoT?k>4vT za%1w{Fm|urpY|v|M%F{Y^>YPdaRX3` zH4)R^>tm1{Vzw$femWGm8T(m)X`@Bq3w>Ygl+k)+ek@3Ol*zXE?BUNwa3o59J`XwK z{39SbxrhxJg!3aNHMD@6S8kt1lI)W0t-Q&rbE}-O8ADKawX73wa2l{1LsrDr#qn<; zF{P&I35RfV{RZ=Lsn_*#Teu{VtMsFOdw5U|37U*2tKZ1o;o^u{dh>@aW_nyT~xec}gj!h!`NM!APUXE~c}{WRJFwgYnm!kg|SPAm9fdwB@vMoW!_Gl?A4uTDIl# z?Ns6+Ja29KU2+dKaq<&nI1d(H2xP`OZZi)0Vk#!8IMU#%*$vW5a9xy{r14*Z8ylG=4OcF2B6^DK~5W21lcDUE=ic+kI5A zo_~=oAGvg!8oD?L;5W4%n67x%>~}yv60Qga!M9zg^2AQaqf752inO zJNG}1R9ZgqOKIlV{e10Atip0q;&3_S>dsNX%%J7HHiC{@k=ILDw8OaZuNIes!L$@ zef@mD4mqOO=K^SYl7z1jHCkx}@Id|cG7vra>1E_IOv3ElP3{l(a=%xyZ2NWTATO2T zp6~cOTZR4&GJqiEurhy*U5e{zch(ixUEgEgss5CB6Tg9;Ow=I2_HxMMO534+*PTw> zE}?0Ev@erRDV8HC)(cAd9c~us!R!s5wN1Kv0&(0k&dcq(dJ`0nZBs0MKR-sOO5J0X zEW~f8J!)Ho?+xDXU{Yc3wKc15I#j1_+VzhC%d|Cqu{@GGpI&Cu`d;o)BfwO0(KsGx zW38aj$&@H`#ISCC-f9HZ8Xq0@1!czf@K0t2=0yU17wFJf4{SnM@?xXN{+oCasTC^f ze%NeJc-7I)u!)4rcsIhsgnMV;AccTqQK**`Nbp?pz3?cRaI0($5M1jVhq{ zw%OF!P{i1vs50(e?qC%walF@9-*cVWZ{)Fbo8nv`lj64c*5wF3IuG6YH991ge{@%{ zwV*F@XST!2(Aa(Ru5Mx)q$>uYwmsfUL?-k!36UN+-M}6SPbp(va$` zUz>GJk&zb&Xk?toim9FVu!s-)q>J1y?EtG~W{%L}uE2z{CV_P|t1I!1Rs zH*o+}-O*xl(#(Uz6tcw|d$|=XX6@+`CVQ(JyUcxIyQrwUi|5l+5gc1jS=D?#UuNNO zy{#QE5bt;#cJti8qPgyt4F@MDMegl@o7&;1KX}XXz3|Bo2TlYn5EZ(c&GZaRliCq2 zYaN<6^|048aM|>jaLL@BzJ1sDq%vwFL9g+Uz}e>~2Sd5WpavU}q_KY73wVVk6j|B`sKbo=;X7Wz$=WdV;#lODYY=pmzoyQ@@b z^O`{(ycKK}Cn+;wS6h?oWnx%04^<`B*3rqWvY#2WN9b-t`gUu>EIorYz0n*L!_#g; zl_*ejx#38rY9JzW{jQZHEb#7tpx^O9*Xp4%FU2%b?pzI9u&%M+7wfT-`AqZ)?v9x( z-F6&kKb9Ly*6xj_vu?5~HR1Q}|0o@HY+$oiO#fZWs|(v_dc}sgEaGXv0CG1cZn`kn zir}l*@2Q8)lc`H$!j0U{EGmY~o#9?fzNQi+V%M+yj!^N=F+C^6x~0t^Y<=;Ocn{Gx z`!chw^|Vk3bq9R{2$a+^kqI{=TOW#!<%(C1&J7WjRT?nR>{AA`yiE03Q_2HPZb=G} z4_l9@v|9kLSZ8W&U6L$B!s`7lguTu>ehtC06MQ4&hg&wLW}WD9g4oKyteofT}D*@^y(fj-WqUQrOhQVY#;uu#g^B zSFUaSgt7tgFberoDIf{wL}KmiX}&(8Y*$*5x>3@dILCaiRU(lzZ4cH2%~bh8?> z%OO@lG2z_0HHAF868Cu#M)@=YEEC*D1Jkw+=fh*%Mlcdo0!DSMz_K1xkY89Cb*BD4 z9buXQix`(-&+rP6DanNWd(M0cE#^#lmDk5<`# zRXc`#g;J)BOlr6jd4WxkmX)1_$Ep&H0I9+ALRMkXcJrW`SQo}xQyU4ioGJJV`yC2dPs^!}iNZ!N} z5{u$B_MyPQT@kHiIKbO^1&AeVgEn2)wOOOF&zcf1kf1&13y zuiVx^c+a8tPbf9c?KD1yk^y*0SvMT~`3BbJ9e0HsTn1@Pe9MiVdaDdSvex-p%kc(A z>rj7YNiE7Xs5#=JxDa2{WA0aK>kd<2Una1pc`ZOw9WIU}Kvya; zV<9cpfkRQ%rHTv*BP=sqZ249T07OhVaak2ef!yYCk~CUv1CptNX*!3{rHFV$sHC0O ztIzc&4R7x*h-93&Yyj2KPM!Kz5{;wwRYM~7^V)ruW2WDQUAzx+bVUbDg!%O=LOga> z1hu~R33-}_on+(<#M_Lp)LVwiLw)*7vf$Bb3t!o;Z}9|fWur3(u8%JU3n$uy5qDM% zwFbTq5giDzWdWnU$GSUp%aO;}RHoEy)MKlvPK{8o48IS9m*-ryaOHv5<7_Hn{Vizr za2IGg7Byv>ytoysYr5{sA&U%LS@CAmFrKXfdqlso?t_-La0+kKIxQ2kC%9q*?c~Yn z;co|A#b4_h>q6BhWRl}bn-d-^3~-*k{VZ;SckDSv^qsg*T@v(_VSgM&LN2CHqLwI% zHBQUTK{eQ6yI;(`gk_JX{=qakSv+KZcRuqjiop0mUv zGC{{8r0mSN<2GTSMcS7j6+L#0es;^dkBvk=S2k3}7rx_}sx&@?m**By@XF>`2324f zeaxg;H8vaoSTuoOuuKRN+J^b}JV?$dOCN^A{MR)8U=GNz1YPS#?!X%%P8D?3aik~) zrNL%KwU0ijK56akkHwdj*?|xHa)ImN+YrQ#P3|V(@KZF{mH)a#WS#sPl;xe%SV42~ z;i}~>-$23n;Fw=_Lau2w-PCNq)ZxS!t+Kz`!2+DFr6i_$0mhXFe7ex{K?Q7B-=dAW zS0lKsb172JwA`rcP*rKs_X|{EwX7+&gosb+?+(tTd`a+?SG_&rxuV@bzFzzF@z}+z zASS2wTNSvPb?XV1@-dPh({ne01XZ(9KJRZ^v@_7{Xd=EKeOb9p z#K1IDnl_XPZszr(VjNudrWD`App~yNyLr_`AO{4;LtJX-oWp9x*;vZj$wjw#PnS-bji?nMbr~7M`UGsFqhelzJFs#ojYmJ7b}$`z z<1*wn(K=O}JEZ2P=kQxMO)Rx~*OQl_q{Wyx1kO&BLl#RopkTETM@5a} zP=73_K0Szq1EW#JFJYb~D^KKV6C3l`KNK-a#Yr7k5=VHn~X0av& zBod2MU0Mef2%m09P1boVII|m8^KNFTZCiv{DxJpzR5T6~^O!tL=zVWiPwzZ221>!A zpar(IQvuVJ>QYNPwft?0e#{^$M2mH+RbWq5RmaTh&3s*y2YD-*u8&8UB^4Ei}AAE{#|Q$p}eE%p{Jt7W2?wRv`(i z$;V4~*VFtp3l``ED~IMy&r`>mZ83em)J9W98axPA*Rsq3KW}?i7^6f@qwL%rbt;i* zY1d|dujlVm434ed)P+roO<(8|&eVhp;oDptjrq7;HiG-UbpXXpiOUkdxkF`s_Rf=_ zBvqRn&=;99>C3MzOqK%K^k7KT_nk=lKjxXS_!9WkaC>-^BnH$7+QB>MCS^0)CLBy{JQu-t z$nz(`{G+hCDLHete0`bF8Z;{vT9OEYgmdGFKB zv6l;EN!kT)^OKAkdrplh$}UW?DyvOp(1gCFO4{wGW}5SSf(iL<ZXtuCq!I4R%XN|yF&OViWoc$c%+fZ#gX9l)Fm&z8J1x5L?)z zfpS7-`E52=nQ47VZ;BF=l$3e~FY;XC9rkSK7b`3}KCh}x=BuUoue}&)rlP$%g>Cr4 ztO#Oz>$d#t49Px4s$chJ+>M7c1xh2OsCJm9ylu2{5ZQL}pV64CDPBEz-5c1u@9qfo zviT#d{1oZyDv&FfN@!So-fQ00bVRxUc0uaaRD>=icebq@3T&QD@0vCnG&IeK`94cB zpPL5*LY|2^$WL)_a$^sJcF8I-XDX%t=#v>wmU(MKjW#;s8FI|m=+Y6f=5R1A>PQePl2_uk0 z1&h#Ev6aD|3OBe4ylnr`8EPGna#eG?YYtGb)6c;{5At5wB_PD;P*~gqU*2L2$8vGUGVIQ~&Y!+M7N^2(PVO z(rTrAC1YWw>mgBw@R`(gighR0df9^)%&EAGUG156u_Al4yrIcR>vDW$_#j&#GI*2(ru=miSuTTmPo@;L?BBvNx z@35OB6CynDk@tqEsg>|?AFDyNjYX?lbpb4ngukW;R&p=mqVXe0yrF^6wdU+c0K0Cd z3OQ4$pe)PG>}nC%ir8qz@-t}RlZC|>@Z5Q!i-S#mU;*YL3`$H|H+Ez2*fK`fam-m4 zO`KN6Eaw-iE%<1JMyd;!Ix!3q)>;SQT}&@W;C9uO5t$^*U)OH@g8LCMG-KAb)fPOr z3S=uw<|3U<8k&hk)(28{%|Be5X)Zc5RMkpt`;1;!A!CPDuY{2x))zl%4LO!n4y2RS zFiV(1H*lBEVg{=5*41>mU~xZ(EvbC`8L>($v4KW}J?F9wQfn>*tLBKHvx3iEyN|O{ z-ZvtOibV38;6!xq@7f19X5zm<(mtrMDZf8FK>2i_R@a}SB{91FD-g<~WWaZp!o|yOT+n4;n9Vbo+oF$M%`X)>|9~I}wIOP*w(fQNO_lm?hkg37O z#cS(bJV+;l22A{(cPgYGd%?AxZ1Yw>ob(A1R}GzvaY-{t<;u#rFx{qo#DrmK-Ki+j zygK|sWSgFrmf5kTZ7Z9L_Rje^&gf+ue!s6L0MsDu!oVhpG~c}qGQE;PJpr4zp|np7 z2iiw2e$ZefN7D7uGXv?_1xAqT!Nk+QGiVfkBVF-oxyS+|=^(TOSINW|OV$b~!u zzXJHJ(g_UQ8ylLHS5*T+R{K6)6m zk&nxndN;os2}Gvc*c&}o(meE^wC8eWHaCy)4dfQ8mX)V8&OixN@;@FRibV;04Ekec zYZO;{oBYhsJ6!nu4$~=twQCWwvMd>sV^}^?Im)eM&pUClpcf^u>(?eX`W;Ot4ZX8s zAtBouG|Npr%)M#QZk6*=#oFxPC`2uaW-df21RMYIXPj}0O!gjU50P49c%8QR%{rA_ z%=%4I_mWsqZs-T4bni6D;DT>EHCqG>mJYG*a!C>rHeS9?7sG8qUx}CreL`*rln>~g zA!V7dak~9krH4ACpn73Sc&;jg)m%)>_}3aziyU5K)X(OXjM<{Zg>yTalI8RJ+2Ns% zj92ldH7{(V@iXP2aSSe4uR+fzS3JfQ(|Jm21F4ri$B*chasqoANM8#Ibo;=jh(RT# zZ+^DU%!Hf=o){;3h0*ZFkSRnuiR{kig!Nw^&bIfWd$&iy`7~2C3qdm0pwBf{Ws&au zIx;oTQsU@jN0>6&FrIr7YaLJ2{p;A0)yC{coa5{Qf+VHcMr$OzOz=qlI(dZcKHD@Q zhD|jLGFb2?eMb@OIOl^!kSw=xGfbAcKpn8BKPk-xQV9Mrs(}2b(lmy9dkh2AT(W*nf)<6#g?|=sJdX(>mAr5ukal! zFGmNtw9TT+iLD59O{3-8!=d=yi-@zx`;$lGTcXL8lym4#`7}|$QGn*CfqOIsyU|0Q z2>Ly9N49Y=D{Rn5#uDc1SIrpB_)#(aGXI5VM4ySRo>`AXp~cVI$CSK+*Wt?*Kb0qf z7TP6^VgPlvkf>T2Re~Tp`Y-GOgs{ z`BPP-=L031SSgxK#g+eP_M@yq1aOJSBb4}^|IiDhAmH)prcQoSZ$q=8aI&lBFw+VVM#hKydczF*hmB2IjzGim%) z)z{LNWhv%X4n(#Nmy75-Y1rTzDzQ7zJF4>JO8i)mQU=zh?D3N`{FKB&ePdw(bYrwp zd0<%TSNHz0cKys4Fxk=7m zDTT5?BR{Sk?r5oZ59KZ>7~*0C){1_?fmCWo0BFu%3{fFLIhs#yKjuSz;`)S_rVh#f32O zq}H?|6Hse{k&}CaftOgWA#LEJ%F4==;wB*Vr8~9b=*;U{Vz2kHYdoAx0pmM*hPXVk zcZ$m7)h((#=l%!&6tM>7NtTyo`74pD%j)+QiDr5c)t09x5*aOHP5W<1whSiEGkC`= z?W;G2j?MH#&R3HI***as_j}Zi1}%0QInjZ8x)*{qt3hM{_e!^2$*ZMLV?&Nm;|LMl z|E>9>n<0Jgx^+v0;!RkORED;|f@_!1yQgRw$k)x{&n>f?yhV#IT*JY_IS%ugGa4QM z?^)Bh!QZJ?KRS0mx4hUc(Mx%>CU#tc0(Q@q*Y@P0DP7UY^EIbr341pc9%|xp1fHA3 z?Z37e>Feve`RukY_YCG_2KmJ0BUee?k7MT7;-B*A#ODK4%Tfewj7H;i%iNwN0wME~ zX%oMLXkz2hZ!+?>e7$ZrH+b@yid+(Sx3wnLHd`=k!own#=7t8*i&C0zSl&? z&+OHW!D#58Vn<3rhKd*%k%JP9Rc9XOgHcMvbCsT$l1gS4n0x4D)bVlSxuXf|O_aXG~vsl?96vzC^| zF>(HP2tf~VBXq4#fC2xnfekw8UsVD40hNj=>*hB%IqYZkM#FQ}knl=F616lNY@kaD zP6?;1lW?ep*a zI90Q#o?X=JImaCGjAz{UH4aaVI40JXOsN-Zwmb1WN0!DJTgm}e#`k*13;QU~;IXTE z?&YnF;of9J5|+JYn_Za7;SpW|tUfnuUS<_iaNWCa#4&v_R95L+kvBJ-1oCEIrm5ug zt~YpyBLf;(3{3o1M5@Ys?OGh5_V5s9{@n|{&5hLBUTFB*qut|ka;Qo1=`=C&y}``* z{3M=%>H#{VNac#RNNp-7JGb`!=QPO%-+_biA)H~k_DEdY_k2cc%z0z2or4Gsm-v4= zsD!srI1bqsij4XV4*kBeVSzZ8Tg{r;bt+Zp_c`_mPbn<;7hSs8x8|a^u8?zBu*?N$e)TEvdor;?g_-tis0#ysY)TD%Xoop?kca6FaYorR7}jpNnc*gL1i&IaP8 z6&ihvWfsN;#sYqn)`t)V%}mu8O>g`T*wN-p1dmN4rZHO0yJ`Z(p7*;~YDft8#kzz? zrL3_We)W83JIHXBMLdF;0BCN6&V+>vf(!Qtlx1NmS}~pSW!Lu1yB|Qq`XOJ-lHH3( zIcC1m(7sg1_e8aPXT^u}a8@~{52vL^e|9)&;Xz&F9#1*vXfwFR2kgXs zTX?C+u7gL5NxZ}VVbEieQQv`b=X==Ru)QDw>&B zAR$ZX^G4!&ooOpIA@1z&LJ`+`%cZXGi=L%y8omac;u#-3UW6=iZ+qfJ#*!+SgJ6;2 zxme+eO*Ivt&Q-MX*sm(5FKJ~Xdbx;~y-)Z8pA_LxU>>+&u| zaS@oU`9KQxlF?m^pz=GJ7`N6{T=UC9x^##4VAwE(<_tJEeFr~+r&Q@WwwU3ht}<#%4Db9NGT+K-&~EQuWVjz-boAaf+}zi&l~xX!wkt^ z?;$gh<1i6Dg+Ys(b6I}Jp?clN&+eNqDAO31rB4C;lxfGoUkcovHw z!QmX`<&4M+%rEL})&!$V z{e8W}gTv!>fz5F~pZ=#45(1wksv^&+v7$#6)zPeAj;m|VG-LYzNU47Q`WpAECT ze@mQSmnX)l-oK|y)8O0>jN7^VMr>3|-j+&JYXQLfI(r~!-x-*|%C6tvahxPH#6B)` zdM#Cm*$dBER+O3pXnkN7dq#r(Ba4W|n|SpS{jR_;gMt01qKn zz0lUg)|@r8w9K5B1ir=&q}SeBldr%+YY^H~hDqnCSMsL<+vU;b;63PD29)*MS~Pk2 zblzFdTc3-GxI$7FXNNP#R8(AdUMz-+&Wd3Jjfa588?onv)+eXN@fN{;u2G1!PleG7_KYOhY1sJRNvnv5pNtpDmtdBEi{B3fpGqMRU>gDkNBcWmmqNx=OVS z^mOyoah)<(CrYzU$3?@8!4^y-v`aT#C7Qz{56!>6Pr?u{bNx*l_$+v5%0!V>jq<0tC0 zA4(tQU^;_sBN~v92$$W}DA~195pNM>cel0gP#-&N&dUnxV(WAFwkZM084ICLrSw|b zOZN?KwKcrTj{7)$n4o417T;5FF3oftt#v2~K3rixgI^YvIg#$Y=KPSBU@Ew)$Ug|~ z@RJd(ZG*?bAUqT>jAe$q<^EhYjX(y!&-RDqG2jes#$i#jCCkk_6&Vb2{O)skv>lfW zYMk-%ZY+08%KW-QzvBQ?SH5?=fIS)xJM#Z)VLF<7p%gGbXlqXp&?be5N4Bo3ieUk&YnHiJowRyD}LWFw@uhPvxb{FQHB>! zGjRQD`6?bmS6SIu%Q1vYZH8;y3eWH6xY2FKLVKluHuGVAaM#}td)D>w+c(i{fwJyX z`=%~aI^WYxGp#A)xon@SSbf*#yByn^^vB^m%;$O2IG-b~@;!qJf@VUL_Khhyd88Q< zcNLNL)A}>_luw`A^zcTTh;B|=Pa3v=EF6{|9xt^j*>^y2!Pabkj}g}rg(8)3&VH-8 zV5tuFmuwhmUN;4Ydw%vE+ql^;q+**%193p+s~amuKaWYguijusve=D2aQYTSG4nrX z_^|r6xVx(w`#F|WTpW+2UOd*0xA?Y#q1FcGDVqlmgL;qS3dsU@J)61ninW)I5hqd) zM4;b`HgKy_iJ%T>Gd;c*Y)g=!=X*PkG&*7v&FW zNfqLhgzg5$oI>tNJPyvE2cv0NO0s2OqM{^o?e?dGVK(Aeq6PF8p!sXJHOYe!@j+Zmrd^qa#_I? zO0o0{c~&mXIuQ80+**h^wt>s&vJ$=;@3jomtTJvFJxo2w!Fvz$LopA07@x9Rd!2os z8&6l1=O8Pp8J+VH<3g18hOad1QjLz?)#3A3Z4QB_cgrYOmtylD$7R`#jC}VIY1!vG zUVAYESxy# zA5fbu|2*bpsCy-F2F*n*Xs|%~b15W9>SuBBk%eY3qUT@6CtDphgLaQcxYY9wm6w6h z4Q@+XC#dPdBhF5y)s9^1%1C7nG9XzzK>0lRvI3yLRh2>OO9jhx4{0wbRa$e5P~ z#~zQm$m41qLZ81BQYw?tah6*RX1)u+;a|}3vXpo1JXpOcyY4(U&X%g$^nUOK4tMp7 zrIBo4F{BB}wYcq5EH&7nOKyw-W;mKZd5z$^x8zdlr0Pt8yt#{_doLO?zp%BoxSui! zc#-Y`?+@pUhL@p}$&D!rpMR%iQ^ zZ4bp!n_f3sljmQFjo2Sx*^G4$+!VoIb)HkgzF&~a9MT)?GHECv0oj83bFaFGaF4yK zG!Ew!e>T@VoY@z3xe9QP3hGq*G+U~LZYSc$^MGqDlxX#~VXL=s$4iaLjWYEN^P3HJ z)0$IL(<9w05Sq=BD`x6zVXpK(MJ<=&0J!H)n5+w^0B4=;2n*C+?RT|3JL)x9o824R z(6aVD%o_nX2^8qzk!YZe)BCW&G9U_P@bYSri^KQHN-~*CrSw!{$;I3gGH1uxsuxOF zSBLp~c&UOn`OsU@1b&e=4`AF$Ld#hnu;*<6PrEca&h+d(S+OfLv(xaN+xiG$gfoJ5 zM%6HrqgLl3d`9R)L)rtEHfWgFuyjxmbP}@0Q)bC>RK{%nX>)NrlPfemIeRyw3_!*? zAqe5;q?fOq;#dMwNE}X1n5Lg_jJ6}8f4DoXtf}y_-{0}FoCHc?Tm`Fgpf|)?;jik)XNTIe>79t?B>phc z2Bf_SQ?lQK1@vVQGMATCv;_*T z8YzcL@O7)lblpw7s*99$l zqL4(rF!k)mG`m}HUv*7idK~2Nb_*SR%qLUUL#XIDrOL@vS1>HCTLB3()uh|B*+!fGsl^5Kik8bX0?5M=FiaI8O$n0er!}rS}!ESsLRdRP%$Qs@aP_iTIe;*Z3H;Z zG$s1eO#5fz?XUNI_9hIH`UNh4m+mKYt4FFoy?s$r4tqLzN<+(tF2^+smaN^1TyAi4hu&stqnf@>oWi2rR{KFm)5H! zf>c!bU(XkBr|ufX{Q4#8{s7>={i$yP7t5(KH9c*1oxzhUruP?KjIklgjX>kzDZ6Fo! ziX6%0R$8pH+GOwGr8xnt``wvdn8Gj&*Wk=Kk^jwQ_22EI0Uo)^q- zo!$uTO%vI`hK;ROaP4+MvQga3%naHw-^9>vmV3oxn{BGTFN8BUHL1a}w#>`6JP@}$ ze(uNL))fE!Rm`}-l&AGjG}UJ`bW;n9;jBmjdz!5Q6}$l$L#_2;QuucXEcrB?#GEWc z>h~cK3BxHlm~E<9h0=4K6!X)P(0NaMTvF0bZ7PXev=t1p0ee6HjBLY0$W@(A!<`Mr zMxE#3=b-5YLqMl^A%|E;H)Nze9M%*G3yS1i zTpS|>nVHA0rkfO#m~<%QMr>dmN{z)hiHx*-Orb)WZ0Kv^e7X6GsS*=ftCYD30m@OA z)tD9na%k1dIBf8XRCOpc2FOmPk>512Mf-G?QF;0kDxpNOa ztLX8(tLQt=-+a=BBfMRzw@HS9`gnZVEA$$>tlrLYMG$&{lEQtSBnHZM@wVj5%?nM< z%!1o6=>N=z{PT+Us@hv(Z}87Nz_2@5C=ZxMH{{?*I<55q87 z4FZRB3Zb2$N^snl5Qu^@3-}eMaEb?+aIuIe1_>@QS}!V{WV+RR297-YGnK$#LYGJ` zO5Pda{P#f|mo7q%<|)Q*SO8;Q&3V_k2(~3+6u~r4^O;>Un#?a7-|Z(IZ_FrSxlnYB zcX&ml*_pMB%taaqPM8@IK!}JnOAO0t%r!jBvU9ur1BJivYxSe0OKkqS>qVSxpMSdR zF9-*z{u?=yh*Jy=%7p#zWGS%;Y>f>|Xzr80Pyiq!EIhorZ$~{g0?2ZZ&^eX=dKTfn zl+Tf<=+-~0fU3sde0z1mB;p+UE)^1#Lp{fuUiT7=bA60B@u}_R&z#F?RdD3WLwaZD zmIo8ip1Uq1(b);teOlKcI+|&rO+$o?cyj)Th`m~{bZ+-TqG-KD-_Y7z4?gy|6{mQ8Nb>jbwm@fu+AH zHKg~Yl)?BV+pufPr*&=qESsI}R9mqXi}SLkk{N#NtLeL5vD%}~IswUmR5v!F(Q9+H zqCMrn?_L$WF5jZftuo9V(yZ)uI0sE#3R7N<*QLN=doadH(ooFyh^x)!O85YYvhbOq zYT>48_U*utvE+iC`VV}%N!$HtG6EqnGs?`4KMwOIEEEShz<@Ho;yUN{6ue zA4#!glmbTWe1W;zDrC|f7D#0rb^k7$}`hzA3Pc!VpsUFGr&yaRqRV@KO7xL z96VW5#xmEIoB4#v*?QKf%wgOzdv(_|%hAZYCax7<6P|AeL|y3H9*F(U<0SqC=%N_T z9Rl0b1XbM60WS7Zp3Er+Rs4iY6M@2J-azz4jhg|pb;LgvG}*+2=_Ta*c)Z^rg}`C2 zj9mP2aq5o_pq#Q-3eNCT(mWX&qa$I>oIyP*VCiWoCCp5&cgo=TVaCr?wKb{D0A zID45%MY4;p*pWw>nY8Ha&Sp`l;!K~g!Wh8tCb6*4i7l@3wX4`4)3$#rBp76NVilFI ze`gT3a!`ob{b_o}I>UC9KE{ebr|@oqLMH>8lKv7~zP1#BNDTCqPeHAW-Fd?-Yd_=S z4Cu3;7{e$KpQpgWW+++Mn|jWlY6BO`&Yq_*4ZM0oPT>dTx7x$RSGKyR!f4}n1vM0aS8_dip7gaN5V;SO7(0@4qp3VFJb#X zD(IUlzWui{`17=sVqyfLM=^3JCVs=Yz)HRjIK-TwLo@BzfEogQYX%psV#=@CJKtK) zrPVryfX^-c?NK>~QVQoJIg1rM#mObB+p{GX`k2YaE~K*~RWLw8KC@jPk>FS%8>aQ; z5;h;J7_|P|aQycQqO66$0rXJU&&o(sC4*PPE|`!9wDZZ)oc@SAy$q+CMxgol8+*ah zO<=r@H_hDPfjZUP;jmv;X_~{PHrIE`*LwxI1!w8snF4^e3}LR{Vmo9~2nF}yoZGVHr^{@v zdxxfork~BB@&qw)#`mG}ahm5m7mkt@BV*s=Urob;H8vRFQnJtWC+5zy+PeUZnEO9+JVV=s)2UPeX#y+r>;%X>qu%v`D*Lc2TUiLsflAezB2 zG!onBjyIH%fdF>+W}Fa6Usb>&*>@V9gmJgXVV^{l9rqz`I^`- z-Q6lEwms^`Fza2^$a9%~%UC3nN$cAgK$w<4;gA2AItbyl#EW>bC6c$>`A;P&14rmX z6q{jEv%jIhWdI!E=<4T|KRfSV{xrz`l38{O703dPYQ2^mYiG>S;HWHA-w(K|JYrGaSI^7R$%Muulro$z(dSu1AjM?&74&PJHx)d2`z`v7-%8u;FxzOk;;>?jL2xr$4VfHL ziXZv7f>OfOf^DkteXzb68};Sj7f4*NYsL#xZBH=IKMnCMos+1A}CZmp8iu z>4o6gUQdoz!u|Qt4!>aYkZWj@g?sza2=fWv1;;eAsh501TO+NKAIp4#A3t>V7rVj> zHvWpE|48+N6{&TAaQ^~7Pi27g{1(C;553mvqJ|}$#`)EqHhP6Y6`gfQjDxxO;27L7 z9^0y^7>!I|3K2mEpH}vaJN*r%69b zSPuh3$qMRSNB&bwqWj77H89?3yC(smD1`K6FfkQ;UK4%PgaZ14Q>hu!oJ49tGe9!U zyv2i2Q{WB~Cx|Cuv?6F`v&tSQ{D%Lr^wu6sf$$eqm#q4q=CCu2FYUZswXGvLU}4=y z?;2BGbKud3e5cGYu%{dTkf2f6Jm*vUy1)wt zBGs&<_5P=^2L&&T)6+rh5J$Qwp9*Z8W(c*d90>7A+lo9J*4#h9Nn_kiFLb?0qjBRz z;Q@-|Mq2)aikc6%dS7hyw|z=mDX+6%$3WdicKgiq50z|2CE&XHu8?O;TP7+h&IXjT_O!o%1nX6*f$Y3~^LS-COJA%n5v9zUE|M2EoVlWF1R(rcC_SKk0 z4kUJEhfav@*ys(fCy*@@eUAGO$jTA^Dce(g3757%$H=Nn*w-^4)mm$&;Fn<)lX#)` zcERrc{*i@UgbmGkyDcPmijzl#i4|N0ao-)XNIkzo)WzV2e>q?+Y>M}9_4UtFWj=(( zv>mPV{{Dg0UvN5c#MFF)en4WpiZq*4jd#>)3VoaHzhF&>OfRY;8`d%BQt{Af2`-b; zb~qWS%fK3X;_X5c6Y9TlY*QWh{x^~R5|o&75SKkfW?&Vfn)XTc%lYWHITK+>nwy);YHDh_ zl14%Q<1msyIl-$)MNOltdBPY&jA;JtA{}>P#~p8{SMK_RfAHf_Qdh}$CpX=1TR7VT z`A~|bfgs=vROCgCs;#X$9>T_#&3r#uUs{&p-T0&=y20<~HNH!l;Hu9c+qHHBG_=y| zm1O+s5D%CDtH5knbE-*3ZE$2P(V&%$ij!L7EjG3pY~z8rj@Pgsi51X_C`I92TWbX>TtKx_#hodau&~y1L9Cn{P>tsRpYXw@vaOiWtp@pM_ zsU}8|f$$1~5vG=&A8DH7!AVCUD=`;*K1r#~&PzT;w%1QP8Lf8x_N~nC$l-Ga+Ngx# z{^No5DWK(d@Y}L!bK()^7#AE;bhyfI)TKNx!(uko(DPN)8(g9yVy8FQ)q_To4PNyU zPNWt&I0`qVG?!uvFKBoO{z~JtB2%LQ=;dtW{YD;_uKOX_IYE2%L-IfWChT^wc;RGz zBj&!*rZzwvu=NrOdF_Hz>6to)dS{~Bo?m>nz|5+B(N^Ixp3tu50MgVu(i;9wbR>r&g577Z9}lBU*tG>%#>>DJ&F zb4@AfvqhGjr)aLj$B!TVlFcOFlD+)TM?fb^PcV+Gsdm%WJKO_(KtQ6|Nt)P;tZLX) zBwx$C;z}kmF^ZL^hN8&dIRxn|sWc5wC9vvGUHmR%XqD6I$4)KpXhuJZ;K zzKe|xr%G?Ybyo3_#C)2oK9>p|2ohHXN*yofGGg{jV97?KV-{@Gm>2)~5H?1@3Voer zJ3&$+gw$72xV>6Vu7zi|HRM=-QD9=*#4)D)k}cXV=E)G5YMc4vPT2**#>Pf?6uD5* zNLAUHEfJ@60???#5GJwkJlFCOhcDNykE6}@QRT8-Aah^!EaF@PP5&joPnKFM=0QAEwVw@SXHg=o2f@y;g?eY%@Lho zRB?{kM^#60GBvn3R=OU}U36m#NyFB-3zSX##a^(a?CHb2_aOvilk*uF6w%VjuW+g+0i7@Ib`9M1 z`h8g#6(sfDN?b=y6hcEohvSu=rK*BJHz#~G_v1nMP1Ig*=RCB1s*R1(w@I7TV0W>fL;qLAT$I7MrJ6UvHxYZO~@< z47D>C%4adu`ehLe(UcjixJR|iA-yIvC7xH!RJzG|_MX_pH{n!=@a$%lW$hDh?d3%` zTtCCuCu}F(nEV%P)4_k+}$7*hRrpxYMTqob4U1r+N_wX1DQLY&t~rCp^sn13xl zOy4v$dF(rG$Y>hDptuwz$ghL87B7({LHCgDrZEX-E5=8=08`Wa2Q}cYOZDxCV!9j9 zFC~umRDZPh58MI3Un~JAI&%G7lmtQb%S6L;_~{GEQ9?H_KhCVR4|jO#)?gmjM!4Yn zlm$si4rf8oO>Y)?+`P>6S?A?^Jc5j$l)WH#fTRz?_v7I_Wh?;$#kq36r&%k4(Qxo! zcJq-K7^+g+lcfobU2eCfk%Qj(954oz{)W7zBm|{`-b3PH>ztoz7Y`+Trk(H0X_0m5z92zod!`3e5lcF+t!L#K$ zwfAA@F_aZ;Q*TKpKfY2oa)ofh5FD6bU;d25c&|*`dE%nLd7O{J8!Z91DBZq)feBhr zVnUZ1O`-+nw)MH}rs{qn4B$fy-B$5h)njsA5G*9}8m|kt3d3;4jE>X-AX9(R)mUcG zMQNhF#Z2OffS0nr3mmF3bT2Pmu4DRMj~eEJ-f4_k&=J`7#*Gl&HToLccD^|LvhINI zaL`wA(h?D(zA#wq21msYMaCqcfid!{v%5TgTW*umZ|xEY$-ovQ9awt375BYMsT!>r zZ&#sabMjUbRk2sR&5iZ$&riM@vi?_%rykWkM4M@|WmM|(hN)+q@NKmUMqGB63)b1AkJz=*t=g(Pbk>6tcRHwo47=hS9V%G?ML4_cnSy;)Mwb@8oV}RLLv& z-S#HPVZi;Q`}+od;OFiTHmfNrp7S1TY6TGb3Wl%E3>6ry`=Grtx1rHt%|1fR(z(0E z)i7PK*?rQO*6r7lb2+BUtj%ZU@32ZxU|FxATSl=LlOuM#31hG3feaJ18thiA4cH~~ z*J|AzGz5vRSCrsBt&M}ua)YGaK{cLh+mBeSHpHW+kTFT#U5*6f!@n7_I-3aTPo6$| zH8e8fLPH!2aUK^kQam)G+QQkw8!&ioy9~RcoRB=^w)`N)&FpoK^eej~D{|d15vX-4 zcu)@3K3n16EFz_EJH$x1)h6@r0gy z+zzI*c&eFm9DB&}N=vkx{IzBp`b4Y@1}ZF>0GUKwpbwQDz)NlLz4pqzbN*@aL0^2o z*dN`v@*N7%hgZo&ICo!W;Mr8ftR+jd^eVh0H1j1S`(>bW0zt#j zhTC+u%Vb)y=;5qM*7OfxkbRb|;hBVI>6va}RVRx>%o8-h>|66}eh&GHa!DbvcHW@_Ggi=n2Ybbsi7VTw_(S2>!&qZU&7 zHK?X2+pk5A)x!dM3V3#wVSiufP*_O=qDZa;UDPlbwadRIl8zl0f~s@fV}W@0g-fah zT7A6})A-F8p>~ZxuhQu!E1{W-Bcm zU#6S)ZkV$iV3-ptq~VU{f!xPQ$`(uAjuGP}BxYTyPLsoVB^&!rwTW!7 z$ltmL2`r*rK&X!rh_8{qQBFnn_RM341+6gOMa!Ta)Oa>J=Yvtj3Owg)zv-UVRFcLM z54R_mN3_QZwLds0A65(u9faT&Ycs0;G*RI}Sv%~tsi$~QOI*xFHr3$OO9WOLNRrTx zdUMD95IRms%+|6$1y*f@iu(DrBlm7b@hP4(ZN83n8CeQzJhm83GxHt$wE1ek_;V+$ zBd1E|va8{zVtrv)q)7bNo(vU)OjzW29gi1strcd&Njj^q6r(fCDq3V$eQylzVAG6a zA8l4&c3)Spj>!85^>_Cj4|4jyeL0u3yU7S2F2^;@>zCyKON{RD8g*nl%)qGY(fse< zFn=H{qpl-{rQ0{H3V>JL1m#$159A^F`NRZpw@>LMpT(@qu=l*J0eo8rCmqj8H)|4M znH1^V?hVU6OPSx!fLQpgF2^)-$qZbr21)%y&Oi{zZ$;M|#9L{cB^_2&uZRWk$7oy*B!D88)eq$NN%axBy=QolShZ?KulWXRa$zB%F}s2Y4Wrp-zcaw#c^jT26D} zRIfy*+zC?>k`-l4X~A}*0rI?B*&Rd6_bn3@dbaT%VLf16>PFK@&)M~xF8ndKoO3r+ z#t^7wyQZd8zk?vLS|FFCy9=M=wSqyyK6ZyN4>U9|w-mhLg#$-Tc>k1&&cdCC!#S9* zFeuw~%bKTKEOFOrdyUrZR));LKet?7$DgTw#SK5ySRI8E$y)8ArKi+{r@I*}j{;$Za($(1%0H(9l#&$3@9q;Y?u}|;j zxpzbbo`SG}JRIGS=u(`6-wmecU$W;{&Uul4rq;SG&Dnj6iSd|&kg_PJ5wFPmJs)%b zC5RlGcWXPoGs7o8q8uZ&h3)t7Eg8!=#i-mbFt=*fs>G_s56XL}+r*@qM_~^dj<*oSi=Hfz6x_gY)X@W}I#aa&xOs+Z}!H z;Fx(8pnf$OfZr0DNvrpu9XWs7mBR8wWPsAqjD>|&h3!he zx_lXqt+qywnfYb?`OFcei66fIh*n9?VBu-<4%{*&I!mnA-=B1>FL0ZF9oOzq=4E%n zphf(I8(uaozVW^;0iI7&)_z9>5P`_KrV@+DYh;;lG&-8>k|~t1BlHq2=Bf6}*cUj( z^EWbQ{=m{X)ovJkcGc7EW^~<6T|MD7kk~BvWu1GHNr7g$?lnr(i za#Eh=bNJ8aalz+roG*45SRZpEfFjw!9nVbB0{3Cg$@ zu8t3Dj+um!T2~Go+ElzUeQH*A%DGplnA;y~jupNUulZj7fY}<>hSajIkB8)RtR{X2 z@ZW66UEjHwgSH!%%pNVW2Wd$GTk;L_lfa)TJrz+M^*hjw zb&)L+1WJeF5j;U}v1tYk8|+sW6|;FvT0&HP#};q)OrmAraW0KLnm4B+LJpy8dMEAk z>^*dbqAafCne2L5eit%jL{F`^adM1VCy~{d^FxP~?G!NlkpP##$UO8bWWa_|34*x_ zP-=JcXc2nc>nOk6FpS-QzsR>c^7*8-?2+rFm+zF0m)WD*?7l7z&*cQ)HyXkZu6Hi- z5xUcBUeArt_*s7FG(!KZ{TbDvN%E01O!v9zNwUkG-ga?@RGrF5+xi@^>YEL16P5Jo zSbON~0J7csdGFs@7z{Pa+fxUIzM4H9^J3b^YD;F&EgnzZXWBQj>kMS3$la4-=s5*> zNBj!o9WIA$L4qcS(Zwz(*ws9221;$OdO@$y*}LpZ3pqHx;8#)-q7r&K1N|g60V$qP zLKP1kxXQP!;E_-TSu&I|v{Ej86rZh1Gu)rP4(m-XmOPW&J_Ma->-4{19wmpRf3hjJ zUhe7)*$r+;6o#$Iu|HFuP_he|6<30Cy2s)+uMp99FX7>~FxA@WYuB*AA+H3~cuD5L z+r8*lfO^Tul*eN#Jo1Y69H~ z_uv-Xab+5mOPf~@?%+tdv4(QZ<(^rs*VixHiY9B zihsOn>4&&026E93-91C6OWkkMc-SnCKD1(tyaBu3ZcYJ*vA%~zR!^hDwrjJS=S_VW zgTO^g6>*-rHH1Vl-meHel*iUsfZU~UEeL>8eLcf6S|A3D#jCoVLXL;a%Nn!kwsEsw z7@@A9gPv|EE>HX|UG3&3)Kk@kkp-R}2b3q^#q41o$pl%kO;E zR`$1dm+=O?Y;A#Fh|Pi?3U_ZPB~xa9GP6!R4B1qAhea2XzY>PFHJo&KmCQe!Y(S(NSBXT}1~Hz6p!enWVgIKOsACzxxXFP6N2$N#YGT)qDp zw)2h<=J{kQD!JVnbX_dq!)B$xZDpwG)ymC)F$MTND~q?5?{(`RjbyKR?ZbJQ7|(=#@cuhx0rTdx%U5Y}cK ze#+ZmY+ui< z?rm^5`-C|7^DH(HQ$uP_fB#^o|s8=V_k0K}qLwnqK>6S}A_+XfJPj zLyq|di?o{b*YphL`}sgc3aufOhKJBrX7^hnJFSYYo|_V5S*ZhM(FD6hp> zV94N{Idt}g*F9eqjZ?T68n6t#EwX$oTm*9>`Y+)hnI}w~y-XLOjzE2vL9--}{jJay zu(^>Ii6kb$79dc;O^u0Chze@L^+)<_QL}kDIEZ1%4OJ*bU);4 zuLkAueeB7qLq36XlKakk7RxGE+u~{bi>&2`cRU5BB~G&gfTpnMfk5aFLhd9$WJ}j( ziUP5I+@I-J;bK&nY6YzX%)l#4XdN~h*I_BP;bD_v6eiYBBSFkxV5yP|v@9mb)!1E@p?uDCj= z4)EFX_eRf!4=!n$kw}aHmkM~F-;mH8a^&wQV)TYIj{P8iH;<#GZ^Z@GO~Wc5h@437 z6J4pWqE!*o`t_B_%E~G(F_F62%O}U0G|(1{^mp%_ z_)*%vY66#h<0toTKHyQ(P@Kd%tVmXO(ZW2ElO#hJRwZVR6QH z0qiGg9r15lQEHn>8n}Z(dTe)9i7SplbQkG|Eh>2zsMSn~Uf?|#2Swkl`A`nt5<5ps z;dZTN@u?$}WbWmCoY0jr3CWkHs0>5nCR{_`O@(9|CiVH7AKYt4PWI;`_s~YfB-)Z% zC43)JuR@34)GE6b>>=K7nQ8q;*Lc^6qcBN}%u3zMWsGV(zB?!P^R~Ij8}2I3^M>z? z1Y$)yo4ty3tn5;IZ>X!t_mJV7k^b#$D7qNAu$i<9+m6hq)En$aC`)kn`EqBh`W`v@ zb5W{b_i$sOZd~{rR`&Ywr>9ya)1wq_hUgE@9UFWoB%x*m{3Mm2ik?fyJ|!XDRSmPm z?kD&DcIs0Qd*5sL@Li^cbI<3@#$&oOHl!X-=coA!9Y$;oqWit>8;+h!p9evq967Ck zn1sIT;}siCfuz0&Qof8!hV;ljY^q8qD)UHEQT{@P2urPt0#SCG`wmZH3zGXKfK+=X0{0EM?Q^8tfY<9QrZ^N^z_jZ zZVSv|X!5;3|AbN9HYnQ-@V&pTormgld2+8-q!R-iZq*w2=MCrW1sLAoK)UI%NYbu?QcuX`ZYpU6k9eol{9l`S;bm0i$z`TaI@L|ev6c(a4s zpt$?!;#CDp5?6majS31959s`H3Axs*EZaT1xn3icvhsLRT#RA`oZ`ik4(||d5RMNx z(D<1d;GskKdhkWjy3_Fidh#j`d+vR0R-S_IE9D*)b{|`(5;o)hnB@8+(0%JHY?B6O zhfbvZp5iZ6ehXv);!HZ-ElNMwlt%$@w1Z7H4DzmLWUU#X_9R6eRuNlS<><77%hmJ4 z8I4kdbHUi)yfW~@WLB3ymyHg@5TMWeyqzQRw&3L-0oRbHuAi# zIVcNVDrL%1p|^4qwd|W)d06^Lr<7KlY+E>n*TSTi_d>O`^wBaHEkOg z!#yJ^D9nYJg7*v8k4HjZe@6OxM;aOU-@pf6RaFtxIPBxsuVf3c<=RQBr$buTvS+Ag6I6e*U zFi|L>P)Aa5Rw6!s$i%+jbMePh{gcJ|=``l?{8X$IbG{gAgu26L$8v#ClASD{1EKK+ z`16$a?|y+v=`|5l?Itc?6L5_bjP1kn=FFh8w#1MJ0`kxmMA>Ax&}!C=p)y;N;+@Kl zr?_;7rd3>ONqx@(eXrCqi-=kt53f&RsGGX@zWu~WpVmUBabLXP6_61ZQ4jHHa{FrZ zWsC*?q`s`8SyC*x-P$hnpxr)kc}Nf`D74M{N~rw$jI@ms)?G4sKlETL#f=Nz^{l!X zfy=*aX1XskA+Kavxj$bj4wsovxyK(Rc{spZ$O z<5sTopp8piuCPNMJ~kL{X3a0T$vS%2U*^83Ko9bBX`BvyRoj8LA~y7;y*H6wOWV+| zN%H=hPXTu%-KOJq-7wktz4I!;QpeiwUW>O8$q&SrUqtHjyI6dlRdz3~FBOm?nqGXC|*ctaSP-sEJ^r-NXkussua}Yi! z$dR;D4aYDa>)SaT@?s$QRF8Xnd&AuDC27!bWyj+$rf_cxPKf`jj$1Z*41o8e3V%mK z$4!JmYK5?VP>KV^m-UvgDeeKKJ=H5VloOEq)i!+F#7i-h&%kbaytx`P*dI-bXUad8 zlE?zk$f}Hj^GEM*uFvoFN)3QxI$0`YB?mYZ$TcJz7zVQO{1KKj6TNK0CHHKwz$-fNfUK{7h?B=eSTbevQ zG%irPLs<<}8(~`p+k1>(L;~}il~1&<13^OX=$i-?qv&Jua=)0`nMc``7EmRW!bfKN-hZcli=Xo%3;jvEausAyGx`M4^5#qUU+sNWR9sz`Z4w9? zJUGEEI0Sch3+^s~KybGtXmEE5cXx;24grF@7H&o1kbBa7yZg)E-CzGN_vtpH9?qz$ zacZB<+Iy|N=3H|fFGlPQb79eVhD6Pilw4(ig1Ft>qKJ==BFl7|r*Md>bH90F;W^

&qcg(mmhr{XNTDy|Pmtf?I74xGVA4JLJGe>|fyy zp4^wY54~@!!J;U+VD?d6B-SOoigK@0$MyzA*JZoxmJa65OU&l=Wv8+zRd4Z50AZm! z3t@+|<1mDyo+}Qq1-G?0nP-I3+5bGQp?-#i#DFD93N{$p2g!yyWvWo zx9QfnSNn8QdmzSHY4&4>J*)T_AnU?KVMMl~+hiOkBqjRG=#(rWjF9^2%%>ut8p9n9GoC9%>=l_udI zeO`^*Jw>RUVAwcrayuoiwPMzM9VRFJVX-bHgLn@KR6Fhze9@#C{vpsd#P_5D=%_)D zxQvM<2di}LeX=C^x%d1IQ-5V7`B=EJ9TvLDNhVIl>6xZ)WK(P>(307yVHFl0}@71a55x0Wf?LC2F~HEZ#hNHvaW z;ioM(dV15N3S-_chdaNS`_|tBe{4DSEcTM?XUW^sYKE(efUH#I&b`K}p*RPlq=%bP z^ipPe^$#fZZ?ID6^{pke3~C_L5Hnq0@uIXcSLifM&0@yXIRRO3RPnPFU8x@Uvk`7pM68{b?GgOsnF4e z-=pEAZ1gXo27RxOCmlu_$QV0G+MrECmL=L!rZzQWacoNi1dynUI#Ud`UF=EcG!#*L>vt1U6Lz?;S6aYm>YU1@WLvXx-SeYxdcAe zZ(66=5F4D`7_bs&rPZNzykbUie^)4s2fo@&Xng3HN+&OV7v*7v?B|46DFpU)U&2R5 zzW$}~-rcx|v<2?Y8}V|{A2+Lds=NJUO8H6>kK?x5IWa0qDLyhI(&?mOHe-{%11lZW z2{dm_1o}iHizaTS21`-e^ws3osJBaxeB`FFvMM$Rv$U|#+R!#N$!R~i=5jdP9V6C$ zSNF-(Z{Mw;bwltwPv409cxTuO#3AjE08~`LNWwMmXoxYI>6~>+kXknp{Ce<9_b|O! zKQ%{P%r-W1Xfp0(fLTQNx1?SDi5dvECV6g{uUr2N-(m{U8LwzLHHTFpak5MON(<&2 zO)2olBhxwm&U57B^6#2gpKkP1OK>RzMn$fDm|N#YV{GL*;yN`aYWP`TDyzMzOnQ*a zKZthJeJiI*t8p@O(BST=OoX9&Ip`={8Y-caxvIvizpTTlxb&8O;GVe6kyzIShr}UW z(T)!6a4+k&i|D+fnSs!UZR6w__kD>qd3Kyk)R!~*ED zjneWgWw|6_a^2kZ$;w9$ONy?l0nefeyH`(wXMVq8 z<2<2`Jd$EUJpmLKB6<2TQ;y{0 zc#Wjixwvh__vk3&2qnFY>Lk1ea)vZ%qYo_F9J;0&Y&vfeWZZ)rWS=6-I{H#3a8FW z=yn`aEGj|&%)ZAy{pm&?^WBke@pM^x@65+f?cA$PK89WJK`d2-U>`a{us68}4;8Z@ zv7*=N@aD`y2P@AMGns6Ty7J>&M$K8Ugq*#vgvZC~yMp(h%R0cbJA;t|t$U1)2r=*P zSoH6nc#|Ga2xs)Yd(Tab2GTefsYbIJAD;4nEW+qVPD7uw)P)K0S5pKVS z37&oaCVRsq^ogyPv}(sK>?*^OMT>6NEoYq3$jroNtoPx;VdqF9jnyP3QC>dzL@I$t zp~@2^h8EqE#(uQ$zkKRXe3MQ+|)8{+$X`~@v_T*=Za5mx7zs%dm!NcM_N7!-MLE7 zQx6p3Vph`1%IoTZakVW#mR@zX<06F9e8z+F+O(s|&Do$mKK?QLxPPOqU_alo)kTos z6dm6OF&*>X8wwMxUr0#USP_O8*n4*OtBnqBcr^E0zP-_geX zF{Dc#^H*zKF$WxBx4c&WK;q0Mi!OxRj*TJ25uYRU5HP+mVKZ0t%`?j=fz3PIC*q?*G7rKG&8!kXILuH++uhaUbp8PDHrpw%peCl zIx(asGJQYaDEC~5ineA^#OmX;dF+;;EG!=MEqQbF5Q*DHL32{Edn^-5}mu0 z`Eu^O)150K!Z)DNOC1m&YV+4-qo)vMv7}|Rf6*ZYf~gFnqGSDH>*OkTC?WxI<2Y4) zO|qDTppDfll};DHcWI&TT+uq!o##QXs*!rH_nEr0QZV^(N1L4A%+aw%{U`oODZdNP zh%+xL+I=kZnupUaubW)aqKj2te1vj6nq6`tV_bP6nl*RV2y=5&yg}26PW=U1Qgr$m z=wX_bIrifTMXh?Pt8FC;m-X`ejQzJ}`a;`@| zWh^`qt-RzN=6U%{(KYNddHYIn`i!5ilnMgrmupHdKImsu&Lr`hxGPV_vdhiB{nupS zSrM|L4nB?3XWh^@25#`Ed4mDxTRVkT)06`3($QYvN3^z}(gw7$*mAvf&N=FenA1Y} z>eE(Y0k2_-U%sQca|nJ2tGg{6kYf+CSMOi!ra?HtdLgN$Y%{)hlfhFm0yS=*O3%)XIbD7 zX%VNhB0}?*`jm#-u0J8^q!l4htm&(Hx8+m}B08|vQ1NL}7hn(fKNR&K(G&hu)Tkb& zUDBw=(pWvIc<|1(Nz-M^dWlgp!ZF~krm5O1MZ_%{LOz<;YFts3Ef(BDljPOvcDlOB z=uHLJItSpxC!RjodaVV$s?Y2uu8-#?C=SOOSLqBD?)vY%&u8XlzgI|6HwFk6rkfNB zhii9ur?f{TDAylONxvn`w)O+s1-h0ZA|h@oREZ@Eze3;Idgax0cD;67qs4RG2GMV* z28fL`3*gN|yN-mDKA0?Gd>_jAT^Dd}h#VViQg#pjFX1MDw8?Y}pte?ad}1xeAc1Q^ z=i}KiiMBdq;{MQ9doS6wj@hsm<8&L@OC4hHmMTAH(THeMdS1N<#K_M;Nq4zg7*|Mw z&iJ*A>$_d?fLo3R;6#IYwNKUzFZy+8D^9z_^fH}*CJ;^Xsoaw|BDuy%y zH>}fxr)^Oxb+^Aaz>mA=i646L1rP4DI*ggo10$P1_{2M=KYrl4`kVB+cTn1+#X=2t zJY7TMrxlx6IsKC*O-Fq){zi=EjKH%RM}@TOFBbslUYqFSmsXvYEjBxcBm&c~~?xmw5|MU;C8p~1Vvn2;}N11`#IX~w90Tjtxgejd{}jCy-2 z&H#Lc05=^Wl7*iG!P*$}^d{}T!@{}b9w72oH17RLSmLViXwE1$^K=^d5f%)Y;aas% zNqPmd$y`c%ewSvao!PibOkZ7Zt-bPS+J|(=`_3o$#^Jz<$}k?C{j}p+@Lo@t#b5(x zaW>w?P*m$_bEML&dk$*{K-jn$x=sspKVcwvvgl#q8hRE7+qb(IO|MmM?HbhMMD=2-{5tZ3@iuIWd@tl zva+#KBwl*!90w!RiVutCxD|oFh2E{u9ajV(7K)jlPSN_H$FDHLgA{p-lU6`Hk_`UF zClkpU<+@8?COl{wZ+bV%uARiZsp(3Ko8~UeSiyiJ(3;ql;H1wo)2~Yco!DU~;e~NG zKOfhpC(OKTb|<6xd=$eaF1k`r7ddZfO_&N^~K?AAZ_q0~ey-_-VR7 zw^_tLSc|-A09C<0s9)fI8FJhSlkUOyW={L0?a<)RNfdXEWEj_wx4Q+-zTNwA2lwJQ zukyHaEGWYz@+aL>YqvH@#g=a&$`9PkHZOBt2waQ7>?7s}pHZbh*eeMc-@UO@a0k16{*jW9mZxMN#CVKPR)WgFu;9R z@ED-lU;##jIAvJ+`}ao(UG(LtAvrfsSk|%f{4!6i`Bo6h)jB>L|C;Z$fXK}cT79m~ zWUG5ZF5}+3R^|+d7H@mCe1~%V#{=e%0Hh4S_Ld%Q#HAZ_#^|A>cgAP<2Jg-i9X#uR zgqF%^`WJNlj&v50AVcSvmB-f8cFj+%Td4H>gyQUlBHrx&N8`?RhjT0TxjsyBadGC! zs76XpC%SgpBl11Gsp@;W{B!$BZ;P~EC65sPaPhxnvP*1N--(UoEd4FL` zetw6E^<{Gli{Uw-b}7?W?_zg#qpsQK-nHxTnb@z+bZ(hwxR`mK;PQm7<4!IEF9iVd zvqHNR`yLR?y=xsd=QZPznY-77w(3@Fyw#5~b+}Fb1&NQ;_3GHI1bWnN-Mho&L4ODr zfGhr-b_|DE2k#QSD8D|~XMxx9U3aws#|25Ew3ABZYK`i|VaqdE9`~skM$o_wpn?^1 z>jc&UB~bs|ts^NI9DL7(0HRv)0)5DU2+ct5e`NbR+O%E~fNBdFF`w>6CYYF$;%9!5 z6#6o2MiH5tizQE}p}4(@L?7IMT8K-AD7`CeeM0Yb8lNvvsK{xQ5lYXW7OV9LOJo!7 z(+tTY~e@hm%t?a{5P_KNj2eX`S~%3d!O*HB7GJG^*oh@m#8c z$o%w;=UDy*Ydh?QWQ6fkfAi_85$EwvEMnB)_twtp?l@PXJ0%(Z1H6UmBY2)VuQ-n2 zO$WpyW3_;wt+5z8Rme6CHpw-P+UTv&@>bF4&f7JO z-CC@i4i88G`&Y`;vbUQQkxrbtG!*Vcz;uN$G#%@kj zRyK6m6Qa;?9ac;~KgY#?(_ph;Q_`4NfA}-T4ExN!bBo8kTcyQ}4%~la=m(`mtOQXL zOmS*mO$L*+Ac!>yIq*w*%ew?jx!7UN-5obBAF;U+p1`v>tb*6SdOf=?n=bIa&KPis za&)QlR%bUG$BqcT{0`KZ-(eSTzUsmP6bwFhTa#B)I(1GW(5;hiXh7S4$Mt$b{bv|1r4f3)XVHx(fJWL@k1oFN z`o#nGW6zeR&p{5ueX1Z!)6`M;^3p&W&tYfA@#!qg_S~Vzb1fUvnR1hGe2k>D=u2?E zzIgcQ2XBSL2I8rtw^BEH$$}ot{(dm*W<#~aV&?01CSwFRfDbtBBYu|-IXbk48@OsP2r;!E?<_VT!t8-Gvr{oV(Pbu(l(i@ z3Z$@!=R2m5L{j74Ury!3Ep-VHnqTQsK)GzcB!owow^w+m!>#aXd+J?-?ZOvl~xuw!Zhx@u{{{&FE3%04F$kjQ=dD?0(0G&oB#s^1UR%gM)cC&DA1J z>4sd2;vfDi2Zo_ zZrOxxbCRLwdtXp-^=??Df+`NtK!<>&FNn2=QhNlTP0cg$4Og>jX1=sLtnJc|7c;c5 zZf(j;-}SYbzg{e@)FKAj!-OfL?Gm-$1|7B=NbR(DWcWB5c0vo%$_^(U@4n()-*l3= zU@R=B@Eu;bmW@AZ{aOoS9?Yxk)QDos(CRX7Zl*GE`LfmKSvtKC{MCET3s#*eSxAYv z?U!H_r!wk2$OS6~0+Cyk^gtMM-*^U*Y9T!M{P}iJ>{l$Jq4!3|Qj6atr?|bPkN}%T z4J>4l8uT5a|bumj}HE)*yPGt`Y(OMj;{3ho$BUVzXbe) z$z9*dY$o>(rMo*h-3KGAX9=+Quf)5?M&*fVU~tdw>f8+1&Jlk*YnSeU4nW7n7Arggs*af>lZa+<_$ zj;s4+57v}NI@m6GfivReg3Fry$?yNfnR|wcq*e_$j2=a%=?!bv}cI0VZtEKB?X13SZ(-P zDn&mhkRgqVXaBZrS*Ut;Rk!Gb1BxZz%iHGIj1EKB@^mtxPRHWWhc){lpo_D@;b<7N zozO4I<8+lW$vH!KPvzpz8U#=1{5stW*6mk!#z z=*xb5b{7^r`wqjV-A5ks?PNps^v91Bbn^Cv5DW^lRh*t1f~sPZYmr5r zSY8=RIN0FL8#cO@8#={H?mgoX#i7_7eg7w3ZlI~enpI!*YVrQp|k!Q~x)Hj&_RUb6sutvlm zuEuJ*|8s?vU*wDc+Bjl&s;C|d82}d%op83v@wpyQ;_vU*81$&LBJZ2eWENfHc95(K zAc|maRzafnYKFIbzcvzrQdWCIYKEQs_7HmaAfzgtPUqy$PVDT0LY_kp=jOo1Ko&}s z@q9tILwNe^%~vpI8_PL7cN;~c?aC&UzzQg$0B8^@rHJlxBJ)W3*aGw)_g(0H1%8Q5 z;yy4s&$XjzsrL|Kd|i)WxyEsssPa+8iRdKwZ(X%B6tnSRpAeNlEO zcl^W-$}=dlbyl3XVtqNqL@m$Tdys5m6Q5TKGn`5A$wfx;%jigGG}I#|R(X!CrN|O>I8`ps2n@ePdz)4@ZEdmkzPd>PA zVXLdu@prCEwv8TUB3==xl)5l#UYBE6!)BS@f~z3hBc(UbfKJ=3bgI|$xR|sF-xV5{ zOPtI=+SZ^c*E{-_Bn|lM7=Vr{oCUjnKAZoMt8`wD`9afBjivl#7HEglycauC))R2^ zK{Q9>dTaOm_jmvDQX_s5opsl5HZthBF_oT z%&XHt%OB6+8Z#og{ekOs8l5uOOL!!7fzz+7Sf8)gh){a)6JjYegLejH5LtPJj2gT>g$v)SC=Cj?ZPT@!a+J3t2&^yCadQ6r zQ4&FplqX}BO_U$18CS$&h4Y4N%ten+hGO|hGdS0Uj<;fBJV~gw+ss2T;0U0Csu+~3 zLzh*60vpT7N7N8u&^Rm38*D}t0?rE^RD-CVV6-IdS_>IK*A{j|thR?#OALt0Od%AxsC_BJ#ixdn zcjt+i1+a%t?Xx>C7I-t(>JH3nTJ8?drZX%=Q`AUG44`Bm3P3_ zI5}UeH*pUQP8CL=^(?!NXk-H=@;0za59`@$w22Zoj4>-kP04oye=3*UQ0~#FT$>6GJbK*L==YR9fj|^| zPRQ!+uNUHR$GCfI+wveh{I+FL}s9-$B8p*5L-M~=>anw{H z*hrOg2X~VSXEk$-P2=#;;7K|L>t40Ty%yiH`~qVEQK6T^grl{{NE{Eg*=8m4$rXq2 zE-6SGtewhNAB4MB?iLbonRL~imo?FeFV0HRVWu+QF^Qr{|KeuV~fyQ!|VI zS+1!`qHjD^CIfT3aX%z=iSWBH%Jpcm6m3paW+9Wj*`ryiPRJ(x52ni>r(nS5zVkgF z3=AX1(PzW%(8-lcocRg^wG>$mV-}iFZN4~wWT;i5_Au+htVg0B zb$ps|fhYI)#J9v5Izgu4(FBk~^Arb@ilS_I0@Hb*qoYP-+0r+0On1c`awLqJi%Fv;eBx75}VFu0Y`nS?9{ z2B(%^?3Wp9wf0#^gPRbn3b#fxwz~6_6hUPgUmO)&v&)82lj?z(ti+tOMg3*i4-j=A zuIwA=ZW*BgX+1?~L!6q7{C6oD$8cmc)${k18c8?e!5df=-KNP@f|7evn8aa$((+Lj z43$;Nj+b%8NM<^|Uyjrwi-VEO3_mr6#!}tN`!bc{05!1chu+nVB9xz_3jx(9l~N7H zZ((7z0bQ?4pX{vw!HqlE(&i)n>Yno59k7g~WRRJK1zf4;>|Z4c{?n49v=2ZK4tY=y z9PHx>oKk!_fMvo4=r1MLMMcDR)ogy>kYBTCI*Uy`So%*P}s-Lk%B$qR zUA$RpFZK`W8@0r0nWo9saqvB+WWZmK(9`o<=A!p)s<&K!f`!lUBRz09P#}zw8@VPX;Y_B^-`HnJ zIns-Rgc))0-Z516y||Ujg}#~cc#Bp%=&n3X>REst7G6xpw&`D01JFbZHp$ztttioH zff0YfH1+*60Q;}Tj1c|Z7n|a`6t7vjZx9b9coBg4Qzc(ZQ(#ja;!ZS&*cUmJT=(IG zeT!*9Wqr@ZC^9Mi1)UsOEi&MH5pT{8nbodlfc-ZQY%((w?bkT!+tH!n!D@O87iMbN z)hwcY{r2?YbOLxV{3)Xb)WD$3$xYz?i9r!R4`5s=GuGjvXeb%SM-<~$|L7};O|#XF zRAyiDJ{2c_38A@!H;+n`oEcVnhL~{!O(OzwiDf3nS|pK6`vw$lq=i|M5h?t^fOx{-M72zqkH}iTZy#AtA4H z6lU6T3dT~^Ar#vie-}9YTM!kmXr#H{+B`=tj3#Y>@b^LKzke!10eoBN{U@!)*@^Vg zzn6pjS3j%FhJErGvH4~LQ%Xz)adK~0pd53=Kufz literal 0 HcmV?d00001 diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index 83565eb872..d907ab8669 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -1,4 +1,4 @@ -.. _getting_started: +.. _`getting started`: Getting Started =============== @@ -21,27 +21,60 @@ See this paper for more details: - PythonRobotics: a Python code collection of robotics algorithms: https://arxiv.org/abs/1808.10703 +.. _`Requirements`: Requirements ------------- -- Python 3.9.x -- numpy -- scipy -- matplotlib -- pandas +- `Python 3.9.x`_ +- `NumPy`_ +- `SciPy`_ +- `Matplotlib`_ +- `pandas`_ - `cvxpy`_ -.. _cvxpy: http://www.cvxpy.org/en/latest/ +For development: + +- pytest (for unit tests) +- pytest-xdist (for parallel unit tests) +- mypy (for type check) +- sphinx (for document generation) +- pycodestyle (for code style check) + +.. _`Python 3.9.x`: https://www.python.org/ +.. _`NumPy`: https://numpy.org/ +.. _`SciPy`: https://scipy.org/ +.. _`Matplotlib`: https://matplotlib.org/ +.. _`pandas`: https://pandas.pydata.org/ +.. _`cvxpy`: https://www.cvxpy.org/ How to use ---------- -1. Install the required libraries. You can use environment.yml with - conda command. +1. Clone this repo and go into dir. + +.. code-block:: + + >$ git clone https://github.com/AtsushiSakai/PythonRobotics.git + + >$ cd PythonRobotics + + +2. Install the required libraries. + +using conda : + +.. code-block:: + + >$ conda env create -f environment.yml + +using pip : + +.. code-block:: + + >$ pip install -r requirements.txt -2. Clone this repo. 3. Execute python script in each directory. diff --git a/docs/how_to_contribute_main.rst b/docs/how_to_contribute_main.rst new file mode 100644 index 0000000000..e00078541a --- /dev/null +++ b/docs/how_to_contribute_main.rst @@ -0,0 +1,129 @@ +How to contribute +================= + +This document describes how to contribute this project. + +Adding a new algorithm example +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +This is a step by step manual to add a new algorithm example. + +Step 1: Choose an algorithm to implement +----------------------------------------- + +Before choosing an algorithm, please check the :ref:`getting started` doc to +understand this project's philosophy and setup your development environment. + +If an algorithm is widely used and successful, let's create an issue to +propose it for our community. + +If some people agree by thumbs up or posting positive comments, let go to next step. + +It is OK to just create an issue to propose adding an algorithm, someone might implement it. + +In that case, please share any papers or documentations to implement it. + + +Step 2: Implement the algorithm with matplotlib based animation +---------------------------------------------------------------- + +When you implement an algorithm, please keep the following items in mind. + +1. Use only Python. Other language code is not acceptable. + +2. This project only accept codes for python 3.9 or higher. + +3. Use matplotlib based animation to show how the algorithm works. + +4. Only use current :ref:`Requirements` libraries, not adding new dependencies. + +5. Keep simple your code. The main goal is to make it easy for users to understand the algorithm, not for practical usage. + + +Step 3: Add a unittest +---------------------- +If you add a new algorithm sample code, please add a unit test file under `tests dir`_. + +This sample test code might help you : `test_a_star.py`_. + +At the least, try to run the example code without animation in the unit test. + + +.. _`how to write doc`: + +Step 4: Write a document about the algorithm +---------------------------------------------- +Please add a document to describe the algorithm details, mathematical backgrounds and show graphs and animation gif. + +This project is using `Sphinx`_ as a document builder, all documentations are written by `reStructuredText`_. + +You can add a new rst file under the subdirectory in `doc modules dir`_ and the top rst file can include it. + +Please check other documents for details. + +You can build the doc locally based on `doc README`_. + + +.. _`submit a pull request`: + +Step 5: Submit a pull request and fix codes based on review +------------------------------------------------------------ + +Let's submit a pull request when your code, test, and doc are ready. + +At first, please fix all CI errors before code review. + +You can check your PR doc from the CI panel. + +After the "ci/circleci: build_doc" CI is succeeded, +you can access you PR doc with clicking the [Details] of the "ci/circleci: build_doc artifact" CI. + +.. image:: /_static/img/doc_ci.png + +After that, I will start the review. + +Note that this is my hobby project; I appreciate your patience during the review process. + + +Reporting and fixing a defect +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Reporting and fixing a defect is also great contribution. + +When you report an issue, please provide these information: + +- A clear and concise description of what the bug is. +- A clear and concise description of what you expected to happen. +- Screenshots to help explain your problem if applicable. +- OS version +- Python version +- Each library versions + +If you want to fix any bug, you can find reported issues in `bug labeled issues`_. + +If you fix a bug of existing codes, please add a test function +in the test code to show the issue was solved. + +This doc `submit a pull request`_ can be helpful to submit a pull request. + + +Adding missed documentations for existing examples +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Adding the missed documentations for existing examples is also great contribution. + +If you check the `Python Robotics Docs`_, you can notice that some of the examples +only have a simulation gif or short overview descriptions, +but no detailed algorithm or mathematical description. + +This doc `how to write doc`_ can be helpful to write documents. + +.. _`Python Robotics Docs`: https://pythonrobotics.readthedocs.io/en/latest/ +.. _`bug labeled issues`: https://github.com/AtsushiSakai/PythonRobotics/issues?q=is%3Aissue+is%3Aopen+label%3Abug +.. _`tests dir`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/tests +.. _`test_a_star.py`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/tests/test_a_star.py +.. _`Sphinx`: https://www.sphinx-doc.org/ +.. _`reStructuredText`: https://www.sphinx-doc.org/en/master/usage/restructuredtext/basics.html +.. _`doc modules dir`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/docs/modules +.. _`doc README`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/docs/README.md + diff --git a/docs/index_main.rst b/docs/index_main.rst index 978c216f11..7cdbddc71f 100644 --- a/docs/index_main.rst +++ b/docs/index_main.rst @@ -43,6 +43,7 @@ See this paper for more details: modules/arm_navigation/arm_navigation modules/aerial_navigation/aerial_navigation modules/appendix/appendix + how_to_contribute Indices and tables diff --git a/docs/modules/introduction_main.rst b/docs/modules/introduction_main.rst index e9fce33443..60cb085a29 100644 --- a/docs/modules/introduction_main.rst +++ b/docs/modules/introduction_main.rst @@ -2,5 +2,4 @@ Introduction ============ -Ref ---- +TBD \ No newline at end of file From 9d759d13c6481d001da72470a2eab67a740490f1 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 26 Nov 2021 21:46:14 +0900 Subject: [PATCH 422/940] update docs (#578) * update docs * update docs --- .github/ISSUE_TEMPLATE/bug_report.md | 3 ++- .github/pull_request_template.md | 13 +++++++------ README.md | 12 +++++++----- docs/how_to_contribute_main.rst | 28 ++++++++++++++++++++++++++++ 4 files changed, 44 insertions(+), 12 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md index a643b49571..4f13bd074f 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -17,5 +17,6 @@ A clear and concise description of what you expected to happen. If applicable, add screenshots to help explain your problem. **Desktop (please complete the following information):** - - Python version (This repo only supports Python 3.7.x or higher). + - Python version (This repo only supports Python 3.9.x or higher). - Each library version + - OS version diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index fb412d571c..c541063156 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -1,11 +1,7 @@ + +#### CheckList +-[] Did you add an unittest for your new example or defect fix? +-[] Did you add documents for your new example? +-[] All CIs are green? (You can check it after submitting) diff --git a/README.md b/README.md index 195eb1bd4f..f297b6fc12 100644 --- a/README.md +++ b/README.md @@ -603,11 +603,13 @@ If this project helps your robotics project, please let me know with creating an Your robot's video, which is using PythonRobotics, is very welcome!! -This is a list of other user's comment and references:[users\_comments](https://github.com/AtsushiSakai/PythonRobotics/blob/master/users_comments.md) +This is a list of user's comment and references:[users\_comments](https://github.com/AtsushiSakai/PythonRobotics/blob/master/users_comments.md) # Contribution -Any contribution is welcome!! +Any contribution is welcome!! + +Please check this document:[How to contribute](https://pythonrobotics.readthedocs.io/en/latest/how_to_contribute.html#) # Citing @@ -615,7 +617,7 @@ If you use this project's code for your academic work, we encourage you to cite If you use this project's code in industry, we'd love to hear from you as well; feel free to reach out to the developers directly. -# Support +# Supporting this project If you or your company would like to support this project, please consider: @@ -627,9 +629,9 @@ If you or your company would like to support this project, please consider: If you would like to support us in some other way, please contact with creating an issue. -# Sponsors +## Sponsors -## [JetBrains](https://www.jetbrains.com/) +### [JetBrains](https://www.jetbrains.com/) They are providing a free license of their IDEs for this OSS development. diff --git a/docs/how_to_contribute_main.rst b/docs/how_to_contribute_main.rst index e00078541a..c761fd9928 100644 --- a/docs/how_to_contribute_main.rst +++ b/docs/how_to_contribute_main.rst @@ -48,6 +48,8 @@ This sample test code might help you : `test_a_star.py`_. At the least, try to run the example code without animation in the unit test. +If you want to run the test suites locally, you can use the `runtests.sh` script by just executing it. + .. _`how to write doc`: @@ -118,6 +120,27 @@ but no detailed algorithm or mathematical description. This doc `how to write doc`_ can be helpful to write documents. +Supporting this project +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Supporting this project financially is also a great contribution!!. + +If you or your company would like to support this project, please consider: + +- `Sponsor @AtsushiSakai on GitHub Sponsors`_ + +- `Become a backer or sponsor on Patreon`_ + +- `One-time donation via PayPal`_ + +If you would like to support us in some other way, please contact with creating an issue. + +Sponsors +--------- + +1. `JetBrains`_ : They are providing a free license of their IDEs for this OSS development. + + .. _`Python Robotics Docs`: https://pythonrobotics.readthedocs.io/en/latest/ .. _`bug labeled issues`: https://github.com/AtsushiSakai/PythonRobotics/issues?q=is%3Aissue+is%3Aopen+label%3Abug .. _`tests dir`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/tests @@ -126,4 +149,9 @@ This doc `how to write doc`_ can be helpful to write documents. .. _`reStructuredText`: https://www.sphinx-doc.org/en/master/usage/restructuredtext/basics.html .. _`doc modules dir`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/docs/modules .. _`doc README`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/docs/README.md +.. _`JetBrains`: https://www.jetbrains.com/ +.. _`Sponsor @AtsushiSakai on GitHub Sponsors`: https://github.com/sponsors/AtsushiSakai +.. _`Become a backer or sponsor on Patreon`: https://www.patreon.com/myenigma +.. _`One-time donation via PayPal`: https://www.paypal.me/myenigmapay/ + From eb1fec748f9f5464e036b9d555b624a4d9c01c9f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 26 Nov 2021 23:14:23 +0900 Subject: [PATCH 423/940] Clean up Path planning docs (#579) * update docs * update docs --- .../quintic_polynomials_planner.ipynb | 143 ------------------ PathPlanning/RRTStar/Figure_1.png | Bin 119836 -> 0 bytes PathPlanning/RRTStar/rrt_star.ipynb | 74 --------- .../path_planning/path_planning_main.rst | 35 +---- .../quintic_polynomials_planner.rst | 106 +++++++++++++ docs/modules/path_planning/rrt_star.rst | 25 ++- 6 files changed, 120 insertions(+), 263 deletions(-) delete mode 100644 PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb delete mode 100644 PathPlanning/RRTStar/Figure_1.png delete mode 100644 PathPlanning/RRTStar/rrt_star.ipynb create mode 100644 docs/modules/path_planning/quintic_polynomials_planner.rst diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb deleted file mode 100644 index f094ae2c15..0000000000 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.ipynb +++ /dev/null @@ -1,143 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "# Quintic polynomials planner" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Quintic polynomials for one dimensional robot motion\n", - "\n", - "We assume a one-dimensional robot motion $x(t)$ at time $t$ is formulated as a quintic polynomials based on time as follows:\n", - "\n", - "$x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5$ --(1)\n", - "\n", - "$a_0, a_1. a_2, a_3, a_4, a_5$ are parameters of the quintic polynomial.\n", - "\n", - "It is assumed that terminal states (start and end) are known as boundary conditions.\n", - "\n", - "Start position, velocity, and acceleration are $x_s, v_s, a_s$ respectively.\n", - "\n", - "End position, velocity, and acceleration are $x_e, v_e, a_e$ respectively.\n", - "\n", - "So, when time is 0.\n", - "\n", - "$x(0) = a_0 = x_s$ -- (2)\n", - "\n", - "Then, differentiating the equation (1) with t, \n", - "\n", - "$x'(t) = a_1+2a_2t+3a_3t^2+4a_4t^3+5a_5t^4$ -- (3)\n", - "\n", - "So, when time is 0,\n", - "\n", - "$x'(0) = a_1 = v_s$ -- (4)\n", - "\n", - "Then, differentiating the equation (3) with t again, \n", - "\n", - "$x''(t) = 2a_2+6a_3t+12a_4t^2$ -- (5)\n", - "\n", - "So, when time is 0,\n", - "\n", - "$x''(0) = 2a_2 = a_s$ -- (6)\n", - "\n", - "so, we can calculate $a_0$, $a_1$, $a_2$ with eq. (2), (4), (6) and boundary conditions.\n", - "\n", - "$a_3, a_4, a_5$ are still unknown in eq(1).\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We assume that the end time for a maneuver is $T$, we can get these equations from eq (1), (3), (5):\n", - "\n", - "$x(T)=a_0+a_1T+a_2T^2+a_3T^3+a_4T^4+a_5T^5=x_e$ -- (7)\n", - "\n", - "$x'(T)=a_1+2a_2T+3a_3T^2+4a_4T^3+5a_5T^4=v_e$ -- (8)\n", - "\n", - "$x''(T)=2a_2+6a_3T+12a_4T^2+20a_5T^3=a_e$ -- (9)\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "From eq (7), (8), (9), we can calculate $a_3, a_4, a_5$ to solve the linear equations.\n", - "\n", - "$Ax=b$\n", - "\n", - "$\\begin{bmatrix} T^3 & T^4 & T^5 \\\\ 3T^2 & 4T^3 & 5T^4 \\\\ 6T & 12T^2 & 20T^3 \\end{bmatrix}\n", - "\\begin{bmatrix} a_3\\\\ a_4\\\\ a_5\\end{bmatrix}=\\begin{bmatrix} x_e-x_s-v_sT-0.5a_sT^2\\\\ v_e-v_s-a_sT\\\\ a_e-a_s\\end{bmatrix}$\n", - "\n", - "We can get all unknown parameters now" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Quintic polynomials for two dimensional robot motion (x-y)\n", - "\n", - "If you use two quintic polynomials along x axis and y axis, you can plan for two dimensional robot motion in x-y plane.\n", - "\n", - "$x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5$ --(10)\n", - "\n", - "$y(t) = b_0+b_1t+b_2t^2+b_3t^3+b_4t^4+b_5t^5$ --(11)\n", - "\n", - "It is assumed that terminal states (start and end) are known as boundary conditions.\n", - "\n", - "Start position, orientation, velocity, and acceleration are $x_s, y_s, \\theta_s, v_s, a_s$ respectively.\n", - "\n", - "End position, orientation, velocity, and acceleration are $x_e, y_e. \\theta_e, v_e, a_e$ respectively.\n", - "\n", - "Each velocity and acceleration boundary condition can be calculated with each orientation.\n", - "\n", - "$v_{xs}=v_scos(\\theta_s), v_{ys}=v_ssin(\\theta_s)$\n", - "\n", - "$v_{xe}=v_ecos(\\theta_e), v_{ye}=v_esin(\\theta_e)$\n" - ] - }, - { - "cell_type": "code", - "execution_count": null, - "metadata": {}, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.7.5" - }, - "pycharm": { - "stem_cell": { - "cell_type": "raw", - "metadata": { - "collapsed": false - }, - "source": [] - } - } - }, - "nbformat": 4, - "nbformat_minor": 1 -} diff --git a/PathPlanning/RRTStar/Figure_1.png b/PathPlanning/RRTStar/Figure_1.png deleted file mode 100644 index 72a4ebadf94b2bb803be5eb5513284b63c6c59a6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 119836 zcmeFZg;UjG*9CfLq?K+(2}MGXPC-PaySuwPl~Phcq+7bXQ@WAv?yf@|4(C3+@Au93 zAKaNcb9Edfgx}fEe)e8_t+o9wFDr?QMS%r@KyW{Oe6I+BAp1igNGq7=;3HgP3mf1K zs*~6!WlZqP8`Jn3c>j_8M-3+k1mED{4^o~;t_AoYpRuvzvjV3B<<0+1}dD z+1kSJsjG>jlZBn_Qw~<}`}I?EXJ>nUHn#u!0#-XmGq&Kg32X@DDdf}pcgpU`2a6uw z%9qWE(`oD3tH2k5FAf?pnUXMx-zgJlXt(K9RoAHO!(VC^&uMAJ*32~+*j2N-6e<_{ zAEald_sY%?VrulYu*D1-b2$0>;cT;uGxSNTi*cke;?o57C39}KZ4AP^TasiIh|rz| z5{O~0@?50&K*TV?J8O5*5T^fp%*2H4Zze75QQ8 z4>>W0baQj_f|1b;YT%6Z$lvU#pdgk1!GX1*p&|c``7m|TP#w;hO~M6d&I0 zU#-c7$!1sUY}>E4XW`D>^;1(*(b3VFK9R8J;NOedKymT$8R_UUW1_Ye%4e+u0|N;j zKVBszrSs!e;~P2Z(HmA7u7vFlI$drbY2DABu>2=Ad;VWf%>-LY2#?*;;N`TQ90(78 zO62B1Tq zQ*xgZK3t$3?e1Y=e!JA-w+M`Ks)k5OJ$pUzDO$`YoX()KeRDiL^NP8s`*y ze&EZ$t_@#Zt`_p8gdpy=MU383++3FW9bR&Wk+N;gnx)yCUgyXpVLp1qmlWdmZm!P3 z$c(nbY`SzMT8zy&BLlRnBTuYNK517=jXE|TFWpHe*gX*heq()o3`Mg%yoK9+MukI=rq=WC#h~N^tn1} zf!W@J___R3cmxjd)xUx9eCr}((Lu!ijt2Woll+R|+E`hy6IGJ0CFPSW{$o-#cYbF-r^cxfHIPB5l zP~p5DeKBuDU>Pb&q~^?Q$n)V$+eV^f@N5nY6BZrb7BYLX6@?X_m}SLF$2qM=i-v`% z9DaX-5P^pmJh{SJ2@NNPNXw>3Yk$;cq>bR6|L?7#alXV_k%Wn?Wf!wK6s?iLLa*K& zi=4Z=9XIOQwF>(1LC%8*1=K>A_q7Y8Pz=22HH{=8@ZypE>b6AFOpS5Q{!kmjLVxWcRu| zcCWB2$Mg$-xp|F5mIJ04q_#g3pS)w>xDX|n^razg#9cG%YnltqiNDw$Nd_fgR+RYYu<~>!{F*kfT*JqZB`_L+; zePfc_wQIP%-^kyNSTtm9CFG74Vup6Ie^81PKjoIFHeWc@>Vz?J`HDTXiizZ}XNyg2HdIYpVgm%qNeL78S$6WsRMyMkl=o8wLM>87e7K?- zI?7yRV#4`ODW>SI*f?J>*-DOLMqrF{cFQF({Q^n;8+TLHCB0|szofOfwP9f*P#auT zC6Ussk@473-7oJfrMOgvR3JE!=Ry!!*_6R)jp1FrCY^g5kKnh6TSAaiRbmQ6sn>gt z&MeP%ZXD%0^f0&Uheix+YFwcikDd(&RPtlZ^f0Vs5f48~kLig1h8ccx>mqoGIM3m` zGVf9VhuWRT!{M|dU8*PNtn&oY=+EF4Gg3Jm#(C9WqgKZ3dU$+UY;~TLTZfuQO9q9y%@3pf0TR$Sc zg48Iz+H^uITeyPkIKcJTZV|+j#1@4?gEWHk`_qIvN#I8&-~KIK!VPsQY@cdNbG&~q zVT2Y3ZTjV>eT9D*sh2x`y0O8SkFXK)@@)xO6$);&v2swq)<<9r-Wrn#-Tw;+8X&FM znxS|UAm*%K6M-xYKZPboVWsmURqfxlE=eQKOuFMB;m2I5x{sTie1*oUKS7$>^0Qhe z8s9k_F@<)pP2GJx=(hF@ywIQhYJ!^dRY=&)d1Q?0Zt@+4-+XV!Pi(F5gF>5vO}Njo z(_(As^VMwBBMpbBz<19Y;%h!2!TRH{^eeLx)>V3tj$shZ|JGE|##@@2j(#I1Nwpm*_aJn+;yR{Q2_Gme3e$t-1c# zz@xvTbsL`4S=LE1l3$~IURvc>AJksmGxeE_Xbm|RO%y-Nzr8kJ-#Z^-s%B#3G=n*c z_T$Oey$fb?3@^`Y(l`7F#==+F_No^h$Q^SFCEbcyT%=Nv3$`Z^Hv7|z)Awi+8R_;# zYwBjSvbC2gQ)+YRQC?n)0~-_2<3ycZXMWq}Yt>L17CPAUto9fTt2T!&mIB@E-izT8 z8@>H;s24qsD~hAjl#oZ_`N;T4HIH`!rsm=KB6D7x){1pl?nCjZ5rGfP4OY)kaR+ze zo_h50ja8Eiz##AEo%yK)j4&#j^##a@$-_UAjm?Hk92%>cRIZ$(fiC8z<4wxxV#bZ3 znzkeC-FTt}y2$;>BCWd%tT5ijw03)ERKX^HtGVjRo$XL4GaxfTz?hW>zcIlAp5q~; zQN(*iB#{AXaDIJN*KtKKN8~SR1FL&gTQW}++U08pGujf~FwhTllKg%4PV8?e>QO>j*?bvyzD;|N<35d$`+&G*d*rXvwo(^^B!7#P>VjK?z6CdTG4uO69J{+SHJEW$e_n7oa zPg6#&YWs;YC?a%j{CbK0)mZ6qNTV6N*Uu0bkm!yWrZ;f});OkOXMx*?f-ooiW+?^W-T|!XF z1HR!#ngBS3-i4Pbr%Ve_)%Qn{&lq@vchb!d_X(6fCehxhUABg1;ZtXq)%*yV78dV)^*Epe6Md(H1R+#nIO}=o_h&-;b8L2KLHDZ> zKTr1}@FMzqnCW?4qnG_)Ua9kURG@hS_+tC+Bd%9TjBsNFGBg`M9X~*H0uoR4>tM14 zKb9u*zwJ2lmadKO3GXP`%$BR3nV*c0lF+BsPvM^^)+epLABiLDlcqxlK$Nw8oVhB6 z6T0I6yg6vH+rAO5Vm&MsxsT1ph%=m^^zb`^EtDVN)gEglvJg!W%gd{^xz#UM*Ox-X zMZ@HGZs#vgd)WMvMYL})e&@1n1CXa+k&il>_+5sd5S|HBSW=gjFp>yk=k>ex&Vi=P z75`1oWSUU7s>0ItQfUYc4y_RhXVwxX(#IS{PPrA}=KWpf&;B){9hD53eJ>^MW8+`h z=3-qfi`Aq9JM#*j3~@?@Rm{xVSHD~R-hF&ryQZU4(E3N;-70+icnYNab zY~&p)!m_zLFO7Z^@1%2<6`k|ahTERxb|-%ASt6Y{)Hc>O7uL4%r1*(~G&aKMRA$hj zo{$iH`1~FVy*Z;2KUan_%5H;45038Ns(nfN5d53!8_)(mab+uJm1Z=RFYLFI%Rm`I z_rqS6ut9fuop&%fgT^+@|LG3o%v71A8-6v~Azlhw*wcPR$z07&Molz?D{i;4Wx(T> zz;13)Q?+!kw_3|HR8r!+^9}p^bJiD;J1gdN$aI+8=t>%jpN=P%=2{g%t!3~cyp*|A z)+)%aP`cAh$7jSc-gz4=EQoDC$*5YHND- z?`}Wp1;iBz#SlGxdN;p%O3{$jA<6Ou7YDIDtJH+Km9@)KgVWHQwMi#}FG;S@SIOmF zDSd)Utc&GnPjBNj$GVhnFXBsHI@8p0O=_l)#9%TXVN73OCes1i>wb#kiGtVlPRWUoq!A4*$Wv>7=qIQ;EW*Da4;QTRih5}lhKHW=<$Bcp z0qoiz=(9koRf7bzVi`b!NEi*6PEYwxb4}jdQDo%EXMWAZ#K&RmBoj-2Ly)!fO*gkE zgV)^kt&v5|sJ>PDl%^B_mKDJjzXb|xZ{)26gLq@wJC8aR=UQ?vQaeUiZ^$1RJhB}L z!wj!mvGWaV+|dUO-81H}9C@Z)p>0VOGWk1o;+yhUoOim1TE!5CKzezj;%6M}(Ndne z|F*d2Wv#QoJvP>Vp>|QSpk`kxPlC868cJq zt}IqhD*G<~!o_U+Id~Eh8l73e8Fw>8WapK9vvX>t7krxRQd?@|++iNd^e?q^e3vYN zH~Q!I=Qr?Q%P7OxH}}!-BH^0EW5?EY{l0gfDL>D9>m>aRF79)ZVD2S*uc-dyp$B3} z5*lJcQo)F}YzdN?z5!`T!i8A1fsJnc*hVSK?jg z{|`|T#@5n%wAlFa)hol<3X{Q<{U-ByYwlFvTZ^e84RKXflAk|+YP(FT-0jNw(Y@?z zjE3ECzp%yBP|+~{WyYR8LUibmA}eWW{7SMv>W5m)vcrkS+7)3W@RFA1u>+F~@yMx8QZ0$tnd}w@q-{8_(vvvPcClBAU zJ-DyL5yZOGaoMwCsxBlNlNu~7W^JPWZ`zCq!f_)vrykcvlO^`n@-0^!c5>HRW`45! zSD-d!$~-w`nMghKRv@vu&2z2uQE6m33wjDtz_7pWF^)`V=IDX>)U8T=1+%MV5f><^ zbBm=UYud<(6w341j-a#bxOiG~Q(8?GjlF7UVdqKkFh3M;ii6UuBZzuJ$v zBrj)39xRh+fuw?-!ccyGNS|Ll>=_ z9qj%29MBwIb*J5wi!IZmqiv}|UhZ27W@LbaQc+R48$sORSDKBOPM7GUICt7mQVGNZ zLc(2}u+B}{js@aMQjJVTL$GAgGnz_T+tQmGBHRV0jiMfQZeyFLy=0yJT523GUH*|D z3cP*#3rx}RzxcnKmAIq(hX!N05+4}?aKpW6ZK&5LY*}1=c*HzP@U2fj6J(%Hd95Z| zk$I7RUnD)`J^F`#JPmBzjS&D7fif~fRpZJWV-}!OF7P)s>vB79d=WGm%r`*<6a=5& zi=u)#1dt0)NGT-6%#lH>d?EQ_T%dsG<>QwCJi7Gn%v7ztwY|9`;dsR{x_==kbYqcP zzm|Xv-TL61Jcn8&9`aSp#3*~JI;Z)2y3a03o($@uEMb`zTG<~s+!94Jnr;11$PVQY zqfOi-gjd%kSycS#G+tc|ob>UcVr_HcQ2d(!a!ynCJ6&Vr7nD4<&Rz$A{WDvrbJ*D2 z{F#{ODU3J9Sc39SHjZLdaA_FFf3J#S^$V#fL_4iMm9f?Li9e`59XZJ|@fQrgS=6^C z&Fdq-;eOvtM4GlA^0#vTZKgmJL|D!EKuJ)e3Cu*-1~p4~mCr1y{Vba+1}s8tk29km zpXMhGt|)q) z8%>4~s9G1WsJ1?0?oOZ?ae>`15XoB$h_DM485vx_l;-7OJDqd@5bK2WyEYkH zzFA8s3F#z)+U`W>$Zdh^jJ0IfOQvx|EyS<9XY51>Fp$#%SO&*y22 zce8x;uxf6t#oPYagaH6J<<-?bzOzA+xRm&nFpy_nbTT8o_njhhn7dh4F6svjP9)`E z-5&>>NNVZjofge+p?IMTg6vIyhjc+(OR0|R@BR!ja4wzX(oJQ(uje%jt(~>2s;G{n z#O*_PL7BvnLDwzxjhOi{!=1bL4x<%*TU*56fMpMj@U$ED>I~|1*;$a-?k^tR%!1P@ z{44!41lh@dq&|7Xv=Ui_w(#MBY51ho<0gOb6k0xV2xGJMKmz!fVMW8boM2? z*u#5zUe8oi5d=?>2q0ly9fWd%?KZWGAKt%zUpP{!S*%{1`--!=dU#7PX=qDjxtw!M zq(TJ3H_11_Gu0?_l0dX|P#dq6;x!ey-g8HLb8up&o#_5jDJF%uq6Vrnxk5!wX^JJV zjUY+&PP-ENZtxxF8~F;<9Y9Z~-@^|h3bZ}*x-RkWmkEDpPSD@25+8q z(F6GPl@aFS;@gxEZDJtqA(AD5WB+Gm8r{!N1+CQ>H>w)SjEhOu=~HcY$PLn2)fZ@eMY9vQdes`M~nF zK{m4}SmJWuQmR_3O&LZyrD;{oa8;E28_qocG=*iufHnhAy*D{p)tRkPL$jsq-!t-rs& zYOTFl=n5k}Kd2n3arYk2kpap^a-leCvJAnqTLKCy+@{(!A;kbWE+x__0X9WRtf(^6 zA&S~V-60?1B*S&mzSgIMJ3jfXb)$S~i|x-bX4QACSw)&>7bd4diy?2P-q!F2JAq3~ z^V#nkVDALSwjVLPml>t;d$TQpH%Ub&PYVtUm71UCv&Xm5WcjI$qE&Oag7EA6ANJzB zBq2fkUeuRRPYQf)LkD$0^39xT=0|q<@^Cs_flq9482ia20^fXPHzG3#W*5WF z2qf2T;SM%v6aA9yKiDnJLCL{4WgpIwG=oG8mOP5U7#M~mxbc%aYQESZC zPe#r2BKQ6{+#ry$qZ*-f=~nkf8`j`vZzqOhhG-a@8nJNux8$KZpX`JH$fewRk^}jY zMXk$ybp>0QOYO0VpbFaEn?uRy&}5#;MkiO4GES>pR~-R$-@R?af!{32m{8lNDqG*B zA&ybo6*=waT#j1RoSpO(Pj2=KOZ}C$HB1UK^I9;4Jh84wDoha+!msZL{Eg`oSQu+~ z-J)@=u(VpyOJ6yu)`bM(7;L+dPOTwrpEu8suFNN=E&kNQ5CzKF-OYL5@bFfWU5iEK zEyl@4jNDo8^C)w_(&A!zdio$BF-6bJ%sBbf;V@Homt^X^z>(A6`jIfVE?yXN=Dano zJjYz`+Ffm{^6kbiRW7Fa`_-{~+AqvwNwyN*#>7(Q)|_R3U+FaVl>bUH7pjtqriX)H zy?5dkq7pdGJiUkOD{9@@7@;W-EkBD#@H4n=xOXP|dNU1n%$_MUg?~M+;8)~++qqeO zSiFp=zIVkve42g}+tWDgsDJ=qc>Pq`%JSgxzkur>?$LD7JLFSJg?JKx=&_pk>GUF` zDExJ3SlG+gum7Z{x7}11|M2z_Mh`%W>3eTzNZ0InN%!*Q_w>|vFYx8IqNP}$F)(x= zl6~Hjno+45xM>`{G1Gb;MNH)Qnr}nhv8o6CJ+8i3>m!`wH&jBNc(K%m;#24a#kmZ_ z*rNg%wt%Gp{V!-r468VZ1zP%-kFHtoSEc5RNKWhde*FDK)SjHVXx<27*sR~Qvif#O zNWtrCkRI!XdFnX=G5px=Y~k0ox#L@f*_nz8b&Gswt!^2(S9W$ZkPh&uCT92ZDyP4Y zO03u&U2lbB(0X{4EPk)u&S%2HHxrhQs1E+Jj_wHL1(wtp&0n8YJ`pQqC@4?!E}si2 zda*kto>M?o;abKfregvbwXQnMvdqCT33mVfdEI3y|Zt<|6cMyPS!Bkkl7vEKDI30urxpSavE9i znzKgs-CS3LsPh^;JjgKs))jp^_$!9>6@-PJ>ID4 zsWuk9g^sb$+aZ4OFT=qQNr&>>A)XrNQ0QXf+eGiuMdV)b&^W0jmQ8JxjDf+kLe=86 z@rbkvn|W@V2I6MjsCNCfReSwfuaeg^0?di?%(h_B4KujvRyx()za-yMu{b zVHA=Cv`DT7_V`?K>D`p^PL54+_ z`OWK}_hWE!&@PbPpj4H@dM@0c?E)dPe#a$)>U|x=*wrsZ?vEP~>i_|m8{yjkqDMH!eL)KSyc=|H0(!(kBLC&bOXPm8`4L{;)=(_R>zA^^rx|Wp-3?VkH zfSjseaKdfQ^0bN~$ITVyj`)x@jhM0w66z)DJc?eVdL`7klbW^2U@ffbf@80{FV}i> z#I}gvmi;NtkRze&t=5djM$t+_Qp(UY&}g1NO}~7{02ngsJ||TyJ1XCGv@2o0wBtqW z!vz8HT3r9j%S&TZQ%k>*;b8_AmWcRxG9cpD?dBxSRGQ&~v+1y{Rnk7NJ`4Z;-QpZ0 zkF%Ql32z&LsG|E5G#4~baO=@Tt3M4-n^aHaV>K<7ROWmE?8Y5zr4^~pDDWIbu#zK2 z3*l9$g>gul+u9qjPJ^0E+P*JRpGqrt_wmP@Z*sPG?~}0irMDsm1_ssx@P${vc&UH9 z)C?iRL9b2Uw&$%9o!;`8J!C;%`%cKHUSmz3=68f+l_eRq6-;Tn0yK3xE-qp)P`2*) zUW6U>u#hey^A;up(!4%b+NG( z)zav@G~2Q+Lc6`I22)xbIx8@i*DzzWkf1l>)jK7g{%+t zHnkSx3^~#Xj!Ti_q!)fuF0tHP*t`f@HrcxP zFhbU?`!`o8Wn6yDBfhZLl$G2KLB?{=Da56p%^Yw?@gM{8?9S*)wv)7D&3T0Dw8bY2L*lpxCF4zXk;r&&_+aJ@C69f$ zr;tl5o$(T#bb@6Se$}Ap|MY?==lYQ^TQzYzHaA1+1po5E!@}>0MV^4e52~nyNIfQSw8ugFI#xw_yDz8{~B4^ld!h9 zE&@!ZRmTX|e|8?XjB+Rs)Wx)~H%pL95SWE4kDx9%QFdM}MNYJX=&@(9nMu3Y1c>l!f#LS&PO=??!9ZD?pPZ3zgJzX2$gHO3tX7d{(Yb+ zmOpzQI95XIy@K;=6=@X&xK>4SkehQqs?-dAdbx1lb@(Efp5vJZ@-%K!3{Jgr3SVfF)Fc}<&N=cF_HnrUr@3!1c#l>|0V5EE=~(krQTJ7k>_Fu%)9td zzqY^ow16ch1i}K$Y1wS64Lb`F!|R6L&CA?qsTMV!Pb^xUgjq!k5ojPO+Xv!E?3fFA zgQC+*Fa|sCBv+ExdB0cTR*hClL21i-Z#E`|>klp|5EUaRKaZTG+Lmg7(Qu?Jb;p?> zkg`Q1+W2iv8Rz`Yc$r?iHArOw6l4Mf)cgf3lfM$B785-u>mg27j*B(B=4hkSEAFgY zNJVx9c9pFufHfkOY=Nu{|8%RkhIQRt_4-vGi*T$yPEER{f-G-(_atXK<&{sdgGfv* zmPc-2F6YoAne6}<&GRr4mbJDoD4M;Nwot>N9H);y@Z@AF+vZDE5;onz2X5?QcU%j8 z754VSS?8wQ$%b62vB$0BJ#>Bf`m{5OCXLb(s|!%1)~>QcYp-Sqr0qr7f%x-!h=hm; zkb~;KTcnfhq=D<>wJlkeXQZKW2h#_JNMq$SrZurOOk7Np_Z^rYUWA*UHUK^xsC`wI z8CJZ5CBr#=OPyn(Sv1Uoo++uitIc^ zdNv}JWmzH3%gLY?t3q^OEkGG>8S{C>fnG18R8iYI+c_`NAOd(AUZRkxSh18q#Km5k zxPyIPQXEjv4dK-Le2Tt--CG|#C81EymC&6fz+*oH^z!Zd%V&-JN#UV5QAlMHXk}SG z5T6CveH3?+B>&R;6H8apL(`kDn}cLCjw*4)^nWl41wGctdOb5G}>)7Rz*Nn6C#9+d?kuNiV>89;Nt z2z7>%9A=L#eKgAQYVClCLxv(vi!0XTspcj)XitAan?O914cHBcvYw>0+XEG=IDw^& zpbZG_G}Co80td-?LK$dcwOEFm4&Y(|>B4rN>a|es1%57y`S}M=OI_jV0L9Lm4Cvu& zt~f=TeA_p>m7cgZRVki`+d0$&d8)UwNq`kOyh*L&LekRYMyj2>D}E{^m4*p%OW z1~U3V6aSu`dzrFTGXy1^e+hKC$7JsS0rL9Z_sxT?XaCnGaaWKe(3&`TZOb?zzs*i! zmPE#A0124tfOfJWF|bv3dh>H+Z2$6go%y@4?X)l~eFL3mGSD1Vk#Lc@W1J_P=!5$0 z+t^i&r(Tka1N)qMz(07}9m(Sk=u9T2K}wFOD7$O*{h31+2?ciq{K{h|Bcv+bNjS+< zKuo9wmy(;^xR>DfYmE*ax5de$AU}|^ODX59ehK%aOH1e6r8a&;Hf!d9w@Qvgt`ppJ z6mGoX^aSunZI#t#<8-y+?_tX_n7;vy17tb?FN*kFEte|fm6%8wwFi4q&0_7rcl=N8 zuUd{$?oe-1WgKe4LEv=nPfb$qZa;y+U^Uo&3ol8k@?TNV`{{QtEtL`r&$*Z+lC=O$ z3(B0Lw%%ZQsF5u^YgHLdzWECp08Hj(Tm*(#V@po90iv>2$oJgaS~))K5n*d=Yi(>= zdXZx;1mC7GMzbHOQ!nJYUOHr7BBY#;5pJJGqyV#rM$KQc;}kT{z2|7hi81`XbiDFx z=QG5nEr|elIpW*P12p35OS(R;Ed6Xo!Y6LyJV2Q_u;*ss=BKE)n$>{}(h9eBVXVxS zKwgE48KgLs)c-m8L$b^UOk}`u1o3v*z%CYZ8932$-@mOL%~;PbOE$G?b&W!+VW(Fy;CWlN4`{!P{6k8X)=p+&=dsEkSC1;1MiZPf! z-9MH52~8f?Y46lG&Ce0OOtAfDC+?!@Pglg*gY#{WTrh;CUJLM8FTi6DD6!d{^9CV) zKxVq~NJGY_QB|4!O>j-#&QVmqnw|wZyyx`3JQbPq5v`+*3S@cVk^xxW%Jr|mlDOp; z=bIOevc{+8OsRX?=hqlVH$3TgK`CATODWu$!CPmy>GK~Vp9<}6Vk6hPWR8l@F%XQ@ z(P_ul9}X;6<+5q6ZZG%iH=?D~D@}1x&~ePom>H+HR(-l)?mj*H-c^X_wZck3mAE^u zMGRCf3k`%Lab6E?wi-C@8P{UDB-Dqe1PRP)l*QPf&CevZs%Yg5ZIxLV=!HZAI~Ey% zkbm7MujOklV`XD`L)K?mbOE5U-aGAx%=vl+UW|66E7)xSu3KqJ{zLk+A8I8&L0)Vv zan)ASHN2%j;p|5B5@C{n-%4X-_kLSHx6>aK<=(c1&fv52^HRht{n4?S=yx_TqVId$ zcgT%|vVB_PKIr&3x6R%a>V9O*mR<`()6=)9;Xs_<6!F!dH_MJBRW5Cq z#oY}SPCHk7URv6=!d;70_tBOY_E{PiWqo~xjk?2Eml5~1BlA(xRDJW6%UdIA@Pyi{ zrlEZS-Q4sNQCN$(L)q<&r7EqK3=o|Gpfz003j*$d(dShd;MPujSOT}tR)$q%3(>nB zB4P$)kIov5MeS9UyAy7B%2Wz}y8YTyBov&n>-GG0+9FhSB16Vk4?&3si`l`L{W= z!9*0Jl~Sm4F|3LP)pJ{u=r=wvzL>Zbd`Z^b-N>zIRlM2Y zr`Hqtl^T^Y;ATVyv3lD+?FCOP03?&;zL?u&fu7ZYt3X6V#9$In6b6lZy7&OJE4cG4 z=~L_K*!QRhcT`gioU3I3K77arnxbISkpYQ~dgtBhxyMC?WHsKwigzpY`<^(EY8Uv| zRNH1BBlIi~YwIYqm6i6n(A47csS}xD9$VNk;be%1_|{_@f?=Qs&cT3$#n0HvDpKUb zi!69qo4Z50I8uD$Zrt%v@wt*u0ge|ZQ`fjNH<;z#&QMgvDz*&YQ}|PcEHNRSP+8f% zuov6Ohvezb3!;g->=lnMv$d!~ScXX2JdCnjNqJQraL|H)qF$__R^8ZJPjjjQFGZHU zL{QR*Bm?xzz8Ar=#i4?-4D1avT1|1li6$ofO!}CodB}+9UIIjZoUyd4jvp6aEu;C%KcT$O&tyVzL`*KB00f+>JSyE(I(Ydo*EGca_AY;=KCEvSNuGL_ z(j3Q`7H#2+u)n2~trZ+0E7C$8BmmhC9I<}|q)epsc*VVn8Yj8{2gTe$I}P4jrH;*I~4M`~CdOh$gM5&OVZS@%i%o9%lCk=ZsmVK$Aj1I=v|jx!1!8mA9+b5pjf+|;{O1nys;DjmV@j}1DC=l- zdfo4^JQ{uYs(8-0D7ak?-=`l~rh!bnkXi_x?=KzN23h@&2LCN82ZzCn_2)fKhuPCl zXozGz#Q88j0)uRkpz8YA6gzX2_e#jlSkm^e5>*wrn z14SlFTvA6#C+tRPb)pSxy2XEwYk-TLi<{?(Iga%kteI)xPuvXWfg^|{3?#pBLS#Rt zLXxrkEq@3$-?(j##WFDgf0O3M&kOsBzMpNZv`uD(`01%i zZp|#nD}DEV&vFQ&o<9|eaJQ1PB5pfAZ<%KGmXq^M1OhE!2&8nBsGqM%mK{a9&=dwA zYBYOt0V*O5q$!37Ygz0aI#@4E{+kAY_uJR_(F zR|;*y7f8x>9YQJ)tt8}}Kly=Y-Hu?I&w3)MFsYtB1k1H`@+3uexj0^U=G0d-xS_xM z4t#@3^dZah>p;X$$P8LFH$msPw*Ph|@=iV?4b*0rbYV&#h~5&EW91-b21w}BzRoP% zArZ`;dhKUgziZ=nCMhK&sSNJ#ZiMZoQ(mi=`KJiDaX9acR#u2)E%k!&H=f6t2IDiH zc~*$dwi3#Nw1`WHI>k@=I6-l=e;8uj-3!$-0csiRXmXxsln9$I`&L!ZPcX*J(7d$n99 ztXe+@0V#Y|lK~;EhR&)7-qjMx-toB478J>h{h`8J;eWf%!0wS}RWM#+R2+e9TbdL> z!RkYf%yW^h#5k}#n5CDmP{R+OGZe zpnU?2;hu;BfTvA|lfO?|9=f6kH)S(nk%R>S&{ttLLQ}f+=%VXe;NvD2xYqF2st_m( z!#tX=HPnG?6u@%*)2p!hf@Kv!$JyuFiwH|F&P@Kce6U)3yIylbN{;-vXb0hT^MHMaOhtJ>z0 z->1-t#1#Wf)WGjYL`34(8n04YZ0VOJ%gtm;KpAOw!b{L;L@OEwvwT{DG-^Xs#^wW& z(+wDs8RnCkq%@RJs7ksaK^i>}TpEWV=!5AWsPT=ZnCc{N|I41~abr6}FcUxE26*8S zMslGarUO4PxBlRN!kZ=dw^*r?0&;G3=D>spqJeZX(?pFa$E9X1nX&wrUh}4in-tF*CPegt1Tz_ zGPe1Vtx?0OI;3>DC5L;@xmjTQSU^|8A`W9Zo04Rcd>YnnHLf)R|_6|O85ViXV$o5KR zt1ev4*LQbh9*%Iu4Y-WBe0^{Iraq&-NU$avYn+9TD-cUCK!{ucL=6z$B>Y@C(q2AhkzT z%aFEjmq@$xHfl)D0EZ4!X1V&E$<)+(>|=_XD53q$&55qY6y)y~e%c7YK{w<0erqw5 zB79Pk9=26n#NmM1ZT@7-3`uPvDWh091TMY?x?C>D87FC|zNWE{f@z+T0ZdLaKOeV&bSnNzPD_E$TbS4w z3MB8{(bJ=3Hw|9Pj4MXx#IIkGX*_o_SnHeS>;H`Jx}UUT)bAA(?o1X=^Z7MD5E?`K z%f_cFVIE*3tf~Awf@HkW-wAh3ujn3)4SxLu!Flgj=d_Wc8}tWUk#)MBQ&>W4Pli+3 z>NUEsz#Ta=hpIbHz3AsJ)G)^75y>D+?p3o`@=7Vxkk{<~$f}0i{8yL*N zxo~h>yk7T=FapySkQjj@bOkiUTK&3GcUs_HT#t4Fh(_RnI$)=#+YEnI30zBScJue$ zAbD;K?@7(HH+?{_0i*fLG@9FABGNY~plPIz-4D|Pfu&S1a?!xe>WzHkle(oBjp(8- zFUt5mYpWI7{O5^2<|atBHtxeq`4gn&l{3i_tDBzPm6~D&^gxfc~(42ln31xYr zEJC@V;(9(ePEe}Bvc?Kngj2tR8;U0SN$dkwQ$c(!_y;&2PmhNAswe+dQKqdH@;@(; zLy=IoQ%ZXvGoR5;O0^LEV6P92pBtI?&FjYjOQQMpzrG(!PqZMQ2el(icP~Rbe6AKl zx(t7wxKT(bm|I(Kw7`x8N+-tvwjq(x?gUV}?y$ACI(|0Qb3^&RV_HEw7 zej&h?P`Z|Wl&tqMpmZBdV!&XVj1{oU@^@wEukF?raQ{E^`09if)k~yEr&Q-K6X9Qp zm8y`Mfz|=|1+Yk%m0AAPC1GDZu3pw_aiUk5g&-0v8UVFS3@qjV%1u?}x2lG+{lgP;OlNGnC2pif5VkS#Y+kb3t7l1rbY=Eo2g!)c z+XTkkQ~@WBejZ(KkypvVE9}t(zUHKi=`G2YmKixyoB*a|3z!x&5pGFuYm! z&vpVwBE;MGd|UJBWp`euf}qHy2MuD+fkyX=UG1V}ExgcGPS!JevPbp&zUAt{&kQ5_ zIKl`r^#MM-6zKpHk}Z;a?)XoF-z(hiCGAuG*|T3i+0g;-u@HK36f%0*3=56kvWx$> z2J{+Dq=_8=?@npRre0s1IJV0_8GQk}eTh`VR`pg005=~-W{wb$a$uF<4cJB#UmqUs z1%L|_z09gFPjltaoaT&2Eq|QzL249{P>*xJC@=?%maB*YX(#+SmDnzpwB?TBjugn9K4fV&&C zagcIv$?PRRZ=xitS71nwNVse+*l9iot9Kd+<}>}T930b z&CZHCjRt+%tYrEYClwT=fqC7nO&hkDCqFYU$*GpDybEb7R==!D?{WqKv~M02I}uj~ zOcmfbEJaEWAH7Al9Pdkh1fChlklSm1+Jhi9?p7N`PI~hF1hagE`F1}68g%Pn&l%9V z!{%MTobrpmJOx5IZ*^)_LsRyg%pcH3N`}gc0e#twq=usJZ2xwPp>pc;8vi3_K-v~r zZbN>6oaa;a{04SJ-vvK??TY;<q4xI??7fvC9ODB!=pA z>oGlEf;7)Wk@e$ZiBjLIi;{uy9CR+|^-Uh6fb@MVkIci)h~E4?MUoSbm0uK2_@Ak* z1I}}B%1uJvQ7yN7%s@sT{*=BONri`@p`qaoznnf4nZb5jNEw+b)0wHJ=x044KCrZiJPL41>epVpy@d;1M(MY&sw+{`KETA1wk4@9?H>t z#Bxw)Qoep0{dGz*sXTmKiST4s6W5=yv=u$&-8@*sG6uWimOC^=dxEAe_ac{wb{F{a zL4h?i_5fTar^WPrpc~`Z52Njr4iI4-_cmsQfk}D}ZOG;6HwwrAWxqukS8^<%-3Y(U zO^juLCBH2HkWK|jNok~!?(WXFxc9v=-VX+w zKfqZr}}9`=J{tKOY-T@?GR?0-8$U zd$zn#OdW)H*!NVe^0!YOEkX`oWP-?H&8s%Qq$khKvlB>q-Kthq@`mD~Fq)l+6=nZ+pfp)}t4WTuq#!i1l0l$9zuibFINVj{f zC#s^={|91&&MBp77UYix=9UrFyf^K&G0{7DVnMTbF;iTp3 zr^=^pi|)Fe{`_A*cK!v|TB}r}FlW4B8vNxv7?8=rY>iue)^z@7n`KEiHqTkAIT!IF zsh&x1w1qWWZcw4?&Azy6*xo@iWvRcJst-+#+<+`53sBGMUjTuVmzl&() zex>NN<;&qX_(jUl%U0;QXA8AA5W*O#Rd=|eK}fa|2b_{wJgOrqd5KDVk*aJAm`9`Q z{cMlr)tU_+Q+!r@QDSu70xN_qe*NdVf>BOUV`0)O((c0Elj-CiCpoL5@$I42*8@vo zM}tR;jmMZrc#77FjBhniFto=96q5+XZG-ub`l!Tex6iUEt4zvj%p?X8A@a*2t+Q>N z-XZx2xtuWcZ)tttxB`+HF*q?6oX4HpZ9DPzR#zy}B9=gklGMje0F%$^WCySxn^MqkhJUutr=7pnLvqJ?M#7kUCM zUoQ_~TWtCCPb6Rl3Wfg)Kl_0Uc>KyY$$A{OH)E0@k<**n^Id_32< ziAWTKDt7sZNJm81*kijMC1Myp^Q}H7FemEIg6HI&^1I~W7%8d-5u5c~*A(s;|kf%*(Y)TRtX*2FO4W zAK{^;!jkiG(k#o-Kw)o53YUO9P^38% zc@M7vt@W9LkB82TE-k5=*&H%B3qzm6n0tegJ8sFH6o5k@zNt8_Xc89GxPgc|fRg(_ zQy|e}!*V?I;5nSmqro-l+yT&+qf5*IoLJsi6l9{_&#UmW*K4BL$i8SoF(e763BQA{ zKfZA+GBOvXh_Un8&T$Wqj)N^!$a)YKH}#=LreulpiIR&e=o=M*RZeeqvCbP_TMQh@ zUH`Clr^Y?NI5`KabLZXt~LqyF&=!M9K`pY6aN_Xb;ROso9?4}J&9hsr*YQ3D)?+A zR1C!~YV1==cc`VzVMG&vgRj`A7DzV}D7%gwy5Hy@iKSfm`jq z#43+5xX&qXU7ESHY|Kr2t%MEdd7=LXxnbW>Yn?BchRA`CWWIA-;}VtjRVuV#$;pljvt)hQ}iKg7zq;#Gh=oHIl*(_ zquw;#tRC-;mJX?!Z)?~3@8bN8D%;f*cBO0QokcKzV`52DCR27E=gYu|94ijM*?mV%3T~*$0wjvhwxwsoNHWi7S8{ZtCgs zF2!?E77Q+P*&Ij`Y7WK0WHoG)cXmE&H3-FV$H(h;RYm6tGm2tfvXdBXkk&-;@_C`v3mK?wl^|?5f9-8G^Z>$U9gj(?RbdT^2d&l@W zYbZih%HY)q@3+R}HMI^(7)xeR7nF;*5QdW@3%TqEpnme;z=z zZb%1@3;SkTr(`RMu{mQPI#gO1Y~Lo0g6U`=3UmJWr{^@(R(5}L+8-A(QlZ&I`nY!q zLv37t`XGhYgVT!P{ryRG*5)vx8KWof=HI_+o-6z4f*2|W0S5CTb-CAEpA#cTA<(l{ zhu!UFh8=-*0i8fh!VEP?(4niL)@ZGZ$%zU1(_*NhGYB1z`^3VJ?T?V9OecFxV*RPZ zlDl?w;g!>(eZ#MWgp|(4R6FtU39*f{%muv z?e>W+k`BrE$U*4lxnJWy>BQ64B1lt+?} zXE;izq^n41D5%~D&j=Or*^E}cbC{gSm4yjpg2QWepS+|;>n0H|o8~MTCy&}^Lb%=L zq5gyb3bP`?zR1Wh_+-e@Y)ufUh}X*gew1vHaZe8X^kcQM*2fG`tIEG=P0`@^+BU|As<7O~sbX=#vU}&@iRktd$=`PX#1bf==Vu5+^`c9tY#I;PLj_#w+V zdQXQWDn3_L-iJp;>1{3t^BmKXRc|U(qE7uZgi}3?5RJ^uY4h^(-l5gzi24e0nGYF_ zWC{@TJ3<^B90XnWB)zE9K?NHra9qR7z6pZ(SVTV11GKo9?ez2hua=$=|re9@MWP*hM_+KF7c5k=3B=9fnbcoZ!{VG&(fQ%Lk&QSb4?sjjboW7Jk}uiG+0HMB z()#oX!_MDU?s@s%g=5qB51mN&hqB3s*?nnY5@CT%$5i*{g!hXl-?}1B;vm$R+}4jJ z640^V+7xy%7v2dQc-b=4@R_hINf%7BgA)%CBYmtnfjVwOCi8(L(iJ?dz_1f4`#;o3 zK8fBymV8r^p;(mj*7VK-#9 z=r_0K+0@juv6Vi6Wo7lZ{NKZa&)NB4_D3c**k5wKWX1NGnENNLUjp^@((5ON_%;$# zQZ#AREA*cFM+T*0bYPoW9)z88CJ)pgne~e1Ii16{s&P?e6*e_Fqq{`KJr@v~7Lu0Z z8<*ihCZW@Yd`n>2Uz}LJtd%e*dw3rCoJBy&n|U1PGfGDHY&4ao9*s!WrCYJ|{Y2CP zZrR4Ob8sojQ-6E>dGyJr@t#W%&Mja6(rsu@I4Ycsk{uuQAbRmnK2;R{tWoYV6x`!;+eeGEW*5f&(aLSvfu!I0(La{ff+`YkPYU98&@3U3 z-p3z3_F4Kz`()N7TL&(~K{km^B?*zuziipVNFnV@>*i8(sgSbOVJ@!B`Mqe!XrWol zrOt?yY-?6%RveLS8Q_zJeV;`6S}w=mEt{dO>EADxwPxyXe@nP0ovYqyC?;1=S*bK2 z{$rD!7O+kt3>p{z7tr|NJM9xGoszDf+M>YNeqFwZl~q{{H+-G295ssj_D}1|#8Xyi zr)92HFwDjwT)B$!xo^5N<-C zlBwlr2{l}ov2MR^e=155OOg3Uuxmq%cA`wSN}@{Wz7eLe0P1YAT9g?DyFKpdm4ANt zS}}>(NAIQS1HCX5tLV9T7@JdekJoa{{5kP%?|c|Yw>Gx49`5rgKO;I5?LE> zHn}#&-e9rBn$8!Uc9W)N=j#U4oW|5u_CwZl%0wstJD=*j7ppwz5p$yh=hzFzwQNHV z4u340Kir(IIqB#SLP0^j%w+ZO@>*(eO@_^ZB{P3u4>ea-kowe2p!ga~pL&F1JKa!;dMWWcQiUHo{(U8b0^*N3F^5 z^IHux5BH8EMVTf=el&94%tZ|Ej5%?vJ?)-YMU8Y)r{=z%mk^1x0zDD9+|cLvK3f`SFHyij)d z%l^X8G)Gs*l{Ec0Enx)cG*A~;$zCFun3yN0rx>G#?S8EvG(I2-2?-q>93Y7}n3$aB zJpR>@c>JysqxMbr z3YqhM1^t?9m^hR7*HhQ~j_tjin!ypU(L|FHXyY+SpE5c*J>9qwR8G%hYiD=7dwh48 zU(!Clbm=w0Q^@3kK4dm<#X#KdmpL*hIKfnim*aX@F2UQmT;Z|talKRN(Jz1My5i<> z^7sN_w{vBzb7+qt96 zo)DKrxBK?%`Ge<{QZ}k@@@YmdmMc{xmJFSw;lG$6q7t33)ue<@ROu34G}?nu^ksj; zT2C*{Jq265S+s!uoA;k~9IKsP?^|vxA_OEx(CupcA|h`>rx#-)(U@ z@VlQA*I0df`qOrKcXpWP0JVeh7Y1Hv;vSYEt>$JHs1r`h^;9LKpxd*)az?M~#CCz- z(_Jo!OKbpnzs`3&wS41$tFMExuI0J@8Rs*0SVxC=OKa=!-(gQrPuu0TERBkz1)rPt z(8P+w6YDP_R%yiB-{!oOsz^6}-`!qL*{1jl5N)Nc3eI zfJa~3wgRZ3ZMW7)jA-A^$+)E&p+>g0%%j8J`TTNKLVBWCRf@+lIe=dn4vQft1I?O0 zQ=JpqTs?qPJEY-1>iBL$A0!I)_S7rk-y`X1zgEe_K}r4QPfwOn z8sN~XB;ba_^G9;dyEr;W0;>FV0LbcAZo_Cif~lqcHr~^;-CV&q7SuLeauZ^d>r?`M zkNj?gLfKX)(Q`J-q<6_aZ$&YlFu1R6&^iu$>;4Rk=7V;IwCdI)Z(sY=Xzepi009BP zixY%OIu`QfWE~7?>hA5$S1I+loYK4n;~j4HtJ?XU)?nX;q4kW9Cs+W2l(g#MirgHU z4o3reP=v`$9eR+_sOfa}FZJt>u=?WZ$W~JSrv-pxCdv|==f`DKfY`>(jhIA{txsK6 zA*t7#HE-rYUY%TD{~&ymg2hdU`t*ce$xvQgKv&m1w00A|{t59&qKzVlz}w=3jT_4r zX{zo<=1dr>gV-5w1&mH&cFM>~`>O)Jy|f8eG&jOh!P>*Wyd1?EQUI2dypaxHYG%9k zW1zJ`u@lDDjbRB}Lw907B7aMS4o9sdE?|D!eCIszCema=f-ZdDZxT%g&S!8>rbq?H z3Vz-En3i{dQ&}j(XPWs4JF~zh0>bDGIlsJZX}z_>fR9pxV&Ywv?bI!Cr)QY^wo9|> zx0+9<<1o2i=tNm>T|xkLK=L=kWF`(HkuWG|x|8x_V(YWl%&uJ{)ab-E;+Y7o4+^>6 zn#ExbTt~Mw?b7Lu0uv(|sOddUR^I&n{Tl%p8O8`?wBV2s4$s=cbg%UozL&jtnbZzo z()GQmGNA0hz{5*fWA$E^7=mqFfuldB9u!0^6!w8E9xN~$+#Bz`YXnH#=btcZO?s^| zAN37j$7W_`1d%E;b2Z9NFE3kX27m6C=r*zLzp6BO?6{n~{4Qs#K}j_eQ+V3a``~+Y z?A_YpjTWQR^+i<9vBve|%%;BlKYvfyq>eQ@x^^PDLUUFPfM(0K*dT>K!~71 zM=q8%tjtQYXCDCcvSO<7{TW}#&Gu{48g0@oJsDz9qcfGSs;@f+$K|>^z+Yz+Qa9h; z%vzfb9YOswz8S9U0BPO3Fz&HpxStXD>5|uWM68cC7%S&y-bIMc<$ZWvvMkg8zGJ2* zg>GNQ?A{Z88(e5vk}AQAQX9|YY8-T0(piVztHXZ)RzZHe20Z|@ig-GhjedFxM(S=< z``)_|a$7n&;Q7K=e}(!g^Od;To)1Q=AAamZExM8UQ^k_F_n>t<01$W6k(|F>;4v#f zTk-_5lI>jHg#|(eJScAvV`KPxGg)0uKAlkSNntBJT)-|SyD~W~9R$US$BDNc-SI$F z8x=l2Pd&<8@_e38qOQ@@^CBiYzL`D9WbM?q+?!A{g(^PIX5~$Jwz(36_=%o!?RxH_ zSkuQat9n6e5b_fTgx<4#EPLPkeTi>WOGM=mLp+0za5T%%JI03O5nSL5wIgEk=mKk4IR!nmwd^rRn-z7P%d_NAX$9 z)f@+)MmN9i&b7u&zBLfU3@z|s1z-$I85Pt}NT+n+c?17(#k2zsXItZ1XXs_|V?f6j zf=`~;kO9j0FPs6O%>|o6o;1b$hBn|`Lfsi<0O(PxV*{D!@KHjMT4fl)j|8wTTfm$GktJ^}r6&7}3a1z|cE%n^D;T zk|@Lw+08Kdn}7ec<;LIem~FmD7w^fV&Z3MIez!w>!lclnhF^HiDSA&Ne=Wnq=gxcq z1k|BuLU+fCM{3aDFl3|VQr26C%4B|@i1P!T3Cc&DJSAY1CI{=6N}A-K;KN3)fS#lP z02XtdbM~~i61OlL=+XwjdE1KL{bezQ_Rg@JueWN_>qA0RNXO3R{V<-8l+*LGy>EPb zMig*UCby-VA)L~rXrx0s!a*eo$`>fR5lbZ&S5I@3>H1OH_vVY!B|VX7NwPf)_AZEy zs4JlB?zO}3EBG82d62bK!bXj-OYk>QN}VV|ey%?2%V{+LrX;!kd^cU{^n8gDU@(ec zkm6UaDMFTUyTWqqP5pP?!Sj~32-nE)NGYGqT%9Ll=o2cKSz!>i)>k;sIfrFCoXe9C zb(LYqR1Q$Dk^3yUBQYGod3zvYx_lYiCDB=Q)|zt6DvY3;mE3{O>^SAVv9 zfQzZ;6tEWV^DR`QIkLhu2*cnoJJvd_sjV@%>CID^&oEAPu#U=(hLFjL7toXX)UQ+3 zx#CR0)2HZfit-2Sn7(`UVH^PUV(=AzjA>Z-hM9Rc38;AGZJZtS?^ZWYTrm$+rw`ynA&ZSp}Ht=%W}c5z#Eu7=a% z%gET{_R%MU`ML72{g2}JgoiK30D@vDLfoo6S{&!gXh7Cr|MkNI^hMcBT(f~|&$^PE zU*Nc9_tZ$zXVfBPXBYGlGw~p(S!-JXuS0riOlrO`DWx`v{6wTtW~!hy1)^W>Khk08 zbIAj0wqVERrqlN9zX%2Dk&0w|(rBqH7w$iTlTCQ1W0096vK?5SI-O1AbP=@bl!eo7BSKk`<_Odq} zngY6l-{}z+<_TZCs|odXvzyHvnjYkLIR(SDgPppT@jX;qo<`f|>WDGVyl5@1K%z9h zqt#!x4yPZ(&=Jqks2GGIJ~D-!8Ykje9Wi+h=_|Ak)Mrg}*H|Z|%h<_J2%+_om=5-^ z1jwM&K1@0TsyuLmS&&kpY;1lWYf5Fn7WJ3T#lhBpp+4I)?eVwtZ&_gm3oigmjX`wS zaK&#utlj|d{nO)%g->;uj-A6!R+8l8>bBh0F=>zuqlGth3SRenhXR>?TEa(wgX0;u z0U#ImsTHMdo9RJQZP-qsC9xfG$ag|&^^=FU=TP|nB+}Vy_l6i1m-r(xvNGsfbx%(K zD1K}*S+0f^e|IMvB$$m`ZiHb_`l8BgF`%s1wIm1~Q;g4qq&4MLv@jkst^cSO0%IO2}>{tmm2z9rsC+PWccDtuVlzwv} zGz3I5bDo6i825ti-tKQMOh1O8Xd^h&93s821~FbQtU=YFuPbMo>Q!&ic9E_cRLVw{ zW_2W0)f)zg@`xn*8N%;>a~TCz(ohU0vlVVXjHlX>(dFja0WXfk>{;;Htcab;mVitGfE<+$rFaXhBdMQj(s;k+{I(JEOWfE!4O|Zyb{rvaq+~EE? z94swR&cyv{6)MJ3;&Qwd-}6_^De6m3p9_Em{AZu4fAwLLU9e|ZLUKm$euhEu6W=8Z zV>B7}WQAS|8)*vjyQPH(TAhYu4wgc{I?xIg%*5dKSx@QIF|SOgRuD%Db*~0@QMUOI z-LjCt2(29+D1a&$fT8fYs{u8I^KYj11 zSkf3^&q?{FiF2_(2qNlCi6PYaS=G2DHtlE?w?ABk4%34sNj(}Rm1R#CA`?_g9L50! zM#o=sNYpuWun?emGGU!pzE4)E#1Ao4UN&w*$MNQ^>(D)MFC8Xd~4Ny&CQN67v*fFln`3mr}&Uo zT(AhkAcI`oHlUN>y1zEOL1&cWCVKNjXR&{3n-lB-AXupprkY*$gKM}tIznNF?|h37 z(|e`k(z}T{N;zzse!eS-#3M->=x9V6Ik2I>-1E)E)Y#C8#0*5BIdL7-UWk2&>8OBl*cfQ&0h*B_seLdHnlHMi>iiTt{ zVJ1=}t#*uKlYW8@7ltCL0B81J*`8U0d_@(fS+6^OUhvo5<6S@v{gwHpBcQ6~xM(B* zSoLj z6Knm0h)}? zv_~x4YYU;cCOJKEZ2-(Ke zRpzeOVG;4VAScg#@TbMWsdTH9x8+Iz=T`oZA4dsZX@n-nWOm?V@DSo^SeICMJCB8~ zh3MW1MzNv5@C0ghZ+HSIxuh%R8d4iwbV{+Ga8T8=%4(}qB;U6!+|yJxRvJ_GY}OC@ zwC%e%9k}F;BL0T^!nP6?=SNRk6=M(;Re=ojczIkq!A|w6gQBLhf&P)%=1$+dz5Pwk zPLV&McY^>44kr9MTI6rijrI+KjIqaO-g@Abt+klt3r*^>JE#m1|Sv zRa_G$7-<~&IokvTRerS3V)3$*Kp9r^?Nt)d%KqA5`VJ4|qSVCTsTE*K6&$+Cd6=dI zD=K?5<6QjBA!>d(APtaX{D$!DFJE+_y~G0wi@$4s*M~Swd*0aZw8k^?=neYm1&;qdoo}o|l8heYyttJl5EP zS(O_w6|aFuC7O_D&wy>cEjTI**+JwC_oXV^HOWx{Wf#aoC%?brA*5mbc28JFq|{n$ z6%@O^PtzYge$gaFx1cO7o$m zGiGv(YChd|hLL+veE?|((q$C}6*48>iC&4Mt*MfDMG&%d#`|ukA(;t}-!@)}5QQR@ zB&}B?6Ef-;X0OKjdRk`GwU^lVk+q&~8R_f;O7khMrI`?O<=K+}shML8pdVux^e-zW zx@}4PUEC^F%lbhF?g8suDeY*v#G0x@4U<6<;(#Grq|Erf2j8G%em^W0_3>}8fw#P8x?Jjdo+~wdq*V0u{qx9LvL#d2fq{WLvo-6j1_Sz? zV9)FCYeRs%j$yRilP9hgimH?6RwR1xcJG#_wCcCg^WC=&{`35?*#KU zn$ADd5r`GEFKgW9@qqkYP<`|7uv|<17LE0AWzR#<`JajHJdIKUAe^<3%K9k#i-F&g zWR~Dp;udoH`9kFO&vdtj%;nwI&p<&lc*oi$W!H74ItXaxcj2NM(p9*T8t_E$OO}_R z{0^%LA!=^r%q<51|GEJg$t&~%)@Zk;2r@}_COD^4;zX4b`mLKx$nD_ubMigJ-Ehh7 z%Ej)(yL2mG(an}{G3PRcPAA8K1N}9S~-*!06QO242j0Sc+I`HBm5)q~1M$oyDz-k>g`qHQzSZAbjEEL8}Ve z4F9)6gKvZ`XFCO}9g=#fuXF0S-Wh#>{yO+|;aA@P9+ASfH))XXYK$Lkb*68dIiZ-X zG2bf_hQ5FdY&d^1&DF|Y9;^i!qUaZ58&W&l}9; zXPr3MhOSSMaY8=wpnByz=h6n6f$J`Bh&HMxUt zgHM&=W#;bZduKe_AMe*1R?EVohBpU?4RBq$TrQh@ny%$Qxp%QR@s7Y_F2ZalT2N2e zmw#T1(&kYy?P$*4Mrh)(waal#Fg`Pj8Re|=D^zr|fd{Q)Cx0onBM^l!k3h4&hag`; z7!i%O)3bVD;{%_-dvVg8_j(!L2_hyk9=th+K}I%4RPrYuAGEDNp_UnCE2lNyM!7@Yx zN5dHahhStK%f0-AK4`q~fV!?v!0Y@8ziENR`%@C#q%}{D|C4}MYuiQ;nK4jDiryd8 z!Smk3zh1%Z=;p*esOW2pf6c$RYy7pIyWrYW@3huS`P#fO$IAbo3_N})35^q|( z00py9Tlw#6__paY9-zNcGWVl3B)drmEe@39?iNkk!Z{7OuLhQm!t3oJ5&o3#it0Tz zAZKFkV7vz!cfHYOR;j{WFFEZ_i-N;ySRiQz5PE^`u-f8lPE?+)kCQ>!T#X{R2>%>^gz7vrhg6vvVEHOIljSXB zXzE}C=|GNL9*WUt%xYoEk;SFOHCIjPDqe5qQJ7a&eVGpZeHtb<-_V$qgs)~zJUl&< zd{*9~u(4Ia`(0$9B+0(px30LY+;;D7#~lT*x#Tx9n<0(Ra{RziJkge)d+*$OkC?eA zT&kUn6@=_uk``leYB2PWO|)7r}wfg5F7^Iht#>uD*EkSBTp@UcL6;d zObUA86naIlaXqC(!F2V{YvYB(#W{ahv8jdc5en-Yc8Tx)c$=OlP->WMn6X;$z34)sKpCODo897?yhHJ_XvQ0b3&qS95Idem^8$t>c4O=% zf1~fQ^cB@8QbDuCgCYUW-^L7V;yNu~lYVD;&`D(o5PIddF{+AL>Qd{JpY0-|k)42G z)VWL6{_at#ku?J#E^vR~f=|yu+3WPf-J&;}0Nfu-)e6)&HSg}TFw>s5FD=cevIg`H zklzQE*e+8>F>m~}wW2`C%?l>&fF|gO_KENqpvek+Kf;+5z{41$Eu(dWT)wMZ7hhZ1 zQtf$ej)^sxjOsfZpPJeaxcZ|@&L$`lNi#nf_|UtO%CvJAO9Qgd1l+U zFVVuIukSZ)X?^v~JQt%6_I7XP`hKP1`thC;0NPD>qbV%SUvpiLPy;YK;1vx2HJg0)RZlW^R2tq`p0}`U(s9PveEZM2O#09|96 z)=sO|sbklFA`k3|^ZcgDC^nASitcAgjRu^|Hf2m%?9bQmZN+vPXppBvd2nSV0+{VI=%g`Zj3S~^7@?eHMXs0Lz8Gzc~FOMi@{dz^%-}$VP!H#l_tkA41dfB0veNE0Ag;J ziiJ>|M{+UElGc&LKkRKp>#4Y5zLb`}RmV^a_gBY7{#JSo96&8#s3co3TI=lwWppAC z7We};x5!^koDsavgQ-&zvWXP@1u}5RG{E7=`PE5lix6VN{rEfT4% z{=5Jn1wcg_fvxUGxR+ux4xk61^aKC?*JcKNgg5q=P8Ab zy58htRS32Gdn53zzHAANO6moF?%0Gmefph|qS-!_J?Jf~PuVyzf7)*TyuOg?GIT7O zvu8gA=rW^+-c#6Nl(ncu!xii8f$P?`?G-tAE8SKWfo5XSg;NS3zBM0Dc=w}1>y=D& z!}Fe>F`!)fe@oB0cq;v&Tcp_fl=T(>zk1D{5#Xrim5?+$(+dWn0bt4?#zUR>`Sxhk zO0^aB&5;Ut7r+t$iWRj&k+!oBBIMG*gQyj0uh(3)OCq7GtMhHVh$km}Y71mDLK@@+ zYBQO~KiO#65c5bw0&}2L77380$dIQ8@L`F%b=~qy!b*J3G5q)}=9yh3RkV7V+Xn~5 zT=JAuVVI5JCvk)OZCh5`I)G!<fSo5HI@xvq`RWZqNPz6dv_>*g@9j<_=Bo$YKmiF0gNdk@)EK)p^2s8f9sK zD1Vy;$BY2_(okN~fyTUl{9;?eiT@P8HS4+pfxr#u4s;&JBAX3o%;ra|iW*&B95pHv zDdD6f!-1s8C94KOHfb}d)mG4N>H=?UXDos}LSHbhhug^<0C{2LV2q9>y+t&9Z7)SR z0L>=N<|fh}h3m)ienj!x`dVzhj~3xVEPoHcyNi62^EFDfz1;w^MHBZYbrQdA{u~Da zQaw+tDm*H%=h8Tdxa!WRP!IJ?9P zX}4ipiC+>W!Y$tC?NVrHK>-0hg=4V>`_!Vm`4}9FR%F-VYzO_ewi^;7Gv#|A`D8Nu z^BJ#j@pQ31V6MfJ3y)Q=8Z%wxw-LMJ>TkG4+d1c|6lX)qeyZ?mGT$6z6Siuze%x1l zgwa9MpSff#JiG`0soj4k)c4!_4K%SVQ~i7Zm1X1gOxRH#_gOyohF*ke0&o!@Z~L2= zG@jHp8^O34pUgxmCCuM(m%bn!);tGUCvoE-s|CPhX*_Jl8!)8@@Lv?;(lhy z2k%xtV%xXo9y$B=oM08c$yR3x|?A*(Xb1=Wle>q~2B0tKSd+Moq=K;yM!KO<9A-5#VL=MFq|e z5HgvM>QaLd5q)OXg-A=U5CBPxy3KoXk)yPJ9)eCa6T8td1w&&#V$01dOm-y5e+0wAdV(p_IMBr^6{`YiH!BDC~<^2B7vK4nbhTK|mYU!RF4A7oyplEdh zM*?X20Y#LF{=;8uLvWNfYx9uB;oN4jDq33%NbNfq{(Y<7*`egk{0D4I_IK_q3#njW6Q0DWo8OYx?*-Ft1E{j%M=6UkHwc! zBX&XrV2@-KQGDIsI5i*H)Jo3am-3DU1}SdhYY!O=5gIm!*ZOUYB;C7p5Q_n5bqb(G z5TwaFcmgblM0IaqYJMY?!&Xb=mQRRppsZ|WqqVs;As6}|}X463EbvMv=$ z?Q4Jtu`F%Cz?Vg_5Q-`32;!D=GW0-h-1 zS-!A$h!7lkk_jP&?fyaO9sJn@JzrLTgXhG%^SyKZ4R^DFkvU7-o3`z1d224j_ycXJ zN)oG6!UkcR8h~=BmE3Ht@cC3f21)c`hq%wTy?qfMkB0Xdaj%%JcLSoOr#ru0@wumR zR$tBO`|t2As%}qJcg4-1tG~XWRH&J&0ZsT2;M;A5+c9$DzY&))L`dIhjn#o5sytQ7 z2#&U*o>=Fd%l_^C!*V_fvqgV?A`LXX1?;9)F?Ky5G6hXOf*&E9m?sfLbP$A76poDN zGG-vr-=jw`s+MMNB-G{LbdkTochXbQz$_anhc?nmEqxGjS(b;qR4|~x_G#W%g%~(o zHj_taXeqx2Q4H$CG)gXTasY|eczZsz862XP6TKyjYCrr5FKGGh^S^!@b0&D#7_fV% zs;T3BYcbAV8vn3*+H=ufM>UPkz0WfHr4?mT-M zEHzdQ0htHC&5K{5-ELqyN>{Gc0LTQSNkrE`tqgFombd2~XV-KrjG2Iv>d35AG4}v! zMjw}z43)($kZ_Wes=9%8vtT9`bB_e+y_3w65t@!DLhBp0gcRMiNGe2W{xpv-z$FD; zO<@HCvnP|xUQ15dWaHi8!x(N0PvtEV_y=ttNS7#B6P61yp}yXim;tG8Z6+HKl4O|C z+d`A1(Dp0<25}gcT*z1@oprGV_I=JFfYk6gFpcnxre*66ZaB{_Jh`vznQ6T; zWrVu`HUA;cSnY=1Pv8_85EL&516jeK1Bodz@RFzoT6|q1{F3uY=$yeI4;T8x0sA>6isSj-d=S;ndFhwH&*anP7MO|xXfR#}y<%=UH;Cx`M`4tyPAL^R8O-hD7V|MK0(2F-=_tF~ObhC$@tkU=H}PP|LU_EhZyS zO@@Z?&5yDo;-b*mczk6t`CPZvfP)xXJXADD(7+X<t%(=StuDY&x_gMic;KGFUqp{eVG!VZbZnQDbm4=syC- zEW}w#$zm*N9zlbkgSFTYSG$?XN>kQ%`QI*-+MTU-I;=C#;#a5(=L^n3gaItcK#@QY z3s?T@PXvcM#cMbjn8*57yTX_r-dA`>^!LACTVFrE#%jGI$(B06&Vq{L-+7VOjeDMRb6$=yY>C+`PRO0b1HUY)3LJ` zKV*~I%&}S>mZ30f1a^L10sg9lmz0WiYS=GqJCcdG~WKk z)XTP<8O)$p6(p!BuWSws>xe78*{}xr05BmQWW4RioA=L#yU>h)- zQS*CFRJ8TNaE%j+8y|Hi=1!$F;00H)N%l7SN^c2O@bD$^5z5AMdQB}~tq<`NIyZ9V zkD!;tBT_v81>Q8;G$ZGc`=PH4ZGtpI>foo=w8*d6;ytmDir!?CnOF|Lb&m)0oALXU zC9vuers-eDN_d1PP6%S-_(#|t{qnLkMVw=r^afi(gQlU}g(hCfTTGtzWV0b;;|u{c zqMW*nCFoq9(e5?n%PcS7GJ&;EBPmcRO)8{2;X#XW`GnEA8;I~d85%`;4MMu`b`byUppHK))rPM zh`<1;`xxUYaL5Tb=Zlt4956RIQO~*RHpAvmK-VJ+T|#_H`!-zMHWQY@t%uiVuZ%CAW4CGyrQa#s;Kj+vTEEYT}ze>_hL zUUcpj5mJyI$LNgv3rC~>#bpdl0V~6r^;&YS%bDR4)80*mJswfVD%X~Dn!vRP7;KBM zy(?PZ{Vf`TOn+CCGo=QH!T6ItKxaA9a_u*piwqo;|DW}obYR@^84k$t^sQZ2XXyNC zo*Fz}w2H&N83kNBFJZ#h?=WZ?MeIdBR%6qLlvSl{^U{+ibWwS>_U=zs>E+n!^OiQ1 z&RQKfPNok8fYToRKQvusP?lX2CZs#1Q;_cN5J~Aqy1TojOB$q0q)R~Q?(Qz>P`dLw zyffbqXOKt5IrqJL_KMy8%$?A8K~Q`4*oQekS8XMJ-BKL}(oREy8|a}HQXX(u1oRdt z07#I$qDLO(njU9DrXz5b9bj_71Dp3H0W?%xd=B|crPKQQE8h3^WPX*a4t4a^j>akr z%qy~s6%Bi6yl$Dkf8GEt8dZNi0;>5liiUM7-4Thys=C>QbhF(xI#?ioFc86Q+ia|Z zy_5aJikQ1~EnROE@u8FPJH*ezAYPG}uZG-{|M@mnoLrHqb=nK(Lk@b-CE@{^CEwaH*C2$;KI02-e2g+1uY8(@xp8^Ht$;1`suvyj2OTeOy? zZK6Tw#Skf&v|xp%c|g`4dJb%a|1O#gOL6MS>y@U}F`!R&-cZcnxz_4kktlqO4(4RE zdf%)anF^d1Z!1Q`k4paZzx8{4^@CHeiUH9C8ZKX3K7eVcaPX0OWR1HyE?>Vwd3vdp zGfYpQhxF+sS84Vm(98#?OhH3#=SSP0L6J=u5_^SN2W{ov5hfMsI-G8(%hIwhDF8=I zSxUcG&(t$?i_V(+x}(5Y1UL^MWbC)pIhQPb0&ffhY4zu%PF)+_0ru^P?46<)pY+4y zS^O!FaGt&8?ses5B`c(OwPrF}!ys(|(Yh*PF4%p?P_ek-j#tRe@IDUB6K+V#d3-*Ql(Y zUNi|?Q$T9~psV+Z7-C#>+}((QK)GRf(g}=oAFfY&shJ~fe&DEM!_h;Qlc7^>B>hYd z*b$*i4H#xa)4U4-{b61~*#f@Vium;I?LWKZ+j1~r3p&f+5dF1e^RC>~3;_Z!$hsit zKOo%7BN%{9Z5owHZ6}kF`HpwzrU{9%_V4U^v+}@0^SQn?|BUY+GCN-WLx0r|=;Az} zH?T%Xyu7BdJs1?>kU%jVK!xOG59fYN5! zv2bM^#Tjwqa%plAHws*v(!dw(*M4OT1UoYz-8NPqFS^cLmw);@s>#Rv?=#(&C$Lzn z3$#Lk!5Dz-1i2kU2NXlEOqvN8dC=SRBJlKHSD^5&9S~1lV!L}=!l3=N@m>?D<1MB?rEApwOqFM~t2-VS(X2Je%O2s7UjyiG1VRX-A87isVF@tPK)$}~=^fwf6YE-~x zBr(kqkWq1f*Z7FFjS&p$GK>y>21rsqm;J9}zq^RQR_+@w1Tg_hO5l$&TxJ z%mi7ZKuLIxa>oG9nMC-e!#`Bm-p(^|!6s2k4#Y%}9Vvx=q)Bf84q)Pd%+F%P!Ok^D zcr~&l9F?0UI|d;??LDV6}sn&y93bbd7d`1I*+28oZ6i{Ilp|swRodTiS6aiYE%CM}w{8~Nh zR(7)klRF!BCu7Mj)1h^)BG#B}RKf#b`iJ=)t@P7!kvys6dT{g`U~dLo*$cSfYIZhp z0SyQoMIj~pMNpWcNe_e-)%ovU2i64sgsbL&-T<80ZDV?0`CxP3RP=XcF(&AvXg+pQ zk;ca|F;jKAl;jpFtqzM>ZH(IvY?0U7+idKUPfU6T2K9L?$(cFAGWXtr~hDFrftHxf>zWT;s zJXsKUME&ExD@Ty$iQ|#7>XpkuU;pHd%`lahX zMy7;+uO=9m9!Y>Ry6aKPjaF(XVaX_o>Ih6gI&-;XxWo_Sg-nY1nf!)@Qr}D0&a!5D zAtHMh5Niu=ju|}azdDu6W(3quXhCNXf&o{v`>T)`;{_VGgRe%*eG~QzfotabUSTb8 z8>$w2)Lv!42&>bV(_o_g<1Uad+5(gL$yr#?;o#ta5#V*c@Uc!+19+?xrS%{+%i8Xi zt3nNTs@l(F+-WAip@OVSf^?~N6e(1G?N<28B$*_P_>~#z;#n9tk}k?6~;c*3} zg~o*3%T1!9qQnbo#yT0$EI0@@H)US))2ak$Phsa9f1M~)j#vGKq~1GMv>WgfEkBQO zeA-S8J4m55{oMosD+?YAn7>4X=NG^^UY^%z?_86nni4Wjom2QQzWOr0<{2ibRPTGc zmar!7MV|KtDwu!|KAb}wzSX^kEOJ$Yp(>ILR|p3u_^r~Lc)d4b%*ur{jF<0%(Gwt~ zrB0UHghSK*{;(rM7rSm_Vs?hI5o zks#P)bt+pKLE8|$#xOe~iUO8I!g2W4FJUQDI3JLqqcRqXXJ|&Y&9+OO3U68xoO(Cd zC*Nx%)8m+jAEo#;Xg(5s7-Uk=Q3!f$_ni+}TO#>I@;4F}QJ#Q@b7Q7L<=xJ^KNbg4 zXfGrXU|m~^1pL$2-p$yV7FB7k-7C~8*(U$)bku?x*)299Ei7soWowj!U;}Lrb)xINcd>-y` zT;cbBV-{t>h!juW#~o$w@b;N&Dz4~-fWoPSig=xa`j*t~PtfEmO@2LINlsM$nJ+=V z-CEW1aEp{HO|B+pIb7^Cy9|ih>>2{!p3XbBPmNX)LbyA@xI$OR58IpjciVoM_{j7Q zvHW<}K3rF{=PQ}fUW~Qn{P%k0&%dY6r@v>mZaU9#y9~2K^s0mNNtcE-Q2G61>fyR{ zK1!DMi{5A)wfOf_d(ADD5`S-1JM2^yCgZ|7BNO(#i@}6x*#VWk$*ESVHMh0$rfS51 zo8~tCYdGt!541Dd(5DME#>hlGanDZ=TPG*u)rQ^s(?w`t)VFLa?wl~o^L8RPM_EO`$y~_GfyC)g`&bxE?1$){Apd;u9;s%{q z!Q?kYD-vg-Q6kUQr=!daudmb0*=Al32Ru5wiQke3G$h;e2ft9e+!tcKJly!3V4IxU zbkq`MI7Md}yH5=ksYDzdOw{bpP#pT|$J#$X_vI4c2BU9hpLsjfxom4bvNkdOvpRJr z#zgO$3KWCvzIor4+M>4e$7H8xS1E(4(>y*SjeF78mOBqJFCcD=LZ$)R3XzKPFWA;N z_5FlrGYfm6IM<$ahhY-h<9LjhR$rb0Vscy;cfM{jwAk;t7EgwI0J6m#BGN0+R$xhr zare@j-h0VQ=4j`LSTD879~ps&BCA%|wcVk75S@sDSkZcx;nqBm!|Zt7dGfGMVEI%_ z+xr*Ovr;;X5>x#g#NVZQ`iJX(lx)hk-2(2%L}14Q`MY=D)6Lbnl2g7+UO*fky{sw- zZ(zb2u%hKIKk4 z@$^7B>VkT6Yd?=`ILvh!lc&?GU@k-nauo-GXC9T`pL#C{75Z%Oy0gCtUY4#$6^s*` z-ZZQ#=LHM#mJ+QkUZ6q>!=COX3!}6c=^nZ53~W>0E<89;?I33P{~NjE-z%K&ugB|m z_icv`MkSS%XD)Gg24wqrf1I!k(Tl@NSj*%w%E8@XRN2|j3#hnr2;(W^aJd+YrmzWf zO?_;FU@>-gLU%;Y5M@<~&wDah{!GWjqZ)gu#ZbRkf3tcJM@EY?dmH+pWD&|#Y(U7b z<06(GYR>*qzh>NI+pOlQ{h<&f6o6jOn?$Y39Q9{?RD%mE6(cOF9%=QdS$4LQ`Xndf zK~(FER)HF9aUlVHnr~oX^A%|(EI53g@Ajfe1e-=!VPIgev9URA$49W;Jm``UlS?<> z?ZFjh2UTlI{P;j{<>&e@vb59Ad_AS~OM!B};w-yen=($dd`#N)nsH2exliXtt*SQY z_x!$zhGCAhhv^(WPIFGe>25nV#oo1PT3AP+krfrv1%+mfb^v;_S4bq;`{C|wkdTo6 zdrH{2xIzghUTWlH_0*$xezZq=I|B$v@RVR%z0TrqO;dJi zmD-3PS1OmAEl-wf`p6f#!L1ZM#hG2Z_F77g({%yggS;P3+sm-B<3 z9F3PGWZ}u>_qYy8l7UV8+#(EiTJDBfE^_S?@=S?XIZWl=|5}%1dHq4wQ8te|c5Rm3 zdYC(j!la^0R{WDyHdGw3-o3t;rj^>MPzTP2w<|QaGY=v?WGDVvki$OCAmHK@&;^)r6y>b;QScLdU zB0gdQl1?FZ5HO1{HjBR`FkNsX1l|r_<8|}ug)^6uF@`h6;p(!#>7G(M7)r6#c{iTh z+?7Sl?}o=Y{&QfAOYgexL$8UsIpNi+_e$|6T{*g@c@e0zEx|C0J&Wt2<2}VC^3B@K zyTg;JTky-mXgWB1OfYSiC#DV8SIgNO<*hSvl<3#@L`AF2|MveZ1WB(YI&fgoSqY!s z2Jm`1HzYYn_|ZR{rL60?xM2%KX1QeT@2o_%mU!bgJ2H^YzkJ(u8y(KFcGh)n;&J<9 z;T2Ebbac=3<4$hNC1pc&di<kI3!0yxGr61|bcYic zF^Cp!^x2Z1qx(vRm#&PJE_7!l=1_WyNHDLb)arbnuf2$xBO+`>;im}Z9HE%~0*VC) zAJaA>X7rZ8&U6FZY;E`e|F-ta8_ts@fj`c*hdpD&{1JmOe@;icX%sioHV3^Y#d_@( zF0wh#?SFER?5tbbRi5?6DbTU$N@z7I(6qI+jeKJb($Mpi;N$YXwoxzF>`bOFq~A*2 zg}l7F+5uxpW=d4{^2YBDSIanF^qp-+Z5to1bqns7n|zO`>vd|mf4{F~NsRv_dH#^Q z9^*AWCd+?uQsIABye7#r@4j2%YtPEzKodlOX7spw=2Eqs#VJ0&ah4U<*^sCrKQ+{v z+{v2y;vBz3WBT+SskthICUy6f^J3$({Q6h01`!$I)5_0#2(B zHa35ub-O=cTpiAWu483w27w>Ns&v^**>`2&n zG{{x3@l7dz8@yaUxUBod>uYykK!-RZ3e#+xbV)Zc9YrP`L}Rte--0i|lv*q>a3|3n7W&vg9wqb49OofL#%$lO+-@Z4a);+iQkyN@eP@dE;w>DyekTux@3i{XjzyIG0FixE8A}`xLITBxC{AK(M=S0YAj4!#(ZH-65Kgl&ZE_`lk_JLpf9X)Lh2o_<}}hJgyT?vbO#rd4W0zNddJ z?C4+~<;|t6c!iqEXY!B2aEk4UKWeOvpBt~xa1oJ=ri{ODy;XS=YegTc9xRCzYFu^S z>QIB#Q=y@&9fC?M`b+dp18kh$w=rGY3JJ`ewXBa;X;Y)IJ&|AV(e#wazDjAm4nOqc))}32OD9dB|`ki!Flh%mNN{Y$wV;W(G_FgK|;Deb7~=L<)hrk@BjnEqfY_@mo3H(1&0 z2OH2^gsYNEn_HowGqxrqtL;Y+bI4&Nm6#uCh(%2&Tfqt8|9B=DibB{22A*0>eMdNH zxj&|S9S+14Osg@WmC0~-CJS(r99|bndL2Sy7Gnr1Li*94@ zg3T`-V?gNHmKVgIfo_1Es&RY$ql3Fqx zl@rc ziAh6=r555-JaFynO=gVIj5pcQ|SeOBM_m~4V7#v(>5^!kZUL<4bWdY*N)vUUylSTObG z9Thi>J78^N*JHve;4s`N;B|1!$Tal{RF*%P8eQa5v^u+wVeAuWZVEUzR@*&!oJ%rD zA~J5l>O-dKg~nPytPSG6`>A{$JP__@ms3M~e*ZKfQ9fE;cu9z+gGSq~XfwHIeM0XE zlXLDZGbN8xs2j?OA6nRz5Tn7B@GUvKIflQn^s}AmdKX9=j*NZyoWJ`a0bXs0+0w+Q z$!{t$5<{D2HbyC!A`xjtcgWKo_*9ah?m!2=W)1pT*Q==irYX!HO&U+F0D_=@zxA__}>vjR2t^wuQ>>^dtohUCx0U z%#d5@8Q-J!S^aZ_^9SQ2uX|UUY!u3FOo7_G+6k|>i*oo`J}`f*9c?kWOYWW6c6Oi+ zjZ5kn97p=c!oaCQN|D>)vsD%$QE&u=;}6= z_?0NlU~ma>lrq1^BM8VBRZoFa{LCPW6t?dT(a%9ji69*H(bTu-er2SEmT{$*KKvv# zHzJX4xY!(w6TXl7s?>s{t#yp4k13}|MAb*R{EI}Mn5tIQPJu`AUiL1SD|P(sn0kr5YP0g4 zsOyhtH!tS<0ZSA_Yz~Zh-OrL=>B2s`5=;&jVJS5#5h?I|O`hAv^vZesUX}@$KX3-Wz7rUH_No@qO0zoQEu4$z6zQ9+#RK-`)>b z#%vJQct%q5n$Qy<{OO)2s^r<-0%=B}izh9S1p@N3a~dq(+W&bYB|T2Y5G~Cs4Li@Q z2Z6b*&KdgA!NDQ;*KJJ8e~~DgCa`@+8o}Rnp#x)l^;CJnUZZwE&`ezlmk6oZjV|bAd1tB2B<)GF zjR?)08(x##kpNk&CX3KdB@l2U*0K3Te`ymdg9Hhl933F@pQ>GWtQtjmD&kBD5&)7}M5NWVp%Nw?3H@+w3oQX+25w%_Bg%f*N0SAQIauWYj|45Z5>5 z#&9%*Gnf-~YY$Qw`t)jD|H9w@MZfW6cCAb>$L&ScOK%1GeWm1U-6nt|_lx(|RAkw^ zGkh`3OcpkGVO9KdES;<+xxra_OeTT!k*Sj%8$^~bzwB(g5tY4*6$glK%G5#pbti$} zKkcQV7AgdE99i!uu5qvBthpgaW5WffN4vLLhimy!ZXEshUM1SM-)W!^RefQqrTV`Te@gB^3m41FHSYiV zn)o>bl2)*lFO);{>Y-De98Sb!Su_XKxP&N1Y+R7i z2{?s~_g9;L)1sY1g0c3O$E(fYJ<5kYoqUche)07c;=je$g3($?UuG+reTOQ?Cvtgd zA#{ArO2S2T^=^Ibf{W4LYA}O%efyuhJv58yF!nFKRqf-4-Zor%K_fJw`ztr$I&YB?3z%U54;sq2vaRj2U1}T3{ZEsQ1jML|8EsC=`Pgkx5VibmSzxo0O=IJw zE`1Ba5!!O!K;5wR}WT!mu3|6*;NjjV|vFi#J$_ zv3bI&D?ib3p5!PzjRY=07q+>*e?axsxTK=u4lx)vn2Xh9j<8AX&){D-nXlK?%+RWJ zy;N`c*GkX%9xE30^$0P!K(EA$hp0o5p(-1i3bB}k=Ik;EpL;l^{Fh@U} z-3Lx!1{RHU+5D0UfzlsPnmxnAQGhd;zx7L-l?K`W^wP&c_al}9mrP@VvC7vPuYD`1 zOlW`{cVl$zCoKFZQ?j+_@I{@{UT@Q%?p=CpW+tb~r?RlHGawCb6vgGh+hWVK@#Rb; z=Oui!u#C3lO$m&F%NN%uMaJpqqHlMuOs?jNnCtj6o_b^g1`ki&MjR66kw(86k1PupDg~`0`wXST5yeLiVrtl&^&&Yx^ z$wl1O7?6IdeI}e>D@g`GARqkBCzZ_Mj|6i%By>SO%4F2|Ej1as+4G}6Vaom8V{>R; z>c(_Y$d(a_fmt9~qN%l=j^Xd`n|GnTQ6fF_NE~1GRNC9Ci(21rZC2waOz^Z z@Jrla#d~Lg?=>v%pnc>z%PLax=^VsEu_h4%<65tnl3 zD#l(YJLQ#}0HLA&{<^NM`I{n$z5TJI6RKHNr>c^gZ8Ng3qp1tMjN zBH}OUe^ApPCSMg(pNF;s}DcP?x;&&^zzuw*ShAT6FRhTkl`8enby1m_s zEqiRLhpbQ^2EY9ed$D3jWBhGzYnQ3=1Wd5_JgNj!BA7P_Lf0ZOubj9IH%+eZ4{g{Y zPHR-BHEbr%F~Bx9!h^&49vXLQ>P+X|_M{rA>i#?ED~ zcMk9X4bHw*PpleyKfo9cg7u><9*jsk?9&2KBR)Rc+QB7iXH<~o-t1RqZ{LWF7(!5a zG4R&DDbBoMZf3~{EQ3o(PnF@Xa(iUH^jCKIP&9q^IJftz%FLO~1;-+!`q>X{fuuQ@ zo4Md*l)Oig?!ohVpyB(IvP04oWn^U^)>k(*)3pA8!Jq#!mzClB7W_JJetns~fQZC? zYsz>G$)Fc7wNk;Gnh-_cDufJOZMWJK92)x5xF2=qa0sb&PCZG6ikzJM_Fi3A>1#xK zCx6zOp=P4ttH$|qKI1vH75#{Oyt_)pC>#TvR6mhw0Y;0f8Y@y%q4B(x5igsT$(X!K zou4+=LTfv?K(TFIn)+?1@Ah?B8o=H~e_vs6tsAXYyIwvNkWQ9N23Ml)2;05TUNy0M zkC@EfsTC6VLzH2;og3Bi)kQT7PspB1aGz#v$@1s80V)Am(MXUTR<^KEbV0L1#n{?z zIJsFPfMPM@H3M-f(^%oJd>DAa>TXZe`9w`lABd951#f)3!;XqdG;*L*)EMUy7(DW( z?dX9RVx9CQ+s9StU+c0g#R^W|tYsQ#k9nH_Og~4RKjJfxIgo`HZXk!p870Y8s{L-g zmb`ygou&`+4hB~uQ`M3s799$i8YrfFw6N|#%!vRl&!HX{kumxo0+HhTjt$Skkld&v zh?Ffzm!E7&fvl$xOP;c={t^Vu94StUNo<9I{XgkE!2rfjefm^NWwR~!hh_f(Vf1?S zPhw_Jh>cLPg;bu00>HM?_{}Gt(ou4OpfMS|p|zWjh;AQFHas33nF>EsFtLAa_H+ji zA$O|u-IfAV;+E;21R$hn^o)M_=H4@B0&n`^T)3&L~LofgGAkLpIp$$S7>)3sVx(~ z3y4^=TU)N(XURpXv=o zv-bsyKWI=J=dxA%JcxTlu*)! zgJ$BJzmt$Y$rENk4&38NE#$bmM=O*or1%`_AFrl~Is2`F7-h)lhxTLMB`UIk6ijI)7EyXb5RC5NxW(SV8$eInCBL{n**=Ad+&5LG z!F)JhrC?)IE{)p<4_Jxk=VyV75q6v$o6QQoe5Rkw`3YY+}QQO zMq`&UDQ_fiP|^W{4fol8FD5lhW765%e#Lf0_9^4*r`VlD=$z`u6{mv*(!Cdhr^2h2 z)dO2Im#ogf2)O+xZ+rQ5zR@H`m0RC|6J&k<%!|dnv}#YNBgt}R$A4%!_i_5;kJ`Hg zzej|#FxcSRV4f|}k6f71PHA8dp_36{bkekvPu)_~qbYWU_plM2b-X^FK3}2j$7VGW zM=2moF@IJ6YT-hlyU?raL-)>&I}$?d3)h z1jAvw)L{s6^`9wNz2!3kh}!Jz-tDr< zULKu4#*#cutZhjHn9gQCMzrmulAHU3-Qh~)y7w=;*H%#y{aM`=2gmLuvfx<*YjU3H zpOgLZpQ6LJ3VSc7llr96jh!&*P`gBF-J8=iw4YntZkJ?aC%zT?$-x?+6i#Ue^fm>8$EQl57SbdS%NO94CDKDgSooP% zttnzW>SRD7*%zSEgVw9@d2X^YZKxkSlpmvCcUpXI@tE9(VSoz}6IE11?+!z&IxhKE z3!LNAEM`je?WNI*&C0h~=af#)^@B%L;im_cl7DRVe2gz{ zrLw2V7s##e@B)Hj(SAh8VwK>H${B`!)cpmixl-Jc(x2TahB@l2Q(-FlD!<^SsH7$L3 z?@D|qGwVok%ykTl$%0k@@qx7Q^BC~n9L!g(i~HuJfBjfsc)Zd`eX@?#bpskJLXqvg z?E!&UW{R5Sckn?@8yWlyn|u3VIYBw63!P}fl7G%B9h-SPw#WcSvN7_H9pbZeBOoZU zi)!u7MbK;Xb855En*9d;Qr4#VdT;^s(=zvm^Pm-6G#>3o4=v4my3h!?@j1RK9titH zXnJXJ7HGOY%~G%imUkgLH8=NqL3^&{hYt61mO;iw$F*WV$jX(zZO0SN`w;bS#$q_W zhoUdUDZ*5MJT(jB_H?YB@W1IU66zTmL9ACFU1{Hg`Vy}*39I*a$Wic#?~3TC#%)2{ zQqIRr;OTi^(#wwz@C~(212P5C&ngi`c)uNqAf}fUnCrP~BGLn2(}JotQgxkQM;Zbw ztO0OTNp5|m04&_RB1_y*LLf$bux@;TgwAF^Ks6HQx3li0%xb*{>;2u85L|}&zov`j z3#@$ov*aZ~-UV@OII z4KP3IGx`)>9(zF9`O2WNj`mBw=nsR*X%^cGRZuD@kW|=WF?6wE>Fbi!=Q%AJkOle`Gef zMuMuhG21VT!PkB{9K-F->9%(!ew>eKk< zzKDr~!yA7-V>nAYd(-shCjf6jRvSNoP)26siU)4|d(OZ8zkS;)9Kf~qiipKAP?`XA z1Zf55`HWAC&(PS+I1btcQ23pCol_SJmzrYgp&MpfeOd0odeVhn5Uy4SoM&F3f~ZiB zib*pZm-I#W)`aTHi*Mhc$mMR$^zU+q&9fwXsPseG?D=u?2}SDgC-M!axZ$0ai!uI8 zUgtiLJ%VOtROPeydP9)jO3BH+V`YuMz4fqLZ~J6uNKOy~8zL6i*vLylLUMb1yRowq z0;~n1qM~o$;I{sL{%L=`^-*ore5jeW$Gi{Vcvwe##}%pe&X{O`G8&?J&S&qGMP;fioYsAqH3mUiUe++6@ZNO*t%<}?gRgwNn&$fp1x9P>~sK{jKbA`P9 z*_d74ML(RbaEF*>AOP{hlw!%pgv4vb4x=ys{@Rc5v!Vs;1f@=|wDOX9aKizV74jX) zW6`t5`R|zW!|%86fnHoaYX}-@rog3H7FNkrKehB>wDYn`L%hUT4Gvt2Y=~^((ouP7 zI<-#Yse>lBy!ZGX%SO{iC}S9{?nZ%d`#TU;YRVoWmk@_<1HuzfdpQxVP(^{3|Gzy>2lB;ABf z&uEToC5K6<`VL+A5}Xp=Y_V*?zFN~_ji-$xS_rlB1LO+TFyi0Ug-`EuM6dFs0GFg} zo+;4bGAlA=M`1qy&FRVz`AxWy08Ps!1vQ*38YWL?gf&RRqRNNPJ<4W+Y|EBp*X{}( zycrAg{%!88C4vJg869UN#2%QufYc@ocV42h_G0-bfFK-Ie`Yu@}m> zvJkJ2y@WpOW0~ROk29hsM|e6Z6a`eQ!uAl}rkqA})ag4p;IMw;H@{}IH;9WdA83Hf+bTtW5q z_SX2^IdR#o45YDtDbmhU#KRNOu9z!6Nd&va40(F{`)e(yspqQn(L|2sD)8A%;K6{4 zT!6FGJl^kI@T?R8sbO`F*j?v_Z8@FFg!*(baQt>>gxP|{2d(gPgm&2vMHML*E0>T1 zRt=jA-hWg@pYl^gH4LO#fS2f<=ax(v8B^3|77VTd;pDD5aW<=+5Jx{DxW z(kFf+4J&5g;9t?jU?3Q#xxQ3rx|=mx)>}B>gLw5 zn1>d?n!A@Hk)V*RN_0bH=V!u&bU{s3MsQ;H`L7zVic+LU%5cFQjC zTg+Gh+der`k3S5@m^$~b(SLlWKT#M;Olo1_m>e+IiEr}#5gsHCvuyHrUj-T#G;MgN z_j_MEou8mkCy_Mc;S|eHaojsV-LopyPA+);>w*iu7bq!H=g2x!FpV(yuFN;xk9QYJ zbf4r;hH_Qu(uDo}TotzBb7!rzTD>^Irkcy6`PeLe_x$Mt;OC>_6Bb~&T(<|b`{lpo z)PMj8^(sAG)6k7Xha6NHxZSI){(7M3{?t;66l?ofy!L7AlUb)Q(zhiyIv|x*gMw7K zs`f0~WtDxtlNBw$PAphVFGM)zUMW8BQ|QlgFl~yuKC=hyy&ptm^r)q6(OI|jpM`z} zUk3b!{F{?T_3=M;M|y`3z}@^KRAC3O#F-3P3j$WPNeLGZjq9HFRTDWkuTO{0B1y?v z*k_A{*~S+Voh}~OC(R#YGCcmi1~p!d!KPntu8K3tg%JZbt};{3H#p4{bPjkD5mx<= z0@S~XvA`v)+w`@dut3x=ueqXm2J*wUA$|Z@iW?jjmZ9CLh6xrU17fog%=zhkKdek#6oe&()zNf5^~}Hv z*b1WPH3M%GE|N}MLWbBntnb0`d~46G)Z2!?c^z^{hBq_CkvCVqibhi*YkPrAfkdsI zs^^#FLBq7EHHw-J+$T&-b4)9v&9a~zVqDQ-sT))T_D#M~;4=jedF|i1UE0Y7AU3t! z?C=4pTHie{L-;H>e|@@=vIpVOJiXkqc<`xU*O&2%AZQ->W1$*r`2mZN_kAtg9iE&( z=xZfA666KZYsH6=CP#f$hwZI-NEnbWQrsXue*^fRd7S8RY|H`O^3QRDCa~v-SHwrM zI2{yy+iYuS!>P3O>jqQO2)34tF z4(P->0_-c9tQ2FlX-^rVb5U_Ds(9 z_YhwAwkVacEzS78=CU09Icvh`%gnIG-yg5llh)-41%%o4H(J|<_WK8Vh&~Qd6|Udhu6Z7b?N%d}}+G)!M<`L2xDFj@_E>l2^UyVy@{& zS0YxWT9&7%IfD<-ryu)J0QkYlKC#`ijbm472_f89gCfL&QrC{pwzv4;wTQ3I8X1+7 zn)Q}1YfMC#et>a6M5uFkY?y}k%Y)%oUrg*On%*bTg2`&ft-izTkI5jsZo!Hucw}Ug z8#~eLf>P(TQUXUm@Y+zbu*8`Tr>N~yl`-BRh)wq0V~CL&`p)oi0%P&3uLk6BRil-m zk6lZPdjt!(1{3U0qG!%DrPcqIbD5hf|3Ph7z7#FuHlmS|%vv4m{cC!?vDe<>a=3 zp){7E{XlyA@?d(U$+c_~%NnAjqy(^wY@X*PPEJlF-a*AYV3=QKCK2_g^bZymG?tc@ zh1nW9$10?Ns$E%gzWe_0o=UGd%~J)_cy8|t;fMKn!;-+~cr`ZHh@=*55%kV=Puusv z{Zi@L4E%OqQL~ardGdDN_z8m71&|d~5;|PewjaX20+}I&fOwE@z-Z$z@cT~DWM?xp z(gX7c>cn^uy6rem4T;WSpnPBCaKgfsiNf59Dwsa-uNZ z=vuqy``tWIakO?4m(v5q&3ksV5fcCazR{1oK4d*Nz2bT+K*#q+1Y?1girQCsLePW1 z!2P_BNz`a}SWlmg#zApM=nWPp>U5P6O3_b}j!nbhV7cyhM?b|n6u-X|oj@{Fg3d*y zcZ#LVQ2%WAMtirTrkq3MM4jY+b}odOLXZgiJx1J-motIQLtu(l)v@IYw`?jC6)0O; zT3X&8H-nYs1H)j@)<);!X*U`&KHGLg`#31i2{_HPn=PrF*6a9eBO?E(=%F7$aMA5s zXO@>j7G9y^)Y`d1o3k4 zn1eaL=3oh(LyTGK^frv?2e4B}!%_>d5dlIOyw_9{R1?K_`ch3~I~ekIoN4a-sk*i{ zn}eMu5OWUipjk$FpcMu5zc+-toS|2X{fPT+_#rk6Z?0ZhTY4|B8fngc$7}<#?&gn? zay;ZdK%I^Jd&q0eCDtkh$9ZhufBcZCD3=q!MMJokkM-Ks8KSeu21h7BB!Ss&p{=oZKS1{xOg)Z$pIOrN4G<96IdL_ z0)!Q7rb@_QP9{1|nZrE7IhttK)H%p6HwxQfSi*5dV+DC?;@M~ZeH%@{`t|L0?}Nxb zf*tOw+X`5A%kt%6-zH`Itv zv4ueTzFhuJo#1EbAHiFk&uYIouwGMh~!UC@7 zBN(wm)y(oCN|EvZqrH$p6N^k$cQ?|DUV}qt(u;-!pmLc$Hz=M(#3C&JvNb-ODS4GJ z(BgrYH5&vszUy&7AM^s3S;h=grN_ecH?((4U&J8=uvC_CqWk+sV9_avmkUBNd!JDr zWZ76CS_vF`s zS0teG;s?CAJuoxZ`wkZK0z|8~a1Z6b{z&-BQuha|^f$@(LVprq{pN>n%>$Y%KsHda zRHHIcm+2lF8OmigJ6mf>fUCwH&$cj-Ava*BhkokZ)K<#ph$$$fL~Q)B5UqItX0D*1 zM30cohZ#dqQ&Z2gg3=&SmZn!T zVujYAMUXsdMi0xWuR3&;2`=IxeCwn4t5M2i;N2fz*20fP(?EMduqOJ*Z!hX|-<5@A z)7S(9JW{$SPH)%Op1AybpF@BXL+7Jy=i*SBF?TGh)e{Zy`Hk0meFa`D0>OUXu)S&u zBN)WAFISXvgjviMn}d1kgs^wRSL3u8?| zc#IzaT@{dz$;r`6AJt0}Q5<=yx>~g0p@pt8pI4Bm@cz07UhOL93O$k+a6{3HJg~%k zUp@!j@?M%Bc(rFfhma~f!*`qn`4^?>uvh;0Y}!!@xm|Jrj{skydc4*Yb#%L56$|l= zluiGT$SB`U3A9Sq)p0br9DGSj!v`~wH>L_@eJ)11dHDFiN(t72pUEBfh8w_n6f__C zHc%uUl7>JzA8ta<&}?E6G$Scm%gBAXuDKy6rxzU}eJa z;R`{QeE;p)Rt^mUHr5WMObAU0h$c3e9pi%|)^=f{#1^b<4 zG=u{7u7*(?UI8!;aRo#1E&hm&1}v!de3?KQf&5nE4!f5)wgqzP8iF^~pIzg#{_p4~ zBP8tjz!L)clJ=YPncXjrr`DPUt-~rfzlnQ3CZ5KsemM6En@?MsOQKfNDXE9u085)g zz@l$(@e~4lef#hLl&tZIT+yINIAJpmm(tJV;ePeD+HHR-8(V-JwkqVviiM%}57G(I z`5m(nbP;UNcO0r&fJio{qWA&^;sonXU%Tf>hg_}cV;}Y!Z5G*n*{|ENJzL>}Vh((w zQEKjrbc0LedrV_DXD2bQ)RA+Ol0T#heY7X`)&dd2;%GJnu#}*h<Syp>L?mQ4Yc@OFyD4#61~@|?W^LyA zgocFNUtVtBgcR`&yC=$a z`G(r=66bWu#SyYM-myV{Y84(wsEOZmT7`#u3_NLq^HCpWlG*;4yQ|hJak$t>`DhDZ zaU+m4YAm&h*}trT?in^`_Pg`@)Rn6VFOjj4_8iH#Fc38OX|_ zq2e=bSHA3R#t>NF9*%FjS+dg9)MPR22~r;PKJUjL%g|yQzNzkf>RD=eNHZxmMOm^o z+nOLMjPv8#tGfEs`gYks)>;|3M7i<`x9+*WZn*6p5e6P+M6k@Bk4g>44rEO7Fq0~@ zB=sFUQUp%wn@uJb&`)3Tr16NC|J6tWD^)`rSC*t*U2lAzbq<_)Kv4xOE+Z}jpnnGf zehMzGg)fhD%HVHcn>HFLPXZX--lS~YS@q1ptnZ8E?{ocj1r~^yFXcY{F?)3RGW0XI zSJ`yAGpuX~D@{lksL_K=74CC*F!y1D*EwL`76@PlauwY3iH=mX#Sa&s3e z6F(}mC;EVChP!4D0$y;SImS$KlzG~^B(EZA?ZK@|;2=c?V(;XI&TZXYZjyx8ZMzpl z5;vr!vu0N`?g=a39G#r#1rCsl=ZX9Q)CFuFFO(-lyU}*MKLQ_Y(=bd$SpR$4IjLjU z{+@qwY^)D#uPM&X5mNxBTYAPyG z&*R2q$kUCelVk(r#LoMikNVE_9mgKR~-nDqUmCnYk1(4Lus^g)#- zLV@|4*EMzbQ@5xd-38K(^=kZgTQR2+X|Q5eN=mBqP83_*(8|i{%!d{o&@iH+@Wt|( zo1nGJ;PZ&1*QolQ{drrcp}w99G`wKZA-HD5UjqXzrtC(F;BsohYqB_uimFO4E)fh!AkB3pvO!KgveTP5HpVj9?|AQ=81rd328SoY zmfh^wYj;G8uCjZ+`r+CC`ArMJpGWQ!g;Ii(R_ry0v)@A7NO=?O#5bk`9fTy(yg>lE z?F~i0s#;s#_h|2Y_K`Qu>Jv8XPGZ$TqiQBYRHefOzgDi>>1s+UVe;r*PAFE}k}R+| z@bmLqEX~$jipEpRE!G%{q#6SQRZUF|jl=J;v7=ZY3z_^}84(<|SAd&QzEC-9U>1Db zusw|yF8VKjCPySh_g!*aoDJhEk04mN0A~dwwjb)I1av=#(fAoxZ&s&Mmbt~6jeO;O z5i+I2Clx|Ya(#Svcd3d$)l|K}iX-VV7U8DC6rZU^bbx z1JD*_i4gH9qVpxIYF6Jz_oL$|D}9Wfn5RfWc10STqThnppb#+~OX&uKFzE_mcsl0X z^_Q=S2wxFen^O?@i!k--_`p!!zBjtlm?dzAIwWpagNV@Neai+QCIwILp2S)Du|+{R z|K|3+>7`Zw#4KrMQmxFZ|#_Pl4-5TsaXm&Z^#V z$oaI#m$EW4#t&BqO|7l$pv=z83vX-1-TAfONrsDSVoz#p!arZ7H+p}$CpVCd{2vWc zSZJuhN{dS((TDh9O%7*VNGp+W1L2F3TAGeri;l7RyEhECBZaMmiE&}q| zcx-?b#~cNe78`Rn)v%Z@T;WQ@@Oqs9v6@;d6g*_A+^WnK{-9wNZ%zgymE1V z&WbFgfrSzbOHNK6XuPqp@zM5o3SjBtva_H6^D*zQy}!R_&~5tO)zyX4$_K_d2t1yN zs5IhZBfKatz?2YaD}Mpvvx=V^Lud_%NQ04;2zY8(ZPvk2_CT(RQZGD}6BrEFY-yLKY(h zO3S?Pxjvx(nzqW5l?9rRFSw>sc@v%J59nOPT%aHa;;Jpj5fdN>`t`|(QbVQsqW_wi z2I%Jj&bxb^Zsr_qt*uX#OD_T_g~E0>FJIz2o#5sTYD;qH12Gm6*syrHH#|AH2fB$J z=`KFHkJ@s`v0seM*QxgLiL4-;PK{hoNF#6AriluvoxhZ-TVN^?0OAO}OdEknl6uLr|qF zwNRxeB`rGHeujZ5{rM>0zxChuF=;@F z%>PcB^%lzPmbQ3r0r&Lz^x61gci8`J&+lqOL5RTpA$EhfZ9j;liJ=)-XL-5PG&x}@W8 z05}Y1mQBInL*CdYs*QbFp4H)VE zv(zv9cnf&os1`(HBoq`jkB~AXz=wm1P_M;#1AN9YV>R>UA9XvtQztTci3tM!k1ohp zFCQhe$!o|{FaOozLeFKV{+qJ>(~kQi8kh_0Ui5qH2_RCoFy zU_EBN$m3Zqbf|z$eFdnF7_40sr#PqhU*0ZGg@fS;>(F{D@f`!`jX5L#JaZ2XBRm74 zzvnvxLN+)!ML)N+v}8J{4{8avfdRyG$%Cjq27B+H-Dc;slaIn?;2RPWU6Tbi7;?Wy z*4o3x|3>_72DGd@P4k~Te*Y?U8ZVPH_X`6zsP#reXCsqyD;IzYdYM* zCdm!0p4z$L)#^_L-@Qvr4z7!B9~|InizES0 zQOE0!X=B#U7$Zn9qcWb5$^>-;gdB4!SRl5Oi~+SaT3cMdmtFX3hu@ngn4CyJ862jRCc%oz%CPY8vWD+1`^XsrK0FX&F58bDZs4r}Ne;m76UoeMY~^?-U9D}< z=(t}by(md)&9c$j#RF4$CGU%9P-lQ1c8&D;HD*s27#9_ z>C0O`+O$4*aY1QPRiayMo87FERid^9?jJE7xa;$|f^Cfl>LyOdoy~FSR?=&Mxhv;G zMN8g(rDHiy?R*#Ff}#xt&|+$4;39<`0VTh zzapHs;J%mRSkUlWMK>HpAB-`2T(ob6Z%R{;X{%_8WR=9t%N6yHAIda~i?jAxJ^L(I zf8SH5GghX_3+%pH!*?$q)Vc1^hf^R!fVun5I_pLAU*L4t zwGBLLA~IJ+&xPYIQisv}zE11z)}tz^ad z`9EPQq9LwM2Sp3b3n5)y|A`drzgD74bo24n5s3x6@WwvFAzT?A&cD0~XP1L;Xc*L$ z%bpP@5&vDHB(SPhJ2W^_zvG4ZAoIbO@B;NsSP++MM|bDKbN|R<__#4w-PNozo&=Nl z*C0XhMkl~1 zuR-&!l~NNj)X=xMsiNQPW=59!TE)!GOWr9v9xZgsb_XTazgn0F|K(Y0c!f~uNCJmo+4~kk&bGAFSQspaDveus)Y4Y2 zzZ?#GmgEbo$lok-8Ky>^7{>M85(^CSXAAo-Z8P7Lx^MI9=TN<)^TLjGw}v89q6WK< zJZ*_A#&Y_yF$LGgmvGE~R);^;>EqlR?Ok05!20+z)yI_c8YE>n3@()5ufP_@VZN-z zZyIX?gJ_EpN|Z~9QoRZcBwrmbJG3gdmh9L?X{Oc7Yy*>0wi)8#G{|Yb!63z&xAi1g?fd99-^@`ePip`!-780_Lh{0;gB)Egd5OX3u~Wh9 zg5OjQY=b47`AF7SLnSWxiX}L*`z!(XFqelew%Me2k!rQ&-(_|x$e~&4a@uo$ABet! zJ=x2JHWmD>HytFCUG2SR(RY}6c>X%fHkGCwy2RIVFt-lX73{-|RT=e)bEt|ckg`dM z@Pr@XBgJ~-A0}sEbJv%qrj}jo-}CSyBeiNt|BeL%^u4X+!+uDQaQWO1n&gHHz0la_1)w; zZMOF2NPG8@9nru4UBtm!o?m-)`MbV?e#|C{??2~qWn)t0ZKcMsJ<<4x2;kR6B$;pZ z7t?;l>1B*>^!57t9#r9R_P95u_j8E}mM#6PN7i)faJ2VSWBw0{E}NS71G#T(NOlx& zVB)v@qo$3>mg%v2Il=MHDr%uLttVu46e*{*l{Ysx_gg6z0vca{WTEor<|a{nr3N;0 zI4P0SU4zrSJ-=KoOvmd7B642xBHL7HRZASXv9ucNAvQ3AQOHz@xx@ws>*8A(Q zpBzHa?8WTFt?ySgM}0OGPKEAMM8O;Vm5AE0ls#U4I|An0P~*D;{-B{kM+6UaSObqS zM`4ZNi`i<0x#rBm+V}EF^8Pp8pY;~CRKpuqlIbG~TnhbV=;>5ClBkokzfHWxd+opO zS$%_eWqmY!FT3J4`Z}6aa!CGdF%_apvqif#29dC)W{RO@5Dc8cTi_*0NJwbG|Fd4# zk*!t~aE;?H(iU>&n4GL-|0N)$Opn$3RkgKO@Mt5`Oq+uf#ejr?iILjvgl&9E`q1|| z5t>pO!|w}kJJ23~z-Z(PzA||=_Dc}4T1=lIMk^Wx*LXQ<$7oTk1L-kOf6sP(GSN|UX$X~m<`HNvKJRT_~#S2BoRh+CkRB@>?n zUUe+Z*yS7-`-}hi!&)m3ToW}cEUfudUT`kn%Lzj(RQ8a7J)5hl4!2k@t`77eML-9i z6a(>($joH7i<2xjn0G`?XMMsHDipv=V>}o{x(U}Ru${ci?tX1BjXGm-`ZH^eQsa=H zys3jG0mV1^fe^e4Z_jm=aQg6ro%sl3W)kD;p*i=DH%%V~Iqdyd+pq-+;2Y5fL`{1@ zP&4{sEzuLr(^zgtDOp_9QEhLM!_#PG zp(036;N@gEt7xiJbeA@PQzO1$H;0tti4q1vm(IX{g$hY&4L8DwKNew*98X`p?Rt^5 ztaY>-vPqHxdO6T0I$$uozP`Q%|KROY(fa4I7}_heXF_MEg8^`Eh8V{SlXaK@T&wBp z$;}oP3C*9M*O6>*+~aT1UHTd}76ek_Ooc<;H~nyVFmjBb#u4(e09;p`gtLg#8~YJ` zuPEC%XcDRS-#Tj_I8{dAR9*ErLtOP%#hUZl8syIEE7v|^LLsvmUxEW$9EQMiouH#+_PS1wqBc8QBiRs z#&h>~a}8odYS3B!v#IH!h1yguWz9}tiz|9>b36jnJtp?$-QK=;PLQN;Oz-Q}%-f^? z$&4{Gd}@LC@AM|ktU$d2tMjR+QKnNKZdG}hj)x{jd0FF#&c$!JBvWF$4p%;N5y%J* zyo9f@b@f1)Pw5_bIx0FB(wCp&oD1e{{^-D&+d1&UYL;NZR4l#H6@jmzi;{(>G`}vu zKz?JJxPKygvN0c6muf~^O4Gg6M^sI%@0oeJ@)p2m0dR;!dHy^=j01GDg8MTp2J2Oh zA256nu`ysV?GS5U8x#b+!!NI1=JFuVCVh;wIbUW;OlQkqMq6F`D*$=++3jrGzs*}6 zR4rBQ+Z}ws7oMC0ixygF6H||wp zx9S6O*UPg>)8^=36O+U(d8I7sEqc7Hsm^I^E`IHttAV1~iy$6V^eR%70(S=PPZ0(^ zHhtA=Ym$-RVgBK=Dv`0bkUr=gl>bpv%S7D+rq>JG5<7J=#E*!!M zo!dp18}+})yILldeg9pUj7h%9N0G0&m%RLI8~OjpbA|g=J4?NRRA0AOiqX)&_2e8^E4^bctLR_oBK zk~(}pygB%Xrz>aFz=M~TB2hAR!Hx`M44CzM`N_KdJ_=ATp`DZUYzjpjUe^%%Qe@1T zX{c1u4T6~&pT9jiYLKbl>a9rZk@K>fT;c#!v4*R$ILe23q9EI__a1#aad*RFt28;L zB0z#X5aK;VxTKBgzxN|(a2#lEDtTJVB&pu;d~${SWQNsLLDAHALeW&YvY4l^oDVHI z#LcYCXiiZRiH0{fWyE1A|M2a~YPEXevJGE0i!b&2cT5qwJ5G>Yz*j(r1MeRbGYKa^ z2_6-hyga(sPX-#spPqM7PX00t24()3xtqbI9V#BK|LSlwa4sVU*^fGYr0cwI+}~IV z1W{STNvY$L=ExqS%v76`4gj$HFU?MOW1zw`XuyRW#c783oBMsZ;W` zA*?y9-u(C1$R4z~i?}n}&GDqYhEPIWpCN`ZDg!YHohm2|1+4CWk(x-dp|HEVESJ}R zp3VZ7^ZW0oYE>m^Uo8P(M)1Cy4bjc?NOZ}cS5j8$8G=$CfaNP9uG{~+c8*kU!cq{_ zRWwL*s^gjc7Y%iY{~#H-I&h*CDpFN~m`DrZAQqlIj2MaNThJqJwiH9-I5=KSzusGb z6MoQKX}Wk@1BJe)pn%23j{nd=rbrQMU}Pi=PI&doz0xhQIDyQy-5Lm+zv64=DV z1p1QeOG}cCsP~Oi>$@4lES#(JpP}3W5luoJLo>s{<}s&FfSok%d7YNRHTCxs?g)zK zzv+mtY~3agjk%puJ#Auv6Zf7IE?+g^w=STlG8D-Fv(SQWAsOnGGFM*UUk& zm{M^BwP_E!bg6QAgqHpbEKt;MeIM6G` zzLh3PAF!rq{gl4ic~!I$=j!cpMGwjnhZ_6!N-{gFTj>l<=`ZW&V$VJBa2SzUw*0jm zP~2im95oyVn)C1GIC{9uI?Q8HV;~??fG*RH*DmufXB?rSv1M;%oX!_KQzJ9mVhwmj z_E!}R{!=*q(upS)#306ECBH*6)li`D_=!gJF*MuvAq@ZX>{`)=!v+vo0N$ry>5!Di zIS1%i`vwPzr-cy6EP#3Uc!|S$zG+wYdOnqf1ty`3;(5f&h`CXpM4B%sb~aSbm~(2l z)b|!z9qrx!?UER>zc&@b4BPS3%hm(*fmV}MCL8C$8Pfb}$A`y9%UJV_k*qd@_7pqt zFDXcFk1Gu09MpS1)pKPJJ_ZLcBL3lzQz=w-cy|aZaPv)jLjqR>{tW9srbPBdubO!) zXkmbfa_ZexkpfYZ<%b$3^8dz*hkt}i!z?bUrhKT-x-6DARxON`qGX6<>@$7^MJl^| z9KkU`$9wBlee}NltzI>hx$O)VL}7HEiF|2y_fM08&)!j=<0YxU?87aA>{uAMTLeMD zPEWghRXSP*W*ot658j8yW)59wVveX3=)6eedC-u=$6Lt8T+UCg{r;yVZQ^n?19hgS ziCCOtd`i0;=fr1j_WSB#?afI^%f7ptE$)vyn8btDRJ6=tU^f?b8(Rv8gB6Wh!gO~n z+#0-}$VK|FHBnvIyH$}tIDT}A;p_)yclK)`?jc??rVhlJm#gS}k1xkvc#fwFga%7J z=6RT+Kc5jxPT=Qv;7SVE%8ChLREuLd_AttMz00RT0WV*e@rE*p(noyW!#5(Dxo3+P z!#DIXcLJJ*lYq-&xkAI&aS41B($zL#L#eo?Cc&Gq?SSHa4f`&6TD3{j>HJXC{l7h@cSo@Q(r&l@ zwV%$=wc$EpOzeoSqFc+_ARQ77lv)&rdeDAbXzh#+3>K-}D^V^5GY*X>p1AM4Peld` zNmIS-na+Qmr;NyjNkx<{a1gt@vlRG~V}0cd1o1c2@NWbcv*XS@uJ+=rE>#7dKkI?Z zvxE9E{Cpzpyl7pw2&s_jLN)l`&CZu`6PL=xJhES?KWWXaY&2{o$j0|~stpi&s8W69jS85k(s6v(U#oO*SBN()P zZ0G(J0GU<9a_PTJP$;*!*)87HGbT5Lk}L4P+Qr2@hDS^b0O*nC%|*-eVcXnRrRQ<0 zu#(X7dmB*R34IOniN6iQ*ixgVp*QG1!1eZeT(-PbM}C7)PtrxNr{CSP_;pR;Sw7@F zY2Q#GfO{6%Q)n}bSo*w>s2%^2?N69w86W?Gf^I+QQY*1HM(ztW+7;2zK4(6%4Q_a1 zm|A<)a#!z5Q$V3fpo6(jI5aP#)4$L#XlLfxc)(Gmv5*72&tM6SWt6E}CgMwN9cBvu zb7~sP|FC%hriK+dm5S$H_DkiF#*T+Dao}&@}9N zrvB;M`1#4*_f%9tz*8hFEG#K4?YZBlAOfmYaICPfu!KgF7{fwK+S7H%KV*CNfX&gv z)ZX(aR)`p!6+^!^_AzDoSTqpBK;_> zMiP6=v3Uo|Q<*+tV7tZ*+vDWMcJdA!CfOVPt;n_QxG$@V_XwR?_iAH9B^K68DHgsn z1V{WSU@gieDE^=)t(9r@M$*N!vPUdf$>L0&nG3-csCoOm=^pCdD*$`+Pl6*@G5r|W zju_#xhCpV62788ORC23m1Cx@Y18H!xj*+FHtfPrfcudf?gMg0RN?OW%9-~&(+o`d4+QQ*j}T|!G7m~mILZbc1| ze}aHi?d&1;sGF;biACPcCDCd4eEo0kW@@~dnAybxxm0w7yw>k*Cze_1-S6az$V!44 zS2Pvx;-9_H5dFL>u&};@w>28NH*Xo$#vVt6^_wka%0`?WoXPp3c~3oK8yYofCR4ov zsNUgV1DF-w1G0&8F zzI`2`(ew~2^tZR6BB&^%3~ktLv9bYPieV&zUtfEa4Fm*bsu|z$ z3gP&qad?Bg*@YJnX~Fv~w=yIg-50&EsV!wFLGtwn(p|;PciU8w&XSjME&Bof{Gh5D%Khc7l;~!DbbhBEp&h_O}t64$Hi~NO} zSj|0AEW?E~=ruqL_bBx6S0q-!2E!f!V#?sF53MbvJ9u?KBFl#~s{pa(>x{iSa z$QFG5uS$<8d24H{H%}}ALcnSS59n@>62I37WDKCiz@ofjCY{=Te!3Tgcv1;9;?Tr) zW9Y#XGc}6aT9bE@I#D`N+obh@16spx$jkfTXf_<72)E#TxHJ1qWmdsx{)_Hk2k)g@ zm0Dk39*(rrXrIBdCbhXg8Re3C75(1nMdj+_tM2~( zV4#t$HJcW%Nxg&1Ob8AR9j^)|~%0Py(ObW=(V=&fI^Zp{2%H`}1ny;XA` z{=$~VVKtD&?^V-)N5%rKK_9T}o-A_{xL*O@cGLRs0W4Id3&$LM|iiJqz#0u|cT*;C04f1#e?C*xwAs zLl(@lK5(3V2p4d{D-kI1fy^15g0ubR2XrQ7C(zUDqEiLG%XbPfrm27BMkYpuYAh8XI%^B1?Wa|j zduhdgEAVpzsFJhx$6fK=w)ta@_Qo0fFi~LxgSUXcs?ceS2JS(poe|t^$L7_6%3D~M zzRBL+K#$8^R?AtMg6Y=Ni|zIGu2@Qm{WTyNihv*a!UhVdUhwJK+n3Z=*t@xX`1mma zh#Uofp0)>sU^nZ^OG+Zy+S*<(RpnIpI}i`#s?s`42E;ZJ8+2acOItnpp4b7K8{S1{i!pclj*7O+9g$VpeqT^W9n24e4C0|ZVY(8|DgN4S-RZ)qI9v-3;E3X z%h9IphZ{V+(Jn8&=J0lW-a2obvna!!5~Yx^PDn%E;^FZsam)bOH_y%xoIpt1I3W8| z`Mo&7^4x6@DSdtx=f?xm$--hLE=Z>*ett(MIjoZ~MgzOr(rPZVOT(!uP9-kCE=$CR za)@q3xKP<*4hK&I$M{{{Pg+Q!WUM3=)!zGv>Vpdid>^qm#sV2skD4pOHhgRI4<%$y z;dth;=zt@H{T*+vP+e%DGOh7Iq~UCd67YwFfKc9GyArNS*M1tyTBtk>gsMoWsQJKo zb}M>ku?e0|u1JXcF?0bCll}Y=U(0TJfes3fNtZ_a=_4{Id_f(;VQsT6Rh*ai709+c z?QS2U7sO=BYp?-0ySj^c2v00gk>|0s%lGeaCS#mW#&~AHnz#|&58p3okYVp7Hi5bk z=B3kbd%7gp<&UJ~ie~X1w}0xma)X-dgLhM3Yu6iah^XmlX#u^o0At6JTiae>HW%?f zahGvoQ^l@w5TWna=li{&RwMjn`Xw{VFAX$yC`PBQ(zmLAXc=!2F@NwsRXydcA8yQV zMIR!d{}x1p#r))PLG=<=NqP7l>oDHGK?VWJxO?i=rWMvX)|fS0-I6vjJ8_y8*Oupr zi+pirQH(@3(QRo*DYzCx%%g)Nizua{;mU;tC2b|@FeMEd%}Gvj-f~V9l4{{}LC!;% zcE{1volKAY3dO!gmV2dWR{W8j%ui9mg*k!7Aw>N)awKv*BQH!RXnS<{4{x@^I|&t9 z-yakFbcB>kRN+x(UklMCf5(x|GTX-+|QXA*(tF(Tc{RU`bfFOgWnJQcW ziZtIhJS~Oe)&ARS<8a$ba!;U#?;N%!C&wRn@GoZ+1kZn&W%KXPOhtgiZi(6zgk;q*PJeLZzvY>-nBsYr(;VCUiT4wjw=Yf|#lpo_oKx|iIXvqtN~v+b?LV)VLEi%_ zoJLW}QaJ#98D@cxV*CqM$9$ovQm`>AGzbZx=lus7@?13k{@!m)!lW!3<}IdHpn_$( zR?DCB0sU?vRyxtr|FC{?GJ#0$-39*qXK6{N(`ah~Bt9g9z8M7tRR6gfD@z<(V#@++ zOC)t!a8!CaF&K6P|LPSGAT8xg47ADtTOK~M{udxxW6)`cjEj5YkKnRfHX~Y8RMd9X zgX(=T{9$o%akeE&mCgiAJmI_j?Q|{Z0T;svSZNSf=je&D64Lu-8C77q-CU-_V2P52 z+ZY!GdBbd(R`#!Dn16)-IQwyJWZT)?_Tw1W0WBk{6#ewpH(N+Q5Zo_X_QpvZa`!oR z&YM19TH6{Pyax!s_UCw+9W-n1?;u8TCwoL^=lkIi(>zW-T%NO&$E$y*4(|wDzzDx# zhP1DEMdVd8jaI~kzscq0s%6V8m)EkIp6_6M`IoQNAPjtSJ~8gYW`-0iWKX;V8zdz6 zFYpH7mVacmqIl{)>1@gF`O!nP{OptIeSg^V*@f$C%CZx9jHzO&U;qsm-j5BxZUfR2 z)_+iYW#aFgY!<4O4PsHHV>p;-vQayU*Ywhf$|N>s6kOesmQ)X4_?LHoX;13Nfm+S) z^CL0xo7IDB`OHJEjJ2*8wjnkZv^u^Ec9uXFX97GlvYB*kx!~SlyGvdH@L`GT$TFkvCrmK*1(ht+OjU51%FatUB>9WSVJGV4+Jb~!r=a7c>ZAN>pLJ;iT|K5-%dco$XHlk|D*dIvqDXdQzp#+ z(*p3*f;kw;wI?fYXXz8xCLXCtK5I>!1g)T5lx5LbnJv7=BoeaZmEd*at=iN7z`>k& zap9=6xP!Z=WUE!B0!brIRnga%SFXa`_`%jNO$(XpPy;Z7_THOBA~AWX*N`WsClG@2 zg~jNX)!jL6rVqV%pK}!daA^FZo6$MRCu*d2W4{7&)I)zyKt zIz;4$$Zz}BZstHgA*RZ;?6noX595cbWeMJX7hVE)dvNnnx)L>J_JKDRrltd6w}%JN z;fDcD7x+?COw3`k4;hr?3KkZnpArZ9`rv^=6ig2JmYq%h0tf>$NFHYODbyEi`GFRN zqw{eC@xFqZBs{NLc;jXuji$#s^1sT2bVEi z^3lN7WH}tO8guN6sWoq1l%2eHz8cs5>d;I1Z@azrmXk6G7_AW8U*|-`8&p)w?~%1T zB!DDrzdaC3G}8>C;g$WdkitUNmE)lpK=kH_WKI_TF15Fu{&5=nkorL#LjC?dtJAJ5 zIIqFLa;(1$)Qj1mfasjlU+eS}+}*vdCU3<~+qEcu_FcS%i@W=yRB^otsh9yVM@$K|Ma!-AaIl2gigNx3i^IFAd*PtF)|Iu~CU>_y^XTa4mrY}U zBZTcCj^~*!#q;Fe;r_^JIR?^ilY@xcvAG`TDnRxP4GUwPg%#)q`Ul|k64la5UCn>J z6|s4LH$CXjvSB{-O4HG6eOiNm<8smdzmiIo1X7Vrs?K5K$(#|Noj4teWb&C(q{f>R-2;LL@$(8UZWqCtyyhPn zY-)sI9$}k@No+FS4Bnx9*u!BnA3l9{&q58xAJW*?Xq5*yTU)1oV6Z1-9pkfBpAJBh%ol}~J1JCT}T&X6bts6dpp zwaczKO1NS7cX!1>S_94hii0N?EdzbuIViIuU$Dub1LQg7RIsgT&n~lB%R3&-tle0c ztseNt-?`(VK2Y^Vf6Zg;4{L<&XbV<6SuZdK?C-5&JimYH!|j9ViBe>o_H4P?&X#&M zxGY2mI+r`1`}tJcC%4T`?SpXr&YR6IWoJRZ^BhpCwvi6Dv6(Y+;*E=WI`P?E#|$iH zm0{BmG0%06x&8sN_n@VM9xy1JF{@*sc87L=H3t)5rZX}cTHnzA2`<;O{U1dAW!lAQ z@5igbu@nBkRmZLG5|WeI{r-6;6*0drr$JR|rhPtq7SzA+I_Q|a({1yJy}fB4EKN|! z@VP(IBc#dB$dCo@X<7z`kFtm!u%HA7_8d%N;_}9G4l_VF+4fU@-S-sTyZxR8K zr{+5#i^M2Ws3g8vBt<-uU^17+BWqHmnW`D4uANq2ZxIF(v02@O<@lw|RMV^6O5s}0 z+TFz{V=!X%vsGV_F5SWdNf4S0SF&xBW^;}ztrQTh&@q;2^DL;^N-q@Y9c)mG-nFzk zcTxuKd5we1IWMlSPv+|Cy1lzQU%tKVuo)Hwxj9|S1`{_b7m8$4g~50nkJ}Zu@-RUN zHa51bY*`F0I~!YzU1z-|5itk#BD-bYafiEj@YE03?D^nTYq>9R(mL+g>o~Mn-{U1KNI_?$m zt(5yccZM{!_HkRfd&D>uSrq^N=5(PvYn=Y~i3|2on3R9BN7{a`0ji(cYO0)DVW4?v zh;}~3zkFl+BHWu36(FK!pFeCcuC6%v??b(sYLFxilwRm0o>Zy$i3yX6KfOe zse~_hL+i_x@Yt@6>8GbMwF;%xC7le6W16ZYRat`XPR{QY>XnEm59<5Z80$dL6 zp$?D>gu~jarYm`d6`V%U!;)~>TPD^ca+p~X4>b^`6aihtAkdtm@bpi#0*iE;BlMLJ zs=3X=Llvpn#rE(E1^}`j5s`4#TR{1O;S1Mk4==hk->7?B$f@)DWsR?Dsq6Q*M`w;W zY=)+G!9RqZnIXBQy^^M);5Te8Y~DN^U^CXO&>f-~`zih0qSMM=Kc@&-(hY-6p&o^x z2$lFUy%5oF&{7U?763`EBJ`>>_-l39ZaWlE`i#7I3d9N`ZdC!EmwhN*g8^kq@s;N~ zR#%;uHlAJ-l8mr5OMC`V4)y?yUP@oKO8sw*q15(0B$PJ1;buvxDD-Y5p>h}E?9<}s zB;$Dhw0-N3sa1ZAkfIXTTd`6Hx!XU8xgujsR!f-6VU>dDFxeVD4x9tfR{zQ;)(+A8 zZD7NWJDJ7B#i3E0A^!)!zCV9PMiS|-pZ-dZ$$eSEGn99))2Xp~wTRn` zY(~I|CvEpEWiGxKSs%)j zXZ7|w0y3oseegm{U=EiH^x>p0O^!`qD z#DK@11J$!yJvukd{0m0bNiJl!yqV{S1Wjktz-c;@>*v++y2GqOVXbaJ9BL7@Tm^)6 zg1LlGb@zftl8Z1%7_VgznciQl4S9L~PN^q&kwyQlK1K{$OH}ylJA&H5JbUP+^%?l? zfMY2K*miO7@rnPykQ>jE?f{;}#Z$cOrTkv}6!3dmmjuP&7R7!%r0#~r9u`Nn^g=0p z(<)pDl@b+4`V|NW=efUtOMD%#8z%`LfN@lSrZ-OrD?^M6evatOk|6x!b z9*We%Fc*11S!8Uey|Ov#AHdrWkbQ@5P%>(i|AM8vSLwY7PuO*>n@`H1&r- zgt3?_P=o$cjex9@A!=x#ECPuQjx97--Xqdd=V080=`zE;ZT_Y*Og0Q>VfK9zc&PWg zi(HVlL|u zQ}ZIR1SmBHtnc}8`JlDO)0{=tS;9cE3AhG4c&2qACtRKR)m(aC>RodSmz1p!B#qQ; z*x)Hq12uH@Qtxnk&){GP)M|mv-ToK@0fEd1*ux@XVq#Vg1qH9Tfyl~84~WyiKW`QdyDqqfqD7X*FwSoKlJq z`=Ke{g8VHGQla!P{j$DLsq%$x>)!rCTedsjcQ=No zRkp#;G9eIP}cW6DC8Ar2ndM>oZpL_sC~h%xhXj2 z#xF>V&|2?R<}@I!V5x<|2kOF1x8*Y*DiziIg;`qd0PS3n$DoX={L95eqjGQ-#}6oh z@HiRwXDTp&vi0X^WwJi|C^|tC{tN994YbybHrnBtraDYESmUl7=Pnnx@CMo+jhCWI z8^~SYYd|`T3y-s;HPE9N0EhmN`zvBj>hB717;|vML4E`xQ|-O$h2Tzz(A%>7P{4rz z^MlqQhXxJ(-NjHcWb6-jxw^xR)9hr1q(DGoE$-)6KJUrg25ty}Hnn1ar(TcCt@dI- z8f0TD@v82^Sl^^KfNX)UMk@k8+IReKt?%pu;>8tNI@!yjr_fPMYcJD>$?Z%3$y2TT z5aq%zE=QK8$5~?9LOTRq^75IQmq%&5tIt4cGsgQV25?JKv-LDfybTLp%d{#*n53lR zU{1m59UmH>E~p4DA1@~lp*QO1jHb5P!{Lj#1ZrIm(4V}>wy7wwoug_WQ+SS1g-O9% zMw2m?0kFyt{Wv8jWy808)j?TXae$b?dm*q7Sz-Fh{p&kVMSoXJ6+$T`@xpqDNQDsm z;a5G4!-GR8GXiu6Os~(kh_5v5ESaDY1H!VO+B3saXEPCiqIV#Vk|hdLXaViF5qwP* zPEAy4)M8t%%u$J50VyeOcr|Vkt|Nn13Un4U>kE$6Fv7QXHV3-?f?H49+7lcg@O!Lk z+!Ft%u7n35esX^h^Q2YEi@xBRoKMdugWzhgHs>=3Z}3H$O7Q(Nd>6~9p{GQ~gjv=H zd$G5mQUlLy7}!U+(>;=Gk{eiyC;!#@D3z)*@YII7xpq==dNPnVWWX>Y&U$^0rHvIW z61@NlX)8UqPvDw zv&&0t%77SSxtxdFa=W#Tqc!GPT>&611V&S!wou=D_&N<+WRp3NZT2i$s!XBQbDI8^ z3MPD;#hj#Xp5>n+crAGZgy|ARC0!*30kj2i>^f>^hm#)6(|15GUr=Z>itv0~u1Ys8 zGoyvu7;Zc~_$k9V5lxKP|J1LktO^!r3@P(j0vm2@?(b4#pz~`CEyJMJ2O0P$;EjQ6 z$7mr@udn@$hSh>S;6nfTohpC_n3?WMZKMkiMofWAKwbSYrbt~5Fo!2x<-G6O-)7RL z7r)SWZ#63(*{<+O7)bs=vvv9#UxYCXVY**s>9%NZi!Eh|KexLiy4|$(J~$mh^>3~I zgfz!;w^kh)fod|+PLK@DMD@(<1r~uZ{!bchc>b{hl&Sw_tuw`UUCy(g9}&&W%)s<; zISY#e<2h0WfQ4~zn9P-_ff)GWg9iF+vcHEFQ6K{k*pWeoB6_3(GX>g=P6W?=I zYd@=ZD^Qlkq9H~XyJ-ttY>lgEcKjIvWMF(nrcQ3fTTcELIQUb7b7*f^h}49_H@f%p z0OHBpTbmirvOPOTBVa-58uUM@TB&7)V*Q(Y>bTfufR+@1GZg?022vzYA%SzROOKncNJr4=zz3S} zMdDvhOot?Nsz3-)tA3uGk}mnY_BUSpyEJcz>rqBcJhg~o z-eI^!X7SWweeLStnwJaniw+1JKu8bq5fBx*ci#Txc+iq6F4& zCnrh@imyqGI$*G^5O^8eA(O*_;edeI+9SXzb+63lxX$NHnu;a>nbJUG^dU14h}J;& zx4+gVNa-#9v%h(iw9pB41m%U=kSqDOVP;{8L-=`6#PAye&?6FN^#p9{eL1y>i@l?8? zNdKjZiaU7JF3uInK)!w_bG6x~^L@JQ?}X`oD$LPsI*7U=)UxUg0_L2j+BcLZ05lRW5nF`|IU-cDx9NDxo+*B`K1j(*{G zi2Iz8^5Y7H&!_*S#^egr;?<9`n$lmMlSZ(zroQCom=0?XTU5M(+ku{3Kp=vE*PDkO z;s1@xGh_VIXgOB(OSuFA6aGydhKwFKPwA^l71e7PED2xORPUbN91YRTA)juCxk*^+KGi5boUAH8)oSmP)fT_sX z)RGQzgcT2yV72aTKrN5GdG zXZ~R0+RpHc5MYzhF3ASI&x-)iza?KediGIO>4;RC4~#^YVQz~KzEH(tgL{Q`ewKmKRPVR4 ziT>@!uNk9!5@7M!JN-G{y^p*BbK?0>7Z~EvNa$EPz3Q9_^&gKU+o<1t3xJ32I|eh< zX`0?6b(QVuB*HCVyja74imYvF3qA7?FI#u);A&qtv8G$fDXk%c(8<@h(adXkMWd8(_SA8Ef70isN<$ASY>?VWK>1oU?{eDG7O_B~ zzomTh{+y#(RUROpeFcM|dg}^YUTM#-9u=yW1c9Ffs5ij~6DG6iNr*81{l`uVP|yH9 zdn3<{BG-ar)jKt{>JQM`T3~#ve0=(Q8WbF?q^tWVDFze-gr=sZFR~+xX{yY;ZHLYY zU`_iUz?`k~d8=Jw{8FjLpz-Xy73NGOIc?!r>hjcbC0G7ZG{q2mNjJjT+k`URp_aGd z?Y&YVKxH8fb$QWZ^E5Vk*#W;GE@S@4=qMoS{#sv_fs2L-pz$x#1#j<^};eed$I*Iurz?MY_97q`SKt1mVo{t##Hq z>->0^KVFpQx$oP5)^Fhu_TN3nJ4)A{HWrYb-79Fh#K^G`cia#Py3X3O5gs_FF$hv5Y9C z-!C>Ded{IJ;Q6V0HQ`~$txwd_#Y{xY2t3Kr?5F**KeOP2=XU6nb=I3KEcXQe80h2< z)Cxhw6%J;dM0fN!ey%q0)6uVn*sHb|A)?9Bgb1LyY?sslvf25n<&(JAx$hxtAQ+CI z3k=gVog99H z>kfauDoTg?0nc#3`yz8`ahD(2FZA}OJ3n^;htC8aM9$p~aD#P1T$N##4uaCHeGam( zW|Telo&-q}*ETIQzZTlWPUIN-C8a2L3ilgM zxvR~C_B2MBkE?>C0=v_F^Yw0;$WP;}my;j7P^f3HN3W>H+|&!>o55r#0yQR>VHQbWzf8mMg@CYv_ z$IPC8_gT)ceCf&vF6`+B7x(+Y??Q-hiYVe`6*}JSf4jciNq0Fh$q3C0r-WC3&3`iP z#^a`4?c@&*ub`INlson^E%z#@mUL4ETT#li?tFnZ%N`NBZjRyDf&g;9EvbTwKYqwJr5(I$TFThR~C(cIDX?Le3Hc8V9pN)+T zW@3he=ZC{`>?tU*zRJvExdk7s#(iIU3M0m5Hv6EVqK|p|&1HI}qGh3ZI4^L=rD^8z zcvtcwv$f`7f%75K>!;&)f!kB}{}imnA$N4E#rK~B(?7suRc=>aKCaIBcD;i6 z?Y*h`X7LS+lAOd2m2r8s_RNyIIw`fktIbXM`F6wfltfbdp8%p{sVsuMkaQRgW$=a# z%D4oQe$0|S5Tt~9&9LoYtX1qz0;mWOhanAz>ZxfpBOcjIw0419VR^-P-koQ8(->0# zY(PkYnrw^o!^5Dpkt~8NuxLLeA8gUJdJZNnM<9pyt|_K%p0ZkLj#QaIc~B6d1JYoq zC?VaemR>DA#@gp(dQ5sIB0O4_|N3@)Jf-Mj#Fw!4`}b^*9HmahV`cc*ajIzFrDz*~ z$9^xk7NHq)Zg;->RGZ4DjfG$j!bE=uMHGofo@I$RprpN&E zC$2~rF!^XXM@mHB+J?1A!_feT>h`$g`6iN|6dH7q2I+=FzgwS|1+V^W%T|~@VI09x zYc7@g2ctW=Xt_%_CZ`GQy*j!bJ#Be3^ABGJp;NpS9$1PA)o^!ag}8@==tc(HYTeAL zaT1?JQK|mR@HezH&=%UN-l>6Mf(R>s*>*jkZ`;s2kum zH$}9dkT=*>>0a$bp?VkIF=QyPMqy*&bLcmf^c{E$=KRYs<5xSg5eK8s{&hi*BTMRZ zcdnA}9vavK5m|Pr1G7SRx~Cwk)Plg>;@fz8wM?Nwaao4)<2yC1M{r4Aq&nAh9H!#Z z11r}8ZaAoA+isnVbsq>OAzu9(==?9l5ue7Zu*7_+#jQ0{I16xQ#qsZ^1x01j@uzmS zh3O~notV||z{~>Ti4$u%=1b82O7xe(8g?jE{Zkg31b7|rfII4{UH7{V*{sa!?vGW$ zQ~^fuzc5sQ84gq_AX8qwnJ~bE^8x>|ow#)=OH-&az3?N`)sjFK<#0$(>>Z#GC_hX6 zAN2hjx-w&iU+`&TzForP$Cx>$8_a!(J`k|N{ypFK zmS`zvestxOy^?dV*zo9b`GhJqw`Xf65)~66ms-!oOHnYD==XbHE=3xu$F|D9{V-D& zDqMIHnH0y;1J-+-_PK9uqTh+K)wI?P*Xcs)=l1H&^@lU&6xxAK%}~l@u{=|JYqz-37;0uzYwC85~Z zBF80h9}hOmh7BZs2A1Ci7Gemh6!0$<#r4RtOXl3#{;Q5+*Um|t3FD;;^ZUPEfZgRv z2k2XgxlIZKvc@1V7!l}eh4=YjM;bW$f|c$f)CZ#f^fq*~62PVhD>qjLOTCd7j5gcG zU+HmI%&IdpGgq|`0IlijdA?0vYbQG+51zb^A}mBrk&F|nOlxf4+3hj2Zpb!M*VLqf z5+!9s?sfB_oUabJum+(s)IA2# ztSFgFo;5YQd7wBuD#&{Cb@a0G9mWNuw^zTcl^kA+1KS?N zrDK>v>kA+hx-XKL&>q9&DS|V61Kpz@p1YP0+sJ=UjrER&ey^in;_}~HYA!_QF1`hS z=&TW9_ldM1DuzfS__K$$7#KwS(If~DAiuQDCjx7OAVkC~DGJq$lyen-Z6C1_QtCY( zd!b3J@f$!Hu>L>SdnoO!?l=ou z9XH>lI)MK^Cnfbj+?g!5B!cN>Oi!eO;-s?_Ig?b9-$!>F8N|xzxUa9R1vEB_z{Ve# zqxGlEd>CD?H}!)^@p0~_oS?qYl|UttgUS8$Q46XpDG*lRTB&LBS~UM{cd!#m>$)v< znLAX$H#@(bi=H`|bAKcy`IzQ}nFs$BHnw)Vioz>91;X(P%V{08iSqw+O3;+w{D<_7 zxt_iZpZa_BoO|QH^G;W$>TWrVqW%5T(Ud`^bb9E}?<;gz`#A98?Z0W4Xz#2~3-<`@ zUe3JT&aU>gA9s-r-jKQpAqx#(Qs>I!YBLu@f3EqQYrr-|eUWUDXDLorr@zO9O-*~v zU{Z`NR&T)|@!jNhUM^45;9Ri;+4$&`%7;5l44iak=ukMpQnp`~rQv-fxdgce{`CUa zyZ_Ll&y~nr64p69c0FzzWf@4DZm}LlHkW2{8lIWG*XxC#+HLmn{D45 zl~WmMduqE)T27DkJ$UtpHcdj1NE?*b{V~yfqqA}Ek)f@pH7gr1@^EtnId*QF>PZwT zaW~r{FJE^gYMbuRK>1?B_9B9n(e*{E z&8L(yEfknSJ^@3Y^IvlBn)#F^K1f9Z|NsJIvwrvlr&6@}|r+HOk-iN|x=J zFH0rY$XVeR|%Jiyb=4W+5gjRpp0*T1g z$MNmc@3GmRKc_W~t2OfS{}&(-=gr|0pLC*LwMkiSU#tLBR_#^~GFL<9!j6&4nT!Dx%CtL@N7LIS1}d3ip*#+8w^ z&oCvtCCI-~QgEREKt^QX_m6iE<0;na@9!U~uNwYnsQRcij^vR0!kgspUL$%;(y#odm>J#i?{i&y<8{9%E8k*Xe##X9K`vwQ2J2>DvY*Xh6i zZY&haPt2B0MvW5b-5Z=6#I0x42i0RfdRTAqvVGBAdf9*HjB%HtoXUXlAJx9WIWpk1RK z6dmi(3I%x4hF4T5e$G3|rE}L}#o6cUJL?Uz=fQ5Z;lq4K6J4Eu%OjI2NYjLm%AWsg z8)}If&#v!4X{EwuDbdUJ?5+{r{$X8Auy1N=6ZpCa8;ewbK);UvRONc-+I8{bJ}nMU zOw!@P!QGF}Ev3*i{#hlaT`%I=-|qx9>N@hAZ15N_%~bp#%!|T7RgN%OiT7Az%5>?f z3szk~g?6-kEXK8AvD)L?O11KBA~0+PwK8O;M!O>0mVt(@SyFl5WVa*iE6L-Pdu48{ zgK{24deaW}_6E=xAe%hq5_+gQ^lfwD%_1hO&zguYeJiNSov4vMY>hFh+!) z{MTFRnNjO^NiCZh!)>u~7~OTC6W%{SX5_oKjhdM17Iz^K@gtdj2+KsLjbj_}hE zp3RA3n?hcTdEFvxTD7)3Bcd?yDsC>6vob4S7$<9M}nJdb|n7yA$6T$Sy z)A{qrsfGHVjECwYrKVGUC8|2Hh|UBiJYcm}s|@9DWD*y76>EuKS}~9TSJ^CmsDP|g zUi-Y0Oyp=LvL$%7r!R!j7|-QFO=h6DV&?F{zK?gzpIBrJm7GB$4|zL7&bO4f0Y$}R zr4evGZVXliV}}ffk~(=HRI%TP_4l?*T8~EUTsWx;c{_vr`n%Ln0>QFL~W@8DZ!&V?ikP^zUQ| zKaVvJy$aLe)_QTs9}Mg{lwp`z3T}$_qfmMydZd=^f9FrUiJSs&8{dtnx80=tgK@%k z^tVA#==~57-`oZ>=A2)X{?4${Urr47h&n@SmuvUTzT+798mnZLqrN4?jzQ7jNXyQ4 z2&IFx4p)LiENbqDMEj!Sw4nVIYXYA)&1s&SJW=Xe@-~&-*1;3DFM2hb5A?9D;Nc z)j!g#M6xL4^Nmsz)9&7-n7~7n3s1vONH^#u?|&mlA@SxXRljq7l`=pbB}u&YB8naYl*|YSMoCH|I6yM~(eR^5&pt+fl>;BX;YnYR;7SPZ0 zu~Aip#g^&5-^S+Q+vJ&B%N#wrMqw&jEnD4$Yh)_Dzc9!=@aJc(gURc`H-EIIlzVgp z_Fm_VFB+`Amea!Wokc&s^cf6qkacpSU^y?s@1|FI4D$}~o;i!u z3%hpWb1NXJ4uDWH#vX5FA;z44R)~v5K4ddg$G0w2qLQW--wBayGI{oei-r#>*m8O_ zd){p-Pb5tr#oKw)2-By9oAUj#m}frOh@#g2cw(=caDx18;2V8B{qe<3XSl53aqIf= zjNf|Dam2ET*^b%D@W|Vb>(>GXVlqCcBJLv0TFhecS#SZpgDz3>#S09AIzM{}hjy5$ zRhBZjKf>I^+!>r@$3+JI>P=(tYqV0{&{>Vz_ABsKCXjH&82iRAnr&W`p1HHYexnrD z7c8om5AbvzAPn=)T~;Q6116fk%Wj$3*5k!>EGY)5+|yFWT@*((orXi3iViG%O4?t` z_FmvV5$$zM*#640sMJl}J0DO(qyLyumgfB#mq&}?;n;R}QU4lfARZ2T_tV_=t95-N zYhU~LnVp-7yJ5az9}tLmJpPz&Su{WI3wOI|*i=>GXd+{GT4kY2B(IH2aDa6F*2oqK zts3*NTcLOWzkkTu17Eyxjm4*Z&S_j%jihLNpYEIl+(Et|YlFE_&mWVUz2ilCP4IKu zwMd^5`A(g-7fH=3MXhGFed_i|+4y^!%CDlsL#;TbFTJN44Lv)NTRaSWCu-&BtZeO@ zR&;$8L~2fOATFT_pgWkZqzcWS^{<@i}O@tHKdveqh8|8})*eM>*XK#tuIMC4tY zuvK9}&PtwZp5F|aMMuVkBvtv;O(=5TJEc&qBBXaN;Syb?Q04mc2M7P2zZCmH%XcC# zoFh{Xw*ry6w1;wcVT`>8|E*FC-QSu_2xs#VH{o(ml7DYHO(aYo9IeD_a9dzOGiN{q zx-S12u5C`8wWGarrE|`&^5|c2T>l+B?>8DPQxQCERTA_rE5&t#PhIzXQ;b%J?uD*v z%BWPn7)k&trp#UT)yc!bv;5bI8mZlDvHc!tXVvN|ylu!|c;bWk`!M1$R67gT(h}U= zR+P@}!rG%{|4u2%x9>a4Da0pDZU}GM&^i=`G@FAn@Rl5CU$w+GJ$Xu27v_(1-#gBv zheNMYWIwnkPWs^rCG``&VBhMy;mF}xxK9i{IyeNBsXZZnUt6^OtuC(?{B@2q@Fgu% zZq_6kKha0~z9=(l3tt6sN9?CYg@Done&tEY?#P3$hASK?IRkW#e-$&V$=_MTYBM*s z#fyp9ZyoifJQbWYtOkYOre+ zQ(DjLX}E?{gr__f)K?y@)pQy)S_!G{OEIf7qjL}sa}Sg9@n*phMX>R$?#JE)5Sc|egg~1or?+t3Mc?d~p+eY8g&!wC)!t44#eU9{K z*E0yNC6fNxz7Xg6!O2CA*t)GP>;R)*r7r>eJVg8gl#5tWhWDfp#!4Lfy1y903pZGj!!0!F;tq9!*M zZ>}I{ctqWx1s*?)(TJJcMtkp4Rd(-7JtqV5Vkiq*zRj$9A?h#Br@0ZB;=*3E4W)5Q zc-)kHxv_uG+~Bh;=C5G2pjou9QV#Rfw08dqR+!6d_Dq-Vm#IYuJ4SkKk!C$4IFc1EGirNdq()Li zVfL6%oDCoIy@?#-7uGMd%^b3*Qu(smoNNQ_M>%#M3R5*c)we&3L@GWvvyiHCx! zlkiH(gpmi9@jxkGEi~iE<^9?XnL&;LF}BU1D}=Igzpfz$rTQ*Md}8SfFK#OB>rap_ zgR*A+JdWJoX3-0+;cpFF0d&K~+NIvt066;Q<5v38ZRiZ)P=STX@??0+?l5lxxk%2a z`Ny?D(+O7-I;fFSu9v%$D{LOEP%bp+oGVOfev}c9+?leXlyg%qX!C#We=xA)l7J(K zQm^|~Q64vP&wa#9IVNicH&s_cH1Hi}8s)Q8FeM*u<*I2M>>}F<3HVd6%ee*fWRCq5 zu;hD0FWi)6Pjg?MM(LpG=UrEe86|NCAGvSeGXG8l>g1 zFFTvG=1g_mDXtvOViHoj033-EbO>pdrcf8b>52zrbBl3g(cWyEOAk3bWv(O8ZS&4zOj8+r&m+>*`Pfidg#BW==iZ z(VS>;McfkQ?hF0nP%h<-F)QR7nuUfPk{JG4f?Yt9A2ffn3%^+Frd+xuRJrfXf53#4 zMtX(Ml^b>%h-QB_RW^=cckj-E<|z-QtOxc>E8}@QhevP2yjslMskAR%j-1~q2-Xs9 z4o8lq!x z5oafXTfxh>yeX5^Z(_Re5f%Daq*kQ=j1P;7ntHu04^yao$T^Uh>RqgDaoZe``UMpA zagl6ZZ7sX^+fVUv(FWhTr8S1#-iL6#tZX12*m)g-J;<88qrTCbiB&6WxhAts*6~}Q<_M?wQZ_G?k)ABjQPxX-|%X57a*66l#*1VEZNyE zN1igZn_;NFBj!ZnLU1+Zy`Bt|&k-b{;{^hk#4miGCz6NDi@F)}QyEzsL-oKGtFz&d zU5tterK;>fa?@j~Z!JWdq`}(E5{0Uz4*T-<77ngg*V8F1FC=VqY|^KbS44ul@5Hq8 z+Kk_i4c};O0{3zHIXr+LvN0-IF9^d8obj$j`@b$F+ zX*KHsFQ?mTt>t_$DoonNTc#A1Hoq6o!bXPI#5Vl0&F(|e86_(oChlR|92t7`17yFa zEqff~GA=tc4WR{7Pr;w%`uuE>va-?snm{^98p9D|1rR#7`?MA04cVjgwoE#Ig%3cC z5nAiL$*&=Ry-=FUtYHVF&37F{IBIBbnU`58C(nZ}ZhID4hPKLfa&f{QCNJ}aPVa|l$;kk9iGgYHPec|!&Qb8*I{pq-?qqU(e5KOd8kC|Ty%bN$%@oRi7n$ei z3`f+rq+JEfb;8lanSb=pUo(FV2oYQ^T**G^XL)ZrtJ)XLHoHc*@>8C?pkq5PIo5|J zpExYt4gfV~&ytb{ka=I`j7KRZ(N;Lu)?~l>U^@6HeX#7S`H0Ji1NAymevGQpA0rPM z{8ds0)k`QOuk@@hd7dOscsU6O6z{J9)tIN5Z&S25ENWI*;>@0Rug3jtaz71ITX6Qo zV=Kl%YNN4PKUXwdpAY{zW?wugrqb>$@i8Q&YiQ@y|tI(s&=Y=mYYO9ds6XqH4av*aJM+1mcBOO6mqTE=qfbNrzxlXQn;xl zRfsQ3s!^`NsMQj%JHfI8FLDI>8%EUM*m$z-COJpUxPR~TM2C|nLrndtQU7VUCNpkR z>t*23#Gm#p>JrveizZ1H=FtRJu!QGv8q&rQ64#x-;+Z^pm&Lr1zQ?Y;=H_5XtE@ zY1`n-@az!rl;yin-s>*h@!8^-UmJCOYx<)Pq@z z#je!ZaQu%>*dc}C(INcOIiXuNZ{cfG{$~_bn$<^}*KZT?csp1AQdec^y|}q|`~31z z3D>gWdaG9H+)~6Vm#-ttm+QgaM@PZ&3Kn0M{ylh8sWBP`VQ`&EaIiZgreLyB++(2M zcnwi-Hp*R-rECB7lTf0}It%%XxnZ!{5|f#3*Qg-i8oh&P&Dx?hPoMM zaRc5enH3x{d>q*!)bp#k*RB8K&h85tHaWuANyQ%4u^Pk+V9HH>bm??y@Un7of=GhR zWOBhc?3m0&hLZ%iL9edc|DbS$vpsIMmM=?dsMthr^Qbnp*~Yi~M-TNArr>Z>UeaXk zn7myqRm~8cUAos@8ayJ78Ci@lc5CLEck-KG zLG}tv)l2t_nFArrjW&^}+3)Xnc&i}S7b+vDt@JA3)-o<{4QIeL8q7b=4 zwPAb{2_Kw^Ok2m9Nrm9FM-8@#iy65)J0@Dw)9<`7@sPm=a;4}=V74d=5NO! zJVB2gk2Y%xxKm=&M8V(B;9$IG81!CQya6ptB z)F7OCC8ER4dXYDyKji-YJ_vNRI|}u%zr=gZ>mM}rjGc@flJOu!+bentNEcSplW$(T z`Am?Oe%AUrz6}TUnd7tfY}}?0sGxE*i9P?J^+#lNWbG%9Aq#L1;zN`G)BT?NznfE( zeyhH^9<+4Lqt@w{;zUY@k`;atmyhlcd0)4l@D|JnX2iq`3j=)lIT(iZ{?cN zq7-lXycIq7vCHbKq8R3iTO(~Jxr7oD+e`T_mEE}T#2=8HyLbUyz#u^L$N6$ z@&OT9Rk^r@pN(VVsZGU0>a~1j$Sbo|nziJ=Pk^s@7%fslcnwc~28|Jy~2^$_WN+EV_QUV?Z8EoeYiS=mJZ0D+vh?dA{zFHQ6GgpdRo&fTAkE?E%4TL$F40D(cVp zs1G_UpS;ezK7G|w+76%QBecJtxh3lYq?f^rVU@C1_hV&J4)YzPwyk-1VeVlPQ*kBX zP{5bOY90Lz8`mhYM1$y>jV8Aoh4VUVPkHEx!XvYwbyw3f0dcw&L?kPWGzARpGc*1=RQOkNTUPOmKLjK*Pf3 z>34;3-Oi9ymWkxy#Bri6{GJE~fi~5DqVANq>ukOs?Eh>$do8~FmcG%FOeT^N#sbxI zo*(sC7auhHKf;(LXI9-n-a!ef3^#2(!kSQ@N)TiN#ABdJo24yhGt4(XB%p0wj{?^*Ou*w6_7@Rb54>OO(94g|V zKR4I^b_S;8?4^DwIQ0z9MP4o*lk9RQ)tvD^T%|B@`m;r;-xq_-7(D3#nCg}Q6H@nw zybXMS;;UxO3T$zD_FARig*QyI7oe z5c2pL_6j&aftCnXBBCV@Oy|I6eMDOw!DAk2&={XsJ>B71cSJ(D;CTs<**(K^^_24 z?i*=iO9lW@8P8|mo#vb8Z(7~4oO1uZO=h!=1vC~+Gi(^VZs@cIp5shCPCL2}E+~A1 zv2YzzM=enalEixaU8{`3A2HT}vy0^i*+V`u`ApWilRY^QCXVzcjyDxT^ z2Sepm?i-5}H%HrYDF(&8keX10*c2EqOz+`P<@$?ag)7LkL!>oz(Z&8^K|hAIV5&k> zxZ#9zU)NPFC7Bu4dUW9%lq>l7O@1rY025MTGxyc5iM3K?36td`y=?F9<~rY{<VHT&=7#Xx-8zJ3D~Y5KozjTBgNM;=ec z)CbxYd-hH)mB#YM&pmUT%&d;t34ih*j`7!xwZnHZG}D7gNi^RQyJPw(YbKhyle*(7!c@QQb;ng?C*)$N*{*(_A9hspJ=b$i z^9k?~?oNY^v9BUtA>`VW-!A|HgnUUPSY=%`_zYm-{1zw@W7eON_i;MIg+sP+y;%6`J0$W;a^f9bhPtvyw*q8gE#M44_086 z1>Zf$Z->MjZuqJVd5j7t&*1X(5~gV{S+9q~?}OxOG-ed78O4nIQuMxh{y1$62Gc22 zI?VMYtNSLX98+@CLi5I6re%UXJUuH3h2E)zuTyWakMEWonKdCu*Pb!ymekfnGXD4| zsz}s@)5PNC{e?*JoW-L3y^OjnZAam^fPX<^#IKCfitmjb%n4%62Bzqz+Qjj0xh*G% zg#D@WA0*l+#2547lJwoW39t7K(8c$B^d7hpXBu4dI`n4Z-YH?zw$a}c+Xb?dP zRtC_lY~E+gJTS_FAKkyN5mmtNgR9F8y7C3>g}NEKf3`kp*w#N?^G3+UiM)^AHYO){OTX`m#z?79hVu78w_7o3b+^V2Xal?A9wU_q)b$nUZ+W zdRQ^(*RL%fn~LXFpSILt&@d=ZZ@w*~T~sA&ER)skNxI|_Q1i%Gb>k^GS=(F3e1Y?I zFFpUY+ryhCctVecg;tL%j;*=V9MK#GRVl6|cVgnpzrE~;n6t0#8rZuU@BU_k_5}?iht>-B5T;a>uu8(&bhiVn84>LQ z2}Ht!W{tUDa-Uv1)4-3x!0p4?==}t8j_S@5M3GW^K)L;}aC>y46$sbTz`n)|LFMVw4`^r@kgS~ zi@9LZgTmO zbTmT$S*ukjjLjsHY#MC(z!q#iQk$TdmoKSTd(qhqrADH?I+bTa%cUeBv#9VRHct?Wg=QxAvVanEFdx5X*eNR(Z%RcU0 zUa%Kxua(hN5|ZGW76^UVo!CIzBk(T#fgtksc4o=@gt`KWM81Fh_I2>HnY+IbjXVvU zxqd)OGlZ^Wn)PvEc@Gp>6cNNgWBRqg=9f*zO1f8w?+Tg@f`YFmN@sFf_o~@GL9fMX z$ODs4#Am+NA2&wvx(J81q)`Unom~< zcWNx-&A4)H3QdkoW1d*zV02NhzXE6-9h>a;I{W>&PHh4KSMP>vG+E5YtI$ewl}g+_ z@`1Tk_jZrwq8~PeYd39IVws%7eNmc2t>x~5ZdBA9eI55y$(t3$7wobg z|Curhwg$K0`Pn|?v#{%Cuz%(jj&rzu;~{@PrGtApeKBU_Epe@J!9|iBW4(TqyC5$r&WUYz9z`?&t{Y8<%Et5<(UF_uwwTBNB&N=J`A^>Yc{G z@Vi<4S)dKR8)kdnl{uTC!Rt!mg4K|(M<7j+blf1!)?j&-ipmrbvJe|Gs!~9)qJ02^1nw^-&Fum>(l05<}5qH z@S`8=@7DYV^kHHESX`y@B@O%ktK9~N&rtt2ImJkauI)l5~TcXc}%DR-ePg(<`{3@Ob;zMRE;>jRiBTz!_rUh%d@_5>#E%pjF(R>owy^R?mt_TC%AKpdXU9e7{XN=AR zvJ$q+K9BZB1xhZs7dJfH2O!>!=h^)Ac1PpyOjFI@&no7tDI{b%DI-hrhgu;Z2AGqn zb6bQHiycGO{ROU+LnBi*Zaxbsc{o05p$!=dlU*n5ISyqDKU|ZW`}2n^-59)pFh^KT zygY@K8dI3r(xCudXB0HGe@22qFp5aCaV2sEH^h=Ll=Wt5KvO@B(Ck~LqcSZUG>e($ z`dX41wa?Xvh;oK#oo$AI_*|#mlx9`s@@rH)D10b<#r_bj5{|A{y!ufToH_mr&wZoj z!5~orqo=AOi-~`~fz5>WlIXH~pZ)Hm5ltSV9=0HYhGDUsEBZIoZT`eQ{c5{fqdEGm z6)56yh%}1t>l?hJ-B9}?%lDstA90<@Q`!$ZRsk~f0F3O5Hpnq^8jb!56a(8fvMrVb z`scfxcZ`4E8Y#5V!t-Uy=M9xvjjvL7j(W@H-SQ=mg)v|XO9G|ZTP z6OtU#Zcc)z%Dk8U3F$JSKv*!C30ZuhustGfG&nm|FQLNT!h;Mz+oC)P#sHcG_U-Y^ zXk`w6R*N@%a{wIuvRnVDZhjm*-uImglmzv!*nEF-@>$1n`FBK!C#m#{ccXw7TZ{vx zu*;|C`_Fgqoq?eT??eilaR17u?hL%=m2B}~@o~N<@O2o|iuz+V#(TZx4A_P`w0$c6 z9erUgA#HK+R`}TV89$a1N)GNi1ruAbc|H!4PlZn`T<9N#Zg zBsUnggI=`~`C7ROM}XMGG9|uS(u2McLVQk)q}Z#Jcr~icX)Ei~wsC1+;kec-&|nlh z_!yyufElH#Gq|QUxsrumGJ#T%B1`za z=7hct?ah)L`o_&a`Y83}6PpFF?MYmPMEt1VfEz~pOU%niZ6qnpMP9=WVnV3nB$nssYX23G=~?pl?qJ^~4HPpF zGUsnTbiv!e^Qp^CfVk)!pRzE)#2%xNIJA5`NdUb9ZEhX7z^Z^d2^^(}Xa`K$7^Sw1 ziBqv0AY|MxlgYoMQc(?NCx{!&1vzD7vbF$SrrVyPu`M_hF{Cs;T+CT%#Cw z=6La*3rNKbVGh99m^XNzO&y4*{J zB9!kvNd7SZXoig04D<0ahmvbrcn}`Xp>ad3CivXN!-eG_2a%VoPZMYl9x{&fPl7g+%ga^Sk4PpLd)3sS>B73f50kko>H*<__3$A&Sg;u&b#CAJw-Li&m7?L zl`d3FDWHw%scTwZiW={IH_M_=XV3#fyz43B=!{du{PtSo9%iw7^gt zwrwyakUlFPr#6N(3Al^?JJUh`sBM_Rrw5}&;>MXj&K)Wop~TIM=bW>>mP1K$*tTyU z+sn;R694|)^2?yIaqnxB=CTEI1KCg-iMNHSF^;EeF)v}eF?gNHS)ccS00HoE$dr)+ z!*8&q&j)Ti(3V^LTe1}ztRp^T<6mdVv>w#ugu&~BV3A`6(*b3b=$1SjQ-n$zd6xG%9T>-jSa`wD_S1aBw|-M4?RH7?Ai@2Km#@A9;? zw%%4gD!hB*_RpJvxk2Es4e&Iev-Owqp|rFGKrI69azf0n&6ouv7%CJ>1Wmkh`=}pG zx?~&b{}v8$=?Um%MmZqaGBwHpQ-Y&QR|V>x-6gz2T22r9z8Jx>bs8kl##$hfAoLyZ z9#AWLzfO65VKJoE^_>fXs!W4UOC(y0D;F%7tFx*HE`Soi@7*3(s*HLpR z&_SfqU$K~PRdYH;?~`^2zIbonn9momo28cR0BUdq0p+r5^I>ul2c$xd_@voxxz<6lq+;5 zJCr2Sws5?xKY_OE)Apmq|YPy;Ex1(Ki9M_@k)IRbxHzT>MtU4AT zCSXfqumcHAx`#P_LPs{cc)kDI@gxEDkIumy0eFYG^?Ok>jlF|5$!k@?;vJDMFp&bQ zK7om&i`EL4Z_V?}N2+34qnwlWx?e8e58Q}4n3*8$+&F$!(lRr&Y2B-JUN+kdk}qCH zv>6yUXSgO;7V<$!4E-4P8)>4TF4N4NLn@5hQ4U?<>zOjC0a!{j zLtsWcYU^V9ye6H1I>;Z<23W2DyFQ2uN zS|+1QQv|DGXKH4W*RC(8ukd#8W%GX#K*q6{wgfeB!K!<5;EP50_`dWRB)nXULfTrk zWH`wn<@_&u7mKPXh2IId1#2KUc*P0o0Vjd=;OaW<&-N*h;AByPC_~%Z|3Gq<2PCy9 zzqrBd^faj~hf~DTa=&t=j$CS70jd@UZ+9A54IYP@Y(u|*R+dy(!PCkIhkFWw@r1I8TpN6 zPh#|p=%W63KT4AZo7ctCrJ>*g7xXD8ycmHBHcr5_1yY)Hs_4L$ zLInXnbY@W2$g9tT%-rDrS;qi{%YdCUx) zD(n>A!QfB}({#}>{g>xtu_dqtjU0U#X*B51$WAh|-wi1?&+XKMCet5vP3NgA=oko> zvs4tV#f3$`4`K(H?Yz3K{wuci=>KOsXKTd8fd;V~!~y{9Wp0JtAzv*+OPp=rkf=Kg zq+5RfylW_S`Wd^gL#~a_>xm|nt#l9jhoTem&ild(JzAD-;qN({`g_7bv@YSS{8p41 z@h4lcC#g3q!=XkrBo@;P&(&th!H+*saZFoWQ;gL7i@Ar#rJ-GHTKAQ+d1+|mD$}ne ztIa;_NE-1s?0c_LrriDs8*!KqVa-CF~7i z$)AQCz^JD-rutxhz}Pr`v5R$U9cYHs`1ZO8^S#S6-g{J5OiaULURjF4ij$XFvm^A{ zTlu3FG0ioNsDcH87lUQDKP_&V(=HcD7%$}C|G4^{US3#xcb*lu2|^Gh=^3`dfY1G7 zi%}I#0Zq>M#N{8@&mN;M*5_(8)i)0gMEbtC8!k@|os@q3ei^FwRbq<>@nhz=FoM1G;BxI|Stk z|NcY81cx&=74Bfcf<{{vNg(I>*^A-rQ=@TXhl~T%&U=w|1qbTIuUgP25+=WjO4Qa+ z2>qo@63Lb4Fm)W=^G|q8I;J7jh3S&z^ya}?jLG6NFUHGVwC}N5ALW;S2QXgU?Lv{Aw|JdWsj?cxCpee zaKt3xEaK9bY>L%lW6K4!dQ4v_91oYi%eJdAD->VpLxm$_7iSQ4AT=@t>Mx=VY)SZ4P}O*P?m(g9IGrGE+n6BymupJZ^$KlkLm{Rh6?|W z78U!*ck`t=mQ?wfNLt~R_8EWoq8ZW93jgs|U8XMPpq(+Rw4RUm1QIFarWlc*A_H|e zW7cRl>?v!X@FuXqcco)svglZQ?eJ6N`*#y6<)MQ;!YEDceg5aPbFH$>+U<=B7wDba zk$6@(&{Ho)Ar@9n)%*9;sfW%X&%ClTKeNPiX2=jyo?>wHLD+UQ#nF3JNhB!A`RxIe6ATYsIyoc;3?S)@~=84EwW(q}Idbdl%tlUBO zN7fuywD5J}0>^)L50^ji^6fqt+u$*(Fp8c@=)255R?c%1A#n*T9EnrEQa9K&Ah8g@ z*ShS__kaj~PX$d)v*`0s^eZ<9eypUqe2_zektu2@N3BrEr~JPfqfC;i+^d+qe#lQf zJsWoYo^Pv#?)QU;%$fdxlr!z33T=j3)~oDJ8qt9KYL!#+2MFj(&@7f9~$55z%jI7=rklY>wl>Q_u^#Dd?{1`SMJj03#jwQ6-mUJ zKM{!i`D=a}8r1lK2o8B=boD~cbwmI3S92Gk#bRjzI+fG^X92{6Icf-%ii-c8PN z*;bNj<4x2j>IR~(e=EAkkFZacK3)$;Tv$Nt>W7bF_BwLR^unw59iQUuo*jyti7V8i zYVUYDx#~R;ZWOVz?-d95_3rMnzhtc)52XkWoNNwW68eYgaeS^v^xxnDn-t26?Lfm`%w)l{Pa1z?9HJVr}&}bx?aN z?~zFP)@i59ty$dRKaRI)kBDuyx4l@jxZLBBVTdIZ9EYHe*60t&LCm8Cn8MO~;Rnrs zhi~l{&$8tz~(LN9#k?nzuOd$ujDh4Fg8Pd}t zF;#`*bL9am??5CgODh}akP(BJlh|CtVxVB`6X1!*OUF7p*sYzwq5^_`KxmppjoRuF zT~CAhBCX05lLb?wjz=n(hH0F%%~p-b0s~{4V*)ippAz^DjLX^jOM&%S(kNB3wllW_ z$4Kq;eZ{O{GGAs)M?WfgBx3WW`@-eCe`y5|P77pIw97$Cy|d*N>B9wgd>fP49J^YVB7 z*@^8HFH@!XyXW24>3rGt+=jeY7-?zghK2@!b2eT_U4|LLSuEy$|M%ZO2s))Zxeo+f zz`KAf)1A?gkz=1H>7yTKgJ25XRHO?5T$jt^(6tv#Kcm_CHmWibC9pj-cAVNm^vcoA z6$Ex+oP*he{}K~7jTuJDzL}kXs@r#bZq|sr2xk231ICtn?t4i7h%MN81&O_+(51SW z^$3DL&jjN<(m0t}=bWJ>AJHSM`U_dBlvuf}%I3^uKig+&4GxefY?1fCsw$?tk zBo}1$dA(b1MSW9!A=y=I!vof7bK0_rfarpjKpyJOhZ0VNeCqbQhqjZ8X~vnV`LzLG z_k->nk=ih@OIy>n3F!zfs;)mb(k^bFfe1dGt2)Go?110K|eiyDpL;-?CUuld~+PnS>!w>7-*de_abw|WvX z86c|zJTMN&)@Wxi2l5N)7s54;1mJW){se;$U}#jrUY*Iq{$|BdR~y{H1X?BOdl9A? zhk}AxAeAvK+Lu@rpD-eBXidUH{jH1YytyacuGc7sAM;+%YZuKFKfxvg zR%3<3o=hYmr-+{3YvA&$jlTQ2V;aFTS$Vog>Z8lL>_gE%%{220cJoRx2zWfWiT!T| zpKAC^EDfzmP27KNz{KBfl^OuI>$GH5WEcxcBUtD&YMy1veSO1|Z1#(PZQ}%m+to_4 zR&iTkSS~z}hk^6@7MV<`_#VE_q(c@9q~DXUdO*BK+K#9fbL$Y0N)NahNx@(X%W`*8U1y~Y6IvPIax%lvzGwqYZ533RU>Lun?8P)-caHp_M>`8 zhODgydWXkpW6=H8UbX9m0WB81v9SbC?5Ih%8P|8O|I!*aaOa40hQ}^bSL*Iqy2L!2aZc5-UOX*nCh$rRCiz)|BX^-nx?33b}PbX)d? z=?Pp(jv`A8$ATPYh*#ANX_e`e5khf$uO$xIBBe$eAR2HhO-A37V<>X3GByOvs zg~jR@VH4WE$rlm5#YXW10X%nQrtSN)6L*FUXDFz#L9U?weBQOeipI&w0eIc^4$k$~ z=|SdF(t|MOKD*uun*I5SsGu_MkA7>fpBE0Tcfz`L3rgob`^L08P5ZbU2Bhc-JqykI zR_vCO;n*&~&1vdxX5`b4()ojnJ%=r`<_nxS92(JgVlivb=n~5VYcrq4ejK)V%ZCef zo_{-z>6>IHNq&DI?8{qz?6G1<8bj|V6eg=gZ_Ii> z!w=bUH5hCd)%o_w9z{1_)p-*OaTUKSIRr}wBy*s)-n7LNl6?BDKdfhatQRdM?!CD* zv@3CGex;UL-?R+Xz>SuLHbbpJJa|>;_9Z^{cY74Lm)A|vP3)RJWd^1-CqKP3UE-K2 z`&nG4iG{E=@6l};RcIoCy%cuCqP!KRqj4|oi0$QO*~a0hw4UhoJ=}Zuh_rjvG1IOi zbTvC$=+}h@LewaAx|%e$fK z)j6<#nkg?c;h(4Sxw4$oXi>fWolJwn9INK%l`GWY;=z%W5H%}ti`K9y4n}WI@L0{J3+of>K zBGq0D3U3vS&VpWaKqRSW2NOPSN0 zL&PxR-P_eG%p%K+Cjo0|f`U0r)qptGFU_24>2m{SQ zR_EALxsMrx?MbvLJy!@8f$R3nL1RKFP&cY)s#ixfS@9q8cp#`mM&NJhg@i7aFNbuj z@x0IzClj@rH#D3$(G@9~&Z^vwOP7YfpQU8K=q1;h91>oKi{W%GCC^7&%22e^r>hf> z{Cx~PV>Cl(VcsJw8&#>>VV?E2-SJykb^e?E*UjN3Ic51(%jCtBLU-2(_q@gPJ^+)h zQ`&sFTa{~T_z{>SW;=Atg*Vu$!0Cr z^X#-G?aD%K;qgv4{a&9u8XpYm%XoG z5t$&R4*p&sNsTQ?HRim3I^Qc{ukl5M#_y_|Id_t~=p^-+aMhDi$6rj=`1t&Op+fmT z=*vKIMP}Bp%Spe5q`#ZRp{2*g3JP!w&&F!~Caw_~+nNqGmxrDGlkzpP1Gy zWTVl$qWeoRE#7tB`j4_;MHTu_CqbkQHCX)Brsb>%&;1a8IZ+e@!CwE`sKtGGNI#$Y z9|x*mU&c4%+Zy|Zo3C5Z{gtIg`0H_A{j;Ryr?IM7NRTV)yXAVT-#2B9)OYt@9~(KG zj}|n=YjdW+=7BvN`}Mpb*3Ob)RVMU%0OgpMFZ^07-{_tM6M5zSk}$CB?01t*i|&<0 zBK}aQqJs`!y_?5E_8;1UQbR~1@n~*Vqpy(zQ&_oX3H5KVWv;YsJI4j9+iSnvP3`;zd? z@<_tg6BzkEnwZ{?S?}=qDr`*4&*BqsswwN>6CiG@>{R{hP~a72C}(A$;%ELLjUbCN20GDy zP9{c1^!WC;c7g0zo{bO@!riLSx))1z^8zXnAAEIYrg@uq#dpctyTYiO1uolYUXhyW z#W4@!9ox?>J)*HK!cSr~_b=Q5YcQ6a#A;O>x=D0?++F|g8b*9KhvO0p^0TigUq${j!9sFD@>Xp`G zYtXxqLh^ckABFl3^!m}O3{I@qJ(Vhw1eX)0j1%S1yu&dJzEGUVs*#sEVvBgIkqBO< z6I6(_^>eNub7WN0@U3M9ayHvFpKA}S=F|K8IpI;-`h=%Zxxn)5q>~T#8aPG0OE>U&(|F)+|LuLI}xr zRibd~j#kH??}!iNo~hY=*EsRMKFX|BLF$i*vgZNlzyt+69dlWwmh?*mH_o&ilKEV% z$32!TT&kae^kJZl_*kEGg^&?LmE8(eD0+4+@9du2wm% zXq-3a$UdVHV@Amv3Sk);sjD2DXcSQuFzD%y@&JGZ|G47yRV;7}vsQHPQS|mKmT2Oy zd1gi1?~~l+_gLx}EErCOwtknIJEV@!C4@>X`y&;_Zho1)vuM9(oX9*fkG;SdVWd!B zePfWoDuE-Nj2+-~Skv!&!u@Igr_tkJ)zki(Qu}4&*>Ocy`Q04=+Um9uXnlub5aj$_ zG#<_0NLYSIW3bd|kI>_}qDE6)Yz)=SIVB)AhIdx_y&*eOHZJ&|DpQ|H9hMiC2MPz| zJx<@XFl}L0{jJ7fvq{mYEI@YxD`HHH+b@n+CuCG_%O(9aGJl>Iu_LAAdy5Y^G04dT z0PgntCpPn!&GWm>r@heEbN#U(qqY=WIek==-@nbS9SQ3!Wh2S?KaWO>=nG~p{pwT= z@yt0D;~VEFE!er#Pq@1K*N+>+1tVu4|5A0p&{B88Qp-n%6OKo^cf*^oF7=8y{UEK_ zFNr64XZdRS)?Q|VRJQ&FCTuw_P7MFYXas|e+_W%GTGo*HA48;P=a3(bdR#rVQTv=+ zMP1i+R^3zU7hyek+flCna(2#xl`ezwE4~Qo#l_0XOTx+_5^XFv%Ni(s?nVzpH&x=| zEIwA=R)JA9e9w;|6xfG&l5==nef>W6)*Eaxb#azktEp#2o6AMz$6ZiC8#S8r(tM`=D+ZZ zEOf%7`kuQZy^}hiCF(m*=rhc2NC5u-6zz{34TV|L^*zv3WGI9_ZhVQ94AL6%iaFh~ z(Zn>|m%a5K>Tl*%xmxqx%;Lu`gv!e)^xwSbMn$2rpw2ESlo}PiBxiMrV^E(vPPcHl z?P*?AZVU4bWTlD9AM=4zk8iZ;^#W^wsRS3GtY~X#Q<*se`qzDXr^RN9wcgsrc_#fe zC}nbhpHg%v6{qv7p89so$m!M1i zW4%3q+aFqS9!qRi{8b1&GbPK9g-OkWnW?e9wK)(HF#i`CADZE%syJH6<+v-j!uWzj z>kf}p?ny(r6tGYmeSU^Pn!{ zsJ@@Co3AY0mAksigptuHOP7DZmm6Nq&6b=7sdRtJhvAbEj>5@0n~M>&qg0H|ROi|+ z6(nTY-R58NCE>+}LCnO7o}Y*X>W2|Sl^m!6{nejK`a;LhYvouC+QQN0d_Zf&U4d&K zS;U3nbzncTX!&G4rmWJbvHq#RjS6+%U?#OSXalNYUjuuPItv&TR+LJ1*Q}`)CQi)N zT66jf7(a)8rjH84G7VcQ%$r=qab{oppxY_@DVpt*`%ky`<6yy z9u5mCRfwP|T&tHm06Y{Y5M_1cs<-q04GxFfJz31P-?@(WOL;rkcNpI8oCd&c^5I{^ z{Fw~l09)bA_d_ZhdevAsNe+;sJ7la6q6*exKNs-!xjFmJyd?#(wse6d>vfF*qUa>I zG_Yvs3KX`lv5$@Pj~r0^9XocFtTv_5th8$hy|a3XY1anvx6G zHiL*n%Qv)rFJ7M$qd(kHz&Q2ST)t&7NrLK!xv4ICLj}HED5VHl__^XW05zZIP=+&? z1kD?qXET+}%a`>6=%PO{vO8C#tJ`ON`9oSOdiON2=c)NX_qO7MBRx@2zM3J3W%>6X zbspFivB4rmWe<;AiQd7{zr)nd(VPYqnUo^!T}QPZ>$#=Mt+}E`faNB^O8L0A>Qo^X z!YbrK!)4*JI9NVv>N0JO=fb9-UoI!6qo_$$ms3fWGwA3c<||b7y%9a}iqs=s$EQTns6?ZamQ2ptyoV6sZ9cm3f215AxFy;rZ`F9-cVrKl z64IYaEU+xx7JL39bJT-p(6|@w(O@&=)g#(lP2%$&T_?Q*XkR1@8SmaLhAghIT+n-S zyyTmaAv%>hdDc9V#vf~TnLhHuORnPLamF@w@4j)X+3?2R*{-JUBiH;pLT~P~dGLty z++j$#53`SZrx9O1Sb-DFXFE=%NE-zW7FT5TerO>EUDHu1L-nhO|JEP6KCpHt@#|=(741JeJn}ATHYU7h`QYo#`Y$@Ij|y{1Bb%yc!d|oGLxgr!gQZ4+`B4%@D?DGi~2G%sMhCVPvH$yppC& zLVGM}4x}BP;XEv?oRlOA=?o8f*t!@A_9x3s&M? z&wm< zI8O?AGP;nRf%1feEI;1K`h|V5e)KXN>PK^T(M4?NviwG%$F1+ee=)vSkEst##$J{B zq4by@8=3P*Uff&s({xW>n9^T>b-vw@pX%z> zO3Wtt{e$sYbX?c7if^zcB{aqQI%c*}U#qbFR!0NkRNWGDfqP--1`>ux)>2UwjA zAPc|SE0&`X3AXU;(6x#?eE{2#W{C_u2Ayw|PW8QB+0|sS{!Su)NLl{2t>ZYl$qSy z)F>!uQm3}cs=TTS-WZsOUuKL+o#KAt^|>F&T)*sM@GfVk@x>eC5gz}**_~~BsC(Ofr$H`-+DOa2 zwbgmO606LC(&CxJkxU|w0JER~c8F7u8?Ep_5sV?Ld0ghBe$)DT{;urlPQvN9H%ynT zo?4Zz?;MwIo&8WGZSg!DBo(XIx9<_ht2t~~CPb!85E46mi?PoWMtwHf(qCbIO2TM& ziK=?}^BZntDkB#z6Jha&<5$~k*QdX-X1GuDgySOtc8pXnhaTA__Js;>JDxKMSxtW#i^E|46&o?oXJ@>3f5Q^7kCyFL45a<+c#}Rt zb&^;juvFpSS~30l=)=P`t#(W7-@Xl@Z*w?Drm-oOGI^kY-_L$n&~8kQfW}vEa3L8T zJI8G0`~9bz0=lwK4FF?fAOs6{a!UL|lY*^j()eO#M(T(U$9kUL^jgtw0FI2mVrb$L zf#j!?`DpS7ZAcF{)|Xs&fJLcIyJ6E>9z~pq9GW)Ej5v!$oFbk<_jLY}o?xI#D!aN; z(>%qdiBgDO0$;d~=%lYn~UDBV7_s`(R(dm)7-XEV2vC3$w=L`^R}7zXMT(AeL*5>%k;#wLodx z+in{k0!Wd3q~;t>1|L5tPUW9p?k3D$1BrWtfGGxky&0u`K0@BG=d{jYb>L`*)e-_( z+AEkPXzu*SY5w7V;UmW-i!E%o+}an{H zF1{aKY$sVl8C`0r<*Ir>#oD1itm05WBg?x^?gKiWY2R<$H$UWbXtiWab9DMBeK+~9 zP1hKF4AIQa_0pTA0l~zp1U*Pyp7P976M@}G? z=47<-)e6Ev`}IwTw_3>FOqKlDC)4h5YOP8Dh62(Y0fM>^YGm$j5)&%4{PknA(F8d{6!F-wrq0dsTwHhg_6~9DNG*KX4v?1rK!vpHKDeBwxKfte z_^g&sY>E1L_dKQCb2okRQ!qYK90vUtE$8Q9qRiC)zJ2$1pHJniQM#oMm_U2*U-1Fe zuqcS>XHq>jGWA~a-lhy~?liQb7k?`;h9wAWDC|BRZwDV#0skTFhTcGNGLL>V(<}Ig z{IRO%;aZNtR~L3}h6+k`Bh9=>r$U*ze2?!K@Q%!s+I*iTV}nJMF0s40MZoq6J|18( zB%F+zgVP-55z(5d#k+?AL%)uRS9K4p@VWoXdiwl#>hH|ZG3dL88b|IzFkJ!S76w2D zirY3;V}8=e#hk-_P#(vc!w$@y>%-mRa9ht!oTeK2vi%@gPB|Nocb-??IXRIy<3yDO zBs9dw)=9|+8941vJM_Pm!)S-UH76-wV##?~AWEIOU)D35A*2o_ku>1#dHhom`>xfX zMGvlSoU_WkQtAm|S6#nuZfhedW~o_v78DkO|viy==ThtW}}yWEJ8BA51ta41R@PMe+bvlRBlDB zB=A?WAkb3;NX=&8Th&cXc7G=twZ|jY1jIZpK2)~pwN}0ELxxKd^*i9FUoFo$EzV!; z*N7&*+&D(g5O(I(UkuKsf2B7jNbqrN)Y!LE=~D-qeA*a% z^@V7d2p9$w9eB3&i$39Al3}LW8;us%KYyCPRmd=rGt#>ekfMuF8_7?By4Lf#_6FMe zo#R=)zVb>R{#M+(f_OX-kf!=Ut8cZY5$_fmI1xF?SwZvhBaom6LPy_pS%uO<05Y!o zGK+F0=*sS>UyCa^8~~9>Vxh}$-?NZ5nM-`0vvW_un8C8$ek3hnP?L3&bmQBhS4%(Q z+lw=jITSkNK;zbpG^s9bM0Xo59WplD?EAerdzwSx=&v(X>|e^cIlCpj{W*BUNZ21D z?OlWIMu26L7kYx1Ev{Rwo0OLWHGG+RN5Fdqgr>1D?Dhfdp!QGo90@R@?|HQ^6?vLB ztA7@C0Ac#h>{b-Q{G*BJL8Q#dMpG9cuutaKe6t8TC@uzb@EeZI3j8e6&YA=gg~-VIluNEn*6r+Ax(!7l}ITEn2D=g`y$O>&6CoS`_lE})^M{f{SFeSu%>2D+`eDmj;O$C$a!*C;iE1V@>g5ov2iqEXGDWUv^ z9T|)O{k+>9CZuO4_&wn?-#&5n9Op>=T@f}JRJiG^#{F)w&3~K@^c>n7U!8Tk0INNd ztZn7EyP7 zw~n3c8u^iSd!CpV7TEgv(JH@TSC_r!6{eebnc+3w9q%}Z2aW6#s^!j%1^!izK6OFU zi+(2`s3n9jVvW*&Uz|NwbJV96;ci{D$s~C{37evm0HF8QuiSd)1M> zTxo`jzj@e@`!+|iZVrta+$-n<14SgxqVJ+n;yPAMS0eh4^w)0OQXbD7{H*(3+5k+z z=0{PhaY1F?8$X^ZG6p@j49^>LnmK=ZVyPp`E9_18&}OSl(AO*VIbAD&`^_Pgkz9K& zoz&5XkSKjn@tv?px~l5eSN$2B=axMqqr=or%mD-om^X9HQbwd)-u{auzT{x(&<+qR zfs0Lu#tBut77BR#zL^qi-|fzNaUGu*WNJ<~5S~6t%!jME(3qqq5+gqRF;A>|nz*d6 zH$ayT@lK^#Dt1Y%ld3(lim4VyY$ht=?uqu2WY==}53Kfph1$7^eY0Z~4MAU4{=&%G zykZIM=`Ie#g;ZFD$D zeWU&G*sUlN!{%B;>}jnV>O?xvUm@DnZs6atBS0B#-vLZbMKFU$a5E*807%){n*F!y zE3ZYhcH-hE0m z&lGK9;m%msk)2>1;avHaLesB37}U%QQY^Ai+Ok4M0*6r6xDN2|-ld;D$6D|-Qsn%o z1Ki>1WzPZV)D?%Np5Av3FRfSW<}}S2M~$)OTIo$dHHv;0{5vRHUy;KzHIvJk{8v6H z4FY6pM)#M;;_sbY`%-x5V2Q_AOZOMBP?L=BQs2xUn=W>4%!YyYr!exxJX1P5`;WUQ zH;5-(pRHg|NIqobt;s987_IFeQE_(<;p3Z{)lb*U`GSB%$!mle}WL9j$TkE~WZ zg`Y`oPH8va@(Fy#?`jUefhX|mX9rj&Kf(Sz)Sjp3vRt`O`;9X>s+3M0=c~miFv>^U zioA|NBbdhbMXv&WkO^{XgviAC;F|1R@1?H)N}b5e*U#Qirlx5T!$$@{ngb8Xl~Wa? za+coAR)*n7Shk4-TbEBIWTO};@Fd~!-|)(xr(gD!N2W)julp}xFI>@KW4XZtL6rrS zCOWgDMj#dEPQQQWT%Rf;N;*1Lr&YNY7#u7z^=a6ikDMl@3>VPnZ<0yojZ?f$KANYg zwZwSxf;v`2%``4=O%`ysl0i*D;7iq()&eFG`JJE$l?D8t5_cNbRzy(g>ZT$L2S6e_ zwr5&xnlC9h%XjB`+rM(Tu4(2}&jeysZ$h2X0uu+F>WbXRfU0Owz4cebO!7HS@@rAhTz*-@Eu z^2PK=@Qn|)z_wCLZ%^~9{lIuMGSX~Glzx0Kq>M4D!7N>7`1%VuK;N!An6a-S+fsDG z;Qh}x+pBqf@l$v7vt&WlhjEwpy*CD0Q|usWv8Y@b_NJs2eZ@l#r?bdE#T00VnEREx z%W8afgmA|Sozm(FZ#t_!Sn&mB1SFfly%*5e(EK(Zp`chQ*S3_!B&w?$MKgQk&b?%t zvdwBmYek`K0Fu>4Xw3x;jR1BB>dq#V#G-5kEZeLBwM=2iRA4}L}+ zIn4T#niYo_3fQ?30+a`~!`4Zuqcckug=U2x6Gd@>pCn9T7mtCKjrOC|(pcgKW6JV} zHxvU8^-BXfR?sr4!k?=@^*3AG7c1z{e{ck))QraR^#J&mS<3n?hH1P0Spk|r9zynG zD1IoTdAKFbVjm{4Zs(h8_fVqi;B|9tmV3_oG#}m)D5XgONYN+|J*8gejpDW1{X+`T zpW`K~^Db^u>Kp%V(Lgk~+_!3dJO9jE#ZGAv$)UX`*Rooq*>!urq`VlPo}2K`TNwUi zP*>EZ^QgMqbaG7?$n*QANBwV9H%OINO58A{$0Ce6M(5-`(g(_`UGGsd0x5# zPf?fXKDyp~4X&x=Ctn_241y*MXg+V=E%v=Gloo5IxcrT0qlani&q_hEA-ayS?d-#~ z$=}xA-&X4kU}406SBSGt8BU`L%h!GY$fcs$-lb!Q&K(|4-fwyiCh+EbhPmp_xYg%KM?}ybrTFrm0~CgDkGo*Zrip%%PqCwX1YlE0Z9L!5hw%GCgcPX)4M2yc!zgt4mzJMSCWiA3 z1~|eZrKqI^!YHxM{xVVM&C8Li#{HXij+z1CtU^H)PNI8TS$`u#2K=+LYML~gh5ve% z6Bqx5lduaW69e1?Cz-1*hG}n@#8UP~AdxbierVyqJ`Dxb1jc8miVypUr2Bv!lzUy_ zfjpG>^@`*-^2?6c4{t%A1%$eadWTitBQ>BxLX4-pBDC`y&3i+Y4=xJb6fYJL4z?s- z-7WT{7nbw3p8ja3$7?&q*3RUv#7E^7u+p7t6SejD{P8P`7j<$dE2PA=t-PRoIwpjg zlL}sHXYm(lytm|7sKzwfO1?B-he-tp2J&-{SUUH5_a-#6HGV9CROqrtTe81x8~gce z_fKtg`Xe6b!#FiC$Ml>mH%S?LC8#XHRUbb$aFr3^o87_yWl|oG{M%u1pOqu)&3`Mf zAAy_k*7286q>G#5fIKy6@y|S(Y+@>qt4EaydLW%|n%eEe?Tn(4} zFKyRnKd11lKxpMjgU1TAr)?kUJ{k{3F&KNFKawVn6cB)?^t9R@?*V{&y3__W5IU^T zy1Z*Ns_(RRNTmJWJAN87W#&D;-@m__A!-K}e)A2avchn#Z)M($(KoC0In{CgNpFqF zu`ngGx*QF2&At7Oq7>Gz@8|Ruf_eohELzs5zZdQTDwMY@P*C6na){?Aku9&@5XEpt z6p-*xrvWVz)Ou-7?}0Ng@iHeD#Q^jQoP${*SoZ!GO$7P}kZ3^i>bc|@2Z#ALh>pIc zXw4K`t*wfE+L z2nhmiLQ%JF)F`C&s)Hw%_N;|bBBt5vo{#+?Q?tVJ;@obP0=KuQ`Szau-rn;=7G}!u z*5B?FWH;yTY7jhxr{b-8bKgLAD;Nk1+SXffrRBEkp^xW7I%8v8$pQ1UWb{QRcWLTi zHG>Gp&#WG+r$LeH&nE7DGjvRIJi5bFxRo9Plz!yN(cn6h?oYTlsa#2=y_uW_j@X28 zeUTsY+bjK}Y1b!FmbT?Cuk-5Q_xhmOSKn6x(V-c=(<8i49Jo$8*~n(vQ$#$*yFy>w zqCb7fP`2sKVEjaC=<-D(^~}J%WRC{!Gev0#jv>Neo)KW8 z2*J1=6AhW+QaFPk(kB7mWQ`#M$QKYTY8x_(8bjZ1syu@KVnvZho5>==yoW*#B5K z-o@0(8I?^gE?D_`A8bgfJ7>2$DfmO&(0zvbDgfc(-*yar9M}5h=P=`^>1&2WE9L_k z5QK+`Qg5i#FVsoqbwONt-qRit7PH`N;Q4> zSkz=p25ll}q}rl< z=pLid_u*YFQv(pglH&1t+b0$m^5e$)L;2F`Hw6ds*BuZAT^4n_D zKm)ywba!g%oXqg1{~(0?=`6vm|JjqTk-yBU%y@8!T#Ca24XK=z)&MKC;yO3!kS6UC z6Yib}EA@3@!2b^_G)tRQMQH14;n zWpQ||xUR?C!C@(1N*HnqD#cjD%d89Y%4#FQD*~BC4enCP+4Wr`&_n-4osMTdA~`jd z3~wDK{pX~#pp`jW-$pNi1})!8!WDnk^=3y(XWJ-a~rio2~UIpo62E5(>9yhfBJrW=_|IcNSYxey)=n#!B(?^gP zr2FYsf*3;IWX)%qpKXimx|MT5bWe$f>Y2(<*%+ zN1!7;CLZ*Y+LSF5l?CXLpun*iO3UVSN@rLtMsw5@X6An2&V|eLjGfpiT9xO4P!^bc z3_T13Ixh&O3Y4mqzSX82IK(ya*0l&^IlQ*)=U*E7w@ijir&iZ4^RtUgf!hYs8+j&DCvjdPANAHj5P=k` zLX>?CY9a{G{j}wC0^)7Y46N_}%Lb)ivoi;d>edlWPjQ!R+kE2h@Q6_AGgsmyc%IJ_e{VH%eyD z`md)&6Tx`3s+PL`Odxv>A{T=d#=lL(Nyl)4giXN@(IU$I)T0`pJ*kw5#SN5gy9UBm zYgk9>PE{}K>18k>poXXtS8)$#;TVks`75jIGt;B-=g`o_CefRX%LZHbl$r)jUus(~ z!nV^0{NJ{>hI5I^%^9|0$?KlKuidk@328vN*r1a9M18kFnnLw%|BWUxSbF}dZ}X6B zT_#HXmefDy9$qY}b&}9QKg=Xs;vsNi#p$x3wbuUR1w494A40y`Ry^_F3qEJw&Z@^I zH$l}NJ2lK z`US&^158|)MLRKwDT=H}TH`j0p*W^kIxbbj?AME~MmKiPcxv4>8Gc~V~{Z^)%@b^I2VU8o29 z9oX$qWxhfF%dDx4ZMS@ZFSqiLzCOVR8mwqO_t2=JwMhA7@$lHIH%~oX8zS)7L9?K3 zw1x%2A1MzDyo?%=;YQ96ql(-%XbxQTWWLxUN)LOd#?WRBau#v}X$&ql7I@zdI2mpQ zMO|JgU-=p>6ujJbZ&mP0s+y*)k!7ZbKT(>f@OLimZnQ`QrIaXA*L@#53# z&t{)!S5E{r_jRbi2^~w z)$kGjO|Sl9O$+mB4rll+inum-i)InN19EHhj~h%Ndq5(A-|Lak-rrqJOi|8?jQZzI zZ#&}D;jN_n+`WMZcD!S_{ei8d8Y_|EDc8(98ImKiVDi;D8R!h49&7>niibyJzAnF(kuc-141Za56FE}tH&6H>gC4F zhx-RgU58O$3pFP*OjR#W%&4?$Dxalu$`)63XIu4o&O>9I)UTC2>mCdwKPj&>almgl zL+^C3oXm;ABl=!LxiJU@$zMBhjyh{dQc7Qb)bMz4|L~GjBVooQk-vQy@L4}o2U%$2 zUv%5J!?ade%y7_G-!eQte(L|v0&FUttm@P!8EoD(O@?Y9{JmgXjNJGq;1BWgGjo2w z(eR0Ih4qFN3n(&g07dnlUT5XsXP@N>C5OKyEw{ngA@zHWKum4Cs-%E&c z!IOQMLkp>`@G&rtTUw%1KG?W>(KO%K();n(+d7>{%eVe86L0oPGgLLYGOMJrB*I zPLdF}9)dGbx2bdWn;%7uz54M@U|r%8L9|2=UhwjaOQ zyQIEh0_q+F0-m3Qb>y(irr7$~U!hGUDTm;VneH#PKTb4T9uA9J&b#1aRH{{S66fh6r!AEUz&Kf}Sx(1*CS~Vd z(XF`9laNi%*uFa{;_k94q<}?>rUI!>4ds)oOa#_-yQa3fw4OVmZ_yOnRo>;$ILM~! zlm_bJzipdI$-erw^@7PO-iLkC)AmY#1;Q0Aq*Q^cZ^79C?H{K-cSLD-We+3a_M;=ehRwVg{EzL|#~moJTHHVKm9pyQx0 z^VN=?*CsF>NSQOpXU_%8Op$~r@Cjgs53p+?IkTNm^hW!JOT|=&fau!Wcv__d20cGV zS?B@mXJPG5(V5!lOTe-Z)f%?i=7of)ho}ce29)S5+^be^wmNmtQ2@dbE}xuUpCc~K zK@{)uObg=fJWwJ)<%jYL0V6|g;CHWhKc1}E^%Fw0JY5c#Xf;O9>v%+%rhDB$5o@1i zEiOvEw%>?i2r1AN8Z9vmhL4d=#}7ikr{DO?k6r!LVIP02>)W0EyFEX4uG^dJy#6Tm z!bP+@CcR$0@;}b)bdO&tLa%L&9}K@6&$Qm?%arB_Q&O*DE$MD}dfWPDY`=baUFIOV z3-|J}s#!wM0;U0&4l43Vv1#Fc6Q&iaa&2U5YHZlnwS#>Z47)yq051ZGAlR#Mf8d(2 zXzZNrJ}wg~OFr)g)Y<)Cd0*L-R})0}Ai>>(yF0-x5FCO8cPF^J1c%_kNpKP*xVr^{ zLvV-S?oQAh-mTr*{jz^xDQ*?TbK%~Z>FGY*eWqIl;$mz4; zVXwH>h{Ab7HKa5|>DqkxR&ZS3G1wJ_f`@dTqifsl}hX0x~$DO+w^nP#03wth+>L9X}PN!mEF80g8=jADq z(a`R1>J$wl_Xv*n=B?EYcBLfz z_6{zS@d*D&72{O*j)+$4VyPL)6=U(Hj7_y3D($g5f#o9)I$o`%2~by8_Y@*cNJx0- zO-x9jXJSHbjO||QT(fi`vA48@Bnh4*E(cLeCdhVEp(gRBs%ja^fLtu#D&tJy(@$Q# z!g+%O^6kpQ{#L3_zH&xBhfx=!%Zurdzhsr;=Mf>J@S{ggH|-1;5jzcZD49tDu%euY z>DND7j}Tq^W_?YMQq|Spt+ozqu!28sqo%PWl1^=EHsJq%-qC zDuLQ9vtDv5z?396wvOt)n)!Yia+_tYOH&r@a`eJjHE^f5yl0&1yz;Ee#dIGD{?D|c&l{{o) zVp7k3 zWCyu+V~6R#ibw(UpUvpZ5^+;|7P@Vke9Tb^UlU{P3P&anO_XB0V%2V`SV^D?s1#}x z-XT%vy-|_ai`6K(>&mPCEN?$lbAd|(!v0pSJVB*P2)9DbgoH$6(tGOYY}wLjY?`Bh z6EZYdT^MyG4=bt%tNOc3a#PUJ1e1(xH2O7{;-&E=0&8m2bcv?RxFkNwtRi`#Aehpk z$-OjoW9SmiitY0uHqAcG3WJdhei!KS@3RM>7GP#?oz9W0dJOFlCqTir3=3T|>t(hK zf4cyjH1SvzWJ$LgG6UzNY4hKkfN*bbVKiNbNH+3H+m{y2nbRr!)0PVynlViX^yy)f zpCuLvv`DvcTwgHYfsNyKDzHP|bRk6{`I?y?I=mqhk>a_+fP5m++h9=3BAHAEqtc_E?!hQOPa>wVoI7{$m{ro;dYBfsQFF>?@)h? z<~7dl*9s%0wUSOdcW%{jyPmMT2B?2%3Wg7|- z!J%Zp|GbfTLz9)n&kuYv+K<>Eh-IB_qg`i@`<*Vf_qd8_1EiVV-2UR4EzL{R$PcI_ z#yfcugOfpy*MF)Axuqnhr*+lbcvpSHooZ$dc^xoN8kt#HNn9BOmeCho`e|Ag7;}|6 zca$(-qjh>PgaGdflsK*itekhs>$~X{RzKI?u0hpmuz(=a6*ma*N0*kT8)mN@nF7dZ zg2Ev|wBXC}9d&$Pt7z61F8zboUwKDa)?q>}j^4EYUCRO#6iC_Mx6blCmz9&3ANcdf z0-TpOv&bTx_5f+q;U^;=cxyCQ@ApjBuhWGzXnYbUXgR3uWn?5vrk4j{N=Q48+^D?P z(034p{9>c&KWE_kk=oeIRv#DCG+AtNBaotlSiP_3RrrgSbFs+l<^4DbAk?cRcc1f* zlT02PW#t--x{PsO3F^`HuW*}Oy)*cP759nVUe2etWf@GEj%x!p0LYf(^o%D-6w`2% zTSasCVwpzoO(V+`noiIo>4SB#DtLpW@Jf$wwac`<(X*9QM~@}*vvL1FjF9T_`6BnX zl`The%hv(CoPE%HK6_~h=9OMGe|$eAJgC0TBQM@$#0i>T=39#W^1G^J)^~avG#&y* zhisBx%QeLwTY9Bc)+Vx+CVI7Ty_Plr;<4h#3$B|8k!Vx#X70>)b>R?DQ9+BwJ8_bh zi`EMT?){CgR7JO>rk^j0!1^|2}?jaIAmUtHL%MnW(^gmpV+xLnT*si zGg~5UFrjkJ@V*idLL&y%53Y;twZDM$&lM$b9%(2T1A%#pD3AbI+h8o|OxK5L7TKiA zT^6m&w#f|b6mvjGkb!=ESx3IX!b&r~Nagb&;?V~6y?4$gWFoI2CsiPvj0%AaRF?os zN_M-Ge<_!I$j)L{EMjB4(v3W{dSD**?RV9G(e67IR#Xwv@20PH1hZN0qvwj| za(<8B@L_g9VP-5~Y`#TA#0&`y3xl)eAp+)~t`uRjdHd8WmAw}Mek&Q)TJL#(N-G;o+$^It~9(2JQMi{T+0rS9qxIO*?K0^tV zo~S@-Hvx{$wZ<_BoaOb&Wz&BK2}c^U?+wOdgzR!s-}K%Cxl^&J$OmzUL7I9Z>fmA? zknok^q>IN$ehXyCskc$_$9P^{<<(HxaFgvHbb;2XeM|H42}uQE4@MA%^{wOl?d+F) z54Z!x&7RC56Xb-q?vo9}t(LSL1q9Qv`N9h~)b1)v&QQn56SBeCz0?_i1hSxabQ|sBIJXymCai8n<^KgPQG1nn>66d&%Rm zyrQDdx{fr}FUywi2)9#}1W+oL4;FD?14aEGKfc}j>~yi4uB~1j2~zj{Wq-{5etB=B zr4u<5fs;3_9QUYMZKv7>D^CLci{}lj-Hf29N%^_{A)}^VK_Xym6ADC$W?aAnhHv+l zTRfQG>x84yA;Ugk<(~X~JV>WEGf&VT9?cBNe^I}cfK?IOM^azZ?J1i{-mjgU8Lyuy z$=q{|oe{`%x?BKD7c1aqJw0BZau(gt=91yL7fh`0@mM(jk&c4c7$_U9vB2b71Tf`=M{(Hf@V?Mgb7p*jWI z-b9bNDpa$usIgDHO{-cOdmkl^ zr1SL0TK|{@`MdN$Gj&d4Qg}upMyIwl0XZ9a6%Ea>l7f;V>r(NUIyj5MrmIPYZ)aqp zeF1CRRG}?&6KhVLmKC4IgJh0jWM{6G1fL3w+Bx4PJW3n+oe6& z78F0ZKJzjOB>0evLz(-TC<~uc+`c3;z@Px*lDzKLLy)AEKJ)gC`nbUFo0%8e>T*2LmJ5;5 zDXN=sX4*CIy2U;A1`~Q7dG1)bZWMl^N}06!Pi)k5rc;~G_mO>uOgnCL^b_f6c=L?L zK}*@&pij-8EFIrCzMKO;WLb%7+wy^eyk0;V-W7#WG8YLwJf7bzJP0>Ld3fbvs2-zE zU(P7C79&pF{)s@6HxdZ64lK-bJttHhCsxrWqo+2Tf;+aYz3$slGgZQ-FyxTe-%x}y z|GnX?eZ5<$s1i1z73%jHf&)nc}liAnEyD!Te95=|N1~oDqWJe#lnhwqvb9+0wb-P z`(1Um+bP>lFC3rm;iQ{@%Nm7%0tRfK^hLPvMW~iVwDh4~mhvhAzcxvY23)+tS25+i zJmJ0R_7q#9&J|R`Cw3~4$xH0@-A4hxYy-gZiAcq1$uc)cMrq_;jf5uO*MF4LprNYM zWo#a35u;IGb{i^?p}|2IfBzSCd2{)eHB`vR63vLtHIzSK?X=I&|Mwu7rg$fUk-kM} z0PgCdLr2eQ#;@JBpS-ZqkSqE9+yr;~zY;xVNWP8_Fq^oWPVac2r7*@!Q*hEljF-cI zS#sx{N>OBFrBFz-s8jI@Urn~8DZ0zvS9OsF}&ME(fC=kwa9PMAzo`B?F;u8t5$K;yV4%yf!1 zAVr^@C6axg(TF0nLA5TcE2{eUccpeoA|@Zs?OI@NS^t8W-=7Z)`F8-kGK1Qes4Zo= zq|cc5U14&?>(_yk^l$VWELtf^BL*dk%&mXRnB-tEk$&!Zy_O+8?YeQPTy|^kFzV@p zNC4G9mM>l!@F6cmE^i%AZ4XC)n%+;B&n@l{VNG2zxI5(lVd1}yJWV`1qbQ^LW z>g}EB7{wulKpC zEnhPfzV*rBC>`EsV|Jp`x_>s1&Y~n0&)UB4>}jZTs`c6Z-S32x~ikVTQYBo4$BmUf&4d_XxHITbzi==EX~;u4`S>{+GGeN-XZ z&#$7aZQP>lWH%}Ky^Fmm74hK1jK_9uCDcuEt?lX>|2mS)5|x`8{%a37!9>%kHpAR?iJajBZks(Xm9O5$&5_Ee7p_-r_BD<^ zo^U(AFX5io<6)(C78}>W_AImdTsu?S)O9Z!{y-;G3XggX_lA$i_a0S%rLwtfNlzek z=Z_U@S?K42^iY_$rlzJPqBX)mo85-*Z7a<7H2jsrA02 zQFn?G+NAskgUR>^%w5A*XZl;-7<*C_WCt9|XJ-*xR-zx24EuIh?EDJsf+Lm9z8&CD z9n~&-N9vVx2i1)LyfQP!JK6*>3Jpg#tmXk<+BT?+6I!kIa+x=cW>p!gAR%ASP6`z%e-_^90;y-I%`)m1| z37@mA@MC|VQTcWF#zpD2DnV3i>vg;nRKN}n5hl-Jy_G<7ue%_<>a6*C&0pf%rXE>6deX8l6}cYg0u3q-EN*J*tv z7~iABpy7OhnjYSLjdlhOv>R3!6H!!AwMB5oqsUgtLglj0?ReZb*y$LKd}WX0QsPs<%cS#8)>mFPWe|uSXa3JuI_{ zOZAV0UuGw)iw;&=vE}=}Dil@T#}U}wY!+k+bm+kMd^K0|QR(*$!N2S{((GG4!sVD3 z8)kz#t87&+k=!&m`_8UREVC?DmwIgltAEWs#FbHk{Rum~Q5ebr-LL_dIK2ZOQDO>) zz+wtU2C7n(k^^GTuoPtIcfn+~SEGD+KnV$a=6`nDCQG}y5{f?L#}Xa6XRvk4;K+LE zD31H=vhUw$+zWOBuyL~&@Q|;~3d2L+!mHYP*DbeHeBHOXfbrn79Q~p|-HqLr-8p*q zhyvBM>_U;((dA+0gDTR1xK!%9mDL0SAD5XkiZ99 zHK9c?9G3Iz)cJ9X2j;V4E^?Z~?sH>BfkU|FmO!SW?X!g-srMxXfnBdgw~6%jIZzzT zWHrRdq}pS-I$b}%`)g^8;1=Ti-QG_ii$@rshiPRsWL~yo|U(9(l&C^@eQ0X z5AWX4-Sg>yp@D&eM)2)Bi=bYjM1Izu=SU!6RpvpZJ&W{oP4uv-di6e<8V)P>$Iz9U zI}dZC5bH_=Wxc@hk;TS)@TP)noD)=(YIk_VMU!^u8B|HMGkG+Ym(8R2{tAG15R3DL?=XJ0>(vYKG!B3`k2cA z6MbVn*6z8B9Yu{2H;fw1>H@LB%E2UxKk~hZyLU!W)r`<-w;@XR?H?w*0gQ@hX~Xv` zip$ylQRp?3hseq9*w(h(di_Op)6OM4px%?7LvlxI^&TFl2XYd#mgnl3o%BY1y?0Bj zQKw@`Q@%I@(5X0BJ(;0I4fs}Xj`F7%Tt6rFP)K0~TibBsn7q2Px~CBP8lYvxe9}Q> zl1qR%2un?mEpX{aS^?j1*Z>`5I@w??&uy>ckhkz*3m zYXg^b98IHUIVfoye!apSSmxSzxCKb8kUJj~T_W+B!8$!Q;}j9(dGD3t?E-&#qRbfj z5+)l=6nPu@anW|sC*g{#M9m{9n+tL#~$z#L3ja_h9Pr0;i zx}K2ok?nln){TAsy)jvNJJDB}nV&B*zsSuU;tlyH1_h>)0|GbsAi7h^X0cYomA!UU z<*-r4;jlcbqm{B%AOCNC34e)<{n>gJfO2-7)jXiW-@l(8f;c9Dg*jQ5Q<6aOF7Y zoiM7gYJ7#m?wC;&iK7W*6{7sn0dNe}8qd|CWFe@d)mcDX($!ry@aW|5fyzC1N6+uz z9a@o}zf5Z@K<3gjz-J3gfa+#hvJ|-a)1hRZ!5oVm_r#z0Bq{i-+%5U-9ysA@I*W!v zCQNM6&?Ko?;sds;e9^Vh>SE%Uf2}^fOz1?*wM6e{Q)LyMz>GEiF~+*3 zV%ulZ?`viR-}#q0r`cXHePr}Ojlq+1L-s{gfImgw zt84(os)(u|Js8fFbVhI}ch+}sC=?&}YQ}`?eZu|iYhk}zTG5ShFYFtB*;v`nx2h~{ zn7#LIC~Y5G&z9foX!9q{_dn^nufp_Z|BzcNDP!w>X`s8tkrY_X6<0W7Zc~>U?^DBz z7~imR$>E*E!o0zg%EPbFp0!#3x8c0*+P-%sg^nxhH*Zb*-sL0gyZ<$6AzeQ_7!hJf zlT56xyu+D@((m=!)yc$clgII^B_2*_sel1LIx3)=?kf)aUR=f_)#;yU>D>4()!Q%l z7ZNaU-0P9r-u=f#u3?>{qILnhvMZ7W}=3!Qgu-% z?swkuq!uaIa)c~tPBx72$LLcqFQJc5D3YHqEVzm(PO@t|l=c0hg3pyxUz>|D1u;9| zHL~kO1Apvp`|mPZivF5{!&e!1Iw5y*<-t(r3=t|VtHsh>@3!bz-gOlDEiLI&u= ziYu+NEujP6y268Y8PKZ`2-di)gqT`+vRHA#T>;zD)57Ja$+Nx5?64nM+w_nRki#TP z)Bxro%C$DwDJ>hv+pX@~xXtI)770lE>ZSg?hnByqaC^t4u!k@(oAbdRzt`5|JPTbY z9Um${fZUK?RPU_q4Hr`253M;josJwk`+(0iLn4l?0yMIq%p@^i4 zIwqb-Ge&y$QuGa7TO8Y{UqlD~Gs*qnjZ@#y&wT4)LOx_RRBuFR1a<+pH@!C`qsupm zua$y;&IX|6II5l9b9aFvNi8+!M>DJqTG@*)lz68gZtu-n@I$GoFnDb-0nAE>2sV4} zDD3gKY4e`f8?WsIz z5WP+@jQICwoy;;c=D8eQu{uf0q}y0moFNKaISNcUavX#vO!$Ub)YQdSiPNwe{dwc_ z{qI#k*xgZ!#6vius7-)~e)3Z_WH#m?1VK3uTWZ%@W0w_e7)3e&R zD(43|Tb6~$uP`5>Pp_ie*l%C8f-7k@bt5q`+X!SH^tknVwu46I^eSI7RO9GP>Hp3+ z z*SQ&3`cs)W>6fd~2G~#h1J=CKa%S7bOAM?CU~4~2F^Kt$1fO{dx3d@pz3N#cO5p9- zUZI-+w(!tufiabB`0mCgI`Q8%tXgEUGH7w@M;40p8J3dut#>QwobWYX_s)C#hg;sD z6Wg5V#Gc$wvVsd@&BRCn)OjypjMw-aQgF!PUTxbd`$Lte$y0)}GVzs`;L8%Mv$zf|V{O`;~qD zj0li=+JXn8Gnez3#0i~F={71&?%U4_`m~&GUybiyhhVHc*Lmij6m?u1X&X8il(a>? zfA>9~5VSAvT(9aJ@(w1IoKFGZcOCbv{h}=S3`C_IKk6Ug2>c${$iZQtz#bsSl!f52 z{Bf`+B!4utA*G+57$ZiPITi)O+6Ufl?+t0(SzDj!GWNmg%(D;jt1Rdjx5Gs2e)|LB zEAiuuwd4)Wb?}GcpY<~0i$(H&^HRzDsP{I@c76$`kBl&D>!0&|1 z?W;#Qchg9)>jHvR1T;Ctdw_Afah7pxGnz3$+awZ^)EPGI*X_8@RU12_qziRS16 z&o*l)^|a-?Y51ov?*xzHUHUIn+&DRsp8H~Jahchdm}BZ*Q_R1UFmvrR;(`>hs+d>o z7KN_?8x6!3K$Onf!_NAr067j^i1c$EEm@z8iKT%dzBtsEFB&Kc1Oy59@eyWeQyy5f zSD7KGiM%RD>;h(sT# zXP}tj&?86iI$yjko03rAgWf|@rjzRqc4R_7u#(%SwFV06B%KC>G2dWzvoAfguEgAu zfUwp%+m7i?&+_f{dIM1Kb58c~?iq_v5P}6iAV)&XRs^uo0XujY;*>E8)bBvh4mjkN zvq!)cy{f-+cc@S`Eeo7B5AEJq{e!u)F-3s&89YJg!_bsx{d3LBby{tJLx9wnyAJ9U z(l@FE1QEUR+*uU_j5O23p#k3{3nqnD^u!5#)Whlt zEg%#qgHK@uOYql}FYJaO7S~iWr??8qhxHifxt6oX{1f9^g0q1ErBiT`V}1UTn9w~! zGCXBIu|y~?lbVmg^o1~$Fl92a|0Sv@gP$KaZfbw6H$0Ms49J4n-qO;N99`QHIKsI zfCxWYamu8e2MvA^z9*;x`*fs{7Q&2XugH@GM2ZksW8ir9!xY68pucE!WHNn(sL3D@ zmu&hgRx=qL?z+bREdo5k48)-OVH6ouOaK!)4b+~~O6jQ!v#Awhq6qoIGmgPdff-_) z=ALaThd@E?tpcGA!4OA?;KYG|XJClup}cx4jsWhY2lxVfKtVmI{J(Bdc@3%1YYIv= z{Pfz&%IeF|*6w5>Iw)a-RyaA}VfFHFD2(xw?;%;D{-g#K_+Mj zw_IqA>0S%yUPHJgg%p*PAlumaf|JvgI%P#=WuaQc^K=Rl^144W$gw=_B`ME|Xs+n^A#qA?NiHK=f`P9;L6&)Szm@M@&Say!|5#^F; z-_&2oVKF(kEhasYIZ$OkH~QjC=PHetcHn|Rr-kTWX&k1N=0hnw9SvUSt7WuPI9IBoPA?~dipHM`kNwL_DG*_OGCD1yuxybPl+ zR#Hw5>183*G&NleL1#80jh8vV!1@H%x8wQACn-5Ox3m;xU|;~s@Ss0Q=BHXDAdbS5 z;KfqE06g#iCV6~9!}{Z9L_xhf4Q3s}e`_DIMDpJEzqS2;OA|^UlVse2wY5nn)m`>i`_o1Qa8Yn%x@MWv;`quAOJ$~2He#RE%AnQ?G%PW3fpnwIS! z&f@$xvwXaPpn3fDf;Xs0J(&PYX^x1!-@S=qhw$}WNW*`LV<&c!(C}<5iWTDcsJVt*Uhfg z@#)d8l)YIQf)WV&vUML^t%FfW$;u+ml<9_#r1P4Bth{gPjMZX;Ltma`)aiD*Ltar4 z!gr~dt|SIk$E$tyc6sElFz{$bPY?h2oHr59FD};HTR5E7CA66Fz-Q?|Fsazs(1YR8 zw_ipLQj7iZR1|noRUb!5GlYHcfEY@GF0?E8p;IjI?1v!R>H5RCU{h$487itmv;>f}cD*8eYv5k1rPh9ddCp84i zG?1NJ5hFO;ozmXA2D7Mon?Vo8M~fBg7yucn=3BCA!Z zT@&_RUVft`TG3}SUV2W`(2sjn$HIcP#dYsP79*1A_wjycBhY5F(}Tg-m?wSy^3s(@ zR5Y7}%L3*8?x5mA|3g2Ec6G?ez`$Bdbmh>jXlVs>c%%KLiM|B1_E#J-`%y6)R@s}~m;O_;=mJDkhm90wjmS4G7syBH~MX2JXM z&aGZLj`Z*=*T=c3DK+=yW;Y=^Fp{E9S0|lY0_kVon?_pdT9258FT>r)0xf4!@rC8^zs_J9kQcqT4!Wv#P5o5$DrasT92!yq^_otXsFUS5EQZrQf3k=6 z9aTcIkFB1H}RqKlta2XX2H+(uzU1L3KHzJ^2bxAST)r-PG#$)dMsakkCsU&)) zFW0Z%;*MI;@g&d=)KtG2XZsK$Q^jnQad(*Ubg?=l;PB8kDJf|c^k9xGf;0kp<--Qq zb7#HXBD+y11P34AbUaT|Moz8^@WXCd*$(seng+I=sR*B|JeSun zYWb$#bBhG=r6u_bpOeq?)F_H8k4g-PP_z_P7#hi-{)MLy_%%6?-2!ZQH&m{2ziDXh zWSfu2<;jZZ>cTs8;gADhXZRXa7=}NmF=KTE)P&QqbZzySKLR+@aJWpFz9?=eFEBca|G;f($ z#Z@4-!HR|8+h*2|iHV8Beu)o-L;y#(!9Miu>8esik_qZwPXJLssN$4_pxIN?ZyL0WVYjWA4Z`0^?44ifCWH^v4gAr(NSr4cOJ+}#uiX`t3YJ7 znwrPX!#jYun>;@~j#=0FrsCk$d>pmsVDp;zA)6-b!?XP-b4XP^J_gzdfdBFU`mURoC(@$QuE*_OsbZ4=8$;%uQ3%a9td3j-ubFEC( zT1{3uZ^;2oXVe)0MbF6C1-jD5d0lLu>FX47^YG-AmPX&Vwzd-Y^z@8bzLAlY{RLEg zrS&x9kHSJKVPTRIjj|x|+|G+p(NWWB5@1~bb@ueIW;Cy|5~IcaD5!5^Eh`%+A<*8} z(0nBk*q4#+GA-sXg9>S2UyeO~jt8zt_Qx9^%#<+)&v~# z2RuLY1?!JsZc0X#?r%" - ] - }, - "execution_count": 1, - "metadata": { - "image/png": { - "width": 600 - } - }, - "output_type": "execute_result" - } - ], - "source": [ - "from IPython.display import Image\n", - "Image(filename=\"Figure_1.png\",width=600)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![gif](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTstar/animation.gif)\n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "#### Ref\n", - "\n", - "- [Sampling-based Algorithms for Optimal Motion Planning](https://arxiv.org/pdf/1105.1186.pdf)" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.8" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/docs/modules/path_planning/path_planning_main.rst b/docs/modules/path_planning/path_planning_main.rst index 60651dd5ff..50ed9bdbcf 100644 --- a/docs/modules/path_planning/path_planning_main.rst +++ b/docs/modules/path_planning/path_planning_main.rst @@ -91,6 +91,9 @@ Ref: - `Optimal rough terrain trajectory generation for wheeled mobile robots `__ + + + State Lattice Planning ---------------------- @@ -179,27 +182,8 @@ This is a simple path planning code with Rapidly-Exploring Random Trees Black circles are obstacles, green line is a searched tree, red crosses are start and goal positions. -.. _rrt*: - -RRT\* -~~~~~ - -|10| - -This is a path planning code with RRT\* - -Black circles are obstacles, green line is a searched tree, red crosses -are start and goal positions. - .. include:: rrt_star.rst -Ref: - -- `Incremental Sampling-based Algorithms for Optimal Motion - Planning `__ - -- `Sampling-based Algorithms for Optimal Motion - Planning `__ RRT with dubins path ~~~~~~~~~~~~~~~~~~~~ @@ -367,20 +351,9 @@ Ref: Autonomous Vehicles `__ -Quintic polynomials planning ----------------------------- -Motion planning with quintic polynomials. - -|2| - -It can calculate 2D path, velocity, and acceleration profile based on -quintic polynomials. - -Ref: +.. include:: quintic_polynomials_planner.rst -- `Local Path Planning And Motion Control For Agv In - Positioning `__ Dubins path planning -------------------- diff --git a/docs/modules/path_planning/quintic_polynomials_planner.rst b/docs/modules/path_planning/quintic_polynomials_planner.rst new file mode 100644 index 0000000000..2fab8a51ab --- /dev/null +++ b/docs/modules/path_planning/quintic_polynomials_planner.rst @@ -0,0 +1,106 @@ + +Quintic polynomials planning +---------------------------- + +Motion planning with quintic polynomials. + +|2| + +It can calculate 2D path, velocity, and acceleration profile based on +quintic polynomials. + + + +Quintic polynomials for one dimensional robot motion +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +We assume a one-dimensional robot motion :math:`x(t)` at time :math:`t` is +formulated as a quintic polynomials based on time as follows: + +.. math:: x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5 + :label: eq1 + +:math:`a_0, a_1. a_2, a_3, a_4, a_5` are parameters of the quintic polynomial. + +It is assumed that terminal states (start and end) are known as boundary conditions. + +Start position, velocity, and acceleration are :math:`x_s, v_s, a_s` respectively. + +End position, velocity, and acceleration are :math:`x_e, v_e, a_e` respectively. + +So, when time is 0. + +.. math:: x(0) = a_0 = x_s + :label: eq2 + +Then, differentiating the equation :eq:`eq1` with t, + +.. math:: x'(t) = a_1+2a_2t+3a_3t^2+4a_4t^3+5a_5t^4 + :label: eq3 + +So, when time is 0, + +.. math:: x'(0) = a_1 = v_s + :label: eq4 + +Then, differentiating the equation :eq:`eq3` with t again, + +.. math:: x''(t) = 2a_2+6a_3t+12a_4t^2 + :label: eq5 + +So, when time is 0, + +.. math:: x''(0) = 2a_2 = a_s + :label: eq6 + +so, we can calculate :math:`a_0, a_1, a_2` with eq. :eq:`eq2`, :eq:`eq4`, :eq:`eq6` and boundary conditions. + +:math:`a_3, a_4, a_5` are still unknown in eq :eq:`eq1`. + +We assume that the end time for a maneuver is :math:`T`, we can get these equations from eq :eq:`eq1`, :eq:`eq3`, :eq:`eq5`: + +.. math:: x(T)=a_0+a_1T+a_2T^2+a_3T^3+a_4T^4+a_5T^5=x_e + :label: eq7 + +.. math:: x'(T)=a_1+2a_2T+3a_3T^2+4a_4T^3+5a_5T^4=v_e + :label: eq8 + +.. math:: x''(T)=2a_2+6a_3T+12a_4T^2+20a_5T^3=a_e + :label: eq9 + +From eq :eq:`eq7`, :eq:`eq8`, :eq:`eq9`, we can calculate :math:`a_3, a_4, a_5` to solve the linear equations: :math:`Ax=b` + +.. math:: \begin{bmatrix} T^3 & T^4 & T^5 \\ 3T^2 & 4T^3 & 5T^4 \\ 6T & 12T^2 & 20T^3 \end{bmatrix}\begin{bmatrix} a_3\\ a_4\\ a_5\end{bmatrix}=\begin{bmatrix} x_e-x_s-v_sT-0.5a_sT^2\\ v_e-v_s-a_sT\\ a_e-a_s\end{bmatrix} + +We can get all unknown parameters now. + +Quintic polynomials for two dimensional robot motion (x-y) +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +If you use two quintic polynomials along x axis and y axis, you can plan for two dimensional robot motion in x-y plane. + +.. math:: x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5 + :label: eq10 + +.. math:: y(t) = b_0+b_1t+b_2t^2+b_3t^3+b_4t^4+b_5t^5 + :label: eq11 + +It is assumed that terminal states (start and end) are known as boundary conditions. + +Start position, orientation, velocity, and acceleration are :math:`x_s, y_s, \theta_s, v_s, a_s` respectively. + +End position, orientation, velocity, and acceleration are :math:`x_e, y_e. \theta_e, v_e, a_e` respectively. + +Each velocity and acceleration boundary condition can be calculated with each orientation. + +:math:`v_{xs}=v_scos(\theta_s), v_{ys}=v_ssin(\theta_s)` + +:math:`v_{xe}=v_ecos(\theta_e), v_{ye}=v_esin(\theta_e)` + +References: +~~~~~~~~~~~ + +- `Local Path Planning And Motion Control For Agv In + Positioning `__ + + diff --git a/docs/modules/path_planning/rrt_star.rst b/docs/modules/path_planning/rrt_star.rst index 5b8d62e7e1..cf136d529f 100644 --- a/docs/modules/path_planning/rrt_star.rst +++ b/docs/modules/path_planning/rrt_star.rst @@ -1,27 +1,22 @@ +RRT\* +~~~~~ -Simulation -^^^^^^^^^^ - -.. code-block:: ipython3 - - from IPython.display import Image - Image(filename="Figure_1.png",width=600) +.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTstar/animation.gif + :alt: gif +This is a path planning code with RRT\* +Black circles are obstacles, green line is a searched tree, red crosses are start and goal positions. +Simulation +^^^^^^^^^^ .. image:: rrt_star_files/rrt_star_1_0.png :width: 600px - -.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTstar/animation.gif - :alt: gif - - gif - Ref ^^^ +- `Sampling-based Algorithms for Optimal Motion Planning `__ +- `Incremental Sampling-based Algorithms for Optimal Motion Planning `__ -- `Sampling-based Algorithms for Optimal Motion - Planning `__ From 50ba79a3f53cb96c34002d54375be022a9bec5c9 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 27 Nov 2021 20:10:45 +0900 Subject: [PATCH 424/940] Fix clean up other docs (#580) * update docs * update docs * update docs * update docs --- .../rocket_powered_landing/figure.png | Bin 688548 -> 0 bytes .../rocket_powered_landing.ipynb | 482 ------------------ .../Planar_Two_Link_IK.ipynb | 423 --------------- PathTracking/cgmres_nmpc/Figure_1.png | Bin 33823 -> 0 bytes PathTracking/cgmres_nmpc/Figure_2.png | Bin 30942 -> 0 bytes PathTracking/cgmres_nmpc/Figure_3.png | Bin 25270 -> 0 bytes PathTracking/cgmres_nmpc/Figure_4.png | Bin 19078 -> 0 bytes PathTracking/cgmres_nmpc/cgmres_nmpc.ipynb | 208 -------- ...redictive_speed_and_steering_control.ipynb | 333 ------------ PathTracking/rear_wheel_feedback/Figure_2.png | Bin 39590 -> 0 bytes .../aerial_navigation_main.rst | 6 +- .../rocket_powered_landing.rst | 8 +- .../arm_navigation/arm_navigation_main.rst | 11 +- ...Two_Link_IK.rst => planar_two_link_ik.rst} | 5 +- .../Bezier_path_planning}/Figure_1.png | Bin .../Bezier_path_planning}/Figure_2.png | Bin .../path_planning/path_planning_main.rst | 5 +- ..._predictive_speed_and_steering_control.rst | 2 +- docs/modules/path_tracking/cgmres_nmpc.rst | 39 -- .../path_tracking/path_tracking_main.rst | 23 +- 20 files changed, 19 insertions(+), 1526 deletions(-) delete mode 100644 AerialNavigation/rocket_powered_landing/figure.png delete mode 100644 AerialNavigation/rocket_powered_landing/rocket_powered_landing.ipynb delete mode 100644 ArmNavigation/two_joint_arm_to_point_control/Planar_Two_Link_IK.ipynb delete mode 100644 PathTracking/cgmres_nmpc/Figure_1.png delete mode 100644 PathTracking/cgmres_nmpc/Figure_2.png delete mode 100644 PathTracking/cgmres_nmpc/Figure_3.png delete mode 100644 PathTracking/cgmres_nmpc/Figure_4.png delete mode 100644 PathTracking/cgmres_nmpc/cgmres_nmpc.ipynb delete mode 100644 PathTracking/model_predictive_speed_and_steer_control/Model_predictive_speed_and_steering_control.ipynb delete mode 100644 PathTracking/rear_wheel_feedback/Figure_2.png rename docs/modules/arm_navigation/{Planar_Two_Link_IK.rst => planar_two_link_ik.rst} (99%) rename {PathPlanning/BezierPath => docs/modules/path_planning/Bezier_path_planning}/Figure_1.png (100%) rename {PathPlanning/BezierPath => docs/modules/path_planning/Bezier_path_planning}/Figure_2.png (100%) diff --git a/AerialNavigation/rocket_powered_landing/figure.png b/AerialNavigation/rocket_powered_landing/figure.png deleted file mode 100644 index 0be109ed2b79f52191a0004c70390489cde54e3b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 688548 zcmeFYhdZ2I*FG$`gG8AjA($wmMWPF4)P&K3K}bRf(R&>=TC^C^dmBUxX=?Ot7@Y`F zqPLl-!KkDCCeL%<@B1Fd_xuOnmI)PbwgTw}RLLPA2Lt_FKd zLPBm&LPAzYd6ii577O@HLPD)>r=+B#uB61Fu&skozWF@zwq9)El}3nsN!{sd`T?1x{bO!%0-W( z$e8XPS-u{ZKbpe@4&%=+vwr*I&Q*pkFL5OA^tzKC;dNh-T;mR}>?{!(Pu{0y{6N7$ zLZ<(c+|k#+J~=xcaQ$8M%%xCSsglc`XT~YUm!QkCd_F+m2?+-kz=mq&j1(C}N+P_h zVHHjSIDa>54bRh$EPm+75lW>f@MH-jA*8n?AW{1CgqzQuV~&g@1GC)gPV&t;-0LY& zfnv{gK5SA84A3C?#;F7vVA>@Is4B_UynC5SucWY$e!#3fG!Lm#f%-O~bU&9W^Q^d5 z7-tS=od(q`2WdQPG3S0Gr=O|Dm|gOj`Ebj6?(;34_YY@;d*4Py7_cu%nFsf=nCBCVG zOWqR=B)92@I1bM6=4jr0wifg#A+2M4XZ{9NJ=dAA2CUa^9VKd?0Fj_IcS2_DH5J~f zrn5EzFLlNo_uPo=J9FZs1w6{{7(1Jcb~Loi$Cy6lVE@2mbeA5ne829!PBQ4r;uIS9 zVNdE!-IF_J#nC&It9s_D_CQKB*I2bhT6p3Ot!9JTuOb4v;z#xO6&^0f>4l%@K5CTc zwBF0-9yFG%0|==}D6sJfYN|cOMcS!^bucg?F)WBm6 zIeIFe2Up!+1M2JrxWvEfbJ6=~k@75PBf}oZOABjC+$C53c40R5v85rz@rP}Ky$YKT zrP~$cm6M%XMF|Zt7Qvfmw1P`PFdW(#pLe(W!p=fT<1;4z)}qx~v=2QOa~ zUgL*sR=S7#c-jw$L6)t1HXbYe$Eaax!PiIW!g3WwlUFvWy+~yuZeyO4T$g!MZO&A| z^+>kiZQ!#n`3bg>AN}_@;*QyOeKOPg;C-_!vxJ$sPuVJhle#_nx42G&J}WZ+BKLn z=TU7?A=kab??G6! z+fR-i{W)7eW$oUJgU9@5*8uli)X#!WW-rKhGAO>qq2U z6r;y8^7QiciVzQQiSSk-4m3Nj3|Ry}mfKVn) zrct_ThQ^>&X72spwJ)ECJzshLxe8)GV$)krU30^zv`W_cgrYyb%X+oyqhYZD*;DJM zBTuh=`ttPlQ>Ag*asKh5albFWf9g1$IaWH2Pko)Ho_zijUYYGOZF`z^yK86|Zdu#D z9X;#dM{#=p)Me9XlU?SPjO*=3AeP(PkngvZKsGYtGA5p2=@aNG)XBYJGg{hDCJN<{ zEnNRjNM6W1O-m@-g398&`w?b5u6gkh!m5$6Ub111y&J?NQ|e*dUst^B)NK=ODt9q( z9OpdeeBwMk>)g1}sO=%_>4FH_UfgUyDmkcIS3ip0H(r@qKN;xn()d+9weemG?U#5Y zHMcd#?(ZL9DX%3T&{ETq(c;-6bw+(gf0lZheZY4daU#5@uz4xj#`jL-Wl)=GaA~k_ za3dMJwre^EsyskZJKhr@Z0n%oEpiVce%!dQ4fq5wQ48n^)ydL%_$&6Csw1D5kRRQt zUAj@az~;+I2RMn%6`T)*k?p1la1NNqoiHR`_#Ba_DA4GcC+e31^36uUFW)w|vd zAbM-QGuaFX)XaTrB_eV=63;NqEt+V}y9Ixh0!nQXJMnsJ@fKVp_k_>$xxLc*#@C&% z5_YqC7;Qt5RmBFo21v6+XmUbk1($`ZedpMLo?o%A_Pt!MfClvb(i+Y>eW)kb&GP+_ z=G*{TM%cjDf!U1TzPnAY=3X*NeG+nbJ-q0$pa2ZJHcmwdd)Oh-p*r<&%At}SN51-b zaE&1x`4M(*9$Tk!CLks4t+Bn)bljBfi$1YC@w?vhSH@ov+=N8g-VcV1Rc~!PAH67C z{k}bQrD|fBExxPAs|R@E;p>ohWv1LzA9A5T9-p^t*E#Q8jjg3X)F)pxtznQ$bIhRtmp&#m^gm$i)y~jGD zqHHmrW9KJy3Aj*lNOBk*Zysn)Ic<~gYEcLrINK#$q@Qn5oYCGtw>;9DeTZp)YhCE; zjDHYSQq(BXT#f(MskG%3>_id7c7z{7KaFsRyTxYcoBZnQ=C7TKM2pbwqV7}e71S@g z+^N9RmE@#n+FJ5I+@!JlQ>Ne`sPCHq?BvwDs)*sgP%<8Kzy16F%Dq0w)GW+)_TzLS z^tSx%!8Cv2YLmm(nQ>?y-u9W=MC852XMy#7&94@p&r}a>@K3nRrF#{ezF)vD8=chV zoIl;4{{<=k(TSz)Ilpc@$kD+syXjk?hHfi__D&%831l zCvgJo60(Or{&m8YzxUYnE`J4p1H{HmFN)`KJ+*J=UhF^nWy(bHo_b$CNscwJ9A0Q^wjdAsTmAPZ1xSGH=`H;3kZb!+c{1Pf zhZ@pb`uAm6U*lx1yelSatD`=m)BAywP2pIt`fx4yGVF)V!<1u^Z{#k0ThcfP$?3bF zN<~UfoPQ)KU0Gj)eq>3o@q1NLZ@bf}G86rqX72maR^(!~2e#lm2Y zf4$=2AO|+k(&12Yakt`-5V|iU0+zqV!NDQxZfPz37^d=fb>e?=U|SClS7~8kZ*OlQ zZ*d_PcN<|*C=@CzA|@;*CP;ik5aH|WVdf*~jNtlrBmcAmvqD(7+qrt!xj1wDY1ho$ z#nVF$4E`hNe}4YmPb(k0|CQv7_? zEi2{-;{)~6_VbN}KkT3SJ^DB;KKtW|_W8#K?;LUM17nZ*fTP(~ySu^kcmC7mGf8Ev zpNBPL4`tCI<@rxn(u43!c-VigJ;^|N)Bezs!(N3d`N4m<^h?%2|55CnU^z~mJZtT% z`PTojVlq+a(0}SLv9$IV?8Nt+|E3i^ZPCL6_w5O!eeA0&DgycyA&lnXZ&idD63znk%*Hwdybg^oBVTGT+JfF{c*1Y~C>t0!t zJAUr>`CL|Q&}r>_e<^d>L=#p5G2`5PFurCWhtC*BSyZN7ohYF<031iP9!Cwj5anvS z?bFOH&`1uy8n2S1v%a8b-fqGV4bGnp&O2W0&|SJ-OLIB2cB#>=Jso4n*$GqLU>fSb zB$QqLJo{mK{-dc(**~zc)~|7Jx@Bvc?Lk{i`tp2;!o{+}+>Fn14D06Ham>6=CA#dx z-@|{jut{H{gYfdLsiF7j1ROWEo;JpuWwoAUWtpB$1VadyV?aQzA+YK9%ri3EXhLb{V zLSggf&&#vnOGjcyE-Wlg*Ppe%!l!r3TI08WUuZ| zx18|nyYjK+AFN!Z@=kHkP-*JzqlEoA~R)yVb`=_Z! z&Qmk~_(8pr6QW)o@;{QrL5DMR-N>zgubIrBUz12xeJeod)IRIXKyv{lfZJ59ojx-; z7yHG-sLI*YfAA{mHql)eqU|1kOd1Cvy*!S)tV=LGTViqvJV^`kRk4&kof@8N8k}w# zykQRO1=w1$&j?b0H_r}CFAqGBvW?+7c>dfy{w%uFaypscX%EiZ+0WWn7P4?b=MzD* zNVcCiWTwI;ULjXQ6=I(1hjb()3ZEo4$B?}0eDPrGTPPTir*c0+O++!KhlR8~gInXu zYVKKY?u>u8w}1DInAtSgSW}l#Q>I6Q6U`6k58EHud7tDd*z})e!W2Q_o4G| z$yU$RW51F@0Ra=k8BROzO*!YaRe!CpOxT#u)4>+iG1n#m zqbkb{;mbYY;=02prUy^5w9m)1sJb<%ued1)xUT z_u{YyhC8w%-|+^res6x6`zEMPCP(cZAkvyNz&9YHF**4Kt} zRIM7wFc$(<-`tg@JwKGCDf_{7@80R*bGc2fWZ&)RqeH$~S2PW4MmEu4waTQ)of9|m zslcfl`;l7~-SKNWwUJQ4#lb4x(t2zr8E#`?LEYq6mMO*PdmF~Z!KtL%_2si@uCTZ2kp=Z@HKb(+3qB`swyU2wMDNdaPeQ z;7QrV$7eyeCt9Ruo>|hJpA!u|VXDPS8*INK9-tCalctet?58TH39)z`iYSk2J}#FE z@I3E@yxhK648XkVeHdhgAC@Sf4H1t0c|WK;p_(fz3G?W@E}h~q``0V8PZxdb=B>M< zDx02PswVcvb5HAYvyP}d*$zd_@LeaEA$0FKX|gYx4WS3`n-L8vA61=5t*pPy)Dw$M zyfAy`(pRx{=SmNB(=611Z@D0jnZbWwPj0;`ceXTYh6%pfk|ghG^!E;>qaYr%bQA|Q zhNQSF!Qw!B6Tk0%R$j;Nv!UPqmcs!HHHAHR)3N0=eK6wI=Q&2Z zSeFYd#gFHNmApP*6&jh?S1K_rwo3Z+BX5)1%s420=H3*6+hFQH6VgTbK{&d@gcS5o_O z>|b@=GZD=V552Cc7x>4V4azi+%4m%|uuQqA3Qqbc{1ea~PXRyuaqEmu15`D3`UeuQ zX54BY>B>M`gMLJ!t1x6`RtoF_2vh|v?pe!T3Ib}7Q`A{XM|ek<376@1&iHC}wm;~A zxIg^)YSCqg$&Yc6eqgOJA0{p|PP}n~|DfS; z|4B2!eyD2tSa}SLCG`4@IIs~MHmB4J-L}$?Y!aiZG)V|GE~hniI9vHmjV2!OXU4Az_ z8*(q}w5YCRl5G8_h4SXupEk9pc_()_P9wKv zHoQ(-{=s|_L{-FP`b^&o#)q|KP)f)PoVH!cwBlv(M$bv9@-SpFQ0@pS36u)$4O~{J z-N_ByHws_ckWDg~Vu|?%_cxGhEiaC)m>!z>uW`G3j12-8zxIHXGtl{3t3R?`UIt7P z25jUJ($pX&xbOGJCAv)A?t){kmR7O1ZJv1~sDUJ1H=#y82J-J;82Zi&F}xSC$;FGl z7uaE`9dNR9QS!m~dZasWjidy_(sHP($Ik~xgjFuTsJP&P?10QF!C zW&eGc{Um`sBNkv}wF#N{InHNv8bhI~(Fo~}Oy%%Du?`fZXI91ary_i>(yJznMzaAc5@6eVDgLt7ztv`0lzJ-fESk%_FueSOnHl!Q0Ag=XrUn46$eR6?e76; zn^W@Xi9KCkiYC-s;LO&2*~t|Uj7Bq4gCqJTxt95;=!D%wN+c$VOZzjYe$z%{%ZA6? zmel)1#8;OVASa}VAbhVtJ6-t|$M^F1Z%-Rp3^=Y(VzJ>@Z1 z#()y+Sj!)TdUm*1Zc9R2?nQZD-UAWKkTdilo`;q`BCe`;aiPRja*_*Sy8_Wc3C4;n zh8lF7tbFSSDaLYA1d|OLE^HFsq#=sVDep4p|Cz2K(ujzpPR@gzq|bsw6ns%=p=seN z-Q0s*bgXJBLphf&o8wpzEiL0Fw#lM@w+Fhu)am*b%8TNXbURF5)?6ep9qB*VCf34qtlXU*>0 zJoUeSF-%*uUI3(KaO}}K76W2&13X7$0+fc>oaoiZg}l!jcsIo(+!aJ7CVI~?%_;G= zv32a3s+Ca3QkLsSh=9GHa_#3&3=wz0vTq`&qBbP|$GEZ4{!uL2b*C!wAu>{+J<+!c zbdb&l-D|z|^@csfKambi4j7i%xsu7XiN0@x7FIsN<|u(ba`)C((j9_~R;j2_j}riu zdzG&s&)1&~QFyR-K-oLFGLqUy7O6j_jdr-LQb*-{WA}99hRTTX#p`u0F5T}1UB^X{ z?m2lU$`f%q$R{=!$pU0>On`b-mN3pt?$Q3@vFib5VSX*E<4_-Wo3RjqxoqMZZJA&3l0eXCn!>P|#^eB@Ug z6h8khtTht61Hi?Hs*G{mG5hjjgbJ8AaC3xruc}+SHH!}>Kzc>qapiu{JQ1a0|G+~W zWYKXG3CAY8>EtkA@>aQ75b!Sp9}Z$#Tqd9&K>Bz}CP{{LN{L)NG*^7lKw>8vU{fP;q}r!hnW?z8xi;`0_!h!IhI9v ztAp|>IWVC6(F=@@(XqjMUe=%hT=F_oPT)w7xN3B<=DWvyqJK%{bJ|R$ch^6mko@DK z%X0+<0H{e`+!2gEaD@`b~5tAdSukKLV+(6es@pA6gF+>q04Pra(4XC;3{; z2tz1s&1q}}RzE6)Lnm8Z`gR^KIQhh~Wj)FvigJNPRDr(P+_3y z8h^QY&zui?ev081n4z1QfPMZjU(KyNBbsJ;I>=+O{2UP{mWKK*@5q)>hJ6yA3D~ar z*9rY{o>ISLsuuV`j;EZD{PX#dQzab^WjJ(GHCJa@sg~|QUKVj@sp(`#+hd{5RV?7a zA8+>fBsdG*QK7knB)r>JYPJFoty14hEB7d~f>ZKMLE>ZH?3)UkXn9BJ0XNqr zOGGCz#1j;FjiW`vy7-mV&_~prE8UY|gn1!krQ+yL9@c_*0v0oL`I_l15V5eIjSs8#n))1#q(|@|dJyIUH|b~5Z0Fye zA=YdHu{PF{7|@dgUQ*<;Kx9*UHzY$Z@&ai1o9{RP;^>85X zH=*=*CVu`H%IK%81&Jf!{-Adw#%=efadqJ%{h0bUA5PXA=)3TVK+Y9Uum`vgs8lY- z7wHA^u;^tR5(})Dkmwy*d0jctv}4SqsMRSJQZV3!xGsE-hLpunjF%#oZA$^eJLR6G zl|#Lr9h^)>FVCo0AeNC)_$e!D%CfLb0SkAUl2Lz8+IF>O!rex?^s3JL7Ax{q(XU0e zZ4%+CCF)Z%6JNXG`I)EJ1A#UNy1b9h{`fQkO4P1enTQPb^`54-Nx5PFuF$%Ixb2(R zJAv2_n?EH=4H|z}ERPb8ew-)j4l|;wiJO~2lu~6AF)Qas`F0zK4c$A;63%DeeNsk< zN!r_daVcBt<`w|d8xUR&NY*K6fsIX?TdkBVCy)WmuGfo#b z`NrKipEo!o7b~HBjkPRF0rzt$ANDag+#L(Et^Idy_7qO^)?4Cqw(bQ-M82jQBq}AC z&L0_cfzMS?I6jq3rev@QCj%o|{)APA>CRE4wAC(YY4g$VW#rWmVMwZc5(o{-FZPou z@1E0^w3`am0}xbUzMuc_O9=@0CaGTtC^%0H9*MOETM1L-hH5~hlRT1j@IdxmAjJ}i zP0VrIE*Ma*ajO-X==oMW-Nu^e^RNz$c;mh>bgRs}Ui=BBt-V}h#jSHG>~Tpss!R8o zEW1gLJ}%*eAHT^#3n7MJRIc=Cy%6`it1ulT{G@64w5j*C_**)+kP^J5#=O(F4k?z;hoVNQ+N;lj!&nbbJkrrj{9kkZo+^-I!iebw8qI77;kHmFpWL#m(_jyb0@ICvn2?`V8tTc#(_Hay&N6W=OCdBb5)jIS)8}IrPwoZ{#mfT3U1uDLm?koCW?@ zgrU&}cV9?Bhfu#6q|0!KyHX_;!ns~;jH&H!>3V|GCH>Zrjh;I#7d8)3+L$(+FGXlV z*$;a`{;@THARrlvXN1yiEbYL&>!b&N*I!TgQ7Bh%HUh8ZyRLOVg7P|P$QPH{-5LQc z_|m&uQeMEnAVV7w?8Td*Q}p&Q3Rn39)mHyyVT9t8imcK5BFIbM)Qaa(WFT2mDhdsD zB!X~cmwRZ3pj{tsFu_|0(gGgCHeB}vyXf2BIeV#;h-$~AiREXw@;b8Ut6GfbTF?nVDu%^D88#mdWJ4# zf3aaCDK?fsughf~3b}KSk6n_YdRcbq!C9dhDai9cP0nR&QpG8v&RHV*|E^ZLVY zIbz1ELlNj(=^CZN3B+*S2h~|jm+TX7Fkny*e4DfUpV<9j0x_`^07@YSLH!=IQ8)u> zKzeYL%OTW}>KvC2q$;Gm7R%teM^i!9)nZ3H_R8tLp&;x{P&dT|b+cOgsm1!WD_2Vp&@;}B8+#h%C&+u0$r-vLUFc1XHYl)9H|d#LkFhdE}i~SaL*ZPvQ5u)}Qf8;-WG=R!wn7GO}b;kFr z{8h1XP>?Qgjc!_qpj>=FyS_NDjr$lmdjb1L00Okc-@3N%d;Z{ zxg4naj#~xjKA6O<_}@;0c6qp@loi_)f-u-9gs1Pv3ukmmZ0Os?oxe`4e( zh|*tCnw0&<=2i6;LiJw8rhT82c6WFbORtm0IbZ^&n={LQNjv@%{0-nH5`x%OizHLp z*Z@1hMzK2RkwpW-JHe1PiXF=PC>h$nY{D&+3juBqN*2F@4xRXL5x?4lxjw4-9xCQ= zB5quTClzVuGeKB4U4?MprMhB2C8aNhHtYn^*4??;pE$(rMhj_6jdWeu0SJah*m8iw zSFh*a{)%2)JO-su%77@n+&duCAj#MiN^0DC+JK?SH8v14E=qQXrm^DqZQ1eL!L)#> zwA=T+OT$>;tg7?$w`yD~TNkdkytH2SF%VPTNu**ID;`AwsW?bqi@f|mfqS$c_1VOH zQ1^iT#+cxrB*pnarx;wM24#-WTRO8(Lr1e;Q9RARi3I%QL1s*V?3cnzNEDGckCLQv zmE`3+^p9H(j9NY4#)bi7KL@&6#(d$v8&dMHe9?e@8L76XOGSZTF~T*n9VmIRb?cpC z>!I!P9efq~yf@rRxEQ}ob1FubaLBJhMK^ivGtl&<_2c49;!@DzpGo^aB;pEeb0;^X z(*$3f{z;P<(jq*+B(?PAe-(IfpK<+0hB-A|6s_SOEkcK}bO1%UH1^$1$W?)$O|JkO zlW--h<`Ac4RsjK~))|6)txT``gm=s*l{#T6U=7w^799z-odPBdS8Lzb7Zx4x=QVG@ zF;g7LCOq0!!o2W^Th&!9A|{&nDDoZ}O{FCA)WbTkla4{ zrvr3w_Tc3bSRH!Pp#|$8Nldqz%4HC)X799Btjs(D>j=n*t3swKq2_Fh>sN*`8C*m* z;Z`F)QWPcMLC-h+l$jQ?Na2kz80U+vtmll(q4z{HYgxXfj24K=41XE~P6S*-zBH(# zwIY4vpmC~^_ofFn*^|gQjRw=+FM?~-wAjElUYeWmI|vDJnM`sD;_?D8;YiER&@IP~ zu7Hr+gw5wT0R}qCx1Fg6sGO8I1>o!Q&OQU#8$>8yJ2M)s_jp?)Oqevd0=(1UyZ7MwSJ#{ z*21cz!jEkn`!zzvh!Gaek;o7m`)FGZY)=IDoP_`(i_jL{6DhRBI}>nIkQC+T?I<7R zubRHoL^TG-*xWM{jB@<0;K|BxB#Y>!m$RrxrG1zVAo`S(#|M&*?t>m{dUyU#8I+e1 z^HG}{J!7TxKIv4hkF7@7P*$<&E}hDPX29l7~|k8ze{4?aLPm-_AOq zcxB#A47pzFM(S|Uhd>rs^@gY^vL3Wma53`azgh0J!_K&3Aj39^V1HPNuJEF&hic0g zCgq3el}&F#!`gLeKM*X3sEgmsu77s{4@Sars?Sl~vK!pp5EGCU@IfjKKngZ*u#|TYa+dY+56|3kFoE0Oj0|u)k=ENamuj<(reE#3@-TI zNsFo*w<&)PaY;jX#kNKAtWQMDP_ufpEK5gb&OoDtshxbmJ(F zQo@IwcPw24Xdj!YkuS?N_Hy}o{0r7fKM%dXIaHfmf8a6XZuJN9!`E%kOMp)n&^0bW zP*Rizyka0DK9W?JxnJBL?NCorjKSYPGJ&2$`RN>1??6a^V#0Uegj#3+}p5G1|&nCqS)cz_E>)vtV5H|f%ehiwxmE7Hqux5 zJdZGU=-7DceAPZ8NoAqB>GW6RNRsir33?{YIRO?Iw^Qi@Iz}!V%1#@Y6Y@TnFj$yx zyCZq#XBlOcgZyjJ3+c6I3yf1BH_<#Cph+tVfX3my0QGq_@1cYN~S2|l@&H? zR5X7A4HGny@_`5U7(_LDJ1w=HC$a?kBJa&CHnrZOH`|u624FVH!|>iJq`?8>&mGV3 zdL}9LXm&F3%V{dllWhhpw;A8C)}xGS9rV>rW7c$m?#|{nI|5OfVsvocF#sX5$PrL& ztB!kK;+CDMv5m&kV^T*918rqjJl*L;i>V}1M||IChi6I@wFv);U<=Vhr7BOY{CBN*uFm$~T{hBa_Z+qp+g=OZ8bYIfYone2ctp-DW_ zbQw{uid4lt6fU&+1N95H+{Potg_)P=aHF-YB^=u`3QxX zF00>vU4v9Y`3-HDB@p-aW#^4^9d^}JaTd-^{VndR%yhZ{b@C#JBnkwd>`lG4GBY}* zQnFa`Rz5!R2FN``5%tq5yJZy{-CMV469`z7eHK1CppN~@tlDIC@LXll=n}myp+JAL z<3kEG2b(L}E(v_%C_?eaN7n%?J}5C`;G1gdtAu(+KILTdjg729(ts>NNLeGP2}9$a zedsV~AvSCSIV#9NOUtl7?&&jpqQ(2&E^82zF&ZEZlptqYN^)dQIw}R?(~^R2;n0qc zWAAja)i6iRT!(CS@+Wu--=a(9AA8?hJ6c>0cECw{}p$K(}{tXmSJpWd4OkFkKRtX1aVGWMVtK1#Bq&WIMLwF zVp4T19J$8oe%IyF+as0Mz1S-X-_8TD5UgbJXAZYIg3XTC(Aj_RM;b8-u z03NiihCXTV>wpcH1t^~wJk{6r7`oXfb5xFd0;4*RDjBYNuV=-)|$-KHZ0O+q7`(iS}z43~RB(kpK ziN_Vb#Bb(Q@xJL4EA&5LNj<6Ou9eF1K9eOiqI#{XOuo+a6;Xm%sf0myhS-L4Oq|6p zkOJq>kf)deZ24DGB}&WF&ns$T9g_0vCc-~s>g5oFy=-?_eDa;-B*6f8HnZ;PFjl?{ zpLX3^|A_QT|EGfu+P=gdY7rjFx@#?To}|7Q)es$;G2p}19i=yt8ymxvtky>N+N(DZ z+WYdPY-!`p2z*TgmVpEZNR)O)b0?UI>5j_9 z8F*I~X=C$6!DB@3N4^Io){tOH%P=+It&jp=;r3_oI~qlA7h&0Xg_(~`!Efr9GryaL zNCk_nhcXJB3Uwm*T=AhxRcO&|bkroOF@Gh(#LICO0itlzk=1&mle+B)D4XXfu?Lj#P zV4muyBe*vQ7(z&kXYe}Qim~S?Sz7N@r*v_0%8p!3<4Vi7Nt)zI2cuAou?Zg@b6_b; z3Er&sKsT*?Wl;WF1#Yb|3REfJoxA@NfVifjTaW-vI4Je#mU z!zZ3^Q+2W-vJ8?=ES;rN{>`RqlP8iUtKteCXFYmJM+t!YH{Pb`qzIzx-d~)NDhqq- zxn%3+4y{BnvX6(aAi$6U7>(|A7(*;AMW{GNcR}DME;K-1(;>7Vy>cDQQ4wX)zDv); zg&;uGQ1@0-7R%ik1%kjig(kF-p9SG%dyWHA-Gl_S?0sERf3(XQ1E0}-lDs!c1?-hJ zoUW-E^l7Rt=gQfG(bW zW>0Pkyc&N969>qAWtg7|4Mjp*`&1IuU4nB9;EgMQt}?K9 zQ%r$U2BV`OXtZGbAy-6|oU^8cfy<)D85~^S<|{tujv4h|6Mi96_M5v<}nM=h#tv@R)y6kZDzjg0RYNpk~-)KQ=u@_2`}#4dNb+aGgTIJ7J-n3!o! zt~c;WHoW0ElCpTjai1x1APYA3GQX6lTlM3!5iwgD-OY}IW91{plEnhdh%Hv8&qVG; z#f*ly^QNb;1O*lHm{q2~aOTr$VKq&u`uVFvWC#}usGbPJz#O><%+o}QlPqLLSRq3L z3!NhrIvI7|+d3}?-80)E4|A}TgS%*FoS^8Q zJ5F~ABRjfgk+_ixc{#+YJyB4(O@ra5`Xug~US7d7cFPD?7M?klYs)AZ2^Li;6-FV1 z2kU@6f^?pP^gJ(4G4YdHB0OR|8C4pr(Y2=*IY|XEg$L&Y=c}4wEd7s^CszYAPNf?M z`HmzIof4}i9IUJvU&2(6m=6K9n+#eW9}}$CwEs>}@$9$)OLXwA2`-I1=*V=+D134U7<~&Tc@{4M!$28h4Lke zXS=8}++IqD-3QJtq8oO+!SOC_P<;^p@J&vAi1vO69zyn$=kDAUyffqY8(r|L|r8k5$S_U|X*$bfS zx`14hDb}0?>Z7{dp3*gb4fx0pl=!(o-8;-Olrzv$G)pcrBnNDREGScRUPV?eXjZyp zBzNT;E2D-T@q`*I# zo{VhLl?N(A`Hb*wCt-kP^Cl|WFewW#E5jLD&;q_9h83eQEF{0u4*8fy))HM(F{6xm z%FBTgs8GkWq3)ZM>N%Aw4WW8v$74O9cRLF0nl06P4gUYJv4+gko8ZCNV0@T&&tto|<7D9dc1G zdG2=ktGy}#+dppgJ^0S~XdxP^t16Z|^Lr(lOJ-{8m1nN2+&b&xrm^Z6U=6lZhlz~d z=HEbO&Lr)t&l}5x*=oi_fpk^bUkKN1S8Ru4bG>rpT5Mg3k?CzY!puJu=~Fdg`cgjj zk<;B^IgSUG@%ZS>QJ_5}33LUXfh(izjyqn0O8krcC0?9`s)Ce(#Mw&%boc~ZiC)on z=nCk8u4t;}alF=XxppiWy@#RXl9F^qXYGmn41yATr+m~`{xhP}pY`6p={d^CiQ5ef z!@64j=u$T!a;Z(KHMqZ*BKEVFJExwsQqpL|Lxw8%43zaBOQ|Ldwp6E4k=-)ud8(Lr z82N;lXvz$WeL&@s+_Bf#d{#D{>%OdX>j54aH zEAqP#PS=B+;x+}X^pJZC%>>_;dtjQnf|!Z#T$sx~^u=T$`z97C??4GlZC7s76Lxmn zPxZt}h(4CAK_L#6K`-YYgOCpveL27&Bo{de{<~6`pcQb<{PP4qjzt?0hKP$B=uO?? zljQGr&L^Q5JLA4;7x5Y# zZ!|~&cqgrBGYk57){^je5D1Zob~=l$l}{gDC#Ip5CnGx&kVwqKbL_7SZhy=EUjm+p z*~n|6&!|#LPYP$eqoYa~WL;ggSeeXIcCB259pw8KCrjtT|5UO1Dt zU+UvE{~uT10nPT`{okRb!|pI*?^0?9L0h{vEmf-;qxP!3s??~6s!dR%MNuO~?JZ_( z60ujTP%B1^e|*RDJiq_>I4373Idb0X-q(HI`?~J|7Y*oZg}OVJmyU(8`~CGz^?N4r zIoD~=$EfzE3MUEU{rO${J!bB!-xf01-8#h!8>dx3?tP4m;K!d`DTO!Jv~zP^X{(L0 zxZ!!2zw6WkIEXavjB+lXNaIrdX*ONXrDE`J!YW2Wwx6IRlX=tu+7yq%dAdYs)J?{) z?w(So4Sm`eKoFYLWd>3ntgrf&Rl}uIDq2175zcZwMAr2wZ(Yrjf9>Ygx?BoqL*S8e ziURDLXhHaHQwl51%6-DaCoh$aa|Lui^3DN}!4h1Ky!~^Q@Ls7ez|ID=fn?s*tDbId zQu89$k%JQVVAPe}W-QzkZ8uu(ks`S6k5T6V^J9G-Urdq5{(48C0OBxG$L4P1hPXTI&$S!T+HZNN?^TH3Q(_ zF7rr_pn!RUt)Ol$Ql~GK+g@hI9Z+M*NRK%g8PRh4t8uPPTyLU<6VaA|<#AVgE+c|l z*L+2_r3%Wq%y)GC!EwdwPq<4hEGTH=A}BZ99+s(%Nz|H%W+%|hEg!#wCCA2Zw~qP0 zwo&A>+H3YVNFv-CM0iu#mrA2w=BCp+_IW`f0_fBxbgSO7x^wdZ9=#^@6P-aVq(;|= z@_DSp5E3B1HS2aIm}7 z0rliMOPI=XdS8&{1*1N<6)b!fV3I-rZ&O=hhu|=lHXv*=8mx51JPuGj3febLQ zeRqj~fpIe$p7-$IMdnk0P)_Xp>q0?%)Ro!NVp{OxQWS`)q18<7fa%C|S- zM%!HxkD1C6XhW}YmmjR>W}u1#17ZUB_(fWiL-Rbf#9ep%jd5u%IG5*2iJgZj^4{NA z$}*?u2hyKC__r5;3YcDHqttWwTv0mT*(lFFasN#gGHx`j5|!_?z*)$TUB4@ z`r2N4fP*V?Kbsua&W!=i*oFt-g|Gud4PQ zi8W{^BkZQR~Tf{Gvmo0XA@-pIdA0>Gm8qRM6rr6fi|+zMMMgaX!z&w5eq> zwic=Curci0kiN1R;E!-@y(wPqv#pF`%Guph~iY`M=V+|3Rt5&IK+RRIDT3rJH*B zWxsH6xpg>2G!;<0=7lIR7{`CU^d#((0*cL!#wkLijVJrF#-Xm3C7o-B+c=1_+kH#` z$4C>;_kFev*$Xr~8{y$<0>=z=r;jUKecrjf~88ow#RJK4+WzV~pp_s!{DKqT2O9;@mQO#%`(9}Hy2M{!N3+iccL%n23&|acKk3iher+xFL6cc;GpXui zKE-@`N8OKD*zYWpY2}VmNb64wD9-!0ZvGyTl(&hpT<5#s+jirdM80rSu4otn;>K;O zdz;{_Ky5|l6oo}bhem1V1U?Qd;K^w6&SqOTWOb1rGQ}$9ZI#W1k zC@$mOAAUWXo{X`7$3}UV_$!om(PMupN3b_8&wp~x8ULV>?J!0y(c|P}5WT`66&c5g zm6AZuIR002eWAB)>bg*YN#!K|CFa}Bc$|SLy$60Lpq^2O?4Ml5tU53mbMITJ-Fc!M zs`*7)PaDrv5p7Bo@5y5GYib(*8Ry?|81oI{3W8{q%L4xTXK_@lzb$QtYIw7hxf8t` zt`1rmNqp$t0TE!db2jv{ab#&r4NKKMFyElv+ryQR4dgKilDNap7+rVqs&o zj&jYZKrqd3)*GB}K7OUqF^BDkfnBjW%|OMZ%FRjm?Jff_RYm8COW>W zBlHSXVm3^)+tkn_7JkxK26pNi1piNuj@?M&me{rZWoLgeB{1&GAJjACX}3Al<7mVc z0Bj$Cf#arLnz0>nPoL>!+id8MN$h{?b*lwQX2%rgj;a5WTKgUTUab5e3F`aJFP!Nh zx=t%5a4*MZq_2F_Bjq3R{qJEA*ZzWB+YKPG54!j<0WvCW_6QVC{7FaPm2i!>Y;7p* z_uHx73*uSagbi&iBP_;C`b}izsMJR$&)c;lWq0fZt;bP3)OMT9OIr==n-&XGq!NdB z`FtMU>GQ>=V0hENIhyfoeR}urp13&fI#>KOi3rw=QahUeV&uadR8P3(KRTMxf+GNm zv{#^~mFjF9AD*=__d{bx`9)M--DJyqV>(gAbiM*80h5VN(CUhQObv-h?OR65Y)uk1 zm1TXnsws(}C!fd-OzS;5@JyQ&Q)nIt`&JlU^U;X4?+pC&eCu`Y+*4ghb z`*ZIGl{|ZBzUNJrTWs7{+99uv6o;tH*awQ%|Cq_@G4H77x~ zHN+(%ee(L@cg4rL-@xpz6+cs%DK=B_mhY*czvY7)HJV%;9$E_YLH^LXw&LH>5=L^; zBiI%4Qr`5P9>l1ol?Aoc_u7n3N`b%&MW_i{QY}gp3UCAFb4`Qvc(rC8!3Ld5 zo=ugCmV)+jwV?8}`9yC)X0-6v+`I3-vY7XSU(5=jurLbrkdI zWAald?=X)d_a??0Ja_G$_GuzAb={vUYC6c?rQq{JNd)NkYlNmoMVcU#=seBl`vpIy zJN}zWz1X-!gFsGnd&ukUW4ae7$tLBoBCUKqRW9a6c~HL7AbQeIB#W1EQ*^fpaOotpfWp%)t&) zPTl`9s{c$?D$%Tn$Np_>WLcZgjgBW`6|lVvsrVU4JT~;w6CKt|E{CVE3erEmEEcQ? zSV;pYyd#iWjM|R9jTh@NbVs1Wr|n||^?j)fk?g=q64U|$xFa0jd`?uci z?@cvE^a@3hdjS`dN<o7$N-Fu-j=J{Z6El5{+^#Ti~$&q39~;@yuZaU(3_u> zo|@&bqdVme>nxr0eQ2w|Z3zhiE;kVB%?r79I|qZF=PCE+vTb|U2UN%+akSZ%EfH@ymWIL|svZiStzkM3a67+tKc5w-cRYYN>X)2$ zbt}>7cLefTxu3OsBCXS?ulx%q{bf6ei+=w)(M;U$09GXt-}q_0zpCvJ$)WxFLIo`; z2{D)JcKcrVv&QbGI0;!K8I{V6kGgIXAwsJA!F}Cu7q-0Vh)ZQ`x*Tg!Uq4GLbJz%s zP|0mFQhuX<;UGxQ9%b&$pog#)$jzSYwd8oU43(kqQSMtg7Z1!Z=DaxwejXpVo)*~V zS%S`Jcv$6A@94Upc*=s$Rz#oS;74 zxgV3c(BM6ylw0i#D)QoY)Hq!tn!&)+M|0Gg?tP<%Ol0Cn3;PYQ3a|*5QMu({it!ln z^YCWwf0CZVs;iWNxK7H)KIjiWq{XA}YN^Yh#SdbhqJy^b4>J6gntcI{^E*8fN%Fpg zNj59)LZ;GfJZqnC2LG}SyF>Ch{Dk5zk%^P` zgxtgR(Q5D5U`*ficPbPa-4fTz6MefI#x??w@jNliBzs|KD$dO9zbfHtt&>)~8q{_t zpoNvaORo<2Oh;;HQMZKjc7OP7FsNL*MWdElsoZpI={GF?pi*6?zL5kGyTzdU!V9up zbBe5$teW=e&p)5t{zKKBQVGI9)X8xgjoTLX3u& z!EjUdIMN&D^;C9YDWc!bE0a6Tgy3>ZD11@e2@|$o%mMba&zm+&S(ZMo)efCe^O2S@ z;g-3l#dj#A{acRK8}iuY%4WhchS-wi9U(nrt353bbT-lF5yKR#SliH-DaPVK<+-C{ zsq7VxYKsGOAg0X-19^I)fhci&a)#-cZD@OtaHA%`2FYKP@~bT zp!m^vPXWL3lU3C$BHodZY*-dgGj^`_!7G^mq$g%kM@_y&q_Synmbu%?KY3PZe$F(U zx5tlVs+nSticUZE+N29{-MQnZWe|@269G(p+TD(DG?_?}PFzqbs%|ZLK1J-#k!b9U znS9sdI6R#vw;GwY&U}vI`x3iMrhL$Q+!s~+GRgH>kce63js=2aatZc-oHIUzxY(z3 z;jf4e=?@uKla%((t2^Y>$~zfw0r&6qSRH=wYQKG$4x7rm(hW7m=$&rfb%0i*2zo2| zcmtlGSK_z^4lgfIkSbY_YyHxHJWwN?wPr}>2| z`RA`GgvhonH*c?_|JoItm$kgzZYo_W%M{fxNm2h4rofyxHRf(fqZ=oZtp>^qBWoT^ z)XO}ewwixl7?d(b7|z&*mH6X*9?C3(Ui3|Dq?M2fK4=@b$L;ft* zwK=AXWe*q{&?5GO&T+7qaC&$DyHFMl>5CFxRPM+@<^YJj#puJ&*IIr8_v>mmc z<9H4tX-y_BIpe=8fM4X1_t_2Q0nNSVkL~!qpjTg+rKqe+iL7^}1FI-vzUZB_Apmpl%km zGm~Y`Ph0s+^u%x6iD(*WGXf0Xh2U@aIfrC>+%4>(S|&5Ev?13UmecKIFMT3()|P7Q zT)+P~-)EjS^S96B0<)LP(>1OE4dOhj)i{%xAKVV!BKAs3@f7-)ilV33Fg!sPhUA{Yi`ju$6gdhWq3alN}8)%Y?gY%T=XH6)U~+`;G!Yo|<@g% zRUu+&9En^=C!K%yTs@3_!B5g z#Ijm3hU$NjL$M?@Q!QPZJFmDIP{ivX*f^|$NUmMEs`7H)h2Z0qvcO-Gsha~kMe54w ziomS2yrF!E%Q3W>#~Vq%GQkeg-^98j<#aRX6ef&h&Jt%QMcZj&S#r!5?n5};+GG3k z>D50*a3;zr<)>gFa*+?VAojCFVEVzdx@O1ftTtB}KDas#_^vH*w%KI&LG`eXQ{~UgB5Wv3^NF7v9#`xZ9RT zmuDIghAOT*9V(~Tvg!8>I%&ffc{!{yvjdk)sG<+PNVAXhcE(%i(==P;b1IO~$MSH< zh;UMeK^rr4-LcCZ+Yp9+JJ-|&;(ohJ&3d~cwrF$jVap4YROLg2LCaN)*VDdIf*x3e zk>O!kkfo!OpGYWtkV0!BVc$65@NFwzLvKxu=@^F{aAqD9lZ-A)$~cDDIA#2a=jqQB zBlRUbULM51J$S!f$^&jbL2qS^pm@~r-()cm$4Yf5Iw{aGILS6cJl%Klx#P+qJA zA3>_A+f8G%-QplhTXNE+HJFSlYgstPr}xgSc-fSz^}l#ZlHP<>qT<0DJFn_1kDDqv zr_w0Nm}NYJ0s4E%)Z)XsGdGz+>D1pT25IE^jksIYCyT}lz0+>99LZBk|^>&)nQ+{l}aVRhBztS!WK57 z7B=dDt*&nFKTiYqBUL$gd_MpDCeQo;a9I_z_HJ{i;Dw5t!fJB^nj&HE+0<7-sa#-mHA$7-uG4bX}eSuhM z?uQ3Hjn?1g_$s||CU`55yVgXHRJU}czq9%Ogyf(v#QF5$jJ77|5iR;>>e)KCJ*n27 zJ2n{MSjNa{9d1M-wr%^lSvpLM;>TjWC5w$@uKK23jy;(zqRd#OfgZ;-vNj43UQ zr#UfQ86^j=#(e|F1nuZcjLQX{fDQ!fp*nCldJdge7M)(e5>oNnW8mC1&_PcHSthi* zpI_c{iuBOJ`v|osK7wo4>)|yU7EE?^5=G=A9r;+&_Wm~}XD+x13iVVfPl@ywke`HD zcVZ^>8PLP2l@kvJSV(E*owAcSBt$RJySANe3`5Il5YLGvv%?fwVLGu94Ew+sO;?wM z1g0KWoGQ#1XR9&>1<2UUklmzI)pwI>umLo7!mX6c{8VHXrkcxeg?y&H0q#<9G~Ll4 zGlw2&dX*HSp!`*y!0FE8xjpk4r90HNdrFGP^j&Pe7qwDOU;we+HCW(A_(&F0FO(wa$w%*QDF50G49>L#8kl=RmFkVf)7+R7b-wXKU@W4I}`#(oz;dQ(hMbN zI=@I+g@Tl){ag#5ZFcM2$i%&(r4HJ7JuPW{fw^gGcW)X=4ub67p+*F{ zE7ig`1Q5S)^wU~t9j*lH#v8hP^}JOw`-j$hD$)tQ(NV`0Rsi=5RT1}LIw_>nc>Kd# zxLQj{Kq$i&rFxIBT#*Le%I_u9l;MBF6w3P-)cpOUN+LDyVn!7)+%256aLMftFfEi4 zDufluzQi+Rzl5vmD;t^f$Ntc+G_TCmf1s2fne0CL!jMVeRJY@-BES}Lq;8y$z$MYO z_IXqoxA@5Yvr6Lk*+-SFKaS33wV^CtGuSM?Uf?oYWe&@58B%TGR3j&5f;Dhu%it25 z9;h_>n@*0lL;p~o3N=jG>R6KLv@Cs4FbAT_6#FRh&5an~qJ=D)lg3*07HRPoU74;y zQaOe0i@yF`Q= zkM}+i`+D`6f?*lNrcaJP{pM+T5e#nc?WAq6Woe~x|CDERme{nis?WS$kE=F9JyZ=-t=K1Z z4BDA+!m1Ky{0HPT#SjBOuKI5t0v~=6CDBK{y08+DXp*4>HXN~>f*08^4yaem=S*!6 z+(%_PpQH;t>`~?{bCy1dQcWKzWLD2yj36gE<&WRwsoh7~%MwvZl|+V!+M~|EIh2c# zaFFrHZ3cz3(#*MyNTc1lpR!yc;tCC~m6J5n40uh*U@XC%EaKmb-t5eo6~V1BrB5rR zIDBL{H7@sf7RnII1%>M?#`ap+WY&o<{N9yQ`fhp}8V_77m?@FfbhU{`f09vXVttz5 zAL24nkDIKF*42`sgV4qGadD(Zu-;`O<4`+YRSAVcFpI#mQb*<1M?vFS8|m`Zve3MY zv<^|bGh)9EKe@scdSW*(Jhr+@lj+FtKFX>`xsoC3mpCQRZ=A>RLBAGkkFmcid{%tg zG0Bfy7py9$4**w{ujdZxZZ*4=xq?m&N9xk%2fUY|53JKBjA7t=wE31@$!Y6`WH zJJc^|v#gbQ%luGT8Afxw@&d_0n=GeeiFK81yG?=n{k!QMXQt;b;^KF94^b%xQq%vF zZUWu8Fgtgi8{1rv6-umH={RYn&`7W((}ZbO#jYporQ6}!Qd*{f+IYlQymDKqr{8F=dc%@IojaF;+;M|SW@yO6r`fnnkp+<(l z{!hyFIX{owPIMc+y4Bf3zJC_ZxGZ|@W}`&AlP9mtr#>!Kle4J?qiK8G%j4Whpxjaa ztC;ga(i`&h=X+5uOZiq{eHdDz^6vePK-^2_ii)iUVP=HHxg;}pQAQrI3o7_%m{tXC z(Rf|!b0t{r8ATkLZ?)dnD!q+^5Z`%%5^Q8piFbcEo2A_?^CCc|c2p*=oTCt|%!01w zk84QFj2joIVu}gr%yxW;35*#h`N4=N2~Z2YLkZ>9p|SgJN|AeZNy~9&=AoVGuY}Az1lii#fUAd{U2=1Ohb$im}!cNe-WcZ zfA%JNGv)6BjxocItJi`#kxU3dER~w&))KIxd!pa=S7v^>7EIS_elgGN>9uV|Pi7fV z&Qce#!KcafFUK3>%$P;g=Sn8Hc6AO7;&61qhj(J=CpI+KteA4JN%K28WAHhJl zaW|>AJmia82qsod%HOMKPvEpq3gH8BWrxmzkZ{xS#ydR3NS(J&VgD`m>)Ez%r7S0B zzk2G^5mXhx7$FR_%V63%&$r)82=I9cU*8!T{3%x*7N1V&5dYucl#(lWo4y0l`WKh^ z`wyARu_ZNEqA?XOh_bcnP#;DIWr$T={@RDN+<e@voAdkbZezlDco37WC=0V}H&hhc|GltXyf{eB+gqLJrr_q_866^0@ zZVF!b?K(e_XkyN|Do_vWw! zMn-(zd8Pi%b3U%YOgd4`RD>i!y~Ci5{7Gc7yU$>0NV5BW{<*NiZ4N->8?^LTI1wIA zR#%^iOKN2;>&7s6JPb_*%Ns19LYonxH;cKreA4x8BBzdkPKjk|=bnudvm2g|vB}JP zK{of(dZSU|?Ku{$?Ky#PiwTkGnERiYIkBj!NtyNF*MPM7;io#_Et6+rcC0WumELqP zu>~r96gq4tCjj9%zDlep_=VEg02t+JWQUH3wo?bBhF4t?xZVL)-o8!vewf?KcM!Da zDkfc$##Uzm-%PWg+Fv-*V$XWyKazZqc?Ga?`ze?{^a2UY{xb13v^GRhZTfLvS2|W6XS=WoDNY}K_(-`!HZ7QeBGScM7?xQ#;@?S zcsc0Rg`ghCFim5jKn&iyBqpb9+Y1HiFJGS>_3SS-PM>Jr`NUjG$r__uImAf{K?`j>p3gQ;t_6I(VJdVzauN=-B>~uir!TI)j z^}ypT(^Ee~`XWOaIu)x-ip&+fg_*5SHaNy=s3?g-agMv+jIZ))2zjwBs#|LDD+Qsh1IkocCW%}#kq`$Me}Dp*0gE!5fb4dvamkq*F-MYsc zAMi`1tva0COj|I?2@#Se4@H-pIsW?iHZHwXiywWP+4YgbH1rBH5-R;~i04Sw`Xu2+mnj!(EBq=8akiK_ z2>{m!6;GssLt5kG_DWst4tptX_`vH>VK!2JU7OwD@!AGPp_F>?m)mh2;<84L>r6~( z5gmiP_PeK7CsM*YWpX-`w+_e+LK)O4`f6>rK=uTlT?eH58|2SurPu~yWzfG>Hfmp= zYVtfKo@9id;fw$?o4A?(EbFb0L|1#u zDi_mF^Sg=6WiR5&u*Ky5lsyFlPmr{_3~680p^zWC$NJZeSmhDrw%b^j#08*FrZnxx z`QMemw`-bu$TMK{%|pkyHuuorU9<0=-NpdL7_n@q!J9C${IGC4aJ(0$KLI1kNw8%Lj_Ay4 zxc$y7vv_|O^1r!GK{{eABAA@zq@q6C!dm*Sg~LA=3snR7YRU6-$~FF6v}j>2UFRv4 zCFP=|U4GmR;6tYDtZB;P^B@bP(0Se_qZo464n1pw(nI*W!(ob8W#~)x)J4|?sfUV* zM;mb#=K%@>fBbJ#9`0|@;W~XfBJukPstPN*;RhI-c84TTnY^b~958`n-98ars%Adg zcQqZky_u97rYCw}E&_NV@&Y;68?J(qnOPU0g_|yu0XL{GFQUdGxvp<#3Qf37moUWM z>xhM?N02!xLEgw?(Gj$_#pI6eXAqo^IaF4Z_7_xs#NVN7kGR} z8J%=MigmU}`~F#DA1MWIc*#*ePCw@V(FSV^)>*JYvwVihuhRw4VT=&GpCwue)56Ld zgGr#m4jL9*Q4j;+^8VKJN?FZwYR2%J@aS0v&mU@pwX~uEU2jW?zD|}&6(b2=o_0B` zce?$`m@&dVvZJI_=~wL=$UYbWYjlGgT!Qyu9#}Ib#@jBi9j$Jg%H$lQ!?0xO8+lXd zEzDSm8S>oSbfxh~8jC3P>tfv%aYsy63i*^XVUe$@68gv8??I>Le#}YDD5I;V64t)| zOU%rkuoKg?Ck!R8E|@TyE3St?kQ06;T@(ZeL)SC|GyE*oEh1P9qq)?X^X;X`%04c5Vbd3~ z8W!$z54OrRP_PI5LM0koFOg$@Ux~ zy`=bD<8r&7$419f*>VY-G1L%0XDtA^l^4)`N#S-)o5Dv#HM0PS>0DPR&)Z0)V{98e zcEa_bQCYmLdb>wArkp9DW4`HVX#{$HQs=Re**`^yhKYkhpC%a^e;nP zJ5JxzD@KWZLhf`kkv)^q_WNX#Blk2dg4csZAmABO?e4M(pkzDxWrAEEI5`GZ)smj1dqQO~Hm$!C!yb!vv&aV-BmCvNSNjh|d!pmMYr@aa9j?~h0@#pU z(J*2ot;xXgIdQO0hP|txDZ_&A=XiP_`H!j17G?mBayt|VyS^g%MpT-##8hQZzas|7 zr#_99vt&-y)QAvy(q4adB(HAXr>}f1^mx*=)vwnVi%Zx z>iIT+^$$x-6Y%5sS5{SvyB~ZhAd4o;vo2)oItQ;Fy$2Vi%NmnBC6TbC_)?U9Ed6;& zUD*x7<2$A7I4^0KOK3={IAsfWLh9nkW|ufR>zF#>cS;P1qWtQsoiI*j^t>DE*JknzGNT7Kl?Pi;l#yk_dXMFV`EF*ayhzMl_!!DH$HM--h} zf|>x(O$DP5d5=H(4Q*fcAMSXWwta1650P;_2vq#QZa^o0AtgS1ugu`iU@OYF`2m|}1+x2Zl1F<+{_Kz;Bu&frcFP^O;3Tz5CgKTv4$DbZf3!1B ze~@@qzUHJ3xVPDsuEk>D#V)NyLGs_{>>C*%I5miGGQ9L^@YP`RE5XvQVYRz$k<{;I z{mGuXTuI1EsF0=9ae)-&Q!i4@{_!2~`TD(?b_egjZU6N<(%R#PU_w`!jMpc;_E;mN)S3~7fy$9=~h(D;+sST9VS)DXLXgeCcE z!4xHLkXPsQ&%QIt%LrjSaQpDUIEq9-FFC3mTqXZ(!kum(3TcpDiK#F0!SR-ty|Q-> z1IqIRZr#b(E$oXDss}>tdCOZ=XCG>bn#Nso;`WB`2jQNzo={>@kxqDrLGE!EI)QB3 zdRUcnm;PA8$F1T;@8;T3{vP}sQ(#4OV9c}EG0Lu!_kXTfyyl8|O&&gF-EzE8?=_v0 z39;!}jBh>|r^z>}RNjZtDdY*?^TUvK&#oj0m9W=@RH9LKBIfGcIc@?3>)dmN6%*u0Sy zLJ3Lk%i%#E?xI%&L$qrjYj*F>l5x{Bex_jFEmD_xl6!+Qz3aQNyA?CyVwwJZg5 z6*HgivVVBYZI2Op#duX)aMcdXCpA5g38Q6#jxpqk@hphWj$(Wmka8qmej?z}$JSr{361iJ zjX98pa{H^tW5e3nwIYSKML$;8sSJid&LtGVpHNV1KzrTL!v5#$Zy9pgZfS!S;oRyU^R-&CXQUtG#iFR9QA-bL@h0aKlj*;rYA<~NdQsF~+RG4Sl~g_i?ua0O)6Y0oMv?2_V| z4V||v|LV~9V*l

g=>D;$Vgv*sP5A;w$NK0!W8Lhs|ZpJG-67r-N#lX38tTpm&r# zMOe%->lR>Fm`AFS%{DJ!yLtFj0`-u4xcudh8SGHTUc(cuC>BW_eT?tcTkY^X8V$b( z3)pbL7Ftnysee)KekaY!9UbYQCA$gRG!t2S=Y5exnFeD|0OkK0!Ro(^pkM>(!Cyv@ z>N3GONw=S#c)`lo1E}{pgTNp&3v%w95OnTrPy!>h`=exN^N|7&fP_4z zGCS#)j1|Z2n|eT7?CI_+1DREp z0Jgy-SE1BOv{fz-2Z$qn zT8*lAg7cJo_h-hCm?5|pzMFgY{jsKD+APm&k+tv5Eem#AUPbrU8;&`3;NyOadFP^J z)V4^4g+b-h$=4Z<*sV~IQzqfN{!UHFzH{;BhyK2j6nZS0k;_XT{1N>b1Q z1khcMrBcyK?SoO}4WHp{|LL>ea{mDtK&nG5D-mX#N&RLvxmdEm%Ot?tZo@#9Z4iD5 z7A0*1qeD{I7*32=8whUoRFv_w5sPFIM$JRAb_|yaimnrH&dFtx61pO^q~0MHo0G8{ z5;pu2?a-VvjvO3llyDhaI-{WoFDQ8mbbC|(B?rdjmJUDq$XTNO3$)YSn3gU`x`AK$ z2Bo0E{w$GmJ^Sqi%$%(I;}26z(pAOa-t4IhYb@@L$c2?XPI#fTrzfboAWj#+c2@ym zBN2Gm{~)6{1JcYT_J@U0@)fExL~=5u`P6Z=FR-7{ak0`XzVq8Hz6u5jUWl=ZqXHVN2$aWWwZV_UI!0+cuM4aii>T{PH!}l{iac+A2;#Qvr^d( zZ{Yq|iJy}!6l(!nu4Kd)@2nHl{UTp}L5y|2^I(W87~oOQD;=H<8+jZp*IXFP&|Esr zpD=n?dhdW1f0)B&Xyj_1op?t3d%|q)*7mQ02P+k=JS;gpru@zu>Zh#^S6ehM7k=z7 z&x{CQZ*9=eB=Y$r_Gi)(rS1J+y!r(^`?|{{MtIe}E{78@QDbmBoX->2X{}CsK~-q&6XH(nw7t_jU?yVbH`n&1e5*&6N4oQhxI>i+<>?~PeR_gr zrn`oS!2xnxs4_&|d%o<-b+gv)m(TV(-@f{JQ0`+Elnvft#$>eW1pVsYevUVteCL7M!&Bc;^ggR&W;~G#YxW8dCP*gh`Da}`i9K! z-;~$1Rv%_|cmwG&_wK$d%z)yO-e?Es4VCgo4R~{@){}(b$9+FO@c5v~F7yk^%0XAD zIgai?60PwlH zN3;0oXQkvdJLN#{kw65k^@F(ht`M}Rd2uR=VRDJPzfJD`|7T?b2_b{_DjMO1b2w_b)_X3QsQ6 zr+fNgzd_Y{x~qH-R3+$X7~-T@1JRnv9eTT=&uW&uk} zu3>*z04=pOF4ymexr;10fCkICjytuj&TkS%Pw1xQZ(FF15Ot zyv%72=qR`&K=tgkUm1E=VEW(#>1~Gmxd=?5qBW)8szhW)^Xt;ySjdi$=8@Ldj_yPf zy9{La&62}VbOO1-!7(h;@8Q~6J&FA$&&#;4H&41e>XLQ{=z$6sK3bQrt+RA#IPyJ> zMdNKTzp&h5ORIR-@CIC!pSW@ebca6+^(jIH>Rk&$GQP2 z&fVKah3#*YR#pUFBwZ)UTHF<*Ncq$&| z7o}Nu8w8+j9hK(A4e0|lQ&oay_?>LBC1Qc@3?o(lzo*c4-QKr~At$p?I z;@JQF9QG^El8v0$9GqL61~<`$yuWcm!ZiO`lCLmswo`4k6j%v$|7LnseBwu(pBb}9 zGTseHYB1!#H>g5O_x7vux@Mj${kYxoG~Vlj z>5YNT$dSnP4dB4Yl*q1!vj)nwj ze!Xt?!CHP%Jb@+7;u$5PAS%Q3<4A(eF&zA)NsVyV_@6CH9X{oFPUUxQ5E0FI^{ekqo;VM*ncYD~Vnwy6Mbs`EYn1rbOw^A;~N z-K4WWI(rK!4chiT^gcHJaHsst8gc8!$Ztw>4XSmw(UF^#AlYWYgZY}7uD23lYUPqW zlf~5%mD@#vQuWzhnCzqNJh3}(Bbl|Y@n6oQyV+t04A944=3X9QvQ0! z?-_B;S+D#ZeZY8t&0R_p!dhJ75dW%QVF4&9QM1rrF6q+EXf1=K-!lWv%8&G(;rNop zODdHT6Q07m9b1*sCbTKB8;`ouVc*%tCxb3%T zLpMea`7ECVU$+B>i)55b?8QA$VI`R{KDwT=3o-Y})*qKx>spQ<*Q&fZM239F6)k;o z%{Jo}5kn${e)}hlvzv82OO=Gz%zwmYrri~$mMFaXyN`V2Gk-cJzo;f!b8sopyIZ^6 zXYn^VdAK9;Y@2fG5frQyh$K2BdU!T5K=Jy2OnrwtT;aEMf)GTB-X#$&qC_2aNFllq zL@~_NMd~PV`K*xoI;!49&rF8JW&YK6^mQ{VBD8cjVVrYxL>>Y zMxlQ%Ls|Pc@3#>sGFdtHpv#s;rDtlHH)9si>|+S2PJv)Mod))7r$MY5+$$7B&J zVPCAo{)d!+YyN8r=Jj2H$i_n+Np7R^z>~#rnnuDOl@^1Q*TXb1>Wi&UR{kgo>BR+#G*FZIQ;ql)zu+4d zGUo8z(g@X|4Z(=(Jh4+coDV#kE#mXX95s^C<-tx~i0Vv}JWDXj(>+gN9Lga~`uRTP zaJR*{M`L>Yxo`r<>COu7XJMgm8bwRg+du0Iy?Ml)ee`1X^O zwc%pdjUqOnlUdIE(ddITB~Pjt6jLk6W_R6hitVwQoOhNn1=;Wd>U_S949RQB{-thT zBi`8A`dpsru=z58`_C&o1+U243ok<$IgVoK;a*?a(%9t_D)t z+VRUak^<*!=brhIjyB?p1x*CMnBIXw`%$EXFGnqQ^-)>yHX?Ap)A}NpruZIxetr7J z52~go-nSZ}$j%xZ9d9`ffqyXkeTGyc6S`Pc@YgTF7eJ1Jp_V+3O&I^H_!v18$E#A^ zxf+!$&|D&=MOQnj=pAAJJcl_;!JPm1_5Sy+3BE?jr!I#W%eL#fAEV5_9l}{Y(kUJO z$3J~cE-^>yzFMf7!$3FYYc6UWcaxF+d?-K8ynE^;+`NNJ%4p2(Q!%I%*n64i17LC4 znTd$7+tY!oTJY8#dFwe!$U3{33E881WpIeT8l0ct4v6F8BlF?0y+idqT4)?{jKgM3g}-FV3(FnmMjNXkgI%8#xHU}w)vSKk&818_c6`1oE?|6F#}{<=}eM+MgT-rE=29xGhqNBE4Al<$Id!9k2iv za5L?^^$tFNPq<{}xvuz{e!5xep>hAZx!qH@h~5)Q(oSFWrER%(uub#?SNK#|c)SwI zq&++e{%bsfZek11I5}+uThu}>Mdd=%zUKxYcB5PlieaVD5u`+X2ZqBNVMu#(XNfi1 zHM#_O=AFAwU;3W;e1e)-NCY-lbk_dp~-^moG-ew_I&b`K{o%nOSJ_kWCiY> zJX&vu{N-N|3l9EE5Il>29WD03qqETZ+s1~yJXe?icVghMG{vA`d!%+7_RHagnhBQI z?_m3S%|~16smXEf6e;~Fd>_9ZZ*goMT@Fv=-;E298%S?;ItNHA54$f0=wi+lOcWn1 z+@QSq^YrM^MVY0=V=C=Wgl;380+-LM@-24W;FR%-UoDE|+y@5!VJ0qVzdu~EnUAqJ zpbd2);dd^M`u()KV1XH2w?{rG2SIr$GK@yNc-7CAG%`t_5iUcj8Oh!-W_dOR^?7&L zp0$+OU=3uqz9eKxWZcS)3e~00_d=u7uMd)=?_916r%+yVl2S$0UXj7P-63k$9sZv$ z{P3U1l<@~7>m^5fa=j3fTA!~in$GUGBco1DuVK^Jk~cL_af6YII=xd;&P6V{B<^!K zLFYI0wUOQEbC5Kvj35&8>J*Bi()*sL+;tj}LhAUaP;TH=LLadd2l?R%rAR5OD^8pC z<`?5MkpF34QS_pKlh9zNEQ~$>RQhaqB2P7QC2G99?3W@tKv>>RPriU4tw&5lcoa^P zZW@-6mV40^Ny^z(BUzGadYlh&v90yyB9f9R&KDGg^}|o3Ru`s^uKk~$L{ffbPM{y^ zJW0YcRt6>Gs->*Dp6{eo+^C*=AuKeyEIrtqN)XmBnIfM7VTt9Zh6NmC zsox7j5gW(eHW}P|#zthmK)(3iq)?*AIOfE$4gPipQ(oG~XW`Cnh=`7J`^+$uU!PDg z`3TEFAwB6@o3LaE6VHn!bCm}4tLf=qlvf1(1*x+vzQ`n+%YqT zDXh@7%4wI^sK0hhQf4JG-gBzi7V|keYTi!56{cnf8B0nu@1D(SM`=x+WoC^)D=Q6> zXgu=Jp73|3w5g*{^}hbiPz?8&v(q@@FkqS-Q0h~&$;wHr6!qLU8LzayshNp=_EwqeSy76sm0A-D&Jw!mjwe5E#Y#@&AaG z*R;|<4zcY$_YyV9B|WX!{p~+VO?(R>Oh!c$4ER*n9UIySs(UrVhL<6UqC_Sdy zA+!C1`F3`4g+QvZkVGdF!{P|u@Md{@f!c;&UrjJu;DB2M9y;Pi!JhwvG6nnET&|Jt zV0~8rSpAK^cHkc6+|-m)@bFO!rD*i9|HjzcAE9Kk8+zZ#S|Ak)dyRGFqZ!PZQaYS<@?H^x_iDCzIjo=#u7~;H&D=f?lWto z@?Won)fYf-uWuUw)0_vQDYbdB$hoQl7p|||aH1O=i{v9DbtbNNU<2E~GTw5Aibk)enrM4z5Wa7Dx#>vHejC)psay%XE3Y76WL6&hw4Zm}vp7nNU|DEgtQ45Rop(Du%<6&xkR-&CZ3VL>W z!o8dka}lj(#-t?SjH^Q%b8~9V1zlZqUd4}E|65A0hzuCg{Oaq~9*$~g-`cp4h~V;T zsqcScL!e2Q+xi9G7=iZrWpMp}ocXU2o&T>!)Hf6USAq5<>b?chjJnvcRsc33^|p*2 z&w?1*!V8B5%%W49_?^G68QZTbjFAuZkxVa7X210j35S{8;np;Ac+^0@^RyTh*zhY{ zE6yD)vdnHK1P5pt)lMK(QJ;|>ChNa4NE6KD^W+u(?yiR^0P8qekCV#AHC%qdPMWn% z`|6e3jOS-k&)2&r-yB^dl5Y!48Ji}`kHe$rjo2;8boaX(2*2VqO=bEuqRu*($5F>W zFrS(E!!N$OOqH%;wL9`XbLJg`A`G=!D8h&g#qyn1*mMew5f8B;jEBF3(`3hO#=ujH zGfHu;`+`(?al&a$2a*~hY=u$-F-@Qj0uy&_^R zlTLqQV27|3tgLNBr%lwy7fub)e550njk;)Lp4`*Bj4t2Lpg~jVx~v&p$b|(^?L@2K zszzmTK06CP<5K0SOIBsypL^}8hZu0<5@SZ{n76bggmyf1Dd4vj&ktBrvxFWWhA4O+ zM7ouEAyJk|SN`zq86mg)Ag#$q=!nU=cSrZl0Sjvn*63oSG7_{~eFR7rYz>VGhk=`S zLIW9~`wEo#M{8i9=HCuEY?}o`@=o? zx7zN;hKpzaG9*Urtb}fqRYrT=@?cjQmn57%)!uZ4174jj=>`#oNgPNV-_6!5Lej6n zZ`RIO5V2X;qM#|OHOJ74mKyKjd50$Wp39^(60zkrSPe-L)~+fZKZA6%qBa4*|4>|N zv;ZQhtJ?u;)BpGmmCWc2@-pio$Dcw47{3fMM*#T1U|1B(?6NeGOp^6%$86iWZoFHz z&pIu%i>Lp?*;p|k%-uuoF4DOYm7HV1*|C2rf&{@5<%a#{*@k=9ZwbK%-trENvf~2x zzRI2ERVXr69%kV%=>p{zz(rgn%AMxcl(bq3LN`; z5TpD7-!xx2+`PoJZOfUlsfC*hg=^zA`7)f2e=g!axn5}w^loa>&*7|-pYmkIZUA7P zI)?(cZ(@wzZ&&_YN%ys-#|jDEw%~OI6e+j0SnilnJI$=cD!8a;gY_^+eILoPZonc?dmcUB&(NsdLaO=NEdFDQ38>b_w`Jxi>JqkjD+ z3B)O%xMhT}k7>h`pTo}A?3lUv-yED5=fxqC!43O&?pCr*@6Sk7?|r;K>#DJegHPY> zQPL)95$acZbLaR+ouFP8!g5H7&-mxFjof?OqXpj4xRa9V(;2aiH|u`%`Fm4w3w8IR z%+7*K15D1g=Az)66X+Gy6)xO9sBm8VvLzo)WVgve!`VO8HTngm?;id7R&PxzUv~utKmzlxse+5sn4ErbfcItOczB(#uw{?Iom2IFmeuMIK^zmBIMzM@- zg&w_G+^kNdyk*8h`@5FwlKOls#z_3boXm2+QYuHvy56MUo6#lvZ@LIRWKrPNg-5RJ z2$-Mc!QZE9TZ7Y-FGRqE21Gmw`MwRgmq z$$8WXVaXLdLuKn*esgbw{6;aORN6V>r{?#R-~Ce^Rwu{-5Bt?Wy8^-jWuKG$nPfOwxJ^^SFC$al`a09rh@MxE7+g;| zGLdI1O;24hC|ES{Ds@5%B3R!C5@D$P_P~pyqS?7C;X=Z;ij|_|GC^Opcm3Kw3xK72dNu_}D0sg}UheH;r`pK|`-Wn<*v#1%vT~SG)-9aciyhj#e z{`6TD6pu#S>*XgOQwWkjb`54j0{wGew#xVo-vzQn^I5vRV7?P)@xXeNM4ml>S>l}J z??bfyb)To*b>GVQ8}Dr^j_FkUnD{4|D0TCVQT4O(p`(}Dct$Qxr;LISNp4H?B1vSzK@tiP$@*6*2lzn+t5sajsU`A@pJNX)xm}J?1v)-z2WiT#=iYYTu`^u z3nZxV;8>nqt`R^#r(>o4u6w+0Ki9pa`d*ZwWEyGQp-v#D?0ai@+?yrCIV@)C1B_z` zkRBp*NXK&D0E(7=FfM&=t@Fs#Hb*nfLG8FJ&7e-`_Uca#-Og8ERVEoZf7pGuz%C_cW6q>+sQ)%c~vA*$1aRBD>7m)jkv`lv>JH&^{m2E%_s zzq7u|GVXH(mnq7+rZ(RGG#jg8EL%|fm2(kOTf8vraXIK>RpK2sI{0&2h&AZFAW2vC+=`^^SJ?Bkh;f8>9~`DB}3MmhW6F z(3<_c5kda+1BeqAv36OH4ao(?n&81ia;(1X(UI^I*Qe~u4kq3K$CD&(`x;-yZy=~Z zHA6tKX?pc+_+j;Hh$3c|CDr1u9_Zp_1&KNu*hKJ}_S~Gb z(`lZ&RyIr9eF%S9czArIKD|T?UUzydrI9Sb6+i7;e+Wg;wpiSPGiCHhB@A3C*F@Rg zsuF3oLe9KyG+mh}A3DrWc7N17KH-6YQUk^HvSt&iAey15c(voxH~8`Asyq}g>dPdA zVn|{PhU`97dz`TV%PU_0s75@9NNQS$ zZpu5Pr);>S@z(;yb*A3c*7PL)K^%5nk4?c^u0WzpX&fnOeVfRy$(B3+$&Yt>nOm~7 zs5O_}>_R&;8D&hWD^l?G$b!n%x-$Bj2sJq3SNka>*U?2-7v(k&JQ@UxfchN2jUTZ6 z{u0Zh=e@-JHV$5=Q>Nr5Je&Q@rUngoFZK$)=HaZ<>-Lu0%k(on;L5j32H_}0{YuBV zQAnVr`B&U6W@+^^Wo>uhg#zAooOUHtDa$juiZ?_D>6xC^vui9`73JfUWfGjS%Eoz}VPO-TqA4fc%~!?y(bUO{?ah>@pv<>g1WIqVD!s zp?%Im{AS^*1TuI9^;l$U`s1?<<}G|B;&+Z+r)`GZR^^j~D$7v#7K`!DTl3*dv*e9~ z@}d8X0nSVRQ`Ku`(c#`?L}(TwzEr3k9Y*eb7gk4S)H~$Yth0VFKiG zUd%y4Zx_tm_oMd%`w4B2N=IxazbSiWK}Lx@D}Ua}YZ|%O0$7}!39BM!l_4L?!=U8f zW5(_?;AkD!>yk_o0+6n-y5Zt=U$X>tQd1=Us6tLa?OCn@vh;a)^NY#o4pcG0y>$rg z*Hgwo0}R{R#XgFWVBPC$a8ro-?A3RORC4^4wze}M>+x=5!SSF}^4zkpzcZ=N)B}n* zdZV;$m;6}0>C#&=`upYA(TD9|hwj#W{Zo2rs1se*DL%M+90;PGQh%U1D2=;U>Vs#z-c z?Gf72&ilfOP3EGLhv^^qu4W4ytwu>yJ1$?8!Ag8a{ap($GY#%^1zm4NgoU>=>WF+w z-^y0f=*gLZnDZdY-(h2tohg!#U(~!t6)#$sH|Ee2G+$C z*)lZK-_|aB-C^P3Y;B|Daak2tnM|uNxroeRpR)JOn97AM*r#>>FC%i&|LmXAjypQF z+zb8<;TcdbAfk|H%onfYzpqvg+!f9umr}!qH%u}}H>c24JSjOJ zV@Eff0C$?a_x73cn|*h(lPf6$PgI-eL1%e04T+50?g3gkFyi@p2i_kP2`jA^)hC1RcX{&-OsZV zvW#(6k50cJw^chDPW^Y}o41a>FlThb8DohPPml7=#R{Y0M}A4vZPd0?YmjED3*Or1 z&SB8Ir$TCH?h1%#;trYR+gFMX0}+ppw+)^!-y0??XOzk_Mrfo}`=!^*y{F! zj6+?~u)PFD$FRYbPc??iI&70d0xuF_XjV$xiNJ7-*u-$cmbaQqgo(@J`HwM1G+lDI z9M{Qw-L-`by_G3|*POf2Y^T%iPr@*`>gKR>j$^(kN7=E*wXckxm53itlwnzK<|?>y$4BDHGd|F|YOn4AFhooQ z(C-=5sr`mY#99-{qqD~y&Ka*{`y?K9EES8+x&h0FPffrI8orGMa(J(3q1u|a%{+I= zY79M&4A_HHQsLLgEcFm+M*_n}OQexkzjbgPRO4~oGHpL@7Qfgnt=#F(+3CGF6H`)~ z{U4bp?jP6UFHTq-SW;g2{OtF`p=A$QMCyT!zNl+KT(g`j-ytT``rD){L>n;L!Jc}K zbN+ssr>oSRTZ%M4M*th;fl`V`iv`7}+f#2K8g@ zLlq$%YydVn+KyoBgYXaLuqH3_X|8Lh$?AtlrM1Zg^Y`@GPmb1e**!%~n$BIP=QI(z z`f-!PxC6kJ(P`twSheh7FSjqW38a5X=ff7I8Zu3N5pbbA;O)!)y#8`m((etTv2;F?rhz&M^hlsm?>caDCe+ zRmy<#AyXc%TD+JOmW}~YY9jTU9TZJ-6RR&xs*UEvKCZF+$+t*;3awks8r^wT6SkHl?}yqA*N?OG zzWhA1K3ZLx2G_YsSPL%`x+SY4vNstEpLz)yPb+F*fLjZ5hAscmU`?J6LWAO}eyaXn z4_5BAQg|viCS`&5P*p=rzl#GlA-M_*MHIwAv&Z3%!!PEYcYN-A0VUx+LxY>q6h`^hqc zY14ybfpN=sw6>_pzB#c&Muqi9N$Vf%PU8d(nI+c&`Pw+S?=b<<^>>(E0xO(%D3DgC zKFK0eiK6xUXKG$2XGSA`>OM7L#M)0kG3(QF2OMr40QOBd+iv37*c;miKP#e4t{xOR zpt@={w2yCm<9``1jhT3Hox%{GYVm+wD9`ZDVdVRRQE?Yf_(&9$m(~D(y^)UU$%w;& z7Qwjwvk`D>n0LN1>ZzCGP*8h@a_<_hZWu?OFZjyYH^@ZFZPxL=^*Zsu2&Ka9_B*Il zk@nRVfyN;_v6KsW64R##wJd9`Wze{eQDN0B$Z^?$Wu;V<=Q~%rtkt?mccio;!a{%( z-TkI?oDn)Pt8BYdJm-731Dnp${){!P@!YWmb0GB;5xoH}Rx=}t)~o8ieV4jx2c(h5 zIv#s2)0xtRhLK-V_1yu;9lzbeYc4{M$9O)`s^RhPO6fV!Icy5Aim1b>;yv5P&B+?V zqtd(GW9{~fewy5D3|g7f9+6CF=#K*jZrHYrlREnNT(lBYMHDVg`so5^?Y3i^C4w^! zpeTHsfo!MiJM%!a;u)%knQV%{eouLJG*$jUH?RHtbpFQmaLYxlq7>kN4K^8mB>VVI z#3vrk>%(-;&tp;U^i)u$cUgR#gD6@+t<(5pG#{KVEKhw^n$^WLI_hz+uBBbM2`jf< z=R7Kv#kn+i5T7lW3 zgkQnG%kR|e@3@cLgmh9+aVB*;B20gv@Ev+O14crTb2RLakRX|5=RwJy%NqNJKQv*|Yus zn$zsG=J$o>XsybfN(?q4IuRq~$tNp>b9R?FbxFPuDrvXIj_Yi*&@ZBK;4V>?reok0 zZs}tYbuzi@Ns?UZdO-Zzaj{*8d!27TT%-8I-YMab5~%S80g(7(*m}XxX>q2R0ElykMFyR9=*vW^&QT`@4E-BX1oTK?FHShyn(NR_m=Nvp_(#c`C~cm2`6q zOM(>7l)5RpMEB2~*i{H7+J0kjS5w4}^O192V);}>p78v7h|bu`{~mH((to(Rb2a?g z7vkU`N+P~@d`Rzg_}}Gsd|84rmJ-bp{!Ys8=|7|58oyG(Y=1ggp-q0wo-XfByC!BG zj&>l-0+VwteBp@~s+YTSZIq|gfgqbslA|-{TJ^kbd7hUC=6uCj9f3TE&#rtwJkvj) zZB8p+El&;c7|N}s5zMA(<1hqokUK#Rt!yLiq`wi*AN>R;(gT^VFmdF%*bhixloC(f zE8OzBr}<9bXojQnBP$z=Xwn$bNO4ck0QRVXo`^`6VH~#f z0aB)^>%l%Jjxq|6of}w)PW3)7^4O8Tj_lTR;MIA>7aHKXTL}(VN1yL-H7aO!^Iox4 zYU^K9*qoC6e2LPV3o7Q6JJj+}-2h0{49@*9Jp(^|2*mPwaHi#b5^=QssBPbey%)Dz zy8d})P+%OSvN@;Vg^pw7r6F}RDhLuUv8@t0AN^@Pt?xGJqja=w*l#n$M@6~*~E8~eL~|=+{emq z0Ly+sAQ<7{%?MqiuYCQH%-fBDdqah2)8G_I)`TD4W;esS_txhghO-_N(dT%jlN2z% zWr;Nyi&;$mLcaMLX*LYqr`>+!A$)`6YJGv@MMU0Jy6Yzp>C>?O7OyqdbCQa0yPk;o zUe8I?>wkq_6bjFvyWi>jbN-u+)`yz<>^ULI`~mF&F>iusT|Je12~v|swQbjI|Gj*Y zbM0{=*;xwMoh3(ls(J^ehdRuFN50LoGwj;7c@c$cV$9(5ykLAfe)gOhFQ+gLXq?GT zQm}Dq6e${T@GR(F$9PUH;Xc9pgRH}18s;=)F}dXFW|zXi=>IADK<;23y@P`%@^7zO z8CzPhAL6nrMPoO2G=g<#wZGzn+2UGsmI&Glgvpt1^82XO>)*kv#*`tsb- zDr70mW8MgUISEE?x~niX6umAB$%PVmwWwdNem%Axk@iUa`?X5t3n^HwKGRz`k^8Mj z6@8j=p^kshQ9T4X3sG*;G)8=EkGYG)ayQdlXeP2+FxCEotNB^U&Y|pf(r_ zp){zQ|69nNGU(LQB@KBjdH8V0l3X;E-1BwG#VG%l#L2*9&9kM|D86;+OF@mcb8fZ? zjnX6%VEu{}M^0rHcw?{vBKs;eG_l-{gs(Mg{!b$Oi8=MFe)W#<)l)t=mDzUAgVlr@8nYVb@5(6hhF3eg!Fh)2aFy_M zzs)ljw_xyQ>OGz4ih43vh?Q7LHs?yJbND9~=e2iQEgkF9$->*j_@zPaB$UDe+K3ok0ZHiV>a)@ zmV2AU+um{GKg;*qA1U`|PfuR8XPDTx_?ZyfP)X4>)@B^9xjCd%i}o|Gu2k|4gQHvH!aR6MCE*CyK({^L&ncPU#SJq@009LZAO=en#2d04+5Z$}dIE$5h(vrO)LDc`dWO0B<5}e7UPgN%dUR^@ zv`QBaQ}otjMVk^aZGGf#K7^0cXS=_YVcqI5^gNm=!wODGMkd8i9F%Z!i*t@SQ>n(Qm#zHUXd_A*U6%#S)8zP_747zj0sj#pw6!s zRyGRV(*N3CF$ojZJNRweV*M}<7@WcZ1zW^T4JL1A`;9sfJy6jSD_~c3eSrJAq|P5- zL)6SH{DG)n;&>Y5 z1OlVZr$c}lj(TZT~ ze_epUf%=sN(`2h5U`HBM`1f)-JFzD%T3eY!>BRqN{Rq(RdZNC3tz;2vRR*gQOQrnI zBxE%=sL+nLmC_sAlyArdaJ)F}54t>PLzLJ56mlf28%%#Q?n%?c0U|L?M;CwlKCn~e zX-qf0I|S&q)%Zlkso-e)YC2_wN~+pkHDuoW>aHbT(|<|J3XLt?%>DBYsdRg6fU4RR zm8_(Wo}nJ&*o{r6QKJ@ohl}<<9sZcEU$%In+Dt|yRqLLevJ1KhVm&Dx%9bPq%`>~y z0Ig)~sisH!hxzvHXzmhtJ-rqM^f2Rtk>J97+ZWm_9&E-I4zkhh?go249M3~Ui}*`P zHddr-7i&+RgQY3jAC|pBEm@0vdD;ePCME_KQCQlCCv;>_JpLM0_n7uAc$7#@ZsuzBb;^Knqp~fK*3F!6Sr)T+KiALH zO)`-{+?JinEr0hnctk*b5A4M|I)a_EURqB<)lQW5x8mQdkZgBK^Na?tKAcowL6+%$@o_8rk zEn!4T0xMSxS_|ltEbjIt;-}15@TOzO0g+1B)5m%csq}N@Ow!XadxB!3YRV;3V+y#P zg48Rol_K9pEBj8bevQq6yc@D6B+$hTkCk@Ax!JWa;wAM~z~9 z_|B8>m2}pA>(18Zq|NdBIX#?^>oL+R^ZSR(?$X=^iMF`qnP%G87^U+A!PNz3^M`U? z*E0rwe@}$s0PW3_*(KG((K~JivP!QfH(e30clM1%szl8a5%;1tO%1P|&hgKM7GIr> zZ!jjpvfq_PTw?Al6DBw7Fj7&uQ!4_7SF-a;fKBHd=2-{%Xx*-r)Gf2&a7ebkBE0;r zEOk`1Nq~w|-yOAvO2Mhlqk|3d5o}n`)J*EPu-GiK^cm)ZZfOD!?kdu_YTdaaMj_er@s=@Q)7@fk zH373439u08=qN+-`V=*d^nSSISd9{-=J5P+|7MP$rg1T9g2OJbMw)Y&P*r~D{MJt4 z9i;r+0HsTqZIXxhPuXF1il`g$E}$C`|m3NOPaq^^o2b!2kEYAMUS2t2Dp=1b0ug+l|0 zr2KX8jI~b0*C443Dkp(atiMdceOAESum4J!6)ROuo1ybHF4rMC?@6*J#?nnE2dcFY zz2&j>zCvN2r@v{%iSi9iAA68E*UQB^z56n9A1sJs+TG}6+f!gE3TKao--z)=rY2~I zqVYV0{)6cxz_9OOH`(LtBUYG919M69v-cW`MG9*4BdKSi(kJpR2!0^|TK5LE>ZMKq zNQw$x_vYLPQMnEHA0~YHG>Oa=(M-nm4-lYll4#{7JSz)f;nVRxkzafqMXt}E$)}wT z*s@d}E^73GPU%#RS-Zdr9rbeqJ9TJz112AzWYGX$mac@7kN8F91*h!a%OWh@#}xK_ z@Zq>Amkj8Tt{$*CRwkcS7|@>wQ{PQW?hLTEqf3?($I59ENrG+lA16H!L}V%x5m$Xq z>v}37Zoqdmd$DfrY+=e#M7#K@lIEA@X$2Y%Zaiq=CZw}N@*wPc7U~d}Nlw>Os3fR)1hC`~DUj=V#hKi$ zwd`I|r10Yl!M)b)&6TeBl&iH4C=KVyA(B>Irn(6TUQE1#h-v4}T5wFg&J;yjwZ9t0 zm7J{`eA4mw%LWp3=YEasMzKFzio|AE+O6isNc%fG%UL4Io4x;hm%mxKLz>7?ILP+p zTe+t;zmfbA4v;P2l3;eM(dN9|9<58CU7B37ti+&ok*?@S;+TE6zN!~{DE=5?_vE<* zu%81S=V8tst~8#-?E_d4)Kn}fJpE$~Tu^bTrl7d`dJ)Pe#wKe-1xJjlUL_u*p1H0VX|rUKIt!E^AAvs+-&)S)IDB^tYdW`|201`exeSM z=6k6%9xqbnt%&!xx7Avy>!Aj`JWMKsaI}RS4bSQJ&Og2|=^0di)=gwZMUx3dZruG@Vq8Pxt8hKAvT$$kbFVtcU4B9j~j~@;j z&Izb)Pt+*V=LS-a{818WnlAz5B%znTc{>g`j!KtOdCFfPqq4-3`aMH8L5o3N_W69Zedy(eICOVj01`;>s^cdei7`31$^KP|_V zqvW<6hb8;S$oeC=$c1GI8r%s8*9jK^X9Qg^n{;V|oEBy`IBHb9pEPyK2o)VlpHhs@ zo!!o=mecSWbS;m+5yC>FxrG^G5(?Z0#vMg|u^_4#S`ti5z(Dl-*Dkt{N;bgzet#=m z^$35EFq0pli0ULK(eZ+=HUO(R>>H_pTD4^LM_Xs?_uTWfRe=wZ_#1K<_r%Iq)uK&* z1f;_d?^V2O9WjnlIy4G>_Cl)Yic!Bq0`Vp2t`|COh{sueQ1(85@(lT#E%!{dmlih~ z-haJXLwt`8?Ynext8EEtxLp{l(pTr=JzxwL=)x&^(_%l;*76h~Ig!vLhkn>rYFqB#4N+<NRH2wiI@Wd~O>eRaIi&>b zP_lI&H=l~IGsh@B%a)=~po%t{@GCj2!`AoH<6tPq@iNhg9JEEvb~9Eh>j`O*+!|a< z?03JSHSKMWjFarXH%W#M25xfV11_1}1pDjL@ zn8+v@>#S46joU4EVE_BjBa@bD3;rhyfa%`_DBP-lwnrTNQJG)fd;J!>mY25M<9Mdq zDp{zwAn)|=g`UExyFCwsWRf4eFjpG0Hc;Vv&6j&ti7S}-p#3Y&A!7r0v37AP#jfLP z9G*#zkDZUFb0VtkoLdhw-efVCr5|j)_EPx5h5u}5x_dQ+y-!d)T-_i(mfq{FROHUk zOc+R}HFey!YnbdT^OKrr`W6^X7N9~Ww=nzJhyP17-w9AvmtGgilDrzT?I8c=TEf%v zne4n9vSKs4jv#d=N!v6ZWRxOQ?oYf=hBNH4rd!0g?*9tgZt)FLypD_5m(NI}2`jTC zSWoSILdt5#jmEIM_!sT3EjEwUT;#Z1{fJ-NIugVjbUG;L}3dYU5ixo`R~JEJi|wlwT(3G4inbdgpnZ39ajYa!Jwv&`O7$A4BoEt z>z3g9*9Yu|j!sj)=XbIKS3U8iy|2$CMrlYK#hQ5zF=B(^DxKJVRYGrVY72w2S5r-; z%h^Z?K|t20$4P5Z{DP(en?&Vioz7eT+Q*$`DvDe2@T|y3W0J&i$bPTs&*HyOEla6u zw?^60W?ZxFMEw>2Cr$o(sqiyFtn6K}T-&_nFDvztmMLC+;`34{?0^F%}?h~JMoDiICiP8`e(ae zA+>`KB*ncds%#z3vuC8jjOWXFcOAyX_E|CsXXVDmk)VCx{QqcrtDv^q?)$rVDb|+a z4lR`8?ogyqikISE+}+(vvEuIT?hxGFAvgholR&UwZ|>*){ZBHJlO&V*?%Dg=*IJ(? z&dztjI~9Ic-*1hwp$Nw$497h}Z3+s90=Yd*{44(Hh=!<> zgDe$_@j|O0Vy!0Hm4a*(=+8{av|vq!I9rz@6dh=x&NZ`}*bE0Q-}7{FSCUvfZ&6jj zwum1YTk*{s1O5}TRkJ>)+fvW#MGd9;>HGF%ehcr3>Unn+(YpvY_(#oJrDvI+D^;WZ zsXcC2*5RK7IMd#DjB=gxGm-OMR~sm8%lpC8DmULy8GrTft@dh;?YF2(B(ARQ*1`~O z1m$Wv<|53{d)*#0{lxowPFO>6JIZ^4(Y&%L;Wr%K(^+$JW;1 zudZ5FuZF&SnYIUI={Y#CH7IZrE;>f-04{?ZJ6+e5F^WJ>eeSy96Q=&6CCSouef$5 zT35d3f_Dc0y_4ohux_686LMP<^r4R!!q-q{+%9Ob z)!knt@PE7cZUWRx_Yq^*{~pb5UQ~HI`BN`pyoK6f`a(eTdWoV#;v$l(-TM+dgBo2@ z1|arSh`hLkq=%Ckna@nK&%ZO(>qhb8hl_48q{Q22h`|-<+z2+vlYllFKKZbcBJ;s~ zq6M+vZOB=*Lec-cR}umbpzE{uvkG=^aAGZGk2D0zQ-M|)^GNBTHu1UFlgsxqKG%YwjYu- zneU$#PJUkHs}TYoGJnA{d|fCV)9&&#@^W3YAAMUUo}#mV{mLG(v_r1Ft<~1~z1aDE zy}wHA6?d?O-buqv#(TH<$W8U+*PTaH_qU!;;M*ho2gpQmULGHG_?-JZ|H>vlLhJo1 z{)~8&kpaa>s_2`^gy#IPek=JOH>CpIu_e2wppdIDq;P2a*XZ7!a{!?mP(z}Fy4WtX z`)e{-V(+ti$j+XEn<;LLB?k278_Ji4zOP~mYuB0L7wx`vbwW=cL?{uA5e4Wy_K127UU#D)BDRk;- zfbT&>GQEjK`n*ciV5#QjHG8G`ebt)I*9?UTs!(GY#SO`MgW9w)(-8r)`5f(B#*K*S zML!*KT7-$}ep$^0@r(DTfAnFfFIeaTjMxSHK2Edoj?D*K#M5sdn81{3Y;9B0hoZ(B zKBUi6vK)qM#xme+-8fb|=Mbmhx2}13az?|V-QcyU*a_FOhGC+#7unGZ4QZ|2GV=yU z-6{B){`W~5V9zRocNJoUu}|g?+PglFR6Ms2}2)dTD^^O{JYs?ShW#LhQ zpLbkU4s-gKHTLIRJP>1o4oil{;%^;Sk_}<|e7@9E6dtC?N|%lJ#lm`yC|pr*ve8uo zkO;9IY~T6+Y$JX+{|UDYB-tngDPL#O7;^T-o%1PFXFc4M;bzN5X+(BzZ6UTc4yN?n zS&ap32HXl+d$~#SJ_|xt<8co0|QM{+6RFxqRQ0K6ArO`GLU&Q0aMGR zLSe+#)1f|CCLln#g2*S~?6oAkPeDInsA69E8qyO!+0^Z$lF{u{IFs z6XMRqml1}RL_U^^SRIzK?G*#*zoYz6y%21Fmrtkku&S8{qp%68c;e{{LLzcg-#V6B zVoSSO*&es6|0r17J$2H7DG10=`-yBzqx)dCpu)e*bmQnn8pVE9gX7UKNldpzoT0|K zb6t3<(yxL@@TwAS5In8Jmq(SJyFm!;!sd^fg80oeG*AlbSi@=(u3w~Q85p=2NSZRgP<73}ML)3G4q-<5Jrs&j3Gzl`JlV>B6!Q|^ zqjZ_Zw*46AE;@Ac#s)lcveKt1M(plX_xt7zzinf!T)>VWxr?|~TlXcXNkRNgP1LLy zbL8?A)xRR>fWQd`ZU1$G{yt)z22&NGV77okT~oNvK8y?p+uS zZud<$X`jBW$P*HozMXK|1car5TR6701gF~SqBUpw~>a274Zd2K03^BLrHuzV> z*ye{sb`?9%v*n?TmSXakP!!#GhPT`(lRSS3axLkMd$vTU`{-{&g>R)?gs4F9R0Su5 zT3U7W{}4%j3a|ItPL&4!_cq%ERj^JwA&sZ(=wl)NH{2?M*9gys|56J#&gaC~h{(}Q zFZ|3d^5qBFSj<`Zm7k)$;p9y`5jGu)=|6;ENN(gQ(FXojKuY$DuG{cavAQSt&qJ$u z7@FrOV78lT4KQwvbbA$j;(G~7y<^nf>WM$g5F|r=C_WpkEF>vm^)l5K6&@NLwY+zy zm5I68C_r~(H)&Z`*xT))=g%7+Zo;H~h_t?sc_O=*vkoSjFxjup@H+b}kgf~T16LvJ z^UV-R$&%xxg8Jsrr@8R{W^$33f!4Ou(Y7R6_Y1Rxd2)eBpn5DYq-5QCSpQa2hyL&# z@T;ij7#+C%m(QrPzJ9e(aTl^l{j(b~kNvRam6gnEqK+9^Q84pzuw1n)Ily8?zN9LP zwj#XpBk*J#nku!`HI)?nl27dSSC36dJ;x>VM@X#CU5)4p?3bu-H#}Bf!P=(Az<0H~ zZ$wMvlf?9V@yQ&+^&LY&q7rXDS$^oPJQA;N`|&_(YFyiq-bRFtn8GSV+tm0Z4BLCp z@fRHyi+|KgjEpbWq$)2wP{zEDBvz`vyA=c(?OWs&U z2q{Nga^-9r*b>#kvK1yieAj-ss1%ZL7#F!nea1N&afTx+H! z?A8tIi990@^5VS+t~QJ`c-)kZmZ!IYhri?#Ztq*KD}H5EqcCu;$vGs%9p798SAIcn z9Cn8LSQi{7zW(8q`asLjCnGkFO0Y(>?e{wnPj;`)lrR`H0gv_E(SZ+VS3Hy}uB4_dVF4 zmVCn9mm|sinnmdU#-|sn|EbwXp^}?{JzIeRqi7h_3E0entDGbW3RbA({7t^561lxh z_(hgq^AZ{r4dvD4Pa$GCr*S;^B@Gdom>hs2_l3>9k&jD-)3d1S3#IsUH6pIDq=AKY zQ9=n_Ga2mZi4V!{MJ1d@Piun)T#nZ`pk*EE!SXbsOThsw_sd8{#{-`S24`L$q0@}7 zs*cTYG{Sa*2F0mzq3~CB^h5ehMhNV57A*a-j))2gwG%Z&{uQF8?EX$m#baaQ0J3z| zd7qCzD!!%6GE@hnw;<$_U^NLj2H~}0-?Mg~q&!y^NFDd&n$EQ^JfN~ zMWb~bz^oV=Xdw*x=A7ToQr&0Zs4hKno;tL@d}CGt3A=CH;~>B>btLzKpNhPJ#9Rl$ z?8*d*1MaIF)eibf**J}?kItFf@GLzj)Guxau`Nw0`pmyF@C2O!iHMCPx6f$Q~-#A`l9hl8O>Te13x&MaczRRQtz*mZ5 zz8N2s!N7+^>AEcC6?>}cUG6r;8+}$r(uX5h@8CrsFG?+_R7`F-hrxsYE%0P@=CKJ= zeU(@x(9LwazIrTzF;neWKN?YW4qX+Cyo}pf z{qmjJ;^4lb8dRNnv>3=}3k!tLr><{gP$a;xPY6m!nX1&k`y~*>pLo~-A52^GW->Iamgx+2jG zIP?jnj{-fYf*scmjg=@0!M#|Kg)MeXk`9P~eM6XYX} zA+6ER#l3YYoi@xrl@m>)AvR9KbxkJiTLbQ~r1;eMc*63(fJ-JN3GeVfx$c9t>FKDr zNI)jv@qJVjQyx2#?0tOYbVPjng%p3eFx$HFZ^^H)wMQxJoM`YCQwYqa_y}e+V&yv+ z>NO0ar?U-O*7^@djuvM&;^)?t(UbZVId>#g*bgliwgw`>{0P;}@O6KjtcR#vA`mNo z7e5>rpRSs?%>7lm0&F#YGT42s6%94cd_^4p$=x6a-RiHFtCLiCw=<_65tHCtnMZuA zdcco^w}@t`!FOk4TrAj#^E`w@@=$P9d=zYRC$u%9q=9bz7$1q_MY3fkST>w-PJakT z6|J}bxn+|}@505}azpN3Er~4${e&x7z&sXRkYw!Ix*LEU>K#cSeSK5nNPxYC`CclU zL+=zCzhdZ$OBNANp^02&fRi}qS?>caecc^GGW#ZJp|mm**jI+7l;!MOkXz+;y!1oAOBn%<(FM> z{tdpfzusVij9iuh{xP<`45tmjcX;oTZth@#`s!NjG29*z{%|zetC4KhR`Px#Ms(}- z!pGaRkIGlc1Rp%|lICliVR78OY*8OUw3yR8=Lg5!xW)BU8G2pj=KG(7GuY#PuSHRS zEGw4%fs;>!?{6`Ez83`w-qPSUOsfKUd)#bu%}Q#%s-f`ss!bA+WE{(VRdFRV`M(C;{1>W89)ct8yfq_XT7RDy2HH%R7b-R#P00E>gB9satwm zjJx-;e0g7kE_yw4hqm_7tsb8)`M%bgJ)LPr+3kuwae=&Mqo2rF;ct>faKG8)dKe`E&ynE8L6zPnHVfknDe|6(9Oss_Y?=!Akuhf;y5ij?xjGil7@I18Fz zY~mT7E?%B5P|0raTNKsF6@K!6r6;5pKOCEGVs`lb^Y2g%QCi~s@W+LL7rz_69c7Ue z!{|ag7dahH>Dxs2cxTE|r~*xfyxpoKy-X7lsyM0eNO#sGE4ZWypBic{OMjtmXJL={ z41G|kSv`-BGr4bp9Ea-EO)`;Cy@{aaAa(4IDnI_Vz;t{wnsUV~hjw~rhb;%P@Gp(9j}=Ia%}##`Nw9ja z6@v`aKSoQ&^X|_B90v^C6!k5`R7BC2N2J7a=?=ibOXJr!0zO!b&wt>MRSj}QV9bEg&e zU9q_oQk?iG#k{g7u~0N~nRG*NF|RMJ@Ln6yQIePO%Q#H-thgi~FGT5vtZG|8 z&2=cnnxq_?<&bhrj$izw%hh9$s)29)ZQ_F;wseKK$NIvuhe81VuP(M?oL02fl~_r5 z`lB_)A>^Oi(&Y6Q9k^mnm;rJ2(1JpLE9u;TV;SN!GKX#ECLUe*iu#>X>LX0-#q)VjC6-J?%zhTw5b;}>_G+&RB* z#?B_+jce$HYEJm-DHkSub>SN0As~ zJzPt^I=}eV;em}x0PU$WR;IdN+y0D6t*wF*ejWAfc#b*UXMXwZYYt7Y>;%7(OO?p+ z&2m!};*jeRAajY@lEt9rmh(xq^`VCd;E{&k$`JGaV+kR0|HT#fVSd0vT$I1OLe3I) zk=Tjt5`$mL|B5@nB|2melwm)I1sX_mu)7G4{6 z0s9^kG;4tDHg(O{fwJ4G-K-RY(Yc3CbdD=VTqSz7w$jbJ+8Wa=m@8+|d1mtZn2U*b zcNEq+Y%%2%9%tA2_vI;)@ zElueSDV?~f;=HU#xY}Jy`Vz!@1FsAG>|>w^+1ocfT?|u%AF0k(XASpA;1W%4e2 z3-t9uX13>@5N)K!Rqv1Wh9x5HbAr1@%)}_ZEN5Ld=a2e9<^TcF<=9heeC$4~W{`Y{ z1u}jd%^3&wejk&})DnMp9Ze{cQsjx)QY)AkHJG0R85x1)mj&_Xi`GH4N{nPOID6AE zNrw*D@N<8+-01g%YMuO6jBIA2E4v!v<9mNneUQ86@K1Y7a;`j8GK6E6tLHUW+1pKE zn7N!W5-fAs?|`TAWg@))k0Uo>!f?d6h$Q-|MK4W?`akK~Fwvlqo9z1dp0;OC&GeFK zk3XL1Av6<_!EPoKEAlVj@k8Dyogt3)NNTmet@!p29(!YN23P2nQRsRT$xD>xe6kfR zkF|3uJ1sV_9_qF!9h9_Om2qsRs(g{6s2c3}>5a2Cmi=Sea{gj04TDRM#|6Wsa zUSdjZ6KMO|HvC?7?(aHZG4JVQP4Zs$JzJ~<@*&z|4yg9PKGM6YtVT*A^9+aZZjq6! z+neCzT!Tqj64w)PUeezh1Q*)7*f}&j8k5fqCzISpy~zq}?k2)WgQW@9;<(J35Am7_ zc{$*6um}pD454CBp688q#pZohl<&5E zQrc?Uy6mhSPBPR*DemVQs>1^y1pA1ns0$3!`UQ}#%`(`u>i-?+{_BLp{D_1BKDzDL zPFeQwMJeT*;k8++7sXeC;-{#&F4aORJ;N1B`bjEol%)uuoV>977j1QYk^BrbB+KCD zg!3+adcU+m8~g;Gqr#V?jq6Etd_JEum8<9fYEC49rQ2*?jey>i-UJ!{ETt1LBf>|Cd{T2E!(B4a-`Rn*PHdW*=1H$~lKh zd8R}=(@XpAi2DQ48xky+j1K?>F*BcR{j?Q$c&FKA#(1~jom!c=n&QlVZ|R;*T0QBj78 zNB{+D@z9WXQ?11xem779?}0OS|M7^ z^*;;m-!hle$SvHSRw6G0I;*XRla}?CR=OQVB^zwNQl!K%$t2&fD<(v7Wj+i!`);P0 z9B*GQpB9exLf7~`k4s6`F-YZJ@gEPlT5{N)4J^N?;`Eh8ac_5l{KQ`e761x zl~2q3nLk#qm7ixtkN0C@NS}<1`S$!F%B#+yxK@w2C1w6E{8F*57kt3I*_+YXd*{WY zeIjxlFw4aob>Z*^^eIw)>uq|RObQ-8%Y#h6rJk2hIH}tr-@wd=1HSEl2LEy!5q5B3 z6Q9!tt7}J7#E{ky^*$ifyMEb2vAq2%dU=F9v$-@b)fg4?@5_IQBC&o}C3&hA zCM!E<46J+HwV#|X*R0dqP3mxcS=pHzfOe4(}c#vv6B3zD9i0+D!~rPjhqT{dYS^>g-ddoFbw zSE4ocqa96za2$4gzGTtafG$2L`X9xRc3@o3->5x#;kjgHbj938DIBOkoYtM-S!q%(OnN*l$@g4T5a zW5AQl9i}RA`#_xcV+`oa@|eMsddyO&*h^FhqWs#3}sGxDPhDwsvuv z+-na!KX=joWcR2;64@R==dAsYcYVWUzIY^6*|&nt=~r`d3Dy<51<$@05bVB^KxN;# z!?n*AJFlI!JGeY^TG}>8r8u^6V!IaCo)&=K_I~lk?|c>KH4Y9i7z1xUrFb3r#-VTL za#5xxi%oBox@)J|Z7oXoBGLVo(2KD3c4gp;DJj2@)pLs4p;ji97^03yim|m5S}<34 zbt*ZIwT<)f-7ZLE9R6Vc#uAS7I+_-~n#i=DL*5l+-kIn9t7=`*0K! z+tY|B-JLF_X7s$ilcWN0{L9CePOUm6tb)K{EDTESwkxBCb&#}9Gmy>O&IqiV-rkdJ zza8?@&<5*u z3K>XibNBFBy!<{Q!Xw5ag3_%TZBL+ITO!pHnmPWmwFN!fC|vYiw6|kQHhfPFmG!#6K2G8*G^iJvUYm?QCgj~vx}Qqw3P z3}g}r#HgS+9)_vNL=PqkS3Qj2KL&M5yUz3a7ZlJ#-ua1jo1A_Bv)+p)HZ=_0^#hSj zlarKSeXX6j4-S9SJo{_YwqF{@tF%J1Q~TY5j2J@=c0dgyGVpOE{F+(YP(hE21*T^N zHLQyZ+y_(p&jjnk`JJIHP!*9x40cJ;{SlhZgeuk)7M166G6z)y#sw$UZAf@&ZB#bo z-POhwJfKYJ%~(wG`aui7#k!qr+d5%m zO`Kd#Y-PWs3+qI6^RF>hp3Yh{C}gMFvQ1F_uI)4zHWR8Uky%52AdUofTsww|-_1@n z1)>;{S2^HrCZU*>?Y;Nf!y$fN3ybxL=jpIK{UD+7%WDtoe9#>}v)~T=VUk@(Bu|}W zurOELoT2uT0+Re%jS9Jgy*epM(a+5KMp^!ca{bRi*QG-dgu)KElsF$2_2i0O-8R6Q z^_CYm_PjA^T-5n*I)Bf079P#s7)j`hC7~&I(0sNSQNfVgsIToE9|6y&1Aq0}{qP*&QMmN%T0Vp|;^T z;Gg}BHun$W*AGcGKKl}lBh{{;IJY`iqh5N`=N_gvGAW;PcEK-M*G)hOv2l zext*Vvxzh!yaW6*HyvSO^JtW+4y-&6EFIoOOrQyiyk{Jru$_;AIk9{1R!La{F(#{0 zgun|dewSr(S4mRcvLLu=oEF{hyojKf)487Fp)R;;Ii{)U^@AayqREM>U1N2^S+O6- zb$~s5#e;2Yk%S_;8ktMTcFuez>zknmC6M3}clmfC-^Gn1#JG z#S`CVO&Mx!PLa{*cs>7+J-GkO?IM2mg%l;KW2idjEOvi$ib=>c>I4RKJQ!9nhviW? zEG!uD360a53)9T&r(o^<(mB!Zs?@-)IVgE!XPppgONC7LEBsOjgLo^7V7$z+&AAK| zgTVnR#El*Lb23yK`ZVPa&CTk{&PtuCfGfHYie$q5K11uG(DFI_qiKvFl#;_-whgwW zLY7n`OiQ<58fmY+B#z^Dfo)!=9akU;Aozhlxe>3I$whHMa`=KO`v(y8f!p*wztZa?qgIq!q(8h=K-nmD=uA1p}!->Z`m5|8EHvv z8iAH$(*+dtR{tZ#*w(4O+lUaD0{^Ai$Rm zH_g4E1kWTeXTo$Md?+I$q31+A$~Y!f&}zHFZpQ6J9iSLg-r&qk{)Wqh*RO~21cz#u z@x?Ha$jT##ws(M$E{RCGRKP^?k+Z72Z0HD8&G`#71rQm8T{%Q9%x^e5WiY4+mA4|a8 z?GLg*$(X9!Ga8s#u=zRfykeTM_9-tGgVKjz+Ef2t4#+G8sa;g4vHV()VKVt1z{x`K z@AoxcH-t^TV=`$1!Y!|N+?_zwS>2ZLQ_`@Bz#%DT9Ac&hyKF+CdgRxyZ##O z>NlmU643-ORZr6&J*OQ@6Dk8{X-r@?sGdJyzgobx?~`#BY^H>0$o5kt1@D77@| z)y8TMe#7N{v_9l~o*RQFzluChhZUIEAg{09R6vz;xLjP-@&O&}e=_m5UyC-8SDw>AYWuW%;lZ^&vr&Z*o{bm>dXM}EikxhY3P+h1Dins5b*q2EP< zQ~jQO|5ta}|IK-R!Y5}F*Rgr%%sorHmrlRw!$w<=Hu6+Z)b%C(m)VUh{@{$|?)Zei zJWjumgFvh1%iy-8ciLg^Ug>Xte)j``g5?@Y)?)_T{0eR|CE3`wWT9TA46I3epFXwe z@aL4w-hsNy1G=?3w2pRHpyeaHLmoEZNIekI1A)L+%(d;i?w3yg)ym}y=P5{Qh1?!`@Bt3$f74l#4SQz}jSjDoUu?0qfA=6QtTA(}EcoqMOW{YiO~#FxOt{wTSI z&R;UsV?jy7E9Kea_Rw*ZU<3BMboYD7i|$>I2P;~cXuY4AT82Aj3!sePn1nLdzJFI^ zU-3Q_EniBq{q|(^AHzMHc@#&{HEB~NCU%G*_Xfb@B?{QQs)L8l-_Q2uXL^p66__@9 z6@9U#g?QLMlmnDJJ*cmr2V_Lupobu;G1VDZ;K2EU3I;8u#Bc3OX4qxqIYdgskhymD z!@8Wt_gIl4O!Vo|BY)WzG+TsQztQNlxc|smC&K&{T`aAwBdK!U(369Lu+N(9)0ryR?L6s~DGLplJ=GUPoy7 zZ1LD!{<9WK*h`lf41Jv2Qlka|q3dZy{Y|fv&B-lt*DRU7{SA+fZNd*s@NLRs@>1|c z;sOXR@3v(s?E1X-T{lnjmY&9-d(lQ^g*Uua5?8u34>#m?9#v@5)?nWF2&zpLBQWh{ zC3XG$VXZOevyp{;L`!c-lp}d(CA6oZKo`fk{+k!n+N*(jw2=KUbFA(i#{02b<)-oDX=U1 zgzI&)*rJxZPG)nYpj8yokk9O$i1~tzuPGRfOE$wVZLGtNVNy}YG;(&it9g`rqVy9e z^U4RdI52;M)y-i%)Ke8(u8PPz2y2k&!gRnsUDta?vhSQjpKVQ&EQ-c}Da%aaAK}vu zxKJmS%-7j-UO+H#T({gXOP-~~TKTh8xSoCk-7br{^kTH!sX1&-UHo3rmb`V+7-~@M zYR*a#yG+LrQRc)0x|U>7p>#DrQO!?xPye@v7*<6wmzj(;@5*X>ezzPDu~-PiB~D%mui4`viR?0Oc-S31ErpuA#ZIq=q_mJ? z>?;9AT2o7Yj}>-?N{#0S>l@j6`UySy8#4bRULc&%5`KtkKta-&SQfrK7Xbki>ha9q z-9*It|0c%-@WYhJ`Jz+=A*=Rx4~;cS;E}06Lqfo$5)I46VD45;N&BIreicw}9)+Oq z&o@ME&^@&bL96v;mEdB{tSZj&udv1U+!Y;Vc&?<9HrZ}rN~YtHKJEAwLLOLjRHri% ze1dNUtfVj)5rbi8^2K@KQGSuM_O#opaiq^(oWI;>-Q zl8}MzV3Fsn)O=yjtiO(2;>4~ZJPDzEcL9I3e^O7oj2PCM0trDHR2B7Fl}N@vV->wl z8uYlM$W`;(qau}+-|Pf#>qC3+*v5WHU~DGLgc9o#4pIa0-oPcMN<4Q$iAoeHr|)Hf zY$XMuHy^O5t%Pn+vUVH;)J2KA8xQDSGUdGQ_sU549hIKPpX<(vezZ+y@L}{ zU&AH)%rJGJp?`lKg#_Q@|4iHM1g~=pT!(Y{@=W@otbkG%cn{k39U}@vy9K@j6`|)% z0=H*GXD7pL_HN?TiK1VJ<~4}N`?IRyNR)#|7A0Em|MzXdA#5EpSGeF zdmZPQ0+%myCud?)x2|59C1m)OcaUHN^_*8eW^o=E$55*YbMQ-tt!oUkP)R4W!vw_m zye_fG0x)Gsg&p3Q{DLo4otBPz7@qpG8?Odi;(-vMr?0pk!EbWDB1WoblKJRR%&|nU zEdLX}*@TP-heQ&C;p`ND$?Y-$2kTz>X2^~&s{XA-5+xu}b5K2p25i{_;)s_OszKRW zH>CU^RMQ{mW_sHp4uk@ZhONhw>>M|$*53`^-)fjmD+0h*r7P@P<% z{f)@|mb>zoIY(b1;VugE<+1{4Ev2P$xlWx4r;*mbdfUy}(Cu3l^Yd@QjT8Y)Y<_&) z-JXy?dnpVXh|tDwWs*S1g7#A$g6sO>LN`IwYXzv~Dd>uD*(x=T9RH4X#;CdsLf4IU z>Bp1-C-ovrkofLR^4XtV|6$#j+GQ79FbntqbDw1+-m?32?Lub;s>*3fPmCshy%I6-le;B{h?_^ zrHS(Hy$EBmg{Q*h1btKr4X~)X$5uK;&*<3wy9 z=cfBf*eD|#hNjqK)>k*;>&ImiIgnp=%JN)A&zO%~l*7z#bv+8X6q&D^CFUU6{E92O z<1etYS5?i;z?#bj??A=GNNQaErIpCK#|a+x!1S+v-8-r^$l5>JLCOb(?>Z8K3Z%UU zoX4Xkc3u`_CBg(?JQ^Lmm36~Le8L6IgblEegOPZH~?@mt#f$v@G7_ek1n$s{Hhcr29l(MOrWa`HA1EIbW5MkTcqu zT0;n^A5kzw!b7QkV& zxeH;JB?G(@5Thh6!Z`1=Z@tCHU=K1IN_ecs*12p{vz2mA(^J$Txjt0;?!19gh7a)E>Md6Mv0EG9cxm3su&L0{Jzy1}<&zHWsgo$l7Ux#puu+~-+;W9&{(}6s=0_YJ zUH-QkaUsaTeEevcn_wL+iEqI$eJrj`^z2NnAH^JYPJBW3kCR^ALn;sdj6=c8C~_IU z^l7o=6i{1h>H-vu728jGhqiC^wpFIY^E?(dhVoq0!I!r6S7m}-Ux<7u8OHZpvonq1 zccw5Bz{AA53DZBSCf5Aq+*~Z>O8s{TR{)8HLz1*5$R0a?(t*U*CJasUKB?^Xt^&HF zO|qAu@Vt%l?*1I=@3OG)_9vl@tF*?pUJ?NrGmJQskeOWR@<+-3xV@>XKR0FXV%Zga z7X6Y6h=)GskRF2pU6PPZLJTynHLuwZc=UVCJv45$1Fk34_It8+@_%7i=?Ps;BJZK@dqEBYK+g%0+GlE@Y% z$7%A!`lm&*SbZ5;n22aPuC%@@y;7xck}r&)wKDt0O+=`_yaK{Jk$+KtgiXVs!KB?dsqp1LD2E%NL^=6&>U3G3i7Gq))<#A%$mE#W-rFm`I6{Oo}d0?P#Qa zk0Zv9P4SC3Ri>NUOxoZ+zgB*Y93VcdPHHL|0N-DavAh>o;I&0h_4+oSj~Jf@CF8?6 zQ=c?c53C#w^enr3!iKj$t|1O&8f5Jm7Qk`#x8!f=`%2cMa=st%X%(~W|JA$u*6qkY zbun{;fWM#=kS7A;sFp(lPJ5?6g`cE%gekh9*9apSAXCb?xkTd!>P*#}*wv1$$eIyF zIBIUq;d!$r!GXi!ADor&Fq)TeGlbb^z-L43)#?6GwpT*8`wI87Setz*TNDYsBg@Ot zC?`odJbVfrKYSgn;$lI&e(hK_+tPTjJAGuY9iyY8jmQf#8}})4y~Eo~9$+`r2iggX zxrk%%ky;zY5{oEEP~b=iO_@oZ2}xX3Z@itgp4-XhtwmJxoAm|D%V@;tyD?_T1apak z%U+k^)?j&5$0Y4*^18=}UUw8?9+=!9%S`r{Vbn;9W((AsFOWO-FFSTU{=&NjZ$D;_ zhPA};L58>OTm+sZaN7u_?vu8+Zv0&YuL(2tKLrumr!vt zu3{`|A{5c2)VLbQV7fq&yuqeLNPGSFhIJUpe`kAkGxnOH%2g$+ozlpz9E1{aHT~Z$ z-5nCQgWJO6t1%%W5$o+=DD>YG$|EZAb0a1~mZ=R)5?yDvk0?=Uktq3Nq;tG?QV#&N zSs@C$xH(O)pVn^{OGdG57>sYnFvmSsnB&*o-)B!e3d~vSTaI!$cE>a1)&O_n7({D^ zas$X%hE(wSVN#F12q*cOH4)&kaZ2ZYU6{qRgd8W3?rh`jiiep;fq}>U9seQ=-=?GjDy*fu*m8ew0MvJk2AOdk(ivMJ zji9;@Mq)_QWx9TC26)-F>0|IhF42V7_e#^?EAW2e5)6Im8u7eGj=os7yhaFCv6tmj zlkU|AWL@98w9S1lt#?|8^yd&W8v zyCamsC}&X7^Mz_NL6NW8b>W}Px+hbNZZ}cTSkMKV@XUyl$2O+KTaEsiiJY>g-Syhm z#h3PigVqEIGBOc6)4v^e>;p19?a;!;M^c`xKfCM6dHOXhScXkMe_>D(lW(q@x~tey68pQ3_>(BIeBr^1j>YK}*df1YcKlO%HU z(n7`hCBv7VYdj+?cQW5*yD4}MWSu=J+%{;+*yc-eH>G3NJKQwp`3JYLSr@fLm>OCp zab!@t2ROdlQ_3w>D3yh8OVy~<9hY0$;$6mwKQHJUy7_2=&eC-X)!Z}jMb)M)t0+A5 z;5%n(BTI6Q{T-0Xjj_v!?-jtCLz^$&}XhXyMmwI; z{kR`7W!PiT(p0b&P$L8Ll>dJ$fJ^oMXcuFP5POZC*Qz4i6tPdy{vK~sR}14}t4YM0 z*S)E-RTe^jp5Q6$*A$3^T$Z$>1fxHWf$(we47uWW{IiS!2P}sMfAINJsoq8 zG#IQ5-BgNyjp1mvOOU9ep$zW&ZR?tQS5=Gx{M8UZHe4b&j8d>3WQ*sLZee5;_-a|D zx%ZQS9$wdo0!E;M+G!-uevHvkIb#Dhc~>=?%#m}7SE2P|U+!~4(@3;uMwlb&!OHioZ#aCJYP6zmhD|^Z9h1<*02eoo6hGWz4j+> z8~w-E_z7feiiggSE2SYH=3xbI_fe!^tvOEA-Et}8OA zr?1-)?0AGUc^IAlQWm3^yR7P$?5e}wZ$DBo&f2{ zH-D=%FNvom>D4E^Uu@$r_$7Z&XVy-sbE6P#bwOP>^mC# zp0?$i{he>Wh&J{=b=O`QGnsELbidJQ?aQqBuVNh#FBClPOVa|km4QN5x#&ZVyIe;+ zU)C|pYrV5&H#+vyn#^gjZ5YN$W6w$a$5M&)b`spk0MV-W_otuRHl-N8-FHD&^zuLNaqHp?-5 z;sjDmJrp))6|i(g1|I)W#%|)M-PZmbhOT*SJ3H54!5`NNA24hRxW1* z&JdQ%bz^zUBR1KsZz`B0xjBRnra2YC%l{u&@BI&F*M5HoVWKCI=v|^j?}I@^84@KT zAv)2C-g_A(f)PPp@4fdrdL0IXG1@cN{ds+VdH#oUpU1J+TJN=Wa+KgUtYDw) zl&xF@Wo_-S4U2xa>MY%TL2L@G@WFFG(9EmS``&TYjAY&-IjC8VZuhdC9Os(+AR^rx znj4-HsGn4rQmNNR>^ntPpMBh+qy->GmP!iEB5hk06MT>#n*I(%`T;uLGmjOgVz+z* z$dJ3jj1>L4K5`BJVQ*3mpsQ>qO5zY6H&q}=o6z`lr%6I@d*9%bz9dsADL0!HcVzhp zZ%L}UTX8Ye{RaxiZt-5E^_3NQc#=Iem)?xJs*J%#Hnq^6hoJ|No|^gZux^;@kw)MsZ+Lj`HWIFZhsAQx_tW$B%1!4JgpC?hU>M z{?+ymq8$wsgf`z?c*iuP%&2Twn^gZ;b}{vfaySL^d1Z`1UxwjJD53(n_H^^AJF-LO zRHwJGikr`1q5y>qkw&Li^Mz6o|F{a!)1=W`we5)N82$rJNfNsBIghhygesJJx5>jd z2Q*Ap)ZbTe0fP(>wjMMH#2D(BIrFM9#v(%x5^jUM)tssNdBOffata~y=ptx@Y#KY* zop>g#I&Y4TVrHVJPj*-r@pYe6YeX~OFUa;bs#ggM?~2$WfMQaP4Izog{;gJ$2eWgl^ ztw4YJFM+daenMR*@l=hq@AbuXHS^`m^M~B!GlZxK4@Bw#n^FXCV{}(Ih`a!$5$YUB zOP=4^?+|b|TbJJEaeuvQky^!9r8`{z&Vp>5mf0rriNyI|&Brf-8?+%}qXDDI z>^=v&x&|(q`cEC*d%rhV+qKWCV`HL3U*jva$64-ZILXh;*Kn+5@hYoJqTK+aXHePhXynX6j+7_UKDD~tX z;talN*zEmj&8bL|ZsS^?J{Q;^Pv1&9(Dh?W>$uh+9{9c*p0laE#&oB$X*zVI_ux6q5pNJ->21t^G8Ii8{7CIiV&j{g*O0+bSnIS!g(SiQ}rbRCqCQ zR=T5DyQg*L7?E+El+l1%$hcdenk!pBN_F{9F%q?8^qobz{@*E%#j{3g2lLZXTCl#Z zh@BP);)x;;4aGEBHHC)RMA0I3O0Uz1w&|wg_{9h!-7pLBH)3Wp6=)xwaK@6`^!z$= zEzxpc_{&um`m1d+gEsE>lKVLj)!rG|3@2@mpG{1IPZp4TsIw+$a`YDd!jzi7TPkRe zzdWnPb7LE3((B||{tH96_W8SFq}{gWgVO?8A!w%OByG?w`p{m_hwZE-wTsZu8$RRt zup|M4LCZzge?bkOfmZ72J^%6SkG*@l)vS}jZ+P-|s;ZH^$dHhtu@0ABO$~IqKAkTw z1zwxf--qF>9N2OH%+dncdP#Q~pdfJSmos#wDf#GxAX17IzXzhsK zgMm`3E7@&fSO%^N6rDUvB-MT}wWXp_z1)~3dsGS=T!>V^0%5xeku+NywCJL0T>Rlx z_c2MH+ZUUF2%Lt?n8;cA+8ddS#Dg2P{>@`2%3RS`^^4f{6cVwD@u%(xeQm{s=dkA- z1V<;Gagy5d_0(ljr<*&*2ItAlp#So!ChunW+qrEx?l@u781}AH8M#Ki#&pO6D8k-% z|JoTtBra>q;XaC*Ij#{A%6?dBElxG_xL~h2mGTWJxW^cHB{g$U=x-^s z)*xPjqe9#Sq!57@jiI&WTmF6zAosM@-a7fMO45nkMlJ)PD?TFbugEK}#Yfd)Rv1%N z?KclfG~^iWVP*juie9mmukB`vMIIMeHQA+C7V*rYDz|b8=gFa8SfLlg6||MTjhAWB zxx_yhhQHRK^g!$@H&)V5Fqe4Pu%!6pY$?t8GPQedrlXGe^H1h(RNHtdX(r?+MPu)$ z^4Hl_%)%1*SWn={bw~4Ezd@3-FT2MUsvj6GV40)J7u~abt4TIuyYPbb#JY${D6J}8 z<7QAMWbmL4-7ffJK;_+G_m}&ib9Y={>p@!dN3%C}*YP!4o@wq8hl$`nQ;+Pk&y38$ zDvPaaNJf3iurIBC7iU8czNe>0ukPmiq{K}ErPP-l;`0RF7oK-ujfH+#eN14fm|n^3 z192Y8C{x`KF7IMXy)L;M^WX=*XWPfAXObEZE`7nK?Y*!VdAeMW`BX@R+Hpv1!+Guv zf!2sw^ufufMUDS{K40l~)4O@-xIZe)zaG`+f7=(q>$6Ts2LJtkLGSwi4c@ELBEc=S z0zBpSkpc>_Y;Q#uh}Z;S3@NjQQ#06g|6y{ zCe*1b(cI~{kC}3FDsJjqBD}!jbhM6~6MeXF`5r(ebj0VII1uep1WhLO-^!*?Gn=@Z zH#wXtN;u}gUe+@3g>NjyoNiMX)_X`olP%Ic zcY?AH?ZmruAt5zSq)k43yjQ&qvIyY+ZZ}z`CBp^V(@FCKMqCa?D_jI=nk_A9FP;EI zSWx%VF>F)u|H@}%hsI~TT>Ht432B5qulUpsCrc%J>fR=?O+`+O>~*tI6FK7@q;fo) zo?CB=bv$5H>#fA?SK4=jOT^ zabGwzU`OS_9g0i%T4jfIeo#|Pk8r8WMN&+(bzWU?)Ji-&@?V@U*SgRrl9C#r#5cXR zwhR%mvPX`O6rfXXt`Z^fK?&OJ>*_-3w(z3L_4B=gBr({dqL%$ba-g%w2lVwzFmZ99 zwyWorlnYr|EIr5t0=SbIiC_C8QJZu*lY-VAN;QCZ?c+v`R}K}rbarfUI2*c*h%IPI zPRxR#j%DHy6>)L;yfhP1uYHI#;*&%E?a z1nWf&Al_u#iT6>TAA2*Ne|Osgxky_mpdv>n34ZR>9;Tt?mrMy?&fXo>Pchay6asGX zkMKaz5EDqtQf?!Q?vl*mUzE61v21*s-{~h>;SBT^8*BO^HG=)*O*Q>`t1dh5U_!zq z>xMdM^{}VJ4K~YFB%wRYuiM(Ng9KSJ$?6ZzU@|K6X3Q(d$3hhMSqQHuQ^`7jeOkWcoDvui+uC-x(b ziH^{E@;Id~tLjx>CF>5)&pY#K*DTG_SYtMERPM{Lo5^wGk+5?iA%zo;)k9ig;eheb zDwm%h?jdfLTkl7ETNeY@{`62JZ&m+rvin(`U9of3onu1Y67za)Mg4p|S`U;&_xzA? zd7CIvi~rli3vv=C!Wr)Zz-#883s%hP)o9S_yP6E8? zI#h!rTnn4#qw*64Hb=8Sb(M*&t-KV8j&9_zA#aKGRfOn zT06%Cw61PA_?k2*(>k~#x`=EeAI)S)D{#K0HIClaTD4}Gq)MFO)iHMXwnTCZn}#gD zwIMH7Vu`phsUIe+zBP54e0kEI$93P^5JRW1SdH3>RV(4u&oLO$%W1G$#{{I-jhVX} z5@z!c!E}S^Y(pJN)IJ1Vh7R=!0s`{U#0cTM7%qNnkGOCy{Txr7WB0>$`)4FpVBlHy zl}Bn4Ek)uS^TB=r7^*v6Ir%x%RT9T+Dm%;X}_IXgzwYr`O zA%HVq6PaJu=V_*urWGRJw)?Vz`1Gh1KT_*wu!;B7xx6b=oohLaym&2EYOct($Zef!(S)54ANE_xC;W$1p)w{?x@uGA|{T$Kd`4Ul|t#FsyI$nokH{ck5$tZCx zyIrK8QZ=R3MYuZ`c{N4z>4ZbD@{wx$%P*x(u5_)WE&x9N#o40W8GB77vtWI9=LG3V z`7^d4r<=>Ah0~PFw+sehe#OqvM-~ElXhr2c2`-8H3>kWq64hFs3b%y)(BN9Q;8mR7$55~eM4m=dbI2w9o z3C;)FI8{d9j9fRqxzJ@?@)uA}W+?$uL!Ndme$lQVo8QOQNmBiqyJ-OW^M$^(bM^X>p=)5r@E2pRpv%TexP4p16Y zONxU)PQ9m-gap#l)u+xs!l-=?SW*42;@IGSGcUky6$}>epeD=>_EIZ&a$nk z9sc&ci75?LO0OQ4_sgFj;?D`XqggYu&Bf{xbrUi#yyBvYQI<;`fb>!bck~F&Fty?a zXq)q2{}`irfVIR1m)kckHOV|4T#w$<7*1NUxTP#S&~rI9*zyqBIL+M-THzosVs7kq zI(C8SQscalv>qd`ZjqAGs9psL5lWp3wb!YBQX179(|F+MYGC@MNF>(J?if6WC~+}6{9eA>*aHbHN?Tx z&2|BYGmYO_0T>4NV`CTFZ~p*UumWG+2?CM#t&6 zzRaFTJMv8|tu$x^8vhy9Pvc`0<508o(F+oWm3ry6zW0zN7AOVXZ1B>eU{S!;QT(5Z2KWhGxjE_m9zY3|a`;5iTDOr@E75 ztb$)sd7atPXQPKTld|V7T-v^@chct_pwG!-SX|8Yn%^ge$82z>QKp0~&-6V4wlbl6 zN6fWp{P&V!uv9TREG8e?n+kCr`?rgs@b=rcJHi(>6svC%N_?WSd|33Z1#v3JXDwF5Fv_s;*j?O9_?js|t%-N+0f;^{{Mcf+)C z(&@#*Ux&RVdo~8JzaCLgDSsMlN)AwV8v1CcP})qbck`IOJB_ICQN**nVqov7$g?a` zyD+m`+%-z&IWDM}wa>+Vl&GCP=x!mOSL*KHc7ZWjr19|he2{!6B~2#$AF)YHVE4$M|i6w)KC;sI_B4jr3D};lZ&?JX@{GsfBGsN zD5m%K$yNqK>(=dI*oil_f`*S+Fb#@OuO|`F*w*tOMi4m^*@dWDa7Qe~$y?)=Pjl9y=-5#jj2mD>op?R|fkM9j*&Iv26YkkjQgvH|7*Wsvmu?V}=pR;XQ6#`-k` zEq5mOI2!(Sa@8U#B4zWkJ!;8ruz5Lq;=K)?svi6orN#i(c^?mu~j=iv+=Tm z<;_l|@Y($Hp!;@^z6UA)H*MobxzlOoy=(nxx_2BsIjZ{Ak^x@~AI^9m1Wq&V_cM6z zuQBWLhP(fjd!KgIsP3R_fviNxHtqlTV6Xoa+quK-R5V#0R%}EM`smF(D-+&Rmb|4< zs*jOugzRndOKS3j^gwa3n-%%Dr?bywYC`C6qMkkVa3t>;*nNs(?6MgNhERMz73kmL z(DOJpHOwB)x*RgRKU3aQle%zWJy(k+qNQeat?*dyHlzqm4@SY242b1OlKXZ!{^Ywx z58H(fdcMaz`r*FLJCdV!5485d50LGY38xkI^?DCR6-go7r=Nk0^!i+Wj1o)<>`i;b zu+=9RB>w5h7t-=FqP*Goxk8ljaJ$Q!?t8f~!&CW{d`}XV5)+gFwEsOTUMls7|5DPk zk}p-ODCnk!5?0pT@3mbsSM_8db{s_P`^wAXmAKLOgt3hzT-iZ?U+;_kaLU4r>)}|; zWT-WOWCEJPtEWN-HPd3%7J;cj5fx_M%~h)J0S_96fwF>(hqpMc6x~|nfl4-CU14^9 zDgvqT{!d?e{H@&ka39|@W;RiBn-#W8ol7KrR|-uIV?IZ|EOtN-$9FUxeA2#90mQyc zqWp7!({S;^fA}WzTGarIG8i41n48(%GeedSvJ+}iM4Z)7xxjP*(UV_bMmc<5Pfwnf zZq{AMo2$i&T^${xyV<0ut~I^6->bHXT7;!(kx9lI0-kaTy0)GI;h+#M(^+Ov8E@Xm z9%Kbe(NNNv&<|5eE53~U+F05{s-QiW(rGsjFf!n;$LI5!eQ4g9qx0D;@SNAmm^}F> zWOk^h$#4*%SLJ}Q>0Fqy?(`l1Z2O@b-3(ea{M>4CxRxz}viN#Sn7~n9qgB&yH;qJA z-)oEZ!i>L^?=0~Nx%_2M;L|j0GoqwWYKbTG{R^)chV8&I4`~Ia7;u2M6{~Sa?GPqp z(~ARyM3=Bpv56zUGAWezd}SF59*37B29&+vZY5%+gbt!BA+@y}rS zYe3<{!zjpR)sxGSR@hUe*4N%4q}HqPQym13md47slmX;pwPLKW4-6mfi?*}E`Wp_J zlIZLSwImt$huo)D-x0QakmTCSiL{Gp}I4@{PVLvJP%B|d`cf#;!e$W>L9MFEU`NH z#@I-%hy+^i$f9MF0X^xr0n_g?Z#3Ow1))&4ZFBYq3BB2$T>vUkRvy6nX(f%J+Af1?vV za75T5-|zmvef?L1LfwB_l3%5e(V6WlPc{?0U-ZUHmAK_|fs}`5Do~=(Y{4$TCRE;HP@pDMLXkG}`BYIrt+UrKMl4aHn10-;1;%#(x=d5(QJ#*8t;i~L2~A3dA|uL0HkFI;XJb> zH5}WJ_hBadGuF+I+RKhssTKF-bGkm_#QF5yJNttGAu1(5sI)`Wkbpq)ETF5&3AIWm z%pn?4+s@Ts@`R-JR%wwx&fWnh;zTZXsDBDm*ObkgXvbN_6fE{Fip6QsEK=i66}cFz z|J7~!E8?$k!~l-8>6f;xNzHebE9Pm8D$1E4i+e}Tc#QRPUB=S-F3PmT2wkmJSs zIDOqsIaTizk^22_ixz&~Q3NF2bk9pj58S)VC%IrqcfP?VGudni*GP6<$xUquoVkzp z@4|oG^ENgpoGl?AMNaPPKU94cU8SS}TGI~{kqAo3^%XW&57ESMF$Ze{zoS{h8Yli1 zN@$^bHxb`s>f+@Mmtx1LUKz$k=h;lDn#s}F_iQ(IZC#zxAI1N=eT2cEN2$Z?s2Sjl zu+M39PdiQqZn<)Bq$Qpyu)(tl4`afNf0~QZTP|eP%9PCPH(b3&V=*j~VeJ}JD2=%q zz{AsT_BST{?tu`qnlwbth+L-V1)=4BamTyQch1wpsKiSYDl*yzOiY5jSr?l-lc)}B z`li!7N=J3Za&%&w^RX17w!?b36{X!g$t?G~bc04;4vYkm{Cv9ym`ca%m<^p2oiNyx z#XRM-8c7;fq3c?l2lyb`w>$?ZHp}9ZHRQJ^==l)re*%2gV+QBy8V3 z@U>QbK?|2BZQ|hcAyr(0Ea*cOdzH`hVnMDOI)I2~llJ_$yvcO_30Koc%^iv-oCy&j z!)8{|yk=~B(pw+Y9^%r3=m#sV{dV2`EK-Ht6wqXU+k@J6A@-g7flXZ|sGl(dnQ zbD`8stl8Pwy*YTZkFBuQ@TYRFG2XRuZDgWqvPZ>7OTIugzvo-w$5bzfRVk zq!m^Zm1DA9xB@r{J-P6<`R98*pW-Buy-SAN$VGT7^a#+-u6KH1mMWhku$4(?YWv2< ze;;Bue!;`?S*jinW#{OZ8^tFgW=+}Tg2_GYIZv(ZiS`PvXlnHc20NK_+}EV4Z+;wM z%kUAGuoeMFiO-091FIa|W)IowDcuXzP~agSgKR&6qTEkp|?a#c(4f1^r$ z+Tnv`b{g}XhCz3I9iV0zPUgg04ebSv-Mzf;1P^`vy60cjUjC7g9^kPk$`{eq4zMpU7697o!f zdbPJa%;ZBx{y>ZhaHcDc(5THJkJKA&{~eZ?+Ve^d-!egTTXRvbK*SS32@QJnJ3)Ed zevrr_!ooFQfA|}~=TZAl?!!f)+t@1C=1C29;P|sbz|~-5SvnpJ#kM^iwIWCRB_Eoc z8OGoRRnm!p>=eC+UwwRH(NDY8im1C35 zh_t}~k^NQ_kCHc+WgkNQ)YIb0Ov=%_aU~dmO!^Ocm+!}AnC%_kUR{V4GJpYJmlBNQ z8CxsiEb@%d*^^k$&Qxo)HBUfnpxO3_@CcYCYeK7?S!LR=Wqe=`u0MdcVCXte`o~Fq zOMiORA*CXJ^j$QxCitbMJx!L1PqVEK9JxZLCupo}c5*vxzSDDal@##0_Q~woXu!|6 zGb^o~-F6yOX)aYhTRw9iN}~En6K+h!@ij*7K2$!_=kb zG{7p8dR-;wcv4eyOuxWsQ3;O+-@gtv&I0mSbgc+C+Q5tFm`iU0p+O z`KJT$%~;ozrA(@AuZSqf=(DpzWur*RQk420*BfwXE0pz!cFAll^EuLECZh-nr2dr4 zh*E^;bqqht9|K~JTO|Nzf0^-@Y%sk+a#-6&%Dd|+fk}#dlnbqs$2wm-MI%7$WZbSEJ;OF^RAHoV2 z`uau(JvIN?jlUP6B&|cT7m>A2*glAW7=uLdsP_J{>|Q&L-Jk*!yvq5H;+6!1@oW5B zS)^eg-N#+v2WBut#5m%bMQrbs#ZftYkkp=NrJv`sh){PY@`E;m*j4^2f2}@b+syG4koZ8G{P+EwvS~6# zGky7>^V>|&ie%V&{<-OjeTD65E9kUUTH>Kvy2)xQWPRP!5|@eUF|dZ$R)cmvr%1vi zpyIDgvX9oYHqzb(6b$0HC`H+)Y$>v5v-m81(Qaz%TaPePgA95gJ~-s6LP zjp0SsUEUq8o8gbBVXbT6!OQ40LJ4{!UFlF#uDdVpGgs|-C4}+*cAeK*wdluBu4pB< zv!K+Qd~7SggN<%KA=_vt4GE5%H1;Z&fB~v(zPb=`&3-;t&wiR;h^WRkV!v36%H+hN zth)8sj9TX5B0Vhe-vK6w5K*nv@ZM-B)8WhVR|Erbya5)5w^}=jql;r^qI6*HC!Rfr zbN7Rq2RJy}nYJ@E6AhNMjc#7z5yuy)##dgcP1vcA+jJhR1ot6VYbS3vwo`M*OqOQA zBTGeXWp0wr3ND+@2V^t$!MgC^xcKU}cP$w1?WqE31x4h8+lx`V_d;auQlDyVbqr}& zc8%;Xil44oacq^|Fi3#TorU%>jx*gVvFX7xTFNv50eHziJE3{4w{*Vmm)7M?B`ef0 zuTg#r2_jjv##_Q+SC+hDVLHFDdTI1H&T-l@f&*vm@!1})5@m9rC~KsK@P)udz08Sf zddc3n^bEicmOxJ*p_TUBe}2UXiQ)Jjc*CAN_`1yio!{Sx|FeV+xOYt9vw9Gj^JikA}qr`Ct39)+j3uPAg4m@dK^p zdL!|laY2&T^&rcSIiSWVHnOLU41T}!m4_Ps_%|0T@#A61ih1^U{)|>X-{vh7w5Akg zMV@^GlQpB5cx8t)EhCu1M7>l7d7?bukO>B5_Zt6EqV|j9JlXERytUN+qm!dpA3MF= zVH7!&-x`FaS+LCFeB6isY?FvAS1jOq>Spk(K_S>-JD(2>z|}$WIvHrw3jV~n(n;aD z8npRN1OA(T$`rPXjMhetr^5GOCRB|Jl~SRlye=T1?%05Yg0p2bi_uh?Q;?U~tUsMF z!^l)YeukG9IUms*zSim7mI=2dSOu5QagWBGCaKYQ>8gId|10hq$$D^^_EU#xE|50k zz}h0DQ9E#A5T&g6@UNA5TGdd;s-wmMYzSd-P0gZxZ9kgCS@wXS72XS8n(V9myU)`) zbt2L-@$U62PD->?XbojdYfS^O*3fhNeP~4!d2uXxeNPuPA@CEICj2rjp%RJvj1u;F53@sii@S7@nAldT>nnRpeY;ooz26uwO3 zq#O4#^-0xu1WTWByKPuV)2RC9428O<$#Xy@ZWDhYmi>m=JTfMDhKyM@XAWEl5cpz_ z40%;jzJDOVG(do7L<@C^dD1NK*&IIITzNbt{c)A{Wl8pdhPHz!E~Wx0+mbD(zhj6> z)GVx|Ur6}S-X#F+k$r{NIMFs<0zpFlz4cL9TSU-ab3|*fqPAk(U0(R0&m2k_)V!P^ zv6}5sw;Y0^lb=4O8ZG}==9|?v^-J;xxH^y*dY{{jnX8{fdwhI~3gOKaz>`l->)k{C zor`Z$%!gf?GzGH}o^A)U4lkKWzSRwe>dC^N8=BFairm6)CXw)s*r-8R(7XG_`V>B) zN3Yey&YyxuhIrdtPLFn_+)pEA;SfdQBM+RqCD`aFJci*T@oOxH?`E&KJ?;9__cLDY*?+op7m52S-Db+` z09GkPBhHeT#3d{^a;J$CGuyrs=U)f*)!Oghd`(MPw@^*-Qtl_HNU${LxyVst$$l^VNle9x{E}! z{l&z$FObuj&hyn(3)?$7eo7H*CcqZy38m9FxGtuP_w!MgCH9j3rwP|wS8I27YifqG z8UCB1ew!Pj{^z2*Lz&=DyKDcytaTrTQ?i=Ch8TDJGD3MjKix@jBk_O_Jcm!t?{#J| zU*X4jZ&L}-(nYeXUG3ugrwS20A#^IE<1vr=y6KW4gHMKaBwP&-EdL}MA=!2rNF{}>WHe_edkY{qR zh$p@Gt*motBQc%!7n6zW_7&x2O5^UuD+|@&wp#`WePn>tE&2Hr>2K1}4Iafm z!U?w=l&FKMZ2%Z{LQ14Dll7SXWM|C_^Y-EWrPN8mMC%;;(^*7Fj4UIz7+2+EpV$s= zSuYzAjpHY}lFFI4>aAX}cq4JrPiYfxPq!HenMdE55GAYGNo-QyOH9D1?oS0lrCxy# zlzU%4OCS7m^$k9~nI}mJi=J~rT+sZ(F^RirW&M)4;lAcJes8wUYHd=g0uXI3IN5u9 z#3@96klr3NV;@QCwlah9<>6=ZZb)3h*y{3aqW+6owl2zMj>q|h^(vxBeJ`Ud3)|_e zD&vF)aeC~c79nLjuZbZRrNqn{vsq%QwekDy|mH0GvG zM&-{fC%?%~H@?yTtEf^?^>IV12;qv`BunR^U+ingojN1^Pb(xp=x2t3ZogIXOdj;h zZBpCEj*b+Q*2VlaAM_Mehu*_cFwy4kk!5}t(!BQ)cMl67J`WLSa?=@&cwYrUDIQ3r zZQ!LEc5!N_mX2o5< zxHgYC_xwlEp8Gcf>;8cR!fTgn_Q%0#`0{mMR%adx>-t;}Ox!1rMB z!}x9igDLmVZo*qHdiL!bsIz-HLU|NYEJ~%I>Pl>AZ)!F*T_pR)v3EA0(^qt`21|jZvdwrrIZ9#p?_51m-HNg8ytIya};m zGo4~H2u-ZWHIoLE56-v}xwqsA*-2u?wyhHOlw#yhDIYDYx9`o5n{_<2=CPEKx1c)fLhUmC=>A&A&3JbTod_eRBI5*T zQ}1n1=Gn;tR>Yb12vn_*uZc=A0-CG~WH%nT!4(IECZA!`b6+h6$$v4l*RhyrreC%R zBh)qzWr&tpQdevkz z{n#Uik-yRKtiLBPJ*l*mx_5atO+Zx->gRyXKPM z*#Xin$U2kA#{a zaO>veygj(sTKko<>5fQZ8K*m8+}shq7nO5x#^!akYZ5gQ0%_vHD3KlN^qntbXAJ{} zi+zooivI_&|}eCK9?asq4p>Yy{#9)#8Qk?zq6^QZ66u zWg>5GMvNV|NTN9iHKo{2=UV?~D^W3J9zpDL-%MkgJrzYDndH1c&1*qon$Z4t%$Lh|)1(5h zlWBC!Cg~A|eOvzv3UJp=KHOsUO)VSjx1rs;rP{$;+6s($rR?c1l9(IT1G&x44&^pB zKy^~II-J_HUD{ZHiE;lE@J?j@>*DeLI7@}>lf{Yr!6Tw3R{IzJjVuzsS2DZ3#d5=} z{IWWLt<=RdsZYTjU2Al&gLeejaiwVb{*z(EWY09RZi-K>Qa~w1k0G6H zGC?(TqpNLRzE<8gjaVN+Q6@+V3jYUrZ0iA%H0e+Arc$Zp5_QQc`L5z$HmChq4r%|O zCRKC0#>*?q?ZVX!WaLsr1R2Ph6=7*nSp+gL?uS?}UC;4Y` zfmGXV4e_L-LiGe%y-wG=EOdK@L*bgz2g7l;YU47ympf3n@uqPqx77(ER>_+TiRB?@ z7)r$=weS0;Aw7}T4=E9vQT1Wf9y|iHLLj9OG)&-HiMxpli__;JPHt4Xd-6FZzNYEl z^T!Mwr%fmB2aqdiYZA{qqdof?*?C`0gd&8>^tQYP?Ohe@d>q*i0S6yw$S=sQT53lu z0gG4s)_uJJoi-`QVy~kmtdEsIwmi3EZ+&!(HnjvOO# zzdP2u9c9ZRcP{4l6H;;2?XZ_qjcH%H(K<~!%ucIMNr|_wVY)^EX{n(q41bb#xLjA; zvCe$`S9SsbQnm-;;1NVT$aZh9Kz&!TO_`>iR-#s_dcBRDH^?0yZl7=Tr?GCv5h>zR z3*Yjh*6B;-8P%PZESsv%?-rGU2mn$G2q9moIk5~I8vn&sq&nO{ zH?hpEC&pRF9!^mzxMtq$7!iZ z856RhtFxu=>s#9SQ*!st_vMN8n#U3CxMyo^iGB$b2nQouEpa4K%PqBHZgEf%j+=no=;2%lK#^a(C{mtFi1lci5P zyLt&X{IqsW=~_iglaFiBcGN7xQ%#tDT4Oixc(}Y`Mxy)fSg3VdwO?|8pQnSozva5R zG6D(q@|+^yvkJr2Kq(v;Rf%QqENscQ4QMF1T`CT~&{LgSLNOXVVYXPuczp~6P^ayuKGni0{i{~!&407SXR4l z#cY@O2Ajz4LrBLrrfQIRYPMJ8cRDNp#%81#(;OxkSRI`iBb}Q|$Jv4i=F#h^D_^~= z!(>ej&3QqD8R`VdF`hUv{&e>nDVJo498K}50!o7E9r6r>el=q7FDs=#0&d-RncnVZ zj`g-ab*y!(@AUHh<@~~bB1j|`{MUg${6JFL*j9Iu07~1N*C9-)CHV%xsxIcRc$PX5 z*ZTcf0M8}W=WrwvcYz8R_sP7&JW{0rD##^3@`~`zO!75Trt=@Vp0xp>CCOfr3L1TI zQz0pG1KD)82S0@gSBN_okBc6f(ZZOla=qHw*r{T`k zTm1HGNXIx>@3vIj&_nC4$C%g+qV1KKoL)&g;(ux3?{?b5>*vVObB3GZ^(Rd_;plwTrW@0(Pgd*+1t`vbrTor^6Sk> zzWQul-*Jt_IfD=W5vx@HGN7^MV%C#=i1Z*6BNFDq)~zBCaX6y;$!r*RZSSL1G<)OL z)BV=o2LwbROZ>B{DI$WHJc83;JNH^tKT{<<^Fso1&QTVczfW$H%0R+(bujh#)*fx= zTO4WZycO(a8jgs!CBMqd%pccq;Lb}<*L2XPD9BRSx@*b;m=P7xa8)B@D89M%G8*1ieQC32nG!5k zo3x)XDQiz2+3?4(`jlyM6JZMYN?s=xW3>pgB}`3&!KE7yzZrnr)sR2QeHQb_@};kq zMS0WJj*dYjZ!+(=jRb4|jfK{nzs3O5pTLm%BvCyJ8M=xPS?Bbdn(S9e|GGL}W=)Z{ zi`X*qJ{0>stAAzXy$Eeg3()d0Tb3BLw>`Jj*r{wqyEJBpHtY9y;y<9NHSElPwNCeq zH?NaQ&2(7>l$i`7-s26j%9^&Smc^z?ml{xX;h{JZ&a?)(U=tmwg3sw2s|wHRpd;%@ z1U%9+RcQ3}jd6y$M$|8vFVD`>sX_MYi4?57FBek#*MsU8!3Bop(AcLpv+PZnQbf9m3I+| z-o?K7#q+n<%953Dl8WP){VA5O8vsdRwQacx_J*_#FVmdGopksgWGxiAs;+!nzXI*BFDixPEjE7RF+Bd{Kj9C!18`RLD*u zqNuuqu=4+7>b?7#`rf=CB}5SogLNE1;}Lhmg=XbD|FK%`0U%^*dZ z^xh?*_ZnItKp?cxTY$-L=6;@;H*n4$=d<@d-?i7e*6t0dQ~gpQ5Lr4YjPba+XXKoj zC)RU3bA%^EN%NJNVY;*Hl)=*;E%2b56UDGl3efIfu|luTz{jhE`M>6>b5!$@QrLfn zT42st)^9GkHEz>#Ud$llxIpY4pxkZdi8x!&~sS%SJENs)v&M%b$GH4l#2^c@>o;9(Bi~&3=%e_sn!|oG}ff zYZt%aD}~M&g~r;FiN-q)uT)l*w%U@A4g@E)SyXL7(fximJ zdE)W&yPgKH{X~&C7^FeL+~{<@Z6uS}ovBYeG`e!LA3UtT7$kw5qbh>aVgDxpO-ho< zn*;w#lKIL%HI6av`c60UkBweZ+e*UaUJi_BA{4p&N!jqrdXPY~=69#AidxJK6ZK|7 zyBdpV^TCo(R)#OWTbA%Q%;7JA+PcFfO?~A{9EVAqLc0^~2V@ULCIt(2lKv-)1hge- z@;Qc)`zEJW%CMhQ*nQ5KmjjG@Q)W>{@+qRXWvyOv=u_22HR>>RltU&!+K}J=O6Delc+7_5toxXP?^C_@R z{M)9f(?Ha5ixL~EtH#LVa7ixI@WNwxF~l9mf}$lKo-ngIJLw6!O;5Qn%jk*L-|6@O$Ks;2&7$R2Zo%sPE~n+me4@M0>+cyid( zzRC}Br%22~LQ4Nj*F#6%8lM!5z`VN3GmyJHk`|w2E!Le6SdBqLT(V+9 zpM)pYx?XIJ%2vGmGF()gn>6l1u%ljiGRN(PgTV�|heQ&y>5g1!zqjwm87#gVITm zGL6LQ%q6_SN$#lzcf|HOy-ba5QAD_s(bd`Hsycn?_<)@+{3cP(SKKbh>0#|%n)1UA3OQMg+jnX+B^z6Ian ziAZDxE5q@Mr)gQu|9;>3VfAf?yYT>4f;y9#hw3|xB?TIWDK;LRd~ok*m%_fhn!TlkT=NWn8-ClB!0a@sj7zhbX8luuQsHE$c zRVQy)eeHRB?T-(~fI!R79iKPNU;QqUC3V4BR17cEY|IpIFKEtbG*An#R8srs`H5%# zIJO8W6y+^xZZXjDvm20tIg}1LJYD3y7_%TmL!eQDmfy|?5ad+Kkn~b zi4~5A3y)TwcoMzpHYl6vp1hPT+$M>b`RcFeF9M#Tx7jKZDlGBOxRQR}7o1})9owud z%Q0ZlQ`*zpnQWWBIR7tB%0e0f{OWdAFY7YT>u3g2NVXSHMEd9eTP;Z`Q0eclm&Flp z+O*ynrba$=5I6e;K-l(nIE?1(P{KzV07~r~{G#jO7i?F;MjXFwj&GUmffqa%m%yTp zNur7tVCUwp))S?6F8<1q=gRrodP%&4G^TA?U+Q+FYNE+A#Xnr~Hz+lycdZ#`IdRCR zSSLofzBVHLVK1x4sxZm2d-K)D3K4(npm&0dEV`B5SDt_mgCaZcAZ%DEcOpq;Nv~PM z#N<7LzSDQ>dhdm?aA|WX)Jku~E%azl&$3Jkw5%{GmVpP-LzaFjBNvMs`TYbNlCtLT_4pCt5rIn4XRT8_PfuI|jkFg< zoPm2EL@^IBEep5D9=kK&WGGX0eJGlk!KopNf$w`e4U*H#T^SeokI2{9X&YCdSuaRu$Lk7Shtf*%AV$HT~701B;tz-yPP_i8a zP+7kkoKL^hOEj>`UKl@iDD3%IQf@&1?Z%xuWU4o>Q&UsylKDToeS1;uj-EfJ<@s&K zhYq~$R5`u(48GluVB$~YTEg7shX(eFZ*%I_>90IV+}US$Q8+KESa6v?t_sEeo8M2X zo78iOl&znRke$%C3q?NNN;4T;f02i5I`ys-7c+aM?3SxRZ5$!%v`Oxp!)}Mh5hkR8 zG|Y!=oMBAwuZ+hopxUwfJ*)Y?>j}IuZ-sMIs+`o(BPdMZ#>1}P<%xTmQC683#)esE zZPOYZ+Ac=st%-UWoL>H;BW(-tvpz*teM2(; zE$UiJ;~L48Q(UTY6W_Z3w7vF@Q1GD|c(+`P?t_^y$R{;Qljk^KV%yovHOv=rgyxLeZf)R;s~G#YmkV zs}*+UIpQjLq@1Uids)HMb%*w7tI`Eo zT^2M%tT3_1=yJ`se|i|!qot5vkwXQq@@p-@-S(C(X^z6)!!X7oY$wHkx?f#Z_#F+> zUm0;o8D58QoR{pJm2|*JuG$PvDK$6TLItG*_`jV7Qi!KL86W%F-D*DDnQj+b9Ga;8 zVDRCC{xYPF2c;;TJRtjZlN}Rl$1|b%1hPU7c<@8)BJUTVo_zB~vK76f-}y`)EitH5 zS=nP-O3&1UMA2EE>v zrQ|;|DcIor;%BxWD2D;gW^g{oVUx5S4ym7y`TekDK4mmPJ;ix_rcXQq*?-4%#ERY* ze=j=#__NW(>Bv==7eX-r#kd$EDl1>F?v=LNFQcSsxek6!%#it zZ+V}&MY@d@aX!LW^E*Epbl`2wh%|%mQkCcY7AP#Xw|{i?U^5*=Xo_LK&Q)e%#=$8C zRcAluyFu9wmbG28JP1UXP+EnNe{8f23UVIoxK?^SHWX%3t0LpEgaNRD?|q#%-om89 zMy*rNlAXb;K?9VKTZ31aj-B?Fp9R=?;9~85WD~zjtSQp=LXhxFwx(gdXMx2O6)O73 z8Go~XL)+_4(}v|dEY^JsYHHS+GMG5Gl#7fT)N+$@&e`1hR&f3}-1EU=+4qWK712j{ zCD+yh1U(zMl_I8fxe?b`J)_<$v_e%ZLd0d z%X#nvMFY7`zM$;~<*=K+81fw@VoNGwb&Iqzy*Uq$FXu^>53+`Xi~os@4o3ei`K=8+ z?J0Y{|HaF|BI@igOu0CdE#J6^ghuNKhcKuO_FhDhMn|lq4fs})tc|yxIgCYt62t|F zX{PxRGE%2hO%rB$Fy{sHCVp?T;M^e zodxsdVUQS(_Q7i&az-WBvo*6QZZ4mLGJUIPX2~}`q1T)82l4rhLo4L_>j~S;aIk}I4b3n#h=Abzq6PrN#VW1rhiSw ztiRnjU@uhaCh8_#pEGh6j&ta#5pw?up>+Mwu46O$MZ_1H!>qelL4`?9CdjRn6vmE z$Tqh4Wk_+NyWWrmfs78-*LIE(b)QqGR{D@iuF{X+8PovBtwL*5_KU87R)XyMU?0ky zI2p|xea>JCCF+SK0ts?gArlEOh#D6(-M&L5?jj{H2o>| zdv##Mc0eh8;piT|=a)v>oQw^Y=@&ofUKP|Ei1#{qskS*)RMJW5f#gN;GNA2#Njyk< z;H@+G$EpJ%rH2_^*(E_Mo8^|kMl3!VGl>qHcuB4i6Bd&+UQ)lKi`L8#{mQN@zARqA z&0p)XhvukqfANmU9;tRT67kw_1jmS6rZ6>MIrt5usq(OTQ#+=TmES?WDgIE4P)M)G zeE=aoYPg&)CH^$vz(qT+=V5OKUgHimpGDGhCm@YY%VwG;CB zW@D|u`C`~Fa(vT5jEGujO|x<3 z!_AaYy1+9=1*h5M*ak_n?+5&1uDJ`=flM*06rJYpK5TaYJ|rGy(e zj=*5gER+{^3-Np5(0m|<3 zpo6Pn%^o4nCeM>+&F@dIh@*aZ|`OP_?-; zOYW(mH%hhR%l?OI*E5Nq>C8?8FC7CIII~@cY}ZU%rJ7q^14J{!rJ^fd9VEYHdW2YP z_S!#;1>OcSzGUJKq2+L@+XzrvNwIQf+2sjf>RU8-fh~Bc0k~ZsNPiWMil?DJ%jO?e zvzl8sU50b;Q#g>e1vIOPT!k~U5<{?G6jQW7s2N;WT9YkO0MtM)DnHJhQK*dDy8&Ao zUl_ihGS;!y^Q(2~^Zn70<6h{1d_D8q83UhF=9|m;ij|K*(|Os`C^A5L#do!7opb^I zCEW~6{o(i57T6p{BPIm}MpSgV6b$DhyM3U0)Dyv91`neWIpG{;Phr*_Er~(>rSET( zlqflBpgpam+7cXwnx4>|0McDz>}q=$JW>>KE=}PR7dbA}EoU$Iubnu-rkA$#R5WaI zuB9z~lpo_ECjy3`(bzFvr^jjxW;5-{K$>9=)SHh=0*_h-vhM>p&Z6aoxAXZ=n1VHZ zgL^S|dh%ESoRbre&zg>`sW|I~%dCAmHjI=Giw6Y0s|N~z0!L2Aq!eF&<#AbIfIq?j zzTACd&&_E#*7?Sj)zPGqw`@`vTMN)5iXXIToW;-TYZf7p0L(TNHvT#3?#@kk&`(Iq znSfQb+4m@WW*1km;*8P(`O1?J?0S{NnYb(=t7PkMvVn8~Lu0j)D6S80rKTc~>dvdV za7znu*=ssDKCf*?WF!fNBR$<|kCuS+KpUcl8l5QqCx{@65_GCbmn!_5WHZBhL1~OG zM*_YC9WiWWue9D*H`-W1ceE~9h~?f-`qqYfdLndFxWFnq6Wd-x(EF*EG^4sY%H=LZF zG^{t4kIPowi}nsgP%2=#rW4ya5=RZ$SF*%ZK+TUt;|xWaJ{<$q-h6@UGU&Lj?{xJB zfG$O*G;r)Ye_(42A|ns&;qTh?I&5a5ON4x$Q2QyPP|pthB0@3MpQrHtk+Nbq(ar-V z7xB~SFUa<0{RRt0DPIjGdZKTd%>wSL@-V-gOQ5x z$bFB>%kHRXox~;D?KbWBkj^M#te-O+H%RPToN3;g;q%?7@!ePiH?M$6$+6y$}X#WW{?K$}qUd#LrHh_KVe*77L5OAWs>F6~xL;qh%GNa$& zwbE-L5|Ib~qTX-7u+xdi5-;p$vuBz3qQAv5KtUA~+2*lcDp_0Sywm74e7Dd%mpZs> z;&(^-bT!>;Inq30Nc^OG;CioRay(V|gx2U3s@%_#P%_i`b!Ud|&o4MQ`1uBnW`TNP zhMPLyrLdmEdcMG~jmWm*2rYJ?e}VdP<G$&P2!{$KZi{!o@um)I zs$uR>XG!}JgWC%kbB>>BOQ?Wgk=ClgwuPrSrWeZ4`ntJyDiLM9nj}xlz%9+_jq7aq z<2NYT)1gdvw=dG(F$k=%PXoE5JxrwZqTAzK{tJaOyY8zC2+99zgoFOrEKfU%%bWm1 znHluqA`7IG{qRx@#L6ywQ+TX%qkV|oTjquJf=(j%lgY;t{=@|H!t-_VJ&MMj(dJ08 zx>X<dbehj{LT#_m!dYrj<= zm)g38ygFICaw~xW+F3*Hl9}hw9&*|sg<_?m+4#(e-#qR915Z z4d(S322qqL>91r527YadfP!!T-cMF?(G)$as%0oFHAo22$Sd7&6t!r+@?KIKZaO|M zqdC4XI$eUajB|5$!9S#SBi(O45^2=un5I>@wY9NTS!T~&%VhP`C zgEZTl+`s8e>jv6Iwm~Fn=stS)g6BQqz2F5W0;952igLhd#dLXPW`3#%_tflhqWvPoyQr$`7G}( ziA;DKD%4-tb8(MK6Y|2pa~a550i5acbq@>a&fYWY5oDzg8Y>IsPJ=)z?DPb$sU}}F zs@YA~AB`<|=ucoAmpVKADJ+@0YbipfpVtIVrOVL?X5D?D(HOn3f$uk+Z5KgW-nc!Z z_+6`dDWzy4%Duemo@?o?o+zGVbzGAgb=0dW-dLyb^|4`^0vgIcp1UQ%YEg;?uP{%A zU)B@qc?3bBrtO1z_U_u^@({NR3XjE}_DWE22yvWjE^;kZeiHw~`$pOxjSBQ_0t}x& zOfOH_0nDtIUe%s`t+aZGq`6U0NC@Cw`8VO?tUJ~7q=oiuO(hxgC`zI|MmVL_< zg>7B_zEdq=p|7PM6rz+gRO?SAHu+7EQ;N025@pcya_@Kk5W9BHZ$B)JpLK*Lze^TB zC-;d!CgxBXw!nT~@(Vvu=5(fWUROEMsR)4sE=oP9l+un@C9z`Y6FafX@orwyQcs3C z=QIsYu3X3c&Mkcb90AS)%tQW7DCzo+)=wpf(y^dVyI4G|dra*QNHwbvwM%pE8Gi}h zwh3-NQGyJOwfaysP)1zbv$b!+!TGE%d~o$+B-?(=2}b$U)Wr1A(mu%m?tfLhnlIkG z?6;MxnwowYZFfN$5fXs5KH4Al)Mr8<^&F@nh9lhQAe2~#iOz)u0w(=$0sa& z+;=3`VI|+@JiR)xTA|)CRSTT6vpxx4;L7tJiQgbn=bHU+W#lUJQJG_9Xe}0(l39MR z+_%7$*`sgJppjw>I{?UEXolQ-)LrC@c4|G#gN+P6|R#2+L4fw$2uuz# zkOwfQ5M-Qe#{lt`i>uq&6k~3%EU>%ZW;--d$1d1v$h@La+6>I}B8A6ATw^q=GD z>Jsg{->udAXYM{2vgy77bV3UgIZEAmn6IKk?$j^A@%bJP%@Pe@&Awwp?w>9q5qw(~ zXYG7`CNm*j;wve`SfnFmTL+5{^Q_Gf_gH8>RPln>6SjO?CgEwRn>GjD)Scp0WF%^w zoIe6uC-V?=nMBp^XS)Am$32p9J(!bw%dvj%0H@)AopLi`K-UC%T!pXxbavXr{Y~Bd zmN-5ksi@vi3xAkwr;(Ax;Ir-0tBq*UwK813By^nCN7SpXoe)-b#U6`Xv|15IWM&j| z`yUo>ZNB%{H$GLH(tuLJXD^yd{WY=q0u#veJdL7EnhHL zM(&+1zUwdlN60fI(>0T_Mebsu%%o|-O1A0vB24)BvhlbR>x6>oTBv(JKKj5m*r$CK zLx@j_I=(30I{wUZ&sgqqMD${0k^2JS=Xz3*c~;QDO$_vNS|Y{1WVrsJd-z`sB>wNr zR|MtALK5h|@zk-AQr%L@LG6Mh+;<#3tqwP%TgV;%EbafRj##PT@u9*W3A&r4++YM$; z6jw>l!9D}qfkTA@f1>t0NK{>X6{^Yicl06+RAliOo7v^%a}=3EC{{Qb1EJ43r4Zk@ ztV$VFo8~*R0yExZ9$20qv+O6lt+Lae3^KTrS2|_!ppO$y6IEQ?ssuX@aJeXMyms9% zsM<(!FrN5uVQKvjr~mMtyWuWB z7t+sUXj-7ND`k@y_N`M_VdScvc3rg-UrRcusrQe1gdaUPOiFBiu=N>gpFjuxX)Af~ zkYfWXx3g61re@oDF;pr>T$w75P2$G(wzEF~ga0Wt6~%1iH-^H%kRhDTTl z+07vW-WgL}|4l+5jS($yLkFcAuNW6hHc8`0pLpFH{iv}-*@I7U z;D}H3of9EnX{8nxHJLBHbCxEx;uX>2A!D$*jX>~W)1iZar?nW>&cZGnwKL-d&~EIYnZ&MIVXY>nXdVhP3T*YWB?Z6?J&MnSu(D7UH$zLxU0JZ+e1GB>M%H{ANX7LiC! zmp7g?}{h!OF79rGrZ4s9Fo$<08z;RF@M5O_% zto>A-4Nvs1+wQ~q4VJoOH&)Jf4gM{Y^p6z&s^BXo`q>w_qxh!rsu@^L;&?+kI?71Q zjvea`g{SXTXyKI1O)9kr#UZ4w+f;pP%~O@r5reRj_&{)xZ`&sZ4t4Y_O6jt!ga1wg z!qOeEJSXEs;ucf3T-PJqT%+!kV>vDGr3s^oRBrg$h3e`HP64b8i=TF|^SW;H@oUJs z$v@9H)4Bv4h~H;**}n59n+-{GGST8xAo=>wtFXC8+d^R^X!RY(i1ix}yfZ}pRi1wN z>5z4zxXp3j%R>HnRSPYeRSg58>!iA;|Ew#ocqDu3*%ew)g)W%_GTiQi|9YuI;H z(dBdZ!$I9XZ5`(Wt&Ar1)JB6OqltT*cNAjm%U#U-&ED4;n(gDsjsLAv6&PKR$Y;!< z*A;9g@qjeD!-d_ih!2|q;RxjCKRZ8|-8Zz8`=|>PjIsq5?(M26F3AOTrH}H?JITN{ zIu0Mjm9&nk!9w+~|Kz^rveB$$4O{8~19SE7G@o>elAbYZ(YNh2zTK^HYZ#k|rR|0; z@U4TDe)UGGJUiGGNf|#D3Wr_Py5(FpK5nG{&}Sf}*eaDno&GK_a9>p`Dh&p)F_HuA zmC~3oy<28B>`&zNDc-EeoRhUBl`8L8CchmadHcqij+idDyc<7$zlj1BAdpGFVpc8c zuVH2)HdwY~c{P{uiA^F~FVL>el4tLt243{i*TMrs==H`sY`It4s{$ccktuoAWkz!g zSqt~`kcG(m#KLS7ahy(#Dl3O-j;7g_HaC0U6eIeb@$O?0{RY@U!6_!o!)I9A=jUkS zqY|y4mYBhBRw9x$x#_o7s#I(Wi>+`_cY-3RPi`lo*^y)SaayWVqW!;cx^zD)bwnzm z^31^XmxGK#pxnqGF6Xq{8DQT>%Za9Av41-X--sk?{B@?f+yBdJ(93t1;79E6gP#<@ zh|7ynSG!7z!~MZ|F4$h+|M=q0Nrd&^G8v=@nUM$GSQg$K_t~sqOpDaMLX-YoJ*_8A zMEV%m>i$APpeo#Dy+`I(!EUO4q|Ho@`?0#ZU^-MH*3~#FGG((Kel*QqlgD5m&bJR+ zunUarCc0$y<~@+qmK^cvNA?P`E?ZBY{|z?Q zm%3cDEcFJjNBEcI7xTr-0xL+;O=LWogUN0sD^1-zj>U1kp1HoZ24nGfSRCN*fMYD8 z+5^0B?Pqk`A=H_h-#o3qgStkQ2B&Qs?9yRDXYm%1q*aCS2mK8F)=ZBd1kFeQU*P+!W8dMLa0fBAHy; zJ1Z_2o#T<_zno1y(AmwqPeIIpDzhw5h!xF>7s0jz5g68dot9WeO97!3(iEXlHRL9 zPxn`DAtQD|Jka9Ww*Lx6%Sv$dvjvD_X9)kIJN}pF<4m8YBT3f!gjc|e30`tFl|cCT z4B?(nFhkgn;fiXO+l^|Om1#2SnQmp>QVs9p=RfsXUNJ>dlQD9^=cbj7Ht{Q@!VZl1H{S)FEIhcy!Mex3_TpdT@zsZ$X-@>L z70!H5i+N2}ilqaX*YN86X}&dN!s;R=^oTrjp6=(nB!5maY-}0XwmunouoWsGR@$&%kjR+YU#IGW z`~0d08F2-r1lxPRL_fATShAAO0m~YCPMM$|lx%1}geb$`%@IT1!%XmQYJyy@!z!s2 zmIv988x9<5(Uu3#^A?kDAfnnT@Omj{u(YEX1XRD0_mjC?^NF*4^wg*JN&z=k1!>p3 z>CJX((N%XJ?xuMsw)02yDbsH0(6R=fydA4>*ALv6%$XajBS7Ac`&?jLq>F$6BR{HM zD+B6#Lfb5*rMbTLWXh!;J+@LGwBtvNx`LiiU135PluntHpeLh#XIk8sW0_|<`@XU} zNpf#ix;5`8EIb>4^5syCfVT==`KWtD8llB_C`X2}|&98b6ZNjkT}|82N=ly=)y zSWLYC>Mw2afPH#B$bN)yqh-*4L6VfhlpUd6YXusjNZkaBIzooE{111SX0~s-wz&+6 z^~e_JY0<#3F1kiehNMIhz~$hrFFlLR+8_2>Rv;Q>s}(Kf;nT+L$*jqIll!EV>b2j0 zdbjs!L1Ujdv5*Riz7wKBh}#*qE9u3pDNRNOWyglLy|}{0g>}4P<7)M1VGXO!^^%@b zySI^FAQ=@c4ZChOcCYm4J+`ElP=zxw?;iX}j8XerXc?c`d&uPb%`B6;G$80Ywx3tK z;x8g=_`RP2PJUf#?^92w=os%#!oMt^(-okwyPWN+MSFNtam%Z<^-@~D*KTwg&T|r9 zxqWNS{>?JyS_Uv(ZV;*?^ITn#;kpCYC$aC-1kV53$_cQik5dN!8^IkU9_&EK2E}k< zH*h4M;tHqKXz+EM`0Xv&iI(DkRdh5j;4EoZP^@J4&*h{8t@r%voAcCiO&n?v5B7f; z2QJ@`5RSa4*&LBuV1p-C{!j3wZkV%|`#@ZbBB05`zF5_APSsq`dNu`y1`7M0XTB+pxkiC%b z`>N2TjHdj^p#D1c@lbKP8}hoDJkTt4x1{VM%VIr|X_4M2H`EwD-z$@}UooQ33EmoN z#N#4Cb19ZU2$oaI{lk~ENo}m1k>Nvyu&MhU@$Nh3!jU!g zt%t;pi6PI=kai-YX|1Ye2A+*7e= z4P3-{S-6Z%LA;3aF!xdDm~>^S`gB3>7>_CS+*ba46$3>5ouw%zL9!KIMfzYj?HCoG zaGoTjh7mvLA{cUjECEcO*uL4yH@QX8O6xSzHvZ%-NN#yn7M2#-WY@o>X!01=cZs$vjH9C7oQ1Z;-K6LD#yEC?*XcuzW z#435{BOR0)fqVvae-2%CBx2#qqKh1PTjt)t>U2_5-4R^~o6clf%Ds!=I*VTTv1sEt zL0RcQIfVPFj9ZRar*w>?{|{F$C--9OR_D1aDV#IWy7gZhZ=H`pI*+3=Io|802ik*Qae}YU*04-kZ53lRYjbT&xMgex739X7(UZd!_MlI;o~n z_ar7;LjP(gIt47=&R1SvZzhOms!}HWk}RXM5098WN^!34mIVFtWhOSy3V1I^heYi} zEvn~3JH;4x9Zh-J4Fz?hMwY|iI>E8+yh?6kLko7K+pjs-yNXur8ufd;F0N!$p1*y5 zBsOFIEPf54^wvEd!E{F5FV&tF`M2D#n!he*o10PX-1BP^BxFDoe**9hr=mGcH0&El z2DmF$oSu#?;#NXL5S;;ea`7U<=ojq1&PyzYG&i;eUv%T@I@Nfb&>Ip+UYDMc6*o|a zBr(#sYZ7Fc_G<&3P6Fh7GyEM!r#Nn#N2WrTmpbSo8W_HKmscVPTmsT*b{ngQ&OL7V zyXKD5KI~f$va)!!u8Y**R-YE>>bkQYW6CJTvX8AK8s?N#AWT|9x1za%H^K_Qhi#{D z*Rhv*ysqYd-|+Mb^|{!4$#(j!gPhuj`WTIPXE^p_yMIcQz=4uPK?YJS_9cuW8%a)D)QHJY{V#PI! zlE65DOr6`Vw~b2=Q%0#{>1F%-uEv&oFRT_ zz$>ijj5wKEotGXraphs03=Wqmrt!6!>0i>UGLoR8ZY2z!Dq+n7{w)jIZ*_~o615rP zt$@nzJf$7%nr|!u)G}(-!L;?SENerP>CEPu908FT-`p!Q1qx1F54<*Z$XEFOj9h~Q zMUjX|W=BypbuKj;`IM)=9;4qZdC(h2AGs*{Ho{U_u6_kDE%#a`NkB}Z2=r;Nc(A)y z>y&fCoZmeh|A6Z!(S{$f@lg{^h~d39Stt*;5`<_TDY0+1v&_3do)>Y#4+==D^GaUlJ}<8|&g&~WEXbUri-OS{tpzl?Pp{HS=*`(dU)*FNTItB1-jLe*p*702 zd@VT;!E|UUf>gdPzsyGU$ygUm(Xd%D!8iy6&1 zENg#3>X^#exxtywon0l1>n&;32PJeO^y5+PQn%jdaY_M{&|0ZKM@!sYXaF`>7cE!E z9Si4Pq`le5ea13NJj_Q)MA+tw!D6uMpCqp zwvpOGQ3nvX@3Z5z@DF4Q_`}C&qH$se?Y35;BS@GBjr=j0QK1ASf6=E|S-Hu=0Y;`& zYJ8^NYg_8f`J&RVg+C^pZ*Mloh^8*_`s&vNL3#ZBwFYlp@p3Bean< zS8DBky4=H04N*5t651Zc1>2QFLElGyLw~`!$pbm)%E-7}^**r@eH7(<6*J|=_S@UM z8JFse&JPv`06^HVOY>@VHaxq&rkrl2 zAkK6o(2_$>$hHC<<#M=G;L$l4hBau=bbzm+-l$j!ek&BY9%i+-htTX2!YG3)t;d;##z=0IT0(WKcp^Bt zbFkf|>@&GvLHHgR?KU8MVSlzoC`b1}P4fB|)LR5}QnD+}xec7(70F)fIJq$?JuTt( z!5U1eZ|J~gjm?W}c~84OV_9LD|I)Y$JQ?ag9Ue}&{0NHVc;w$`LUt$XNcN(CWxd zRHcj?$|*ilsWzibFZ~FOxz&PBJuMg2Sjkz}?2T0N;=m5k@*GOYaFsxRm2f^R2y-&g z$1k}#L6lZ%Y*GO#RvdcTd(xBxLeBOK=*(veg|ZaVgtcl2%TDW-aY44+A|cCAVOy1f zBLQiwsV9dACA{0-G`+>uAe(1;SCfNOc^FcE7n-YKOHS&MU9YHcD7@#9CbyLuZ}kLf zZLmhmfL3TU&_@ zn`kp|3z*rzcW|eaoem*+FEQdG@5sLk#AmYN;#j>;-trm8v>Ol=dQ^|rPqLc&;J0fR z?X&@Ub{RCyi;$|tMSe|vckz&ImW@``Q(i64DVK3}HEwiFr+{jXwEiePcc+A2N{$Sks09X^Y_BTN`B{ zwlZ)uU!Ax3IUv^ut^Wsj-TWW$dgediH6NRpF^$v%PC0l@5}Do&IVM+Qd{MG0FOv$V z6!SKhptG*_+Bb|f6ht#d2VEBfs^2jlGJ$9D4!i)OrXOVNr39hyDqp0e$sA%p? zKJXlWq_sZ&|FHmA>jS)Pf(nYv!hh59lCsSp+qIs65Y4t9L61t`fxObUObWUG9*oLQ zzBp{09F2i!%+toQU3VLMOiq$+!lA@CemI!rWa+MUu!E7exF|N~?Q)a`gc$Uk#KG>PRtSqSr&I;_i6$_C25UiEI#w(_ zrq$2^Huw|Ob2HJ7INE}+`#ZT_;_3FmP-wxY?TLZ7`&gb!*fjN`S@Vln3A*3pDl_z# zYvm9sr3dNtVAOL&u?Q!wGh`SyJ3J8Ju$}wL2qKusA!UXvD6Pu3`Z0G;*%vQt;fagn zWAzr)Pa_%hL#xoUO(fDU8&uYI0-?1JALcSTa0m08eK-9wArAal0()5WDxp{P)-UMT za@Xg3{QA#d#DJ79-ya3LFq0P^EE`d$dLI^x-0&O?5k`+281WT}uwxigmfrgAZf^Kp z+n2N;#mwQ>5eUBZ;?ed+@{H)mjX9sJqP;F&z@X63Jnh{-T9M8`SrI~z)?}o0Sil}+ zLq$ac*+T_0f7F^Owv)tfca`3!w(Vex7$b=K@>is!uENE@j`3ITrOB=A5-n6!XemH)!d zUi(hZXa?2ue{^L-&Z-VMf{Aw72fmDHqrZZ83TvIEhSVrFs!ZPvAT@h&-^@@9%GHolnPp^lYuE|Deku<#)VuIoF|e zxva%?*<*An$g~y7G7S3P4VC|o8lv&^FKw~KV-O2%*ZK45mlNIg;r{yj#F@)=#ydYaX1=$(+yI;BD#7zU4ZT;?=+ zZ~jrE0@uBexLkTkt95Ly4b!3p$*mwydWR=As%A`B&j_5H_hq?>EE-SD5gmlp;k?7h zjHs1?J)MxeJBJ7{pfjvMf)YC7aPR31%{+PL)d&~4?9D6zL5zVgu{Yc4ExDozt)tMg z9+=e(29K$2r~BLB>QU@MBXzi4ADJ=%o?$Hy_jap#T(pNlPk<@aH@N*ClynLxc^eWw zD;DBtsB>Gd_w5My5@;@#XtJ7Xn19-7->18LJsDpBX(GX_1Jlj-Gwyt)nFzzWcWBKxu#+?{j2&#mqQs|@Wj+BxGHflX*B0SR#fM|-B z!}1{5w8l>tGgefX!3Pdk$KJ5MR|8%gPsDjFP`fKWd~Fs`%1qBG?sPl3v*URa<&hx4 zmJSuh(t6k5gKSjWnwcw3nXmNSBVr7a>PIpqHP<9LFg}eo*Gf*c&pty?u^KzWWp!bQ z)ya{gjr_&O%z2IwqR5toNs^uF$@;+Eoc~4BSw=Pezi%8Rl~O=DRFIGk=@5yDln4sa zN_WFHT1o^4NOz2s?ik(OouhLw8peSCzQ1$+Pxs_=&K}(7e&5%1y{>*9HG;GmUgI5z zfo<*G1mSjG#t^^pc;SocGERTNZ4cW(pYvw158rO)*c;NXCWG>=s3gRwJIk`bc0>ttYnGHBv5kP9pdP69l}($=u0rdr~!D0Hn}d-|7ys*i@s zS*qT{Ozp?G9UZsPMBq%tx+fq4;Fkeh@9#`muTK$6niN40*Axz>HfR*A9-P@Nj&u`( zZEP*?B-D)5Qq0tcby8gHY!?3BNSgfe_}QQFd46UZ-4TGn9sbW!h}@95-w0{FpM5~d zU#89Rn`$3=f&bUuH~t@en|v#^%D&W}1eK{mK)C|>)!xi_tJJ5?MhL2EQ(0I!bI68c zRY0@;8yzN&A*3oN6lFr7G%O@mPlaT)3J5POBtDuXm}o-5i;}Tqpzph%x`$LoU*L^= zcnI%i#62&@iX!^_^!1|c?7QzHU9k#1HfJ@tvn;|x3Bg=Kn4Vtp6a|KWeV!htYz&6% zpW&cL1MTkT;t@m+f0p1mPWijbF>+3-<*zfRUv3Pbk=tKU-5zom`q)_zHbR$Eou-65 z*oW&47C$3~jmQ@LP7NJ&XsW>IP7%kM=)6ltfBfz!L?f(aCtWNH`T6>ks|4I+=1EX2 zq3!PGeGX-!V;fHSkGqW(-p4aUec*kL*ZP{47zj}Aio|7;#sP81gz;~0jyE*TsG4yU zcc=7eob7H;tz)I~N(YkcyWb31bcRgqJ0NQivC`rZ3ze7a{B+SPOBY|L-1xkuVe!&T z7NH(BeE*F4f5lCb9~E{^C4ke@6rB{o#p^4geNEUTFiG^&6uw-NnPChOOOS|b$LtcBv8NDL! zf-rdBcAuZ7>Z7_5OY5~ts?cc8$}uG7f$))jO|e5}3PBxS;Qc%Qk+l~WUnBqQ!&DRU znoFoc%3KRX{S}ND&nqVy=Hc5N!VstT^(Sro65gz*P07_4>4``RAAk#vishZL$MNT+ zA+(CbZ+q$6d8$)LI%zKk<&IE| zrn1evp}{kPITsg`-X^qG&poEO!9fSX16G?)iMU(%_Vx!H?!j%vwvs874B24wYGWIk z%h;&4*(1}eM>L>6rSm%Y`|0-t?@&-~J85l+A}pdh9G@%JM#wcqWiWwF< zBXOQru-U=D)f0#Z{e92sH63{*iMFIq+y?{)V1uzm+fyfw4@Kl_TEMUbD!c$n6i>QX zRg>6%g+TV=(_1KX>pDC~9!kpoEBdJOVet9N!q-L zO^XbSMm};6D7@H(#dxGRyDptN@s{`YJg;U+T3y#{AB(#cy8%to5?;u|+B7x&`e*Ht zeN1)eG~CdHYAAqI8mAklX*ErP0-3}`Z*kx~kYs9AO^AC=2raL?h8E$83+<7tDNB8QycRahaJ?pEE z^Z1noGdXiQ57)1L>oxN)nx(wUv87%&xd72Yhsl#gp&gFQUltbqw;Sx6DqwLBWIBZT zhy<-y|AtW}pmBp-&2`+G?pLL&XDn-M>1bU*-E|UdyM3}TSe=WDS=CE4EWekj=5}|@ zX@4!0Uum_@c}goEr5AyZda?DyRhKOyK`r~CduiD#PJ{fdF1C)q#`5FQk%R_V0=VK# z3AG!r#-KAR8!HsHI;EhM)+u^?H1MI!yH#M6!3#1mhVrUyTQnOp&~X?^EO(!>9T`Hd zk<_A?{aZpT>g_2XO9vOXY)dKxr+=BmW_uNioK%G{d!7zjoRoDhO!Vt+Mn{ilIInH| zg_=Y2ZLKKPBNzO{*F>2`7{KSUOje$W9hhyoXmpoqKbJ4x&H!v;b$3j^Nb*V3`@5gY zA_3FP+p~{P8S3+T1J`VT^ZV=|C5GnpGLxbpe*pUY7<1*@q^I58^g7`5oEIBJ1b!#{ z=+;ogj9{*YJR+r&UTTA;vx&_D>s~TRN8q}*_o+~)>Bh?Pa}Zt_XLNOMAREM3@zriW zW|A6PI_99uM6Ew1D9uxBeoi z`R*2&5%cykYr&B4GBSFT&ji*)*$ zMLti93{>pwE`;}>=jW?&f@Wgh$DdC_-CuD5h@S~DXv=VN6%e~72S3%KBw;yd@-J$F zua=65J3_Z7Gwy3H2z1UJ9kxG;++7;|c+DhE=&;+FaeB^Hn;}u!yBY5j9=Cm(Fgbgy zYSg@QbO98Sctj%pjxn)_f$mRav(=JfKvlbE&;4{ON*fcJ>^71_*R)>FlK5Vf-A`9c zn_DcMSNyz=kXlzRmYVJ*oR|OAxX-NX5CPQ}!uuYX7-=sumvtC~v=_hCYIrwX(m@XD zIw8Hwl5xG3YTdaaV)B$){dXw#VDmqU!L0k8Pj}8i+p5x7X2<6P`0HlAd=-irIB9T} z&Q71_>g`H^W%>DIDMfK$IUHVM(E>bZ5Vj(~TRi>3_@^~SR6o~1Qi`&cuRE+(D2zRz z9JXw!+!@o2l2O*8!kIc#IQk^P8SAz4YHdEUy&lslCJVD+}mkQ{IxsRh+I;2&3}OTF!#EFYTNo zX9JI;+h*mp9U#!{c2Vn}xw#dq{~5d7hQ@N|F7?uCm)Cud!h8OllMvfu@;(yA--u(p zf~2!I-z0V~Hi5LbUHfWC_cb2I9Kgk$+xNQ*ls2%Srm9Y8-~!gpyw?TC#$#{wkFfQR zYwY{8NyruVx_r^x)#%>06ie#FlFXlIi84(?%C4uxYQ1i~lC%DMCcIQyWzx`{@8^L%T-%!Y z(>qp+99$~RFlp2^*#e|{08EpnwLVljyZe!N&=<#!4-;F^n# zINf^?idxn;UNcH5z5C$n$$pk!Q6_?I-ZX#SPRosN z3_kZezV|QhcOK9gq!^pleeXQY=(b?(lf$P6B-P%#osW z77IH2l3SR%*dWD=s0kvXCSQaRnq?G0#;S}A#V|fM?&V)v)s{OyRwS&EuN-}JmfZeE z1-nPM?BMBNe}eHrh~Zb2h?`$fGj5zEZ^yc`swBP)U!UgD&dqrPL5RucZ84wGt3O2F zyy!1}J#;m|ES-nNXn)>dPTO4r^1hod)QC;3;5b0hcWNF}lJT$;#-t~HTN}8`sf#xP zk{!|Lak=or(}|6AMYm}vm|{)Lj&zLYDDhoLQqz@$^?rd93$vs?;AmvjBpGop6oyOT)htn21y?OPM z%vVCoAS!WTzTxyHn5lkdXVbw% zaWF1~v51+3cC_6l;fU2o+U~s(IpXc}$R<2@#)m&#@1oXH-Yfb-^uAbKSzgLf4Sfwh zZ7a<0s*Ra9c(Jk+k-=rh21#mwi^}oRq`p&B@o1(ZJ0npkaZs1V5E;9al7dYKQuGH$u%VcPtn+3VZ^pB&`4V0_S#vCXktsoPcgY za6U55OyE=yD4c}nK2-%|5)*zepeBuG28``A*_p=~Z1L>>Si|omauMqF+GM_w^gw|< z&hHe(tmBJq@Q2r}PBzT0%S^S?JOU%`cV9k^u#K*8iAi%r{d6m;1pvl-rB)2$(0JuR z8EFZITB(&icNm?eS>;+a>0utrW~c3vU0@k6RG8N_RcuD@`pLM7XHn_&#egn?{FqzQ z3qpAC*WsG9<_?mkwCESlLn$NMxj&Trh;5ZO4r|B#;sD z&NoG>dCo0y$uzavUsvWDYhtW+HyM4)=f-R>q(1m|vZ+H^f;fn#nYC)e;^c*4KP406 z-_JYW(iCz_h?a*&vb}~+x|^;X_TOST^bOOCxKcu81p@0%SiyigP>G(Mrk1iQ?3u9W zKw_od+!<%#X;ht^k9)8=Wa;4FPSDN=IYNVqy*+v^FMe1 zm~Iso7xGAT7I@(butyKufuHGu;||5p}%x@26~8Q{&<$T5|Y3~?_4dKoOw@Nl-at^i2hG=bgxul#5nXsw}B z=7rp*Az^7ej56js%B^3G%bc|CZhaq)Ngq%~4+l;^@BSM#q^bPG=hX=wtx&v(#Vk$z zosHSr|1^{`1nSN$dIWBdB)e*FTMkNh#TM3S#~G8{8=#HNp~>6~uuHee;{CE&u;;0K z89p)}y~!pm zeFN-;N*K0$63CE>Xy0olBKiiQ?Xfyhfb*|d;44thyRflb7a2*$8hQP;d2K+rwlbcB z;g^7U7-Mo62#$iE0)K4kz(>acfddYp zb~f>IO@p@6tyB|CfnAfR^E+M?Rb;rXq zSR*LnnUd>pD|cm`81KAEp2h}I7&qrEr0o~2F3U5y7Bh?$nz)tvI{msNz;B@qNkZ>R zg)QbS0aeZtml>o5eRir(r~{Pf*<@XD*t|1KmYNFkRgg6p<3({7-CZ4+y+ch& zq`{3O@FIf+zDMt@k|fmd%}tTqB`^|jbQGID%XXZbDhbk#{_`tF7%i%kT!1X+D-u!X-d|#~Jn%S6odQ zTGMErO!FHVqwT2`PCC<+g3HpF?Exf%OAhrzLC3YYC zJ`HP;=F3=HcDDf^?ll53AZRw45O?{yeNt}3g%)8iD$g45kI`;W?MAGBih$UY#; z+0J^^Ax%33^0Su-jG)HNhgZQ#&56#wAdgzIJdDn6r%4~mI?KA1tbVYps0vSAa1Jpo zF21;+)Lp2quyAj}p)_oy(q%KI;aH!W87Gixy#4UeqgT$Y*41ro$xedRgY}Z4 z*-}oi!ino`U}VI@kKIiR`ghUGk{|P3uYjpSkvpt|RLB@zYbnw6;2DG!xT}7OgpxDt zL0nnayb#EyC(sjJ&rG1GmoOzgf12N`sdIzrQJoZUcLAzLtGiAj=J+a%R-%B@)GzSz zRsXp_zur16W-shK3qS33N>657QQvFiY0aN@&64{v3CAstwZazJ{piL!SIYpz>1W_o zyMVo%;ca3JI{TQJV0+spE91>riq4d#!-4B;go?XZzcb*d+8#G2uN3- z8VHYg>Au{&KB&K#dPmrbBn){t&$yoyeLrV!PXTV~LrSMT1T?(YXMA!}JvwhQx2*Yto0c`K?m~hLutU z4MR8;88evdjQsCsqyuJKVo3g<z4G9MarHD99OVsQ_T|f#>lc;a8{M(DAqDzWN1FSt)3zFvxpXTqHv|pNDm9XB`EwD$v z*76u2g`|Z8U$i9`tY++l%FxO|A+#Cg-pKn4H42g!^=ppBrEsdSRWU<&?Dnp%-s;(Q zlUbMtsYLiz{;}nENb&`cp@G|cEx)r?5TOm5mhR@imh)IpyN18iinq6s%$gVH9bOcl zFnGvnED`ljMKRJn=8#cP^bKky1Xu!;{|am^RdDn){Zm z$sQkNsa~&?V)Wz+QoluSc3-7>GQ1^!C|oe*u=<&_LE2>&ON61KMHG%Dqr+e{q#Cs@ zbu{9VwsW}wmiDdU+KW+ zXoEj|YiF=+tG(@Gy8>70PFEUEznW874xj&rCI+-CcG0}G{b~pq_(-4t)xGIaY zNmvaJ>#}-B1!X<)*s*hBR#QK0AEzPolM}sb#3_$Zk(FLp!(W zJ*41GZ@jRm;l<;1WRS?22rO;cl$^ zhv>y1yiz_M!~y5y4DVXJE?TadkFQJ9DGLz-h{{m0fA}U@Kn#0&>_2749$&<=?WH-E z`H+z7uRVAr-fj(fd)v?Qy|&k+5U3Lw3lWnUtSyKtJV*?Po%;ymFZ`M4+4Y0|UBBi? z*yPf84Ye+E#&H>jC2B8Zd>M%sJU2kb;5}7jC1s=gD@XQN0Nz~Z{J+9fg;>d$q3-yP zVK+6mZ-%z)*HA-F#Pj?1tg8{eV9_mu1w+Nz&0Rm9Nc!#&qYCr}l`s7(-d3`^oWqo# zNa<)%pk^(&@YVZ-tpuMg&9oXR_ORNGCR1T@dTi8)Jl_`S>W{Z>=Doc^a=*r3eG7q4 zOQk+;B$eEaX}TG@^uA)@Gh2nNHK8i3I;f8!r?8 z)c?=un0z~Vbku5rkRO9^3oW|CHAwEq*Mf~`ebg3{&Sz3wqDNxi=$*VJ^pG?91yH|x zOU@j!G{CNR)BnD1p{&o?OSHU}Mur-?d4JCR$N`n~TN+%lG10uoZ+3n{ahXvbF005Y zrK(~u%>K97Y(IC1wM=5#Jth3eyn;?@lK>L>GwfpLORqZ(P)p6X$m9uzvERCBDFqJQ zEAlX#onCG*$=E(0GcZc6b>o%VI`UrI9RxkYFqqSVK9kJi;Wcze2rs{1Uz1@|#y?Fs zA(?sHxBi1$C0;Pg%oE4t(Yp+N5*Zu4JBCS0nh4V^B6l`2DVej^!?79=Y#epd?66bq zIgaw@DQL1Ieo@-s1pOgT`VYTtkwt_1hrg*faIv9kC)v_L9V58(3#gv_Wjv>ZHxuAL z_;p_d-Ep>|PFjxNELX#Sx|J^5?1a@SoOD=Nka%@5Hn-QEI4aF>+c^OgI&aE%c63-B z7lhJ(IZjkC{H`hLw6YwK$;OHjIQnD3LcO#QU%$|koS#=>?cx#TyVi-XuNfKLKW7)6 zxdMZBF_VD1RplzLo^_=O$94P()GPAHx{C+hwY+r2TRx+xVLp|-Uj zZObf25YD44L&9KkzB8%49ON)IqaY$DvL_8=L&;V4;Gs6tpbf)xQ`BX#mx5V1lUi=`J~-`>;~Q6J&z&^T|94PaLGHGb|Ll&{LNgf z-o}psJd#~2jEgJ$4XR~1wrm)-S4u$^DeJtHRJqr&k#7=0rnRbE|J8_A(o~#S=^sRh zqLTZL`XyYOnZ@9dlE0Vh(HA;~f_DX6>3@Z%ghi2^_C8HZw=NB0*Gm>&cl#!jBH}zm zr;B&8GD6A#exYqJ-DsWxOIm#OaG^e!_;YVaj+)M$&jl-1Gr#F9uUROW=u{9ZU@md9yB!N>!9-LqxKlce?G>ft_@Dcn2ggWYZRY^}KVFf}CuO+f!y zrwqE2Tr3H>^SpHR0_HP2)XnX?d@`kRb}w3SKeLL`3u(O(dDyP#s}AZD-*xESW-2tN!Oj21h0B(6G3Lv zze}C$Y^!Zg(xHk%ZJ|VbdSpxk%9_W+x3XL_QY1gxS8+M$Kj7D__ZIn6>Q6Slm(!%! z^jBcw0(ph@4l2Xweh}s5MElGBW@|bb3Zwk&KCN@OZsbR52>xJ#3}%&9kGN_!-1 z`IgPd_B-EcPCJ73*pjkG-lW3*wb!0m*qua=1}4b}Su5u19ZFxF08r`Q07h#*(;Cz0 zoxed<##mP38!^WD<9m6qdb4^Eo$MS%LErltgfFM`rZDWH1>)0yG zVA$Q!ubJ!vaUvqaoslt)5^j?V2glPMie;6rs0_>(-(J@kFCp`Y1Raj@lywPq0_XQn zWW$`i$2TmA-oyT!%VvFcLI2uCuV2z!RX!~WhaAq7)yry8A z*fd3>5N;U5Kf(%d4Be-oXB#erDoRW{P%dv3)C9=Re^pnGKiv`)2;$vQ<&~Lb+OT6-DgNBZtLlZ`xLHrpu6|*CR$ofF{-M2aj(jNP?gznd~D%fW^`tmoe`2b8LhspKV9fuCyY!n4{Hq%>U4W|~9CyT@yUhaX?u zcc30QH7P6fpnM50Qp=Yj>Ug88zg)=3G+EJ2w}ohD^BMhKinV7{63`}wll$2p-m02WHz)pPR<^IUjqPy8?iYS7j+VMG^8pyAV5s>Ihsz!MMfz18)9g{XVki`wpjr@jF%d^C-EY) zyW*7Ys#7VGuSAir-Ub}6zv9e~mdMTMOM5l`Aw^BJ1vSlfF>-yx_WgFfaiHhaSf#!+ z`tx0uvc*=(p5+D%73;%L{A7XQ70T0qsB^aUp11*;Vj#6v1SUNhmuiZeZNRDn&*#G^ zlV`x3q@`v5OwcVV7ULU$O2?{;1_Uv+x5D=-ne znRRMh$mtBYD(cggYR>Wei^@HZz>g&)S;jIR#`j@nC(-rI57KGEY% zLYcCFQ(u47?4)euU_$enKhIZdG@B>9@``@cI?bGOJ|Z?qlX!8v1Zvp`o1acl$QBmf zi!MY|h$mACD9WH3clpU79n!VC6|#>GHY+EM!w<$*Lk55eJ$!8xlcz2zuCDSB(r_|50&nlz)R7V}qjzy(=n zG^SIqQ1(=T-2EL+O66WJs)`|MBlStfd0eB}q}}@b`RA6@M0_|T5FN!tgg<>Y>b<=_p3l;9 z5)sL`61Ch7Z=(y@7h0P1+i%3W8YA#K^R92J11jJ;U`2xKwZ;hni|yxbW{+hMwlN?} z+sfk~RQvFB@+qEQ*{E|uCoOMlM*mw|d3{*MysrEAl;iUkcKA{VtKstT!pjVC%ldMr zzrr9J$cG(vJ%5khW(aZ?rNpe(eqL2#plX=>-0M0=)C{nKoR$vdy~FAYB%32!h&1E% z=1JY=Iim$cT%nQ(GrUfRL)e@H9D7P!FbbZlw&SJJ6ie6F}P zlE0jzMYoGU_;D#>IhI#9Gv|OJD$Xo}QK+830 z`&lc$PH|dvYfHd;mrO`d(M&hdp{>VPcP*V64`;sj@ZI2k1oBBQZ1wI4l!T1D-;Epz zi*MaaY1w-zJSBTJBse;x#?ZUa9wf#zN}Ktgcjus(VaoE*iMOS{tS8?KFGF_9Z@H;s zkV=)v0B10zU1|@{m;9e7d8DkbGE+US*HB6*UsYWHZcGNcYs@S&3{Qwq>k&lLu!owE zY4`94@-ud8%;Th-{*)jCR+2^KEtiR=*wC>J%IqK{Gac!b8PzXhSv5I^y8)l0@gI`oB1+(o0Wp$XYo}%wa5A7H8InR zRBut59`GXNV^QZ)QXt10sR$pRjT4`O=nq!@h+c1#8Jgo$mL25wnY}Cj(I?MXl?p=(cKZ zYh~9V-$$vNz(7Tb=Z&9JIb~4C-|~&k$D3?8p-iU$0OjPt^ZF9f9AJE_OU$O+s1F|u zUs^iy7PyJuGV2b}0+aSvBsv6;SsiWm4?oIy5#R6YKJ9SWsLr5>8)zcXnun^`G$ z67fd^BdMUek8r&m%!=k9}tz{%^ngLl+@igjyco|ODtIkQMvPn4uRqpxKAbAgW>xs&-#E*787jo(8 zYwp3v9ZQP1ZGYrG(eW&OAV5g0vIfHwkd8}u;;9{(DO2&>>ydJ+;7%lz)oa}Zr3F9t zcH^m5w_+=2T9k*6iwy{mt(k7v@p#B=`CdnyF&Vg4XBaoK(9tN4K4N4uMRkRf0vqvU zzTDmm!@dinHihylwlJhTO=(AXaQAuZ)OpW-#IQ|LOv$yU9^B{+V7S+?F|?|B3-xm<(C-{W7940$$4jCnkZ(Ut=k z;+yQ{^D*eO36T<4fF@|Z3y$NG9D(YTAe1?*Zx$uIzlQ$k{#;gNPXBJvR3K*D{+ZzJ zyY-SL@pxZX1=(coTB;JT^ia5!H}F{>rO8h}C43fjTC#o3mLL`5Oq608-PsBv^FjbKSA8 zqI3i8iw{nn1n=Gw=7*9ptrPNpI5CkeCGMjVV_f1s`$)R9I|=PmGSU8g{6{xX@tm5X zXe0n$5JKB+YLm7WKteYNgMJjTquRA5U5VM`r$ep7CrA`dJD95(|9FtqxdKxRY1-@T zs=4FwK_ZW23MI?&euvf6v?u# z>N)N{6>@z(=^!TgqO*sDZC5#rv8`xy-zSw6RM^ScfGxAvU-!aL+60_^DHozA$@94U zdGmL#Czh&oD#@d7!md0$CPa}lkdB#r6YQkE6~3m1kI8P)qOWi;o>=^RI{dhEI!5nb zTJ&#YT_mz23uav^sDWG06Y$ zOp0e^kUR?G?0>=$Ax)p^g&N#-IpsOaTZve1h7O9cIZqJ)EIwIwGS7(lF(oR?hzV%> zs;1OE^N@lhz87z$$V12fZQ`My{QQ@?7h8X_G^VcI{doZgu>tsbG>PrS5j*^|p1?taB5~LE#uHN z`+A)8=D1thOiv#Lqa(13{nf)Djh{pInnjR4i)>_}3U>LHA*fC7_1kUUjb)elVGK}4 z0IYO2H%TWz8bR_{)b5FqC7Uk*fk#$Eg6As#eS(V*;VD-I?D5P_PDbHK&Sr^$sCK7s zDkLjn%%)uQxwjuv(z@d8wsDCkIAy-dR3&AM-Y(BFvO69ZMaW}nJ1MOogB+D8+}8{# zx(FL=Abep)XTpP{*%xg>dTcNJ?{xI*FtsK7LSYd_j}@2Xpq zNHOGBkbw7kzlc=UmpnviqpnIZio~cP_DeeCh2OufM_58%O2h}>ERR5Ff3b+R37XN@ zwpiL@%;;wok=|(J%2kU;3-DY}=2r0L%XA2d3=&(0?|Jenmw#HX(uU@;%x#s7L8<0x3g*?TmaAbC_3f&a>jTlA^a>Yz-d`2>k@w>= z;?>qJD}P4B9uEE|{msfsdAt;P{~M3FS1n$O)~`#7=pykv=Qtvj#9Gh_SCNsrK3RKO zH*>&5vO%J)oiB{h?5~B>-T^PKU1aw)j_|d(6+QQm%3Id98}aA^?pQ;!#y_ho5!lQv z6am*aT!GZ`?xVn_u9sX3KJ2>BHsso1ZNSdfWg)zu9%%WnpK591)NSiF;Sy9&rUQho z?Ry-|{`vIhG>u6%@;Qx|(5}5O1cl!@g_}Nhl(#uj+=5Vmx@N?@Mozx?5HhQ?H>aG0 z;feBX1pdHc`FAWGx%6a=s!~NB9;?wx|Blj}2s_vXG{z%pb2L!ve*7mZ9@AQv0 z&E6zyCn?*Pi_pBW7MHhl^i_@oMn_|bQ*kelvKhu>Rk;t*v(5L&WXXRQ#`FX&U#1lR zYbUP{Z@73njgVsrLO?oe`AaZO?c#MbilD>Xz>{cUi<+j0bne9Th@>;LthpjQl2&V@ zE#l;CJ3k%Le(s9e1MBa_y515#wc%g04T8!thV&@6Bb?X~G0bBmuLUMKlB;$*Nqh99 zE7c6Tm0U3PpwB3@9O>5br#;UJ1+Xhi82e#lxwn(&D@CeC>{zCAy8e|bGI;xjA$>^q zw1Ct~^3CtJQxtN88w*PSn@mymym)BJBnjwPqDAAg)k}u-9Rc|7&* zt1$kQ0ddzDZ9s(Q^R%xXg!r7%Pwg6D)iC;W z5q))h*WBuHec*dn#>7;-^1H`vg^7VU=V9!PQHV@2?bs{oVihcT@>ubguHq3kWO)vT z+l~t~@4URx*VH5)QD+)TQNRf2g%|IDS*1MMHr<*Ys*~>`#O_UQg$yKwF#fbz`T=A zcg3rJWsndNs4h+>bs;K?! zQY}GB2(Sf_Oq*Qz#rL&fRyEiTLmo@`l8IbD)jtcNz2O;cb@?NZ?+9KW`3wA$l_cJ% zwjkE}g+>PI#xalX=*>ea+57Y(WcW<{^IS%(x&?46=*{KqJH$)G?@U(FIx37z$INVq&H${Gav;gRMXN% zq9G{3{_@&txad{qv6{%WF<_zONu=f4{aO=rR6|ZAj<98&buw@a@{Nj+3@I4af3Dup z9Wo1T(q$cO)i#OAW($5gvMJ+L5LT;anKRm9PwAq}bFLRsLdEymGumTP71Yh;wjutH zMsYUdRNdaG720E??l#pH5Q5IYioDOf2>ym}!EONhXFmGH9UD@(n4|u+rzMwj&B5*H zPr~V-_&Ky&#nkTqSpbv@LNYpQl&kW)GcFPc(Zq`)sN4mEi%y{bFHY&?u^!=p`6>a zv6i4_y~E#3izNRtn_vk9xG|f-Gv}IZ8qu?!M>m;*Y13c{P~w`fQ;_E`3e{E+x_EzCME=*5op}=+T`{C*IQ+l4!NH( zq|{xQKUH%Rj_;UpcWALg_}#D_Rl#&yaf5oXGll{9`R-rz>F+!|A8)IHZj*u(4qnQ` zXkE|69Y=5(KI6X+lddSASPpn09x7xhRIMU$mDieNbCUe>MTSyxsCW})Hn8UXp61sy z{Ts>LuPt%7RXej?WrnU`tj_kwt(F>NV z5P3UWt>vxovMBG?2yDfp{_NrS5`m*uLkDglh15S)(^M*ZAeGkxre(CCiFCsJFI&@ zCM+d?Yd6!?(~-7hYFMp(TTgWCRVxOZecWMsn=QDZB^)O%PU=Eg%Q^}yIE!hnUgQdo{1>-Bn;} zLwS%AE!Sj~Z)NSdzj2O|zC9G&$eAE*)c~kE z9hM=h9{m_uoI4+q78kaT+}Dygc&(#n1G9g?Q=>BvKq+69P8^!1GPH<|{_`(!qne>B zsXM(zyNvD(h4=3K2=N&&{b-U0q@DVs?LId_mn-)MQN-KnfnK_rG4Cb$Qc&xnizh9? z88|(fNA(*L@twg$Z(CsQvNdS$qG8S-_bkk5s+ts`e;{f|Aqwtb^1xJqpo3f77h66V zs1cCI6?XIXeM`hj?S;{;)^?PL)OkuQR?fa@%2ZNE6)$|f4Y`|hqpyM!7Q3JP?AddH zBoA#!mWu{Q7`YR+E)*;Q5;=Wv(3YfjDOB%8&=UadX|tn6$YREgcy1Yk)6{SG7<7Oy zl9a^v;rQW>(6W_|EPMk+>;3DuQ3hpMRVdg04mI<8r~kq9c4l5XP(8R`pwXB{`@_=l zotuFvqkBw%{z3D!zwgVC$z``IgCv|p z*J8x@CNCE?`E%?)LfD}gCCVc6ksmpZr8hp>~-= z0B64XZ{E|-^qJn5OCsJmCY_6k~>*wbgt`fw5(X4=*MyeX9@ZF8jw zagBU3L1i>Vl5gjj(@JXb3ha?8_T1LBdgqa=Gphp$?5b&5$4zrr5%Qub{ujvwPd!(b zBS$(ObaA*~moKV<2lD8391T>)a&d3F<#ok+jn0MZv@8kX#^20ON>$=YKIJ{!570pCR^@2%vy?V68 zB-u4mTUs6W?r5%2Fm=?m0*F|47lQAFQ{Nnpd;*6l`Z`uj?)LVlkg5~L^#=wX-;#1CX@BVBek;yYp)jNA#}j;b zc$DJlXUJHyA3KG%CmqmH`KWrA-QNK>wJ@3FSD}_;WcFAD$#p`1hl}Lwg4BUvG#=bK zl)6Kh)P$+@cuP9iF??ISs~5mM5LYv+9rPOf!!6!n>I+%d30armUpF#qAega4g1^Iu>U7 zfq5CPom*O|ap|EUO6ZM0ul54>BeXk!0gAK!)ASVV8gcd%_o8si;6HpiSJSCObADefl9O@#Ip`_TUe z3PrB;ADKbp1Y4`bX8^VX=w)oTYDN9>wM^#z`tF@WwO%37`}N?49v#z^fqHMxMQ%Nl zO+J25O6I6gIzSV!*n?i#%YI$Q)5USsllsT#XI&ksy3j*;TbB6vn9`Ls=@(N>ymBHt znL45O{YhYJ2{ha9p0;(p>Yzx65c$2Ojrp8ypVY-UT;K>7Bodb2A`-0IUhUJm@0zX> z3=_@dU!)7LIt3_!1^)P#m5wW!Pv{iwE|O_^ZfhhJqz6Eo2r(a;GOb8^ug}m54>hG3 zrDGZ{v{~XqkM*S|w`;CiM-@wFU$+bs1b8!Q4Z4hk7OMrp#Y@;cSI0TXT`o9jt~SFH z9ty_DZ$1&ac&ESLKGEp5-$F;y@YIn_%RHl(reC$vZ)K|>qo3cfhI>I&HemOZPaaU| z9a1U#rNs(CV3QTV9W?Jpi(~&`nsjNE)~@n+-pd8H;NNs1lpR#K;dZno8FC zm4b3LFH-(>>yw_lm(b`inYH0tw)ZPI|1$Pj!4y~|e*bVxErjCK!P5SG8?OScZa~i# z*qDrDV+HQ%89P>z4=*K~_FU})>ZqJfmPhYQZt1M?S_88vo5pq0YB=k3ZXL=4LLu6I znEF!!+K9~kespVcEh{V}X_dBF-w5!_zM>e_ z0k7uCVhi^_@iQ~~T_dBa^M-|`$zPG~HIZE>UQD@e%B_qSApCKMA1<0|Mzw zsw5s2lalTW=dL`2^JAa8#)*xsJf6%VWt;wB#;KeJ3HEE&UYwl{I!w0RTgh&gM6ads zhsLVvTT>-r#}&Z`qX(mBkpqQU)`8*(;*F2*K_ejwIvau7B?adFYy1INh<>7}F;Dd|`-VqQJ#AV5xDgLS2S)y41`+99pE! zy_x1n$FC!ne>uXZ2<$fENYcH(@~ulP7Z33dUx-D*>!272t%%sPiY zfUsg|7AE)|t`BbJQL;yS&9KN7KQPf`RLa2;AT972&9lh>7eu8<*ig$4Dh_NOM_g$1 zdM_WXKTuz(ps~}OLxg7jsiUv#woqT3NH|?6f!{JItAKGfSvrr}<)i_{Uz6`1?>0vZ zj}I!-qBow9N^6h^VgzIB7gY~|WS5lLV2jU5 zs~Is}DakiwHt#Bf@~F6E83jB9pKEY>~yV4J$Ao*pm_sc}$`7<5 z)ydk>BYx5KucxIYp$Kbv%ry}vDQkC(F#t+cX<(n4d>oyh{MI9EI8+F27B7+1VLlGl zF~E20@=D~6{>6pXy9-5nTkoz#`LEB!)eh5LQk5k859@3f*Qaz18ghSFI5rFYf!>V> zstRP@{c@cWKdec2uiadqEHuPK6^|;vj1Je|s|9R%(v~F4P{MF4&v&iHrM}PPd?!6K zn`m`uT<_G5%cY!@ETR(dF7rTPDm)y&QbC)Z$9Gr6?wT^ntI!Px+6P%Rx)D8Qk+Sg{ z_{n}b*>sW6Ky{KJ^X5EfnnALjB3@lC-PxTCuOeYW@lX-W8B@Hkzw=RpCq$F$TAD$g zkEFmiJ8r@XF+Wx#{DP@ObT7zF7O68t9LcObeXIVpvWq zE*=$=^G%@mTv8<~#zs+`eD*TJxlh{nXW5{sQ^xjKlw>3U(H`ZIo^#Rt)fH&*Q3s`ET- z8PWq*A(RKtS?5HvJH=OZrF5XhgC;D9_H7mSQQ@18T2iU0$O#o&Rm?9@&s z;hQOf=d4Ory`F|G+@0FrIadqGoc(6@r*~b4pTpX!pOH5y5=3cwo@vfFLlJNb+sdNR zWN_Xf#0r1u*~cDyn*CjT`h%`)8%u{x*fL8%0-4CM_8q+LQtp4;v(6rG`Vt$G@ znl&d5Jdh{j^c&GyBc1T2K#Ip9^E^WyBLNw_oeFN{z}m6uPNR=;#r|et9X{%$o?~Uv z06UDiLuQ%I(~w2rae*+iu~B2lp$kpOtRPnvwYG{}qka=oj`+AhJS7T-%sjY(K~E}A zwtvna&9tE}j9~VkdZ7s8JvUqk_&kIG71;4^fw1w@w2X5&ail z>r)rC_{v#LT%SbgfjOlyUT_r3kBB3J@5pZ|r%s0a^16W?oI#zrAEbX^xSA#KdSuAl z^W%6850~HJmnR{oAsx-#Ld>MF9?Orezmx?boCfld*Uq}&K5xQ zyP%vTEkcXP{$)0Z=wZ|0=I6*D z9BXtP^5;ETKl^@Q2%enT{vyacYj{Z2uL1QZ=rWYpAAWo)SBBNf=MjVbroPCfKJ#eh zo=Q0X06CX~`;!{XY>AOFcP?CP$N4@BH2~&vShpGg*1Ql37b@yAx=|@w>CrSpky_Yr zBxD)%Mr%kV`>VxI=A`Yz(U2PvF@<~sa%TpQu7xV=`pJK+KO6}-8%9T8A-MAYbj!W;kjHglot{cOTC|u_ zI8-dX-W}oDD>=sGtq823u}vu1UD5oa`m7W1ouRS2?vNBu+(NU>$bG>>Mv?TcvKER} z==L1qxNUui@Y!N}5Mxpjf4wx6RmxUh#;z->pa|7mZNg=~o!&2U2SKq|P;d48_OMAn z5QZN%J~R`4^QC=?pM~x%-23B!RYR{vV2IT7bcFd05R2cQl($Bc`L+vJ9LlxQ8c@FcYgX#VfLih zjA|E7n3uXTpYQKL#=$Ua_RQQ-Zg(98#T4 z&P;EgzXhLW3ZoqNn!5i!!wcQqT+)VFedpp_k61&=R>DpM%)RrXm9a>OL7x05-9o&{ zV}#Ys>X(n#nYE0v`Usb_Z!#O7gVmb|1Np{mtcz@(#KFPM-TS_=K&(SeXAJsIf7V=2 zyB_T~%6XN-0JYAPjdUY$|M1x$Jw0&VJSxGPVyW_YC9Y*Jdeb++Mot^J8#`?w^(0+&T3 z3q9wQvKRfhb`b5>8<|EBwtR)S&ur!}t1Ul7e$nPu`(_QEk2PJu(0DXXm!I;mO$e{L zEP!vZU_6QU7PumDj>6&V63Qr4QtLrdPCi23b?TQ=D*5g1;LYw5;u??PY0NFPH$??8 z{>AISNfR#NDvpGioKpA50KFYrj|ARoF3UWTw$mVy%d6nszpLIfb*F%g$he1}b2C$x z!ABo}U-D?05lT}rxR|AFEDnu58+b`FxZS6@NgLfmzuTdGVn@=@aug-Ab=%F8L7yDI zbk$tklG0%LniNdpI>120&}97Dg+ylU;P1*n+uqhy+Mb9=Tt;f;RJ*k&DV+g82ZD&c z&QvB1sZ>%+Q&aYKmxw9*vQ5Q#F8eD>q|M@HN=555SuS|pbg)Fnqf3U!+iadXV>r%j zJjg?CpVP$PZpyA(VV}+~j~k>jQmBjLuk&?wBv?8xX<%%ae`kkC-u`Bp`ECP-N~?-V zr2*)>@03^Gv%16-Ir9vvtVI?_9o`GDQ-PJguA^D%0CCD3ZGD_M_dxq96D;6)jkPv9rNdnTk)eo_Y=^m_G`AhrlJvpL~u8_D94G}j&Y}1Kcfb>7D0>k z*OcqbdK;e`ZGaW5ZY-IdK=Rls73uSXvf0ok3wPDa`NK%oY#joja@6qbqzImgB^T(9 z=(9^rU2!u11(7IY(kk=tVVt-tQB@O>tdUPKlx)1AI;-@a1=x{QQ`w6A`FM9Fa*pQHzS@um!l6FPEc#ly(_Fdvr3ZAv3{ zsPhmiHs->a=Nl%tue;+_5|B0W7u=f{I(W46=S7>;-}~c1S2L|6y>98$jvhfw(PmqN zSo-HVck3tyPwIZoZr*R|NKEGG(Dtp!2YPr>5Y&HH&8gFOIvjb}&=LALJ>=8-y6^b0 zCw~oe^a%{^esuX!d06S%;>2*Z8T_o0 z^46WHv8%50J!$(dZQx!wq_dEf_9`0HwgWBWUZ@3TK+cu zH%|N}OX6Yzo()r7E$w5FY>!88xlMess0`%D79)szDqI~eN+T4Syv6r^HmI>(f|B1Zlut~qPW4LL zO??*c6d{&XrIhyl^;6lyNNS`D_%TN6R&p^CrR%cv3ppIT_hVq{9!G5;!Zw(-v6WxM zyli98PF5W;6RVVm#d)~;-;0+&jFNVsRaMN4Lq8bj?lgbW;P8o=SIKHR7ygb$6ne0> zFu6hkZD96Hchd%Y|fYJjd9Nk0v z2=Mhd7>-wB{wvqnC^=uncqzSLqdm&oV<46Ntd)^?>fHC__8N72Ryo?vxY|O>CUwI+Ye1 zs?b$cs%6i=6L1fCI`@4 z&4x)JSgKCmt!_=7SevER46GP{m?-4dx=+nP1B)g`FDGB>0pxvfSZ9AAhz2FUdieQg zN3qtEw5jfl5UAJFAtKWu(b}VDKiU@a9Ymnkhf`ZG&SKCU^)$SbRPUf|VEEqxi@=4u zwwRn8+9R%%m)?N&8u&AAUGMizSBw$8xAn`9rJ0KLSz0thdwweB_9h*@w4T-BIRCd@ zzt$!6d~j(<4WZaJYKUE^`{f%hch1L(BChzF+HGa&Ika5q!_@_`%%Hsfoc<_DK^Ac8 zdKfD8SKy^dG1&Xa@lg~CU`O%ETWqR@oOC{HjgHmr$C{2Q_T~BnlaC$s$dCg5v9gMm zhjqKI+ds0ra)YP?6Wd#XuEBFB3;v8ZQL@xE9aMsEG{j{rreIJiQ%u+A*aq)8ZkHI{ zsU3Z&RWWOoMBTR_A$uK+sI`1>DG_(O&s)aJwahHxJqrvI;3QtSp$z3!An+0MKA`s0 zYloiV#!kl%D(jQ()-4SmiYAOTHF}RU7qCs%iPNx}bpD~fseJlf-h9u7Pino&XNw*uwYnvuA?&qH_H*SHx z^Ayp*N!g4emx&EQ>ymcp%u_3eK+dE&Dn0D;!o35eX|X+a`i-hz@^3NQ&2ly*X20LG zk=9CE1hj2oJ-+mlvhkS7VrW>_x!q!?6n)CO&+_>GXf@u@~4Zhl_=k)!Al>W{SG zLd|~LT(hYOlpUc8@KgxznMw&+S!KbQMCHavtzpD$wBXir40d?fO86%aZf^ZrA<^#E z^uQHs55M=F-2l2O*9xY}hT~&@C=Ac4m7Swg9k;4j3aDbZvT2BUITqv0Z`5GnWy#Q# zG!J6TO{G)QeZ@2thK@ z^2i-bpyxe=Z_i(#HTusa4_R-L>ln;CS$Nyk3HU)Z2^&Dr_<)-% z$|8dDwS3iP)%@JySwOW~W6Twf&6jd!qu~>uxwrXf z>K)m?t@Zg`%X`Ml6#&(%>Fbs7b1 z5s2mgf;Rv4xq#;-3P}5|$*gq($DZ461so5xd=VwWtZBJdd;M>KXSub2=gkK1eNv&@ z|9W9d_}A}N-cw!QCg4A8$kHY1_VV_ruBYZ@{hR+SnzDQT{z!oQD8RwXdMC{Xno|e# zLTBI6(9Z{Tborwz5fi4w6*TU9n zL?!y4P;-Caj^nrvQyRtlq-|eWl?kERoiio9y|M<)pLGd4AUuQn{EiU@KRsJ3&vk@D zJoAW-`8U#)LZGaa(P zmC+x$aT6>*i^)R;yh&0hrjr%+Y5Oz>-%+IrWu8BMOBMy1>^>8%^Yu`H_>KfHnp+50rAIlJy53cSaYy0--|Bl=}NfjOU=?mi}+>2zyK?3!+V)KMM_&hN3$ z_FGlP6TUK1uMF#Y(tM#we!mi#+x1Q3#bUHt+@l!P)G(?OS8g@ji#@p;+Mg{&UBQo= zV?n>IgaD&+*|;Kd$W7hH(IC?acn z#Iw$tb{MXGc8(MTr*`%_epY?ThLbxPIlm5%dIQQSZXOzq zLCo3LT%=6De%!fJ1Yc_Vo2}q-h&sAh@p0Rcu=*PhJiZS*4^qf!J$x(X!n&9Eg3P0C zn-90LNexbQq(VgqmsQ%N0*tL@yvi5`zC8c*F-cSaT5RF3mQ4qFHc1ci3Lkvdpk-Fi zJV~3w`b93|=vz*Y&xgVtze5?sdYazbV<}hRyssJNcD?P0s;xnY_tuZO&L-hE<8(4i zo4-m`|K9We933)c!ioC$@@r{m{N+`px)X%ec_qYzM%c38w`&#^lOv<>=)Rl_BXs$% z+NFfvn@MM>3Yw@CFCNKX7KO7#Et(I7W^i_c$;A|hv2b{#$BFN|ZDEZ#AH3;4;0SdxuAwWRi!G*LR_snF_K z22!o5ohi>5d9CIFr=?yNv4KIHU}atQp!=TY!kv6$Z+atLGjb&<@0o8)EmErxj#4eF z1f9Fj%SL$|sJo>b}iK@WD6k4;0 za>c!?--ojJfMDqDDSo*v{j|@oFZHGejF&tt(cC^&f(xI&fcMryJ@IB9u|Vn(n)L?8>uF~jy-9>#{o$T z2zkC|(rglr1+(-uY4pC`$$ecQB)NN%TTP=fL-ha@AAC+l;5{6=_I z%(R=hfQ-zv+j@vrHhJsrYaVr~4ZW%HI}g)MOHex&)w@1bWe1o(2Jj(7B=N{9e- zOT{IoKNYS5o$)eVcYRhrw*Zr^m9w>olzM+czi$2M-_iJ%pN{loYl>ycvw>`}%CO_l ztt(h=>}R(gbNz;RfG@}}oG&~?wc_34>hGX$4VDrFpDk!3Xn~3q9&`@(}I_VH0#w*CSM9UcK=fQr3Uf1HSqSu46A-qJq{EzJo$*8a`slRMlJ1$!UI{1 z=C+rgLyyq-jZX4|jh?27e~#4~hA;27u2$2uCpHdaA0ITUNMfzBLaEZyg1~*P*Wt;S zx!a>l>Wsg)E7KCWj)>E0$k?CyBKz-#cZ>}I7&5l z^3F}(>mQF+3V$^ahdZ~ELZFCK@|9O~(8=f+3rwOMfvF+V28JyLv#KVrxTZaA zszF6$$0iTTHv6J+H|#2Y_S)8HDSo98uTUBtV9!p|yZ~Lb$X;8Y113aRY1Sf_i?0L) z*Q+L8U0$_tva?4}-wr!Q2qPbmcKvyyl1(gTX4FW0Fl9S3v23-%f3|_G0B(LsDp8(X z9(q1;_!i=sKPZ7T$c2s-gNnQm#uuW)U6OJR4I{4~6q)}S=o0;YZAc(&ztnKizC{z; zE`NlEG+g}P>U}>id0NllMAx)Xi;N2T?48z(?}&q+Px=-8Su$qiCqZ z5|ez{*Piwl0YhAdYmuysT>y65PE39lB-jz2&Yo{wN24-;JsClb^ED5Jq%a4BnF!04V(1BCSyG zFalY4vfh~3n||L~ZdB!{YS+A5R~83hmcVRgq%V0dI*kmuff!b7@`=J;jdXp+H|?xw zOg2*n8N!nmbSBcY>fcjL#KY_IR^u|cql=POGl)7@4p~j^>UEE!i!UWi1ps`+`bT*b z$-~-goj2^q8UgH&ezr*X2bru*Kc3s;>Ap8%zdoo!xBCh$c#RjeVABPb=^}NVAY)xD z(4@w|*ZK~de*g8{x@=mW-~&(G3@QJ0wmPRaj68#R3EG4Co`wttrQ!i8B!wE zW@upmqRzun()C_L=A9nVrr1SOl(o=CARb1A>&8`#Wt`K%KCP!ZTmy{lzmSx&NT5R? zLt2mQ;my@beD$Mh1wjdjCHpZzhoOfve2_JfNO>cdNc3>a%;P~1AEzY!Kf$`;pZj$r zr+c~ucaRZs(!=SZ-F{nn)rTmF(BBKO-B9x*vgmid`@J>dG!j8o?ce;u4dEGTb=|4N zPIMQR57xrDxoEx9zvAwS77*Uty`Y&7Un4#k*(w*!<}Z1{_adCxyP5akg?V`tXcNmN_D@*%k z>U^9+`+PjlHHW@za z)6+l;(nz9GdsUlegaEwyrrLyD8oTXZD62!w)-^Fd`<||#EU$jj5a(zTkDi!a;7+YU z#RduyyUALc=O^c^Xxxa|?kl@9voh_nhN3Nqy6anvgF%e3zeyTPT>KGCf}$i%7ys;6(+reLv&1e2bYZo-4l4xyul6*6ZWYU^R8=v@l8yz) zJC2*%y<^EpA?Pz~f2~uNrjwNrbynO}lU9Rsahuc4kfIXyspGC^ZyR(ESyu33_QF@% z&?h8#H9`Tkm@17LJpPzHIRQ+SxY^k-K8Vg)ziGG-M^q|@%0B#v@h;Km4BjKfjmOw4 znI9qG5{uZe@~SlBkj#ucPQC)~!ORJSjzQ7*0da!`8@lIeJ-JP4m$#?YDN@Sk$?0iC zO_=an-|wV~`d6?_cvU1*<%aI>sh`NFNXNm+yyY=d#BV<T*eOU&;#P15wPM^cf|?F{v%i>Vi0@yx)_ zNw+601B|Ek&=U)VQ;YvFB5ZJ(6kG?c{1fO}_V$u)MegB|wQ6`M`%KKKvc5x~H2=*I z_4Sanmi$o|C}MP~LBDKv9Y4^)WMxC^ZWbdh`mE)}PApz9>uq|MbbEJf+3-a9SZ&05 ztYG=0GEwJrx68)Bh!`kK>3YUGr$b+wF`0CcxU47e9fG#{t>oq>F6qir*xXwm4 z1RMW0lwctdK!j%U9Lv=8Z_MUQY_j*ku1+jZS)w^$)WvcJ+V51VzC5OUQ<=l5Pfkuw z4N9onL?+aP>(?_2yzubnX8k%yMxIV$)S#a+GBk%Co#hi=yl?R?CCtd1YLO!Lya2`` zJm^a&4A|A;E{!driQF#2ZnBz+{IhO3dTY~=g0_5_)3D+g&4zk4dX?Xqv{LqBx_x7G zP%hxyfV&}mh}CN(nA@0yZ{dc{baP@S={?xhF4xJq){3Qhw}EXSIC-vpz|MJ`Ern1f z__zXv?!9{D?Z*zz^F0ltFpdVw|2?>#Ql<84JlNkOo1T_YEI2=Ra^B59LpVaSH^X?1Ib=yX zzimhmhDQy39ko;>$E*`lC@Kzz9hb_~It>(~4|lZ&h}k@B6#fF;v3%15;aD z+cvs6+0)j^?MfA4Lx28R-<0LW8qtC?HF@$pVqDZ6*#NHVUrOTvzkliU*}qsR zp8Wyaz$eADwyhQX|C5!rRO@cXcdZ_xFGc9pB09*hsLoT^bE6}PdC#dCuCzq>O<=S>uYtB$jQQVdL_&Gxew4LSNBq;etQss@>Wr8XeoAE4hB`kj1Pn zxL4DLOK$|tw00ak1cKKy$m=O&!Bg$ai2#$|xY;zaGd<6*?FQN(R=K+hus<1as%{=H zog7%rndhFD`%dX=Re`Oeu&SQb9T)f%f(&Zy^Q^!SKl0%WhQy^m*}TFRUQJDq8;4 z(a+(51f)gsqAq)E17`94_|!H_dN(1OL1G?HLOX+*?G-Zks>7?Ku6N^S&fnY|N_oOl z@A_}02D?6W4&Y(6liC|3<%Jyv>Y96-C~P=;O4hy2cQ?9Ofn7zf+%reXn`x_3HuUa8 z?m_WHe5foepL(S)pqkxNk;KB7?d^oQg(--3PifJm+@ix?6HX(Kk6DtIzgW2cviE9M z&KT9P^_`XR)1+{k1XZNh>)EtJ{3K-zo28+W4M_u@AJ*9tZr1#KpRwFl+{nA4quCn@SD>(GQPEzEp4M(?_npBfaxVtKRK5Tu^YbDqXb z$Z(1OWraPu4RcOH4n*-^XA}B9MbITEsYz%)4@deGR*uZ)Jf}?u%5Q`Y8mM~$LT$ENU9V7%>d^5ibCGo{&ynRG>c@pv}Is5%Z0ayw17a8(&3*{kU3s*3I#T# zJx~8-AmG_6flsx^1NqPw_I?)ByULAR?&(x+lD@vJOPp^0xPQMVSN8h|KRA?aa@5R| zA0~mlnKT5H1N+ORK;S8+`2%yKb?^CIdi3t!3}hnOw|F4R3duIIrTL*IdqVPf9RQ-O zxeT0lIJ;M0ty%ZAjl+-X&A{Dptwckp6JYiYtMDS0bUPOjRAydIlg)X^bpCK;H2(|a z70mxRLzck#?7CQnNoe=C+g4UJW!hu=jG3Yf4(Gk)duOz;LK-)}8L9fhS34`oT>;W@ z3&UQR_6etdZA}ZCv%&McB1WrW$$m5tj|=4(%Ie#_YGn0+@J_P>dZX@EldchQUu(}C zlXmgsu+`O2wm4@UXv=v9UCmi3ti{cjHy$>carpK848QJcN#|3j>&DKKRfp;{c-rYw z+Y+d<{_2;R4Ktk%sn%Q*0wuU6MEB?ZAx;z?q2Jie9U9QY2)ad#(-Ix>wyoclv~|_< z&l`oDLS|PV^k*zvgKa8sI;>-NX7BnXu>L?;^&+4rCx(kZ(F3)lk8XKo?9zP!vTCCG zej?QDLc7nxYsX}#MnXZiJMu}PBn}!jw`FWn{udYfedTE`SxBl+UdZP z;60mJp-umEZvj`EQtx4u?e$jC4*FQGgd!{9dOd50U{>g54eaue?WPSzuNvvQ@@28` zA)>9Cq*UT?0Nrt`~n}CeQG8y&Ggk=VFht6V?d!yTa(?MERJzP z?copczslU6&ZUEBWE;F_**XhqvS{SH!=ZHdy?@IW$Bj7n@}wnLyV5rnrz*>NXIsAe zHrSdE0`55-il3AUG^3dsmt8@mrQ24B`Vn5?kYxCM+gLMnOhHxYNh%d+8+qoEkdNjD z-mAXeuB<&EfEZME0v! zbUm)LlSQJXdV4*}wv$;Rp&l~lR$|Xc&ocaamrwb=sJ`1{q_3N!#`^DO#}?F+kJ3N* z4_Eup|E%b?Gh1GHH9d3e>n z>%4dbo^iJv_S&^@Brm-&1$}S4n^`&-I^*n^toehbe&*Y{%USM@jw<)xSDY$t=XSKe zFG|k-9bISnDTwZ=FeR5i3vVtTp8DxlK$XBXSMmCI2@#+uqnj?5lgAq*f1%8zB_kk} zGQgI6k*fRIhHkin=gdA-zhv1JBT#rf4HTHoGXva=**^1Xvo3pQ7 z<|K$;csu2iKK&~EGzQ*SMsqE!id%6V^HA-V+G2n=J1>I_VVhAU2+7S!+)E?%+&rn; z>f!R}%GDNk9f~X*?qRC28*gZ6R%Hy|LM_$8BFV28b^Vb@DOtp;Q28IT&MjbtY3fuz zZi@={HB*0Ec)ut$Omw4M%m<}om6qBAxrmyav#%H9&eIwrpZ_7o)3vYcXz)^JmTqsP ze0G05LR*Oka`y-HuAF_%as;Q^NlUO7U{Sivo)y_)eC9aIS9tiFZO-v52(wE4zED?q zUOVSN3XC24XJCCJ)fYWNd!y^bo(r>#GJg>Cm;Q^U;S4CNNvl@c)GcGB_OF}C8q#Nm zd$LDQfhZwdUlq$gl9B1TPJ77PeH?oW=Q}y$16TotZhnKexM*q8is}e3sE{ z{pB0AcHzCB$FiorBy|)Wz`st%@tRy-&uz$id5pP;qS;i7Cw>3zxReCiQ#MHacVb^i zSy)JX4^SW~48zI4ncQNa_skVL&llUZq!XZL$(3XIlUbS8BCfxceP==kaL{<^*kZ$< z(J~kpEA)IxpS3A5f%`F-hjH<=tf$$8RbzR*n8el2Abuf!s=|z4jCo|^DoVgb^WAIQ z;zDY7oiObZ)(H1V@t(32Ez*$J@|hUB<3qtL&4jm@K+|2|KTO+RQKK&`M(*m%W`6^#UyYiV0+2)&u&}@+O=%$ZXlqH;BF^D3kW?Xgui@-Z*ovO8i>v=096a(H?ZYJmd1pHG5A5R# zHn2Sxb};XO9ev~-qU6!@dO5D0iRzkB1@ zl8Bw)lXe>_FWaa=a$b9@^mDVN*9C?5opb1TmTFizrWaQM_qMZ;YSe^jBXfhTa#k`Q zJ`cxVX

0P6Ko+qkrJ67)>}qpHqkwYJ(9;i#XEw9GT&a_5Wm)l7%IGKf6L6)FBf zyX(RANgOFMDF|XZ4K_e2r%TaHeUWsV!z1l~UM^72%htJ-{kh}lDM>a`7ORk_27445 zatH_qu2rq&ma;s%c(<0=wDjJo#|bqZ=-WKWzjbRmFrIaUT*+wsTE5HZ;HUvCS92_K zG)#GZ~&wxuRlir=M3iW_Z+O>fMlA?ebO-q2e8Bacd1_1TW}s+XBcgj6}JuL-y3 zq^v#NGh|-5tCOT3ysZrJF&LPtZ2!?9_b%g3!o?l+Nyxw#9_sWd)Jw2OvGYEI#94qi z82A?R^JQkLPov_)@467e^wT{@SjL}Wf{OxzrZsNzD9v>MQRxVge`PVxWRIldQ_+%O zvH7Ky=Rjs3HMsjkA3bZpCal^sz-6$IVPW|&^Zkm&>!lO}*?X}fB>pOw-)~n#D_AT* z6^YO#jgD-F>)7IokkIj;18?`S;UUw85>~vtWZRntAjJg2o#3|!q@VNi;Efqft((VpYRD5DrfA#ZcSO@86aUvee`~1sAF~)JJR*^V4a^u?4gja4 z9X*5Kg!)(7O_GHF7$iVzPYgou?}%ZN#yg+z>IDcs)Qj^c@(8y_dx@7^=Ut9l!>h%v z6Q^!=Vb_RT39$0^}!uev*iA>SQ&Hv8=7=H%Vs-v1@{5#QXH2UAMsAOwz_IWki z`6&y0ptR+mx&}-(oIftS+FL=k@bMqfc2ZN-QZb1syc)(R%rR$ji*Z-u>+3iITNjT9 z9dQ-y8`}#Uh;uFT1ZP%nbL4z}+N77j`&6nVHQSoG`ZJ?d<3mQOk1oEt|Bx_J^^`Fe z!wC1_9Bv#Y*4$0yEk^d|GyB$yXIp?1A{Ly--5S4&q=TMkB>)1R__M^~oQ`K-s?O_q z5ZMO7Lm6M9LJnEMM|Iic9l8u4WB^$!($JgPm%Q}+RBlm8#`d`VIEAf}KC@T2Q#)t> zpkH!~nycwSGWfd_OKCAxylQw(hn{Zu?Xm2uRSV@oAFGzi57Aj~do#Xj0QvN%j>n2IhRS*Wtm5>(lQ31` zOgfd1y20m@gw$Jwt}_&Smx7K)lZ0r(;1@z0Pk8zd!gIKhmRZhj3!uh*7B(h#_wq&B z>Ra*HVXKpAQkDpKjCRK(YfGUyD}BjKM_;S`9q?_(6!sc7GTta-px3xbO1F^Z|LxOg zQt+_r%@=!Kl)C~FMXw&74oDX+e|*0Bqg0;3IZfPQf#IV??`*Z?sC;v^qzq`#5=4)+I@vY20-C_d~SHJfng4kWuRqH43k;OkX zL2a_X1fSrydJEEam>jatM9efZ?Ynp07}iOThW;_Rr8xT}NT=Y2>T*19Md$X$Ceh2^ z^-T>C@MY?2VhJj8*nNJVx?wDMk#9GiimGgAQiNdadb6}XH+DTRQbh6g@+b|2DgXD> zD60MG=%6G;)S=3X{jlI#Y#D#hCLgs9$BVaYm${VvW*_9&R1$NOf`;oc&&EjRD8OIv za8>o8M6_8kwbhwu@}=ByBqAD5je8xHGP`mv{cSk}@Q|xW!N`AN`XSDDd z1|aEnHh7&8dc=N~bZe~al1*pQ*W8^8tkOameW5IU>JgV08t&rd=IHe!aY*Rr3nUWJ z+JvVzoc?y$F-?(IKdg5zM_-hnQ-nFL_YZFN{o6OAugeuA!5SA!Y&T1RjW_Q98%lis zHrz5+ANYROSAZ_lJ_wN1zb_Udi0zI4 zcH;yL&jog0SQ?g(Gw=|Ml<3rcy=X=Z!JpZA(C);D5OW_?C{$0klw+f3z?YbH{%{p| zx#h#&qNZjXlLI)}wym7{SUM-nabUkE!j)O#;;uykv}iAD586~H-ly{Mif7T;^o)Kk zi!oXH%dXkf?6dhHla!9TSbm7M6nPa~oRO!}yryt2@v%W0OvE?ki!bF}K4qtMHnDcegZ$=sQyH zYuPqTy+2oO%(x!U2w{YauXl(B%v9-^20kI;EVqodvk^{HVKRa6^rk}_o)W~9*c{n6 zB)%35+v+&9%>Y*g^Uj9=l_+vK3JP1A&CrxsmBG%s`NN@l@6SP_zIyOnr>XQwcnAAK z4>wh6Osc`nyyV?^5$T)`g5`O&Y|6P5eN?AnxnfaEOX^OtDdb-C)ByCUh+~zSnoY)a zlrzA>5leok30IBULbx5woNCav6u(F0vdl7Eej11oX%deHW{#W9nXEXozRe4;?_Cwq zV%(UEZrtm^jPsCopG7bpcIacX5ljJ5TGcDB4@R0iLu=$}_jjhw#Slv^Ohg8rn*guN zPbc*jlSRNj`+TAp$%iaiZ+s+yNn5*E2| zR|S`K7FO;pd-PjgQ> D2rb6GM@{!htAu_m3YR?5*>7jjtXCN*w)EN5oW;oj!@q$ zQa3%JE$ub7U;Ie)KhVrs3k4u-Z*lE+j=cvWXOv+ZbWqYHBqfJdk&+kz>6Y#uasZ{I zr6qh!RlJMI zCz$%yJjceyH@NzIhy8xLn<=5HCf~3BJjc=W|h4AYgG*Z!C{@QnQ)o1{@ZJhkr< zJ27=s6~e4ibNrUKz8;}E_@x}l#yCOE>DXJ@yMP@uEjZ)8O#px-4{ zHvp#cOQ22_V=Ua@{^;O^L(OZ>9#`oIsJMG8Gjj}cM9E$!N~xcZUfpYQMY zuT(btBL}ned_tQ|TCzB>;^KBJtopHsn{+fnFy6t4XHW@Ejtn84$zp~qJB@qur(0cX z)A65oT5kJ&7LaUK^$BA3E<8D9oFw_=_A{9CasB3_k+lQa5C=hTJ>knlP}lA}`EE3? zp}W$8l%8I;n1bF>Fj*-F)k*M5{-+iE{s5t@dPP6eyPy6(vuJ!~JaD!Hlh?>1vKCu| z?LMJp6)fhc1!S2tE9FDm8uC8WgS0MDiLwC54g0^(>9JkZwh1c^6OP-Z-e6tBSx8KY zSjIa)Yp>Yq4Wl~(f8Db6UcfP;x~Hy_aN@E1UcY}$-sR*oi*9~J*Cbt1wxsNSBJYD` zgd+re3WHgE6PoJo#*2l}(G+Df$aTMsvMBO1ee(G*x zr`MvcbT>Ra|DeE;3FTbHAdK}v!_4URK#w2Q!uj?7x&xWTtitT$`3RVq26N{un35#H zHi*1QLD=KRinz$NE_s_T-j-yh?_i+sb?kA(vc35S*r}0HK-ZaPC-ctUot-~ zIc^=0Sz@x0SUFVc?GtyAz&K*q-X;SBvU6fxRjH{ZaL?8P5e0c|}# zk2X%)X+V82(`k7F$r`=(dKL{`3DpL+8n+x@6F~@>`3+<(_6s=1;eo46ghruV*qGJK zTLxBTp>i^F<5;0n9tNt-nBJgbUuXw#H3q0DY(ybW#)5Otv< zZ6M-Jv3$^c2zh~!O=e87#!zjAAUU1K6;de5Jrso+TgC{pHfIu>Mc>k@=}8ALsVLd# zV4AjkB{R~`adP>C*BLFjXb;s^#91U4!ijt)}CIf zIl_(;ha|jrYzRLcCr^^(lb44H%r?6Q0k+0o*#ps5#6_tu4P4;iixv*=-QU|E**MyL zuzYQ3#M{7AIh*8 z>rTu3IcsX%%D@^w5Fue0_sNXjx*;-%tsqNfbZD+SfH@*TBhf>sR>>hK*R-Q z1Mnwd1d(at_2(u<8{>HWH%6py=lcnufBrqIz87nwbzliUk~zcO$x`&{!#U7dn1B;h z=)>hp)T)obKfHB++pg*=c|1?ReX4Mv9bSER+GBrQv%UFlKnFPTwN{KX1GN1)S`|f` zOiGP4w}zbdZvSBna}J#|9y=*_Y&fBPYQsuNDZmUB->f_pz|u1%lmZ@cE7pGPA)VvU zqo$@gs9`{*D_)c7%>E6m`C_}jR{5!3m59OeD&OGQOg4D!p&cVi(6vniG8M^utLIVm z-gG;kbx7X4s5~oH3t;1xw(rNdm9QD$2>cXy!r!U0U-{B93 z?|^h?xJcNKQAxHt&uoGIY-^nu|AnryIBUj}0NY!cJgCuf6vGWO*V!|oBMEQ_XsuLo9mmqL_NngG-g}8V?&@5;L%q+)j8TPb4i@_u z?sz=psez{pFb0YNrIwCx>=oo0oBbpoTi@kb%O9Cag3ZTVqKa!$p~{ldl}sJ4Djk;A z9u1kc3^$8@k>I)eP2|P!OFA9o;7%>cU>U^o0Y!zgqTZLqe*FX_&~@GW^Hzwhpid1{ z5UPLJg4&;%Zf`?p{%&mGnH?q5f`?aUKaS*_0B)I?Q+Q=@0}758kHePHQ0Z9 z092k1t;|WOzI4XQFBFI=6nz!eD>)1KcF|r|`GqIsfRG;V1bI#>pRiV1Uj|#pm#(=J zx$(uanZrKZmX|%wFIP=0=swG|m2|hceuPp(r`mA983oQSPw^R0gv1p-pm5;Ta_$w3 zZ+T!8!qrKfZ;8VTB$6gaDpmvG<_lshjOh29^9|EnFggoItYxk{xZ6k|_xK zW5dyk%!#FJx{8m$zCnuL3%~oK%LtQ3QavTQkuOr?m$Q~jq%ZgTvSuR#iZ0^qe)AQf@Vnylkdqe=h7g{jc_9dm^t27DU&F2qX6_<^o027ka7Ey#VX9s{K7u znVzJD%2Tx_(@C}F+^%;14gz>$I@L|E6|SijK`U*aHT1$xY)2)}`*u$K?6)?5uLX+t z5-=!uw88jBz6^dILB{LY^^T=xlN|I@hq_%*?BM%XfRY=V`6RyZ4y|^Aqd}W)rXo)h zLid-%x=i;=4t71BzrMLQ`ODXZS`(C@s7@ritZ023!eeqo1PskDAL)lJ$BGJ z>8eii+MBt2;%~dyS0S%dkJ?u@Z&OaRSdCtbQ<()>%j+Zs|PwOl)}XV(UhyfRr>!oS%+a7p>xe9%hI4D^ux76UA;M zO_vV^SXvg<4MJ{h0ObHe^e?Ul#Mk3meMQvZUDaazjplCTZ1sK<{mN{thbxAZ?;whP zy*o>-&wT0#MBS(NVtj_vdCM-vgn2(#AqY0$>Sv2Sc-I`C5jm4AyrJ6-gMM)xNAp^} z@JR@l<(hSrax+wkRKfucbrsqBoxS4CIGuddqvWZIZ*xS-OXMUN#?v+Y0g10-`O2y* zr)t1WSw0(Ujw%k{OJ#OL=Q+%8JIkaDGC+6b?KB**<#aZ}8>TiQ%I8nweOxPsQWh^F zZq9h3ado^Q$AA~>)%QK`95mQVIt;X{Bq=hv z;}(bo{9ZO1r_9Fd?abb%{Q)Cnpkv_ie$(&~4;h)~1CP^PJ-N6W)$E@Yh{6u{Lu{RZ z8~G$USXfzyVs(KZE95M1E$0!JGueKMew0gAH0Qrv{fvy$LQtQhiRM$88e4m>rq-f= zwE$#Uh|#MTDL3Oyh`3$h$%Rw5E{QUuQ|I-d0G&!e^XJA+>x(P{BmJK!lg{&Ph!gFj zIx~hpP-VEH?h4fL!4UoJ?83YtyH2QRTPEi?%n5bVC~XtD`LCvfsMxv--vHbU1k7g1 z)aH^)=Vc&&EnW=VIumRLLZx07Qb1pG!N^v` z95F1VkEsFn*yaD|#3KJg{98K4JK&a>@lk>a#hj}x*;YfksJX|lD7XyM;~K3jWr zV>lrkAwnxlebCG+%2DD!_Cmn#S>TEvOjTj?<5bAU!+OCFt`ltnO&XSI$US;~rq=5( zHBJ`s_PEwO(d0h=kq=iLC2|!6F1IxJGUVYUWh9y>GErBt^^x_#_|<|`t=Co-NvNjG zgXdHU4SV%oOEPXuUFPH|M`57YJKhMnnu!-49Y@mXeG$4q`J_JIXEv?@(wAQElb8Yo& zFB*PVYH>U<7=8MotbAhcy&(2zGh3LA%bkUBl*r8lA?QA$^xQ>gOu8B!OHu8~sgH~8 z1l+<+Qflg*&VI{nITdExAu5Uwn3#^@tK6jwlJT1ziiuaaK5MB8LlfSmGSfJ=#f$tK z`-l6fq2f^(??3!)Ag^#-E^vZyBU>ZItXmNk&79`24B z50iG@1wa}ge2n_kM|z=inoBek9Q^^@&M@69pnRR~|48ZAAAg3zyy!kgQG4#=oXods zEgJ`oZ7C@1g7OL}4Ym#AWfD4<_Hazd%ej^d{FRn{_OW{1coa`vp4U{FZM`p)`^P$k zs13hwZpWr|A9eRvcs1#4;1+tuf_2*mJQ4v7ygevNlM*Na{RI(G%!kYT99zWrZ^=E^ zyElcNH3`xX8ws3$P_y7!J#2fuB~!`h>if#(h{Gc`#Ye$0MWoEsZ0l=dagD38ia2hH&lOIc}4&{B0kUe{I+f zV*8Oc{JXT=R|HWPOTH1ErWFWP1%;u%3|xsLiI&0S&bAe2qJ zGqu-)UsevBJW~j3N%mJ6`Ws7s8f_Iy!|agG3Jv07cYN`wXlkI;c=v+z zw2X&ZOBMC?^RZ}wqqqI`mQ}%Wf4J;rxO3}%$B=uNj68Q*wWoNCv#l`c9H+yuqVAl}~=wP1^a|0j>M6lQ>1 zUgAx^99WX^J(1~_LufhUoviq^b4~7lW-^_z*|+6by%yu$8I+)w zOKR@Gq1qToY|c|};7$!FA&R6SHMRr@F|{q+ZX{`_$1!74=SerKB;BIYhIxpVMw2>~ z-PM9Ba&)H2c(OiqT~%3tsqczjaM^}AQnoPtb1^OlpU+=nR2^t9fp_T&=XmmP2@+d| z2a<`)X$I%?zt4nc`^}UMAJhPuMZCRa6eS!z&gb3e#s3b;FZx`~bTG1eI*>Ab@JVaN z+?DogDQ!v*-;HWq>0mZ(4V&PF#>Oi!381g;7c;bLH^x(j^OWSdDx<34n1>W5&KwNq zub*2U)U`aa-}YM>zPiA)Mg9~Qb20GtL1?7B=1TcU{7CnxO-*16eMsCaS{2@yaG28c z6UJ+P1#CTy21>1ySf+w(?xfy_(aX7Y`#>TF@>CTW=usNUYp*&61GS*lpzRw zSP67_;S}GJSWF!LOO4UC1@)b9j?BSDd5QHebJmy>Ofc-7O9!UTbnAfu_edbU3)%4r zPi<ln31EH0!q`-Q!k+;ndJWbnl2j77{Y+91ZvpxDu z`}!TjUBm}X9cGYeK{x?P8IUcjs7j{|@|)R~kw^op3C2e}R+_Q=dyMq_svn`HiTQvi z6B6;N@5vKvqv&zkm=XdNhmplY2P?^os?GI#Dnod_tjTPb2?2(fOP(uQ z(Bfb&_-PSGE;Kh|2pDB(G+y@|zL8(>PZpVpW)&1>c=h2JAbBx;-cn`G0|zPM|F!Bd zJyyz0+qCBH=BzM`@w%Oh=cr(nXoJQExUf0lLSYA8w)qPoEn-Ux6$sJ13wbDLPInwA zg-l8rpnfvHm(D#B%}5t!n31EEp{_J{EaOhP2&h) zgZxjs#PnFb5_IxiId&?B#CeVV>Y#Pq9jRI_UR_0BV&U&FI;{D z-t;{+fCt7;{Txzb8EBS_w>vT(wdeUwO{GCH75Rh&-80;;!&#see!r>$6U$McRb#Vs8qjSiH&{u|8CHJMoKh?Limvl76S>X$(8OiH3iNO8 zy*vNFP{ubJ1nkt=_}GH&Ag6n59sIk#iiK9Ut$k4gP(J2*_rh+6N@B(Plrf1#@t9o+UQ7tCiaiS z<{qJL7OxkYHz}ZdHM)XmA;e#IPvCIi8K)EfBhb>ejt8IK3yy#4aRPzJgDP|+Gifd7 z0>_+GeL648u)NMMGXvt)oiBB<3$h=CJ@;}nC=9%gIuQuay67KseNoYy6Vl))-vhDW zD~Z3(4SPLC5jATeHu@fKf(x4TUcJFs{P-X%5gRpxQ(ye?L?*#lf6aqxs@gV^2Bf-l z>yB;pTFFlW{Rmb%Z3I|UlCXQPYNJ*Y6I%S=gcl3Th8{mh4=%!B(se{@IwEt@Eg9b!_Ynd~==Z08YNQXsy=~B)bmR6Lf_b(Zf>4S4;{rF)F!yPP#Hr^d z7G~sSgAofkWaj6y=&ub&@A@40Mdim5y1?z}!j=AWt{ARbb91X{_&=`?e-`Ay58v2N z%S*d0$UUcLqQGs=xCTYLF{B}t2~G^trifG5J8Cw*t$Eym@zF&)|3N_UWgb;BCZL6a z!AFY^a=mR0cNo%Q9n{bM-InZuW^r7%M_i0ITN2lKW5NH6&ie1r;yp5^A@={1Qbd&4 zT{JZUmF_6uH)$Wn!#L~JBq*P z)TiX^J=zj0RT<83)!|CI?vqnA3|^waQ{wRm>-53c=)_3^2Q67`KNuk+U5QI(EcI7n z$gG~NZ(1(~7Bw*T&EOu7W;$l+^dhG}s6Ff5cWDiyAxYD1LqWnHtE;*m8h~vkPk=HL z6;nc%RK@*lPxUnY;kV|8(4&`7WBH~DN7rXIm;6aGa1cWixpCRvK#UJrMs?Sg;fS%D z3O#?G=+k{u&*z=1Alvfll7;uPMN8dNj0^Nl!-|K`s)3wi``)LlxVFF+uW4DA%pmly zilw;V+c?q9xmRf}2L5-(h(R%(tP0#F4KiXwt-QNgkX-);P zQM+eedXmbx14<5_K($g!@+y*Ej%Hp6|Aeg{du-^LFw@o4thy$+nY7!EpnI!Hn1xS@ zksV{g>kb6RJ!4!9KHKtmn8y_xh_M+reM}{B-Fiiy?sJfaxZZEsby)PO7+ap404olg zx2M^a#GdqhzskS|t8%V|U(a*vq-R8I8%)325@(QMk{JZP|D2b3qCKVPcI{tMBSw)Y zVm<2K6+&Ppl!DXFjHH3k(C(K|@2(aO3;#@1EC|yu7G!u{8D*z+_N9B5N?Sc?((>v% zq=1+dQakJuwE%zA#=HA^qB6~^tsia?CO zY98}dyWd18XTtJ1DrlW&b9<+dI_b78;Q2XxG7jBGcd=f%AGB<5;Az#eau707)?m+O z;~50=wA4$*>=X>hV4rbQs0|*90-u14L>RZ+D;Y`q?N7IF3LPs-o75@j7b~MsXO=0q zIR@Aqgv2HDt;sr6;@nxn?V`x{6poYxIlnWe@GU4~BwRM=_lLwN5sv!t` zAzY2mb&(IfRW@gC@((HcDV_F`g4|)(C8uh|W@glqco)@4^@l+o78I`#V0_R z%@~ul>y#YiFn&>g4sIM2FY0iT>Ep1kEIYt3!A(^BU=1TPZj8~d~ zTCG*j_8(Jy`qYM|zC4-dFZ682*;X4eTH&_XdEQBa zufg**B3i4}W=IWK)jQeC%6=U^a?c4MJ7RnjHP*@_t@F5&rDggzn^5n>x5kdcO6O}> z9f7)G+9UGjSEW@WP@KNoB`yReEg=$CJ*>hWFM4Y8$>vi)RGAL0V$Bw;NI}Qnav8`> z-g4TRM{eMGQWvu5whs;7zde8kgCIM52nz3=reLqV0U=p`cOlW9YVruNS-DRFF4ENz zi)#ZUl6`h-A)YY5yydKh>Qg+wMZ{`Z(;)2g+`l^v6w8*}<#@Ph1vP?D{50VT^AD(P zPx%8-V3I`7Pw*W7vL)pd>%_sdp7wh~0lGqcK||~+fv8oCJ+jZ|9dY>8k)rL~1R@f3 zYFeIPFh0FKx6SB`RGW2m<=-&q%pE?rBGgG2cij%lag!m_j?X+n(My2|0&5lNdz$NtcHtg}&663gZw@>IPUx5#6}#t;TLZA@0H=^)u^Obx4$9 z5>5?L;wGhV9?@=l*r)-p;qre&2%bNu$ftD2$R#WH%0N5wNAvY~-95V1IElzNye%)+ePNR<>tn04>PN8n7${Z(Bo%5KX z&Vq4pZiLwr%Th)VMJOVn&gx(S=yhIomUjk8czL_9|5{8efDsMdZZclO{Pp-#cTqhLZ$N8`-Tfyp?x((%Df*4hVWt#5>wHc~$8fONcw}wFSkL%n@fN@)=y;R$18!;}5kVEDuK9SkL*uy}bvxv|TbVbu_fg+pIlNX{&y<&?$AQ0h ziN*#;7P9f3l|O2R?()GKQ}Y&ut$Lh%>Ev82+AW+a;iPi|ndOr^PD=Rj`7_}SDSe!iA-R8w*;pe0sgN7_GW;2!;k8zRM2IAunF zGOXXWWKcX0F?=dY)rx5;EpdTQaCEozC6#Y)oSAT6s9et1i<7=JRo&kZv9e1B4_Dk5 z`2Jh*`vUR}siRYDU85Lw^*GqzW~H0F<)*Bgg7J2z6Vc5$ICeD)mzeYFJ`J|N3~eA^ zyqplCU5QM+rlNCC4}6~F4|7$y(#AeK9sV04=1FO{DvPoXT+Z~ZJuH+kN=NPQu>;cCrZ8z6W;^dO!&nmbVcBP8wX;&BsJU4A=QoYj{4J z-*#RrurBkU7hL@D>RjExq<7}|7BA!!*{(gy6Xd=Yzt>T9p%Y0<4tts68B7g5lkc)3 zr8_KcgR|=yY}vdzd&6KWwp=t6?F)m%`Nm1!H&;67KdB#~p)a6TijRB2;PlQPEq>d* z@NNPSronLitGh-VX0*#ET!CLNg;A%AU(l6Fv1*MsiSLEmyQ(}=Z3-hc8J1lrU}&E( z_5Rg%vKeHv{FXyUSwCMqS8-Uik8TL6oJafSM1+s90vRS}Kqb`M!0$JwjI5_$-N217 ziSqJyr3+h`5zE?GVo?!`pOl3J7RI}iN&u9kVBC@s9n(obi%H9kxYfj|RZUp{SK7>r zf=wnCSl{pieQ);ZO`ga&nBpFreVL#GcIs4apE|O%YfYwtaPFd*tn_~Q7BS|zqzx9e z*}TI194u>Q+1%x3d&IToTDakKtBc|d&aZHI9*Z68>OA{UWo)p1(#cBEo(geRT(9YB zJ5ttb7?qrr)V`|2+BUqb=drO!&8mWL8ZqE(c>HEXtm>OBTHYA^6(*1T-Zq_4$(0*9 z?cotuP2r_K9;I2=od#=})Ulm&jT(aVKV8Hlg@+h!c3ZA%j_W7!R09h7oB!Zcyzp6g z*qOKPHROK=5Q?S;m@VH#gBRS7cW~Gl<1U(zf^a}(66V9dt_gQK{~7rn*K5@6!bf2PWz$tZN(w8jN|Ol zpApcxnErrzold>0hNI2#*|Nm0EcY{N@sXML`k%^xJ_l{Y=IxU_6O!`$^yzt?EDCTh z{e$rI1g-_K0S_F0F;?j1FAiWm$92lEGbNcXY z-rviaO<7NkA-&W!ef!(p@llS_L=Ia1ef6LZPu{*n+Pob2pF_|96)hEA`Tm7+u6Oyj z*ax7Lh59Af)cQ)M(@A0DOZ(NKebxDA)$W-5Hr|EFY*DItdIN_{NFmo&n#y|A?YfQm zE050}AAV|^YYcy&_3%I;fSlb63C0mrq)^l!E)gvUz27T`>m4ZGU#LGN&WH7BU!vjV znJtMe=bbGV25WK32EUHgCsiAFPoaak_?@Ot5E(kkzpG=g3Rg|vKpk~te@=Q^%@V1! zI<;`{Ee`-JkB(l*U1+CXFn0<82_znkNfzAU|HGyuI@y_x5Xk8Ns=Chi_uu=Pp`t?6k9g@7HFHkkNa5U7Ytreeyrc<*dA4tF2M8CLKH-eeV*FdVI;a^_K4xy? z>VoBGC^zt4-*WsuLO^E^x&?2{9>4nt%*s>I-({8{0|W%$3+k#N6A6b8Wfro(>55q4xpi#m>ObV+3@FR`A8m9Se za5KP-)i{Zmp8U_$!u{GxH%jXcjfCqL!Svt%k<~PDyhw0%-SI&=V{>%3^BV+!B@woR zoGWqrqSj!r>D~udL(xt>3w*xv_(4*H82wuNfY{p(C64|Z@l+y z;TW00Dv%5&DaJ$`ZO=C*trieaaBZ9 zTljM-?`KhDvc^a((vm}c^0gI()m`(?W$6kMcp5^5qUsCB#R4}K;^4@^RzvQ5>Xz6P z@J%4W;(a+I)Q5If(B|sV(`pwoZ@RBgm*fjnTdT4^lRj-6C7Xm+R9G-`dT8Qpfh~16 zKd*%*pX2D?Z?no-soefb4*Q4E1RR!k=UgU=*H`~c`kRq`C4aq5^$b`P{OONGr*9e( z{Uoe~=jXG+eX)gQ!iEj%@Rt#so#OXhoBJS+<8v_;l8=UoHjZYnR(jO-9)11Nqb_WZC9QQIF)J zL-kTi=VA&8?<=z>b{DFu_!K8GL9csI|8;h|ro7Nt#AiAyFkhIV8C=iSjM*6gm$OC8 zWg5LI)nWd&&d#@P3C6U)?VrS6uA0*&=sk8Ach`o@p9+RwFZk#*`z4UXRcAp<#Xw_r zk$O|rGn5QHAG?v&hYhYeGur2CQ&pZN3V~Wm*$Rc9udqAFOy7ggS23s*FFsFcvgYg& zyv3eFb(RROr$`^=Ds*eL3y_rgp35x>G&QsKV5+H*?adzgGSkj8Hj{L(T?Fp8CLHFc z@MOc%$ zCI*h3w$Dg%c7U1zLjEENO2KM*m%~a112LILY0m~$5?!2XV0Dc9 zZ;C(_uv|Zl`mFfr`cDlmXh309ChhgelIZ;|8N>D7Yld5OyIS3sq#*R0uNJnXH?0v6 z8`ryf^!yVu)8pfvGZ){Qzm8giu=hoH#4ZfCQBVPJKp^2yBJZ$*VEm!!tRFL8$D(kF z?^}aAjmRJAND!t`ACR=$bUgk=G2<@w`qF zoX`Bm94u_E{M^}W97xC9@cp5wRJbo)!s(5`Mp ziWdnk3L}qC{Kya2>PpbvhR^e)N)?WlIfMx4ARilF*(+lM&3D*y)T90~_VsW--|e?8 zeNY)?MK7E3_%BZ4e1cgdzKO`YZ~vgCC?)WLrI2~16D*|5w64z5fZxg1R3@@V#p|10 zfrSsprJ!z~V*l)Fo+P~5_CBZoI|-t2==Z8pxvc$DhmW+}L|(wQgf8U@p`Avi{L~C& zxM2G@tvK4v;HBtVGo+oa%T56nPJ$%?r&dnS^?Te2X%>h)1AeL&Z}pbc?tao)HOqfy z?q-9kMs&l6_RNT*hEi2$m6AQkA{=N)kSwoHrybo*2A$1D^387^&8g0)T_z2Qdb__` zY4gD2h~wVEj?wv=)t@t95>y2GfOJPm4~RJ&hggJr+)1+_si9zrK^!Gg|)=?p2=k zGcO@ia%(j+wmkyDY}$kWA_9k|WgXPa^&0g;2U6d-*Po}c|8N#t%RIZoDE#^GZ$`T! zAib8W#odw)RR>!C5~~|lKH2$lAieY4smmi7sI#bQm-Zy6TCVC&#ACI84l#yKTH@=j ze?N{;&J(;Fl5`w(r|-(1=Oly-R%x|5__46LP=5cVB9pKhOV(VL^SJS%U0$eYeRQei zdJ++wep5W8;BjE!xF3j^T2D`dB;_-fSs5F@8H`V7F9sygYgV<@VFVP-p7rB4Do!E(W z_9j#hT+0MV(;|kXvX?7pS%4}wZ z1PMTJNnZwUp_aO6Sl#MiyY36VI1QOTeCsGt`zYyMe4LG)s%UYJ=+kJ7AmrewP#K)e z*XSALX8$E0>Lju7MIj`KVYdW+V67qOA~P2V^51NXgNq2s_4o!GoV=E05f-sld?usx}B zOIg+$l*Oed&vsZaBT`E&39$gZStPGO@}o+OFaJc^ma;AZ0VT7}w`qO8M3qHlXy`Ze zf_!r`n*DHmp)lKqm>@T(Yfs3v z9t%D1WM6<>OPPy;*m*CbH8g=zjgy~@j?Bw8tX|6j8j~M9Ri_c->aZ`wUs z0M56X&sGn`FVJvZatIm#=UkleYZy6I;tu_4Ba0Qrh(7lDrr{8&(=me5Fn3X{?C1Ht zKmN3bY5M5o0@3$m08}4GGFY>U*fj}2fgB6u0f8Lir7m~&X6W46#p8<$(mdxb&vx>A zi|pyt0iQaH*+u)3c>Z4e&2}zL8h32h?NguINP{pL^rM&x9djdMU-IZCenNhk|6!2K zT)GPAH^1ykccFTDlGcZ0hKEl_D9c0`)d=r*w1BlB%ZWZ`=kT10_B1@UGfsb(+TLOZ z>Nv0L{4k87^dPjD%K?SnoDhBI(uas6i74=LeFky*R|bIx|2*Ei94uhN`zlY12Hr&Z z*db5L8lR6t9~M9kbp_#OE<$9l`PgAQFeU2xt4F@r_wyWo4Y=mWkZUF) z?Q0&6{qLIh!yhaOd(O7=3O{a2E3}?&xG@JAgtH%{q?S9YHunQqd1n`yPI~kDGh-z5 z&P0>S>`O5S1e{qb;Z<6)-#UHez>)CDvMni5CP(!9?C z5y9d|n@f@{=QD`0p>^6m-Ga|gD;>D5VXlv8DY~zq1KpK4O(%H0 zl`un2Lnzq=wT`b3#p04=atawhAnn8+$NY-^D7wIEIp&1f3f^W*Y) z0@;u)e)ZA4G0v^)(v!Q%@&qbug?Xuq74pwXC!5a)(C-r2k%x{fK0e2ct&B~1u$Uo@ zeZZ<+`6)aU(|*J}o$A+vrl-!Rt!Jm)q0`u03scNWelT0VL68hZ!1T$-JXmlv*-=E3 zF344V+LW1482c@>q%gP%)}?v=keMGFHvTf{NCy%D;T%uAHsx|@q>!q>R_Q76j9Qu9 ztiK_%-T13^UNl&8hN=#|Em+*_loTL`%5#}@&kG>OMq-o=EX0i>tD$bj;^rE9Swg>{ zs_P?QbSrCVFvxtTVr8fKYVn!*b<>C!ii$S;?)V$oH^ueZp2LfZhio^Q{?WH|zo%Ae zt;ghB5RgbKSro8=OFHH_L?mr&(vpOUDZhw*ngu`*p; zCVy<(Dm7?m;%}!Fk%WjfE-1{n%_PG#j=B+Xr2uC9%jY=R=&*GeeV+^L{JZAu0%phW z5jVN^8&>gNU2)=>1Wvf;y^7%Yy=F`I{UXqb3f|#7=Qiq9Sb=G%pIzYqImFhKu31u$ z!hbVX-g6zR&$yM>VwZs5q`U8+!$j?)U_p}jN=6Z}ox|i*$K?S-v1*fz0pY0SIv}O@ z6w~mHc_S~)1S@>7m{0@(r%{ zsy*Y0W!|vy%}{j-jFGk)(8@@bgw%4cWe=w~Em<%3F*IwZ$FK)iKBGcMbw+k_4V9E~ zfh79R{O^ypvZo2~`AdZV)2JSobYM4^LJPb+JF)>!;IxtXm#5wYeN*Y;(f)z(!IeSM zOTP1~MM(D&p@H-MQqh8kPMUjHwMwKez})q7CK)4r{Qjj$t(3wl-x5^quF(DS&waa+ zwqB;4B+osB9!;E^J1Y^+ffJ?)gifC}MUqP<-k7&NPrXRatI8x}Ztl>^AN}+IEiabJ z(HQ%@T1iv5Jb0}tg9M4j{4$tF{$jtA{ee6h#28$if6YEi($ZTp&gR?mTFkqSt;Ka5 zcrKsbrz|NDw#}NtV?9zqmupky8BGzz_I!(lYY^UoH{sM0IdE>U8kU2-xmww9_ZwN2 zAq5iNmGfI(*;{yP+CWLO?jhGa=R=Q9=l-+49PvJ-hLKM_vAvSS5PvXV!>1U5-7vE7 zlGo0fG+RghdsCMhy^NG5O!UK?boBg+gp%nggROkF;+3qgOn_=q*V)RQ z@x**pcdqTLb{!}est4%WPD=ZoYt35HH{f0DjeJG~GmpCOYf@)txK}kjKY4yN+fsS6 z$-{qG#Ox?yav@0KEn+2?xHgXwhcPsS$RE0 zXCW1-Ko3ns^mBKLyG>`-f)p|ldi)N*SMK;z?WY*-PElK~{HUwN_3g>r^v7+S)!=XlaF;v8~&Zcjl!HTT0{9kc)cNM@Us zOo~iOI=ayP$pW+C6uE*==E7_7&8hFW207!0@ajrjF)Wu#N<%r%N+m~>h6qk>bsWHP zZsDgze}K_zBc(@&PBk&O->fkM%TCVDQ)!u8g_Zpc==nFFp2+OkBeZh-$=e%fd)p=q=oSmO7P5(XkdsBeuDWg9AQ~&0b zcHXzYd>>Igiz2U^sq3WlM91#o!QQ7^e<8v8lc)pO{Ypb6eq}Ie-&QlUZrB~Hfj67Hz^-Mg{VHYKdVL09AP3kWad}Y@GDPol z8pR+#U^K{OTBD47et~jZ^tsrBdzsS-)G*p1J;VjyM&wrjXIDr+ix!O)zy|?$8e}Sz z9)&Hdip6?ekVT>h7g`=Cola3e)_E&P{VV=In$E+Y>i>WLN=R~4%E&lLk?hT}iXvqs zN!B@L_Fe}EnI~Dv-ZLX{?9H){d2Gk#*xSLuvA^g2x&40s!|V2VJs;QOy6)FmnRfb3 zIjVK)HQjfJ?#uOGZovau{N>o7i|n5l-82n3gvELf1`uTsWp*Ho63J{8Ok+x;#I4+h zDtWv+*Q+|#b(38p=IHNT#h$(GwD;a#srcSc81!Y5Fn=)WxdQS{r&^_RUH!kt7Wx^7 zMPdEOls4bt=3ZbOpR!(0lti~Crbm7Jz3er=Zpiwr{lNm6e+Smu2~DpJ=}oo@%+YdE z>0L%jD~B7tFb(t;J$)6$QycW<1h}V7$0IMD?c5Cz>}I5$mWrt4ylifddT!RXu};p< z@N_|Tdrv{nq4cwJ^>db^o9P`aEa=@*65b*ThGLnfXO!d9%uHonhNxyw0hbjP(QOJI zzBs^sU^c!@d3@T9P4ZMqF_ze!3RTQ)WfrDmzM}tgAunul-KC|_ANOo?+#N{R_N&JDs_SH7WVN#ywV47rr+h*ZYLh)w-ed<|8 zPFoyGtm)odr56Q#PMct zU+*py8W26?7olx(SAMcR&0zr=C7XH>m)W-MpA+gv z%Vr5OwIu%n;dC0%Xgg&yh~ao?Qp%q2um7pBXZMlF=e&rx5RRGh+sco>N-IaNv4T&Z zf>+|{F$WOF7Onw}5ri^<8r}L8Me}9b?~gYsExO&P4Sjne{dGY6!FP_P1qD=PS^9xt z#_wvlRu#yf)^><337yj%fH9V^dfeO=6ghr>%7^OD(o2Ik+C1upL$p0aga^vaWZsr%s~(#E0Z+)ITE&-iKR)eDg++As$!ubwLMvYdg#&P-L97f2sI0SP$90^u)fI9cM!iM#j8a{2Oiyvf$zqz&98nr|zYh)3;)=Ou68-CTLom!)I;PjYlzRczJ@qWYK zvu=sPaMittw#B)Izn*tDsr#wbky*6kBUSrl(~~u0f)hHU%$9H!i$7iKLDJfHq3@aD zfd^6hA{O*{p3O7{VZ{d&VRiSrLUV)&4*WhBOF%go58zw<#CAqqiKNxH8;_^xs%(YN zG&L@1npCUU5t*vumKqO*>m;XCEFhLQ{L@Q7n+8;R%n&w`XD`@>_-U9Vk~y=T+dOf6 zwL`fy>E7dTgFg8+<0&Tde-@~}>-X?^ztMoeV@e-w^QFN7whr0*yVkDYsMs~iOXk6} zrY8>{b^9G~PJro75tZ6qm?=`^pg0)+mg{6D3`XDyin8{n1P4@m?|SUH^p z0~GDvGr08lpLs%2Vbx9l*PuAfAryIH~xo~{L_ z0zpPpt_WFI2OHD|_?EA}fNk_J<4hK+HR-!c5wq zMM65?lSno`dNl11q38Cn+_;|pTl^voVjZtd*r*2D2L}rVti_d;NYe?twhdp>WM~M5 ze9d1J1x)Fr@^#v!KK}k!)zs8)EvV^3ZQK#Sd863-7ytH1@)rq@r-=r=q&`WxVe`(# zuMCS*>wdKHhBnaOJo&hJm8tH#xt@ez}4x@2EYwLQSp)#zl!jgKBryo#p zpabh6_9GrmYo||Kchk&yZah`W0N2tTQ5l`K@>#~=+t1j>gPPqH`!g_22UUc3i(kaoNl)H?)|RKL^x96N zGfrE!lYSMOA6z5Y{f*yTJil)%fphI?Ykm&&QE%b7^FcFx!F~Ge2=-5M@TR8=BN2`y zaKeuICfpWRW|9@kFA+m;eh@j3({F5?-J;PJvGaEb_0vK7WLY;flB<@ZFA>@%38AEH zQe_!xsnZxAJdr;er9XI-pMJFicgn}L!Ijec%>9=dYWH@;flV9SyV4EUy}MnRt<}uC zzSI2yrk$ZN3b((_>w|BoOTU8cRu2u1eMD}*${yizVg$VV&TOlIvq1K`WEAK@KD?q zxM3(hcbMK%Sec=*3TTsD#JU+XXz#`*d#hTG&AB*x^>+Elh#;@r!iZuF#Ui$EL}z^i zc@*B7%1ASJRVAHq<5$flFJn|9dVl0}gy$Wp0&uul4Z?sc_;6eOWxHPzxa%f_2QyBoy<(7@U6&Uy+bw6 z-TFj&1ocEUWYY%!fT`WYRTv$Ck8XN3>N(f$OLoRFIzE|@>fm5mzHL=nGSym9xjghw zJC5VG(UgEPA5A5N+DyE22EzH8SR_sGo}{!<+UmNcbh~BdyjL*QSN!PV(`9Y6tMS!D z_*j(znjElB?*4x3t1lBjjtLo)?DKwlN*;A?ay}HHgq9BLab^9L1DmckUKYDT*QCha zh>+#kf$C4|xi+L=gqxV$B`t*_h0-@`gN5mo+>Ex3mfU02WuANYvL^Ii-K)VeKXF!- zdgZ&j=Ch0YAAY`RC;!wBNbrlR^KAUzNiyIubVSn1B^V@=x&RGvO(IWx6aA1S^|jJO z8(0}h{zcsj`!73}#j-a;E6G6MXgi^`i{3T2XY1W;fc^S1k(IT@eb8JHfI4v*ZP9@7 zZp}rbJezpmk(vETe$ijcf>!L#`rN<;_9D0}_e8gmM9VuDqg)-AVO-Ms%1DRL<}2ql zKWHw`_tx?~rd1kLy6)&r{+-tzQRw~k_Qia$KfW~vJ|0At>K?(HAnhlVKM)f+wBmGf@_euguBGe2(y3;X%_)L{$lwZ(v-7Tz0o7qOY4F; z@2d-M*`xD`3KciAcvev#2EHCOGQwvx@JNUz5uvuYqhd*A9EO<#n5}Z9{u}B!%YM zuCL)XYBsYL$lVhG3+Fi>9x0x73Rb9LmXKku!kvE2H+#p(MM_^XXzbPijF1^X=pK-X zS9eE3YmRcaXdwF$daEC?_OOK=I5Gcx?$|IGS7}M>1p8bib2gR8SxFF7)ailSO{l+VgDxOw1bq#lr!gbyeh2WpemkU3Kzw~^G+l^p5C3W`KZVKY( z)Kj3>9$wxVdYFsRZeEnA;IUf|qRMg`l+`+~j8?twN}Kqdfwq>~>UP|OLA_jAb8*%e zjFTHb)M)o*sICVqN}g}wFQtss%@pJfZjb5gygv14O@&pE`#Ly|It)uRK#;tiEcmPK zoTNj`o0`8(&4E)v^HW(tjd^&qczr^tH}YJusp>7#1XVbp3+HV+5O^?S!FrJpW!FV`37d}j_3uCykh*X&i~01_X)%TKO1z$rBvc|va!2}~X8Orn z3U`#HWL;=uQ)bCzSQ##-D$gLhP-a-uEc*vW&%W~QPN-~x!nt5Y;8f0d8Ne0u4ZZi_ zOUO!1g>%(X**@|xvK62C4fVlxBB2rJezKzroZ8Pe*}>Z$>Uwwn+04Av6jtt*BCnBxtK1My?WlX_o3P85&kcEvDJb!bq-=&>vA4=OxmTQFGSK8J+E^6jL2S{ ziqc|71vSSF0*X)9B&~SlLD1SP^MfLui>C>Egr9{KJpo=CwM6Z(+{_j9nf(KK>hfM& z(?9&d)~ve}fag`ZipWr#9{s0cbV_2mMwvjPBuf(|GYoWi`q_w3BUWLq#}9rGbYS`F z!Ama>Zkn+V9=G%oa$9c9ZJ7eE+d0i0x4M4^iHFE^@UgCtnXP|)0*4V6_;&byCa>yF zX$tuE1e~w(N?Vu7s;dZvI8fu>)E8`DU`=tlK{BZ?^JoSz6-;5~UnRU(g^w)~<2*_K?c_ z#Qi)Y6%5J?_cHTmALoAbT4rT4gDY|eGx)JO&rLTmIf4SIhuRF9Yu8#URL!iWyW4v_ zw32iGzf4oeHUjp!)78*n>gomGaUSrUj5cD00yx}LjfY$=4X9oOzz^#d*y*!J+OTue z_9+7{zNqtENr&--xvl+RzQ^)Ce95{;+{$Y1AN%CJAE++!l8X~?Zhu~ZT^$p%I}6p% zSw!`)5e61~r6>yydfu}%d=7K^8&XC-rJ=TwFVKKlLJH>&6@Q=~$FAT*guF{R^ee_Y zm0O_xTU9}@^zZ;SgR56rSc+WCXDfeyir9`ozgUuZ90Ytbl*H}hAEL&&YVL$!h*1tS zqI-dIGXHZnR@O2NnzB$0*P`T_7O<#JRtEU-Et+^^xhSJcd+s8*o_X*8_F4PWP?u;R zLhqc>;G@?dj%fS=rZ6z=X1qVFC~3TXV8fIkXo!~6qk-j&6j)F5*0s9od5tJFYZ?re zy8YoDw_{0@JwYogUyWMhomBC%2uHHD(dWt&Neqv(qmNLtFRO=83hv(syz3Z=ytIDw zJLxU@RE=ljo%E(xtoy~DZxB^#Gi)(`pZ_Pwp8fChM z1v|9UUv)|*R}Ay;Q(27lPB`2-6=z%F>643PsoUHh_>=u@L}qT1+M`SH=1Jl1Wo+ft z>I-hyn-;5K3re$v(#$)+i5!p%AJL0|Uz^krc4e4mJ6~sa;)hchX{S`Z)0TIU*Dj2$ zfe4g|-~On1-D#d~ee!DSbS*s@vnh#~t{xuyXO^W0vml)+DLlv8zWX;T)*k=_oIFjN z*)s1_4MkoCS^Lu48}*zlMaqduW%yu;V30QTi+1(9*TnX93Yu%;TS8&^|LHT=)YJ{c z!_v;Ei%k{)i~i4RNTtosb|w-~FAb5c+d#=^5^A$*I#9jyX30nd_MjX|4td z(xMJH|F{0vEtzt(@wm`P&03=3FqowzO=+0y?%DZ3-&El|8`#e%>LJv@$I>NkUY285 zU&FKQ;mII>s(`T2QYyxMKt;b;=!RheJI1HC5D?m{aoZK{c^9}`g`}0uk+yH8jD#MY zs-I?y={PMjfT_Yha(AyrMyh!+W|$3sX& zrM-hYRU-fhtK8D}(Pj!amqZ^8*r^*{Z-(=%4i*E$Z{PmoDhIUE^lAXxW^oO;B{GCPtOQw>Dt506e*nl1~S5?owF>e(t< z-ndM_-|JRr%ju`#lSj~>c8du64>~`uSA8$|q*jdgOw8sG0Xr)8D<@v^#;Kf7&rNY? zVRZ#`KbOqTD9LG7N1N$R{-u?GXQ~0tY7fK{%w-h|i(m*92Gb3|Y(qB@5 ziHBz;>b2^CZ2oq}0!;E5;Obxd0FE2pyhUjmHb@tw{Z~A+9Xq1A`iAOd{f+U>&9SW_ z9ul~(Bs-e$C%S;@YzkkP)^L_ngg~$s3FqTy-DkZA-s~taczqEt+8I=CiBTFDyI!*9 z_>^T{R>fNdm|~S~sI8H-oR(YEcr&74%r^~{pPtBmMoLr5&eTxPjayq4*V&P zb^9|bo>x!34%>v5%8f2qUkliBz0$4_7Gsdi+nbx5q)i{F{p^8TA~}+ak4S0+bG`l; ze<~xj` z6ROzopIw=>lSzo2-kZ`>c%82%OiKNEOErfi-KBTXQ`rzlthDo{#oAP9;ePhcoc+$y zgrfW#J+Ujd;y<=-aQA5+tih0TYMqLAJUmLS%zHfXH}){z_cWeH?nqNkwBfQV@}dj7 zcYTTU?H?!frO(F50I9uOA0%(|rHi-r!#m7tN-#|j^G%&3)~Ah*b?u_O0)igf47&A+I|5kgD&<= z6&A|a`;0JMT^zrC8SO-2`wZLyGlNf>kqrAT}xQBDE%Ql z#&VezvNpx#DeN&uk;81Rn*LSq9Rbft@X%#^Ud7^05!Mmi_GOY~#>R4+4Ma2)ah$fh zpgTs?%>*Cj8Ld^)^8(FXk}9F=gi&669uY%VOwc1~+6?!5dxi zYvAj$$Tqo~3Z^odW4`0Zu`4zYcXX3et+857WttQ%ALfP%n?NV6U1~cu~#fhMt1Ql^6q9}?SPD;#H;a}63|coJo^VIm$u=) ztxf<*rkklTbIhU&SOSPEPmE%h7oD$c&?YIJ+s<`Gy>Av@BGPb|>>vbdWJ>c)FCVS< zYgf^Cc{K9*()*)vp%3w)C#o#dPgzOXXIncm9^f2v=R2}N^S)_Gv}b53mRv7P#iNvF z89}6FnTx^De&lpu8;MWzW*|FcdSw2WtsDQd)bL7vvg}L1-;1FtMO2Fh3-v%$rU%+u zF9OL`1#VQm9!a$=yeJE*S|LkBVgrOtZuJzAYDvx?DIGp}<`Pa}yrLiH)Gi>$VQ*#m z$GNV-6@GG?1=g#hz-jLKN;|v$S!*T!rDM?WvwB&|e+!G4y5t-aNdIek1tx}Zay?gx zUoBcv$ukp-Oq%XWN~)Vn1C80i0vd1JiL7`|3Z_XLZySLlLEE1k>w;0>%HVP3a|$?R z`B*Qrs3Q@+YGgF9X*k9x_QeZSC~g@age!9aICoi#zi+*+@pNAG*1eVEq-YTAd~#G=F3-3o4rgc6A^s^;6g}yCdLvsr$88 zr_oo1X6@6}M_0IS03+r!SwUhnNR&pyx0@fi+s~UsK86oh2Bv9_lWr*iiFh=O&khD4 zcR3;_bF{C1)h#D^F-tsU`CTWHpS7gFOV5HEWYZtT);(c2fPR02>eQ`|@8e$aE_jXX z39jcJ2bEshvdpup=n8*@X9gVq=Q&!lTu@!gx6GSC!-Yg%g@4ZDsKYQS(>7Zz8_S^5 zo)It5eoBn$*)lgOzE@0CX=Jq5kp!R$9ego2j){emP$4~~gLrAkaeQ~z z-&oAP1@< za>EW#_eE#UfXYRuIa zb;CmVko|BV-{Y~Mj8r$JaIfQBh($67B51}Y2;hof2RV1K%~w*a(Cu{5fh9axyG=Jk zRKBjO9g?KD-6VnoR=$>w^at1a2=B` ztA*&)lVz>5@fl50-PzprM<8Vi%)SLPeN_0}WycQS*=|c+^}WA`RDHuk!>TV$n5ojP z)MxYVPFj?^iXJ%VKT}*PFJV5PaAELgA37@}tSBx~Z|w?|{)m-R8`ba5nyHw7xE1mE z@=qN&dLp@#qiTvpH&2Aa@thQxG?A2da_ZNV&y0%P;))~wBwD~F0pnBIEo!d=aKDVXieUMP z`c>vSy1sQ(uihc4=9A7H`Gh!xj-;eYo?e3OTZGI9AMz)h`l~M|3+6BuE7L0aUM+vQ z)A&Tv^F|4k$=1ur=-{F?@g{gEvD3o&4RXVEwoUG1&x$*$a=hcWtpbol>cs@|3VB%0 zB852TY+$ZvJLWip<>H*2K1a zM4^X8A(Fux>%RKfL*iHAi)M&Vw?m4Ft>^geSCNSM-)F}p>xYxn$9l*ky~7pG8sGn7 zcsTbf^gJWXH_o?D%4hGyXAc(@30uaUBd^b$MXQoD^Jxwe?bqx72{&ydH*MhJuZAH> zaP|}v)9X)d5))25H$AVnd@m7gaJdUCp#M%}2kr;k>Ol*Z%$Sukl(j>k~i9%9eIxXGyEwf%bzm zk+aH)?OT5&u%(8MZxu$ByMSs3L@B@=y~K;4syi4V`${heVzeak@&^c;rU*dL@J;>! z)6EtNU<%o*UTvkZ051>u5iku;Q%n4O8d(KLto6MBT6N*CtM9+jwny=@WWR+$LQCHb z)l$Q7tu)0({O9-W7jPea^s0^!eG|={@Czb??883#&6iX%lAR}DD%ARr*XUCp9@f}D zz8KIqed?RUOf(sL3_s48G-0#J0s0^&79!<9Q&rPkBTj5hT_UO=BeNmk#M=GNl~Izs zJ}&SHSV89i@fK*{_Z+#^BjrVwdGV5}v+>NG3<4UXx$;aXVG&44IkY@{F}XZ3ZVyp_ zCXR4N6GGEInwH|?7Mh-W7TZlavQRl-uo?zm;KWb>^l7B^X%Sk*SQe;6uGIe_arUc7 zgN(W?PtrENRxBb+$KuZ`$7YkK6??!g?$2&WJ#~x4x3ve_Up-nE0>$sMM2CZ{Bo-Qs z%@3^ZZw>ZMCehgA0|0PT1#-Plhi)qF06kawBuC-cvrSc8y@Fx+N&R-gzQY5_@$1^@ z!&Pw~?ydVz{(s`kwwbtKFkVEwC)$H{oiUnGvnDUDR1K9YoG_ zy=DtXyl18`C8P#*sT9*+X3UpUF=#3z7@Ri_uA4HT%$88KB!(OTFnC#N=8 zMamKGGmXo?P9C{NH1+URxCY-7`@;BQE8i$RMRU`O_X?vB+Pb?Rk6ve{XrT{_mZrMk zQ3*4p)2NI(?4cjns(S#+biI*&W;u1y1r$3bgDm$D3!{`p*l;WHJMI{LV6j8H)e>f{ zWq_wRz_R28T&;M=J!@jYbA_2BBu22FRqStQNX(;E`vZf?A3oJmy35D}AMNEFK~$6y zz)kQ{XMt&)QOBCT0?FCdRGpjWIT_+D~V_LsacKA#Cp=aZ6UB!Hbvaqmd zHm>32db{$1NZ=b4PYImNfmA<~S|Aq689f(EWC`m@8 zo&G6h;lPB%yWtE4J)f+OV&Ogf{2tn9IBh#UNOUk+*iz|R zW+QaHXH6!zebjO--5G9cRB1^@I-EMPBD3MkMYWt69WlsFzdO0URCA6Q&pH&C423)I z2_+Q%eJRhlawKT6pbQx)>1Wq?=N(KNfZCNY+d@bh6J*O0v_=~k>MbsxXx(p<%eKIUnu-p7|ZYr$_WDWZs zI~Sx%zrOP>c`k@q=`Q12mYjTP9~a$*x}9GQC!5t5!Oxd?EIHIYN5E87E-_pX0VdFT z4aG#yi3pmlX6g1M-orLU1QP@ag?c`^JIpLf_YLILP!X}5U7N?f7XxV+q`2D9B#u5; z!I0DJ?Ir~>lbe1JQ2X8z<11h!tLk5m)%~%&i`k;VywIN8&^JI?4bW6TG~WZJJJVjc z%16kcDZld`J?8b2fJqHnrpll>J4CWGdC05`jw%mIzbpD$()GPRs<144rQo6mA?*^8 zzDe}PV;0ObR`nmGuQgp(O=nL_qzWZEMEsUe571NxR5fD10UiT_r7OdmhVFMZWsy=q zes=IjvIcIVWWZxGK7l>Y2I?0gl^|emPr>kmpf`}|+O;&E-y_A7&BH@Fk_5GL`0Et8 z16@>42+>RWWn#599?o9^9kbi|$KX|%%@O@$%S6F#zmJ<5J8-nZ4BJ;h!=Rf5oNFIm zg8%sYq7&YqAFR;t^A0sax69@0Y1P(56Cxsf;{L+NdNeLiK#9}o$L1qQaw^HreY&~k z(4y!?=e=s5u$?ks9qrlklqneEFzGEvZ87t*o3NO=lneQ!N>_l%x*gHgQXfiS`z?n& zE#Ra<;*=r>5=FtjS-tM7nzJ-B-dJ1_#1VtlD=YuzcK?}oC)FdM4$NtiKJUO;ero~{ zBOp!{uVYG{5n4%BJGB6&7;Br;Xw$JB0_&Z;PYa?}Lh&prWZ&4Cd`+7sp*_C!#Ar0( zR!Wf36Y}ebv!BtX$;<9uS2Av|J8RKtT8y@QOm}vRSe0BYS{{1lmBrFDq>zc- zo?j(Q5Pr#-l)BYm-PMD!QT?H>JDR|rmfn=5P#GJ+H0x?+S!>67=qHGAo9YHqMg-U5 z4~jo>?D;D$ROss{F@IGONv;gNe^OR**kNva*0&m)E~ajhJ!+O6Uyygpsc0v|kF_S3 z%a^f9)tq6`@FRWE8rN+^MPSE?6~zL04&W~)E_{O3N6Ljt07)!f%qyiZ6|e3gpdGkH zkBv+rfL?c1?>)5RgE!{iC(AEJWdGJE(U4}-Kyd7P4~f_(pTFg1(V;-^pAIg+`(}sX zS7GeepF02Ml@WZmog)EqbmerF@nkSgKZD4$!+MO&3^yTFh-xvvX+os7ULo&tV}WXL zQ!{Rdf6e!-s(Bz^?tRAX_j+Z1C)VAmc-~*BVTV@wGf_@x=DnfUyKpz5u+yp50vY^~ z_E^xIwdB7FJ=@Gn^~cc1_N$H1r%WQ<5TS1~B=td-sKX5N{#e|z$LWn~*A}cFuhiUr z!U%0hnM2x+3Ztbsw{z{Q9!O#;7kK}EKlaboK!0rIzFhcsh?E}DO?73sy2a{}$kb=I zT%jYBh??%$yHP5dN)W&5oR_%hN1lqC-#sX4X1=bxIVsa{9Sb>)Z6iJ>uU(lHn8R5s zzFLQ@6K+%LPMtvrRK8eT_0{-12-aH->y^kIs(V~)Wr*+-Pt8`$`(w1(%yV-jwBHn) zB+|ONQ4uJ*UkCFaQhxN+;qeOba^Lf1j6XTJhNHlorGoN3J#!D$ZcF8%aK?HUZ$u+F zYS$UGsok7Q#J42Ufj$AUKJ5RB6ql~2;aTKa2Stsodjt-(A^_chdo3jSOM^zcQf$)w zfm|%7NzaO%X>k$6YRmi*oZnk>c?*v-G0*YSHSx5KT7jl8W9y?2{6*ywIW#H@ve9kb zDiizvqA@Lz?9W(i_W9(k1=Z#Nqdggg5j_ZWQr>i+taF_dX2hCwAP|-v{ zF=~WO&PWg_L2IMN$bvk4XjdyrI&|Eg4%S1h(97Px+N4Jsllt^Ti zwGK(|o%?P^r$1&g*gHoEt8Obw6b7u^{yyJaWMjLJ7nPHyS|6rjHq9eFi6v7x)gqUk z&}7^S(?iHMnz*3ozi9np+w+NqgZti853i7L-#}jc*Evl_4Coy z+1ybn4eZhs;_7eI-fz~yowYw?*YFPD9k&*gf;f zs}3I>h7sB1-b;alk;%SQGVXaP+-u>d>*=P=UP!bqh|m`8qbMsg-7=7QD0hXrmbjQ1 zxSWBN_GlM2{Re6vS4P0q>(jRA;{WVK%i>d(c z-TVXxs!&Y^q*@w#4i#w?qSOr zEj9heycfUBC+!e&^CEnunv^=Nn~HAUML(hEnZd(lURg{r`QER?q}~&J9=0`zSvrn| z4Rk2E$1buO;!|9-)H?1q6YqA)dpD`b*RtQ;_7_dW1jl`c9d{E+?zJc-RvFk;ciutb z$TW?8Zw9mu%Ho{|Ad6ld1Ar`ubbPX%&D*>!rt&d%gWSF=^nHtt=D-KEchjn}hO_-f z%q!#jwhBMl(5PXyoa64SwZHETWN)}@vpjbgcs<2mN0dsZw(32gT#;_0U!P0|BXJEb zHN5Cw(~B=m#qk&?-leHmyQ_QqXW{A|mHfnZsz@b|;$iH89*oG=tQ+Q2w3noy1i(T8 z6kkrtqn}DB`a;#EH=SLkFb_AO;VePp(u@PHXE_ziJ>q4liIBIlCm^#!l-*r1ju*g| zi==b4ac&b=^PyF4fhkHaw=wgO>Xj{U7Us2tm2|Do{#$QBrJ2dBU$QZpa9p&X+J>=B zm#A7g)6()VVzA!8SzZ6<;bkq6(DQr1<$4$>?M4_i8DO<*+D~dTAd)UfAzpjL0Oess zN_GstsX_c1r5d!dvGjYe)wA)GxXL)0k}vPbAO*_(_AHZ-xu~b1!iPe z?XFSiTP3{ zz9;hhAY^s@K6%~rR2%LA)1&5cw)Gpr0eQumY6hI-9cG^29X73nCK&H<6HgRU@9XuXD89&^f>vv@X!gTo zxb6fvb>7#;EpIUA+PX~@dB_{DxIUks>R049)d2-5-Ra(_7fXXgrDdsbPyH)t6-%#{d;iz(?mk-2$E^kjMJvyt?|y@dyC zk5AdO?@b5%e-=Q4{44tXDgXIq6rZy*kEF^9c=pAEwDm$yi347m2z~9SQIiKbs`7kX zwanT#7S_{!nKJ#T?%q>9hfm>Fq8 zA>7c$pQNkezK7y#Jj~9DQqHnCKbk&$YJeJBl<+#I?*S)D1Fr=+(t;z->xiw&8SbJ) zZU>9;8H#b$x2g*{$77^)z~7MPO8xc2r!!udRCu+i#%Y|( zE!4eroa+MPEW&xio6FfMm%JR~{QWkt28qtee zAs%#%4VW}yt7^8e|4ElUNHtAwPCqr|#}%=;F4kR(&fbTLm|(Ft6Pie7o}69K%8iSi zKX6!f&Yq3Z=A9*1D z>XaQ~!wUXuE}*KdR`qV%ZTf$Q!p&v}HcEul|o zvP?Fvv2W`Mpd-!TjpO1QR@ZM?TIM#Eg>40>qKHn8NyBZ+CLcO)7s31n!hv3~6bzfh zw3uHDCD-B9FPZITUgs_eP2Q`qG=768d5zEo5e;XFA*`uDxNZ1&_o53!Vf~D ztS^%rs-ano9^cq#IkpJR{DjS7w|v=?h$K5N1PpTUD16lWhXGimq2E;IOk78MzKt`D z_uVJOsH2VDG4Ri3gJ$xki-6R(JyCtS8E&QGX5!$k#_NClvj*K7nk=6m`|%D$&9BMds)W*s|?ePRE*2U2cLQ+c#$!`xnAZ*F4HM-27~ zryFho{D66;gsiomTR@qIK+s}Wx(g8AN0_8~K~f_XUw^i{qb_J{Zh ze&i$g8(S?e$Ib*crsRXaK{fIjqGHb4%Wc@Q4R<>=-sSFK_1Ua!)#b)0Qv0GEC*o*w z$G6=1*53AOSh#>yhC;BzgNoT+SqvXAL*9f3(Jps<=UIk}1Sos0T`PSuF$v?{jUL*? zrVE`&zH#>z>-{3`=I#(D_(Ss?WOM@c;-f*$?4W|@S(--AVmIsF#;=>#83WuHhK7c| zY+R*$=M?H1gSQ?T|GXVaNdjExEXsECU8kCu2uktd z2K$YR&!2qWe~{=AayR$=zBdiOa$3*PhlJpD_bd8UX?B2$7dT@T=AkOsgj8-Rg(rj8 z57r0>^3y_iAZ|?7_$T}u#M_z$D$_%HZ^vpUjG5QYDT-f0Y$`qsX^8=L8#N;LnUI3! zWfQzvyi#i&d>^FCL|3c4h1T{KdpEd2O~@xj7gyh&(yDn!^$qXUMakS#sy)a$baxbVA5Zz+-zEX~IIl z(&#CA?*gse3|56YTR*w{RlM3yEAo!^Myi?A(WST4XNRW}7`1;EJ&hR+YAyg;HI$2e z!>s!$NX4y0KYcJ9H?wKjWS>i^Kl#TW08~Tk857a93-9LT8mRZLR1l9@Mbj z5`#dxO6eu_dJY)_0%mYpT*)|sgI2{xF-ui^SCz7%f_Ux zyji;2+X|V;D;Px#5NN6CH0 zTUr#{k8OCSRG&&^{=2}-&y#;jBS;;@T+i8ja3#Mxw1Fi0ME8>}>_9DOVlNqvOVeP- zsEex$akt-nrNV?AdiegH=XUSYqjI9(eRVbtQ);JLv7~g%>#m>nHwK!>*wP049afrt z6xHlt?ELVF2VTdZZKwP_J&*gWwBoEz5%$rua{2(mY+Q!T$``-TU=PL%k$?dmlk8iMGUkCg+hi*PXCAx$$%xTx>TBWeVC>F z7%!is0OLN>ip>@!J72wghOgTlpD+41*(_o8dvl9-;`4iH(6*Q?J#9B-lMY7|uLtyv zvCY#X^Pd_`SiKL;LBiEkYG+@LM>Vp68MK)KMb(R1Cuko-J;hWk8{xpDG_lNrw%llW z>PjUs<}KO0CSQs!!eG_V3aecU;3p_cA27x2DsAd3(J%?e$;`fW5LEk$5Og;F8e_TS z=0lw?_lShg?YD%juvnfP+rK8?Kyc8Doqx=LW|dSP?=Laf?x#Gb1`pW-tUU(9Z(Z4( z3{R?l>m(b?}`RpzcFmw*P#*~|Oq z;(G_puS2|quFIKf#3bL*Wf_@ndwh_ts$K~8mF)C?-ujRAnOr1HIiHcG=qZ)DkF!&t%e&lEGKj}x7=v;`lOX1;dm*Y{@)u4|>q`nLkN>RE6V?l=YxzSS?hY8EAG;ll zqt1vW{<~%y&BeE@g^Eo6kEZi}r~3c@coLFTDZ)Xe>`~@14oOH>QZ|Q>y*buFB^_lY zdmP8gA#t+z&gR&A9LGMkbIjx5d)}Yx`u+jur}Mg=*Yo*!-0!#BFs%=3vs|G~gCVM3 zLk8NO6PJcO)Yx3mC-HIyPQFHHq#06VbO+Wg#^LG_efL+too;(rPWF3ja{6ztwu%sP zPo}lB7H;b9kL&U1suy^zUwgSGV4$uZ%%kMz-fl=j%H_yEfxr0VH0a+e;ZFNYMTwyu zm6Kz50(4w2U+G;-@M~Uk;Gf@M)o$v(&W+UEXM3dT(|gOV)w1Mz9vF-pX%rQl&-nJQ zPGSM5V*7j#;*LOytL=1&6nT!K(IZm=P2LquMI7!c92vAV*|MQA1cODb-%D*H^t)7r zh#-6OtuldNV@%-sHR4l$j%<{)OC z;S!80rM6d-BPF15rLryTfKKM?1P4Afx;+98J%~he?G|wL_@Zp6#EMaxE_C|~wKwe zM8|bVvC`uB;ykcc7hw}OaS0S^5jxik36cI&zW18o-{Pa$^>?gELy|HDIX-~S>*N!Fm1cnrE?(fq((Mt_c!%!h z=e{j9@Dp*Du!FKWhL@1aTzCZ6m-Uz#gQ=uo^gCG{F8oLw<*=KE_p_($kZ;BNAXHGE zi`>$0E68;I@nEf16BTgHL_VTNjPAfik7-S>vMA$<1#QSo+QhhQteDs6q;l+qYmZu@ z%pD!S@G)(9<>Tr$;lrngZ$MuLXPc-o(`jTeo}rBFagjB|;lY4xUhwoW{E#k-qvn92 zD8ggdW@t<9Fcs?3tZ;lcVA95#V2`Edgk&*XhzK24tpSGOSa=xCAz@J(Ie5nFBC&t@_o>kQbO9j5%Hq*0HpP9PpB~98uU2Fj5 z6y6T`&WL!;>)c*qI~~&R?qiNpT)X}2eEvD-= z0f?Ezi&?F$EBY5EYRDrqboNvCpdnd$HYmIB4R3Fm*<@8sMx(>-`O`1%_K+<1?-P|K z%vPtoEpnMXrfVwx?(Kzx7;g%@{a(tENmA@n$!4kKm+vlg>allcmvZRHYr18&bm7IJ zur{3pDQs=MXmcx{LEbnIAKmF-i#`s^tOMn^r^?7ksexTkHT9<{@$5*3hG+OiKt}zN zh^=91*4(E_39Zf7P;zO>-r$+NFKX+t+y1to@>f$-b1X ziG#>aHY?Tb-y^G=pSQn1q^tYO!$5B~wmG7UDiea19+Y{EyGQ41N^7{bylBlH_g5TY zwdw38E+1_)?di#ybM#0k1S6<%i~9~HCmanle`%O#o-T)iEmSfKM) zt;M*wnv#9-Vhzx0!Ya8zUb{EmcD7sR?ss|4%2>55aqL`GztkyY46r_7>D6~B{hKg! zw;$A$la!m18ONc-i`)7OHM!DX93HPE8vjt`%2B@9SrKDizBKhA0Bq1d1{)2>Q;(0hkAfh|rca3bZq22Uf!p^tPl z-*<7#Dt2-6l%6z}A1$eBH=tOf@;FIg2k*)nOA)@#lGOq@|MJ;lwUGAAx9B{PFvg5M z7n=TdphNw9{&pcjDM+0`mPh^pE~*&!eB14Kt=o-SBbvHtw$+QRan`p=RWL|Ir^<5~ z5?%@qy_)uSlJHuY<1R=Tx1$|Yk_mEZTHxc=4jfbjzTXFVeZ>i7A2&zAR|Cw4|2d`m z+FCq)(#th58MJy6V2p?Tv5v4?)G;+FW%uO?^ii$c_~p=c`08tRHQHx17nNpcZt@`% zbzXbJ8w2#o3wq?TA#$4eb*_17yX$9tx5CoMBA|S~9kufEX@@8vE>X!Yz{oq7d*Zf<1;$T!M9931>wZcbE39_7cp ziCBi%2RBDkIPL6TTXXo4_hqwW_Da+3S|WF?rOuO#3SV*cul?hR?+wqf+!7a{5CNE{ zI#ZIYBN=X%v!9jKe5!op&h`LyL|tjaRbUrw5@j-vV}o?{s6VDtNPs3+Oz5HhlI?VAF9Rm?BUL+h6p*jjKe~SEpo*#D}q6<6t~liJiNv0IH)A z1OLgP7Oi6wUhJkBe`cHQZo<0GFLZ~SZ7*CVqONDTmTAXl_Qp?^j#DjG0$8j#$OjcrjlEXne4r$T2y$$cgBwV*Jj8sGu^$ zt%WrNb6{`3< zI*>S{elW&4hbx>(dKD6@!WRVhSb4vAIWP}bx~zoze7by8(+!8s3dm4)H&}^V-n>Jn z5&Hb2U}mjI&+S6VCS!6iBK{pQ#3*rWc+Mp89XkB`n;YSGR8w6|?)-gsHT=4Ut0!#M zALz@qe!OXXc7D1;ki~e>48PjT@Ie!I1}rv>2g);~K!Mv8xYCy0l9~Fezve27Y8}(I zdnb}shEcn|m>0oE80kBSyf1{DCVt3Yk(al)xpo-_^D4udscX+DyiW^qLT!gQHC2d} zPQl3`qP74{@Xa^rlD&FyPnE2>0#>Tz1!g&_>Rs0h-8YWPIpfHOrs1Cc<#Yl!Eq)qp zaOSrHG<;&we{x5@dL_{}CWm*Bxku$@|A zRT#(_V6a{?IM;oM=^@uyXN0G8O6-)Sw2ziKU`E{!sU+@S@$0qq}wd9Ummfl@XtAemUz7MvQ+FSGn%k{8_v-b@2wh%mdg$7pNA^E_5xIL&n zvA)Q+0b7;t^K3op8;cD!M}w%`8QMnfVsG-GCulx875^Iab`>uIHW`^?1^ax9#uxW1 ztz-e?eXi$k?$sygx!Qk8RO#Hopz}*^R*Zb!+J)MABYf?_-8F11DHam^AX_mc7{%8m zVKhA_j*ioc9t&+71isnOKxwUy?W-O0dOl5O`@3eAOgj2!>ixC*Y(B{l@kY#v!fU+5 zkV)dYn~&}LCjr;RipR{YhHg8ts?RN}TbWcXA8~M%{N*idB>vND`+&NOGNoB+lz=!t zh}l_J2r~)Zcm$lw!8jdmnoMro$QW{4fG3UcJqK{{ntN+bJcK2MHz6hRFay?ABnm1_O7&NH^@Ut)V*21Pz5_1ck=63h8`wfJPpxK z_c@rW<&PA%xw-e~We)P|qEAfYAgM?E8;XGR!@M+JhGRUy>5`4NJFKjHX^r>)#vpBa z#gZS#*^VvxLxPrz4U>STMG4cKJM>ql?WsjrjE_O@%xTAQDyMe9luqL8O!THI!^HP*T5V!UZ+u)IzJXoS^ zWmAK;P2=Bb?G3>IbK=~p(ZcPii(5he;Y!8X^@i^>1H@FLVyrqxa;LEd-%@!R1LT!69@T0WvM+g8t19|%ZrxBbO>#8<9SBCH+n+FEDD7BF%fN!+^A?0fcb!;DR^Ebd`d5;{8Cvi z_%8mJ;(nh;NqLPogIaS`V>ILH;H-%Ge5nUsIDPnt;wuGa{YP9sdw-IPFniBmRcqRe zI*v`F-Ja0ycY&N2IV1Q^U)3B+r$84J zU5Fptip%d59fk(Ch;3~Lodw4QnAx`at)Lbsd|KzGxLAwPNECq-89@|H`N=qS26hzlAB-o$LMC!-PqgCGpz?UC8e4c|#kSiWcJU zeGI}7KuderEpj$CP*i}3(+vr*sLHM)ZwC;`{>@-gM9BW0-9;aw=GxJ#R#Q_-H(B+l z=&t5@op*MUa09tw#>wr4YC?c*xEH9Ozc8eMD~4C-VA2+H@Dj&!~AKTS6x zm{=Y_&Aody2=*E7Kh(~p2c|UJ`P_mQCE~u|^A#(V%Ssph2T*~)Tv|V8laZC}LlYn~ z10(PDH1j<${3blmGW(a=_F|Xa@P4V=1R483l6^>vo4lY7{G&wF4teIw8^7_-W^yf$ z%!pHPLC^*{Cx}*A(IAt$mGlTZy(^W*SZ5ERWo@Kyln_UW!{^d3}Ap z2#s}_yi6SDlw!eI@EvZ%U2$bm<~e&L5?oc;Nc{4ua{4AZI^gB4+SX0sWN8b>P`agE zlG{JH>P`Bx6bKscaXbLIiKhmTC9cdWBU53cQ1=*4rUFGW8pazg<|P8}$Omd^LUD(3v2^ywa&cLj3llhb^AD z=@o6Q^*8yneeotQhY8ybyO6j)gR)m2Y5I!D*QvD%{o!%i&@y^k88B^*-V|$Qy3EO$ zZB7#325;n3(2R+HvTeF|<77Rxkz=r+zv_}hTH4~qnn^nP=4P}Wv4IywD5F57UrO89 zcl(o{T;()Z75DCdJTLRQBKZntF1Koeb-5F`3)&NY&`W8SzfTrF&0)If)Y-mu--?l@^UA{IxyRo?m##u3@GE6b z91mdLDc#BqWfPpWd%o3hO!kgR68ssFyJYH88hP5cDeF{zHbK`!=Gu~zcLSV&=Y8{+ zt>jd)SLWX4P|eTF@!@9EVZD*|xAG?NT=XyIM-yMm+Iu#(Kq7~>oO^ihTox~CD8tm^ z{55@N;}iO=?ev5q>(%z822J?c8lrb3bB$4q2Gg7Jr{Sk=O`~TJ@|ONy}*-@*K>NI!A#5@hCF`6WC}jqN}w3spwKAf6ScbccV9eUlGk^* zE~l$i^@o@Nv!uimXqm_uCs)x z&)slu8EUuX%Q>molZ+ntCsLmg_q4?EEpTaQkyxmn;`cHdCiS!3Az+ zN-29zx|44Zi+^9ZC0OQg3o zg-iB7i#f!&sn3MmRWDgClg_a$jp?mX@suvnpQko%katG)?>ZLk?08iGQoM00eCJFi zE`>J6Bvp-14-l31C2yezRZNzGtew2o)|0%hd*81b+3KhqKGglAXx5ul>g`_B+>=sE zkSCjQ{1z@`wI+q0`NX&E2l$D$GGQ0A1A8m#%SC@asXTtau~^f05kknaV^lij-ccec zHC?!S$3oIl_Nzh;irYGwcWVXg49q!$Y-wMgIi9Y#TgZ2He2eqsJ#p@=QTAhbH38yd zpb_LODf6)DxX{YQcufT2zo(I};JibNb3*Jnn3uzH>vwm?_Xoo>k`xDEErE}UWYt5{am`VJ|!~V#cvQ(sAD)c zU9pa6oMU?`iB8FCYGE>S>w$cY=)L^r7s~OaJ!`Q2EqLOJL_l)Ds5JG~Lv;qw4?7DF z9Wbc!O*2&^yIOFY6kR82UfyxgJjh=BvrudF+`7=urz^-}0q%wa+A>X^g>s~@{Jp?8 z(zp$edtaC05zD4yE{oM19QPD^=mIkd!s4M0TL1t%gz27GB*%Iw$S%%(+-zKrxqewU zg4547{_rh;d!+2zu}P*|txgJCj=19bTDwQ48zk4c^9f|E_8wAYZwbs%Jh$%Ff3|gS zcQ3%(m8vqjz$f3u?`10S{v~mVMt#ilUz+a5uE@dea`-?i0C3`Pe5=n5vMlI+ts#ma zQrf_NUtZnDq?!*$FIvA6viHYnMuAQBuRb_bLZ;=Txqr@Di)?oeMqmxHgfmi9S|~=} zhhY8&V;RE^?JT{lv0GLT`KBYwa7?m}!7_}@yc7HH(34bb>vqI_{twZdMzsz(q41xNVCSH}&{vOYa}RQzetKoqAe{s4cd8Py z&SbT%De8VbZ7IdtV{~wTZ87t-|G#UT>Y{fkPZw))El)?=zX>{}0~ICjlR~oVPKO)6 z9}@yqRNm<|0AH+tgEjQlmZ2N^2ssjI;F5%mo0`iJ`yX_&4MEfo*|>IW8F}WrT<|@5G|m-A9&oWMnz7tu$z^#nQj#X=%$ZU6v9kM& zAgi)mUQ8n1MX}&)6uyzuth;uB^(CX+<@lC z4m)(F!Q^k44y22e$9a&f}EOR=LQhoqGSmF~Sc<;=nR5>AILD;1! z!Rg-g5aPAb(f#q7UlxFq@U654`$4gjBiApz~?$%IwILp0>GPt_av6F@q_QN1Tdg8V2z z1MBjnXV}tmHS4JvMe56o_rZbuO$RDpdzLpc6bmu>Mt+VH)b2-b)cccchg%9{Ypn(j z{^EZ7=+%#zpT;pBDUeS_OVw(C_n9-<%)$s9Ie{NIRtt?Iu%yBDQd@WgY1_H8r%Nn z3)rbyBDT@Y2Wb;G$Lxj+pAc!ImmVx?R0;KcftSIe{IZ*hosdZZskD9@R7_i#dr#>S z*PYM~)eiDD^4nN;7oniB!I|~nBSGeXO@U{DHI$NvO)wYuX2HHOk~-Pgewi5XU;_Xb zt?gxd#w(XWr9-@Rl1p30pH7^#lu1(<(9@s#Y}M0hJ@nD-7Q++2grVedf@M-sSK0$ z%#J4${SdZ$I#)h=O|8d(oL7#Lj+oBMRYMgbxY+Hpo=SQ>MycZB{4<-ac+3&T>SGHt z_S_yz0$Q=}mUG{i`HkG@q|Q-++TFL1gh{6vqtmB#k~Pnar1POO8AnsKgNfT$6OW!x z|0c4@N;i^@0;J^Y1$8)vjGSqX9+vxcW?1$?70(+dIL|iXPE*XK+ElJt z)h#X37QLe>ueO29I{2BK0=I!*SF&p4%~XB+3^ z^>*C_Ti*bM)s$kr7_&q$`fRUW9Nk%X^HKM-BqCQy`=amsAaG--`uNvk{(}Ykb}95d z^!J>XHr((qT=)`G+9S+0aaW3DIR|4|Yo*htkTiwu7QnxEqg8W|Gfsl#2e(bu8RY{m zj=PR_y_HE`4gjt0G)}deT0@Ujgg#Bg({{ee5>X}I^237O2R#?-COn_^ zGjc^XdD6;C7Pg9mYA?4EJigZ-%>LuRkKK>vlBcWZx{C4cz}*vh)Q+E`VBsD%+rKY; zr_$31ntDC(=P0G%&`nc=wO{Flna)0M?#bN=3*yRXj%b&lOI|43#_)-E&LBMdeMRQ+ z5xOwRx+Zj?_>j79-5r+gAGBI5^4MQc_7{80^Vf{ZPguHLZd(R!m~5FPd70vS^u7CI z9|+Fi-S3O*3jIWvEdFRArSIW%$?i3VQ^A(Noq*k~9)CmL7lio$8!1Zz!*= zGpYSD5-n=zmIC&Ti4i*hVMvw+18y9(nj8+e}4zG>2G`hgkXC?77KSo z?d0QX&QyYJfo&f=DtfI2l;sJpPryQN#o7!H)X0BFVc~=zMq$tUp9YVdk(rJDcG-G0 z-Dd$`MmK%#gZTV;?Ke&%(^(%4@k|J>%OijwiG;l*RfqvDT*xhBQY#&-6A_HvJ5zKg zV0plhUaZr62m$LvIGdXgTQl;gR{JDZt;eE`Yg2Wp2>JnkF4kdu`F=W=Lg?-mJZX}-oC zA6(`U%^o3fUT`#F7!oP7SrOB$68$>cBY`s_T@uo(4dUgT-J-ru;mgvIbj@B=!;H35 z^@F>U#D}YU`D3(enQ?DxVx|NlsB4bPZ`9$X)wLl*N1u|YYD=Ce$ZYLXYdiw4iK;TO z45|mJ-IuP|2*9~b4YG}w`218=cQ$V%CI>(9v4WDnHScGaUTjObv>R2Z^3tKPs$Wrg zXsD#+>YZ5CnLA0GVxX_|Joh-B^-kj6ITJM8A&-p!*?MOyfAlit*)!cU#kd>^ewN%8 z6ME4i0z5&^MyI)k>TTpW4$qg?WbxL-;)?~jqN;hCl`o+Al(lvZ$ms4>KCwBp?+=j#uv6P=4= z1LHtRv_6tGQ$G{uA32Lx^lLg^p`*!&S@{XMF+-N7eB6J|NzRx~PFTqhUn`m3FS{;t zG87h|<*Yty(bLZ4dmy`7xd`($X-TG5~bFviCS6a3^K% zQ6o9sCtx4gID7CP*ea#5^WO5NHe|v+2E_{WyFg=3QuzBmCKi6ntmgg8wl(bGFa9*H zAb0a6h$4kg`O}2*v^n5?+D>x2&feqPc&*N&P}kuQQyr;+ZHTr@E)1o=>i$<3S4LDDmvB? z)Ow6}C@gIES4@ImS%1XaJ>s6_Wli}vO`Ax&qCcffcwXroc)NNYEAzDfi{x777AHMC zHxaYZ*7~nGn(4^UF3QP2Uwi0M>tRsKF;bjWkNBQp=ck`QDA+=a`LrTw-3j1OMsgl3%>`Dmq?fyd_SF z%5-Ac^ctjOvd_32?K-k9YpZr-ll>f`^AHu*r<1h2CXLT?ixiEA^IZU>*bqAn$7LhB zQ{5eU642%)hoBpa3>o9BTwP^NhH5WhTU+E#S{47D4|7;MoJ2B<^TM$X9ItnB?&Izn zt^#R|m6qaFt(2rdsVFtcZU(4nvxdp6NR6e57u$gM(q|La4+;##V@$3KCVhvi?t>N5jg^g9&)}sw6xO*wZtTmjE zq{xAg(O>_C`EQAR&y{DN;#__bv{t1O#nzS`VMK#yKeU|Olbz(8to|o3Pf^87+cxV5iM zV@!ZUI{Q78lcR%;ebbbL<3WV;GbPk{pb;#wbUH`z3Rr^4OUXE5R~tXX#4#?dHs8-U z+h|~fkCRCTid{8B^34*jm)m}c63K3`L>40(X_jB!5N-?;2)WG!EBZhKG;CzW;A#}dy@FHKEPxs&?Ef{bR09vyMxEM!E#IQR;5 zNT+&_-7WY|MF`t+-4pC7`*iHsM)wW%;bxUPi`0hb>wU{+DWfF^zw6u#D^+w)p9D^d zhBvcTmKsB+^+Mg~Amw%XzlhIFWue|#YZkSEdLPT6wMmL}KlXk*vu=tI)b^rP9+Z10 zGue@IWi7lb)ElN{&m=sG6zP*UY(ca}(ZcdKfE``5u=eQMEN<~F&Z`y_rJ$+huJ<>! zR`zG&_!)U2_n$=hd&Y4)Jt#x#FPvnnNBGy~vSv-xbaMk$aql-{iggY*ErjX0;-Auf zY)jx;XPMpOkWZl2VNU_9pBWuIv5U)1Z(DcmzsgN-MDb^V3sjxT%Nddl1-je{B7H-y zCj7QT^l$16m;q;R(@fVf%aZeV;FcCXGh`(t3X+pCxEyIeXO?DoQO>b4ct_g+8RWp4 z(wwqzV}(v@x3{T&`jNlbjVy<&5_R>@O$%u>6_1)f0ApWJuAh18^jA3K_z7A}5Nzas zQSJPh$K$l+`K9IN9$3HWF!vx~F(oaWj^b~C7${4*g zU(S4aAw0Ps{}~=8e`L4nts&m**~m4BJiO*M65n2T@rJCxGN7` z7zfsf#NY0SMQ9uXZ9mtYzu0H!%acE6ZQREDsW0x`{unI)@%h$c@@HLFHnW{pAbpW} zv}!*zNAf$s{MF`rSmQOafkHZmk^Og|oceC5Po&k;Cpk-;(fVvOAq(X*u_7xv`<2lN zaKpEscfCA@-A89L0xH8Ywmye-nA|~-{S+ZNh6n6|Uc2UF-`Z=4fA6RU~=EHU(Rz0m@9BD@{85O!5f;&9@iU zoRn|WTWK$>cupyQa^y~2m2(LYl32^z3wO>c|Mih9d1Uea^PwtfPLKJydi}~{@7(@Y zy=m&urDZMQ?U79~;=9dX&=f`b;l6KS1nl7A39lUR&vE%Cmd73PU1WLmw+FUvA zdmypqbT-UV-sVxh8RCgT3}YPXAS3rEJ3Q25{9XXvEefMqIxIT##)95V$55obHZK4? z0M=Gp(4N-eiv918#T3>~y_?}B6h|kSMCTtV>1-x5@-C>-o4aT}lAjkb0-1>)4YB#h`4=KyBYJ_-mm@d z8?voQtaNam_qm>M~9dz9)a4H6q!!#|6 zEXL`kG;g_tu}{@+4sWKEUDy%6IiToMMpDH5$2tp@&~~SDj2lDsJ*47o74G?Pr6;RD zAbwuu;Rhm~z#y_`3~`k20-=A$M-*_WXc5wau=p2ggnT&OMVv5)yk|5}GYvH4D$-pw zOXWTv;)cUsk29p3D&m4N^pPhhGfXP`%fQi~dY{kAZ+ND}wj?F>tjEI5I3!mc{%IUb z4!oFLL?9(*FZQV@jo<<*XD2)!jpctKlo4Tl0+`dE(O)VR|nv)jLX8{2Zf9{sM<=?o{>a4~G_ zaz$GKfyChFOad3)BLRUvf}f;r#tpn@bE7t;p$)n30g#G~I}#(y zAW}KyLTS&RfO3E9S1ug_6pSN5=Lh;KbRdVKHs8FR4hLJ$R1HD1hrl7xM~pAG$CwS7 zWo&VoL{J5MTxI)eV=HkEKNcmF@mrVY%b9~qP4-x|7{R0|0n?eN&Jlu7T@}1D|40+@ z*wZpap(J+tU8KBi4*qZQd;rekY6dfQE%H+pUfL}qfX@w`6fXMOVr0VhY+%JK6-Fr7 zIpYdE+9UX%<1iO$jK>TnZL6J)#Ar(O{yEvg4%e80wY4w#dCvo?nX z5{J6>$+(Ha%AfNJrhiIgMQBkK9wqjW(wsAix<&cHhOWYx5a&9bIo0X*S#DX=^fmv% z)VW*1TuUD)4TMeYgBZlpv=en#3^*oxuurYPyl+2Wx}4f>(r7CrB&j^fUK=(!{NQyNOL;so$RZ^%NMfSo!Aa|lK#5?oI_}(wQ%WYUQ56*m z$9Wuv6zU8tbE{i9KcJ_^wnG#g(i)EyhMyY&zZOJ@Y`dJ+CbzSLMuwW-%e5q5N0#RF zl8ofH4V23LI0ktzEt0mQat3*SFf$GQ@v1-l;~_;s2suX+H7ggjsio(h;%zsVAOCVp+u&5=RZ<5=Ku+)|E>9$&wFW8|yeQCtj6fOaDX| z{3HSMa@`Umj_Fh^$>xYH-SqRKJ+D8#S*^B|VEDNl!!{AOc6=ap3M%iRZ@AvTNT~7E zo-TLtUre;Sg(3d#XZHX8BC)`WU*?3Q@U`GhaT*GXTrwSy-kng|x9PUXy(t{JD z&Jwvlt-2PxVqVCnkY2&VIIr7lHK2Dzl$s(~w?6{f_R4=T6qC64v{$cBQ>OjZpPjU8 z)KMe?;0!TzcP&iZe(92l<5{nPE>qg===}mbIhPDh*Zo*#O>yUw#A`_oXfDO%6^*(ksEg`IovmE#XA(#XFo#Vk7Y^X&B_ zm)gRpCTxc+V7GveOUczL9+h)f`#DjHPRiqZ75u^<5+G|78mi#w^E~8+Qx-C3$RGPD zR2lhLT38m%QY*JK(NItg~KN9$F_DNd#DSpOENQ)HUJS-B=$b~ zn_fDv(64HKs8*VDq3TJ)3bEo?J_LH~bKj{XA@!|a|0V4Tw=0Yww>}lkk778$h0Dn% zM8$O!>hiwL2*xrMdEB64HJ7eu1HDxXcw0<**W@F~a(rO|@)}i0tqm4GnzF3w)i$18 z@&L20r&BXujni5a=vRi#6uz2foO!${vfC(y3R-EvX+6`<(0<72=ycV6N^bsoe{sQ{ zI?73X>M$j_2!7k!_2FC457T_b9=F4*JBJ5nY8%h%7ILk0(jZ{-HE9Jhg~ z#Gn5jSbTl-^CmlQI`3|heA=&aL&T5v*FO%Jku0CYIxi6Zii`t%WPqr*;>h_((@*nY zF2v;e ziq@(NUm)DLSwq(Q4hB3uTq^Y0d@>A`deVd~v9WA(PPtfUqYU1NwBq~h9mE5Nc+k6E zRXk*kwRyT(N08#}^!pAC0yAaRpib+8UE~`(pV4v@1XaA>oaY|W zqhebIHG$kcy;@kq1!qIGSvAA>p#6o49^VsmfN%wVAmcUnwU+U58vYRUo@k&fitcHQ zxY*N}_ppwU>G%5pAC@m}29=Az-2mD81G5GLCiSV-w(`Rwo${*Ic(vZ&%#}Up53zs- z#e}D)1*5)gUImwS;xX9Sp|#&mSuO_P381{TIEzE)aQRa7TKlnD@d;Cwrm}vMbDocm z67jsCsyRkPEzhtycKZ>)s_I}PiSv3Nj7zjMlmVp}QKp7?oUA+f4&t&p!qAhYR}TPg zQSkZQfKfFpe?JO{!u|Zyf@E^!|8r)$+23-xm?dB%fv%Q*%k+9@UpgcN6c)78Is&7U zH8X80>K_R`{UtpVTw1p-C{lAKr++vj_cc@>Ln#T7vwllF^g1gm5{)LQ-b&h3aa{VZ z$u2MN*w?;IkIlr+0(WoD@yuW9C{2#?l?ApN7W@yOv=}^Ry;UZab$b4yN~ z_^nFo7OPgZ`?|pK%HBe8EP7Eyw?`rBY36j)5}}agy`kO1VdO(NKjgN1PaFMSOC3{E zXak_Br?pTepn+^^Z_y8`K5F!AGSZd%)1o<{bJ#UyBoKNRMbYuhaq&Zz zIIL$Squ4u|C4Xh$x#3pp^n?CRlh1tOv+?b_QL+(va%Pn8ER=3AXIvFEU!#s1Wn$~H zwqp3ul=ETWIGa#O9_Hs>Hm2|!J9AtCKGn)T!V3vy@^$f)@h3ZDs{($EH)EvBlAJv8*uvUB=-(;|(gSYd7F|0s z2(@5f#4?PF*osw|v1(nGvU>GtXpBqjRK2@9V(+EyGuXwXKt0Ptma%j&+%GQBhA-ry zyqPZbMD`ESGyhY*Y*Z&VbirNQ&mS{)3~=opdGKh+_1qz}Ecw+}q!o*~1seqrk|;MV zU$KBF^_G~+*G1?o>GKNx*Ss2TAd|lxN=Fe<9|$EWvzl>sOX#ySt%KFj!qh`&m)Xn%+^P|Ut^;{3a;mj z4{M|}48djhUfvE02c(ciftX1fPN||o^;N-pY~AlBJgPhS%q7biOO~fC1!{_LQxP-^eb|?&aiC_uNk(ColP* zZLE_XkxE2f$f)o)yv)znk8g8u1~j}F&`@E;w9UBJT+loBj7$_z=5OZ&09j10GQ!6U z#p)DXWo_1zv9%t~n9G;6<1ldTeDj|N8~!#i`Qe z8tgyJJDkSJcg|-5yTpBY0yGk|=8S40^)^9IQV^#p9$oe@`@Xj7N%4D5EIK0Rifcn; z*qkq*ac8s9bzElpJi%R+GLWHu1t9eW!N|`r_Wldq?h=L7jE zE|*iFJ*b?xvU;apoAPUmu7?|DK2YBKGP!X}eKk8@os%l$t;j%OVi!tIjiaF*GmW!s zZjk${_^ZZ9Blsk>-SLFww~C=W&sM$vG8V?$`c0HeHB{L)t@YIFH;mD9%xjaAwCECa z!=$#^!Zgpv4AkSs_5^Q-N0>hVNTEKwu`Lan2;51xzb(q`QeP_=qsHpT@;%#|cvZb) z$nBsH3yi=HT11>mef#HjXx2FDAvnEd2}uXqQM<}h59)X1dXJTu>$6tTF;nZpwBBIW z*`#b*eYeqf;Tu|9ja_^%?FPuyBQr&*ivw)S*{;08N%J}3-_nl4;lc}YHm=^iigAHu zcBHIj3Npd>h86I1?;c6Dvgl8tLWGDs&)%D0L^qoux~BGK5QwvJ{;v5Pdq%NtQz;9i z5UdiHp(QEu$ByRpj_mfm%0QgYC_QPs@?4RcgakC8f?c{P<4NSr*PhX;RPf;W_xfzjfP{Y`f3FYW*phu) z=m;NNs%fKi$p^ViAAI2)6~DHl#fdnM?A()p0`M_$s#0FDl{+O@%TaRaV-H-##z9-4$8VirO|Za}X%}(g&=r-uyDrl#pUTniHX!$! z@%yQ>yZOzCABZf+f88?fQv;w@wJ^17C@H`arqQ2QjVW;U8i6C!8{7P(<1+XeZmt{OR)2C$P-o*T~f`1^Gfx zuZgvui%svD7KSF;;emFCcvx=5h8BmfY)F~M$OaJ67WI1|q(w$UfpXkCnjI#UzzS2)SXXdGS*Ys>M z#MuU%`aRq2Q!_Iz4%wf;BqS19py5#ZY3}f)DR{S!4<8+6&10MO$4t$&G}gJu>;6}9 z#-EnaugneMQ7`)n6B$21_a$^}^>tiNrqEg3!dmMPPPkmclBD(U?kc;)yjzfhP(z23 zx4XAe7<1lE?qg!*rTa(jAdXMBt*mB_D!zXiQ7CR57vfjxlI$^xB5j{pn%|iP<(&Og zU%g|MN)<47Vr1##bkIKAzV&!jyrp=6ZDh_cso4z($%Py5M4NXwVrMc2&*-^SE`NSr zE3DDd6A1bpavUQmav5bBQgIsVrpXvhB1p6`38gp&ea*sfw~|~R#fwg9GeFM;!CIHr8cQu{Jm(pAb0M>ZB@vBd7<_c zFt0oNN1GhPaThK@R~+WeZ*0=iiflx!-MOHRG>!CY^)IH>(%=&f8wO9WW##I zB^unJO>s6t3@qpmbR+ww%k!(rk&86CBJKgf*!CTDS_5ugw}5d$pv;U_m(@QyR<~iG zUn<>H8++iS7UUa~>LUuW4JQ$sM@pP`7G1j+>)DXgH309v^uar;Z8~ zzna~}xzWXvXIGWUp8);D?c9sMo&eSdtTPDn!@58NqCVt%4 zY|PB&Yfz~^75ADkJA}i!Z4)DP<_Z$uHt(KRO=mBaS-RmS1#^P-Bm81rNQ_xFmDs%! zoZ|&1n{LcCAYTIS_{9vd<0++^Rp#Ml8Zb1;#bY=YQBS0w9}pj5#QS;(uOlmKc{rQp zqt^occ%_3}+};lL2H2?OZ;qxPd*mruplTZL3IMY_A9P4Ja=X$_p3i*16`iM#QvCAo zhV#;xlm`T9b@%1SE_R&x-||0l_8nc6Cq0F!7$>gnlHM%El<~4rl2LLw75t`U>R<22 z;OT#|7jtW89>z`4mx|t_gn77pAg=X#pfifn100J(_>jPdzt0zZaj3xGmpgJvo&Q{0 zu8Q-=Sy=K{?Y3gXUA&t=r$36NX|P>Im4o>D%v6RZK-h^0Ufp=)lkcU|p#~vni&Uq| z)0>oRE}5x|fBAr-Gd%cP%;K%%DH_|h*_CU**4-6j%9K0D{}WK{zt-N6P1uu2S0=@X zXE$Op_=8VgZr!cD(2*Slm{Lb~kC%89(voLVSX*=gCC>;i)PoVr71N;8{0c9+&~Xl) zZhco@GGo~-iALW?iLZ93oV+KtgvcEC>YvUTa5!KwY-=Rti1af0-GLf7#YhtJvr*N%FQ&AI86f}$(C zvcAy?GND-lFFa9kN0LNy^TyTauL-!n(xvMvunQgbt=KX{x12A(OZ$=`^3j4Zd|Bnm zEX_?~;G(Pgz&JlTX6fIOcC&2&pLwZG>=3BvW7P2LfZ2v9d$`ay`<`y9y@u5fmm7NZ zyhv?!=CP7Gpu5v^|F4Q}_1^vV0|WLIPR_HNyKS@H?;e77_(fptttYI8$DOW?H;^Bs zjYrj(s)WL*gq`IRrh_=*^1sVe4|oL}Zk+3$v5Xh$`2M6|B0LR)9Vb*@J#MylB_k6I z4D-}5T(@mj<=WZjw@+kB8++H!W1nnc_U(|rA@-TmUW~WP2rVl5g7M8BgVxQV*_lwe zIaSAIA8<0)!`}zF*)lSi*7@mWy^EpxA^{q9si{DN?AM~N-o_>5m_8LRCcDpnIlK9= z2xMDE7^NqUwuK-if{>xr-G+P{8m)8fN_XfOhJQk(x7yPw88APbHW-F4SN|;kx;TuI zm)V^CJ8g5@c3zTyX67G9yQk_bl_%>2C+r8M03D+~qiiL;^Z}_wHmkA9E)JJ*N1Kq2 z$!<`JMUOaE+UjT+odZc{!<~ctrfdu>p$l`Y=(}YLoK=r0Qm2@bl;fWeQ`b_3*zAlJ zOWUH6y;4kGw-0x=A%E6$shb7A4}`~6M~l@g@4e>JA`uDn4xcaT7&K|gRE}9B32Cxs zzp*&7!%AqaiCDa9)1w#5>sVnj6G1DRg#{4wi!kNZzs-dE$GHA1g5&p8!wlI(_w-NvIwg+`3uraIWR?}-;}9q z8#{FKo|H81+SCR3PiHHO*xxCWm0O>EWQtyYa8ML!Y067YArov`x`Z8nm0XDz>&+xo z4{)foivm-Vj#UquY7zZVDOJ#KL;G;A52<@<%L`Zwx@bY$RqZ=oaYOPORgdo_pu)T|O2JyS>L zkEEl=<}?3&?-)zj5NynL#EM^Ro@L38Y?`p z$qvkFybb*J5;kVG!&|+PKfH#N27KpU<0eXW9jw|n!QgTh8Z4q;QX-ZTSDwQ;u$Q9h zm(iw4ttqeS5YZ9G`_I z7KT{TyZW-CD*Nia8s3}aQ3`WiJ7m_}h9)Yt!G%!+IfZ+B!5+irb#v1#qf85JE%idp zWiorKe}*1d__=Gr@Jg$wnlbdr?@obl-a?fV30wneWxG#$R&1yTo(OK3rO4^Dir<;a zA(&F5+@F3qFq|QWi!+clFw0Xgpv~%5rj1T2>mR9DJx||f5TvB0k?;ADvoEvd&kvWo zxN$@JlRTs1iep53l6;TR0>APF)9&%ZSn23U(wGue+C?hs-|ai8B=I~ zhmqE#lb>HusTaDhbpqIx*}!fJpUaPCcglvRMb6tN_Udg(8pjX}m#|y205u`PcDu~E zN*sA9Cv0b&EVp-y-gg$)o;!UAZ{R*=Y>H>tbFk?F`HlXKbxba+D>tFQ63j>iCg+c| zAv+`b4yhm+tC`L}LOxe#%L#*&9D}z~3G9%KM|fIKGDxRfkG`etq^vHIzJYOD-)E1r ztv5UH?H!k_*6!ND&3w>i#4Mz!82EJLuw*R~eikiGF#(9qaf*|T5T79cCDdDmW%!MM zm+gk`6l=$SIGcpAc~p4pl>#%5Xc41;9(w#I99z?``egyjkGS>0$0K9uA|3pgWTdI{ zd(=+s!8OK=SlTI%qr5i%A(_~v(811u_=0Z&^yZpPmZM0d)y79TbuW)=PNX@Yrxv-v z#lV+vksNUe!DdL}DbijTTt}N%#-D*&tSPH`>6zwN+&o(!eDMBnUMR`lLyF1SrLiWw zMGmX1y2FpYIj5OtPDc_I8EF~mgj%z@K6p>reFo}*jVoB^0*;@X&CL+r=6ii-12ZgO zZ>!tx~rz(&~9Y?K<~ zlb?Q5f0&rFKVb+7OOZLBWMQ@tQn^T`9PaqXK-a3#%{prZ>6YWieMy;HO+Y~L&X6WY zvdQ%}Cqmus^VW#u>+$GW;?FYznu$a5|9GUu%YWLbIeK+x7oxk2Rboqd-Pk?Q7yc1G zdo6K3dy_j5mGv)}65k`_oonjj-wOjG+PmPdDvM40GFq*;JNm0mGEm6j95p%T!#*Jn^NpDgs_hKX@I13Gx%ib)` zRXSq+IJMHP=)f+95y0Oh6N=LuQ1{3FtR|WzUNV^lpB~PtC zs{J<8oe&V<>a{mAaC*9hWZa{l_edJbUH7`hkQJt^c+}Lda$Ouxm>NHFEN#3R*;hFo z1Bitehuq5NSK%w!Gh)eTXZWXL6nsgke@#{wggi{V#8{Yz(GO`l%q`Vj6-IZI$Y5%M z!j}$L-sSM)gILv?K&O8YQVw#x+KJ-Tj6-gP@W*o>IAcG3!nH}WmsvV8xpk7|nsMFk zx~qH6>b7aEXPZnd8|t$5t@iYBHIaq4nQ}^TAvJ3AvkE=!fabHt0yRQu%gSXzz`Yrvl7wqg5jm_XZlOPh?6}(|IZ|{MR~X zE7;e$#~9?QyQ1gB9j9L8uJN(C1t&VK;^?*9Ji5$3hp=VBS^p|gzLpi7=ocvaf;`#G znru}f@Y`zfOD?D)_sM8texH(M2d?xfkh(&Ym9qIO==s<%JIY7V!(%x>t9a zoU;s6-I)mW!Pw3i1x^mvXgg0o8Qbwf>f4q#;62S?KMxcvJM}JZMD{+nG}(6a+-*3n z?hhN@ic#Vk6J%fC&5Lf!ghu;Gno0D0cU+gwkwnY&{i+G=; zWd5x$gi3pcosQ4N#?eSl*k9JVk3Wqqn*wXy_x%uE4zyuGtwyk(TVyTGqQ`?3opr)v~Dusbn)t=P^EK*v|yK zh-mdXlks|ed+wX-MKX7rF{r)_6&5}-+H$8DFw2W_V>X@5SU8NVxDVT=)f%(Ee1i! zZH71s>ouyfa~*^AHwv>;eOvQrCPU8t{ig|n&T8wtBw4r4vDIB?>psR=DOLWI-WR$) zTR2nMn&B};&|midEkntcxPg}Gj;x%5;U-hm&TV$FIzzLs47(kH&-mbb>sJ`{DH-kK z{+UT=Mc1rX?KkH5kSE4H5(FFr+h}(HL>%&S5G&M*FOxO+>fzP5qeIhZnOLLQ3VHgu zWcYW~%1yrEHAtyQ;4jnQBd(MvonUHd+yA;2!Rp4>fx8EY?0gC{0ZtDFv~A9=?u5!$ zFP$D_b7U$&3~cdZ-|^GI;J>=Y(CWrNu~3u}KrCJ!vV6G3pk?h5IJsOt=OWj9S;W?T zHWTQqJBzuKxMdP15x8n96<2|oe%S2GioQ3}X-0&mYzO(dl{vW<&;;`XclqyMPVzJs ziu}F(m#`nS{q{$tv6seY+mG3$eP!gE_Ca|PK;|stC3Z>Yvs{>28m_t(8_~&gd>HPwpThpV2N(r}!J-M<|BmwTR@1J!fuj26QXs==s%1c> zJT~8qBXCl^CUb>sR&1kWb?f7$-pIFkjn!r<%|>Tp&g4;DT4D5Q&ii3nHv(a`bh)^kPXmHq53zvG)bJU|i zk@|iY%{bOGE;rrzjLvbk#@Ah$1`DQj0F^5$wvb6}fLH*ye@Qq|5nDtXHT=7J{i#9S z?~!jri+OmNaBy2uuGaj{u7_{W5yL`Syj1I;j82O^TYcBnCgkfFPllw2AvRx2(QE9# zq-=k!Ce==j)>?d&Sh(s>P%(Ho&;eQbYU7sBdZ@u&kJH{GVed~2Y+Sv4p`#c6a^!a0AjmYfjSFi*L(giSewc? zYy6%!_Pa=C$N|+*I!xHRCL1bX*L+WWiq-3t%>#bMI$ZzE5pT08aLctKN#%66Hq$yw)-AA|fhpYC8$P<~;pTWoJAHc}Z1{ zQ)AP>ktfnhqU(RXaI#2B*!UfDLOLIDTe?aE9S*7VKaYeV2;RbZK8@|1Y5hy0+qnDW z{=dOQ3d$&tPp2l#fs8iy*0jt3N4I;WCr^xRmFh+G>p)dMHt*bA6=V3@`=v-2zi{$F zZh)HEzRVb8z5LnipPAon<7T=aE%#K0M8=lc<(N$*Y{phkg`-3-s}ewg&;h{=gYo4Q zKXO4^g4JfvY5D_$I|y02cY!(Qh7SG$dsq#|ZOlt`&I_PcYnD5sl~u{U8NcMQ#u@!m%*zU391@9F(1d{TBpi z^J6qf_(5t&QVUR%u&`B~nN88|v8d>BR-i}@L`j|6tX_*cCu-LI9 zQE9DDiFJS{(aYC%bKo2CMZB#{(gF7HExTB?0ksQ05(alj%Z3BPU`Yq#TuCmwQV^u!v^h zPFPIhJHS?a-yq3?kYMH&(lE+H7*lmCuY0#&89h_ESzuYa(b|_0+^WD9FhP|aM z-__CxHOj+jk#Z(KC{x`Fq|@8g7gXwz6ycsHSpg)e_hIZbe7dMZ@AIkHE)B7lF$T#~ znf<&PE1?h$Ubf4j&7DP83!!K7BE5^U_iXX~PY|2#bUE>=oViI%nRaaEPn( zi_0aFE>+$iXB@KQs?mDYvUJ%J<$AT@Di^}Eg&^_rNpm4(GFMeH5UH=r*}FoU5?4!c`)1Uc8;{yP|D z{&G5Xtd>QaS~c!bKFFu}`z;uG#9yBYW-D8jA$4qr8afWIk?~pHpLr%*eZ8kv*q4h9 z)&Dg(I=NED^InU2stR;iCY#5G$-{O0hKjZ4-(6|vfZ-{W)Y=*9G~Ee~nIS)M;P$eV zE>W>QJAJ#MgA#fESl8~WsU#G(1av^_y0VJ~3ANy}@zj8IXr#-+>u!Qh&5%DFDWs=xlfwOjftVyMHqDQV#Ovt?1pa;g; zLMu+7M!kB58Oh0;5lX^iXsJfDo>71$O zFhqb&w`9DhdFz!f;OA@@ll;2#R)aj%8Z+hF@gDu7oZfDbe1#LHVCGr9qx(Opmjlq` z*4fo(ZN`eHs^{5iztn7~A*&*OCrquSajfs(r-7c%rY(KLdp1J-m*&7pkDZ4vzV@qx z>uOzZPAGVA(JD&bv6Jb+_)SNrrm+_Uc_!5@XG3x}T>9(6fr8 z3(D$b-VmjtczDrlY#>GfqS2Z)e0 zM!NNxw1Xr;JF)0t>_TJ|OV5JV)C!s2O$l}?kpZe**C@FAnR*eTOS4oFegUnM7=G_H z&M4*BR$E@EF`*yJ5UN%d6Kv0j=!=KW>;pHskGr>AP!4NHKiW(>K`TX?o%!NH>};J& z2N0E^s+dWhnBmzsYrvlQiAaZ7Mu*Ocbd*{L@&ccHbzLagx^2rYW>3G7((|Lk4Jpf> zSAj8#Yc^2DrdIRXvvCztznvS8YDs@-+z@m)iy={NuQyI6m(GKhd~h>8a^i4VLrT;C zO`es>%(DKk!M!~*E(OUe=6WEYD@j2k85WVobH)8ZgsShC4o@gmK}4aK??#C~Q2&5@ zDM94H{@>$aHAV&VG5hp!g;E)>TYN*0xV>)efd9cn!;3w_MB7_V`cuZdfuEv9qD7-7 z{R-{4zq~ufk2P)q$(z(GPq4c?g z@O7tq$p;-_re3LJGMB%0)$Kl69yYnk?pvJW$*WVHF*dLzotg0fu{y#hcCnGmHEVVY zt$*U@ul%#Wfj6D9)o)~-<^_|)f=w9jn|^uW;@P?`pysJz^nF(_ir=C zVYk5(|9rDte3z0EQ@DjhjHAlVF&3JZSGFh3 zqttx4-$ehv^C?;(Gm+wekqP?teUp@b^Ebij=#9udNJLOmTlfb+-k5p2?TRDpGyI>u zEB2g73a3X)NpB|b+aP`@#c9lE8Gm~6hCY93>uCK=Q_epW-20CvzodFbOIVbx=$87M zfgtBsG38y_{f0lj+Wp9PzWc|ck99uiH{x2|#X8IJhRQ;MD<}WG6|(dQ#J9q4*OE9z zN3WytF58J2JtTQ^wfRSn(dFpi0VeQ~Nw69N4Whk|X-OSdDQO?PyA*PD7{PN4bn>1J zMAz-mFX0}NqcmrFMO^YK9U^_E5Eu z65U_rv(EcgKg$6Jdu9070ega9m7W|e9S>> z%?)?NzxL)6?JZI9FYEWl^yHxAxLF>R@~hh6YjAeiQJkdHl*@hWayvv>@~m}1$Z#sY z`A~*RMP(?ng7TG-+xa&B9(}8)^48O0A-@w()?R1!qtA)~j9LJ(=K%0@4yxVAL`AEF zUQC-~rn9QBEed9z`B+^`K*wwMwe-NXTIbG;>)d#t?EUN-mB0%4eXp$BGeG(amIfZ| z`wKGqdHJ&ngg4|khO+yMuuS(_;KS1|W2nX6ioW-Ykl|hy`d$Zy6+anuwp&RzP9+~< zEob*I$DzzVw5Fd;Gvwf8Psp1V}dB@@I>g+`$Mx3 zRG@npZxOWG+xnOjS}(42#cNUB7klHcCySJ2pU|t0TC4AZi8dxSl|mbiI;aw@FLTbo zxS2Lq6_ocnn-WU=sQ0LWT{K;1?R3d!y;vxoHl=bUFFyYI`c>w_xdfOt&Nt zYQHDDdQT`*+Iri2(>Fd$v#y8Pa~$GC=2HF49<_dWiiGaA zdd{aB&Zu{5AzZm}O&uN+G8Z`fXc*#G+yDt?Ydpt(`9T#%i1JA+sBeVqV<*7X?wfEl~)RJE5QD7gTE&c6@h`x?vG|j_D#k zxx-OI3*JgOLo`mIgT>K*na12mWq;rQhWWUNU**?tJ+&vr68#*Ooqh_=FEVWQWM5c` zWEB=RFL~?zvS=e;`ZkDG0|Io5297=kUwYk@=a%qNpB}O18QPL#IG5XwSkeV(p|@J% zGRB`TVn<5}Q^v>_Yz+ks;%A7{g;%~exRN&J*R+mE+{c->ObJe3Tv*@cj6Ekj$r?Aw zw7Fq=zEfgo{UzUDE}q9eLIBRK8^2Dipe2K!S#FqFs;<;&UM5NB9@hsqWtg~sMCa$M z)wF@G>5{}}6~pHbQ{SF`matB(dqT$c%otbhw4TY|A7HvwIg{sntsp1kC$!Ww^IX)v z3%-jUsrA+L`(YNuL?Mt{vE#A;uW^%6@09+WuM#&6bO^NWeZmqf-eDu~idd&Adekf^ zolvfol`T5jEp~{XCjjM4OqG;Z*9QDJ3%%Y|@pIPG$DDlffw5!FSQ^_qsZCdj$EK;SiGe<>n&3 zGU+~gWvC; zk+=pYAtXdvv1k%uR>sqJt%T$YFu5-8Jh*Hdih^IXX+*(;u7{%Nm;5>txEKEsvJnjA zHKhaCiIb^Nx%m98szU6P7%yu-ReZHuG1BU#F80d)4|5Btfmq2`=wbQ}eYY=so6#2*uqL%Z? zWQu2nXu3>Nd7EuLbd>E}$>cg7oU+xHg)}?)pCDqTbe2jEFH$?!`@+td6$5bYQr!E& zF+X;>gStQ6@Ll;i7VD{1v&%&WO_+aKC2~ z?m09kbE7T%Gu`EV0ae(+ub17>oxvpWVB@!>&;RZgP5B$bV2-;mH+}XDjV>cHBSyJd zcu!#4;q9N8F6r0!E`q_p<~yna#G~~@5$dZOILt$y?1ra!?}-WRaG0LWWT*By^+M!> zH=len{TLfOTCd8nH&mt?1Ucd$Pel~23IvpC5Cp?L5q!33-R%0yvwM#vqxS4b&3sP+ z^eAe$tu(c5^xXqd%V(_Pr>9P)PU-vnuP7UyiKC-|8!s4;<=f;#sg|Cld&n~2dC487((YHBCzjXfrYPFqJx+k<(b|^~6CRrye zwyqVXYe>p^5!+Vd%SMuXG`DLZ&bR3CETY|K{l@oN`oATgy!*)sh_=eV4&qhcoZlr# za_`=V$30M;nfu^QSPdb>(_i;oU$tt45MkFRIdX(CdAtf-(!m?pj6MENfnff>SSJMy z!<%q_N~-8rV>%wx2S7*O6w0}BGU)R0aQ4fJxa!B@yAkYRXCKS!7lY21>;A2%P!F;E z2}6Ds9C=!$fUs-(X?w_^5IenlVMgCe-+7UdoJE56*ZgU^M*tDNj zwTZn4@9YyAqII*7qf0auf=RI7*Ukytke=>XXWb<-Gi7DD^j z2ian^z`o65zcL>E^<^2^EY$2ertIW=8tL7vcfql?>tki1^%nTh7+(F z-qIvw*uR&`HVo&bo z4c0#9WnolQvuy!i8Yg~&cU>D*wcKZQ_F;U6F$yVZ(G&7o1@GdF=WaR<>g$`$U(M(R zJo4Ey&*H8W0~S={%NFm%GqpPr3nHZ1?l$CtkWdhdf!wX=}+y|B#bJwN`G!^9s}q(A7hwXWa;no2;EpbzBrV0A~KR99P=Za1Eq&|PJm5{9p`Mdw#r)8Y*uWD=v{t$ zj=a7KYTo;M^$_XT(%`VMg!T*EZvm=Oe zt;Fy7Mg5KcE7=KsB(q<-biqacI}7;rx4qqb)Gp8VQq1=A62-mTXm+w9s_<`SIs1lB zAs)YCs`a3KdB=TGh#%AHP`UYZ@}!x*L-ns-*l!f>xqdAvoE773E0YlJpWKE31D&nqr{agM=j<0h2ZK(|NO#f5%&E(P z#Hsce~bPdD60P>N?-;si^LNg-_xNUp`RiG&cW;^C)YwR)9TD0U8C z4RBYzR?h@9eIwS$olWP*_2c|N_{FvK%9oASOTHxws~|g~2Ea)m>`KUEq9Fe0eO0H@ z^nOPcxp*Pyk}MwnO~El2D9tv5x6x@U&DTMpc25@DZ%(sOajo39-Q}WES)ifwP2n&X z0-tj82an*lqP?F!&B@LVxPB z-7o_PTn(Q9u@Q?&YTCL)M!xfOa4OvZ=ty$`cEk54=m5=MWDD!MhudSR&l$An-(^|C zp9396*fu{0bTUp%iWJeQCxUJu_B{38;}4@BQS zC3tuT4nOWvSjnk&0{6+ddWSpYGzF8pP9hKgn}dv$tUk^&4VCkMP0uU}zG&faD{E9; z>HRd{a)y!l)9*_o_^>$*MJ#I(umD~3*O6uBOz6UlvN`haH01v}RN@h>S%{~Z``BNe zRGFaRx}dESq$mQ6aCuS&Ht7N1yi`PyWzXpSQ-I|Ascxv&0z^l{_y9vEVzr5tQWx!7 zDe0h%b2%C_;|_Gc>q-{I)=qIk>n`&_G&c`Y9>2^fM?lkG)uuNQ8|2S7>6VTFOE1r& z5BQe9Q3Bs~Z?}2*extwvU(fG6@;eWb+AQJ8 z>33wO2SA6Kx(|ksTG}^kS8QM1xsuGCcY7a&ydj`T36*Jg6>Yk){l)7Q$@s9qHy27j zgne!*_4kd3$Ap{utcHk|;1fQ-vHQ!~MY#TOnVV4T$~jmf`!-3Ip~D-pyODdqvqx&r zGVJUdV9LqEKf}02Jbzi=JQ#RWcROEOMdN}W?As5o!R{Ez8B=hCI!&erY)8!QI0>=+ zT{$)`&hK_zpQX8U*Q3O!vPiD0b;5n6h#h*s6W+S=BQ7n!?GBob3;U`|gSr8KU=LzF zb7mscd~8?d$=Iz3?%(kkrxEzELz_F+SEG9}kuCA@Hu#&v%rPIWTvg*;-{5MraW|R010`@Il8)LQrK6Un zo7jnxCoGRWG(7W{T+e;g^s~AyZfRiqCW7M3`W0z(q(NU*8C5bzs1wfBswCa#(z!lq z%u?E>CriCpH!9w>a!f~A9S98f&3As8y|X!!mHE)fZOHIWf~{+-)xB*n{`ulcNSUJn zprJ;Tnzx3-cQ?J07*7Js_l(H7uK8l|sYty7HUsQca>r;h}3N0lsQm|Akm%)42FpM^_@ zjmB1$=@8ztMY*5^H(RGgOg7bg$}2hXPQ-kkv&S)@ElHmmh3NL8raE=MfCWBl>ScG_ zP|#f0$xZF?q9XEo;^Zc~&qRUqh@xyXd(+(~yZ%NwRk&`31+K!2iqa|L(>%HYs&R1i zS$79pV~m$lfIy9-Ee>_uW+B=*cbDH-ifiG`3IG4k0;u#pz4uuGA&^rPjKSJYICX6$ z7#X&7@yyN7JxzB6O?GYpBR2F*E}kRtQFYcy3~RCF^S6W9AN1?gm}_cQ{zKHZuo#q=?O!8o0kXd;iua_PK=l{y&yvHCnby zUpFG-Z8^@yGAC&SQN@NES=)X=P6D zsXLvNz;EFaA(8_#Qa0H>wk{qt<2UOV4+B}`;;rjAEnH9K8-~LH+qu?)c9f3;aLeu! z1oYriFq$$LeVDy;k&TQ>xBS0E^Z%PGlS0kWX+RtPZi2XKG^0G@OrCQ7&0GtLA}=RW z1`l0lE)DBi)6tU6KIY;Wd~&g!t{Wgg`uW5wCR?VV17uR3EqwBO7s|~nBffN?DOs>R zYHCI=dO~@-Sel#vKIDqY%{Y&eh1;f)BWSMjsv|+ zQcy`m0iPBJSt*}yE}`WL2X>FQT0-`>E%C)Y4x4mlY3Z-o-_so^g)}RpeDOs)Oa$ z!@>R^4>{SNbb+8I=N@fH8EfTSXY0qqVL}Xc!?1cvSYHm+t0+FojcR+Y5xGne*oyjt zP5Y^h=1EQV?~)9zc#R9g-VKSxxAbfpURtM*TFpv2d~!aojub2+RW90V7@wTfBP~dT zJdgiPoh2P!xSqQ8lgWK4LY97GM{%2smvZ9A<+cO2UqF62Ju$Rt&st(A`l&Dd%COqp zkm1T&0u3UT0ZHreZC7r8l&;r@E7J&_>}`2GFa~t~&k-KWB?@e-*LS{UnCTL*lMHTa zzqBEXOG!I+bb$t66?P&=5Wa_ZCq}MNN>P*?AuimggVxi=PM=^B@}2Xde~x~7T~AWW zFB`5PWNWcK5VYes0;?&k1{JwhmZ~9+{;`NLzEK-_&dI*9=p_$f0Q~si*Z8M7g=dAo z_h;)qmdk?ij&utz-@X#R^xs>2FXfHom83%`4hn=!H4JTRB{4lVpE_{aLf8q*J_(=w#yVPyg*u|wKt;~3 z-jVRc*DwW$3p1f9OZJb9_*V{D!HfYHm3ReU4#nbQN}j(s>jYrae=|;K{?V32ReIAj zZx>zj8MYi{C_vrT^(FRwtFjEeZkvyP@gdK-N5=_({#`}?YFnn zxrSamfLOwvjj?z318lNR{uFN_F?W9_u%QKM29M+np1skm^1L&Mo0fx&XE6PBh7C*{ zMOxxnjCixlXn0DcYNm?_b+89NNL5_m3h=KMPU7@eE>lZSfXLf+klTOe=)qy1*l7Xa)Lzp<0~ z^9zN2Dtc}WQJY^dO^ha9{K$roAgvRkzbwa6uN-+t01HoBs$T5wI?)C_ zb~(|w@5wQAPrLXSt|GP8l9rFJ1n9 zyZk+xFR`s@Si92@{jPz$PN8GX?SQw!Ky*wB(2H93`M406NEwZ=UHx_8MAsC!kq)D0 z5(3MZ{B>I{PESdHr~VP*eYmZj3Ddk!(|9|Z-9UJpnyXb9t2SWV?pWW21WWXN;k{#P z`!AVY3?@ngz;AiYP;~8JUwj9WpCk`2W_lUoJidOr#nC&nk~$CBc*60o|DrIkaI1ko ztMy0X0p|#xwL`v7N}dGwD1FPD5+=5STpNs6LSL-Bk@o#aax-p^E<) zqomM#8mRgwfE`g6A@eD9gyc>B+VAn7FHvzSLoIf zqY~rS`D^v%G#B>jExu1FKTxtY@W(CWw`uZ zE-K++wte{#v3#EtH0~?aLHO%IL&FXSlcEvY}eHMvemNP_EZ+3tRPF;&X3FZr8sD`mS?~9 z{!_mj>kH6TpKeWYe@St*Bx0@Pl`hX&;Vwxqm7tzF1cIW95nqi2D9A0tE7-k{kH3c) zf!04nA;_f>+ZUZo-f^sdJ4X&v@f(8?L*BadBQn_(Tw(9_&?<~?c8{}SGg+y5xgfF?qALyU_m?v-}|7a8?-9?n+#^%j?q*E?o&_gAsqgbZjR95ysu z_lpfJKRdu_6&NuPuRtlY`+1)D|Hh=_ewo-(MmSmq_;#J$3;(pj;xa-PZamO) zIW@~#$V_w^;56t^WpBEjDd`U!mQ9JX@v+|kW<6Xj{>FfxnmhRWPg}=7H_JPPQ^ocU zInVH4DX%hl?2y~r>r7L0&~5Y!-p1ger4>%e=S`eF;kJ*z2<0}LVw{Ri1^7yaQvq3h zWElH=l;ewyU%pTGau#Bal$(ni z3gRx{fD5xlZ)Rl*&y64RQM{`C5}F=fpb4Dl9@I!Nhp5fX+(;vKiQ7(VypJ~#H|%3H z>X}DdJ`nXe?%42uI&-)6&5;?-m;9(0UJ^t*yCN|Y}o?N7|WbaNpe1=DG0o3zAf%YF<<*b3fWaMI6($G0ZP0W*)OjA zoKGHgz0e@#;GooBE93v3t$9D9NYB;kStIP8y9&5TD_$F+tm(}9<1o%Bl7lrxTg^^2}!nu65U!^*_)UvgeqB-F6GQG)XeWg!F5 zNrGmMiyx$?{NBxSlCryEr00~oFaV3ixDw0H z7u|3HW~5nEKGVSt&d!A&u)y-f9Iq&m& zy{_weUXRC&qaFUF6CM)vx8uT=?wJ$CN+E;^&bZ?Yr=M;5W#iQAbs#g^>$15^ZXeb_ zhmtm_mpUd(KtYd)54lR%=bot`%HL<(0u{`CcL)rEwddriz^_V9Lm2^xwE1Eo;|!a{e*% zbP8ivDt3L_Lrw2?Q0#|BaVtIJT=AC}wj-Idg*EGXd!rD@sjzSImecutO1TtujZ1ak z&9OjdGV&C+q8FGzwyn_>#c_JhunSr5g_F%{x6w&mG0I+86zp9(rd?Qa8XCy1)E)X& zD{V7eStdm>=8BJWqksC6i>5P<+66*`qip0UUHgXEE%qwqlnfu5VK)-qba-#c35IiN z8M;@74a&NCN|&2Ht9lyyXUH5q9#pj)vBcSNG|iPk`!Q%*%tkXv8}oECibNaY$m8aj z?w_%w>Ra#j%laR!;Rf*iN3K$@t3MfWD4KN1Q?;3WD;hv;kZ3*6;_LSKFnRO#lVaE1 zUzAEKO(j4#sp*h0Au=GI{g{XB)5YDxA`KETJEQS#wiFy2k?U{@6Z(9K!Z-hp!xVgr_$O~={O>cVKMl+MIkP(HCYj{JD8pQk3s!?63Cahdmm%r#=Z{79cmsVv- z>UW|OsO_e$f0jn=6yFeZRGXoBJEnoc37LbT{&d)x@9+%iu5S@DSG9s#A<)3* zCXJ*|(R2%2iWT{-blVTNpYA3$^E6~UB8Lc`ZidzU<8k z{bQK4u@5e!wT(u>H3xytA__WzOixX!S$>jf@?VX8`!2aR4todbUP84RTQWK#5;^&& zZt?g@UrE|@DtBXIG9Tk#2hYFoLmo|4mIzh~!85wMM}L(U65Y%e|LvY|QI~psb)z$h z<@j4=HT2xz*i-vfN2&%ooJpFRGUbE<5<_;k6xmp1yE+Imv-8f8K&RhmaA~aGMIt~o zDuBEZc7sdW{$nA7{ji^H9!25$c`uhj&UI42@{w(F>kjdZ*=CsL=>vd{ zg7opDosqEy;F!2?6zSqPjai^uaEjZJkBVk@pFZr{y8IB@$5dF_=&fpm59LjRK=Z_9 z)e6&a$+^uxHd!w&Am{-L7!7=(zP}Ni48DJ2-(t~o!IF?=al-H>9e}QQPuZ01y;~BX zM{pJm{}T3+9Hy=3BtJEQHs_OY2)1m&n`+FF-6aS5j~l--7>Bc{#EGMwUL`6!b5pt$ zsPaAUm|9&6vYkGT_jesR%bIwu5U5Xo)ZSzx!sWY~-dFbM=%?GqJZ56yxYfr&r-Amv z3oL-97uqWsA^wh8ck3G!biI7d!+@$Y9Y+VUO zze8Bk%>qm$tWM^?ax110vV^%6O3d-%hnuSzALGPJnZ=juTstLIAnx*!^Px^fxnwE( z7G(&??_*WKl;WF<;1{ZzPET}nw7$0vOyjrIrLO7cy|SGb^vHI%3L6??E=G=0qi=c# zu6hZ&6PjD|{T7h$FP`r#} zLbb1{lqt>EnGwkKQ7@Vmjvdh+O-ky9*L|<{l0Xu~XZ55i3XA5{FQS4H=(~)bEVLkq z2tn=Q%LB(TIj_-KR$o6c_^Oe&T>+%|T@bO{dv4{jungfu0jc;xgv$ygz;j~_;%(Io zg>X+;afzWAXI@J!y|PG$e)>fyZ8Lsy)$s9&j`r8(=QE!k^M>smijKn+P;4G=?j;(~ zf4B?*1RW%a%Px}7^|P5rQ@JLpc>VR)CYkSM?9~)fXHCsvjcY1$F`R?np>9K%tF5e?j zVQLN^O$*gvwf#`#AZ~=2v>o$vl!B+-BULs$PyCs|y$;3IA{Jrn(P%mRXg4oFY~N)G ze=rbmfHMj{`L{U0>Wjyvas!@WZ$JTQmrVPZYaA8Z6PNUNnghi@E4ea;KT1m>J6RNn zRjC@MBrYpl?Q9uv&oex2;{>7uWQMS<8S@dt^fXJO^_!Rz^i(240^p>aUQupCiprKK z3?NRaQv1%Mmm8xH-}*!0dJ_W;x--9=AHrufnZ>&;`lIj)c7U?1nP1eA*0P%SJlR*? z_If}A-lS3iXqCQNuzI3AcRCLY*WUzGyh3F=L9y$4nWd`kZdICci+~fz zHUyX-VW2G%HdXpQjIuEW@H{7D1%7eLKqj^ks@1a%1^qhu&kBL+51Qp?9j)3?An0co zCq$hpjh{*Vh(*nmD@rr**4=Lf5MaUmHk?04SRZ=GjSOZE#F%b0oU_kjP`Fc4I z`Z$r^qx>EYbE#cAvYg0#pCGbll|T5mOxWp8Lb>mvRXjRaysZT*r~BeOET0){@NLF3 zL#l+Obrp%FX2ev%E4=pb(9>;>OrcN3`cmA!H$JYf!K0OGU`E9PY5Ph$tx|>xl;1%G zpq0Yw!ih4c{?sAN@`itFinHDvQ3Vr8c|x11bPrvET-TOt&$;!3cFl17JyyT5wUAQCup? z8PCBzNO#Ef1c^oiES{_C%1^cAQpcAHQg*7i<`=xT&h`}j-Cf4vN26RAcsE)a)O(e> z+g!WnRb<=~eU%XI5V=(>o35}L*70x4qY?j4m$t!Uw6v<~j&UTw$FM}wM4KdIVI|AP z)W+`RpSI**t3$dKLrNv8*p|y<8Z}z*uH{Oicn<5Z+D)ge?E{nAG&Czu#<8N?m9oCq zsO!?=lry9Dn;~k%H-97DXHMUIWwoh0K46=pwPjCt7MCw%&tU(|k8En?uUiU1m*tUb zEtk#^A%(!5?L8Lgfl4E^5~ixY$z1#P@zH;>!m0YOa(Kj1+Vw7rm_V4LWVBmhWJ~s9 z>Ru zru|Z(WLNLB=65}QSY>b!Sw0%V30wXe+^O5zy7mq;5QsNe@E(DktE_f(3f~) zOTu);YMGIpwfYAX9&JVrrOI7Oz|u!L#=#PL@Fy{zP&gTSYsds$arvg5uAS$ivsEOz z^wn7VNmqp=)+}OqmqvC2$|6>a+Us288b;blxkW5f)Stw;LWdCXA^L#2S1_TS|Movn zvo8x=mh0Itzlja0o3~GI-!9W;n}T$mcvAXsP99D>n9rGZ=`NcE*BdIpj_&<$>tt#S zpG7mLfQ+43oRI>FT}prQ{wVP;1BTls%E0skHq?Y> zCm=9EzCVMS*RXzWbHk6OL-M~$cuttex|se~;6o-2yrjZM8rC0Wx9TsUD`mU^KKZA( z(+4Rg?HS3ge=AP!AO}(Zpxx``*OS&8bvXl(%z0ELD#Ddx@(J%mijL|`{&?)z3 z=6Id5^PR`9CpXXs9G@CngNMiey)@GI0CpBi;f82cz>Lj;FF=W($>UQLI14FbR(Lbr zHU^#sm01l6e$P!$DhOy6Grlhr^m{!OCzy8U8E%JJc<8?{h86M4eC%L0`jX*^%%roY z8f|?=gb0x%i&#E}FY+_VnP%*2->;pw%#C3)pLJ+hczRObg2$@#;dpy$XmhrHQ7_qj z*)EA#dnjL;N;}8TehtaCB$o9~zUJ+!A5A@ly$j(a(Hl%QraQ0M2`@#hnLPL5Q_*vQ zN@w(^XwMBO=g+<~oQ>66zi;rl11s}8(T6m0$AfRd0u)xKg&Iz(#mI2-T}#i0Cinb} z2uxb;x&6aW3@wQM>7@;~kuF_pT+WrGy>Q3~>t@_Car6?a&@7%>S`biKz@~MPExg6W zNgX2SOe`7?Tn}-5HFz*hq@${IPN_*p<5(`5ul!wGBm82&z}<{k2KYTf&D786MadOC zgz$ocv_&F`E)MA!dgJZXyB4ovWIj3|_$<<6YDAQvika*n0Uiq@3LGxd$jZ zSQ@r@Q^-vdEla4!lhRA%(6``p>iOFt8kWY}nPG&pUplGMxjv2IUs|6bDJPV+a9Da# zW6V*%x0!3eWfsk61O3(bPmvj(#`=h z(~mu38CKsoqZWXwqR3Lh-dNf_*J+u+MMcNKWG~~<>O~3wx=I1rH^x+Xh(}yGox*N<;0UsXUfO+%7mC%qlz)ipgNFByN-K-BY5?C^4#t=?54ZO^;kq4 z`eW=iXO2pOr}4mKk`K@t?e<6SjR`fsJSulkQ0Nv>Yn!;dB1wMwNum2mlG>(zANMX3E~0AwGUTX{_T1}3!m>>{1oyL@S9L# zY0wX40fj#ZMFh|Tap6#p-p!x;9#ikWNw731oG*ZE5U!h$15RmloF<*~*M68?iRNsH ztwCT(#WJ94c5TO)2}T|)b!6zlQZ9}V^A;v|&=G&R_NRT?hHas91S*p}xHrYl06yXu zU9D^wTZfKBe+F!A@%0Z^f~4&w-I6OjPChH^yGB)TN%VZ#6uS6@*!?zbx{(9B-%LR4 zedsg={$~pPYNSnXpyvt~lN&1SZ`tW$h3b!%feIf4<2N*a(ql4t*I1@A?ytA&qEG(-<^txDbfqKLzFi zUJYwfYMlCuy#$syy{U>^Xs9lk@ECt9MLU=i&Fn!%%NOy*E9K7benSrR^|YAflcA?l z7DYzi)%SG;Q?!_C?+W?6I$UIhP)7p;+r(Ryz2Lo%8RS4I2?f1|G?&UFM~hS3d&s`= zW&iyH-@Tb%ek}#Xt$ck?saC$!@_rXT`FS`cV{mF$Rrih->g(?GI_4dQg;8SFk*#L& zl~jeq z#O6Q8V9}%uc$E0)C4gev@56rlKtq7f&So-oFm8enbi%`Af#+|jpEk<-uk8mB_Fmbp z`Y&m2x4mZ-WTY$a)?wN3g#x6jgSrL<9@L6dkoRNOQudBx2nX6zH;pdQM;%6+*dx@` z6uVj-^zm-%k=AJ|Cu9W_Zp(< z-rgq>X}S}JtlySw;e=+d*y;bZJ&3=(}HM<_oJFAYLU6+@U*=pDIxFxB8TYF|Oj<)9c zA<>z8ZNoZlYK8~Y+VLd71307v)gauM)7S2%SGzYOa<3-OX+UdH=Mn27uRN|B6@}71 z+Dg!8ZAjZoRIxym^<-oQZUGj6eJ%aUxr1|2_n;jq9e5-?H0N=breBWDAXj4Zht?FKUS??Bmf)r@uy2LH@ zDVDVv`IeI70I)J2lsbuExhz%NjI@J|r-j>E7vr33#2hnVAbuYj@zR#71o+IDDexJN z^jza+p|DXliw+sp+VNI>f!Q)0Azc3$J54gh!}*2PMYY36jKh}$W`1_npS=vNFE`pa zm3=p>bf9mF5ccO}?9^d-E>~t6X@bZ-G0RC=jq@cMc-d8O`c%xo#9#~ z^UCMlJfK5APT32MsFodP#dZc!%y2tx<*HIJX1Pyoe{<3gre$&Yd7`k>Ogzf>3TY+5 zlq$!>B$`^~kr$~Hd9Qqs6{k#X@(JP`n=F(~^QX`sjp|itc`9USXfg|tUvr*mg4a7t z`f)XJSlSwZd-$@YtTU@U#mXu(UDzJ@vo;K@>S+(4&$}1T*a-TC_1lFZH1WytlLk)M z+RfrV9=8~L=}*H-|E+jmgF5g-1Kv2$Wya`-DD4K~TXp*rVBvoK8J3`m+h%H*b`@+e zy3M44cMK2SG*}J#q%t=l(1YAagmlU7_uAn?s>6PYVk0IUOko$sHpG3gCA>_`*G%2i z?Q@AwtoL69SHv;O@nH$+t@V5j`teO=sg=!8pIckgse{XA3mUWY|rdi>=P7qWWz8u19`#_4cXq`YY1X z{B#kCk9nvO^hn`>8j}Qg%Vh=`QmDlX8Zz2Z^x>9H3B6RPa%+*k-)4#hyWex^F?e$M zTL+c9{~|ZKG`;sPMGa$9iU$Kc!wZ2FX-`odEOa>WOi+GMXaqaXlVP-|#z$toxLebh zD)?cBp`q+#wCzHVvE};35xLbLwq>+bh}@QwazKRl0XQ!L?7~VW8{>Nnk%F&%ICNqV z_stDL_{oHOVK$toF9F9HxyE?)+aq`2eaw~pw?^Rcu)0w1)aU8f^wKl~ou*Tq^wfzKI155mY2E6uDdT zDlzQTr%y8FW3Oy14r@QTrE6-J4_})IzMi1LoJV3L9bjx1v1~E{JM{`EAj|GJkxNxt zq3i$keUm@1@A@k^8mC>{uFF82=|7XP(aN#pd1hg}Dj_-E-}sQU0=Qv;2ZVKGI!pzN z0_8)=+zY zu>L@jM29O*$Z8SqUIMI}{4K;*%uJ8IlCZ|rZmtVra$5uoYrQ!MFCCibo6TFhYX z^Za0{bK54SG*TG@S*k;OLz+x3^14v^K&}w&|NN8!37@o^2ETz-+(XDRi&mD8`dMYP zla79#JIRc&fIf7AbH7_JwYz9ll2}8>v@^K~&{e-UVUvB>=gB;5kkZA&j7wbOOurmD$h2$YE0 zA=x&>8x9mOH^qeed=UC-E<}Hx@F+ZqM}xcEvPakAvHq37hRjHe1JeR)&DLmKyMM))rL8GA;c*d=IX zlgn5x7!5#qjLtHs_L;birfgti@*6{_7XG>n;s)w5 z$6MQ=`P)y_dRGmqG{FfFF}j-SS=ZggOL=^A>sjD7IZgFkhO)WK?-9b!sHfp*gVo&A zo{Ky+|IZG-J;|?1bt$6dC1LJ8Iye)-yV0^NoZPIoA91o}MrSaT`*=<&mdI{}RyfZo z--G&Vw5+PNa8rD0`4-bcA}fW-s&akNyFN1E7Zb2%rtf-FPje1QCw!*BX~+JDcPpc! z9Pgc;=k6bg$NZ^Q-;bZCHeP$!_|h~I_0FcJ&nxV;v=keNkR~;B_eR06)u_ zU4K6%&G4cYWuc5Of=399KEmqT;y6p%&bB1-G~pgwU$2>sRZVh)r9V}>>(P9Bu@aPh z>CpncT}po*vWtFu0S|P*>)P1PsbaO`K0N?lNMt znrZ0PK2WKt<-OY32Tu1*q!%bypUN;;@z`w_)ne3=so!4XeA>Fxem8?zD7_pb8aO&m zHt;6mbdk5xZJgaQBU0uj)V{^f$$n(uOY(DyuB-P4Rx{C-&Vo1X1bY+uX2mCz?Yd0T zUjB5h;`BAy|39%JJYt4ZA4qQs5*A1-2gslmCS1}0U99}qQi3GV8FzpCZRtn|LJt7l zAB$}@i?b>h(}FLIG4yAqQBU7}rvsy&ThTPMdv)hME%pz#B~-akEek>i6hSNWN1p{R zG)kHr{&R-wvv5VxT@1LyR;eIH zY0@clv$T5ek!i1kp-|)ThvQTe4)66bgpsp+EB*C|Kg`y9AtKTu7-KCFqu3aXlUamIX1_0V;2-pQSZzeCk(BHAJXND6i1yy+=*NG-;WBk0mLPGv!%STx3PH=JY zfjYqJ{@vZN1IgPR?9cxM$jJM68kgj1_XtR#Fm@+2kr1B#Q{NSjD1*9M9Etrvuv6gB zV{%`!2&nNqUMp@4l}FQZyB5&wUBd{;4!=?wDr=Z>%ZB_3^W2VnBl=^7v#1<6EK1nB z4+>0|q_G($r?9xROp~Pc=@d69B{~o``Dfj8J2TYA0EsW1$0*8(;dSayRwW}Mh|+_}kif~CToemW1$yE>*F zxKLa@_gZFL+c#hK=VAgjeD@HeZnJZ6D0|wUwD}#YyfftNP^Ojgyn0|ou?0aJyiG7- z;v6ui4j@9CnK|gHBUl!k7EKi$u7F4?RQtc@l#4F$W^}*PUzf7;V2qhGFH6p3W<}*4 zdnomnR}1gyjmR{PJZj{B%((U=Dd3`gd`Gaa7Jm>{l z`n|8K_u-<1p`Yn9Pf<;Bp^PN~emuNrv=$i^Ki&6< zJOK7u(9`!^AgzEyS&a@F*<&==OC!1Z7xD zXb@OyMP=}{z%#4}nDHc=^cxArIYMXo)YH+W(t!D&(6$dsWd9pB|&#{cr@O;Cu^2$zr;F==%e5#ernt-?zvS%}u4;Tsa*0`#> zbe8!kv9`k)$&Z?-`L7y3b{(&JH5k&CKKBC8b-I31Z}DtNoOr}R!0=FFv*6o#0SN-7 z%xd|=ox;RCLxM-V-ufHuk^N^g-e>^1&n29a-^EH-$K=n>0`lY!Q$%z(B*2U~x@g+Yx3c$h z6~T^RFO(LwTs&MfruCS@3{i4C!PMxMgaCXC_W%-E$EsQP*E3z_6|PXdLsVv9U4AA- zOiX@P*rk;Zf!y1A*co7=$BRjp9oR8jEyh#$SAuwaQ}h!~cBkL4c$MI5Q5-chpux7K zSV1}#9TxM}gO#vWg_M78{}CU{Si+4r6*)MXt*CP~OXh4dPh}U08b4c4g;%zuaqnGL zDAu$VQd^yQs?)L#FgQl9WIb-!+IPlWgBJ{C#6ZzaMW=Li>{C_Mimrz?`2(=50k33C zhr}skKp%JfMZ-P0r03}^f0*McL^b>QVqQP<_JOG^yr z3}p>EEnR72xYTL%ywn+&!yMIPWct$xF=^JIW7XheoXPx&3BneMHBD^#d>^fR-`Hz( zhf9Wwgo{)(^!{o8|p}Qg_Sq zUvW%xDdS*EiR8$_I?pYLYdyU>@-Q^uycs%d6hJ38Acv73+KmCgFsQcU#*C1KrzD<} ziDpZd!*`Pr26ThoYnv+c41wKaU8dXKi7J9#Dn%TjoE`ahb4DZ=@DaW z+ohhA#cCPzE1PD!hd9O$tKYfZoJ3AWpY2o7rwt8-AP;ruqQ~s46x@4K!ZE3{;csge zU%G4*?{L2kCLr@9Y`FW#vEKX4=M)G$*Igms6yx~fch95;!^h!Nkc0@|Haj>` zf6F*9AvQwAZcCi9@N7}iUXpdob3rzpI{1?+r>Fo7E=yv$7-PmjCgjkimy>zYyZRW)-aGD-^ znyF#iyRup9}f$Y*7e+?;5c{=W>Fs}LEa55OxRR;Z6OGHGomjeM_m z6}KQq*b&)nF#);M`%EmZZI47ddS>-&OI`sYSI4;5fLkA7EMm-bjb-e z!F=>E$BsQ7T~k*MFeAmdv_W2z%mut83ZQ`4yGntuoe#L6Oc?eGUt;QWCpYp@n(`}O zt}e@47Y)V|WctZYcIjvE>4f-R-s53WtH&k{=I_;{teD#EULQO2bdiXNGo=pn z|D5$eQ#U%fQId!*TtRDlG9_E1*2qddt3Y#BG?M{fsjCq<$gI5y>NRoW^|@@zR`b$t zrMiK`6#!BzR{daq>(jr#m3ajD%oPa4xqkTFEP30^CulXjeahsrGwDSHz``IPdZ4Lo<-5FiIUhW~h>~1AcsV^FirgJ+eJJwP@Oak2m!FCBqkG_He>4?as`-C4 zXVk?>ZUT)w(So=P#xABy@|*xc4^);#lsKXxD>iQ6ru@^Jtv$< zs)VKVR)q|fncE%Mbw%s^b$zfmd&y1h|K@M!-7jzitZd5Yv%5^E@uI$DebfQcGGVIR zZ$;iC)<3DJ+S@d7696duIr0iJ_RKFGLoL2nn|=Jka8g?bs#tu2q<&0!C2iY^)~Xk+ zP0F*dVSKaMr#J3`{u*%J`&=~&!bUJL9`gr5gYc0RcS`TQ$`bkIzz;z!obu?ee#8%z z+R85Xz2WGKC&sB*lFVy7ST0HpkuOLje}+4E4UdPn^T}w-pR6oaq*nTW^FC+^Zv{!( zi_25glQnHQH1wF@7q~p6A9ul}kyms3n>+tVgLGq}v1C58OrN9@0&0JbtgWRl<#%n% zRAc?rw+y^y7>@1fI3SW0Pr-6mKqV}~W{b%rHViM3N=cROJn@{9;?~#1QHpI)|Kf9r zt)(p8n`O_=w=wXD<>r6PtS2YN&vDDvS2{3u#&Q-bAmCpIMiuhZS2?)3Fd@Q8a<)ybY_hb;Uai|A|C`UQ|%H z<+uHM7)nOZM1!%V>#jabEb6~lqZRapIe4quOGyX;Z>H~9UZ?i6sF0l31 zi0HcR8ONvr&LM}2NDC>I0mqth_nY{0Kjtda4*_z1esh*W!rL54-7S&WSK)(Gy85YA z@_vdI^wU8-g&MQVP6w&)oLu|$hL59qQX7~{;(>kc{3c9g<-zN;3mpy|+Oh}dgDC8T zDUy72ty5K@5PUx!a3$Cf6o%}dbzp00`my%X?jZG$B)LmOeh^t?TfPTf(`;hvx2e5d z7$J=6)PUmwTV?Asuz}>vz1rP~fa}eOR`1~JOX^?+q~e?(oOJz@nAcw*-P_tYB3UX| zIEWf?qXYyU5I%0XIChWeD!uZG&AA}?$Z`6Ltb{gHb>9#J; zPGn8h+9r3$ViPR*5a2>ob=mT0mVmULmOs55`$nN?V9j^t@`*hz`~3_A1AHiFS0ei< z1qqv`^a#opg&<&$~J77(n7D{fb3tx5G^*%T(DCiZ0rZ^!JP9x74Q$j^C~g!qP#iXMs57 zqb=H+W(MXRN6(TdC_QlnjkCTfXg!g$Z@}&9$-K(?u)aH}tN4wXy34L&f1E)~6x^Cm zuW4nV@Jm6F_`T}7qucUV7LGVs*j%xYWsnaZj{EwF9 z&e4mnM?+O0p2q8^4K3i}#M0~Q5rylKR@hY+jQQq&;Yr+j@Xa~_07&pvUX29fwP}La z_pc!83nf^>vK!&)<#8YFz#{h6`r}AQ<=LegvJwcEt_Hn`dg9F!r6I>xP(YB; zf+c(E6{I&BXMWc??2)mpX{08}S^QD0O8j}G+pEcI5ttIT8Enx?+_ND?(vw|KS(|P8 zBn`k&OFwAV@_^>kYN2nU$oWAU)d!9Bd^_95t0|hx9M- zHz1rU(8K8{o5OLS?7c%o z{YnT|1H@A%PGmLDp5_XI+c#qmoyfVCO=6aErFXpslrLgHKMv)q-=5f*8$R_AbDDw;gPcV)6curdw2DDAGwrf^u% z$e*)+0>(hM7xAK2Y{93wt)@XYwXHBYd~b&SQP)6tzofNu?dEjr?UjJkr*oq{nc1L< zqnJ>`)X~(Q0|zcbE_KLs#d>JZ>)zSUfL0ip?9bdX*^>u*HTk7?JS>bb6TiZQM^+x3B572l+@??QM6MJ;hNA22AoF2 zvXbQ=-{diixklZ51d*&wfm!UP4K7u@e%Zctn1NsFd$2x1fJM&)L?pv5>yBmmiVm>xYGVABcVpGiB24d;QkN zBgXe}GL>^BGZ9eXBPLkL3VZO4`e=f6Cx7(j__AGQIsX*BB~@q}_$5G&|KLGI83qOT z>NLLIVAB}qHYUkcC*l2Zz>d9o+V4UkyewYjSiBigezTZ=vB-9_*jgQYSq%#XG+_QO z0tI^9=_4$6Aj5w%?_D<1UqowZZ18epg)-xtvP_MZWz+lZmi~BCmco46AF4X^U$Z7^ zr*6JK9kX&H2@Y$15pKP>*ECmkZV*|$Jds0eY^ZVP;5i*~US1%7#{tgMw)qJKeTkH#wb4+Ozs? zWVx{iO4cXr^(Y0&Tc!MZ{#8`!ZwPfN(r}%&oPmKEAT`*YWd4*;kC+kNIx0zeQ8RlnKSQ<^ zq#ym{A9X9@w(4P$^(oLYmMLHWv_u~gw7orQB3dQJx&BpA@Vs-C4x{u}L}g8bS>Z?4KE(dF2!b>B=E;Dz`EKK0etAvb1r3-{H}@`)jzk%ZW`TJl)Vo z8|r7P8$XKYQabI9jR^wFZxHvA=V{I9?*UA{zmA|cd9=QlKTFh=e0m&3)kb=r`$0d{ ziKsnYzlvhH)ssK7d=e%Va1g#j?7K!dwE|A3T3v1~mO%>mV|p8#7B9D=;M?lJ4IIgQ zEJXXl@+`naQ;tXEonA6x+_u`x)~v8!6mPRP4y<^S3g-6JAwq9IycIQ(e_4&;z#a))fB{?lA-6o87zF&^BpqMh6Nix$ItR4ssrJdnXxvB&c|CsQ&LV#<+p^|;DeJ+KDTGNdDRa|F*|#HKdr!00JUiz- zr|D7n?U{oW7i z*O+IL8AhyS^amSH#4e>C%9!j1cJ*BEWODu#c(QgDe0xTNIrGPOpKoV;ZXG(WGQF$< zvEj4WqyuKE1C11K$B}pmkGFwao3q5PeOjvnce`$DA(Yw1}i z)Yn|TY}wz`6MFxuD8RN!djoZ2WTv>z8Dokpi>?ejkR;CLF<0^Cu&548V*lr52a?f8 zm4djf&@<6Wc?u>%B3j2t~ z$W=FjE!=aIx9J>MlC_LF%ri%Qld*D`E$Li+Lv!W!B`IyyXrn!42e+CBi4?U+51tle z7vF{BD`rz>u|_ScN4JgsQcdN9^8y-?6!MFe&^7%${m@t%)mc=}Vayfh#)z4$sgQ9a;ebjrmbg`MX zRoebHJ)7q`Z=Xw~YTc;Tcu1R#Zy^kgo)^2Ky7qZ>4Hm3>uN)D^eqwIMTR&U$D{w=? zAee*NwLeYUQoj#*y}1mUzh0r|V%ZD6+9mK@mn9wc8U)tC#%yUPV-LAY5Je7dRR$fU zeYJ(b462#{5+4~bqi0-UVffr}?pE3**udshqRq+3W$yQ*Te30!PvgTDVI0-PtUSAs zzZFy6^6v`Xk}Jl6Jwx~!r@E3FyHjmxu))C@Q!`*j(ka`R=I}M}Qzvg+Mnv~rmj&$0 zOj?u7)6BNl<#P{hlb3$5;B=`K#eIkulEQYto+<15x>Bu9Do7z2cqISg9TE@M;$diB>Snn>h3kL8*^~(0}nos z*T3!x3Vn0XF2WR_Kvv?&k(`rC{)ibJWq^8}rqz`ZIpOIPE|1OWTVdr58^r64)pwj#97Ezj%qG#{9#g{y6X3 zDy^fO4CKw6LmSSR-?)J;np4M&u|ww>{nFqd3p~vjs(os|iEB*dlwEVF!f3z0^Ewye+0gK7_6E%ZRp zYwes%UM=Pz)%U)W@NmW}(Q9CK7+D9tS#aR;_kG{@4Go>gyjhv6`R`5%q+iqZy!(QV zwVhcf4LU264p%{=)*0<5R4pS-9z4p}8L(a@`ob)pETA-eu`qC|YX%2538$UCPO~&9 z2e$ON7d)BgtkH3Lk`4wQbfZuChIwrUUpnx_^~I+zW|xQ8O`acEwCc2O&DkCnZFMH7 z4?b7Ciu<5Wb%F7_vI3)wywXw}<==hfjpvLYW-$j}(^)6muR&0!`^is!GM(%T^9k|0 z@40tdyna;%bFa3<5r)6i1s}ZC8+ryyXsh1j3)P>iAieaK*XpKn1t$-F3n}r{eAd_` zgQLM@6E7C@@S1cg+t)PaNm-mY)fZA`Qkj9>P7P;*oQB$i^vcffJ-xjz-S7*QZ+Cmy zA!1tKs4*$2F6~r$F0V&D7bguz4f+hGoMCr*mp|8QEX)(t2QQeO&4Rb;Pu@Pr zs~t#JUNAY)ULK0wee$7)GKk+l&YC%+CbH#3qYD8}beEU5RpnpF0=@@av%}U^8NC+! zcsBc}FSM-4}W37mGzLBY{i80E_|8}yX^^Jzyf=ggx zeg54!K6r9~sIs0u;RBuMHF?ywOnNQKq)%StRyxbObT*`3X?{x!me|*Tzv-WrRi0cu z)qgpYR*uGJGs$8D<*mqC51DqM*lY9Li;JFppKIc*4Mykr<#X0UtoE}JO&;h`ukwQ< zzsY7M$GN^58-F>6GynAyFC2d9j~_ey)?ei_-LJ$!n)rPm&8trz&8x6?+cfxv@hFzZ zQ<_TKJH47_kTbE4uPTT_*6`m&5W2)pdhbd<@W3{K9_N|L6$&$KQml^u#^?>s^K??% zL|;Q?)%(k?U7wM7n$*+hpjS-8Z@FV?=FC z|5qB`b4|vyIE1G?Zv7ZK_ieR$JMO4SoB!bEsKK}V!j$aO>+l;mVHV=(&u!&4JSDGo zMkn}wo#SKcpH^Li;!Xdkj}FMmb?Q5{9gBafHlELx`@P(i{Tw*7j*p8Kn4vgi;pe^h=DYj8vUrO($^VFwG;fQyb(+;ECFw4Rk(4UqM z>!mxFhHiC#Y1-5{YBHZBiyLDD%TaS@(HyVKc4Bi;#&Y;9VmMK|tERx(r?%Yo%nk+P zYD6>U>8VCR;md#O}`j`mg``!w>wx4;;SbTfSx4 zzc!HgW^K51{!LstX@2uJfAjDMfA9yhBbo!)E8ilTMX!u=2BY^ozT-O%-}sH+I1hr& zKi>(hAOHBr58^NX@-H8L{^x&w9;k7)cb>TCtN8!PKlvwzpZv+6JbcqPebe-b=(-xN zO5i*RWL(iRz59X=xC@(3_DG?Ps1gAutuQUqG;lgSi(!i>6OO(zqM)&ZISvMss#6Ya`8yMWZ2&``&UD7B)MfCqAhgKkQRZB*zyN0fSNR*5lm%l8_Rx^YNy~E7c>k4r@6W(J zPudJ@i4KXiAO|ZJ=g^Y->dZnIjis}+U5Q@#dp#At>GH_XM8WPP=lygbkjIh0S;OIF z(DQqCV{C()dPO`0Ty3LAzs?Jl#g%BPe8J&)4^JkxW!jorN6mgmP4zmHNyLb3DY%N) zZ-;E=a-_3$l-|PbX(-H~4Io>EV;14jb*~&XCMER4Nn?>h-zE^VEkCd(1{`>uM0nr& zmQBu(5+h#G(VYaIcC%9fZuK>ge`Qs<4!xTU9BTR3acq4m(ZazK7Xz=!i*oxiez$IU zquW$;q-m?Slbd5%#Hi1OV79u~{n7!ak;!E3w~iX^=>9m|?#kA1`Se!@?sLzrbALEl z@MJP<@sGA!^Hs82@--~yOPCB7|J0fK(biacIGxyg?Uo+p4bMr(LGz@QKi83ICaub> zC1!r$RXhpcTfXwNBhBQJBk!r4r`0xfs=t<1u5zwTRwvS%CvDQFP3lM1fsE2-=RxV) zXbNG+9SN0-x;U_=FNlmk{p1UWU;Oyz5C6|!KA8!3&N<50pT7GW-*@=#Z+PF~!o9Z~ zK6poVDrQ&Bln?J+K$4Mq8^);~$B%>FKcClAIs4e(ahE{>b1mO+vH?;xYS78>lC(J| zA^Bj|KjL5VZ@pwC&SAQ-Ik|79uYkO1=y)*>12iO{VcEdytA>>1b-{1aFW#NW^rem( z{U!U_aBQ`cL3u4-Th<$1P%|Xuj~)b#WJfRXRW^{QqtU(4I@jIhe+ND?bq#P9RCY|J zhTM;Q=_bF`slPMUany9)pntPi-_tSrO&JSOvbA8wb8Tqw#U_bZSbB5~{cLP!XXrSF z%^oC49h!61|GxIxdJve+?t#dV$5lb7I2W=A2DVG0^%V?S1P61S|WyoV8N;y&?KmR6Uz~1oB zQNEzkuT9u=I_*z=Nn}GXLkxA>QrrBbr~JHD8Mzq$J{OypZV|~*V~jK2HH`Ct(%~Gu zi|)!0oVt>ASwKzY(9FUf`v(~cCyq?rj+EF0S)Cz1mJQ-MYHEwcUpc$_w{Y*;d;q^R z&XzUTRp&Tr;+)3!2c5x|`M|E);cpx$%EG%bHDf-~xBICN{VBX}Kgy_+JeqgpC9*BP z@>?2aT^|*+mY1!fD)0#!<|$qcRvP^3 za&<4gb+-&W(u&8`{dC3|bd2fVciq49YM{9}XQMcb)J~90y~dM#U)~D`FW(kruay{{ z;VZpp?m*=!zbEmffvonSG@-S0za8F`7d&0@2|%yFT*z(^XVmoRq=|u7L#nsR%pm2- z77X2?QyNb7HkIVhdGr>xbnoTca)Fjd2`u!k&avdfVpV^;<-{NJi*nx1JnF+{e74ZJ9vM0##d`t=hTH zg7K?hdE*e&qesr=$MCfKJU6>QGy3S2?QlfvhZ{^BO?ulmk#`+E%8Ko)rTZ;ycr1Ov zkJnUm*+REGqCt50sTU8w@bSm;sqQE9s#XqcPyFad*5|pu{)4w2zWV*|J=}g{9LvFH zGEH`R&B}F<GPeWlzQ)^^9mo3OsmpUz|)XCP>+5Ts*W6lJxYv`Fg z5hjMWs;^Vp+;_aVCW~3G0ce*)L+aSmKu7dv!mlsT_I>qf@2IgXnT1xw-2<4*KVB}; z+j+#Cq=l4`3EiU4!lyE-PRQz=hRPLh#dpM&y7q0zgOu*5F=mJy{`$M>37v1%cC@<` zoIYSZ*}vR=kF=cgqk7{=V5^+Lcz~CT1da*q`V`h-sC21KYMa{NY1_Q4oejp|OdZ$9 zfqcV_H)oN4+u_dJZ#&Aa`UmP&=~(8pjlF!o5_{N4c*9Haw+*>U+tW}49f#P}mHNKo z8wW+^I&^KUGk@s3vG@wxKGjYNau`t*=$%}nUv>qNwocBYc6`Yy#(?9*wvlE}==&Qf_s}I&UVgo*Y?bm+o@E3pa7vr!ozW&5d{KUMr)p=QA z-^!I!Nc`1b{nc?2(br>uBdA6oXX?$r%P>n<(o zl_r#yE`FUwV+*BxyK1P}B-eQ;H|8rZ==fruP}@1+X|3pK6gc=fVFcyDmR{Df=r>6- zSz7mdSxLh~=`7uNkOsDRrNJ$&LD|-4!1C&o3H%51xyE~QMvVzd{>)SGIWr_U;6djR z?}lUWXV5PVtw$a5TpRk^(?L%O(Ez`65q|O&>DxjOU45G1-sGA?f$mMTIJ`XBgDXg8 za^bhS!}L7$fVX+2MH>C;)K6tr*_7TsJ(&g8jwigrgRW0)j+zgD_`;k~V@vIxw}H(7 z4ZgdYDl@d6(lBzx(-zRGESk_)nKj>)ifMU$igVenNxY}X-Xk`dugw&Xr!kFWOQvMf zI?AK^E7$c@b?pwYGmM?$<&7LQh@+>GX?~;Y&34p)tqoOHrJ+|ck%vyafiG-j2+#1r z?gH!Hju(2UTzlO+YCLH(QSwUD%W=ATed5Iz*Kdb2ngnnz-Q*DD;Io59yPn;0n_|$n zmtAQ&$~F0Y>dE2d$>mJtXV}O>37*hfeQapQ7T}nWGSkYA_uB8S-6j39Cxc)UV^MR~ z)1!|*a(FaOGySQEH@2W&Jgf!bIx}kMOW8R;BQnLGe7u!Tw26BiELy{3{w@8jcItp) za5KT$bm+dansUMQxi7wW`1Lqx{@+hNb$BelKmWy-4qx+uTMu7z->rvle(=u2w}o0KbOUtgRb{q zeM0+&V(3HCULO1Ur=lzTLB-(lXN%qGf?oBIo%oJJ@Zx_h?ATds2)<)|$)^{zq&{Ov zU!Cq5ck^|n^a1+yk>get4rBRIzA2A)^h&EtfD7y`|0ADtU`cweBh7&m^F>a>-n0%j8_e&y^PZieBcZ+3-ODXXS(L zqYgItcWkN6I_K~4$3MSz)WlIU3;Zb;p2L3(WX7C%4J+yAwbAo*ykxzYqQizgYsnrxJx${FXJ9s-r=DK+Ou#sEvXxP`?_BKwDv>gw8*@SUU-#>EL$#t*} z!d2JGO0Dpwc2o~t8_XFM=l?=a=eBeq>bqtxmAUZiudlC{+L_HkqpvbHnY)SR!^#_* zKk|`}%q#44W1Qq{Hh05^b%rl{+C?Jmzeez?lh=^QkF!X7vP;oisR0jm>N{WOzx1w$Xw)g*{#1l@|1(M;Uc=LZs8|mPGW4x4t*$d1U*f?bLR|aL_#R$ip)r@cxR* ziyTb`2myZOOJC(uy30%DpuB*d(z%zJG_caZf)k6sc)Kvdhrxl<>7Ms};BaSN^;iq1 z_Y5C+DGvBf>78LV_)CMjh2nP=O27I$x%OI>MJ*gHZ!p@+w>mA|2C54eF3e5`^o(v& zr%8r$NSvoqdL5GbY8(RUp1jDWL49zdZ!fcf4PDY(XDXQqj00xv#OR<03T8E@qSZEsa?rM1`6MwbE};BDyBsP$xN<#ULblz4h%VG0M{46vd> zp0hz9PrRWIoujLyDI-W%_t-&XXChtL%5wlWSb0aA37#Mt{1yscX?e3VYS4lX_18X1 zLv?(_9~gOfD=b>TNkg}V%}bj-Xn)}G2wqT+9Tp}TJ)`E9n{UbI-<>)2^z=c`=iDh< z=9M?O8>dEW!em=L&WyM=dT*#);6_X3E5G*D_7G~Pm_^5Nw*~$al|2nhFY-**7yYT` zvPtY^@7f2^Ov-ch)sR>6Dg~ZB#nYdPY{EnjPlCFJ&Q#=F0Q8~DSC#On-PT@Q_mfgO za?ciLVj3Jhk7>S^5&8AH9A4`cJUSzk>doUqJze%nMr}hK}-{4Ywnm-xD z7eElh12{0^5pU|8Gc!`|yfFF-%;lOq5Be;vG)Yk(-qg9LVLd2d?-sbr214r4Uq`|^ zb0TNdeCE@K&*YWEd+xb=oXRH7Zxm{~Zv?Z?TXK)RhX4!Fky(E0sVdj=?0Jvl4Sxq0 z`^BF#MKU@cbxc|69XkV%e0A!h*|_npPk)bJF{5XK69wghr*vB=@98FwX%ErC$Yx$! zWv5%ap#Lk_z^dTvZ~N?VWT8DIEFA~i)U#}tP76D)IpvioVZp9G5-kmFf5uY0bJ9Qa zTz28aSy!jlattq?>4Ux73G8gTo73;P!Y^uzuI4TxSfRG5>T#qboxP#=oraOA!sL+) z-ArFYEs5>VrV;`ZPXajdLWk%-Vkp-aw*N$b%AOtZ)DIrW@WyG$p-Q2#!l zFkGDV>zn*)uW!pyLoVzyIF5F!&eTBxtu^EqT2 zgG8?uae$D62Y(Ki)^AL^-_TYkrC~Xm>^F)HMmGBTw-bifjfb|?b-Vf#wi=~bZb{Lb$@eDtFqoygArYXo$9IEjY#3msEiUmvnMQ|90P z+kZPwryu!|9~nnY=bnXqE7zV;!|C&%|MP#ILzRE(r+(`2z2E!2Q~bQ~MA~`jZ>7Gg zFz+r2r0>(r-<`oAE;h8I+NW#a)2VJ(F!J|}Oqv}m%Te>p>{PH@!6K=zCg?PT;#*HH zlaR8?w+?W7*upE@yiQKmSq5usvDcV%@LiOE)nO?Q-dAyMz4f-)O~Z-gd>RfA9qj!% zl+@Gt@;#r$%_Im-@RUCH=oLl|`CVF+Rd;Cz+q^y97N5$3Ri^y)I(T>THF0&e$_tV2 zJ@0$};jX*yIb0WheEQb)+H1GhF~X;^m(e@aZuACk1Ns`9hMt8ZlY#u6iE<`@-ns9D zQU@=hUo=^8t^;`*#BR@4?TZ&Lj^5$&v}~R%Mvm8ncjx7d98>8$QBAtgFLKOH{!|W? zVdd+(PXia=HHe3&8Jy`U0W2FZ5hg?WeqeLdIICp;dK=j4px4r{ms8Wg`wdoXIE5Yh zl8H{CjQ8;Ez@g2F{som$eu-@WVs5@Z(<~|JrzIb_FZG9oXs!UV75D z9(rhf^-25qP}&E15v@rO8uolw9_lAiLG;&go_PvPJZOzt=oI5TdGgI0SF(wWeX4TkpOQQtq}rTgIX*QCa5z} zwv@SDIqUCMPI;5^1#>b%@zfR#amqv>Ycee@7)(ZemfcgbM<0Fk*r&1!Uqs=YJl3B& zOjb>k5i|?4@QRPxir;KzovV=pt#gn6(Mi&sBAkjTzk0v=4%h%^|kjNzW0Cpz~OSQ=0S6f*3iEV7v`s(5Au(xZ{hoTN`@P-=@D2VzKYCPq zZs5>g!a+X8i;l`knOP_WCjSQk90Ri@yryr6J{}pT+-GLNdf~!_c^di#258OkV?g!xc@8eNahTUHv~}=yRB^KF$BhFGgFiY&F`PJ4m-3~duvfYcf1@J5wlF^z zFK|LX_>x{bt5cvwdd1gyJ8Jajwf$i}1@PQ4U>pe{oc&0jIYH)G=6f6fM@LOxnIXr( z!8D*v##kS|%t(BI~NjZ0&cSzfceT%F%^jsjNXlw>J6=X7`zG63qv>k zthU#zIAIK$oCzk>YcjdM=ygpdgd)8^^~B@pd~cdBD|uP~A3e^(F#OKKajRdQ@=RDN zKTla3N(-3gSHAA2>}Ic1CbGnfg$}t2uIlDk;;13VD>-W3iY_W6xZzbF*^3Re)xx4v zC@m)F&y(Y`&m5l4^^2L17&PHBh}jlPc6C&+Uz4`tfVaOZkJ8Y(E1P}YZw6~&Rh}a7 zu}?A+?Kb1cM2p%>!~R-*m4@mdjE^(GM9*#~?FKDk>BhTquF8pMFCTD^4MpaC^~oe- zWR&*gKwz}Bzv1w(NcTmjoAR2Ye01QeG#6j#Zu)t&j5RHj8rl1^rlKQ^nT+!H16d9P z5L-ySCf62lo`iz2Tcx@I)mPz$ZuSmFx%@C0)gJA*;-tc(3EoYSrSpf#b1gbk2>z|E z*=3Nj_){mDRyQN(rODY*VKJiRfqN8y-g(L?O$5!?#y!Q<1{4CghsIOQx@FI;$MjvBbfCi5e1$)S}^jB_NiS%;%r zuq`S|%g__KTrmU(xnrgar6a67GR{?BPB(KnGkxq)Dxc6g>BE9X|7^VLt53#Y?b_Fq z=(9+?=4N*c`B(q&!Ltv09gs4*R@w&FOYx=fk*B?Vr7t<7cGZIg_}D@nH4*rd3nI{x zh^BxnUF6#SVRjT{dq~@q@%6Jg1H-NgV}J)-+8LW@D6I4@{^aY++LyLp^P1;Px8w_! zk>9m>sAJCK6;NZ$jKk!)g|XvMIdqy;Tq?$b%~jUy^l?WB!Y21RY9=Yz*5ZC48`%%= z`ZIY8aO_{-rmd6L{?+L5r)Shm!L9tlqKY@+ zd#iieNnk_C)&{W3K7)0$bvNLK-joA7@&GrLpZ#ecC>;%RUEHj4&<4lIaVv&fwx)`a z<^0$(w+p)#XFeHOc>VFd^!vAGEQ?AE^R8sw<>Zxy;Th@8n z(6Rr0JG42U#_LaZ)BNnu{_Lz1d||Z@>h({3aNiw8o$Gdf`*!NP3j6MoK>E*pSMu&* zUWd~Ow@#~*1RGiYl>Zv`^)sb^J z_f3kBexqMU z{ZON}LVq#Cv(G94a6AbRnJo%YWg} zQ=Qv-PA1AW$cLk$GAoQLoEG($IBGJ0*tK$c4pD8Ta@pUb4_$kD!Bu9ZS$+FjfI?@oU`%g(#dZ@Z`JuBxt{Cl4u489ar=%1t1?2}%^l z3}KMq1&9|&2q7dufuNkzUA8G*;lV!E?#=e@+T682 z7V3{x`!;r%;OlStW$5av+QrPTx<|Tq=9VqZ0cl}o&2{R{`5aP@;P*Rf;2-)CV zLiI_{^4O7`Gn_Toxsg)+jrolJQab&hY?n>9-J;(P5B0R}Uh2M~^1H91|25zRzpJ>N z>RO1SrY~2R)ERp~H)W;IaM>v-T{|~#RR6|@gvdXT413tV?6x)PXQiLA#~!Inj6)h{NyK>pZ@8eZoPZ? z?~nY*k4*EZtLM)9Zp2T0>Ql=nKJkg(A!shfF`Rir`lxrm``!Hx8=nOKzz06i<6QEt zp5h7Qn@IyFj+&YTXR)GV&BQgGyUs-;G9eJt*=T&O180!QGnwfOO}2DiIz=6p;9S0e zrw6N^ER2OZeA4hEq=9#bkGJaW4Rm(UJojvU7P=;P&pi8lPsDw4*E8GK)=TzufVK~x zsl|BYX@vDd7Bb9^n!D>Wi1*xcUzfkJz6v8`!s&d+bMfvm4zjc!iVpmd4Q|0T-V?5* zU-|Gv|H`&*N*4w!i)D@yP8y#hCTn}+*FmXetaIgs@C!!*n3*RqTYkYy_qpxoYNyAg zn(&zn(m5W~O-Ja#fu_30AD*HQ z*F-`eY#zgiO!DDM023Lcg$~_uI`pGYH3@#lJKougUG^fN4Hh5KOYk`26^y)@-^d_6 zvf&AA+C>Sqyjo6~b~2P+FFyTDEk?B|J8{YuORpZ=aYq>rcOhm+4Zh&q1~emY^bq@j z2cH5Sr3W^0;ZaO`0OJ}x<>54ti}(>a2slMzH_E^dHh9BB_?6E2iC?(Yr6V{zipqy} z$~l60u^a|3y;9D?#~!VCae2CQ`DFDq*VY8UWZqBoEssC<^78+F;rZp$6<;Z#E#N+Q?+wd$pD#z`t@TLSsk*y=!>D_X zdW*-7+C`l=$K{x{%fN&Z{>vOSt1K;0@jc6SFnKTe0o0Ep7%@6=Oqw$Eaj4#u-4j}i z>kqucrt73G>^6X78|W+TByDAe!ABf57Of(Oh5kUh6Nucj>cj#St>f^5FNt@Lx3#Q= zr`yNcCL8gdpX2a0Bg$;#guleBK*x?i4%^^Joqnr~MWXTeOXZw;yv93ni*^-^ovqs3 zVVzn)ssg(zW_^>Hjs)r9!*!>QESCqNd8jsCDLY5aila<-&{=WKT&y6?+AdvUd-fDu>S;@Jybqp5v&|pQMe&=D?F% z*#Lbn|KTpO(8Hs0%8*0oa(;vevF7crM{Xf3jA)XhVJ~lEjlX`HW|hMu-Uo@Qn@VeUSa5`9 zrN@4=v&cgK?RBH5*AWA8I2p24*&$ouM-xniw7USa{q(>3KV{yCz{w%P$-&6+@IBx2 zJ?)5qpN=_I$(8v@<~^>zUg1}MNz@}{UK&K{foDFe&S)_4@6tOOrGTVBK9sz-o zA3ezHj70Hq)r$>ZtQ|@wgeGiu%Ak3AU97`d!(!#vBD-KNUVOAaUkK)1 z?|N5v(%}oN5Lu&#tKs^RE@D~_7j$XsuD487QgWAva?N^yBV~dox>AN+$k#sXI=idx?772x z_UxI~8~w0gyEkmv4h=ZMA3Q?v&ooEQ<@NxN;F!97?uGj7bbZO`wWpp~UVZZM<+-ZQ zXDa{3x+8U0O^mb&FBG<*h)j_`c9FJYl zKq_n*9jVQi-C*NO9pjEL+kf)87ne`o|6IpQFTGX{-&dFS-Fe;e2kyJR95wYdz?-gX zXAL{Te~un;;lMO5*`0jD1A>SBYbryN&S`XKEn*;TuN5F0|GqG=*ocjFqST!SPbfi^Lv>D&4L;_LZ?7 z3_H~J(qB4HOkQrxq#koDp_&ikfn|@KRte7Nipq)k*3N1~P9j4F-?E z-!)xj*zLBQzK(;&f>yK}>W+5QjCZWFV!!b^j&m6bzf>Qb4s61zQenWza@X8N7_TExSOoV)F@L4ZBAd>w4=@ z=|z0mDMyW6D8@Q{|E)E@Zzl}iSLX84;+<@jv4dILarzwn&$jRLlkJeuZa?_J5B3X#&!0d4dQp8%;A3B2`s)!T?auh}-uJ$@-zoFG-}}8^5g+PG zow>Qfj`bt@as7uK?Vhyw%x6B+p9A;eVGbgWnm_Yr{!BkAW^5n3p}!*XCx!ku*T9?B zQKMeddG$oAIAYCVPnb;i#+wU4rTRm(h zj3(#?c-JD@XuuyD_%pFEiL=<|lzE{(#hb4|^j+9`pNs+B7HLOL1&;ys9U)srSG=J^ zZgk+}-L=*FZVS;`^eOKvO0%rWU5y^#1t&z0eNjJ=C+UuY^u$i6pYWS>j+%I(+fh>k z7N?2F9&-0Dc$L}mn>x;9%rzJ?sskMNr_9TV@RYCTRP2{<7LPhv9&s;Y9WO2(@Av85 z3YBjX5I!v~9;~luf#+C%Lx$q$@!eA=pSYSUA&6NgSCVKj74ZosbqzK)(hJ?X-s%_3%$w`bPI^z0%VyCuD85*Ol&@RW?ag|R(5dCE zH393-&X!{#v`x}3mi|26g*UrbwzA<3ZnCL2WziIaC;Uqjq~lK+6ZV}xD_z=*BlLpb z_2a=e6NqBk-u?Gx+{92iHGp$9Bwf|9y&>PO$G}J?XzRq<#QEJmkpk- zw)sq@U#vm@hI-$^J+&p8BiJsu+c~1suRyhObDn9)}eP;WG*OvF* zebe#>-g$QUrrWMx?zrhKOTAxsXXCNGRrIbaj#7QUNuT;Nk<EA%4K*dMlgj zo%~10yDQVU>ZcM+`kSX#(&btT-p~gDbYFw2Whj;<~-+HeuKji|FaC7058|BHw!`a25;ajFxjKFByP(#-NLEAe6V)Z znCR~uH9a1eGkw+9;Au#T1_ktCV!rFEf2O)9*;UJSQJ7)_@2c05p>eO77MZi7Ml$ru zBv=^R$&m4)GLzLz4ERxII30pRzv;2qS6Xh5yJ^q3;Jqbx|n{AO}LIMyLMP*QoqrS{!^N^rw#TaennXNbyZJdx69fUCj=+H z8%L*&I>E2D)r)HSF1%Yujh!Stk1NNmxg)!xR`Q@ZuCoiYoRI6IadX{;2mGL^o*XZ; z1Berv-_%d(p>?0kqz`BP*s#k+)^eqP0#4s~ ztd>(H+!fWqXAx?;s|?CKYu>cZo#=t1#(aq5ZYW^2=i;&Jy4lb^l&&!0k{FwoHF(Xu zXVe2(wsisaYQw+#cmHnrxBvFvwv*v~?|WZ6YP^F*8~*(m@)_-4{ncMxKKt^O9x|7j$qLpfkvCVJ}tZ`gBdQyeKu{#u{W! zojupPRBo#Gs_39KTKIdguK_5uU5oNH_P}Z2ys;+iIs#6Gb9HC`=31zntvkwR*1O7m zN2Ca6vecb;UE^ESVZ-T&zOU{0iprDKahMcw)EN9DmoftWQfAfzTw*3KaE51cC@)Re z!YTt-cuG02(L*LwIyQXLg9)t1Jx&#V+ro#eHHqO!alP^|PrjU^lRIO<3zn=Vp%%i= z)()D->+zDuYG=$%r|S`yik=I;?UwrbLM@P6zg5O~XmEFzMjVfEjIGNYA)H-0T#lOP zK6R10j*jsl%@M40x{xL)CoQ^^hyUPHPT1;9zBEU;ECTFG67eSDQwV;r!CyqoNNT20 z3#!#7_VJ)h_(ms#l)5s>V7F|x;fkNzZo6Z-_4YgZ9Ua%#0>)!wFTP}w{={o&oWD8i3^@S+o$qzgysEOvkwWx_Z3IRxjNHlLe3Yg1_#bDnc1OLr{S z1kvRBN`X9N7EM@1P8yTg$b~O;nR+Kr0-n0QD&eXprF2(yC!|m9i|Gf>1}PclcSSsN z>80i8{`&*V&;5@FmW$85wmkOiYsZ@?5PI6u`(6@pW+Y$6S?I1TM%p1&g-HgjibO#fc^V>3_Tg<(&{rdiXt)y$6qMJb9 zXm=jj*SzMbb$)caXkh%Wb_(ZHb#v?K(t(?@?9(Iuz7pi-L_+MKY1hwXwSx(DR>zDf z+kOYgQEfhSuIBg?Kk*aGzxg-+ru%A-J=sws-gn=9S5y3J0;A2FSBd}mKmX^BZorvO z_zIO>Eu1xUZBFrf9sc=0|L4n({n(FH^?bSeIgXki{^1|)$HsoIX`kT##?(Od5p%cm zjVZ)e%e4Vo)R~zeYe23unS(zaT?Y9qiUMmv^>i&vy+0=5bbT84OgU>z*7`G>)px>a zphgGI&~`1tW3V!DGYIQkOj2~JCI#ravwwPBq}Wx{6S>MyaBaYcU%;c#llB@E$nbQ% zE98ONQDeK_cn8P5Mc>_pQFYk zMKnZ{j1K77fEhk>44udVC!HDu>DN1GytGid@+MXsH5P&v`S4nVm4G9EouK&~?JHF; z21(gofa%d9lePI}!qL}U*UrgFXXuhWItkw?7yU=SbSY2zQ94TH!!H_%Y&er$<>}D?c>2uQesruSbX9ZXt7VrvYE06}h9-R~ z51%>{w1L#CYj8sJL5^(<|G^u%EsV)vy3=>Ri(h%@*~ul|Qj27t!uD7jIlS<7kR0`o zcI&Q=!5d!C4KLw2c{ze{&K})ae7^MOJqmbBoAWk2`UBa0UBbnK2} zAB*?k4KL_NN8vNqGi=};1-6rVbPaZvC%EJ#(2LqgyV#}IN$0KlkiLZp?DmKccbrAe z3R{HL1KWr#D1$dKdTx4adU$2x=pGrm(5Tn8Dg}fb$5sEf?n)z`1p&zMb7^&^t{nZl)f_(l&2H+uTU$?T}n_f_oi9S;SooS;no_kw(u ztuwbjP3%CH%VaC~qwqr2dg|kVn;kXs`wN3uC@8J(9<2lm9l zV)soscB-H5FO1c-deDSfyb=7CIGODbXrGK#;b=oc2&(_?r?W>$Gug6i-Re+xg z_-R`&CR^{ttz-A@sR#wOfn10;{OB_RqPJ_=t6bA!I2B>(bby_K_CZ?6NZWyo)BZK? znfJzF!%=hB>Yzw_3*HoiYQ`shcU|Y9Dg96gkVHUrZBEh-rn)`~?`+32KIwvkGY%AJ zJ>t~Z`htc=0MkY4N9wB4&g7(NM@`KEw2OU?n$S@oJRt!o+jbm%y*jA0%G%klLKSvA z)OoYlsjvUXZW@tOouekvSDk*p1bY1K-~R1>*{_{6qIuK1-u142`LP{9cEM*p@q5iT zeQ|EFb>lYrfBcXC@#VuG{_yWL=@b0lpc*)F)KtZpEQkilc>!(EJ}UHpJ1w@`QB#v@ zjW5B1LWFk?1|D>zhju2~Cgz@Z5Hl0vrCK7lTRo z+~VEqsHug!#d{`jxxx(|M0qrBZAG87b48G{Wo#=f#YUaDCDRVV?hz_@Hlb+$B_s|Y38?w-n=kY<4 zYXO{hCRjY-pDeKpxP;ipY-gQOKWqw))Wtqq4=gy7iP)sOY2Gt+>eNlUHgEFhPN~HV zp1g#1@8?T{w2rSw4=EPgjP1;Ao}8k32N&B(+2f9-;&t(AB3p~qVRpwA+2!HE-FENO zN?l}9g%1%=+mQYNtvD&RFqd5yqq)O5--*8rt`edTdYE}Mopn@`kK4ut1Vl$*M{ z^d?6;(eUzWrN7i?>E~J{wRDr`DbixwOBKZnng4Eme(KNwK5uqtvN>P(aA>A5JKIB? zozTi60KK-hKUb1?A8FBVC(8tzxQUf!Tdj;e(lRtu)7R_5rQhA7bU=f)Ey!!ukj6^P z4~`pK=Ho8@cspIuA$RJ4q7q$%@0c6@yl<=pe4GcGk%E>YY$M5L0p?qfRm4Nbg6&H| z{Os_`HA)B9VgQtf931}rQZo_`)MK4ouk~V`)!cB+=E&A>9Njy6-gqX$k-wn`Im~B!2V%HI0SxjyySbFmS zXcz_OINP+Yt;{`p8uuGE^Hqxuyh`=F)$a0zQ0Qr?E>r2uR-8;VmSxfqn6pSWzdtd} zxxKR)i!U;Ys7GxZj#K@`9n1Oap9JsMG!dIGmYPF>>5Y6c58Z2bmo!Ri1?|F0%*DH?+ndGP%gz;zN_ZDaCrPD22 zL-XaTb3fKIKX13Pd0AUk#FY-QVc(;9sGxRNd&bSUPXnvZh0dX){06fM(Im)f-(e`a z_vsec-oLkqEcf{!p^?Gex7t*5ER=I}g>-+0lwgTuAxC{=B+Kz}=0=YKQ1wC81T9Ny zbvs^Nmw^AGzJ9eSXkA$&JE^d3m+HzFh>=d!h%B>ZUb150mD7i z-6B2Ii$~@&dc$U|Lss?s9nxh;l|0wNB#O29$NRZqE3XQ7V9QL5q(O3`;4q)6EYxPI z_vizx-4oiYbkUaP=JYk<1jkr*a5}NiS-;0iUq6d zb3xk{)m<{FZqZSOSl#Pj&bk0RQ+r@XmO2~eiC%_x<{HebE-Iw@eG zqv!e)pjxC_GCg6-6*|}$xQG>Bk#SiFn!4~;Snu<|_$M}2U>3GKCP}C1cLb7#W%Q_0 zLT``#I1_IVgYuYe1|m>Ath}H>Jalzo?b@LbLS@@Ft)}IrR?TDQ7boGBQ65;ye_Ci? zRf~PVJPR=;9Ua}I-)&{0Dk(Ry!EyHWK~xzxEHmTECKbk<@1`=OCGfutUVhm|7vJvP z6)EVYY>=IdZ*t;7(lad`iy6eyFQn3UM3OI68l{vbEY|mELfOYL;OXe)y{CZ=SukQ? zBmPDK+p*~YM)h|segK2>u^j`NLs?{|5T@omVAAY5m5~IJRlMuwcf*$x{(c5WciO8V z!7RM5j;;h#!+#;|_1oztA0WJhuxec~r6I)Qe97vH%Z_Atsl4}?*j9RK5N4}`g4QNz zlVgMPA;W?jvBOUIQ=v$td%wv?74d3ebK_#? z2Uyzm!K|Mow#-ZP@rcdM?wu!!WS9{Pu>8i0N*f|d;celoaQSz|ndA|3n!u}87(nxf*n`L z)V^&RrCmzLYbVE55oy!nb=~-sehSGKItk)Gp@H5@rDHt1Z0{nNqCgVXe*n|T85+Zj zU)-^q)dHoXF*$uJJXBBYaK$wTMOJsRD&hERH`i7443tKiD3MP0`*rEpIEYJui>6o?Q zX9)X!sC=*~m%NEIm6dBwiqu`;X7&nnH3}f5lJb4nCVSRO!Z%-+YX8Ipsli9$)VRL? zaq(Jbr}*Ji)R8Dv2J+xIlZA?&S4uCc zS862g2a1UjmhlBe@J|SPzYlW8g%1qJp~B& z-G7x)SqzVI5U`VtWI7xD7MCV>2G^oF={Yq$bSdXxm09sr@iM=*758_@p9j;;nchu& z0B8nE=dWOyVJdJ|Xpb<*PY$@r!%(2tm$_%YNB){aLwk3{_$TkULQEvpX0=#tU>^^= zY_yj;!&a^}Z9ivo#du=_Ywvn~Y1PSxvY1UcevcAcCPrpSAM-1a9(dN)fIq$tKoQtI zge>)Lyqw}}@Yy(A8_)1CuK$Rz#Vxu{T$M*P+MQ!19blS&#Q|Yfd<(NnqmrjF-Ezh) zehHivoF^Q8CgjQ?d}1avR<9yQzu8U+oHMA*lC@vrq8rbDpsGqsc1&>nU4kUr)QY0w zjqo?paW5+1exQeZ^K@Kx-0CExa2Z@kJIQq0r=aQ8E;_AKvBo9haNnnwvmnVbOid)y zN^GaQt!IrL))^`tnWEohMUS4I++4lC=byiSf|RZ$ml{)G5iW_@6(3McY^s>Y$DiT5 z32o{%?6{^{&)%uK|M@;-4%9r|t3*guAy(e|A@%lBXy)18O$l^!UPtRT zxx%siYe-lBFB+1j(dJn9XS$@KwVHL9%*DKIX>gW|ijRr+*n#;AQYDlc@?;-n!HPgzz;9LwWEj)hr*ni&{y$dueU4 zmyLdf=4)0$l#2mFZ|!v{JG5N~>PoAcf2E(akI~$$;S*_L(3`9Cwab><%h@gLKBNV) z!^>}23O}D6zP%de`{#q1{o4NRnDcfuL+@rH<3bC8qDfMT-m$jbjED_r{#Q)Xc+$go z4qH5jaUSHm!Q(GmUZmrdVvacd2%)fK3eRmxN~nE@H1rcFq1Tb4TB1~psKU4Uxd`&} z0;Y&tf+VZe^gT#J#*<^5!-~!}lH?#go-P77hf=og6ASLfQrid5uj}gV^vpF03EYACT7HY|`l9ChFm2@Po^@@HSN?FC$qiMtyg#J)(QYr#)9 zj?~`nkBRz~kB!xMfdw!sYVSk81u`dx$@AiqYCitGqAzCbanTarANxDA8h9>c-mj+W zWkQdB#gQjUeVgK1V1;7*yv0j47L~p;XSWW6AEsmOdDo5bXVxTbBcz{+cHh@`tMS=Q zFCQa4nnh^xNm08-l;TJ5N8OG_=7ohAZ4K}aEaxjfAdfnVH4 z3yzDM<5=|v`7=%0pqX^N%f(>Q^^&-+u_eAXt;@0N@-Yn!6WU_SkhqO~iXeK@xiY`noI;P+gI$srT zw{^?xR_lKI)6T{1^M$HU2g9v^c+7tHFvwP}XzPrNfR&z6pFB z^^5n`E4*&}(epH@T;b^2LAKU&clJP6<}6b87xT6a?}FB-JCE?7I|mJCgKMEWp9gXq z4HPR!i~K3wktsnxl`0o^bB0NT=rWHrYxx9(1c2&{A?1|k7+ut-g?<%}Z~LBknf)4@ z*^}}Pa96(Cke9(5xJlQ~KRC))r?g{8RS9J}N=h%RZvK3DLfv2+3$O*;LzW+$Rl8FV z8lKUdid%>Gu9|PqVKwz_KWOHR@1v*Kv=|A#OA}Kil-&AnNf2oZoC>@K=~#S{Zz=4c zBB|E?sl1q3e7B-i?(aPB=X#Qb1Te9rkYl@im$~@vJm%=Ruf%#<>Y`>PTo_jLROdkw z-^w@tdD#B_;uqiukZ09A#woa9$4dhKw`RSyq}x?Kp0E+M-nqRJ;jlZUjqFN9ifMG$ zB?DqtX?3ZIhjXi&#NLg!bS?m1@ovmLlr=3I&uzIE1PU+li~Pa)R#byIGDXut5<&K$ zuJtp4^jZ9*SVK#2Az6esF*WA%hfmfcCV8-0WSo0H9?nARRpzyqan0HBqE|Bj;i?zE zs}CVS15;}gLi%RAi5^r8N%+5UKkzIt>8}EbIFbcSjBx2Wx+3osSrM0S7d5moW@BYP zc{PI!X2_e;UrNt;M#9%~*&Nsww!U>TgD8QuQE!1gB4_Aw!MkYvQ)Qw=vyTgy7zNuZ zFRus51I4-mHoZQl!#6We{)b6AI*jsZ1PHG?)@!;YwW8MF85-Li>$aTe_WPXk-I^VW z?^baRWy@ZL+&Ugx05f@>l|@t)h|k*_L?KgenM7x@Z+c6*@A6N*_=-qww?beoXZx6j zJ8!Y9Hwqv`WMf8Gf1ua(*46p39OS#yXe%3KqZL57il5_=30p#ESTMe!s@X+Au6dfs zQTTNkQ#LZ_xKsZ~%ohKZF>C$0Ydw+nv?RwlwnHE;C=VXVc4f*B;R#N}Zar7Cs0^aK z-TI*#3O1+fCF$gTbQn#=;iC5WqSK?(qVXaVz(9U#P?spx;N}RW_h8c`D!U^iRoBIN zo)cC;a|U)FogaK(5z0!XV)L~Gqtq)H*-8@G1 zH-G|~q>jHiYl^DxRHSzH-(fe|?sFp5{hsV8ts`j-{G-%FjDwxTqEdGv^ZA&Q#gs&j z?(5EH0%oU|DXEPrHVKJ9*f%Y>ml{2Rq!fVEyB^_Bq7Fv_ka%h1SvK!QmbX8v!xMyg z?J!Ea!V}z+$SV~K`NKkN;OLc`C8*EZr%j;|iKMyO4P7Y$2(Ni!dGAC;Sc#Uyx~jMF zoU4ACn#dGJIv$k2;HVqtga(vsV2YzDq;)7EtP?fE^nQ4Xmo<(_v7i!uut`v~>31MUhWc+n)vb*U)g~QzUQ(wsjRQElX83Rta?8$pC zK7XOR6SSyn4f-g4t`y~w@9dg?TZ^v;c}-g>)AOB?dbSPv;k{k}-FW|q{A&lahS8JR z&ld232QJ#VU>&HyhlU;IPr{!wGP?gI!3Xwb{fn|?RA{ys(3tj zK;)A%f#!%*iLtT$CtNzZvy5&wvrj!n(P(v>Fw2WXWk^#JsiD=nccgw^++JXf$w~pc z%=&{X4OwYdcpNM5F^w~AcVN9?o^>78)3%j^3Hq+#c@F5h}F`8#Tsx^)(dp#HRFUfHvvS36=R%f;JDx z$0=&dJTqWdv{2H{eo%ecw-Cg7J<6)D7$r4Ruq*%+MGx3D8!S0zT+SW!w_NpK=Z{;+ z94C9*UQpj4W$QeL|9Waj-iZ4TCXO{@dn2pZ>|X3~UHy*(cl1-kGppO=nChB_w7=G~ zzxJ*v!STO(zor_D?^3>T3%aQKS3RqNVg~W;M4rrKROrl7yJj49^zMW7v@}bjvDQ?y zCXKY|!|WyN{H-fW1`d8>LIz5Ab%>pB`5hW@5{d?xL+PIq1e5`zBy_|9S)A*tHUw_6hmG~OT?FQPlNi% z1nEXl+z_UGYmi!V7BLkp5TmAp&0@x1Qd@toF)*xkw!Wjj-K8+ZXO+Lm=v?V@TMW)L zkUJhZ_xG}ahH z;bLSt=4`PLpTFe#hE5ZTbe?3$Ej^2oqRkN2SpZZJIB+zZzKNQC)A#|Ge9dChy zETgb9Z7Ov+8Q?2M>X!2chC0=IszCgAqHfc23i;BSb#+A;iVPjY63Q}SV@7B?QqI4P zwte{>f)f-I-P+BM`|^#6UpApMy(Z3E+V)JzBXYZ7QBw=SE%@_E-T-!jmd249A|Msw1 zl3vngU&`b9`_5LwPVlg?kRXVfV-M){fpiuioPYmSOTf|Fzs&egx+}wFoJJ{QVp>=x ztYY`69p^?#9Gyp$bk5xV7xlrph)%=V9vw2vQQ9wTcF!W2;`HOJy;Pw)f(l#u94=Tk z68gs0R+TV-OXiCApTUBDgEITw+CyQ3Y0|}42IsS<|Fz`kn(g|Z&`e|MaaYdLz(Qvl z&%<1>UaqVN4}&gST0g}7*)CeYU1*ZG^75@|_a>_5rCXl*XOhzEK(BCtM}kaT>a*6DS^;LN$TOm+lfLEPGWE|b8p+^#JXwZCyPH^pCBw$7S;Zf;=dD`w@-0lZTH)$?W>^+riG za(UPJGSLiZg!{RHq9jkd?h<%*QD1*Yr#s~>zUtiH(YsW+bm`!^ka;MJwj8wETd+xe z(`3p^f}I-z&n?jm^H>2cC{PJwgyGJp7)l>INtcgxx|~7yN-E}~ND1qdkpr^&%v@Oe zx3ubM(UKhR{I5--A;hmDJ)#GdF@?NTriBB)4)1I}Z~RoX6@#w-Jv2sQp-D*2;X1k} zK)lmKFvdGX3$n_8IId|M0{Aic_9Cb?&;Ab#j(hLSW7|IOuJra$!f^s;(#62^T9UDn zouasw&T;%B9kAw(Or|9jNUgg69jklkz{^@YhZje9t2Vx?wj(Xs6Ro|sA{$uC zM3^}6>$|gmQQNhD&?b*Ge{#yIDy2P?&Tt9KinuOncx5B%W>glPaqr-!8KcqmljPJ2 z)1j%QQ~uw>Ad36q!*|PG?Qq5|h|gn;1&b9hfyx%lpori;CwMti5|YW0vXSITKt-_K zVGJ3+dve-P6?n|gDUww#1jA&%<}YjJe3zXyLqY%+to}(+7GTSvg}sOG`d|it_n`Dh zuzSvEFI3UG^*6hr#El;5uXMP=M(=Fj>A?vzDfA-`8?|M2o9!r7 zjmba_Y0Sf$of6qkh9dVHjDniMTijSg0sL(Vrf z6Ug>8+{HZF%gK&s`EoRGd6-=wrdxnbEP>Ws|L%bduyr^_9sg+T59~M@D2%bI(9DP4 z#`nQ6lcLS*hJx*s!5jlDL1N0W<#-PL_P%7d{NB5YS3l?bMDP6+Et^Guih~q{{~b-@ zj{M0cGpVsdyT4qR(a9&By%5Z;QkzH$JevoO*ruLDGFA1&J`mR*kKykpr~j%Z)Ib$B z6iK>OXy0IT-3mIrTQ=I{e0nny6jn{Xwfud5eVo>Y{AdskE4w7Lx~d_J69CKo#X63S zFn0eESx?dWW`B&!zs@T%*?lSzI=6)4t-CyEX_=Af(^QzMpDXI_Vg4F`5>6>O%%@QlfyC7F(-H=ZhkrW^j@6>=NRU&UI8}p89hHP zJ&7X9k4&-5DyIx^>3z?s-+cCRy~c>SF@R2Nt;rCRfZjTCZaKsrWq4Q0@Z2cQv>o&D z{atWhIg0r^w-A|9yXb0Nf4T1dwWvitqv5x6gM}!I^EQ6Cq|68G0AGoZs*H?wL&lXna?t~q#+if;Dw~%k>tb?v1o0YWxT9k@-xJ@0Ei@W zGb^Y;gZxZ-X2?!xU@!QF{0t=Wo5fe^j`cGMQ?SaBl)^k>rx;k6b}pN@VyrB5u} zbX#rHYe6`m2j=%9ub{}|S+N9SmoE~k78qYn_j@cNkfkH}LBr$s#4NqLd=+0izE8B~ z?Qc2-aeKw9yY_&ZgKR@6dCDSM1QQM*8FT|GV1-Vo$=rJW@Az62I}Cz~O!1P?Ew9~A zTT!tz_+uOOYU!IP;L0BA|5U<8F`C$1sZn=x3T(=?4>@_0dk93m(+50Ob8K6|mF-3Q zbkJMdHh(;dgALj!bhYfhH9B^h$c8zZH|bml$h09GcK=gviUYCOm376nZH!v6f*dC} z_U;MON&am!{(jye@s$dtHEFf9eD822tx0Afz~<@3>5C+W z)!$14OP=CBH=f<5m&WnKR;eCVi3fO(Ut*Nkt_dY8gOHM>k$771Nw^vMj?S+3tO%)4 zH*L$_Y;$qTSzwKeCoGVLa(DdSs0I&syg~f)O~RYqq@NaJ$WW$qDLIq)DG12AEkP-0 zNUo}~eJENb!J?Z~kAw~Om9ClT4+ENUm4&9wK_ay^P~)5g3{d14enG>sbW*>p6tb*7 zHMo|I)JRk6Yh?>pAB^-H-MYIt&`zPk8N=3)@(r94L#D^^*AL9&?}w64lu z@Rn^ayIQ!+uKH21n;YFH4sj+dbGg~$m|GY z8p(@AC0?d+aG_pmi9{NV7YQL(JMQEyYz`?36L=G-@3n*bvRH3&GDqVQmXY=^p5=^( zT&Tm^>F1wOsvhftme$b1xE#=q%}3hddFb``{ap8R7jbKy(`AKLmF-x&ALYtkerL8b z?9AT9uFok$HXWlom2*|0tu)DcE4tE>^z8?DB#HoeV$gS}GVHm6gXPmex+`N_t*@w~ zTB&SX9E~>%XwS4ljN^hM`jVppIo|F6!q}^!GtB2?=`G1da%-;suJeQtAE_l|HM&pU z>OlV6vKenjI`%zR**^VeSBq%&L-VDxu-irUe!h=a%bgp)!Ze!7=3Li<*8&b2&CaK4 z7aJQ7O2+#o?U|#<<(Zh@>33)<+^nz&_xUTk6x(CqEhw6?#0qIov3E2xBFr)A5^&Z% z!N`=JXt>Kmhra2b;63YOeZ!LeH;0TVUC)M?AdGlh#p&ROk^A#K*(^GCVcUQFoilez zhN;G;`t=v6YRG-bJC@iduA4*OHD}r7SaYv*)4%ua*e6`j5b2Dduq7>wn!=jf;ODf9>=RV94yxmRGaYv#4L+!~#8AfDR z51JU!L=R+r|I2`WH|zNWzTDdoLkk+5?GuNfV336NrfqQ4kU4IN-g~1o&%W-pyER3zq(_*yH)7VibodQ~Csg{#nX>!CI1pQ@woKYA{hT^lvfbiD z&P%6G!j?h&eyK!wu_XQ2(1UcV10&{KXyM9!d3hFUkAiT6IL-B;r-oGdetyBgPUx^V zZfo7SpVEw;to#t$j~!jhW-Kr1ecK#c-z~5aBl)A*-(>fTX2b2J&+P#O*O}LXrN5Cs zC>r%ij`M8t|2uXy9d-Rh_Qs`J3aYmQXT7$RG~7*cLm?KbxwZxVWL(c=?1{W9!RIdd z@Ue)+S@nWD=UEdzcxkWNQ0MA=*r(ZU#=Rpccb<_*JhX^Z8n{0C;(!laJeYxhJ+b8Z zi5A1(guEh&6<|~g5X@(Me3ySKNf2x17w1xTggL^aP@=@Fg{;X#y(3#3g>9E=dxRhS zOwP9FvZ8oRlDTc9ZP3OiWo#6i(aXQEe5Ra?-MKgPJ8y+T4H^^P?uvT0;YTN8qUyW~7U}p%3@ttCZ7^=`LnqD>A~+vG3_BQ+SW22`Hk% zX~LIUV~mJAq;Ul|65xa!Ekw>KlD70E)s<_bjL+~sk}RXKmCioHix1K%pAOfZEw;;x zUfCsX>$sI+-T25YmbF~{;`Q;|dC3N(!zd<&CYo|q?NxuEfoY`oCLIM+M4n@IN$(R& zJ{J%#goz@BEJo?8OAuaQxFXGP4txD&X56{6?wU7#6mP4*ZKmYaWlV(F zrrE)JCWq1(_ZaoR1$QGDQp1TfJ?ffCtOCkG2YA=^*@)T`7P7MdU8dws9?y_PvAf9W ze{UtxdBqK9*i)XXHclQ11&xnym>OSE?>-@*&bkvazM0ZAb;}#^vE*;?7@}x?87tUG z>Vgdr_3};f#>a&iJ;U9p`7-BO{tg4vLu<&c?2S|9BMW_XVwX!v9bAqJ7VGOgw=1J~ z457H0wM;bL)Odozt!ONKI%XTf$B2(B3#BPyNh_Qurg@90N>=lg=d-;xc^)nlQlgo? zB-?}yyG!K5nlL;l@mz|tX~QG5pTX(6dP}*(+#xH3W+`RoV(J2SpH0vVfRv0qz(Xe2+c<6RyC}B$Jt0_>f%_PF|`iuHc zK~tmhPTbtkg-+8L^=tWOBXTg6589&&V=1{AFNACpwu2fznG}os76067CMO|j{rkgW zm%e1=-t)t=3hxN`pFQ~cBTx`F*zkmRcjdU^2%|#natE|y%yV!g))@1QKT{Nq{!Jb7 z;L8TAW&2(7$TLJ~hm)$z879%)QWN;IBB%GD=@XYpc3t`bqyXY{UdYn@Q<<~&nD&+Q+w16 zuOJmwHr672O=_`z=Luu@5{r<<&OGL&O$;NLv76Ph(FS)J6Wj3!<{&S-XjRnT59#5p!xwCvbWr9POJGa31+ zd@}U>9FX=@p^ewXv}M8Y$o6vLUut3h2y!#DxYZ54SvI^1+sk)4?m@5b&<@1>JF-`9 ztZMfM)bn>MyH=WkQjf4+&1rlreCu!Qr#gEdU0v{wCfTVOdzneW`Rqm;`=!)Y)5^oT z>eh7-l4P7rV(LT=*7)5lo;U`n!d`_L&A%JL9brddOqvljl>Mj(NmcabrTfhYz$omi zn}M-MgR!KA(9rf{=$EyeR~ej557t&{KwL^0y56pP}U>+Iw?g`}1Pi6>Z*Z<)@ugj&d$Iue;Eh~uWTvs#kVkw@+8 zbRWUY4<+b~#y*1-)>v^=$oHV2m+QP4HDo9!0_y#`(3lgv7cX-#8ztfmxsAFHog3u_ zu!>o88&M~=@iu}tdyfSysp<7fZ!QmH%CBk{y}qB%1zG$WmOZi!^XaZ<{smbCo1gFh zo%=kL;;etLEmKqCt;YYjcOS0mWlN%k_-4D$~SN@m-D5CJXlWuuyRG*|JLi-el># z`_7)Qw@32rXjl?mo_A!M8qKo+u^8I74+)xF~~gg41si-R@}a z=?0$gEC)Cz%L)zO`{^=A2G+UYqPJwv?r#>>JU22ZYCh_;_95f5Np)SEXgd@KNk(%S z>W<%3Ny-6C!_^Q2(-?Cii_9cgFZu&|{FFt;DyBspF$9RZpZuy8o_nV$ZVlHEXNqAJ zTfY$n6Xew|Ih{dVREG2s@0~pE143$d3jeSZ$b!Uw6O!k`^qJ9}%C(}nM^(3+{hH&) zbJn*DS_zPsB<3CzEfXr*m60`NhJ(V)${8sFp>gXDw|gy3SDCW7kYD(|zMBuS5*@ur z0;fmnLXKH}qHl;CbU>6RIpd=Q$&G_V>JwaQcjEq2`x>C{i2coEt11RHP=YAg7b>F) zj)GGi9a*3_g@Lx0aa}Cq1X%*(ijs|i)ZMLjWv)!W-#6zCiA_iyQto5)i8p$6nn3LwWnOYsHniI zi7}wBRr0JFOI-X*K{p+Q40z6ZIQ-sljb}+Oo3C@?5t6*Rx?y=HRef?O(w!v}+Rl2u zIem8sCVDY=>9L&D)7GaiA|-qa-e>T3rij8RxblyFJ;DYJZ<;JdGOc0WldzoiOm)92 z9e7AyBbaFi?QWHzH%GIt@l%gAM3Pfi;f~&mD~Y{1>e2EME=mjZGts8YM$2$gO4rzb zUQlz{!rE59fRKdjQ?1@(9aVrPnei-zgs*Zn?l-!#!G8PnX8)KU7PMbGAUvT-5|@?e z3K=i&s@r84vz2fwOG=;~y3p6c#bSMm??}|JlE5 z?|oAN57yVm54g&v$A!fub{3rp3ac&=<~zTCe)f22t%kTaT!joSU6)kttqaB0lWXv` zXsM^%ejQ4=Jq_Ya+%WJ2*Vm`z92CHWWU+pT#DhP7Cj%3)QG7HWE4?w1DG3M2-5t~I zmuHbB#(XdQMIR2MJ&n8C^txUBLAP1ORko8Q0GjVW7Dn0O__*VmS$vwxMZZa#om@TxgJyulhBe zQ0_c_b_G3gpa<5EtW+RQSg@H7J&_vJrQb^A<4WLs7rv;F#z)OBn;_#wk&GrO8kytb z3j>*o7xcs;!@R9xU8lbSHCrN zjA#(qs5^9-cPw<`vGdmDka}_3k_rzl!r6iblT#A$J@IT_zvM&ILDHiE5-LgG;!Y=7 zmgvT7CEamb2iHw4s3^+oel=Lp0m$wAph$zVim7Th3cU<^e)Wa zl2qi1V^}kpq5<>aP5Ogowcx``)k8bKwelw!1dlZ);lLU_UF^NpdY#70vrnG~{*%u* zyWi3mILyO6uTwVSz;TJ`wTyYm#IOzt*)0?`>ktF4cRo*fMa|=Kt=Li?l0Dpw-8=uD zLHu+@lg|y-FTS|FWW7!4Ei|Jn??UIfO8>zDXa2|*iFez!hcb|`;vBSeJiGz1PYwy@8|Isii!orcF&w*Ec z3Q+8*YW`g#C#JF3Uq{Ja_$K4~HR)4dA}9$ikY zN&ijL_g-apFl;`U-CtmvJu)J{n&ZWBA>LQuU`ro1rx_i;3`^FPVgu8&3K@x0(c8S| z-CNqXJZ&%XwOox+5zd+hk&af9=m)cO`kc$(_KDhwbmJ3iN=w*P&K7FI;+vShtoOc| zoSatrHP+3FD0!D_Y+IXZ#+!Nj9(56iIB2%0M_jbp^oy?@j>%a}l%58Y%7qfU9~6lb z@?mme^7l*1MpaDy2uYY+#yQ-@W!_P99n~ju)plIYw5#5Hy6Gc^#h(N&K9t$JKr`Ca zEw~)NUKww^r+f?d!PI1qzpQNc_=re?-rMumE4tu+KF%rJO!zhxeOR{5Z3ail&q^)v zoJPB{e2Gl=e&H}mwy+wbFXZs??{4bVhP8TtNb2hQwnBF~q8l+k%u+rg7lY1Jtc~+l z;JlK!@4Yf1XQ-0-|vw@~(p!|v5}Dco`+P(0u?xyoiI=B0WUcJ}Qy=@#79Vpg_Q zxYo_&MnsW%Y~#?F9J1MvG(B~gdDS3B<>1C`zh?X>CcDeE=dXTs3yqWR#md9Cy+p=B(R$>f!!%)dc?w3Qj| zw_UkzzZ@ZV5fR$?+HBb<_IXkr!+)ySir+CM@IHN9#wK7ueL2t# z0}z!H!ibYNaMX&MXOWS>#CKDTNI2Z;W&W^8Jh_43g~El{6Foa&S#3$V6x8;$4Fx)g zYl*lnh)g5-j-p6FnX})*Dk5^=EKWVqbu6hPsmI@>gyZ14U^Rth#E#<#`-clEFDVs7 z>b_AVr=j0Nt=cDKvJ)kB_546eC_W)w$qz=KQM&OZ2+krL)8aRkF+xFoc@#^R6i>D{ zo$g}w%=1uUyFKxiaiMfk=~&)r2nIi zr)$=Mk?W1B$qIx3z7-(fcNW8Wezs-o0Pjpd!l?V=L9jFQ5W8?P{xYnzI=dLli?{<&8BdwW4 zD1_f)Qs28s6#hrG&{2-5oO=Mu^>pm~-on@8if?$WYQaaldS)S^JguK4-rw(qMApJ0 z*FLp8Y1#TbqX5ewq{aHT@GJ~TEpHTT7<@_h-0xhA%c!rrTD-kpT0?RgJ`b7F{RNqX zYxwL+E;f7OX1BwrQB&;1YpeIYA;@aoYhYfQ_sH^~^WLr!OKaz#(b>IiL$~iPYht7l zvr~3PNJ;<@M-a26#P_VU+iuVI!Gy=fDvL?jjOGe}Npxz%>e5CyCu3R*>dSc%%~?TR zv-g}sT8cEJf()7t$HkMYMplgqPEx0}eVQSHx-oTue%8!_5OAx&X=__fR(gg5aJ-WZ@yCEz9rl9BxYz4kM=vdD5 z)q#Mga42~`ly-)D+Tuz+()qym>$k5|s@ST1u8dv4=b5QK#&El&*==Nh;>w+$@Z3v+ zd#H-*850p*@QC^^xnhQbHe+ISCTt9%@+B-C545TTaF-y|sew5nBn{uPSQqhiKnm0u z|1yMzdbuut<_n0Nxvm(sydwHF{{x}TZ4DZZJI+%AMiF`W(VyqADlITRbw;k7jT9~P z<<}8H73%uYm;{5F;{W_s!4WDT~75RLi50I;N78?c+C0^$N+V zcY`*(w7HI*8{i|w^&b2rQ5V8aTH^)VS5_l|qrTbfk6Z#dyf^|F^C>K|Kxy18E}#9X zjRf;o_k9UacQ0M+ma0^gdi-VMdR;ECoO}V~3{v+nf|+}P7f5<{|D!h7_bSOF1S@GE zywz{*9vKipvU_hNhB@0pT93@Zr8>%xT-LMWp)ZheDQeD0kBe{7RGQDc+DL#OGkX`a z;Blb4UqC-}s{Wg4x7$d3q1aCYwTax&QN0$=Lv2<%eP(JHr3H|Ul1ptf7Lf%W8Nr=# zNBa*pK;qUPHjDy$4p3GpQS1^;MtTf>*Gq$KW7 zfa}CZAPe+SsyZ2~2f1BCSR>^}*(KIt<82ABZ^_R}hO2D@(=h1i8HO^?{-wpYCg!bQ z&a@8u?)Rl7@L_b9z)e~M&wBNAPtO&6&m4ny2K1<44Ig_XD1-=1I$wcBX*4W}L1**Z za*X^1AV(+-dy8jP{Cx1bH+wr(uIYm}_~qPiY85bjnthJc>g4_}3`wF83b-UhX>lB# zTzPLh?c|dgoDBqZ!uL7ekiHlPx&Dd%^zy=kA#u<v~=I-?P%=^zMZAmJy?rLKMk68 zIGVQF4FdF1tGaxqGYAWAKWiwNs<7pSSVa`>#TO!uScK;}TJ$2(w81hXk7xK{*)TB; zkGCF_s?ht3;>$$0*vy=3ATfeVi__$rM-`0tbfny}>NwM-s`4-4w7B*5Lk95R3(-|< zEH>bDMDkIRRZekl$cUkWB&A_X~gM6}q(;w<*U8FkN6dt${uTM)UPKuwoYgpF$%5-xc zdrxaREBPl9+3tlGE7Mdtue`dHzKTrQcD^4xaOTMl5Z;w*GELizEPyb4#n_axV>D;+ zJ3kEWvXW_neve+(X*5fj%|1=?zCv5CEU!fA>j4pGmbKCnnCxD5q1hUS3zp>LMx6%V zMVzwLaJFWxe%?uCC!+ztqT`o* z<%C)WbD!L}WIWF1dNYq%vK=@87b}+@nz}&MHk#pD5>Kc>ILRfu1E++a3m4^cv_I_k z>K@&0$zJF6%bs)Inx3C^%QjyXx17}e!na1X7tgNX5Q$UD%m4oNj@cyYEW$ZVfT;Wc z4bB4{ek+>BXnYqH4W$l8xW8OC#)O|RgWk~Hqb12M)6s&z*GPDriaHYO>y$QbakKi9 zOrpD^^_fHS=QrKp z758AA7#3j?LO$dUnY`Lqq0vD)CcAzk-GkHzTua_O0&{BT)7Loz%d`hVx>fI(>%HKj zrfPVk#o0#|H32)|nS!iBR1ICH3>H1(3r8YfSeDOKb+N)gPQexuO=HiKMsxHIYv?i`TTF$NkiPGLrMSF7G2YF+AYjFbmsI{?VC_fe{*#~xQhJ~sBAk=b-xxMv6Xm3 zYe_iwF?Y(f4Ec$+P@gjfjMo7N?o7;bD`=>632WNAnsd*rddNp@t-J*~cOs>fD-OXQg@%$SZA7~0)jJtpwHXKS=O*4FWMCwx$2 z$1EW=&_#~-%Cc_@{M$jo#_i+fjt(YgP-yBHH(wm|uDz3@CW{G|vM9i(S=v|O<18TR zF`WbQX@Z;MwoYOX(fS+nMy6d{=_~K$Ne}9r=O&$gtmpHFer67rrzJ`~RpA>OO$I#1 znI@V>DF?ONw^Yemp^Mxp(xV5QaGEB-sgq!D;*IN{SnEX%l*Lv?N&WNlN-kkZ>jj;I z#w`*33uAH@q(}oG@tCk?J@2gOc1-d5lT7ogDdoJ%hdN`qi&wiJLfrLUa#8Om%+p#s z-&4ohe8w@o{Yc$PwUQunMCx$;!@a4nCuyGpO(_gQbW!Dm0!2j}-esgP8@QAn2yrkV zbk>biigyWbK69iz%8aD7-tn{~>(cfkPgnf=3Ztw+gyO#g# zsu)EghadlYM|6qZcX1>M6yT2tigi98M!`iB`@EYp9- zL-g3O5ju)H9Nlz)s&>J3=X+(Z z-YAH@LWvcc#g0PLp^cEl91@XUnVf2`spk?1b;m(sr-W(*$FI9rB|D_EWHpcw z?Y&l%zQDa|xxpOGgk*f>ZNeUX-^ZQwLz@0Zu1PL{b$v=MJ@?9#-@h^SIJVf~!AulL zxEHuGTB)p_3PQ<~LrrHw7n6?ieJgeCnFiEpXSbnv4CMH@` zWN6ZP{e$yzdp?_A9gFt4uIh7jDQgYlbT_XIT=;-;0BM_9sgkri#ob;yp5^rwrd5Zss8SVV>@Mv}`9;Ep<%tRKx0y*9`dQcibPO)2ZaJ^6Bzc{|FAKa!2P2X&dtz4| z`x(?ovsJ+v<-`WywWcrId5Z6+Uz8 zs}#523_-XC3^(ihJfvWL9j$1=@#`Sn^x30dalWtoXF&7KWMp2eo+M2z)GP=yrdxaF zojwiK8P*PVcATa>_maH!b}T8@UfbSMPBba?>Ix2e2HCo=9DCnt$u5QtMUWf+roR-` zcFRR?J!9`FWwgBOv<;?dr`CSt33JoW`_y(VGOI(&4K}QrsO*-kutP1lUG|o)sr;xM zxh^Vlibp9=2SZrKu1PJoyyh4<=K z3_s+JyXLtRsFgWKs8jTLuseWRsT;q|8S`$__VB%WVJ_>$4v`8?DX+AI{`^aXXcip=9GjqrdNGSF>?i*DPj6g%rwFlnndi+7he4 zPHlAclF5aK26S1r-_bEQC&K=!?nh(=m7YMBt51QU*>hmzfUy&GhKVf%ka z?|1D-eqLXk?oFOG8$FU_7CGxo)K2FE_g(bebOzrD^IKc*b2YiN%YOOME++YSsMz6z z&VyORoJ2^vasrleXg~6`(1YT=4o&9VqyYX>XFE@e&YjRqci#6&+igL4w&_VD(I)sk zOVv|rS&Y$mwEPapZ(cyf8o0cN5?%1jZCEJdbA5jCtFGq@j_112fAW)%&HI@_WO#LW zT>8!n53DGfr9Bh=c02D=XpFSb6Y+}}X%~ao+ZeswUfV&Q`ikM($lKT=tJsl7t(XV; zcC))~w*dyfhXeIAy=<^cdQRAmPqNopRDWO=VV_?_Fdp4$>8Wblh!wXO$oqTs?DJmP znDTJka3~(Q-fn+iUE54^&61#%SkU*v^6BP)q<>~bS2=bVSkUM~tD(K&{)C5-yL`g; zLR0;+@#~@pQ=cKuijWuoH#f}Cu2rr&plfD4wuZc2Rx+uJ7uiShW!!06GV^Q*6v;y( zn?kwx!{+Ip&P-ug_+}Cb)cZH=mM_6fwLev)$X-vL7*8e8JqV)VD^1gZh4IFhA8k-(oVdc#mw!=X*X-FC|Bm#WV25!7K!d#8VQ+pBo zUwi#;;V*;~_lz<{+~Q*tDdndDhD6Xri2lCOErFj&H;*2}yjb#Yx8I7AQAfCeEH8co zkoh&G?zkBv@)Z3AGaoaM2t9*vjH@z?!=yNnf-BL96jm?uMt+^)R%$3I=#v&=i9Og6 zwl~xM%SOMH=nwGB0Q4J;WrF-|iLn5mme6Mq3R~aQ<&tmwQWx9^)T) zMQ6}$P%ZyHDl41Zd+HX-dS;B_xII4pBH)T*%U7{!+wEP({@uf*oXzrJagK>-aUueF z1Eh%pj2IfSzCKh)p8ZUVTBN!d&>Jr5jtI^a-}g#CcjS2mpto~#C5Ur9x+YK z`}*r835V`DSg_d#*cn-{7vt4n(+&a2LPDz9^D)7}&3T5a#9NC~bzHR(pyHNats9?^4y?v9!2pN>MSGn?n<`D;{koAPwY$w4V3~5-6G3x62(G z-o>idMm{j|uH*=$>nSVTJ?hr1?g=U>2=O?m+TeFjv45U5OP<)gqfm0uM?k`E#j7;C z20q9nI@eJHJ{I-gU$^zz%U@Q<9DKdmoAg@v45^;8?^NkIbzhfQcUVgWO0`PoX(ppk8*7p0h?nH za@NvFO1J&jCAtOQzS(sGo@xMDS47!hHz0fTc1jY)laAgDpLORjAZOBak<)ygTUQo@`HfjM`){Rj zYR0g9+U#Ck-bP+@L(%6DP-P1A?4f>k5l>zKOdO+mU*p$zpKzJ)KyzJ*a4BR5;3M z1~1C`lgpQd{*fNP>CUMXsdv|umA|GN_Z+H98Trw97K&^kft`++S_xVkJ&$)7MnvW1TXjiTY3#W)arCrWNf=6^X*G z&mU)x@||&x4le5)ap`@b*CBru(!5Ll?mn14(yXT&f=Z6Vr)D=6pWMK!!IOK2Z0BDw z%0v=2;;o<2H&YKZl#Ras@Gl>ZDpkloR_DoX`A&5$QjKBbDNS0Ng0c`%eQ2>_ZO$@d~64gr)QxQ1j%(OUF^=V z-ad2IZr6L*;D6J4q%D4E>+Fq`VikXtAop*BImjeR+fHa;5A|z z6fPz1$L1LU4C3BTH}tb1V@$4XU>4apo|>{xhpBuNUscYPPb872Ow=~zz8X0y6e_>J z#o{ew-KeO9a=d)YEVA{h7jY7H6D^G7R9z0VgF*P;Au8ZO|ChwQAkM)mdU{|hIlU(b zOZfb_$!zx>|6IJCJ@kY$ zkx!84&*NgB$gJv{9lRUTrGDH_honVcCF|bDoWoB>-$C~tsX&5Yw5&rl85(MDd!c$p zGSQu)e8H;^3r60Qwlk%Q^xZj~VejX`eCkV@^IBV9cBI2Ta$ApGKCT!CoXmO+?|Xao z==I2Ra|~eY-=}>OEZk|@+`_qw#iz6Svz4%H%AYa2oW(&Iih^S^vWQic4WC)aYy_tRYy77)q%-Osarq@s4f*@an-bI-2Afpcud#!8`) z()rLc_Drr?8(Q6w5cyj1>U+ZuN|0tTWZV{V>+q@8s3fcWbc|?6=$dQh=R9&T;oklq z)Uykzi~7?mveNR-VXA8qkmO*U^P%crC6|7R4J7O)js0#LYe+t#8EFs4P>?p8M#B<= zwNvGI8M%cWEoxq~&z`CJxJUnvMpD9PWe(J$+arco^lEHzfRn5%u=|tanNzs^Z|d@# z+4fH~xRDxnTU9K7kd&AhWjQ1w#`z1|eIctufc5zJ({!}3WlGvu-HV;Lw_(b?n8KFI!7CW( z9T~;Y7~u6XP>9<5cTWwYk>wpcU*!HE_1E!t1V@f-B8-!~n}n%8ViM)O{&_nypN_Oa z=;R|3-~IP_^vxgF&??1deQH78sW+#a%G7L$i&rp+nnvJg-afk~F6&<^itzNSV6S)z zri^c2n0GF2*O3UV-8xkkSs+|GgGQYm)DaG!|?6$10F);cG7CO-tuIz1F4{} z`n!9dNSP-Uqj&y$|M2_s#|z{avI@=6hmYU+(W)muzc0)DHg(`{ng8}gSNbCq1>q-_p3qtp(7S_{)7*|_57!iuD(*Tq-=H)#8_%^3$?MLh}Z!L22i93 zDo98%*C9xios+jHGMC!9FNggrEzcC44QPiq&s}p-eg0Z<5#b`1Y4WsSWy`rJIecw z2dSGsw+&NSX9&4o|5YE!ehuC!+j+?d=Do2J`^3Y^e?Ykx*>OuL+CD}PX*oSIq_D1M}_U^?Xwr3)(}`e&)$==Z*?xZqvn!+}llzX`eZtez#GJ9-P! zV-7}w32LYB^Ey4;*Uacrh;fULpnNX@-=BJDuzVgQ_HG*trp}hHd-q>%s1Gq{bfka& zPe&X?3SeI3(9gbCXUC4rR9*8g%J@(}6@d}RtA*x73ne_pB#G3KeLlXM_AeTIxNKh& zcFWZGhsf)mqKhoq!|DszbcIf>>B!fZ=}+}%q9yf9&(&QJZUfb8=8m*0_6Ep3WX>FW z+H?N0d+p(aq_euyzSU=8grxmWn#J}q)~=u8|NVhqQskUmQX6Fz`~|!TjeMQl-IU?G z`?qR4#$>wjO2=c@^I`EZ`A}tUlYN!j4=)dLVfuK7l21GTul3Llp%7k8UsJIZwhSe$k6L z6{7|d{lVh=@!)vI+L2~gRg$^Upd=SHm~BE)ysBXTs%i)^ai+OWj+*yo>1fplWntVM*Z2ZpKDZ?V@Z~CtBWjg~Z!D?rs_H&e?2j z8wJgy(j1kRv}i)IGB~2M7%gBFY!pCOp^?AmOBs;caU4Li6yUm9RDP*G;q4fo-|szS z>R;8np$^3*K^@POV9B}YnHYvGu2 zM+Ei7=_(uqk_sxxr3P^BiXAXa>tx3BE$EzVX_wu5>wi*}+mPAWlo6!7wuN{|#!8Ki zk-h#xy>N1|VnUVPVT%aLwZ4U3F!0RFSh+eMH~o(6?FuMrj0xV5$t!FhCWn)qATBbY zppEEiELTB<7S}q-%y7uv$FSH_%KM1bvzb_TQ&*OY^D`ehRGSXVWC1t9-*$2L38^=8 z{W2U@-ohJE?0NrQVYRIM@1nxfCRu7~yOi9Dg}a1Me(BMJ+21wjZ;<{?Nk?6R z_Cbf%oD``~v6EFJX|9OXTAqZB6?*E?L9SPp+w@3BF0-9p&W(YwYkusg+Hk*P!EkI9 zp;PTNi25u@RRSJAjs1GtIiuui)%%bA<}=+6{j}krv-;^k(H64nf~rsn%u676T+P3q z7{4{7FFX<8KW0$VHpg)tSLqV-GNL8FBP55Vjna14k}HQ~S(SQoCeu28h?N<^J z8gAPWtWMU##b<5o7$yu4<7{9F>`|*=eM_NGt}OL?tyksL;N{Nf#!}oe{aWWSFe@4A z=ya9X@3}%y8(NZ*Xz!xz*LPJ7^oViK8MCRf}` z2f?M>O6MHX=cTFQjNgHiyp48QE=%4Et^R$-A<9%JtQNCSmoedZYPiXEe<~!EyyNF+ zNRN6_aozr%9N?`*ZDt%#0K&aEN)ANdnDkfs$pNX^$!{TddUkaRkwkGYjbZrqAkihE z6sp$T6HMnX(s=mH34rz&L7mjQP}}UP4wKW^o7{4;RRaOwbOUA)gRg1A1>(LM1w=T| zC;q~Pkhl|{L_*ND1@M!FmN%RQc;$c)!<goK3dLf6F_Kyk6W4hIpQKzwJ;<)f2%G*muP*TG_nM@o}EBK{W(*bXbAQdVUrR zSw6hLWx4cn6FsB5DAV|G?kjlN;~xA_D6#suzU2wL;)$*60rRj}QXoy7%YkxA*ZZ)m z$JqY$X+#4}6RvZ<>E?n*Y)UB}ogTc@B(-bOuB$5EweQaDJ7}NwST3`r9@_h3^-)Ln zpnj##sRFySl5*c97;Wf;Q{PjB(F>7Hm< z@dMCX->KOWcM4AWmvmcOUEzV|@Dh&K&vJJZbils?FW2PsX0Wc*@Co$UQcu8{sJkTk zta2}e+j^K6F}Mp2`H@>2dD*L4-F@&Tzz1j%zVP9toyNV_)yNbDS$N7JeGrcH(_~g88`9v!q0+YcXGCG2bwzmenRA z?*8LSAxtpW`oEABndrV5are((}D{WWC(gR#4x6R#igw;y9%1 z_9ItUUSl>$#A)0sc^1|ZZd0V%ME{X!Y}W|o3yZg6jb>fZnf}+yS9FV4vre&T0EcoC1mj}PYZ$?kLEuUFTxN)K%6#gO4^+^6gz_K`GWY<>2dOLS+jQEjukUXLLY(Z{(}1T|Q zbwB_r?=@-vl-7~%!6 zwoQlbX^AmeHz5eK=0#+(G6mO%h7uNZ80q_#&NFknvFaYid8cA*NFpJsAN+{j(goAb ze{kTvwY_J{l+`<1v!eTlKB@Un8ZG}u8woXtpPU#M?f$n$uhLtsLq$gyX^Htw0`@FQ z_OJ?!s$Mmw9^Qm<8(y3!=T)n0@BJx}mJ=0jK_`V_mognB_n&|WNN!-XJj3W_u*dAx zJsanmi)!n2$f4d&_wyKN!Wk`9W4pYl>{3ddjvk*?wXx7m)q_gC1a2-@cPU1T2bF=bz1wo2 z6e9tGF7#R!vx=8G5sB`Ky|&afIEt)jSPyXNiDGu9&;X$5ExK$w(*-jk%%@JBw2WXK-h}nJ%y zHv@x(72fz(?LAvWD<^%%Sw~x&(3kKsi-H0UW|*m?TWSB}>FvRylSA{*G5`<`Vf<|{ zxD&xh2c)37vD3#me1)9#xlQy$%2U~TknQF(Nwmfv-wr;;>x0WRq!E9pkHQKg155g^ zTiBRUim7#C)9Bs0-7CwRDH`+Gcn#4|+hskpQb}lX{DD)A>GQmJ4tu8;)X444?DMhf zEc<8f8u0ahoAmli%L7X%XI$PxdUVxC&S_LZ)2psWaA=T9v%)Tb) zZ}p2n=iMn)hJ8$m^-e#?dUXt_rl;qm#*T5ZG4`z+EgO_6hTA@;(}rqL9+?zK4sQg> z_n?Kuo=q1uo(m5aVKxY74pU4K4aqTgb6xm87qC5cr3Acy=n1mGkD^2=3PqdBq>KgX zXMcq*i0@JD#qyqkeP0(kyzJcVP&;U$_Fg97`=v#Ll9C@wg#*7dvv1BoCJb;_RgJ4UA1?bcUv2m z8}k5GW6LTTCAUlg{m-d z_-osqFLgUjH&vtb1ae7nQln^bk}~S+$|S4sQ?JYuW5d zaVeCh+I@Wa}XzeSpJ;MB+`0 z<|g?3Qy9(k!*W_@L4K_L zSr&Vc=Ue1%kbT-pCk<{WW3XJmjTXzkWOJRPu)`*)`Wbn>7Igh3URk^0I*atc99jjZ zruJjlWP5k7uQ;jLu8E!0Z08f5H{U}1)eyX1c*N7=4f-E4-`7!upl6wvLCI3pmz!E& ztC|VqQszvQ`+j>g`$b|$e@5JT<5BPeeo%tx$rcsyFc*yUJW}MG>tkbHMa2j2zJ~y9 zKXJm`HXejR`I%YYK=u}zN`G@h7PlP)WZXH(p+P^-4fE;%K}n2iKw>jF_2dS&M!a&9 z!JD3khl|$+;ZHet&iAz^)Psnh{{TJwX}QPY;4(BnZiI_dLzj-mo;R^3@y#5NuX^ge z7N#&d2zX)qiDi(Qh@HLA-PufQfY|8>kLxI79>XfdPuGT|Zkpk52J#&q zOQ$)S+te?QNpLQQBQ_jtK~nog>Z8Hu8xX`-V&eDxzP!DW9a>ZFfa_=UUkO>)4-!g= z#Wm7T$Rw~NliH+4BqV?Y&I+#ckJUqhBQp%Ly)3V%C3kAi!jd*holQzAa#{jOwF#0w zgYVbs8ebg$rHN!ih2=szlExH6Wni$=`8WN!L5v?5CF7f0scEGgYFD`po!vTmj^Dg> zf+zf`<=_osbzq|lk?E+Y@&P`cw zerULa?y)>(RVA416eY%rONKaOPOc=W#f**=O^ml^NS)J5q-CnG53G^PnY>m>^c-XlKYZAd-N|B|{E9kAS<1RCT z66H)jAX0kS5yGXm5ye&)y#)6n_crZ@4MXViI(Oz!b-_MD#Vr$F5gwl@OKQ3Np?C~o zSOMI<$gF8sbA(Wc&|xbdWd?_y;v?(<18GaEKT6%PQCHYf3~>jWzlW3gCG+Wc<$XM(d&_*Cup+ zGxOzT%K@NKn7SIwz}}m?06y)8L|o^mo#nUPkSVPyhS8PnBM>(wvPw#F1!BFP!cRdG_H@xI$MwVjkAC(PQULi_)1&6*=3C#=qv&+)UFJ8X>KhfuhRaHm1Ek{t z)B@QALYulR|7JjiTi{xAMSO_vTE;6}MjdKPNR#-^PsoA@^k)a{`@~aI5jS<|cIR`V zRRF0eA8pZ6Jk0xTV*rkHgKry0tdjD|l_>%~=zWfw7EQMwHO9PX_c&W{hS}tV%AudE z|8^$AJ~eoL_-~DIi>GNAgJ(~+peCtjmhq6m;Hn1Z=*bGdWG6F6p{~sraE;)^!85Q} zx$Rj247=+me*Wu``_R&44+q*g$5^KkVkF-i|81i2vEdBUFl#u>PEZwcwpOl z2rQma8Q-idH9h5LNlGr6r91vMD?$VA^x+x=8htwB_Erhzc@U_V7Sg-J3!xZxG3C^8 zT8ZA(A0gjen@a!~^RQOsRzR6};(~Dlx`OG*m}M^L)NjjWaeGtiCy}cXpc4@dVA+4B zc{lQ9aWjvZ8`@@R=pR)tGX3+A2XWK-k>-jCxjiph>1vO+*Q`fPTxHTMGhULTk3ruT zX(ODsPZr_sH*+Rzmmgim{@y!w!mhW+Q_r0rOH$9BR5wt06ZKA*ueus;uA_x2U4^~c z%>zwPpTmAkw;xxdDp{2AHfYQcn53thZ>mnO^&WDmaC#rZV!G!f%zt;>IYXVxxq*Uc z?fti_zeElirXD48E@;9S8ptA~$RBF8{Zi1P#Bwn1^v?Omt1+sI{0w!m*zmo97n3&8 z=2_-7Xwdgp;`S1SEApwXZKblNdg(P6#!0fKdyg@1>Oz;pQuWs@WEoLMlB@A8Kb15+ z=S`0Wp(cEp;YzNmlTEgs!`XmZ6FgoP>lNdux0(-)47KDV`C*e{ds@ewJpVkPibOVi z_WVqu(IHkq#H|W$-_3KamC8J@yB6tSn&tt82!Kf>9*yJWF;UL9_-1>6?w)+JN{xfZ5x^9 zX>HqI`k7o{GO7qFKElEBc?f435R?QkmO2`V4mS1Y{*frt@pigBtI-qj29_ai9-A+? zK$Cj3F&x^qIh?WQNgE**E$3D2-fnvOl+2bT@pQui3m~@3B}C;`miSV_?A5PY6puGr z-bGQ+4)oFU@4avHn|!83o$J=EnTjQ6L*rvQPVyZRdLrVtViZ_1`=>vP*38A_ir+_C z483n^+}Z?qDapILzEt)cqJK@#O8*2h?^69@5+KlHG15-4=1wyU-=7KCBI^q zcC+aZJ>O>sz`r&mGV@3`n0}ktS9Gf6ZrDsL4FWXOr%WzYl(k1fX(Zf9Lrabku|1b5 zT8H(<&2<70W#sAFD6<|H8S=?u1d9QMh^tX&J5Fu59V-{as6iH~YfzHOYYlgKOk-Lm zLS8(8%Z2RUk=QtTQqrzx?svV_24V9$AD$Dxhy+M`5kI2u98C=Ov+Xo&#2z*e=txeFxtWI59*ybb%)Y}+ zE%5fxmqY}tm8k|%_BnX=H7aUTia2?$e1`2XwD!FqqaE3zdH^vTsEe2t+wgVqqdRzo zRCNWCDz2!UtZqi1r~+$+^aAf5x)$P*%(ba)Hq$Ik{t7(*p9KJ%`Jppzhem;3EYD6I zkAA(Ayq{E!i7NBB-Kew7-&f3T4cPl#^?0A@LSKXpc=Rz}{77rEvJZ@M@a93LcwJZ{ zjIVZLt_jZXoiuH}nlVjH)c?^ja^q!u^B_Y&ZXicollIPUW-)^nu zTNQP_AMy|15oP^RXic-FfhyedXJ6*Nj!pS=V0F>cFU92j%D$V%v%{3Mrti~|#CCGn z@QQ!O2lEb1!&0(mqoc9{BLtV7DLF;zVauSsK^6vo9j29-p{|(P!DY=z=!WYtouUKc z)tRf;DyH+gFDChjO12kpy$@hx^(3_H@(e0j{qOYR<5j0})c|DzLj8+d{xzpB(sJt3 z^j372c%)iMx@tR?kQiEv?h%Jv93=hk7>2iuzc6;jT9#G!W5zE~tSFP86SoGUB5L>^ zkORWGajiC5ktA6~4f^xV1^0i+{mf118^Ke)B=9AUElk`A_2SXz%^M6}Of)?Z=79?d zC`kNwki%ShoI@eVG3mxnuTipm^kjG70fgwl%QlJ6RfiDMdW%_h?WeUCLm|kc5KojS z*09;naKSJ4aA4Q(3p1(~I#ePo9?Rgh9PA-AOAy|%@Z#lLv$M?;m=xu2^Dn;mec$wG zVJbicQEAnXwGy**fZS^Z)9$Jd$C^nwESe6HUZ4Aj0lN?yv+0OTt9<=^tGDz)>@Q0%I=aWii zQV*rs^!8nbKulS8`kMY^vABP3PuqW+v(O%W_RlBVIxGw?D-9f$uEp}E&cs5vimqNv z$oxvf+N1gi|9KzvsvKNplU*oIR&E2^^>|y_JdDbR5YF3BnRm4 zZtZ94gvwJj?UQkO^@MKXA~QI2YE{;Ft!zrac4Ipd#jx7UoK{}MuFQzAK^{A?jycrL zU|N{TI+PRQRex{o#aQP3tNJgovkTU|^hu)6Z}AC7s_I_we5ik@xKH(N-}4=mlbc)m zmXAQa>Z#2=%*8}SaAdo}!5$HUT<&g*XGN^onW8V8iABLD*MLbGhXY19&yUx_;m0VRnG$X(%DEL>nWC;oq3XB>^+-nKCd&yj0T}4Udz4%;?T|D(D+Xh z*^6AzSyh5?SyPBGr4^ut!hjCQEOprNq=d=2G?5^1VqS8P-n%nf z`AJnTO~hA}O!SIdLUg`oZ-qfB%LHvgPfyLY_Dq+z?pa9N;+skRgdb6d&}eJp%Q&y9 z(YdptImTUlcJPn?O`{@+jyI5F7SGJf4@$Nr;4*F{&RS+7G%M*?XPPwx>+0@}F)0 z%f;#xPPkcDHIu)wn2ol{r6$<#KI+}zdrM+8DATQg_(0pZAd zbXn={x8jezLAQX;84We`<|E<2n|>zNeNmCIej~OXEZ_ylpVL_=7`mG4yn?9q)mIQOG&65)0=eDRxBB(w|Hkoq+DR{uhW#CQ_Ka`1r-k_xc_{)x9Qc*n@ZyySIx_l zeg}+jU;r)B?1J)F)A~0<@}sd@h)uARxZ0Smu|G6*u_x4hs-EB4Zex|f8~bg;dVi$5 zAoYpuVj#P-mr0a(Er*HzXm@^mv{$vH(SC4^y-|X_ zhi43nl7ROBlvIH&=Qq?U3?9C8B+sq3hlzg9$%b#SMjKD^1LF!o&>I6@ZLl za^6l|U0HK~)K{TeZ{Qcz7pvd)XrF~%@0aWUz;Bf9M{b#4Lvl;J1Q$_4`-h5s3(p#$ z%8$7FJ$OE~ugU7t&7L2^{1-nz$+87<_Ppn>w>c@2CE+AVa0B&K)%H&6JysOM(fax- zogG>auSK6^1AHy;y=IS*P0Y2nL1Z2Fq#q5hhu5cVRqMn#34Mp_vDRm)_*Yzh9htgC z%_rz>Tb|-u*LZ`JMtyb2Qd-6IFVP?oX9@EO>DFUGd}eBB%+nHFvPYN_+MZpv*qz$d z+{PYnVg_Ax9E0dj@$m_cs2!5$?{18rxwR%fvVVj*t0}D9nfJzePAFlj$`q;fe-AEx zx+)mteP+LO?;@Ad6b=5n)PPvr}IU)LRt>ozl}bZlF8$D6(I3c_wWxJKLF#* zG=7AHIf~H^k4|aTt}q%`9coA3N9dJ5ZLy@-JAq$sdb8M~jcrb8zs>Og`MUn!Co;=-S<%8#w6^^Fe>X$nx@i-V zH@;i{Uk`CB!C9$WPFpRVzB0Ki0;rF3RfmZ_f&F~Hl;NGS)y=P!#dXl)Nvwf7@-WXVj|CPqJd@w!N9Jxh}rZLJGR@>RTGu4QCsnTXPVzG?Zs z50V(7jU}NZ?4t#OV)(wUXEw%z4VIrN9dYBD9`Z)}Fn14B^k+u1x7#UDO6gxTSG+#o5Xu(&woD zwouq`HBX#_<-Yf4(n#>Z1)h6S;~)eeWl!u+b0ZQOByN3wi^9yq{E|O2IQHj^GMI`L&L#qNmUeU?o zV#oGjJ6^Bx3E+pMW{92w=Iq^+5Ik!}aHOzAI((osTI`}ymA1sajE%esx_BqNlC=`q zMICvp;XSf>|NM8wxX!f90QGJ=9L9+C=P=B^o8&1UOyEoR z4g{RF*@D{KusE!CdV|4?Aw36f%zvBhilB_{{G0Dw{sJR6{$L?xr!To* zR;BF?EQwZA8hB~-$C|TBI6`a5e%ryqdDjcvQaD()j9#Hvs#>i4*Y3TB1Oc^@a=Bc4 zrWb;c%kZcUn^@Bu5jpqbtX7-PaSkZ2_MlJlL%f@XRDso6uTAF)^K5B;UvJYb8>YrT6^Q3|`FpK#cnO6nwpEUeR#|KFYls!S`Pz zf`t~JBq+K5Z)VMNRrn`bmj-jw@FOt;ev6Jra#oE;P$`j3J}jhynhBbGGif-BU!Vkn z3f$=a&M%2P7nIpp8g$-;lA*)yo5iQ8)?%5Ymn2&Ms|g%xjJr|KOfFDU|Fz~A#adV)>DP{jaA=ZX$X0bs0Xt+_q?i-+b=6ng=kzy- zWt-+HNx5PL@4$gvj`dqU05Napj;|awvw?rV%cw?3 z&s#8j!3=fjAfM2}_B>gpjuze&l!Bg8xBaMo17m3;FJUg2Tj9P6avKgp)UOnfiPsB} z@$K6!-)&leEZN)N`Cy409KPzvmD5ph$CgkhjisnbyRAh7(uUz7kv3bT58*8Np-zU6 zIvZAY`rh^RaeGdOo0e17H0t^I%rtZMN8zZhUoNfA$O^XKXeqU(a^3Ls^mL1@VCjWO z@+#itj}$nF)cFOTdVgxT1bJ8xe7&hY+51Esi3MDANm5;VTqN&&AAC-;)5#_|{V5Am z@f2q!B}h6qk{+JeWW|)9MdbkjgCru1C;yVaJGyFTb}NiL#wNOaVV#1k&5iJa)ZC7o zSU+yTdQTX0D=j-TFAZEfW?5usbiSp0W|MEhXB=hj$9+8nxUc~-5nDV5D_MzAky7kqeTQnN<|umG>9-nx&}-dMl%{lkJ=cqjePd~o%8$) zJD=U>eP8!=y{?`q(R4B5hbV-o)vrJ1NpJ0GgAS`fazA72mSxFRIas*o9KrR;oTSi- z;W|PQEceTF@6Fj~D~V=NJNwxmO4Tu{L9{`>h@q2~rXD?M_co;^-|yU^4uJ87OgM~|#JvNYH=> zK5j~K@$B}~4uN({TUk!e230*vJ>vU;ml%Be4Nh6UM48ix*D7ut&jo{UpIzl% zm#Q+BDSnvx>1?q??lKYG5ZUbZGB}WfAVlugq5)Ys!G*ZLkZ0MO2BxRGbduu$tIzQ6 zV#tBE@W{q*h7aw@+(CkQdZ2s{>y*y04hHo|ieW#gP;A_EOd2v=oiuTnOa*P4ie7p3 z$PDxo3||_?>`!5R)|;oI_dBIIDcL&|X~wS9+y85=LaRR?8%zD>>ywQd(+cQYDU#Lw zu<*nhIB+AHUlB^Iz`rO(>iJMlCIZ$#3V>|}qI7M4>8Y6^Ir){5VM z`HnltI?s>vgF)$69>JY<4{n^`nQwNZDOy<4kvL*!@o+vkvxBB3ST-Ck&pNAn4wFK; zhG{{(!&7>PE6t0sXl3VU^x&J?al1VOxcdi8YgPZ8kwSky811xo-#7Y+>9JG#!3Yq1 zQ`YDwKR_Yq2vbCVv5pHO<8vTEihwtA#Kl$Q;Ms63N62|X^A0|_v62f{=o}t;`Ukt; zecE~z$WABuH_%=BGFWiEgZ%wlrcc4n`J40hZRD^4=}+< zq0J718sND2A6BzD;9mujg`p_;ai*$=_gKhes=3hU@jvr0Fd)Z~N#QJ59R7?(cBJKj zUB;`>4`i5kl&BVad*?O;ouc!n;z!pdek?JfR*WS zn8#@kp9W_ z!&K2RYxSi1aaC9B)#MJptvyvdgIVy(TGFQF$x|7kqvECoSEaYFK2Jhb9)nC~O7ONY zu}ZInD|Bh`_eoH!1g)eSO31RYL2;J78gNOlQXf@tl(cX-f|PB#OID(t!=`kUB=Ai} zmxidyGuZ+?=K@~Lx9=WS6qzWBY*0iN2Cvl6xUo)iE72l1Np5|UY4g!)jUCN&nf*_P z$4dbb-*TJ}q&)=;OS^(6w;t4;ZHOOmjPwgHuJ?CbEQg*ZL@kiw7E&d!;3F%rFKLQW zDKkY^ZG)iw-!#E}r52)-)X5Ku4MI+Z```Gm$d7D2(|_5W_3K9Sl=U*v*M~yE zJ?O4F2s&zb2UzV51ci8K>^AJ)J(6f4J|kmMcAvE-S!iGBmPRFuwqPeds+qVmj=g%D zNRfYv>mJ+qC;HVdvv9ihFf76hK5-s%TWuLQ(DcEb=pnGzVAkbFV7Subi}Tp@wUX23 zY|okAn$-!3igFq~)55~q-=pOR&s_45uS0%CO^6eQbY{$WbbHH4ZT5YPD%=L`o0y4V z9a@DFFGXbgBOpWpFh~;lv+DMa`R+ZY?_bbXh5m#L|@_Rdw z%&&L&z9~-FWG|^e1pO(|A)u&CUy5P7FKg-X-@iM|mOGh*bhhvh9NhWF>E5Efipg!N zr@2?|{yZL%6P4?3HhJCK|1STu^~O$Rn#^9~@yy)Q@du|Qz4h(7z4u>a0Z84$U#=qC zX;))CRQx08m*38`_?EdnM4b1qNK#Cl8GAR%Wcwa{%ui6y>NkzjFI>6Ol~;|OR0ILsLYN(3 z{jRJ2Zw2LQV~*m;67>KDO-EzF6#W)x&(4Mn*#qnf;onnN{5{46RFTe-G4^rSLcp$L zjkn~V6!R?P|IY5jRJ3%5vE~%yCP$AqXm6Lg?GbRo|EfVz^3o9xfP>Z=4{{&Bgn&Qc531#*TKf!&ypB<;gk=G0y6EA*p&B=2Z zW?M_2-}U9@!>)MSjtFoo?i~d@lNXJ#1k|=ub>>GW7G+uQF>;#zyV3Sp_?5o{kI|%% z<*eUjv_cWIFI@F|7GG0DqX{Fomhb1U5#fD5+wkU>Rv~*M_lmqys4r?C8tr>u$`W>n zP=~O#q#_xc>0hf1-0B}J0rAcFA0K-6KUL$b?brJ#uA*zxa2?koP`)yrvF-`_#?u>n zh4umJ{nXa)sKfWh%NI_-(BP(?Qi$`6gDU(WI=fdHuv)NsRJKtYaEqeED95V%j2K?B z&qE)V(vMdQtaL#R4d3lWIKa|Qaprr2)$#3m2L5}U@9f*>Io>}@Op^1tW1KA`D~_F* zY1V~yVOj$BSI%IK1F67;*^M59xugYy?=Fn|J)=^>7t$l~98b2BK#3)Rdiv79bb1~rXCN6|P@dLFW z)1adsCtArs_Hxar-@S}wF`Fodd4mRF(;(#3`FaweSf23B40K+#D{;XqAU9nn$G4J{ zq4Y)hd#UNF;Q7)?_C3=#o$wcMACAFIlEzeD;1?pc>53I?%?o*sg@+_ZdH4sQ_U>Jr zY(CTCxgQd~4I8z~SM;yL8~5f0FZ{EawV!hY=a^PCSL0kw9J0m+tD6deFUVM~jl#1A zPidjBw`-k6Rvej1ZTv53ZezYD<(0!9LjfpocTzsTp3kUrk|D+N(+Nk9GDD=VrHGzw)5K?q+uKbS)yMksp9gTL z3?NP@O;Y$$#Br$;017HU>rOcB4kAZ~kw;7%7j>^L7}Dhfhk}Fr8tJdm`DD(9e0LO) z`jAnKADNW~H9@mhkY*QZr)ay|Znd9GuEer)OStb-gDjYwI%u+G9F}f!nZgK9#)fw- z1T9;=Y_c(yq+bdWV_ixm;&eVI%kVTLBnjae4&SE z?+WwHR?&$}O7V@zc=$TL7H3vLJRV7`ol;NVNhVGSm5 z>;tIiZINP%WAc3n;VxLgeo58Xr+VGu`l@=?B(j}`X+g|a(9Na;;x`r>W}6{Hx}t^< z(+}P#7syo1@xkYMIq%XoA)~bB{h|Kl5_|o5fiUMK8Iip8SwHnSo__8Z^b9RHrN*zG zz9{;d<5nvh$Lny?glZjsjFY?G%vI^eB3-~3gNV1GK~O^H1_6(hU6jH4T1`dxumu+g z<%G>|FZMp7Ul5Ph%#`{BF>9&J=wvWDKg@|rc%&U7vr!zNa^d}_jF!1v2D1C=z;5{K z3C3c{pz(^h5HzvQTI(9i@XB6Le(lb`uPZ&$iuQVp6|~wBTT8dnk5ut^b{VWZl?{&cu1y~B**zw~yPw}Jt4s-jELG;z6YV>8>6jhQ=yw8dZ#| z9mHQ2=}UcMeS0Hjtf(?e*(6v}KIgleHv)^=ZdZhjCpHjvK)BsQ9mee);TiQEI?2U& zQcVyv0?{JD%H206z2f)FiSUW3O#<|_N&dEe*p<{zCcW0VHr}IR_?p%1?$e=|kl4S> z*2Nyw84=TgnQh4?RDrc&@wdG;lGGgBh$;{@i9Vc?*2-GE!s9v1ub?8t zOK7b<-pdM5cUz3HlHi>0wy5RcNS7|gp-l8R$9%Ha7{5Cxu&) zo19aW0dXPwZ!WS-NSSntcV=IXbLM+eyP6X6T>Qpav=YF(OWgsaEMqu)FJCuLUl-e4MDtwEejf@ZB%L z@6wg*I{yyEp3TKE^vX

TkAkMN@y4XW4;!1C@eNz!(4awl`kh=nn4ciVweSzBmpDPE608ZDsXSlp#xB ztSzvgQ-sjk{Y%rO>9mq9rz^@67Y3+!-~AUk#?HNBT>Qf z<@*dyyk?FP1{P4gnl++*ZWk`0o#bn8x^}iZ+**)h%kM!ZiSLLf?4|qPGN3~SEJ~8z$P`$rMM+t1YUCn*$bg&DCZHAf#Mdf*n!i^zWr0~7_1u+(4M^K4n&=p?V^I5hET6Wk3o;He_-^Mttb?@LI0tyl&lH7#_ z&f9+?C2=5qc6QSG>b)pNnXA7{>^Cj_MrOZ;OSpAoTFpX9rBU$Eozie4lMG}juE{Bu zL6Iw5^i6uS((*OMpLw(00{L!D$q0hURO=WpW^-}tkF1yJqDyf zp+?#rT%g#h{Y`E1Tf|D6rq3JL7veYd{q#u#gp?W7V^JWl&%`0GHnOM&+f_LkD3N#% z?(E;-=VS_KJeik9tq|9+iKrIl%i#3YoK?tqgA<*klX8(yUlh*cn~u^UV$aKzFPf25W67PbiZUU74ESZkE;huW-W^BM8VlO?auo2PSW@8Z;2dbeZ z!B0(6!zuN`3V@rTOPUan(s=i zPSVA1C+|pp%i0x$)?3h}-n>8e1~9U@ValO2cYFL`YgpX^esjElWH7Dl{taftx%ihk zfDh0ca`ZP_F^FsDD2#a(G|A!^0K1WevYghvGulguwQ1ry_KcUfm9Ak7t9>5x61iGd zC=%VHDHbksfa06zgi0Q*{5`G4u^O2G;y7>i!y5h~z`gL{-F$v78~?y2xIC}0*@3?j zO`k)C;hW9T1iLZo6k3&kV|fCgq8z&F($EU20P2^8UVI0oZNH@w`?oG)Td8c=b%%S7 zb&@FoA>BS^7rqsIC#?uId_ymbC|4CI)A?H5tHVe-P1h~l{6K{HA^(}U^f#YnV(#&! zV(O9}r7y21cv1NU6VC6L$|s^6y4Ye*lU#%oV@dCoo;Ydy68Z!r?Y){%U@ z+x5_@W8R;_##LA!tqEt@>~FrJw7k3ZpG=v0iEfO&9__JqsJe=^%w^C%pb__eR$8vG zz09UgUk+t6dzZDHq)>g}{}fUQL)Bk`tkFE5Pm0WC&jirjbQEA$PL=wgFLXjB9|TKH_j<|X_|UE=o@ zzEf5D#R+~L2Xcs>4J8t64whJIXuse+RyE!kgan!~6AJ`GJw7iWB|^zt50h83rJCE@R3Ut1b z7-2pp{`a-4BuH1fyXz-`o=PLNp(rJO!SO1rOWb>HX_=4`>Q z>|<$7rawZWGM*27R3dNv`nxpOl@hi2w<6*}X;4wHhW{0VCR$0elWC+T54Y}cUl50Y zPnpdulE>S)tfLSmB9~w+xi&{7ylcx7u2pPq|g7&aolwuQ% z-TCXyDa=dQEwQmC8MFGW`1Bm{I;J@EuidnbqSt$?B?tV1&gz|7Fukce!PRV+8scX2 zJ{U)r%3B{SA3H!g=brjf2V~X6YB3 z`m!=tbe|mm+`*bG;x|HsAFj@YvNY#+fF!}5db3D-A zny2XSH&cv#l3o8SckXiAVPvdu%TYn_LMrMdVs1_vR9RIvJhg57;R(8^)B2Rbvc29^ znzyX_9k}eec^&T$A8dO3CkdIlXHMRkcT<+EA82l&lw1#EjHaksM9OOCbVfznQ7`Po z=hEkLzb>cTrsmx6*zH_Q4%F$z`|zHKcB`7{+=-lMrroXY*!b6Y#Ck7pu&Q8IcwV24 z1qrDv7G9AhWU)0QhkB<~DF~+?SY<$F-wIVwd`@?|$d41m9fNX>GT=FC!I+Jk34zi+ zV%SaO{AD&2s*gdAKbt-F&Ds@BcwU$F(M=9j&Y1(4P>83Qp&Gy(EBb~hd#riwxlD$@ zjh@euC(YsWc7yA0kGF-y6M~lZ)a^`t;eWr3&~LX+2r=&$&VTh-c3P2b%dq}U_dCmx zzGQ;h?sUd|yX!gLLZp8n6go=+{!Nc=A@#|6?f)6T|I`ZIw&G-Sla7l@2qgh8Fvx`S zjRaKYNI(v-pxW z?7?oxiiSEw*yMXavxvEzfnxABg`^_cDOPL@_1xaD_C)Sf^{IQi&NN9iW@faFSWo@A#CD%cidj=eJ<)B5rY~-7eUYse=V84o+dgZ5HOXb^;y7#q> z(4CLypKY(Lem*h955%-M&3~GmFb>jIT$t`LMG!n!8^vyPgaym4+LxB!$hwgWJuc2s zV+rSp5+lAjD&L0H^P73J7ac7x8s#+6m+jV=2KDx(xJmd+Vpo6MZrXn&-2iVXKt2Wn zB2h!Q`=`dS>83oD94EU!c#jJnBsj@L7X471B`qF3s2jOzgzorKc5u>S4b%%^;cxlI z5h$#1F^h?$%hq`8NP3H!b_N#02Ak|gz&kR*x3h9oa6wxD)1%Y+6sgL(Vd@d}AqeJ^ z0t^5C51q{=QCuP5Ny|New6UZ}Zr5B|0LFbiqjJCZU(j6<%+ylz!Qx`04U8T}`Fw7< z+L%D-#XRkK!+Xbkx#Qi87#nKcpQ{+Yl8qc+QVGSpSuhQ)`wmwKCJz?@DdF@U$}l_3 ze7k>$bdg?vTa&TiPKw3_FJsQYnZk&s^Ll2-7Kzi;H|fSg?2NsokleV#A0gk%x1uOf zvO@PSZaxHsTA6sz_l@H>HT#6;!~6mKMb__W)QIwOtp_FSCMAhzr(#2!`c5VCTv7UPK<8ViE)k?+P1bRQ4zu%bzpmlAuuF=Zc>x|oL%05mWi0O21 zmzSaWaUM(4!l?|eGBl@SSj>#UoGL)MV}UaRzn8wmI8m?ZpRX^H8fK^tB_q>C;&Hth z36QvhQ9WIhB!ND>tFlAbU>RAJ_D!-u%Tx{~$M8nwYDj-qb?gb>;->m{^%g3z26yuF z<9(jLmux31HL=OeqlZqlkKbJJg);LyuqfIL1%wF&Dd=6E99FmKJNs5*TsyDbtN~+@ zu6z=zfq>01neV-m!T_H)SY`T9=l<80D0|C@^?N=y_phyrb~>>K+;pPu5* zcX1#k!ncIqUO6LxvtjVDIuLQ%hfs)m;KzsRJi(0sYrD zTp{-E-;}D=Q>beo&*>McI@OoldW=GIjK#|zoEW(n?_672`RbogBu2S*|6T|>tVpSaYG$A|t_$Emg8oB7!Q`PNphDf!ORdz)biaFY zly94vzuRrLwZJcFy~5Op>^>cin7`jYm`*D=_u7CQ^_QNLRB|;O_H|3q6r&EW#3cT1 z->i;gRXB1uoT))>4hfppl>*S2%BM{Y^z;L3OkbSj@qBmIo$g=FI7tzc@m-RQCR1YW zkdD{l43AH*4NCuwn0$KDDZMKBb$!uPVf;-`W}7OZ4_;!dA;&dIyV7 z6RNx4wJ`+ARJC@1{8I%FuL|^zC0XbOzN_nQZ9`t)P~daXHXF>?MyJxcnyJ6nUaB`_ zS6y(Y3%eJL!F7LsBU5isDsLWn*26r-U|J2mT2W6`$@nyV4PRAI&>hMBYjN>+PG>2E z`y7Y5cCLsE863+ZNH++DeL4WUroN9Mil4nmP%+0zy>q`R-}8;C>fBj#!LAJ+AsYlw zs9t`eX`bW8(kpHw^2salxs3$%XNt%%hO#YB9IEz@-unwdV9(s29mj>BY;tUFjQ8#9ER(zOLEw5D!N!#ip@P1)*(u~Xwrdl;DMpq4#1``Fp zXnT6!1Nw0&>Pa$=$ny^siY_3#ZFuo!Q{#@Hz_<_u)a z7_KCQJ-ilq^rF79Ty$~M!(PRI1(%LySFvJoWRya9|FTUuKXn$7M77E8D71FfwO;0! z?9O*)wqTqnm`>J{tL|AKum$Dtf}10ZPaS!-a)zc9M*N{}!CNzHUOPzQiVn95$FCgO z9cI*X$j$s&YIKP1nVxnLeU-pskWX(sKKee}ysldIN&7kwae@JIhFlOsLqTfq7y5(5 zmJ0y(P1VRi5cGbwLFj(J;%=SQfHJet_B9(Bi>k{pDHkleNX*`Uj>IBJ8?a$5VZzLZ z!mo6!AghFK06ET&DU0ZS$1j4xqyY`~!``YM1(TJDUY-S!<}c2PoFN-gA@<&uC<<#U z#KSbEa%LSJdWHsqiC$no5;^;Vj09fbft)SGK!hJ?t%bF$?*QleUs6Q(TwG%?KWy}N zjrd*EH3g0sq}2|e2-I5)e@yFGnx`o5hP-d7W1+nLJ^*2AG5jyO_WF?Q5w8odXy>20 z9m1>%Q$U?y=0Tz?yk$LTQEM-!px8j_DvQ4y^oR9FwdlSJ6(A&LmXP3j8qaW7%jJlF#$9C8a7W zii?qtC=vlBg1cxZoJUZt^(n3ldjPKpD9fRSdqW2m)2^@FXuk0c&a>@c092ob$`_TV z@c0{Lud;xW#DhOYu`wIAC!F+l$P8=9Er%D~F|fQ_|CsC=msz`3(qG1MzyS@kqYid8 zb33Bcrd{p@p6`Xj^FRXa3{ka`WG#8x-*T5C69IH&yaq&}$ksvF&zdKyCo!MI zak}UuxX1VTZGGF3dh?I+x3_pbH#K6v(tg|jB;(R3<|rInvGJCNpjpJQM_R(Z zWeD~8^iB6H1r;s`TlW%blZMrKlEC28)u3M|eNGP;AIs&f6@}c-e$pZ;e}j{}`5=KR z9q8bWa|b~^EiyLr9jUH z?~S5he`uDA&(FQloC;-Jf;=9XtX9fbFFbT4dC})TXFPmK--w%he*INZ<0*8RFLsl} zn}s2q&WG24y`Aup2kKGsdy;Dj%aJO;)$~hzrSR6+}w`MkeQlGT(TpVZDj2+99K5p6b z)jgGJAAk4kLoi#3^G48qMoc$Flex#7{+uDMc>vSUxmSK7i3RoB^R^=bDv50>QJ^M%aXBm=t7 zZUV^Pk&o+0$vY+GS3JGnT_NhCK996S!cP8;@+_0B9P$#Bz6Pr8y!#e$3 zw~`KK#8TcA4z8GcZ_zreAwmg|^B!45B<9nrEH@4o61~Y#mfZ75R+9rRQt{sjOcs2f zlGz8t=D?vl@Uv=U_W5XN0ON=1p)sbOI;48qayrYE>4!ZV5`9Y262vJ;a1V=Z4QsnR*Nd|@W}d{?o4+4 zQlv7#Z3jFZJOE-<)>`_7pVZ7apku>Xd0+~bh{M@mX3`W~V!*Q^5?_wfP! ztKuhN_<+AO`CaGudMCtRnQgbZycgo5e_B)-R*G^ewzwtwQ&44KMi1!8_>^ROSD{1x zHkmhMwGzIysuAGdhWz11NIRu{g+FQds%$o$WY>&7+18GNaDX)Df_MX(#sB_n)Vo_^6Kkj~_Obid?*E@}K-4J5%@G&|O5FWvEJI{{UxkSLEv%ZqU=V!oAD3eCY6&vWXy&kfd8O)7V+HvrVCr!K{cz$u zK~4)zv5AgfZp?G0v%7w{DoiGT#UvMCjEvYX88--gsCqY+Oai<)^|NA%*VSaB!|;}A zAW#@9+#Q7rkiX1~98bs?LBub_N*?rEg!QbI@C$P&k-ov%l}L?dSyX#5X&e_rjk~g^ zlf)J*zA&Tmvp)fYEMu_^NX4(1w4>T%-empIEJZS85lGMc;E9UH@WE%Zg2B;FEzvhj z)l_!&6q=ZlsyT``dq?&S{U19%p}3W?JXXIA)mR&Fls@*c7MI+>IGS9;&uY@^SSw({ znnUor%5Ofv5^WQjz~QeMw^p=xQnrNC2^Zh-|11E#HLnT%rLGqonZ8T*UYpOh zYMgeDS{GpCB&A?fl}6q4vKS?NlF<#OA>l=KDw-Y}@91g>P=S1aWYeg6DoO2gykyMj zCxad}K!%rU!n3lASEuOJ@gjE6*5!2aOTyPcR56Q+*33@ilgm{!3+}AOrLNTi`AN-d zd>{E#4aw zze>fGM0K|Pc&yQ+VL+YT_Je zaH9w@ZH`(db}*UAC}fF}_(jKpL?Yuuv*1dH<3$;jeUmCTyq4U8&M@RU>NnGb!PEXh z_W#ipN%tq&0fG{BkzV^?vigOE^M(4w1}De)(ZczR)hjZ8=qjB3KQ2<-?H(c0mJg`& z;&15DApON@_Qk#xBXu_T#O`7n69xdubk>W6S`=euLWleOD-3L!n(D`%{tt9==P0~I zEq__0n?_M<^QV=FwDO^ZKGR=nVv?E5<~7~C75N-#(t*kIDsNr$RWr()D7(TnzaL;)FbV@ zQfC4QcX5;@1kL>8RXVM>?}Np*v*~HDVf?|w+@|v$w0FH_AG~ZM_@d`=7ChFRv{o9= z>vLZ3meLHC~)Iab@s47u?_EdqvAxbFR%21=qgR>*il_O3*jx(94PjL!>+o zDUy)%+Rp~R7XIwESY?MoOYfTcrJZ0bV+v{WMW#2Q4^8j_L#{CtK8gf3G6k(7%fEIJ zZuFKIY3#Fhix2X{x0U)>IQ$mA_XO1Zp8qC%k9_kw$0&ehQF1765Hrodn@GkypwsJy z9CI7shW{<&v*m(8wEnGQ*NcApujfMP`jiuV5npki{Yq=cHJ3}}z5hvuY^(tSy^b^q zUfy-+&_i-};vhT7|6ykv4=32zUo5*sd%<1B7de-Hruxj93QRz33%B6haBejVOU5|Z{G10`F7+g` zNhts9$HHa>S^c=+;|Agne?F^5F42K@|5yjIhoOF}RNB}((ZJh6@XxisJQAYkzZjDU zM9qv`w2%g**+Z7~5;&9&0J5bI)iQXpgR%HUqg|O(e52JYVzmG%IA}K#(zivq=;b*Z zrM-WOekaxK2VPZ$nc}{y!#1~>Ia`>Uia;Wd)Dl;+%tbj4$q~{mP(9U_Ss$ii9Aj2n1vX|mRnmV zi!vP<<)N{v$3odd)rs9#x>E;Ud)4Goe;iX}F?KyQd2F$SciYx6MIscId1g+FgNF~k z6YV|1H*D8ao_w6YNkh-;8J)sBNQ(bR}iE=MO?J`<7muyjs%$fkehc z+*ze@{iQd3g*QtFYP(ef6zr`y5==O^hB|8vKEpVbl3WfdSH08*;@WV_^mAdUUli~C z1iqVJbdp{+2(^6hYG}yMQv9oY9c(Y=}KM*4n4$v`-DV#cK5v|F=FT!>I~# zsLMQr{$a%MU~y%k{l;}>;kOs#N8{&rX%fZ3Y}8Yc3HQn?UCrLTb5Ng)C{&vLb8XNz ze%QYey|CMdG?DL!ELs^(ah|($ccwI`{?bs*Tf3#{b~nR_U@NFq!9K z1rNDMxUfPMdfXSz8wn=PWdqdR-T|X}7zPzdi{Z;<;SE*=R;wY#K|b_|;Oh#a+*4Zn ze&?u#w16Xni%m1d)9u0YZRYD`qvdG-MKbWb4J>ntq?|gsuCFF3MqNYTf^ivuoho`qi`@}XI1QPr$lp%I(+%YoL0a- z?5bG{-Z-S7zKe$ZDU-B0s>ocqZ*BePPCM7`8!2-AX1K?{iDza__0zBas`aJaa^uR; zNF!1jB^T+aPqc8P5>#*YEf?=!1~L4JYDCEzUd^l~o|eHCO~c@~18oipqX{*;)QG?Y^^T8^sBy@x(O5+Xyk20(P-SUESL>UkZ*Su$f&< zEBIJ!yau+ABiVq1p`(w;oyfV`IrqA)i40r2&kZ;2Y#v=rCw!LgUCaCih2Tk;P|YqH z8R$mW8UNml=QX{oalB(LCORg|gWXi9od(#@`yswpg$%kzo*FF;>A<{w7lI(XVDwC| zR__sqaG16bR+`G!{?3fn=Eu)@5vKwtp-aQb2&nK96J(V^pn)Amq^C7I_q?4dsWCpd zy@u*?F7n6YU+(_ket*#Q+RDC%aj=c?TS6R>_9<;Sd+iuO;;dX}dhOi# z2xb5tN^rl}aZ5!jE_{zZInd%2rq?Es^qMt7B^A5%vcfp+LAc2*{rjU;b3M%knw(TE+h71=C=mNK!IU{`b$le-X%%c2$ z9?f)qL`fwm&lXCE$Y`w0SUl=aJ6hGBeJ01o<@hZAb|1Y;R0}v!&U#q0*4Sdt)5^MD z)@6MnmY;TZr3fH@S%DVMTIT^_GlHY?gQ@5em|E6nhde&LzsdQsk<%vPyc0Q;)Aih6 z4Pv~HgSB#4*2Mqw(}n%bklwRg&o`k&tKSXg&XNX_ z<)RbJU9lFu9%fxcdB>shKMlbQO0DSO@WD)m3u7c->(&r*%XVEz(OFJ7Oz>Zy(|Gvt z(0;v~>ui$v~H9}66K)jWu~H=d{R$+x;uOl+UMi^hhYtOafSdlN;MxJv=Ezd z(CdUlLc94P#a+9gc-o9064yj5;bLS$5+pQxx8H)D@Rlzd$Rw9ZW(vVD(T8riot4QB zt_3)lwg>w;QqHk|`H5)~Hm`@mHr{+<{9x+;{_JPO;yCVv?H@ENRU#)MOZyiC1VY_> zED@v2VXrWo<-J+laNnuvD`2LrlH*BoK~jzOZNaSEXxPxt#C{gMmn&6vPq}gh^}{Mm z(x59V9Nf&MzvtJai0iPuv%Dq8eaF04IDN;Nc)C>Dv^(Zcw?Hbes?v)6#PJDY!w-TM z7+$ArnP_^q0e(@pz!~|G9=n`OiAJ_<=3nIxp{9y>x!7p^1EvQ1He{H5xa4Aa2c?&y zXhYaGB?>w2tdV^+_3sD#>dy?7E$%A9%Hpa*a2`L*n41Gqq!PksHu7xCWvcyTO&Wn^ zRowO&cY*-5Ty2fWopz&gG8vzo1?aP_7dPI@vK+j3GqU>>#PghjhH$hI9Wt=_1*{Wz zDEPU#{CRvD^ij*f(6$fuXJ4a1;mB%13QulA(Q*pq?noPJ@@O+xj%;}?h_6!+Qs&ys zD>o3Iu08hN6~DLJqamF%U=Xx182=~DI!Z`pwfwAiU3>y|R5fq<4`-S^&cdZ!%SC*x z;BMclg3@cU*Oz{F%2>1dcmZFJeWd^Zxws^v*5u4?5H?3Oh1U+@P@j`R0RiXR2x*!O z`M-I#d|hgGW{e$yAjDE(tO^^uQpa1wfKdy+^PVj?z9;d*kXCzX7Z9`xZ)#jA6~fXg zJ}@v{f#=vxKOJ#JaKQr&hw|wSZ`s##uMx@xiR%KHSO4ZvjHqTS?(UzOpVq9s?Mh1g zid5Oswm7OR=AZr`Wh*^}3qI^62`dp!F*FHEeszjwp#l3Q(j4(W5rJh>f{<+t!P z%b%z%yOkm+fJNB&3B+7PHOpU&3)SyFyQrJn-P>tXtZU=|y6{-vk7xMEe3j|iwQl!& zcOJ^#dG<9>^=|uJ-ca?BOV{q`eZF?*ndMjJJ0>scR<3AVZ;Q{G^iY$ZoZErT?K>~v z>~_wAQ6a=Y)Qp?ow8rj0iPvUHbE$sWd#CYV4m;D;M(>ao?kwuDW`R+tV;5Ex>C0u+ z6&p##Z_Qs1Jigq)L?K^AR7hYOe~3S7FrqjALLha8UN?K0`3F{dejjDrj>@pfG~AFf z!=xCn4rnB!{q6j82s|^!344nW7p|9jB`K!-lS^WmbU=s)+xty5*hGwz>kQabC?RAM z5JF*!{MRxDB}Iady66{DkzS$dzT-{%nk_5t%K`52BU{=rbsy84>%QeV{YPizp-WqAKI<|4NW9vpAJ32cRd80JGHDit$j7$-zpQYk!?-A z7@RWPx1wYsquh=Q-Q-TI5l3ixT;Re<&Chl8`klJxSJorb<6e04QTt?NM4)Kb>Tyru z`@>(!zSc|W^htqgtSvEujZB#(mOA~|TN&!IO@S>8IvkV9)K%k>5IPAtVsc3$Q>Z3P zZT5Rle372C-FHfLY;wFu4Eo@#7M3nsc2-X;y_DIE7kto)QMEP?16>%`(6$z4rv=JSv^mm9`vr}aOqA5hcN{k8-WJvlmH~Mj z5H)-0m(ap@7TgTip#1VeX2jC?H@7UYZkTdU{#7NP^4+bM>rUUo4I;KTKjP#VI$qtc zC%jzqnYpZE>`yfsVMQld^D{R=`I-qnT#rfIFd=CEyT<qBA zHf*}%Tx9q8I&UT(i8iQTQ~^j;NgeO14`>7-&|{RoBw0#yuaD} z|Nq}sOVw(t_G+uB+I!PBEmgbPs+CYP_7((HMb)lVyK1&n)E*HdwSw5x3K2ofh!y*j z*ZZ9BIp1IM2V5uD^E|J|<9@&0Of5bZc(ZXpZ_r1TcaPDu&Lv?Io?(0(%Uk6ohn*@m5Qu!& zg1LF?W_&%5+u)Nap81cij%`s=mtq#O^JKdc*jdqDR_5-TlXNPPRF`&;S=WM>ili9k z!1El>#7ClR<|O{>hOlONF?$Y8ntOkpO=v*zN<5+`NVdN)2kgvKws*J% zLnvcoyQThJJ^$fn^!_bJ+@;$kyoX+^%pqPOEhekUtT8ycHEqS=>G4){@gtx>j|`>R)4Il7}v z{6P7q%YK!Agq(qOY4Gt+p%Nz9yjC^ugZh(Kua2Q^!#S(oYfIy6-=rocYx+G7U02^F z5DPULXaA{PThYo&Gzjjs5v_|^;yVow^&nRt1rFDDhwhk!;IS3ZwByMB^$?Nf(45Iy z=*t;5_F&kY1RuGLhOu?!@HBT)w~p!~Wv9>@3a_?D;LQ;3+UW3;|wH zS*`p*63k|NF=L?E&YCAZi$sdF+NDJ5KS(j*kBk1j9;{ARPnR)d?lQRbZ2|Yi_&N-p z*FPnp&R_}7NiMvA70p!{@(g``>#-)C9iwuznrTb zm-)3IW7QGV;a|gI%kqo8980-<*)Q7<4J5PrGPk;aUfh(<@Rq)^vadqK{~<}771

(R%86-bw&38V&-PN;UrOvZc1R?Fj5g{PM{MJr5nN5pLjJ>D#{j8iKi6lEE z0tB)Q0r$nK9b-<-(7E$zLZS@jM_+%d4%DZ*OY8C`53LC|EQjsNmT=p7nA|X*UNWLq zUhUp_gZ>+|=q9}crLhuh3OnQ-g!XNS^TB^k?)=29fFJ~q`D6*+ ztwCo>FZ!DZ3F-nK`12n}+6^ua7O$Bj>(y;Z1GZua3 zA(rWy9{UmbTB;D&!pfeIU<*V7O?DD zBkt*#t_6(g8;j{Y*{FD-bmNLLq^-+9vQb_`1fh?|Gsf z8>Mg~e}GZEBs1IMls-xVZx3qg4F+o6gPmx5+(P ziZF6%R?YLk@uQx^Tk7ro=&ZIS`y}kkA2dSCvd7*q^OHcdn9}4{6J>6mG0M zRuz_z#v1>6cfZ4x`N0x)Z}wuzv3G2hn-i~;o$tu_dVgH23VscKwUvt*sk-5L?eV`m zH4h8~H{G#%e*hJqu=e@A5!}(YqxgxeRS1Lz; z*!-Ol_p`BK!`*>-DEWY$8=;t2ggBYoR=3CtJo&x6Cx-rnz32-)lEA4gSsVVLicDIj zgu8LG>^dw4uv!b+1%HQ3v?ep4mj8)Hb$rEjvIO;~49tMb|&^di(sblXaw z#pu{QbF%AH?Ob;{j{Z|S`IU_s+N4Kx=F!rWjJ_4O$UZGHF(b^SU#4axsPg{xEa^3Y zTGu!H#f?|+F>_HT1}*Bj)G_mu@iQZZs*(!>!$CYz$ur1EwzK{c9>(=EZ)tkuj#O`Ag3gH@nx7 z3eV#aOG}TPndN+vXNC=#k2gaa#Z;2q5;hLtwU|$bI%e`^mc z7JuQaYC#CO!36|2&=YvCuh7Oc+1tL{bWP4bu0FMa|od7ZT9CVo207C21XLh2vy zE=_$({1bVLa}&Sw5=D;t$Z^asN=NUEQ6FZ}fQ~diP(R;@i5l#>SRGV{kcShX_CU|( zgUm9JTosB5y~N6cID$d;BO6g=_IOX;};QpYd@a@Ao_`jJJL=m)97+ zAlqI{NqBe8k=y9EMK*dK6817~ech_BpiDQu0CUwY90>RS70WRxB^u#E)!=crY>?*Q zJ3vN>oS}N$NfG=27kdL2Y2wgw>@#WU&qq*M(>LQqUQUqky;VJ`YNyfhK%Hm(DRooB zvUW3=M;9K*VUaHY2IIS*A6H&gmxQDophWA^kJDw{P{@8W`}-W1hptguQYqUBcwT3) zBnnCZ25e;XCC3W44T2Ci0Rs$Ef6Pp906W2RQ2@hUvU~(%Q1y_I#K_~(9>zJ(3a(#t zt~#N{mOIhJ!A_07MBcgA4ttudS0kN+oI_oByXsr?0)fUklSQ&r&&u^dXs&8FW#y>3 z9hYIUR{24k^s^j|GJj{$y5+~MruYbDHgwDV=Ag6XlBgK%)0!}BrH1t9T)$Y?tnT_9 zG@#3l&1LytZ(D1o%E-;ONz@Fio@YCtAS%e@EcFwDLpym`WZwY7o)VCFZlFQt3f3G* zn^+4u(RO{7oha_kAUA(b*|vpUEJ~a&?wR{bIB2*gov}8^x7vQ+;n++FJ;ha*b(ZPR zAGprTt5~hhID_5o2>YB)=l`RxTqH`^2jdh%a9G&IerpK%7wq`g4^^f?0gqo-M>GiP zAweqP;-Gq-9tKp-kajw?AD2Y@`X!7Ikrh~B>b~83BtgBMR=_;F=qpx{^8m`TikFIB z{XRh}_6}@0)(%5TNhyFQf96IQ1dw_M4UsCfbK1LX;!Ct=U#NIewT|x4`0r%>doeRY zM;!uGX2PgV#`E#OPgCReF!j1{4PqOW&2{Tj;!7j8`>6t|12fQ~YFSzJh~-ezHa@27 z=u6-qniKG769zdpX-}W+(fOkcuhW!n%BZ_~gFfH^Gwjj;ha~Gk5iDb= z)w>Uze&88c%s^YbJ-Cvl5_0IP`szi~P{~V6u_#f*P5uF@C<<(9fmqi=q@0R5(bfc7 zazj!9MR5LVDMfBi)5J_`=@%3v5=1CUXS31FrEVdA9TXCZ=dQjKX2a+n3q1ZBB@}5) zF|{SQ?f-~VEP2c$GLEhEr^u4@)*9eq)Md}NF;!EhpDLP0UVPqtkOD7PyxkFgum-RW zl3);9SW@uZN@t(mVz(gV`U&z)s&*O&_7+QuIg6-(W6e}gW97!x0th@Hr1O6NgWjuQ z&`s5zFv; zOvCz~k*h_CPC1J9M7Fu}iRFu2`PXNzr_QvgmJ*<&%(@-UoB2gC&53H8`BPa37HHl; z^(dDMV$@bbs{|<2OK>`iQVk*>A=5Djl%LsvO{^uQD%7xEmsL_x%xKK#vuWFnqK#W! zHro!~WZqoUeizJAw^ct`^ygmeP=_UlMG~}qG$%#rwSbQ$4PPd4#BaiLR}>HjClT?U zF|gBu>YA7JD#K{RaK3NJ7qXbUj)sVzCt&x~;@LrF1JQ47{T6?DEsSxG*PYE(W};AR z#t3N$pr*)W{}j8qa6yKXqe57c%0z*~;ucFv@UQh%MY18!Wj&l{pM^1~FSIu;C>0C6 z3S7)F9qT0Zyq?u&(FcJAw%il#Htr_JSQ*EQYH`kXn|~LN%uMgPWDXeE=K>6{gGk01 z*9PzmawU7$*a)uIrxKaw6qQTWr=tc#a(0yrqF7O?hb53I_4Yn9Niqw8&&W0oeFqO zr@i@FmoLqF8Y1E9j@*+6RM7CcNc$rs8|&e}KbHi%?0iWu_wj1S1K+v^|FViOMYa1b zq@?a8J$ZQ7*g+&NU(nSWan5PE`?xP%X@AZy)6>x~m-D6^tO_3p&WedmxmfqzG{-(! zAA&6?G70Y+t35kZLEuyv;ZY%L3@xp1xLZg9YAWCml29m#IDc^xn%DUC=qn&Jn0JOo zZck|%``+a{{2vsQmWSnNv5^7ME0bBiLnRt+SZSqQa3|&lf z&~}SIHHcurAly0QweXyV(}#DlS*M-x8s=$wec~vgfqDiqS;QpH8;4qY3BbY+{su{$ zAHexSkqk;vLW;g9i-1oB`rHP7=FpK&VLr;iB+(jl)G+c66M=tXw)4U6`k&|jK4AR+ z>Ddz#Gy)=K(=a2ZoHuOV+w}bu`j((hB0_`n>E^`0Hn$BY?XGGiSFNE6s^4vxNqwHG zeGh3?@I^m1Ij1y15GpT;oIj%6etWX|k*_m)7*nX>pFG#3_j@iG!xsfZB8pU^zbQ&G z>Ot?p-l_6Yy=0K{UlRWKN(D5UOSfK{$`#vP~H1Dunfk^COJd`?1 z!d*CU=_9Mbv}pgKuaR<8o$XyMyYKaoUrZ65^$jEMM{Gv~6Lwv7(aj#R(Ho;|$9E+H zz863a@gIy>O##Wi?D68(E zoK*umSwJ%pstfu>=^-Sno#23&6~hjFiAPo_%|VkJ_JM-yeDX??rKHrzEGtiLw2RLZ zsO8L%XUFWP$(z3}0;dkD0vJl~vt3`l_@`$F&x&LGT8Q;v{79jAR zo59Qpfbs!RKgF53!ebCkx4FGKe@F+XW|F$H?hj`%At9aNA{4P5Dv41RZWF;6xU z{YF&A?*VI!7On^E<232mDXQ8o!W_;DxWrmDdkJQ`OLL{|Z>ai?&6sI-1c5CX zz(at+djCN-mCr4c&yRnu9wldpjJ&b=5;D*Jc%`g$JhgB5H}}33T5x_iBE2BYZq0p| z<>NPHx&>26f@0t;3tKN)r*d+9uQ<9*XRFE}gO*TakgAdQXHbhv*+HI93WQLnJD2)i z7;7Rk#=S!=1YFRZe$F_z=Hc(Ob?OaHia-T$mY%FK1=8*cxm4TTPN zY;Zw9`iCC+=Y{TrMM`(qjRid1N~7P=H(5F+e$||5uK>IDTYj!#rUJe5TsSF&(@DYZ z5PIl4P}qf^CO|gbQSG(a@V@tr4zC7g=llw_1Q>@;>&*W?cQI%p%M8{OC??pFP=7#^-=a6iD3=WvZXR( z9&^FQAuqLdnpVE>ZA(a(F7=*;=QV1ahnZegD(EU4TGRy+Z5@*wJ1R@sAJA2#hp*$I zmVhJja^3*5wbx$s==yHRSp*j;V*tV&H@M=G`TB*Rq)*7O0JJtFhjx$1pFmM?_Uo#S z?M~juYHf}N5a!cU6_S`#JoM=JOk34f(PS?Be|O zsCb+yV;OIvao)nFP>EXq$bWL^KA0xGeZx>($#7Jc!1N+>Xo}C^6t#a`4~F91O}IH&OM zvDAB2nwgv~`V?L-P;rkq-V)t!u7l&1Kle5N zDL85A^*x&(DzorPu1wbotG9OK=5VzI=)3A{^6z84bN=icvFpe2Y!UYB_%i&`<#Eob z%O-=0$q#~+GPw<1=qn3MucuK+jtH48slU4Bx-AR$r!>#~Vx*uis*#d^=n}}C5JI}O zFTKiIg|h7MLR+`qx09r|cGrMv$m-*3+!eiY0?n$NqR+auVV;g#;VX^fhNDW=e+H3> zQ^RrHDb`oR-JgeQx3o8FJUGAo?~+*LGXYBWVIkJp@%h4YxHerJuI(chM{P2~uFtBf zWBEeufLUAUg!A2!N=U$?$#7x9vTxqN>0)%hOyuO>f%su_8}bVfoW1qA-SA|U@D$mudq}O4b<0aOVF_hiP}kSzW?eqOGZhG>yHFO<0qEZV$s zo^kaYL1eo7=ny4RBKqAVqkmoXav7R?x1vf!{~nCH zISR;#rr8R;3rm~}{gq!Vz4p<^AUw_LspHP%p!Rgqo{Qh@xtj&C2G1#EDxU6m4g>lU zMwxKp>;4w1?;_O`f0P3r(s0x1$+jsO4qJEN#aN`h{@hH=O9rVWX-r$j%uFzFghgqY zSyM{Gw$+?%H3L0#;+UtCpRzpvwhbx{0oqfIj_YMpfS%k(BHp&FbL?k*=z9i6IoE7O z;Mz*Kgy&yQee|<~_G%fi){-M7aQ5lt^0YRk!S2bqLKAtEcyL9LXPk(Or-{8)9a!i1 zhgJ;K!2W}^t00EtQQT5wqU3?N#i%x?*VEIP2SL2F|w) z=48`wqc#}d`OVje$ueQ|eXn+IiijHRb%kHY8TtR9R88@E|Nh)GAm8kE zMJ8<*mxuKvT-y|_xsq@&x{BzbR5V7Z$5VWJ4ICx?ymv*A;-kE<5(2&J@wMPs8fiak zOfuE(xGVdO3UTUix6aTd*KwX3`R?@3IF(#~nA3?F7k?Y78lQQ_a87$tJ)#0zT5~9H z#$m(#d?ooK;8CoHD09NKx)k+0daZ~737&GxtH86JM=NZUgbS;JY(9tUi68y)ZMJ`& zw7rNJ-#Ep?TmOY(Tiasmp_N)6dTfRzNAt&)~0y~TBtX$-kW+m)E9 zdUbf2-3R_sZqtM15z_1nr?r9FioM_a2f>bS7Z6vLqP;%9tu@D_$)}RXLVY(&Rg8x| z4&tkH?8i0m!2Bm!@LWq!@UQ$X#no{MZ#%EH)+o)@{BG3rBp2sFWTx82D~(T&U&I*a zAyokHGQwk%@2bhhTbWGx`ZFPCRjo|p9OVuYaW|Tl`qa#TVXRxL5qmbR$%^pW!Rn89 zx4CxL=Jk@0=2cWWDnR10$?{VB;Fz}?8<4prjUg@e1A@1H)l*mF$>Z)l8Y0*&$@vq3bcumtRZp6f=Jkv@&Ex z%@TDz3p6aIiU5|N&pTVmY&bR9;$}*alEREofFc$8-S)+RyLEi$SiW4C8izyekp@ZY zya)SVN1JIoU@++aUx@2Gs}g;!YvKF7uh7TTXVs!p4hWdE=KK`lN)|L{g(awxh%Qqa zo5npJt9#3Bqx3G-5Bp1EN_Gu0Y5M_F?;Y>CymA^|jt=o3W$#G=|M*ocl}M+fV8$tg zNInoNS4_qkbYJ@6T|J&%fA>wimy(a)Qwz^%<8$4+Zxy}T(xoAUh|5C1t3H-URt)!r z3p0|^C^9Zh-h`$7av}a?I`nYwlmxYud9*`&CF4yZlWU@&`%d)A_`s;tSYkcx2O(5F zeE$F`77%Cz(6b&_%T$D*s!!Bf{8nP~1sgO@$Tl)}=QF78xeo?)xd-Uve!pgbA8GoK zV9a<_BkEan`GVW@!xX9z9*x6_tN`7?!IsN7bzq5UTj+f-Apb^FeDsQ@So1Tt z=zLA(!8dF}i)JBJA~{qkd|oLuu~nb8+Uqwa=2dAK)GP3J<~wHSY}o&Nc2beQ>x~j; za9o_*wfI7rQsf$N@s~OL;F7sFfG#V+>AASYPh#A93+eSxZ`r0#h?1Y*JK8qrWM1YI zW0glcNnzOmdLA|BJAHYAG@h&CEfLSFW#eOiWo@YtinPbTw6*Twn2=2NNE|-{YN2eG zXt6W_)ye+pIQu1NF_RbW*jcacITg3}GPXB>LF^c7xVA?ADAL6HaoA<6W!|XTu$gE` zPE$xGrA%JydroNNfIo>H*Z-7isdT3vdeZsKlci45V?1~@nG!5#zlb@c7|l{?a#8n+ zC3xLh54@x1lT7l?>knJkiOsEhxdmv~bz47`tJ-~0uUg*n)hRnct(JDzX4ze?tc<_F zT>_oChWPfZnzc-c&#so%iT^$_n`avj{&uHz^+jWg;%iJ&))`~p3HR4)T4yE(9XD43|)@H;QrSK3Dm>MvYGW_*^hoEr$o(ru+E2(ig zvDT!oPTnZ%7Z+qvgBBWMSIc`OYmHQ-(v`_XD$r?edLNcYYDw$5n+Tw^&TS@dD!-H1 z#4QLV?SCVg!AbQMgpbl|H)c+BI@%0)9$;nvElwvjj)`397+CQYwYFvQHkym?XT@~0 zv#AAZH=C;=KN>t7)F;F;palbt>~`DB>|ZLkUC)??;_Drnz-? z#g~cy3g~zl;eHMMsp$!B>|C3Pi2VsTD(mQXCk*lYBzNc0HDTv@7|nRi8%PxT&Tx}t z-lfn&X2a|`Fh8Ga;sCov+OgSPQcP&i(Ri(Ez5@q8e|k^J*$fKUE+i^u!_5mAcz-Da z8rBBlqn3L6%R36}OtY37UVq%gHy=+nk*=>yK9W06QBWmJ&P)(v-bN;Dl^$)io~qHD z=WIi@c*pP-`M!)hoH0;9n}Zu)_+hvD!Jlw%EBIDnXgg9NcvK3YYv;!$KS}1(Zh$=D!2fkE&eQ)xB@x9H_qw^@I{BOGb8PiwfXb54t>#LSf%(&fXQQEzxb zoC}x2(>m^e@Y9e(D=|O5SSiBJhG4^oE(lF2Fx0Z{x`WBb_BcRPH1#X&HzE0qOO;mU zpT7ydTR<;$KShp~EmW#>uLD(;c4pJW4~v|+wx=n0YXXF{-Oshf6M$NfwEmmOqYhDA z&=L{SI4XrTjTmP1O$N@4JXZhBH`zinDvd4C@%ZJizge3Uw5_J3`>t^yp<>ZTucQb4 zY>iNo$DtZ)vnpl%>~MeG*`^}Z1Q_mvs`GT0Dz$Vfm1^VcVRzD8Np?USr_5QR7KX!0 zMueZ?($L!dOq@$ekq+1)PL8(~GK4VxkXQy`=DF-DlmcecYKqf|eu7+9j!myWr29=^ zd%7)?#D>h7?9lxem6icn;m%vlo!o@#^@sJ5aD4Qq9+{sSSJdLNgodQXR)yNKWLH6M zX8!+rP0l=8QmL9=Iv_h1&ADmZP+2N?39mIY175zh#uNN*It@zluBfkMCI}H^E(7`F zLD{sJQ$C^YaEV*FtXVxy=6f%Ke}>oFKXtb@G5Zp#k>sjsmK0N=znUeldq90lMQD3P zo$|g;3uVxYrvaYdTPOZO4x2Z0VQZ6ULwCZ2m|AaMcwekjq@PgI4xE*eBJYrM|B}Dl zfi*a<@aH{mOP2s$xj!0_AkbQ+kNfRwbX3Zg%lqpv;9+9yT51J)J^l%GtDm&yMcXft z24I>35WZI@6S&-T=o9ZBI-bSmzVZ%aI$H^ae*&2|TLe*+2YRS z-6$D;@Jeqi^UZSKpttA3;j`4@{?mGEra_}2tgQ>XO?}J;g&;b(Nm>n8Gq~TOIA_Gw zD8>bToa#CTa$Fa zlUfhu#<0aEtt@F@z1+p)n@9im_l_9V>i{X3q(T-Adj^Q?h&10#?BX8Nx|YK9_Q+v> z9c2;2-Z3QKDfs$)#9YvAHRXmb)Z(*gzYg78dQA-f`?j)hp&hM^rI2&hu?XczGLLLu z!hIa8RiOO}$z1?2kfuO_jc)%EVLCbg?`jp*dO^XSV z0U{T7V9sZXNGmh%oRG)MKad`Jl+H(nk-xy$Te;IcNYCZrBNECpQf0QGOZwNhIx5&|Zsqy0YE7Q)3Yto}~2 zNGQTT)Uxw4r$J+u{pzT_5%AZ%PhnbQ&f(-FLUP9SaYGwVsP|fXM_Q{q{853dFlcJk z$+BI7x8HP6JUK4AAo+RC@BG;y%x>HsC#9&^*il^B}X zQ*QR1kgK>IB3HdqMW6kc*{sB}kSwusHbt|paY11z^#TEP|x75zD? z!)8?G2l!PyDBqm|#atU#q$|u&lZg3sN1jAcns+OtBgQ_W<2h@-M~C~dex~iEL-<*c zzlp7eQLH36u~~c`K^Q@INXdzBkWzLUtkUE*=8$3>KH&{LAZmo-hmi)Si~LHj$q{gB z$T+sef6j+IA9~2fb51l_qVxLKK8pUs^e_)9-aYetipXK$SpC_|?t1Z=K=^{lu!Hjc zd!NqBGt*@hC^}=G@tMHb@+vXS&(3SmOi#~L*x(L;c0julLmKvv6^jtZKEI?>72-5)9)gk|cQWtC z-%l@e$N!SBDV(Gk=CWx%?{Dx)Q(0ta6Yy%#Ew1)yF%^&UUz67$FAyL5*TY4HV^qaQ zs2Zo;9c_9|)Vwj>$OKi@$kc;*UQVeit>66QHzhtveRbl4p19y^`RdJUUG+;1mSzNN z#}6z%K` zrm);x^|OQ6likPCMDwG!_9*zs!MMDvU0=_(#m=Lc+4<}KjekBkuDtpEX)NqAEEto0 z!oum^Z{1O{S^DHW7fAk_BoY-K@R`_EDXnblF_tScf_$*BXa#~;FzP9j z1q#D>qsWBjb!L`(C{qGe3?G!3uf$*2e4kse+=j#}E7h~&dncLnyDYm2B7AW|8oJLg zudG0b5Yr2S^YpY6HhNx0IX>p+!o1g`neA;kk}nGsG70% z{bWj4@uffBtZ8^cnRSx%vKmURlC1ycLmk^bdD;2!@A0`8wGs1g)J?cF5eOA)Ry>sb zAf{_K5fpIXc@ngTGzG*}f7Vx7Fhdl$*{8GNVxeM`Kf=U2d6i_+amE}qq@uqqKOsF2 zRChf&kM^H*Orjg{(01H5F1}}-MKvOme;CdN@ zvjcCvsgL4;ME82gj`a)*)!%*yV*Y7$-r=bIz05>_buGkMsZF-2&8W zi6||^72V>OP8@9PJhg;Dt;1M@>H@(-n^@h@64ekt&gX+c;#xRuOn@Y7KyZhIOVH+h zc%Z>&_QIs?0x*uE|Rlru;3wqt14%6UukPpFiN@5R88zzTTsXh)h~cDha^m zoakkr2utMe5RUd(=;e;tH;*?tWZ0d}6ol=3{79eaEiE4-+gI&pMVnXbYS!zEO4_EM+_?yj>cTw2c{HUmmYIO=@kbD(gqy4Q4CIl$zrRo_=Pz z?^+gR47?QC`6)>^*3lDdLnpMhuWa|-Xx=5BvX7$DAW}tzo>I^+SohPoR!=f!`wSEC z;muq?3;r~4SE~FpIh173#r`zc2lJ%mkdhMeJeP=vxv;;@Hr=Iw5&UEIw${)0ThAwH zFo7M)xU=oh3+#I9`MLueJ-f6i<`X2)Z}gwhXp|!{YlU{8WWZTvyE-e

TLGX{J#n zy$%21zfGf$@)H-W(tG~-LIV#v)LNr{d-zt4;Kg*=IynpD+wO`ETp6;hVSbhT3M}|A z_r6)7Q(I>VeGQ8{_({5A&Ijk5E9)C|-tM`i*QyIjblOp@8l+X6schH7uVQO`qib2l z=W;ScoNMks+eDZMChd2%k>Algsyv_#RT7SSRPCzu27b~sG&S|Kl>c?4s^#~lmA1WJ z`iv&(?lP(zNzPuF*Uh(Rv7kh}mO2wXU3Z@$(RTVQS?XJolxff+#2KCXLu>a<>|Ka}FIXz@O)ORJoo!29 z-Cbeh0dA%?Q1_WA99JAae{J5@3f)A;g*yc2HrpwbZA@4?yU`v;3dU_a$0fErlo- zggQK5&RTPPNKTPML@MYcbK-@%=XiC?7R3vfEH%=7DXYo-!mfPkz((xE%X(+4`(Gbk zy8t--#8E6bh+Ivq6aVDvu=)CtXv2ZZc#Z-7&C*3`1dK+@Ti&Yc8y#EKsQ+jJn>&6z zCI*<`a2L<+1MJEE%Bz+$lwP>XV)=@~)X1t18bvCS*m}oH`{jx>`g1aC3bGna5y(-pU_O0u|i3W>rIMb>id_x8dcf;2w;}P2@i0!sP zk#pEJ0^6m7|G}Zi=i3+O;U;MnV^ab+5ksI>;5*8A=nA zA)AwEC543pw6n>n!TFK_`bhDAoX{=>+}Efdz^vmY*h$k4J>b+Yr>@&SBvd@?_tlX@ zS52%dB?ILgr|nRPESJGLmxyfqa5|A4RyoW*&2HC6oW*m}Sun6L#=MH;#9W>D^mY3I z{_hK~s?Xd@N5a9VB&|llPDc}Q5OjdwMV(;Px4zI5>_4Um_AQWXaWzcJTp+&*;;pOQ zYroVLghkDF11Ld52f>)$gIr3N5*r_(fuLvPjoIY{S%BerTOc$~w<2l>sB>X%hedH2f{UCn@#S?bJ zIAEw`q;Ag07!cPP(ObDm*cIOH=_`w^7*>KQOXbccO1yjKrvUUHU}rUpm)1ebyK#Y( z%4iUgoHdOKy$6}>RMVzSvoF|UFC=+;L&*ikd?lIhH`dCw9dgXdch!fj~Ir&Ga7=p>Kn7#TyY6LZJ{<&Fe zK?|4$%9h#!<6gpJow7ItesDcHu0a81s2YD<1McgplfB%v7;>h!u8ZjH{Wd)~mRC+i z@zc2;5#sW@#QU4QZwBWP*#>_^(fQ>a@od7m-9>^^0St0N$4#+fkXu@QLCOg+?S&`C z#Z>P5?m~`x=Lev|6o6_Dlw#NSiR-8}fMhIr0qL$;QqEyrrpWaN)L)h;W1;*q5DImH-HoBKT ze-i0LwJpgN9l}>AoizG_mpRpLko}(;Rgp8fM#hTybB2B=K?Bk4UGco$TKg`Ta@ToE zMAA6^h!e(>+w4ti5q%ZSAXk>6oY*wpp!+al(HCVo1ZlxXh<1r`a>(!HDo^X*_RV$y z3M9ow?+U~L3aZSD6P!8wpy+PD}3#XIJPWA0SWfhbA|{=MyQE=!j**LlaQh3t7l3UmnG> zKCB2Ppbs0o-LOwY_+tY5^)anek({;r#pORft*$7Ab>2N*9>=iH*07z?&;3xaBHRY? zj4`f0R4W9*5io1m++=TGJt!kW=1PiQ-bCFSvg`G7x@nnx`NzA@G&l|o%7omTGKB>- zRQBgseZABo#A#$^E@N3%w@UvMENnr#E(dF_zhjNh&QbhPub5mvGNWr%5+=$7>3PI6 zI<1he6wLfrW%58(^YW&w-rT8Lsjrb76~s-42&4CvSKsC# zl6g+UsBkX#Y7*T)7Ubf+wt`(2WuzvCz&2fR90{;ibsBU;> zm!L~1Iflw#8(He8AUXVdf1JHLxnn&#P5sw3N0s!E3Ymv*L%FN^p5J$`ushs@ z+TK;Zdx2X#OUMZ zT^tbhj1vLf9XW%%j-NINTnhx%U!9T!tbRf+GEG)cwI|I!hUj zae@$Ukr>rL=e=@Dayf{|dN^tCyqT?$B)zs(WEJTy@(r} zi+IB{6fKnBASQ10 zUMAOw&8O-4T@S8=C>M*@d-++yNsD0OZ`ZpD-c0q`s`vvkr+gZ6wsSL=Vialx7~B)Lt(%-w=I$+yBkpo~)KnVHBg=@u(O-b5`Ev z*;R0=K>h>Y%2ebRw@+2i>r-kMsug`T2fUSZ|HX4si%K`BM4Ci$9uXxq!)z@cS}bjh ztN)^qym;w!scRY&K&)*#7S_Ryx}ch&X7EUWil$u5H?ZMhXbdL(uvH><$pWeSjW=AvI^v2?~Yu4jD?fs?;HwV^VNlhzq!z<33 z>gtKjHDazWH3rK{>hxTVW&nKTcxS(9NpXku)G&W=`1P3edrfX^fB{@o_XuooOAC-B6#+(D+-8 zjvAvi7`8_(?f}pvShQ1cye7 z=kgDteC|(><#zrtg}28XFzaEWyRX*gO1pagYwjJw zOMla;?`1nuQRZ7Y9yAlnmn9f-sNebM$Vk=Q#CPrp>e9;z_Rgkhk+2lZ!V$PpOiOio zVfC3sHq^HS>w3OO6>e`3zTrZ4@q_kT2Xf5bFmJq(IvK4z)lQ|ay3IL1Q#DLgQT2Z` zorPPI@B6=16vPoKN{0v%(%qmUAUPDJQ@T3_14K%sM7lvFlo%yBa`a#{qc*y08#Vg7 z_vd%~{(&9avFEs+>%LyseV#7^aWs*&DV$flXTRJXORD~TFaWzd?UV!1{I6avr0@aP zVg>wGAGr$OO?9Ml_4r9i7HJA9L{4gZdZSg^et62iYQ=PVT9!4+J_l?@vsq7cG(S`tsU!jnmWsY>}+m%j?r08{;ff7f>vi4DnbBkEh}v z4~XcP0D5!c33PvDihS$EwV{9Efw_GW%qKM0)^0&&>`I z%N&1q;FSD|8k$jF9cC}tm0urZ{f;-+$e)4Lj*i3fbdq+%Yif|%RKvCr$s_Xhng{oQblj^KPdbK^v zR-Ws6w`hGU=5sZTcbsF7Y#{>L?oqEC-}W*J-r$x`SB>=a;>Gmvv3?jC*s+c9Jrg%k~fMw0zMN}RvGDiP2c3n5ev^U|JvODUC?oozcQ2Zj+1mM!_* zL7Pum6q@yJl~*QCJ7U=|)^U2YkHhHpI-}2jhzX?e@hPeX+4R1@@Au5}ZNy7Y8c%*o zC0g#Ip=8g)X9X^69$TqYsw%YEYA{;6qCa%;M1oC8-;#CTkJD6mbvo_}4LcZ(qm83! zTvq6`WL8%1=D>%O_K^upO_CAxN=>0R*j|xhIGs|=pkD7q)0U>tL~YC1 zdxI?$EmJbrOY%T<`n2sZ7rtTSw{kUmB4AE88e;DQ{7@q3**O`ik_UCZc~4#{4k%fyYvf;QhDh*raNuW z{P>OUB#iZ`5K^xB*7I74iT2yJJ8w*n-0%@Pj0Cr$Yy*U`-DOA9pfDfwau`>O$>>ix zozYYiHaN_f3zTXfsoc+-TN1$fz>NF&GXbsmWYSJ@EX+RW+qcHsyJ&44v|4dBPn%rJ zJ~o^mmqq%)%`i!>Rb&E>gJlc7iV<=Mq{$&ms)0nSV}6M+^QHsTQ>#&WKFLqBR^K6& z+3p+~d+ne3MU(c>?;))+##{NGB!?Ee%++&!thf8?)Xw88G+~t>OogOk`WaU=&>eXA z3qVk zKt|mi-iq3eS3@_|;}%kP%@kHxhiR;lIoSaZxr?LS8YMTs`!3^%5X(1qzh|hwKXZvC zyz1=S0Fl z_ZUwVH@Xg_e@}OnWGK19Xatutq$ZTRRm zKYRkq8R3X~PPn**Fy~f$tDs37HeLp97|no1$+#jdl?HIc#n_qN8PBnU;1hyn{Xar9!CHa%%UE z@C*rob3rHCk*u{v09TbtA{R&DsnkXSeAgq~*>mvxh`W9^c@%-mk{jWJ`BijTqlW0k zh0b3fIw(!(J<#`+4&1P<@U=0=9(7S}tOk>8vBou`?o`-!f7^Ip-;7#8>Egx=isUC+ugtAQj`eV0RqZ9oW|_ab}7(pAX)`!7qZaeCSc~l zTJLXNP%qjfK<#oh?r-~HwV(&VJ64XID6#ghrBmWL{9y6TKcd$JAjLfn`73Cmc?sU_}Id_AdgBZ1Q zI~&pP9X^L9+KwiSMRBa@Q72~;x|BcBtKnu)rNkQBmm+8XNQo7q-&tUtU{iZ_6(d+2 z)Z+(AnSg?6D3sSaa$33wi(C$ti^y=!p7?g2BBitWfS}klDNwzF^&*#Ip)cV*Z4M2~ zObx5P0kgk9qH5zmP(uV-#IFA8-EAn0H>O5x(iW&MI+#Cj2N=6O4O$-AqjaKfN;P_- z@`!{YLhntf2QU4H^RFV3h8tdX0tEx4mC&{BupGcFdXa5Z_#c>Pg+G7ts6$0sf4NBv-N<%H@yYW}9I63>Ajrw&g{0^2S*-&7|3 zm5|~N7@o_rP9|gZwW8ivN$Ja|;tSteas2&gJ258H%k1Krk?@Ps6VN!MP^D>U(bhTh7_UA zwGn5P*r4_FzC|Xf+A$g;(rBlKcRRm+8j6Bpo*&}9B;19GpLLaNSTb=^6l3yElmwYV2g>r>U);}I3Kfc+*$Xgk@=3cQydzp8vCZ3Y(XsYyW)udW6q^R zO~Ju=-vsw{96As@=M9l76V#HvDB82^nO?N(yR}`j=&-c3|T5ufzFvj*Y}n5TBhe!Q{iRc!QYZ%%+*uU^aodRIbDV z8nQtMp~keIZ;u$dGZ7X?8_*LgRogw|76MDHLGN{>M z+|r--v88S2rIsaUSe6?sVa2Em$awvqxGnPF5^<0fzGJ1lp(-@53#}bXX5g<)TN6#rP@V%C zlnM}E!3kPfO=fk#^cYVCfbNLe)uP{p<93WF-7}4OLV4)-W6GpB=+jY2Gz8cH-MV0q zEFrJ_9&=gZLU*>(PZ5i&dsIOX6oxS!iFwH@fT?Bli;Ni2qyL%KVEx=RVY@9+uX0V% zbYB$xJHLPbv9Kkr?)CL#G44JDhYfW(Ql+A#S@0nt=C2UMF>ft&!H8OAfkhIFoZTj} zSn=0p@IVi-pw!}SZBIg*_mmvr!U9k)N;IhDzn_}f;5;0mIyw`1udb zeu%&NTymv|HDxbVevlY!?kOdh4@{qH((ajhXNk3mRAQm6MQ`z%&L?{Jno^R0-DBl1 zvSbQs6>qX{D^kd2C+FrkQaTfnjgyHXZ6aCg^b(k*N?Jo9X!R`Qy0RAAP)OTb1b4m5 zW`(Sxf+D&9G02ZaQS*&5{k0uC>DP`AAM+C!8>e3P8oD!7CS2(vVCHszM+-4<`8Rv? zW*yAu$^y#IqVtvK8}8XPp76+r*#!e~!dv?@SgufuYK^lLw8BNrhuh;#1wBxhmQ)12 zncUyj>?d~*enpeX8=uJ!*s^7|Fe*b7iv^ag!eymj2YE&#-o~@B9P0`QN2w_4xy+%H zszx4WlY!w$))ZISY0tD+J6;z5c3+i^$iNWH8G{u`o3kSgh3fpGlZ`PHQBA)OjM86k ze4P7HxrF^j^td*=p)uM#tROVhF`Sgyxb})JG)8H?kq`U@?mg zt=N;yrQyV{c;s^Pqj$!hlyqqxL<;&98w%f2 zDYLIWkC{^JgNV3?2~LxaY}FsHU)<tCe=Yq!k*NJga zC_d(o06NW&$C6tld_Cj#mjp);(0@krwM)6>+WwY3eZv&|{WZoFw+I@@n)be>!DtY4 zu9KV5U(Y0lDEZ@vYJg}gE*YA_#>Q%U;I^LyS`ryf!CTxe2l7UkANiz-!|$5cvlUk= zO(QZGs%64DNFW30;W0259eibWF6fSoxBst1yHduC`g}i8QY^VE$ipN^Bc66KOHOo; z%Xy${+c|-Os7n^~&)Lwz-H#_Y*<@`1GmbQ*eXVj^0<`Mb*e&!zSW`d8rmlY*W8RBo-9gzmW?vI7bRV@B5cc|$1}-t`S|SiAd>FR5!kXT?=)f0h47 zy$e{F5lONH)F@p&($Prw@S{A=>9Cok?Rba{%r;+JS(vUl`RS%_J8A+(1qAzSD_`k% zEhMP&u{ong9(~~b!CR{(R>FS0*~eP%*V&;l=_#~UK`)WDX4|>0$wm1*RhZLzB+eN4 zAk7QVAw5GJ?Eb=H3;7@c6+U`HVP`gr=g8a4XJd&HY(REXkD?8R zfuHLk*8Y8wC8hN6CqO-UX1Q;20*N{5vm+rB54lx*OGUW_$kSZ&;=WtSb;!Cri% zhqK1)ps)}>Z{{~6_JOxrrqB*0?|az}+J6$P7MFbfhAX>&kqN2TpZkLwFscEa1!#8w z`wI=HzmDhnYdZuGMy(vf&O#RIPH1SpfS2=Jyx-b=BNCN#%@B37I6WwX3}$}`20ec( z4%-=XE&G+Rs890xzO6N7xxCG4t(Do!%JfiyyT>l1o^5@s)h1=sG_W#U4v|AY=P4LP zo452XEQQ^E6MpqbBmJyCv#2M5puOWiWRJ*@((t{?$iz#(m@T}MTsM^Vmyw-i4(qQV zc=m^JvEA~FUC^JIS8)~N$?o$-g;*tYC_{I}U@p_caKk8_i_%3jwEt$gfU@E*Wh$*h z49}=ovo>|#rxc!FY;vL2LLb{(Mp*P^yIEq@Do9B*c6|16MB+zwsjCJX4p^S6S1TP{ zBpCx9WU+KSL+T2t_&=$%YO$~$?I7H5fkzUD)nUsRm4h>c^=yxW#-8kWORe)XggeeD z)RPA}A7kW$<69f8Pe@Ek_FXcF$YAI5PKmCozqeC*xeR>d6=7y#&0$<>wJveaX-m*b zqR;9;YXNb}BOAP(@=wjM;&xr^6&B0?6_&oyJlIadw%1?jQ;Nr^Eej9p57wXi$1XqTY)XAO?qP5p z2wRzg?YXviBVJ;)I15zB#Y`RwQ1vn1&%E7dK2e?AOV`&8kiv$if4fZLIQm5rbK5l< z0?OypI}ZYwyD^47Hrt4b=;ks!tsr7*0-ZwpJ!0?8iJo;QGWaJOn656(`&Mo)20cfv zeWH!rF`@B?ZntY6did4-fUv%$+x(*Ngvqo&@uSR7w9{A(jx~@+u~P53*-^3t2y;7L zlERcCtN-LAhF)};9J1Z>d*R>Zay`hTEkm9wG-mZ+m6&P25L+J2e~WkjVl^Ebu>=oW zjQ%WJ3y+ph%izm6Etj!&@Y+XwI%S zvmJq&x;Fduw2Wptbkez3)-cCvP*1Ok#wf-}YHNVHt^F2)=Q7C#N3UoxD@N2otM~KN zSxRCf8jVF{MS6Ks4|&;+7B9bGs6E8w@74Ou4@U{?VXW#?WpT^z(R{AUql1{90^m26 z=J@@Fm6Lt|F%$UsR$$>h*(<*6Rkreq!0!zyGqn+zj-il+x_rKh&Nj5*GVRRV(~}uS z>9e;K*-kg+0eBN%RA7TV&|HewYc%Ei$1MZNF8zE7{c&+8E#`BV4r^h@H_+Np)uu~I z&~yI#^@-T2#z8kj_FZfW=a#YkTq-$IQsr3q=-6LV2BUn3 zndL{QPx&5sjZc1cq@7M^*>{45s9;qoxhXqKGX{;SI$L?cVub{T~s)P>gG)T zx$X=-7LRC^;^bE*6Eg_h)OsMJx_*oY-Fk(D`fETsbs~gt6LEz6kzSu#>MiwyF5qGW z3ti}9SrebDkK`6le=?iSv5?SRx~x5Q6?D+H?&YRzkg`mFPY*)sNHGh07GCRoNO^qx zVHJs*U(Z+(;p%(>8+4 zF>v6P-A5TD8qm=m&Wx-}^>1-dKK1IcOLF<0QI6+<2F-qslYwhn25i6lZv8c)XK^au zb6}@MSi>tk*3k}UKccLF4le{y)cW3jkRrfKPrkTMjuGiwkpP1VV^WDpY`+#5hi;Q8 zsp@3fQJaBC&&oq>4;}<3xo$?59=T$_v%$;rBUqy}7CU6{%O9CD!UDjX)8jh+;ZQH; zpfiw{@H4|BeM}k$S(Y?B4pN+Rx!d8$jyM7J(g;n=(@L!YQOZ89cW9!VUo6>6%pXNQ z>Rru0aPUo;TnbZ((C6j-T-5X1_SR(%pr-3Gk_Z zyPaxONIkN^>#MEF`)`7LSnQdQcZU*J&*l#!=R94;WoR8dMp)w`3$aJjEu(+g) z>~u~aFyUf9?r++3#5m23=t5TQnS9@GlzRAJ4Fp^Hl*{XT1f8n-FoZ#I-$I>!AWt@5 zF^(H$M?CIxPbFLQ=!>(wJ2b!=N}cM|+oXBoP9-6knjI!K@v)bHQ6p}BVDqMV_uW|B z^Wjwj#KLs$M9mWWhQAQ69=!ABJe@z?=Cj!sZnr;XxW$(X9k~~B=oGp3onhu8*`UkT zUP^@%Ps%Ry#B7t{HPT}qJtlO(X*fQU!YtsxIdXxiV2B*a4@lmQl-4eWHjHmusViF7 z@!E~$QVxaagLty>Rd%=QvyUXM$||Ef?yrAT)U@xYQB=zHcbHL99oD=)&ZVw0_AaYN zrx-NW%hTYK*N+|DaC%w;E8WK#70uLBJ2kNi#^XS%451eu;_E-__2~Gx*6hvVnOnVu zzlkf%rd=!FY$PiqRTRnddkHMe8Tsd{A2n${t7`=5>7T~XerX>qubH<>NQ<_wx|ia< zVF(25s`Wp4brbrTGPf`MG}^u-zo?dw4Zr?tPB8AMXj+v}iaZ$l?Au+w$M?Zp|DDx? za*ze}Z&k7Vo8W%!74u+#m*-o^8OZI;!fr|WwXAF$qmcMlw3>f1(VrM6YJ>Qgsit(< z)%qgfzF4_)O+-c>R$;B9H`bz0>0mt0);6v|+8#^w`@@|_jP?Rs!70e&RM2s4&E`ez z!mW2T_zlOTt?7`Bt>`d&qfo)MeD$CpdrvsXzv5qGTp$J`q9yWMDJaI?$0C1x7^4>T zkfCj)P4LBchUqXOVWH;S{@T93e$;REB4`xOzg!%&9k>O1g;1o8&#vuSJZvQnAa!VX zVOe;4e&dKLzvT+X{vyb42)M=>V9giD>3UW)#BJLRpmvonxK4-%Tak(7;=4F0{&#op ze}K>kdgWtJU;YqJQn1B;-9=-JF*&jHC_lRf`p{hI7jc_KWt#hQ(=VwjJeDc8irx6*Q`>-j}jFDei zP0Oh9Ise3Zs91bJH9K2w`03GhiUzo)$kW8f-y~oq9Hw}7cQuq!-mQVn!;|7p=yM4` z+-7w64KqZwQYnM5ms%}I9J(S_XU6do&D|V4u z`?otb)@0W#$eK`>Jo9Mk7q4|d_36VawRa>f%Eu?P3j0ylat}f18@w%Lz4e_nZ*k#q z#Ns4k{m;3Ytv&ZmA*E*4xzmheilugwfL?FSI45A%)>5*1e0AvTWta0Gc&2OXR>K$m z>t)AuyJa;hLx7PSkI>#lo%Bp?;Qid{)%VKq8CbTrLUh@se)OiTX<22Oe_3)*py6MSCQ5_%ddD!s@+P@wta7siWCYa`7-i-e)r%~)t;JnD3HDWq6F z7{7byDh=J6+UdDTfHds1n>Fk^DGo6otnJHCTq*aL)zW~0~gn!f>6%c?6zIZ#e)8H!b9`uGjQD21f*#=oudKel&6RH%G)rBY#ppY0Qo zK_bGjv|(2gH4h%bHt_szzi=y5YMH@yENWk&#-BOPfk!WOr{7yv5Nh1HperHC%6W@e z+M8T`_=C;Wmj1n-!BWeyI9^AYTx|QM_F9k9VPiCnOn6=M`azWimaWJo+&S|TFiZTe zT*Ijak*&zTq1qP0w&steWPB=-?P;vfuPg7?TT{kOdljt47^Xj@uXyb}LW%R8pW3~vL&$Cte7 zqIme!FRKsVoOQ>`C!Y7`;v^v#4fPBW2c1<+HQLe}hP|l0;&3I-Qu(Ir*oO}ySwshP z>bpay#@B<1%ofkv0|8J9ll=qlK}i zQlC-+(vO*C^)9zdqMt_a@9mi!_#&pRKldyp@e3BHE{5g$@e}_vs z8>RZy0wZeWAQ+zyyGqxd?H~YGUOIUxGgy{z-we#di%!QHS{Q44@(yLZ*Z&F*88s0w z*0j?uhlSs0lPVB1>=a@0e8E`F&q3dP0du1Hq`y5$Qat5_EwnDe6j60S3|}MT1!5dU zn;|5=8GudPgkaQo%PQJxc4Rf$jAM6LUcEOrU3k$NlY?X*OSPevKSL*hw@`O#77K1L z34e=YKA=Kn4(*R`kyVmKGlcP&B6$WoX^c4o|4F*=WZvtaX~TyQnFg~RVlMwg3JYB) z6Vx=hurLKIeuI)y{;-JgSyt6*Cn3hbwl*&xAo4rmGaqo{uUWG~|pN|I`(epRynxi5@ z1}X{6%daqqWMERmpVF>+^!%X;AyyM>a~0?bYOQo@cV?_D(9X4@N$@OI7IZ5v8@0&K zy#G-F{9aCVkxD_{T%}$;b55+vi=aLYcV3rk{e3z}bvG&gD`0EPfH-eE{d}Eec==%I z2(s!WI`JE5y=pkiw`VZFGy9&(5S>M=ApNZ(Pff6au!UsoIImPa*S8e*H9W3AH&+k( zIB8^>{b2N6^}5Ms>V_3!P3*a_Y0szxlYH_SYp^2oFM`O@ac}BK@U247OA`R;p^@}F zXN#iYce*`3P+hjjHHzj9dAR z>Wk)2K}MUm4cIuO9&N%>N2*ADl0o-=RK>N)2X>7xF+1wdEzg_6UOy@})uSH?dcdvT zn85AZPy1AMb-Go$y+DG9(JFrR_0)fo-kAI%$ZjCK9t>X^zD!pTIgAgHxsm!`zUlVA zeDk@O#WMM`tf+JpDL7WF48`#z<~}um_`B8*8GHL_#9$ZU6VQQh2P}p5Kdvo;j*?`oYQ+i%siyL>T}MUuxoklgFIpyN&IhjjOwW;WGn1-p*6q6->$iaq>b~{>F8B+R^JeEwh6b9%rgPf`M^j;@LYF)bRj~ZQf zchq=8R9Z3l_X3TWmzMYLV}IYCzZSH>;F2l))F6IGQ=fd?JTCkbuREi$LVW~cQ)r|L zv%ecg*a79Hh)`?VS_eILE=~~$<4(MpD5j-UNDetJhxjX#&n8*kDYzb8&QTP|P%D<) zS_Zkm=a_wN;dHWQGo;1b3!({5&Vc_hqlkO$MSn0w7N-~(F0S_L(9_yG7vt>5$&w}m zD}4s=6V0kMNLo#5%~oe%+d(UEII%)#g1~;y?gJk`6IbK5xhd24!EV!FU|%MXE> zPdT0C3pnMeECSB6GS+O=Ok9#%M%Z|mhWiHpwVu$231h&fC+RRzR;0u1Z1&niwKs~} zyb6{sKSCC5y?-{T5_Am;TfI@+&kQ*sA#ypStn!4f<0pkHhk#R(YJ#^yW&P+wb-c_G zngjZnb{K(UbRBi^xde2H!KzS1nh`V#QopZWxQ?bjAMEIY~y&A3npK0z4F z{>(M~`@){Jj5lphi|JpM6Sq+L9&IWVSZuh2wK?z!#mw5T*qQ8)ur6pT{YwAlyK|16 zKM0PR-16LKD?zD=zbyl}G?r%%xB}L~V^0)jCl9QgEJ_-ANG27!v@K2T2jlXK*6y7u z?dwykLTlykZcYdJRtwdcOy%YuixD2VgJxQ_v3T=v)^&m+k+#9?cVH7(4OU!iq7p;FEa>gC{BQm5@+Os&wxy;=xy7EdcJt<$Lw(Kb*uQPgR zfsWbrlkKmPary0}Vtdy!QhZE}D^eiuLaS$G?C{|p72!0n^dAnScz$>Gx{BqZ3OgmP zx35N|M~|PiTO81)YVq+fQT(Es64Jih{!gn-(DdJuCi7f>=p1lBI$`IcmpEd-WJ_mp zQWc`=?+%bD*?focTt1;v3?+}}m^DWoSQtmE6ysZ{oP_+0IPMVpfckBI^&8b1@@5Lo zcxcHBy0ynso`TQ1a*rtT_5p+)@w``UcK2m|48TF0zGyi4kc_9Zwo)jp4W~_wGc?Z} zAyD5LCf57=I9%^j3~jqXh}^w&p!;xFYtLc5HgoKqx=Y>bb^FU9GO-~d;8sCLzRG&a zCy)zQ{Ns(rRKFf*Z6qxhcXNmmb#DCzzWV%fFF0H>YRbxA#dF-H8VAa47Al z)@DoY^j~Y(X*{WK3iSb1WVN``!BEo3TDdYwC{6KBQwo9Iy4|NDk4u34b412ra0ggj z;3U%w5dO8b%Ts<*T`z_L(zTh_TB^S0PS+spJ~w;3cQ~0avA24)yOJAaThhPt8FU2OH8kL8mm?^KZFbpb;o+eB zBhEQP8^V9t6%b02!8f=4%pisBBT8^2^Toz0?7d$$XaCvbzVTu37RD$y5QkC7@!Q9! zo8fUw5;^@}ML>K%ZlFwJ!R#B7sM8#noUgSWlFxQe{R}}Nx{2r`8>XJwI2t*Ehz&N*{nTHlJ1KF8Oep>8A= zHms%~fc!LY`2Se|2Wlp}FwINX9Wtf<(}?GBDI0* zMdVKPu?nSaMj&=3CYPhSWEv}~Y!>i%Dy}Ba%=fwOTt?cH*2`jw{rx67*>F`Z=T)Xa zD-}%&(qL&w>n4CuMrJl%15LL?-+Uw%)&AbaAHO&9jvvjXCb7*Hs=AYo^2CYeW{^UV zfe+M+wj>_6-KG4Qcx}PWv1NV_y9e-)s%ZM6F7?GgZ$w!y4=2K!Hd2zmE=Mq5T=rR7 z5^7A(c|m?r6T^dz;IE%Yzc_|ckzIdv@md#;f+gk}le-E#ox)ZY4Xnv-HrYBhwYwq; zSQ!}y*-ow0-gXM?z<;fNVzFcLEJbkDON>K;YF? zC9NMzn`T<=3KoOKoVDiyJv&SZ}k zYH=K8n{4ayORG)J?P)M6Uu+buyqGjP8yEv&t+4UAJAP3Qb4?qZ5uJgEk{66fR*3vOAgEd)Z^nU)#polZjm_LU

A`2D_fBaADgs=%+s<$*2sLu{A75tbcje4V@cDX91eSU^=77W zJU_p!`_oINSGMiy@!Z)eR54zsIG=|+3?I5Pn_*wloB3eA+bjFhd8YnSK}2 zLC)g$GI&x1-R_R@m^9hS+OD@A@1R2rEXam8rso%dBJ6@PRKOsv+_h$ZzA|KX>rvqb z#jrmv3;EhK=&aBwwN--ZBA~~wq(WMICXvU#L2S(l3$#JAx2ZWFko@O+yYpmEodv;kScbt;g_1C~r{m z{-2F;mLitlifaH!zuOs~>t=0BitG8R5v0RoGSU$=f!wwjCNbe^=tO>#O~m&78ti$; zKo6Me@~B90%52T=IB>ED5=1-SVgc7&zWl{8n?d_;ZMj*^#uA<3^<1^4-^`q?;i6p8 zx8s=pjbsosq%vZrANT(?7z1dduQzgr8&!dFf%u`}HaC3N23i`t{U^zij0mzZj$*l4 zKV@p=yoOOOWP2ukUL~BOFb_#dz#xScm+s~T_qv}25QDO1DUV!F49A_|Zke+~wzoCS zysK0a(w3|7 z`d~k*wxQsm#NY1Q_b=H}{5=w`1yy}XGX}M#kCY|g&mO=<2%h_J*>njODSC(JG-oy; zf0_2@9YVBMZXI;c$8WS?ts$w?f;4Rm%w|7-YRM~SyJOs}r~fseH_nYOlED-_S?ULp z^1sN*2FqnO&ZFChOM&T}v$rqaQ4F_n5@*U-mSE|35`1uG>(u+<3&)Mp{5oe^_gT^c z>3}A61tkyuKnH+6=fL@~4<0ZYGsd0du`hR120KTo(pF{mxgIOLyX0kTy>r}{BnQb3 zxV7z+GNbtuyIvjSaqI~o3EIVY#*tq&BPsq3*+<%2lD+XhPe+dT3dTWy%KMmtwCtS5 z_oahK|3Tv3x48Hp%+WlPJ5t;zeM6~q-}Vxz^XKcoEXm!{qo9G1E(_w|k4i~2k=V|dv&7orbE7)MTu zICyPShe3;pchq0(kV2rF1ux>`W}d%4xPQtl0J!9>BjX~jj+M{og}SY_`gO1LCMxvM zduiMWbIV7m{tnN*mxrQ02;RL~Iz)s>Edz6w`PwjtS+yN>h7}8gIu^h#y03m-yTly} zOup!ZL!GI&Sz6|cf!w!pb4o_Uqzg$Ss|ky@Z-(;L`&Trcv2nHxF4k>TSceGs%`<4v zGh~G`nX45O`5ey)Ps15?d!M=<&^hetTlitlc2sJz=`?$OE{7JIwk|)-!F^G&E%Cdj znGw|u5b#&pTTA}}eahsUij<9tLG!AGdJ+5j_piNofeJATi{r}<<%BS4PZ*|cs~*xH zNgQMJeG%JSsKvy2Fv>vAsB(WYz+z4h{_8Xu)l&WG)L%I^n@8S0_&d#>(AyHG-c^2kpb_u!8_vhjbTukM0f^}*!d}j?`dJ~Y0)V1HsldaWKTTuifDjo~J;hys* z9-Jwa-cIHG0U^w&cDN(;KHmbf0y)e`6}F!S8fgEGe@(?`=)RqnDH)-Au1GnI!#JzQ zruOVv^bJPy%-?cW7;|`AQ8m?d{R{co>UOZ9gg__2r(t;b?{H?m@@mrL&+roU`R)si zEH;UtD3Pj6=0!$M*0`XeU5Pg}t07M6EO~pyeppwU1W1jP-C=#M{}P4=*s_D!nR$PB zsU8)7bK*!Db5nGtaoQ4jv5=T;sge=Bk0J2|%~Q#=Xvt(Kxw;MBvB&Yz8Gp|G*6T03 zrS5~}z=bCOc+Qh_X2Y|0RgvoXrA#|>vX79In4UQj9NmBW{5PWfZ~6_gl4%kO8$S%+ zj5*RUPpV?GBIi-z#pB^;33y^3I8qeJn$y%0Y#iYORsA+?H@Jcm*b-ORCy}mLmXLM*$}t-=$MR{ z+!`Ls`pxC%&6u8WJ1|f!qP;^*IdvYIZt~96I_P0fL_L6#D$c1F7WSxVFg#98$_xZx zMDt{_TO*?83TBYmHS)oaW?-6w5tg&cR$n(ix;*3h1YCQ49hh-3rGT8bWgfOoC-h33 zW>o=$epw<8yI&`BwQOEV2)^)WjK=WHC4hy*_SFA)1Oef+*`D60t5+n8K}JH&2+PxtTUw zKCxjGFQU76Y18}t?5jhMo8`1DR5hK~UDT!(I9$ zU4rA?Sri7ga!fwb#)&0j>822(h6P{kF^v*0C#V+_U?+z3mn^B|vNS&%{DrC|vtt ztu}dB#3m%&5+wd4#L?uG@j+6Qu;DIzOdk+bTUh2vl^>LXm zE5-XNBbq;_ZGSdmzBCD=*_WdfFiNr=74E4e+sx@w{+fVAEFK;Gfh>*coLLMCiqM}W z7JK+nX82OT2}pA&9g9vqY#e&>_{!kP{Nwo47SsMn+lK9K_u|Si#}Zb`h3XP!tUBeu z>zTiiF@-VWESHNUy}8Te8R`0q1#>q*EQR7(z6juQ2U&B-B{`Z7OCGO_j|k)S!AQwN z(;Ditq-SKrCIlODwwIDfwq#XIE1WNd^`#4_Fn)_hMU!->S|+>Fv6iAfyZ6v;MPFHD z)Xna+YL133?3*lO{Ui|^`3@@a-gf!)$%KWQ7#eN0qLpd-<=esp#88ra;!y`cCLQ~Mil5fR= z2Yy~efF$ z@#&HAf!7CPPNzK&r&QRcZXK)tglb}V>LLohX~<;$JMEqVk>~TR?}K8k^ql_=PBzqi z;eG-)v^wKc4b~+F5bsWfQ-ru`vthII7-a2w3i`$hTM~QE=@Xe!CVVPzG$r{+TJVEJ znkDlq<8LiIm+%E?d2DlTLaZj+^k2umr4Nu}hVkmhzM=UX)~$#VDG}Ly?c8Se(+PLk zdo*UPx79Y@=6V{T=qyEA?z;RtGr4jghEgX8_MLdJvC^}^LJ2@8iUW*zr9F$e_(t+< zFU!r~QV4C1+;n=Ru2lks?PZSXp>w}VE6|>2Zi)NLc&iT`&DCMkY?yxa&quP|SQ&{u z1`k<^@5vNF1JCoB3>($Y2Pi+s7o7|5mr3FDZX8vZnpGl&tbaA0bI_dY?Qs)hV=P5% zwmiq{WR1NPs_*}s!_QpVTxUD3R13Y&bZpFUwRiPhP2T$FB6(501MN(6Z>k&}oOOP3 z>2o2tD4&jc=~L#V1&G9IFO(DBmEkw<1GmfY+rG8sIV1i-n-^Y#cRUgIDv!^rgUG>f zax|yMG!}RhdEdib=eNc2CX2$9{vb~@8zRcojEL!;e_IyaLHF=yakSFGTt?Y8E7P5T z+CgA(t51nWFMZb9&}uKcmaYGs^G5mE#XT1KO@qn@sKm(m7#8Xv>X4j$*{tvdltBrK znmL8lirk#dDhOc*F_9vcXxNQNzh_1rgt+5=|Ih826GVXJEq^YE-5`P;7%LpoMPjSH zT-w|-&SZ#LA&>X#uDSR3o?O~G4~xlt-Ro@{zJ`u|Hm~7&r-1l5u)cRNyP0Ih8)K@JpciP%-q;*(4VdqP? zajfF>~L=F~}OPm26Q|WHzRc00Rx9MUM@{Xa@Ri56`4yL@$90nfhCgNdklisqE=EubqTcDDfoy zUt)5_`c3mBF7_OgasxPW%Y%1XB8S`j0}!R4B@9C@Tk`<#NpgRlVcYElJAZv^iwko5a<{m<`0`_`; zY2U~p8)+7Td=`pyoArg4KrvDQGc>bjsJDd`B7r{yj?c1M>twgvb=Tt0^8gR>OB>PV zv8k;-p#*)Yzn^Kh7_*SLNmu|}{C4Z#i+_%GxlPT)ea^Ul`-^7jMPV>k^XH4$`QOQG zcgK7R#bo^a#En0!KK*H7R+m^;twn!Hl-a;{j(JP*XXDs*U6@R4uVz9f2uR7on6qS; z8|iW#4~{kMJnxEx#F{*W$7)f>DQn6BQD1EbbQ>y}4Ziy;sGRHp>Fg{m*~t$m*r%?y!8S&-8KlllLva#bOTl86 z760zsgiM4`1}%mPos=mqtE^AF7PX;q>XZuR_4c(YEO<6sU)nlgcRH6;;N!o&n66A8 z^fB(wGj+%lIWHhi5`!nmD+yq944}w8vZR6G%JVswWYo!c=) zvP>HqM{`@mwp%aT$-2jzDIos)L&;j49%JO1tu+B>GeHnFp59U)xXo zFJFxN8J9<)|1NX`I8paYX$VJ;{8Uv_i&5#G<|xM;Z{HLb)?ZGO3TC(7_aOg|rnCNQ zvVZ^gjVQ=XnREy!sC3r`A}S&=6lEYWkj~MJ8YN7mM7lN+5fEe&k|RfVcXzW51_K6s zcfUW6@4s;Ua9*#+c|M=VQEaLlK*I8>Y^j@7Em}QXSc`O9()FTYRYgC4Fb^2~jMV{26%0xQT1d@9PjT+@OJ zqmg@gaR1%S!VmdP4X0Iu_i2N4nKkFTKUEuD@4Bs8liz%$J2It^QU(=83fky@MgALI z?r|tb=IJUrC>x``?p%siEzc_FeFGW=<2Psew(fFFnPXI_F{Z+!foDG|gce0)DsdG% zHEFa`_Un1EZ0$%Ws>t7-geyIMaY(gB)I(dLqZbEjq`%i1fdywmUOcw4VIfFV`&-KB~F5 z4G#@45N#fb)SIfZ3yiKKNjq$p-2X!1Rz;|K`aW~^7^*oFi0Q4etv#Zs{s`WiQQ zvQnrNbhpqCbuVOJiKOEy;h;LEV1*)Wl)R6vM4mN0Z|OpummO<6ZiDYroXf<`u727F zQr^B^P`hjOV!&;-p3XQlfxfR=onMzx_Rkl4^M6(vtfR&8qV&$6p|#RM3x9Jfgzf$3 zOC0OAD%*gy(DEjw1LpeE*YyWq9xa`@%3Qz|Gk*d=`=$IXa?EQHP5z9E5!tM-ORqK1f;I})aEPUXa%^S+GgrmClKb4 zk57CrM9ZY>E2{E&{N6oX!*r#$rn{o-ja)SE!BczU%V3W8f{vu6fn~qT84s1H8t(!_ z@+^w3^g!$MenNbkZ5X4Rm#d+<&$rSqrNgby{LQ306I9VUGk3!p!;BVGa8H<=difc8 z#gLDMxx7ZXk&5=FnO1u%yvmD994Edbw_ya+9tWN8N{3!r`g-|ZB6Rai2uyRlrN_bZuW?pVLuc*Z zEMg0cThOVJSzz?P!yF!#jn<#UMT+AI2U}wM?}QXKHZR!Tais=;SpM0Mym*i965`q9 zLXHVk71D0Xx(p^MRjLLUD)E3Qc_nM%kNN@I{M?@$16_k&XWc|>4>v4xeGV;rvvF`NQm|C`6` zGm~tZJ_$Urt)~#+F3&YoVO2-<$6{t;U&=6So3>4fpTscf-u7%Nv8D0bSIA-Gpu@rE zdicmOjgd_OvG2bb9D>2NFxy;3b0W}}NEfl?&vLU%-PhQue`)ChMjf0rk;F@q&&%{# z&5K@+TNR3{y0N?D;~FUddP@I7*>5Yhbdja*>iI|M(fG3snmF+nqUyc$lG^seD{@Eh z1?qj(Q2z1O`wRzDFQ)!*|Kp_s+F1-PNm-;UTQbdv&QogB!vKYesg(NMT}ExwX}y;k zBfo(E0dt11-!vGExs~`3mtismJ{r+s=j3*1f0Zen8Nvc0HWT78sY$$yA zhN(&GIFRJQB=JP_Z111+GhEdcRZQ{o$6TLZYHwGo9Prm4%iyyAY&y+Yd)emd&RQ4_ zh^e4v@1ris2?u)Gyn9q#7(YN;dPjJMQSP$0x+<~wyno4O%YjXCYe$M_gPN)( zy>}-4pul(zdJ-aaD@Uo8AbP**ZGuar znC=-z{v81lEUc8h5c8#Cp+H}2mH>H~)auy-`p z_X|K)lg6)9(tF@@CjoiKz2Y;AyI+&IIYv{WV_t?tE?ozel@=I)E^Y zty1yea^o6QG=J(RIFXvpmT0-X7q@ys(xQJ{F!VXQ2R_Db2Cm}Xeyl9~IOrO!S`gPI z>=dJ)t8I8xjA4Neuf#he4_%@{$96d_K#u!E+;xvAh{!gbw&eQLw^>bp*F!EgA}a-+ z0gL#sdu)W%>x!J8ZZ^Acz~}oG3R&Y=lth;!m>}NQ%MNn6+*CpN#0`^cI^!9p7x=)L*dsI?UjF-HAJ`na?fV^S5nxYGtGN zL4Wq6>whAjLp<@`OnIEOi>mH>QswZ368F!`$Gd5m@Yl2*f_vp68;Jd@M)TkImRLoA zZj`kZZebQ3dD1p3;n!w=BC;)51o)FP81m(=Ot1(2<0l7R566d*3CWT8$*&GcfvkeL ze1N>#nH;bNuV;&1A=>}Ji~Td6fEC>8^u7vt8UiQa_Lq`~qLagy?G1}fSPGL*00D*F zr>O||nSr;FWcydB6q!>!SZL^S3`k_HvU!U7B<3k3hA(@fg=ysg5O}>R_-@4Q&Hb%s z_BXzg=4khu+}4F43_RgAG)lMa%L~cWT6rAh<&WK$xT#n%@cnCu?W)#2^zm}r)=xjEX_Ffxig3DlPaZC~$_)P#XFF4H=E>-DmKHB?JawnREa&j#nE1=R zJ=gauuVKC~(XSOovLMOEnt7%BRmZhx>n*14uAI4$6KcX#@?sKfW|h zz8lQ!Y}>0S&`KW2)G|eJ%eGfr;I8s2=|jT<;1N)H&9`|K-OpO6*uLHWK6;i^17}^{ z{@WCKe>F4yLzq$d_cBH=Yvr5*QME$G(|3X|g>3l`1FN%~zP*nq9wqJ>c*#X&W%I1D zCvb7O7{pv0iqq9K%aq`>=q`>L+K*U5mk{RzdSm;#XCh5sb!0>gy0I8bCTL9IXq}18)2JQhA%`5 zEWNFh%3J))hlubGGy*tz_QY#Iq-pQcKW{Oe5|gN|ZlZ?nRXXXUe^J|=CuanCkg8E< z)xI6=e@J*Y9Js{S;tbN6RV#jri|{K4{8P-yRjVg>NeY}}Gq z23Y|4RumI>qM~@-FbD;0*|^_HAC7EbWQNe~z+Zm~3j3m9VeLo!ixE0I<(v#XBQ1JN zMmPyRoq>@=!>B{O?` zoL!2&Q6zuNwzN`+ECkzi_@-VX@R%j%xA5DEPJ5xcJV0hLzJ6xF;>lZ9 zM;Q~+!GofE@`jZ&k88rXmWd}lJJ;wpZnBtytwzn6(-U`lUDaPnDKbj zrOlu4g4mBZ(-AR;o~kCjgxS}t*{9CcvT@y4m3n&1LvfK2uMN9EK}~F-5{s zW`wCKa8{9au3i;J3%M0@t@L+Zoo(s+e7n3nrX71_F^1~S87aAE(?;&yrpG)NL?Kn> z`aknW+5XHyl!`Bp%IO3Up|RH;7L2(iyZq)l1Jt-qjI4rTXV$3thr3;|ivM6nV-Cq& zR{mG;IAzO89hL?ky-Ofa-WGw-srpi&Xyv(Xebk{b*Lw4?dz47to)pHjb%C$Q@pAes zBHXJX`ePydhliv>jL0Zf*!MZ}gBW2yN#)pP}#0R2i z!@3W7I?+=q);nHIpmWCsG0|+f>7%iVk&BmAyy6|NeFpcg5kr)JZxaTI`VbNsbFs7- zrh>|*fqPPni~bKmc)8zz4PM=CZHxCo{%GB>R)IjeIzQ}n*EBeF>6UuxnLEpl(Jhc_ z9=djZ1-RT}*(d74`bRh8dYQTt8xCozn=CAKbTw z#VJj1^=tK#|n?_k8WoE!$OyhAer2t1hrB4aC=kSW3JfqTIPc z)p4rr=@*yP|y{h%#S7AF)My7YMS ze*r^NyL;yu7Pzj#;J&YwdP|H)N>43V%}rq&7++T<%~w~2O}W;ITyu4??}VJ(obaZp zYxWwmtr4Cw;Y#+d^0*ruFyVPSWOL0r;}t@fPaMdN>?k>eVZk;p$DO@h+3)#i56!32 z4?{Gy65#_Otn*nTzB=uW`h2osEcK7k+jZFff@$nmMp1yaqE++BiOAXsv&q>@^54lv zR51YyRa>J#uFS(Na9X@k=7AAFvIt%%ZBO`j+s_o^Z|K&q5_FDhVXap{T+aC%n&8OR+?S1O&phZ-_ z2sHZU)7G3zt$ zQKgLfXnGjtH0*K0c4Zp$^@ZFNQ=z=q3W7SdMuuIi^DU+#rXjOGbU9vsY!@0~vxJ$l z2(g#cpxLF)@;hn47m8)P6&H`)69O)BrE}LM)BzeTpFP`82BhCP%@X=uE!YeQVVt=Y z6(W8pI&n|)2LW=?Mi=lpB5RtBX^UO@wV zVJCkNJMrTLO6@hKWX+Ot0G9`(qwlY7gS1lbnK8H+LKz}7RNZnQrK@Id_v5N)9+u<; zcf|VmX_6be*=%WBf3*w21n*wt3Rkiyhlx{}+Fg1lmpd!<%#FJy5_ftg?3U@OpSvwS z(I+TGdes8H2YZ6MgBiXrXnlVDRQGjz_(TN#Jap~uy-mGe`Wi<*3RkXtSm8p-kT{x)i`PMFiz=}axEx{U@-ljBo<#0Z1vc8fTnA{~a( zM6q2D6*gQ0yXdPa1Myrz=LwMDD`6ZS3J8B=$e7N5o=p!Hb+xUd~c3qDXpA?LHdqNJ8 z_GB?gxYjZQVfB4@PGDQ&7HKHsnS^Uge%K4w6;faA(R|I7jR|d>-`nr_Rp21ewNx0brg9@9sj{tc<;_vwEAPWeTF@c7%KchsUI`^l|kAbnp1=gjjMk>;Vhe3)_IYZOd~= zafdYk$duF$ikY&Uj*T4GjR=#t`-lEY%@Q}td>pN3T zLc8waw2^LJ;ceY@;aF7o6Q$Q6bXGNAgMu^S7CC=ABoX@YYK~d(hQ9Idd!d6_?*I2T!R${1DB~p=F69y zPo|NmD``qc&&-H0xfj<#<4)npsP&af*UI2rd18Eglv?*~O-M8hEu_2HSz!(-E)9Oj zO!{3+d5chjo{9Z@>AcRN4Ne-2lQvfhfq7zzTK^&=nfL9MsCuJdPe6Xt;x&ZO-;TBB z_eWVagR@_#pfByq2sp2PAPSq-kSOghMRoX2aJXcW$RcnLh_76y|4_L~lqjzz)a3!` zP9#gl%@W(RQ^iwz?ouq>A#o^wndbch;W?|9Z^$%g_!pn(G&+cof7hiS#`}X?7}P5i z%nHMF7dmY^Ka40YqngW5S|W3!hha(ua|f#y0>Ilo2|m6+HQ7N34JtS68}I8DH%G}$ zhHz2Pk`6hJ{vt%_OihEwlVZXUH3ITUhpnz7$>a{gVj{jSt?{zqa<>3`c|4C&3fMd? zT;{Fb@53VIeU2A1RAKvz(+!lpFM=|~=A#OEUJ{cM@dIBwn?< zGhDeHf4FC(hxR=efP#O5sdl0{&CKTr-JHK1@pt_`FJ8}a{ZU!J3P)BgGu~7Erzu4S zmRLggrJQWM5t4QdJk&YnA@OhFelu%o>J;sH`MR_xm63G}3#}>~(w*R4YT#{s>8hgX zqG4|F6FPb5pZG}O#RcQOJvRqGym@?Jrg?L^Ssd9q-0rCOgS5Ky%gfa-_6_Jg&y3UV zZtjSB+o1h%$Y}ADy!Lz=*exqV4zfKtb$6L*ePG16%n%b^BItV%G=lwSWt}pvM!SkX zD#>=II4P{#m+QRom>x>xRG}6Yp3QP>*N1BzhuM8`CYC61kfU`ZztQq#9?E(_bCi8I zO~xiQ%*Iu+Om@{nfnQ@#(BmRoml7u~q92rfVc=83*xOy?FVWjg8x;RnL?5XFTknY-y zH1bHoZTsp)NhXMBhdCT4+sU%&6K4zi zbF9QJm!9`$PbYL`c@|Bz>ZJAC6F;;n%)~d2DPCQzm6!$nIdaXVPR@?-=_mq!X0s4s zV_*^d+H53a9sC>Lw0+&5T8A~)E|U<2Ruaj0%CygUIV6_A7({afmMRDov@HT8WU(?+ zJYe-A=3MW4Ca&a2T`|@G1(;gPEBtoHUsa(t={iZA-vR^r|B^u#QS-6s{Zp?KJf7@z zJ6=DYV;A^xZSiOK*6@{bFUCHO+RVJC`}!`^p$)D{s}Hf7f%oLa>xf5hBlOi7-w+LL*a2SaV&E^pBrq*`kVNQh>0Q0p!@$5tVtX|i& zE=z4(fKk@9JMYm{r(TO@U(xQ+E=8HC z&J70^BS+Sl$Q=!Edmps%>Rh7foyMG~wo(J~ zt5l2Fa$hFZZCI4MeRXP$T-0GxM&~K6O7L9kDJGA{Tvg?_`Qg>pAJ8Xn7rs8;9lvVLw{LIv>R&?duS-1&&dR3+B z=T3&aW_WxX-I_xfA4^#OQ3K0U&YoMoUqEw7sxQ8FoPMXsa7e#)c>73at_-rS==iAn zoQ~=vv+jX)Pq}lp(H*&g(Tk6(L^|fLd!Xw}rh23zel(0zGO_n#jCNT^p6~YT1rNS< z)ixef84{BEs$U>CG2YZ}$T2o@uo+Zma0jOBQcr5lTYqAT&qJ%cvn{8|EB&2qlZYa{ z)_4<5S}3F?SIlp2K(8Vkr>4!oUE*Y2WcDo+&xCEu^I6ZI#gq04KMM3^=1%3c*UVro z;S{WDcCEQk(2~E+Oth%t<<5wnfFp6iZxsKa@=S|6?MC#0R`OjjuBDW{`z{oghGDM}nh^bWLz)y&}#w~z2Tc{&mVK6O(WplVSlnwXg`liIN z0^cIB$d_JCUhDuT2X7x6Bjm@TESj@3gq6P~W@t;B{U|nDX{6nV@GCj3U15&jx-Q0? zk4d&e*!7oL<-5H|D)k4VcE^q~U;l&{PT)N%v`jKj0hSXH`qMQ6>l~-~jU(8WezArcJihbs(`Kb?f`gmCmK+ z=F+H7&3#t|VKp5$+;Q1prG@l7w^dtEEw?A@bgS3r2K)kd`W78RGYlkv-9NXFYVP`` zZj*_ZnHHmwAp9$O7*0~plS+cPMw!vNDhDUWTiqh)Peiyj3PXLq1CmSjf(MN@bd$E(|S_gnq9^d1k5T=TjT z=Q^14yrI*myHh`IvOYba@&U6^qlftbtI%Zuymc{$sAd#=^Vc-_c?1WM(}jF}aJgIG zH$U1RGejbU(t3)8iZYXyGiZOOSO({CqRN6)qGW5Iji^P?dG+s6qP6)x6k%f9$sDHC zqkncg>K#lTuQvZNOxwgO9JOTw;sm6&#m7(^!%;6YNKWK)dsf~KebBnZAmc@pPq$2! z$cJA7o1=s8--<4Oz4l}k-Pcu!89iU<1-W@vHthg9mUK&?!S)4mY5Dn|L|jZIXx3Z zfe=w~rfT-}iWJ@c?ESN?8~ro31rl^IiH*XqSnJt*J0}?Ibp&frW}7}@Lmikg&eZ&6 zI~o0@-dVIk`1Xu7#$yCD@Xg6Ca$yL?uUmi-Psa@h1X>`{=J^%Hj15DwSBAb zXd5Ah|FKVOnI$67rpf>kP5^Ov)N-&KMD#%d$zA&a_JsQ5zGzC5 zFL-O9z1CImEGOVptEKHYyy|I zN$Ukp=1)N9ud2q`(@T>CUv*?9dwp+jQr9p$u7#h6W3}vSPZj-O5bu%v>9hXkeb!#i z&vf-15gfZ~F#!>uOb%Q6g`X^1PZ@ND2F!3qmQ`65+0Sdz(7!si`g-JNmUrZrD80p| zsu-xw*kU=N>F+Ox*jGJ2)E~Z}T&&gIJZn7Z+c#u$CE6-q+M9Gh%yMh9OUHf()KJ|~@Ox~Gd$czGc z#51minh*Bv8&nJnZ8++3y&)~@ZnxsH+)<<(oPJmhmDqUiWvZyGtu<9M3;2CBkORtQ z)$?F&!IisvZ3V0qV<8OIi?!YHZWZlW#424 zV9e?YUGbCM`Hjt^lr;e4gkHU6FCjE=@*OrK$h2CR(ZqhiF^5th>(xbP-SfHf;XCwo z&ajNp*dwIavzo@+V@=c=C_f*e&({)SC-|v(>i^^}^KetYa;sUZfjQEOHU#)91T^#M zU~XJ`k*;_|sNUwHeyVg(FW%!C4C?#dfAto?#HW3tWu8@lQJhEBZV|LW;odBv0Zo-K z;zyfK+dmTb#@`(iGCCS9EE1zN)O#-qK`aL>1{)nw6*stfc#gTh&4ei?%->&LJ8d<_ zo6t?~#4}e#V&uB9P(Q; zs}9*s;84g-K?Gj34RhxFEFEmTeZhMkq_Ea9*aMjaqS2 znU-$w)KDR!GYz#^4|@Tg{wRSd7wI}~R{b7llHrg6u)xt)xr=S4Br=Rcq@bI>>~^Zd=QnDAI^_qNNxe)2uIXC^OsuTfX!Lhw@l&sSD zy1noy*7_ry5;~Ff-Z&d^cC~z>5bylwK};ATdf4__tY=E6TvrNR06Eb#82_&Zo8)`+@RaAKQ|sN!lLNq)}=a*o6C;b9G5$n`nGlaSBM!t1!9kD z1leDcGrs%@O@}9$VYS$vUNM$j``OS(R4P|>mW(I=0P`8oRJW40p#z5;$$rPbkV_)#em?sn zLKy*FDtL=5@Ac`O%^?EuZj3OvU(yS8#eNG=H(!0U&sOyb!FM}gtDg}jWHT`_RPpKR zsab^GT$(nM_Ay_W0Ngn-RfyP1WS?9AvJ}l&b|z|> zItvw-9&z$ORy^O0FF8!^d9?d$^x~(gP9XB46P9u`rZ~7$qj^3mUq>2>8kV0=_9jnK zGC_S{l*$R@aywwNlNEI_zYTmxa5hsV=yC^m zelNoOTvO|sRxHm1hQoG*lUo8j?eYOhR$ zwmD?b0%LA=X#5_ph?5)RUJW=?d0UQtGvS8{hS2HegSEYy7nbR!iuh`As!5}@qhnVI1n-~6#R1% zz&9#N5+Zvj@-o&#;&Ud~w?bx`b(!2Iktw?10I%FVd(|a{Rb}gvzmC2~F1I(Ouk;j~)Q)RBURQRH9Rip#GgC7=5;_n^ZiC)k0;v*w9GhaLapW%E{!zQZR_}kw zm~5LcZnH4P;+sOM8j}%76@l`IhjZR!#_WN&?O&&vzGQGX$XV~Qtp9%&0IaF{RoIgg z&7qkHCUzG=KJt`H9BX?VQHPK@W|6qKS~7<^Oam z7co2`=nOtbKy79|@u-|l3Ngj`$0$dnGY65j4;B{5?6RbR*tI5u;=BN%MEBbWvFxW{ z-z83-Vg(%XaoYi^)t7l=~fk!`rQNemyK zW#LK3O$8jb9tE6NQ&~;vcv&r~d#zeC zz+S=!6Tj6Y0H!;2>~E;YNx;j+F~G$1_Fem9LhLEIMenq@=O*_R6@)$lWgkWQ_gls3 zEANVv?}d(JE1Ek3wnLWp{DeK;A)*@6XSL88<86WGMQ*+1wSqjPN`Rn;^SYgVT))kD zf6&PZ3MIMe-*D{DOs1eTn0QY*G;Hc4+Ar_+DRlbFZU>R$E+vVPH*+1umk-)iFYqTy zcXQ~_yuNvTHejSKlm=Xm%-#Rs1*_E7uu!v>`tZ~S-%{GOLB&d*g)3Ygp7a^Y zvD^>UR=^lpntFi;;MvPF{yXgwPQ`Wa6 zsUdc~bcdTgg*p20!H=~v8D?oX;oqfI>yLBjkde^=eP0{zWDVx#^(S>(rFw1~*k1{A}j42o(^E801E9(L>t1-%@J zn?AVnQQeZ+xa3u>7n*_%AT=MF+R3n~@5B=5OcGXnIsT5)`RW9ee^fks0BFR<7q&6_ zEzTZTxC-WZD%u9$U+KE7^2-*s;ldF9Xnb2-q3ASi(3H6FZA1A)dn5%c&P|g+XS&fm zD)rFJSCMqAG`*euC!C75-^@1bzG~ou0o!%eJLY0zL|&Oz&`NXU}>n>8hy6=bZVsGH<#{7QXiQ4 zDHF3O^?1NZ?kw7BJFwJ=9wTzef9du{`A#3aZ;_Gk2#BLf3%5A@(Su9 z3W4oWi_?%r3*5>F64M+xPT;mc$H=tk@U|q4@`26PkL{67-7oCINq55}=j-F)n=u#4 zDpf4~@ut-Wqnj!-FXLkUMQ1o2cDSroglbiALaIbN0xF*#-%vqSwK+G4@4`zXHSQo+QI{x0l%ek0` zob%ZA)m>+bXFU>#DQ2gJa=y{)ucvw?iG7A?xz@SZ!puIW>28&k|h@)czNIlE&IrB^^E!M zL|V=50pBFuh~yAV(;%FLrz~kVzfh#9>5?Nmb{)TpmqCi!z}rTZO$Kc*mOWt1mN0hi z2TaFU=u#BpX>UgYtz`OoilI06ZO64gG0|wx)#M)>X%&E$GwWRR* zPXue(0o_9UYk6ga?kDC837x(!xpVa=S{~-t<3H{73D0#~O}|zmxF(90&yPNBn!g6v zgJ^NxAg_Fw=!;Xry*eeNlsbmLZYl&Z$o6F#TXx+t&(`Gz@%Spbc_%&BqF=wF)J{tR zL*gVKnq79K`og3=%1M<^4`K!aM0fGIZ;QZh=A8A-z*hMu6jxIqX%rOb;9X$n&-3)+ zzo1dH7DZaTM^RK^$5%;I=mO*Eg=*)KzehXuFxGX*IfU8eH!Xa39KMVDkLc{7ld`sG zmMe4?cS(xlrg*>M0A9_Ljev)_juAf1jLUJ-fFPB&$F@ZB2-OT`)^00|_wLl9 z_(dy4jn%|UZt~qQpL3@m32?fyU+PVu9;-(j5(_>dc~tI7@2Is{Rl{!*GCLLb%@De;6%Pg|^G?M*w>) zo8x+*q zHC{@xPE=Gjzp;l@vy`$B{_o3dZ!Aaw6TK}~hTFnpgpoX@=jMIgq(7aWUBfBbcbH&R z9c{JirWr+*E@w8-HR~Vue84B(6S3g14Bf3Yk9^}z@vDjtn*4I2Qm|XEEMj~Iu!O{i~_6%Jjsh`dZyA0-=JU#hr z!z(^KQe6&QExgPGqxhHoh?Jnc1EFB@UL!rzfcXtJW=Yx;gK_XPI3oM6f^4@@>HWj; z0Q0S9M?CO{Kkn`)3+g(s>b76=9H#!FqZ`$KFJ!&yiReX>Tk4V1Ym1VfCV0E0dGYkW z=QIJ4(%ILhZW#f<$QMF;g!%Wgpr09AgGAT2^;ckt(&bUMUqTr$hI}+OgV6SuLx4`+ zpEVs?Cex>{n8^lt)_LORqZz)dwrvM9#$;Gb@Im>cx`^}hT5}BHbDou$W73meib6IG=Ed|q@y+NdUsXI^kSBYXXt#q=dHf3ZM*zQ*A5oJSijWI<(s8{ z4%jysnZJuAZI7t>-piaP03_!;pMQ}pY$4PZS8MW2&=3A&)EUD7 zTQcBQNEj@ZUVW|6HilkuHnR^CyXik$pud&Ya>Q4hrQZ@m?p2oT*2@W6cKjysQy80F z)|71Y5R7xr)OIsO|PpN<`=U2;#><9%RMweU+8EB|Bx~_$O=P^7K_77 z8Uy7Abwf}$Ow{0dY~2eIw- z_#A1L27MmNK2!CqOx2%sv444i-}OHtGQkO#i>hQq92#-%!tiWAv0s>Uc`oB>ov-*v zpS!Ma;z?H;gWboy6ESV^jLhv%jw2S|7TKLVd34Jw>xRDvG8L#l$+Hi&;s1&ed_d`- z0z98WFw$yt3_LBHTrG67QE27xyKx#4u;z@|l*;Q%UNtlf+{F|H6*I80-vf3hu7NPE zKoRyz{ek95!={_w^)D@~wLH3A#h&7jZ_&Gs7gDVrSo%flyVaPvloX-ct)p@rK#cOn zvsQqXx>MY368-sVpNf3Pn^2F3F#`h@4*16a*Gf1kj>XOEL9X9~MVwDslP(D{ar%=T zA`pDAoA^fr*Iv`89yMBl-fz_@d!L8fm$Vd~*C(q)L4mZSfJpQL%*?9d$cu$VNDpf% zGBO)?!scKG-#pdk;R!s9pH%zi#OTs0d7IoLtNpJ|3%kP>CHWQL8(*oUjxq^D zN&^szwak~Kf;|k|`wIXL!T*j*$ZjSv&QeL^3ucVBhvlZ9i(nr;@7`7eP4DI}CN2i`2-RH9 zUtWY`p{m5C#ZETIIgfTxgk#(c5d9>O5)1RBq;zMLt2T7mb%EN>*$Ej*bfiF@0Ox1@ zqGOwDBRZy0TXu2vN!`;*`hPj-63+7RQf-iN_L5f$Ws2La(1A{goh)!~oP&c_VATPM-0%9&3vpYIh}+HJ*Fx6!c+ z1Vqdl_B;}f;*NNU=6hI~Ocl_@Jf%g<@Cj?!SNl~F_`^!J*zQEe~- z@AY_Os4Rd%BjY}+WVVP#eIP>s+$yW$x(-XQ+2p+xeE*5ase#ngYqg_-!cHsQ4{nBe zf$Z{)4$4z++7S_5hz4o}swy*#alE&eZqPLI?zjgcm z>;sRmKDmIyKEpEm=&ql0I=wn@dJ8lh&yv6rd|7Ghn z7iQ#~!Ml8SZX_(4muIVh8sjS;WXuo;`$pyUBrF>glZKT{88ZiHsW46P;O2 zmD3SbOgcA|j3#%Xd-iUk@Ay8*QXAb9@*2YoW)5;*X?x(DQt54OXON=Gk@JbRz`0O< zb^Z8D$ICDc^5pZJ-VDx#69_pf$c+NZr?8<)*z76RYmOJ`^Arf?jd3TSV{1b2x&mn%q^U% z-RmjktT>JJHkVMy6q9Jd%Z?b5vZt>Zdr<}XsnrA&qmz zKFES*enCLsN0moI^c3DvOTfdWeY%s76nu(#z1KuKq0Gw>wBVoKFRmyl;=t?mL zX}M&5Rxc&LC_D4mQE1o0pJT5(3Pu=P%$7oS8O(+x85mY=+=3>}KWWp_FQzdz2(lm! zOHC|?PXqh2mhK{4EO5*(45yNI-}-n*k=}fY%$Sv_=xUg!h(Rajlih1&YrzW(i+{r9 z)%HZ0#;&T9(=)BzYlpJ{nN>jXC0uuBH+Y`#QkW-9+A<~&DVTsfJ$gjE*AWM>5*Ir@ z+^#P_K1@ejY=#gI9a$1J4@XA#9!E{sqWo1NLJnCYJ-#eB`u20h=zb}uuBWJnZ#6eG zh-+K7AUyXHL4H(VS|_#87-+MYNObw@gJ(|Fg2OS@11L~hS3-SBz_%a=N{P`Q5{>G6 zl>W$Xp!d6Am6iwcCCxg&yuQa%F)@(u!ywJ#AEq;k6Uk)3zPbI%>$Z(IZA;I89ta9* z*Ufn5?mO0ZM)6eNip^XVaO=_wEP!%;cy>w2uhK4cQ$oDwinZo;5qsi+Yt`7G-V{or z6B2S7BV@+*o_RefFRt!#?!N*}4nmd1l5yhEaCYE}AiSGVwP-cYh#79;b#;CL5ZS+5 z!Vv7#d1kKXbTh2Yi+|UOLtSU9`m|Wp{E5v%z4ZA;ZQcaiqwlI!9%%93H`R=cxRwix zM7>vyTKjhF@pAuMdm6O=wLl@S_^M08KjDs}-MPF*QKfbRrV;6*=*HptUlNS#jy@UL zHfB24>u7B>dc%e*CwmQn228#s;&VGX?9296>X}-&F)Nc(*GKkm)_GQ?S=uD5%!EHx0#hd&{7~$HtXK z)t$E9>n=kaqh**}c%Or@uig#p1-Ifs+jzL#nxGD63pt~}ge2JB!9!JkB8hQo7WHTu zqHf$OIq&_sV$Jn6J?Q+zidp6SEZ_)GdafohqRsx?hWN5Np}mjtvzE8Mudr_QS-B#~ zWZbZP-{*z$O^jC})57{uMEc%+Mfnu0c4mbrGwAq~?NNYlCVcPvSxo=6hKKX_jLkb< zW7MQQKXTGz!_GW^@o{xX^8B6C>6&Ct#|w9Ob$stNPt#;zYc zK1_DRbpX1iJxiY5R8|n@kQc(2qGH-L=Wxk=oKUO2RF%~1FpG$i5kQLCN*4nZ8z@Y>CMx3$2x0M{lc8q;I$aETfwK z|2D27pi(Ld5(5PUky08)h$yJEh@(S9nvtVhKqRGOFaZIP?q+m%jUJ;$4MuK*0r!6Y zbM9w5J7*7ew(t9VKG*xYUYCFdH}YyGM?3HMU@Kq5$?t5vL+I)>nHG-UvZNhpNdfrO z!q2f`Y>jAa4)P+a1Lr$1=c`EJHKkOQ8xO9t0Bm2U267 z88D2v4jUl03QC=juZLCaB!Q9cX_o%TmVLfJ*^PNuC6JLJ`$SE|0G7?dV95VBQk^b9 zeO^=gJPX5Hcd6rBt6N+7eS$7yTeTTo4Y2<}ssLXJvA0zV&c7%;?PA%HUdqaCEn_4kXsgCin?-Mh~kc5QGjsHwjg~fr#*V71zIoBh^G718ZtJ=Z~ZS_|d8j~1l>8YvY zD9Kx(9Sz?U&bsm~+qW{*N%b#QY}i95#{^PpDMVb#tfD5|CP0oFtW7z(AeiwP3p6Juf;ULJ;>c~Wl-kfqD)sX_=PvZ$1y&K z%966t?-`Jle;Ug4#ng6b!#Z`Chf-1E@%(-Mtn@nH%yE0e{kE0Fsmy#83Q9+-h0J_c z_l+&N=?no*KWa)(X4M#?ad(6jBcl|qZ2h1ra$q$z(g46Lt6Gv%l(_1uOhXoTD6a6j z(u??j)L|hATU+Pd_ zn#eF1uL_ejIh+(@TUg5I_Ffs7XR^qTAxrUgpvyS$Mi5s{y{zVCaw*j_+s_vAGTsv1 zl#1~UHB%D83SPVohm-hUn_F2`AW40&`ap$DB4j@TRHxxmETgYPrmS(mJBF_t9k`-# zQymYup=WB)nTPI6NT5N!u9$OxQH#?G`c&;%xf96>Dr34Ob1^%XSfGi)EQ{v-S|@1@ z71Zma-uQERW5*f8qpG^crmJgWp0&^7YrW*QpIB?nH8q%rb?%h*Tub6fIHT3z-J&mj zO*OC$@{FW@Z`;r^&j%i7^V)3liN0(>wT(;&wRn1L=ho7~&+t@X8pP?!Frk(*2%BX3 z#?@H~9cv3NoxLwr_hnpqS$a`!dC2zRrj6rzkFQMd-wZ7cUsQqK zf@jDH*;Yrin@?;hrL3eY5N-D-^Dp1r^s&b6#DPJvAon@Fxy0DyP&tW;Kh)CuOfrE} zLNOz(J4ul`#(g(9hb_Y~+lIsvP@cny{s+g;bRu$3?w+l3_iC8tU2+{phLO9AD5@R2 zs@(=3C#Ii@RZdt=oo3x02IU?5PfabyzB*OA?Edw3fw$<;PbI6f*lydi1+FiAgK;{yCUE}M*A(OE8LgZfff`^`0(*5Yp`ngB!qv7>6`kY*Ql_lZ>u1ODRI+0Xu~=>Os{&;%Rc1nps*n;&2S z7(V%;%PAzWwoH1C(FKb>!3%ZG5lPM&3*eGbWyoTCUHq~7Eotj##;AgLN&(v9!!>qL zmc7>2=Z>T>*G>eSf_{g2MGPRx-KUOaMO=%$ysh7wv06l9XN zQ8m@nMc-avl-(G3L$DKtj>yA~{0{3~JRC+GH~?ZX5>8(g!Wtuy?Vp8;*#*oG)+?pC z3OzW|XFRvPz2zosSG3(p&{>7IvUee)0;G92Q{hNQ;bY_m@{Mp;JI5bLclhY+Qo-0~ z+uWaowg`)QV$9rR{r}>X^A=Lx#fPI}6mt$In2-&+01N@DO5la(V~Q;}i`Z1To6lTv zi*sF^J&-Y1GoypdZ3St+{s}pa0R}a~W?PU>IwoG644&b@P)z-?lpB+(>gc<7nzdU~ zClr69ZpW~;IlQr`gz@r0O_Qi^JJxb#rpxwLrpgl13am{@FBMTA@e0LR*%A$Vofo`D zvqvH;!a=CBsr+U+)$fxAXE_oSZA8}D6c+`Gn2_PuF*Nk{^nS6N1LVH;o~hx&k!{+# z#~xMP0V!45Oa_a3^zAsH=M_$gLR*?xua!W4f9=lhi&d2JP0}!JGp|j)P zuaNr9n~af(6L46hqH@#m`+_@={ZAa3m+>WnQ7_FY8{AgQ?+{i#%s!m^p<${ z@h$6#0Vm5)IcJk+Ec_ks*zO55Z|K*UFJ7m=`gRysYR$6E8$TiK$zQv?GD+uk*O~1d zQCv}t7$$ez)`92(N)o4g!}lzJ?>_H^l$sA(oJ7)EMlyvWW?tYFvK@Yf9C-(;#>c^U zsm}7U)<46(uz7#ZvpiG#dSB@(tCaqcUR)wEvey{KadqUmiMzpRzx|K!2k?FF%5S*l zmkgC4Z-fF1vE95rV_n)k_j2S>lCF8bU$j51qx))NJ{*U;Tq0dKwoNVy!{CRY%l@K= zgR7hD!z&@+IgNg8=BslI>6XRruB2w{fA-)0%hQ4iyg$hV8zlEuB2^TMmGPD)=&k2a znI|22w(K;v*h2Ot{rjTJ|KqM9iz&uytLBM|*?6Ro36KSlYO8KZg7S+E4oFKJjGG*8 zHR`4bG_)KKGNP$~48NJ34<6LutWv0ZV<0^DJS3YbJ6x8RH@~iliaMbL?)o041a=d6 zk1pYXFPAuGfhpX*(vQ0-v5-O!XLvH>;)U$ldbN*H_kJdNgKPja5^_&j@QHHC-d_?G zT@~6MlL4Fp=&223drK$wYe(F>J??)~X3woR{XCmQ>56*!19Gn#NyAZEv8J}?P`_S- z#eJad^pOkR8xX;ZJX?SPJ`s71N!?VXRip$uU?RlTu^1R7f|=QPZBQ>@xNI+mmZ}nP zWm@~LJ&mgMpnN939@2EImGLXTL?!{Q9+`-+)w7$kSW`^|t?oR!xkYO)%G91v+%;E_ z#jU!A)Q+%tth0oFRcc1y7jlf#(oGq6Xh{n9c;Q`_ck!9Fam}{%LA#2H)uCJ0yr#?< z>jFvr*>a2H{)4n`tpB#)JRBafM@F|6KR-6*lghX5O_F-gNU`xJMKNmutCZ$duktI} zjV=#f^SpL4J(YGgkvc7l5`xVQs&?Nl?^}yg8K0E;_nQVM63%u}RCj&hVz4twJ;;{3 z0!ZW@%_&}P+d0{3x%EwcU_Y;Lw3q#8Ty-0P-`V@A*SXuj z-^bt!ibtZuBDr>-ZMG>EMhgY>tH%xrv92-n4%p>jM zI#9xsh8oRF47SJp@63q+_x_HbQ>oO*4=7>9q0w6cV#hzaySjNkt#^oFY>;d9Sw?oA zH~B{5iZ?r*az@;w&g8bgMc7`Wla)D{WTe&jx|Ah!(Q3Xk#Y5$Txub3&ablaIPoxp} zPAFzuVIIlNm)lYaaf$vk7wc{R-rH5zZDhsDdjeT)vQH3alMDw5I-=+YeZu?q(*Fcr z2jgfs6;og>U$)P&&0GA3|L7oI)x|73{MSw_jm^Y_fDOE>$BTVo=$CgWO2TD4DlV zBOWnYzC^b-2p3nRF&{!$8t+E@qzyDaaa+9yqdH%)ct_KQ^56U|cFfgn)*vYThf+EX zkQ^7Ld~M}Eb%Ud9`_Dz!Ti>aC&hJ;y$OqFc1OcGZz-1P;Mo(_P?aqGpKZ&BNM5r3Q zd6e{DKe^-44$q4%)XT|NBKRPPS!QEL;}khX+hpabEm>om8vN1dhJ52A*CVpL)sacm z^shf3Y=KD|`ir=&o&Qj5m#F`-ApMWPmqQ&$Jd3~inbn18oxD{^Xc~!W0P989`}@d{ z-MMOfIr)q)?A)6?@>jQ6JKN+Q!ey!u!oOtJFK2OCj65qoip3b7Uk2xu@%df0+C07( znQkNoS{&eD<&clk`AjqPCA3l*nCb9pg*5Exdmi4VBj1vP$1YI)x#=H+`_kV(L(mNo#s598sQs zTC*FK#Z8tU9?oOz&F62uny#21?{AH7i9~MjA`c-IT+yW@^1V9=8mMgHBDv1;^3e-v zf-8?tMsH%CWDAbrgYQ(hT${-A$-fFh445XFNQKhQyQro>sRt6GYEZUFLBa~=_bwZ) znI|tid8?L;Lk{<1Z_B{%#fPr!R)zfWpQJi7QJT;F`ipmi0&_eJD7vUL2u1v)a2H}M z!{zPfP_<8{_++ob-u8XCRS7z+;rTU5lwBzF&>dV3QGtRrPOb zN}D`vg&VQHZVKid(r&_L^`Qd!;CrNMdLxc=alSo4i})I^eDU-{vrp@}%}}xs*wES~ z70jC>B36QyeUJ+`hMf`?G!`x7Lwqe%Eg@{Q3F&=jm9##t>`7K_WLgeTHxh|_c5%`E zz-puVQpi<=@K(b&id`bLeMkI>c)h=fiSECwJStWykNM6i1ANEcMl>VZ%ADK=|H3A4 zWM7z}O|S028Tx1SUa0}`#sc@A!Gcp(mD$UNVGgS1PE@7EYvj3bmZe)PS&r-ssyDz= zIq`kgA<85QMXIzz8_W0{icpJzS&h9oFWxgmus7k7I>Pp@u4Wr6Es=4Ba#;CKM@7#Q zKjp@~N#^2wb=|&}Wwo1vKUS?Z__mDf46O$02`lZ$r7f$U>-P>JzpQz)v=>p2QwC*n z?%ggBP5A4n85MVSu2&C-H;(LQx)gGK((LBhAFA{Rx~!);uUA3#77*-97aQqx`wi}x zR$--bDTLDLc_IaI`m=sgR8_NRG2(~(86?;HxjVjSM{cw$Uav|nQIcw+br@amA~-oT zJN1GxAg@)@=%YTJyl64LBU;D9dH-5KhA}!Tsit~jtovkB@w}j8c4Z{E$ps*`wt%04pO*RbrGFzr z%c|hoDprvfVPRVaTYPogb`7@8W3FnHY?`Z|`eF*;#QGbRT1(qE`?s_uSjph`8OJvZ zUz9ioJDtYRS^KQS6S7x$21dU49aHgK z$j(cbmbo%$&KU&{vsWOfCQ9hebrG{13AbO9(#lw}TMNeByz!km!>t%oVjft$ zODi8%+U)h)9k&SXpRskg|NDiETUKoB`N>J!)1BjcUv=wM)MDfWf;+QG1u$sKl6rPTYkAe+9cR1Y3<4k@tdiM$P83skIM7ThX{mD>bA^lx6e)Sbt*iyqs}GRU$tI;1*y=_qaqoONI}zK;REupU!1}z z*fv})bqlxU`gILgQD;hZE7`=)gzm83w#UwOggM%#TI8>zZ`msGl@6FcLXruT;IU%b zmXzrEyB-=037K)C3DM`DFfP(b3q9C8ztcRWDxLP~_L< z@-1y^DCn`w10}Xa+Pn}!BHbK;^EOjm4}-fW)iU(8a66j+aj+dX)LHDPsB2(YKcN`3&Q)DR?#D|9c z(VH0x;=XN!-L)4EVjnB4(qpAq>yp`G399~(iZEU|aIP81P&dQ+KPT4@*K+paj zya%qx3%FnCpy4_5s_-oE$a01~6M^4t3nY(H#FM_@d{6hzU*6qvtd)IZ;fIu}__y+zYUy6P>@)?a=z!5NGhLWwP<7<=qZn4JFkJxgV^?E)Mo zOk-Yi{vPXQb8LOPwrA{3YsoMeNAY2qrh?1pt&3f%6 zV@<1rUF2nN(B+@?ku?W=QmA`P_^p({RplRogQMT6*hzWAo=rxRwrgKeRjB z66xh|p{D-A zJRvQnoVjPmtw2!~ZaxX8%svQ?VD;~ZKQ+od4Dz-xlM!UlAGqx-w`&Z3AOc0Cv<)lQ z?!#0Tux@nP(@}lL$?{KZqj{7bZ`+!$mCp2~(56hh(vz7Bbe&KmFe@CdsHlHo1RjR; zhswK|foP!kn$`v$^`D{b4MP4{enZ>CK!1&gxP}{iqm-=cwc-Ubv;FZExjNF-Z<}tj zdayn#=?|h`uNC~sNHn%wSN8JEk`RR!oBeW9-2Uc!VUrQkk*80I-Sb>8(yYzYpYi0* zJS+>7Pb~IXIgm;J6GO5SEE_qR%=RPur3PQOGl@aSq#DCJLUTfCmQgZI>on2Z1!W@d zN4TnK4RI8n_D84u>Qe8(eJhhUsvD8pGO3`f3YURdiX}{~dA~M?x_~P-npW?$VsHL# z%69L*j)OpSqS*U4rCyGJ#qLR?zVs^)ci69&eSFYA1CoN+yjV6%DuXASu`6AL)S06< zf-YS=6GsKb>|MCurH-COZV5;+{%c}oObt}7jNe{)%Ot0edYffe70c<}F}fHaph-d0 z{i_Kop>pl}3E}BgbWnDQ0a>erb(#3_@;IbT#mF3w=6_S@xQFfo=(H5-Yx8E$H<+vWi`WH)u2S6u3c*$z~(%{_Qn@J;|(F3 zZVr%_>+xXdGGyBf$U)Y6YHmmVXys?O~+OgOPi?nM5qw_7$6edZI^y?o1w<-e$ zqsU-_=)b7g&U_GS6x=sA?_C+>AM#f_ zEGq0)4TF_wu*$TK@R!@ArZp84kl(X-a%Y{^YeWMj#x70jtSCy;d>;nTNvr2om!tx} zN0a*U^>H$=w{mxX69@FH;+c@$z#QF6TA;I;Ymc3$Zp2LS{RcPGBWA?uySOiY<|s*@ z7pn2IB!4R@+i=yq-7V!Sc9|iSyAVMbN}V`do)J6GycESKv)H7^pT2czOz`AB*^9jI za??feVzyvU9UwNf-y8Xvqj^;093b09BMwM z#j^(eyH9O%SmbOF2#C6VO`gVliiu$CXD!vkHcWf7@owZvcbSvsO@^QAzXM&SP-9x0 zw_mOFKHygRIQS#~y4{U|6WdY~dvnL@@1Cjd97^V~It9G8ylm7{@Jm=l9@BIT=%qBv zx=c1bP>vF6k&Tzq?#NjE+s8M2)aq2;ttDbL_FV!O0q>2UcbV_%-q$&McecrYlQeie zQyM;+WOeDS#=6)>n4DLeq>mT@-{6oJjsEU9ZjX5vG?G3xL z8%Nrh2HyzR9l3@x@D&C=L?%b4_upZ0R_CZ0dEQ*AtYdU|ERAT*&Dnt78GkJHI>U^o zz~~30RUk52JB{zr7I$qng)PcK%i{GHCsG>Y+hbKG>=(vAwxb4HU7#5z)((0PKS`Fhj9Ao=T&5En|&XKZ7ZfupI8Hx zw2O*dZz|~$3*zfDjJ~nH`&#Z+9i6uKPm2Li?r{(RKYXPTB)t-Q-`4W5)oIk@?OycE zoY&KrZnX#Xl6v+O`~WAmtgQ^&iw`FsXzwi@uCamlav8gudriPMBEXc^&Xe!LDzj?d z3#bemrhATwNjA1-yuDfX9Kz@F6H!9ub)Wojy2S<#(NDQ11&*jzd=C;i_#7=$uOXnG zc8ogt4*6l2y1Re4+?iZxy_r}PV&(YsLiHBR45Bs@wj7jQ7@A14v*Mnt6HC*T+=DtF zRUFXDk+sUNwr_QmC4OoN!fjTP&>d^^VX&)S&M=K`CzsU|u;ha8JWUuJo7qTv_J*&kJ|cOt?-pzB3vlJuJy}XZfG(ggF`DO@2{qlv7IzyQGI9eKlU5L`~?)ep{$f zRJ&*`f5y?MAgN!)Yl8EUL!80~@*;%_qpFJleSR9gD=!bIc=?N4 zK4D+V42NZq(QC(Tt};6cSr>uTW+#&B#(5UlM8ZuyYf|KSq=@?A0HB4<3qyk3VSfCd zX1F#ZdQ0qI832Lp4)SxKUyeC6*<&A^dYBl;Id+TRTkv>gQcb0Wn2AQn!iIi7GR zfQ4V>Q5m;%0WB_FLMdZcf6y91UM94v65E$Qhbc_2(EkZDW*>bE_{Ai46NFSeFWTDgup67*6KECSPZXl{xG5U4 z;x-+4`-gom%pdP!$touODBj(9kFxOa24#ce3dk$CubJ5X0j3~Z_kG1xc1rQ6RV;=T z`hj#QAaryPit;t4Tej42(MO%H+g^!hlV3FPuw^7JS!c99jZJrH%bvYCcr)8=;cbKl z7#Z93lRN^UA*q$n!zhP3HK@8K@wXoG>-n(xK3zfI5ArxM3JL8M5x#oSJbw9CW( zc-sMw58y9v9Eej|IhlRYp|huS%tWHde^+DbnaV1BxO1(7M! z5US8gQeAvToxw6SIz~=QKdVJRHRQ-438ZjMsO9=r$V6V2ec#PwZ7PRSxiQeXfN|L& zAH2|eE5u1CjrdZ=tNzJJuE6_Jnw$~Az}v3W>?#B6D~`FXtv6%@u{9s_JwVPMYb&hE zX`~Btx=Vs<9ir2$`^>WG!HRP;*YvY&IDpLjmENHm1iqox!8c-dGvvZeU$2V_(-lV% z7T=D|W%6xT2Lp7wey(g>$=Ukxy`PPdC9V0gByUv@Xe-kkZ|~MKPEeS55U?z893Iu< zcjOXA=X=(t=d+Zm7;;7Q-jnh{doQ`x5zZt{?+bW0O)K~~moe6zkY}GIMWg#sE%qTp zWj*a>AScXtB&TD)fOp+T#=_FSY(JBKV1L|5Cn~y3K7MpDcJwdb{$7>tFK<8Hhdye+ zmRtJ|Xg(hg)`fn$90b7*woKg9G@r4MGi>-b8@g0XMxQo=wOR&L&wV%;K+;YCxXfgR^k zNVE^hD7T%;RU#rzo9)gM*{LzDN_o>H+O_}-FrVPL_M}xlSk&CbL1R9rrcrDlE8Xs! zvum1aI$#B*uwmMw#PU3c%*(>E%9Hf`(XAMk<&4?F*j=Iw(YkV$p&;Lr58Ig2x>i90twvfF&*YTrI*Q{wqL`} zJ)l(^Fv!d@IvUyx@$MG)bx=I-J=HlsKYeQVDx;d#;Pl^)r%&dMF*6S9H;pa3aT`AP zkt>4y$dd-h1WD;RVZD4tl0V7_2kch|9sl!Cr;6?F|99N*#T)qVfSWUQAbs;YpU9G< z(_Ef+bF~K)nv1@idOu~P-0H@Vw zW33GMK;|A3rv6Xhvny13)H3s;UDbK71(+WLZZze8me>Y5cy7`({+z{YxOutAQym+1GubbTEIu5zn0tWC{lA`f{rieyuKJTB0)lM#rI zsxKuIByGQMXUJWI=367i70qTrl&j+|O|zuB#?wMNvg|Zhch(EtJ8>2kqykF}Xq5qKvHC zHvfv8A~z(NH0UyVKZvv~^wRpTo6*U`Q8U||4=WP9Z+vR{qe(hoMoZdslB7Je4>)>H zHCIX}LCXZIyCx<%(#hrT(HJ1U6b&SQ@J8krxt<*gwbLS~(V^V}yU3h{gs(|+Y|xEo zwx_RE+C$v4j3Mji^k~;h{C^87%;BV#NJBrnUEH~Z{0Sa)MOfEh_mib%@vL3)SVWEZ zbu@>8HJWhI>9n||%n@qK{3yW9^|u$(*FRs>40}J7Fz#(#szzIrKyO2H79PF~v$Xm7 zEN+xn*_CIHCFi==6aCiREaEj}GyNpdhmtwndvWteWvD1{lVyfhr2tD2^!Wc-01msc zKPRudr4>&Ov6Onh;3x}*_LBqJ z@}H7l3}m=_*?ZQKac*g&IYD?DJsFdSSjNS%!78c-X-Y`-)>OA~6x-$xxfnOx^W%W- zWpyo#^N5h;zYu&*4DoVM>i8{g5pGNcL&%Vo?xsSZX=x)L%`Hq29=1Pri(&77Mz^lO zqRP8StMpQUn1{5E`3x<_2)G29^mvGQ=D%eRs$lS+mkEQ{CpryDy%|}j-?axVcSSGG zF#@biIKnQV8c93JM`wwbZ_epwtBEs3&gq#AgW@SF+Q6!KkOSJQIy+vXgn-QmaPW&{I>7 zhI%Fl*Sbt{Rfq-t=+?~=p9QsI>%r_Hi>>*Q@+6bVye#a2 z=}{L<#^nK&5?bP|yO4@8@liqcY?I0QB(humYt(K!Z<3XfCC$(*4S#NQ3qNHqX8yIi ze~Hoo=Hzjdd0xc*cyfc3jyHMIddqo!GJul7%DdsTST%~K&z9bq&x1wl5S|Jn(TZ)S zXbHHK$-%n?jWyN&R@j^#0U|(y@0vESc)r-|cYtutmt1gpuv|);EX{6+y0;8MzIMv8 zXtQ#D+bvzasm|KKD^XJ?%k*{M?m=(68|2HUmi4ULwFu8|E2lNJ=<1qUi^B%Ui$ppL z)qoHOno>4yr*mz5-otOO7L8y~!ngZ$!}JqE7C}DSf9pl4-r3t5-&-*ZAD+#9NB4Eh z7vS!iH`G3IkK6flvS7}+gd;=Cz@i9Kg>g9}DISW!@uZc&t1g9&X1nI(&r-IEhrQ2z z!6xHMlm@9Af%|W!_r<~uPo)}Eqk-kNRYvjpB&PXzDxv**Ca+M83T zsc(5S&tS-0-0NXu4&1?1{?~q72M_p8`pSi`=-G_vK+;RogJwqvll3d1sZgQnH9zWt05sULUsv zs|a@yf~Zahpb$Th|!=p1ppyuq?qq53Nm+XANj^Zxl6 zrOa?aKsDewiDYYV>K&GMj2)}t@RvF%8G|K@uiaMpdD6I3xHnlYPHGcZD6E{+!K3+DU* z>yr0|``gb4!@G{y=(5A?_hij?yqng;`HO9d^=Kl>%HwRy(z(|Z|HBW-%!c&3GAIeU z_;5VxrA+}i{&3ErHxewi`O|GOwzTxHRZq4fJX&`i^=xeowVS0Zx%U$jwU;e%HlG~E zIrJr+YyBjGHF|#W$>AiB={XAvLY-|uJ*alwR6%1_8g)~s70pXGEBT>`!S!EQ#BL;O zVu1yg52KI4Pin0enn>hRpV!IRcYbfcGb9f@d8d55t|JI(NaoT2?ASENQ~G>f`vX-l z+MGv-YnZlVMkqa3F}f|{M&=tgzS!H~62_1T;kkY1gj$$0oy1}MBmXt0y0aNK<~RaoA+FDP!yIW;@bs8N<>O3r{ z7>aD&6&T9x2r}M+aDfEp5PPEz(Hg*OS4bw?Xm=w5yeru1V*f2gYG1>eq|4?s{(&8u z-ZQUV8QM}o{*t>QvA7twYXAH=wi(&h`i8ZaDbrG?Y*b{{XGD`|XyOKWpeCPOd*kzo zJV|S5IobG$+z>Q}xKWQKk3(KLoi}{wFn?8%}g+ibb zdl6jxXFswnV|kpuw9Smy{Fyb}PjH`+t3t~@A!mb>jZ*#=)+>KO>Jh^J*FRGKyK{%r zbN}ywr^A8Kz89hsF{c%LN_T~&i^)-vO+UYgf*(i-j{NoXP3gXJHT(mA@xUbXNYwO| znCbSebRSGzZcDlaq`&+S4O;mdh`jdA%rXGd6s@U(D=Eqj~m9SrA@skL~r_gmgk0O;yGal7N|nub~0()mWCc&RmGTY^c| z=B!TI`^d%j*+;MWr}_QVTw7=4jN?P+qi>b=jppKCGbjjIu!aoqaDaQ;S89A#5Z}?$ zo1a7#?r-&Fvm4hjv{XuSDqB2G?@NALg~=AuZ{oVTbb8io@rD$VXg|&0sxF-%uks=O ze$s&4d6(&3Ue{W!Y9^&9X()Y9)HL<+sWlt^Fm^7DXR77hp({hr2zsluc;T?m;v9={ zbypewlhrs$W^~)*nIWAHHBe-XJpiNO=@wCna8{=AU5+6Q;)|tPbFa8*=^lh-)1~_cX8_+P%SZesF3n3r&#w&! zP4hHiYVfMVLuUD<(^_Qga-Gvo7K`%_pk_8w)@^yvnb;z8_8j%Le#G8}TU3G+jY{`a zm|<1UM%CZ~CC*P-4TB@u53m{er@Eb%JIE8!PkDN=!$T`N3Rt^3k6yk8_P?Yet%3V@ zfWI5h`xY+wMX3ojbdXtyM`T_SC0f==Q1%qXGH~Anq%hC1pP@{;B4oY*#_wmt&JtnH)6FKHH8{i7 zeKbFuJbMv$86aCeciM zcd2hb5%yl+N{dcQm^^G*I}+?~e*o1_LH2YluWitIy)G&2gzQwz_D}jA29C2Z2|73spNk~B14-i4>=t)C-QC- z)ZTj@$1^hWP?0VQ0I*n#693a^dBp3kraZ(Xr_Ft9Trnmy8vlfI<@ch;ZJJtThSuF6 zSHkEHUsSHKw+QGi7=95wYmKpEt|OM|Rp z#I;9Lu$p{;6JJA^PE>L(w&Mv&&H|NILd`TkzfPVi!>+m4gB55y^>qet1! zv)Jt=A6JzBT)OmQ73+JHKCE*kMf>N-isRuUhrE>89o72nVE3;s;POP0`4CAbk0q0TanMG|F7so< zEW_L-Kp!L-rfJeyp55Ghl(7%h&5y1R3oDzx=lf`;`q3GOQ6OQ;+Cayzt|0V5~W?7f-MV9w-7PdkWV#Hcv zNz1P8Siugq54$08egl!{5`Jgr`6s#($KObWuN1!*a>CS49yd2o^6h_uJ0_2`uV}m> zlWBHSrja=|Vl$4^9>`agoxQpkk(b$$*brGC&VBJ}?0kr)fv@>6NO0*V;~s_eVXwgG zJc%qfm!TDGOt1y0a7xG((!bzX>KySs&Y=gZde<#pubCZE03WKR-S8=jXmKf}u^nJ7 zAelSLg?A&GvI$nb&*jF}n1rk*CX7Mr>$&`)QrCP*fzc!VLFt@s4r9Foj#>4c8w+3j zrH)5UjCvKu7 zkXq<~4Lv!iM-_4VRFj2EWJ%rarqTm10ji<&h1O;5t0JT=JC8kkgkmFoHRZ(*+nt)K zrc+mw-8A~e>`#9)hSV;Px6WSpXBtHbBk(iA#e8+2<(ccXKfgi$JJV2j{%B5XCK(O| zynX+dy32b??1i>+z500@Ob#|K5puppd`q$}q*v%Ij2w!J21l&^M#(4-@joEbl%i^c zt1mvi4vgG)4Xh12@qQN9L(`ZH$!xKh(7F6uu|BEwOu@_1D!%*c7^@}Zc0SnWu^T3_ zo731ev`xpyw=2rUZgy+)x<*V*gz}v(F{y(4e?7?-fggpL6 zF^tMqr~YEs$f?qq>Uw!d*_xmF)t7_{o96 zLg8BBy_PSx1XW`Mgp)dt<_>1!iKW7SIq61s{}TQyY9n04T#m_06FW#o8Tf}tlld84WQvvkVh(n`05Nx^hm!v4oqFt9Q{+pe2*ELH+Y%U`zN*^>k5x@>RPuQvEE9y`^RUyajCKex?j96S3W;68~pHVj%^Ct1VJLiVW4RJ-O!)a^M~N zcKi3f*B?9i9%a(bx3Eq zp3Rr_Vy_UcoiYx+L6{(pyO+{NXnPI#oZ{pXjl^Km3m&${^aJ(pYByw_iSr<}p`LN{ z^{mczsA}%Pg5YKBdUWHSezZb_R+D&&Ca~kxe6t_Js0#bxfi~O0Cu14j3Ks=~i(^HC ztIK8!XX%ec_bcDFw()pXMc`VTTjJ{W^F0UzF}0TV)%-R;YWuA40dWu1@fbV zXqQ9jOar|VYp7TnTFL#tj`7skm(!y?2A|B7_hdg4QWkyR3bNo^c!`XO8r`(}S9Ds} zFF5lQerQQr$1#s`xrmmb_|$3{EO#zHcy3tQsIN~?anbJgmIDyb1MBFpCRlU`|PkLzS_OGVT>2QmQ<*VN`9B`1D&FUqk zB;pfv{h9t9sdGl{+jF&Vx%_66PbbCYf#8Z4gls@`ALlL4*^^z>2v3{xKe=VU71Y4Rp}(T)y4 zJ?;0M@qYKIAgv`1>GhIZ%`Zb84nfqwuha%;0c^q}Swn(|GaViF*|W^=ZEE%L&DA_I z>u@%f1}1;uJl)4mpB{xpN2jf5e~o`TJ_+7bGw8qAG_B0dVY`78FEE1MCTsNgtpOFf zmqeRqh*ye_4@io#pWr3~7CnHctDQ~&f+{B0Z(?)fP1Z;iw6pI|e6|-H?i@t3vS9+F z34s0^QV;zUJAfSr0{!efy~rd4T38 z)_|Dm_b*D8b1O}L32u}#XVsLwZI{llvB^-z0F;^DdFfeu9)3M4*YSNi7r&;Dee^QH^;`M)#;Zhu>WY2 zNmcP~L$K`_ZQ!5O7_a3owH1UOa2ETp2{|EnP zJlO+YyLR5!eICd0K3)r2`R;&x&FSLr0{u{Aq<;63WPf8>gQ#psLD;o;a@I+ z$sgizu5)9Ur7-}uQa*_XYMch^_s?EP{ZgT({i1R%H1^@^ule$naGNL2uLtCJ@LU_rd8Il=1 zYYCJXiixg5!?oUF)YCf}ZP`qfHkPzof=pvau(I$1<52n9-uic0IQZpOC!}Q@-^C0I zufJ8=IaXhZ|HILhtLx}*DI{WoD#klAZH-R#Ao}A(!ItI6o#pGj59?0K^t(p&?q*Se z9*zkD10j#DzJ~Qy;&<54la3Dkpc|SihMu3RP$j%q1K8?me%07zeB0~yhb}ex&ZA;- zFZ*^P$$_YOH;wezK53&2z4mc><<>4`Oq8~8V3#hXTk~j$y>!uD2f{h%=e8)uXJ9zov#3Sv(v#wPQsyD^ z(V)!OAk$*fb&=?nagk$JojU?rFr|8sj9pH(43H~65>Ify5le8+jM0#uzhANZ0gHbR zVY!`Tkr00ffBVXX$+o2W9TWr4s^B7iUgkq_-KhVdDg5JuKEC6>gRaK`!E-;Z>I#+q zt|aq_9@ZJw8;%%?IcvU%SAe~KuJ|vs@+8@W25i|$GW$6qvyaaFk58u^v6&Q09-&*N zFH=7Mub9qOO_$~X>1Sh7Q=cvF$n;!|sz8T^c&^jgfdYJanlJ5euxsJktIORi@!J82 z4-&-#Q|E!G^jc!{j(p@dd_wD2oe$O(Vd|R^D$bnT%NvY-|57(XsUr_qLQvHd8hX4o zO<#mDQ2>HtLB^A&2#rQ7`^^uJkMx5*J|gZ173^q!WNot+u@JU+@%0p@*XF;B8@r;y zL5ZUuelpN{V`K%U;L%I=$6@*2W{HujmJbY+PSF}6%=S!v`-cfvaoLe}K0~!-znU1> z(8;l|5Pwa?eO}=0TkW^m>S?};yQ>D^+fUlGm>KL!T6Cy8q=oU*n|}Owe2d7=X?l@$CX45)PFyRsx0u0R3Evg zL!?-wn!Onrbl|Qx&jWq0&__zDpnPvXcEIkwi<4Q|UCz9|#~S_;-e17hI3%yD;w!Du z$%RQ+L>aTc-51e?FC-rch=m`VRVVGLt@WuOMjH&hcQ_~8%+tR#T}`?g7gaS|QPQv5 zeGC%MuP=w2rh9BXBcCP*Cd3FPv$WCy_%3OM2Bb8e*JU56lTGbB_Ew$W$~e5GOM{N? zF$k)H*`dN@fLa{qDRIt45v%OtDY8-KrozUF6za|+@gwWgw9WPZM6vbyjfa&756Are zM;lqa67k!$mR=_d>C^5=UBi>O+YG(GHn=|!eW3vyv&TfV&1i?~!+3S-rDk%v{#Vr$ z{lfYeJ!XPl?Dkao{`8nu6g2cJoh={~frZhwi#FSdQy2cenYyC7b%3pp;A|1A9r+x2 zk&$vCTQ0~L5oYlFmwdk+p-=z2z;Uiw{+xOPGUS3Iw+hG|E)18fFNIG@BPW+AXQNY< zO$&eW(y5aYm~GKWiaoA;uK5J8XcWGrLP{2NBd4CeYA(UmkM{7e9prW;$9-H&e zFD_AJh3Lt__dj+voH&T~ekh}9{(-Js*dR4T)hNF!6bzUp=#BitL@GeA4S@Y|aCS3< z$(D~0Pi&ryiAfl|_Y^-`TBY)OVgGEisPRpNLiDSMG_<;}PQPgvnfK&)S@ij>yuG07 zG_AXhS;1@-s#f8^c+jPnE*t_!5-)nPjKKN!LP0LVVN2TkBd=oOWPg6%XT_hz<(}h- zD8c8t>L>&as6R7n`>njFJ-yE)6I$k^6cyueLSVJN`#x*)swAcr^O?!Sbxvt!Pli7WLg%rRBc-?8~S_FKq*(wJg z{k^sPxvFO7RHvkDRNfS0=t}fGF}L)47A~ra95Nl1+sAhs?Xz32XQ^DEFJ#p*(e5@` zm*Z1$PzQh`7o%Ih{vKf-PMkPRP0|1#pKee0w+tnDr5K!x%icMwJlZFVp~$KJpmfdp zFSdTp`D=8kjk&lrZG%?Lr?{HUx2|zGOsIKR96MUN1xMe-9Fz@(wZ5atDsJO^9pSr@ zu}8X>)HmAiWb4?IOOBYAByysXUdH{3ubRMXI+Z%|ouawYo(or;AF5d?P}<{zgGEh5 z`ad&2etlu9He)n36j%vd60thHpyf-ej9d|98K57vy}gb)8ecG#E&+#Lpm`+YoOYDS z+{`x@J_Q=jRPzeS3+M=&t-Yg?rF7#yyo&qae%Fw(Do^IZq$lJGMP_-T!@8#|SKYoh z?G|xyY!&%yI0(9NMk@Y0dW_DqcNG%;B8w=8^VHciFA4^-YDcL-1-c0`Baham3y(|J zZJLREY?-b$i{y-;-5wu0NMq|Qs5d*<3+XXMH^qLX{X+RG#uf|^k8c_AfFrT=6vF8B zsAR09rcViSO-)dy0v)oRM&|^-vw_EkB(OpF4RB*;{D>6vI)5blXg!^@7N%*6l|vG( zJ?+T_r~-WyNN7n7zAWB*U%T68i|~x}reA<==fgu=J73)9cFGy}Y4%f`R|$;Pjv%IR zb<&*yEuA%YM{joPxdxaDd`S__Oo{o`_B&#GoL`+Nf z5t`(OFzK;gNzVeju(7H6ccv`!CW^D~r4|!6aFs!bBaueQ)@fT<}har%5v=8=F0>BLj24Up`m4n2Zzq%Fsz#)MqFH(+`jP>J*qe5GSv{$O_R$(KF#{1 zR&SSn`FG*noEaradZ2*!#^aTtWnnjiwtV$|)40$=w1FP>f$5*6k@dGksV2U}_am85 za6!Etqhk`X&BG!=e;ukDw<@C!iY(YnpVy@ZqtUyosbyz^uP(l^i0-YkSAukmW+xnaobH zA(y;?U&Jz{lhU)ggsB14StZ4K@AB*e&5D@4oi*k4Gi4qa9uR_90Mo1L1-Kwjye@~A zL0MoVioE^gs(Z|jclWE<)oqW&aR(sO9=rzau5a6n3YEAzbEij+;&fY(+FrW(Bk!}L zQ?-6S9NQCc8SvN=vF%?U-yC1KBm@D+56|VZ;Aan-s=Nv|UpME6p6e_GYI?PaBktxy zs)i$N>fz0k_hZ%o?0*9y1!7vNDuh1#mzT)ppY{~W-F@_2DUpXs6b1-Lb|UX`e`vs; z#X?Mz^|awbSLgZ0JZLCxH>{st1d3DRZc;wx+-^kMlKwW($wiP@PV}83YYfd9gRQ8w z#OX?}xe<`gn~@%=pZ_IM!sk&_RsLvJ0=wnuX6SFv34UlzL}ylu%!5fB1g1E*kB}JI zeqZMNBVt+Q!(T3!ssVLhxYMh)w^NVx9j=qs@ez{-)4NC5y=xBD%%d#9=LTtSWr+46WL`}diqOXESIs585negX z{X^2~82!5Sx50Z3nklGYfIg`ST}QSQ!QlpYVf|U(!IuNk;^NOm$=#J9LZRODb6^Ej_`1P12Fy_9x+eLEvM!*jj zBuxBric@Z}65b=Oc7-eI-7aJME*A0ie_#mw_G?{vj48p*sn*Vu zzn})H2LI#BhVAh0w~A)Iz(_UP8W@+>EP~oIn||R~6FT!Xn+d88bmEvHVU@kK-%W>c z(-47gPkxv4?Nwd}5{fQeAGf{CvHSlMtUO1ETq-azqzEV67ecC}kp$(=&=vUzA8Mdn zToaODmE5*&pk@)djaZ1G@c=_x7YM z35;66L%C`!3YJI5vDGzt%SYJk$4mlFVap|3`o23^2`LdCq&r9^Fzth+R1#?sPeUtL zv*aN`({^2LbLaUbO|?Tg9ZHS>r~UHJtcyo5Tg+&;&Vidj$P?G;S0msnS7e=*)9iQ9 zP^=tGOYqRe?O*6*xwtMqeEU-hY`t>EaX7u-KI6;fMlw!Gi=^L)3rAq2f5_eZ13Kbr zNW{J}3?0zkRTsUTL}|A7$QBGsd0-FVa{*oad_V$4Hhnx3H6uPeC7M+XcSe68I^!J~3Ft`*$eQ*0z0&k&U;;I;$|F+1L}RXpTShSI)>BC84BuKp8rCNEh49OLo`!hX20do zYL++RYKXg?n*7BnKWh#{*!8p@1(;*!mPUjwr0q~2iOIzOq8_9j+OC_N?PjvvT|JdE5>-lLb`k^N?w_4L*!oYS3BTn5Q<(d+J~8a z@jlWf4b|T^jmfKovQz{zfXxMBPJ1Rw=yh6KImzBt9Wa6>6(!Qnr>YB3AqH;pet@_U z<(TNy`N~sSlZrZi{x)Y*_SRBDz~M^3Lf2e_{ihKvp6xDeJgxGoLG$O0?aGieo5L&~ zS5(kF54wJYU=h2p-F4?a7o9ep-u1u|T9d_v=N70gspJJdb4ag>Pj{$FWu3a|T#JCD z7JA)Fd(4L`)4S*`^bNei;4x;Y&{^?VD0e8Vh15@%2+vUdD@mxecuAIvahYX@ z7Oodn#!1uPN?~LEy^mi|kgEQMh#x9F zFQIRy#8Pm4vIJX%BFtMBNvcRSpaC!MMDsP{;$@m!DE*lF6d@zqwYLHWjfu?n=}#Hy zD73tQBp}7%D9&aHMR&H${TxFyb(-6Bl-zxR3Hg}y@$lnGo@Wa2YkO~Zcjj|=ybnd6 zE1OBxH(BXrpudTy8t7{$KG|0>J)jh_65W0(B-YWPL0fpPL+4prA<+0eB)4y)u<2iG z<;w{%{eL&;VFj^mcWD2$4Q6-u?1@eTe3;zux{1#dogXa(Vsuex=wSi>XiX5OlW(>x zn_CGiM&=Jf^oJ!DtIjBn3ZqjKgMnJ>Z++PVmb-5zl}7+19A?boOr2Z9Qtn{Iq{5zc^x#B6st)XVyXE3iit5o4$~ALF>81Rbq+(7KNGS zlRgGMAD6tl_&xn?2P;iIJ{tHrWurnRZnoAn#P6gxHba~3hK0V@FFRn%;aaXxceJdx z(E{5QLr?7hl!eyY8LR8=`>X=MMziz~MfUKwV{3xw+AZ5Zxnl2(Tx#BkkEuFaQ?Rv# zW3m8keyU`hJlng0z;z;tY~D60+%qHi%^^OR7l(?eNB_7{hApGwO1!iT&veGuiqpp6!HNs zfF$lo^EG*2_vu%^UBcH`C0iprFP1M%Cmb&no{(5vE8x)8=;GgYu$v&9u$6zikG~<7667QUjN@@!0xr)2&kw+)-cC{KQqT^4lUTS9C>_L z|1(-sOLs22o>u8{f44E=*<8{uyD`b6L1>0hJ)>uBlqDoD?=O&A!3odRbA`aX~mI-wZ*_qmDT}OJa@C)xJj2_vgnYF z_wAyeVEbvh6#W~GI%5%g0oH&Q+80i-`XmjR(qp=g6w0srRI5_}bV?E+`TL9A$E9;R ztRqG3AmM3k$cBJq^)KQ(j9q4lP*W`K5o>u|4TZG^Iu8=O`!&K762N?_PquHw*frX+ zwxFj*!FNp-kzz7$Bbwl)8#&}9-rV7PU%X42<++v8P3U`bK_>ABY@$DRl3yrsA7wA@ zeV^sIhFVK=F4v%YGBOt%{b=lN{=`eQHG}O>vqsLU*h(wi{FYjb1ea0-vdGac^hEn~ z+YqMWs=tu_j?`d=QGeu$=6aQ~`axAPn12FBOH#t-xK_SwUOmiBJm?|#cQg-Dl$(H2 zUghI8NxRZu61=G@vRs2cV}l;NvRFC(*Y-TdC{Qmtm5I~jLNqobWd_Q?mzaFKn zIbigpdYy9P@DGFtEXV8aJ9WMRJe0CF5O2Tm_7#FKJ3_N&d*%MPHc#mL$X}{aZYqo_ z-xA3=N3WRBCEG+(5B3SVLhruHH)XHP^s8fFLo0hd?6@WqP@m$qvA8ms^SS*L=uGXn zC%RdL+F+o(k6<&rZuYqNq8vax>L{}-?a}+2XWIJLg4}TDn*}!TQL8<4-r4L>+Ij)g zr)FCv8W}mbSe53z^VNL|@8lmsvo)VRIHE6XLRnJj7-?G=sr%i22j(;5HR_HOTY7P2 z&wVEgqC9^uGqUpeX(4=u_xD7#&28n?Ie9Ljlda_x&+lj5kDaVUfWF)KA=yxI1or=#lh4yzfj8eXbV~8E8c! zHl*mY^R1Ds@u|FnDJ}y)49s0D0#fs}@N)Tx$!UA4Hi8eYupyK!bAv4d3%RBv$)p&p z%iXBvWZNu`xX7I7ug6(`@+2eW)qAL2(m>b|IzYm^L1M=Gc)(sP8LSaQaq2rpPIH~! z>#gq`9_Y`WA=6=5IR|nzfBt`KeFiIxz!v|&1 z+w?U(WhRi}`sh8C!!kr}8U|1uI(z&oWsto?>q;RUm8XB)D<_q;pB!f-1XvM-QrCqE z1iCuL6P}h#ZO|ECsofp3l967!u-QOn{H@R6;aKKtbJJk~m&buAS!PHg+~>@|H}sz5 zLcxtF`5=>U&`?G&zL16UWIwE1G0Xd-X9ThhrF&?*So{(&p_a?<6H+HPi+@H?-n3BZ zIxRKzaY}!70`UV9BX+InmXOh&Ti~WZdY(_4>VP=blP;;*HpsDr)iV~bxtCdQYqar7 z`8w33{{f+Km|nCubC^Ne9v2M?zS2RrPIlq^Lo8YzC)RIquCqQ&G&@`vdKzBpa9vGC zQzrLy=TGRZ>_JQRBdisW(dbxI8}{s&e2H0q{JmmkNO9cKp$e~c`c4~bCxwt#E1gP< zDL*VTpt;NKr_YNf=3~8@pNRI1k9Ers+%oS9 zeEX(amyHBhUv~=zPbFgPP~o9-R0)m`gJekGO}R;tDIug^jHg@=B8ejuAkgwU*KKtb zhwC1i9oLTu?UzB?9XhcT)r#qn_$3CJW6q%TiiRr5Df%>e1wDn;_>I7gjk<^1L6ZZu z66zmx3qRfU?VuV$_x@^f!R5&gE|@cCk0%&AnMm!fpH6heo!&MMsPaI>5f-Fn>fo14 zTY{K(=N(sZp6N2@oNX55b{4s08pvG~{HH?NQNct;gDM669iBEe+i!5W+1 z)$of*peT~-K(v6#6J(j6q%Tp{0fW#^xfY4+d8h$!kfo?IDZ3GIW{ktD5wqAR<)TN<9~uSl zYo)Q09U_`svnK@KKUM*#^Ht-x;12PP8G=)9!i8UXiKdWeiepWNnq$DNisT_$-| zN58Bmv&=pYM-EC*C3>}c)jY1f{~`40Z^sFDbE;jk$|?R^WU%w07Oek!`G}4tq19VU zPNsUd6jAtz?iHZKJ5ag1u*yt@cY;DeP)K674s&Dv`A3VMuB!?&S$V)|S4|}8Ns9y9 zJo?~chpIP)q%nYxkqj!kRwR@#DrvFC>%rHse~xuzH-Nh0agIU;e0+?}KKhljIe*l- zV)a|LHF~x>zD#jRTd1M$ztG-226K3}lH!8@N3OSI8;1jxBFOuJrH*}Cg7A?qB5%VR zWfiWeKfv~#ey*#Tk;ys-F*TMM+p6uWLkX^u?+wZ(r54PqmT7T}T#H#@Q8W8KNAV1O zE_!I&TBTkvCG5*r!N|Vi@7Cm7|JjW` zoE+ABwkARe21{i~|uA^Be@j$m|_ohlh5KHL5YQ_24~ci{Sc*%m)1+fkQ?5?F9$#09X*hDs+=c z{5Y&~kdWTnA$^B(U5wci%ngympg6=`F5CU!Io-q@+o%J|b{DWR>5DtHqn2INO8sgA zhvc#^csOGinc!0k9vi=+-uI8&P62I5Lp?~YiEO9lrjT;?E>h`7US2AS+x54a-Y{FP zoxezo;A4YdaXXEahq$Bu_hAMj(WDSLp`vT8xtg00boQtP$3lbeuT9MxcUwV3u692f zc2qkO&UT^x9kq}{M*52c;m0I#34KVziFp3NI;q&>9{gWI9Es2akRS|n)&sMFg^D9?q zVjIQ!Te|ZGo&Nqi0ng>duUEkbnv`A-cW?Q9U2MwKmRk)YdF!Z67TdzRD4%CAfe+X$ zO<S#3X(f*3EIZF-9+bn?p8A`+S7#ZjFrY?!Qc?7ixGliTc0ib)Nqze(L6b z%s%CZx@=EL#C>TT6qcI4*idm2WU@0hS!|-7l8mf$3d}DhG9Bwr98Vv*6b@xlEFpVC z?)rcp2OH&qIav3`(1sse_J(8!#CUo<`m z?e2Mmv5h;|;?&_~ayvc@YpVWu-7^zSK)#~}RIH(BtCC`lQIy{mT~K5o7vIZuZQhMw zb$Lh2M4|(D0W=GVV0#s0Yn?y!-zm)e6}WsdRkfQh5VPE&m4a&6B}uPPmdcWnJyc4a zbv$SjF5`*r4mtF?CFWTwDPMN4()SE@EVCIEX@wx-qi@AZ&w0p`SXJhJtO-Q5!MzO% zxYHMo+U}GrkFHMBqNTwwPK-nOdJeP{y~v|&gViyk4&M2>fsR9VN+zgCC=ASCCpFr8 z+Ci4`Uadc^VSHK`wD)9E?oNJ7?CH6Cix_$9%`S7^+)7Zymc%4gG7dm{FJsblYWQx} zb)lNSHoO+a{hMv{Z)tP#8lLrMK**1WSdCcgtj?NIj@i{LH1M=TCpiVxwOOG~Y=s!a z?O^e2d!9@7YT6MEw;av6jAY#-kL{ZVqf?7mg{?4=U1$)@RvY@D^xA6WctLm~GlA;N znrZ3B)2RU=RlCP<~5(c3ot8JxD zuCLu@7hhh@r7J8tk*>%3^Ee|C>kf88B7rAX)#r7~n^vC05yJqE9 z*pSBiLCAKhu+OTp{dkYE;DT*YRKs$JqK>ohwo7$h>8mo<`LdX$ifsnIBoN$_rn~ma z7(D|8bAC=K^7>O(>6 zuQY(l+eZF1ouX(ZqjeP~^u#*|FZYWdZM@+1&7#TyWAY>K)N_S@4<3AImy`bVeOH7G zoBwK#Zi%OBTz~%6#10LLnZxb!+St9?ii!sFIaa2bQ*1cWo@HQ!`_C(e;t2(N>qhr+6l|xC zd@QIe!Kwys*2Ns2Z-zbX?^e2bJP>dgi06}>-m<54TS#J^&Pqp4XcD@rG!<}o3?o_-9FHXI51Cjto7twI{Xlh7n<;_&nPhdyjoP@p-@9~c0 zht<<{OD4^0c3U`yIWWX2^IT{#=m~ijFoOXJa!POE0lmvR5fLlw3}EPD4TbhCu9y4 zdl@IzeCK2fc(FMEco0E#97fAsBBr_4fem3}G8;WU#Uo6zMEub@3H~#%cnw(>*G|*A9*Whr z`;3srT~|{R=9QWZA@`4S6J#)sM;fNOm^L?O^;g-pnGJA97aFQryYwdS8laW9K^E5* zAN#o6#w+(GDama;W#bAih{lFs<0UEErw96sXt4& zAyw*?^ZkE}-_VQpdkp2vMuqnO)^u$l)L+t;qtFIYJ$|$*@OXtHR_`a=NY}pvq#qIMYz45OK|zLotXwA??H>ag(Hydlb9+5MgK4%&>9? zJVF@)Ht&eu)o6NlUII6oHKGVV;vaZlD32*hDDt=SD=x{0rHIpW+OLsy{n1wE%>Q_TGk|ynM282=uruIV>m&%);?XMTKvc zcEtst&lfwyjHYE#q;;NMp+BQfH5YbK zO*;i87lE_r4E8#rl(yYg*94L`O7-<Y5CT+MntX;-?oD$({DS|c;jrK;mSVf zivoKgWKmeOSZ636D|M8GToyiZoM>m9W%abfu0tMAUgGrB`x>%~W}bine%EQP)N3iQP@u(#c#DbvCT%`>BDf(Lhd)DG7E%M_`W^ zXz;qkH{3X#Xb{BVMk3t2Rh@+yx%KTAnKkM<<*$rfWAGFu(RaVz>sAJcCvr$)&ZStK zo-W5r1-A=9#9NPAFF+tg=$B^pv(_1AAw2GLg4Jobu5xA8lD(*$;&FZ&M*SKe+&RqC zhdp77caf=%(>+FxYJDScp1*1@B~ND;e`QH%%#d7H(%?jCF2&O*s=IT)`I216*Z%ZZ zH5Vbd`%>2Jbg16zDFcTE(-ysp19?H0-U5`6=K-H35`n8}kT}Wiv=SmrN@okb^=Gi4 z6@jxHjWmk77x)$1B|lsGoZ)T9#4KrYpO?may0hCcMo*+fE4DR;qRy-B9b6fTdBW^R z9Up91VRQM@zrCT=l1yzcysTL{*+b0~Yrc|o>Vv&0Y!8lmQntzbTOzTyn(6WSGc-{y zP09>^$i#aN#V3Bu8??Fbi0RQE5-whhHdXK{hbEV1aHi+-UKOLnSWtZJBUyVlohQ!| zlPb>s*nHCyQMjxeXx-l+u~slT&?=G-^scP3kot5NtIMr7f_M4pfwJj)LYge$EVp=} z?%!_)zwO4u!lMrHviRexrtaQKbvx8nhUjsYlsg0NayL&;+P?Bu1%*EL=jrznMW^|J z*US%RW_`950a3Za!l{Jc{pZ*t5tjl=(NT710-miRmQQAPcADLZ=LUh9otLT4`ct1@Qdx9eo|zGx;ttY+e3srWzGW$4jW z=22tOfZ6r`)&YFjQH2dU4)Jojyb%bLX4Ien39FHl5D&{nP{(m}A|Fl!Kwpk9#E1%C zF=mLjgA4=YLs|D9^eU~npb@3{jrD6UY4VhL9rC&f?EAwq-fcHu>X;KuEqxI%%+Z=p z5tU(wrcTM+GMC~gm+FU)8NzV>-Ky7#mGYW(WUtD+Ss0Txm?UAO*e6YGKAThxQ9&}~1uE@^$HwsmVk41$F-LiXjM*Q-tJl*RS)5M7ks|FKA*k2jK{UFu*_1pmr zWSAM%sqP?Ryj9<45A07uQn0--4yebM|DduGIl=l@Jn-5;f|jOEYlOO%&=`N;aif#kur}~P_N54*>b(N|AaC%{}y~B7$c34e#exK zdW`+7{_$7x&hTv+>XZa~Ly2XvZYqCD@2dK~{gJ%bas>ywN9o-qYE8Yql zPkHs?HBNN)XHr^HV7~}8e(v&K@O5x}qg^N^tLTdLeNVrHIOg{<#l^DUD!*3qWYYLc zVK2J9p0~ZmIAv&(@@T%6NoGtDd9eG@iscLnzL4IR*<~ZlkldnqkEdGLpP%zD zY_ncmwZqjlE#vJht0@~hN-ab09Sh;bu5&hO_XNM_{`e1&Oyc4XkW^W0_emv3OfI%o zZ4eufJUcMyo&$}1X>YP|VCxC+HN6kdoc$QD;zLWxAJ=rJ8>BJF(RX}&8rODx+Oxim zt@To9NAkUPqZp=9ZGLUp+Bx!_)fn_fM~nlH8WSj)OZwT2(WXL5;#>k99XR?{?O#LJ zyd)SmurBZvP`=N{XB$f585MqFj#L}@JeB-UFMq&LCu>!Y?8SokHgTVwPt4r4H_3Ch z?WU)A-Ru?oqYM`e^+6BHluz{s@g&Zf{8$7m1094Qg?_J=Wq0!E5mpZ%xBkY*n}j!t z_tZD7=3Z%^nd&mDTyF5mUjC)QMEHg*+4~&e6(4zLdNDLZOyuOr(!9%7NfI+rAYQ`y z%ie7wR>SM>%u~oya!6?jhZKeO{@3pt;c+0?maMVfXE1nh`C8X~i-ZWXvG);-iHHYaxkayAIGaUQTHA8;1{JRT(Rp5K|83XGk6{CkdcxD+`W zIhZrrI%v73YPdohpb8?WVTioCxH7~DG;Nn0R^ce80=z8JKLfZdR3>GlC|~YLFKW0a z&x8=D-u=E=a)!i4=RV_W2lZRn@lzz4*ld~|7ue>PJv5BUiNFO$2^sH->=<2U+?5af zByH8bux#vw@c%_ZYw^s+h$+`Z$i6RxI`NMZilh9yffCmfDIDOR=WQ3Q_8T&0>{A?k z4#obEjQ`*;yL(QIX7CYV!2=r-b_x!?Qq2a3kIBE}2(4f9zeWi)&y(5a&Cy6dJnfTPOFM()qEhAavh@N>yj8$rXck7$7CLTH!8L%fD68` z%T$eh+1)Lw+%!CW)|6XK?ki=58^7hrxH~Nx*X=CvyV}ZE^!QIwjU&)Ow%xcQc$mHyE-1fH5@=#M3>T#Cm@JMVi$ch)5d%8Q|4)zqKf$QXH-oJ z^CZ>S@PJow?k<|rmpNjtuR)XnYI?LD0Z+Zzr+#c

DQ^FjxO4v8EjJw$b(&Evk-b+HR@CBu(t!ZiC=5V`?M#=&L79HswCoLn9Q<0M$NI&ye@ z%nb`O-o2rXnRcjnRx5^4eMXYICb?ygOe%L`!OxJ!WPU+n_X#1!FI8j}HuiNA$=8K3 zOR{l3F1IrVm3)NQ=yKIqL-mB{+a=!)VvplyTQAg&!fV21!nuJp@dw=+le3SizkZ=l z%R2a)*8WibJ3%HqUN4rp7(qt%8R3dV?}`GWocgE?z?((u;0Yz9$5iVSwz-1Tap|A3 z##uqe1kEmJk&0>bWMPqirE1&KtC5Lp*^QJ3{eE;QuuL!OfXJHEJuZgZ}j`EX4IrhU=~}YOII8&+I?-sBY3eYGxxk(7qc|hR6Gz z25qRz>aSyDBTPEqjRvTsTKs)Gn`4&rL~J>^dn?j`mewswvuFOTwGrHMB#nEVMp|?b z2y&^MC|kaR6M9V z`yrMs58c_sXLr~xzW!0Lecin6X?x?)-X9@=MetIkb(3rLq$~xIacAzA-fqZ$X!qUx zR51YN+HDlQyUZ0@-LA|v`8}Gg9!ddRolQ39wqD0*E_CI_h;uiz?B_<};{!*F=|b9< z1KfY@DxXR1sQKpeDJ>F-CQlqCYP8J2CsgBt*V0wVL21jT;yHAW!#LrSR$>Ql_n6ESE-yrWW{c|ymUTO~^JeYc`JJR7 z$0Yt-M{Vu^E>=7*tB*WR)^%1K=hpq3?S|&EW{s8)ZRyuuRCwyY5_`B8>8niS->H$I z`+M{+6H$Q1a%J^7XrWE}RdaPNqtDO6Rg!Hp&BaR{k97u#cR9@I&A&**ST`PfBkU+N z8ncAI-f7$DRRVq$`r_uctd+iY6xxlY7m7SK#oc&{=GdzJ1R;ese)iv9%HE}Ft`Q>p z=u|5rx%h0s{e~n)`Ftgozj{G&|06;-n*kG(+-xZTOmV+0=XiCrFPT+wMm*(aVT_Sj zReh#e1(T_Hchd2Oc&UedGBgLFd?wNm<@&fE@IDP~PW#o*061Dk6}pltei-GLNW3-c zTfLF{hDhkB&@IjLQ#aBRUiVeEHEeRU1~^m1=>_yPyxGgl`NhT;$g zNkUiF9{XtAmIfR&#eEZ|BLMwQy#83;T6C6>(+2f%V>^txR9mlwD zu-9t)L^Ko-8p*XvJ1CV*Q$=$cBKYl0sPBUT-;91Cy_y9vVyvRqw?!D7kVb>6pjY48C{- zeLzQw4OU}8#S_>ZV|Ty!d1Xr6)$_xw8)rWx3b1+%VEUa@|NrEx9DjM>sF1d8|BBLb zwhAFhVSo(ygmvLbMP{G-WR0*5UagWSWZ%^2_zNxHQ1Wl^Tl@9g(od4{O#8aQ>?67~ z;d4J3C}f*{D#Oe5o{YVwNp~2=V;QR@F6n}1r})P)1ew6^K}Y(&Y|ODdKj{_l`WlWE znk{2e=I|p?U-S)67UpRnnEtnKdiq2-V6P3|S#NzBKj%#~S{juk=HWOzqSRV#oGIj> zYuO9VPrKMD{x>o(@N3|gx3rnMR?i}d@tZ~ea$c9$J=LF}uE#m~XB}*MHp%|NPVa`t z#BaRQ2`L=5B-v>VGD^GH01$@_JRf7g3yM)61zDdp`BnY$$#G(HWsa7F{3;SQ9sRtd z{-M&APNv_jzv_L@;3=R?q4bQ5vgS`7?$YMJdHlI7+n?VFT4~R{9whUA>pA`e#Pp_p zFaXxGaziU<9Y0fN>h@8D+|>Ony6XV82F(y!}0yf!^Z{iJ}9k#Q}2|#hveV zxeuePEtB^Yz_XAYTD=-4HI$N^#(KvD9OaOp0_4PC0fhklfxn&=M|cBd_qcQ=BEcz< zw};ydWoTFFLT}e!y&6E0G@t8cj}!++Pw@;SfG}T%rbzxLUU}WvyB!cxMV6_30MW9d*I5(@xu3wfiF5bm0rx} z3^k&rOncLwbCh=b+x}zsGo`tWv%3Hv?|i5rq9TdMC(qg?aXCT*x0|%pYlI<0d`#@k zOZ9&Ygc3}a4CWG#PuKs-42=U`2^$|v>-Pg|`F*klsvi*hf*;yebFxT+G_KZxX+%0$ z4)Kve0py$;$$IuJ2KFF%KI8uY??4d0-D`2s=!-wkSn);rKK&INWpiTfl>^pJ9DUCt zIo44F)fJA=L~Xs|a-fVpryjbybU*3nMPGz+`k2(BE6}sbTzWcO2QS&Q9~yzHYm@Dg z3`!DqaanxiiGMCckk7xJsU&ay1VbMk=f0RsJ8Z!8f3;(UIS!^c# z*nX{Gs~cbNOdD-^rM>u8J;9%U)#U%k%g`TOU@q!QrW*O=7MhTy{E&xz=ZWf+hMu|E z6x(Ls?T?Lh-pe*OB?eZhdxI+W{R0U2g!`dadU>P=m?MW%*o*KgjW_hkpD-xyw<+0$ zb$*nu{!T_}^avRm;G6m1=BV)q99_7Pm*I0n8*`KwmTYpItIgivn??%E2DfF8j&=;v zr;xKT-wqt}rH)aK@&&fR*2cDsO~x&DW{e6g9p4x23tqi>P@U||Mr^m;&+`s4jv7vyanvLoP5UryhuwP;gLMx#at=V!roJ?qBa0(0 zrCm47RbU*?`{NDfq^|ehfB*2-TW=jc_~3)t_2b=euf6u##NxX=UP|Cn0uN3CmyVhX zWZQ|Og`)+x#ciD!op9*f4XPGv7H&HF1~B4ujQP2pt&JXiGGMqPuZ)Gp)eO#^jOm>B z6PXU+j)MH+Ri@<%2gbQ{!2l!9fR#b1Wz-=ZzAhXK+sTvND*Huz9W`*3hAsvz#K=M@ zKIiZkZ(%FLI=yULHB{JnboEc4n5Ya{itwVhG8mbL$2w|?*CdCtOgkvAO!;<>mR`dF z22SP4r94%p=ogd|;V2#D@szjH=qTdxI~GXmm1ze23mnG^&$m(=KqQ!l`%NHG1T@lf-*I&_@@~&dv_s&Lq)}6ASm* z@*5{oLuniOlUN=dt58g`swe^B=?W={woW*(gL=1owh;o zkk8VmIPjvg;K;i=wd^o2@ebZ`%0wQsBP{wm@6?%gh|W)+6o(53~ zH>r5qXRZU5>(RH!iDPHllKtm1wH$`pK_Cy2BX8bOlSiMvAG_jUo5e@y20ZY=E%=>D zu4B?h&N&Bq3>$0!rtFjqEv_d9a29&U0_)^LT(Tku=+7s=3x0UF;z45w5E~@R7xsAD z#vC<2_+dWJeSAkv+BL=Zjv8eb$re_NhT6s3KmFwJ_P>3S7Yl!WxcSN5f%EmJzxvMA z!$17>Q-{AjyLKN<@O^C{tMG}(*|8L+cI@0!td5$YR}QxKz`;dN*yg+oYUikVB9FaZ z9Y@Xi*xCheWkz0b<9&22=$)(LxL{Q8E+`9@f_UWaNRAWf31B#C;clHGwKHU}PF>DAR_PzEWLMgh ziTz*6j)3(@(sGQ9qdsYl=k#J4-&?x{A)KRwAr4P)%L*FCnho5@t#^K30=ZJD3(FK1Rfz!5aGZ+8~yZX-?a+R|?4aH+? zg`ex<-}r$hQ5c?bJlgMuUw&H~O|?_0^S+{_wXa?6m3}gH`T}L;JUH^BUD@{S?9$Y~ zvQvGo@kBee&qvQbv^>tSgS3^Fx|6VD@w`~+FKlv7VNdZM3#V*#V#y=CY;_lAPs7N0 z%LhmPV`qRj;=piH_R*(#nQ-JWk3RkR^>u?Ng;za(m#wO&`fFw~)&(cM*aBLY?!~tB zPutkj$JQLzuI9BKXgYT$L?7n)%VAInE7-v>}J-%(()$ zbcpVS${pVtY~&f7^4R{ZTR+RqqdVu1KE<9NDJ|eqzT?la-GXQOU%bQb8tz5xq~$W# z%P}NRKfOi;K;+km60j?R!LNR=;l20XJG}Yko8zdlo9687?C|QVuO41`<&}b59xo+u zDS-zlflEit1;W*N*Ga=^Vd1#E@p;VV$#tiHf5+cID=257*a@;U9Wxvj7++>GX8XTE z`Fif+yIZJ?fxBgNk{xiQcS0uJK+w8cpYmXiA#ghM!oneTfG{A*gRf;>iv|vpCU>k& zBsf022$!Sg6xO0zRLqQO?0fL_71boou&(;!cP56m7fcxmWTMsSWtju5(I za1+&|{m@;90$BK^%XclnE2>K*!#Zi)fpo5YM7k&z2Rh)H!FSL-lnEgR#rpCRdOc#~ zZoLWev(G*|ck}w`W^8nz{@>()hX%BZdl|{AyenUIpTdGeJALvwVlqQlohWs{RX%X2 z8*O6okrz2tW*jtkKK)hh+TP68t8|3J&wg6#`$U2#Vq0?JN#V~N|W5HfBN_BBc==BA4DKDx}{??w#l?LZ%*cX?_p|Kt%0kMKU?!ym19GyNpJDWSM_c%WGNVYQC zoc=ggAAWM{&fzCNyL0&Qzkhmo|7N~6lU+4L^@HnA9RBI=zIXWhAKe&w$nOHKO3wL_ ztjGp`J08ygN({b3Pxw3K?FdU=V4@$sgu_`gkA#MnKe6jHFBo-qyR@xGNR~YJGOK){ z6YzH`=asXyMG6$g@igq^{IxoBS}2v1i%_Sp&s*oo+z z?JnCkeynkb-RL*;Mf%BJ*QTZ~yJGj6F&{On&m>QCk?JwJi0&xoTzL`fk&jgvf)(&e z*yUF$U5I1i_bE4zfF@Av9FemkD&dwlij`t|H=j6IL(z*qbm-fyOy3T|zT z#+?6O+OPcJV+a{+=Rc?IM{4ZNm{Xa%7PX5sG8KlM{MZp|hbBjjb`z(sO&ig5=i2QL zh2nFpU3^`c(k=hAExxV{f=8co{5o4#w|<@SoYJ69cGNKK8d11m>0MOw(TK=Rd5<{$ z*|)BZyugF4F6u*6(O~@XDB;q#0c_UsICO8iIf-eDae4%iwn2mWfyaFt?7)#%y92|q zqc3gS_V`%Z#|@u(95Hrlr<cTLU-$ICgi~I}R#sW%D+f62;#n3!ww%=Z`(?-DRLeDb$$ozm z;N5rMJ-qS88{??49(eA#=MFEw{PN+YmtGngFMlp2a4CTYD}mVYt|xu4b^X7=t^+km zwuo7iqc~qOcv?)ZyVe#GYcXL!?SjZ)?Hrt_)0bvpZDHln0uvaWyTzhiHHB#z<)t|q zsCwOrKo@g_DQ#k4^FQ!?nXmx`Y!_zm2yk}ta6W-pdEN1X);{{AW40yt6c)bH*gVJ5 z+W}AgCS+tSXijFzj}*rUb2_>fp8ddGR!d( zc6FhF{QCHu^L>O59{3+}2Pk!!9vHrh-(nYi76%@EvLlJ)h|k?9cYMEz98%;MD(lLq z85gCWrn#nnc1y6AI-$yA{(c*=WvbE-TCVGEUlI zuGz{KO@O=j+{+BzLiwMI-H(1m^y1AM=|kywHVT@7jBjKKkgRSyY^zeRD?* z*$LH$UwnG^@bf!&4{!hU_TgXt^_Te?R2=NtO7i_UYX0$WzH@l(`Rj+rAAR`n_#^2n zLR=T`aKN;oJJMG<+#@T%`!GyxvLlP+;k)68H*k{a2?wo6)6nr4C;rtZ*TOY2pT$FD zO16VOaK&4EOK(=j@Up8jsS`#%+q7re2w^*VjXK4r3E=^9UqE}}+HJ7m0F=Traw(U~ zec4mG-Mlc?>a*&oY2U{#MB`k~*^eok-E8{lj)9#&xMo-EjZF_Zp$9+uzxg6t?8SJ? zW*$!3^mT!?vvt{!T>)gPp7e|Or1K+(ogju8Fbn_GHOxv-V_>&3l9eQOIDef5G6!xQ z#rhnNzC4-sw$L41VCO8y6Fgh;sz+T@!8vWp4GB56?v^PH_}Q80&^7OfQnvMNDns*ZIbQR5AJQlD2Ww+#QaXs=&*+Bt;=t9hS z>BUIvIaVfLz0;DbD3nLLNIv~l4>&jn^&n6%`QgKn(_wbc1>jzpEk{j2rtH|tLN#qo zHpQ8$r)|B^pPkeF$xOPJ^ZUZv{;@uC6viRAoln9fZnSc!p}zT3S@O^==K5%#&I4zs z4SRB9YRwTgtn%{rRcvT(G_WN%7=mYPB<1Cq!`B|PXY=iB8~cfXz@wh*r;YPS^6Y90 zz10sk|BKASKFecZf3ZFK#V$E(&f9X0v0>yW$Ke&f8?VC?rB2YFotMq^CI@tY(1y#xtp3!Z=e`NIn@yl{B&#TO^4^Dk%LF4`7 zS*LE@U*Fq38YF}5oA>6gsxnWWJm=)e%#)|Gs`kC|$}3lryXx5guh4kE82Lmo6=^n%OxvxYJ;Ye{GNaQ`AHj*33;LKzWeSg zIQ-&uleg>9yO!@JZ2CxvZYPD}~zFV%FuuZRi^2{^Ol+K(uabmjp=9`N@JT{(98d@*l)W6Q2J-g_K zz5@q6qjw^?i@VW)PNDlBn)L?}Plpd5o^HD7rlL#UtL1H{wrF{%6P|1FRz&5e^$a~< z{_>Zn^XJb`+VAeW?{1Jq&YO5$>zB%Ce|?;MMDiBl2iLTa0~w3E1-vOEcG!2r{%K$2 zbwkRF`=%??zPTS=NxIRf#~VleS|1dhYe(t31v-IlZJ|B2i%6!|3x>j1@?+*RmK)Pw zO(^>Dfd0hIa4o#*QYRQ8BAI0~uGhZ}tBoJcJaqBm%hQ7yKkmKv-sy5O<@Y?aF1Oox z%lVgn=h^9}fAh)dtIuDUZaj3ubpP!)P49o}ozr_B%6M}0&~)ofhe{s%_ur8A8UelL z7GbpINWbQ9;7e9HmYjBx)f(@WS1wPdGOnM>xY^;*k(;K&M~~H>tv_X z&D~_yuyp#;%P&plNprb+&EYp^40_dV(e0SyZhF=hOBCQ z$jSc1F=G@9)jzk3wyHWzJhNOQD^Gq4-{;a8uDq3a9KvH(DvG7Z}cQgjHN=O{{V zd>2#4#W)C_efF8@$tRvDqwx)Ic*AsiXay@Y9_P}!Y_5tPliJxcrxyd#qOgMn6+?8y z7~#1-bSRTo_-Z7c5?1nl4|8 zBC>H4K{cw`ZSycCvWE7aloTEXu*cAt)ob)-PIS7Wj<7VYKWk zeK>mbrs<|x=Xw#Mtu|?ZAFX1^El0YcE;Na*;b^+(Gk9eib`!7sVd(9nC`mkt_4@)RkyNaq92M)A3XB$LZ4bE*Yva;nm=WB z3h;>Fmq4B|uh&L;fJS!ZZMB~^6pf9dai|uTITzqYH<)wh&c`@Dmo~jA&nJdt6uc9oJTnoq36o3w~8*p&@WZ!-~FvY3p~JqbBph zk&G$q0#P+^6^{HYc;_@J`bj%wV0GS3PvtLX%$KJ9>A(JfZi_U$TMSnnx$eHP?k^V7 z;=#}+>N5h^!j8C|wGSHmp zIAjC)92LAyXc}}MPLK{Q-_gEMoy*+93*e!i@d zaBQ|kJK_p|ep+VA74963YnB)KEjgo2o#m*BQ3A zs=N7E969(}@dl>CIz4oSjB7e-0HEL8-SZk7s^%&-W{~PXFTZ@T_`yF1w@`e~<;-Vp zSkz669O*JxF#09ODt);9w%cQ8=Z0wPVLGrsj_K})cx;(g1@lki3A(~bz@&`T?lbt% z#vRa23o513xAI2%Sl?8?n9F_o)1RLH&A<6K)5Ec6-}~P8PVavAyQjCm{p}SS@7{4w z0(%np#z|n$QL}?=4aRNk7$6OLy^v|}UL+cD4VYkhQBZ?3xw&D#j7)>dTb^smBq|~r*AoW1f zhS4(aKD3-2dtq+E7wt^4qd*(MgD3onXx)ikav)2`<^ey-3(B^vqu8bP78dJ&v83AI4p9HaMDRbv93HW5CXw zONn8p>Q;wHA0L1G@oTnm%c14c@^q92PluLs>);v|ZD5=4mL2}V3C_!ai@Z4Ez{1&g zm%E+TZ9+y29Wo{}G>Ip&xV!E4J7fH22MxogV)QIH1$A!HKxUoac$zk{5?yoDFsjkT z$$>^RHS8u{##~f3hFZ#Q=z7!AJfT5o8Il>f2rZA!<2a&UWadt^9eVJHLerx>8FB28 zE8gUR7kgX-C$GmbFnDSBLVBH_rWKfeEDoI?#^Yx3hIg!Uyb@N9ucZFL`H%-EllDG& z^112RMD1|%iDN}CgSR7@HBVqVN+Uz^IhZyxwjA7_9brXaoZm$+Q&kdkH|L=R4emJ0 z(LD0HO`AT8gb_n}96*KhYGxPSDl2#(ghQKFUvgJFj_Q`#^SSG;jq&#SID2c?6#0ln z%+Qz3s`?sF#&q~p_nC*EpMK?cpP9b&)amJkvst_+@Al(|r+aTZGJX4-@2JQ?U+<`C zT-7w%DG6i%=XFEiYmq>XyU^QsEr`yXK9zX7bo%A!_3p4%6AOxC3)dr}{0}^0TeKHR^3gh0vzV+}_*r zbFnyTjP=pUa@5#eka(3&?jZA}@63q%+5#D^_~Yoi6o-G02^TX*lkfQ)&pDsRXL=~Y z(S7Kq%-7H>}!(R@()^nOTeK(wCt#4ZG>6aRcJ+>?p8Hj`*>P z_RDc7(ns|*{Y!rdjD>yEG>hQ6ho(V2Ye&ts3ci}QxT<_)(0bQ9J;3PCZjy*>m)qEa znNv8--Hf?zpwGb_EgbTVw1~e{tYn>Z`P6hq211*F8J)?=MhKJp+#CyBg#goAvD;!e z9k#}(!nZ=B{&(VO$O_}t2ZN)= z^$@!2j+(9~awtiVM+tNE~hn$%w26?v~AF&Ro&G;Vk5X1BvkvVgS>Yt)8)GlH7%9CFMUjZ z>VARV(DR~~s}djI?1KYi=Be(Utsx4w0H%Uj;k==P3#64;Z#H&6oU zhlabou$Dj%VvZdQdh3b604IWJID@0;S{``iERbyR<*2D0HJOZW-Plpnuwz0Tj)tDx zq`_&SAvO%!lxw=0Ch1K}FC3+zWz9$9>2yZXrPTBEQ%_EhJ!-eb;pw4=9x6u-+`=Ya zMu&-)v1d0FxAlB0nv+mYwu&w@nz=&40sh%C6-C2bpVgh8PFJ{r5jG-FN@}k%zmJCd1KY zp%3+);PjGI@9Cwp`PKj;0aKWt0Y2-vP7m7VW6{ z>Q}#7jf;(iun{!clY^c!uPY!o-Ccv@6kTw`SQFV-ExqZLm~25+Gws*8w{se z95vE%t$j-Gb3XKc^i?=&u@X84Nt^{4uM&%O#WR|fvmh|b;$oB6T$j^AIzAh3j;~}K zz+>NaE&a<*2xEsaM7wd+*ioZwEi^(W+DoGKvxsXEF*@NY{R^F6c=Gi0TaP?H{qEzZ zrZ2}?^Wxcyc?9Obbl1%{PT%#8yQdE&+PUHpqo7_wk&HJd2|bq7#cn@UD0R!v`68DU z{2H%u<4nd(k9yMkOBokArfngLo?KZM-+H-F4SJ`UZ*)PT}WQ*tLu@rC6}PDw4K^o-ew58(mm;gua28g8`mjReLl%0 z`?(G2x4GAil78&8AI~)&Z-(Z#c?)C1QG=$)mu5pvAG&X@>4mTILWSd+mMRE9nDMHw zU;^FaFnO2EVJI7It}Df6whD!x9(R^D3P3r30S0$DYBILb{hrs%rRLQG+7FUqNL_U$ zrOJ+z@v9zDf#oqCjCW9${v^Uv0f>9W7*yL==7c6`JLsgdDENT zG`%r5areTW1okBGjh8_BVGVWP_?rGVs-Xwe^|2SA%|;KFVA{AbP#Y*augmlz!=q2` zVp%xenMV~YG&(eFPi}Atj!j2TYOcjD)A?Y#Zs%ez3eh!;s^JvrdeqUA!7z|7O;0`< zN6ll8mRH{b!J|*R;WgQEN}M^9$93{Z0-BD*=n^>=L}k^{^rOX`VNqtnYFh9C&SKkw z9IoaGoeWCR;?!hsAtREbN1sge>T1|7-#Fws7t|@=QCP!NLVn~ojxO72-3Bc?Ji#HK z%*liy#t6MPJ09-4_rCBy3|q$M#f#$+5BzXAJ$EvX{KRNIaPUx~cNL7gm`4uheKv{h z{*V>xO1S?{gB zQWfQ=@im>T4?FS3N#mU^=m(EByHV&{^R$TE88mX#eEG{?uD;;Wr+!Bb`d)bP)bxDf`Ezk%MLz7x8!ZAO7c#OdOI>2q)_AL5 z##r-c(7`OYI5qImybL%7^04}PVIX}o6iDjMKcW{$#cm5~d{uW$fi+&~-RGap&Y+WV z)Nsb#b=Tdw(|=>iq+G_4_09ouxWr&iv>;_HGmM*$)~lxZ$l*Me8OO9c+Ty`O*^Lti zf!#OVAHeDocGy@T`LFgdnuYLOZaE8Fhwd_fXZss-HpX^!N+sr>{J7X8P=-FHFDj#go%xC(lhs@;-z+ zP8^=T_gn6rK9YDSPMSk;D9-2?{LmDB=tk8!+a-jac1jih3TzZ=x*IPCu}7c0qh{#A zE2XQ)^IkZM`2Uj}HOs;=GC7@bjC0!9XN+GSeTsey2uX>9JIw5;@ju(Vf0in+;NL zIn-!6W)jZj#)REG<~}xrzIMl*ch$REYUf8_yPwr!G6m}qnt2?>kAQ~O7xbeAP10O9 zjhvvy38h+(yI&NdSMj4tM)C_FH09(EPXSyY%3sh#@o$2K(=hqh%o#EOi?jEo4Q!p1($I-_~Z|n58ZQP zVF^n z2Ih`UwMoAWm*hDb%q(&QdEh(9GoTu5<#8%lXfVbM%JSVE8=H7@wA^w`|Q~>+4*oGi|9PAllN~h-j3wx z#n2uNhQqmzt6*&)C6)n{a zgI?tYj+%$_jv6xa=#v*}Yghg7beyKAPM@iI7>(|3+m+?6rT1*z7~N_bx^0?1b=&C` zDU{y16AD)Bur~UZJDHuC@=KWYpstf%MszNg#rq6cCGz9gI#Y)IP@_u2mxyl*TQ7Fk zuWm|zQ4O7~HlFnp>Wk@Tm(r)|j;8Xn?rR%uqOH2!^~=N28~P66{#+l5v!)z1q0ES? zjF_Lmjq}=llDy{4g0OI;4vy%$`zo!&EC=;kWHIjRKXtZIjSmJphviq(AIN^2qh^JR z%z6fInROFn6eG~mJ?;DAxtFJtdF1K0zw-R_OLt&(2gm?WiVNm3A)3M{z@jL=l zj+!brc*QT(uq@(4ODhhXbK3!}FxOXYGoMRu{e#ClT-3EM+x}~@8(QGr3dzd_n!pcz zvFIAkYC2S5g}<(Y2aLE)4zB5j{KTsqHJLj(f<$CjHl~f=uLW$589m!`(^H&6JoddrlSVRP2Qwwul(oecdKvK#cn?{Z1;z4 zeRD3e8{VoVKlG>dOEZvPj|*LG!#Xy7`YKp;vxiS+Y;&Up@AReP=G@&l>qysT9$Xtc zHyt$u17_hZ#Fp-;y$N;%S9&${3?B6PX@06M<>}&FzS^_^0Vi~QWD~r2j;hbN1|WIW zxKRbhqi^S9?{QEXSja6e$G7expH=@skdcGM)af|qk{~6EH_sID}Ueq zM13v9NFTfpJEQuL_RyzNxaX|3o=NjgHZu6+CqFU$zyIQ2OpnG<^L^jG6<_9U<;fp5G7_8c`k$aokmW2Z-Fml2Y|tBn}xJrT=u-k}FP11nsNk#=gdqsHQj z0|YFb4GWin)^(@5mfm>R*9LQ;2ItVwMncoFo8fXTdN;oagwBR*NNBUO zXxwGD^MSKw?7CJsLkz8V#pMH^6PQ1S;rW97T0)CcgsdS zu0^5glfQ0nbhXUTB(Du2&H>R5jUXx~+ASV^ioPqi=Be?n)8Xp+n}&6ndgO41sYR5# zdGN-0Q}$sBHD2WfGV-!&;|iw{Lyyjh1snd39`!Dro1<5eVdT;~x@yPTEEDb6e8cOG zTJv9u$)H=cKNyB5gI&04v6Av-D5p#WQ!vZVTqX#YBqwdiIPjL-+Jd2G4b(II*i#6kkT+KHwu!m55~Z1b*; zavo;qTfh6L+A{EHXH>hcyZ4=zvfDz^;V0`_I0xP%Bi+_^FrdZw`e+`JV6-ofJ~bk^ zQ{KX_7X2wqtXd^mqkZJZ7)KAifB8~&YQ+J_QS&pOd3^exkGv2OUCC~%{nNL-<&KIE z+;-D+f8wD$GS~q=0e+#|zjSqjwE>ae%|a`BAqw@oI%+s@$i?oj6LHAd4Tc(}ET}9m zEab;dCzxa=m%cTT>Q`rCJ4JvkA#g(m{HC ztT=$T=&GV~4aqkbtasEH$IPQ*w_6uc3eCb*vY%<#)Q19|e`c~nOZ_idP{KP<4<}T~ zK^h%Oq^qKILBHv_#JDKxJ1<99(QQl_FvGSn_88Br4;jxhe|v1T`{A)T8P)~9Iuig!0Uw8ePCCOeRJ8C3mSXQ zuFBKJksY>QLM=e9nHSWygQBl1j{X%XYco&zxZ@y;t+>tr_jyvuO z!Lb!GXX$fj*FW?rb3ofG>O@yxJBr2Q-1qEIJDgpj>1okBGjhDclqh<#gw-Mqf7`(@T zHx{M_MT45q#*`yCp(pAZ^pn<3ntG>3wtK?Wcfos*t%CXKdU_yslm>spHVpa<0?Z|l<1bB(DX7Sv#pp9%= zu6RelZT=gtJh-}UM?o6;#D+na#X1}U zeBi_mjkoDl77k7Y@0Z|Ax+9Nh+?j3N?!Jrkpx#*&2cGg|Kz8J8E3i7Np5SWPnM|Ai zuCr-q9@Qs=mqmud?`r*Ry+9|ttwZX=hwGNxfC*eq7?IkjVt!gTQease*Nb)K zDVR{bW~=MW=@#X|mwa%ws{!yTpbIT%vbYg%4R80wSfmH-2U!gFxokgffwpCFGV|EG zYg(?_T;zzRYtn_5M}$){_SjfEQCmM+r`6+}yo#GR+Q#$#TRQ>3;1f^1@LkJSo$9iP zcy4yopw;-+kGB;JIVVQ&+Z+_tHW5Tn#Mn>&%YwIbDKwQFQuy?AqXV~fyfx?|S0yuJ%nnTr9+WOYAYtYT(ZjKs@_SU7wv7O%Gm|O7C1pu=Q z>bPWH<0NH}jBlY9-x~}2fKl8pKs5?Z{DMm#X<3&)VFMsw25swX|zj zbd4i&S`I@OikxjFsu$m$|v)dyGrZbP}x<>!9yQE{_$U#{@FkMr)AIn;1B-b^e6x1pRC7l zmq&32ssBrVjRkE#ny*FIYgwRO-=be+A^t%EnX7}1pzYdDkS>tra>F_{m$8n__rjh8 z{-6@rbJXl0L4$xnY;73ywa&Pnc)>KB!A@QeAUy!;*bEcia|?7h407&-gLmCwjjz)? ztzlg^J&r=t)Yo12CM-CEhob>TY`lHli+DKt-7hBB<^wMVdjp@rNbI{JH5i6Ivz%$m zMA@{!Pc}_s(;~m?ZuvIPcw5WC?gNhw`F!=s+?9FmnMAExxT8`R=Y&iw&Y$*p# z;8M||XX+F?bQ`bJJFR8ilXUB5x3P4KK)aG!9(`>5%`^Nhhvs(^w$qhe)8o3^!ud{t zLz4l=2~oRxB7^=cELn-@C9BfC=pR{mX=RA7`WRDPFIv#<*gDuWfI+)_G7-Q?+YIOt zy&O=koiw*aUPoeNuK86CezEbld|Y>E8v1(ds7aX+Z|4hV#U|dy*KI+sIBJY3-50x! zTbJzq@Iqzzc4WcP<-6`KgC=u*a;11$KJ(MIkp+I>JrJnnekefP)EpB=+NTMPWf#2topxme*0{vcYS zT^sEvfxqSAsII2dx$(}}*Soy>C9L#?{MI^yUye31KjeK=Y0v%HP0+e4uNK20i6rpe z@*NCI95UjtwB7t`an!(3YzBKTu7VR|&@&z*j0y8FbT z>7JVpPT&5=?wQ{I*1PlWn(_Du+KRs%3vYg;2`$#T$PbydZY#5vOERuS-Q4u$4%u7ocSF$7iRc6 z=!1C9s&l+NIPGL?AdkdZ1Ov-bF0iRm-Ts8DyV%1Z9L9tP49AC z;Ty6_Sp^eH2N%HLt1)ZKj@Z_Q$@B79j+)1_Gw?MzYScBVF8Wthr(N(f^uS!WEuc65 zW5gbP!mhNXUpS}lDbzf+uGcsZ`5dZmM0llZNh|S&HzBoGdGg8G+#d!Ic=J5_gDvbv z3w=M7-5;XIyv!f&q>Lpm`&n308DJ1aNdp@W1}ahzs)C{@OS5iUfrZY z$XrLwN9kW4m#cAQt|yf(bCz`YyT6s)sC?4RndT3H?7P3zyp;KCeeArNYx7|cJ96BN z`qZy}a{6cg?4M3gMrVKchktnb=tno{B>wqF0i2&&B9t{ohE$^+jTh_z?b)}f=+m9_KvTwwusqs3(gBEm)u0=e! z)(`NtlTMnP837(iVF+rs+v8+q#E=afO-swLc~mEQ9N}-8)Y-6%LU*y;J@z#sjvD!J zcW7BjCl~ZE7~GZYKCKNI2JJMJuD+&0{cwuTg~r>4o-}e1HhCLzW_%BW*kd(#7s{cS z`Z^3J0i7PO((wt0P&l$=@Z!)gu(JUyFYRKH@KR{jf5yv%pPd~w_tkD8cQApzn$NA) z-Okj%>u0o!x~(62Xxyfow%2>l#;F*Br*bWHyS6;Zn~u1nc~kWC270GIrCsT9y+a`U zR@;zQV3l1Wq`4O8on3j_d#4>WB}}j@!@dg6Kivk^FY?pv_iP+959g)Azn`x_eJ(E+ z_64ZJ`(K%E+<#^I$h%%QedOJ*n~onIkFG#Jc+8%b@TU3j2j^y>L#+?W;Bg7bt3^!8 zt`|Gi#QC|H#mI{Xi4> zoXNtc$9e5%T-Qfxyo&zxd!xD!*XfKa^QX$RiG3Hs}+lHI2M zrfiKnIoge}r8(p@V%MRb3WS#EF|n`Cjv8}X&uhkQ)UU*lqKC>cXI>e$oXOK5JfKDaB6npzKR=reRZo)s;jq3PbL ze4OcPY;*7LQwKfM&%Cs|ZhWom6na))KFs{oyS4QzeTnl(^sdC?CvKTO^O^rK{n*F; zzxv?CU;K-Iu^csR|0^Rd{Vt?jrT3eJejTojDdt8t(5FBB>56vRwynlKawGgt|LH$H zeb4uNPkl=KwSG?A7$LGvAI^ILIca`1FIfJq-}bhIbo3O6eawy(o)O%+4*=L@fp2^*HyFtj) zUC5##@@#y~V;d)#=Q3G_#+erM2u+jnn{>)+IvZaVnt$YV8OA6Y8Q`2D?us7`&ZFcO zS&H7d!YJ+Mh}$@W+vLf4;$19aFY?p@uX;80%ZG)J&aL#G>p z-7$kp+cU(#kZ*^U2N^M<`p%I$IIr|a`p=0(Mt0R~(f}7arK?N*f@=Y7!ur~I^9F1{ zZovdtiR$C&X zcG2M-;wqC$MsFTfFsyqk`$)+zA`)xKk-AW<`pr;W;tci1*v!-ecxkz-45E>7@{6K2I~&yjMuDAn5@rhXEZm=7G)6sq=Xk)QcC&QS%#%hK3Zb@V8CRmimSc6@7Dkqk_T902^&3ec^4!JLZi+x22=@&riv_@$?bj zR(W-t^}3upk^gRCan!{5hffZ^V_CQ!&%33_oep3`%D(97ODD|FqOG21^g&Po%LH&k016$1XM~zM-5Ox5b18FpiD(T1x0eefYDt8MhZxaAUV3bYlBfr z_h=a19YbK$v(NW>p6mGs&iUnB=X$^I_v^mzUs(%zI)s;_a`VK%X?I@A4+3{3B7d~o z9_d7Oi4;hi`NwW)vyBNN^f^{C+S%lwITA3D`b>nwqj=-US@j(m(uV@TNvJLf-MUt( z4y!+`nx_6Mp>C?ck)PB;PU(!mO-!DvK5H`cwwc&bLys(pLseN8-<+krVoA5?WP&)F z%?=89^H9XG|Ah1**7<_E7<#%KqqJV8KieA)4p@_{y7>*^9lI9hvUQImG?P=XnAVIN zC(tQmQ>F*$)*Qf-M36=BL|(#WG4f18dtP6R7mB+h*(5c$1@PFl9ynv2R3SmPq-U&C zck}{sS1sc}B-Y63ain0*uejq+mtrPf=e6Ewz{ke89P5y*V+&bS+}~ zaGlP>Umb2=mIHCV){VMw2AK%BgXf4zoWhs8dsjAZ8VZs~*F;j!J{)J424%LN8Y36e z&axqd>74ZC|3+@1zjqLJu;wB+!L^0!l6WoD?P+G9T_I-(z> z=Vm0}*lY#IrAGP1kW0#~eOxovs@UXS(oN<#VLn@7q35Cf)!AjSjO?X~JrS~G4Q7_) zk_7#?9&F*PxQFhMEA|rQ`W47KgFWx%{DkQFm^RgCfMVwCq$w4APNPl0YpS7{_oXRVGWk_`U zd#$0isZ7^`JHEvEbJL?On=ezbs_|)z&-=T|rVZ!>^d90r!Ofq~L5 zk;`i{++4W`)!$K4y#Fh;ghCg4Xkk3IGX2xp`ov!lVC1X~s{SIYl!l5eKGvCZ{u;Q$ zn;Io(urOQ_aXt*TAkn{E?#7>LvK9V-p+BGowiJ^@89YiHMzS)*wgsCdZYLRzL7q*S z1KDMEe83g1PI?edN0>^cLFl@1jq`;PD9?aq`z1h=TLhp2_MMe57ZO9QI^c z1b4C$&{_-ZTPkK0aHYf>cra8cDJQ7=t`69Qjp5OM(e3EZDf^P`Q8a zbSUEFVyonfj!IoiSU=5ub&YY*Arf3}R$rDqO(_1U{2*y+42+%3k+%w(stcKUPY+`m zfw_z(2UnmOd-YhxKiE-(-iGYP) z7hG|%OK#}b2G{(|u@-l3JV--NrS67ooEL+s9Y=-yCV=Cc+Gh!Y{8;g)=TrT(OBdGg zsQn$+87;OXNl&xw3ER^xmLz?)){)SwU9TYiVQ)DUjJ84;&2y%l|ZP=eLmiGZ9=>Bi&9?`Pi`k0 zFz|NbXqHmo(>`b3t}^7l(ZxebQi<(JQ$nHzJVe1iSiU5+;Qp!WoCWd)1f z;n1_Q{#f3Loow9E*Y^I~2B(nxu4;+YgV4q&34SrV(u(^%f^Qoo?_p}MrzdeA$*Fyp zfi=?7$K?+smn5BQ8IjtPFN^VQGCDB2_Qx zddD!5!&$mA?p*JJ$#3ElA)l^i z;0_}_v<}KSB8?K7LQuCrmE?cxrYg|%t29_jAC&aRlIq@MR{&XG{&L}SAGgL`rn86< zZuvL28gap`7Qe)msS`{Sw_+1&GQgY9m>Yg9YY_nT3thN69q4NoRUHQfmn4aj_MpI= z+O6N5ke@YU$qO8JoW z=9_S?ePly{6PbLcxtCWDf*`slG}cLHLksH@@d*qi`?iBWV=~hBGacV3wgLDN>R#Q^ z%wNZg%qXlmqIwMr_}1zRHxNp@R%1&M=9TG3O94Y9MK8z9e5Pr9ETVzcL9*8UKjLh| zu;4<-vb4X#ci59D6N=>h@PA?3BYucF_OR7+qf^wq++Oy9lw_|n*OWy0%j~rZxvOC( z@dG{DS?vS96V}vOH%;KtnZ}9f+ee{)MgnXc@(JR;=cv2s2F;^dkC?JM4_|;)Ft?l> z-AY)J_bI&A!Tm5#y_3fVZ%9z4Xa8U+D+LvbJ<#H7YQ;-l)pKH#+ZT(SdvB+h*d{~u z{))4%HK<5S`QWSu2c)(lRvnKpF3%E83Pw$(#2VLaQAo-F`Hnt(KSyZ>xHYWw?#hGf z9@Xr}&lCC$!d;_24O{-RVe0lP{+Rygh$l{#*q28Xve+#3^Wf>AD2Ex zuu3#O-&B*@v^^Yzh7GDEZ+Wi<^&RvbFP7P}N;*&Wy$~&39nU#PbWmj!zF*KOiTh^> z*4r_rY{oFreh|?Amp>KYj??AvH}L2pljR`+EV^U~X# z>g_Yx;H_aUxY<|1hUIe9e>iIT|M}DbC zH+NtJZH_to9aK2ixWuv-KYQ9P@io;Vh|1lg<4BQKP87Z!BzF}~)lQItns$KPWNH4z+y~Rf%nTX+61n5ajHQ(KGv4rQ- zhFPv0;7$uZdbKC#Fr*|5rg$&>ZFszkcaqmZH43Vto4qxS-C#y?o1!x2fQBfF3uCcU zmS`z0Obp9QQ?2%%(?5&-_!nFy$La8wr4xdU&1*kIx>!PdoyL=0KX6qDuA@`>n3>*q zF0oz3vUn2TiLjh(8!{QIdTW~i=iN@oO)bEr%g#_8I~2UOsll)fus9Q=B5=iBG?mm1 z-J;2Mg@x4alIXtq6(I5W2Da^?vT+!8<;&@e6f$sF&GQY?)y5>b=`@X5S2FVw#)bWr zamVKSNc3uaSz7szxZO8@Tvsb=FuThpwY%+i*7xMU!%SGvxWxV(6BV{P@q3O;x{Nxv zuiVq`n(zvODZBw;-hFA|E4rr4M(G!o#u0x{zXB8|)SW5hG)`Z<+r_ol_@U0; z>5LKQMq=C@8*N0PO&&dDj(2$*09Y`Y0PhV=N0#yiBHC8JRkTJQ-P=1rBQ=`F|FNeU zkn`4CLd%b%E1}$W*L@-GPee7x+}|Xs{^R-C!Gr^c-MV3 zoeBz~dvPrna)!%Y$_p;{;E%L4jq7WieCN1l4JK+6S7RFp+Xe*c=+C!70O=8}EWvIG zH`{92ISMy>vG(3rCz8x+olL*fWh88%XY1Ul{`{9Xx4a`SQ-QUnv()Hre)I*AjeAMZ zb^%*037sa*WbbN}N6TA%EO!p}#>WgtN`Z3%63GHOUNt1O>lq?+MTHuVfwn?eeF5|Ep95)2L*&j;+9$e1#heQ|TYOdWko8X$!&-*Ir)!$%xM@ z2z7s@J~`JVZ;I3Dz4~Il$&!HomjwXH+GK5$fLl!bQr>UoeOzhsRj>svwe;Oxy7Xn} zb^#;3dfu{s zicz~va{J6?MMlM&?f9)B$zKjoDTK1;Vt#HexQTFz-#Ob5OJZa3 zLe_$TJ6{XhO#bR1a(v0aWvlG`svB~~gZ;0AO27qzZGLCG79PipZh_Sf(OwSHs<2({ z2SJoaJxu;_e0u1K@6!tL-zX<^8bAt(Q+QsleVq_sw;4-G%>EGdNj zpq#vK1pARpT9Y$I`5yYRzVh7z^5a$O1u1ht_@+?$viCx<;j%LkC`ikNf5UP^esbcS zdqSd>L?@%UmH@0Is^yAHJJ4|zc|Uynv~b(&(S%JE7!=kL|B&DGJWmF}>bQRuaX=!o5RvoLy)4_0ZYf?{8;)v`7@-1M=b zyuJRhPSJLAdoYlX@IIH)3m@7S;APkyc`yj?;#rF&#qCn+bCDDXEE$t%_s5S|Hq^z- zB+-lPx^oz9cQW=P2`D``07J_Z=3op5BLYCa;g1U&kK!5NQCrknPTP?Oy$R|Ovt@#2 z->va`(J=kQtB$q-mFuIZwMz8r4BpIT!fj?F78;aei@@$+T^pBDHZVGo&&&9J3h7rz zq2^gYQ`SBYbg~DYZTz8L2KpoeGVpr=cp-?_XBsbvrcBCTv{22H2dmbQ+^ku`gvLi=%iT=ZpS?BreRq5LYfa!X4Ix6XccZ{QbstgMri@ZI9WyP9UI zDql1kmonSCB+Z9ybz!aH_iDD&U4Cq~bx)UnrAY`wjCMrlutE)UW!7T!nsmQR4mUE^ zxOI8_3RzoEzIgENKz2&OuSTb*+Bu4qsWK>YHMoLu#;kxv>}W!F_>1pghrO5=?1J#b zbM|`l@~Qw6OcU(OEv4{|;@8!Cw}QBWQagb|^4hP#%>stWL#HiUVOtILH;`{g<9+Nt z$D@1mt=JC?Tza*)Em!W<;`N?a#Z3*-wxA#yI^9VdI!+HFULaAU5Qll zte&upPkb)?(T3kCTN%om_GbIu9H_orqv^ zecBnFnM0p6&wPTiaT^_V_|_&m8=LTE>96e5dm7bCe?Mu37Kqd*xrz&{$hxi)^I-6y z=ISR}73|+zv?Bj(4{*f(MF8)!YE5jgJl*7R&tz{q{W0?t^r!~do|^>yLGHpQu%=?W zMS50re1ppUU`DXJt_C+7!LjotB5{!SXOQTzKdBmP*mFa5432Y@DC&OI>r3)%8RA%@ zao7R=NT=>sjfj@!1^Xz}GFN#6Xt$1{X*h4h&9IQP6^WhmRK=$7cU z!TW8T7&S1UAf02{RgK!<@IyXj&%4ICa#^7&ijb3JBN`2df{rH{*y`w~p}_7= z&{lU)Zlls;eN*eTQ7)+_^Tgb|HisUAIOk2|EjljX`O7tl_UGDEJDK%>us#ZAPq#B^ zxMR#b^x|~}y6n|z#U`J>{IM%&3olJDpFl?ZyF-wsEy=40A3|Y%T2p?NCqm}Xt1xJ4Qm>Lw2yFQqg?Q{nbHK z15(Un5Rn%A0)^jW&cV|2t3i6{Q@!@O)Uhzk#SC8O%=kp*YznI)v70KtUxUt##GGR` zj$Msm9ZJoXB4KT-Di!~p-fnn={Bw&~T`%arI*5v`^d#i!ZHS#n%Sx;ay`m1!~$N;TXFMt&Dovoch__XC}`pVh)k&ECCvqv!>cFlT^s)Q;*0u!B%9;10v_Y;se7qJF>xKDlskjfNd& zQX!pLOgB7twpAe9Qn%O`dy92<@>0W+Zt9@1z4r;Rarkl76eM$Gc-*n@UYP$%Ro9T` zI5b<_nJ zad$Y=r_=ahhEep=3Tc%Yh&yG*V0MUwzIRQgFZ+yeF{M$OHNZ1?lg_5Oln^Y*mnKgg6ZLpZ2uNB`dQU z<%MBDb!NMV5$43Bsdkob=^%IffowOP4s<|wT$dq6E=$DZ=W3Tq(gnQFdX9$;`;$|z z&r$^@ul|$ua+~mRSHqV1?xnpcx8C3Mh)A@2?&n)b!4ZmK>U0$S=`1)XGy;_Aq_BM) zJst>D9I5OoVe>STv~Z78qD6KK18>>g)HPbN$Iwxa`-w@#KV%TtuiO1=Fb;QQ6}m5{ zzpoJnR%#+~y|lSSUL*iIPSd}&8e}zZ52Ry)x^GvQ#jj=>NZZTX9FjLZ7cJ!*sDI0+ z!S@vx1%G~6m1Zp^9kQtb>G>eHe|vbmDo>5^P?L)^?A7yc6T0u}DR=#rBL+9(4)b0v z{#J%(dhPy5y761a9sf;^6QEo&OM0{zntSM#n#BUDk?o+Qk-O>M{b@BGwIxI;oHFee zt#9J8WX+Y}%;beqm1GDu=2BtS;gF=);n$;ef8)CyqPl||#CPpU&#&WmLHGzvupW4i zCSRu0-maxba=*b|%Hk>AUY=nuH@3ltu0VCe_ek}p_|qgCPapg3iU<`Dl4YT=Cf**c znl3!0KcDx`3QR4x)V%!DvZ3!>8$3$c)ZlBg?u1Qyp`4w$a zc4znO4&R}sw#t(qJ|~qmZ|9-G zcu|GxZd*8TG0CsXer;agP2=VI`{1UAGuJ|5Xj*pjV>%VLIj51gJnr|AK27?9;W5Q? zfxm|-$*n)XIa-Rpp96T-_92i=(o+SYe0#*IOAwuH(%tevV9(FA(0zTDN= zZ6igB_@V3Jre%s;r;EG8hmcpvODtlMaXUs{A~lY;9syf8HDsKhjQ?H-BaA^#oySZ~ zThGiWl10)xpkz{Li(b8j@wV!vn!&S{SKcw)sHf{HOsGZ_H9+=Ds*raUvagQ^(kP6n z_HS)4Sp#Mni~Gm2Qi1!no!)t2rJT4W6-8JcxXW@P_^|yRlc8Y>ksmLXXON$09@nKO zY)}U&J{H-1A$t8V+?OYXH0PVxk0qM@U(BUa=OY{2rjfv~opxG@%yp920fl#|Vjz($ zVsc99wN7-A!G4yXASC00NP+Dz$khr_u3zow9y<-X-e*(wJ`=cJNkAFWzUVN8qBppZ zkycrtqOy&=Gk>p?bI|qLwJgyk%~lBR+sQddNufooD`Gu}=`w}iMoJr(CzJ!ci6w^> z+biDtv{$dXtSnXQ3nui5x?KskZ`eX0@;{`5N?UGnoC6tLPtg!4k=Nz8JxH43d(V@Z ziCiueI-t?C&_b~lvF}R?Ro*Ssn$Pd>K`~Qr#&OxSj`1g)@i&rjG4V}N6#=?s|GM~3 zxL-KUG9PwovcA(h-~3Nyu$P#7J=IU|l$S}$x?t><@bhhEctW80l)K-$Q-_MX$KlV~ z*fmtqz)>(jNMGOdRVbH9SLMp%KKKy*)cl}6bzwvfq&_9jg4rod-L*)-guYK1e$u-k z%kRXwJMLn+e@HYB~!5jF~$scAe54By)hQRAl zqAOX>#ykbW{E1Vg(68sg zqK`f=&|;Q$H;PY|m6pW?MxqJfXfNnmw|3tDbJwAg-O*Q=TV zT(c>wf{#OvN4^QSD{46FG;4*9CfpvWiY@|7sLXlZij=W_>S8uAEU`q-r81h|R}0u6 zOMO407^EEM=O5sKo^fh~FXRGtq%^-tQo~8!SSjsz-4<#`mIU%>!NhsCQ5Q*}SV$xbV@VfB(Lx)-BZpL%IH$UYGc`l0e;Til(|- z=0@*0^1CeM%o0NayP0IUlbmR3;Puzt=bM;ozPe9)fbQ z`h5>|EjlaKaFibHQkhzc|4VwJAbi;P*@Fu?Lba{&yrV@F502=EF-uZ|B%ab~D z6|r|3L72jFTCQ5kTzVhSd)pIgum8=B^)(V7c5TxYraRH#VW@T!@_)gL_&bd(VpO_A z)z3%1i>l3vwQ%+sbbQkn@VYAr0x$wP^dFp~Bmuj9EDKW^Df9|1jLxkj5XR92vgLO$ zjvrx;5u`0kB!B_~va0G&G!%P{W}o-pl5vHTjIwMkO|G;^KID_PJYZt?UpU>5V=K9{ zUqZ;}Ej|{zE8uLkl)aMP&w3H68mML_X3o;t`b!8)*PPhFUmN>mmI*X9PKk@9)Me>B zTnJ(-d2>xl+rUrbQ+&eM3@wB)s+LyZP`mAs;;*FZlLr=0b!T@R zl-w`QG{};`*o1On+ar}+4)=OOiyOnnUi;CS{B2G3tl;vGMT}RrZ_TW=H^v1iwxK;@ z(k=0kuZG>mg%xd&OqHeEe0)FBGht56!94(N7Fue}rdahqRS}S7}duq)$Yhq{1Ft?Og0YkH+jxQh}_*H#0mggPl zfqO*O+)T_r$p@I};Ocj!GT+Sna#^)x6O(DHGflU6e04SUNv(B$5v({4*JE$2NJXqb=sp9@)z~}|!Wk{uO zCiwtR14;C#1AA_k5;f>)n(rkZ*7%G{s*P_4X5Th#=10p-Ua7t<+vi&XL3jR`~GUJ~E8!-IUXE1QoJqO+7h= zzv9u`@mgDLrk;ERy`KQnJn{;eX^bf8kkfX!9MSAoYx?&iSvO9^rBS%?AO(t*SPN+N z-o`9pllD3_`xlGy-A9uhG-VT4MM1b6?KmIpvE^d9@x7Kj@gGa*WkcFeA-88ok1me5 zf-*Tz5xDNS$eNwJJG!HB!p6Y^HcQAcu?7}x%(`w+;P0{17a&G4RV9~I4Ma)&2h%uT zZ;1vwjZ4b=l_k0RHU!h6BTR(L2vPolQF|&xezI)bE;nxQ@M~b>h8kTY#OQxxpw7Y-bUzVNz@Ezv7y)#|GTH-;S% ziI}-Xv%Az=0q|&AFJC?aQ=8|X!ZQAOrn&YKVAnymBzVVE6tW?+bz8SN`t8*!2h{3l zV#zwv7jvo+`L@rbnH!t~a0H40%i7D^g5<`e=XLaSFqx*y5%!%7qU-C(aOe>aV`Q-1 z7f2Y@*#{r1-FsH>-oK*o-{$rCl`CON(zSz3o|FhrcVD6vy%;GS;5hlN^=f~eS;wa` zus2M_X1BVR98c5qDhpTB$LEMJ`xs8>%5UEllr;v#8k=6^|NPgi6Scy%pQn`TpwI(f z%^7yNcoi)i+yfjFj;HJlJW-g1xk;zya#6Va5=~t-^)HtnoD$v>{^-=?IQz;Ai!(Qy z2#;k|*7#Jh>XWP(J&j0#wt8+^g5_QNzRo-Cd&Ppf4Y8k&C=mFrwQlcauveB%#D9^a zMFNrtBDv;)Nbyjov7%c#6CgI5(f@KDpSzm&_8=U2UkwOY7WWBzjC(w&BWBnTJpey{ zzAC1dOrlImae7qRm9Et5`yqt{6NdTFeHcJIq1%r%>>fLF1swD~zg4OmN3w^qALU?l zpD#FxT}BEKSFdk0lJLg;O?Jh>WJ-A0Emxm*G}TNxTjYCD+k_{fG@<^b?LX#kp_U@H zft|@E>=HEJgo${5X7AJD)zHDm_?HktA=5G01?axuvLEMt)s66`m7xm>{W|H1WRBTi zEMzC3{g;e&VJvjo-v3aTU%$}0e6*({TzP8SgU%;n{^9!0PxU}i7v1fzmx zB7%hZg`t3}5&I`Jpc{uJbpsVjCbJY_LW>-2c`@eFX8tjzn zLSHXh-&-{1Q#{r2LRfhYm7MsxUkWZhAWm|#j4@>bB84Dz?Abt zqKwxwNT#TSeA%boQ*_`e4Gx#t%+0KtfaE5qHx|=POPiaqnhb z|G-yJ@OB29wtqBvgf%+JR93r~>bO(p^YccQ%V%*@!Yi?YwZ)cQc1+OCi%|44ha*gM%qA{+ySF)A|d&VIs5|Nc|{?T$_Hlsg4LUsTxrs%aEp?E$OM{*poG_z)#=E7SFS1uG<$U!!Oe-j7n%E2#k(i0SJ|aM|{fZNa%W9m2 z1C+#=oivRM(7Tu#QCoPN>>>8>3nZNp6Rc&xFmtiRDP_@~x17B6Sp^wPK$<2Ju zY?z{%EF9CM&#Y%jqGCwWGvCHWehlVb$^DZxo90A%Z@SO=97ZW@&&h z`~GXHIXd|6^;;wbG-H-2ujgJjEp(ESW)wcX16}j!ctL|&5~1CuY+SzY6|%?hl>Dl? zm-lwk?kX9?_;GXPYViY2(Bb?&CR?=>WA2*Fc3h`@9E`W*gWmEIT}_f`^U!G`mvG!H z7!6<;HtzZfAlSgzc!WUD&@qob{M$|ZHs2JFdjMYQG)y~YH$`yKY^yr_9Fx{SKU)9T zngdiYV>DUPdl(dABU`9~<_j9@QbBy{35!5)*k->_&bj zc^N!Wo;CXZ$!%dq_nv5qJmC7Qe)<0Mx~11%QcDReMleTN=iOHPZ=&)a*$^KWmWq*- zLrBXk@WZJ3N)l>koQ(m}v$NM6=0C$}0}=s{{06cUZQ= z9)t$5xN+B6OuM|{AZzj!8~a)5!oy`eTrwP5|5TV;YpsLb>Mq}sDqSV~`!@|iJacsS z#$#%M^|ynyy;}O5p29WxxYtjU#IM?W1N6VA2+??#3g;P(cletkEHyT8$MQ^g(d*T? zgzX;|%CmeyX%GYEfs&4U>Jb${OR7m<+C53*HM^0tB*lq_0VUxQfj>Vdd25q5nYVl% zxDM5_n{AOw|4ER)aL?7*qAw|zF8~U!cer^HO=tE2O=l9(Y5Iu7tJDuv8!g>seCt^Pzu+Z7u#s+>XESl>_&QaeO6pCP(Sdi<;4XJPb(GaI|@P%knc+G#uRw z9TvUeJ`nKtxAi)0!>%vG+{wtFKXvrP@!Ife@ZJD8_yGfhNFc=rohY%FTlEc0c)?fkF8jg?7{SA&9rwt4F>bdMEo$_TndE87`e!QuA9IF3~ivfd8 zfOltoPuSgPrCpIH%KCKTY&wDbEwYv{1y&a2r4O~MNBvyG{Vw0&4{arY-K~{2r1;@R zg79a3q!sLk%(q<*)?Sfw{O>B>0>*u2`eVOOjhN2#2 zcFnpZ`3{u{jEz(gTzktO#T2Xlx~hyA0AlPxOpT1-L(R&H>C1l60Z^ZDz`B#WGkIbC zNY;>F7X&AVW$Ocv$NhiUpA}}V?3>F?{F%nv=*+{xDo%6k>OgrtQ}wT>lYge6BZCKc z|7ItTJWCd)Qcr6dNcF4gE}yL2`i2)iI}PyZT8#Z$mEgw={~or z=7aTU`BJ{-yJ7pg6eUCCK~)-GK-4;~cV9kd8ZEUt03gv)7W3b0fbWi62<4e(&wOs) z-4n5%m!Y~y7rA5kSsODo;n#0e<~m|VTF&67)8f3Kl)?@Lg8WdDs94-hpm=b5L*`BTZ&J{ZjPt{qEI%ktf&)Xw>Z4|+dT~8dl zi+cRqdu6&Rp|;mo_KKP7x8;<1ip_G>+IwJhd}A{Y*E@W|YV{yO(W$G{kSQXF*x=X@ ziPV3*2N6MwVoSi5E#Z$*aIs=4i#Cj9UBfo);K8Nodwajb8+01OR>L0!eyOZJequ6q7(Gj-?y{jyLN3s$q`YAp(T}MAz#RM=^s=>3%W*kGoR%dK)G?wyj`E9i0!1ozRJ-63t5{yJi? zB){r}hbMPE@!DoOC*5Qn#nN{FkN6o43HJ2ZkbSSyA70Q)1fe0%0B6ZgQIVF|Dq#yXgR#l(=XBC z8f6)5RT(=Z)@mpYjW=-9bHrtC+2w)HENZ`iY`}g0c_+K#BA2g^o36&U)UkNS;-sYG zD?|NK7BLWB5hRMhXR;-;dhWM`lm?Vs<5RD&_)HKXGrN@7_rSavl}qcj?~nDEJxVDY zWb9$Nk0I4zqhl7dpac0gO&(JCL)PBN4vgjsR@>k=yvh@cHcXrp~Z!{Qd zIQ8AGWp2SuETl1pN}9|E+2*#4>8X%Lpm6yxL6KOGv`;1GX6`yl>)V5@-e~*%Nu|D= z-mwPfNqHB>)6qgq37SQ$*2K?4Z+4-1@K_%hN}6tdbFRYD(~VA>#>_}o3wTVa{JZ?# zcHCTzM8ig06C>00s7$Lm2;TANpgrn68gkKQk$(sqG2+^4O$fId z4}4!sh6#ve%&a;7Dl-UmO?d6FgulO!jt0JPJjS{)yAU6#*k-la#`LwR6$VCh>3yW> z?JEl&XE$_NM9L#f-3j@!aj8Nty<2IQwqtdUGM0JYcjW={hVql~hI9gFBmAk7KB_U9 zrd4wbU(UsBi%Vq|c7!a{2V!tkNupJ~RElUR5pnyX(w?+YS}fZPqTy$UeSg#TkpK3# zuogE##k9B&tRGUFeu`g%R!mxrUmi=G|J4@n_n^p;H+%)<&5c_uyd!tD>9IR(OKwe7 z>$Nr`dq~-Iq`P>8?Go7tg+ux-Yk|nw^T15vie;*g^7NYWK2tdM*k2bM8(GV$WcL#p z`vz-}kPlv^w!iZ!*5ZT%@8Su!k(Esfn6BhXEiE_l*5@3GV7kO?S;&qr@sYkB&D@S3kUIb~U&1hUPjEvIHRJbFGk0>a})j zNrUtB@`Ue9XX)`5g8L^RziHxEfmBV?_D?c}C0`qdtqCfutj{n)G)$>$^4muJ2!YWN?t-u`bM|~~0BONy8 zuUePcw&V%W-uqigui9Ig>EtRZtR?;wWx83qGYfR!ul6%9$1aPHwkD(}gDY)@{l;n+ z{s^k=$i|w53Q=U~`R%<&w(>=$tT7{Y^17&Nh$15$08E{IQy34(+gX+&{^|sp<-yNis!A(ALnhR&zTYMn%v(g?sF)~*;U-uaxyj9>!QQEfz=y!(zs)7nVy*s}E-B^_C)F-UT!scPbW|`pcQhjsko*VaY;UcHCuLkKd*`b=oH=a+I z+aKQuZ=&J+=wIa?vtl6lJXEj5+-Kls$;NkzFjP+(RfMp-Q3H=Zy&ZoezxPwe*LTE8_exG zNX|;u=i`D1jj!Lq+NwSS<4ZQd4sMT{<&yR8M82WN>7n@q!v0ADGn*8_RvYekt8B$*7C|6d4c>0B*Og zJ=^>S42b%j7IuU7Omy~rFKvCu{JaxKT&&D#PKy-7ajh)#S5#e6W*}YVmIV_N#pH9> z-D}vMYLYX$;Cv92w|B1Z_m(_N=+?|UCY1Yp>WlppJ-4@?XO>3x3xUt@s3Z?M&3fJb zzp6l25@^Q>ip0N#rSbQ{1>T9CqlpS>EYGvBN_faF^4WLDz*Z66PN zdF5f*yqsGiB^!J~i&R+Vys`hKr}_9`TJ0v2=K)F+(;a#9pK*zaUPB{)qhiMmxVzaP z?{!gLFqE?2?n#%e+v)16k+^=Z%pysZZNvK6)=is^daOFRC1)NjYa1v)J#0IvN&-l#JR&2&t6AJjr2e{#Up#!Rz{HZsKBgEoIX4xL!G_at$&&<9dFa zL@OWrNQ`!-3cg-rDRDAuwOPAvb@;4F^Q7oD0|sESvmMx%m$|!u%X;lp0zl7sW%F1N zPzAv+V0ks@Gak~$Jtvp%R+OQ5)Uu?-n{b_;%b2hHIaO_Ot=rM-U5zS9{@*|Ce{MI9 z7k*bm>gjLP?Rr@1T>~GwC#73D^(ndmQ&#g~B@g>a@ZcneVBUU z{v{f>*G)oSLiY4F|Ay7JgiG4o7ggvvsnFBiLEGrn=9)L1+to0-g=r}Z8x(w>T?n#! zM;xykH&-Iu4BH#cugqD{l^1N?-+~EuG0)P)jTVO5u~SY&ofs6^YcRIm0f+tFSWb`@ z)a-fjzEE(qd`NFIsXUNiq2}J4U!|bshpqODY?`ixG7X|aBU?<8oM@z4)K1p4fEq<-x#~ETf8J@vA zK{+3=&Ai@}DX{~Cx2?9wrfxDR^Xa-hSBuCb{r*d>%;MW5Gu!;DbGMFUtw%`|5$xJW zFB5ssBNA&6c6UM}=viZ9E;8Qa*wxr%x_cun%#~mA7QT!-cyMl8FL%6>EACAX>&TTq z&Y#RBPX&rKorX5mF?&3kyH+LEwG%e!yc!AkKXhsh+~SConYh%H-uH|M*4zQmIqcf% zDDr9ugrb^TlRv5NOTFkywJK70FuLb`S$ciE>s;O=jO0XG%)bz|+su=C^^S?}kvg*7 zgR;>;N)>zvD!@jZ5kWbLu5R~-B?1$5G;MD&x-kOA#=rj$03ku% zzKuPyRqW74(Y9@#{F66YFw@tUOeL7kA^J!yn*iQGCt!qS5O2!84PO7-jz@$kE=^DBIXX?>uN{W{b#c2AIL-c=)=uJsVCqY)#Scx^tIqU=mYAg(Y{&jEnb(`yu2#C z=zF2GcGO6zJ?z@*6_0a@;EJzFi%qJh?W>}N?JG{p1FWM=e9AaKi_=m|zc`e&&Buln z-8y_01+41D7REy;`!hKT*X7mFJJX+8VT+%2+d-s#N6oQ3^aeUIChoUUE06_mz^2-6 z%UoH@N(WCq`Gw8r{_-z3fBBc6-F)`5pPlyjmw)+}XU`XS_U*m6zthJ$YOHMer~mYy zZobv8K5@8MQS=vo@fWj4o>etg$XHplAFMw5z2E!2(H952`d#PNKJ4lBsRpiA18KWe z$qgf7(slk~Cg9$owW`A)z#zISYup!)!Ucy= z{KZ?^)kATBg{Su&%SVrE80SLsbVbdb8Q`rQHSh>D2 zD!;+w%lSGHTkEPLI;1;J2fD4!IHe3UrhX)ythIw4t1mPvk2JjX^)st!E<}e0aW>ty z(g$q7M()ZkU-2$lIj}$1^0;3Z`I^^ppNBQR<~z<&LuU2?kJp=~K1MH>E?vw(JGPZg zTiIWT%!&g#R*%%{>Q;Vq25wuXV)d~DKH&rl=)rRwEigF62N--CU|QXw?V;1LgV@3=ujKRYu|WY& zdgLh6HdU7kK1jE932dS=Hffrx)I<3@7@o;X=wV<6wat^`Fg1+1$R)VMark&DyA30w z`;n$!)mWT7rB%q~xbWGuZJs3V>)Av`87ni(wmE996i7Mv;S2BBZ`w}JM<8jP|McHK zw-G=0l@~UDl}M^b?#b7m9=UV#Uu|d^TS3ygg$+6+mvG!GKXY^S!`W@mCG9Dv zqp1HTd-;QNi#FLhmeC&d&}=mx!{s{!4EXBTV%zXq+J;U7fvdJ+QVp?juOXFV^j1@Jol)lmxyvrBLUdsmuUYymS`ml$xKb{peRtKr$vV$Ev+u~3nEiuX&5Gzm4w|uZ?{IzaQIY#EuQDC-Ug9Y4zW@)pQoI#cJ>T>|sKQahtFK3HBaz58v zUO>%t%JRiLxH%KsSH8wh#_6|b^|2Mb9gcUJ6$PpfG@``OQIKL7d8&+9zerhoOX{?+E^fBxr_^E)3p9_g62_2+l9 zk?+6xH~(hycYpVHvp>zx{_M|g-u>=(Z{G8s_e?pmdv!uIo;6Nqi}29D`uJ$JQfT1t z`ShnhJu75j zDAcE229SkW^9!zc9E-nrU5j{-R-NHxUuVrzJ%FJHc?Efk&*~)38V%wj8St3AaSR*< zTYfdnoB@5k2EN<3&Mh6L*wr_s<)~AH*CYdv?Hu4W$S?rI7g*s^Ch9ul=QH`3CEV#L z?@fblKb?7nDtJIP51jBnDxRTuM#;|p2& z@$5IA**uq(bL77%jxQT2-x2#V5xF+{U@LIS*NB!V{W#f_8yN~?g69iJc(WowIjkKu z<5WN=F@&gK(R11ilL!2*#)EU;51x9&lTe+ZFE$-7?g`b~Tx@?Pd(bTy*LRll4xSJ3 zl1yYZh-Ggt#10&|Gf|kyLb1peKzgAEw3l|s>b}GB<8LOOE5!1)EbvIj+IK6mOyb%2 zJAEZEea6*a3&vtqgKjvuHU@p zq1!jV_} z`?Ygtf#H;jTWuaX9LTR1(Ep`wq#W_Y*2#{i3Gi*1aZ2X`nn&?ya%6?EvNuj4vwmdy z5E-F!%t>uWTZSguM*(R zxh1rB09&24jkH=u-}{xUsNsMW>0ps-k!@+q=sEQ!WlugUZS?1_rtWZtsza9?Q-`XP z>P0^yTH)$d_i$`~Z3_8G(T5Rz%(DTX;^Ikv-IBNbZ{+3}oXeid4O zm6wPN`xe0;8PE=_u=ELGZ_7(<2~SM}cQ*1rod;ze6ta1J_mopsNll{@dh4*2=)lhK z7M$v-`nvEL{sK6!cOF{<)uI7$N=gT~&UhCc(SHsI1VY(g7!*BX%qouf{% zjv9?h9W|X?$!ib-zlg5R0WOnc(V$M=>11-xyULb~-jYvk`&6(Fd3SF+h&qnn(!e9S zc*HY$J{|1yfv&F!-#5hpq(d>7s%#wyxHhp8suQ?{eZ20Y|eu4;|o>uggA7`cbp!IcdcK#!$Y#APtIRxp(l-wz)rZL%klsKKmbWZ zK~$OLT7G=OFTG^}-nEWJCxur}1UMaLB9u-Hj5wc@_GHgKE7>2!6LawNYtI<)om}km zi}pSbg=zWWn@mFGobrjCt1IH;k3YV7{D~)q|0~Hhh_<+ngWczWUZe@~;G^=BK{Sct z5UCT1+?Kzp4`eY=z7WS8XAM31{H6^)Z%w_q{r1~7cf~%{A+C_Y95&30UrPwws0J7 zbW|SPmcMrAy1J`u@Q~rCfW*QJD-I8Eg++rbgDsKHO=w=txz&O0@b#%AX3loxMudHR@tuD5G7~beA3|0OJb;!9jxVQIb)diX8E9J5uDl@r#mK}e_ z!v`h3=wH3Zui)P3as^a9*HObJP3ErFQ8S2FKYDn)O_}fUvjUsb=gwW)Ja_J;IBA~Q z{LW|2Y@UAJmjmCidDp$SZhrp54{v@ft7>k_=W}nmA@Xg@EvTn0J0z3DOt5Sc{7NR5 ztyg`uLs`#?#?&49Vn0^U%~R&s8i)AoRWr61`@12pQaaCmEC(xVmU=`k^@6@@6YKL% zz(&{6{Gx|k(aG?+aPHUS$8pNUL?##Qhsc{uyY^wfjQ3#|@CA1ej(%%ruF4Sc-1$q%$&ZSAZ(d`^TEMZ+Y)qnXW zD3{1`XtJHOmQ(JGJ=E5>=nfqU+cG_LGZ*gf>_2>K-^Njs_PY-v4mnJe%aqq5OJ!4c zUVAnDP4X|1qbBFuK7RJKOMTuC@9g+anuj}dW4yA{QDhk1 z=bi?Ojs-l<4}7#lmyH9l{D4!3@OjCr=F`8QnZE0>$KJW|VU6k+Z_F!*cTNQDZn)k# zf{>j;$pN|HVKLNUZj!<)Cxo`eN}h$UrM*B4%u=#Na$xIIp2-I{TcMv_*q#qe__DVZ zW(H&H)}$Zst3q(NRaaIGel?C7vyxNM*G4^^8WX~fBH`SXSW})lFhzv9(H+E=`)}C%)H94&is>q@=qpKMq?4U z?LG7Bzy9kR`_LF~(FYu&cHF9*C$o=t!0A?ZT#cCaSdB~c%4Z{%IeG+n+czt^1V6B`R|Ie%V2bH zMNcQ`VPC&!&46LbY3cK?+fG{Gss6#yyZqqk3O_9iNBY)@(Vu+P109&`SHC(RpBFbU zHxzNt-VtP(_v53(mgzpf($_qoQ<&nXGjQbzpX}T~?%D7sKAH*YV~GZuSCS1r0o+lr zNAW-x<+J&E1TWT6N*^ZA^k9D!^;R0&x)i&zX|UBqJQZV2G9UGwjUWxl3Q;0D*yB& zZ}U|)xZG>{g0!@kG8)@)Bjd;XPhGKh1sg!i{oB&UiMK|t+B<2JCC8pmLVk9vlQ0)- zR#?*2pJf1hDBm^{8B7SP|H9yZ?kTt6npG8%zfVtx!0HG5#L%Y64wzRUJ3e=5;cMY^ zNuf9Lvo-A-U7FBc&8ts4oU4;5(QUDA)wjBP_;mIJ%GaJg`PXMQzxAo7H&14-npZOU zyZ82draMlWAN;O+HV@x@%jS{0Zr+s}3|lo0GMb<3tuAtR(TVG=tTzFvs>7AjV(qA*=&{T2#GY!Khxp#RKzba4IT@X&3~UT< zHCe-A+pwz}@G2=`F-SH!*GuBuCyy0T14X8-jwWIIQ^$hK;~X{0SzTx60-3Gs)F1B$ z{6}%4KYG}*Gd8vGy`6IBhI{0yJY;BSxzWIs34!qs9{vRN8jjZaeP`SNt$r3AE@J|A zr(E{~7@_oyLHdwsy`p9dq~O9sc!DcDPVW4?p2_Vk^_PRU~DRRmh|P7LwwMI zva%A#Ll!IB94lMv$D#U?`m;Dmm;G+=1doS;vl=w#+xh-tU+!<^qdC$ax3UKPi!b>C z;)|PSzMd5&=U<$?8s8ab&DP|mET+6CfgQ#!7Y)oge%KdXwv64bZkPJ8z$j7WFFzfA zGaF7h2IZt5=KvaL_`zQw^`WQmFJM~bRCY@|Ayl{5&wXC8u zF8$xpQBz%Vc-V7=BZM$iSuV_zC$ZRO&qO*L-g zOflv*1{1BS@fwuXFhBgmKRo&6{qsNn^U0@9ST*Fc-VN=K)mg7V*{`S0tB!Npp3{-n z^*M*&f6sf~Gi|xP=`@^b;LU2_)KPPS=2ZGt#DcX`TQ}6wgu*TzNIC@#bD{yI2Ef4k z$#`5jTvTSSKB>T>ykbM03w6%u+zo2L)GOQpokpSq9<*E!zQB9$_u346mkvG?k@O_^ zb)126I`Z;a+Loqz^$AXcg*s}`t88mMpamD5piNe>p?ONDx^oSWJUdL6P`$pCSDIeRlS}(HnM_)> zr9D+6CR;R9Fuk~X}tyA0ZfZ)w}|!)rtB8Nc$=Q73pDZR}b3 znXm@Y!HOEPh_(E1Ae8MY=a|9Wiuf#xfW*9yTuEC zUr`DN!|ULPUJS5&8IRLTAd5O`u*E*vX?Z}q!CC3!q2*s0-J5xL?zvANg(;5Ohx^J6 z&+>tDPy4A|nG#VhDTj3!d=dhWAMA++@Lk0qU4Zwb&^E+G){{&!e=Cj}wD5xPakPiG z{E&m*{`hadvH9)KJiYnruV%lpe5(7#IEBCGop)}&_p!S+AI$LsIj+OxUr3DnQ^vWb zGrB)A3{#;Qu3pJXfv2;=k4>{7d)csm4tw%n$^#1Zr*vv(>cjL=u}@A>{m$gy9-S-G zon0u$;A}fE`E!34*mC%q*A}*AOeezFPL6YxpP7K=`Y0JEPx7@6b%Hl`7JF(PXY<-& z4`56v^bhSX);5XX(#OkDVc6W3vGd_CC(Fclap14plqu`&Y?cgbHLUTk@iL^*kHqb& zg&pi3ZRy2Zos~v66IQ0|UHfG`bd;lJXa)v@yVpr}L=T^^-FZzcyp;A~h+OTLF`3{` zsH0};eA3%L)CRz;%R%}+ESRGLSkc(7jvB8tiu#KQxlg}juFb4*xixJlxZGIUmZd$@ z4!;(CzM8r;`c|*fZ@rTCbRPO;;%XHKI65bXIQ1;HzOFmYrC07*(U#TQ9DPI6>Y7z+ zqFk?sE63q`uYDu~hwsIFAi%?)Ghh4a=EAubMt07s30t{G{@^;UtoO@UUOEw4=Gq@= zuC>ABP{g1_y1OP$u4$Vve+0kEVC-Uxd+ZNf;FUSYm~(Y`=s1UX9ncLyF%>cYug#c& zqsBOE=cv(sB_3*bws`hY)_(Q6R@I+^gcHHL9qMU8Y zXFl^68+)?&V25$6ag7ahf9j`xYM19bb)rw;JTk`qjo zV%lbG92e+lRA;4w!AUyA^%GZmJh)H z;o4EN#;S?80#_Is3_?UyAQ@|R}ut#QI5U-?`%3Vvmr2xrcGZR(azna<#YOMRrrIus1v zBH7egjv50g_~^SlmESNlc!r1I+UJRk=!hYf|LmJXN6$SwuLrd~D1G>LA@D~9AfODa zJ@s~OkhjXoSY|-mdRQI~bZ1hu@YMlwWt*qFx#!cn>Kkgx2@bS99ez0uFq>2>Z*^7O zH%O<~8#xZe=v7^9TUQ<`6I^)4Q(t?mJxF&SP7>nHQ(V?f8f8p89=e~S)^Tn*Hx%kqnn+LLr=3V#Sy7`&+Ke+kn_a6*E58)4DI+K?F zIX{Zt0stbsg(Hr=ujeVdy|WhQVQt`+(b?;ne9kK{;DfxjWb!w!d`y40?46~pP`AL4 ziS3O2DF3YuSfR)H%eEH#999;_x2KqIxz^^TjcoamCivZ+&UNj$RgsVd6`u z&i3s#w>CZg8@etygaoFG^uS2_+_Vsv2 zjR$A1Y+lHIcVCO__Py(?Ut}H!4e`lKxRs72H5^sO$-V^HayHIMfKkr$#Q_-o!pWRrb}{bU|~f8h&X7<;}FL-ehkA&X6e)dB6V_DEgO&OZM5 z;}iFBfi*tmwDLf~Y980>bH^vzZw{?G;Ert1_7R_6pK9O=8aQ>-TtPu?xY{wR%&pKW zr~5iz9bg;2I#i^0VkXUGr0=7f=&8g8l?IC%9+88=Q#Pv^JVn%SXjs-y+OWLOSFbD1 z47h`j$6d6X+(cWm-Od^R2DFu_c{!9g7^J&z;Mmt=EctmP<`~Cbn?@Yd-NpD z5e@0C#q!d;=u3B$CYH9R%_3cD96Nb-U&E_G?O?>yIxsrJ4&)bnONXd4)7kExeuqxW zkxcj!q~S%7zcM)&st1maI%=#uF+p5AYQVz--%)y~jQe=eaPKIcRaf$WaV)=R2-PqB z;LkOE;M+NURcCi+mC`-;JusW$-f>$#^&T9h4WC#Y$y=Jz4KiYW86@SEso=K)r?P-6 zY}4>YCVJEP;g6$cy)+zNFlfnFyKpVK#*cagzoS4l>6H;InZXy|J}h0r0e1GD313!w zJQGKajT~o^7aZz_daQmL1PF`#i(MH=->|pJ%YC8zx?by{{Nrt%zTl0`Wkls&|8p7W zzLYOZRX%)(uECZLTI+MyyAT~2jP9P~ZF$?>Kj8##920_i!#>KdK_46FSAMiRE%(Z2 zpe1VWL>nsFc-fv)w@05GHCGBDu?%Pj^21OZ%VAeEhw+6E7 z*EZn6w=!WH)v>%ypC{T8oY`F)57>2d628Dw6P+k|WszHl!sspOlEH@YX@j+IY|w@#O(uLgTI+9=xx zRg8kQQPWn$*>}m_P!}(xPMjb8soVH)pYHUp(#8Rlc7T({Dlrcr^atwUx_&rsY}vZj zhH#ROjfC%!e=GA^#^#Y$TiM+Y?=v9{K6UQd^s~y?VBgbM&KmrRZzNnz8DEC4yyV7F zt2e+8-u#5sL$;G**y*8oM<4kK=%G;9WEmXbwC|!ouiC9XxSGT_`Ewk{E8pW!&++lcA0KB8-q!VE7?<&gaK$oKo^(Op@HhOpPIS=T1Y$7fbZ3*7kqYo}cJYRI z*hBn$qV+MBL`9MM258;pQ)R`-W6Zmc3@=g48|HeG#3w=2@eEQR$+Wg@k z{6SXyeR=HGtGD)D`OzQ!(Sn>FPc?9=fp3Eb(hjM*r{O3K7(DC59NR(bXhdo4tb5); znd^o%3@41v*`TbiE65{q;<#_~MFUY!C`@h*FbyXAl+6GRPX>c<%Zr|CQP8G$#e>O% zubvnT8SsKF|2kgzE7N4oPn|_NX>#Misui6HJfcw9<|03pTY7oIYjsy1U3YMdHkb|s z%1d$K&pmn8a-(TQ4R1L9bar6mHy~*K@=M=hWiEesQd~;xx=ix=I*)X6!0A|7i+3#x z9@hbk0hxj53z>ipo&enKHIBqS(U+&?hi5p;uY0BGT!6QHJMQbOx{{Bs3P1EChx^s9 zrvX;f7_7P9yl|EWd;gd$Ew4G5lBF{bUI9GapdsMhJ!$Sq_oSOOvO9V$40tqqT^#av zAX`VxW7(8VWdA1G1~6ohr)620O1t`O@0W*;ttkmLGY8DD+@lhJdfnT@82l0o17lV zLh|Y}uWf)29p!6)uDx@vjUgNUJXN#@lCt)?CFkbQEF-~ZS^(ED6sFK{8-G@=kaf=U z)AAep&b1>st5>}4hv7fzfsVZ`OWF(Lp1ie@U3$`dK9_Aagv?9;TsKb&VBuklBOt>o zydo#SB#f@UIj`DjXY$I^pMUYW&F}uj*EWBZ zSD>zo^XaZzZ`l08haZ`EOEwg~<%Z~JaIIr00Gqd8x1apQnp`+jP%7^rpS0}h+#t&N&Teo`c zs2+&}8+zwlCr{m`p6YhGQ>`4z*KM{sIt zZM*q~-&~AbIRY0-d%0Tu7GQutC6vZa)}{R(+(|oBrb~`vf02idy;?!&0UY_gMq$%Y z&KiA(P*~^t{0>WC=0tn3@G)?)_aTzBY2)Z6H?(6!7<**2@NQ@Q`aNxn)sN$34u7tv zo`il*&2{SCrN56tiqoXYX~Z99%2N;bz;cV};#+?({|;T$5nKH!}kRnfu1 z8RjreqRRvJOK)AqhaiK0+M87(Y)Kw_Mu%-XQp1sW0K+q|`6)j+z7ZaVC|rBtxr_;Y znw_J@Ls-t5_Sw5USeUx^_}8YvyA*h%5i!7Zz3I??Dv ztuW0azcf#cbxB^5Up)#I?cL4L#{PLFXec9R}p9JgOevTS=4EFF# z$9S>AL8ND~`1koeNoU9LP@d(j1I<81s2(^#=#VaxI8S%(&5E9Tx9_aN!M+4^lE5e8ZEBmb#IbnydDzzje$WtGZq-p`D~|QiL`rOZxIIpq2OoMk%UiSg<*jj| z=5xZ;LuI=fJ1Y(Pm%lt5rQhPM&Nx%8db4VbjdA|cG5z-y3g?33{v@-smlYIoKxAm< zNuyDk0i4hY>9ShJbxb)woHW;_T$P2d#CSEz+$PQn9#p;0U$r1c?h=zLNd>z?^IK^)2@+*PADp%(ZOU*~ zneLUFc49y5@aEQWE4P|Q{Ws>(u61nTcvWS+S=;f7s$z zvBze&ef#klPQFtf#tt(^xpe7Z#i&&ZCcyL{6xR7$$?r*cTW)9yigw*T=$G^{94z)y zdoA%o>e2a(aX3nk3%+`ITjKSp&sH*W*r;RrQFafXzFi-`Yafn7mUMj&UiZs*mnA|@ z+mhq1+`_vwHu6@iqL!m5mu0_LbX|EGWYr!7f3U_|c%Tk^lW#*m3iI=Dd> zJf2Qiolu_8If^En3kL=;f!Pw-hjm>!;Ou0=B+vwqvq8E+gbu}^S&*j_$L4nwg?&1e zAO7QX)jXBW^%@rL-b2GR$Ce0xaXWTUt@G=kf7u{(nJoD#l>Ft((Y3tGWNN{WPDA+v zCw8Du56ZIl;Sx;fZbA9r)sr?!5WYbA6nC-8+fjH69a+*YdR4)3W6m z(&B_;e|_DA9B7#&*Qr&Vb)t$UK7~$5O2@tZuzzp=8oV@etnoT$bNDlm^Tf3)YGweR zJjpovDURwx-gWuGFX9)>Oxz-CdFlNgD-WEqq>%e?zDid8RZ^pS4JZR2} zq}ZY&(~f9cW-?7r2GO%wWSkSJAJN{<@u9wO!pJuh{pf%rVPpcCdSk_ueR#@mWq&!7 zX7A#Al8hIhmG#+euaC_p#i4oUop+35S{c{A=m9M>(P@}HZ$d{3hez+ZF4$2k<7x-^ z6E6!3p`mFoPWN3=Gq;jKJDTLn!j#>%8=Xyv1BAxtXG?GPMv0za8NPF7e;|{w-NZj> zXbq2%--;>k!qY_^HCN(g&0KlFv_D5YEjGW%vxYzF{4c)r{N^|Q>?@l;%j-|)FD(w) z?|S|<4fI_l}~WWY~O@WeLMcPkCr{=6ASO;?;* zCGh&|S*6I1wq?*Zn?5;on(o>j9##;v4zU+;?&ZF8_NlGECaY>(hyAe$X<%Egowp4b z+lYJ%{N={;Ry%4!YTNfuaSwl^>($Q=24969VZz_sOub4@X zygR&2a_^YXzMIavy7-MaYKEWSKIqvNLOXu9bf<1jn|EOM`+OhCV&&b*wzS_%-AQed zz87}&ZJSkXCT}j+*KhUJpo+n%G9si_u8v|VeW(3!nKdJ z0&ZSO&+C5r5c2AWx&o(l#u3A#ztEf2;?qYB>cc-|5GhF9UJvbP$8i_jTc-qm`AgQO z7tc16W`6XXbbaS#Avnhlwt8_NPP|mF#@4$PHF?-`*IhQt&nwg!gO%T|V8h|;dzSpm zD)~jGliJjgyNrb&u&pPRzr2hH^pMDU)^+}m|M-tLzx~_4J$A}*Za*PkeDcMl({QSR zQw@CkG;r#uxq_}W%3=q3b+BmY+F(PWaR%d9nC2-C4iJtSlVlyA4y&P0!I!7X%hz{i zCwGmfhBU|JlgNGYvUH4S2s07Wp(UXAa=y6Y$)YFAUR^1F?t>NN)v1CPq~o1~!2q(a zCm1+Cl&2m#)lPW9itUt}-*I0L&0_!yzfjp->xio>_wZ947Ir$nq>pUTT?h6C_s;Rb zxkZmwhTz%2x}E*f!IE)#1x%+0SM`FvG8Ia@*I@SfbuBI(-jZ)J=chc@QDei)mtTpa zCM%@wyZ7$l4GnPUI=ZGGIHg@lzen*~SsaC+-3<`E0^sSgRT#?FM4#U1$UwPH8iVEP z436pmk1aoG=%Z6zffcUC9^@6_T;qk0lSVzMqo#Y*D6i#Jsw>-X^?*QA;Qr|Cj^JJ#wZ*%Z4NkgLmV$eDXxX-`!N^Y+ zg<0!;GUsQVwoFLb<+48q=ST1R9IFjWIdWdeiYa`_v(9g*So+wv8+&<>Ncg2Ae# z182#ykAcCPHbiU~8PmSl5O^1YTP+~NI&gX^Pha}5d8E9avUDcU z@74#gPif%gQx1h&C?5R2)sC72%x}-x&Zbhf824VNo4NP3(??`{nE_R{6U}4JY|Hz%(=o zVehi`M%^FhOYW;*Uz?~IcjSSORiIw?6cj55s(rcOQ;zzG-T!q%! z`099c7&^b{qVhA>@$Ty_I~iP0#H8t<4E8z!H5qKEL&1BhVh4F>h=Qkoc<=<=lW>C% zQJN@}ujb*TLDxXYBn$6&5jxOl{^Dz=h))w$e8Pc8OLRFw;1CPjfe`xpc<~|~9dOQj zjUS=%7H{R=ht;`*!H>z`ta=Eaml9u3NBGUiY0r>*@40((M~>u%yP;p9naxe351nS^ zt{w`Dc6oOMhc>w5_^phN0zTJ{8qONL-J6w3H)T%~c;E#m4}J|yst5PQt0}jASa<~! zzKam3G6>5MsTs+X33~0pgwmdPaN|U=aEFKLEHzw#*1EYtns6HB_8BmmsjoT{Dq5C zUuR&I+3k&4<;F>RDW4WScQKBedN z*z#RFt8OOKF+a=HvT_8S z+$-(kHxaQK2p08nbRG(WW+n*R%{J3c*dUtD&ZTYh^c6j?NBFYc!bRkXop}vxm}E-{ zORYb!xg8H=L1T_fmdS7xKVN?C!p5qa&wT0Z=JWXi)KlNMu(|Kf8#njeaZ|qj^uXq4 zz9*ZF=XEH$;?!ICJD5l+AADSW#`gb$E@;v?)m37Pvx~r<$c^{ z!sTgAYY4wZKgI7@8e=8wB?((G=N_2WArtGJ9@anudHAP!nrfw(Xl(IzI%?MZmNuTP z^H5)EukKBq&b^U3f-j}(&eCp>0nAahj1Kz{YY#1dn9z~`wLCCU)?HD=Q6u__61!Xn zeCB@_+y=AYPjb%D9T~S-wFF{X&7ryGSN;imvPpIimpgJHe3b4mbW~eHHg!h7YfRHV zf0u4$Z|=YPT3~WtUkl!NLtIvngc11Fn{7W-9j=e#AXSglCwF5q5)Vq zwFe)5q%8kC^q1)@3LJadmd6gz$yR4As~284yZKsd|D|k%e%HMmHFwV!vwStHVR%r6 z@WPoJ)j?r;EM7-pv5#-ZQ#`7zjjHLC!w&4kb^WJ2{({w6U$<(n*cA!A`r z;+L)}+uBhx8$@S-a?joOj1KFlLC1tv9_0^r_268*nsVEREe~*eV*7l`(uxb$>`gRK zG6~c%-k zag@B6eN0|_`YW6Js2tL8Y;l`Wtg|yh^jd4WZAVw#% z$#3+}fwQBt9o@+bH(c5e_T?OXd2he{&a6hdHD7mHoX5*xJPw+Sit*b3uksP9-`;B( zkK9{cd(YAR+Jn3ze6_Rkv(DqZ?YaEJOV}w#qmj_EGRc$D+78%VC@aq7tF7N=? zd{u?>J?FB8y`gCpq^ONMm%;pnywax5vSID-y{VtehQle>v?tfT7RP%s+at)*_E{wo zoaOH@4~sx6j?3DK$LBBP^QF&T*nI9QFKj;f`7@i(WM$2*H{~lmiNElnhY}y&+?~B@ zOxjbB1Q`bgI_TH-%F`j8ttcy}x7$&pUg2k_m+<_KcPw_cI8B#TP+&|PO?Z`&-imW= zY&-UCpAM7FSEPmS$_Vccck(E2eZ01v{I2y&OWzcorCdE-f9k0(P5XSDqo(-BHdEg0 z`K=7_HxAy>OY91*oSU?+LuK40EBg}y`0Bo392Ls@?RM0lSAI*o+>TyX_Aqs8Co|h< zj>9;Pvf;`|&b6%!wV7o^Rm@zoV&|Z<3G9jwm-D{aSHjEP`GN6lp zIGoE@N6_>QE970NGaJi?fq|dQOJ7~w2ge2R3dQJ{4o0VuQ+;;5=stLcljYYQJ>=Kt zT1h32eI(yYsaN#ldXZtF!sgW_ah%@aPamy6YMr9@Hxd@!4stB7OOCr`5>K*+eVxJ8 z_7|_0*U>oQBa^b@y>ZrL& zC2I^dggPLdhz8FSwdpi6iP1RrUK?tT4$-98WYBK^Iw5#`;l!&3^Ch6HWH5-+xVqPl zw;d0>(p-aU!(2KG+bzwS4k4wm~n=!j^U?u6RY;V9KYht@r^ejl6I-$SX=W zu|QKtB$iI`I|{{7-EnBl{t}T94U?4OFi3VS_WasBk+{Z0#+Qk*g!I-s@(Rywd8HyN zR;mX__>0GR^;$j(TUqw?3l2X*Wvd?Kg|F9OO0N#3S2FoR-~KfBWmS@ag?#dmMWAE2 zi|07J(hZ=|@PrC{^}DY#t7%?5_u|+egC$45GN6n(CQLjnxiwg-qXteoC=bJ6e&lyg z7(T)Snq=!>Nxtf;dUh>e^9+J54r$dd=fz7|wc^v$FMjnan-}7!x$j-?+T5RLP)6o8 zPw=9L4jnY0IEFUV(Wn~;#g%x=QH6n@eH3}zz0F>F`GcfCcApW#BySE%8@g?g!P4|43d*) zY2%i5?^1LsjochGcig#bn#hqwM-6y|qw=_Jx#4HgZ=siCWpvei&ew7`FWm4|zwoW| z%V*#X&ypTI61U+v{r3JES9zHt@e@RF?Ux0o54oNx~xIgeNR^{Td0ZjGMw8N9s zrXD_)_AZq^$J!TC?hB6i>9w@3DEW3cYS3GU@?CqF8XA))GdX%of)D z+Cl4IVVcK%;}`u*U+q1#nea+q({#}17JqT9kEQ9@a9p_osiOug*&3YLTgrOB)Zn4n zdR)|N_y9EPkwit%X(FFbEwKU@)*XS*6g9lQU0Zx5iCGb`gcYR*RPuYc|7oWGL2?y@O+R@G=b#dQeE2|GS}JsfT!bCWJaJP6eR zKK28U+JQ2aLz-AQRbi_6{onun&9D91ug&=A@y8$Ee9!lM&*lez@CP^VfB*aU(VkwP zYT#4@Z=(iI9W_^>+-Zc|eT7^B5OVW5Oh z{B$x%hqVX1;I9Fn?g_o;J{<7EA*}hYJknbh&IR`x<>9;-M@ zs4ZqosT!$Lv12y&-h`s4B5LowMaAA?)r!6M-mzjwtY6-r?|uKDzw)@Q^E%J-^*o+O zT<~;1iuzaw)pK#L{gveUZ*usJm;PB%bI$! z)3TtTSrN2b(q z_lsk1XTD%W+H~Z_p}PJP?rk(>oTg^yw5%$;@-2r_b-x*Y+ziT{Aff;T+kCcZkOPj`7v-55Ykl#P?A-S0u6Wtu#H3}hh z`O$=__Hf{?p%>-&myk}3YVj5UG~w~<-TWIu>=)$#+v`O~=<+205t*^hv5NjF90?F@)VNmxv(?5tK59hUpZ?82n>nHzZkG4AMa zNlqSGJ`rVuPfuBW_+R%7h*_nlh+Krp=8mTWT+xX6smT-RR#D)GN z3(rukn0sO8%a5^>VO1{238RA@M3*M{SN>PMJU?(vUk#7M&rhkE+PMBXnd4R?Rv88I^pPh zN8tO_6SJYm$!%(k6;{XLnN@05TG0$NkBjz3^(R!uY@MezFv#wJ#);7bE!FR~$kI6@ zO}G<3IU2Ox*_C2)Im$!7xi$eqfKy?6Q|@y^au?x^N2Q@;?BrqXjOw@_)S%*n;9nJ4 z=w$~O`v8#_MQY9*kaklDV>i`Z6@D6U!+?semnfpONXje)#%IXw6LENW7cMD=g!*L zzL8&>Xo=(BNH4`SYQD3(?pQG{87C!R_pZU?U6o8xI;Yjs%914m2!rSP)JB;XZfa{) ziQIO8{N9<<;24pIkvpSD!~-9aU^h(T;gt9qsO|}9E%oPR(NVGCV1^8wDb4UW`!a)+ zJ$}<1?pm4G>E-V>g!T9tbHC@-Q{YUjjen3@oX6nUio;w0!YPI$|Mmn|F=efQ6GR};H zr-x+5K&Q&?cT9oX#MZWeozn}4>r%%PB1xe(7p3Ur@~}WXSe33AEhWUX{wA1HsCt9U z&3$1)%R0cgN=R6yZqp7mPtW=182wc|r`D&4XN%pZ6)OpZ!{lf#+>k$M;g!YBS#2Cl zLz|)!BH-LG49~Rie01aY)}#Sj2%2_eMh#>e&Yj@oF#4EfMepjh9`NB5+|zDvo5)8# zpz7t`QmKo}BdZZKzo_C&W0u*@@CQi!qkQaU!Nz-?I}rONh?!PTnagNz-&nX8OL4LQ z$J69x%!?!|MnuTYP&TY{fILV|L|=vSdBkh$+Q+Q^gn!COd0xLB{P^qwYoNW>%veOg zwAUT4)%AVw`)PReI?W+|7_{yq6H@zzLT!8Z*NyJ0^u86tAy72Tv!(VtM4G(Kqi;~51l zGc>>b#~QbjgNZ?y2`~-lX!tFyLPGCb$l18C876(J)cUhEop>tioLXQ^2Hau78k}q8 zD3P=wCr_~HXgt$Bc@4xy)f#emxW|NAOg^i3V7Ia^DS>n&{$^J7*7*I6($T@XkTg^z z585}n@D@mYaF#!FbDgW0*6ks_WU@6SuBJZZ@?2qpGjVCVa#?&$-3k25dP3eOSu8lu zm9p};#XaS4%|_2=^OJC4l%g0%eT)!65%~J=)${tDn)u6O?59)7Y$B(wMiH{(ZABaF zdY7R$ZI5Pok1}0`o$o-yNXdonf{QU9X9iBAEa$ee#MMi}egwT_OH}XJ{-AbF*vL{e zHdos~HccMUPI8BQo&SPG&qRSFMPUVi*AWoSqi*V0Z|D-4p!xa2UoUO3K6ISJ%(En! zk$3g$t_4IP{0|prL)0v+o=%{bs(mheti0F2-liRj$pY+`i=@K;6*mhL;<}!sXIlgR z2PF*s2PM2YE?OEl`~@^rjVDyQ9|hzT>6c_5MFxKc8nZ@H%j`sX5XHp}w=`#Q9^RcE zwy|eN2C6@rK5#Ah(onqADlZnb{#xlgFpnr?D|CjILyt`)+keP6u}dfu$$x-XBf`C0 z;CmVY&dY0YMT#o`77kkh%8y0-CH&J@4`e^)c}ap+#WKe2XQLI;RnBsg4zmSmCH=n= z)w#c+gDR(a&Bb;LGi^x<}Z#1Wm{5h1MTl;fE`rGa9J&wt7OHYed>3&h-cXlH^{A}^@hrKW_w4?4T$%ds7!P;0a z#bQ`P=aP0Fm}V_Y-pzA9OQ4kYz5m9M{i&9{Nm}$h`Xo&f*k>5YoPuzCF`RWP&!K4K zAVA|eBVs~upr5c*+`&aT2}_?BPkNdpN^z;SFFdsV(UCCTb;rzr<31G zSaj}UC^tW?ox~Gc>tnD*FS@TKb^)7#60zZE9Ts?qquAlbEQ_OF9`-l;d3GFRqg~6p zQ!5pvq@{c}Dn699>3Uf)N$PsW*6RAW8!8OB#Mk~iN+R8BFh6S66SnroNt~G)FOdq< zETjzd=$pQ>%^Dy)jG!q|OL~b}wk$>*_!h*10N|6E3NEYN zzdYEO*AULpc}!yL{PTL=GQjBEdd^&HlcA!0dg;_sqHtkxjV@Yi22p8U!Q*VCt!=ib z;8R|nBAlLwcAkBZGBihTfd0XDH8iIIwW+V>$;wOhc;k5_E_f9-R_FXDYJZm+*XsHF z`vxEYnAEzlnfe8#qhD;v-U#*%sXj}Z&pIsPcX9u9)cRDuuX%}^({iq*nycwqJ$gl@ zgZpywC>dZXa9ULI&+N7yG?~wji~2V8Eke|=iUI6n(t}q$MLCYHT4sj7V7lo87cTRr z*ssQtT`VRLnF_V@a6^Ah?Q(SiVtcZca^<9f^B2f^S z<3g#SJw}$ncZj4R;fp+#9cv{-o>?lK&VVRMO2S`o45 z7%);KkX6O^vciT#-YoD&xbaq>vp1dS5D*o}_0eYd|K;^Nt_AkJ&*~RKC-dA@{^K2m z3;x?H&^?--$wr$#_|p z_c!U0BpwnXBR}dlY6jYvs#sM?Y1${m8)?E-&<~278h#J2@n;C8V=Y2eh;_xH3lVOj z;9NCDA|DwcS$m_hk%H%{lRytfVz>82G1y9AZ+1iH^#+nxT z<-nJ|QNI1G6#T-6YWkElX!ge*gAYPt6jCt=URG(pty_>o+VSVWxXF1%WawOq=R0PSycPM0A1Q1i`WBusO?(cTP9LeX zs6I_*awf$zmhH|krqHpo-fQPVeo8X{c138!zwG2YxJ8sEEyp)F6W4UPrp0vAl@)Hy zMu>K@y^5Ot|6Kqa0DgPQS<26R>BhEBZY=sHsw@Kgvj$0xy5qgrX?aqc+t{z8^`;F! zk8i*&mQI~!fNX4U%Lp012IDsU^at7%9LJ-Eq8X^%jF8E)XCK`@I*B|1VpCw24s#WZ zyqr=fF6P3+(x+Q73iz?Wb*=3d(bUa)+>%Zk3$$t5#lb1|u<>gxo$%!|w=VG ze_CZWyTA)&Vs>9$!#~$+Pr=dkX{R{=nE7)H&qjP^QOrxmrm+&9f!8guD{RZtLtQbR zY~-xq0dmErv6oI4K+!Gj1g?E&sR|v{@(Dn*e=eWZ`EIGtRE~IkdSh>UQ7T!gzo$YN zWpX6{(n25Z1Yv|x$RxX&bTc4okhzcpQE&1X--Y>I&(%c2q?kC{+Xx74QU27(zQQpY z3Apcllw{5@%+|b6)ho(mwEf{cL(TZP@k{Fz5oX$rI%_f=D_ArKb>F4aiO~pX*%3wq zEAu%Bfw1Vq4tnGca9V^|e@s)!WKxV&1ph=&VOFi6)No$mM!t38@Nc%0&Xq0@2Umc` zM+t{eo=7NoJR;m$9eH!rbXDEwbKP` z%dTmyssj=p7>VkZU4PmDN4EVNTsZai!C)o>)=NdkQ2WvNNjDDz1A~~) z;6kM~#!E}>oQ)b4NSnpzM{_3U3J)JC$U#e`(=AfwU6=cr{`_{U0z(D&fRBg@oqx!5 zJ}C2!qkaZmD;KXAdF{P5?3B-tMNy%oE6clWX5ir|L~%;YH2T3|Z{=zmn%b>43FT8g z3rO>7d{wue&Wl5^*^PgxGh2DU+KDN4nlRO8{T3VH-XkUA-dsfV*q@K+p^7gsjcwk0 zsfCu+lkj@`u*@%a8k3$SYcAJLrusJY?Q907lu8ik6Wy=dmd(A)3XW}A_F8-8wkY)E zz+~iK*9pq%@DsyQVez8ntI&oIraBAz?%|fG&v90IOj2AHZ0=5sUrdSnGC6Aj)z!<% z^-HR(YgXzcR@48eLB}RWPh6f53Q}oNXc~7}$m~clFF|wmKKeBN z12j0E|)*sIDWXBst(4GzBXm$NQdlLJB2c}Yb@sL z=ZJW!m4CckVJgZRc`7?&?z_u7tWio9<8|{D#ordh#6tRWcDI#Sw`)|JvUk|gpVxxe zJlxP`zYThHP3_(ibf`XWtgAHoWP zW8bUXU2*MuuCM6H4yZZJ8xgwwIOu4&KWjm}z4S@e3|)A<-q3m9!ev;W4_@jowq)!%9dvk4r3a2F+a zxpnv)NgZRwB4}`6mX;VO><`Z4fSe1OWwfc}ZVjzYG>4T3L|Gl{_Ix$*Yq- zaCvJ>RJ7%=%$Vv(3y%lY80qu}=Z$3JW>`N}X-UBACin$D#)magzLxQi-LJP?KB#wy zNF{6xHU-mB8p#(x{&X;p5v#PZ>k#-%jBiMc+P3GfDT0zxcXKL=l{O3Q!$N~L zka}dhizuUmU(w~7vwqrb%N%%WbZ3MU&iXG+9dLTUbiYLgbVsj@Tc`siTQS7tgO)Z+ zAV6G#VR_A~ZX03?q9-lqsxBI0uTry|zQYYZGIh2oS;f84b_jwWhO7qFpPb(xJk9i& z2T)FqZ}t8208m`cES~2SRf+oWSnKUfA%Zc5x2;k}?5A955$qVwU?rm8D zz1W|5(4_*kQcbdO#3Yq#5B_ec->)-vJWFxiIepkNQAeq=3~hp??^iz?43PW*(>65v zG_Z9zTN@{QGmr)oWTud6e0~(+x=?>UMI&D0e&%0oy;t`Vf~$MlKiHK{T7MU0v}?Rz zV;QB-UL_Uwi9^U>ED8T+KZy!mE;QMwT`bqsCqr^BB7juq=p!PWFf>yB)uY}gwMvTL zQ%x&Gj4RVTE9!uWrU_OtO{B^>S@?UHzOW^#8-winV3ikK6otcTB9q){@kVG!5NX4U&9 zUwR<-_OJ^#eeUTk4fm}!F%CCg6{drZ1{cR1$@Ge|a7*U>Mpu)}{_oqNimD(pnB&gG zrCe1rYAge9re!uVh4IZ=UoMJ;9hbW5j~A~DkSD!zL(4HLUs0shJA^3NszcqrkZk`N zIONcq+0d>nP_&A+#-uT2Gjf%IH_$rGhu-Wn;?`k*_OgRIxz$JF6_tP{omHC)eJcHZFFIk!PK$Djd*w4xV6P|^Pne+K<8VC^)gket&A zv^oe-vigV=bDz$k9j5l+mY4BXWZFL;R_LGct$r@p9##a+K)=h1L|X0CY4ltNZNrOG+W zkn4gdj$|UUe=xiK$4BVPe(5(UC2RSaFmfw6kZ)r)oyZ&a+12M`Sf8S3lu|R7V^2C? ztZnDvFG+3;%1W@)k33X1Pk3x>dxfkgGT3k)WOeU;~q;YFs!QAk~F~HM=Jd# zTCL7(vZ+~()BjFY=ed(INtyEkq*vncNE5W@45cv|5NF_k<%FX9`P}RK2eO#!H8G< zsc>>PB8+g-Flxds*Xrh_z9*=j{g7 z+FysN%b`ul`v(86q}kC{gT(p((z7WFfUWliKfxw<3Pn|kGS|CZ2RJ5m?zwfY!_FYp z?u)TjzdV&S{x+r}XU%7xBLKp4sW^guTuGonE9fx0U+SpWB|NeDNBwS9k%ywb^+>*H z$^lg}xC3@IthGX|cdxX(+Vi9GR?2FAh9{nJMyXMajYY^&U2=xcVNQBHg`4z!Pio`a z3*#J~mc+c(@;6UhL{58iX)^mcoi*Skn;@dW)^=LKuu&TB;U!4&iv1$kE z_=cE;YzMbg=FX9Jnsb_%tw9J*4|lur=M|mcJf-&cXBHOCGUDL z%$zO~g&BnH8LNp-u$xne%iiAw9b${}->u7dF71Y0Qm1h5u6x$A2-fqFJ#86b#^4zvpwpv<0IzM-~I0#QKmFaVM^oOT5<11rmy#GM&fi77Wm#(kN2`T z_Dkko=PSHrH1Iqkry!D@ZRHEDuRSKSyc9@+42ye7EZn`{Vx6ON{B zX5i*>z}9;+$lI&~X?6Oa07ji?LGu5!RFx!OphkQL9;w$T`i<6+fwVdCl)TLSuGN-p z5%FEuRZE%b@7*4x*liM!|7$aKm_wq!ktD!vYt0FR>@2k#Sijy;{1Q+7r`fX0`C0$c zRIc}DRq!Kf8wG9_-i?d^4z{JVYpj-I++rvj+@P6ZWyb5igYr!Ob8iy zph86FM)gH6+>uKqaF6i=p>sWfw%f=yoS=^ZT(1?3wy+6uEV`+4EMhfb8Xe9-nxciw zWrGV$o3;vj395?L4D%}4qui_{YGbO3s zh%1>=e`-ng>9bVvgsN;5NNS4&bSy1}jYYB@0Mvs3owZAXs!5M#1P)E#ZD?d)v#9>) z{aQt&&GjO(pMWV5J~EKYVX!dBdy6Y+Ti?Um@j`gO#>Qi}z0Vn$y3pWoy;HXTc{-MG zMSS|-xchPybiFDIAI|b~*kco9Il=7ov1m=*oBJ6QWy&?JI)#jvi-lcPiBC8rE+*!8 zW^)P+Y(|A~qUbzFqnDys1Os0CI8qX!4O7M)vAf2iMKiAIDyMbuzcM>oPILG|%F(~h z(oj9f_}TbIPTq}B%Qu$`&@O>`lZRn{Ea91{C6knH^h7fx5+*z=`9l}U153u`e_S+u zx9>-UL@1JzD&y!F^5#vooC-%IqiN)UzFD}wQ0CSrbBG8LXTyAGo}8YVvn>r~_}&2?Bt$aB~~H8Ds;ns=8M=~e}00f;aZ zn>#3xtv!Y0aD~-6<0M2`Id@D6D_Vud0p!9T+pahhJbu>>H3HJu>G!*F$>8{f4o5tRano zLA<Q$Q*@%ra`vGf*UfoUA|-EP{uMxCw06|lkXE+L?jow zxBhH)zihl`7R{qeb*KR$nZquT^`7uQXtY0;^GT`LT`35S$vI;se7%1L-X>xpQF2`; z6T1F)^<^r1#kddYiO$YAo8Y~uDrb8vAoVzkiuyrBl$-$e;NJsD#O=oloX;c*buu~Q z-VXjQVpbM;C~B@mUg$r}l~%mfUCJvlOmn59YW$=9ylw0IiN;zKxJYUB6$-Oz5pEYN zB>v1@^nUSFEEUC1pS?A&p&q{XuK*?weh-M^(7)sk&bHrk^kNEu2o_m99TkwF6Rgi1 zqBhzb-QEgVhmr&uT49Rve#7d(SFwcvlO?lN3 zw$hEm9GJz7uHNKN?Ib0cWQH-<-_I(sLNSjL#~mX&%51? z_Aa}pNO$)!idnHcK8pC?TJQe|k?(KnzmA4>9+s4sFXjM%8QWR7k23$(m-Drzt)kvyN=kCx2Mj*;&mFpurX1l8Q0Vk?>zq?h7D0?nvY=Y5;hhj$(^uA= zFaN=_IHPpoekWWmPOh_v$KbZ8ORKPZmZDu3gu~`p`9r%#2(c%O|Gk8sn0c(wGlF8b zkXtJ`1T7~z3fJcN3&GS)0#{K-(>r*xe=?8-r3)(uNs&yoG9K#i9#%s23KN$_1!p-Q zz-hDVt`EjTfOO*LqR;b;LlJV5_^(~|7|Uaa`wq5dc~>bbEh%$aShFC2C3~c#Gk;al zToynVVVl+V1WTTDkUjPSzUk>}fT_V>=?n zz1ei;gP%_T2|v*VxJ+7376<(foD0FHW3#jXjjSt4(djG7@ zz@y1+!pq8Whx+ix^D&g!u%X`0t<{Io%m!O5OQ%7=QTCkBIFHJm^8Ee?W(cNT1YhxV z#{Py!Lgb)ucFfbgNaY<|b3$f=>iLWiWP~2ob`gDMc)>b7Ny^g9HnqJSY=$N^!iRJ% zNEV4l_y30w*j&#wUAT^H-1PXI1B9inSEM8_nT*p2Ud#V5g1rB&9(6*C2k75&W7m8P zWrgeT`m%#LJ;~cC;AFm%l8T{!rBS{ow|YF!V)03jaKqs(`D6|$f=m}d?ESPcRx_#GD) zU*z=XW|yTHk;ydg>*aMzD8NSYwBD!Yd~*MCX}y=>#=-Gmt7*Q$W$D~rZt9huzJMtE zvF*)e+Rag46OQ4=NCPzJd~OKA)aNTd+|FOpY<$UOQLMNSJW&lCjip8#m`5#8%PU`0 zw%gl32|oDPbgS)r26Un!MfwNqI*wODDmE%enl^Ipv&7a#mfovH_*dnj-|HDUW|nEo zyUfH8Irg5My!Vj7qS#2+x6Mh%D_qtBv2S+7ERL;(HC4;sY!?KaYdHW#LyZIWCP&aU zTq}!@gM3W33Y??U1j za1`#+=d(uxeQaSn>Zpt5>^dnp`R!1z77knz;XA(~{sJ zl%!f~WVPq+@+giqqs3~kKRV4(e2-={`u)2Z&+-6nF9|kZ294B+r@%Ws^rKvGORg50 zvDY-xa(RiXIcz|oBGWrnQDh5klV4NO6>FmI4m3N|k{iZE=E&|z59$CcSJNR^lFtR9 z1hAsB>9VJ(;k+OXUof|QK=E&D|Nnr4!T${qxRY@9!|}XH6_5YT!Uh_X>i4d1rs|Ju z`-%%~jzN*1Ults5zaOo>^DFb!tJ4Nb;?g!leyb89;vgB;T^9o`P&_T#!TV5Q#}<0NuU76e+-YQ3Y)Ey>CXDt_BW$}x962%GXWB~)q3`geeqd`1^bIUOG7VAeFeHLT^Nf|C$FtsgJ2|+if`J>+VTUXqQBXZVVePJ@n))MrKUzsX$5YdqqA-b6VC9 z>H#e5YGp`SBhe`93P@JGv zwv^N4mM_paIBPvJa|m>oLg=a6<}K={RS#h`nGxxfsJ0NN^Tn?k+Q*4yhuDg!tU$@t zkm(IwTf5-6XgCjY;(=)S@1^MgzG(_3bO_XlW@w7_zv(abHD~anbVJf zQLxi3`QwiRi$+mUKdF+T&ITLoZyvq$_ddsy8~LMJZ}7D%ot@{;7NgfLA7$~oZM0lP zLe9+oa5~^w&)3&n@vPT+OZSR5v$s*l$fiT>(conrNYtN0+PTV z-nf6K1+@7f2#mb0_tC#vu=TpYG)dvF#~OuUcFxOPxDN);i=<2{Jb&$89uschFzoGzV_I;f1!2ceo>IWuXiN3Pz;`Yw^27n?^Lz%S6-t+!cbby z^rV+6sDHcq!J-oV_zXSRSaj?y6T?ovVNVbZyG@>k8>B~r%<^KJocdn@`0y8*W!~MS z{7-Lz47<4&d9HeMo?~_uH!Cxk#vbKe>A7~fQDo4U4SJQJhZD_J9u>=<*mtewy}#~b zML&ta3czWjuE|?V5)+kd9E_2uI4-eV8nBam(e!iB+=zTo0qdh?p^7B4{ae#2iSyQK zHA@f@XRBV*6}MqjXzjBUp550@0?WI))|LL1Sv5G4n@`+zyUX<2k9^8#oj+S9V1$K3 z#`i1vgyx8uycMXd7|i5WGwFheQ$CmIg!ngZ*RF=6=;(T(dj;nL=bpVq4ld^5DbwHd ziIOHCzr+AO(82ubT?58!kD^5UOei$(kDvLkycv1Lsh@atTexMISaQOJH>cX_@ONG; zgYWD93k?S|v0^yiCMoIIKEjgbEgKJ^X5>RSIA-1&iAhWK*jPNi|C{Pqv(j$#(@5@c z>{nZ-!R_$n`<7ir+jsYK{EL&&p={V8bLTMYGnoiKYp(#>>O=jLLhxVjGgqJLnRP|| z!^p8}*i7|bDYjb!-jfr}C=y92rb*Y)WVrz##9uM>ZM|>;cC~Y4rQGt?sOtCSNNQex zyC#({tc`hnyZHqw(@$dN9%9!KLO{b5dq4O?g7|HiKV!hpTr^?tb{@7l<`03tGIdA$ z_x*U_WzalBW^&M`a8fX1vqhEyPTR>>)t~ALm3ND#-Q3hvu91+aMVd4=WrCBe&d)|~ zapT1_#omjQ*jco$k~PSDjS-&w2zB#Y_@)JP0CcDtlm6jsq?eh{-Q``fm!q10_{^49WWL+;3rvxSni_oeP_TY?>!E z>hu)<{as*e`p@(p($V{hx`8XPG{N*dWpC;6DQd06Pd-#%34T>2ZGMqBWw2Alkevet ziG9R=I8r}b-1+KQgFFg99y88com6htFv>$G9QU&dcB0?6CEQ3)tp=BYkk9n&>>Dk> z2Mxof)N(;ttnW?3ho~6aIA@dY#Q*DJt%+@Pl8(KD_)=o!^M-$$jr_aPs_#hx`xwz$ zu;q$kLIEn%(%tybhLQ>Xl==kRxTS{xUtgUdn5CSqFz|4cqx13n472j}qVKL*eG`_V zsf187gwOGQ#wF3hMJ#V|W^m>ysKHXuRod1vLYfV(*I=M8b$i+N$N6n>;ANIi)`;ld z;N%v0_#ec=ZcX8_cNnQeFkSN57XbNb=3hGHzyuZ|i;bqRyz9jYKcSY#2++G!R>_7r z)$-WCn<6Vet!6M>pT2{uUXX8JgSC>wZ)j;u`KRBvXwRBISb5q#3V#D|NpKN!V>dQB z6!8dM2&jX^omg-L<`uTsrf^NN5fNoux^ zFy1%R^oCn+pK`LGhoQd33~k)PEwm;akHSnvXyvJt2K%ffaIHk-bMS5X>affNRu}sZ zRN~odp@w(HyeWKv`|h&c-*W1&nQll>Ion5dN^5x_^XuqTZ#xU@_e_PPA+4(&gX(pd zpi7dch^vxB{LOFodyZ2hMjgf=2%z@DmYx*AbE-#! z;O9Q7gN$pOwV_B(1+nKN&8Vz(fx7YAN!gobw8I&g)qj+7#eQB`BZG2-|{k%-u!#0t1yPm?8Ya%A(w zHr(Z?3%Q8SOs4l$bhhuuS{D{9%);)ft>nXTA#OTZ{>J&{g7pZgMAZ;(! zQMfSJ6ycMcA&8GW>SspMp5Fdb*|qxR0XE$xvs0xARnED?(Ok*9Mcg&Zf#{6^>sQt- ze};la5gL^`VWCGQ3RRnL@%Oxj=QxqurO}_$Ovsc*TG(~C61CJ{&p4h9qa=kvzguGd zwDG79Q@>XMZEiC)_?%Sv=mg(fr&j-!JV*KHveq7rvwlWu{I?OG9YRPrF?!mWRREqk zIIto-4h8>-Scu>N@lI(0a)7|!BFI+`N$ zk!1REz9C&t`z6bON|TxthI{}95fDkSE%t`Pn2ou$i7!d%`&>rzIm^^{5(}klXg43( zz@K!Ba=kpy)9n`9vf-hfHv-RnFI2%kvjA;X1Ce{A6bUq8D4~_mx_(>mm9K{bZ@rny zA6CH*acgV+a5p%A)xc%`p;LLR&*gOSuY`0NcA13?i5@m7P*#u#GJ02!<>g=E8oS?F z-wkF?g-_s6JRfvuAXln9sbd?&_BF?5iqdR90YTfeo#))%eTGD4euZ&+6Qc`U)Z zuZ@d>$Y3^xPnqy+jx^5M%4TBIUuTv^1CwJqY&ulp-)&@W4@vTBSeLqq{dj-Upa6{- zqkdUfSQ-l7<&)5Q2WQ$n`meAKyl}v}Fyu%iz8?gm+Ob?b%JU_3b(%Y+kSPMq(-TU1 zNkz{c@d@Q|p%vEGk0rY`qqU*5 z`xy`PTQ4|j?<6Ud2m9e+>H1?O(tKpt1UFK0fXwkNfOxT@Scpw*Lo*#p`LJD?cZmPe zX=#>Z=!K2Az1S43?%Gf%fYa}j{IjWb+AHPDKwI}D%;P3UeXQDD&x6wfpc1aBM|CCU zO~@PC$0Cc`fnBep#Gz#|ds_81gA@GlwQ1+3k1R z=W7x9-s0NKjWo-T^+sjJA=Fv&74^!o#c!)bd>6q09U*hqe%v!108bt;{-{x*s_Py> z-m7$%h`?(E|!=BvFIJ7RG2 z)i-SzqMPFhM7_-wQn?+tOQ0IJFs1-ctuSZEG^uJ9a{p*L>N=cl02xphAjbUYVyDc! z_esz}21A1LNg*L@)K^mQHvfSlj0&p4os_s#%OPz|To=MNl{*Q~NH~3qsxtg>MEL}26TxU+cdYNqQtLEG%ei~iA-2k?o_J! z7M&ni>2M4TPl3@a(-eO)dSCS0rN1*d*6z}P0DsxOV0a4)qaOU0cT7-^u^52IY%=ZR ztr}x>a}qnrdOU9H-Q`YSQDQD50*-Oa++BRIJ@C4O_=)nY0(-&5sLsld2>(o;JjYSH zKXwk00lj7~;yLGa9I3%IyIz$^Xx~;B*|Z|b+v1$(4YRRI{O&`qI;Ph{q{aBUbKr@3Gv96UBaL|4WS7)A| zu?Y^nx}*J(P8beDj`^kAtPUpWA=FFo(BmyheDe0~242@uP4x^{XI2$x2AQPkhVy%< z+0R^rCvQtqT{C1j$GUJO#egUrASPpVl-tHBwf4GwVoJiy^S76+EpaiJ!y=PM*SU`t z^P`b-l#!{@PErKJ4q2KRYy8#0kup?%|2l>&t(3Hm8J>vG)KY#TB0}I00EG%GF_sN> zgBgctvQ4tRB^sLH(>oNB;%|3vQ{$AsFXwLsTPc5s$FlAJ)uYIj)wfpbOl`<3j-lHm zzIJB?Y%8+?jgFaMx#ClIMrL{_gys7<5o{^Y)>@0aN%22YhDy;LOMS-_w#f>PDa76* zf~R5|45<$~cJ8OSD|0#%O5klSUG{_L4pu6A5IFaA6v{rEnyO0L#M8;V#b7A=@9+}K zf~-@gq6v*2kYOTY##q#X+YM7q=7avn)||z7p%?d;-8Y7w>F9FKJMXfgXn_;+#E3Lc z>d+3hJe_doBV@ICSZ-49!EqD5Jy8ifGd%F?xI<&i*Yk=cDSpOev&yuB`f^w}1#Rz? ziz<&I16WFEJaulY3PM|UaHwYp#=TQt&0*~cnuyukxFW(SulYm0uNK3qk&<>RtO&v) zvJJL{%|VI?i%2+lse_kvdja4v6r!>0JR#xky!LH{E9h)i4Q?c)xqDw3Cd@plA}cNo zi0M3EJZqy1i?AO(UUs%XV2G4@)XnK_+2krla=hiG9M_veoOV7lEJOM4HkGQr(!dN% zo;caUP;-whISUV*y$yVbY;kH<@b+(OIozhbRmQEED59zDPL5jA=7g)1ZHqZM9pv=M z6fC})sPV-0C_lWLE2t&H<@-=xV-1u4*E1_|uOx~vqEu1wLbh#4>`q!AD93g<5X>^A zbKIadGp8QQA4#P8iFqVXGhbfH3I%yBmB%9ZF~~gqWexJCaT4OQS4a3^`i%1zz;+V< zMTX4?+tBuWZsGk%etPZx(5;(^EPDKIc7PfLja2IBvoNcjxL!z2v{ii0wMio786ji9w2_ zNEZ&@)Fn3OcWhld8uK;QJO-50AyoT;wo*P2B7u_q{3(Cd%}0E0mBWROBby($fD{u> zB)}~ZK8Kpb20~VJ)RNOD?49H*$H2FP9gRD zYRI*IUP-&U9MT~4PBI{rCIw8-7C{WcwPabE{0?=CB;nzWc-OFAknFo~>w6h=*%%8Z z+3iZ@1AY<6CT;S>`UV&4wglrI#Jc4yDaNTD(B8;h74{Al?okf zwJBMC5p`PnNGG9O%=wfy%`A#It+)rTjiI!@4Owi*zG6*tg0>DqN28Ss>p68Dop&D= zfJ{|R?`vh9EmBfX@cZf=mi!B{6=PxZ*xbYrN`&-bh0E=xVsYwT**GzKmECwl2r5|( z%2xWC_QBzjbAL|*d@1a0ZO8nqe|yqlfy~5P4i9@>yXrBGt0YX!+he5?5y59f;#OQO ztKG}(h1i&d8dO#a!HR_{i^9tN8%i#jo8;rXfijdMl5S0mS@|IjFzxz zh)x-~B_D;?33<(}xf-1c>Q~Zi**rR)pwY0Bmp)+CLTL89x8*R$XB_iismFMug{ak0 z+xa8I42joDx7j|{pD&>S-k;&1 zkQTM)oFRiNPw4D5_&9H;oc*201x_IKubOVGoZC9Dv!pHUI(m>sVLJ zBOm5iB3^TUGOgTek{t@BXIvVor28_V-=LA8&+=MHfo?3ogZ3H7z(c&aETYmE141{a zHAGYO;+fc@)f_*njXg~pd}6a`xm~zG+^o9#W1^}YZ*31|jBy^v>^W$h7`Bc{Hm;k? zhv7fh->QB6Q^QSjVS+{xP^D~RD4zgywe{IFo0rV6NlL&!5qSHivpA8d9>Ei8D=9m; z;q{2|uw3lKxf8T z-AL7`A18K^Pgu6+YO%Uw&TnM@|Iu{TQBD4j7Z*WLDV2{PEg~f?y%9=?N{I*qfzi?p zW5hN>M5IJOB*vs0q`RdhMvai}Q3Ez&)Ng*z`Teo8f1h)nbDr~l-}}1vMoY`=)aD-) zRLSZyHbtSBln&UMXHAhs(^!H3k zI!?vEo>E)E61RLNm|Qza@Y9n9x- zE2wC(3tlvq07dq+VRpOhTs_HNw+~-H?wUPL4CC(n-K4M7OW2Enl{~bre-$^h4JzD~ z#Xlp5e(p*uu^*fhm?JL+{XKe5S}d05d`Xz=>6*Yd35UxDu#$NG$+u*4rNvvRG*+#( zrHU2Mt0o_x^&hiByh&iHUg@<3YSG-$se96X*;LQNsOaUcJ1)pfX+&mrUH7}i%B;tv zq3~z_(|i-|7lYFV+LTR-iLKtw`?;KDbYe(y-_=J%5NGHfYW;d7Dxv|HQdMQ5ZTpnjXryDMn3>94Pj_p5t}*B6jA zrMm@i;~8>wm)d>d0jbJK@`g<$=Z$smy2EW2+0v0d3-S`AzJzy0l44dZ@1L};g4;S) zTBxuJi%7n%1fK06tVY16x$8HsVrmeR`66q6{Uw2*mLu=Nt7XImsxT(tM5Rz&n@!ku zV3J)n3^wSQHp*ZKL{BHdH*I#}oAXkM+k4-LuUXGD{NHi**Z)|a*>d%0<)%b9rAGH$ zdjU(YvwFj6L+x#(@b-R((P(Lh5LQQ_>aeKoL{mD*U#a?upoQ~=PstV_yn44PIpC2|q_Jstq zq!7v4$<_OeB#5RLEp+tHte|=5;%VcWRH@MgX$wPlkK>X+D#jZ3 zfv@|BJa0BXUK9IQWCH{vNTRh*^C5EQWxCZxFtS+3e|nU7ZN>Fs!qpUY!;hB+K|<1v z!%4UfqQ!5=(QM`d@3IQ(ItL*LAka|2ngqu2>ulfl`kte?3@yo6hm5{i-3l1BC*LE3 zzK-L&opcAERqtow1~6>fgA?-EWUHIuM7>QY4Q{7G-Q$HfdblXF?i##}Kn#R(tieYgk8v#P1Sq{?*-%R9%@U zW}QBqtz-FMY{)0RnQP{5p9eD%<(hct>$)`-vcgyHle7T$VZ*>LY*JI3V%_OZ(6&8Z zg;wSt!$I7Y3wORl6Ya^nq4oY5l-ldVC-1+8*e&OYmr0Gwka?T`;_HQ=WigMu8^XhI z6(5Zb7Qml1OJaeWlmN&^B+EK=Z%bEnGRuN8t57mJV%~KAM#EVDJ;v0~7{`;S-L+#o zUzU%Y`$5xMR+w%TseNc(s!<|G{jX(Tg5=5qPvV4S4PztW^$&KcbU8EY<@>ISz+=y( zdh?5LnoL4;ZxJJ}sbt;VMcX0XDJ)t~*!I@x(x*0rKpB#luwa!H_UxAC}eZt5#mqwAhvIT|{Hl%}84*z_;!W6JZ&{NDeu*NJ$m z=b{S(Y+6;sb z#4qDviYIO3W!yfc9EwNgFH1|)B)^!QCYVj_PdlO}ZO8FY-3W>X;Ceuw#8amwrjed_ z;(LZ^9CyI+qm(oNU4yuypTn$kYH9*sh9I5cg?H$y+}WexT&!%HOWvH6-YvR7eMnU4 zflzy31?{i2WMIYegdg&oDRV=~+;VjCu!-5eL789kG?#eU`-W4BdMEHiYwoG|;;s3h zNX5VEd>xmcU5r0{w35nSBStwsW>3Z4=rEM}H2xB(Mb5vWZsAeHbkVZ7c4hX|uOStq zT>$reD*7m&Z&FiYlF7t4QQB8}RK!@gP0=a)xqysl91&gfi`iiA{Cev3b7y^T{SId{ zJr2I$^SOPHJ@F|F+|F<8b0T1PSOs*{wwEv07%x0#!qmduVeF!SY0IB|=F%JABSU+( zU#o{Z0`nj_F#lD9_c*FSDZ&GIEX9+U-OyJ2fc+&!sRz-j+7cwpA$vEnW6gNY)J-vc z@Lgqu9G846_d@6{;NunL2qseTqiIydNS9-WUAIxpryt(WoL>1$b=@4y(v{&*o`o() z%`#Rc(!(}X3Vj+$7u73WdV9nHAHt(^%B3VZ&lJ{7&JLLG)=nm^03fhG;3}NKt``w? zS*;e!&udLZhG4s%7%S(Qc9B0<|CYjD2OOr%H~Mw3&J7>oq|6SbcJSdGrk#Jznn`Dt zYWpenBt>VYr)N_nrA7ar%wno9d2PfUOY!u%)aD(p|EyX$LZ0*9&0LvS$*L&?trMTI z^9DFJO}Nj)j*sei{&@|{A8Ysk<9ClUT$5WnLg04maBX#Up_kN3yQ9wqQEeJjk5r?Z zlP&`*gh!tFftrY3%TY3w$Md^n3{N8L%y{Z+0rn`Jro0i+f?Q)j56x|~ninOZ(TYN5 z{kb}m(If5$_Obqo_H<6wIw|Lds;tjsn>69?6D1m%YqfL3cv|qE8Nn0*BKsnz`Ur>~ z^H=uxQ*${soUL1UW)~=5q?oS<%+R020EQ`3H;?fkL#goD%Un+bbGv!yHQ=l2S7>C= zlpcF*T>r=ei>d2>_0o@KukSu&iqW>2r)CNy3 zbcZ3W)=ya&8!$J!br-jke(8f_MNTp_8quhNu5n-SOHIGpYMA~dnwq4U)QB(S(L?6$ z(D>OB7KZ9%c^m6Hs2o|_(7aM5C9u#kX`3$QL&23gZE_mOH1!z z*2Vhgabs6tP0+rJ#I$^pHQO7``)5*L>yMUl8K2pq$&kTYXRm=k0v9QG)$^d#@qJ>_ zLHUd_a5b;Y(}2?hLGbsPP+=XMb98v_ZsUvr8OUe8sg%2E_^j?#gpOZ<;W2u(8M*Nxtfvtqe;H<2hsOW9)#FXYDP&Q8|l!h&pQ%DvzGT#h!r=?*d1m) z#r_5yB95PzV@MDHz=XqblQNv*85xk&JMViOJ@_FAq4Y4Z8-5>*tpXUe}l0`4fhMR>f#`?VvmRUEl zRu3T~miL$P)3<;+9H_M9I8vW8$c^TQCE~u`xJ5jaKi1&D3DUL*w2YZzNhe?(Z<>JP zgv-x%GfiZ&9y1AxaeaMxdSqZOF_<2rJ>_geS5EiyZiW&@R$1r+XTXM`4o#}3`FgwI zB!{V~F%?_HPToF=@rdaWZ;?(XR;;K2n)konx#S@PXYwKs+y!H3JmvcqeKeuixFN!s zwcHAa0N7dXsPlHL$_utp{I`b9?+kf39?{BC5-p{wCztTtnKvTHRODODLYHznKcTIa zZr7iw2YZz0NR%=6nf5FJ`a^I#jZJsi6n2yJp1N{#5c5>*0iq0U|si=;0kaRhXGgYULs0$x3&{OD|`b__+^w{j? zjqY2M)tMZEs-WeBuqS5T*N)$E+DjZhjWX{*_2kf)=0>j(FB)pj53!<`SlYtlrgeqF z8Ku**@e7}M`0bo+HrU)@8pd{978uAu0QEzvg&J2t@M*O^QhWYzy^sRlMIVCxMdR&g zvgq^^QyEenRxVhHepD(+^tt(j?|rk2gcBQ~EoAx`Ls7i2h9p)WthUpg=z?#mnTI$o zD%SZa%Q=()qB41jrAq@$a}(*-;iPejvc5PVl~KnoK18uk5xqHkjmN6}JMI0sSJLYy z=*6%3)5wE_i6f9r%|4Urs8lKWR!k(2g90tkgf`mB#kuP&S3?Tlt!#x|6AOvLV1XaAV^`jGxhCVTGtaYS(ysp?&9j93eKZHT zjfQQ@x@GTLxSLYxU10VmjqUhl=mo-Tof?MzR`mZj!Khw;{>4c{$Rg}7;S9|}HRj_r z2ZWB91$i^Cvglsqkvd`PzJ?Z^K31naU2Ijc5IxTx4d(oQ4P%%1A#%WVm9}T+1TD+c zYUCXYVgHnzhVRo+qUQ4ro5QNFs#R~4f0OR3&eDJrx){55`-p+6Lv;??h7F(CH%bT3 z+FmJaXg-`bv3)fU5pKk0*d&kdNGCmkf%m30rr*|Z?=(U^Ki5e}xQbFu`xjg>4!Em& zI@ne&ptbM8pcvzUvjMKLlq13Es-as$R)tsHIiJ7c+2KA zywV#WJXI#^Z2+vDS;a1#ml^xgv_LPNDIMz^y!o5R0LxUTBP*UPJ!}0X3SF`T`eh8- z5F^9)|Gl9=*1s(g$cHv(8)h|(L zxoIkR9Fx2Nw@$L4t(wl;3z5d|-0(MjhN&|~C)3{0t4%JCgDwqVT@E?tZeJ?V1O0m~4Wk{)|O?9YpSY*34LHfSET4^*iC?=H zSObQ3{7j1wPD?(y()CR%3ra`XV2%<1Jd1Aq&mgb7WXXT2k<2<+{)4!r(YWRDtzhCK zAQQk~)U8Tz{jXo>FasVurhWRJj=3?~l1W*#{7F=1H`~JZY18(Jjdd(Gq+vkw!er8; zQ^$$FK4rZ^COxqNI{Cfsj5di7YyFo6Q_~ma$8r?Z+CaUu zt{>rnpK^71Ylj}DL@W5#T^&I<=2bEgXaQJqRt>ZU>O~ty&I*$Bm`yi%MC-mRn zu9kali&m6==>o?*QE?3&jA5$A3N z%M-J|L*_jVW&ct~0ij!pzb^bp7zS|i9dAc?hf^))GEd)>FXq^4RRYh`>TVr@_HGF_!#iU zpUF*>7q8hfGfl&TEk!@tKj6~7_f9nm34f+Fwrbd<=Gc|oGX}#1j2Uq85KR=L%yiQY zpIab#X~PRP(sY**y8T;f-*H@j{q2#-hkz#k{>NXn7@c<(M;r>}fKMPY{7zTYrTkyj zHD%RWXn_RL3*grhsax>|!JlmtXW95q%`?rQDuUIqeqQu1nk7NU8+I|~8r#Uh zb+f@w`$By3s_mFYNN8}hlrI(i#Fiy!e9MwB=84x2$pL7aTX}8OGql+8JfZTL?sz4g zK`)Rd=P;HlUmMR=(P<3?4Hr*R-DA>vstyWLXkfg?NCv(y-}31FBYCu0pU`QPX5C=_ zaLw6<%t7NBIVbpHS*gX7P_i{&M;!JqHJc^&vg!rE27>Wa@C7OZQQuw-;?HjHwIy{Z z%{=}!1fQ9x7F*>s(vdjtCZIFd^W|!T+wVu>D>?kPG&s2KP-8FE98U5}65`;UW!p{3 zE~4iE)Gjp_$8Y7y9p&WE5rrxosl4V~M~JT(a|@T%Lc22-#aoO}4O4`ogdBHDSb>H-{}aT*8@15fi0@jjOY=l7 z_``v@@_e%>nVr|+++5y+ZDsP?kke#NRl9jJIvfz&sOb6FDz1l2gk^r(_r3gLosXcv zgJzZ7AIo`DMCJd4w>dHz#?(qo%dv&dr5lXac=W>`Xk72mfJ;74hQx zw0TLe*>d%lIa=P9qi5e1ab&w=UFJ9>e{ed4fCIfJ|GEUly$H~d3uWVX62WqjtH(S$ zCeoo#cv*5Km?mkj;Fl!kxF86Ns&||dJiiiM^omTnvti=hxcP9DOYe^XU#+PYz>!?S zkYoks)5TgXRS0(rvMD^Oemxl&FfI#D*CiR20x)}2`z}&GRqP?`WyWjAU1ib&>Xp} zVMzC)v2M`qAWM$KMvB3fI2Gm7CAM91)j9{MQ+QfVqQMu6nQt0@Y{-8peR4Af!y;6_ z+42_P96nk?dqn<1&Q=V+_0HRd5^wudV;7DEiOo_?Hi?gmHYLlVZD({A0WB>X?@BTH z{<80O5`@bo>SqLg-k{v`k~rZQ&c)hjK9MpHAhFW2w;GR@^)Sl3v$&g!JP=0zq|sR3 zKcjyIBS4!_8oJ|NN0@eH{FFf8D8i2Vc-9BO$>PM-)n>7{My=&^5Ijw0OQp8=fWPtL zqc1OX<%KOD9Q|dMvgEYL3j@wm%@K%lBIZ>J*6wea1Wit{G0B%DQHwm->x~NqXRt~? z+|4pOStBbdUq~4Wuc^CKI_JEqtG`s>G&DtA01Yr#{WBn$S=_$dm&*alPR_G3PUDLu z(MwBC{(#%V@pr(R5wPVpipd1UEYXh5ZJC2l>tnioJz)}lpMdgT<$QZ%I<)--v+<)a zos*e5>@B4kbH4itWe=4#w%;7PdHnHJ-Z3{V?UXe?eT@<+HGT7Fx^G!WGmt52EFCZ9 zlzki>Q~$x|S)XuezRo5zM6}*$36&^(z<#??WnLRGG5h=}RS(g1D|6+*A-LyNnb+8Y zu{=Bdouvetx)*6#0~YV+vzH@J`?7Y<6vDEpj~LhU6lJ^@e2#Bmt++Bh78V#1&ogtI zqw4U1xv~zGv^EJ-0$(-cyv`z1>${A;KXp`B7H%Gbba3pyJL;ti9kx^4YGxPqi*Lu& zmsUR6bxrJe+yAI{uigngHLDvUG`;p6C1SizQ}aeT$JRv0*kS$oDD$D27hiS6?t+=L zFYmAB-6OtgGLhs&}H&mxoA^rHf$Cw+e`5~#aUIsBq;uBAt?EmM}YhhO; zy~L3&l={dVN}3nBHo=M7;(4PMTNF1U3g&e6sEb6a`81t!>6re5CLOc((jb>$@0z3RJ9#%j45X3RlCNXX59F75 z{Ae$6ci5oJ0nx9TLhaIopi$~gq*WOtpPE~~BZHEB5nri5Lz;^oBwHD25K z&UjYjB2S33HBC#9mTB!$qKN>*nZm?+`&dx>@f@Zh_IBl|#IWjm&;Sg#1gy+V*$@H5 zIQ129OTSRc7;^P|n9d1=mGneo94CrM25a!;47&l~iuG zG~jW~n=AnuN$bD1)Z`lqBTtWD^>-HU;zAX}?l*9`LTyHOlSEDq`vtH<{5(SimE_}> z+c`HC>#I`!JeGyDru$8;g1$2pvC+)(*4W9AvtABs5%1wM=jH6MkTe66Rm5S#w$EE$ z(9@tc1oq)c#`@m|5pRz36Aj;%wpg+`g>6@Nr(3#iabLJ^-;R-fU& z=!$+4qWuzWsA>?ySd3$x@<5K79r*M5u}g~&ZhUU!J)6EawK~MDj#6=H+Wj!X;@=uF z?=@NmU3VJ3s-cnil&P}0{UG&VS7kKgw$kj?_og|#8Oj8PUq%_4UJa5k#EWj3;>*L# zEAfun3qJLMezVJiG{dk7$milRYK5by>Siu!m9>v+EeDJD#@n=yQl8cY=Q7F0KNsby zXZ8M7rx1UyYcR=y+JBN7s7{@2O;`2g4U}zLCvoPw zb%IY07eu|qEiG8)<|0#%Zaw2B1WXxiA&RwZg-q=V{7D^><^C<7w>5TkTV+Dz-n@aZjiD73$KNi$`}rJ}Y^`WkjW(!bz#ItJ*W-&bUom=T^m%STS5KP-$n1A5DN4z$gHIvuWfYi3)bzt^ z4O{lwUjg=Yq9pRmOnSbeRqD!)c_QzvHrVt4X81*!;c+RQ`O^)s;eEXG9A;Z`3X zevDEPBB~i*%N6pA6+fqx_FjBlI+Ab~?I`Eqrr=jJmsHw2YU(qK_Wo=8SkriK{TJ?Y z>|M_EotkU5(A4>q)N-G=_~B}mh>A8risk?{gQpKBheLsJp@rBA+)^kb>IOCMx#VIv z1pD&6HK`WObic%;{o8z&YyIHKdLFK&F{ie0Y z9C<^2LILl zd2M6?7Pl#n4C|ju4fS%Z+VL--uUk($!#?cuDV=-6ut9Q|=f6%pVB0wHR66!7v{gJz za$MiOCk9~kh^o(Z^aduX)QttrqdV`tn9KQD1g8S;yg7Sqc$Dv!cJH-Pa0_F*S3csc z8QQl`*jX=ST$JOk27SAsBca9QTcjUU>_}GQ+t#RiH-$JDW{~$W^ z+XBmwUNdtK9(C(i@0slrf%jdfUZYhC*spm<9p2D_E`65Cb?XWhkDCJ^>f0UT|Mr6r z?elL%7xkL~y4|tB3pe6}V|agzVz7+O+Obmb=o$XdFYAXs-8mdUHP%a_~pFt z*)9w5FvkU2M7xS@f(y}1z=*iuXlOaBO?XSt3+euvJq~ob|15MaTdsFHL24>e{vmmv zY0BG>m!KN%;&6IcP?BAC5izVheM<+`{jMR86iMD=?B8@vF>jk$7%~d61&&R&0$!H- z{f$s4>ep0StJjznvA_+V@F^?+S4~1EL3EM3m6qbNrW&6Oe%|w=waF^<@zlSN31B0^ zO#)%}1sa4tdM3?^2A5-jP^KwXSF4)P#_sQHH4oRbu6ye3juy8&C#CQJVV=`91VGTv98q$~2Bd~aU zvgVxM)4TZVsYMi*uqh)OwYtxw?7X;tNu$G_GUEw$(o8rZfSEtB6Y}`HW&`H>ZfmEN&#}J zGZY##usk|CcswlrQl#+4!K#hz`uLXi`b0@~*-L&Q{U}CWLJJde-7WP$1Y_EOYwxWZ zfUF)clhtO^It45gxLJANUj~r7HpT^T26~ch9e1!vji({KJsXJ!%Qk#$GQ>j7f&{ho zzaGOTP+hr$0<9{&pSZB&Z3@--IQRGKJpu-R$#Aa>yiagQ<1_(Dh`*~{E<4)#Jm%kO zi?K+#aK|xeN3IBt&4m{z5eiDtW?e7VaQ&65FkIIl?knKsoVLw36#RN>xn;Xm8|zt= z!k;b4a&(0q-LMWuBZke4SS46^)zrxN>*O9oYsY=IlLQpxQBxsbg5>@9lG|gM$$1Xj z51J^hz$F?S(@*;cx-BN-W$K`Ka0{gn-D#Wr`b7wxj1Svb&s#} zS9Wzhq=^41u@Fg3ifj#UA_kr33j>t?Pi_@LtG-5ivU3)TxRq z`WAZkK1@zsOHt#ZZq1YLd^(-Ir|So4)NkIbDI3x^$$ZG5w9fz&8O#xto3bB5|6a7V zjXZSzXVXKh{TpsXbLjeyn>m(t2@yVV+I!*K=;6PH@TVKgtLV>I6Cr{-V?R*6Evznx|Z$=^MtfdE)@stg{_LOp3!d%i&#iDFRVXDXMS~ zh^#+QaMKT?51V(}SYXJqb^BgYbW_?_AjFnjHRDEqi2Bx+w)e(H8?kS&4bVzxf4?F( zHq=l-=@&2uKg(^1Bnu^f9MOggi{}3r)|{^tt0e!j+pJGDXM=aO{py~p7q{83<#jt@ z^Bv-T=)=ZUu|*{Q=U+A*yU@f9nN8?MuaTBW^n~)1?fuOXc~*9Xq@$!>%|=a})^LwC z=p!i7rKGoaK*qI+Sm`zPlMKxEjrlUS_c+q5kvdk%&=oW?!JLD2(H^9Qkg; z-rRH)J|Di*_uP&5jWw5wdC0u}kF5_`P8U+QB!1Sj{23-qBdMx`1?0ReoPDGdL=~3Y zg%RVzFp_dUW@@aH1WTJq&r915Nx|F&zlB6Z>;SGa7^ik@6KXndQc=mrywAgUGvhwS z)D3!jK4f^AkJH$=xY0aZPbH0BAOdn`%kY5kL8#4q1E&WNzV!1nuV zgcU{ag?hao81CdlSxkbO@^z=E^2_)Ym9S1*@%vwQO9=?J5%t$$X-Y@_ zb8JCZ7}Uin*36;sw0E%O0_@=n z=n55!ZLc?|4i`*7wFSMucAZ?*>7JJSe@jmcq~8a+#e90oI1?lPB)u!$K@urytSsR^ zF@3j1QL~l}a&m9@-i^r+v)5KC75At@DII+i+H`P{sd`r;TlM?Wb>S|Hw<7(rx_eM( zr&U|^_@;@_>d_rr$GI>*H)bZi?iHr0hRKV3Hk9HGSGR~;hj9Ddmp>;&<1;^5jR?AW zeLY=C_i*sN8N%oOZrd6ZK^kSFeX#u3T8{@m!jTbXqKDWW53L9ANVem|x^y9T8j=%f zoej00OD%?LZiF+QL*6AZ)vfa*Orn#+wcQ)78a_vs#kg=Pl#I5mN&jA45VKgX_{=7i zx;1|iHUGd1b-cyYP72>L62{lErft`Di4^ivy`s&VTCP}?h|-4L`Z-_g08dCXq32(n z%<}lZDhL{>AH5}?3Jyp22dE5>leVc0)I|g1Y<VL}j2;yR!Jrv?u1bon2eVqH_^q|>wAC2mvEyqfoRj3U(9+jwfe`1tRPasDR$U|Qtj zx1Xg|?6G;(c-Rw%3a>Ol({IdLkY%Z~2&`Tn%L6(Mq@R2of|u zso%FsxZ#&IOso#QVj;B#e?M^^Dz07wj=jM4UCJ$?L-Z5|_irFth;Jc6 zvYz=M(nn)k&K@nYuyyDm#ElkE$a2m>)TI0-zb^ezl&IB%3E3v%rn&f{j;g!Prm$gh zsnd&q{RXN=Yz%y~=0U}X$jU$_K$psM>XFs-*Dy`CtV6%se_Swi>=clivh0EkZ{q1+ z-AshL3u)QUPX^WatIPS2-%M-S@JK9(Zo{eOtEuq9^q{t$>g;En$c_^qfH`aflq8X# z;)~2GqC%~WZohalAJeZ}q31vIGpuKba^Dkh0Z;{1QiqOq)d~LVot%RmY1b1?az~kS zd)GbH2aUVwvs0#v_GJ=w+rKSka7#Si%RX2>`G({CEn}C)vSlgnPov}6HHWu{z&>Li zWn@((h>@B=Q@s~;@wzc(SmnB%SG(HKc&1Qc`59E?kWcuZeZS6KyPYgK17NN8grg8W z2;ts{7XTawB0Y!QCVn+p*`U~hvClP;!y$HPO1^HcSx)}2fyp+RXMlp6?c$>R8sxE&r1ucVlnq{) z$}4^QhWE>gQp*9Kn;AUxs6`7_)JYO_MDJ_s5<2?EYLh~*P00XUwWj_H(JvmO6MeTIiX~JDtL_&6ZgovC!XU^Nn;zz1NXk?4x-bPRVybDa z&~!P3dimPPT$?mO4YCxf?erbC6;oL_R>mHEQPojS)xbvB8+03`bcpke@m+s6EtjzN z6L%^oSRAt%gUtWv4#exdcT{lh6?O#Ytma@0avEmIVNy}o^@|8vYkhVzAvv4Tmu|Fr z-h;ZCb5kvTw#RILyClds?bqFYhQ5b9t>$Sr&BvvMXMS*Da%34EQlSQ^a=8-iRaB&Z z3a~1COq5GL*S=`TWsPQO_=3L$k&6X-W)5pkDVXxX^Ygtk-v|mzRd$N9{x?e1)wRhZ zUhbRFEvUd*I%EvY49)B^5+gAh7016P*01+WX3olz2zS)w?%t&f;a>wbJJOx!gUdal z(*Rd%GuT_NsqLX(=oSyjDX$Kb2tvqXKuuWv!haP_&NIYvTZJv7!o7>Ry&X{-1&+ou zn`5bG|La+p42srNxAgt~b=^rR}2>Z8thWoo?ZwQBxhp-F&_kxe%)WEqmF! z@uT(`DR(#)UWxq((c(x`2HMclT!;ktX2xKw_s@e{GMayS>T2B?s{2*Vim^4Rp+tlb z4d1l&>xSs0ImNw>>)kGDBWH`%3m>MEziKr+eB^j4B#vJjH%GA z;+llzt(N-C2@C(%q1wXC?$X&LB}fpVaGaRcbrd8e+y(zS7K~a~QV!R_27(ELWghoSN>gDRjelvP*r_ zys)}v_!qOY!C6J1B3L^m0;_p9jKbFa&!>&Ck1-whXlp|da8s1oTY}9u=z%r+3*+;J zSL_*7X(f2wk09)~b@`rRZC%KzYNJ2#@)ZAK88dgZQwj%P---%qmmgb2?tGb=O;%-}@mrYsq4 ztjWR}SEcDVELagmTkkOM1qi#r#QM2nZ5dT-LC7J6N=Rb|O@+p;mn+z#>3hvI|MGAK zq-crR=pak!^V6(C#am{Znej#wZ3pmhnPXB?lmOg2+praJ?b})ETF@Ju4%4d+aZ1MniJ6&-J z7eiB~fvVSmI;Q1!yK9wOcLq@GsdsxMOT6&G;qVYoHezYo5){ zzy7|ZWZHw~x+#-dhfDif=1I)5jirUyfgCYqzg-aWgjuV>S9W$gASOr>uEs95vl^!@raI%SPW!`j=KG~7r=gcLVQ=M)?IZVn^*NiF z=Yr`wMSW!&FadVA-9?PWRr86p$eefA5r_KcG&Jcr$W`P1+pxasxDYv3(f=Ds0};Fhr)4 zz}IlxeGu3b)zn$??jSt4i35L=X5BIxz zx9W0FYjKZcpVMSO!*?yY1vugRw_p6ot((`97As@7S&ZJ5mUB=BHfBY7wItXuSh7h$ zoS2h>s}vuk>oIf7-p+LaXBMmBc{_~lV4-P&5kA(*aQj1Z*^jPPoz zC*$0OOR_^{A@S*JvnATd#-62Pc?u;%@$;a0fgdY zu@gEq8QEm#9ZixUjah%$eqSdPJyUr*vEl=VqJ3=3>PIz|hsHAsGpOyWZTmJZh124Y zC!^W%#XlOg&ZPququFbB87=kDqP{)KVQkbHhv}(SYGz^EKi%n~)V?C!I!i;*PZ#Kw z+6BB#yvIr-zE(XFX?wiHQ@)bi_`(p8wam_rTe`>lD+M}5JvXUhKALy~wWS^8`MmOH zZ9^Ad#1ot)W1>L6%M_!p&_mZE>9f)+V)VHGR%^FTz_!)uwM*+~7*NCQos6==wT70n zh8g?Oh!Ky8k9$%$Jhz_*EBMjOTc6xfSEm=ul?$}ms|(;I$G~ur2V|Ok_4J5WnR_lB zRkFwWYJ=!GXI*@y*|Pd{1*8%4D=Y53bsRm&6bk!D1F>`)#%~1=JmiR2U)s_gOeSJ6 za#jA^(TVAyWgC%j>e;VleMXJZAbL5o9;NLGOTDYdw9yW2nFEwzbi|oDM?NSm zf}R=@ThaI9B_}ONtcg4iSD(AJOTJiC84cgNvnDNRoewDVfai*8>7Exc&B&_htWlKy z(SBZ6#qrvJz9FOHxntpD|KVt%v8b9gW~Ve^eBE0fZmsmS=jxC#JY8Of)v>4ZvNH>0 z+|F_B3!R56xG=ST;Xzpk=7Gt`om_X3&aWaZl8yRiHy%5m+gI+gbZ?sPe8nEUX{Vac z?Bt$tP^Sg*pSEu3ZD)+ApT&DZ6t_SlX(@IW;c)TcL1p{U#0p*_k2(fb*;m>>7aV-6 zLK%`n7}Px3Xe=o%B&ul3Eb0-HA?VqcEN^ZcG9Szj>4IQS&U~P?b+O2@)c6g1E8G8g z&rNfnY9SX5xABsDhgmhdU!n_tMwLA;ciUxQU~d-m7_rMVyIeJ!TmN$UcAg0U<>?2Z zWYy9RQ`fy#XzmgU58d>l)JtJIj%N(ZEB9Nj&RSY*l1eSsY&f=Dy;Pl3qK3zhVe`j? zlOsd--NYHpvw!YpI4`6Q`+rouhc_Gk8}{E;OVw(t_G)RV+M8HKQMHP;wougGVg^M~ zd+!lDcI-{;Sz^cDBlaF4c=GxF&hI?u`4`^jyzg_5>v~-ya?n~Y0;4g#aaP>#%tX{> zV%+4UxYok~D+LXe5KhXH=9uNe;HB-){)4wFSFu6#^8V&uU!C&LGj@}@8({pq2Yq*< z&L?s2oGcA58`l3E5k&?Ebh|Mp0qWgZD5j4-{&?dN&CtrEfg6WXN?yjdHuOUZaIa{% zN7v1lJ+GW4>rjhrmo!aqi%-Qn|M~JE#q3Fokm`@vK6d719;qFc*8y$zW`2xx$`6&> zTNHF?1;|;iI$7MaBd3F`$iEMSc#d}3R>}q~XGiv-CZXsEYO{$yE^h6K{8H{0ZJg7G z_8(|<_0@q6jc2?N&Jul!caT#*)IUE1s%t_>dnlgTM<&2_FnF?apNy-J>yrr1-|=2z z68odPv`TxfU5#trHh3Jz#&V7MBT_n!r4uF!X|Snz!b5M#_7&{PaAYSC9Fqs zMF^H{dcXzWi>Vp^dQ-Zp?;U(u4N{6GJDJf32QE$6U4Wk%JoH(*(Y(K~W7sP_^&OgwRSM;gpjM@A8MN~wa<%3!Zy2k3FX{E!B=q1Sdud`Q zhFHAQl^K*}^ENj<2+ySe=v7cgIP|Db!wK+7KD}qyr8siLKAc`pzCiG6=&8%VXTx!? zQuu81(m9l3H4&Xo`o!BEv=ei zmL8>f$5Yaw3QXBj$_B0ZS00wB%jrcBnGN{_Dt_&RzBMK9I^KY(02ma2k=jGZ{mJvPp z`U}RTdeNb!)g0HMSAAe)*h^=LI*``(bE1UjRRoaun()NNIr^gEZU4PEPu256*B|gU zi&UiTx!3i?-uu}I!^EbJnaUA6+2&fp0AQP$b&h+|NPthBmWE2MS?x)gYfCYZf|o+D zcdfvEg#b9+^ojWuusoE{=`MHJ?|3IRonO^`K;v3bv9-4AVyoS^?>|rTEaYUWH_1ox z&>f-cg>61OFT0(ldv9+3r&Ry%s@ar2$Fa%1LeaeZq!@-7fPtF}E(Z^-K8hmq4ue`O z+j2GeqqP6*w1ArZ9=b}@N4EcJmV2#lX7RHDE1TFVG@njxYxuSN2=Wx}E8>2@rvRFi z(k%(&dNa9_J+84K6J+TsqwL37g2aZCvFExCc|KFWB6^z<5{iFCer)m6DC-wDPeGF5 z-*uj+naT_RAB?OD*lgsf^$`oAMa%)8hQ2M6>Fp3%#N#G!VVV&n)i{gD_J{L#s-NU% z^<2GE#jfzD9$o#xjG;RB69cs_=C4UIuU!g}prVks7Wlf}ZoNB&ZC6ji8*eae5$*Pn>X z?cGar9}-Nr;2XP))@QT+Pog@=3C||it8s$`{I2DJ37yR&+>?;TSIz;d=^^AZI){Im;d@%mL?iR@0)msxeVV(to%Y9loW|1-Mp0Vn8bu#}Z%)i44 z<3@L)1MC;M9vO8M6dQ@{J{{cTEYJis1A5fPuSSpTSZhOGkyAzM{xHAcSSGn&aW_m# z`_>(cm~gpGUPr(PNmuH`gp;VqE=<&mlZoQbr4dNAUe zV{Wc{&LakM|GZ*%FIm^JYqhm^X5pTdRHEm`rw&fsPQQF6 zk(I-94|OV2BApr3-WP@@kprb8)oPZ{pRFr2(HHyFvN3rO8I;@q#W(K7TL=fJkuF=U zQxk|@K7s3fgkrj+I~A=&%RZ45VU=1%+`mZVmCwV^BbDBZjj3c?WEl|jk%!rnCAx{i zj)IoFA54rrHgI(ooyT2LEV z8C`AW)Q`!Si>{sKk^Z?2f+&HX+ znoaDhu;*W6Xjsm!XvAyx328p_;C<&JD^Z4L^bdq1Qgm&pB2uhibP?2IbnkWdGQ}3M z)ZjHdBxJL`4|@MtJ&^2yo4-ww+5Ep*I0ArGzv zUrNoJvgFWN*MXY%$vsB3F%sXrCZaue6{#mL9iBP}o3RYpe`P3YtcaR)-3tWm`K8tw z^K!^o8yL)9zhvGIXFn?^%%Kk&>R)>6WH{!cXDsSnyo3U4pcmXeQrzz#5Be8t^}nbO z?~-m!vV~cX90=P`w|qJ;Dmjf#fjT~z2O-moQwQGc57PdpHLUWunOkao)igK`N#`f_ zpLhOfYMx2A_0>6JH=;7WwTUBB4^*Zc);%_%f=YSw_EGUtu;}EIj1gRUTfq!N_KGM$ zgR!i}r-!qS*EexNYZZScc<4#{NALUkjf_{6n;A2yzQab4mboAem(P;3GBw@KjP1MB z;(y?GCovV-=F}u-aF;cY(g1^Q`7q=7MS}Tc^Y}?G9KB)R;}3}G$u*n@u4h(cnzJL+qN_|AyFNAC{JI2q z`{nzBrm`!5YGl^~7Ds-pwB5l&u&J|`A)bOLh&&^)a9tSw@(W<lPm|$kCPS;5bn91^r< zn^$Cc8S%omI5Zp{(ZR$1{@&yFkD*prV7rj7_HN0MtQqT825s36?`8B*2OM7h4V@NA zjx&sH2{u1%=FT|MM+(XXnagc8d?9^ek!8lxTd@YBSFTyXJ1D-qD^5=b-liAOxk_rm zR_Kbn2V)(@o@0_X$Q@3dav;H79(DUX7$hh9!BEE};ei}ZB6M(%X-Tb@V zx)qDedC;{q&svmBB3EI$^&WR9h1(J3tn&vs$)2n^J9rMA0PHGMv*hj|+%7G4@gg;+ zC-IY>E-;>kuEN1$TlXlF=sdf!3?;8w=G3%Zc~vqEq>mwiR9E`jvh9`p)bYCFilW1z zw!jKHHE(~e;t2epFG22~g}a#inxB7hY{AQDeD?C|N0Wt$J&qWW{%V`tTGnuIxy#8Is2J5KA9dHhY`f{PAgDlvXk*aU9YR8fP`;wo~# z#Dom?j9InuckCGGwN-QH3+~;MsI;RW1}2QEqe_w@1+hisl}~_)59g@Pq02aIB%jwh ztQO8Yi?3~(D+~<)mWC={YtO%W6}ZoUS@0e4X$3YlHoYv&62Ad`EcUsLBR2_6C_y6E z&2j0#8U4!|TGXV=d7X>;&1`m?MBrU-r$o6s#{jX23yxgVjzj()C@s{uZVhGEB-WrS zOk5n2m#ikD>me7(QGKA8wVdd}98Tw!UP&j=efV8de_Yg_gr4?P;|ZeZWLTwAhSX=B zUsa8PE(Fp`#?9E~Z_sV4c*XX?y2q!z33blPv9d{T zQOl4!IeFzlUjA6*=7csPvd=ZJQC;x15ywqd6n=Dl29@+WPsgTrco9K>1;soAdP{6y zhYKD4+6@=1{N}mDbHb9FE{ys%qk0-BT2QidLlyttiF`M>zeZj*&);J8;Wst!*VO#* zh!|=5#rU20U`46$g*LU*;K)l4VvZ*BH2>2uGqIelF)Ts36_+0NAO65|#L#t9;KA-E zka>$eD#DR4!`vhWbg%~;$E|Dd%_&gVF_bU4`&x;ezOwd%wX`D&VQ8)ZoyVWnrX zIAB$i-GvRA^OQfD%=3{bue0Oo$0}|w7YLG3F{(-_#E7<^FH;npaFhCyDhJxw*wHQ| zw!xC78(gMJ$!%>kt?eNzzT><3Cn+@MtKSo$)`p&yIv8;+-UT4e$mnc)CXUb z`qtzI!kw`^FsT`aeBXEM!CXu<6=KUYl%nrOi7 zG*lu|T}Q?2Vvp*TF+mZ{B1%^-@r%yX<8ATPari?=>ot_e_eO_{KHiAR#x|d(owOnV z^q`Kj$nM)9hm0$qztD4l_~YlRgcnK6QPIFKY9hIuV4si>VnZPcvZoghLfV5Pewuvl zN;U~2u4u=lPH7#{Uzh~J(;ENX)JQB{UZT@f#g|USpqYv+?iV6AGfRj?D_G0atku%g zBII^kr9@(lYb{Jvh)e1tLlq_iv$}ANEshKprJB=J34)3OiO_0;ML?sF~ zS1*k6GZq=bS9ATNjeAJfD~fGGF}FaoNzoaN1pfm>@2<(F}J-2V0H}t2~$T z_b7&RE_*O`5FD?zJ4b4$!L@M@n8vco=xl+UBnMP9nxW2DY&G+{-th^-tmCsxO* zhhJre7N|%Vysx6S=gw{LaK75_HgKq`HNK-*d?H=%`tW5-T*C;jsjB1VYx{21Bv~|m z$+7E-smk43*#;KVL(};BQr)$W2tV`p8I>j$oclw8;XHL~vy_&MIQ(=wu?HFIKL%}^ zcGdEiQ1z0Y>U&s4Fc($7`RK>uE)pAZ8XLbYHPzZG@$*ej)f;Yzl?^3 zd-`}Bm!OGeWKboaBO5)Rm2L|4ExUAOe49yDMJ@Tdk+=(diu9E5zb1kq>6YccZ^SsC z+8oi^M;$%~XTzONc$;5OF=H8a&N+?3s-po}r#nD>=eufwiLlmefn>Qr)H>1@5vuW# zP$^U~qbruwg9Kc5ntt2_I3++kGRTBiBoK2?)X#PIr`(T4Ebcg!DpIOZ>H%OKLJRL? z>^F&22DC`IGu;*vh)-3B+`k7q$m%*HiHu*>H~O5~-3>MWoKyzw>;BmTP6d90Or`J4MUTg6Sjh028>U$dwJJ0~~qZSi|ID5v4 zyN*0XTJ(zD@{DBjo$!=Ql5Ne#ikGB4N+f1~#OaEy_t3byvDBrN)yMv;{AlJpX=c@0HLav= z*A0pY_D;m}j8Y@m8_ zO=?#b^2RYv2QKY3o35$S!FNch=AZs%%W+K@tGfl;5zc$@%ynWE@HJ`;x zyO^K8Mlrp-B^nmJKcn?1vwUTs7)t=eiX7A5OH)Lcgv$|21q`alY`Ar4Iv#v+Ox%iM z7tcdewv6S)+d@@ap96^YN_t%giORqm4-K@_gb{ACo-C#r?%S*NW5|cCbxrf}$n~^~C2?=)yT0mEGjmGDK$65Wv8^y_Sq92s-zH9-O zc$(eTm8tg~sjdixaUscl8&qDC`k;@h%A0>s6iAQLR6DvHU+Xx8XPKVvZ zoxyxfssrk(%+)B3z}Szw!EwRI>j7M`@rAJ?5~gwzN6^gf!vJttpzlIwwXJx9N_D$u z0*+a`$qP-ow`&xqjl(CCnS-bOC{aEIrt!kgBe})+c8lt73FgydW5(B=R_pKY$u}t% z;(Pn7VKlvl2vR$tIHTps`IS%d`*)2p?V4u4F7>J0r|6G!G2^KCA3?PPm6e6I^JGj! zIGr{Ya6FlC4@-TU9k?(}f)Ao}S3rCKw<;g%PLmMHF|U(vpWtGD?i{Y$dF@qYtL)#X z`6K+rY)$NE<|>tvsPM~us;5w{Fw9;fVw>=`Mb>E^`;Swp2{NQh>A&e`uSmr)~dA}{GXT%z_9&RDF<)|(^ zBH$i$@YXO4ra@ePC3~8Pj^owEvb?q^J9DZuB>Q2+);cX|7qD068_D3=XaM1SpIkwS z0|61?mvQ(oYswkf==q!-B8`tlS`=^EOgQV^3qpJqY-*M3xk&rg*@5mQOq;8xWWobQ zq^ZH2GsF0VpIvWwJEJ9{F3i|y>oF5vc4u!!VmDzyN_@pp!Jh%^D+YU?gi3j#&d%K< zdZy*Lt8qdBLGm=iPeF~-jfKYNFEyzL2F+bgs_F4iUxDrbqLl{=SBU>5celoU()@>) z{&G|mc4*hY6UgQD!AlUfIdqSvLP}S8kGSRA842^$CP|)vrU(uSM;S(S%l}tbGI~0= zKQ!v9w6WcTe6MPN#5oE}9!U7PbWY8w`X zRRWC({XM~Q}93vuKwC!9#vmTz2DCNL@W^uUICl3k+cKteX9RsUDTX$vygBq#9 zy!CO$5zS_Q@aYyMkyW{IbE#1+Jbq4=&YwM*msiVN;-oL9sqUA<>OsNWX+-O_G?UJe zj&`)ng1dRrLiLW!RS+rNWY8*rLoAY3Wzh8pE%nt-MZd9Yt<_i7e?LFFxrAY%O(s+L z(>nCdF|B~CT1qUD=jTy~_bXT}k4@L3*LPy1$R!eylAD;?$djeUi;@i8jO&GtjCXUV z`LPUkz6C9O^dBNIdv~BLHv_O)d-8+(>B!sZ1IYR$G~@T|rbE~w5&#bG)Z_(Q)&LAd zq9TPWU&^ZrBR00X!}3&~4q1%1O_v`2(eVz14r(4yV^a}zT``XRXO0ygC~xhKe^9X4 zjZM6hzl^i^S1Zh2M(H2k?YhBFVaMlRHJ=u06?@+7Aw-2;eTs%#>6)iRiB0Wil}|zk zls*Su73vY($aU;+QJ;M$XWQxyH3&WD^f(K)8!E0n1mDa-iBgSGRctp^D1xgqC^;fX z5RQ0j8-{*3J0*M5&qKJkdsk9fyB&{%PFReP>3Mr*O(zr1qn!F$)L3`R3zgSNm`=;& z7yH(@@#9*`aM#*HA~*xDX!X1OzmXa6=eLg6a_Psj0a4y7m$ief2bA*|vJs&<7RpXh7== zBVCyx{cX{MKC2i(t-5PnG3e+>HP?64BE==#d`&R&9ATg~DG$Up?s}h>hY~+tE68*O zh$=q9eV)#2W`B`-$f!FlysZlzU(3}7qpFoJ_WVQ{7t+a^a9z^clkBhcibw@uCeI@| zTrbtXrkY=?w}HI{{d4HVWjk8-IDh>np~ul3+#`0)OyJ-6HSz=*Ozws-4=84_9Et8r zK6Cl0<{qc%z7A>D_~4yLM-XXs7c{&~;Yv<4*Su>6U)c#x!OV-t1q21m)$H}n1}qT# z!ZpKbeUj0w&yvgm2X{8OY``3>W(PGoJ1(^8V`-o=N(b@bwbv?{?Xc65!5zCdl&0S< zs+!{Kzs(vkYF@Y5myWylL9l7DmF@zENQoC~ODr-=e94)~=2_9~ZjP(UJu8L4aovm+ zE|OmJ_a!cV#HMYmtu}b{yf^b}5D4-h;aZn-scP3jH!MacalsNK1fz(O%6De|!`GhI zt1!2!e9~Sz$f=*_qZ~>Y|3=uE;_kQgc_-uar^L~A=}&Xmpj&7uwA5f|n*_G)CbVSc zC}Nsjcs=cr(uHw2u5Oi@Iq=jPk1BAleeGbh!$JOQ1@1^c9j#W8e)KJ=MvNG9xLx~T zgTT|z6fJ9ea;n=H&#~mY*v5Gs>&-k9J$dFH@b+Z=h-K}p(p0FA|rNU zLOz4+ds07;6hf+b_geb=p=Vo8W?`_I7H*)8r$jZo=!HG^fz_^rZkgmW?eVgN^gXet zq1LiCC;JmnUej^j&421j7Y1~n{APAAO$>^Kb0~)Keh?M@5F{PTm6VS!4%^Kx zA0l9IFVMv7aD|!?5oG9&kDQH5yRAsc%#D*D3NoORWsYo+tw{w$ONm6Wcu*ihp?{gV zX7o6hM<=Q7pF(?DV0P--%Vz2d4_d1A-pY}MK|r+v4GJ?o6`=9;WJMq7$XA9LT)S*k z`Ik%L5c+}8(m`y|YTZe_eR?N?Izz3$*hld$Pn9o$DCH>DPoq2|M6pTW*(Y0#4&rQ zb@o$GfD~jE@uPq3Fzx5F%633sf+H}TIOYhfri^KAlil&8V$NVkIKucQ{;__=Z4%A* zis_#EzPKt6M5qlfe>B7NalV)wR}fu`RCH+}&n5Y$N+@9P-RrVx$xCiHbp3y|MDdL; zfy|IdZc!Eg*JOK2H#brm2f#;CfDv9*$19MLxPMI)pP{FjD{j#`sL>zt4^NQ zBP@*Xd1Fw!=F81EDHmf}ZDg{`Z^6Fg0)WDpZ%(zFeixE_hf#^p*oa%a( zj;rNhsK}z_SZGC$2L5|t0J+vT=meloUIIq_Rd}QB*{PSgY)(3)hQaPtl=kxB$S>@E zqbGZOstB{Ztur-dX-=wit`3u*Hoktt(XvOKOsdDW?nU7C92(k2^d_ra9z|rDv*=#~ z5R+tvRM$3j52I<$6TR(dShK=fzO9D5v?D3JB{rA;8*s(yPO9>r={8=E`TEPwBqtJD zHHfxmHb?QgThn#+cDBQIDO=20({)9xEu!G%JEUOr$Al%2^Z7Bt#|T5v0PBDjZ;{oE z{J^1E03M7A^Dqj)%fYbYvhhhAkCAMZ<3fpm4O1c?^45-7hb_;Twsl7pcydxNB3syj z^AW%MJB@m_P~#2u&K*bZ(xxzA1Mjw7?W zM<{;&*?>S`wc@E4UZB~Fbk}^kJQ9<$GmqGc-`?8uS`%UITx_(Vi5uSwVkMqIKsGXN zFP0<_nj+wgxqvu^o9W&jA=OUTmR)^OSG@Y===PpOQI%MKVK+9|l<9eZTA-NCSCmxO z>9W<8vEH^_=;+w9Ks;532{lmen+4r40>sw&%od-)QlsZp7GBjj`2HXQ_2RJVNXnk> zcH>m5ekzD&TjexyX`le13=CqbI?CPF{W|rxV#tY!dg{vdOjldCS=X)ShZB{tVK2<{ z5V2*ucKDCd?H%;lc`TC3a!hcmHT&PYG%@F`NC{(=n77q&$f}{9Z-gY|=PHIulCHV> zIRvE!4c`vO@#alhzEiBkFx;1tIzSsXwP`HVzAYbqhIfrGpv7E|77FZi)_Mo;9t=C9 zO|+omG!$nmv(<6YM8CU~{mr`nmgx8x&re5EFzsTZ1vmCg^XV)|VW>`ZA>_%kNlN+g zyE$^jP8XSwhX!zBNNl5oUM6sJcchu+jYrejR)6_hmT&i^YdDb#`eDM|m1m}7b+=Rs z6JKSNd7G$2(2g@a)8wkmVcshH9qlwSMR+WEkh|UUz?7!3CGLqdi6Cv`H&s<!!zqneu6hMrJOP+7KOg(colL@RdUua9a=<@#S4FlnVPaCQc4shnU0 zjmVbp>s6v*v5>7cD%9pvYw|vUiL>f}h{@5f^7TY}_8oSs<_>l&`RQfBKL)iEvuI;+ z7R%!MH}(X784itz`p@nOA7b~)*Xy!OcF`t|-Cx(V-7hCIU$w3z*bU4KzWGg6o*3Z9 zmD`20Bt_J0<}NzJMI_zI`&ed*R_nN1laj?!A_FENo`}DaN82yEwU@gd*}bqpex;o> zAFYp2Xu<+8jkiBDvJ;-O2Tbp>?YL2eG-{c<3<4 zUP|K0+v=Q)e|!y(c`~AVC>s5&2hJ@+Jq0EzEP15Z(w!VT3PUDtx>!mNYhZIByk7_; zMj~1T>{bzu@u42$`TbKS6L!7RH8?=MCKf39K?uDEMf#n#dXX%DW~i0;P$#R;w;QGA z<5#T|;g9Qq@BcdAtE0-)ev!kXH`?+`2Jm6tFwoXSx5TSs{fkZ5iihNNyXH(VS zVPjv%jw z%S~K@=G`%)vUkJ^26(^g({j@d#B?`kT}fhs?nl^zMx=)};v|Bu|2yD0RU2rFfvwPO zyHrH82oEF8bc-2|2bdqQBIAvm4PhfABbfxQEm9<`3pilg6u^kHT)ky6j+DEnA7D$m zoZ}8YsDGe&V;^FZ1rNPccl6Mj$)XXr@>WGuOu%`CkC4Yo7sq4iFOLfto{W#1Zq!{Z zJtZ3Q%qicfmdp*^d_K#+mU-R8m-v)VkFP^d&gm>7%MUl)fVm9#kjD7u_1UQ6`73cZ z4%ZGPlt{zb-i}H#Tpnsd0Gt)Jpa&=&ro9!$~__ zDUDUy@J!KDELKiV04}fcaiQy?2d}Z#opQ`q_>NWMlW*+_H{mk(whxfs+7Hf zGS}OXyX}U$4Xf5otDdiGDi!CZ&8h4Zk^ie9iC_Pl@tvO4(an3ru&Ch8wf8;vl?foE z_M8t=5k5Letrs?3A^0RP@q0A+`a=kp10^;4I+Z=4Ir(LV@;A}v(y$WZZ10@zOr%25 z0Uf8jFwhHxeiYyDd$P<*lCe9$1la%mv^(qYj?$98@9kt+?ShSI;?_Vr@h{bhzq=;X z-uyojI*4D#t8E)}UI^(ehrk?N-HdnVoX1HjP&KUWGfZsd zcwW?#eX}`I;xLOPw5By`e+Vdo?Pl*O510y%;iyAZlAW<#Z@iZzCKAr zaA|sMG3Gp2I@m%+j^f%n=O8}V2o*r{d+nece`y$tl_z~kEiBPBuuvnvyJly%3lJwC z(Ckcfk*@95(2+}+;c+_t^%QcZ@*FE#fE~%%cE$J4dEW_U5~?L`3iweXe*P8ER(TVP z%OK+M^P7!V5zR5i-Hk&vfWrVWPfI}JUH#r_+ku(&DzP7~(ihASJI|R<{&#_WS!tDH z)6IF5?tJsCH@;bCm8`;l^vUhY{)V-Gw&{Apb8pc;B=4y=tG9di8_||+jTI#MGf8*p zk05<_@J-P9<3{I{k;psQR>Jmp0_J!DBXg#Evo>#>EEOalvIz+MzP;` z()oD_tW6eg1Isoh^SN@-Vh$YVX!Wp87cUr?u9%4Ip8 zg_3Vp&Ae8H30OB3Oz!@J+h+1*zjp7U37l+|dhnO??Z8b;qWKNAI?0g2Y zzk+5|E1UzptZ2I7Ly`!aU6T#h8zZOOLC(7fV#Jefg<`Rw-*G%%R`hXOXAGOtY8`nQ z-z|s)+*J9}tNS66y7XJ_QdPOq&+8^w7Rehp&CgN==#@t`Tw_*v08C5k?5O*nu7$+1wc(BZq=XNR}Fj z<0i~;%jgk#NV{X&>nUDr@^o%uZO3QW8{g)>@Pp$a#lY2gvz2w??BurrQ(140g|ej@ z^g#V~8=41svS7Ltwj0o`pcmZ_q-cND;0~{ju))980T%Esd)$1B(N95`-P^rg8m8Ub zKlNwd4R*ikcpclygbHC|_WSrw#^o>>bZeBq$_&CCCJPJW+;v;|J6~J9{I$xz5hN%Y z*c^N?A-|Jig_Z`#jPl^giLX2)cAhLX6*a}p_n5r4Tc}lXPlc@jlmRJjWfp@I>Ok|A znlli=zp?wIZ!EEk=G&1mmtX6m(_yH8{Q-U7;FU`AuuV=#_h<1lh%-eN59$OO6TSYq z(UH=kOjdR8x;3S>x)IhKJ!+s5hRoSTtJ9-djjuy6wNVpzng(OgJM~P`XJK-9Em?f5 zns*!g2nQLWZcAdc>iiBw>RJZavs5La}r^7-LO<~ z=Is_v_DCKB=B&;96Oq&P@2+AKu>{0PhBUL|`9@ zVkQ~9G6O==XC-gU?)MH<@A@U(wW^op#cTF{X}Ij>IP@B(a(>Eb25po&g6`)O-M?Q1 zm}Sg~-*wb1tRc3}wu-s-ZNux@prlgV1V2|Q>qBfG=e7O{V;YTLY~lsPiJj#F#wx`X zf#cN_JQG6BC(8_68#hr>bI%ypcv~g`?aMW;qBb`{GK(7CaS~`Ys76~^sHLZ^rxk?5 zXN%`xb1Z+C7`HUeUqWRDoQ_c@4f5fARm(}h7LjO%VvhC7;4vsUvOO(>v|m3)m)ytt z=(OJz?UT@Z!|~53Jf=rXD1#_UW>1L zIGN5IstL8aW7B*;i2$f}JF7N^9VnI#G}%#7{D z)PZ@oTA$@NJ9eIL(7;bau5J~It-{h!qQ#S^|G|QpA|KHkz^S^mTIYbNE zLjQa&StciE5`TAIIR-Go9|`u>rA+;IogJh24EXO9tRo7OyHYxvEG9o@>6MyGrkTDX z_Oq|iGgXy`bLE&0Ehk99LKV5~|0Y5X9~(z)sIHL^j4E*}@wTCJvx&g~%x&&t73`@= zCj?n_A{I+PwNi*)pXmr$iyOy>g3Wh_o4PC78Ei}}qrrz>gB0nTuhdOgNg~Zm2S`|g zm@Pn9)bp8Nd>wj2v`5!yl1wIslp;Qq^pR#2lPD;yUks4jU&UElN-kSVW&nY1v!*32&mPt39+kpe-C(j(q?9@a+oV84kC`sio~hlR=?;u))c-!0{{t{NDN^nV0X5~~Cwb>OF-=mQ>a5Pxh zf7rm~z`!0KP3bGm;!gx%XN>FRcb?n3;@tn-5@`^i>evU#viN*zrYe+F1CDq7M@Fu+ z;r5%z`#uC|dK#v8-EQWXA}9WD!H}?nsnb-<;i0&u$WsweA2Le~&7mvq^{v(<;@3%#pjFTn3EJm}V(1Cc zB?l@WLVlaUs^^hnoMwEc`~1nP6lLhgEM?mndB|vV<6XSM-4LIVp)l@pOsE|DA>HjWwW;Dw1 zJ#JY}CHbo4;1xNMUZ?x?ASil}*On7-e(j>yEIzuyxWO~=XPDaZpUl~d$>h?k{F8S^ zESr?ZKB|E!>t;_GNwJUzvt951@`>PC3z4u_m$$$#LPNjjafN&Fh z{Mjz0z2lIWc&vVtHQlg_!++2ZNZ%^vw{koh(AuBqnBF*Ilql~8ctO?+I##DdH1kez z=V@nj{P;Dnwazn=Xa-kybL*jMwQ!1I4h%f_M)i2NmcI>%E&VP0)<$`uvCztwy`>wW z5vyb!X08<=j)=PFHC3p)mrauP%c)`^aL^lrnLJeht)cFPbUz~-|9j2PKh|@I+4ykT zTY>4^6&JIVfQ2K(Q&%hIpAosxD4wb6w6Twg1B!#3EgQ08I_-j`<)v%21V;MDf{2R- z`>{|sw_6*ZDy|!}E@QVZ9HvJ_&fcTD)p0T>b~MNb9h0^q5Ahl{sy(L1hzD2v<~U<@Dkd5F@D_*Ii|Dp&Zwe$uUn=A_XgsH4 z`iNv2)DQrXK7pPX^mgL-?7D4vNFtlizPwNSv z8Kb}JEPh4}KZUApzWQPSNfotK$F6$<%B*fAHd3yGOW3*3-^K49B?*cGV%-qy3iRib zRA=ZGRO+3%&lhG>j`0m-)r5yelh=8^X>7$(JQogUPvq)y2|FA-|`OI%VBv z>8n^CO}gH$Y9nu4cTHKqWcbckqkuGoDc{}o^?2lcm+GE3<6RPVroj5Xy_zI%q4#IL ziyc1@Uu0yqclnQZ&9(zd_l~~@!7fOhu4Uja;0Kbk@)y$IJTAu+8$!R_uL=}`6|6XS zlxDi0aLv4rwPgpjp0VUv*c4EuFsaJDhI6D*erJ|ID9)eJzVo_%MFOpT1d0czK~QTE z=^xBR;=gZ9H~xT6R&@||V2<^Gt&pDu?mOFkJT@O3#{#L|dQkK>5{GP6+bbh$=LMSi zPs$b*iX}SR71r7XZC;*0J?44y_XEw&-$a}l^1K=@=C5kgKLEc-e5SkJ!o|iTlWEd%wm;HTWK~=|bOd?Qggek&*}c%D&uL;M*NN6+T2*6a-JKk*eqn@_y|n= z+wSgaSiW<-{)HrCxPBa;(jO*z`FEf;|xJnYTi=tIettYu}m%PGjg5O`> z-yKx+($9G<<1kRlgewLN5&b`3pE!B(D?USnR;D>XE zHPI{4@;@I0zc5i5H+isQ_!{Q>J1D0fV+-Ea?M!IxNK`pqy=o-Z+Zg4WN6Emto0kTh zcl@{_?c?mW2Y8P9fJxdTZ;8Df2Fk44(E8IoiM1+4$V#?!Ww(?=)DdmFjGWw6h) z(?8^>6Z3n~`+mGBpv%Fez0>sJmJpTiX*WABcy4Z~!n0WQ7ct%7<3BI_*=(;woR2|y zNT=QB4D)~?r}5A#em|H5zv`e`S$#)GRbD`|@FsE6^Lz zWmQD{yK*0TdtRs)JECp)?c@rwZ6&MzrJ;>?rkoAtDA?6Q$p29)<{_d{~e;6^* zq<>&u6NVrt;*a4679*n-HU?d70a(=kVd^}bn(Cr{t)d{(RFGa&6r@WN2qCDbh(JJ5 z5rIUci*y2^iwKBx5s==ANQu%y38D8AdZf36P(uizg?96P-`qR*FE}%2&OUqZwVw6- zoRcZV!$4!%0C$<5&7nbH_aX}J`;Bmr_8Km!eQN$|C4m!ROzQ6c-SgNP8(moUJ?+V# zHBvnCQC_4;#Vzz;&IJvkD@)&C$e;w`1DN&OrI(ym%O00DRRZ{Pk{^hFzA?va%CzSB zB&PFOO8f)QPqs{ob$wb4$4^bxE?@_s)6af6s}68#6dZxCe4Ux(e-SRZFli{zC@k*$y$R20<`lHK;w=AOG z;`94NxWgpe)k3ZX69cZOQ7&SJ=4yOyMhgOw8WV$x-VB>C2`^OSU_fB)iy99^Hqfk5 z8;bW&@4w~bIeC`-WZ-tNwzce?rJ6uVt^EP1k7jG-6)FZ=Tl>Sa{J!4ptS7q_v+8dA zT}iag7-4BVve(0i=9?PbF zb@=7kgy-ey*1raYWW=BDsXg@Sun>3+Ijg;$BtL?G*|$5gNUa&)zbw-DWu?4g>*%%k zzQ?&}3)lx4*9ccpO1HBm(sMYV+QS&6Ka5!=hl|~H+3!OET{4=k#moZ5qbD_^|8yOG zQc=~2$zI~j{HgY-ub)mTkpwOc|A2KHe=fUWd?_$7yMS;>*SRc8;2TfbHP_#VgCfU+ z(=kV#G3%JsBFu+9q1i2=ZJ*zAAo*Iz|0N^-Ll*@VaPzRwXht6A_qp3VK9CmLH2aJ* z%d#APS-eG?=WLH%`DFdJ`Q}vpTKZ<1PSn}vGxne2k(>caWV6M5iQotK|LJ(Id=wV) zWDxK_3X}>)=RLJupC67tR-WlRaX|8UTQxR1xPQf+r_iIv5t!mzk)~`3cnZ15AFS( z-HspD5ut94KDI7iV~egGD)M9Zr?}~-h6x-=Aju06VGJDIyVl{!jU_HGZRQ%KdPoT& z@^68;ncE*NvcZsV7Twm};MO^R*+zCjUP8+n%FPtYO_W8zG56O@!RD2wQ2*I zrvTDwFP;78jy$I^IF?qRI`ETfLcWzL*ZeiJO^0NeVr-oo2Dvfd$;XVugKmk-i*%-& zb!UdKBsZnHO@t0$MkBP6weboSh|;FY(oz2%J;7v3TYhsIm%B*EEbU}-_PC^B+e<86 z_~W#30KHm++4F7i+WRk6HS7d^w}YyuX3GCe9PrF`OX($sx_cJd+q_kt=?fJ91o=13 z*HVK`+H(N*8Rb?HE#WMamjh_chkfz>+bnC-g;nU)w7SaWE=W~(3C?Lt&t2=J+J0M7 z#R)Gw!~219cSB1cTPsaiJO=4*YA!B7$PLaQhXJOEj7EH^oO6Tc(i&tK!+N$btOxHr z;s(h!(*hg0PE~?rM{F4S%8)7LQdAw7s(B0YGn95RZl?1lxbLD0)p! z-uN_H+W5sX^WX)-VMtP1PfNQ|hLKq9!FY|OuZE#1E508m`=Hj^-vuJ!W3^|84w}4w z=9Kjj^Tt$5W`GZ4$AZeIuSAbOX{rGmG<4|J;U`-cDa+)nPO0g+?q4sRn+sc()ZkJ~ z4TH_d9=^t-D@=(ES3cUWK0-y@D*KfBk+nIJBOMRip(@s4Z3o{Qq73EdJ%5J|+H6#L z?9|*%h$j{#bYyD)dnGQR+li;u%~|Pd_hmV18xSMBP)s$RKNQ|wcTPuFb5cd zQPRhs7_2x5@?v&o_ARrI@=I9wuy*Vz$rYWtBnLJX@7Hpkvk%vKU!YO_+4U8dG-7bv zi~8rFX?4%^;7Q>(d=h4v=SNKObGJg;n1S21FTt|^uD}{bUa5DQ{1oI~&L02b`S$k0 z@um5mhE92`J#)Mh&)y5qbMiF_uhw*dwQHTfDYAhja2c zn@lWkA8$+BJ$jFsA#nAXerGyOx>>Gkm1MkyzVwtGRI=q6S%DKv!d>bS#Cf)07 z`zJgA94PS5)MyVcE9vXec&f zk3q<=aW})0s!+*#_gsQaMdD|HHLt({Sbr5-`msaY1J{Ans@X*I;J$%45JP=ZI-qC& zMs$Dd9{lTqx-B`Cy$Df~JIfu|r3MiFcwBM_bqxlsSl$(6=yN~leh+3O?gfEse{S`u zwvh8r}-rtZL zmQ8SqvC#SB>Y;$|wMW0R8NtRE@A};_K76c+j7Fed6?i5QwZ`qjByT{ye?V>+(`B>2 z|K^n({yIB#B*7M`BtjbqTXHa<+3;L~@_xA2Tnk6j@rOJAl@kTHs?Iij%4QfDzoZd? z^p))Ro!NcPUksQ0D}}daWUI=f*Ykan*Hlu|PBv2#QbJ9EH52UFl%xX*5U3@&RA_Kk zu)iF>g19SmD$n1#&4{$5_8;O_hKZeS-FJ%H!p>G9O!Pcp{~-PV7CFHXwTPMFcWkSX z7d1&wzf5TbiHt-_!h)#=cd$r{;k`b94Kf5uP7#lYlqWI#K-&Zk2*{5N@8s z_l)K{NhVg9qxjZs%uUPpMPRjvMA=>$>6J{OM%k>$Kd=LD`H=WMQTo8}{-10#)6Q0Fk<*GW~N>gNTsLGmet{GkEA|B*VB z-_+j=Ok-&f`RX*ozu24KxhlQqo1YCE*@gY~8+O{TQpiwawvO}GUi~5;0>mBD5+TQV zpzeHfq_^dOZU)aDEr-LgVXiWdaB~Yyx;h2gEH)TWS>~vCMV0k`XcxYK{!w+H2jN-F z>|J;xfa7_)?j7YuOQ7DMCQa@>&*zy1dN)IB_RZ5J)}xxMR5$}!N@O7Z%7~4l|9EFO z@(smwTs`~1ady|you}D%W;;XZG~bOHiyZ81E=G1c9d>OG{7Go>rf`L3FFp2}!Gn@` z+=x+f1Q+};r(}pmBoEbUR@m79st5vTIafJNYNq{e@J&zJQ??v{1dbic0nrCc^={rf zihQZ{nEj9u1ZTL1D`ZhEr-7V$IFNLzSu>1p{DYXu`&*(I`|=5)WaBI=LgSNsAi(BV zpOI68zaQR#?Cm?@?g>P@E^<4%ED7N}b zifu!LDnq-!k@@#?_R_{Cyn{540=eBCnKJ+tgqv#JI>D-kCS3-Uiip|XfFi(o>Z66w z-EVORBuee_(B>)we9`>yogYe5s&x3F+w@o)cWEepbzgS+jMT|$Ra1ZF)L2=L zlGQ%wex!Z^MAAEP>2R>1D#hfTRHpUK;m6XTPL_|`5|ib)>3z~nwRFOjuG^m}sn>%R zO`Tl71`7z0U9DQYn&$l-krbDA^jzs@P3Ie^m6*mK;&8qXpo1=h_A^@xq-?!3Qs7)u zaCU)rW0Gt`4X7okeMnsTh}qzSB8N_+Uz%jTfk5yA8m_Lv~NsC9VV#-mNH)(o; z%2OCd*j`rSyUM_TC|+tp)t<54S^@F0! zXl194ruD=jCbQBnFFU*_`pwHGWs3Prr+{FI%z!mh5G5`q(w23pD{zB1_2i$(p=F)( zQM60k?RiZ;dmXrqAQ=;O_NkuN2SqeW1D+g4&l9SIV{T zn|;l0`o^1IT<-1aMB*}|C|mt}<6XvWm?)9_*_LIw5Si9Xd4 zBd;-1e~bcO%es6dOtQWsgQ)AG*v}VUpWqHUb9O@i%7fbYvyYV1(C-jVpNkrzq%seB zZQC!~wiLFPv<*~63cQPOc=R>V-!~O&U*zDXpG+$(an1U(&2L6wkB&@T<5ZS-Z>GX( zN3dHu6P5&QiRRv)PaD=^Da$`<Y5tG<#xEXU6@CjMcDn?Z&lvntlPy0ws;UyCm-D(H}}#1{^H9zeF?w-C;r`jRXXQ^985P55cBSVOfWGwzS|NL0d9o?H)GOiytGDxO84{taDP62*0~w5ujBMU90sJB-iJHq= z8CZoMiJ>CW*ffhVB zg*;La!Oxk5EEc;tpEusn57-jp(U>l~H}a8=MH3~H66^DMoV({GMHSrL!lvNf>$0;6 z=6iMS&dzcw! z@bz1~sh!H8(v`Pjfhe1+p|*%Kjk&f`iVAc1B=&|Q--P4}$`|LAxz*+HkT=^>wriaa z)rRzD{4@|O0Gc+=IpRT+!)>tbvX#~C(3Fx6I7k?-P2kuhx;m&8uf0$A!rZ$ulXhky{Y;A2(cVt5F*sSyyhkSpJ+#%z zBOG(;_g-enNmm`CsDSqJGLHNumOI+FCJFnKcEW^&br<$l!PZSQvcjEWS%kgqJ@TpC zvwvNrW-$u6B&t3+Husp608kZraQL!UCjs%#lHL8)1eiDxEf3HkN32hT2aZj@GR zW!$lfOazCD4?XX8HJ-YD&lfrB@H1(eHeQP`@7DkyK3g{vivv2kpq1?u_LbLYcqFOeAD8ls8~EboQ+d}FWe&l7Gx}Hl(1X`uphPz6+VW-Orq6X44yV$Y z812G_ZI<(wQrv+-P{Iu0csbxG^hVfj`MaVuI|+XZnX>KR#oyq-3-25}YL`&FQBRyC zeamHWxGf#A`%1?H1o73h`6WU9tNtN2fHy{w+m;)yT4S-4<5&6balI`WTqF2y7{m{K z-pT2HIu+k)xb1eP{cbhRAMnwvO>Yu%>4NL~C%dyJlXVRTDyK`l1E*7&hwgRscEIUeg}Xxa z|6BJJ4(6l~b>w*uGMe2)yCfI4W%|b?k9l%%tyTZso1D$?zYmyXGCdeC&t%C|lrPu6 z5(-fF7Sccn&XiYxT7nasm#J+*QhKgzh9{p2oz1p(YgRzewVYQB#fOX;JsQlLopG<~ z&Qgkd;*3qw%C<~Q61eU2wIOASTZ>&mVa=`Y#y5JqeoB*h9Xg%B3TOUh7B5Ff9YWEE ztRl&&#k-H96x66>SbmH9N|7MV>;Q24lcJmagUVsqC>|VOr?*ntexZ}JeJ~L;Z!BmI zzg{=*Wi?kWn%vpaYGGc5PFU%bjHt67B4J{zEyOdTw=B+1w>TXqmJ9&+w zMFUrdy>}!+Q40enWZ+v z+e!+{CC?>Y(S=Ro;RN}AvSlwF0x{;z84`~M1b(iq-eD;oT;sCpa1Meoy$(Q9y<&+R zg3E8$-t};y=o2D(aPOrUDf@DM5D9dTlM#~ z-LI~Urs??*@~5D#YRJ9Ep`!jxzkUsCE8R%z zP7^(pr|Cm0c+dT2So_mpx?9na|2%Y$bE2g+o8v}L9Put{`SVG%UX`LNX3MT%GP1nMpvc zCX;`X(io-K{j81Ah!9huX1TXyrK4L^317s7^cUo9bmF~Tw~2|Tl7G4vG<-LLn4M+I zz(Qbk@T831igj@<@K~1?G_V!{L*hMt8-ZvFGw?;cm`|jfmA#;)k~BufU^%JX(Oc@H z{V%_!(QC+RnBVZcrY^>X>j@??7gSaHXH?NT5i^!~5a0<6ytgUb z`KFF~`!L?@0h@2nC-;q+?2Xd@?E7d=JgKwE|GDfXk~LDxG>&Bd zCMkvyOK&R`8pXT&kok`j5^Lp0Ik6lY;dMWBZKl-}V0^UtXRuVcm#xq$0Sxpm#{&H% z%_pSYuFBfCY?1W?=a7;%Y~AfGv8P;ZNKN*0GCjQ;+A6(F zG7#{)j<9vA+b*5Xr-rzHlRRqFJlLwk8N<(9+_?UC%VK9GTSd*@jy=yQ{D?qdg~{_AolA3sE(VQ0veX>%kg%#LY6!7`Rrw zU>8Tf?M^x_PG;(tSX}`gFd*11bCbz3^1t$o_@@7;=5A6uq^^?(buCpzC0ir~_mNHm zNGY`&UdH$vq|qKViGq#R{gySJmD{4*l((*|rSb!+l{)OeFlnAA7ROC@8`1>y&$5&9itm^iecEwOp{If3xHe8@~~A-Vc)D|9KKlVNd^~m*RH} zgFk~)_C99Ye$E>no;Lxex&TI--nFdo!m=1)=~Y0n`>d>tu21OvYjk~lruBV|@w1!f zb=5ZP1n6L5Qv?rFQZyW}nHMp+kT9b#9}9}l{laY%$&lGq7=b7krI2_(!1tR*n;K*h z@Mqdug!t5;(z5M|uCkv2FtNLP3L}r$A&zCKEOKFDaLKT-pzzoS16Dtd=-`Nu6jE>8 zI!@bftMQfE#kD*nlk~we6<*-8+2%AcCNd?*l~p+#3%&x{C{WuiDovPm<1bw#vxdd% zV}bD(%(!nNZQO)kwDS@Y(z+SU?eH}MgX-$W*)i;Zt;HSs(QPVySeKPkY>E6@Zs2^T z?Ty+oKZBr?PZ8Kt6Y}FX5!qt#&4Usw$FV3wc;`;72qC}h-#I-$s`IMt)s{UnGN5xV zk5w5+wR*A39gza(xg@*yNG8I2Bgt4+R7CU*!RPJx!a&yb)99@{(p>%~a!Dom6~}Tz zcxG3X=q##zf4R(r(~vP=_kr)qSU$T`*ZXfsEpdOx!(H@c3;8;|8G5`_NRX03makmL z8yl3F5XF?K3Knexd#!cGgyR_g6?MkyeqQSKr6;7)pFTQj90jwB&h8(iBLK*SlJqj& zz%5DN`9-`Eho2}Bwlun_ED|CGp>FRtF@%YLr$4uZRcEUoO-DMYQJRBdwrj1D0mgfz zV>k$jltz5ueUI)&NuQI>OaIENrT=5St@9^R>a=AMQy(p;vcYpCU3}9r)CuX_f720J z?ej1BHv-Zgt4fv0N8d&s4*p0SZ5uHO<*%Ktvky4N1-kDEY@z5PXcCE5GCMWRW4X<+ zGAnYhikzrl3p~k~PCDMw1Uc&XF8uh1y@lPrqVc9ZiVgyuroHHXL-A;5u>5vG6hi7# zZNxhKU2)&xbTGzz8P3d;Zs>YGJ=P64Ss7fyo zpX{r9vm`_M=C=IEqs>9Y=@kSAr56Q7G%VK$2KvTAyPFRasG7(Ek@tBPTN*WGq^r85 zFrg_;6{qD-SwC~uj!d=y#Z?~dp zKRA_>Hv!KVM|j@&52j@>f9t+6!oE5-`7oSHsQ3x$UAjO71l15Fs%=h!T+oDMf!e)> z!AD<*HE(&VC6~)No)y82B7BNZykBRcT_2|a?nBdO6QVGwNimzDv8u*GKP|KJcdpMS z;ubQl4v56G+HW2{AsuaVok!;)MNjNRTbSE!Zs}cPGAKTfGHk@C#5i z{s5lNBzv&h?X{vD^hLKb)eMWsDsLq753CRMy|=81nsvC^9fUjcVk*H|{81#^YTFh1 zY|Hd%o#lFs131j8>}Qi<0DM)F$-=y6rMwJRrq+3@dNsQ1L9G%2bj4CIIPEBJu{BiZ zTdh-lrJ&MRDd$nn_;fvG+qkyNk6&ZXz2-}Z21h0Yiuxp2@?^&K$i{Fg@2wkr|JUVa z@==^0exK9Wn@z5$Hly`qyuh)@Xn#}&akJEGcwYlguK@&zC@4}0)yXKzsI`7)CIw!u_gD`zg$HK!k!1{KRtS)(f}jJiln9Ev&N(6#$IiH(Q;Op&r?mL zL0EGbM3p%$5Y7;mboy6WfzxBnZNVu>lq}gZ;fE~r z#M_=kam|d0$fr9}oF^(n{`!6*w|_zi{wUN8tpe=K;V(_U*nG$+6583F{U>+U*FR`h zM~Lq&HypEPmze~B*hs~y9%Q>=Voss! z!-^Fi?^>ke2b|ZE)qDc4eWIM#(#{GsDrtD^m2=UqA>!~WC`oKbzWw5rdD|}Z^3%?7 z0eE6>B%fWji2Lb_Ia^mby`wyWO3lY~HwS6?*9<`hQ!iGB!Z5PPNY`LZi#2HABWy-M zH#0??ammrU?=%}tGt%mlajy-VHw-wjlD_VMDGg0AW$^7P(7PJRZ$!%o4H9Y|PQ3+w zdyrXir1mj3Z`QST`Fgnq_M-jtYa2)HC`8zr=Q;{B&TE20PoydVhATh+P2Eg;{dNZu zpunY42035;k@^U?nx`*J4!RM;zkbR6Vtz-G*bTkaG4#bK&HZ4_YWHk1%C85tj@dlK zII}88MkscuUa#GE{U74Ol0h`_~I`c%Pfi)Uk9cj;7t<9 zig0J~nU9ed{zF%nM!t!r`Y|Oo$FpI+wBdxzSk$zK^dY>Atgqh!^*4$QyZG@{xbcx`czXFRhy$*Y=V!Fl9J;vxtk5vQZQ)-dmm$ZHM+WbsuZ>-{g z?X66&y*;HwF!g1?G8A`#_X$7LpI`96^6b`Ja1DzXOrPD%HCCU=Cs;#BaeNW|%`#`b zQV<$l=KEeAf+{c;d`qqT7#w@yxcRkng~gfHvVEpJ>FcPbRQPT&l5sNpa?88GlaSI?Crzy@5T zo44UixG%aAeGP1;xP&4Pw5w?Ri1~Ely&VtMD(|XnVE0Qbtb4u(>85Hy_#;#2?JU+R zYHoE4mWf3V{cP)rH}JCnP5SSE7oW-s7(hGsW5$L({#t+6)bP9%_B?vaSN0BAXjFoe zgO)1G`o-$LZ8KqLX_&;JzCD<R7*&>o+|`tblu@XLhxXROYYQn;uOP z7pk9E_cN5zq+5F;FZiBcx_&QpBuf5e!yA8xr_mF}{wtfRLxxAxptu_?^h$`@kJ2UM zOz>WIk!27R(UpBvy2C0mx<+|ZJ^YZ$8pUkdfoM`LrB<nq9rNsh1Jnm! zc`s~tkE$!qXeu4&a9&@ER3Y3Hb@B+9O%!kbr?`j>h`$MVX%hJy)Mq{MGfssXb48Y~ zDRPQaJYbCrCFhpH^7EkAeMyscb|>vOCO*Xps8ZvO~%YfpQJItY-x7`dh4_ZkQpT|0HoQ@#{rzuxk^2TnSAhEK|1Yz z_W-VI;mqdn1A-YmwJR>-PklzPL0RP)6FIXkFS4~l&dJ*_8RIuI10&4;?3NqlYHLF^ zH#Z692Nm1LvN<}d7C9fT+FglNXxGmCF+HtT;UQ0;II{#3?(Df`eouEv3Ir6&i(le( z&T+t8vNXn7B}tEdfqLGveGpIiy-3i~Z1j4FknN0I|L}|NZBAxOOIqt2+V5e!3A$u$ ztOV{l^?Gv*_6bDdUB8tx0t-?S}QN2+v*w(ZKHP=*&a&S4@sSf!n?1*_!PgBjXio%ekCk%I_97u4{ds zsUDIm7M=^EzXm#xuT)x#dY~NhPO@S3*?its*sc(Uw;(c!=H^)L{oC2@Dz26eMKmv+ zm5M=|Wws5fFsg|Q`8oE&EfpWk{*poZ6JGn@U`~+nS|oRnakov%w++J9Ts|k+9PnH19`K!I|K?DPI z&fYS(4TomKQMk2vCTE{%=^jc72%srcecJED`ZiJF;|cESDxHSO8E*5p6Q5@ncguzo z$-{rGb$X#I4oSB1?PuH{oM;D9wL1cdUI9cB@^q(x-sG$bgN;SZ{;$18^ndI%_+m~+ z@xy&$!(H(Y(p4f|z6E|w`%k~g5jNEMW(}+!30{hUJO-j>G=qS?&bLvN5M;IJSsJU=^DT7fK$Ch9VN&? zKYn)qtSK)UT}uaQ<$<*B=U~;x9L~$1jbs|16TJxQdv9@r14>&*0B6^!J6{-_SNomg zlPKq*LTKHC0mhn71t*G@Pf7GvVgZ7K;+kN8c_BNV0ZYZ&5GT+P&v}}f;n-g z4#sA%MvGc@?m?i?hj#2q)9r5-uid6B`kt*X!!Gvsi2Bd3bnxoFZaAExNwU$Ze-`G5 zn%v3DkV80`d+P6UACxbq#Yzd$8#^dJzpc#E&AN_2inu50h=wGQe04qUIFbpcBmpnv z2`bRatHU^OhZK!Gpr>`w{_by(V6Ig3tqmWdJ?0C4breqFHVzA9TeqBYI zKQ5iQSAv#qkDGSWHtu%KM$31EkL(@`vHa$t&#D&=pUYSy_h7AC;;xJjC(EBl9IK?S zC$>?Bc;==ll(DHGCD{7;`{bAGRxT;){i3r&V#Sf2R%>8ghs@g_QwLFnr@QLSkK1dC zq%3>OYl_ykumLup+BwS6WJ?DFM+0ncOnbJf?z`NKyrguAb#@lP2M|@dwmicAgD35I zqt;c=4~=OTylGowu0gFxHsyPABSJN@J7sC#2Y%>=0f*Zk7XU4_b{fr1j(Byha(q!A zP=KY}yDZxC{#}jr-ivM@dG{JbMlW!~OEW$yB}p_%nO&41;i}=GuOBpZU$h`xknQWt0 zjdqHuxj{IlPr1IzK;NYvOACRVxJXJMYr~omu45U&;Z9LMZqz&qJ9RnA+~*8@zo&B2 zKKsvq8s|U#_ao2N|Nbzp|IZKOOY!zS`@4Pn6X;d}2e-d2O?Uy8{W( zEzb{WZ~uN$`jq-oBlg0l9@n15x5A9K59aJ@+BgED0PUD;98G5g(n7ZAs2mcK8Av8f67`=6jNMt ziPU=3yDD!ds$Qv|xxuWe@;s~=0*JWxL{R*ep19VE6(2({rd0RvvsClb48p_q$I*7E z>M{YR7wS8Y65~WRWiKP`2ld+pkqd)7fID(A?67=k503s3PSjGq%aCaxqKnSA;GK7} zs#6eX=2401YCg31ZRv)AuzO&WHkQ4VeI zIbmTwROJJYCOP0z9xh23dn_YuAXG#yE+v+J$8q}*M=ZJRH_CO90Q>q*DD%UI-@z&EkAiniwzFSfl&%JKr24^p#$U#e8QQ$sD=BLF%zrl`y!iJk2 z7(gWB#yEWaiF!YHA3v@tA2DI*J7Vkk^ruq83MklFuO8xak<8s!)&t?7a<#~gjM8N`cgRS(u+?*PnXVq;NQqUS{C3N!gPAN4^G9ReNqFnjfz#p^sP|DV<>mCH$7lF>vcx8EpjpnSiX ztFqsnZBnP-K9pa3M&EO8OUIOxr2pvzXG_n}I#S`hB5qrRL$>fj&&pU@- zI@!1lPled5j&sQt9ljHCRxggp zXPQO&+LBBQi-5IXRlb^7eIveQPab*2o_;=d`?XEmWbGaQ1SCaTw)PJ>HLhC-Af^uK za2*PcY%@ z!qy|;6Y)U2muULb!aq>F$x5*k@bn>MuzN)snmeRz$H{?JbsL(e-6W|}4UF&H3kVy0U#Ko=b|;~(4zpoO2M^a!PUV6bE6CwMt8j>A z6cPdaekcp5%8JpGjM?2@o>=7r4cv)QIsk5){$scjH_9t|6%b^DI*l56OnAI2b7fRmoLYDe_0}da`rJaMPxF|gHN>CntPx?k>S{9cJDEJW;&Q;$I;SCLRf&Sr z=LY+WBab^!lR4Wc!t_0a^U~;yzvd%Z*eEPCX$^c~eeH}HG(wHBE`jg3)WO_&@^Z#+ zExLVp@3X5S!irCX8YTCoLtEI}V{fc;@B#`IifTLKtKiwvHHb>|e~GQS5Wt*)QqU5K z31m+PFaAW_g`?B?p4PgLcL|#ndky(|7cw zbGT$zu4BoqZ_<#jUHo_rd$Nut1uWSH*z9#|-^Mghj8D2r8k^n*O|s4Z<9%uPbY7NK zSw(`%Ud+fS^j`d}c^>a&z(C1!uXpk7!8ks82>0nO2^Fx0@;pu%`pc>8a?P3PHUo=K zYsBIlp>8|Q%yJ{M^*B>mW(|HYx1RMHV4(gy{^1oR!sP9H66Hl!XM$SRu6p`S3%Dq= zSS8K&$1O{rPv8hO;)bTQCScolO!#qd)q(YjOIlH9BcFfz+XGItB*PL+ysyf!ms(h# ziRt+bud4VOmRqLC%om_wqL}c&(#wdo0^PHPesadi)#E0N8z|N%%UZ?q{_Ma5p5ihb z#(q@C<7HyPpa~V=N_k|p=NIjiYBn*yUc~FWz#gb$}DYecKv$y;$L`NSC}7O2~m9$7fNv(qVL4q!2-r_ zf0)dZ)^pf3s%4ttp5JWmu*Ni96PK?$3jJyDM2>~W4bKNXoVg0E;3KJ=F!)kVRc_VRHf8XL?TtoGkf+^0P093dHvPcKQ*5K~<7+Y-l zY8Lvu($3fZ@U0>BbQz0WvYSkce~_&eK&V>Jmfz~ueC;fAxF@(!=(n+U2Al?v(N>v? zz&k0p-@{&IQo2h`x#g2%vwG9ReLpT#WWMZ1c_$=|)0=jMw)@^g3u-58?}f*Rc5_dEETe z<$*>cjqtdiL|@B*Z9B;6sU74vN25YSAte*}3;XRtX zKx*V3Mz7~nAVh1_J`x_>m>x&Ea-2SEg7MK!>M}NAb#x9qoFt0g1wY-w`_0oWF^4k$ zBanJlA@qx}kaNUtGTHO)Pv$3pen5JG4vRPkar`rd?#tb8GTf$vsruTY4Un1ZDB&p_ zJmErE*>U2S>K5bGnfJ3&N<*sq_<6jEm-GT*qmi-QIe2XiJn}TsSJob)LCL6-ds_Xk zk|pj?;WA&O&6%zi?nXEW?^`!@jK|

p}Lq$Nkb7QCo zh?I(ylnO{QnvIm4bc5t1q+2>hNh;mV$kE#vHR|2}dEV#qzU|oVbNXgW4hP z8}7D@;T!Qw{;dl6+>ESO3dj2wbH8(nSgyB3wd1qmML1P|DBUxEkbNsVT80#gho!^U zKQ>;x@WUQBPX4-DaTauw#mWRUrt>_wd;jV4Z!!M=9&6{rT^q+bJz9^?nh)fCaA)&g zO?0nXcXT}#2<)O3P~h_7Tbd8PiOUR zH5`<5x$aL^76+>E97N`HMGv`){bMu|@bUSr!z@cZ7b*kwZi_`$o-UXgoV1bz0^r7g?n2RWHWGcsR&~ zoaq^0nup(M)iHN+fVf=WwX`vjU{dMeU-_@I;o{;`orIud8lxp;E1guAwkoDc{TWS^(@C~?JSHy)Uoo~haP zn0M2AzNFWNot7>HsSIVQvijW5kESeJm;68mTmc-!3QkFZbr*4lULi{jnh2gX^E zcF|M!7((O$SCed?31c1B(s}Ofo$V~-k?`1-_sg$VgXvAyTgIn#4u9aKxAUx@d3Q60 zkg0(3UGvLOX@Av?jMf-nVTfa3VR@Tj{mjTZ1>o}4&K3VQxH%OvjdFhhtL9gzN}bfh zNPs(QC}!sD;WvQFnRSe0$Sz>k!p{=;3$b(YbWBw?wmq*I1JHpS3|hensjtA6z_w z)u9>NjUw!nLlCfRrr3w3qDEeOH9mENzl}c{yR^AD)h)QsIqsC!(flW32=OC! zI1b!WVW5;EV0W!_Gm5%%$Ml+jO0_LxB6^>(hdLD5WxPlFk{^#Zgo_Biq{`HWwE>e& z``>t*^RSzo=Hr6JFUX}pqQf8~2+i&ru|Be7Hp#IU#s-2ww|h(z2g7$SD6xC?tV{7| zN&)8ew6Xih-26=4_Gc=oU60wL##v4>tH||b^XAd|Bp5E?Fl*ok`qVk9 zsjeEKoo~bQp3A0Z&AmC|(`mK#9!Pm-CAI3VY&{#Aj2F6ABM&0;ELd)IgL*~Q+ za%D=S^)rtMk+GlG8<{Dm4Zn6pyrh_&Cm`uxuP>($1$%hB zua^>F-j>NCPIs@k-UZ}LfgK5~!wv+^2xE^9MHbsJcDHO&DX>D_YY>(}&d%Pu&blXMOskhb;sNiEv)rb7a%h{S_B z-#rO+QAPN004!(G^!e-NLyV&1v<^l~Dt|G+eg!)26(g%6B>{nY{nj+ww5dl;r1Nr} zcRA#(t^mRe?5MRT#Tdpj_mwrRQ&ptu`_%-$FfTqu*n7=Sd1seo@t$`CSXX4uUas=7 zE;m2D00#Xlmo9fc%QN z*L~c|c+5|YLtK=TPH5r_p(dx34;&qBod-o%mb)I2#hez$J)PU<6hcxr-Rg^?pe zSf#1e#m*|9=jM^}A~chkc{H!aRz{Xg&!cybpYu3#;g?sxDO9Fii9O>pmfQjC{M|$~ z^9zYq(f_dkM#TnxZ+j3aF9CITIHI>z!%c6Ha#zPhdj^o_Q8r4-k?pcYcCr5sS22P26=Us5kCqpD#)ZR_jd3}2W!BM&F6}n{E`V2ew@wMO#sgwCla9!lU zj)mZLOoU{C?R&)SqKZ0m+itKoGHbLB0k6JNZO?@?SyxgBNzsyi;PA_J}ZHh6nnxRnsXwHMM zOsP&_0q?=jhTq^J7N=9(T3qB+6uSwUcmbE?GuamZ;7;>bKETFx z`-xz#R={9!T}6#JugYFR==HMNRZu7`8)ZD0T3gz&ND(^0ySVAVv}iqFo&HCKM_xs_ z_*Bot@!QfrQuiRvIV{7O==gNaG951B&SFKe2heIa(`km+4+k|iF$xiZv}vF*@?Ez1 zgV3c{Ox-p(WL<>he)Ej>rGe}B-NEi)Y21%~1D2EEA4$eF%Z0bqV~$*WEWb&32BApD z)*@&=<0r)ta+<(2oOC|WKHiR%4PR)5*p&B1FTd7H+YnRXA3(ml1yTGI>!> z>K^mP>7jQmzE&M$B=&=dp+hrW^mEV2v|?%K{hGl+fD(Ln3q_xtg_5r|Lnh4B)TNLp zc9R#IcQstlaQT}bQr@t>1h+*xs!gax+Mf%tM|tl7`~5l{tMKa|woI2?-qX3Rn;MDj zE^s7n1gN_O*UBtV$PL@)-}gZW8}oL~c9fZGT6Qp`c0$k$-R+VdV~rKVsGPaer<{+a zgLP;S&KuDDp~C#O4Oot6+Qv!RyN&P0W!_uA&O>$s#OsF3&LXHI6)3)fRKTCGs&ejw zF>c7g>M&`%*ez=hqTluAP_TkiY}3_dC>>Xi*uM-J-R=`H0odPz;Jb?7lFIhl!t;>n z`p?Ru_8Sp{4Eb{7NWM(Pau_XvDf*4lWOoj%#h-^x!Xl#YN!mV|1-8lwYowSNDUo`k zgB;g84TNmx=C_6#W%DmrXP}2AmWr18fcCWQbIyX`S)B%LhLmtcI)*(3I%l7fn

= z{5(f%0Tr$z1*W+@F>-3A1Glf>UEGZkQ#hO$8Ycy@zDI?W{L^nK=J7xh6X5-#q9%~f zrPy@D&B*Gj5@tZ0P#+Tze6bviibtccohLv*=WF?Ow;CQu~Ce)dnmm1@s~M*v%BQYL7MDOhv5n!@0C>! zh$6GuN2qrfzlmt`aZNefe^;2iDTjxq{nd(Ggw}@y1P!Aw(3p;x&7C1SO|RBXYqK^a z%V8RRa`PF1R?bx0NrnzvW^YcG{QM5e&h`(k_EBlAXK76bVwQ9Ntfd=@H?^+uTIWdi zkRQpd7weZ|3p8x@Q%=wFsTgYKVR+ETuAEggxrvl z-)i|~V}Ea?NU)iafze~3VPn0)a*Dbub45ALEhT>jE2K*&;*>(tl5{e#J>|CuQ&e4rG)-z&vvhRN?gcl*BEKd zBhk}T_04}^@2rQ5!_l>W;PAGuF++w>k_>5bbPRmxIU~EE#9o1c^!P5T$N2dAcdz4! z5SlaW1KDRoue5&1;7OGW(#Mml+6H#?eI2tj8a*Zbd&2uD8+%3Qyhy73x!mk;rH2|? zi4=l#0x@OGF+^%>a!5#hZ;5h_JC?Duf^cnLes`11`v2OsS(N|$|Dt0+=}{+Bt0l<&N5__PBvJf z3$b+E4v)?X8I&Ug)rD`Dg*7`_zRC^f?$dhkkIrqXZPlWra;|-DWcl8E4ag4|&_+Ga zP^Ea#i(EYzMO!Y|b7$+_-=PDXcII+*GjZruRL4nmTB-F~KP5bGrF_{qD21{`s>21B zt!RMewjDyh3)yU=)IMO7J&T7{$vEeNn~e8*S|0Y;_|Mqq&kk`N)h={x&?glY9q1K^ z4OiHX)DFiqrr~~M*S>_{vaAPmn650cVo%>4(+}4?`#AoYPVWZhCpndt(5yIfbzLua zecoe6_9(ocBldDV*`~N|-ox>9oQ*sr9PG7<(UHCy!*qCo#dm8S@yi1-+tNwI6D)hp zEt{~<6UG1)2+>H26x@Og4zmG^i;R$0$16k8lNp3~C1$gXOj<1v9MN0GN$-d8zaDp5 z<1;a_-WnSD(@C-g?Pd~- zfLp%dH*#UlrajFWGw**3;K*q)6Gz!={#C{g{K?AXNeF#j3#$OPxyFbh0zJzWYr|vy5T9a_yb3 zWcRo}NsmE8T-t0ckiuvCok8i)(Z5hdMON9ovOKJ6@+7X{ieHEjOVGIZnnhTr=aU5s zoB_(H`4Xj=3zQ$N|1us19L8RC=ubROEkZ?bcoq1@f>%mC);{=iMsu2ojXKEg)%wVX zhdSkd$g*ZU0Nz*VcmlSLe4g1)X`1}_e&EF)C7yQ7d_a)oTTq4pIUOjnwVyBZbonnM z|C->6o-y}4YqXt5itQ1(bToH$`_gTK3pYRRXKeI-8pq)Zru#wMdOr%t>VC)7 zWWU?k-a{;@c+enCy4qF-QwP#v!KWN^y5S|-#C>*ew(OgP;{{EdOPIWC_IP;M(st|-)~)1AavJg=b3^q{_<=OY17){8T67q2-*#f>+XGz#^@ z!Cp4^Jxun#R296JI7cLs08}Y>zo{=>vhSIlQTSDF80~b8nqzw7G2;=Zpm21Oq2@e zP_S>SA_V&Pa9l*ufox;kf5}R+Vmj4&S$rg(f&El5a7ZBSQ(6MvheN5ndN?4Yw>|gO zB4I}*Svpa8zMW-J`E<0j2;w9Z{}&sqUcD?Pd-p&i9Jj_9iF{sZZi5?y`^M{e$L`I? zk`Pcg6g)_&`uYX2wt}Rihpy|ncg??-PxM(+=)noZuR2tEfNi(Ii z#6ZO`VbM-NcxQwgVS<&6GWh~|ecsV1zTQrsN6WW}Djp|6{)r=vBljPXwrs;KZ&!Qu z%t0$w;q2k^WSZSpuGzAH@LmH(_KPHG=aUG( z&#o4wn679%P_R>MRD^kUOYtPnL$l%4LWWMTjcZpl!Yb;8oNJDY$$`~(QzZyAeWT`^ zU_c{n<#z**qi>APf-}2sO-Xqi`dh^&T0OC8`!QX7aB{I#^sVXTaP02nIW0A!d8bXp zd&R8t5R9+u{0+JO^OifMG2HwFg9$eg1vwA!hpZlLEv`-|WR^JHF|``jQdSro&KRAO z_f9NE4jD;AB`8BaDg(T;#PN|aJAOImxFFiXLh{c$AAYTR+3}dAX|Sn(M%`2B0VtrpcW)jYX88EBE|& z6Id@~;9=(E)Scp(<1I+{dGwuHd_q~r-}++OZBAp0Pv91rt7$Vm>_8Un!YTc+{zn*- zYV}C(Z6t=5Lw< zoCw#m2t}Ad4B_?lT{f`|X7TEFosiUj>&mP;&rw>y7oDldi38bP&pjef$VwD^$jWLp zsXLt4S`q$KC6n<5RG4lLKjq%GrM>*^@c+g?;E!w2Sh>qDjnPw42!-oI1xU{Q*~F75 zkLH|6&XmBoQum$u(f>p%CcoEcQuJC06C|xEImJYo&b8PD5x!)5Fj%R$IRNoJ#O!;t zHbuYR633JaG`SP4EGN_le%I&c5yRE$EyN{5D{`4e@&_9E!8pTnnb;`N8X znw$MBBK2+R*mmn1tdWl%65~I;ah7Sd?En+)hu{p^c^n*^Wr>Zo#c09a(M$(rNyo>v zWd}D?G0OQ2k$pw-2s}K{_ygFs50<7ghg9Zylf2#j;!R=jOKC&0?|^e1L^{8CgTbpH&YU78BjA&hK0QS_g<0RT|w1Mdy+LHVcJXcmwz; zq$5Ewlbf+wZnE}>q32E6K49AK?4kV4Swn!yo_%ptRQp!Fl56*q{&%E}Irhr6j#7JE zhu|+dKICSQ^HHXdx-!LYTscL-BNW>B-OS-2xx%$o>Kvu$bG~_1B};5k*(oFE#NK!9 z^7my|uJ?Sk(yPI#A7ChW@!Uu@GQiYpauQ2JrWEBXD@3mtiNpRCEVeyW?6zRD z@>jZwE7%+f9Gn}D6pKKL{B1pqymFeVZ23S zJZSTNoYs!{1OrncM~{ni+=23X?jYxZk$#aeKYvp!<4~mk_Ir>p1Rr@(zpR>}{56Y3 zotR50&*~a?bDhdI+C0``-+p3m$kZ)$sp_sAI=0dBy!Y09Bwlfrb5X`S_NJlY*MpnnY4=$SWA5=@0n=_o~ zXGYqsr!T?XJW+NdT&&arzgRR5>T_NxaQDdQ<}|Zn@0|C@A-mtzGhWO-Wap5h5NOcc z$-eXPfCun8QTj^s`8&OOxtOT(aZ)DLi(eSxP?E~w{eJWPp{u(+tD(P+pt6eSI zzB(cw(l{`Srj2HYrB}c$_gY=+S4L+)+P?jmz%ShV|4$wR47__-Fapr>a&axDxi<_k z`GUKb?B*3t%u&AFAws%-o#LKchu74Lk+lH}%AaQ{KtgU-qSg$VUAzG#!Cpl=vWjL>4@l514#(w&AN0BGIWsBTGXSXfX!NJOPkAe86x_cn9Gw^yMCPqu zGR)#ZwX6XUJ0tB34gt@ZG)~Pe88g~BX;(Slb8kg859_IQvq|FK7_Q5iCYD}|i%uuZ zR9VleP+7Syy_!04KvyfQH9W-b^R zwA7o5?X(Cg^|I>KHdWQCwzym=Yb^gVZtpP~(YPTi_EC2#OMLy6LR%c-bbxglTCts^ zE;8JDks{;0%`^CYAH@0A>P6EPAaXmBeZUy~Fgj%I$ZLNeitcqhY=MWs9WK@!S4gfw zyG>`^C<`8TW|N8>ccQXA9fe*WVt4l)Fzh!4?&=GeXSa4>3N&}Jge&!gPoHyM?kyPT z&;s2f0Gdu_84*p+A1%4l>%8C4duD=l-#Wj}_~(}Y@XO%1ET}I14M;<8B>%vWYe@%< zLU)-)`ps5jRW4&%krM$wG`k}@NGbU+)nrhb6|?7=T#?hKt)%b@m1_p zdSvS$${ZMba)ZeZztPpCl|PxXE#0OlHSZ?pxH{`@`I$3zr?%BW+nSJ4Suc}HcfcDRyg^008o|1+mZ@TD;Jr*2u7fpXj`Rw>{{ZqTR=emGuc>0uyp7tm z*Btq-8h*n3e9o-YYi{Z#gk0mM>VrxIr(|p02Zm2`dJ9v+u=kL|MhY+{YQkR^u{=&v zP6Qb~csG!YNGCiV>ol29w9LhhP`g~P`fxm+y4L(_mw88JJ0(5uNCs})gIhCoyiMD< z>0ndf^zZwLfkVjM>eQtGR3vPHy+~-U1U0e6Fn0N$`vt?_isSFhSGe3l2|{3hm$S`) z=13wIep|I`)~EB^3YZ0Fnd{CgM!fYjwH_I^N?r^eTxhn+c=WeNrPj6V*s-1nqWrN2qnTq~f)=;T6`AGoTszx; zI+YMt?4hS<%yK*7>1XP+p(flYD&<_5okthotF3}_(UyJ2V*xj*Uw_A~|CooJDq0iP zw;j8^#`K^H`g`Yly4XFOaz|H3a$@XGgTbbrLIqSV|jFi|Qw1AOvtqgqXyy z@7jfCDI>C@(ZCPe$ZuzrvBQsuZY5KCp;bx8F^TGJtdXh@L|y0`^kj$I+sndlD=yeFDHO?&16Q)jXZgC{WHqH z?nS|;PEOYFZAb?5?_{uzcFiGrx{`;`@u}yaTKsHJ+4;)Y5P>UteiWhG7~ug+YFLX; zYE+5`;T+cDq(R>vO8e0(L;~hPCX3Yy)x&h32|$cCT)~&qQ+waoqM+edl)}P!VHzB+ zaEd~8q$$WYZ(y6?$r;{I85s8Jc(dhjF60ooJ_l!W^A}MeBa9~;$dZK#us`8sNE~JI zi3m;vhB;RXRt>rR zSaYC%aTzs5_1H+rFcaKq7DvfPxzg*_3QKF zgYteYuOFt7$9uOkfD_2OZ}nIH2!zwnMuR*nEH#F_HXe2+))eQ}$qJKA3_sN}|At%! z_->`FsjuHjBFW!}8s@?vH~F)y-69m(HtfGXd>g#GtMzEnZ>dH8wF1ORMPp1lc0#`+ zMJ#Rf=k9PchxJ1XGpQZYD+4S2|3($yyWNgu&E~gU5{dV z%ej;j+m`#`+PNSiglql{Xol?D)t9+1Rd1x5nu*X*z;)&sdT?5(`#2U{L1}oQ+UTjC zY3=E&gC!nOcokw_j`18nWoy@Vw7D&2_gE`ny_56Z?oek_Y zk4%fSmds%64J&qPH8MnpY&cZ`s=3}FijLt<5pUsM#eWuk8xCndM zxBU^=ZuIoteoalrJIMu%+PuHuc84?D!)_9m0s`v$BgE za@vV$p91>y8pC?RLmBU1WpmMu{OgMbtJ={clD^_pr|-Y|xs_O1cyBeBUMlavwyUTh zq%zE(ioAE7NN3GlGMgZL^?Bu1k6UshF|PS*`XaHAHRiKdSAX#WxbNP#04MVq)Qd2a z>X^bSQDB(iBA1KH&wqjc9$s?uH07mE5wyQ-9qWj42Y4_=>%EY}$$4rg5deT$FG8>8k!r{Qh3mE*ac%_#3M0dw46U7+-xO zy$w}fuVTv}sYuP1OR+Ee<&{MR)59FKpmnv4|Ke|4<93_oedXBVvc{sVC&e|#xf+7o z)2B*HNJdS>>pG*|^S`YZe_LF-NZSv*H-YE;>cZYA0OG^0VBP#^GNq~C<&n=&1Qvz_E}J^#o;n8tsR3S0ghDN!B6-3UF*tKLO@f>yp?HW3aOd&M z+S7YWbN8Wq_ot=C({u1*pT%S<;#jDtR>&wa0OcgBZdRFIPb$#kpq=OX-Ub!+!mgX) zN+F>y<-mdMUx{xo9yr;0A02atiIy_Ih9y6>h7<5Yh}E=!jiXu9kSEv3wcS$f(Q2f0 z57nF1FIMv%%%F})s~;U2pS{EyUQ;ck=syFJyg)}8k^Ft_vW8u4X~BAw?GKxDKg3)sQ30}oa^)ZVS{ww%h;YaUB(mS;^xnZi42v#e|Y z4QQ6OOI^`owi>QSi6@6Pbm>if$>Q<`XR%9rIJc+b)YgL(m{cJE+?Y^jzr1O3wtwUV zk6$oyz13pq_7^($X0aLo@$}F$lwpxADXJ??@G8TTdAR~&ic$b?GhVE=uw;v@_OQJa$1Q~;Q$()u(Ou+K{X!y{j!Xt2*1JbDB5BoHhR{{ z?VZp5O!iiD%Z|@hdXF_rb{fcM>cFWVv0V%vE~{6&bIs-cP}gvCZ+clOPLV|Y3ayBa ze+%QKqqs`UI2P?Y&PBuu8=;fQg~Ff6oa*dBnOa=*tAjN6qO|dEPhB3j40P z=nnD8JRc+vnNzrKb3ECjr8(b6`kb25`glXfa-{W4?Xyg}>#h$k*Zn?CJI!42pbQ?y zHr|&SAjE#G#zyNIfsZ1idJ|*2E9vb&Lqu1jSVHO!-yoVRmyEYs^vm5{gmz*qaMYLP z{lyALN@ZE{B8MV-FXeX>VHeQa9W%eZE5}zcgC{)k42JG=~m1=Mj{B?vQkR;BcP=y=*tq%arPn~$qqbc*cCzSwIIy>1z3RY%BWxkAwxo8|KiBy|)Rqfh zf0}#i5;ZE0v8bA`Tr1Y&SlTUPQFYxQYjVXfor?9PFxv>cvM&{Hml{zu`J5?Uz(dVm zAIQPK0>y{wai8XfZlbp9oF`_cYaE-KDfd?0%$0m0F8Wv0&oC8LEJ5W3LoVm9PGCO5 zz0f{$M}D65zhe-N{+L8*#g&8sjn9V>lNbsq>{#gI6wCYf^$k^n1qk+7Wf0~onix>U%GU(QFQSh)|ZP+b~JoHaR9@0DQyo3IMI2TiVeI2-bZHAm`84}kqKk431iuOnsM z_8Opt*X4J!)f1reKcydB%bAQ)Y`)3F_QE|g3HR8Ad5yovEQ-y^zJ@8ULnRy$F1;;A>YA@9QrOGJwSe4eJdr2G%VtiLDg*SUtbpsTfKc`WwHkkwlIrnKB;)Z@ohX`{k4#Dl$Ewv-Om<)Xbv z>~(6_)>{x;REtW6csB(j=d5^lTd+w}-12I7PTwkn;FSBw13_E-1NGl}ejnkH(}Z26 zj9LFVg7IGY+?$D}`ZGuyE}ETI+2BK;8*h#J#2|B)lxd@p$zR2H z@->xR@yHu8-mL6rHH6*i00AQ^$xm!`61r`qn`4zZ+-}eQ$-I)|c97Gsk>#s@q|zUy5^A~2%jl#^POArgF#~9lL;kMY2cUdv zdKlt`8m%r$^4o{*m6CIKTh%v5s4gzbD#-g7vVFu%Rwo#xKRm8|g3#jTxBfKDre7Vr zg!!)QAS5n>`9rQNd&O2*w?Mn(q|&O?l1=qEIjN?FXNq)ALT9EOP`A{K3qCX^%c?v0 zQrIL;#SEtb&oYFPEp^q%U&rBwraeX~$|EEr-s9S5XgIXSr_$amdL&iu44&_ElnIcG zPUx8~G$~@*P#on>D~bNnKintG%^)qjHG9d55G(ZeE)J}rQ~zop`2f)&d%N$|Z=ST^ z*KAIPUEz>=%onjY6fMYcd(e8Lt~}>_3y$DO`QKC}-oh(tnyX)YeQpL^^hyw!6C1f>qMxZGtq(b) zS?X3ByvN|b1mvPk!8nr;hL(%36}XVPgi3?&t?GoWU+%tNESb8Fjb!Et%XFP^u*WAE z*j#C6o%fY#i0whs=V`-Dz-b1=Z?j@`Zwa(}QB@q0arFL^$CeNwfx{#z(TB`W2}1d! z!_{V*yOjSZ7vv6ht`6*o3S~#^)NzXKPp_`@m;<;hL zX$|PEQ915toT1ZcP7l_;TAD{+#=g3x79FsC#}*^~t^lSxun;!s&=cGvGuE9P#wqOm zGx}uSDR`R!L2L{Ig^|?|2vM;j(9vU zUTR5>&pUQfcWOv4jLY@EKI~Mu=u8Xii7iK*r68Dmk1hRbVIB#6Bl#9U8~k5P)AFhC z)rv4de1X`8(@<)rcBJ{A$H1>)u^Ug*Xc9KXMEp}|7+0u&$X7}y7F~~O)D!8kJ(;Yk z6&MMpp;u1>S)q{FjIjYjWNit9gQh3hz0YJ<2^kq2+;shJTg5ap+1z+f&dmUE({EdX z<8J9~xwrlqyP0pciv{g2`JFi$z*MLQP18$z3=gHVew_(dQYb>?@#3EO-u|jrm`71` zh!^kYl`G&jmDkUi5{%vxO2o!@%m1bX>Jc-4DhDjn4e`Rb!L*ML{NKj z)bP+jv6?-ss`pn6Z}DGk-G$Zn52fb~RC4#5PmncilH3xXmLFTXB~=CHc+}y`a>d5+ zuOQwmltNWDU!~3zX}mF(*`n*M_j^KpHN?~oeKJ{!E^`6F7NDz!G@ z((vROYOOWoUG@gY+1@S1+qidVmfVn6`6}J{w1j7E1faxE*x0VN^57wz(tZxmxy@^P=$H=&ix5+$RqHDC6ip`! z(tY|UE}6Qi4Ec3h$2odGC>bL%Ws3E$S@qBS=LW`iK4hCJFScd)s9@rIhh&g(Bixe^ zxLe@l7gx1HK&Hq!OqqGK_r$=J-_B%A;RVEELtPy{`ek}ey&U<{(}9Y6oDwJavD!K$ z7*M^}6=0ev3wFYU(`v2ARIBLf^a&R4=CMBRZpNwf1hIPK-lR>bTD@*qZhxj=!L5by zN5y%(f#7M1tLjUn8Ika@V7HugH4Jg z-2hS|ef;Vvk*>#|?tu&y{XM zQ~Q7359c6DOdWb~9sAHx{QLf4%fCW=QA`+P@U?zLQ(6|H_#aj7vTM~!qUFsS3`KlSo0Q~yeWq7bUJ$DiO* zMWzvc)O+XO16^-)0{u)!p|=oBI-sTtkBs9n8Y(354%Bug8Vf{h$(n0ropoFLH|O_VikK!vph|Za=&R+PrsEVe@G`-1iDm zvwe^L?Z+*NQk%j3+8wraUe_qUY0?s}vTEGx$yY4o+Q$JK?j=_c!S*3ys(S=4cPdmB zZO!SKlO9aTH0^7^?tD%hrOR#mSl{*IQ4pY&+k;{1C3Fd_(orZ=CQ;Ssj9)hw z931%t25Nevu#$Y?R^dfP@9iG1^1ov+fxfHbq%bRZ7eh&FP+eY~sm`$Ya@<)@)BMqa zvNJ`d1uUDVFmPPe^?iMRX~2Y33+brT)>EcDyKq_4r&Tu|n^vPdwgVV6=mVgEB%p>c z1kf7iWDRur(ZJfcdn*hH;Do~#BiEY9)O6Qduprf$Fk#cLl_KqMN)w}G?Pl}ON-9yA zWvd#&D|l?rEPV043Cke{U92rcbF?wHz_l+pqYZRq6`nD?^nkvRHKfdMj?K7IWi{$w ztIMX%k|r|!nuTuB`AmOD>Qq>vevJW+kVT7_m;2oho9IVtyI7=8XOR*hC(ljC)eLfY zD`C2&lSJCb0lG@`H8yV`S>T&A(bPloKIV)j?+`|pI6c}XB(7N5wCRV8#6MWd4g?+H z>vnB;wjl(S6S%_7UkJ@M$%Nm&d^mHQU9$28$<}2wJ zGMkVA_exKYJ98Dwm^L3;F9miZ2m`Op)1@4YDy(*Rd0^Q}u&(0qwymBqG_{`h8e`WSF%HHD50f*a~Y=lYIDJ#G5FnjOFWw?1!I zQX{4J5vC)7`~YfwC9^p~%CsKDw$vzkjJOOamE)~CNqn`MTyQe_(LO&vLi3J6Q zr}ca2q(KNppm0wh=%enM&g+ZJq>ST;Ivq{+tG1h_48XU_yK?)k_{!OL?!LmGww|Vr z&@bwuKGJhs#FkrX{*bx!*|ElI2bW}RNi_{uCM=x{iZqTt4WP<%NO;*5w4~H1tcSBN zC{&;-#<^c9rD!u{Y0Q`}_$X#QfRlmo;J3mu3&9^kjS<_jJ@xsn_QybrawqN6dP!#b zi|SoZ52r2tcJneuwO{L045 z1CJ?(4cHP+;~BQJEz=LXcorR=F1{;7oQ5K%ueQfNyq#-BRQ+!n+(Ar(t(g<3-WqW) zlIbmqmyaFqP6tc7%e|(P?v621PAjdDbEKn?5vPb|6IQ&dI8ZofTltNQEd?)2-Txq2 zI!$PG?HoY9czZ(kU~M3Xs|mI|5Jcm^_MS-BeGT%YmPt`xHf4v2zXhx#{@#p`dED?* zQe=5OoTM|{l$3>Wu45#WCh3@1DK=P8-6=R3ucQy5X-$0Sou!pIZ2!JzPUEnCxT75R z<3TaUMcRCZM`n&ZXG_*ia5sxMGF}pmDA}vwX1K_(ctylr1K?%_?Ou2@KJsQAh*T5tZaHOS#6n?S7|V znK`)6x>82jSuk=G88>^{MFHfgA8n`M1Cz;C^CHrvTt4;Dl;dK8EsvhGTGFseC+2Ln z1&rm5nFu^#vK9#2;!-RZTeeTp1^!YoY*!0e?p5=(5FGoBzTen!oo-_NcV0~PwvY@a z?5p>(con4)oDj6nV$-4em2?isUW9zI)b@7?$9IJutQ?Kc;rV-G&jm-$!4$>rX|Az2 zV2CaAF$C2J&>tn(<0IBU`XP^9HwH>&hKkdxv8P{ZR<~L3TZB6`LYW-YH-G5?G7Lk) zSy5p;KyQcKa2&?SyoKsSLddaD`Xct=gD|6Ff`)L@!8k;BE>BBvC=MaoT^77esdmK! zk6!To1id~wq4HR8-NE!XDS*At7{Kz))!>oKI67L|d{a#J=hG_N5aV*M)r#|hDVnBv zo!=CUNtIUH^3QW0)SP4bb+#wFM5iG#IJ@`#KskD zIG~88UKR~U%JvaD*YI$_66uE~fDP#0=t6KwyApCM=Sk0+G57D`M}FqqrnoRf(=u_} z!9*2eL4#aY2M=ZGr17X6CZls?aFb=?$uACO;*`dwYC=ORH{9JQ~e%B*=JCgj1Ho$7{|0C+X|FQo6_y0$qpfV?^Cj}SDe;~)0Ua+bsE`n+IyW&24FIF~w^%I{ zcB)!%%RcQmZ%G*`szloi=ka!c3(x)~V0M zg6mJhez#?hXH5v0M-$&Nk+9S{wPgMsp)JYixwWX*QK46h5ojhlvewzT*P4knB0rOc zT97fKuMv>1rJy$*nwGO)^=oNE;qp{a6|ACA;PRY}(?^GM`Fwpt3sU_lL+T>rLZdmC zo)E;4A+zxpt{_yYD8(nP}3cjZ2Y?|%ZDk1;l0$Tjxa0IEgkLld(#5oYTIrhz-=wLuH{?L z>T?*h~K-nT^Y_kXPwrvLRU)TE=Fpafid-zBFDz)KZ_ktFxvsV$fw-)*RgM z!j06chXvc;EM8aA~2EEdzgWIEU_$~cCyGwO7<`tQp}+)Fy4yu(hw8fCAsjz zb9O>BZ8Pcv{AiZ?x`Mv&>zFc2jl`h}7aL~VX3g2oU*M4&-s|=d-OTt6XOScsEg%oQ z`LTI-%BZSIZ}{6lfdcgP2J6VyHn&duSegLHc}u5#R)cx{)&-Il1i>VuBx0B3nj1-* z=M#?5rSs$pPLBYzBz+TNCnUW#(&0ciOi-+c_b6m7I%({JUtC*>6vu14QRy9{m9P17 z4`$r`4A87I(Q_0ZIjUEc(==PMB+}79vDXX`vTGc#GYYWC+aE#1#e)8V@mQsrpf5X- zJ6l!!L%2`pkEL_&Ex1aSv5C8c1L*ty6wv3(+7g93`6{Xk{HQjbrsjiBf3_=o63zNJ zE3ti%Lj>%D0oE44Irka%B~LCS8f}2|e$Bj@*Lv5`L(pn4b+j%xk2Y6v>Zg`TfO+Y` zU5$k>`Rywcg2aMZ3n^-z*9*1Cn>tOtEsO zrC=F>Nwn)ai^;fP=rTnl$k^Dpu`BTE$VNq9o7EYaZ1Emz z>TEfpse*U04x5VqVSI%-%L}IUx*(FaIWbF=c7p&z*W6?eBMRkQe+Q@(9Vg`U0+r`r zYveJ9D*m83hAV8Ce}1qpsP=Oe=zVezl<{?&oKy*0Q$3c34rC~qv*GgpSO9J=F`P7< ztgGn8@@>z|!qc{2u~JC1#kdgw&HTtu^dy|OTN3CtlK0JSqG$e}%{P$H+8DL?npYMV zb&QJlSS*vf?OaozuOaqUlC4?!zi7`l){bsp4$(}QPaj5bKIThe4T=_btgou<88}O(ZF{>lew7o8lHc8~!<&mo!BtY(KcO00X(R%UM|?w(e#e=p z{;+)xW2fa9)T~k#+v2;6!y9LzWMqC_tNHXfaG%A)Hr!SE zR%w@fC4+y6d#QnH1`l*B2aos<1%os{bqq&#kLzsvU&VlWMGi9VS8W!^t{XB1SOVb# za^DU|g`f;I*wBi{l1#au`;W*@da!)BgWq2ifKD6>*JKat?q#C)idJ%Td+hTRu{2tJ z?*Mv{^8DY#knH~VoP6x0l*3NDYrifuzT%Cv_pvOJ&sR4EpNqgqtr(~E#6*QoB^Y^d z@%bhh%&H20Q{wc-x~2+tvKaSDR2fn7I?w@(flmPcMw5#7p1H0jU%(L;`tG^M#m}p= z_n-V?R_-4zSaT*tSh@MvuNN4TqRvsRX#uj2Z1&`~dQ-)tegri=jDVb{|3+IJA&l>r zv3zB+x%o+KJR{s`xA^%KjRc-Qi)Jv^1^L=T0dhn}B9Foz+xA`n0;IYR|HE#Uu4IsHSn+hPk0jXTPzecNy;P_z@^SUHP68afvRUs$FsI! z|JkrR)s6895(^_jz(l;h!=j$AcXux6$ocmdi!%A_w{ijkLAEzTXb`Pkf4*!f42cOmJ+{;eLrY+B=oVda}IyDXGB7MJssf}kfE zm0}=#=T#0+r4O6M*%6n-Fkxk6uixrLLb%k&HD3micW+%VqEkzDj*qEM6NT8F%Rt>- zI731-``X%>Ljv(BgVJb=|KVo%;_uHTIdt>sY7FT%5W;FriYK$?lB)Udw+ymXC>DBw zZ+)}^scxzF(xg(K%TYUyJpK2%1UT~(6=AsFd@%HEJPrm_;E`xB8k3`;%KF!F{gEuGG-2V>xgZ7*Ydw*CTJ2b!8E{eGv`sqbk=(OEZap~) z7V;{nCoK-zzjVY>d0I5wYi3JIZ=|DP^>RoWyw>#gK5M|^(#nAl)0|0y$ z)h5=qqGN1wErIv&CDf(4a?Rknn^dAZTP-i8vHg{-1ywf|%Lh+($L1!*n`voHJ*M(9 zZH^As@f@iV8CiyI!Ij3iW%y!yo?esa+Lh&lvd3p78xD7W|FF-zcnG3eo4Y_<hl$1Zj9e0tO z8ijlo&yO!9b|6SkdfEOrIvt$;xBqoggX+I3*-mijf4K_Y5G1lT+*Dd(KUYDbp{pw1 z`4wTjfETDnhxZcqsF<0PPeI@+#(<{<8dVIE`BP$?yn>r>NgKjV zP`sL3PG^T$Ej&uZ(zFOD+tdFqhST1^UQ`vCpr?fNaSf)PLUD2RccuvA-rKx0V&l^+9qEz^O?#eh;d^XLgl-5bm1Od3 zIKQp+)zL^Sq#99`2b2Bs*Gh0jxeRzDKVa_}*N{;0tmS;yk<<7iC-ZNvZXq_+9ITz) zu_E*;Pfyyavs*-6WSG^?Z>}CK4p2bNLzOgSz{NqQ$>otromp65=n0=A*0`2Tq@V^H z{ofe%Sn~=^Hp^piFN&}saHQ7evQMO+X7)~$nKRV@i?Fx{a__xaX*?8BB;(x8N|B2c z`Qu}?Jk$mV!*}u03R$umdILd@RT*`=GUApN%P%N6jXTn>zSrl;t|f7n!ET2cJ<#jX ztx{4_{o6Sq{{Hla@nQ1YA|@853OHyjE>WtwpIM$n=Lml&4p)WbLQ}?iq>x_YArwFQ%Cu=E?nJ5#6)+@UvP6pzF`n_zmr)T5%7uG8jbFzZfmqN zD5o*0c~B50^t&~0wND|Ju&Bq;>bj;a55CzK*F%rEmw`dYPPFZmvnMVxghc*UJ;QyW zgt*H?Xm?q3EArJXSGRKC9X%_J)^sl}g-NyyWV^Y+Ck2x+#lk*;R+b{yodZ)xcO)xz zdQ)jO>(s;>7dBkGl8|44ql+r6-OrMandWUgJIWf1_p$>G(chO`-K<{+^uxNj_f^cW z{e>Fv`ec1M)uj(8qYpwK{c`_oH?0;zT6D$u2GUWHez zKEo}Fy`S+!+~Ayd5$DMMCjpe@;e_f3h2Kq4cUy%&pSt~8`Z)@cb?;uV6bySEiRwM5 z7E;uqw)I1QwR@{ILMJ3@5Hz<+m3d@h4TaLVge)!@=Yfq?$&0)an7B#3qm)m8(d0*O zEvS5E-SR!eBD-y(j!&QH`E{j#zL)1Qs8HmB!j3$|ZTfP$v$JmL1a%C^HY0B~e5ZU{ zt?rk5Z#s?6REF$e)>X8mM@-DD+n6ubo9%#mSa*G5oG(_Gu0DX$^5Z?0eG_s3k_AysYmM0&CKN4vUHJsb)`bTm4iAOD z-|w5QcPL_E?s)H5E^F~1X6NTWba<>EQ&)!W75c@|J&U1*j}2$*)cmFvf%n zZczH&gf73SuNaM+VR)4IqVVLCuov6?jr;o%pYk&G%%gE%(s(U->0+WY8sSvdnsXT) z1N2jjSxW{ZuvLlyRb&p@i9azaDy`Fa`j_j>^$&uTw&#Z;N3d=O_xmVbx6;_%=EYZsoOat1(@2sEi2LzZf+7$w{ z3uvB9zT1mH`JeWYh-c)uGvf5S$rqBT5vzup=r0aU8E$|Z=jN(907a?nYV6rtwY&4J?<5ED%oqoS>yMhDgm(O@1*KP<2K<^bDgijr_s z%3sYRAz4raudl?bF9{5pcl!ZCp{x`q@K28$_5KRoU9^~gbiMRNdpbV>n^Jc@Q`Vs) zOjL#NR>&&_&&1mMgCf1}wscUKj$wv!1&pzD=VabrkNz)>MCs~s+jfdK!-~LkFYVCh z>bI#^4rKJ@6WLEk0*C%#LT=8F=VyK{G7}y{C7P{Wg~--u$NjmRD&8wC%mznH?E7+M6;dYSl?V3P3!1~K zg-?e%ino8eRWR#z`R*rR4O_QsG1^ARwQo#~eYU=<_j&2{MOQ^9y>!@F3wA$04U)cC zo_!Lv*A|{xoJj^7RvW(NNF{Aa4nx5@GS8lBf5H+46`)dUP9@mayy?SYAzVt4tS*mr zn)B={1WmuGPnVn`roVN7wQhNe|Y9K#hkZ& ze$U9Iul9b^K(}(o6Hjmh=Gb(>eVxpL3qx?3+v>r!qFI zwWBWmu?L;B_x8Z2f1PH22X(ri_&E_`d==hbt5~qxx;%2^&I z9r^jYe0f7eNyHAZkYX!gsC}%*?5iFvY$9uJW-2s8R5-@QTp_UgUq)45NIJe=fYYxT zjPhlf|5fiUH~eA9{uF;l4ld@bYlse>(`#uaNx$*L%lQzj zj|wd@bKZ>`zUNidZhtlgxWnROjxOqOljbLTl@ad$D=7pvN{V$ZN-IgWz2^J%_Ex6?__yvu;#Ig7I@Jg1J3&35>K)0AWu+(0%u zht@T(3ATv6VkeM&jS3F*lj^KJIqYzs(*cu3fl(t{zQw|R|0+X;GW)oR>VHAe#v=C{ z20}+(8C?DUE6f2S_YBZg!UvUTD6x7MOIWXt66Sf6L7Az=%{=wVE-g>Ld3$gScimBj z8u+c5G~E}w@w7#4bmq&$j#usdG@vXx7GtSkcJ}tEJ4d{ckrGOpFm3rabMq`;SGU`J zUsTWu1J>NMtiLfR_+i5qhrjXIc>R<-Rq7Fs8cc5AdWkY~x1zzxhNdmY#UgY5&E>eY z@$||}?c9Bx8Ei#9)^zCLd86RnP}$+a!NRVQKTqpaqH6|%^ia_mO1us7z@e_vo-INu z+L>zeHQB*@P17TuzvbDt?)=5fTeNI7kw5<=-KMpu(o)w<(X{wFvMrX^+y!AGdFdcC z+GmaK#ys6AyD_m?HGb$oofw3lz0zGH7mb+rNQrF|#;pwvMya&zs%IRA8o(%!2&8-Vpt` zW`_)lcZWudIty=l&X29u!S4C5<{TRJn*jt8u*Wof6sSf#-#mWYdfck5T`pVV}0bHsHvWX*q*Rh zKL>I)Z<)M-fu%9=Z#>HAgyeflPba%|@e9bi^?d@0_$q~)t)po&K27TM2KnGBH&XSq z-U^)qVT03(7usEx0)tY;LJeh@)oR0oZ(D{wQyfZ}1IjJg;def8!m~1tV?~}X2TpY# zDy%eEp3`;Ov+)K?sE~u>-L&icvToTA5c@X9?;p$$2myxzy1P2}($sg0Y9X}_`X-`1 zBGAriM11#H{2zDM=0p3kT>)ZE&Bd2cL-2yNiN8jGNGXv8>UrjpPl(dD)?qr&_H|R1 zIbQ)=X|3J>1XbZ|?PEmvefdSxE%k{%Oyu3*cm9!SAv&x+Qzp9)CNHB^Ad02`4o%BLO#7>H>=T?g=mWnh(1DZA5UoG$mzEpQic|C^6e&N_to><++LlZNO zaFH_413umh{OuZyBGZ^~yoZ;b&fTzB{~hxdvfS?p$8K}$SYyvdwb7O>bCh!??(qIBi*spds%^;TzGQliOM5e8kY|-(xm_3mhv3y1V(b9 z{cnm`_&>wUONkH0RIFK2usph9HZQV1Qo*6Uz;*mB<>GQK>OjWvVkOPc@IxXkBI{!t zk=6>II-k0eUUdKON>YU(b_@vGtj;HMhJ$qE-PEWC0`KheGpgEtCs^zM@m1Aq|7J^? zAcvjXc_lNO;Jbe?5ZnIQypfm8FXl=n>EB=@y04VbNYIEeA$Xd=hSrkQth`TaB&J!8 zXC1U;UItIP!X@28Z&WFx$H)w+!NQZ$2N{76kBSWCg}jG<2szxd!@s1<%tb&t&0JLJ zdu~|UCzea@6mDx}mT!-8`(y!Mdw9mX8*bSPfi~e{!X?%}v;t!@peXg!gWIK|-&Gqo zL>&BbCsdQZj%db?tz)DdN4m1r)~yBLhu7FMw^&#m4-`)ZPJ-(!6oqD~D(u|afae<0 za8UP4JetLyU%jb+v7Q_cKYVcre1|H(QtHwT3N1zC+g(poAdifZQN8ZhCKU?ZtA71+ ze9wF!lZi&UZhg@Qc4mp@1#!zR<|rx5$QHcjVQ8fR95%a7q?+$KAo+BYexJd~|*d8~4} z%M@`nmSpcFV5sYaNV4~7?-()Iom%>yUR&4w3KYBE)Bol&W#QG@LiAO|H1*Pjth=zN z=H=KzF3e3wFOP>Cs{dIaf&RbLLvWDIzMe2oAc5et5Xcq=q}m4X#ZKy-7(4xQ%88O7 z3ri+Cy=$ze&q>VUz8BX`EK-9pdBR6kuLBaTSch;OTy*8*++JXAL4wXAxoKXBol42A z7;lXgB5KH74eOJuh}J&qsgW8Jf-6l?)wng zsI-&z^i%sv8Dq{GpxkrmCtOkCWeiO3V{4YIgWnh70!fyo;g_nPOKrGZqIEooyTxR1 z)i3WcI&-~|?hsX!;TIHjM%C0NvzUyq1;;1Uiy$v&CkJKZJI9%ZoAl=Y=H2~JnJZbH z8UI|P3|k?ES>sx}-)HrAw{y0*j*?bwn)TM7hH2wpn1DYzgY}Dek60*-|4g}mbc*!r zj|nt6cUAbJJ_Yi&V)NUSg_Ug-<$^VnvbEmz~ z@c{DhYEfnXj@Z6o+{FS0+b)|1n+7-NgJHj9!N+=3!>9ZU&x?Xi?1YyOYUKcT2!G&a(_6p+9q2k$HZn-VL4wOu;_MX(TtqnECc--R>~~JWosa#_%<5;{vqn9G9&pR z9ux6UBlp#=-*mE1*kj-1jM{GMcXtrYLf(BKvsCT$llyZyAOHA zC+v(vMvA=%x4t?ORFi)A5pi^~zGO9MbbsDOU=d(+;&1LM0qPkUVnmlO}l7;%n&2-SqBRQ z+8zfxy&CjlwyJR>YJW?Eg)Qk14Z<1!pOv3ztLBk99gXkTYpnte*HDlUkz*=jp}o?L zcQfBrq=tFzwVJj+HxBlG%q627)6t;rt1g{6rrM@9c^H2pTa|^Lfh;Ds=_LJE7X-MA z;CNQSiuSKXtSyv+LeY}K5wCiRmHPf1wvx(Y1jECo9Mbr0J5U_-jyHV1zqNFtq%gKJ ze*{8+$H=shY&8?iPSg=^P=?DeA8;3QYv<=)TkrnvAbd6&|1pVna%N+|Zo|!^2A>CY@ci}h-L?wq6BErSn{UYic#8=ztt$l^if5`+7k z3!7EG>xC%Oy^gN2M#KD`J_e$qy7hYx%IG}qC2%m6A0Z*eL0)L>2OBdbIwZwyI4_XC zf~TK3>7s@s*>0CTRdx**uaC(by_=?puyXr$kC(CM29H|=Kn?a`(JLC1A|gna5|umlC6)@bW`7eXNF`>x`1~>QvAtuSHUG!YTG$J}lmt6fy~o1Pm1q#hGt$M&VDl zw|mDp{V_u!@Gtj;W}H8JO)XM|ZujpupXzkRq$`MIlvkv|W-m+4Hf)V0ch0*TKN9X$ z1m_HdXO@iutFQBjYRp7i^kvy(_Hq%0Z;+X5E86pnbaXzwRyzg8Q3dF^rLL7aqPjow zgOS&VFS9tp%(4um-_)=%&rYZkGUq+fRDtR45F0I>FqxRhoV_{>EznyKbrO2-8C-GL z*3o0H{3Q@hrPGij2;fHGzVo`kIwBH5_M~3)(F*2OOZ8Jiqgn+GRCY2ZIKjNGB19{} z)2r7(k?=02>N}^xh_17>j|_W8|HCjWXLJ7#X7a=@b;)!|@yT1AP8kXmUdT~9EBba#S599A<4`{ZY+2F{|Z4@CY=nh?kW!~KRi@R7HBQg zO>Xslj9Q3kA4CU2%_Dk91mt^}Cb)*8B7H_j^O)>K~&J?g!ZshxQ#COEWhST?cT`E5X z0uwTqzR6GvV5VpH84)d$#KQF;#*pfup2T5Sv_v0Yz?^+u&63{6M%K~J#^E(TM@^>L zk2<1(W37=o7Vim$!BdV>{2)J9-WYm8HTs>Z>bA!_q9vu{oW}2{0@b8fG?QEY!6TVC zghn z;iui-y+S-Hh&n=6v%gKhP+5!RH#E!a31)2b z-KnLU1CLn!hOkA^5C(9*k|X9ieVFdSAIELp83RM7VBQ`vgXqm){G^m?%UMLplj?0p}aLZ_O`hWVgqqT*+ZLb@2}RGl*o zq@mth+uf!4^r!jdX3#P>x;Ix$=wfjDb6WD!VaPtD%*|Opoqh-W{u%HED3`}va|xyE zHnjcNTXHn)Fwthpc$&RpFD=FhqP8IBja&I>FPAlQcH;~$?9+V5FIYJU)M6Y6Yo>E+!NqH%0N87)b=}gn37ba8|_+aB%2N`rHa;S{f=bvQlk za&ki(wO)HpYE;|sLz&yBlvZ28@}F+^G!|BjMlN&b_G)t2Y(ca- z*{2vMUk2$F&VFw`yn0bT9_t5|Ikl|pOS}zEE07xI<2ZM+TW^aq8K^uwxM@;lQ4}ca z5)^ik7tJf)x4vs?TKYSw@g}C(-|Bfydvp8Fa55n+bB?&!s9g9fqpaVP3o=Ya@BOkz zul+J$XMwuTa_TKF;lOw(NHl+3VCKH}-&{NNwH@6X(_L>g-@3V1Y)#l6@$Phedhf2Y z@aBy;V?mUSd6d0?0Kgzw;$y7@zgSZLW=o7o#u;LNwa<5HKtn08WPfPhap{lt&h(w% z=Gwo*g6hWU*V?t$emtwE+1emFQ4GCiR-#qnX|{l88vnY(Pf#qxB4(QsWY8>zM0 zEOw@e6fZU=Fz4)fD8Jv$jUivB0j`_Twr_hj+9EfSmHM8!+;&kU{>c#5ZP~uaSrH9) zKZypuWH&e5kN7yQiQgFcTS)pu30PzeSW9f>@uzPYygp7I@tup!01l550Z-d&_2+$AY%wJ5%WWr& zRY3V%_v^|*Z=pZl`q|v1obc8>(gW&dDGvW|gD;|I@h5nmEbLRkEWh3a=NC(S(P}Gl z`LX1@o~0B2_j285^U9twnkaz%@?Y*tn?`IN`x-L*Aj4Vd&eZu6SRVg}%OtV;QY_T7 zDebrQEJP@+m&Upa?NBis3)y;Z>ND?KcdwQ^k5J&px}9^`)kA6KC#H7=_Pj+YzdC~7 zbC}E$o%Ke&#tpbU|2#esg;JhlGW%}^d-{3Zg^C{eDnP3{Fj`LerSFVOObdla6AkvF z8~fhq{L_HyBmsih{QP;>8ecfw)Xpb)C~)@ohJ8F} zxmOH-^Sko~N=mEAC#h9zyw|s4{#yENqmffA|I09$e;YFiuiQVkwD}-Yi7wllM_E>x zqf9=DR;vsR+TMV{7jW^>gZP>yObl7htj~7T0RSETF8m)`wc^3)-2|Y7P%q5bDf5u* z2n~$Bele$JN+!)~>KES85Jhf2C#_3hSv%_g`Z8t3s5Rev1Ob~v@}q8AZ6)K+e3ZH8 z@_nzpgXIN=2fB2)L0ER$WF51|;x!H?pSuR$%dvdTX1J0k$&$kMRcmTNs1P}C1WZ&L zmXgv|y?ybB8QJ$o%$O9YApTgsa*V)13RzTUwHYgB`3sL78F(v-AiMWmd9@cLGPY#p zy9cmZ8Bb1+8c5D}Pf1XecCuZcWKbbC zt(xrp)?Z~{{o8}INkLO*2;=E!Gif)P^{zl zU-I0c$+TFBxur6b>6WaKlm&B1WekI$4C$)+p8gI`5I>L+p9*VWN99{B|E%bvU4QCh z!V4oZuw+Nm{h+7yP?3s==!TdGE1nMD@f?ne2FkD-I(gB@s2bGCZap7)C8_bv$fabl zXrIWESi6&Rm9uq9Bv4EKbZG67ynT3+%|!*`0)>s)V)tOl0k3@;Iv zos|c^myqc)Q15Os&h!kYO&bQ;UP^+mZ-hN61&QoxY#|N5l;AbeUs75G#*RxkkG^b; z*To{0PV;FWs@t6Yym~6azP{qKxfYNUWyq`b@jc6&UyoC5WL-#o^2~JwAH|Bp%(X-p zL!OT$EQgT}F)?&-Q=_Q^UTy36yUc;2;Qh%U|1IbVj;}60 zVMLgYIc%w!z9P`zUI(8b$D^}?66*-9>&T}cs|)A5n zs+fOJn%((l&qmAp#LW8+)8qMMbmSHN#O-x?rnXLM8qavpcU5;Wjji_cFVv|@V0;1j zG1m?V53;bV{_*?xIwQl0?%wnRPluvgn(awe51BuW@K<1T5du-?sd!3Ybe2Dj(>n*Q z`9+iJV2=8}ZyX6`V2}z;$6K-E(Ru^ zvBdgy=r1&&q!x~^g)jP_)K55p)xmqF^`D>#jfn1{5Sq*&ox;4%gD588Yne6;8%I zKs*z*I>HA_(hL0?d33~Va`En&l@`<)PWeQLMqW2)W6rrxVGUXxjyw>ju`|7^W%j6P zm}BN!SD3J9RwreaA89?&s{ac)sph0{X*7-*Cj10{#LoW_+>EKrDK=IO7@kcmdCj#t z@xly~u@wlE@Y9ZaYPSG7-&l>MKYbN+iCvT2IMp&7rQQ%7_(Q@`@OT#rDAs)#5lZzp zN>a5HWvyevKcwFsO?S-PU*PeapsN{kt6J@oC_S$gR*ZU{aLmWnLiMziq^= zBl=iOfs`rhOcRB_DTvQ=wSH~vN^CnABl6HfJ(@YUkc`j3FQ=-`c)XEE)a+EA`|k}f zl;=_(E~Mm&Jr8ql*=TETv2fy|9|!z2JOA)L>ZRLt;MBsYZs<3Mv)8p&zoOkhnUI#~ zp%A3=1Dig#MroU0oK-X0s_(MMTyNQ~Keu|`b3PIycvU@G>fL!Tz3P9vWl?*9(Xn5w zUNO;QRFO%)Ai&ggSS#lqT{FjOHw-4R$Y=EDITfc8Ei6{+IE0vgCiLXX^E%&s)PDinQoTq5LS3S6UX_(3JD_Kn)%aMcMpL(ke zv=_tPFjsk{)&3;yNQv-F74(WZMDW%(C-P=Wdv^xNIsg~v+5?#_yS+{p_932LTg8Q; z2tp*n+EMaf1*yM+oB}u>^IWo$jhaO9`hTw)RX{OLUC5;s2K9U)C=UzuWVMg3af<@T zG|E%HrT7RO{4LY8=YPUbv&BwLk)0R!7`FizxCu$Wn4lm@8fdYpZnoyXb(so+u|B5VWHlvIExff-no({?sP$Z zsJr6}+U%GKk%Yt=(H)Mc*3N9}Mj*2^KQGuB^V++#_F#H&2@;Q9Z4aX}^P?Eg8U}L3`R45u zE%)6MBK7r%k&46On>Km{yc~IddcX!1_um^^qq>|$n67)+-TUw+yQRqdwq-ucqJVTJ z2Cyq`pc&#N&d<&g=OEI%D7zXQ=Bu`VEx!t zdK4fw-hK4t2kW#B$|>=v#Xzy_{TpbrKvUS8N8 z9LgksghEMj1X$M}HzC9f&lCczru{dmIw#lEJ13hKz+QT3*N?RndPn3pql01`BFP>i8s_hlEIoUrT0=~g7)`xd`Gp=Z1&65lv@KU;{!YFLTk zGg3E2F!J@HyNA%gI2?Ps5qhcx$4_d@ph zrXeASLa(&}Ro)Pu)se&D27H-eIBXodmIG zpR<1hp4sP-@^qLoguN6g{JeP`wHCwoe^6ZPgq?iLlWeZFCLE4w*9ESJ^JZF`YaXJ+ zvQ7uv&fMGs)XKVf+3MokRIXim-JQPwb??pbX2z(9wU;|jM>F6nZLMcUy9=w86Kg;> zYY;fo*6=6bKQ_uBr4_EUUl}q* zI%i*V_|yz#DraX?f)0(#;wWAJBanuLZM|D}laCLoh6BpxNzzq-mgNoujQVWbI?EDD z0bB+ciKcqUtANO*lCuW2_EB>Vv^$)CdEkr;r2a~I9sWYx zkdQF-MrCpCA{7FBk~ovm&8KC_XX064SR}KUwNbW2L$f6cbT5pBiQ`*=R3MfF{rypW zOq5HcPN@;%{ecUTf0^laqd-q^&M3`Z6x2BG)G(kWc8KsV-qlSt zZ5hBJ^+DQ&THwBYh4>b=AKXlL_Izd8G%pbO^kglh+^}eAuPg;B;iZ*nU&IGt*BO&! zFXIBMZV!R{N2KD7?VX~_+Y*;5G7#WqLU%rDd&$?HP_aZB!L~q!=saOy8L%HR9AzSR z(Tm-VRR9~FwOmRWp0_LkL-!RV?O+v1&!x-d$}^NU%^c?`!HK}d38X`u_}Ash_D=|8 z=GmHP)j+pi`14wisElP5E1@AWEF2m{BHcaJ!CO@5sAqGZ1DE=@E{FmZNynHM_`aCy z_OkwEm$`PmO`C%AkC^S{eK3J8^!|!S(tO~C-ljeV%Cjb`jo4$!!n~4EX^mu3eI0v0 z48$zx7Rd=}DkGa>P!P6Ixm_ckny8P?rnp_v9sV^Wls(|ElhY01S{oBMH)F{=nwrLV z67x}1-H5yJ9v%6^N>(c$si|^nu11oz!&Kg{{&4PyBXukLeDAd^ZwRf$c_F{r?F;`} zB4!-8yJ0&*Mh9d#UeoUvhwytI@`c&3T<>{dMxc?)RI01TSS)r*=8yT>$Dz}Ocszn< zL;liqjgYhMw18z@{Z0M%6&;iPnT$s1blLt6kQYe zQY$Csj5rc3Z#wc7{u+K>=0$X zEb(%S)1jf3dG2iLmb}RFTRs4>HLBZ-8%n;DAtN zZJe_kx;^hzW0S+ES#_nxu?{|oOjhkWdi}mHw=M-lDFBxX3c|vyM6WWO_E#98Lgt>H z87N2QN?W|@K5k?$6Ip>1@%`||?H)a#)}ciq4~3C~B>e;CkI)wuyc&yyLpDwLz*+B5 zQ-hK$Qge;p$cq^y2sXsyWH+bUL$xZMg5|N0PJey}cIy~sue4^CpK0T5X5Y>5IWbn1 zJ9S`(2~F<^jm_IFaMclRLPyVgj)SH6rAd^Gu~&W6Rpl(?!mLEdGap81)psuZ?H=xm zw)u!by6;K!v4xV`T3M1N73x#!66Lz=jq}Q`Rq{>#RkQsg%Z2wEXYvP8w_w?AzjOvf z3uGf#N2tu^-y@b^DA0c)(t(M?KSjecS|}ou8zRAfPl8)%t_p5^pWyM$@>{n#@l`1y zjXK=g#VZuA_aBUATRrzjsK7}Vu!9ziv}`CVN;iW1e^j0IL(^d!uT>OON<{@msYu5tiH%SY5h)ev z7LaaOzyJ|pC?zE#45Xw(q!~FHr8_o8$mlUfjXHbZ_naTj|FG|~J3jYyk$@ofi?by+ zO~2E1NfKpzglG^o8?4*OPU}Z6=I$)(@^n&9tv)3Pl+Etp*Yxaee!FX{G+21aV)&s2 z1hg0F|5d<$u+1mE&dFRu^z5T~3c-5W74NN=p#dO=uL3p6w zD8ik=2&-R*{o+BNNopY=1*p;KAXN0wa?Rr%r%qiPB%qJNE`03f}B8*fx zA)9=!LxeJK6Wi7Mha(PxxLk*|F$%6k>PZQGaIe^^n%2@}g$Nh4W}u@cP=`n=_rXWo ztRUug>?D_sHzSIuC4HoF&0AuwcRG&SGp=)Pya>3f9so>3F)H# zjd^g34W-UA038<&dW%R!idC8>^B;YZ{(O)ox89VSK(z~Ko7#|=bQomxl#lFinu|5R z(k-N!N8cj#yc!h0-R%ACj}(B(y8m}bxAU-Ea`Z&0$1?O=r()>%kMZaJd9AxK(sfdC zK5?urfq>UV8vsp_P0*$2<=NH_mva2bw}89;cX_@IW~tpsrnRC`M3($|#r(B6e!3*n zERLV{mdr~2*E?#yYnAho<^D52N*udc#Z=V@dJX{pq00WhHfo{$(w!x~A4Sg%vD$_` z38F(kX&$Hqi6axkZlD~mX%k`)BNxkr7h4uqyZk(VgsPbPvVWrp52lW#EHqn^Paik2 zwf}hA*4xGYLy)=X_dtfe^ z4RZKNfwxKNe_MH162nLh2Fc!UAiEXa_rlDVZ=y`E1QZ={U1n8FMZG4!sq4|JBd>Y( zNP^%uN)5J?DX(ZA%j-`V^+YME>P0D}@0zjI1QsiYBC@KzjVu%_#uXZV4r(D6UaJgV zfKJDw&ySh(c?MTq+)q9w*tdvd{?rZk9rw@aOV!o|rj5jTBbnz2EBhlTg%~q9Q=_Uq zX28!|MKP}IS~ALLX(n0h{M+IZAxaa;m8QDKaUO$Q^Qq_)A*(~#{9yKvyKbqBp+?2r zbhlid&!j71@ts3!;RKV5kson&oYt($lfzzVqes z;}Q=BGu+vXO&$a9#8#8Xr2jcG-1dA;E<8KqY~{X>TW#T-=J~rWW61Afb%}rw$g=Hg z1U~E9Y#4Pr#u-EoWi^9PocF@?8nv4x)%-BFM6BivlqQRY`z+IUF6&|_>a6gcpWEY4 zF*zkWoO7DEiWu{ZAfslnH*@-X$L6a)N!|{c1`%6DIddf>!7EMIbk+t{d^z@FU%A`J zR%jph4SF5D2pn4_jp3KqQ`GQ^vdIh%>oo`s!{^LXH0o>@&#?KGyy1S=xf?VlFB zBb6>B!_v(A@(vh1zH zJid_V%zsRMY65Y(!qLAv-=y__E|RSiBP<})?>otSXBV|91X~sNuO`Y29vE~v%RR5= zqLo7gxqKY?)~AuysaWYq?6|`3G(45!9~=7rSOC}S45I7q1XCgWPh9;TG`=>hJg!`X zWx5W{b;)C0c_RX>+31#DW&hmzIA|Au0NwX(|0|&F_>7Kc>PTsUL*R8>QjaR^`+}B$ z+l7naLs|ko&oPrpnqDB)qn3n=VS~R9TOMX~8+BJPxL7|HUsSqenA~dwGKCkXLeT+z!RW;V2nM zO!Hx#yH5|lZkeGg_2^f;)H|OxO0gDJ}Z1BcK{jsf|+eamL@8(dFiK!jmSvGRNl5Ip<86)FW2OmRKOC< zuv*!!hh&c;>v_C>kfsWAuA3ETh+=Yh+-(>(gd%8qUOUd3cjnPS2TBS`ke;S;Aq{S* ztIdTP?xnhpAgi8SHD4{@ZAPxcYNa9>G}r~p8Y7ce6m^f-@CUtb?`&A2P6DQ1>3e72 ziSgYn0B6zzNlR!oeFB5_@E3uy#+(G!wHS=Zo;v@TZxt@D8WO(fCqssDwSvuQH@)aM z7oV&Si6wfG=*36|&!+W#AxEr%ju9KL@4{~IaR02`Kb~uFapsiT`XIz5!dX%_24NT2 zU1}ZS+V)p8d~OC&pMeD8^-d=`!zOZ`G(f}=5y>&B`}o!1?z`Gi;tWCmQXIk^G6Jhdlun2k zOatz83!lw%N+5n+TZR~_fo$Q+IC?CC(gu*YH*SluNAZ3HmuNDy7Z`3VCs$~5*HEWb_sT|5 z#1B+8;l-6k#rCc~mpPB^(M_#f0dabV$_C5k$T*vt>7ts#4WNNiWUCM@2fQFyJV>#J z&7djvA?FVfQfj@B2f=Wq#Ljd`=H*Y;m956+lRyjHXx-*G&MRKFqiPMhl!dw%S}8{Q z%#gdg1?juQbXe=eA(*~0AI%GdcSEly94v77$G?j)I^teha%y`VM2<(AP1RY?HS)xa zJJV@TqZg?uk%EDS_GJ@p%A@dwDD7YU@9W#QlNDQty%8BJ z&^-UUl)NJyzlTSH$UaIA$)o9r;@Pw;zs5KvX_wvVKGZkHBqWlsna?*}^<hhiJq`ALF+Q}b_!6mH600XRJ)6iJS_t_fo(p6t zoIy;B`^IcixjN=sX}9Ena^*`>$r^U*TO;0oJcybzDr*CZ?ulL4Ll8AWan{D%Kbdm= z9{~3L!YEfKdxPW0sF$5Wj!Sa?tG%86+je6}gOa&E!-7BYVg2)3i_UF`Tu3(AJ&ZDH zN83M_ISO8--lQdC!stbDRNdCv^P6hXtyejnD)BnDDu2OVSn3qn@y0s|*o|Ue>v)gh zn3Yb(7MJCJ(E#f)K0nBa{8`TKqVFt-X_Xz4Blc8okcZNO1bU?@mX3Wr_aC8QrwL}k z`hEwo!B-#piGuzXFFmqKQla^ltw%cq8L{K2XM*>qDkeY=qY;YPD))`IYtH~l(7lH6 zA)N#*zg7*NOB|diqU`w>2U_EJ+GdH;ZdXvTph6_qsrT20ZF|8v+mrQx*X>C)ZL^_f zLiDXk(>;C#;>hp=Mf~2Dy*Zy|tezJW8pH{fBpPHrTz_MgsfC`8gCln>`4)S!dyt{MieZTpv zaY2u^QT5DU=K`A(WXDLxs+8Poy_Wd|`6;NWI_J;lo}C9nrc-Yqf8{VQIz~`&xW-|6 zpe?E_TXxUH2=s~RXsG$OLB>FOW57{vW`AC!k1O!2=pFRiec|Qtqc|lBs|=LAQa7qx z6PLjNG|klmSGOB|%8l*+(|4(4y_YRktSC#3Bb@(aC^M9Ek`R0RiY$WP46jV0`#ygq z`xI?Vb&k|RHk}tGG;N|9i(;fHI#$56 z4(@)bN&lPUV>CbIszzVwO!v;Z0_ARfcJba51V3V)7fkxIdm9&2&&!DRl;M{7YSi$m zM}Er9tM$*!7e82P1chbpa^5NWpNMmZOQvak%MaU_;A@qK7a_W3Ahqh3x;qOzD!!P~ z*j>L?Hy)P)$vBz!W1p}}`tbGLRehob&~zw)>;94sl-c0eyU}X|mz76!^dPfmGB(?d zdyC92EV^sFi__?R&8AWzQLT?$BYZ^}`j&?M>W(s3^e_liYpp)}al#3t45~K;Y}e<1 z^{$$C&~}1e%QlS4@g1v;GwNcu(=aDl&fm*c&nVP>EnDJ2Z>nF-O%p1PmFAh!jO}-# zT={NaejP_z{?1dhBte%1M15AI)YQh)9LY;P0$6LNUFd{}S0eKiN5I_NwW|zDw(Tzm z*yS%Z7|C9T45+8K)h;Eh7}yM7QTf)5^^hVnl`e4^doIN1)noG0fZ)ItFpfPvV5@FF z2BfqFTJgenTIG>9ADbqHYZgzGvS=L_^ zX#YDAiZ{>@)ZowZLBqcW6A0wt0-iftZ~XaeFR+!xsOK%kx_dht-OtAD)C=orI8U8?omTnt3}=qoXeeMVrVkM2{SbL+20?khc0R99?A{9(N+3oTnQX5 z^>NbAVTV36HyN(b&Mxl5z%%(dl&_pmuX`|*O$Z-PNkh7$Gvbrv>ZWzF-Nw^187&YL zdXQ(4dnq`5hIMN$D;v~?f5C2A`X(i4IlzM-HD^Y@|;AWnSV z@N6n=9a8oNyzdLcYw*; zVAYwNg3T{uSxu6kjGX#)>J4eqU-o6$M%;JypU=_MG3yX&Zh4A(Fi|Nt3`1&=mT1;3 z9LZp(({%9B^FF^iaXVRLs&ZL8hTMqLI=bED^{bFF6z|i;Iv40#_;KYDMZ{?Hb|ZRL zNEbRxRcO@Ccc|z=9}GlI4Bcs(*g*>`pR}kz=ZD_&!%6A9$1MZ9=_+*n-`XYfJc4#p zPwfS)pcRM5rO?JA=pbT&C4&vS69W}xmD;K232be+CikC5g-7EOhuUARUM0o=z@(F{ zhjkgob9KGLl-;gevVbOgM9MKD%yLl_t9t_*$Ia+md;l19vK-O9$MphWy6vm%36LkH z!zDm{2IZ^IF@0nc)1unsqJ-bQr=&h0W7%lSm=Y*fnL_aPyi(??6B_c4F)hY0NMp_T zrFwNDe*2=9Qpob~PP4_#8=Y~fqk#1iK$NjbNo#D`ok`SVeo#Ljb4Ol3tbt_n81_5r z2C(UH!CQloJ#=No`*9vx!CO_&y1Pf(zg3XNOLbtWpJvRs!}&Ef zXy=;4-lR-x`;^x$5XZFb$**IK*GrLQ=-Bva!`h`k(n>xpszr7BJ|8Lm092Eq z`+~QiPj0torlzP7QkFE}K67Pt!CslgV6WXnMzDdv)Oe7#uhYbP7AHHPcqr8PiFreJ zEOO2iHYpZ*R$BHTsd@ipAf(}hHC;jF2>Yqr7g+M{C3M>ypd3U082Pt17kSB>V=QO^w#D?s(SiU^;M4a7GBcLT3Y&;<(KUpJzIrnH~zVIlhxf1u$P?&VDh@*V{+bF@OU2hpBb)N zIMI4nbSb{`SfNq>sCuY;_{RZ%O-mJJnY&WiR?HTw+;j`6AEXz7H8*6Syo~w6+$fDN?wj)H4n#Q3~~KRexuooXvUr%^15U zVl~dQ8Y7{-(d%B-H4L|9M|2ZTyI+dN+=x zai#UM-qhvlIB~ndct>oHeuKhz-qNCp|Dk)A*dR;xxmJyURTkI!1c^@}x%qWlL$CDN z*wz9eO1aCpyEZM9e!%yk6p0h_X@3~3YYF?TouyKumJ3y=m}s&6tW+Wq1*VNyg8 zSbKmziy!@vN4z(;msN6gi;JFiY%720NNSA;!C$35E@kMQ7rLIb&p1=G!Oy)kd4o`q z8^iE`^tI2vLUPT^^j{gmd?twi1x*fCH62{`%LJ?K?uX=7drxg{ehxcM<>DLcv-ZS` z4!uA;lX)1%@GUKUM(yS`H|C2P)2otdY#@x5V~n|)2W=XAH@{^_A2RZlZJztULwg#m zUpQbJwmi@itI=HX5J}`n`B*)U`k;m2%~ugp!5izUt7j%-W**5K<^_-p>wjA2W88iS z!P85RgE>RjD~icIU@~7UJR)4Eq|f)tw~8Mej#kS*SM!`wCtfTDLP|^vF2ah#ki$prk^6OKYb75~Kl*%C`c^<;z8A zbW!=XVWEtI)J1M~Vqa?117@kWY~HsoD_ziV6V9TKNvNLt5Z*E3c7@-0&4ojbwPAcP z^sdwgH*Q6vS=9ouzYZ{O|BU6RZxxhv#3uX#ud8?zQAjUmmL0 zmm){W;!CPuO}Mn;r;X0MC*cboy)Sp4aX3R%_UJKND#u~?U7#gb&;dso!@wD#t=xbm zPXiZZf4I@%!JJWla%$7SK$Tdq5GxXbX9;(#uY~G}b-Kw{n@?ytV zwWNM&o;$yFho<(8uIk3*W(99O-Md_GDahK@qCNlirS+RHx(cfeRelt(8-q!X_DAa$ zejYFLh1aoaKz5DN`Jc6DdhYGlccWyc-_{N`bYJSuuNnRn#e{i^bLo4?flJarJ&z+G;iO6Xz=t-VP4Xc?Kefu zZii0F9aY~1+!V1Q!_6J%_H}rd(W>}~tP?)u%uE4@{>2Pgae>~6PpB_-f z20bjs-SnQZ`u3a73ck>|>RFn)b?hO0NmT$k_9WKaMV-=PLV+pWz9%zI|d^ZAt)MltUJK1DNudUjQ*`nFLxPbWIn<691= z5lv2Jt;6>z2`?M8Vkwi$5AI`{n+n++w=LFQ+TE`E;zu6YPD1NkE5vyY?raBc2Vf?e z_N!!v74?&8!DsD)m&=hnO-84TB`LNchat`p}-$W`fX9~zbIsEx5{ zZv~66T{GT{R!hU5TvImJ2H0P-tWuE&5f0Wjqn~1gGyGIPDC~3TWq$nZ;9lxcBXHqxr+Aj9BMV7WaeRgQM zlC$j{Rs?G{rUVDw*MQP^It;{6)F%kDCGx&R&$2!h2_bsYvQb@2|Bjen9*OER7yET< zT7GCIBOGqIPP&$M!uVm;nqjaD3zfkm@E0gI3oStO*&zte{ zu~ObXD6%9=7D$=*_puct!m1bE?^t3TucJbA z*k;=lu%iYV+JVFSh)q*?RZJq8>d42^Bp8*d!WcssVT2nY z)-(uLz$I$K9h#Ay>$$P~?bCgT`+dd{NB3AIpebX<)~J&YJ^=C662r{=UWh&fU|SQj=89Cv)R3um*Ulq?9Y<4z83G zi*+#n5L>sQ3N#j%O6x7Q8qIKGzj7CGyr2cp=;Y+Gji4$$ zJ4}UM=C_&>1pGZ9zIo?B`-fcc85_{r?qvUqb@*(Zv758H3vvYe93wZYsvK0-U(@Oy zuhw^)XRm&D&5GA`Y267VYie+J>1uLy-{DIoC|?M!U}orwTk0YCnjH^MdL<2o`d-9; z)pZJ`^y!Or{VJ`FYONNmK=xFop)1;V-yH%#|eH3@8p{Q|UQW?S? zMp?~E)vK(N_*Qel)jg!?|Gpuj|9e9$0h8L#hY!sZq-xju=XzB$l1phDjllc;&+`_? zy;@pT&QEsT^1U?v+QvqMoqfeQ4-II(JFS!sg_nUptT7Br`e|6fZZY%7i_0^Tck}}_ z{laaL@w!|LoH6{Xvq8j#gMbx1hDV@cAy-cbZKO&}6fsawV@K68N|6k88EvL5A^$3u!~89{C`68&GU905F|z$&`r#`_S# zI_ZZrjI|37CI%;#4dnwoU)x}%Zybd6@xkEaFV6+zxlFG=M$bF%{AC#ZDQ|dcm>$;!Qc7+6nCwTUy}R9- zj7YB6M^FB;yJdgD>cxb;+L@Cq0#jdIw69T@jDI8)ZUUT2UqfWAg2c0 z`ex0VclPIiB@0Y{_BNoY*6*B%G}`7W{mP9#k9I&FSe={^xBAK$Vl4xFCJTV~wz$Cx z8z-bP25`pdm`zPn;hPtOZkH%o9&K!wdBF{W)kR{(K$eNzj;h{L&W6A`FR66d?wqvr zOf#@|F8{7aGIRwwS8noBGry7H+-EK&q9Ax!t*T(Js5i#{>9deMaag;Mtv#c=$=xd> z&o(~K6hb|vhCSzihUVrJV+j;~q2mQQ0h%cSLjMW4m~fD3R4MQNqS+y^ZOp~*ayA9R z!{u3q8aG0@SriBL_QxjJzYn8nu2~$MgeRL%_mxLIv&fOZ?rC{KO|*-_nexe?{TtsA9{V3$fG)uVZ!?KI{=74Tf@xqF ze0wmDCvPz(YN}(^5`g})^D6l)`ALF%y8J7*rMKuzW!4YRHa!jyr;44KypUikh6F`|GNO@M%5Y$* zpxEl*|7gSN+sawtd>K0bYm~_UZIqs{J4KBU9bPLwQcNp(hMT(%9lMJeS@xr4A9Q~I z2tB+Tw0=81z#W~0%H)TR-qXQ2zt5-90_+eYLRp!(A|z;fwG~^uL-shh#br!#f7`yR z0ohunV>?2}6eOQc9bvj&X6w)UhrymWP$P9e^z*v2V+Ev9d?`}}A>0j8z7HK-%o=Q& zX;qSZ6$HQa-e(~U(&fp^+vbP#y_ZOMY{Maax4fIzNSsR=u`tN1tH86=q9qV5^*B%J zMq6u{_fp&33+@rJ5XW+X_EO44B)Z$g0p-@1UU$q5^Q_%IqjP!bFessW_Td2Hc+o`y za@6~6B1yPUB)NA!Jh+LZ#?mw>zejNO`0*NhVWbesv2eGd$&#i5Aoi7^OUrS`PGdrz zGBslByCH!4SK=uSU3&wsR1I6bZnP8aPRY?-2tC1ir59wFf=EwvaQKn|); zpk7yY_{+!>CWhJ5uz0{5XSGp%ns>U~7Dh!>`>a+*V$HOTly6jP=2|IzP;4S}mQN%; zju+d*P&&vt3)dA4O6qIj)ZI(QWW%;-kGk^~1|4pQdoYzP<`DmZGODkq3t@F@|1me^ zsDV?+?%%@PE%SjZU+mGOO11upH1o4Lx0kun(8zV(3%;2Tv`sf@-&-j=X3={U(4?!; z8KXNV`I)%`52p(#-i?m+XLH*O4d=@$%$Ve+$p)utEJ($CPFc!)hML{pBkM5+2kkdv zKDki)A^*(+d}CGiKRXLS1iD&dGacv# zhSWS!Q(*9(ICa&wllOR9u&}8rt?0(JqzmFqvjr&-)c9j%$g{V7B z(=8`a-qUW+-_l?{G;sg^j-rf42g1=DJzcbxfkzsA*>m`(n;Ret5PV>+>AQZ$g;GWD zM8Dqi+qjVC$baq=BCcwGv(7Y={W+U7Yd;tMq34rB80Dj!8i#@nP1b8V7v~}m{kQzB z4mE7AhIYd)9*|+T=U$y38$+Uv9yD|pVETPrR}6Q?056ZeH18)_X6oUZWL#ZF8!=h-M%2|4)P#^6p6zU9D?>{E2E)#vWbxC_L`vS(1ZvjDR?_Z5WtAA z=yp^W4}awUSdVCS-W8&(Bm&i{C^|`I`VgjNlFjU<%A~i{-E{+!kKILT$uVb?0zVBE zEIy)cPs6;K*DoD?zHqj5)Al|3uw8&%A#dy9);;5s%luC6S4Ga_t;=*xQF4Ay#qfS^rdY;zbD(u24U(>byL)`ihkr8j z+Uy&gVwVBwg(T=CHX(PYh59AyE~E=_7k|BC>F2)z?F?Y)?6K29uPZ5fd1`fC2_~#j zOyKQdE5ESOZcN4lA9sxdhBsO*$u}>1fa9z~lT~@xhe? z46j4@N=ya^lab2q^Eo}At?7;?Begkz@?o6KVM;86hVmgE-;G>rn=f<#kEzVIJiRHX zB9l|%1UF1I`n~J7DjRklW z4cSgh-McL;W%E$sHCWWP{0=MbSrq64wNtEH%yqoi__YF8#rudn{AAO9THC(>y+K`w z+kM`J-8296=m2Zb}I*WuWad> z_)&ZcjGGA&vfS85{Ww<}x>?i1G0@yxF!)Ya_cz61Jw66KY-Bc#;z~BJ%3&*WxIpvK z-+czXyQ*6vn2}@L`I+pfB6Sek7aRD{LI8U*_1{U0{C~Qn8WTH!GdAW*gPiXrfMaxl z^bZCx_SwI$*3mNG0h=<1A)hik3-jlMkJ+7v9rG67dwe!RSbtDK{R=9`i}|iSl;?_v zMu}$n)MeAE?4^(F5I!!IW%sz><@(ffC1nRI`D4}q+BItdc4YYHZ=@d0pbCX0$RY1; zcPqH-mbEgfF@{DCctTLHg)S7Zr33O@K&c$JKu%c~VEF zg~cgfM1ADHH#+j;b%}ezsI*_W7KsKnZ1a>TWsMv1e-daS6J68z%o-OBN-5uQOwx54z`47tm=Esel0t(fltOs27 zgK#iBfgW{(`{D0X-#~F(i*RaUE2#b~(|TfAAYC^;Z{X>Oegiu%) z@v_r(QnO@QzQNYwLE3sn?ue7XS0}?$2`6FZ@t_<2nQ60)kjxl75u%H>P~HRCPusgb zup%-iT9U}frW5&k7O6Z?Vts6XC@d0ju1qNg=iXP$8F;%yQkSf7;Sy8gnK`Jb|2ull zSw?}3tDjB(T?>veLM=({w-`+e`|6;&WdG@9jq&bjQcATV>z^e1Z@jYU(pxhjgjrb% ztvgw+2LYi`ASna?BCKEYSYYxZzkQS`+u2|udKmi@8Z&m24}58})@D@2yy4|wBtMwr zm?;I@@#m#9K&~=wT6>YtTm3k6?~07A*5MIBEt9?Zy>XNveW0E1I~2krkJ(rt<8&d< zzIc0S=;?Odj9BC;>GSM?h%FDHoW{I~b5R5iU@gQQ?_I-Ya_J3o^!=Fw0Y zolc!>3>phd7d3nZY-((i`j0EwDROA#R~o3p|JY(SqdQcNdi0nw&d7Pl0mMJ)z*#5V zm4ER6TxkS(^SwL`$KyNa3NOo)0*167Gf-Sv$6EI7N)ZK$=|h@8Zjh(@-0LFhHR2DqlOZ4$?#B{ISAEjkW# zh-Oe<#e+p*D5{wW_xO3#R);GQpg>0-Y6l?$lrnpO!4BxfRMrP|~PVC&;esxvO;>*ft0x%dXZvTPV zPcXE%KzrG3tfKj4MXf_GbpsNoVaIZ&rnaE8VzCtP<mA|pf z2=maM(jz?8*y6~fGY~S{ijwjD6^$4(tk*t$tMgIk+o(@D|4>P2Qg~)(NAX$%VihpE z6L;;feQ(>pI?`zhnHjQD|FVuE+Ib6TVDwsQ_J@IQE9$deBp3`73$t9<$y= zN!I#3R)r$m^v*9`L*wODl6`~ILN`z&C4lbvm?RTV>tYInYJvmWbLt`s92{fOF1|j@ zNHMd&tg$qEbxn_yvVsp>`mQWmPK@u74=+$I4T|-*XXP!M_cs$?42T@f zQJiheN6eljZZ#AZoBKB!*lZsPqY}=O;%%+4R`=`Y87!jcr?pPyo0kffYTo?r-GD$x zyJ@H>*2TJZfqtJuvhq%dItz6u)6K?1eh6Aq;Zxw>}I6?A_5OFu0QTHv$QFy*=$_6QG1!0t_YiJ51O{*-quVoK~>2 zI!l->@nVMZhbjEl9HEZr1M&81{;?;JDk1+$JhpIT? zxj2rzQtgQTJaU_&D>6$lfFk8Bh7di|(2DfL+qdRwp7hSXw7tTiWB1_ixBi>qB7JTY z{#M#fhZnjBcde8N`M$JXwA>&}EniGl=D<@UB(CTctz3r>=^Aso!uCeaFMp50T8reS zY5&u~Q07V;1`Lqyv`eZ!n~-QeTGup4>KVTC<&H%7rI~2@)%Y&HKTC9gTB<`%p47_w zeF%RlY)tfGA6);D`-(r!p@L7pQXzFV#O&R(upJr$xt;OJXQuci0;394 zzY#-Y`cLtNbad*%4IIeeNTMC~@A#_bvV*EP*7{LGK7%(vuV?T*J8DUFrC7X9?w(ol z4BMl>q8o}8{sooRUvg@hsGYd@0-2N30QdfV-Og(#d_$DaM3(NE7 z49)|)Z!V|cEm}6ploZ1)t}^yp0YRi?t%oIOHw>Z&3afAk*c5XaVjk^X#Zdn!6JDoW zbV8!;o26dsuA#^L>J`R*4@&1rA7&kE+SVjJsmZ<;m;zb0SG6bkj!jssMFO{kRs#ft zW4ObNl35xYji$H@K8*|skJ$PNt-SIY+uEDcN%{pUtCqA%L9a*;WZu*XJaIOFUnX>2 z6+<~f=Q8l_pXvRey{V6kq30|#%FVM%Zz|XrFUuXstv`Qm^>}|s$6nDb`;rtiCMJ9nhP0T=@u%xNk|)RFqt7$X^k8n4h6z)cf$!zoET4 z-^q2J&y$<@;KlSqS*3Lu+Ntnd1}l%`;OuGLWQm4tOw3#Q%Q35i1wzfl@Qg|!#~)S; zG`IuBr28Ltyb2Q>SK4ex^vT&yNm`bgbo@sxkw~Y2?Lc28r=OV{S`^zlamV`&WP@uK z`F|q*Jf8osHY?WgQcafpck<&wSfARMI4XEI8ef%cRoF!IZ>HX?ok$MnY^q7~q?8EP z5TlX@w+=?HygO62e~`}kaiM!g+Tv3xCQHcu&Y9C}VGxUz=T?^)Q4b?z>68@m>*p_p z;6l5=?`2f!OPrl}@M=8d^MHqUSYH4-G^0{m zUr_67Zb%vzCjiSkHnjhv1n|ls>CrSIjn>K*C{Dx6bs>ZH>_3+$L~V9w-~Me_7Z~)B zMH_JBE76*I=oGYS%wUDRo9kSFjuLshLiU|v}Y6_FK~EfYdr{X zHl)GB#VrPkJ-(%yd(DGZU@`AU;4L3>MqMoEZ-cY7tM{CU+n7^7Si5p3+>W1Q>!2`< z`#6@-Ejr+MCr^>nvQV3Sh4%V->$}jF@&!@5WNe+?LZz4+BGH<`!8(u zw`76p@pB50JD*}*ODtv0ca0NjdqbfqReEk5qI@cQs&hV)>#G1kxtKe<);pe5mcwOL zpoK|$0MY>#HV=QxTQ}Z#2Zq@#yb&80ut<}$A?#ThEB=Lrr`8YlQ|1vn@y9PhXXt@> zU&+GwY8i~Q{z-4nVku%KiJ~o|$Eu^Ptq2>?I{W1OB8}BcEbo`)B5!@lOQrEn`&;f( zzEz|K)4f(DGrRt8!%&^uJo61`XQ@GX;i8H$GS%cgV|BFACNN9s6J-e#~0r3jwfB&yT&IzMsT* z0}%RO3pv7Sj>BGaOTC@#DOCXjPS$w^xvZp0%Nb9jn3nO5xZ9;?BQW|J^Z^MMYQX<# z!f@vkCb;(zg5RF#zg=^HuB59QBtgd9pgNMCwbCydpj72d;C1XF-@#C~M!mtIzB}n} z01n`%)onHZqle*3>;z!~ycY$flTl6%=&HDKh`}Tw_V&y!o3A zCOR%-;)@ZB)f^T3d?zEPpYED!%R0|Izp&T;vscuSJCA-B^a6AH*;Jbl0~QWQpgl1$ z!859E%u5MYn=Ww!ygPhoSq+JlTbOuzqVDcr4__~m`LZfK+ODn2QoGm9pdM~cs*?=L zEP7OD7{lK35!o`V6w0274&$d^$O%bpDvFE&rWMi`aJdkq-q7{_aMZY>wl*ZS#CF>% zf9^WOYO3V%89zI%>|v5SCmV|JYQ?!HN@};i^v7H4x)0nbxlEbNx`;cU8f~)#5bHOP zJ0@3o6k3^Ct^OSNaBO@ws=yod1xS^PD>A%B^p!1L2bzq=+Os2BC5k+SL(QkZW%D`o zc6a1|X|{+o7)utYH(J2^WCBN(Ls%i9^W|EiF>~JK}y3rTadbMr%-#h<@r}K_y zyN&+--Db)D;6pL0IveU$e_GYX^$mChx;NP$grwr`-YZJ9@-U!DM>@wTJH zpVnKt+>Y{wcy{w|g|~8DLg{L6;^baE>kM-2B8?h3gN#NYn5S2`EV$|w^=Y%>_Fq)+ zz27Zjnu3I6oD%vRTZJ@1zvFzq>2YZC#KKzSixaRfu*DJ73&$?*jC{^f4CkE%+m8F6 zj^^_PoPIl* zjrJGAHy;K2H9zlc%VDE`9rRsr5aif>lgBEk_x04rN;KnVTbDY!TR_t05-9TE&rj)Y zpL$Tj?K7F75pUF{QNtek-6|&Yk`i?5v9TJ!JHjAr=#eH*pQGl(Ytt7*HUFMDhEtsw z2Yswa7{)NL@Wo}ReEQly%GQjYHcdstzGUqU4STYCah$>Iz|)oPUBKLPa?00b5pIqP z`nKbRB6RJU7kGEoSum^WduIF7SDGopx4vs;j}S{$BDcG+yYVp?kva!S6x=&#zK3^*q4%F1u_Fl`Dj1@ulA5GBadiB@A@o4|D0CFN z*Z)EuF3Jc0K^~H9k;4OBxve2#FL73oj)5yN*g3n<{$T1=q*DWZ5?f2n)jS&sq|5Qe?)_N z4y~`!_~Ro9uE{$00(l-j*#(90wS%kky-)EQ4;wue`uNN?|Ka3NS)-YprxBWY#}m6- z!PWf|Ao#r@*X3u>9Uyq!Rp3&P79DGP%lrm|0BoKSQ+7|?H^!b?lC^^1N$?pagX3c9CDv1#+EjQXkyAR%5yREk;{S@@7Ku(IYUK%+zsxO2lDLQLZc6jCfNp z8Y>#jZX=Y>_&qw7JUDsX+oo5aTY2SPpcx@kh(vTd=Aw*s{|4n7HA^za89u^hH(qjY zM{7A$Gw1{^ZzS(BT5JD&J?=PFI<;nv7l zs|CjN!SZ6G8MkO#H1A9g3w0bO0o7)#lda0jw7tVfHx~IjE|XTo^+r`lb(PjS$AGB6eyv|E#9sEfgKk+`sh1|QevKc&Iv zMa-dmq&vT#;_q@H_LQN|fx|aMrSh^S&wwMX&mAESrldzz^G*HcmZ?=OkM-&V)8H@G zU1x-os`r&xQTe<>#m>fhaQ)t=rvAyLg8-~R93X%DBbkm5o6FI3-2@3QSa z*SDei8(SK*uH-VBbsO*U^@1eM^C1rC>4+Z*?zwbqK` zys=;3HzvA19boB@7_k|W&UL8r7sqYT7eo4bUnG&p|MJ2y1M8rkSeHFzQXe`!*{JIbG zwrh8*oJbY6)z1e#^CtUxrH^!t=R;y7OPj5~%c>RBbUq21oz>o8WNyyV9$X$5*p)RN zQVly{@vU{UX)76J`DkmdT=OOE&GCHF5WOJ4lEBYkJ|Dv8qoeLI)WXL7_hf$GamTq* z5kFZzcenVwoh@t&W)A=Ne7&7CC-%EwPN;DoamYNyd;EdJL3C9A&#})TJvNG#OJg*g zhr6nW`Fxvgvp>axy$U;{$n}JyqBK`xDkf~;qwi^v)491vuVNS|UevHQ+pV+d9}AlV z@>WZtvrPep(k`iPX|pIfKl!GWx<%(2!^{hv2W|5QA7 z-j5dKQz#NK=`cv z^O1euSmSGQ8<*#fUdn3Sm9x4?13nLVc1egHai33&Y2voA#C@a23z|T$#hF)(Exrsi z`U&lDv9kJb-|bl-4b9WtKSma^Z@j<-q68$}E(9A8mT{byvFV>*{C~M||6g@vO{c%{ zeLbwpA62c9g8Mgh+(Y60ZadMFbDa$c&aA$ff!;k+ezJUPW}1UW6hiAx3S$Q9Dii!y zeQ!Y(XwxSuSi<;9s)`jBB}s1s{SUXK??1tKus`}0Yd=v<(<~a+5Z7|A-VgQ*2bn0h z-`z=<+yS#232yta)7@T=0uVk6V4)7Gt(cHKCcFWHkiZmM`ZcrT*IPO}ac*@T<_Aw) z4J8U9l?L7nUp6Pwojwj3xU5YzYZ#W$O(6)RDPX?Fb=0f6v?+9i}Zv-NQi&j|bSkO+X{s%D>B3xFJB zLuc3D*nC~hV~U(Gv9@DZ|&;_=BdUEYY>YRI;> z3@G$dkuzCTbFNDs-5)5ikQ?QuAZ?*SKKSq{G$F~{$s?K;T_2zOT*?H@|o5nQ~j*f*7 zr&|4vGIxGY)UP#IowUXB7|?h8LyyXasFJe058yNJm8w+9yXhB!_TLvCV6}MbGRdQtOlx)NLw6 z<5dLHdcOt7xD7@$I2VxH*`V9gDZDXif_irA1Bvl6i7tV_Ai$(oHtCO0hs~J(ZSHSp z*?$M(agIB|aeTkJY>T<+VhH*8)~4NNi@HIVW+s zHP49j@62qUIU#c@fc&!ao^$7Qj!CP$hH#{O^eG|)#$7*LF&I)2XwBJC`(*DYT4s2> zjp%_^jY{PyYA@F0eWE0m;>?lB(B>Bz4RU=t#@_nwel_oK9h;}{p}ts0X&13>AVt;7 z1-ETdT>3Vlmisfgdxw)=o*_gthQla&>8;n237S4S1kP1k`#0BCeDtp4s_(F*7&G{- z20?e&pQ*6)!IIs2$|^D%(qQOX=0Aph)l*VraoDbcUzV>k_T^UE{4j*%ibH{|jX0&N zrerytrtPl^D1Q3cu=M2Y9-T7a1uW+#Z_2G9kcJ>tZm~_}XgRJ`_M-bQQ$a}?UW!qf zJ)_~JG~IG{VBdXSH-`4)TB{N-m>Yn732Sm|`5)R9E~-j_u>#i@MH}UP%O5wKk+^+MRK$YQ5X@UN-O9}N?YoZWIy^eJV;u9g=7QF z=MsbQ=GTq6g}D??xp)UBk|=e-2(0}1nXn_#$z$2fLvPIKxAU9nqxIn@jmN|3VZm&( z>MWD;K6{xjxRMCl6KEgm9*B_iW`n@s0H)#dS}r;!k~Fu*BU(+0I|P?**g`Q0jj@pB zBni0R6N|>Bp8~tc-KM5Wdoy;iT0E&xRWNI2UoAHGFa6btZV@CgW!QJeAQD7RN<8$2H zhagBsa4ffBy}z+gOOT{^jb!)JD+TeS*bfRvuhwKIe)DDe4`c+1f;TX|{8#53np=Y~ zpXL9R5vPREi+IMOYL3uNBaxnpK`ZZ*MY0ZC6-8(yl2&VhyzeYl+9P}5nSh>?U|T1jsqfLmcFy}9xH zeIduJ>fjkMhV#t(q>kQr*?s(ftZ3}ZJrL{=)E9FV+sPA9s8TE9^F5+j{=$GmRXQji zn54~3x6P0Y*Gc(b-?EDQ|1hLW3MDw=&FGqJ?XpZqldCf))gFg>?bUqD|i|cvg zEvBwx+@_b2uZyI0Gy}aGecH?-s01K*a&9k6BJVq@MT)0SaLI@dfd$>UKV9Qg;7Isc z%{0Vxg}nKk%B16Pt=@w_W8iK|F6Jt&>vURT-d_ny0zy4Y^(J3m0jgn=rcdV4`!&}R zXOFf|HY*Ro4?>pd^wu!zzxGV2BRUI6OemYr+&3C5$llbk%qfidaL5JMwCTaPt}U}u z#`7d}P_p8M zAd;|X9dG(Dyh&o{L#UF^>1K&J3;$t;*(3S!TGi_9&**n?PvQT>ahOeVy6O_LuEGZO z{CQLQX96r-0ktSb@^@gg6wfllK)`7IKMUzqMX@Yg1wFRrCnciT`P4;|JJoxqY@4?h zRCtPE8)BQ@)9y@_A|7(&TH^2dq7z>Bs(kFDOAP27O~pBptp5LS5T__7P+uN8Y-=Uv zl(ZJMv;x|s?Cw8F&DWMChS4IpLdj)~6eA5ze`vO7Z6nHO&kRomyblXCs9e7flz;#E zVWju*9soX}s!;n}?&xU(3Nwtjq`%|nU7>g^+J9w;>5}W)d?zhG%R#V5yudMeHa%R7%Dp_GcE0c( z(2`X#>pff({bA4k$sD_q^`B_1Gjh1GynV-d5?%<7@$xu@bea!)44AYTg$alWZ-spnU$4Au*MT_g$3YbC7 zaRb3n<-jNJYbZRXUwC2DJP0MELLBlM+S5X&Z3gaMev;DsL}k_;LlLGhtzF(W!OfK#hEJ+LMa7%Y78+E?)?PGoU0??)3UfN-uVK0pJd`z+wjLJ99SoxF{ZPtm`xSZz(S!F=BYq<9bL6(`-|)bHiesKn(b3vyDg|h`W|GC*&K=#7NZ+)mHdISXjBO zOdSd-VVOwOKPuKqSbRU;N@Fk!;#5Z5efDOSdTdryPUJKOk`8~e}LR;E*-Cr`ad8Ww1mF=1;m7WV(JS_Ehw3E4yYy;vnZC@L18zdl?M z_%G|6T1`{NlSr(@;5ixFpu~24?U5?b*?)I&3`L!6A12n$>@DVvyy&3{9~?}?cnM;w z&zvpKsf*>=E34Q@(>Y3eAuV|!&t|xQ-l*BG`S%fj&HzRi|r#~AB(&!o-PA6~dIWCR((wFNx z{8=NvgDfNCQstmsrgxoqJOP0-w|U1`Tj|B3-8t@PfDJG!uWHuV7;6S|Oc!|EPrN|k z)7X!qV8OU3!SS3bjV{B{bOQZj&pLS(^~=-wTZGQKnh++MVRmHCyz=Ml zC+m&m$jS7La82a{TTgjXhtb)lao4rMn>)RJ|1gP%is5sw5)H*BGy$5Z&418op?${F zf1Tqk4Ghxc$lo3*Dc_CRRbpN-0_gFYErpH_@-OQh!8;Z>7#hX4Rz;K{dbNv$*V!=~ z)O!}cPnO&Rw-)uzreLXkdfxwJj2w&_fd;9Y7pps|RhRO)718Ci{hXA7yx={xK9)pu zm?_<#OgGJiWYqA6?|_J|^+i+irKfHlfmLPtv`l2gg`RiFm(_#dOKKhNSJm|R7QX5T z=5{#>o#O9{xI!b>z`}%H2Pi|JSy6gN>p4{a)hS{^cvyi;s5C+RC9bya*RYWCkYT#? zx$^V78GZtIs!G?hGgVU14U4m84{$}3P3O?PLqCdall0)hx4)4Q$e5$g+Cw$gRK!nL zi8P8jD|MihGnc_a`cKL*ChE4 z<6qq$=JlqJ*^n$qRzm)Qa*o71{|!TgGI zb>j;BGyU8X%H3i5Oqgox&f^5zm4fn^1zgSNgZBDlHIdvUt(nyI zqWysF{ej%YSDci(BJ=IIYh$Bo2k*D_ild(NTc5V`^*-?3DA#^TK@N40ZstC!7WehB z{OAl9XI6*qL_`fep2^>u)WtY-21et!fnwlv{yOt1fk-p5ee9}X&+PJ%-y~h6Vi72z zTk`zH&s z44u(mz*R>cijfGa_r@?n5ff%Xkp_$@7j6W>V#_R-C_AsLkGD_1QnK~HwW$R0PrVtV zew^l~6=E*b(vrYWb-GCM>7zBF_q)p#lNmO#tJPD=_Mc@pR&tULJZao2 zCwFAgyR8ftBZoOxd|CA*ekCHo0>l&*k0)`D;ayfZN9E3dACWFI=8W`@`Dl)}#TTyb zHb)7jm#|1rDb7sQ%XIzBR7^q;tNcB2wL8Eev0V-<7lzggi1jQ4`9YZ#41ntu7`ObG z1hyl234%z-kcHI=x+G!n%F;+g%Drrih*13(jUx>jERu^VB;t{v4{QLuWAcP6x((*c z^^7eWAIT?69SYcL_B1i=0=Tup!5(A?4%_U(<#CN=;DJ-rQQjjgI_q94Afa=<3`8t zu!BeTCvCUh*j8t`k?e!Rbn!PdOER6|GsVu1m4&8=^;WF(&RdX{;yYtnLRUtWv52e> zA-tFr55#De>D?Y5jVx69DwZ+&kQ3^NDvP+V_o}x%o}zYR*C~sOcrNF2Phh}**EVPl z0@|KmnU;PLUfH-P6m;L>E^qE$XSt%l_#3NvLXYu6s^*7)KgxuoM>s$N2bJgW8(li7 zv4c5%z`OZ^hQ&B_v3Ks~$Dhj~vdLn~uj)^w@cY>z@(c0h5q9`t_XD_!DK~cUudwdl zD|>ISGF~C2w!e!SU4!NKZ7JQ}5Y!ouroC;oA0E=j4C>7)F`}2wW7c!^vyP=znc4_7 zg(JgOM|6DT0Mc*^Jp~97TjS+gMTFf#aA#>p8e4T&$V}J{Ul&?uqr za$u(|o$!LA>!u2pO4H?pU-A?J-zDh~G6gitHD4 z>j?0_%oCMRZf~DL69iF2_YcrvI2@=(b$0|A%e_v_$v zjRx3q@ja`KU%aa}KUw@HZ{m@}*r4*dSl%6FBUk|Nz-PHR1M1tyCyYomJp%4EU8-sT zA7nDhN9uMQo$tq-tuIc&j*)CC;H{z~g&ElfVif%u4t9#`ynB8ZRS3ls(=)J~a?bOp zFxq~4X}u5qoNnCdZ$kPiJuMVPxiiDkhP$d4GQLue_S|6s7``;r>hma2%hZREU>2qZ zT|Opk%2@wzZbQf;cgmM6>bLL^_i$I-@APlnG8FvB5Ahpru>n2}WCN8zNXBQrL5EEG zpq0FfQL-a>jA5?UnZ)Px^p5Pia&H`m=P?mNu9QJefAH(oMe$Pq9|kOYJ!%bQgayjB zrQIjXAC`pctgex7yuX}@M|{%bntLTP(FFvemWH48pPZ}Jt;Saxb$x@2n)BbavBgYK0T^X)zvrzTnmW?$XcyU3k{5TW^<)O#P0ZQ)#Er~^H)bcj{6L(tj(9e!- z?sKZq(;XXqZ(Y?d^fK+H-)%KTyuFG@0m`cf{&?@+NMXV}UI7QSG1yIiEB-4UZk-Bs z9d3u~*7)8K^C@#OeHU0GGO@)LRr%eyQHWWcoT6eG33p*#n{VgkUPOaqGB0V#lExC} z%^;70JPE;_vQ&@A5c|IJA&HwtJ1Ug3!^OtNnJt!7@Kex_zb?KW9s$`HZGA;uCpAl+HMOZ9 zr~BVBooe1b%3-U@D?aHfSUdg=x9E@fIr1=)i&aWkEzQdzj>UpiP>wWUZhH&#Rv<#t zZ2ti-z^4lW>{a7B8Nhl@2-dugVbV@?ws-l|9}aKQW4h0=#Jg+&<6ZSFHkCgGDT01Y zGgA*L%go+#1@O&{-vF-57RxLbsPX3Zr74R`rL}mbfEs?}z_id`c1LrUQNl3=ypSzI zoAcqgL>hCqNfV!yt7g~xIiK0JBTtF}$C!kMv-=kLZ!DWI)#J0dd9U{ND|?MTHx8u+Gk_**eP= zme-?K@->g2!p%>-5~3m}bzRktBDOYIp^39V8LX_x(t$c?xLPGa`P6VZXhFyVU9*>f zT1`MgPbGZzRWGsx$t->Fu7AwX1P`5=4ZG5FyRw~=#7QQ0%3+;|iu1ZnzQNx4k;?g6 zByT4&D%?L#lK=M48w=9GbvNFlWNqgULb&E&k|D7;uaq#@V@+F&zd4=J zhVZcgMF!0LpYJ(*%LB!N%u#S!_Z5=e2uRX3t$++yVDQoS>8e`|cd!6lvNsI=2`HguYER0vof2yYwxU)+vRa|5&+|v8Lo= zDgiw zab1|`V}dJdW418Uu}~L`S@lH;zw_4__;u>0jCMt)yG`S*F2!~#2B6MLKGRV)z+gbd ztDGn?aK6Pto`mQeWoqhgPx+jPtOuDv?5qt{F$k|(G|iaOeZ98TBa4`iGfZh`#%_Lt zE0Ke~p+R$45txoE$aV7%ZZw2ep zhC`YQ@I=l%my2efC4CpzQ#Jyy4eG&nU4bl}Ei{fMj2rlWikbOYVEeQpdcAsFmPZDW zdm8I8(AS`yg7icuM_ohJdZu1+9kO&=k(mwNE_Jv7+%4B2!G zxa*c)q}%7M*w%8^Xl#!Av_%o_A8)QguYibtmJ7*i^FzTemwXBpM8Jb4iZ?cdT!nEH$%nJqnp#Nl^!}+#2{%h?u_bl5R%24dW|~# z4o;Zv=&f8Wy!LlpnA&5IOn?~}an3JHqD$m4E$5!B&I53J=%=jUUKS;V09$$b56O?% zpS`mep!Z1Tr=-;xxoTs?=){i9*L-ees38s;ME+tnf}6+=L$x>H7Q7wbEf* z$|_F_r2CDSn*sdgg;#5w7n6kt09%)_6njMJuefX84(wm!+MVC)+1`?d=ZN}^Da4Fr zEk7MB7e6|fQfZ(JGS6|&%+}SN=+aX_ryK$*pqeNlijy>bScj z3cN5+6llQWCOFtjEXVV_7TdjtI9cZqtN#eY*3tMj<{1N`Itb}PG4DEF)SCKuSYErk z;3v8cc=KA-PL+SQ+{n=GrW!}5cTaiXE4GJ1LWog1Ow`$fUP-KtsyP0KOgCJAvI^|l zqwx=9;(NRF5w5NlPK;c)O6uo@n9|A)y6;K*a7G0-#2IzW`tQ+|f7ttY%nu5miH5D# zLZ6tR@4_MhgB$OD+;fm;#c>u(d_#$RbvH&4w%q*%<4Po?>%lpL^3^zZtI(6W;flqH zy%rwu#xV!<51Kdk+}}yzcXnsc){2GeOVf=uE7zBe0)gvaz_!-B*tKQ2*c*k~`75n< zig$JJKjO4vya?%=G$yz~JJ?E`3zBT=KTONBnTKmv)>1?TO3^wdH=#iR^*b3xlt2?a zdxnFH|D0$s&aL5aN71zYTSHw*(af~X#>b7<3k!43#)Ef{eOGe!YXI-;L(vS~4a<$+ zRfse^K|YC?7RSir07l8PBVl?2=HC}XR$9j34d)eZmW1!6LURUkGF*0McaFw?TxGNC z1=nXB-i4Y;UlE~J0K zn8uzlP5RA$!JHq_$-wwPEJkN4UE8|YdvIaHlCr~8(ah%5R_hn-I?{MjziSTNMbD)M zuX-zYZnyMr^QmPF=x#$#zXeGb-dF?fhbHsLL9* zmnik9`_$_0Ie!QXRnM~3r}~++8Fg2eb(+eeq~N?!pE!B#s=Fx zB)-2DVo6hnpV`MVecDv7srz-8EkS8J<=(-YVzPGbWOFNr^7$8Rpz*u4sPLG>zkXkO z?wIwW{DrR)1IBYB?90iQV=ysZ^Igw(i;OB~MENm4UvNfB-<|n$1)KRar2mHawGKs# zYGrs#$AaFp2PmK6+xqhl97K!VxT2+cH@GUQ*`_$}tEhqCTYEfZBCtMzdmI08OB*BE zwA?yCs~6pr0#->q_$Y9-+y3w_x2*x>pfCcdbru4hOaN^zogPkSlHTbC+E}L5oxjzE zeSo^$t?b;33)0Y>@T4@3z$i25#8}GXEI#o{$qf%Yu~|Rm;-Q8J%82za!z!eJb5?0DxHU(OHo^XRX3~D0IM~F`c5gHVRPT8=IX9Vh^vxi2@PQ^r31?y z+D`XBNPF?uxQn4^vU~ENLRZ$pQOOO=a%!ky)r*ucp0`QeZG_1lo?s+VKnwz{Z02>M ztqTQMmkN-S?xu3r$L`(RdWs1+qvtz|XLNNO*hKN{l&|a7x;sue(t`o+t^@BCjVA*> z5EpBE(kP462v?VU zEegIv4cDC&mO#EWC`OQ+@HFFTrH_9lSD+QvXHiQ8sp&7Tau*u6?CrDZ88zd4GY% zAP7U-d49Hge%1~<5<9nL{Z%n%aej;wI~!Cv*4*20ZM?99p_q#IGXAUbUdZC4|5R~j zg;z+;j(>_xrS;G=Z-s}z*1qbexJwnK?sV(MXS|rBG4RqA8a~Y>kx%Q}2VlhkCjfQ$ zra-w=`s=#ZjRCGe*%CGD$T@}APzY}BT8u7q?dO|xXWC}0uPlFNGp91Qe1=%l@;=g) zR2t~mGT-*RR5L)6cQEuu%qSffWy!~ld`UwPr}tp%xd=FZZt+iH+>s!aZYP`&E_N=r z@)Qtum^jMmhOxH%7M2eG|V2#Nv&jfT|iw5VNmm0VlJ$iC{&)eVs^fH z8=L2mQ0e#S&^1`BX7KAdKWZUU7WKk*(cMd0A?GAH?S=h)Q51mHDg*nVr(B>=-k7lM zE${dveU}XZ^RxK})RQ^E- z<1xE_!FpsL(;Zqr53qG)+Cklcx}YyubZ(hYHxPdGHaXy-Fjrvw9ErHit1MVqv0)&n zMw4EpIO*A#O1lndKtI)~nk_FN0nGMG?y;3WzDc4Vzj--4E3QEak!CJ}^nY+fxUjyRN{X7Kz z)1b}6lflgP*2A5dC|y!}O?>DX(xT}K-I=GE?*P>KgR#l^3B!4ojnK9Z`OSyZkOK|G z#6Mqorr3g517WPmDp8CjFP2iHLpPEvTz_(bZ_9%2bMK(_f$wkLrSQv5B%O6^;Em_| zYe>2suR20pe0_$ruPGVnfkguE8^^cSWP6s@MO44+^KHf7A8#{awyaV<>iYb_;jhMz zGNz)~`~G}FGxGQ?(UiHS~ApeNtI+qj~qmjyHKhP9BoLAxf=r1#jyhN`&wZieqR`z}f^l+r&Chs)C z4(UWI*xXwrbs7enmDkh!C?SW^`>WPF795WlzR&8&@D)9^Ke;vKtc|^JL?1fZ47d$C zq-wipD%P8xgz#c&eX}P#cRxp6lT4PA%4Y_=H}sMPPCpG=D~1n@OtkP#qc{BaI(Hho zg)jhUT8U?$kXuwEQx$|0NTjgwoE@uDSI8 z=AY)8rI3JVlVN&XnFB(Z`8Nw}ozaXq8S$~8{3T1^Z|C5FEs%MkeDG%3S!^ZcdN0$$ z1^j#u(_-@HDZ8z+XkSt5T$T;zX-fuX6b1Dq6~KVR@o1R4Vq|&}eYaU>^n5UUx?1vn zU4oIhTc>F@gm_dW+#IrC#Iqu6IV*5?7yD}{d)6qeYQ|Df#p{|k!7Y*P`9iEIu~0&L z(V9B3G@%mHuRCtjz1{2TDtJIC4iRYxa|U{L_I#K&T&u2{Ybgv(seP%iVoMs*>&hS2 z9dImg&GW|P|KG>)@y`zI{n_d6)FVA`E#xp*DvR8C1uT(7> zwiMf~u+j`aVC9i{3ZR@`DF$34M&dvQ*tvkiddQhLDE#8+C(E}dd*E60V#84THLe7p zQ70MQiOkoXi4i?OX={u0^F{(4GP8tDdBEetg>LkbJV!NE%zHmn;9!zzK@8m3U(a~H zJ=@P+@oqiArPSzxSTwqi-mTBL+Quxpvy$xEa8m`}nOT%YPxS(CIluK_K#coN@ndap zF|qbLBCpu3pZ4mUCnyU?IYBR` z_CY-TECqdxGT2GtF*M2HgIO)8YnixaOQiqi;{jlG!C;prrLQwl4R0H(D}=dX%r};- z2kFm&&K0j5Ggo!hP;)9Qrp>7`!@plTJ{GIHr?=E0(;6ZLIVgto2-Y5yjD}#4Warq9 z-&r~m2mouxT<_=gR1Q9LN0S;OGw*q7<54Qx`F6%>d8EbJiUmT!VH@iA-?RBb2xm!o z0RKSZ!+2tgtsSgqX^rV}_->FCZlzyp^m`)o_kaUeEy>Zp#UBjX-qYgHuATZMDK23p zbL|KAv+jmYT}{nm^#|+AA0`#L=r$hh+TL%zr>zO?`oVo4>43og?yVwx)^qdAW9m#> z2;M#M*6d?mP52k}f<1{qn_2)M!BrHT!v9#WXoP(U2(rIr^>p!9V~b91D=&*Z(ZhIT zlJ-h!p+ifAfQ1pz?eY|WaVnO#HIjL@K$zCe=S25{$?`}l-A8lt{wWu@HS%p7EJ*N* zW--ax<2M(=mrb2kj1?^LaiT|BhT!ATRwAk#Ih_@wE??5!6SKQm032A(uEg}V@@p?P z18LCRwG-uYq(UID!3`zphy*(z!U*MT5_0)-VmBhHe;j`F`?XqeIk3%5-Yd;3LBD3L z+>w+B!=Oq`IZD@BKRZ)?X;Ob&gYMU@T{7A%|KT?_)47R)=eDT2#R=CyJXh%56!hVt z7=Ofu&f9qF9*928l;nV&!3yydJ!Ol+gF)pZ9*^}18lV-5)ei|fw=_`tB`inQf2*C!TXgH&z4ONRMD3Aq_F=aYen@7 zS5QvL8nQBqNO4Y9{sx>H-n^ut$SZf*?jH{0(CcGY-Wt#KT<*cguk{*# z-8bP2WZivzm)X^VQ*7F1qT^nWJGlIV>g<5uAuDfim4f8yhzwH+(VB=mwbK3d>1aEz zFK8q+51*-6^PnKe9fj@z$9XAU9WK*XZnsF!=m{xixkXJ||10-Rr?0z}th&r`^4(># zr$M_1)M^bVxdd3aYT+?5YS-g#l~WD9j%GfTc%?}fz37Z+NesVppfAyFz_2snmeaXX)57RuNTL3qoyl+ zHqj%^mfFNGZeT-ozr6v!z~zi&0~w zLlBV-=Gj16-swh^2{(9y|0`r&1oBW5By%<1&W#-9n)LnZ@x#` zioqbsf9Dzh`0)BM!#0tyll#T=-EH`Uak6Qg;r`1*jorq{O8Lj(AK8+9!>w%GOtz zb-UB_cA4pGKknNgZTm&HMTQ@Yt3;>8Pq|+6la5A>?SedF!=)NxxMrD{lJu%q>O55j z%ycG03riwH(|w9te$zV*1zakVexD?Nh+CDHd=i8Xg9Qz~6?6`Hlub7*Q zwM_%YF~8UwJY}jo!hf0xoGf_4@QWKVM{AiJA0~kQ zz^%Y_Z1c>(Y(_PP)7;6*uOJyYnAP?)3v3BfOokemV43EF809KL@0UOOG6#e5t2}aLxH`@QW4^1 z2F8KcO_|?r8bc>G*9q(mD%!_W?v08W--7Og%;a9|FE#wOkK`WKz!WLv~*R(--vC1oSN3zqlU09 z&ag!&Xz(1|R;+{jzJ%gliaD;v_vsJ;51kz*Et4+R~Da+BFTCj)z@iWKR4wCaT18aE;uq9@cLS3w4X zSi=~Rx={E<{3*~~0b5JXJ1xb8o-{?4tyXRf@6cW2Xv3QyWiZl!bo+!9b~_B~$C6%r zB4owDjuOaw<@2mO!+smMWoe$0Yf`q)8(5BS6a{)b(X%*IWexcVU7BO;1F>|n;;24@ z%5S=+T#~dtmA_mHN*=T#ERKE*zgjEGA6=+;GSPc3hduFQKnXQ^NJk4(p|ygk?^uxl zG(Fzg;zIpoLqtwJSY=kO#oU~~Zx}rRms4ogbS;w!5lxjh>|nmHO!WB1<59CwjptBU zhv`=jeZGtJ@!k*~vAtw4V`(IFZvY)|-rR1wJBy|e0}e@NgENs>WsKqypEW-|ru62l z95o-k`7CfN{wZlX2F$)Uj|AwfQXQw;1nZ6N+?J(Uw2g*UWFF67Aec|sV8{4fGio#M zS#vv#il6IO>w~4^QX7u?+=0|#*sVx|s%NNTse*&e|u=)75#xhyj;EikX}%b^o^!L<_}`1`5vQ;)tm z8=SVAVPL5C2wEE8h)_)XGvP-Y!(65KiE_cO96DNP-{aU;f(IY>Cd--r8I0IjNetg= zQWv}$U64juQNeXHj}TP`TD0i|RN8}s_Ek|(ZuXG-#ZbiOnKh30bZnF({{dA|52Xh| zyFt;1c5E#6ekph^&X?@*zay1{XgjT*8BFB`0kF^cTLM!;5ya(xl@!0jtK#g1<+a3T@AuGlYEX$ib1me1 zg5K;V+E$<45zL|@!Rz8H%Kx{i(~&eSpLoIF2jVH^CiN4ebou|^?>QJh{ zmeTBL-Zgh39Oq>pMB}R-gm3Cjgs=dX^78jzbmjsr=JQ54^(_mtF? zkJ=gKMjG#JT|bPddDfoWlO?@KUARW9ShbR_igdyY%gA6R^SF9IIhhv^&c|6dUnIa5 zX3V{wL=b+UvLE`wF6MjJvPe7ahiv{cRUFr^5mp6pUnsODbqyicq*#n|HD;NLMs-pV81c{ zP5D@R3Pq7S`T?DC$9B9Lq%I{oB?TAhPM-b_{zuBrbXrNnqa{xlZGOhUhu`CmrAH&D zi&w8ANwT`Q4dqEPgR&u9m6trqkQ>c39BJLsLP%g4W7h4qbB06c zBn42b(&KH?s=>(fW=z|N3TM~fT}SdPbi^+Atq-^G2zy0O4Qg@F%Wd@1xALh~0SjuXkGJwP=_vY7)LDLHR^PI^&K4Vi%*F%Mn0F9V`LHj5{O?x| z{Pi!krL_WMgn3Io0*Q=+FvFwvO8Sc}%eOsM5HU#p8-Zn2)42vLXUw+h%)vOoujKIqSHZ_=8215FyXK;-QnhAH&510TTl0HHeZ*8 zw>DKy3Hwn(cxoKB9Wx*`?VqIkKQDm(r4-Yq=?Yz37*&R_O`Wb!Npg3;$F;_}u>j&` zexl^gn-chXqxDx%fm3&Rk32kA8+8ssj%=)Id=4lDrT*}we-@d18)@sqJ zYRL+h(zMSt)Es8yEE*O#;E&=H2;rScw!-mHm6f%(NsiSCGR4)0wgE~BkjaiMZF?W` zXBRHcqeioL>Kg0pYB`dRx;$MC_rCa#I3m27j9M-{0s2cE>!2S`IdVlCDEwBAD}J+R zO++pIA%$Xk{bM7Ss*~G>(7q|U#zl4+{%TFme90L1(o z!0Cl3Sa@7lE%v$E`~Y{v@u(W2J99S_-OXyg#O9v(PwVK%2i!M$m-Bhr5=JH zn;abFL71bR3rhK`6G%H#-=j`9;EYUi@zJ?*?gT2bd!JCMI5+p`~ zdZB`v%lS6h(|0k%vC?{NJ9B()uPFgyV5|;S6su2;9cyWa-mr8ESWX0sjfPGYL&k%* z=bA(F<$d0E67MofRcrQ6FBmGu@z5#?%=xW*^wh2rMq{Q{Je;0txJ`U2;9EYk5qXWv zSDzPZk=j6?-#z&VkL@>pQqDWmjv5Ix9*@sWjkS#b-E<9p{`-1Rb~13UbL;aLXJLX1 zlV070S>dY>oCwb|>ftBh+*xx>%%#lq1^YMSbyN>!pBJ>#;UU8QEZ@Ug60E9N`r<7M zMwxslC0tDs2r?CL6N;fqZzwD;!Gb)*-meXgL}_925!bMa#SIa2E-U0)nlYG#Fg6g- zBT6&Grz?ozhwCsMmcW&q2VSkv-7cd<*j zWBD87=r(E`Hx$L<>+Lf0f<@4xKR!4&On8FA_q!wag1D`b4*1aVo}c{XTT?28nP>i} zKdJZ+F~l_Ra}RA5yB9v;>$O`yD``CAk=EE?dpc|= zUJjo_yf`(WQ__^+LMvamX=R*jEpyUh<{AXAJpt4{5Ty|0;#s#k!58BsDaLCWyp zUNYAmC;zM8Xuz)QhT%HgN^IY!EfXtHKszX4B>{}qQ_>4wI$td_`<|7W4~&~?;whso zP^$JFee3JYT8D#0W`qVEWVc2g9cSiJI=@HcXNawTIkI-VUAz^rz2L5IGiRN~_DM=I zX#Hb8__to^MD0S!bJ{z@j~j+{OAgBLooMr(#jDzM8#eodrRMWr1lm;LKi`!ERXaXr zJ$_|L}#0B zym#L;_geDg_Tw{asqcw+jK6E)Sog@u%dEOv-)pGwdwZKOE*ATwNRHlsVv5<$HYh8& z-4Nl4vE6>`5d-Be>jA#r{7hiP6x*~go79Uu8SW1-tiS7oMJ#FI4JM4OLk!pC#7 zgyX$qjonAw$({kLE{Ay$(BmCwT9Y>#GldAh0mXDxY(4h+ud7VnvbFVqEgr@;oA{KL70XhrX&;`deD+ zv5ZnKGkViO#`s{mGqW+UwxyPNacx}=u9JXL)4 z#I+v?qm#UQKfg<1_=n$yxOek?-_R%O|8y4R+|~lX!qno<8UDP%mKAhoSyGv$IL@>5ELbcumA=~QMmj4{IbgiHd7*ELWZQUn zH`#IW{;LJYk1i8F0#kC1`^Cegx9(oT(0K)&QOCu}OsT&&ZGK8h8vV1{!)yvf$lq7F z$8W|hx}2R)g+XknN*Z)b3)KVpgE@X!Kz+@&L>XbYzYIE3-~xE>O0(LLNW4@ z=)87xb*)MJMzyp!uix+^!t!E$Oz)!g<<9_(*gvKS#W5&`xmTdu%G(0mYGvpRGu@*5Vz>tHI}Up=$KcYoSndoq4=$8d}i zt{{{2`giKMpZ|vGxW?cQ&3dk~AsN3ww#k6w&ErED)W>~gg@20Hl=6#S6|lDnVXSo> ztu-bP7^I#Nlfj^E#^Rq3{~lmrdjDb-LWY)puIS`WUF{ztedRuGiR;2k9eI5(v-Enkzk8@p#4GrJ^PAezsifCP6R*>R_j6iv;XBd zHdiR8NIhkHg~tFPX#C5A3e~pdl;9L1xr}@=6*Sq-MJWXq)jYq>5@xMzSyZ3@$ADVU zY{2Cmmey&1*0)#-NT-hFv05pN&}X`HAi=b&vu!^dS~VE2WqM0>Y{_B55$z4>)7=aA4YL|F$bH6qPkTqJu zQbB^vu`W9U#jS(XEy?2&5)ZteFM^%HYW&-M^Qt+5LD?Nhnce&;i3C;gXhaZju_pql z5#M+t$UPB=X{Wn760wnpD#^B>B6M^q!jg-&{??oiAiiT+B+qxJE_^o@!B87_lIxD$pqmz6-N{V->gC_0;@IWUl7 zluSK`CUX#XZGPk#BrA#UDnR4ilcW_X)7#9IuGf{7hfp%$dDu*K0( ztn2D#UE3J-9%thaO?{mjIw=0V_uEj*8@5BAt^HENPkCZ8@BVB*;VxU=7LPb!)V2_@ zh-X*IhKLZtm`aZC(*WQ!Mrl@o$(J-8!IL#lx{21_TO4f`vzdHW*vu*~lG zMDPP8(EI{6H#;z8Re_rSbO!u~nE3NStpDF_@cC=MdxmsYo&zq~VKRbdyK3*q;9XJQykhU%|u zseeG);bN5yTu?EPKM0{l%EHdb4Qo?$u-mx^_CM2N$}TT5*!UlngQ%AhW6>eJN6YMh zMUS!;1we$pKE4+^D*9|*FU|OPl`nz|3qN3N99X|=R44iDK{PrN4K<*x z_A>j5WI1{QYkp*p?bj;_lM++q9n9uUY<@&NrzaYvbx~*|nP~$RxPvk*4=AE=eQ4hN z#bETzqbigsJx+}8f+6y%kCQ+L)f~BDscT4|>fj(BcuQv(q(v${pC1u1@vJ>CuP{n- z7>RYJbDNx@o_`+^&KSRZL;A#^l_qDA>UU>c?wdT~sAA0|bOBwgIS;!R^w#F}LCovL zowlX;i=s#0P3h+L*Ng0A691~6 z7PQnLyoa@uAZK+{5{Sn{2FT7v`n_umzj#GufNnRyx)7=jqxAOdg!!p zjbD_qbq5z)Bv;d9;1QtV2oaCVD1XBn_JvrdcU*Pz^2}x* z5k-DWaBPCeENEQEh8^6BYkWwt4ohedJ1h#mPM)c@C!WT6u`!KX(@Q zMa#CNF?{?`e5#K6TF4}N#j($OL}usS;nhf>>!C`5aaFhPM#=v45Djh0pv66SRdhiMzO<~U<@@651+QLh>^;!4=*a0gcz6KpvfG~%Dj8{ zL@AJxD@h-#%@Pqx8 zMv=lY2dcY!#8gj~R)J>9``{!t(Pf>xJVHwsHmQzaJ^%|&D=}@J!ZAM9YC^m`r~M*J zC;-tkLB&(I2p?*$L3lxG1v>*;TcuV`&aNR3ld(l}_oVckt14;e27Q-MqpcLp>9rrO zc3+(~8?dSVaZ%AY#P@S3B>D`B;A=uDU9-_@wRwe?OcykpairaBz+z2s^ebNQ&a07G0X zPpM>76IR@Kjpzj%WeL2wl{J-jv2}8=8L!7?_cie-I^=W$0=pwmB2?r*JgPRM`hqZ6iKvGT~IXGgH?BQptN2Zq%7yz zI+r<2(&hWj|EFl6dd$(I=qr`5m~ImY#r61@Z=I{X?_xP`Y+o#p3^^IYU=FsP8U7xA zLc8z-cGfQVtDd>(>dnfisa8cc9iN0 z9|KuWq{=K-6z>>847;0Ks*pDKkXfa~YOYbdmfDRoT45wUzng{T&-A0U07Cf^Z1yk- zXS)VBYTcCkm97Yhi6;F}#$`hMnEo0Q2k@@M&cyAP>O;}Jd9d|jos4iDFQ)sVZ>B@!t$f*mT!4$2R_VI*^}U|?*FCuWGD0Byiy&QVF-|}6D<^vY z9i_b_ZS}P7*0U4ixsb(b3CA|R&J}A;zZGK$weF6lFR28W58o^8Q*>I~cC+X4{bsX~ z(#C6){DXaB)e6@DYKdByj8huRx%lz&@!gU9qLx-;hLi_x|3{$jFX5u+8IWu%Zu^vY ziU}&BA_`2_*Zx-yq)Jf|qyIb19+?TO<%0HEC(ECk$A)SCM~8kwDC+!&pSZGq2g^~x zb{`Ppo!VV0(qB_1a&@XxtCG>n&i$^&b+finjp8ljzboNlhC6zu(d9JmwN$_!yE)O; zz>Z+41rA;F-}~BrDpL?bz5c4qL;2pl4)5k(cHf?dIgGk7&}&wV;p!uOH4VXUdu2U; z*7Q-w09FVlvZtZM<|=z3(Ol zoh?U&!+1>mMmY(}UJ?W>hB@naY?I9XUZ>-BF3?lS6*{zdm;c#L13ud#0zDVB2tCft03&_ zYk2GK&cd(?7#wew@HlCBX=?>8Dz_pT6GOehX>9vYR;0uZwh_mOzgsgvdMN z3ViLx@sT@^NA)4qVP&X?g`j`{JHuR7MX(Q-&@*928&kIvi8&UrIWxGpat^c~44rDH zM-8~={<@j~1U=emFy}d?S@IoREvDY_9^oj1-K|6rN~JXyD#1QpmsijijrJqZRC`nF)J9}CseU2nuo^)xQv2_>n)=VbaH3cbgnGg$Q|r8W*CiF_ z5o#a2HP&gK-RlCCvgF+Zc+_$=XJODmU84-6JwXP)y`q~S2m>?pJ6F~VMr!@nOLD>5 z?Bgq~eM+!q=~;QoX+wx7(2JyF!iuvl9xIUU4;XPk% zmgOLD8Z78sXhw0+vwGy1RZ#ur>mvK%!uP6&hVQsoJh-LU&kcd?*uz4zwwHfvrh-NS zzeg_%!~n)OOiV1kxEx6a>Ajc(G=DzI(enMJh4+3=mbu>fl}vV;tz)G`xq%5Re;gAA~LKFoH*% zTgzfj{EKd(ENObO%3Sx%aU{14y)GR90cspg*8jkxLqc9F?*>&{ksZuf-Dj6hb@_oA z$}^AQDo(OhD}Qx%>78nu?F#B|ejhH6+c)-|@0vtkeMl@S@Kt$7h*F5U?sK=VDIq|t zciPHD{dK)Ylj(MmA-sT}&93B5aZ3&k4s^)PVO42)Dl6`(?B856H~xj7jy=-1DGL9Q=X$;6 z@Tw;Ov-g%CyAV8-JMv-oeM%ul0aT@qN$QPOhkaq|vC+no=}cy?5#JPJCGV zgQ;nwH-yzCu8B(hV;Z7dGv4{K*!$$6spS6x{R8br-=%4jtBUQ2S;s2Xb}VX5ePO^2Cky`BiNff(KKdMb|HI_mE5?-6ITID@d<~25j@etYLtQlf{#82R4&)2J-Z*n z!aFh{*CHQYAmYGXR#=XPJrDH`(Hksn``Gds|1k1A$(w4WR;f!&1hcz{XobK1^mFbp zpT+er*Pm{AHiM6-$B!RbuSo-5XN)7|Y_LgQ$c?1Q;?cxy zD-LuWH}SeqTTxS-f!mUBh9RSu;=!J!QvImc&~xMYi-g=&+akNt5j*LNUANw>O7ZU2 za@)#B@T7v8^vY_Fltw0JYeyUN4|60#^m|pXDYe8}Qm>`AqI`qsNJqCuv%ZG+bH5+_ z`Bd-IB;)H9?#Dk!%e*dPNA^LRFxjrq4=UidH?j9f zBtp(!qF+QwCk^CFubvr!LAuRG!&GoXo%a%G$+2#9M}N8s>~jRD=^BL^Ez?5cIqbbkG+15D6C8(Fj)&=0+Y?@PUN=zc$_57p+u{=6!Eng~$U z)H#rJHXR>py>gi?R-xtdMbgCJFnA3>^T59w-L@YqxnJ??yOrkr4Z;_6zpmEQVqNCf z+Bzg@l2&oAZG~?#i(XwBZ@8?(Y`R&2vILM!^LuymNxKI zNaf^3W;SK++ETy~!wjTv1=@v6pnq$7FY5r+Rl{MR*zY5(%UJU#zzlOpV#S~9fyY8=|V z`T;Cmz#&>zc;ARlg3s!9TH+Jv906&v*Rec}STMl+VE(T2*t>iE=PH9;eror59guXgGS#GhjMxB2oKhl=@ITISmAX)%#7r+JO< z*rSspym@UI0Qj1dJgY4xna^l31&;v1lUeuA7~;rRU1lT_!v6@G1TsSNwamBPqQ+IBxlk$;_@SsR$KlwLh^a zE)ArJmPqr*`&ggvN&x=DI`8)Wt@NGfXoPf}po-kg20!yPW~e93MjyOw8wiADC{sL_ zH)5%|`K~0&D_Dzxg#(X;Y1p7A?Ormi?o+~IW#L^U-Dr4_lj3JWcJEl-%dklDH?O`c zb<-T5=6jr~8^jr8g*sE&&jL(n87pS`Dw73U9{x>z9m);0tKyLv@~=()&C+mvfhD=I z@-LLcl@cQLwp?DYBACJ^NY{U3Bs8DS53p8Vv0U$0=<=s!iHophC{%PkQuHh2Z7g~* z8Bzo>;2r;K9-$@TOZ$#}9U^UNX=P!A{Au;2!@+>QzEw4r-7qN==#y_V=05foyVkCd z(rVA?@h8$?MglUEVey$qzf%3l0RVv^^T@zsFT$7pk|jEOUv<^u`PGk>v^Co|IWZlc zUD`fLq@diLuFVqXlj1*>spcE?N7YCHT7@=O znuaf_JyY9G8OoZa)HO)m)!EZ?M%>plvrFLY@^Tm_4+U%8%?G?sKKWXvleO{6guUtr zVQb~7pNobw>zQlggs&$Z*M+pgI*F8+ITMzZn^2*cncwQgogeeY{rGkZRx*b8YUfbU z2{~XZdq8W4&OKz;%E^=M8=9ikDNXblLlxRnzikobQ;j*jpdfM2pN2x zlH|Hy&zxWOW=3BmQ}H1v-t(qbbKE=o^)yyHy5UhR>VqCp05~6Tl|ZC!%r!Uc?bQ8O zOv8CRqiKd%RGUgv!Mr*q5f}+P$Mb0nR0P(4CwH#Oet#j^1%i;-**-YQJ%#}fn_L)8 zh_la*9os$rNAIKTrg6`=Zjb6h1V4BFQ@$D5uzJe#9$NMWYd$(C)I6z{dDB6K+hJY~ zE*q$LZqR-?c2w1cnScX)K`AOcxF7^?WlOQpb*Y0tTZEtEZzje;>C^M%5g6KM3Z>lA zqeJ+{L5~us^>*Y9D3Z9Ziam-=Xf;zee`uzk^UOdfHCN9coB)%A`XMZSwM`Yz>Ia|Z zMeceu?IA;znH3_yApWmGn-Tzjur_R(MZfNYfrckp3&nCYz6+nrMHwXk^;QPbs1n6L z-h~ZsdexaCKVipbfkT@+5~)JLexr?L6!iIb!#4>`i+9!@g0}?JzN0tlr&}6JXch@T z!TprK=5Auhl+Lf5{x`MLaORelZBO5zHIXm^Qf-Dzmp?gco{*U@Pl`qat06ckL0;%e z5^Lv5S-}G%!F*bhs3vVeokaxM*aw7V=TA$xY`NL*|%f@HtS zqKxJGtTl%x<$~F3eF}}Qdq7{hmY#anH0 z)G)D(pLoyvZ#MYU=CUQEy;+J55Ji+v5e4t90P#z%nbky}2@jhaoH3g{F0kRM_=kNG zKEX-;&wx?S+wM5dd)%_I7_qyOOrV`ehbFEO&O%k1T=F{l?GGRE9tq%Qot_d~32cgM zeF_@=Zh${dt@TQh)W2dv0s=eM^`>*Aku}@Z)l5^B(!ezzub$nxlzbc3d=ScM|K9-n} z^WWRQKYfEs)r2Jh`1pwTu$hvvcCK2`K-AUy0S@daJ8q~b74+IRp`4mgsqo{J;gJb9 zOIVD%1VPw3Z1_A6*Gn#vybX|n6^ zD!0S%=~Tc&?H~cqF+(vZlo@6>zEm|wa)`8mCZy?yaTS}lX4j+@uGl=knPPl zwLRi^m9Tj`T5Jg#`%Jai&UoB%oyyuh z$}XLgnoI7FSarkz6>;a+=9bn(3;Yi9s!OGeovIO&XR!XCH*b?dhL5}E^NWWHYhBe2 zYxBmp42h|ge zeGhpGTe520J~QX5~mUNyYVF;DP<*;3tDNEyy%1t4}NK4E2sr|gE>zu-H|1IT!ty$<{ zZh+Se*SORWu@)Js{@+E2|CN7dEnqsg7YyKf6U((?@yfPAnM1rlfOoPey7p9*5BpRe z)wRTMATRs67pV zO1AThXYpaZhlDJr!_itrc*cdE6Jn?dFKlRG_KY+Zk;T8W8&ygp>9 zJtF_$j41%th=D3q>}R{T+r4hEhHA97-IflR7bnEolO;V8d#}ZS;9p}TVn~MLpM4Cf zXf?IOxUjm9mlxrUYBh8bXbf9dc#__yf9MxZ0728 z1qEoct)?U?JuTPiFe4i4rZFtXF#;;IJ6#8zuYSAxP?WIOXHdQ82H~MKhxg!muO7eU z21C78M3h!?T@AW^`OckoaZNXd9(^M}H+MwLT>q?jN5mf@bZ)_RFKH(5 z#yH2hd0v?$HxGp}LfM>m(4#?w9#Ujs4vsSNOnwJDUtjvB6tf(7mfdP&YZ29UYBZSobm@YkZWbTMPj)hXoMR zrV^wH=t-@Ie+=E7GInW67?OTMlcA>s2im!YSDTUoE7#CgvxhCiFx%5th^g1XM>8fQ zN|pP`jv%g9_%q&S~`#^OZUmC9q=1hE^L|a(&w490e z@?N*2)Ob+ShdTcNe~5D~Dwk7Df$NbqB?@tb@?`LlbpNpBip5j0@KUC)k3|V^9Lk2J z0xm6F-!5`gjACWs!6ygceXl~;ult(COVXs+Ar&0uF zcvm0W<*1v~m2zB$!e@xLmOY z@NNhl<_deaUP_wL2wzN{f(W|3ZL=-&t7Kz{YZx?^In}w0RaLJG3?uIbVr_1EevF11 zh_ZKN%Zf(^AE3_XCBy8{*c8soYQQy{Va>EwL%-)iwl_t58W<P*qJ}~m%9EJS2X+CmL?F$DEb(XSW z`=bB4toQVaifiw_ezQLa9e1O~2vXn+=I-k|T5R28);pi8S|c{(i0{xp2R2R39uz?% zUa;aoeM7X*xiBD#-=(BV9X-k?*sHrLr$UeLNW&^dhbVU_u$jzUWc+pKioxz)mMXJS z0gRK9Y7!a}aTgY1Jax`)-MIA;RRX!i*rcv{55zJ2%o{;H?^|K`B&^4w-6POGH}K zqSLI4k4Ib4MU7T$0UJ}@jxvDdiFZH<%QUIuPEAkKqW6V1F_l82Nz2_6x`>#>%HfQf z+j>p@mJpN|s2&$42{f~NDgV6mJb z_P!ZhhLQ4@F}2*Y+`6z=%*Mu}QMW8vyIvc-evOWyN zx3g!D`gkCC+HJP`GI-eH>;O;E?=RqM4y+O!gf?BLLbtlETL&p$Zf)JNqKmFBDKB#_ z`_$@+`ja0+JN)!ym}50pCW)%oibtM9Y{J#AX{z-;8EBe*rv>X#X#c3UM$|c_=+ucz1{N>`)el}9>uqDYH5aaC z!#Wf$Aek^aRul8!rKf6mo{VWYT}`%6G-ep$b+$&qUiV9R zL{B0v&bKYLR!z}z5gpL))RHbWpB;g+PRzGvu%Aco>WS^R$_u3k#TnJ$EP^NI zo1a5YOs~v@mF4P%)TQ}Kpx+x>^8>GJ|0t6;<9H^2PTVQz>g3PZ$2q-Ur17X%D$@%UKxbdMEvl@W=_j75_nvxFz;PDG z%sI4A)f+scrl$o%QC&-&VmTE`0_WQV#;h#f+gagJ0rt7<^Z~8EHI+!_yE_wpZBdPk zf^K&zjI0PX8p1!g44`SP-L4^zgNQ+%Y4f;brYJQHMEn+HgH!IQ2NQYKSZ`Wtm^biS z6})XR_Sq5QUF}@pNyom>y>cUF-Ba%QIa^j6i^F%qc7vg@f2o-=%Lwz;tggtZI_+me zhpeD4#ee)>wgtl4@5#b!S;w$%)rKb@#tfwQBl#jS0&vCb8tu8vqE|uPxWnBTX`z2G zX<5!m+tu5nt2{E97hy9X>y{QyQeo@Np19vhOStnnY}US7LPlaUp)mBFleIn}+|f?Z zgEqOE?n-J=NOjyHN`>uWiXF6))dfb+RbB`@8z$=oKm9Hw4|y%dz9Vaup?+5|TK6z?q^(kj zk!vVTY|WDGeb0IzkMHzOBBcBN)|96YL{GN;GYr~a{o66t)3v_%vg@Y|RxKK#rV)X` z-4$cFa*kljMc{F6HtM3ApTT3NLXXOICp!8D(nk5lSEh;$?b&$46!&kI9pwtK!`Q$c zA04>!OAS>>SXj$|QZ~T>N+v^Y_H53*(D2@UD-HF2Wa&tjl_R!^heLRh0*$M)96r0s;t?)HNEZpUNIP#am>6PN0>FYq&(Nq0YprQqx?1rK5m*v6WjWm z|CIT-Yxd^aYe{vNPY(&2Nu?R?->nXve#UQp#2XNoXF2v$Lpg@A@=YVEJ=Fn94Ky6x zn7m%8dbp>D2kp+X@fBJB&1Q5x;+W`Nz4<4<&F`d?eCv!i^1BDM7-G<>_yu#exMj(I z4(Esb*v}g6b0)1l>5lo5x zW$Dng(NCfaNe8zR1~#F^-`VgZV5YOHkLnMdN%{LIGx4ACB;0k9LPx#eW37F z33Z}1k!AkD4pf`|vAEK7D~d~4l)@i0Cg4vxTij|GA|w=MU2lqKu&hmG@X}C zTPziEdca_ydE7rNNzBCw0?4yPHu&E1jWPta-@A1GYh#k$AE~Q(zT@QIY^F%^K2!C~ z2cKJKWOhJ}u6|)8OZRvlP#y2y-=lKJ$XorPEz;W9*4C2?AQFIkd%6lN6RH@K-b=t6O-kE z_zOiCk2O9)dc{I+G}uqWXm?3MgiOLJPREKuoiMP*IHMU|=ykL0X^rHO*91Qq%!{`H z6!VlkP>mPG#jiwcy}dgc#Py!5W*_hz8qS}pZhJW|YB?*c17G8y6VFglAXJz8@R6-;sS2FkGItBZT z$8NgEM1_R*$v|Fvyp51K>UF)v#>q%&VhcdBFhls?UulO|w`6xF7*0VE;t8_0?We** z-}Oxfnjej9AG%gex=V5<)C@6HGQ;k(@p_$_G!EALsS+))6Qc!&oFG5@!>gC{%q?rb z6e%92?kb%4i|zVeGWDvUgsC#^QrnheAjiFq0zi+dePC9{%ZdvDFZZRIX00>@*#`0} zpNlwoUg9ee9{q-KKTRHV|EmE^@qgc>(Ib4|d+*T1{%-DHHCg*tIk_#YyMb1h){nZy z4(a`e2b=Ur_&&Wjj=MgE>`RJ6$lkINofEYQD=qz{;=sHfAYnD9n~%Goy^z_de9>|1 zzB8vOVtOgYA)u%DM&gs@ym9TViF%~si7O>RIYQB*`rGlpYy1>2+Dv}^t@ZwY(-%&- zuw(B3jC}>SJ+I(Ezk)vTjaxq;czpx2sQ_#QOFm%Z5Cka!vS8$}jR$k}hh(n%ERE~z zUQg_wJ;f zDT$ML7p+rJt}1AmAb)vQqvZiw|HGZI{pM(Pd1!Qi_)#Bwpk_qCJ)8SMoyIjUq`{~T zQ0&^zs=&cBlL^^1-GZYSfl8qA$$};o*GdJ6+HL%hGp_R6JX)jS?P?{|2!ivYan_4P z=e%kZnmGdQaa~`7z&{(FIB%I9ma*4ttfvE@Zkj7Tlz1V(ho~t}xG&Rh-^(9mT2GrkoT zA)@{(wO>Lc(qcqTMCfU=ceF@$o@}m;} z=#~=foAZa~Rf_A2Gyil*v3064$)hM8k@q%&X~#PKbF15~k6p(+N4eAFdo-IRsw;CC zC$!3;gOmttY3^0B$s5@a!^O?ab;QBCux;(?p|M^iQo`!2*d>qshS{O*t?b_hm{j9) z>$A%lACV7$q&jZ@%PHs*CN5CoVL%d$clj8Y}8lS^aGqwu8)p zCd_zfGopR-YQb9t2V4H!WdmMweXRBe+i5aTR6g6T52|?AWTD5DYs8uzJial%3 z*fS(n?1)$q-1&Te_kGU&A2@N|=krlwD`Z9V5SsRIU3F~ zU5%nDwD%j?51b4jG31#eiTSvT9TYt!gJX6wANjace(E3YMW)z&!9#X=|Ec*KbQPATi*yQm=r+`e^8NPq+4_WchNu^>d@SJ-d z6xEP!o;$cB7vSMP(`R;g1 z5(Nx7CmGt%{*?-p+vod-DgfV#hKK}US`wZ1Cp!8ZPG986-zyT05+_hpfmZ0i#u?u=^Y|9@Qoa&Izm2E$X7 zb4*y_yyF@bhg5rZQ?slf$OBa_k@oK5gNcrO!5m7Zxi?3+WJ@wy0V+*qoDZvVoT@Ne za#1))PQFlbe-dzUZdjh98l=mYR=qID*EqB3)yo67u;ydhH;G`+OoCJUEFEm@*1bFm z?(HQjE;E|)Xw@(l2)w^U5rGfmA@5N?$1wr}y)q<_>l8H&R1_pAq#6PKit9PVJ2!u0v8ddy3zev;78+lX*(a#|{kgefY;Gl2 z7wMAhn`}Rk57Dhf#HZ{F8WfhV_OvU!af@Up#XHB@e$pe&%&Bah>svDH#O}9UcB8T` zEwkSoF1Ls)D2$0Kuv75V!fcH1eOU_kx0`2qEz*_z@0;WM+zWw!tT8RWBGqFAc)P+F zf2h8`ZStn|i{MRoxmCRDWcJ2x+G%z-bYcC>!oq9sEMRdVhBlz20p)G=woo_AYjfPk z^6lY62P(?rJit1LU*&kv9*fuXI_FoRQ51RJ-okiDsLebhG+kFjJg$%$ zH@7+8{3hlx)cRoPNBq?k%EdX$;Y@~}f0lgTbw#s&4pUytwVacwY}uy+4qU7rU00cR zlO7}$*fI&r-P+836H-iLN&esIy&cFAC=WVZ{&bKOaO+P8qcrb&w*PyBS4CTpaD~!%-wyyFH z=v-pYQ=xNxa{8W_o+z|D$6*E){Fo^rbun{uScKP zJeg$i#E(9Ewvuain&SVeuSiz#npjS90calza>Uwz`>xH3-mCsfE@{t_Oc-GY9X4-k zzg(;%@cXSdix-23v-EJ^kOh7r{z*30>1}An@8f2Q2}dlt+JWv@m=9>XWE&ZwUDSO{X!%}fHP8uIeN{dQ?5qkOyM zQx{)F@SU(j`nkbv9h5+}&cSLCSXRl!m@x3XsK(hm7mgTbpy^`kf~f!ADzTuFf?>Bs zK{^e11B7@}FJBUKeV05$W$`<20Jse(jOz{gpeP?(`Kk`g>jiJ6S#JFPG0!?IP62J% zlwc32I7=Ya>Q9Z*_r}%mg^+(sr*d6z)C7)d>bS<*eOw zp1NY|`JrNDX3Lna!eslVNs_lI)g3Ad&IC@HKc*Q2?B+|zKLJ18auLt#$V_n}eZdRl zj}%QW>*TbyA?psP3hYl~Wbz+29eHW4COoaL2i_fEhgcPLEZ~6QGR$$0UD++4CFJ$G z30}tkeeo$Gsu4Kp6W~yCplPGwE(r5FAC=Id_v{(-P3;Na`xN=;iq8TxgXzPI^(AuaOJ)89ARN= zEY$+#F}FD+d(6Ge63CHQfve+4t<0mYg2i>Dk@Dy|+X{zp${#dYo`&$WR3|2hW3%;Gb z!?9&%-*q5X9N@X>Y;J!`-l#!$NWnn;*wkf=y1{Q$gP%HX_68jB*R_a$&}Q1^N0p;7 zbKB#^*&IV^p3V2DS$<>19g&@Dy1Pa7#`hU6V=H>Kb~i;J6Y#}2BU0z+aFjP-D`-;n zLP<;G%q@C0XGy?q7w(z1Q6Q@*xPM~hh{;v*iv3B=>$fcf2KBR>6Qax7?*-_ji`Yj) z)D@zl6ZoEeN@WhvBeH%*CzlLvX$VELGIj3jHJly1(>rS{JPvphcT`sIcVGnx*cdc_ z5p>VjP$*%z_H_+-4a}c@fvpbn0yw+L4}S4EDQK`7NV4=o{|N+hucj?d#>OR@VADE; z3r~a|q7)oiIO>OR8JkU{S~y;AzV7VsafFjnj-%bm?bWXk)iDh;4*=JmShuVj*QbJco{k>o3xwG|i2-Z!z{vX4#WbtBW(G4WHvay2A)$kc>T$3m_IiHR@ zH{J`)j{^Jd9o?y&{NH1qL&f@tu2tdtI4C4R_p20C%B26Fv^rZ>@{56g0umBTj%x(#-ZHku0;MqFHh)nRcuGOa%i zDG@Z1&pxd_Y|yE|i2b?Qgc-T5qRiWY`2*Uwy{+owi0+kP3hy{Eg-j~Xv-5c5@HO_O zF2*}!-!dyT;HUz_X_{9w{oFNtl${{+Yq6izD2Cf^lQP^*ey4xBohjz(JCt$HlkcGC z6Y4`-ueC~cm13xdeXPBIETiIs6CKYR+M6hGZjBaNdpXl_s$Plak-N=2T5^ve(g*J( z>}lJmebT-O*Pos&MkChaGW+Dm2cIh? zpcZ#GzumABc8M8s$;;mWn(n;$8HTH?IJr%`sa%k~)T7)6B3H`EXeo_rEcQ*0iB*pL zd0F39=-Pk7k4T&ll1j;Ghz^z-|D!8g%0UB{(a&lHp@M-(s-hyvsIcl5Rr8VXR8OHa$D3L!ITjN}e z_no36$5tLJPd+TN#N7>8kh)jy6#V#y+HdIXEVZN#SU2;#^*$U*W;t!}I2fN^>W2F*YS*89( zxKfnX%cycv*!B;X+I@vhUEx*Nx&*I&@BxgkQibJY$WY#E^xv>&%XP}G?(JP!R}QY59ONfE5^({PUi|~7$GLg8nMiBg>R@1*|IW%kei)kU2wA2G#Kiqi3o3%tLpvC~kk}^&U zs+;DtmP}JyQLnv{pS3=>t*DTW3Nv-+w6^t)@cQG!Q=uCt=eUNsB!}Sh%Y@(*wUfINdMKpxaCy zPc$%L)oonRnu*UM@p&_AmKxa`|Fy-Sz5Y7q?#jy?<3jY5?H~Gg6HD{_A4B|9)pJq< z#b83=VXLqj*GapNqPxxPu7Gn7>c)vU!&T16jl8${+{~`7g2sC9ro1xkc4X`B$P5rG zqAoCR(=P83agGZ-wuq&c%NB04^RvryT{)M&X6SmkjOhF<^t z2d5h<)ljj+`L49ttmkFEivh=z54#kB&)xSoqq!(s>eI6tObD8EE<_%=T&&?@iMMvc z^rI@kCD|+Xcv3<9Ub{^Eh<};UQZ7u_d?^m!^h;b+J2J{2G$R>h6eW`hQ9g^A)k?G= zJJ#%W+xGr=5Z==13okME@()FX{*mEdt)t*kf$BV+rbmQ1q$u#AUzy#uRorFvUrvyRx+4ts396*OgItozWL52~TXl*w4vg7pu=i)x+jui>RVpW5* zVYj+uUtS10&0!2EnqrL&PdmnDj9+e%PoyTeFVNg&&6j5_EedH0>oUU|S>t@GZ(HmY zow|p}8F0|=|I&S4hfGTQOeJK82rhq8`ECu|S70`4Y2Fpp`Y4cl_p!UsD{D|uUAw7N zu-L71!e*x6NF$9H1aQOq8H!jtGPyE!rO;NaB2DCsehB0-lm6raFbq*=_aV9lDmZ8i zz7!+j@w`%PEZ>tTblJYQQh#7TGR>~`KQd?*@Nmz)s=NCL((9F3%Vw>f?Y&LqW`8%z zJJhbu|DhG_tF#$S%#5;s<4oVfouPtzQnekWchLQry%-EwXN$!%XlV(R{B@qLwLgXOr2H;tqqk>Wf&0u zHjwaCIv-eR6)lKee%P|2&nv&w(ZOr%9!v>Tih!fM4Nf|LUM$h-v`qngNIbx-zO2Ww z_2#t|<~P~yTKFLI=L1zN{PeGb?ZXwtme7?I?G%1kCZ0jhx*fbvrF~V!gxWXbs8Xoe ziL)9%YD36Y$QaHKF|zLiFK`N5Vb-=c710H%maN71+c>ZFf!fz z>15ph1Zv;|mZ%u*jkhGqrqG52FqmZKIYGD9xG1}-0?*9UW0!H^7m1-c>{c9X4t_jv zY?+8ilYcJO2fPK_Usa5p)g8O&GR)`BSMMK+%Ln!B3faf&@s`mb+w!)gQ|q6{9c6Jw zDp%fJkEsj$m8aYFE80-w?`a)sgxo#0H^R*JA>bwP$>O*b!8$Sf?<-%ZL_reFfV+){ zE?cck52c^CorW4otJj{fM$_tKFEfCvyMm}d_?0DD!yQX2KWBi!P>Kse2GXHoy|mg9 zK|By#Y1LXjb4z)u#r^&`nDd_9&r4RI;E;43&LqGGSrmIFZP_bo-xid_VB5og1vbkjW#BuFn5t-Gnjb)itTY2ZKoI1YJO~Oc>McamG?fhk1vH~>u{FUw_Ybt z*iY_R_>4c>{y~l2c_Q;tB~=6#fpWFM_aKBASsUHsPowoLiSKv8Ry)!;aA7OnMbyGu z+eR_WoV2!YdUt}(gB2d}2jxLat2|6O4nzq#C;X>5_4NXIeDXD^bMUO2X9Fe|gdXhI zIWD!6qNfP874I@_5Z@lfjgEz#iwX~}S_lkB_gK2gj+VK`=VS?Xeg5w{%JuS>QPVGa ziRLf%e0NN;$B_uA#-QH$xLzs5`-L9%x<;HhpSH~Cc+3Cq)d^#>7A@!)+n>=~X1ICG zBR#w1($e;R=2g8QNgT^oJ^Es!T6>qSh)#lvjq{$?ab-nG+aF%Tx;)-T4nM@)+qzvh zr`M|GsfRf>pFtTccrE}(KZnHwx{-HCRCg#UrIPVDJKKnaHYr-#lYD5@#}}85t{bbp zzgFLRum}rVMM24Y>x}Dt9mniHE4Slp^c4NB8Bo=vKN=s=r|4O$niw>jP^0BsJeOU|8cLcXrV~D z-y5-iUbj>4J?vh~acob0#-M=5(3bm*?-P;#G;9m`Ef#$tbg0Qz6VR!)nxhqVg z0s)4Ova#&$D>N;Vp!H0}WRBB0x0XB~{`o(G;hRNtCri4leg>1~prw(gZ>UMw8Z?de zsKT)QW1)SbK|rI07|EDL+yzJ5U9A)Fl(>J-f-%~2KQD78M)sB7Dk3DMY|V3SOHlsi zv4=1z_`rY63ljPzjqI9R?!TCx{z`Hp`lBsFBu64Udn#8GKf8+p3FTE;!F zU&?Z&P9%{vLawoJCus%{mbF9YeC7MDFWB%DZ4$O^~gJ~qhY0i#LB;xd} z&lHKK{ek#ilN7)hz~+DK-Qia7rkhk0~_~)8MCR%_B3UIMl!VvID{SyHW*vL3@wg zOJDx)F-xC(Aj6vZA0X zg5T$iUneHFhTCPiG?L3xnX~`3^%outEy-c%Pyor*(AcCH#7S%Bqk-IqOdl!(YN;+JS9aN5u+ zM*$G~^GR2+O1Vd_fGPzo724T$(2``Bqp8ouL}ojuWHK-y@s@>2QgF=BQuiKfL( zZQ2zgrpO|U$1JO}ji)|q5DCSi9TW|w_;OejA<`r&kUK3}E#%oF-Z*zNPHJAr5@P@c zaQx+q4Pg;qD+0H(s%0Zk?_~Y9T(!c{<<0M*ZGRh$H=wQ)ak87IddV{c zbW5K)qwG?soGyoSy`-N9pEvrRZWk}gLV%mJL~Zon1<@Hoaj<_7NX!MA29QZztD6GN z7y*Xp#8ksIO()VK-QHvDmgRB%k?S{l67!6cMI{DtmscQ|zSsSLN_1$+MT8Pjk|-5Y z)F{u#MUV5spy4*i0nMmm`E?fGI}T{)_bx@vRL&Z2~t+Mewp^bNEFUaj4Vrq?@X{$=<6?5{0Le22k$|I}>*Zss@(zAZn% zshdYyHGO=4d(LJHhA92+F;xp5$t=^6u^1d_`6+qQo~5kyYd6nA)lRaFsI0P;&a_L2 zPf!SA42OAqq7ve6RLFo;V0+k&HOyAo`@#gncF}Uc9B(Ydw|)1W1CiUnTUC`l$Oqq} z;)S;2$>L5@c6!pZez*VGKL|Fr@7ht&Aw%Jnnj5^Y;&M7p5seQ|<4Q-1IT8>(voSG;ETRfa&33~^>hcaZCegEi@LyO*o zTcn}4$$lNN{#!!|A&+PXJv8gOM=L>VU9Vmv%Zs01Q%_T4uv1GNQRsUNbLsFlCk0s#tGY!)7O1B&LOWEB2si3k#)~jfqYvQc^A;WZ#FzNJwSEQywJJ&mzE-agxKxcy&F7}J`s6~shL+Pm*zAQFJWq8ocNvYs(FgC#)0sd+L8MDzP!_D1ia)tlDAC2GDp z^QRXBZUFE`Q>E_2ZbU|(v3i8wVnrZRU9;Rj{1+E&I=Cwf*440AUQB2<`hk=0eQoH( z1GKBK@cs4e=@*~lsSm_dj{b)x&1+60y*;|DP$3zH%OT>YY-xP;R-Ui_n>ijn&oHe; zU+dRJlI7eL_nSCaWLNXK=hbE2m~K7ae;TKFMTibSaGcCiuU?HKxvOy-?lR-Fa(g?J zquiWKT%Qzie%jqya<|rB9m-7#fsZuL%X!ted|xh+A-+uY9EGn+qbf7PVX35u&xZrP zGLPd%gxpe0Hks*WzP-(S2K^bcuc;@ayuq*G*GFUd;IuT$anMDeMr9^x!yA62%JZwbc~8Jky7(w^@xS{lyy?oK;tarFA$=QU$rJeoe z+4>qi2M0bSI8p0~Fk#fcnO-973a6%uKy#Z{-=oB66NR$U(^QoA+YKUrK)u5$nzji~ zq(|_~Hd;Ju)ba>hTZk6leS;1te&U^z*(7IqEib1lmJPL_=ray6ff+c&p8h9C?$P@# zvoB6-jBWo!%Xo8G7zQ=}JN)gSP(m-+mtQg|k8Dd!X^B|WTJqAo=C3k%Z?YhGm&%=P!1LNxh~zDDyPvl^USu3{cC|cKpd#%?Pacn!1Fs$ow{zzycWnHS zYb~PftDY&A)-|3YJD=YHoNZCr8?-j&jWmIJ;3>-&s7$Jb;ENW#nxi~g(mYnD-JUhb zE9w`mv^wC~JVav{cr^K{Wzzu_N1_fxOW(S9-N4E}ug%+onYS$FJ24AB7lKsD@tVWN zJ{0AbJuStkYbukXLv{@!3VoqMRL`xb$PNoA7+GcxMZZ(;V~G_eVIFvMu{z18lIE~s zDbaP=CyZMe%Z^y>Ev30l>FQ9fCC7)$wd0hm`|>7V;80uD3V~ibRW@@6x3Vk|iPNTh z)boRrqEJh1Gi~VBAkKk>Oq#oeW{KSruionXTCso6rG>H#Kb&-RP`{7;Bd>qGd_X=77G+5fv>oK+vG zv^k`I*JZ3X5C14e@DSKu@S<*uM|f6i>+J->&v%OXJaX8LiRJa2#EJ1C5ZpTTY5SyF zs~wqH_1IRf*3ZKdA4w7A)0i;Pv-ewWZu1=sr;0+RB~g6H*d2hZYI69goAWy`HO)Sl z0<*+fW8~09N|ajM+ltU1&DV}cRJ=F*08OmS0rcISHQ*$T4$u9dzd2&{A3Lg4lw>jL zvceIFwE?)$&b5o4SKk*gXP>t)9eWRdojp-!S~g_|Oyc6EYVXz~QI*1$hc95Uh6Sau zq_APvoG?VHA%WSlJ3ZB+H$PQ^SM)A&P!jxx`v>=rGXl+mlhuYVK3eZwNaaH$={X2@ z8{m@1zi*vqRCQ5M)|wjvI{!uHq1b9}{c!r`#&xC8XK+{;(ne(kN#qq?rO_xH_yat& z=UWc*u(bL(KMV`a{Jn%l!Z2YRmh-EQ$Iv}&iG{_Q zK=c^4nkQU8avh7C5=80_GAHka=Z4(HHqRkz;_#VpK!fNm*>jh?-orE#b`b!n zzOJqkbLQl!5z`+ET#sct|KhXLtkdujLO%B;sB+srRgD~_AYk!+(0`WpwY2B znVG^}vf0n~KeK=9&HDRW$WzvNx?5DeERCC$kJvJw*Nc%&6#YSCWmZ zfJJ_o@n+(oG4bH7Jx^QnlLQFA_p^T3-7`Wre-!96&+8{=bHYbG) z;@i!7E*;S)N^?~qNOx}6~zPBTYziX;swbmT$* zwRy~(aC_^c^CFSzpA6%!1l5J1bJ3Glt}rPlYcy8Nj~1@=b}uiFNc1Z>_8nKo58+od z^j48IvqcqdjQm~&Qmfl{EL~9yeS#NQ*<;n-IGd2&B~e$nAdg<-Qi$lUxcxU-hxyH& z0=6DqQX=MC+*!ZY9~b1E=^@IWnkju8qCkjl)X0WA581kiy-G2`SZ^DKH^-?k6%Hjc zEkriEegu_54;^$Y*OfLI>nDV`Wqx>NI4cV1ZNkD;_{=xOPdPsV#Gu{S70R_)2=*FLT)Lm`&u-Fj>^#D8VsD0_2XAGnb z*;j!or_DUYbP`~+E%%u*qG=##BUyfr+)Xprz}8ykB}Xo7JVv3y(4%JE@S|P)BN4Wb zmgk#B+_1x54>4er-X>NmB!lO5S@~szbe1G?I`zqsFv? zs0BK^I6mp^BkPy$MmKCfL+sNOmp$Y@nOCUdzeKgNQ8E@k4-=1wC#;Bk-Z zi0)~KzI!nf1k#A%!G|7y++0!aS!*d$-SnJyosl^PL{*PYX#6@C7o6R1)1V#)_<5kK zx;RuAZB@N22v$MMgC$$KQ@ZhEQ{`?*zGQU#3#jN*VAQ}+?J|6P@i&Xk8C!&!l0~*n z&Ar<)i4uX#*~}fEkXVsVStWthK!gzIYNH4iC^LCt$HK{l_Dw4% z;^qRRiMOhAH0Cv(uUp46obv~MvjxJ|8~O=|fn52vF2KH4>Wu{4W7G`zVoC@gmL{8q&jVuY*P#EE&1%j&ZmOTH`$xf?0#JCrBj31mrd7?!qZEB zQpgr)%Zl9saL_|E#lPFP+5MO_fexuY57c2*xJDgtTy5)zb=VWYvO zyjRe;REw*m`CyoN^=(?Jw)$5^&@PcRnC7LusyIbN7+XohV&m2C-Q{6yrvt*(k&FS6 z{Rf$R!?^t=oL;y`+wJeJcuMLIzY$5!?qXN!*1LviSoTiumP?sO%Qli$z)g7^Qi5~w z!`a1Ab|BLgb)RNtJ4DPGL*rGTZpJ&$M5XFn3l46!o^jQP9NsQP5I=pbyMX@ye6bhq zP`h3$ueB`M_7%kSN_{kLRJ_6i`*oYCFsnx?mECytCAC!j$m2ziimdV_Y!R%f=V{}n zLBL@wW7Jaml>;A5sJNYj0iBiY%)wrKii|5v_znYIT2oQ6tuRU@+(kWiOU zx-|YKef;evyXRl^{2xWUuYjtK)w`rHUxyU9fw#zBtn#W`3#?^M50 zA@j0uy7E+kh({Hvd;RI=9gAVz{8pDSo(){$<@{yAyy%|fbdq=k5*e+*43NRxNDT|$ zH@5mpCEMwpMvTMzh@QTIdCODV4)FRJ9!b_Gas~E8+dq>Gk4F&xUdmp@5w}XdaT98d^u3aVj`6-&rJY| z(r>uK*)5Q0bn0nWGF-150jjK0VGbe+61&uRh2l0$X7vvzZ%hWMPwRMJbxD;BGUrYf zLuPou2b#W%`i_@>TpT_j0gIwcT7IlEZse6S(`VQ*qe3&fmPZuA!Rm9B#&Q00bEq0( zBAKcvIXxZuqFb!Ft<=Ser>`(?=cFQ0J;QE(O7YM)m>%{24v9cT(aDu&c)tu040cK_ z2>jX1a7dhL2|WBy{iLRm3Cy=Vb^``GTl}}Ay&e5Tmq`WJ_M~G@>j79phOMiv9MTCx z1uN<6spJwLC9)-bEg)2p3z1VjySZSY+ zTJ=vbT0a*@QrLs5g@P~EAe5Re%T!4CId9Y@S?}NOHA=A#T(yKD}A&5fW+pKl~F|@mvC7Lw< zJ5k*71R=8;!Wi2c&b*OBnQr|H12nMWT9-9vj6U@b3Fzc@^i9HSx*XB90#!=$xCbw$n zUNKM;5}eUkKc0~Hg4Hg054?ZV;Uk=P4M)rV%2DYMe{G@$d zvXNT#chDz?`7sm*HYB5wi8?2zt{*4?)v9H7fIzrk<`dI@X*@yt0V#4;PhZLX-*R-^G!KW1|G^hbPB9TZ6%!|a?I{{rGA(FqmFBy)1~5L? zQ5}!yof6Zp%jdIEq?|jh8-Fxl@8ZMz4@W8Ki{vPji|4!`_g?HhT^ueLAPN{i4rBtu zvj15`USO2u7_}{XB$!n24)TL`@tJX6RWPZ)r_1gf$y|OqJ{$LDt7xAGe7MHgP5(D! zYmN9cM$cl=N5CreZmL_3XpSuBg0MI2O$MVdAtwsmANztFUs0_*XX-$UY^jfqIU>ZNiD{meDG(P*Vq`!^H$ZhB0fLN zKc336jFw<2+1+Vx*xDF2UN{{uoX`!gcPNN%?3Ov_XhQ3~Rml2PzN=tf+0@bp`N15r zsl!%C{@ofZ^{~U~9_Kr0=FG_t(xT^rce~@Zu zYPI5T;urVcHaW}hAOaL)xASGFOzw?%kA#=z6b}*EiKD`jhgVsOLI%a`pObGDl>y50|IjZ~gY)`>S0RVd=yAm(?|dp@P@M@#DwGdOcEj@j?12M0P^ zg=BjzIeK()Wy!Na_pvzkohlWp^->X$T`l*!J#~bLO<}f1{-~GQAGNmucTYxCO%r?S zpPcZN^a$IB>poyr6cNulIQU{@>W*&PE7`zt1FXLb`k6s{QOpOcUak3teU@j!Ehi7m zx^o4!>zg-Y5WN+Y;fUE19VI^od@@v^|N7lJA0Hc-9kp zo=PWJJ#ov)_qqQ!Hk0J~lmq#KfWxjKWMEy>FH)HAWlxON3h>h^%a%mXQh$;14M>BBz50g)i}`ZZV)nbD7&0T= zYau89AXzXphtG-mw%w^?FX8=$6F2p5#ERZsl=xrP1ImXDPTRjWIvtMScZJXOHbo%{ z8YvLjNEpxMh-7#hEw?mRpf0r00i5{{jkab9)pdpXI4#(K8!9zd7c`GN}J7V#;mH+itUdGi1mJy51*#qfV(OH4mfgziY?; zu%W6zZdQ$W6Bn51s@$^N!7bggFC^rtD>EAB)hjSO8YE1m^bl^bB4BB95}W<;3^xCs z!^+2>+|JK4{t{@sIvRteR;>MBk~c2)BU@|JJh=7=6xzw z)?x7hOR==%!Dhvcv$o>D_YfRG;M>?LyUJM4&WZzuyT zzcmJMBou1KZ4WeEjuKpD(sR^-`M|ebN@wkgNgrv zgNRt<((*N1cMRQ7zv?nh9s~@38pkQ|d(M4rFyU%9D8!tqeyMqWE*X@yOT?3TusNd>FX3hCl6VeK4*V>ci{^9 z5fUWG;QGTav*&V}#+K0s1?lSJy zn+Su=qgk0>FDWCI8KfqRJ`ZJ=T99M2$}d5cwbSZm_`+s9#|4kxeohALp_SNLLXeq^ z7i>k)3d|45v+~NefFr-|>IbQ;^KvkMl-aeu=7>*4B#A!6NLAimJN^RPk*;KCQHH1( zf<42-7^80u=o4b?)py&GA^XwHOeE|WWy{8>tRTEnZamiJF-~I<)YCLR8xY_5= zb^*|opRe+h16Zc-zwd}>TCrfPo^G~9zcEv|u%LdOR#40&8eluLdd%DCmAQ_^>f?1T z&sGc=`VG1_uW+vbqjd{VHLHtvf#rS-gGgGmBp>6j6E#+y8s3@ifiZ*=!JR_tfene- z??BvP(JCvi!?-y9&c1txLAxOsc2Mrx69#Sz8Rdy^Y)wu;t=-hrx7ia(9Ft`jpySSF z6e(6aV<>-x0sxi&;gD6M^+Vn^!lvfuU)Bo-S0?Hw53THr48yPceMFKCeag>>x`UIu zsQdkUOIizGS@=TXa0~pG;S<&4HO04ncF4DeBo}L%>8lFCMi=wKBMFr%AmS70gsD9X zi?u zZvUBn%gI#AIsOh~3PhvbT|M8PP6p|reZB_JHFnY&&XFcs?jsDkajzVr#?9l8rnNdT zks3e2kCD4$xeqxdi0?0`gK*SFN(2?9Y9;c{@ps3t{5H)ty@Zi5l8P>*Q@V91L{(39 zlF7tLbNGj?$gp*4o*uK_5?vQG(fU3Y%R(;`GoGW7M@N%lF2r2#VM?Y#8_uW6aV0Hr z*4SW`-F%fkF8dVsOixw519ZRUWR+|m-Xq4C>CoYpuwlJMyyo#yUO2@_*VuQR!ihV% zAtB^}5^C^abc9_tu@G8DYN!oL1Ca*@s>$*F=BrAoFEb?SYhgPreDie%fz`Lo3?cb>4(xQ3@ zF*3N|>}pqh0-xWKlsZ-ma98LH+Q1SglrMj}_wtg??6;upbM%9WzmCA-xp9w`JIy@Q z(#dTOFTP6ZvIhN%T@eaM;(R{qjI`R&viiHSr_FwGz1t>D`IIG1H+JS_H~=VEZiP zc_W|?Yr)sKXWKkoJqfT6L$wxg*x-WEz8?P%Rc{&B^!tW?t0?iMRFu)Elt_cp3?)Tk zDgq)gkOpCN4iIT6VMup(H={d8H=|+nfB|FFJ%9iE|GHoI6Q1k=kIv6^UFUHe?_*oJ z$}NQFIU<|yR9-}pZ-1m;$_Bg7D4ad6{~kl5<@5;ft-HwjaYzOz!^7E}_rEB>TJtC{7)LkC8Ws-wO-G{xAk0N!4 zA_oyr+Dg7ro_I^JZ5N{=pJ+f5{{HcQSpakoLCTu^ox#HHo=Km6>olMPOzwhKxcYrQ(FSBv)$R!c%TYGFZJuY_&+W->f86 zPi^PJwNUuH{Hga1;?_czktMO=rUr6ZGx-ld=;CR!Y0TUh+gi=?e-xo_xm{r^k{^}U z$iIkl`_j=6fW=$akElNo#TFMEIC-(J!h>CP34#1cX2}^Ji3WQ(73p$~G|pt)@SI~> zbJgh47m%@Rf1;M2tz{5#sl0zMAJ7%Hh>QVKRq5=6lR>r@71N7S?==&6GcQq z6epMwwoXw0^=&R%w?flDELu26qdtV^BhQQP*P6|ar)gx(yRAC4AGSRIu6GOW1Z|B9 zHKJ73Lt^Tz1wSy^qLzD!$@6`~i=PQNz`Hm*{%I7tt!# z2ye8{`mJ;3laXzkp@w~?K3HrsCppoOxxr`^Znwy&A;(o?PaVV zm#vb&?f&iaGJj`;^lN-F(UnO3W{jCzc0iUgxlkBRW7+!<;yKE}qPmTo{q}nO;GVn9 zy>6~qnYQq9DOUD6Lwu9i`1!5;ecfXLT%63XC^1J@Y73V=-q zm0n;(h*zlRmt*0#*R)5!VNA&j3cgCE{=}(WbS(EkisO{`Bk(OWq~s*{T8T1?eFw%B z2TY_3dQ}?tn(l2hto*s4JtPVglv++-hFK+(HRwt%NPe8_K?Kk@{qOVGSnaY1{{Li3 z)a!N*!g3qOm`XzSC)valN+Q`3CLD9TVFEftc{8sTh?Y(-WE#7Jctxpq{O2EZRsUZ7r#ie&e|{RcRy< z&h&zCDafqT?n@IJWxO0OE#I<6%mX{>t~tbP1M5t(e(lr%uOcHY!k43JPX;n=el4aa z5!s4>r|ZD^-5*{hwvUue?88pw#T5@H^Xt<=cDMUWH`er444&UKg2`BDUu;nd z-qmnw$9|g6TPubg=}C`eIJc?1|AI@=Oj>>Iq<*g6`PvCo1k{j-^1?Ugxt-z**0>5G zH=7WfQVQs+#PooxY7@L^eh<1@?Xr*5s%t)?Zz-3Cl^E~RD9-G~^ff$Sl6bn2yM|w5 zV>_7jn+`n>ca1<^m#iYU8{nIb{f))Oru!vM|2spK2n0n*dPru1kZ=FKlQZk`7=HUQ zH5|d()7g2SF;vYSV}vAAq5Yz|-kDCIO9FI(0oUqUTOC}+rS@0h`n#RdvUkXZ6u`-7@+TRuWXv~jZxkX4(3h{PO4bz&Z-?R2-OCzJROSP(-623Nzq0~!tNp`)2~u| zMUF#t{aitC`>0KqV>Vy|<2B8R&+IzW%ck|kL&Kiwu8=?gXU|7iAMo4XM>sr{KA|;( zRN8Ko$inDKm}vu6qh#7vFUIYe2Q6+|Oi7V+Qv<#p;}Vzck#s;+vUHoZCFVvw5T6TD zk8ApS`oqV%9i(uK>foNSfgj~q-qxN9D25miCU1}*d|!Bf5ljCn(JKw7GkHr~>|9~c5}=`tNZ3GJwI}I4 z$ZD;gOoI}lrY}hMg16C?$>KM>Pu4TSqGv^xKyM|3tFMxr4;kXeOQiZkpOKo^q=zWt zBM!fDOt$3(Kj2C(_3|Y%$`S*|{#OWAEP!yuM{!+zL*dUh*=0Y+C0EmFa#NHgy+r|8 z!{nM_mqbbISL1Qs&eaJy; zgeiR6d)%}N(Blpz;oz@b^it$WIV|wV+u4nq1XhL2`Xe(j-1{$FB8SS1?@{7L<+ons zqK0^{0);OopAy_CO5;W+TW)q+nD(;zuBNU9!RJokX~pEKu4@^ou|{#jxv`!dWo2e; zE0KqpiiSf=(eVab%IF3gpPSMWDJIlRGBaXYpkikGy9wHf)a@|p;a1(ip<}m0mDlkhfRh5TH^K2giCh8lH={l@_#vc7KsO5T zqIJND{+0iDR2rVel}N;FmTqIFz?U)=@-r(?8UfuAsgs0l5#wh-=G($c*`wobpFrjm z0pK=Cw)Wof`MJ&#(eEvK_gY12csxHlE7e8s;~VVq0(F4dwh`0O3R?qfvcw0D+P)$o zn~QP9xPs;{4Vi?BeT3vILe>K2qkV6eRcn%oK}8WC>t4SGySXhmU;U;m9R*YE&;L;5 zleMO{qPE4>)7iubB}GEeYebZh4#&i6?cOQs02wuR^nKHAD!h5OPH)G03S5=5pEziF z>6#I8Kq0Pv{&BWR&WyGx3hc(By5o=~k3%VZ#jeCV+50V>)(WaS8#Bz3#4b_K4;)%* zh%bic=3Z}a?zG4W5jXgD0Ydt~cL; zjP2)=j);*@ElAz1X%3|v_==iw()$fINHWT3=lZkoGZvh~aT9;`aRpw9E2?AMg zSM(PTsD;?T%<8E&bZ<}GuW(>q%c289su0kE?J6w2o-5s73V&69XGVkk3U8}u#Q88|eT2)> zrzpx=E*o2Pn(%}o3txsz-8sv;(U>ZU6Kycm)C1uUT4g7MQcN9`zHs_sX8l2@Xi;$4B|Xs#TDZe0hmI*spga{$YPc-DkwQ2y8nUsqm1-^12P)*vJENG2madP_@} zU-pxeL)GYN&j~p~y?k$zPz;ac6Gs2>LkA6!ElWY`^6RgEO{T*de#OdixK$yaAnE(J zUQWJ){!NER&)a`uelx)bsR#I~3}lq+<8sA{q+=^5#i8x*Zxv_d&p558D9esVlojLz z-`o|pdreEj!8RIPj_eHrCFdjwkdZsgvV<-vuCO7ZOC{YO0vOvvu;@~_wFx9@7B7xE zd~rp7&kJX3STn7k-dYhJjxs{|Gc$Ac$OQSY!)&1IE(V*D$~WzwLQouh@4_=|BO&zE zRzv}V$B-Wo#Y_vP3He>uwkQXT!C*txTy~NGu%*YH-ia7dS>o7adC3L__c=_A&YLwT z2RO4J^&#W5&A59bQ4Y^7B++(>=m2U9B>-TtjYV&zBlEQl08TD?9eMZ?elVK`Di#55 z>5}?~I$?sRwYFO)w!#jU3UDtSTuy9i!QRvh0{OV)MPaF$r_y>5tN5?2La%pjnK(0l zExx9l4!IwoqIk^xpPGGb*UO$>e*4p+J?nkf$Kz@dMiOfCT53Dya)M**UQ~lcux;g< z6pw*3RYewIbyui?|a%NBY=<6af9EN=UiG=(X^V@!UE84s=gYF0b20mi{Stp~mi| zpk*54?S1K{TKZ8Me`k}{+;He*5J%%|*eQjVSIUYMGo2+hvLKCDSzk@`L~v@}?phmv zo!AuIY2^*MotF>;j)Y(-z0kf~jqK3T;JdAAbVdRfV;4=0xW^xfLIpx!{DI^1Ve4}W`oB7N&{ zzKu!Lw@}{H-z*1X{lRti%;A}up>M8``)p;gt?B<%ELm;csZ#Ew?zT@!TeHCfSucHC zwmN+ftuJ}0;#7Win{CI>^b;`02G=+qv4={voo<%1KPPMxGK-Ng5=1$7v)p7EJ#8PL zhyH~K*xg=JI@Yrr*W_~{bgC+=-%IE~CQ1tJOG`yb-60*z0#AG8%sZL&M}gw}gb*m9 zsS2}q1op+&ItjA17ohzh5dSe<^*jExG15-NhgYXNA5iRt^0~?=oBV>;I!k;%HgG#O zQ9+aFrpnh;`bP%T;)lFb7W+{Foul&DaS7r7?Y@*g>EE9Hf|t6hqjACP-`2X$HJzzC ze-R)!1Jx;-`VNT2C#iby{%gser!+REX5WJp-0jB(NIN)^%)|CNb9q1O@38V4Z>y## zJxFoe|4HU?SC@*g<;bU{ZbHWxh81J5h#N>Tl!A0LhV=+g(l9~#zpdBT>kVR;pL1;l zs@XM)Lq>U0bVRJ$Pv0)?8$~IA`bsY2o#K{^V}VL2?ThpdNZC#k#$z)Dvd0V&Jp=Wv|@C# zX>qRxEJ1D0O00@z@E7TP8Jp^)sJkw764x*%2SE=Tnv4Ah8UKiz*qBSN-jt>BOoyz` zduoo+@)t@wD3a9aQWvVcF?r;r+_%$hi5Rl#lGar`=YFCUG0|1SHm}asGhV&6=IFnC zSs3^LG~82<7Or`|;iu))rnHqH{oDS5T0Hv5%c1h%zNfhoBbT>x+tcJH;k=UVf9>zB z#V_#G0rfn02&#qhdyX;&N;p!NnlDVxxBrGJr;z9VmG)}YuR(4gnMj)j@0g_&e^MHkaz<;j*P&3 zUtCQtf5!Kod)Q6lmFuy*1k}Ujlr3%1UE4$}?9%ACx+wEQh6C9vUNX}!cC0*&kc`^! z_x}#LCay=k4)^L7Wux^(wx_cT!S2P@0@0W5@qjx`BlHriN2xrq?-tu(>LqGl&58&%gnH+J2fTL(R%Uf92Ov&=2z6hZeMBt3T)^ni z5_(ag0+~u4$p1Z!zdR@n#|n{qUs{_rW=_u11^H?LODcFs6LHDKU7VzhlKL+Y!(Y5x z{WQ}tXofh|bf|4q8-A^xf@b*kxpvLig}%x4FUT_!gw$hj?T+JkMM=DMLK@~6{TJ~zFv{iZnrrd~6E z$oQ(*>ongYY{@j^+)e1=OS;w^n-!2)|I@>ZJm*N^CtuME?DaMove&+oEm?<#chqyv z4nlazsu)_-?nZ6)q6T6|eum`E~ucbI^1{71N^(^aUS?%m`@oPW{kH_^O z6eW|$sTonQj@Po5Cnvb^3sK~*FET3@BCA@h)2%Hb)f>Z|ncMcx<~WB*${~eHBr07O zAMjyC0eqi^uVGyE3DpB?AIr=gO38vpB z2CqhYeqr=g^6ZPn&1DZhB4m=}R9@scC()Sa(>wVgl571>;QJQtY( zmh7ZUX^)7u#@PHK&k?Xz*ZWC7@E)juI03{k`b6kqw9y;w*T5V-$?O9^$z1LLsQx?) z<(j{lz0FwyqNCxi?18bS-|O&^GR`cne%U~;DE)DWiPh!i=l;sCn+i9+5Ew%SY@6Ay zQumitfdBbRDdqZh6umBXQ(bM7$@xp2>)AhAhdU9`x4o2d(vDAnM$VE4frk@;&T^W; zEJ8pdvmI6^$NJ-Ro&FKXv0Fd{G7F^S0XSIHzlVQ0A)@|Gg8yl{!{kMFray18mAJe` zDtT@tXp6LkqMk!@H&_w%t-ogOh&_ui6Z=T$C?nuK@S7WV5u^0S+xP{1@iBz(vVE4` zqEQIh2v-(~_54C7EA9(~fVZS!BxTnxyGPl1L%zHB^ygd5yX zIDYEjsrncsX8F|-_(^;|N9t;FzE*IVU$?b56xuXs=l^-ROZJw9u2dwNl{?2;8`<~`(e|F-L@!a)sLosiUCv``|%@-yw!#wJ-YlgMSvA7I? zEo97hLh4()!)ncT$4jo3zjjH3tq&kOU*kFOQb@fhoxI{QRZi-E!=1h+AI)i>6o*GC z+^S7NZhkZ|Ht*+y3P}%Q5p?sPGFw(799SS;J@UN$QUyFiINKn@wkKCR;uTa|+I7X@ z*{};@mfKHNerKwNXdXp7s~>sF(}+@XV`tB~whYPZt+uZko`sBW!~&?{EZ3vS%c8Exk!H`3;YTKUmL32 z0ge7fej_WjkX_pQE~k=OAYIAQH`6)enzQ-EJS{O&`$TYpC&5(gC5Paj@KRTcJ^~Jr z_D$`DxZJzB(vg9vPtJ3BYrJq4HMpY$$HKc4xH#}6X-l%!%ll@B)RJSUdU-H*vX<0w z-?Y5Y-zOaZm2w%yt7Yvmkpmt^X^jjQBjAnM(;ccA_#zK#dAUZS`xA?ViK|oP|Dud& zY32VJ@(L(@KT^Ml$C%h6p1J=0E&hm(;0|PYou|feK?Z>m{%Y24^2uP8Z6b2Zx{k88Qd1hpG2?Y{yXA72FMQ|ZD; zVFRKFY#NB6;Uwpc_}{JdSvHmAILEx(W$9OZ-vr-1S9h~s+-S;P=j+L)s4}Y}HoKN0 zX-egpS#zD2pB7n3%Y?h<5>T@lyIVD#N~wp0m_%xZ1h}2n-=&?+hJ04s*&XfKCGKz% zDPbyFx!nmSjc`=kAJ$s4Y0l+L&VW!(!1 z+Bv4T zk;0=f8k3b`@2%Q;)rQJ2q-t4Pqw2IsUucnVy`Di|Ebj(eTup*7U1ke!xHcuT$gC0` zyJuhKaWS#&ZlOWAk!VvCYan}>Y+(-$GGcYq5OZep^x}#0oK(8pT&wBh#?!&)b0j!? z$Zz!8%fT*0{r~D|PE9JDtGtfz=FOc+d|~cRp%uqavI{W#V6MTa{z(&A_Vh0n0;lVU zTWrL&wtZ?g^;XbF=VUL$ITZ2x{FF<9Uc#GidYfvIBufQwd(3-k^6c|%w@s{wcb68l zYv050|M!{xyVG&UI8992%wJ~87ut@9j@O_S_O_pyYkv=0z(iAc_`Kb(P+bbt?}-|L&O zwp6?rh^D_%98I)u^*bA(zgma*Or7$p5dSq3G?huHZ1Bp}y||`mj(!RkYElBMk}hzY z*$E-7%Z|r5sD7$^RqtNutTFg6T#ZLD$+Ac7?MA7kSOMfwC-I9&DRuXc52|di;RI#sV&4qke`_w>J6pM63oEb+MYVLj;mxGFve?__YtWvhQbTqLGVg7CgI zvlJ>cb8IKatq3(yE$T?pA!{59pKtH3E*W3<34{dzo~PP7|JCj%OCIfOb}{A5Kx>NK zg%AFbq%|8O`eR3ZMlw3M#&KO>CK*hBu{ZD=Qszs#XGjNJe?Xst;z!7<3DI}fo4V+w zT*70{9@0fgyLQ2}cAixLL>fn6;`bz08CQIzo$fk2k9D34z?=E&fKOTI}S3{~CcE!TD#3>o`$a5dCDDbZhGNE2B>yhm(lXkWqdGr zc5v-wAS%n=BNp_0)H^ek-mn8EYBG4dPo{IjO1Ut{l-o0kS9G74S<0+XJOyv?*H?=QKBCpX?;oAROsRK6Cz4P<;&Mmw>drV7ZCwbV zB%QJ8^lR!tcCq_YtPhh}$dyQW%-2OG#IIU|YU!Uhc=`4k?As+ulbe2<(` z;G=3d=A<0HN*SO)s$$r|jvT%xK}Mas=by@s!lxr;uul#WgHV}Mj#h$z0 zc>33G6}0KSKHJABi>mgrJmK8;Z6x(b58YY%!Z1#qG15o|H(xm6YKC%m$EO=T48Ona;41`~5~ z($VYOv3|K0Dgjifp|$WEEu~$`sfo8gbt;xl&c_jmYu<7Pj2MiOlrA;d4%)PSa7lXS zh3#o9@5OZsKP%=7b*T&>+EaJ4X|XOg`g+$BrAeAQ|}Ai(abe3+pFS%bX# zmii3>N_C%3)+1y{x9gUcCZdpXV9ay^02mAun>XDv0Y>6jYe5*b$SyvyaJmY=QxgX0 zYgB%pL(Sqm&i^ZOw8je(cAATcxk0-ws{;gNezQnR&Odj~Y1TA9pBkD}6tm%AV#e_p z8nc6O4E({&+rz_8)?To5lAA;aP$fIG2yI3bQN?aOa`D1H7_8gr>*{$o>jU7cX!#sT z+Q?Yo>9&&{iViNX2x~*ZS(@u3Q$!PFk@mOZhOQCCQyfQns_PBZg zCPFy&uG{uCKKv3`V!e$@({g+x(IsPad_Q(;Sy?xQpphrEd6YbW7VoCUc8i=HkY5WN z@+RPQ6qnP5Enw|@W=)XvezRrCjt%`8qS(~|M(K_1@Z1Y78uZsqQ{Ma+fQA1r;!yZK zFCB(^XM(5yU3Kr^yM0Bp5MF1MmjkMN?xP_%wP&Z@w(B=(|0tWfo+w%7Z=UBa-Y(wt z!SD7T@VT}{Hm(C}Elm+a`uA=t|6hDP%?Q~t?TjC78R*xyo<6f*PoQn-LLzOeZTHo* z$JU?b{P2}xo>^ANFqYLN)qUquM^m4G+BffHWuTG`us zc1`b1Kc7avQ_nnTyI&3vx~8_*p5TT!ShDJm&rmJASQUT_g+$b?p~xeaO_|h*d}ucw zUXieDO;F*(L;R6Px&Rh>;qMy>4P( zr4%#r_~sry{=2#S*DT-xiw#*@n3@>Wy!_5CUqv*No z_i*Ee=|Y9^M@Ka&H;toxer6;`i#kP0ogRAbXys&nCqL}PP~xZ;7WKzlQ8`Xe;HlPeezNE_ zTg6m)_I?`MJ~wWHH1JIrCYSifLjUp$3G|A9J$Yh2Oh9hF%U#I(=96GGtfYD8bI*IG ze2|<7^3}Pd6Z9Oxba4}a4(;1jqI^s7!Y&k;?j_r2*)flqP@}>FF#Pv2rf59(-CiiPc7)I5E zL%bwpxUXo5Y1n8?UGeTdB_l2J#mvj;3?uXvwnrM-6WCOg$rWBd77M1LsN;fm)pme zOn{hG9TxiK5x|b(;=}**-al9VAID6b-!%-zh$3^O-E)>t#p4L{x8n^=KL2^ALC2v| zAFo0ve3VYK$LZ_MQvtOmrX27u1MJ?!<31>~?CbH0`G#!VhSPoFozVGt*0tt;95M9^ z-!$(9nZC?Gh(BI=EJv_m2OIg|7cZphesLmi)$| zczNBTco__Zvm?sb8~bB>?#t1{E)jkYxd$0(+WteN4-kiww@<5pjg7pt^FXJue*OEE4<+2WgYM2AH!~<=d8bY8fxqhR} zhS=}KY1s4|1OZzmVnyzDlv-5BkZto2q8~2o#G|cake`xu1b3#8fMbF-5FB z0`0tw6EAyPySwFc$^3QkJRVf5%gk*=uIn-x`ALEbCwMk@RLyXyK)6n?4{<`_tuI=~?iw zxJH?oRp<+?>#{|MT$)iXN??Z2=+Fd&W$_5%6TVx>Maj@s%ksPMo^z5~jR2QI?2Fe% zPsGwhju|dr9>YuLS^%%Nb_YxV!?BSy%NrKjPfO>3o+iY#q@g#q>)&hb534w_=~m*) z017A0`>6uzO{_dl3mc5MkDh}H)oUoave8gF%ouOs6a3C(+=sYj%yOfhHR#hmCr^JX?R6xv=tm4iAu=p zm4e~dYk>can~cw{v6FK>T#Ar!q%1;aRZ>uC1 z7Hy+tjgId+?r@@B%xeEWHO-buYhmT&eC)l9EI74@96{4pEFHTHh059OVtqcMeg>=2Qf zXtz^4hNDinjhzpPZ8d)U!&bO{tEp*dl=+HR0vLmUtTIX;ub4RVG&*^PnJ_#EIY9ls zN*R^t7jadbiEdJDR*E%COi@~swK7hD%TW2F^kwX%X063zYxh0Bq`5NBQ$h_cdMBp^ z8MNz~*c+%@n-dI0y6Vts7xS*Nm9OpNcfW6vlyu4?etA<6aF7)(^#@Z}M~#-85^mKr z#97d$ZmbCf?=k*o5^9}X9mFNJrM?*{-N4nLcP;s+t#|%wH;bYK}u-Tbh!f6`k6du=}icLvQda|u}Ez{L*$qUc4T(^Xo^nFQ+U0Yuq>fAi*Dts)RIR!>e_{PVa|9-#9AQ>#mjR zeV&eW0Y?Gz0h_1r=tTn%j>WpDR<$CMLXA$mqi}1ancCse*sV@%w>aVS+L!H3S+;Qp zwt3Qsi5@~rMOEejqo8l}mQ}H%oDwGOnVxp5VveDX2#oN@Ym0hDq2@NR)xRQkJ=<#i zw6boB7lf(&_#byDX+`RR8QIObM;Yq72>%4>*<`H2_K+FS!8=0Tzka?}GM_*&M1=C0 zmErp4OEmexTmhjax12h3z=+36iU>Y%wezsWouq^viW3?WY;V72MNXY=XTvVdb=9o4 z0vH*bCuu@F?dQY)FjOk(B>i5LE@4}?U-}mY**9W+-ofxxB0p`<+&=h3X9+i@ANw_t zf9whsaf5>Ka%i5-BhP9k{}n2n0U8!kPw?>cwZiGOk6~Gmw0NKJPLwK(Y9t%wD%ZlJJuILSq-B*#{r4^2FTGODSD3a-4YFXb?L-k{+1P4uIqC1hHT_j zN|Uu4ms?JALpk>^^_|ByYdpsfhmXU^`ebI?-ClTDa0Y_VLuHj}?IPlMW4v}oW%xoQ{@B^wMB?nbxt=rOA5OjOO7uzZ#7#Xi_)|z=d~JP_WT4H8-7&tWlZ^

^g z4h5^3I64zvqTNLZ!xPQlr=Wz8Bb5jVH{}-cesq%)c4n>qPB~7%b6D~ z2wdYAxtB)ni!{7AQN{dP$?76%fhqw+*8bKM9^Bue89vr%7Bxhv#YaNU-)Pt<*KN4H zcR^({n+u&SdEa`Pq3QLa^ zYAuo7Yww!w$J!>&6LJA>e%8KG4Hf!FOS$~4t3Y>bR}|pVL&DapTS{(U>=(nV^5n`1#vC#LeFC zTCdsv38vV?|1(%l=mVD)kAJE4=33f>X!^2+gqtedk7}R($aETW#|F3vJM9mD@iA^B zc_^XA^VqFS!f(Fjgr9v^bNar_47QRp70*U4tM;<&ij35(o_mtKNv|soRYn%Dfzg92 z{(@7I-(Zs`2dw$UO;`RQ)ypL$0hI@~X7{Xq`Ix~o{{jHo#FQ6#5A;BSDjx<)S0Yvg zuzs%VD_cj_W3nav58XFKj?CT1T^@eXFSGRtBSo&Wfv9+oUw_J^YD=w+qW%eoFYr1g z9rJSdNjoYqp%yn=4?n0IK--6?ZyB-orWdvkH~+)f4=; zFs7k<>Al%k-5$i zb!yL5TV`wQ?0Xo`ev%ZJG(i*y#3;H%aTuaB&5-N6MC%VA(2YK40e7j{KMy76WlRDI zp=i{6P75YAWrhcz;|ko7`6q(wz3hhXlrpe|t1P#A&|A)lQh65WJd664Mz<9Fb^`~Q(|2DhPyfspu2#V8UPlC#SBEdaDisxU!=RfQ4Ms+lX@9ElF39LCda$NlpuE(tH_K^FC`?s*4k>S|SG!4Ht zrKhrR@p&DEXdyh1Cv#^BJ(8OO^!z-Z5=BSoEos!h=h^8G#?x3XG@Sl>8d@ul%&Ut##eXo{cU)PF%B6iO75j24~C+0|ljEE5?-yz?Qv5 zt82vgS2^AK^_#B1F%O9RSGrQ*+}A{PcYN-KL$N=Qo9{81czsS(+g|Xzq;XGUt#6MHV?=a&KB%dVgdd;Iuaos)q(UpjxM@m9h64$=#%GXsk#Znn3Tc8$z%1>y zRshZ(Z5t_%SWzFNYX#o)#R3(Bx|#T{$o$y9S$|gvZ=8J8M}P4=P?9d>U9pQYZS9nn zV5uz^hZ?SI&DX!izl-8BbEb#g_@~OjY`%Q z7^#a{z?MUxKUHQ$@lMIy5%-q0HT9gsJ{Gv1OuIz54IC8^6te1ud5i z83fJ3B&9qW0-DjLrODO-S z-COpb3LJxe)%k|0cz0O@5H}G9MPJ&raeA3wz2A*B7!Yg}@FkCI zK+#zi(Zc7o7T^8q2g4wpl^l(#z@3HHwLu#n4o4ne-=%PRe<1@r{V?|g>{Mva_(S)W z-^~e8Wn2Kuj+zuCj4D>F$nv+<wuWL+R4ak!_3Vfk?$$3wF@Fhh%^7OX?bL!Hkw;2!lU)I^j z%1iYhunc^~^y0*o%Ik8`TZE)_laZ+o=9%1w4`Nn}brrZjWR$wHuM60`lwITuK`R*k zJ|d)aGs#9a`lr)}L7#A?n{DJV-*jq>y(%ys_l_FzUnvytdf$sm$oe$SuD zS5~s`LH3{Y0HB*ZCw)n9Qyse?V2TwxEU~)~fvZ>?_}u&3M=dNQ>rA#wO3xJjJPTZ z94c&Bn6Kc^fW*Xb8V$S3{7w}QIWp^#ar#8f<@<55R-a`^D+#Ox!D6$={9N5+=&Q2BFJ%z@m;W+Mo3JfiKcht&a6x7R!16lCJyg(*FYVN~!Ssz^ zbKfDFqvA8fpKjdv0;`)aa3sT=C3;DxUiSF&ayj6K&86}Ou+Z@7~NWPK_f zfpk{3f}Qa3N48Y)lH~!HD`X{{{A5$|8LWcYwGF>ayCzA%~c6O|-5VeAmj-*?&zpf-2hNw(;)QKuTX$N;m$maeHza zIyC+IVn_lG7N^Gko3>$cB0TX-`*<{s&Oh|X2Qf`Vb;dnOU8+84z|__CmZpoESAmK^ zU%KsFCysLb9x&5cj8I#ZSdg*`! z!bDr_a83^2OMQb$&(Gphg_gff!DYF8AKOGZWqdUFOgalo?{@n2$pu6H3o3iU+)qgf zg#HqPA4@<%3%!lo{m26EqxXxIPRhu-s$AjeZj=Ul1KIC6&VaIYC1M+qn+)<$=biay zr%}`mZ5Upx|8Y*U!6y2H6|~46W=3E1;;(oyVcc0K2;RWQ(sPps zy8FwZAj+)Op^iaMb@VYvlXI_0_+ zE&#@16>)9B-5(;TK9%8zeu;xYT7*~KAhY?eM=H0!k47ZAiH&qIK7KykQ#8P}qiL`G z=^CLgMKhvMtnFp*jAQv&J$0=#1tuWD!ESf_d)_SbEdb?DK1-8+zw&1ai;A+di2;G^t8gu_JW!Eol2H)=$5vWyyH} zXn{Ih{&uc-0`?U(sXa%_iP4-aF(b0Ms`wh%f2~cgE2Sr~|84$m*4NnZiJHd!PVU6E3d7B6p>Uhl?=e(S)~Zo70faP>tuU-60h1DznE6hJD@2h# zVi@`9UUs3kK@>1hWZScjc?Jl+_29!0>eFwLGKq~Kkwjd>G(6Q@2?~ngMF)0qFJwu5 z!`ufDqVEEJA%waT#^xjfe7KT_zSuk6b$eAR38OJNJM3Yv)Fc9XS<$^@JJ7N( z#dPw+YVDEcHRmEOy^gD-z<0Q`KnQ4QZ#wTwGJ~2MdfPQGtc^J&TkzTmD2>4sCOS`~ z*hQ{g_qrb+a4aZ5*tu}oG|hgiV*4E49uUi4o9=o#X;@#4R9OvXdrhHr@idcfc4fge z*01;2&8{!07ia^|Uck0ilR@>D7#7XVSbu`QC$1lwQQ2q4oU}x@0x6>AZv*} zIG>H5`%{|HhdYhq;|^T|=%)}`erE?3{pJrbE@niFD04q{bFocInQ>0L}Xn z!4ead*SufrO+%&Z*Wbg48n&IL^=jR>B$j5c{sr%z-d=4|MWX`3a_OS(_GUH((hSp@>J6BY!7@`FzSogAfqwiw>;?Xqb9;&aUOjnGY3 zrK6=#ZT{FWS@fINt@%7ww@#!!MH;;VLCxJ?>hWQo7u}xIVC38ta9;Hl<%)uCI9<-M z7IuvnATG4`KfQkeU@yjRxDxA1=GDbe(KU(6jQ&2Ug)Bcl{#vw_R|VgqZK6*nST@e8 zR+H_cI4sfu!;!;9XZ?QP#9iy)hwB8_JBIT3l<)t;)_Fg&-M`_!Pqp@Fi<+ga+9kC& zZM9UbsuDZ(peV6Nj8HXemKarg*WR&WZ)yv*Vhd4~gb@3r&-a|)&i{~4-uHFi*Y&#g zG=1weS~6ZgV|ISYxQ-7ZqfZvOyn9t^(v^g;9+VC(V~54iEMe-3=}b(^?Ww`@OA6T) z?xIzbtJ^*-nbGI35Q=Gbx7*Y7bx;>p{pIIBRDBkNhFhYFC|>LALr2G)h^L3xkB(M^ zwE3;NGJeqfnDOKJ;DvH0+b#;pn2WF8i46OUx&MqTDxq429C|}IMhDDJ3k)lLXIOFu ze|<#0*pTw@-QQuDij3Rwl4#td2$r$m#Vt|ohwy-4!0-P4APSr4ivEE&Qkrb>lH6%HpevtTs~Xu+AIKS(R7X zA0|{X6l@GuNaq3wRf=+Ur7f)_9HU?~y0TY=b_M2E5{K^3%Q>@ppdt!|?Zy`7F4U!$r+<@RM8^xo>d$vx&RKY`dVw+#L>jtAH-MEIs6E8$%ZJSp!HN{)U{!SjOCGcae-ZohGWoC_xXQpf_9i& zGz0}+7LofkXIDn>wY<;Q<2z{_&*oZ_5quh?&1!Q8uyH#qOe>d+BY^F^(XEu^Vj&R_kySJpGFTR442-$YKj1IpCnEw$Tp6bX;D{tt(jZ;`kbf|m@zft ziDJ{)a+~1+#P!7P{ZL!{q2vv9?tO2_WYO^x4c!(&1<6O?p9?B^&&=P(P3MHq9V!rJ z>7kizTHvrsCXiz9@^DEx_O9;9LAl~n)jX^3iZ8uZmS&u`-&*W%ZVpx={861pW|H-_ zFrgP9CRZQqr^OdvZl|DWc88YiKfkz)+|bryTYDa5XXB8TsX|7Ca-lcKMC&9dcNMVT z-i|0p1gX5afrp+*VC=((*B19Wa)0QUUCXP4~b!Y`>f$UALO3<550L}-{h^l7+2&GhB{w!4}Ts}p02 z4_dOm&^ozwf>CWhh~{g@2|y=eAD3@ZY0aCyauO9>hgbi}{DA!qhqLmy2R);e+)m~{ z@gs33Js`0(=Y<~jK7pO>RWP&2-n zuJc04peR^7@+EYrGz-kUXEIE9M7OUMStzdqDrJ~X+1oHsk4zTFCIaaLeeNCEJzO2$ zDA=5!))jU)Z&;zyE~b#B|4qrL%ukozxPg1jpwcze9dz#?pROk_uYXn?Ok`pAW!Ddn z4-;!aSaDGF<#+cypys(;bH9ybq7GkZW^WT2tTYgwr&q3D@Y;Qab*5Q(oncbkak5rs zc9?G-x^{~8bYQ0A<=Mt|3rUI_LQMPz69>)pO-e6n@kO}oHI6IOmO-(mx-ak!AXuUq z>!Y6*TgA^Awt)I#VlX?J{~g6}_<=dIvW=dhe19+ID9lPkcl)0-X)atAT`P8|Qkf^f zeys`no?coqC@W9K!y!Wv=Tc-g>4_fUrVPy$V%rpX{H>O@5)Qf7kZyRE&pvN$?|9CcS3?lsq=S)_BpL? zp9>?m+Be0qPB?tRiFdz=+V^KLw>zHWmsk%_jSc$o^z+dNCed&ckU{Cw)+^NUX_{x= z?|g7ikxqO=J{Xq4l!(AL_AP3M#ou#dmb4?M$%pheoRaSwAIZZ`ksfu$iHJbxacI5&zBPg?X+^z~wOuW_Z*? zq)}%U$Q71BJ49}TI*~rPgGZ9uNB0T^GvHKeiDV(uMDvd?cf1lKF)IrpjpUB61!U{6 zo!rf)yj~}>=zoNqxzTfG1=<6`(6^)fz1J6w3=`u+M6R+2c=ul5VvnU3o<+(L^)qVN z*FIIww!IMdH&+B(zHuI6ZA;VomTw=W1u?hMa^Mulvc937gCgt(|oSCefa&DOMJ!-ha`dx9 z!#_y5YudQVxLRnKy6X2K#Xt2C2)7!(gs-~Kzmr8D zGRUN~=h0g!dG+ssO$|{5fkjlcmz0a@+av*$yPZZvtae?xNGtS`D-d8CPmueiwjp{L z>+?l#*A#Q%@+Ss9)*=T4`tz~yNu3&$!V<#$O*GaoX8TUB+4x?u2Qm+opHKo38tojW zh^#3RK+J?YFRNPnX1ZH`-d=8Qz4njcMz3uDQvo$vMn2NQi-&t_rN=pVL_zg=VS{bg zH2U^b!_Ez{D^S+Q+<$++rMN8dy{as69gI;=nbwvfrXIV|Pw~xBIqHIR(;zysvzLRV zO7|8`IuvSP0p9v@Yj5vz`UJxG?FU;@o=B>Nojy6yt{SwH@K5@QGPY8Kb*WuVJBQ!J zJDjUnBOD}W!c%Af#!FMyCn)H&^kw01G0qcVC7U?^ZOdSOf;JZ+NmsVHP9OiMwO^r- z@MI<5oeCy8O|cF0e=)@XQE!dwgOu9u{FCE8B*XS{)XLm!-GH1GpMH95Lu_U7g;8)p z=~>!B!d7%aBulBXDBj(@)$iQz3dap}z6cLAf)*OixhJBO4ei%vOK4p_YyA%nWTCVvsB6DIjH*fxtC1gq7ab$eO5m4m z?qYwZG=IYUY#Y3O$9}-Tv}sKC;O|=`EbL1B+k0(Bs^PtOCoxH=`oCus&i^EJ`2Lw_ z68={2#mw8gPE7>6d(Y3aN;#CF7a09|e&j#@R$Q0)#Qx@41ZwMHuY zoBDnMVn4K6r0van=Sr-#p!sB@^fQ5*B}>_QAjS+mx7DEfxB4#@ZQgp~4?F#b#^}uE z;{G^Ng^9dQ^*H>F&`Y0mvfJ_t6(n2>r?2V@s_3b;pb< z&>d8|-O2yPhR3u^4c;TRP?2WubRlCGW=wJJg29h9-D!zsh@mURklpMkOR;#5ai^8( zJHG~u5(cO$d0Ns@$Nj7B*>;4#Uikrl9{z&O-+hoXH!!QOgsIBhltfDp4XnKyscMEufH7Ta+_l?jL`byV;Azz_Nd!A?o)H;26bW zj&WK^6n?BA7-pN_sVko5mhLKva}d&-gUt1vB`ifn!O1)`4K;=^qnL(271fy!rVMMx zNA7oYt9t1wxT-67< zl#rPzxLcqQKw^BFKoN(pxU0+ZEk9X4#>S7y?sZ2Rpp194M-LSYZCfq||LLZsjavBm z51uLY`{CFm z?N1t9-mi9$jRy6;Irvn2{*&fs2a3_z*GV0%My8OB2p6fLIfI|=(9 z_wNKPQvs80YLm`<2YAwJgokVHoQK~Ay;Xyhc+DiEjRh3 za$@SAby~y3>tu%HKk~se60&_AFLF{VEHao(8)XsoHa9>$O%;B4W=z}0W;T)L#n=Vz==G*oav|s9B24!w^2cbJ&#PVpw~*lCLzvagh0heayfcU~&0gtI95C53BO(FNkz0>a(G zoHNmjFNWXgQb-MTSN&>(tACi8%`R>=%9BxxZ4WbIs+@Zuz75^hKy7L#(yA| z(&h1H4k;pFv9$ze0Dk<<_Zt;H%KhQ6diK>=ajqx#Ic>59FXf+n#|_RNcvX4UXB@NY zHjOJ!!gtv2!6%H6)>0{_Iv1lmREv+Cd9AD+E<_D=C+M5JJPCX1&VcDDg+#Ajvc2DG z*};Uf>_M+qAbR!;Ir?D!#m_KV;!0$?w!aD4-K#>w`LETv@cPipq%!t!t;_SRMDG*k zsgLq?ptoVyT}KAqfj4E;w}yv;4j0>WU=t- zIcX(Ah&RBg0rz}(wRSv`*|dct=4Fa}?|wm<_7l5%HnuwSiKPsU&?SmRLvhV8yydWE zCvjn;WDT7zAFSsEi6zIyFUzq@uhL#j`Zj&G+HfWoIEv=L;gg?9fhN=}-@$u;a7N!< zK4EJv(%L}A{HromCciBXW#e-weD0a6dIupa3?SxmLlmmX-(3ybIJ8lNP9zIon6CB=fA-39diH$d_GHtjRFh^o{ zNc-MGTlokTJ-71W#tRkP7hV5<2{R3C^%*uNbwx_xUKP>~0&L+EWhz_cveJqEyXM0# ztV9dCJa4C8uWhZpdk!vz9ePh`rHZKcn1Q!M{tPR=%~{WqeEZ*l!;v{R45 z#5>`Hk7?szQWLUbX7pW1G(}?2uxJ|nzh1S&he=*NzRR|C(fIL{jMIT8DmbnQ!d)&Lm7aleT zLQx&D_*>Z9cSk3_q|rJ_xt1eu8m`1nMZk~24vGSv?2IH(JUx0 zuLSX-2BaN9)Wxnd4$*GKjr@cG>8id@u!U(IiPseCOg3o~GKUwYzIvst8>_Zm%7j;j z<2Wj&N6u7EiUH%^to=}>hRuYa-ftTpss|Fj>ZVcFv!w4y_kGTAGEX~wC|iWIo(ekG zR(sv|Ifb)WBKSScuAC>E{h0e?_ko|YSeoHcer!;DIO8bJy=MU(!x;@xWi+yfxH^rEI8M6Ga27~^XNyKa0f8WR2V?x(K1F_2q0&sUO9oAveP&Uo zlBMFx2Euj_nagpWo!CP)7@|7DY z;7hd@)ss<9#uo(86#=8|?5n>ZfAqJM6NkdEaBB~yGcStLShD^!*g1J}@RyTu?XauT~wj71Jx9MvG>dDOqhp|CFYSp}IS<4y^u z5v>#hGI@^7{OZX03hoPn(pB>#uVs^hyMZIK{@S}MBA^2Qm$!#QbnL2TQf2m|^q?68 z=DE9B9S=J5aqmUciw>**be}}9E7IN%h+1#(#OOVy#V{ET1k3vP7`JH5 z@R8~av)ckDkze5^gDlpJjJWfQ%`OJXVs(&Vspf?2qhqYepIPC~2m6eXl&W&!z-$Rvu1--t~Fj?vKv~AQGKJ_NG3k zJlLAf@O*h#tuTL7XvHi)HPnO4756Zb>VHF`nS@mZQvkr=)S6)QC1rPa;%4gPShy{0 zG0D+D>CfZ5?WOvp$WB#&m3DS*;=|Rw`Tde`Fa+LM2Np%zrfRKO5(OSJX=mabzeni0 zRTnS4^#~1XeLt$SrlR7~)q4 z`T1#}C=NM>hbr)1v8vJc2B9{$_O)%TGDmeS(K*OX;yRW3H zU=NgM$@u&rqO<=J>o?N$9#hE5?TV2Js_bjr~D(-s1a+j7U9fmxT z_Ewj`7p2y|}W zYyO>D>Arbvl^rzt6l9{@;e|vs9{H%`gLkEgQ~&<^bf39U)apW&gMFHDk#dSBfor}a zl$$3S4Tks<&%xjx8B^eW9PLvx#7Ck;Kd!TT#*@FI2RUc5Fw2_T)I1O~q@&e$K zbhD^tylyaPiElS&$EZcHv`t#VWZAHkt`u4qoJ0vUKZwB4RFo|1t605!upTBpk#h9* zvas1HcUNouGw5>sPlJZ1L?qJ^ef$R(>iq$BZh5eIQ$GB8yx=TF!|Al&H}Bi+iQRs5 zk-Z~QsXs0S-NqYmH(XCu=C$PGDo=b(ansZV3d5g5VxvmWg)5qy;a`!@%3gN!vVc+Y z38zP%O6EhUR~VdAg6B8CZv$T&u~Iu5U$bBoE-3e>rwqmjvuML*7oWWI=|WA z%T=y9a~xQ49sGj77A$3yNn-R*drmYL3CxXl^j-eBMkZ>@qXS9JwoRlMuf;U2^l0MhL5{&$ z)65xmwfp$Fx@b~=``OaI6DnDt6eD*klIm4)>ndiM7&Ed=Gl;MHtG9yx(_7gxovDl+ zKXTWR4bxHjA1wf=p{8HZ;68G(+0PRRz>tS8hG-rBt;>#V{`$!xOw@#w-r6u=~ zCh9*DV9>iRu$THY+Zf^DqL-eSB8gjJaK(+ zoD)7BL*AmAZV+bEg$pJU+*bB8ie89WGifM{rWkSoM0PxhC4i7^J!i&6)(XWu^$cIM z+@3TEx$F09qw~0qPWG^$LiwayVT^Iv;o;0m6!7I;n-eqn&0@x^8r6LxpdwF-aeSUm zF^`dAGBDlixWWgGt;hK)og69bTWmaZ%XU(_g2hThPR5xLnSPf?=TsJuj!@LJf&U`s zW8V(v;VJaXs2VkvZ(Q865V;&%MMS|;zPH1m{e;=39|fzZmUKCZejfEtnVU43#h5TL zF;B}90|;oR_wiY$M#fg(LSY$~hF+P^E131Mn||TEzo*4Ph;$~rn|+O5c`!E>qtD3I z_*QMB2w8N$+|lJ}opLFzpsPuq&w_iGyvB6sDU8`r?wq)0QZNnQn5O<*6efFI*JM2&>8|;*Uu->O!19SA*zC7=lWWKpz9Lm%5aGhI zw~8jFufU~_dnS9FCyu5X4(GP-do*ikmjkTt5H<#eI{dz;XK)>~I;@}F%{1U$AiI*I<7aX3_tijPSdE-Dj$$N?dQJzfqpn z^jvp#k?A zF?&TbQ$U7EoLopvkX+C+Mpd|ZbE!0Vxr41BCYJ(`HRzRC6I?*q6fmEY4+ow!gV)4y zeQx__La(frqy@wL^mMx8q~nEs)4FUQ>PjTw&K=@8(fuO`UY;5 zrsjf;HO;Gw6Zzfsqe7zn+2d+MmH?gGOx*HlJ4z8H$2F{)vgdl84+2OSRs19;*_HoE9q? zE*?R2T115|!kAzDV8{MVX~}dN-@#CC*x1MC=TV)S5k(jpc=^-fL%GyNP41*-CmPMe z`Lmma8KAnm&pdT5#zM#&v@&FOmVT7G8EQ;>;;p!un-9^};g-FmTK3k)weNt;mErVm zfFiQ!^xLO~kxy@+nP0L4I^d-!Sz4g!v+-6ZzxZ%Dc6jgpO=qGa|E}%AUB4X5GSwFI ziqqKzCxzzIF0@L+>CgzsNzED2tIut}vbWTfFvw+l)e;!~P&18|>y*1rY*MDlGc_{Wx4Pg zzFwbO4`*Mt;MTg_4_B`9Jy^b2!sOMPXHGRhmye;Kg8)AO(%zMZ;_v0gh~%GH`zx&N z>ibnA*{LaQ((ZKMSN(GPNV$(bjOsNgi~!8HU|NdZJjT zT#+DP!fKXi8qXXOIF<4X`?yY^tk-~RPWC`(4qDJTTX=uQdhH!@p~h#2531PxPnPfC za!Vr5lC!8JY0QAM!}!6xqI=_LD&?KEZee1*#@e)<(@SmL27j})=eF3~pnZEgw&uW= z&aNGrZ&WW(DljrdrlBlfs)eJbu0Y$QT?Yu(w(BdLWoWFy{n2aqJe_DLLu*bePyK~f zz!N*orAhK38tw!cNyjb@fBQ;sRcDG~v9}#_tY}pZOZ4*mf*%`C%oh_{?u~a>A^m(G zA^Z%>M1!&7yhc=xMrv2JPLBIep1^G_F1z44hbOI6$H|2Fur|kb(&L^Jul4P>!mpGD zI{V*w9Y)$ge5H}p6VtjY&Z}T_MqQn~)QwC5Qt%)y1rphw!>B^o-=T1fdpu4K0B}~7 z>3x}xU!HymRbxq|3M|OW*j+d2IR)VzyVInp0G%aKUm3X-i>)SSdL>yQ9kJke#DX0q z7qqw>(jS}jEC*LVdcVXJ{YrzFdJBaT^y8ol0#b}hWXazIt|=Y+Q-bh1@%(%HsT2!_ zKIJDf6{-AF^`Gm^*%&Mf?2i-UtABwZb`2#lDQ!RsLlhRsdR}aL`ia%PXB~K|xgY2e zq`gPMOE8X*PLw@Fgy=3~G0lyU;;h z8D}>t{?m}9rkgURuvdii`~7b+P>uRKKj$F17z95GQ28e&isj21X$5Wn{dGB;z69jKOoMcdq76KWbx8|E9>#ZBnlD?$1|+P9Cfll zd=YE8>Bom#$4*t&0u*M)`(F#jVR{FLBbMMU?XaQc>Z7&sPb%@?I-%K~RBwyHAR6d| z*AGWFAx(N;i;$U+RZoVg0~voxgo{4u&isWGzDQ4d?`Nje)^l9dpN;G4`_3jb&CW>SM?85`u!`SixuP-&%cn9P1OFgF;QW>6I7&)DjC__+no>} zJE!4XOj{fPVTpn-Xxaz&!hl>)Rvk#*N7v3(pV+nz$Jfir$>Jdu5nc!5<-D~GGtTK9 zz|#Ayj1cfwukC|VCE%#VY3&NTrJr)XQx|G@Hx=icP%6GMJEy^)k@ZeGNm%n%Mev&_-llsN0O*Cjo`TA%7+HQh*&FSdUupLt?VP zMdDqH0GAw7N?>I^xgq;9)70lV$!B9D;_!P~!a7=Euk9Z%^UW71{%I6y`C8v^rswyp zywKiuZaS4-Z0n8k`nk@%X*wnM3d@SX_iim}D+?oH^{4!#Xr%7aH0T0rcy>Tf*R~#O z)!Sg7yAj3-F3b>Y*=9EvZXx~*1qlwj6ZelPg~63N7La;_dBA4JL`p54GyYSM`nN_> z30DDb4JJLgfTq(8<-56BI{um$BIown0%zbCtw43G@C}wl{N3=gj;@WIVe!m!G^J)Jwz?i1 zSHhujn6V+CNTXweAA)7N4dy9go*I_F`S-^vPD*jdhco?*F4%!FuzQ$`e9^)T6PBeo zN88qPzOu1?v=E@A6Gms7*htrR=3mw)Y&A1zQf$}4dV;`UN)3Tbps8j4z*En$m!pO( zZP(tah!W^7o-0@Rt*WZl^@VcdWxo*uvJF~j#q*59nR3Gh^@a}JC|9n~fiY<|v(Fd1E^TfR((!u7f z?>(%hpwpg_O}(^8f!w))1%{qm797(cHY&yQR{K1o)qOK5rJ*!BZ(}H`ArBTCm@Y3Y zQ#BZMg*fN=9pSv-4x;cMb050R!oG!l#9$-}8NaIt>E?IhKyh(5Vv&BIDrwU@H4WWA zP%C!;0=K`m59;BbEbQPfi)V>`@`pYK;s(OJCHG3jLo1`nJ-s53rh9$Kgdvfdo-_od zzLT*3g>#u^mh`cL&)a^4bC>(hbOvILzwLW=edQ4{PBPDhEgXDM{hAIm<%Jm@tOSqt z6vUQ8Bl}&BAxNYIH>-`HyNds-G|FJK)^^7H+EZ}+zduq9$#Z$Q{>b`AuP$I7DQ;cg z^*-%q{aEw-*^hQ=Ku0DC;TNU68BQ@dScbfPmGUyi9EBME|@%|^xH)@;q@`X>XK@=AHB3_{u9Y2mNuBg7 zA5|m&*2sJq7e}pSAm1T4zGjl3t!0_m5dOM@FRb5>G27o}&Apc}>z*#P3mL?vbaBwx z{H%04$M1x;zgvgyxWBW->g*N+Bu4O%j}R^1Mtm~UV+TXCItzdj9}nHg3x4Kyn8KBw zJfSa5Zy{g)D?5T8&>Qw3A}AuS=Z%wqQlc!^AAd16wp@QKlU!q?z?-}-=`OX@s5_5B z_;H=}RNUV*a>~Ed4|;0*v)VySBL#j>2CG7Sh&}{NjHDhMsc`rxw#F3mUjH?~k@1Qk zM;#je`FE)ktyFo(DNDe&uX>JU*>Z-%GZ$?elk=!|pof)>2wExR2NvW^(L^XcA%sSR zh-S+QRm#wNE0`B>T!rs9klua%@#gr^7mbzBp&$um$wNp%5Dm#dbSd*~`lXUro_CM1 zZiV3oNjZzzZ~9!gR5OPuTt`2a>fZMHx>{<8id#M7_Z!HN@fot&!XnfZ+au3Q?Rsq_ z!g}Sf=bDJMmbw0APrGjeru6uPfLw?yvHvWKlc^&dhK`2tw5GjR&*XL9#-`UK6r%j2 z>men&f;(oe42 zSPlVln(@$e#@BQNX`CJHqy_93h^(yD{wsc=;D5^F(R(v_F+cE6w?*>#)+U;uH`Qbe z)2eSQiIeZ-xD*gpyu;GQXEBFRgtWxi=J)~pDIL4&tn6-uRm7t%Ls>tL zCtK#QOaMok4?n6;qgpM!T#w(#Yrj5l;1}}CQ zS6-@P4`ol6?Yw?@8oFhafW3=`s`5aHDe83gvp*#gyNFQV=EOKJi{&2muz_#V=*d6N zFF?xkkM@y3P_6Gf=&f8`rgfqIowm9M+m{7qdc=V^dfG*e3UE&99960uH6gi$M<{ofPx>#jlAaU;MR}WA-uEY;CXO=G|ck zqrJltU~9?A5*D!YS2~iKQvO>00>GD_X20cjN=ULk@o7KMnvnUjCa5F9- zYGHqrHfEjjdH4;F7P~JUQ33Yn^|8Xv^K-+v377TMEI!R9d#ksP1%>be!;es?qMb8T z4~YulRO;oDQSD{lS2v8&iaVWOFqBVn^T+juHn zI))eE4o3gHQ~Rtf^C5`Me2D6j1dvVJ)}D_Tc89R|yB|7r`7KN=ESxZE&uFH4M0mCN zez=}6_yLlw=!soCU=&%)&*MG(0oph99}z1XcdIJ1rLXwFRK}r-aDambij@BSK?)6| z-ZF>i4Zf>~j_OiJBV5P>g{_G)lL}q0xo!BLED)cH^-rbm2h(FQuDwaX`pdQ460$(9 zsCNYgoR5ygzu|kvkaQW7i4Q9AY7}AUm5omRia6cWH0v9*dgAV}oN~adkCzpLUr62gLjKh>Qee93`8-p87A5F22$7YpYLtbOr=i25x z&RF;2I7LBzu*6KcjnS2+@)I2Nv~U@ZHFMeLW3anUro5gW{GNn;O9Qg7Fo=o<|19VQ zT3q=)>#c|PONh64iBv#-TpC)U^e8p*E=-^6vTy>;FR-sw0rQ8cm@-jpFwmQLvVARj z<&a|GnQ35S^2EyTZtN}PMrmB3GtCpTQvFao&Xvb;@_F7Hwl7(DgO+!QIJsya_$=b; zVjpy|OTuxD$^|VSYA@HVl~c=+_G$~GR%L&dN5-)(lx#LmqyQT740YW0K@pcGwlxsX zqky)%=qI`GB5fTl#~YY;&e}}qBq z+n?5M4*!1G0jS38>7UnLUJk}Q3_WsPxyf?VOhA`O z+CEW&xRDplj#&Sk@_ayla^oKJ^RdKtLr}hFs}Dloan9;uCvyKNgniF_#`)63`27UA zw=QfMfiFywl=`Ov(8hNoPUunv6CY;>6Oy6q?XaegZw^r*dG_9tXGzu_DQc!p`mws? zmC9*o(+UM9&5f9=Rrx8E+Jb;}E`l_BK|2e&{_pRgXmFwocy!eE;75haHYXQgJh z?7Fm?G8YU34N`OnGu&OO$LB5Rt2<~N?#iPUYtfe2UrH9PqHi{+&4$tP;C%Jd2&QrC zd%ex=_F9`~mn)z6$E@xZxK2*pjgK1884E{H#ET3`2dd+KSvC^?oKuBaEZjR}k)~)4 zTACh&M-KdOTa7X!1q(z-)qCLR9DTX?)FsT_^o6eJ+u&j=-R{E62X&ulL|V`D5v`L& z6`invuxA%Drq04-OQA89d=F38;Nm&dZ!At9y7hDi*}81&PWKP7*?u*fgdZewiV>62 z<-&gol^1Jsepb?MYvtCar%v%WDH!bDD_By?jPYm9;#ecJgYA{fma{^=q0P&kyi1KQ zE%@6|^YC~JOB;I};SCNM69~U@S^t~DT>JL7$A7yTb? zqW%@hYLdd`%s{5I029VfMK3rs4YfSjD8%!VW%%O<)j8o8Vw>`&UaRSWrHQ;m~Syb5`Kmd@eYT9U0)B>@=Tbj~# zSWx;G=&`4o)U2GIktAuz{0tpmP|z8vCVf;E^p*<=9!D}H(|K05LoJejdvH?-YQjALh2g(0-kp)dLS*h^`u} zHT_XIbrf>?`EoO14ghuaEHeb$DDTMGmG%>;#ClMuLEJfjbpbbjpbMMxe@`o% zzmc%VXVbKHjYsGROL%S6PuK|420ty=5is8J#wI=P=pVt=7Zo76mwIW)In>x^>BDXP zicN(bhgCL1ZFdfytIj)cj6EMVx-maNF{^W-o=uQw6Mwi(F>v$JWOem14@I~{4dq}7 zJT@43VjapLqTrgO46c`KnLXkiwvl(**Jx$&p1u1mx#-r~UO~!?pPo(joWU5&UAhsV zsR=Y!XQcsWwK2!1{Ih<6@7J^^ZD+28WR8Oe*x&`Ba$`D1CpuE>{x^EpFp2{`$g6pmN`74E(!exc0$epm;e{$Y1exG<-o{?|V z?^)ZOEU{8y*+nYX3#ylN%&6ce=Sq1O_S9nS-pW z^AGoPXtoeN4Xu0N(!V4}r@fu9$J{5JJ&rd=ot$7fTb`AEOOeNVt`*Qh^JV8hhNJ&i z8HE3*45ntT@*G}wipjmNs-6#P$MunZ+H4?Ae>$=8w?Aop$^Rv1kBofw3%P7K6QRo< z98)KtsaL0{{w2>0*Lv`~v_iv{sYjd41s`KiZf)V8s7dUMQokY<_YlPg*7f*Qu_xM= zBRxV7l$)Pzybx?i9sqipLj5Op+9kU>Q?vD+3KUL4<%&Fhy}kSW4xEhJLHTna%k0J= zi-E@v-9(H)A5W{k{ek~0HYJtbP}`x^0*Vj%nTb5<4pAM4C*Hx@nc9|iUBT=8k;lDP z3T@aEWHsP?79(2ozCax(Ax@(XYS6|%NoF+ZExP3S=`=R4t+d*u36@-Y$Usuhf?&!wq*>|55Q#E)#l#q!&yI(tT7$RhKz-dWAz`#lXJ4!o)?$R-gM&}}srd&SoQ8%)Qb^=KLE)p3iQ4UHs2_3$sW`Vq|G_UJ>N_QBsj$2^;<~nY~ z&k&cgYI`QKejkMSJW~yrqv7WB&~F!m!z4u^V9%PD{YUKN5o3Xu2Ya-M{EDkor76>| z*_9P(Mi|4w_pfAHceG3YatfWqarGpKFWB@~l*M5#yxe|+`WLDCZP~uGiTk**Uy5fW z3Ut2qp^DA2-`4kz`7|cO5qi2q(gDb^^PgjN-s}kJ2hJPM6>#yLx0msVznZs;WNfY- z=(wV!e~~K5miKAy4xy7Fph`r)pze)@fC;&!8e89uNJBm_*sWUnZifvaqIGA5)t#7b z3;TLId{XV71=plw1Rf1c2O#uly(ec?X#4cAYTp9h{9#rz-i%jHp|J4D@3$Fe=~tg% zBxfMI3jl;RX%kKCn1>DvIQ+9@h&WE}i7;+r0<(r*oqmy_#l*_o4JFSVdl*HH}G?+4E|%-5KD`Q!~RP%ku`%s&Wtq`UAFUlp!m(@T)TEt{V~09x>jx z#|1re&TGPy|4BChhDzR7=nL0+r4PghQDmyK$WaE=ebr^GaSXl|>}6W*m}mK_O8mj5 zQ4lj%!O!^icp6B@n(B~_g}tC=*0r$J2MhY+nTk2yrfDI`VYcRcoPrb;iAoeSnVMWK zgFK@W=i9ft=GHUZvXm)$sN)ts`c2*Qv}+8u$jGwZ{8`|Cug|~gRD16x#W|s0XxgQl zTmG}mgW#9EGL6`+Q4=Lq!$OIoLW9?a)3Wc5LV`a;@uLk+&?Mz`r?9?Ke3-S&U%0{K zBy>TdS?lw^l3MM-g{aWJOa?j-PN=S!rh!VjF`)X~$!RVB|3mjv3pOO!d$@3T;?>ltSJP7)wRQM&hFZG!Jo#y5`n5Q8j6W2;t^cm9Nu zKN+Hp9j6M!tM}D{%h=jJZiaZQ8$^p{s=7z(4|4d1D!AU`@NU2-d;)C#X*NC=3R+@(3u)Od;VSyT;zn0_G{=fcyti!?8gjC_v6O#`o zl?7%0Q43jkVRii~mpEaNvVaJ=QB@*`u(R^Tj;@R|Z!F*q(}Q3hIe44j|6>8v$C?Gc_*N zZXv)`!#vQz;LSXMF{FC2RWa+aRaZH0146>ysn|desJy0EDqQJvh>0A=z{^zYg>quT%j}vgh3n#5y9#tx~(g9=Vs_(+E#UqNZ!ZM}X6{HP! zvsVK>l}Pu`o5;cutf7rKYtBtNcPIblfp;6igb2mxss-$562CH$r#+3&VUV;<e*oth!Pco zs%<$Jw)NY9*A}qKls#1)`_jC+^@1%%2W4Oz`>wNS(ZmpyT#OP-QN&q)(aj2#IS%JI z6Y!tWvHS8f{k@00kFBY;_hD_8eJT4s-)=qg@$I;>%WUhJ2b~MVYL@w_ndhS5*jV?~ zQFx#%3+aSw>3=+-*1n>2DAp$@63qs=9Wb!4@kOg#2{ph22##ypS}jbiNxOGYr-DukKp#(GWS{>tyqk+Y zTjt0h3kL`Od+XrYxYr4={S+x|JO6vDOx|O6ibO}u@!Ex@Wksvc3pIaT_RwK5L#*5c z*p>QjXPy5Sw=|M{;`Ux_I-1islY5dgyMvV$+T z-pgr4dRS9f5X<e++_sP9DP;%@mpJW)t8O;!Q-h`SV1qgE1eDwct_0~~M|8e`j z2oh2%NQa7acejG%2n7iVX>oLHz(88*Mrw$3D~ukaTVRwRNcSX0k5S+8x$pb;$L|l$ z8HYbOXXkxh@8|1!Uf1K&41V@reT@7as3-CoEkva;YBS5!I=9jlkF2~LE98UUk3W=! z-;cR;DrSi-g`+K@P}J&1fZFFRK+2s=AlvL)t%!kW`6l2(!2qa5iTDXcSSUm4PESe_fz4o9}9 zduh4Xdidh*S1C$%iz)t_1*3kU#)^T_Im9>X3>)uA{} zs6=*PHT13zjQdlIb356@+@bWY{YG1`oTxfM{$)qWgLmGo_OtgUt^6yjOLbPXD~C2qQ)%BM){K3(P=UROVB-~i(+KcF zO%7>+K09zzE<7}v4SY9?SA~>|#19l2Ie%K+S6OCOUD0LiZ~+r;iLo-Fk3Lal#6)L3kFP7RP( z94oSroTL{sA`imJ?jNSLcysX%%bm?e3=zwWMgYE?zOop*??J9mKM^&$pz9^dYpefQ zu5|;HH)xz9IlSBzX&evPvDr`llDPhE-*0*(oVuRvW+wh>2GxS=hTg}QRYT@wGuz4{ zDxK<;&S(0ZZ~AH2zBv#w&Xs3}b}cUUt|cz4gKsC5NQM85P;Id^_hl*Qwmi17f)f;R zJedm~Ws|%F{RFa*{BhNTf$p)#6Ouvezp?KRd!`&*o83>EMi*e7b$0be`m;+1Z{i+x z-?7z$e1zorA7e?0@e@0Yng~q|WQQu4v+H>PpeHHvMdF{R^i9x)Dd(Knu z>8+I7*jy{F)xlL{wC~|7s`!SLDF~y$`I!Mn<5&maw+Dip^{1 z4eF@LLxLO4wg4QR7>qDAogewv*s$|!opGH{?$HY6`CP1eqDDZx_TYs7`X)VDuCK5f zo?JA%cz!(1HflO>*p zWZC`r&rsaQ*%f^S_u++iqxit2xE6XFXU zy$Gc^d8o#MgjqJ^UR#H;J6w3LX|_01dO4p-7gu2)z+0O}iZ3+JeIVeeizuA0w`$<$ z8$q`sh(CN;-MKtY5*!zdq}Qxpn)f!YRH&>uHjarHBw~9#jm)|3lg)?F$Bf8UlZDMT z%-Zb88njvX7)Y`fELfPi<7oW8J6oKiW&ggn9myhWP9|}#6vqacsSkN@-j2F3DxzcS zOIBP!xS#S0f?2y)o-tmlvjHH;*T}fy#Cj>)&Adr z-f_c4q4!xkQ0F<>XSgy_Gn3DCLE?+!;2UnEDisA&OUX6^OC`i{&yB!M4>SIQ^?uu) zZ(7`|-vjjbz*MU4gi|2RjOz38_dh<5b&58Bk2%q%b+Aff!O9(>cm*`qIcAoU(wc|T zrH2kX8C_6dw;Axz}{9#&B zeXRiDY7&#QF(Ow~4N0z)zz;UoqREpR`;-!y6&na%y@57!leAwK<;fjJ7Lu-f@lz9q zBz1ZlXj3zH{5S(WHAl73A@y~HE(U~N8-08L>b&DKJY`(xn|OJU0S}7^Ls7w7ruet{ z0d;vbMN^~`gM|+POA{93=S?*|#V(~c5*bVfr|TU!dF?qrX6z}jTM!CAjHwQ=LhG}p zO@(9O^X4cX?JJyF30hc~U2tZ-MHuRW_N>Zyf?5=Fujlz5Gg$vJHD>GI{uY*}v7h!5 zH9^KucgPNZOtT%EUMXnKNTCAYSo4H^7EEFsPCSs+rrU3Xs8{72O^kf+m_yNOZxnm% z57i==Kqg+rM<5iWJoVcM+zH|g%;{!3>2f%}FMs6eVwP1f;@=_LSp*EVBpxmD*|AoW z>61ex9Yj|o%^6Oy{xx9{tkjO`qooKuUUtVMo~jj#sJITE{X+W=?%IsF^X8sv-w+sY z;Vi4E>+>1CkU4zL&}XVTSK@x{>p5(Z!Xcd+eNEd%S+fNTG}&}yTMU4U4Oa{Kwh@z` z@)sfz+vEH+4H@{-<^A;Hw|dC}=rVH}Zto4G|4>nMkO=gO;S!#dqMISQ6Tz@Kxw8?Y zb=+5>TZF&%OBFm&x%;|)#o5?6*m=_xmn3p+&|@x*kCXdj^0zbi)+pnKn{4IOm$)=4YzMF7z380r)ud?&bIF5w$q5SKzm|o{j7Z;)nG!wss4};_1N8ks z6rQ#M(zx1Kwl3*7LkryhfOaO*bVzx#9^GZ=F4xRmT(9%Bz){driQkZNH^Yj^6~o&m zLF<8jMHRJ)8)`nQdYb3{?&E|QN{!#)s3|gsf9}FR8A+4veRL`Irxi|(P_3IP)j2M& zlsYchgKo|O3!VlfL^^|_ScyJlv<}R{a$GY5md2P`alK$ftk=hKvua(Ri=UPT*~~9# zwX8!7X%*JlyUpNhHb}hmGuG<83XPP<_fWn#2Sc@hAbrH5XAG(1=iJq<`sP9bohVdp z`A$dvz1Yr$<(FuUO}6T#UJ2;xyZDKHT(zab_+6^&y3gJU+cp8?W5v0vt8_U!dfH+K z6jvnpqO?U-os){Vix0Wv;Zq?Jf5d04cgYKp76;oOOIHl>ErzJUCPUgwzA*thfiTMf z@cIWrr{0{*kM3_je0-{o`R01K)8IA|o@VIcBkMPZIz6mfsE?X>!Dz|sLQV;`{SgQM zxMDI$V$r)B-EXztWf{ruP^UHv%910nRIwXrrG+rIx03G@&#fA_0loh@Aq7il1CJ8( zU~Q+Oc=o@RPMUyI#Xtl+0|9<@3M(e3oQ<;T6mHLy@E0s^-|TQcD@g#kcDZ zWrnd-?1pQiSNcZ#NhH`1Y>4+roTnolxxw#-fT0GMs7`jdO10Gt2@Vd*4wociaa1Lj zesz&-2Hc+?*Uhei5T!Lk>}9yF&M}%^1t===LJxZ)zij z5=)eeoZY7+C8y6vS(L5R_XevR1_^o+lcG=QK4d;DbWEZ|a22|#fyr7s7}$BcmYvSW_+>mcE;R3&IC`|VM4GGSr_O+kr4VQg;k^HT3W?G&0A z5m9nM8~B{^cDvq2Vr0IiPb?uq5HIEZSaK6B9wh-@H%yc3?s%TnadK&@&aa# zIJeK@IxBU+RH zHo0Y=2X<3snqz9E=0hIfOctbbe4?Ww(mPWu-k-$Vd2ZC8GKd}!QdgMN_`2v8V#uig z{OjVanfoof)8S3;fN7$;_d$w2YwmJl=v^6)t; zR=N=<2>o?AeDdyHYVhLaRzdLcxPWaurOw)Giz_8Ev5BbWDO8z=mpOR-F)+lLtPB4< zET6PhWqpI0W-r~>Z79@X>-T$RJE)PQ1U-?*Mh6bH3#N*$!`4^fc1A>tYvP)YE&s3d#F&q_sMO z_ZgF!@7vzg#T#hQ7p$2%*-VkUrs^0ifF!s@q(TcTcKdcE+zVc*fq!W}(R{`pUz5IT z5@<*V)OjQkUhnwjkY_DSUrN=LT1~UGW+@(UjYLwf)EVqV7lPm^l7qE}V_gjzIzXVb z9t)7d8~!8hJQVj_#mR+|x*`cB{Wkteyge^0W^wzxy2Q?zh;LWI+DyNe>8|^Bf&8f> zA)BQ+D7~4;6|ny*bn~anVKm_4V<+p^#E5ndvOsh&vy&c01Bs6=2fiR6IaE9@!Vwc$ zy_Sj>+&P^5X2FQl*fqc1`a1KFt}_woL!bSQ>Z$YYFr9kYIgX& zF5Nre3sJs&M|b$B%6UQ083unba%rrY90x-rWXyIVUC*ZqI@ZE+TeJ~IoTV;2e<0W| zg!M0;H{dY0#piFur>g#?Ab+sbbLP|`Jl;aW@dH99Qih2Y0CnNR_F)>8o_Zs&cR$G9 z{^J)Mc_#gaS75+c%d){HS2Du)@-VQ=)r|k#dymX!w?j2ue9<3| zD3Z)qNnYixSEFi&pVbUDy0!qN`GhH+B)STMRjK?!9ducct!9?wM06N5xxhIFoik<> z^kkCOaeqjlI-XSAMP&RC)9#st8lQ+ZM$M<=HVrM(;1v8^xdB>*&cvEaqvFY-3tC7= zM;-itO^pSO);aXNM&SbZD<~2GNCl^tuD>+eW-vp3O6vh`d^%kU+CK|)JsHB)F6!X= zB`?3zwwAn8__-})J(rkGVmp@%)HsH*UX8K7gG~EErZ-eZgnr|V1>v6IDGGsz5V#ak z9}TZs%l{g-@7!M4o)O^)$|3lF?yoO3-jq3iWMLb@L+@98D|#P zIC?xsz@4lS<(zVJS%i!e7~~Fre&42b*7=^V!Rtf2FT!7Ng>IqlubNU6;%bx*4C599 zs4d!74Ro#48P>Ls)J^POZ>Rp|D%heDWTmx99B6E|1nF}xb8I49s>#Jc`G2`=9C0Rm zt{XHrk-7Pjfh0J!D^K{xl3%2Zw{Tvls9F(P{8H%8R1qdq;zhaFIcDrcENmfhWbF?@ z7Ay>6;STl9e+ph^we}Bi;zVazt*?u2KiJzSs&^ZCHSqDEubVw$6ef&F`lE$vpN`fH ztfNpJephFT7jv2rFBcxU?2B3)dBrme^KDr#UgH852*|ySV5QideFu5Qwla_|rTd56 z}B*zFSS518WFXpJ41l6%4_ zp1VluKIR9>%`b^nzJO&$@4N`?C!)K29K~5ay|q~lej!^hqujFPN z5(>#OOTDYXox#D-=To1c_ce9G$S>t#@Xuab6*<~_#>8=vM0?%AhPo@=@nSC$$=_L> zFAaKjc6SXe4)fNc-t^DWx|mUah(dB8i8Q(Q+pzf)&m%^=m9r0}F``Xqx!*cWZ-w#( zJP)<{rhVdi{A&CwINXGV!ikoh$y}Cw-GWs~ae>4KxyMNQOoPaW5(n}lYdSe$TQh2^ zheSb?i~)|SfWf~6S=bOfT<7T`^{j|T8G5BuBZHsqurqf`V>TTwB4_>s`t^jDw0*xH z*=(-)f> z1VQR=M?C|4A^^!|#@(#dfn`R|g~n$jI%n2}#w%Vox9iw~zFn`kx^9KZ3V1*2Qx||8 z5NF8+<5AkuH!lw|BaASU zx0%vLJyFbj=76eZ#ol(=`rP3U?YezP1+P~GjoJ z=SYs80v0*k!9P-a8DM^4`Yxb#^;8x$v^PBb^^?Fkw-Mr_eUEyspk4e4()i*>YRA#(;5O(oOXDc;CvygJz>Y1RH5tZRQ?s-v=JBsgQlm z8l*eepyz{UEWL>6r!9`PF$X?80WfFrrFMJ=R+pngu%BEdFR<2QoF`??3zmaTx|K|Rm!G2Nix)AA1{H>p#sYggPCFGNwW zH|pN=p2BX^GA~C`BBn7>`>oMCuMFc^)ZR4-19F4*e9>wg%lCsOXf8S!O;rFWLiH|V zSgvs!ePaBZpkW7Z15_N1T3^dhe`pXk%SY&|4J4KK~LyUjPk5ld@ z_bhO=FTH;>gn5=*!&iR&OD7kYtYi#Q*mIAcH_;si-6b-IKjsZba8sxFJ8*V$*BUF0 zEoYDdgLR12GU3#3pW3k>q@*-Dsd&!n;aByfhGc5!r?q8Gma)dGFNMes>Y?-W=M4~> zTzmBZ=Efgnvi}MX^R)U&Rznq!>zxCKUQNs%oaO_ggFUo8YR%=>d8poXE-AAv?DVnY z2p;==+&DLp4zoW~hakB&C<7PW3@3$41yUhcd~al7xPV}WZ&hTLyBzJ|hg#B1<;0j| zvp_F43$gGKwAm}DNaEqI;8^W@t|*D{WWI(skMEW51u%s^$$U>2120|8PPSjMxS73= z*Qid5?f9NZ`HpSpucw{U?tqnZOTY1lmn!6^<)qUNMcJ17MU`yWyAGU%E{9+$?7|D`8A=DM4!hXORrX3NA&Kgk0Uc~?{{u{pLOFW&yW~_k zCh}`X;XIOvb0&Ha84-t+v~3!-IpmhzWnKsm%<#boS>4J13w!BCzy~Lwx{eb%^t;jd z?Ai)!<{sj~;YXPU_mEas!Kqdl(alqpee(sh@>i^DsE$eL1XG2NkWb_1cIA$Mdd<1t zw*FN3;&}pmRT}_;6Fq3um2dR8+U)azUkP!(=&O> zbw68q;Ry=>`~%y&f0PoL$mO>If2)_ zwV=?y3buW6bj@cqMrSb<4lkC&tAb_yqJ5ky`*X7fdYzeHU?TGSb*oV6@6q zf;bORxxbIAcKF#7E0@UI`|M=q7!eCTVv-s0Hp7h-n7Ol6?A>x59LHDus^Xf)au47e zbP(*`LjcWdFC*XlCPcWU`X9hEp&~SNprc+PYzIjTqk;;_@VUqmZ5ifbCyQr|YHyq8 zKd#2qeqiF+Ipvh0&iUe?Wc|YbFgX|Qx9e;qR-v&Pwb9qNvmG%FyB zH`iy?3OEFzgb91~u^4Z`dT|4C6z4%ctE7v^g;e6jTld7P!NaJj>Ok*_e_OtDvqAnk z>65pT=yiiTP87X#bsj5JxLK95dZzY8)Ea2nrbRN;B#{DMs13 zUefmCc0-KJMCv?T=7#S^+tS-*t1JHrtv)w6T&B+vK{h&#CtU{9A9WI`HIi_wckKE) z>a$?RzBp7o^f=VtJLl6%6NGhUEZ&oOM`CeO<=P80NEWH&7;IufSjZ+n2cf6dcrfdE zuQG&|*cHn22U1~D>qQDHn<#2bSf0j$FaRB#n$`@4I+J1w+)NPOfFu{Fc&v>!!(WP$6D@aF18b#+%wwY z2F0H{;=%L^Q5`3XKlJ^|*Hq)zNzdL9xx1ki(|5=id>Xo_E}iqrQGXY`Uv*v?$z?si7*o#$$Iy}KhzN;XuFT3 z2kyZqWCGyHhi#9hho;|3f~kmHx&>oN<8E?WWe=KnN>GtO$xzuG5^CG=xEk9p{m%)M z6NEJMl=PKezeukoiwlYr=wXk#U(xf8_%qit9<|Qr50voETT6!SNqvfXwE=B8+5_ZV z>=t`?>_he@z)51;hVvJt{v)NcbmBp+;p{*5Ve#TF65B}9ylr7ji`s-Q51MV8C2ogXNc8U_T^U2icjP{?U* zE>KM*q6UNzBKtrUATIHNDuQV!Hy|>gc*h%`&V_D9pzZQdf}Tb-cHK#W%}5t3VvZGp z-&JKaU7GN5%g|n(PaYuI@2BRV&}RB7^$9;Y&mKiYMYQ*x;=!p>*bwn=2ooDc@Ti~9 z-QbhopY9M7-%+?Gz-J8-l@>-mc>XDa*-e@LK*l#9iC4#XkYyPd4$1|jbX>C02 z#F!RaO=kxIyB0ec{g#v>MT`z4w+k7I!)@NYVr9tW8CqJSn;kh~9D3kq*x^3tATMot zHFS~Tqj~P}lH_y8m-qMJ`Q<8ZAAdU-^c_dCO^uHEs&;tWEw$FKXbHBe5AUTF6RE14 zIBP-I@-LkgY3>c#f`Vf%MtB&eoubzOru(7SoVxRAQ{Lv1+w*2;t#4_o5h)3BRjRp* zX$itYrqHv(o2y&{SanWLTMHS?n_<3HpcUk^uO;{)pzc77se_7XRqBMcSa7xVClBHB zrM(c$>F3A>^PHi7ot_Z=m#%oox_fO<5ZGw4Mh0j~{rZAp-)_(-eptnka=&4mwYQNr zR(3fWwlxTqk)*Y(zB;^_deOCHw+23S#zh10rItn-d4Vce6C4s@sIv@)qbsyP(*iGd zhv-(fXGgXyEC7BiE)u8Qziw_e<1b((Xixkisc1y`F?e;RNu{jjTh`xPVzhT z$%Sfd4e92L)5ynyX#$|Z1mGp@g*Tvs%uGR`S+AjH!72W-FPiLGWt|$ih zGWe}3U3uCmp^C!aUw<^WHmef#Y(Uc&-^Sn;nb@E}fPZ*Yk-bZt>&N$+?*g zX&c?X>x4USl4*AdZAxVAs1XCq&Yc29;sPr$qFp%hO@V_JH_x7#v$47y6V^~WAWyo!0A^v!Tq_yovy^}HSzYcs$%7cu@kdN_zMvJi2KJA4BIr7MjHfD)t(*SyU!UHU zbFI;3Sa^BY9WzNAS;rgxE1_apY)pH7Dp4u;+E6~b^k@z zMg+#sW>r*`J)R&!FbeNMC%~H)39#POuPvE3{mvfLdpWOZ_Pp|Kdo4^k>fZsUPEfUL z`E}rU)I4j0`yOY|`?J1a5`ShXvWwon^}8`D>(YiNkiXu((iac4!RBk~YMku={&1#JbE&s{lsdLfVt zXL;*vDIxbI-VEIPeS^2@gkyG8nqsCp0_jlOj9YpIIa+Zi+v)y(omG0Y9G}R+D6--8 zWhYqG@rk+K12(=#Qc8yC!OyGo<^)l~VlNB#)Ens~2|6Z3*JHvh&gA0JEY{NyupHap z{`4jK2iW7ihcyxYg%4h-Uls5VtD+wzJQLFpWDO<<^gIbkUDub*Ofo;F*1b>Oy!83o z%RHCb-;XyNU7eI3n!SEY0TZrmt#HW`bw~OAYbFOA{YsSyqpeE)2S#ly*yHJ-*m6H{ zVgy)-oKg}!E@}!-hSQE575d z#{qc|`qt8k?{YTR0-E@OO!_6jSK1w$sU7}YT6^epVSv?hck`nkqy0<6;aL2074qQ$8>oa(3 zY)!D=WE?Ld_~C5m(+=+iW~dmVK_coT)@Sz}Yucb(kxtRyO@*_JVD8&#P{`ft_BH#4 z=_{Fdd84R&mXuqX`={leBu*CbjQQmULP~aes90 zFh&R;P)f?Y+ARL8MR7d#Us@m9k4B-Ly+7HZ)C`pikA8nn!z~egDB#?{B53Xwp@=Dq z-!{fV6BH)Mf_rM2J;MzY@F?s^O0`l(%p(=RNu#ZQT{AX=I%!AOC`aX3Cb9zZ@b=b7 zpvVNVXfzK#IzkHk{_V468Fh#u7BG3W3Qff$l7j5MXt5jw%~yA?7YZMT%lk*PCJV^5 zH`WFD6yRQo@kJPa2(wL01fZtD|xE;^MvLimlZpRh}3VV zX!luI&INvuOXVF-2%DPh$uPPU}bzr8^*W zEu(`@iX#&~POy3dv%J!Mk?GZyv1b1+YRj?f*QjEN_Y1W_Qa)K@N$ws@zn4vVOJGEZ zmH3)Ipj@vY;826|(Kt=hqGGa|G=jaii82V&1q8>muEjvks@MhML2C`aUkrviP&VE` z94rl~co7-cvH!hg{P$e(P-sVFzWJL0)nSqvl2Ss~(&u^qerRq}vV2lw@&tBQG|)sf zXZXwTC7xEn9lJ20fwx_E2r3HWmesQBroxt#!U95q2yn-jXU@7;Gx1n-O3EZ#XKnM{ zyCUo_b~48kWeP8sVui@n137izvX4Zy&-s}Z>YJy97cMlxKWx`+!935&UpjKtO7I9+ zeD90+6(_+;%{t^8Reu-$LrkSfrJV9!_32}$Aqw5T(4+_9N?3$TH0Dzr?u(t|zkHR` zH8jUabR&Y>s)>H$e8QQwoa1~s=6cKych5Q3$fl`VZz&BO*a*fk)=?to_DgR~*` z3;yl&^_Twk@bV>0FBajT_((-W%$h>Hz)GMT;t<32k62v4fJEcq+tXh!K#vTomg5uH z_`kJ3&}1X%c=;gqXM}Q}>#<%he@i1~MVYwaMk(W2)J8`%-aG-1RQHeyfz)WSZmTCV z6T1D+YN~Fa@Kf^VI)>d*@u)EQrHl@ zE^u8cM}#$m*><|iIT0^|vau1p?#%PXYB-%@%9U677PFgh{eui}2&$5^JCnNfp(Osd zk_wOy-*~4t$jfFWt72x!qsM|pi$X?txa~}4yUi+g5A*}-j!D|V%JgpzzJ6b&+w*BQ zr0+ZyyrhiH>o^fnD7YTyuta5Dr=H$#U4B{qSK_k6l#oB-OOdVb@psa&v`T8)=CLen z^oe1Fn;W!~H2Y59T>W( zcSOT+QP|BnSEy8zI{G`c=`%ZW)5!fT5oPJYB=#v=)=PPo9>Xc6tRy z=RY`o6Q87!z%i*oRVb>dmW#O2d7^9D$@uwhK1-N%1cA2^B}_!@rS!IYY*3^Tcx)xTcm0c3TP9ab-F-a2Hh+9wm&VRzWU=n zU11Y0v&OjNVU8W@*7}Pkw2Qmj$-_fssFI48Vqz;BL2{Iq++k0&sMm?G!B;6DhrH;s z-+{g1A@jk_>JN2UE>nEIg zjz3HULzNtfDKKfv8kq-2$D+r6H+TxGf&dl9YD;q)hDNu&JX`LJ05^(@9x|K6!*E2* z8#zXU>TAa4P|0H+)vE*lH?OXtMK8Bwk5D@~_dpM>P1Ah8ll=nbuZ@(HwZ^{jA4I~7 zK{b)?J=gE1yyfsQ3^HSGB@&a@`+|#a)q57D=8SQ5xRI`3-v!(d{Ss)txylmOZ=vvq z0Iw~My+v#0>-#9Kc!3X~;VdvPAu_4~#ekrWE|$|D;p#TU@R7fzOtKi5jR z*T=ze5c?(V3%;)~5wYw; zwfv8U6!}ji*x^+|u1iD>Fui7D>3{-SI+1T)Mnbl&*@Q zh*mNhz6PxXTXbqA*42t~Y zGO}L`l>A4uOnQkT=>;z(jnuxB(`s5-`sdy+cziY+d!CD?An#IOV_YzRG+#?144?FQ*bZr!{Zin4(LLiK+Q2x((qfbY%T*V9!((e*3_>Td4SNeJ63d3R1qaXFjJgCcW` zway5kzgtR^vck|V`i#$=w_vutEQ+YkazcI#uPeI1vT-^RnIpFi81E;AN8_Zh1Dco> z&_h+7SRyj9mU7C~jOO3DO}>9U7!2xb(oTp*Y3_mhyocnsr+2f;F$4?RQe6TkrikwpDr^$0>oArp9<;lOj^kH_cWD-`^rpYxuLX@@{iffM>=GKJPi! zQ|VfFdE#KANZPs_tq^a26&g$|PqHn$w~V)S@!1*FX}B#PDL85nCx&IspK|+k9zk2e z-Wlgx|Ff;I9~Yyz8AHVr=~@yHQL z+mTtRlJdF#b4$qS2p-V$bZ`Un*sQeAf5tbT0Hh>%Hd1E`rWg;>Y6?9o@wlnq*EvNz z6peWhz_lG_Bx)jk(CONK5%DnciMKjI2#DHZLHU#QEAU{QcJz-|PhL2uq}#z>sUEPu zc1e?vqH}lo_Ax!N9Eg@SmiYc$kNPf|_{9gOPwcd(V*TTHj>!kdeq{4D_Beh~fnK2V z;@xH=6)HDBB|WPsGuwVS+!gGRvQBZh#Q#*bmw=FQL3Ei{A-{#P+;MAy|AIUh`~ z7Yl!Kum0qU=MNh~4^#d$1YI;V>?_iLdbqjDdIORj{A*1@>4yxp7sLVRGkyv8NbNT?fKv=Zc%`xC+auADa1QWWrHI@CL#D&;KaO-i}UwgR! zG_vR0c2RfcS6frG`9E*f#@bt{Y>!VDu&&M2nB~?U$h%8j@MsojJ1Zf^ADsPNcN>r3 zxPp{(=h5$`e)So4YO2q8Y!vInFZ3Vbi@JQW?jg}0H}sHvaYSBZ&vATQ;WjpH@1(ODtbCP7kbWmqHG9CZPsF(y*R$w_a1jyvfSy(i=lz^#jqC8FNMbT z=t9@dZ76b6!(@;ALW6uLhpryf(W8`)Kshq~pccL)AIV#kJg$TSn*gbi8^}*p!zx?4 zSAAe))|oWnH~0BoFjgegGBagNaX&~a3tOs+E{kx!8oV|?ozcvltoDN++WuAHe6=|A zcIYTP^4nElX5LRZCqD1NK>lsdfyIfL8{PR8eVYNx^I_O?=s>PQSQSDST8M!7mqtH< zACx#*B%bJI#$a|F6z4vv$L?qEQ*|AyvSN|-DZS&C2|p_zyHVVn--4y=Cvlr( zg{jk$0~g`Rw+uAZv)X7OC_18Jf>ZH)p!Sy5Gu-|@$)VP2;8|#Vp)TvymO7&l^c{FT z6`1rYYpXA2Ax-US-SXN_tC|drj#Px>fo=b9x-+|d4oA|`zHWV$LO<>f=9r|4&_c5B zs9|)ppM1AkFxR|HuWm)0LNJFrZ3uMky)Fw$xT!}cbud&iPs8@a)cZe%JM!uyYr#Hc3Pdj*1QZ4F6AESLA!WEvR+ z|EYlWT_R%bhZrM5OqLW9dg~6ksmMf8FB+Lrw4*jqb_Ro~mU_kypiV=>sNb`2$My-j zRak?cxyQCV>7Z(9T!Mnzw>V(6zoRa5&!9n^$CUL$^4P|6*5gi|EvFtyrT}Iz|bhVCz?YI0QN92A|rN;P1*%tRlCh8Y?v&J!jreP z()d|;*~*+px$=ci59;x-sr74r3M(`3nnmQ)?1`;Xg!b^@>!7~+Qt_h%)yzV$1+nq~ zMy+IpXFAaHoF_Wighd>CE0JUU?TBYZ+Lw7RLtxs1oP3-(i|MSFK0PHUV8<#zzc{Xq z+kq+GiB8edi&^1#-z+!OC$;+jSO65dPUF*cTByb8%2Cm4=4ONagCldn6%#1APA%M$ zJ;%pZZ_;6+I)=2@0+!F-PFLRsg6B3^9R#?7-RvltU?mP%FLeAW!i7v}IN`NeKWUhP z&S6)U$T20%3I74UuH`A6dfJVQU)IxL&Il}4O_)m#XD$Ht(qCkUr!5haZ+^I(4!WAI zRmA2iet=exiOQLwcMgXH73Vj=)i*1G*Y8gwB;k3n5Zp>(aptsQ8EmtkIefR;qL&t` zi)F|ZSq_5yZueLqhRXDwcC{J{|m=TD0!Tmb&F6ATID|KF?^{@<+U^yNz&Zq{R? zcp>e@w-YN#-bZ}1n2wOTFsR(!m1#6jbRF7o-8jeAEgq&VC0I_tdl;_rb+{qGr?f-YdI94Q=j&#Rr6 z7@ohtVL&b(TJ(fIYyFwqO<1+#5Ngk&)x{SCdWcnVPEnd};v^3kG**8)ifs;OA(R@- zkXm3F?|^)hh(&yx9po6WifP!i#yl|Xa~gZ1!&xbBo-=50=FS9tU4L z6Ms;U58mBY|I!B;gy2{w7e7G`J|m|R)g^iHTg>>Dk!J%Jnav07PHkCFi?PUU7$dN; z;wptvPGh1W5eKLpC444%&9VQrt!hdOk>#o&*0POU{&O%pbMb=v&+N=hyWuE{X`rC! zUDp(^Im>^?wQKitswM;t0cSJ^c!B4=-pLBq+M%$laHK~OXe_pxEQ*X?coOY(K(Wj| zN)M~kn+|oLU;TKJE8#`}Yw9|zF) z8T?`zJPhvT=|7CX#Q+0OD{ynYD0S^ye091GN~3|H6DHU&MuPVe4;& zUn_1(k7oQ&g~4GH`Qdi&?H(1k@PBrz$F+PuF#L)8WrXSTcVrr)lyX5zq4Ja2uN}oP z2AZyX)|h6Qhhe_G>DOmLnZl7ziO`>yEd;(Mww6%;uD&j-7I=DI4j8raz&Q=nK!m>= zEj@?DhikjFnXKdWfJXcgQN&l{q^+M8d4*78ym+{uyWED&lTA;vZ}RB43|}oQd6Fkp z_XQI+$`|YLPI$KEKM;S}GG?>?)gW_rY?zVLj61zU3yeO1J-syGLZ*tOOr*;`#cAgvB$hVQANfgqjckz*z;Hlt9`V4pQ2T zFQj!%^4jA4S;7_0{{j@1EcMGC~i_$hoZ5-trRl*@#7MJZBfkOE9;B z3J{&<7?&vZCqnN5Wg=ul==LH7TZ*;xLgih~j4bOaT7mK|D^ZNV-Fr|jA()Yr4X^F& z3IHdH3$>)bd&S)OuEGZr*@Jzjol{6wiMO4G3>{LTok0_CX*4kW`IgzcXlKXpL&-{# z{PoGAQIvfMuRd+dH7svQKpwy{@wrn2AZ)l)Q1I;N@!Cf{9-u-{ULZFQj>&{}BFLk`LWlLg&Pb^9Lt zy;57kOm7GZAW2bcNqxQqm`OPYaWEyu%JaVAmoe8%;sJYxO5I z%f~dsittR}vx~G(lGPF5BGrqB>pZ|sUc<>I3|(cx&4F83uhv`v@KcwpT>mkY24S4aVvh~l2$(<#?1!rmjnci zAWg`bVSki_t;l_^^jJmr5|y0?6tgGdF^u6C`DsrG|)57s??qb)>*~uf4xh|kwBcMws%qyFY z@N0JWZ7|Q4KI=jsB}n;`0~KnIK~z=n{5i+4mzz`!Aq=2QREaAshy(GOL=5qmDDHWZ zdPGgsNt7!3a$T+mq2oa`~Q3rD!yA zfoOeSy@;FOY7vAiIETdi1-&JT%^cKs)7h)N;ozc!7X1@4d1-7&XrpAfBC)iB6bQ&b z6$y5ucTik4RZ z3qACF=6(v-{TQ^O2jX*>cX@{Ap=ds!h7dUKdl2xyDBb5fos`5 zOQ#T_*0m@$^_&agiqogQWfoiFs%uu_0WKlPkntxKaGe0i@Vi9X284GUD>km5Br3Bx zkJmXlOCYNZBga4WX9WBNGQeV!yEU>Alas_W{-cF?x*Vtfu5VX3*N_6KSt}R`OU-5Y zENZ8wg-5s<94=QCtrtjv9#uet2x6oTRSG`TMbCqMbWtERG0rSRh0#mm(04xn5y+63 zV(oW6;uc+?IYoP$2$EF5_qI8sy>S9q@pch$Czus2RQd}t6n_&OCR5A?0n=(U` zHL>ceV^Vg8H$(l^1$(!D+sY7{>@T#ndN1S(nK|HcbHnp^9E^MW|1td1H=d+#k^z}2 zTxx4v3SEheu6rXKQUxtlN}j=%Ek98Zj$e*QXWk;Lp|p+1!Wzk6zt~VMhmh08+;*C% zl1-aP%)N#%vvT=rRuD4^x+@#^4ql0_Q$KW5E!^K*b`%x;EaSxsvWt}Gf5Q)fMCqt}>aCl}tl zra}US=H6ub>gfMPy~jWTY)%LC+H1T`MDT8-cqjG8Wv6MdfsNFWU7Hg*4__Ql{Kobb z0?rhyN4`$i!jwR693z$YbCttSV7QU?z1DX73$Qh?pgv9T^zUVm>d>Apq~oT%!w!Mp zfxzc8%Q*X=y{~hFvl;KCgPRI*EK6*sLZ1UzGCeX-(T2{8_=~vSAb%j?^iOX=bhGJj z?dB=Tgb&4W8emx>-xc&sv##jy6)wV!)Uj`9gZGoq!!?je1&tpUlKs~@vtdExG&uTT z$W2v-5T7{@_ymGVfD`JhY>07>bNhU{%`~v8e*y+l@%jx0uJPeMf57f7CO|9V+D||7 zTQy0B(t1`J6wh?eqd%tSO7tws87lNgiu<@=@HeGBWj)Zih z{jv$Lh>o^YTr63_9wL@}qZ(V-fdz8@8I@A%;H~X3C;hII?=p14y>dCv5D5_*`MAay zFmB@fCk@D|kX4iP>g|r}vcUJ7x&ueIrFT7rm4+~}KMXHw|y8f8JS=GS7 zWfoVtjU*ofI6bJszs^OeS!`t2Dz%8|DA$=MYW56ju{teEQ4 zrmC4hB9kQ=m)ixvylKWBvtVk=%35Ell}x0l`S*NE-saPgaE5m>K272zA+FA%)|>zO z?@#+5tMnF;DQdxvk_6TIvis_8 zN5#1kZx2zSQNS_za$DiR(_7^q_pAv|gi}lP6gEvOdt8}_HLEs(pn8jWzmjQCM^O&j z{FRkAJ#AoeSmo882o}Zw#M99KN_wwMBrazW(xADddmDQ);fdfox=XJxVs@N+4^@A} z;YuwE!zL$TS-PoQ_OkuSA8y5t!{G5scaGUj*L8u4L?=nVwtqeWj_wV(-sC^Q9#?Cu=*GY8O zxgT}%gMOLw#K_?DkLzl{ZT0lC%oMxClPBMub?lYkF%B{+$=~i#{4AVOrO5opb&BbA zO4yfk@BdT%@%^{@n-{+k*TjGgosp38S{w=Gg=l{+cyDje&EoftNR=RMIr)7)L5>Kypbv$IWD`sz#{rl z_3r+bteo-1S?bXM3Mvkt*P494Kj$!GrD6kDP!H~3+wh5a5ut7bCq7>tyM4tdNrQ8_ zq=Y7JIp(8`6ez;8QI1ALXD^VtfraE7KYZ9wnokRPI1?NA z%+_&u@bmtohb|5I+lv`oWv$H~s%qX4E~p!quQO;dz6JA9_ljO)fI2O$0huX?cB6Z1 zy!2xC*RR+Vh2cNE3;aY;*V4@Dqys3agmXsIH6;xcmrx>Gkc#m~(f1BYYVDa??I~fj z(88<@W2dN(tL572NfOC3%kS>D1tkjG#2m+LOlpq`5eNZ4+Yg4!zo0g1km;FVXHsU3 zIY+HIaw~8S%3+(&V3n@LGA7w%_2!i46bE!CIuOubVEpxNHKImLWwB7LeVwAjQNCpt zzzjA{Y3zdL6fK?X`c$k=AAwz%`fENnJpgL!1}W< zhW@hr=nJYkRh(kS=C?s zX&eL=YuNB)LRL0+9`g zH3N223CSkAA1@n|krv;Vr-LcPIOEfuZ7lBP)fR~g;^&cCyp=*-|A79p1UuBzx#L#C z%p>P^snSZ{zA|%hW47Au)Ib-l{W5BN)fm(IMgEY&H8BX=1dkw&VIYbJE!!%d0z{%t zs-gah`fbScu;oym>ZKG7QL?m!j`^+JJ_{XPW`_J_2G)R~&UkddD$UITKA`TPhI@0i ztZvZRVMF|TGOGCxv*fKVMcm&+ebT0`e~Rh>Y80?}6ZXuss&7OCEetYOKOLZYIWEE^ z50D=lo)^w`B`P%H{GuN-zeSi{q*mir#Z(-J2ZOEGvgIP~9jT4mOTd^sbZ@Lk*SiL) zb~9(FCX!7_Orn!_HGfMeYre-8|S@!fM`iVKWO`bS! zRr`(ziMv(4PPa0m8-eEeJgRjo$wRE0&i|{ZS_tEiYPuVZ5T8s1A+2?HDu#cLk>rLV z@1}qD7K@U^d4Y2%M^C1>)6r@j@f8#0**D3!7>>$6W<#Gqd$r{iEoI)vh;@TarWQ^b zofc%J&yRiPHh6=xM2g*2BZc*67|l|Ww)O}t;2hKC2g5rmmV9m%nEM6eVt>|KIf9K2g_MaxKLP|9~y9?!#OG?r4$IjIjq!fmx<;_d~1x-qumHZglN0{ z^l~eMWb65aS?w)NG@QcXNGdi>S(#)KB$?E>Fh+uzay;S83I*yqgWE(ZoD zxtOLshCJwcwuP2RlcGoY(f+T8YS8k7hjz?dY#G7Ej>t`RgSxS_$^d~xqV5f10kkuN z+r>qsc;CzF24?o|7QIfzH0qs`pUC2*>N`nP%utA(+?<&LIDR>(E1isqP#YxZqc#VQ z2OJx8#9Z1D2s9pAQ~BYWum~M)W6MZ5p1mANt#`S4?RS;fptzWX6{!IMar_m$&c;C{a_)tILNAdD-5-3f5y^&tfNWjw9mWkUHz_#P0|)*pO-tW7QO@yD zEzi-{EO_1O-fL)SlK*oMo6F}n1CQ9^h@jagAGtsXkc;Z-{G|m=4=)3tIkKCU3(l^w z-sWxKJ%?z>>i$Yyr7(=#{2tW_nn|v%4(r&CeO{juaJec8xG6cPLOF0nnsXWwxVf^1 z(KJehpsR#x#T&->sw;smJ_+>Xd;QBy)((`82C29zj$+75Y;6PED`{It;il$?J5*~h*%gep|5M?eqm(TABh8NV2w_eM*~aJp`|LdZ3Hm=o+XA;0nXJB;~=I6A9vdV@et!ev#Qt1}DsepjclJ%I3Ny5;Xcm z1$%}O_mkV{mcNSO#oRGydoTfSz$HzkcOQ@_nw)_{&R> z;{F4e~a?h!mpNlzB{#qrl_OiheMFRT@#~*Y>m|;qvcGA1eX8 zbidI?&RfI_hdx}-C>0RjSrL%Vk^N!IGaWvPL~pA(5VHC5!S@IF*G>9Y`-0JEe=ME* zsI}~Nrq~yNk5tbW0hfJ1eABVe#{s47eaIMCm zqT5d}|AqR^IN7811=4D^7Jl3jqCQ?uG6#0p=K| z>T@#$`qKDy@8DqlkMMM!vDQrS9$^dK71c{(>X|L0mWIbcdt~ri!~Rm^nD!eOiOK*> z>LaZ%lleZ)7R#3g;4)}*yLT#To+*WvDlrr`*7eY)tvPEa5un;a51a_N1kHmcUb3K4eZbP24H zMP1i|-`AyPuZFKc#7b~($Gsxj1~J;89i+0bOqOpItg)TlxiFY@k zAraLFzI*`^L*J>r$#@9I!V^-QEloP2!!hmQ8#!&&J6j#`t83AXb4ULeEPBQS@_LE% zpkWCQmwT_t+4fxpd$PIM&)%TV9P>6jg9o?!d`2qG3xfOvoDKv$DEjdBOW&)~g27W; zp`$OvThlHseUKvQD3T|Y>jxK`c%d&lR7}0Doxv6vLE`ys$V-5=#+N_<=DU>QA3}Zb zw+Zo-qc+Ua5f!^Li-oN!E3)40YI#(l1ZJKIqJY|;v<)>**Dz<^+EHPn19!FJzWbdD z1-ND2RROXECt(nK5|TGClrGt*B)ZDx&F>S~-olDKHLQa(%c>5?+I?Wfv4DVmCx7jb09|WM7|BKWnvy@|(_|}E)w}*8tb@F3m zSngB}C>G@pk+MO*-CV*}ODIC{z4*yuLuZjIM?tDi|D^@%>YMdIG2$DDwfB#9T7f%& z0B*GdV>1uA-=f|3} z1FFk70euu>^xulG^E6BXX|H<+rB5*WYQ97t!b@&&S*;fWdVH>ute$gTN{2l3Xu|zY z{JoFNacBfD+ndgLj*1>$(r&bUFpUS=bQ9IVI^TL^TeG%qDcF3JKgz%L^A{#bu4MmI zD@a@NA#Ie**ZKuR#MnzvHq71aIL*klkU$`9+V!uB3hL4aSg$em0RB%eBaq3H}sH+M>mIu686bsftQN5(b_ zx<0OSg*ZlD)d8(Our1tB6r@{T&yrw)kn;y~ue=+kIa3%$ftW>qH51VjYDkcXY2=(^ zi3=<~hs(VZpT@wp*9t6L`FcCQyacrJI()iz_zZE4JZ3E&edA%{0V+BDT~G70@60g` zn6TjgG2E;;taiS$|8cx(X@G4tIGo$$SsbM8g8V^=AA;d7#^rjHO~yc+SlrAb6Z@hV z^+}2~*Jlnb_5hc6G{~ZJ0)%TZp!WX9WC1Q0Pt!NQ8pHck*xV{oX|;Ho_h zr;2=Gkz!IF?ALb+E^mfN?rMQit7mie_K%sAhWoW$qM>Fx*~Lw_Y6x&pavl=|^_nBb zr(%PG%}PsAQ`ldy_3}80DVl$=K#*NvQJ@l@Z`Xy)}S1A$>=wb)}XzNj}(N_3sf{kbUJu{GcXq!^o@sNQe9sc-mx%5)YEfM9mtt_=9i z3~mz~0zDT`3I0wp0%eo1 zN@*H6)?O>kW>DO51{MG#{1qS|q)jS-8i!~AA>|s{;65%+eaIJ&0w4k852?nwu(!nK zg%2{5=`d5>4OHF@?5Fwfq`hJUU4E5OLwZq1%B|Ss^NTQ5iI9d3wRe(TbiaK-xL-TH z(8xhv^9!oBl^HvmZLat38<@`bJ7Owpx&X^yt?-p2v9pKFMFAC@JFH~7C=5%vZ|3kh z@?eN1{b19m6^O=Xa6gl)$2@sM3w`8u*x!4WD4+(p7rU1EHgSHu5;g*hwquMuYa9LG z8mQJP^vJOoNkVl?G~09)xd+i5>SnUiEP6wav4Xk}TXZ9*;p?xp#2s>=E&E?SE%~ROpiG zYYmW8F;2E7*k~rm|GlRGBfPo|d^mgQon#95{rGekc`HHjf^-FTBuSKDGq`w9>mT02 zryZ9g7uC!X$nX3YG7oZJ<6&LnyMtQ$CgJ(|$xvjT{H+aFQYF+=GF645Tx@2fj*r6d zb{;#TE5cfxuUJna-s=Aq>N)?VwDSeJvI81br~RcHiBWrwaEK3LI&6O-2vpYPM8 z4;feHZwi$)F*+K?AWaHP8UG`1Qfp}*c#w-iZgLCLZ%X_Xy6px=jni36IF*#3H!l_z z*McJ;RoltCVV~1dMUi$VsYFa4t|8Gdpkh!6E;#)+)`gJkln=Oy5|^yb=Z>7h)-3Mr zqI%)F2t~7#U#4Xh9aQYmbYqgr9t%P0mam+0b((&_j__4*g*CCN@XN#oac#MuP4R8; z5a($HG7O+o>K${t>!%dcXFn#GWTIN09js>%Gb&L({H+zTls5^IVz@_Em0d>}ceam~ z?zTB2Z@=?7zBprRs!uuU5WYlgr3SZQ`rxU*?+~c~ zxnoILmbuND|08H2@INK#kye59RaJfKP-;!_%J#r-hi+9&jMPmaAcPk02?QVoQ|aS3 zj@inv^ctV7mHVkiYn$z(q9K>8y2G5GWO)>JWk*z^HxI9j#*2uq5Bwp`0ROM4;_uXx zJYxDnafNGWdQf_SRA}?o@_wk)I!*9*E3FEGjF0|Lks9Hdg3~iTJBFXfSMrGbY(#bE zm13FRzK*7}rtw8B#8gu8KS0lVm(|lnX>bS&EFk)0Z<}&}<=~Koj`Edy0@-f;PiHG^ zO(-CKCdhOuwM98-JdVOejQ2YIMH%5?3C&DD~t-4dikvVxF`z5K1AE=0+YVL6mldr+A zMX{&xAdzaI)Z>4~JO4zm!Bpr37K(v{m$r00`GbPCoFJ% zmR&d1<>i}7HNWG(SRFvS?L8MpMCpjw@@?XA_pKE$!Wu zr8KHeV2UbCP8ir`vwvy9XC?WL<0R81U(t!bKtr;TdsAk2jCMK)QC8oT#pT`b_8DOP z=oBkQ-+&HC(7x_+Fq_VF86t7*1GUxJ!2sGQbToQUUGV^$4@{TkR~D<@)n15d`lVO9 zE`UIpKG!tol6qi_Jf3sDRaX`7n5kl!T852b%(H8kMZ>o8<-?_45-E*p924_>x3cJZ zqY(I|-O%#Jd(MD-qb9w2L)W-@jqBY5G2UsEaIJ7zm^yT^F~Bt2SCIW3xX<7Q$s;L4 zQY_a-4KW&PVrY2m!T?=yeRDm2^c!9f4_AOX{SMHR%Qio^kKD}R+(dgb+rhT-1r}9} z?ttzz>7my%av?SK&k{l%6P3`Jo4liBKl}cPxnZ#&hleL5KOryHn_sxm;@kLhG@q4R zsZ=(X39tP~D1uiIYVQAMY7#^Jbha?iqX_aO@N~o<%%x+9nxwKv-D@zik_g^mgrU{? z9FiO^T#j{Akuuf(IMg9XM*Z1(-esm(&HqQlR@YZLWJ6wqlPhbU#1{eUa})heMcgTg zku@rt;0A1D)Q^?KNHg{Kc0*5jP(@#QjwL1DZJz7U)z^55B|K4+s9_+!Zho*S)5gAn zE-7QRl2(*`s6pMt@Gkzr&f#0M2Y~Oj!YG(N9A!{grhiBt9IDnyjLu$K=Tdw;-1PY; z&#jGMhGt7YF;(xlXv?f9DWsDl$3>gAibeMMz%5sd4+V2i#6vUxl8$XMdgB+Xp_mze zpOIdkrEkW}M7}T@i)t5N&_R852NV-}X?5Mi(L2z^*z5ALRWO|j(+iPgsXnB=F|8tj!04@CSt!p5?%5AiN z{E_SplxI=Qw@82Q7B{cgeOJOi^|pMRNdrO61`lH>BU*gV+`4E)wfEN&qYec)$u;GE z)Xq!&A*aPGfP>^MLxijE>i51`D4=uCpKiu)|5D`B%K*KNKI|_goU?Q@iO{xlaijOQ zEXJ;Xde7A=?rox`m&W!l&S-oSP4%Zo&Qt>BZAV#GW?GKI>cA*4%-d1K`)Avtsr~v( zCsh$*KmQp03fvj_Z(;Ss3Aw^s>3rw-BXUK#3H$l}Zwy&9l+|yYT^w_5Ewjk2Et^i} z{rNojm%-#Z{XZ>Q9HL}qpFZcuLVn@d$h{5AjbSt=4Z2)STK3hi=jEo0g3SKNFcjh2 zRU`<#VGA>?f-HSBtoUizJFID8?Q2HnheZ|Dmw{C~WK~ZdOa4RB3PSaWS1r(wWcR@h zeTz5Fu7~Ony4su@(+;aOoszOz8z1eBc^N&BPwye#GcN#GDj7V4a#8I+WNetl^A?Yx zi0OKj+p0GmPP4+1ZXn~g*y@ZDMOecWh{h5xTQvwu zj=3%Da+u(scgMC)MJ?E=Z4#dW@<+RN#QViMbjYGu6*E%H_J71grBKBMB~ygGANrT5 z;{*gjD|tvN*nc51U)!>eq$d{fl%@%PiO`$xjYxh@8>+XKoY7K5h@gkYn{FR5wh4Pn zSL)MVZD_%S3u6!Cjv)d58ypWkZYtiYkx87(O3S!M(kI0n2t8AnDZTr_HI=XJEu!mw zlF?UbE_`1wVBnv&J8&*lp0ID`(vMAe^xx;8j7uwSCxm8oN#ba18kdC`!SfqZ;f@>A z%=Izs!2-5S*X3|9rjYKjr__lDe)ejm%kQffvY0))PRmkU zCL!Vh8um6WM4;OSt=O#-&RtN~LH5}_cIua;T7+><^_#_i)&y^`4YWo6XWIHC??I$= z2f0lnO;`My1f;P;4+Tgu`sRskWYX+`H4sj5@H^-rH-uOwqiXB#py|WOX8oyHy=m;? zel7O1FljSk=`{D&O5Y8(d6Rb|-hbV!I>Dlfb9{Nj4nJmnWd3m`b=+0SdqFtT2I%ImFa@9?by7~@u}kQ7S4dIg!6a?= zn$JZw?L%D#`y5La{yv-&Xj%k_10C!JZLnT|8B^c)lN62f;gyMmSgn`xiY==nBWqzu zMY*mOY;Lq=%4@-CP9tMCLBtVrD}AXBRfNLYH)%~Nq!QTUC4)e*SlO1@#k01F3yc7 zgEso%-$Z%O?gVVRGv#yYZJTi^{AfoS_>fdDn)AOU9Fv2PfQ$L)gzwnHDS9TeP#bdl zv(o=BNu!egKk5XhYL+(`%}vW6xg1M;_<*yWV6-V8x6f9Qqq3v){CF52n{aAU*=Co+ z(Xg6=PoE_yh>VzAw#?KM&a5j z`;KlFD^%!<$yHRE3m2HyXom<4!KVI^tDiN(?dVcx#`k+k@LeAwz^U$Jh z%=;iXlKGKxKpO|wWeaDl zO*b`S_@R)(u%5QjJ&~pm26sw$if;U0zM~EDkJ+&)2?Sg}&&$Fze=QEW!GvCJ*egCNg(20`jk)ZI7RrK65KubSG z5SWbB(FZgQ1+iWB%YZ9CV$4mYPptGB{}%@nwF75%n?Kv`o6AhVC!$dO zV-KvyypR7G8TVParpR;Rp5uJj`?&qnX9E&%p5hU}BGbu3k_rXcpD$+r+vTJ^*^wHW z>v3H%-k4dK_Tk>Bt<>~D4QL0Web;gLaVr>pp4S?Q=bsqzVlF?0WC?1JF0mkepALu6 zP~z@*MoD!)-rCpcC26hr^)Om0wSv=H&_#2H%{Jz zaT&_ebg=g9js)}h{kDf%My&bk;xh^=1lD>+UGL8Z>Xh2};`ZPSSSmw!wi=|W4t*uvd!(Cb!lZ(>O+ zK|ddM<~udr>gF)HEHwG$w+xegZN_2`3ovouH{njU8%iH%=+2NZtt@_4`{zr#`g#yo z9S{F#jmhF>b;Xd=Lc&P=Gk|l5nmVYd+J9!e`fb{(Y^O@N#JPNu$gb&)5f?K-soveM z6O|wK%UzG0GT|qq7|U(SSSYC`^%jjOrt#dHm7bOc|JXU8<7a-%2lWJ7EtlsM7T=HK zm}4x`k&Bhnqf!k&yQFBugb*!_8D8`|;yCW*7fGJ#pUq|ICGZHo0)J5`Q44;W6`{Z% zIWPZ(<+?k+{BSY*LC@HIj^PW%GkHUwcZnH|77~4y8>*Mg|KT}0H@N;saW_aT@0Fq% zzjQO*`1j!|?y-p#1%neHLMvd!h!g$%B%b(Fx5A%dPXiS-{nzQ~QUOm0R-o05rCKsa zcebQgBpFc%POdMiG$1eX#A^DtLnJSY=eyKa`sVC_6>DxStRS6?D^zk2&Ij=pE}z-K zkIjv>O{v*=;R=K@#3lyO4@j1u+eIidFz+~pJ17oCEJGNXT<8P*jx z^ZjJRo%C~=uZg!Cp(?B&Zb)kmL&pP=QXai=K4`n7)ieVuEn%DaZlgY%iM-#8d9~3e zTBm%yvs?;x)544KGo#L5Xx1ownY`*xy6EB7m9uV~ELfMzV2N!C!<46lMoP`x7nW+} zA5_)=Ms~mC6q}J5i-JM*^lW$Abz3-n!KdO@9juDi5{4bP zeu&#v3aN}F6JlJ4A-)#SP?YWR=amU_y{yAsLsGv&MicqhR_rtOG)^N*CEjT-`dz=O zmpXYPKN3lTuAvTLX8`>08BmmfWA;)FEO~CFjbYulmi-moZA*Nm8QNyOqhZTd?Q?&> z;;Ec^?@r#~RE7(&=v`i{Ul_Rcw{;}k**cK3k(<{8WFUQrcGNOhhM*b zh@HUd5T^I-ufKN(TcrBjO!F~aId=bP!tU2&3I^-I>PM-mb$kt$Dr`0i=)1$0^VrVa|AUa6{fi32 zfa8WRABn)xdP>A>c=ss6l51Yd$S$c^1Z8Lss1eOx&0lR8bL-Cb1xFB~QgR0dQ`;+F z8@@VG4|@ft`FcXjN%>e<;#$CT1qXv>Pe~YZpzI8SWj^ zZe9h9uq{Bv$y;t7a`#;_)NMsfme|0b=K?=5e#-I~tFJpOk$3}|)%=b+RNQ%y^n5ff zd>9RGfcT(cKV4@uxV$u&pE;vuP;Rva5ET*qU?LR322a@4*a_I~w)fp76pR5`j-EX1 z04hMe%ipWUbOnDm7$Cxib+#n;a(;2LwYyu;7FEF8YkzPg3i23rzkXm+TRU^F4m90G zc|mUJ3s<``LfXRADtN}e%vz?^TMni2CRGOdC$+qJB<0!+Op@r@8kqmCP{)%a#0&q{ zzUyN#A{7rp8KH!zfLRO)kyg9#sI;{Zz}*T3H$|?-9w=B}LP#9(fbrj@##(3dZzPML zcKDZ?S&arBW)wFnIngxXf+*56+|j{md~&7vVu3~f$g5A3(nt#n$AmkS6mL@hQ@(@m z9UK5!f#Z)dUJ>8?qXBwV4U20bhCT+0zD4Zw81{I5IiJ!KVwm)xvU6Z^h@&-;+f|I` zK84HV#EFT!6xG-DfG!zSm$ck-5bD(b)Sr>#gPE6DRUj;FR+PvT9+s|}&a0LCZF(%q zTQQVylbuj@Ir=vwKic%@6hd2b3<7u%CL2PSyy19PUSyh``I1@}M$BFSR(-AUg}6~C z>cTqjX|};Gxi0jIBtfsV-Y&*A9ujIx%^!a9UUFXQ$IAwp9fDy^U{nI!h-irja#v-S z#$`oD2ioVNZyiMsN_JPyId5pEX6BPx(m z^Sw?tE_*HL) z5bQY6+VZ)J-1Lc_>;Y~$iHW}P1)OD{T|YdW`TUnX>*@L5V*XPwj$Bk{vY$DQ*B(|> zY6d}Y%1X#viPd57i~gTjaJ-^##8cQi1%Y|!vQ;O~lOtZh7L&&}WbhAvnDJR6kT{0M zUn&h_%POWf^Ll$(5NsKhco%$l?9qeH7MkL?cgkbRwypdS(mjq&v zgW1|f3ij`4x)uhOj^4OyTEC@1q#`pgv6(g=28%pje|#$}p?y(Y3+EdPa+c=Pi!Xr!JJxZ}`VSwe%@lq+5S zwVfh0G#)9{s6V2)Hx-;YO8@?H8q9R{B|@m;I5piZfjh*sy%RM|+_ka9-&&|HbIcW} z4~ZDaM{rHGvp*W%|AC0iIXph#Tal$`Z&HPqlL-MS8ZWY^q zh4YNW>SZrj+&xbQP{M3)#hc3(5UO9p#hGPOhz0k<-XH&Y+rxLKx@f!wxwX}(zuz7XpxwCyA7!(!J$I#@TOX@oI_=+N(}% zK?=Obn79k{Zl5H_BP8y^N^kP>YP88&K9h>vGvms2gVQKiys|b@Z%4G-B^1|6|HSrJ zSrv=e|JOC<##w)1{9X_3)e0)2!n3U$*I>Rmqso#_Z)P7n0djcXr}&aF?6s^JBMM5b z({xoP$7?$0Bqj_nW=QL|5C5_9YCq$4{ob`{Y%%?v=UdminZsk?r}TcG4VtKY(h#)@ z)^#8D36>4J5y%`{fjR8WfbLTB!~LL`DqXTdHK9)a4{f?cESeL!yqMP%(B@~)X4H;3 zdK)OF%K!3I9L*V@y&Q(&ozHbtUMSltcjr3fGjGTy6w+BYE3bujBySa_5M^t9jnK)( zlIe@hw(KlzbMlyR8HP#&@ed*w?Uj|sYSiO3GR%f**N?8}n+yWfr~O&M*rkT!oKYdB zA1%Ly8Rf9FXZ=t@b2eu62`ovtkZ{h0+D74>{oMOs7C^`CKzv^`*5{*So~62ak(hbj zFP2cxUt-eHdkAL(6WdTZ;Nbmee3M3|pl-mB!WpQeYW!#ICqqE#fID4WLfHBGv!`CH##PPqp{-d`Rgdgwz-uuZBG0boz+gHisv{^tH+5D9l z8kq4ZGo^lz`obvdS{m7rWW3Zm0=!=V?4sBQ z>Ld$Y(c+G*PIqiAFnV_v3FxJ$_lCyO=+3opq57)9O+4_VH7CA~RrE@ySojj=t=%}9 z2y|wOv-WFlKJv3rwXAa{Qd_FU=lU5FTuz6@dr2-H6*_T0Ew&S(Ry`=WnW?v7iycnw z$4P%CfDwl4=e$_bDQv`2eOwoX6=;t@0M5z5(qvNN!W~lPcIbf^zs=` zFLXW|t&YhSe-!$yX<^!Rw&P_E`_Vso1QBzt6XH5Ot8^dC7+3pm;eFWo#AWid>E)R0 zib$xEO@F1s?xexZ2ZP7(wwJ$nSS}#k+~*jie`eo4?Wa2o}i&00M`BF6uTKneG)# zS6`1D?Xn}coLk+tfr)~#4ymp55sMoHM#mI>N8`zGqJqi&Tkn)cgAAl9%~FL+qWw+i z2>c}*ACwhs>?V7ElmGx6To z@8$A89%%DNx|;QdP|%|;oaw@pDt|e=%^D6pU`r=Fm}so8Jx*Kgy9`c%JqUmmZdlU) zSIfcpRKK{D)|Xdc*z|q;_!@&nuaWuRDI;h9g09aeE-y!4yEsafoQjs+vW5y@Q9=Q$ zSGd2D(Siknc=$pwUew<05+FHJadk1rO{(*C8G3|83B2$AGoTjSLJ1r2nev&rqJa~j zt6fMS4twcT$>XX+T`78Gf%Xn>G8lEtXCPVwg$JKhEt8FHwZna+!OxCK%@tSNSK5nS z2UgFf)Bmmc$wK6e(Qz!d{nENa2;W&N@nHUS+liyHZ=qL4{E77AAHx9#3*C(m$g|{W zr#t_wak;``DAIK(cS3O4a*`!3y`hfr+ZGS64D0mSThBp5h?sU0;Nx_up=j(^|Bqv8 zLeo~0SBCBzT4Ps+@MF2u#FWJPf`cv{M+1I4HeWSAg>^`KGLtWnaS5Q}SjNN>*SRZi z=!3fo?M@N8AMNETfidK=Zo@wS^t{v=LwY0~`PGEz77d9{$-;~&Dp%G0EfIeu>9Q2o z_XY*cgS_8n@W(=HjvOZ@s(HI^qr+9{K!sIx}{Yc_p z_}6*nF?{5K?`FNpskHSgk9dNT_y+~qOfTC^4?SZFE0%rp6~je>j8o6*l212nwAfz# z2odjwA0@OcD zQ(T{!-gkXQk)e&FIRLp1AMgGDOAwE#sj*cLgr{nQ`?A%0CylF$qnnCZeABD$O|-!k zscK4WW^vR^+$*)-2NMurJyU7yV9LW!#s<_133F z2>I&3B?Y(Y*GI9o-{Ho^AJYCmT)lTR-0c@Vs<#lm_ueB2qDK(DcOyg(g9*ZDLzEzT zuR-+Qqcft5o~Y4A8={Ur(eHS_zkAoc_it-iYd%jo=h=Ioy)oS#3>x!`VrK*$-zi;4)pUS>h6sbV5 zkD}J!NHZMw1lM5UJWt?sh=`wcGA#8b%${I^x_j^a9o!9$F>y$@H7zhjj0tZv&Bu=W z4&@(kX$gaaR16ZrDOy_Gw4Y1)9Vj(9`kLJ#gHSVxx}r7th$Ib!a7Swz^pL0V$CdpH z-L$UvK2HQU`!bFW+l`r~xQ}xctWn_J;UU~?EB?XXIyU`cT_NdH>g(hc6v? zte;Do#Re6`q03uxYYJC{oXbZE-_~FcCPTc)=Ak0D2esqhk(395$I!JWS;c=QeyG~2 z5%vW`4&=-R>A0oP>6b0_{C{h%QY;O*A0kL_L|Fce*)4(tcfb>Y8{B~fsFby;qDOj9 z^hcyyx4cH)fr%&TeJwcZk$p4xt~4o0c{*r14q}Tj(eP<4z~eJo{~3QAuA|u}DTFy{ z5sC<}_AhZEVW`D}4Z$ z2_lix<6q8wHZ;2X`m`Y-PNmuPi%9P`ss zeJ8y|tI|Y_w+|L4vhkd1&>ts0?eqG-GlM=Z_`}8L?ZZ7o)={2cxI&7b3JZJ<7jAgMSZpVy+6k8SJP0dC+L?zZjdy?A)l+rKFv{`V5L%72{wu*xR_ zm)IG68xt@{|GhG`o15ai|_lx+@^7rqJ)RVHUNd-Y}DU=$=`m&=nkT? zI6E49S>CUTpp1@I=N!UjvJ<~Z3o3-_zWlG2G)G{rw(yMT;oW33koLtw3eiC5BX}VC z?i_Krtk@FsW=t2!CtBm9ONyu2z1c%j@6itL02$dqh4nrjAso!Pwkx8Wzr3+t z3t}gKTbEFXeuv#_@;bH)!jry4>%+rCztE_1wHSkz(nUx!`-^$pt-;rL`J=Wl%UT ze{hkn!#8#>hBK5Sat^LnZ-e-I;(eX>iJ-6Cttk+CsnB;!@zd>xxh%C)J{Gr6 zv^J%hlrAEEZA~RgUH$!g@+Th^dBxc79@tEAbkEw2G6OYg7y*Vgr6!zHgk zG%Z=^b&Csu!ZM{(u4ZrdpLh~ij~Irf|E`WVV!Yu0(Wh?pO9u;{zjSjQWCd;R>4qFN z+6(-fcOdB%C3p$XYY9irH4J-7uI2R6(9~lr+L@_lKig~k2XrcjuX2^xlv&@_Tg8lr zp$5x>+I^P=`gFW8(qcrWj?0AqG^NTqr>!3$hUk;)S9lG${yjQ_zKEyWY_+fdf3gBT zfOk+9CT$%p$7O+7)p&Vw+oT*fcBJN>LcSI%B*U^80Eg$vfehp?uE)b@odqC%s0cwB zZNG@O%pl>B0et5 zQ!;KoE6+F31{s+oh3Wq82t$>4F9}}?_xrmo=ie5?kWp?iL@0q~z2oFJw2X_lFXT#U zXm2bEWf56O!A;xWTqOd<%VT^ye;Q1gY^zKqeUhbm*De22Bj3=^bGvW>az$JTW&Da< zUjR6$CMtlm&6fw|g+8M^n3v{Jx;R2`-ogi}e?)mFgsnLLCSLXF&dGqc-=ryb0{R;P zvmH>K(0mt3;?yq@ED$c45dKcnIUHUg*F-;*+ru95jCEt+bL}S&t+9QTYs5sGrU1yv zB0W8W{Kvinr5u!B9jKrY>BngnI@){;dw zzkXs(P2$|D2AI}r-K>B0av$4I)M+gnx|>b+!Ftg1(ftWEyN$QMN^R+6#*_-?Q;$aS z-7xA>@y22K;HV;G87^CnYZwJ=1u%=jc{{Q7A?YFKdd-`e$@P6S$;dv_S zZh&W$z{W?1?b4&Nazob!=cmPStG_&Xk*EyM1|vOIN`;NXcrla}3G zbBh4CtK&;)$$)36AXm6f(PhkyE2DunqbKzFSA5Z(V)v!JKwnC=?GARR(UP%t5JKk~ zG`*+AC2&jSl!y3@G_KTcpA+s@u^Fr{I)V7*?SY|2MGv)$dWV&p)199smKQtfsT?!L zQ`R;z{kknS0o6NjQ&|wKd~*u6da}PU-D1COPsg;y^a6j^ zwfv(}EPm+#oxD-U%*xHc#qL{#p9%Pp?K+`raEM^^eot0VGBqNOhZXGfhDB-oh5X9+ zl(>8i1%IR6cuczqjoTh(@5;>N@^NGH2-?8z99oCy>if%+aywce|v`I-ut^~EE3+glUeIMjw6I)v1ikSF(^jBpo?gN%1@pFGL;9wh1jVOLm`oWRT)cP!+*kpVP*(kscdpT4 zQ$o5p5X@^df_H7oMh~wP6tMQKc!D=(KLj_3dFuR}!et58u&50vhsLw15wOF|E(~g_ z_Zj(%%l4kjNKDJ7?r1LY4H*aV3I*LbR4%*UPwe}j4|PA>WwnZ?x!gk#1qIq#KaW~M zhH9KlnD>j{j$S*&vhl>LkMOz6=WDY2T{KZhyVm$uSb7Dy=H%^XT@y_i!wr}Chyh-S z@t!r=f>uM+rvl3obF;;>ZOMm<>leqb^$M`l+0v5iG(5bsxa z?#Whl0?-Q|Dyl~W5B8u}(C$8gA=gSrz1BWUsNy zeI4kZ(5Ab~@)wLjRtwn%Ctq&H9Gy?=fP}+Lu{)@)svj)Iit=_Y&1-b#&&dNq@W~Nj z^;%}tf(~sz`BB@0rEZx7Pp@$~cQ|Ywm)AzuLHzKUu(=;F9pDGw?SS1_8kCR_+(u{q zVY4KpA>_DvnVhvNuA0{0RL{VH5e5=#VQiF)j4W|EAHik@mUILzN0;#q^q?)cFmc8$ zNJOri#6A~hHw@hw_>^1TV#d-Kx%cjaVW_?mLA}7s`PzYoGT}(prq>vRs9%#OF6w}W ztuZIQhaJ=~Z|UFkBVg}UaIp&~cCeZP8vZ%}3Qq$p`p1UZ57r_SdRgq$eP660iS)fY zcZNsVXf0Htc;3vUByHSqUUM|IC@M!Z*am$aoY(bGw`Q^e+#JzvizO!+&BwK%oKQJ# ziZe|9Z2GTZbd%k^zgt-@oFkI~s^*IIC&(#5Q(GV$L~VWW|2Ge;+Y#Qs}lS4MHwc5iYgcC@K2z8 zu7m_36laY~uQw>TwD5km!l;`0f@zmLrrQ*TGTq2~-+R3~D_hR~t?u6N;cv&O3tZ#8 zJhxhIrtxfIMr;)_Z_Hd7&$0)XwXZJ~l5lG~?tPN2fpi~YoadUa2tq#Nzz$|1!75=4 zCJ~#y50h}eY30JxM9$_?)SV-d{u>)6cW5&#=Rtn)IQ_XSZwgEF?i4b1sAr4oLQ> z1Uei%F|-xa)>iADA7l9esT!Fa|HTe$t%VZjPE!Xc?ztbe?KCe)ThA!(r zZ+llhk4Yhs4i^ow|VphH>X zrGz)e=cJMLJ9k>)N>9lOQZR~?)XWb4K_k?d^`m?e(VOj>Uv!q%@V-{K+fg^l1+F*( z?*6#g&o|Y8$3Fn<)1`Soj|ltfSDe>gUI6RZX2DYN@9K<%kcJQYAQ1rF#<##dqa`Uv zz(uxTUS^!hpCcp~&iZi0g*3`u7VZBqC$j~6;@lUdl~!9L?n}+vxGGBn6k0x?SJq_V zX1e^K0YdtmXVel$_z}+(k0g{99UV1U4K050y)DJZqeLPf7S**!8mwN%H9D1DK3t89 zQvE|2t}P3gLu$E9O=slxe#P&ql|4+)mp-7JNx(UK-D)sS85cML`9~=PpMgrEuDm&B zbnHHyb&auHE?$}F#Nr}94M8RJ-bnu0G4$^fXE?91UcXZO8gx)^74XwPhQv{9{0?wH zr}Xp*FQnA5R1?wlMZi{Jv&&kBZ4zestHS{0@5nY3T~;2b5~!xY@>q#fP?hMr{JPe% zocs?HD~Q(RzuC=6P7S^V`4)y8~UW3uR>1-j~O0ZhqZ{)$z@ z0fbGy{Pm{N)GSs(+R^;W`c|@zTR*jcDYqF;s?jgac{j}!4-ko|I#w%*2Y5sK=iUU^ z_zsheiqxW9mA3JF@%sgHoMnLrq#sb8gDWwCl;TNIJgCB==peaa@Ry1n6&|N!^u653 z7FE}VNHUqmRZ2i(DuaRL1vqYhdRSB43%)LO)tdfqNp@r8GUvFE7ouL_Me_Mn zSAu}w;{%ZcP*r%S5_;MU+Gm2Bm|HFFWvyT8>`BVhUm~RBEo&hE7=|Vba?{&=RZOk_ z$t9Mj1CyVm(kYmX>$Oh($x&@so$n0_ZCB`F?X z1eOa-*h9HZKKvQZphK|w$Xabmcs=*FgTyRXf)ri43*)4mPtaB4{@XwHF|Q)C>~BAC z)jJ2i=hdTNk#DuDvHKJsAS`XL-5|!27H=l0P6Z!jDR5}hC|`5qz=;N`f2k8oD6$~g zZo^Wr{-Dd%W;F5NcCjN(3SXkc*srLpamHjAO$Np6Co9y8)16c6VfM9Q+zPvI+dd`t zX((IQcPJ74@AgQsP>KdUqy=84zV7)w;Q}G$olVpK2#Kb^eyz}4{c8DIa3e!-K=Jp` zUzIHdU(OVQf?Bo_eqR@z<9{9F*H0-%*`5WooN}a|D@>SFoYgRL*_+7iZMI8oOAQSo z2@%W>hnDtBBcpdIBKkCv5mR$aSRwmQ;zx*$KhIME&u-r4QJdN7{BF80*{IT8SR`A! zy9_2iSX#BR=RIcQ*^;hGzS}E(LO)d0tKG5V9E1uCp)eL*uj4|>-^+KF#LbD8-Hlj5 zjov)Gs*_@D$DsnlnzmOuDq+2*1>gMgZsqHe*O<1{_~TmH58zcW79 zEs9xA&#UEjAZhD87M)7PBoFHPq&C{K0z6~y=}!76mqahLHC8*Wy|*F)<`GrqO%-Me zjT6?z$rM;2uSiVQ@WRT>)O4g>SGMqUpYlJ8`8FIj`fF+RvN@K`nJ|gS53eA6mJ~>b zo@6#mv%pq3xO;mx397W5Wf@+>ZEF-R`qdh9fE!%=22E{uN#t9psxA|6`;#26bYkAq zp|QGmsJU%o02P--O^Py466HeD=T&cu8b6Z}?#srZc*;7THEmM@d}Srclv^S#3R-od z^6MHM);#{8k=D-d#i!E_qN|sj1OV(O)!y-E7YsZe$V&kF7eqab-wcdg@;^F6`v0l0 zs*lv|4YQC;V<+I8Xz2${CBId{?r{Q~4OE_5drz!mIcD-uU3%E|0@TnVW{Jrdj5TSPAl#cx~kcX1u8j%(fVm;y;7`# z)Dt$$oat-YDpWj7(EjCuZTyi~t*=&Nl5m2^U)s`WA!uvI--75YS}E*d!ql}vyzC;D z=e&464{By&y3aIzTB*|WF^gVXyclUHx*R;OMHeAx(fj=VN424S5Ns> z`8Em#JecMH`ZC|S1$Z`&^7xHt@scY*jGnc&^skp&jhWF@2*efE$kZtZR9BjMV6zkM zvZ)#gFTzs$W$!LmEssu+vLWGazhsLh8=IOYza^5mE_G;Kc=`Nb4unnCu;(*%YO_vj z+fylQA>1o~-|ZEbtbBWP<(iKZCSU8%HhmDZSUcXA_Df&3g8kW9>2B=4apfnj-+cS3 zjGboa-=)@G^@ll*THI*5`GgbC)dasu+(umS1MH7Sf-Q5Q5#niLS??}Wj@cy5RO{bC zJV0%{T#IpC1Eol((R+xxxg6fVds0FB%$PF!`bfjX&Qgn9yoPXi4YCPJJMTkms<10P zKv+p5Hb@<*x)r_uwr^l&i<18@8?r(kIq?^Go<8_|HP1-aI<)l{ce#c>2_A;RJ5E-T z0tZgn!|z_n?5}pqX~f{y-)WR$gH!*2P;6~L(a*iW!BZlTk77225AM9YHY(KJ$u59P zSV#12Jit9zod6>_2)jYKR^f2VLKZA*=9BZ@=Nn zeux!;k<%!@XIG`?LPIOOQZtBp7XjOL0(TlFEk&7dPqqd8zNS=^EQ1nmCXJ6uv zVBClBiQ;>;QQTlZM;Q&sS7hYBKu$yy5=H9%AsgCbtVkOklD2|GLHk>z15EbmAR!G0 z{6lHOjn@-=s@3dFE-B zJ>9m65>Z2Vxsbw)i%U$_IvOhI1^w0-sq~-P#|w4Je!rYO&BB?h!i*|gf0l~6MSqOp zrGzMuo~-W`Hhm=m6pu+P`;j{qeu2w~V%s>n3()&f&5tIZ$QzXlfdUr;cX zrxfOk7z|YeHY-=@ep3HK*G!NY@?0Tp`DaoIxAQr7*g&5ykA1Oe`fIVVQ5XfEzE_#Z zp~1f`K>3JUk%<-V99Q?g?YAGP7va^Ha|dnR8ow$%)Dx#KrL0_^$+%Q9dF4SimMvT> zu2F)p3Kcj2`94(K;EnZx#3!#1Fb4W|3&vn>y|=O4Y`A+M3ayzfUo;#_QF|u`sPJ$Y zeTa8GH2LT}X(MPX`XO==p0o3GSS#G{lbcdeD+eAOKOQUhzVC!_3j;C6e;*e0#yN^d zecKz`BzA)sG|we^P-p#>_1Qr4@1DUT#ix=*q(a8>BwIe3afDy8%rDepvSQy}d_kFM zX0keqZ{u&TvOJf^;^|SAo2hCsXfZ*6VHV{@9&gzHXfc8ijPa}gOcjLv-LSNxAQi`=Ss=#E5Ak`F2gW@5v&RZ zSNxR@jquVccYPs!4h7e@rIvk=AWtu6JB0^uPK%(vBCQeFhYCHP@UHTjLQgL&?Ru`B zO{St|81>l5o#?Pk>TYn<_1Ac59Z7rg2Nm7)w;Uqt#Zgs67IWI@=hGE0_VTxv(GZ%3NAzxk? zHb)=xVEmM8OD|T@Vc~gbfyfs)@@vFKh?`) z>oQ;QBP&*Y0+^>{HMsLg{l1Sd-FsqZoQzK^%vgu>cJDo^Px`4MdH1nIrB z!l6a=Uh$pL0;kKWi7!qQQ%WsIJmO`jvyR1pd)?tQde9d&AjVpcil;U7%}vMk7prWH z1EQq>N7|H`o(@O?H_U;iF(wY=zt9c?Mf7cP-8(?M+eQ`+WKB_?e^ z6I#ocZO>8;wz9Ih-DqQtywHgA6+&IG|6SE*EU2scY%Nz`f*iwwGJ(Rr#PyraJ9A9C z&@%Nn$@zG@_8aHzCi%Jeko_btu2mdkoXx{)FUJmXyvj@!j&U1Ou{||(j?!E|=j6BG zl_u%+Fmm%wTG7+J7uwX8KGt9qjQ<@y>k^-BjE`s3GA?l>ki?V*BSlbMigzPe#CV9u zUf|i@jo|0~q=Egdn(qJ*7iaEu$*Q{MAx((Q_|X-V`I|L)s+3 z1hM_whgFmIJ>3g%j`xU0W)h^l#;e<7pKeaH?%BXnQ=M{PYA@j5+}xdh(`<7tK)OEo zVcjke_P`yaP|du6n~_-!-K>i6D!ZQTQhuHJw{<<7e$fsWX@=M{0Q;FIcL$t4Wu)c1 z+7xMkH3hDfWV<<|djT12EDGeOBvdPntM{JD-yXYpAtpLA)M!VzRK=eGS0(hZ{!6(# zLJ3s7J$JpU1g@zXnf`~nkzj2{psty#^_0pIEObomP*%(UOlQnrbSZ4|4s6b*)8ElD zRlf#)ShYi0ITxA#ddC%+Qcr;@vy=m`?$i1>a7@zrC_v$#iOFx=rFOo0N)_bb%%pWK zJLW+a$+9+q)D2eZPhv*TVXzPBJeVn^B^;OPnxq!R94_xOl}$4_i`IBcDVp3ZM|h&q zF?B`5b0PX93p05CxcHihG_sQ#l5CqkjhzItWASJ}DPi9cX&;)t*Aja$nQeCP>Hh$~ z+EU}#A(cNpC2ECvf8F!1k|9C6+nI*K*raD-tKv;*b`0R}ll|1M-}xFsFTVg8k^|=B zW+g1`v=en}+^etKCyej=C3L>FSlvN#Oyay-chHId{!GtZu6vz&w#O;|6KdC8Qwte7 z2k#j`-kNd$bxg@$?gcK0`&RMZ#6PpU9Kugasy^!j670Z`q@NJ`@L-7UcEmaVd)d0~ z<~_iC3?ires~^<`z^p#Qw9x$5P6zDH4LHqy19qIGhL-)zlRuhlul6r@6rYf|0g@cQ z1<>xI1V^tu6P0{2WlqPbe{m1Sr?SRNZf7V5k0WiWevqlRS)o!8vc>A}{DcD71unh+ zZlcuQrgTd%8^T$!X#Gq(vd4!A>gs#M+&l9}K2Lx86x`C&(8FI3ni7b`t=q@p#u>Qt za(&nN24IH!x#y+(p{7%LB%N2e_$_Mk8K{CKwhD$pI#Ax_#iT+@E{)@N6?U|U$1z;3 zHuAruOvxf$FQZ5NRP@h0ZTQY7>O2eppiTPaZ_oOlOVAfX2?PjbfmX8 zDiyk61*?~vgiRz?Xu#nCa8YQ z6?p!3R3dz*LjBlEhcG=DB^sZ;zmR$2@xNw+GBC8jjjXzKGj2_e||B$#v9nj`PG3Brx+8R87`&mEI zOtSz7Kg?pYCY-}Y&sHQNMYO0SIj-o5x$01<%DC>-CI_d8ff* z3cD`m2_2R}4WS27g52G%js)rSc0aj}3%|{$LYxzv)_W!{Oi5o=icj)T2Tku;<(aoS~Afqly&5t^qKGky(XqmITQV{o5zT zl28?x8YKI}6mF_AcEPp;a(O8dT_chmSP@?VYC9vY zYTG=tGHVj!1GDRT>ugwGqyKEN?Jk%`q095hx04_QR>oF!jGu9;RdY}jT0sdH_1?-^ zHT#XGOTg8rm0Qui4Vl=f@)VEBvE$v){S5-v-%-&$rSk!JgYs2hRb{-xG}(JZChx@k zTmJ8gI?aZvsM8xcze^ayNIp32Cqj zldqk@B9FIdo4nyYeZ$?L1oRh9NF?1o0_XD4JYz{9h!?xqE=%mYex%XsR#&H`a4w~B z6oIm`+@_A6C{*>1poK4;Ex&pXll`@x1_8z>DSDJhlK1wW#`jfK9x4 zbq)yXuq4d5xt2;1)0tJaDj+VMB16U+G-=80siz1!*)~nzw@Y2js~+(#KRHA3AUbCK zvZAD7HI)r_D~t7)nPq*?+w$zO>($v#Y9yasX3E_N-9XQNO3SqQ+dOFJH(XaVwVT|9 zU%?Ub%4l%{+W4K3?=}PT1V0?NO+sqARHD^pSb`>`5uKMy2lNucHYeztVSZMmaa>ZS zrH^67@9!owQ1Le6`Fd$(L5oQT|B)RbKlIsA%Uw>Yea}yTK0<2$#RCpf!tU*Tm%iId zTe;%BR4u(%R@iP-X)LDPiv|-Yrmdp;K>Z%$fq=>d?Y@AztIW#Cc1K*7DT&TOI`P%1 zad_urkdB1>S(cc}B}u445m9CCJoK_Dc1&;EhNy15JvZq7YP=xaqwJY++iwTgZyaw? zzK*Ues(-$5$f2|VR>va-ky)aXGL4C1i_Q)S#c>Keuiy9PpN8yh&><(%zRpXSSVl4`VYxH7rJBm<+A%v<<{d0uO52}b^{vWU zjGxO!TEDCub#Yp5-pk&*cCOr?iH|v{21YEkovtJR@4T-VuO5AJk0hS74JjML)H|is zq9f4emC{;N>ALe*^9MMbHK)D?oc=rn|M9GHbdnL)M%9h}4BL3w%lFB=T!u;irOQJ6z?EM->HEwwG7Ix~o1!an`&T#nbAnU?R&MCm2h zDNg8e<@Z!ww8$RbuV4KK_$_~-F5#$@!mAQiJw@vf&W$0oNtzni^f*<-YwGPsj_(YDR??nUn)C?1wjG@$q`l8&ln{=A4_<4_Rf ztARXC?+z#=Civms2U58J+X!O}6TpKUy z(5@fNNCFlGh4^q{eQ5f`DeL6KE?#DSfZ4}k$hfRAUZNJ0c<=Gja$aUY+fUO zp!BquBo!7HIy#mB7<?C_c6ib299=)Ub=FQN}S=*4QKg0h5n1Po`lg`X)37KqCK@Ef5R7^o4Eo{VHAr+{jjxPaUN(Go zT!ii3*|U0~g4CN{dPBkdicA5=J>!%fFV_vQGnKCXs>maeiHs>NuL$ovm|WvO!_ zMe+VlC)!R1acJG1Tw{3jp=={l7GF+n?Xlg>M>dL&>ZP!-$9^m(p#mf`nWV$PNlAaGJIvEjnyFMXjDzqv4>>J)F-Y9^dY zbLRFOw(F|iB?z8rDHfDeVT|4Pe({RE)cg9K5=VKP(D8ByU|jPAW0VMetLz_@4FGSo zy4(6TbD7_`A*H0JX!jf=Eg8P6Em zD54B`^wGTIe$r_h9p_<8BkYb+W z>@Vy+g$n4toB54O)6W`UMRni)(P0qv(JrR4zoXl(AUz1`JHGc0@7`}tK-Ns@di+F^uDN(Z?JK|c^7lg?a7LD1Y`42%ZIPs(5-^# zXU@-3ChCtVD+iVI{zG2>zm4X*!PM9ND0~A4>B$-DGxtmk;FMtelVx;G-6OZau1==2 zq{fKpbFYATsur)XE?AZm-&!A@!e)d7jZp~?9QL}fXwXJ&JP!W7nKAs68f1o+3P|6y z**^ZFHb`zMk)H*xABt?s_C-$T-L~Gmg}L2* z_ue%)7g~hpvh@bSHm@U~wM{`LFkDz;GXgx`$FvGqJV(mZ37rQM|5NPlyy)wQ0JRy7 zp7o$O6xVAY7I1LhaIdX^s?{eN>Sp{c>3nC;%H9OBpS#FMK9K|rpHuW2uSIlL-oR^* z-gCgjOsr-BwvfuiMLgQA7}FQIr8_YPX?X$3RLsG}Y|a6FRfRRXE9Is;*Kt;;!Ah_Y zWLINJ!bRY@_J)PK^|rdJ%=({>+*#27f9cFgGSsoKo{QCOo(>Gc3 zN);4g6Iw(H!1>ZE6bSv|^<#kAYPtVg(#(OdeYl4Lp*U}XK$PkLg2&zg3Wv9|)O{s+ zHNvK=&T1gRQBIk=olPP+Oy|q`IU=MrQQ|d)bzv17{>W_Uu+>sSYq@8$D$$mR!pE1} z9rWZpo7Yb#=Ox|_IW&@$pPkZ?i)`KkVY13If1?vjzz-lDKcq+crylU?FT5z{uAzQR?h^n%Lt{|TjmA8l*~8kX7RKJ2d%~dsxG)*cT+n>0ghT|m6?izlOo9BEa9H6 zCnl%XyW`E3azC)rGnIs|M(;ACOkpIE`TUt@%c>s$84C(5yg{rIoKHvxt*kO~Fl%J( z$RXQeRbT7=bS&nW{N15_3r&bsQ`I_BO5o{ZfTa;3TOu)My@n#>)G@A|x(|fdXX(S9t~TG&wPhzmg3vhgbrtq< z0M@}@!;nyOzA<~rV zQBsoRC^Y39djdGwFE&<99_ur$lz=M|jy~Nj4F>w8*UKe5brh1Y3`AYk)mCXhnnsH}tYg#7H9Qr{4N48FAQ-L@@ zw|4nKxFi$UR6p{pK{as12x_=s)*5i4VRf|cZG!weB-6fB6R%Ln9EjpJ zRxN;SLwp*v{JgB3W~nR!rsavTYJpD%G)3`+y)kP7Bq;SZ=^>9IO0`kya9m(j8( z-Jyzn$d7GB6x6ZZC&!5!tQCj$xgv!xv^g^+=gN2lZS_a;%8bP&H=1MJ2dlW%no=11Nkq~P9*@co-%k< zAF)hrNRrH6Ze|UwyoPIKAi7#%Eb#hgM~7g`VuSyfxxQK+8$w+a{Kp7)58|v9GM+nmf{VKP~cJk z@#>8`sv}vB=yJ3{F*DDt=RVjxtuMPmncDo$eXyVsbBEB$=b)Hq)CU%4e%!#!m%NgA zE*@CUA1t@RX-__LsZ*tMYJlg~U@Rb3B_c3KPtt($^FnEu5A#%<9#H`uB-G3R3Y#_ya;5r^fH`~MP0>rmZ!;bT;3JsW4ew`xrg07KUC|dgrLJf+KU19%nW}j9zL0HeV*mG^ z^7_PZ4GMRA(u{=s*^xT!z4Gzr9`f#l;vrOx6;6k3pje|ZOcHSjPRQNr61o1VQSMCz zg!u3Tc%%!t5&$Kb@0oM-)&&Id1G)vKx}Z~tPxpWT)}GR~iW(HnKS2Aspn7YI@r{x> z%_qDhtMXiC{n+em$N5m`n>ouZ+O{KNAnb{oj?RA2bo0J#QBMFDe;S)}D-l5KH{zF# zz~o`q{}C?P)GsQrB1Z}AV#e;-=@@k2j|suG3#;8H|WV~rzx zLT`IN05`}_540q3ggk9*~% z;seBLidgk_e9(+9Nkut0eWiJUegL`K)Y<@hm44fARUgDu2~a%hIvxu@38QLOLwkJz zNp!Y;!1xh42eu8mnz_Okv(xI@fwQ6(6bZ4ffAkcMP!=-uv`GqV-is?@o z`AvJ|rz)K^b|?_{0-OAPVMuQ75m0LCYT2D@&yK+L_`ZsJNyNqJ5SLR1S_(>(8h)&?=XIN;_S%TN? z^{s8C>Ak5JSo4hYK-|yF>u87ul0V){hwZK{OHl6eyx)flxNb0qZ0;Ap5;ngIH-4`t z(vzQlb53eJOUZ~Q!bSpb4(9{Y+giuBwg)SQ!osir30~6wboOpp@vhu+p#LAposEZj z;AP|er69*j!^FTjELx@_e8Y*U5$YE@;$G2{tKjt3c2s65Mq=QLnyfHzbZilA>XiY> zz@H>|n~vPomN*I3GI;(i*!9Gz%Dj={XVsPT>PZ}z(5@{GgZF~l%%3TA)m+G+1&&!?DoZL!cLZmfEKfETPI;#gc-L4V`7)!}qz{mN~hKRoe}N3v?f zH13(Hz7{8il>3buWZpCJ-#+_p1$y6+DW!Gej!X-JMbI|Kdps6hneN9}wUtNvO}v}|7Uv3_z;xKn zDpLHk*!WyTxHrV>Yk%WO$3c$Buih@RfJqG9?xlS+IUe zf>06aF-t8*{?d&GUWk{IMf$z?Q^sepGuLlw0{gtG$IW*HY#^UL`u48N#Y*gdURs=u z9a|{X5(1UPMg09Hk!!igv}MdL?k)0}UFDH2iYmQUl3@_08=IR%^#{u2CyH%bi+VIp z-1)k0sKp!4`7tJr?WCCO=Q&jNDIvww-r&W0ErWWMQPsO`M5fJCm-lULa(Dui7}xYL zf{jm0C$;+dzyUj+C#KCAL9JN#@UPQKsjnjqm@tKin+`-o%@C zQo*Rmij9X)AtQ~aG%el3)I+nS*W>G6d&Vg7;k9az#AtLA()r<~(Zjy^4u2l%4+l#v zgsr#zuSkcsb1kvF=j3%S2MT_HTHi3&PJXhVy=j{~Okcgv&he*i90JGR$pdXLSt~9W zmnYBJ)ifeL?S!Xvy zp8cgTjBeRn&XapJ4ECEYN`^nelS^B}xhTN=2yiOBiPU7gjk~$je1Fh^fbO5VX2QE4 zdmI$UY=@GT{jt+6{l-#vMauIzpXi+E(!bmgvwN}j@Hk7#cz*7a9wANGz-Ma9g&g-m zTGx`Bf1B|jrP!W_gjZ#=HqYAs7BrK6Haj5Kewl9u%V33({4UySgbKnP7z($`3geuQ zbZmB640&A6wDxpZ$)bn8rE!v;d0>Lnp9%xN_}G|nY!AL(eOBwi^fH|ttl2n(pH4z%Xi zUEiSaa!us0ifl>8db`ladE{v}tO|ecrifd%+zg*3qD_a@`P|X&YXE5E7lKuDSW|7O z0`zee*54IobF}K7SE0F+y4kru_)}~`V>k5Q`fO_3t!@O== zj!DbqUU+paqGc>5EI7g1&WVbZe?u@JI(HeEcio~-G{tz89uzad3&PeGbAgG zC8cbdvG)}tBy?mSMv~+DMUCu+#x~wSlzG}_5hk6MbR+o z?$HP)zrXGHnFETflK%&{4L}Vwh%%>mXrY>&edQljf^Az#8tueE|N6B4ykfy485?2@ ze)mbe{F`RVYil!5jdrcyY$aX2g0)DifPI6f;e6Kjs7g<+v; z&-H2mITRbBVm34bK0cP48%yg7*pY@Exg8ZlX<E^DDd!EXSon5l971IvbBr7FPVq41nK0-Q*jKjK>CGKT;aOcj6C!d%>iUE7`(j z{JhF85@xZ%nBZK{TNFa$5!jdD$;G>utw)SVfElIP4>O&(v~pAutD*XwN9ng#G^&Ve zMT6C!U>JNs8$j>*(S47?_1-@*L=71MyZkQp9IW+6u!DR<&Yye6jFB!-=j(+k5MU3W zvg>Q!+e{6=#xA%0#s})h#;#ee$$*gC#h)o}u=tbk7yr;j^>?uh1>aKGMCU_=vug!> zol1iR2XJWFnR_t?Su*e?_o;WjYt?OekY`si9E#T&r=`~8!M}LL^@z2IggS-#&9lUO z-$jirxnM9i<~zJiMq%izx=N~vO>icg{jQd3Pbhgvr^0Z-0zpRVz02Q!X?8jR1_kSri5Ntl0^yxRq8S$?;tmPeWE!iJE zsJq+C@#P<%b`h#<#Hd0P8niHMa9sdT!%|q1+lV3ksS?>L^}4L;Iew|llsd!O#cPi+ z9?KcG#ddjuNcRS^EN!H$&ZrYTE1B{j<_$Zo+Bex zapVsBh)QC(MKmn_l9u>aE-LP#WvkZ_p^t2~c70(fY`Oh4>K1kyrF6d0yZFyo^`2>$ zKh2Khl#RdErD?B^NVg-1zgz&PUzb)YUU`J(PVPR#PcSbjuIU$e+#&9$flk#mPT=po ziduBl@lj%F1?u)tp-6`(*Q%oD}}yBI?|QprN{aYOIvDS zG=uSdy?6x_WdE;?p*LA7$ylpZ33ugQh$`hN{t3O&0K5xLm zL3?tRMWnlW^I-LZu9#H>F8_shpeWY6eRtvhUxPr7Rwku)r{`&?*; z)4ieoN{gq5I5F~p?!dPns~09oBk9`1BHN$WUpkv_=TF9zAWW4~)hIWJ%@8%e{5cM* zXUywx_K7OHmGTpS&G;s9YIlDWsUM@h9DDYST{&4M(N=`8!fi}}Kuu#3tt{k7^i~Y^kW!^_TVntH)iI&K-_pZs%IX7jk3C>Dl{~H zaCdk2$_Jw>hmz$u?`hg^RO0Tb!A7}+umD@<3X3D-V5zCP$J1NGU8rXq8$v9=5r`-t{! z;dWyTHoasPbstg>5PQG(sb)_SuE`HuVhUcgQG1jpN98FXXF;JZn142*KQY8g12gXW zRf7kMwSxzD*39VmdMZsqx!#cxZ(WU7oL9f_H|w9yA@Z70#V?Lu*G}v1UK6{%E`3Bt zNY5IIP#M7$=n5&mJf>0`uqFItXiSrG`_CFdXv`wS_wvXwa-btfm4c~K6F>QBkHLs?9Xcc_JHmlE?B7DH(7%15%UduiuT@l0fe z7WDEYNvMq4w-8z0-Rk46yHxKGDQQqW@%cJ}+v;rkw^1gJgx|3BEPnfnlxj3_!(&{c z<^K6P%U}^(GG1j~PU8=3$pZx}I10p%SCpIAq>ncri%-bSOTqA8^miyS>k@3d&F`6C zI&WxvcI+hCG@^M28F9gf%?*8KdL;=i&UcCOYW_U?{_CeZA=YCTjObTG9Q8=piPW^>WL-=3%yv$p+f?#LsCxI+S8`uY{|$ z8M-i0)j_O_2KnaASl2b}>ziFgSI$=q&C6Mskn>oDHhsk0elj*Y@_N2_V;R!eRfaoq2#{QsR9IGp>vm}-wDj5;d%`J#H3h8B>gn4Ix<#9@zNvn>>0R@5 zCDP`e_7VDG3CRr=_ZR4QI1@!cvhS>V+~xe@?Euuv3wiFgMaXe)rhT(!5Y4v`ulj{uOYz{926nKL&l)*r?MXe>l-JH)b^qXVa|r zB`O|Nw@BwnUs`EDTFsohxdN3X5;z;ntB*)| z2Qs4=^$(B_`$hNh1#^_JR0+{&UJ~gLzB&zR@eonw7k+~Jwju_`LStbix5*{3gb9~a z&EF`&k6Mo@x?;zs7vip3q=Cj{!^Jm75uU%c14c0aM<@Ab9F_!Y9x^u}lyH57sZjxDlw=6z3-3lJIX7j{*u~w_gLDxpTn3!nhGdt3 zfS65bFajz$#@@{+by#pZg!E3Ti^*kupkTF}enz}!Q>Z_GncsX*-PFF{!60DQJ7D7I z2q;j;fcS7N8*q<59>Z~Ya^tv{ay^D0Jp$5dv>0i`qf_Dx*ENop=Ry{D$W|59>(wh; z-l#TRox3XHH2;(AbY0fan@AkC*A-M$Bh3AVZUI1mO=2c@sqZVryU0a_=zEdtu z-|2`9|Wm{r^NZ{I<&>ffETu!Mi*?!p1Gg)XKkWpcNyYT1oxvojH2tu0f* ziIy7KvQgDxsilCPajUS=QwdU;ln^_QYQdRQ#5Bc&A*wq`wps>?v3}#~LigKA8pU6I z(~7-lPHKoYWE)OUFkaC=EALV?X&K?$N{+P$T&~fFGH6TCBz@`~`jr44-|zR!-UnFl zwrpOougT80CmX)Ev)ZK(e{_BbJnqx+_aHI3_NE6_^0CEEf2e>yoB82dCF6~v2K}=A zkm5>@A;6QlzFMMVx5~@hZ{6-W>op;2`=~=CNnZHI)KzA1R67tn{Pc2R;dtQJ@*tq4NcYxGri z*UMiAw}yVxwOybjRK%##Ria#4_LkS7Bt0nlwnrb`+^L;TzJ%jSEPOzz=lxkdU5%iF zEEZQ)f!)~RnxD1xoXOs))N1r#R25fhlvR(R6AM8j%iG>8dYAgAJ4>!U1E$k_59w16 z25->lJu|nn@7DU2_vpNX&Cu_-Ds0K^fkZ&kx>)!Ru5Zi)9E++zDO?;Lw=T1=-XV|F@75Fc*Guu}$o&B2nb{69GuKhMsVmHMKce91-TNaI-nO7Hr z#hs^|fLA)ji&DvYbdjsvO}#*~3)-Ctf|ecyvUG-ol5M`C_WA5eETwTlkt|K!FI-?% z;^+*a^tv$p@%4>{FFDFF?w<02h$9rm5}5PiyDHO=`sD72TC|;B=Z>12_tO2^2(j`C z)m`^3&G2&Vo$PJwYgOA*k_WB|k`AcK@iqaFU>l4aakA7wBIM-GUeAO}lxx9Z$*tv` zh@z;wNqjuUF}Fo+HGk-IygaTrUa2s#(5>Vn9V8+oW&P~0h8rj?Z!EdYZo0ge`jspA zF`q^ZNfeV(=cT!FV@l|2|-P%&D*e4h1E8pjEK7VicXR#pSS_X?${0U*?l|3*cML_3YcmP zor}@Fh>Igi6Xfms1Hf zGrnE!d#;FBYX03Vo|J?7zKX&!kmWC ztGhR`1nu%eFHOi5t+<4YLk}=ZXlHfWg47?PUsd9LS54;~f`UZ}j>13>j0TD6LaMI6ahb^&Jp0m@+){0TR+x8Y2`3bWtO--b}y3Wx0~cCxk`-M`=s|oxd(?ZFcZQlW2nUit2kJZ6{!i$a__aM=l+g z!f>dD)$%4fqE7iR+W~MjjayBp^LiaOZ@*c6BXe?S=K~;tJ8n-Yt{cjS)t|>~14Ycn zNb3+x^Hw}Ef|7`}Gm3DE{aCKMW(wi`EcG43iF+rTaccf#oBUBY*8!5F=EwcH?VJfK zX&je_lk_6FBO^!rnLaZL^cdBq0l!;pA6@k*Hq|bQ=88(S$2IWO$cQ$5N>Qv=dF%21 zGT*=xvWD`CpOS5Uqy7RP*6ZY%xz;o0N$?i`5LH72ITf?j^i zH`G{(B3B@--JN!#MoNj`4KsJ8=rM(Fx~|l6*vPfcP*WPti2M%Q)tU-FXLj8|3IqLR z_35v-CW(s&qrO3nfRr}KU`3(hmR`h&OO(xb^_a-n4pY`st-7njwo^OZ@n>sofow8p(F zwn)D0+)VR?!dxKkvs6?DMZslCp3v8I6SK?t>9@=b!Gkx z846gg-|ZLtahMMbK8pzgJlCso3$6a(Ay_l8V_49Ul6ty<%du?-^C!paej5+XJtrtg zdM;I)m4ozC>hoQ|Sic8)ShU%l2T5fPriNWybXBt&M&gStQ><-Ep{6?`!te#_Ff(Co zAA>HZ@58Ta9Ll#mrNL5ZMYlnmXzGGPs3%9{1sY+@2dh;@&$s%^$|E%5kgQhb^Bi_G zrOJNz8maE`XUR*Y-7BenA423tPYk1Zli>mUVb{@X>0g!Ob$qwy{dS$pbztv?!zXW* zG;+>EQ585thfoFJaF|8()c#Np366nkLBm4;$xbDotGwM+B-cE6W%VJDVDbtfdGxVA z*d~+L4s-biU%s-iWoeNc@)<5ZvvBzq*BrhQsXd3-gOj3X zJ8nj#sBs!UvMyCTI%C!2ZlkqB;&ma-pghAWkkt*t5chrpgtp4WL@{rSDD^r$TsOej zBJ)O@16vGx{o#w}InyWs$55H|d@S-WUwsMUt1n3(yu1$9iUoIzfJdQ_fYl!EvHYX+ z0w_>e^q@?7BDVnfeBvc%PxqEj&*hwVuNIIMch+?v#6z@6P_>%VrEI@zjF`N0D26^= zQO-aN7M@smYo(LWNxD=cc3=py;H-0a>xnIn`o>&FNo)=dt@|7Y`+*q|bRzA1OffBO zqMr-QS*=`I9pc$g4q}{o27dhcVcl%2bb|S+ZpIP&HBi0=78>0Eb@4Y0OADO#V`6FW zF1Ju|%f+AUn4i>0?ky%|c@097EQ&PU9?Iv(7?jz`lT!%4U%9b;bEs>u(V~07*ewXB z=~Grz$P_XbJ1JUjB*X8>c=xT`&}@4N9|sf}^~vV-(j1X(<(p-VwwUFXaF%m+dUjgJ z(KHyON-T+u0b(C>9k;tfy)VpDqL`k4UP2JjX_FsdRzHm~mEeV#q?3Q{!Tmtch2dfOTSF@#-5>HeOMLCA{So~&4iXye!#XNoGkt*FtFp=96&&nAh|XjUUZRXb)J1sM78@0I;qrJeoJCfj zk_Q6Eid9ct!5J9#?oV##?pHaWBj@DcgVfYPnQK5()A9al6A&UlxwBag%^&n?`d(|g z>iN^pI9k3dIaC|7?7N*czgF+fWqj?G&rb3SAh#5>i7# zSb%bXqy`RdHi?`|w#1kUk_LzCr~d+1rPfLdPGo2J733eKU~oF>2dy@R6G_dBwR3)3 zwbK5n(ks9!^-W)`Ls(Mv#k;Qx0@!T@3;;QYm;Ynsn(3@8uq?-OhqpEn~82MI3JJl-v*{wDJAk zvz8Srz0tg#S!L^$27<^&$scX_Sx%ZQ4dUQPe3J{@VJtq@B6 z;A8)v&uU}DqO!;Gt@Zc|ri910BBn-ZJF(Cc%Mrj*xXE-UPgmfH3_=1^zWk(wQ&V37`Ycbe#}1s*e|2rGc1W_%HP@V zB(vYCoVrc?_GviNG^0l^D}BnwzDxPXe&c5paKmPXa!b(s=WWn6`iLa8u%kPJMKr6W z#rL-4>rA3JDk)-az0^xfj&^hXrc~0y%5QBYAUA+JiznBYz-N|%9%gy`MIA;^?Xs8E zx|gM#6G3A@Er@)k%*>)p)ER?F^31(vVa>v5hDbmP}T3eQ_=S%-2j z>Ncnh8MQ)C6ci(WgSxkW%6xt)3~deW9Xx{2bN}0OZ?l*#v%D^JcVyxv?c3Sz$|^jJ zc9G=Qguv{N+s*fUH^SCPxSVRJE-#u<#v>0lS_6{E`fe+f7cP>IUx%}m-vsp>WG`ix z+8CZT6)rY|HI3Ut`D$=Z)WCLi?h#hNv>es0O|D?K1R1e-H~BK;U$Js$u&EMNccPS`CcEWv#f+x~hJ&Hef{n%OaC{Lagy@1yx|CRF%pIO3 zMc=cR-xV(6(C)WrsW_u_i9)|zc;&%SOJKDa?T66yO5}EA-1NK$u74%(O1j{?pyA7_ zi&Uzr2iu6W9i2j5TTSacFNr0Bg`z@=pAzVAq0gX|28c!a^|d*PSv40Q<3uhGPZL?< zuVU#8RBiuIY)*HgPaf=qja0?xDFTecAU@hDqVK|!`!oZb5o;J5a~^dJwE;B1KH3EZLKWOZkrSuHa7|Nbu8ieT#5*y5Gxw{Ww;JGV!#z&d9dpKx)UT9t{tLW;n-LC6 zf(TuG5A9yKgAZ~RN$i2Ltf@)JbjpOb??m=2T*Q}P?v_eOW6p(3Zn5%t_2&~hw?YeJ zjh;sNexk4)qbi8yh$En3wt<(@?=`0VTxOqTe$eo$Ze{P*#(A4=YQ@lt0_Pa->JFT% ztWFj&LD$FUo*aHDb1En4e_vZYEZu}@WwD1R+C5c_ofPk{tQy<mZawv z2|RkLW@Zx5?;~0RefJ;++D#Bxt-`*0p@@3Jx* z*L7R22$wIHACc0buIxk=DklFDCOWjN4kIz`$nK86C~B(~g46#(re&4`&GiT) z9H86057qvZfDP^}?6}b@tTlhr za&@R`_@UasPl?wB5AKn?zda-_?veU1U%Jy>zbl5b%ev~e0l*h+x|sr7gcjb zA@L5ji1_9ZLZ(ETO6>gGihsp2(ArSYtF6QCMFcywwMfOhh)hW22=g9SV!2tZ8%?*a z4T*hLqaJ`}#mQt$rEk|yTJFjR_4z~}V`eNje_jBvyB3;EeMC?t~n>u}JA(9u&6!6LcTU`c}aX>F!fh)Nv>M*{kg){%W z8KF3LUsHVTat;)5$Rg7H!3t}hT-GM}gB3-RgXRzz5xYaZjlf+WmsAnxCSZ41+#Y={ zT~n5C+pz7PAE6H4iX zu$JF@M#{~S91cJ=x&*W2Zu)X7E8SQJ1W8!~i}EW)ngj_Rm~?kM#X**^<`b;*=wp^U z^>)O~M~7cz0-lxmQ0vdnP(qIic@#frF`2JjrTO~CB7`mNbNC~@xj9Hnsn?aT4)DYfIGszVxUsld(kYUr zJ@9r|yz-4D@3U;EY+c63orC13GrrTSW%FX!T-G|M4l@UDj-8wV{<{hETh?}C0m*$^ zKyu=rVgkrx)Svf4n{MIL+5E4E>V_Hw z|2)%K2+Hg6)aL(VokZk3`F545U#OpjUFwVd48hHfAjo?mU@iD{MFL~=T7NmXE=o^f zb7>#o+}vfJe(EuqA`VmYGjJ9Mg0^FzoH;V*X)IjfGvsI@yuLS1#>;WvJwfRClY1t+ z*~wFZ3Ilw#x;T7Xlvr*L;TmUV4BW%j%HYX`ssZ z$3FAP(N6hcumead3qz+XCSchN2vA(sdG+Z)+*xmXs!sr`}w2Uc~Ol_l+<-) z)WHBA7+Zf|1Z$6a5v%J1&DvS$8Lac4$?*U2i23D3EfCD!Gvys}(1sM#KEUZ0huxI8 zyUq_}LZ2Nwg2NnHqv^^+XDa^3ah`)VH~e}0wNtYTZc_wZ0kKOBpjf;5UjBw(RhRHc zs8>uqla((6h*f9X&oTSTWb>4OzD(=rhD}iEE;%^fZEby%zwA%*1z;qDaJNV{=(cU* zFR#zXJeryZxo#8GLEjyl;ff?A040~KtZdNX%s3Tra?}K2PXgsht|}~_+^h2GqD6yR z5-uZqCFDZ?Rv17DmjBw?xM*M|v|-=Vjh=Sap=h zcGQjL{Jx7<#;>3#0d$VqDQ{X|xplO1!<#$Xt>gCyD7_5D1@0!9`R^?a8Et?n*BXMu zN(AG7>*LxUmy70t#O&SoTC;^|x2A7;^l`=x9v-xw9HcTkR%Of_qf5!ZZ9We01x`=a zJphQ9ojPh390ODXVaSnRIdzqA7-f(wp?q12-I~UN^WnD4iKhWIAtl#LimJe4EqlfK z`m}t928#en{x@##dBi!(S!Qwx&Qf>cV>$&0FpqvGaMPSGXI6az)kB<@IGL%XR&a)D z4I%khMil+pjfXt1gF7A4_7gLxmK#>MWlDd~03^a$?Y8=nnHt8-BzZV9U--#tOUm6j z&qwwNT*7ndUCxnh{?P)p=_2=QcE@(vaz>o%X2&a!8`r7^8pCA{KMDL6nqXIqv}oJb znr`=s>RtWJd~*Nc1|+mwNiJHw)TtG9zqOfvVS24@-hcLe&aanKE`6K-+zbHrp@LZ8 zRO?jK1gGYm6eCMc4#(FZXXi%Xf!;!K6Son_9rF5uIbzXS9ctfRuIMKqYpHBB2Z18-GFS*`rmU@?NFB!WSZBlT+09qG@s!*>QK zWI)Bw{8BNY8z+^^_upVoW>#R7{g;D7B#8(oOC+(>JU{3&KOTZ&R`UVqSpE>fPrPSF zBnA~zO#;!ANd+=Wfe#rpuqNfx+aJdZxQC zN>e~k)e)t!;IamyDlL1Z;?cy`WF6{rRPQ9$>z^G!wFj*2q1O3pU-Oo$+KCmdKDA8; z6~2M?Xgw+S(570FH%tqlFfshehON6kEF}X?S^?oZAvpi_H0hxii#9-1f72di$wg&C&2aRr2 zocs~hF;ZDYSGs-qiR4xvQEz&x)n53Y6rrZfvp4|4%`6Gnwt09lLmtHq^jOY@{K)QJNhvc5B07Kd=%9`r}p_Opk(i}X^LH8 zbr{Xf_MY?6Ixq1ta2>D%9wdHPZ2E-Nta>mJ1UR-jsaB}rJL#a_Mvg!@y^7Torq zq~%lZ!i1;JwG|TG4e^UqqZ$IA#+$&>CC{hvluKCI<4T^ku{ojx89?!VxBA$^=$R(} z2OJk`FKck1>>AGalbs^Z0I;mjW=7Lrw`)euqv~;PCkt~S#g ziC61htJ8UF`n}ExXn1BQ`UiI4ZvTm_n_)IxD&`j_hvp{?f{OMlgD<%i7%T9m@?zpKtRtatV_Vwq?iLDfI*56U_(j=BW-@(n5Eq3VP?a zKSCMx$+z_X?YQueTr6id^G8s6a;Cx-irlt^tsl!G4DhGqFkEoz>V50g3sJ?FQVhoV zk<8EGM8>4pdpyll76%$nM#D|@$+eQb38)J9!1!(p&+e)%WK~!xHQ{~MuD(fdw|Xu_ za^Hg*D(LKWyW}wMC#m0kG#de;hky~&Eos-PZ;3guy=pz*P*q%MPA#ew)6Q@lH;^Wo zjeJ+%J9e-t#f`F$k6K#iZY9%Nxhd#9C#m5Qod%^d;tL~nZ6#VGaSj_04o^N$7JOFE zdhA6kYpmGI_5a!9edxN7zU%QPcnNMhgGbE6A6%vSW7jNlAY9P&C;k;AwyGn1d)$HqH{{!sG6Vps7lsosQmF8@0Mx|sr#1_+y3rB3~7E?;d#eM zsI)2|;}h5Sh>gObX%ww#bv(!aVy<=C+lgyt<W! z7sVAYWmW?5Zyqzb214(twZ{N(_;Wo9Gs1B>U=sS=JF`xnHl*vwAI%6YXNqC{pX*Qp=g#5%yZ`E+rK&fN!leK?-`4d@HyMim}rT~OAn?oZHNLW$W zN~NxNwomB(-VFe1IeG6brHOB8y*1~ELB6`a```l94H6eIzsNLxMd-o1XgYg#9b-4- z+lv?ll+UmhanQ@kaj9zA#LmADMhz+D61Jyi{S!b!V1x)vX;c@|OdLTa7guIdI})eT zQh5#BHF%4W!PQ!{%eCJYv7~h&AX{amrm)J>ZBZL3l4~ouV;o-g$9(3K@Ur$Y*86Wr{37sJ#(w; zc_nG}SfMJpXawGX*2yBbjD3(T`Be~Fy48UwSb1(V@e3vCYM0@Y6yi&Z0C{&_Bo2=C zA{|l0UetGY2RHP{9hSu9ug@O4q>8IDe2FT)dUCjJ`ola`qFfFK&z5?bxs`*EYk`7< zx~0zow}<;xZf#-FdJ)$J(Gd(?Omz+a!a4(x2@HI*FA)5@(p(pTyavkr7PTn-=Y7RK z!KyG@vS_mYtD&u^%M27$W-i!Qjq@}e+Wo^vW0n$x1#MM+`8k!}j zPoh#K{xYopR154{%v$nCvRqhBoe<8AlnClQ^DisG{Nc|KX`6WSM z4i7K%b)*p)34f|_>SL8(swjv4rO0T8Xog*O`|N*FZ=f{*99MRZ^2#6RUd|#ILIG00 zaA8e)<&FKO5j+S{NEEVqIqze%kH@H002 z7S|Ay*@{D2;(ZLWv64q z(z!bjBp{i)`(^7&L0jL8e;)`iJ<-mQqfwg2{%!b7Z^0DM6K`+8 zu=Y+f_xJIBD|gQ89MgRZ({2^vPbO!l_$0et$p9g_CP*g#oBzRwd9g~0VanX!UA4(o z`ek2jc5+Stk<^+0CyTjy@?N;VQL*GkqvKGCj`@*;=}sg`@=_BB+z-~lAYXUrAG57^ zSO4xIv?YIK_4RB1J|U0`b5ZKrdJSGpi0<1KkVh^)0OK~tpi0TC=!Dt(S6`KcR*Wld z&6a`Y?6Q3uB$o!?#MZP`Zv;0xTv&d&JjZPc;0e&p9@iCZ7Gd_X8Vx%FVYI%ftMMydMR^$gm7Waz!>z`UO-7v zt2%QJa5sRkl|k+b#Gz6C-TV2i!iDcZ^(*ZPoATwQ0Kjwf0;)(F)svQykGiHDO3Ucf zwhwZOEfcnr=2n(f>gMNI?;+$KZoKlYJ6Lb3^FV+7_v(WKASV%`P^szgdy)OQ{cxm+ z)BI$1j*>kW&{!M!E1IjwubAbogA8C@MP?tc=PZx5pjs2=9j*Xkz&1X=zQj9g4$9r$ zfNrYc>DmaDte8-q2vJC2qzOz!D8anB!xelsVH@ym%9?8GG84QDW!(JsJDD59uP?IB zDlq@T8B<@1AiThz$>=>(nIIMc)Y1Px77|X`F$SO7I@$;bcw+)e&of`7>p&4>mM(JP z82XQgu7!ubfz)~z^&USk9C#cWS1%6LW)w0z@r~mK(!g>%UUHm$w|FrQQ95O(zh~QSJr>ndxS2dW@RcvYbNS6FcIz1&@ zn3pyor5%|9x=*$L_ug>8TuAhLp@6*s>aO1{(h+W)?V*?<7VqP=;bUw{yA)sQl~CP3 z)gJJ=po2LH8#e*(_`o`wI-v(R?p`ucp-8E{R* zf4K^TXF0d+v&sgZ!GjUN5iH;zLD;}&T#{v0e?I>Gd0STCvt?%yAEMJ=`uo%WU;TF5 Z8K0MQGN?pzHSl(4)ReRp%jGSC{}qm}>w diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.ipynb b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.ipynb deleted file mode 100644 index 308512bfd7..0000000000 --- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.ipynb +++ /dev/null @@ -1,482 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Simulation" - ] - }, - { - "cell_type": "code", - "execution_count": 16, - "metadata": {}, - "outputs": [ - { - "data": { - "text/html": [ - "\n", - "\n" - ], - "text/plain": [ - "" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "from IPython.display import Image\n", - "Image(filename=\"figure.png\",width=600)\n", - "from IPython.display import display, HTML\n", - "\n", - "display(HTML(data=\"\"\"\n", - "\n", - "\"\"\"))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![gif](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/rocket_powered_landing/animation.gif)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Equation generation" - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [], - "source": [ - "import sympy as sp\n", - "import numpy as np\n", - "from IPython.display import display\n", - "sp.init_printing(use_latex='mathjax')" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [], - "source": [ - "# parameters\n", - "# Angular moment of inertia\n", - "J_B = 1e-2 * np.diag([1., 1., 1.])\n", - "\n", - "# Gravity\n", - "g_I = np.array((-1, 0., 0.))\n", - "\n", - "# Fuel consumption\n", - "alpha_m = 0.01\n", - "\n", - "# Vector from thrust point to CoM\n", - "r_T_B = np.array([-1e-2, 0., 0.])\n", - "\n", - "\n", - "def dir_cosine(q):\n", - " return np.matrix([\n", - " [1 - 2 * (q[2] ** 2 + q[3] ** 2), 2 * (q[1] * q[2] +\n", - " q[0] * q[3]), 2 * (q[1] * q[3] - q[0] * q[2])],\n", - " [2 * (q[1] * q[2] - q[0] * q[3]), 1 - 2 *\n", - " (q[1] ** 2 + q[3] ** 2), 2 * (q[2] * q[3] + q[0] * q[1])],\n", - " [2 * (q[1] * q[3] + q[0] * q[2]), 2 * (q[2] * q[3] -\n", - " q[0] * q[1]), 1 - 2 * (q[1] ** 2 + q[2] ** 2)]\n", - " ])\n", - "\n", - "def omega(w):\n", - " return np.matrix([\n", - " [0, -w[0], -w[1], -w[2]],\n", - " [w[0], 0, w[2], -w[1]],\n", - " [w[1], -w[2], 0, w[0]],\n", - " [w[2], w[1], -w[0], 0],\n", - " ])\n", - "\n", - "def skew(v):\n", - " return np.matrix([\n", - " [0, -v[2], v[1]],\n", - " [v[2], 0, -v[0]],\n", - " [-v[1], v[0], 0]\n", - " ])\n", - "\n" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [], - "source": [ - "f = sp.zeros(14, 1)\n", - "\n", - "x = sp.Matrix(sp.symbols(\n", - " 'm rx ry rz vx vy vz q0 q1 q2 q3 wx wy wz', real=True))\n", - "u = sp.Matrix(sp.symbols('ux uy uz', real=True))\n", - "\n", - "g_I = sp.Matrix(g_I)\n", - "r_T_B = sp.Matrix(r_T_B)\n", - "J_B = sp.Matrix(J_B)\n", - "\n", - "C_B_I = dir_cosine(x[7:11, 0])\n", - "C_I_B = C_B_I.transpose()\n", - "\n", - "f[0, 0] = - alpha_m * u.norm()\n", - "f[1:4, 0] = x[4:7, 0]\n", - "f[4:7, 0] = 1 / x[0, 0] * C_I_B * u + g_I\n", - "f[7:11, 0] = 1 / 2 * omega(x[11:14, 0]) * x[7: 11, 0]\n", - "f[11:14, 0] = J_B ** -1 * \\\n", - " (skew(r_T_B) * u - skew(x[11:14, 0]) * J_B * x[11:14, 0])\n" - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$$\\left[\\begin{matrix}- 0.01 \\sqrt{ux^{2} + uy^{2} + uz^{2}}\\\\vx\\\\vy\\\\vz\\\\\\frac{- 1.0 m - ux \\left(2 q_{2}^{2} + 2 q_{3}^{2} - 1\\right) - 2 uy \\left(q_{0} q_{3} - q_{1} q_{2}\\right) + 2 uz \\left(q_{0} q_{2} + q_{1} q_{3}\\right)}{m}\\\\\\frac{2 ux \\left(q_{0} q_{3} + q_{1} q_{2}\\right) - uy \\left(2 q_{1}^{2} + 2 q_{3}^{2} - 1\\right) - 2 uz \\left(q_{0} q_{1} - q_{2} q_{3}\\right)}{m}\\\\\\frac{- 2 ux \\left(q_{0} q_{2} - q_{1} q_{3}\\right) + 2 uy \\left(q_{0} q_{1} + q_{2} q_{3}\\right) - uz \\left(2 q_{1}^{2} + 2 q_{2}^{2} - 1\\right)}{m}\\\\- 0.5 q_{1} wx - 0.5 q_{2} wy - 0.5 q_{3} wz\\\\0.5 q_{0} wx + 0.5 q_{2} wz - 0.5 q_{3} wy\\\\0.5 q_{0} wy - 0.5 q_{1} wz + 0.5 q_{3} wx\\\\0.5 q_{0} wz + 0.5 q_{1} wy - 0.5 q_{2} wx\\\\0\\\\1.0 uz\\\\- 1.0 uy\\end{matrix}\\right]$$" - ], - "text/plain": [ - "⎡ _________________ \n", - "⎢ ╱ 2 2 2 \n", - "⎢ -0.01⋅╲╱ ux + uy + uz \n", - "⎢ \n", - "⎢ vx \n", - "⎢ \n", - "⎢ vy \n", - "⎢ \n", - "⎢ vz \n", - "⎢ \n", - "⎢ ⎛ 2 2 ⎞ \n", - "⎢-1.0⋅m - ux⋅⎝2⋅q₂ + 2⋅q₃ - 1⎠ - 2⋅uy⋅(q₀⋅q₃ - q₁⋅q₂) + 2⋅uz⋅(q₀⋅q₂ + q₁⋅q₃)\n", - "⎢─────────────────────────────────────────────────────────────────────────────\n", - "⎢ m \n", - "⎢ \n", - "⎢ ⎛ 2 2 ⎞ \n", - "⎢ 2⋅ux⋅(q₀⋅q₃ + q₁⋅q₂) - uy⋅⎝2⋅q₁ + 2⋅q₃ - 1⎠ - 2⋅uz⋅(q₀⋅q₁ - q₂⋅q₃) \n", - "⎢ ──────────────────────────────────────────────────────────────────── \n", - "⎢ m \n", - "⎢ \n", - "⎢ ⎛ 2 2 ⎞ \n", - "⎢ -2⋅ux⋅(q₀⋅q₂ - q₁⋅q₃) + 2⋅uy⋅(q₀⋅q₁ + q₂⋅q₃) - uz⋅⎝2⋅q₁ + 2⋅q₂ - 1⎠ \n", - "⎢ ───────────────────────────────────────────────────────────────────── \n", - "⎢ m \n", - "⎢ \n", - "⎢ -0.5⋅q₁⋅wx - 0.5⋅q₂⋅wy - 0.5⋅q₃⋅wz \n", - "⎢ \n", - "⎢ 0.5⋅q₀⋅wx + 0.5⋅q₂⋅wz - 0.5⋅q₃⋅wy \n", - "⎢ \n", - "⎢ 0.5⋅q₀⋅wy - 0.5⋅q₁⋅wz + 0.5⋅q₃⋅wx \n", - "⎢ \n", - "⎢ 0.5⋅q₀⋅wz + 0.5⋅q₁⋅wy - 0.5⋅q₂⋅wx \n", - "⎢ \n", - "⎢ 0 \n", - "⎢ \n", - "⎢ 1.0⋅uz \n", - "⎢ \n", - "⎣ -1.0⋅uy \n", - "\n", - "⎤\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎥\n", - "⎦" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "display(sp.simplify(f)) # f" - ] - }, - { - "cell_type": "code", - "execution_count": 12, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$$\\left[\\begin{array}{cccccccccccccc}0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0 & 0 & 1 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\\\frac{ux \\left(2 q_{2}^{2} + 2 q_{3}^{2} - 1\\right) + 2 uy \\left(q_{0} q_{3} - q_{1} q_{2}\\right) - 2 uz \\left(q_{0} q_{2} + q_{1} q_{3}\\right)}{m^{2}} & 0 & 0 & 0 & 0 & 0 & 0 & \\frac{2 \\left(q_{2} uz - q_{3} uy\\right)}{m} & \\frac{2 \\left(q_{2} uy + q_{3} uz\\right)}{m} & \\frac{2 \\left(q_{0} uz + q_{1} uy - 2 q_{2} ux\\right)}{m} & \\frac{2 \\left(- q_{0} uy + q_{1} uz - 2 q_{3} ux\\right)}{m} & 0 & 0 & 0\\\\\\frac{- 2 ux \\left(q_{0} q_{3} + q_{1} q_{2}\\right) + uy \\left(2 q_{1}^{2} + 2 q_{3}^{2} - 1\\right) + 2 uz \\left(q_{0} q_{1} - q_{2} q_{3}\\right)}{m^{2}} & 0 & 0 & 0 & 0 & 0 & 0 & \\frac{2 \\left(- q_{1} uz + q_{3} ux\\right)}{m} & \\frac{2 \\left(- q_{0} uz - 2 q_{1} uy + q_{2} ux\\right)}{m} & \\frac{2 \\left(q_{1} ux + q_{3} uz\\right)}{m} & \\frac{2 \\left(q_{0} ux + q_{2} uz - 2 q_{3} uy\\right)}{m} & 0 & 0 & 0\\\\\\frac{2 ux \\left(q_{0} q_{2} - q_{1} q_{3}\\right) - 2 uy \\left(q_{0} q_{1} + q_{2} q_{3}\\right) + uz \\left(2 q_{1}^{2} + 2 q_{2}^{2} - 1\\right)}{m^{2}} & 0 & 0 & 0 & 0 & 0 & 0 & \\frac{2 \\left(q_{1} uy - q_{2} ux\\right)}{m} & \\frac{2 \\left(q_{0} uy - 2 q_{1} uz + q_{3} ux\\right)}{m} & \\frac{2 \\left(- q_{0} ux - 2 q_{2} uz + q_{3} uy\\right)}{m} & \\frac{2 \\left(q_{1} ux + q_{2} uy\\right)}{m} & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & - 0.5 wx & - 0.5 wy & - 0.5 wz & - 0.5 q_{1} & - 0.5 q_{2} & - 0.5 q_{3}\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0.5 wx & 0 & 0.5 wz & - 0.5 wy & 0.5 q_{0} & - 0.5 q_{3} & 0.5 q_{2}\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0.5 wy & - 0.5 wz & 0 & 0.5 wx & 0.5 q_{3} & 0.5 q_{0} & - 0.5 q_{1}\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0.5 wz & 0.5 wy & - 0.5 wx & 0 & - 0.5 q_{2} & 0.5 q_{1} & 0.5 q_{0}\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\\\0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0 & 0\\end{array}\\right]$$" - ], - "text/plain": [ - "⎡ 0 0 0 \n", - "⎢ \n", - "⎢ 0 0 0 \n", - "⎢ \n", - "⎢ 0 0 0 \n", - "⎢ \n", - "⎢ 0 0 0 \n", - "⎢ \n", - "⎢ ⎛ 2 2 ⎞ \n", - "⎢ux⋅⎝2⋅q₂ + 2⋅q₃ - 1⎠ + 2⋅uy⋅(q₀⋅q₃ - q₁⋅q₂) - 2⋅uz⋅(q₀⋅q₂ + q₁⋅q₃) \n", - "⎢──────────────────────────────────────────────────────────────────── 0 0 \n", - "⎢ 2 \n", - "⎢ m \n", - "⎢ \n", - "⎢ ⎛ 2 2 ⎞ \n", - "⎢-2⋅ux⋅(q₀⋅q₃ + q₁⋅q₂) + uy⋅⎝2⋅q₁ + 2⋅q₃ - 1⎠ + 2⋅uz⋅(q₀⋅q₁ - q₂⋅q₃) \n", - "⎢───────────────────────────────────────────────────────────────────── 0 0 \n", - "⎢ 2 \n", - "⎢ m \n", - "⎢ \n", - "⎢ ⎛ 2 2 ⎞ \n", - "⎢2⋅ux⋅(q₀⋅q₂ - q₁⋅q₃) - 2⋅uy⋅(q₀⋅q₁ + q₂⋅q₃) + uz⋅⎝2⋅q₁ + 2⋅q₂ - 1⎠ \n", - "⎢──────────────────────────────────────────────────────────────────── 0 0 \n", - "⎢ 2 \n", - "⎢ m \n", - "⎢ \n", - "⎢ 0 0 0 \n", - "⎢ \n", - "⎢ 0 0 0 \n", - "⎢ \n", - "⎢ 0 0 0 \n", - "⎢ \n", - "⎢ 0 0 0 \n", - "⎢ \n", - "⎢ 0 0 0 \n", - "⎢ \n", - "⎢ 0 0 0 \n", - "⎢ \n", - "⎣ 0 0 0 \n", - "\n", - "0 0 0 0 0 0 0 \n", - " \n", - "0 1 0 0 0 0 0 \n", - " \n", - "0 0 1 0 0 0 0 \n", - " \n", - "0 0 0 1 0 0 0 \n", - " \n", - " \n", - " 2⋅(q₂⋅uz - q₃⋅uy) 2⋅(q₂⋅uy + q₃⋅uz) 2⋅(q₀⋅uz + q₁⋅uy\n", - "0 0 0 0 ───────────────── ───────────────── ────────────────\n", - " m m m \n", - " \n", - " \n", - " \n", - " 2⋅(-q₁⋅uz + q₃⋅ux) 2⋅(-q₀⋅uz - 2⋅q₁⋅uy + q₂⋅ux) 2⋅(q₁⋅ux + \n", - "0 0 0 0 ────────────────── ──────────────────────────── ───────────\n", - " m m m \n", - " \n", - " \n", - " \n", - " 2⋅(q₁⋅uy - q₂⋅ux) 2⋅(q₀⋅uy - 2⋅q₁⋅uz + q₃⋅ux) 2⋅(-q₀⋅ux - 2⋅q₂\n", - "0 0 0 0 ───────────────── ─────────────────────────── ────────────────\n", - " m m m \n", - " \n", - " \n", - "0 0 0 0 0 -0.5⋅wx -0.5⋅w\n", - " \n", - "0 0 0 0 0.5⋅wx 0 0.5⋅w\n", - " \n", - "0 0 0 0 0.5⋅wy -0.5⋅wz 0 \n", - " \n", - "0 0 0 0 0.5⋅wz 0.5⋅wy -0.5⋅w\n", - " \n", - "0 0 0 0 0 0 0 \n", - " \n", - "0 0 0 0 0 0 0 \n", - " \n", - "0 0 0 0 0 0 0 \n", - "\n", - " 0 0 0 0 ⎤\n", - " ⎥\n", - " 0 0 0 0 ⎥\n", - " ⎥\n", - " 0 0 0 0 ⎥\n", - " ⎥\n", - " 0 0 0 0 ⎥\n", - " ⎥\n", - " ⎥\n", - " - 2⋅q₂⋅ux) 2⋅(-q₀⋅uy + q₁⋅uz - 2⋅q₃⋅ux) ⎥\n", - "─────────── ──────────────────────────── 0 0 0 ⎥\n", - " m ⎥\n", - " ⎥\n", - " ⎥\n", - " ⎥\n", - "q₃⋅uz) 2⋅(q₀⋅ux + q₂⋅uz - 2⋅q₃⋅uy) ⎥\n", - "────── ─────────────────────────── 0 0 0 ⎥\n", - " m ⎥\n", - " ⎥\n", - " ⎥\n", - " ⎥\n", - "⋅uz + q₃⋅uy) 2⋅(q₁⋅ux + q₂⋅uy) ⎥\n", - "──────────── ───────────────── 0 0 0 ⎥\n", - " m ⎥\n", - " ⎥\n", - " ⎥\n", - "y -0.5⋅wz -0.5⋅q₁ -0.5⋅q₂ -0.5⋅q₃⎥\n", - " ⎥\n", - "z -0.5⋅wy 0.5⋅q₀ -0.5⋅q₃ 0.5⋅q₂ ⎥\n", - " ⎥\n", - " 0.5⋅wx 0.5⋅q₃ 0.5⋅q₀ -0.5⋅q₁⎥\n", - " ⎥\n", - "x 0 -0.5⋅q₂ 0.5⋅q₁ 0.5⋅q₀ ⎥\n", - " ⎥\n", - " 0 0 0 0 ⎥\n", - " ⎥\n", - " 0 0 0 0 ⎥\n", - " ⎥\n", - " 0 0 0 0 ⎦" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "display(sp.simplify(f.jacobian(x)))# A " - ] - }, - { - "cell_type": "code", - "execution_count": 10, - "metadata": {}, - "outputs": [ - { - "data": { - "text/latex": [ - "$$\\left[\\begin{matrix}- \\frac{0.01 ux}{\\sqrt{ux^{2} + uy^{2} + uz^{2}}} & - \\frac{0.01 uy}{\\sqrt{ux^{2} + uy^{2} + uz^{2}}} & - \\frac{0.01 uz}{\\sqrt{ux^{2} + uy^{2} + uz^{2}}}\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\\\frac{- 2 q_{2}^{2} - 2 q_{3}^{2} + 1}{m} & \\frac{2 \\left(- q_{0} q_{3} + q_{1} q_{2}\\right)}{m} & \\frac{2 \\left(q_{0} q_{2} + q_{1} q_{3}\\right)}{m}\\\\\\frac{2 \\left(q_{0} q_{3} + q_{1} q_{2}\\right)}{m} & \\frac{- 2 q_{1}^{2} - 2 q_{3}^{2} + 1}{m} & \\frac{2 \\left(- q_{0} q_{1} + q_{2} q_{3}\\right)}{m}\\\\\\frac{2 \\left(- q_{0} q_{2} + q_{1} q_{3}\\right)}{m} & \\frac{2 \\left(q_{0} q_{1} + q_{2} q_{3}\\right)}{m} & \\frac{- 2 q_{1}^{2} - 2 q_{2}^{2} + 1}{m}\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\0 & 0 & 0\\\\0 & 0 & 1.0\\\\0 & -1.0 & 0\\end{matrix}\\right]$$" - ], - "text/plain": [ - "⎡ -0.01⋅ux -0.01⋅uy -0.01⋅uz ⎤\n", - "⎢──────────────────── ──────────────────── ────────────────────⎥\n", - "⎢ _________________ _________________ _________________⎥\n", - "⎢ ╱ 2 2 2 ╱ 2 2 2 ╱ 2 2 2 ⎥\n", - "⎢╲╱ ux + uy + uz ╲╱ ux + uy + uz ╲╱ ux + uy + uz ⎥\n", - "⎢ ⎥\n", - "⎢ 0 0 0 ⎥\n", - "⎢ ⎥\n", - "⎢ 0 0 0 ⎥\n", - "⎢ ⎥\n", - "⎢ 0 0 0 ⎥\n", - "⎢ ⎥\n", - "⎢ 2 2 ⎥\n", - "⎢- 2⋅q₂ - 2⋅q₃ + 1 2⋅(-q₀⋅q₃ + q₁⋅q₂) 2⋅(q₀⋅q₂ + q₁⋅q₃) ⎥\n", - "⎢─────────────────── ────────────────── ───────────────── ⎥\n", - "⎢ m m m ⎥\n", - "⎢ ⎥\n", - "⎢ 2 2 ⎥\n", - "⎢ 2⋅(q₀⋅q₃ + q₁⋅q₂) - 2⋅q₁ - 2⋅q₃ + 1 2⋅(-q₀⋅q₁ + q₂⋅q₃) ⎥\n", - "⎢ ───────────────── ─────────────────── ────────────────── ⎥\n", - "⎢ m m m ⎥\n", - "⎢ ⎥\n", - "⎢ 2 2 ⎥\n", - "⎢ 2⋅(-q₀⋅q₂ + q₁⋅q₃) 2⋅(q₀⋅q₁ + q₂⋅q₃) - 2⋅q₁ - 2⋅q₂ + 1 ⎥\n", - "⎢ ────────────────── ───────────────── ─────────────────── ⎥\n", - "⎢ m m m ⎥\n", - "⎢ ⎥\n", - "⎢ 0 0 0 ⎥\n", - "⎢ ⎥\n", - "⎢ 0 0 0 ⎥\n", - "⎢ ⎥\n", - "⎢ 0 0 0 ⎥\n", - "⎢ ⎥\n", - "⎢ 0 0 0 ⎥\n", - "⎢ ⎥\n", - "⎢ 0 0 0 ⎥\n", - "⎢ ⎥\n", - "⎢ 0 0 1.0 ⎥\n", - "⎢ ⎥\n", - "⎣ 0 -1.0 0 ⎦" - ] - }, - "execution_count": 10, - "metadata": {}, - "output_type": "execute_result" - } - ], - "source": [ - "sp.simplify(f.jacobian(u)) # B" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Ref\n", - "\n", - "- Python implementation of 'Successive Convexification for 6-DoF Mars Rocket Powered Landing with Free-Final-Time' paper\n", - "by Michael Szmuk and Behçet Açıkmeşe.\n", - "\n", - "- inspired by EmbersArc/SuccessiveConvexificationFreeFinalTime: Implementation of \"Successive Convexification for 6-DoF Mars Rocket Powered Landing with Free-Final-Time\" https://github.com/EmbersArc/SuccessiveConvexificationFreeFinalTime\n", - "\n" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.8" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/ArmNavigation/two_joint_arm_to_point_control/Planar_Two_Link_IK.ipynb b/ArmNavigation/two_joint_arm_to_point_control/Planar_Two_Link_IK.ipynb deleted file mode 100644 index a96f0ea2f4..0000000000 --- a/ArmNavigation/two_joint_arm_to_point_control/Planar_Two_Link_IK.ipynb +++ /dev/null @@ -1,423 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "## Two joint arm to point control\n", - "\n", - "![TwoJointArmToPointControl](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/two_joint_arm_to_point_control/animation.gif)\n", - "\n", - "This is two joint arm to a point control simulation.\n", - "\n", - "This is a interactive simulation.\n", - "\n", - "You can set the goal position of the end effector with left-click on the ploting area.\n", - "\n", - "\n", - "\n", - "### Inverse Kinematics for a Planar Two-Link Robotic Arm\n", - "\n", - "A classic problem with robotic arms is getting the end-effector, the mechanism at the end of the arm responsible for manipulating the environment, to where you need it to be. Maybe the end-effector is a gripper and maybe you want to pick up an object and maybe you know where that object is relative to the robot - but you cannot tell the end-effector where to go directly. Instead, you have to determine the joint angles that get the end-effector to where you want it to be. This problem is known as inverse kinematics.\n", - "\n", - "Credit for this solution goes to: https://robotacademy.net.au/lesson/inverse-kinematics-for-a-2-joint-robot-arm-using-geometry/\n", - "\n", - "First, let's define a class to make plotting our arm easier.\n" - ] - }, - { - "cell_type": "code", - "execution_count": 1, - "metadata": {}, - "outputs": [], - "source": [ - "%matplotlib inline\n", - "from math import cos, sin\n", - "import numpy as np\n", - "import matplotlib.pyplot as plt\n", - "\n", - "class TwoLinkArm:\n", - " def __init__(self, joint_angles=[0, 0]):\n", - " self.shoulder = np.array([0, 0])\n", - " self.link_lengths = [1, 1]\n", - " self.update_joints(joint_angles)\n", - " \n", - " def update_joints(self, joint_angles):\n", - " self.joint_angles = joint_angles\n", - " self.forward_kinematics()\n", - " \n", - " def forward_kinematics(self):\n", - " theta0 = self.joint_angles[0]\n", - " theta1 = self.joint_angles[1]\n", - " l0 = self.link_lengths[0]\n", - " l1 = self.link_lengths[1]\n", - " self.elbow = self.shoulder + np.array([l0*cos(theta0), l0*sin(theta0)])\n", - " self.wrist = self.elbow + np.array([l1*cos(theta0 + theta1), l1*sin(theta0 + theta1)])\n", - " \n", - " def plot(self):\n", - " plt.plot([self.shoulder[0], self.elbow[0]],\n", - " [self.shoulder[1], self.elbow[1]],\n", - " 'r-')\n", - " plt.plot([self.elbow[0], self.wrist[0]],\n", - " [self.elbow[1], self.wrist[1]],\n", - " 'r-')\n", - " plt.plot(self.shoulder[0], self.shoulder[1], 'ko')\n", - " plt.plot(self.elbow[0], self.elbow[1], 'ko')\n", - " plt.plot(self.wrist[0], self.wrist[1], 'ko')" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Let's also define a function to make it easier to draw an angle on our diagram." - ] - }, - { - "cell_type": "code", - "execution_count": 2, - "metadata": {}, - "outputs": [], - "source": [ - "from math import sqrt\n", - "\n", - "def transform_points(points, theta, origin):\n", - " T = np.array([[cos(theta), -sin(theta), origin[0]],\n", - " [sin(theta), cos(theta), origin[1]],\n", - " [0, 0, 1]])\n", - " return np.matmul(T, np.array(points))\n", - "\n", - "def draw_angle(angle, offset=0, origin=[0, 0], r=0.5, n_points=100):\n", - " x_start = r*cos(angle)\n", - " x_end = r\n", - " dx = (x_end - x_start)/(n_points-1)\n", - " coords = [[0 for _ in range(n_points)] for _ in range(3)]\n", - " x = x_start\n", - " for i in range(n_points-1):\n", - " y = sqrt(r**2 - x**2)\n", - " coords[0][i] = x\n", - " coords[1][i] = y\n", - " coords[2][i] = 1\n", - " x += dx\n", - " coords[0][-1] = r\n", - " coords[2][-1] = 1\n", - " coords = transform_points(coords, offset, origin)\n", - " plt.plot(coords[0], coords[1], 'k-')" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Okay, we now have a TwoLinkArm class to help us draw the arm, which we'll do several times during our derivation. Notice there is a method called forward_kinematics - forward kinematics specifies the end-effector position given the joint angles and link lengths. Forward kinematics is easier than inverse kinematics." - ] - }, - { - "cell_type": "code", - "execution_count": 3, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "

" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "arm = TwoLinkArm()\n", - "\n", - "theta0 = 0.5\n", - "theta1 = 1\n", - "\n", - "arm.update_joints([theta0, theta1])\n", - "arm.plot()\n", - "\n", - "def label_diagram():\n", - " plt.plot([0, 0.5], [0, 0], 'k--')\n", - " plt.plot([arm.elbow[0], arm.elbow[0]+0.5*cos(theta0)],\n", - " [arm.elbow[1], arm.elbow[1]+0.5*sin(theta0)],\n", - " 'k--')\n", - " \n", - " draw_angle(theta0, r=0.25)\n", - " draw_angle(theta1, offset=theta0, origin=[arm.elbow[0], arm.elbow[1]], r=0.25)\n", - " \n", - " plt.annotate(\"$l_0$\", xy=(0.5, 0.4), size=15, color=\"r\")\n", - " plt.annotate(\"$l_1$\", xy=(0.8, 1), size=15, color=\"r\")\n", - " \n", - " plt.annotate(r\"$\\theta_0$\", xy=(0.35, 0.05), size=15)\n", - " plt.annotate(r\"$\\theta_1$\", xy=(1, 0.8), size=15)\n", - "\n", - "label_diagram()\n", - "\n", - "plt.annotate(\"Shoulder\", xy=(arm.shoulder[0], arm.shoulder[1]), xytext=(0.15, 0.5),\n", - " arrowprops=dict(facecolor='black', shrink=0.05))\n", - "plt.annotate(\"Elbow\", xy=(arm.elbow[0], arm.elbow[1]), xytext=(1.25, 0.25),\n", - " arrowprops=dict(facecolor='black', shrink=0.05))\n", - "plt.annotate(\"Wrist\", xy=(arm.wrist[0], arm.wrist[1]), xytext=(1, 1.75),\n", - " arrowprops=dict(facecolor='black', shrink=0.05))\n", - "\n", - "plt.axis(\"equal\")\n", - "\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "It's common to name arm joints anatomically, hence the names shoulder, elbow, and wrist. In this example, the wrist is not itself a joint, but we can consider it to be our end-effector. If we constrain the shoulder to the origin, we can write the forward kinematics for the elbow and the wrist.\n", - "\n", - "$elbow_x = l_0\\cos(\\theta_0)$ \n", - "$elbow_y = l_0\\sin(\\theta_0)$ \n", - "\n", - "$wrist_x = elbow_x + l_1\\cos(\\theta_0+\\theta_1) = l_0\\cos(\\theta_0) + l_1\\cos(\\theta_0+\\theta_1)$ \n", - "$wrist_y = elbow_y + l_1\\sin(\\theta_0+\\theta_1) = l_0\\sin(\\theta_0) + l_1\\sin(\\theta_0+\\theta_1)$ \n", - "\n", - "Since the wrist is our end-effector, let's just call its coordinates $x$ and $y$. The forward kinematics for our end-effector is then\n", - "\n", - "$x = l_0\\cos(\\theta_0) + l_1\\cos(\\theta_0+\\theta_1)$ \n", - "$y = l_0\\sin(\\theta_0) + l_1\\sin(\\theta_0+\\theta_1)$ \n", - "\n", - "A first attempt to find the joint angles $\\theta_0$ and $\\theta_1$ that would get our end-effector to the desired coordinates $x$ and $y$ might be to try solving the forward kinematics for $\\theta_0$ and $\\theta_1$, but that would be the wrong move. An easier path involves going back to the geometry of the arm." - ] - }, - { - "cell_type": "code", - "execution_count": 4, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAXcAAAD8CAYAAACMwORRAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADl0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uIDIuMi4yLCBodHRwOi8vbWF0cGxvdGxpYi5vcmcvhp/UCwAAIABJREFUeJzt3Xd4FNX6wPHvIYRACCBIRCA0le6lhiIIAsJPQBFBQJqKEqMIIk1aLoI0kV5sVEGJFEGlBIQr6pUrgkFICCX0Ki0QaiD9/P6YJISQssnO7mY37+d55tns7NmZlyW8nD1z5j1Ka40QQgjXks/RAQghhDCfJHchhHBBktyFEMIFSXIXQggXJMldCCFckCR3IYRwQZLchRDCBUlyF0IIFyTJXQghXFB+R524ZMmSumLFio46vRBCOKW///77itbaO6t2DkvuFStWZPfu3Y46vRBCOCWl1GlL2smwjBBCuCBJ7kII4YIkuQshhAuS5C6EEC5IkrsQQrggSe5COIHAwEAqVqxIvnz5qFixIoGBgY4OSeRyDpsKKYSwTGBgIP7+/ty5cweA06dP4+/vD0CvXr0cGZrIxaTnLkQuFxAQkJLYk925c4eAgAAHRSScgSR3IXK5M2fOZGu/ECDJXYhcr3z58kk/PZu0pd0vxIMkuQuRy40ZMwalFPDvpA08PT2ZNGmSQ+MSuZskdyFyOW9vb/Lly4d7PuOfa4UKFViwYIFcTBWZktkyQuRyL774IidPnuTVBlFw/Rq/nTrl6JCEE5CeuxC5VGxsLDt27ACgXLlyEB8H+d0dHJVwFpLchcilpk2bRtOmTQkNDTV2xMWDu3zZFpbJMrkrpZYopS4rpfZn0a6BUipeKdXFvPCEyJvCw8MZP348Xbt2pXbt2gDMLxnA/EZfOTgy4Sws6bkvBdpm1kAp5QZ8Amw1ISYh8rTExET8/f0pXLgwc+fOTdlfNWoPVStEOzAy4Uyy/I6ntf5dKVUxi2bvAWuBBibEJESetmDBArZv386SJUt49NFHjZ1as+HKU3C1CR0cG55wElYP4CmlygKdgJZIchfCavnz56djx4706dPn3s6oKGYkvA97H5PkLixixgXV2cAIrXViVg2VUv5Kqd1Kqd0REREmnFoI1+Pn58cPP/yQdONSkqtXjUeZLSMsZEZy9wVWKqVOAV2Az5VSL6XXUGu9QGvtq7X29fbOcvFuIfKUdevW8fXXX6O1vj+xA0RGGo/uktyFZaweltFaV0r+WSm1FNiotf7R2uMKkZdERkbi7+9PuXLl6NmzJ/nz50/bAHCTqZDCYln+piilVgAtgJJKqXPAWMAdQGv9pU2jEyKPGDZsGFevXmXLli0PJnZISu7eMiwjLGbJbJkelh5Ma93HqmiEyIN+/vlnvvrqK0aOHEmdOnXSbxQZyTcMgc+DgcJ2jU84J/mOJ4QDxcTE8Pbbb1O5cmU+/PDDjBtGRlKOc/BkMfsFJ5yaJHchHMjDw4OZM2fy8MMPU6hQoYwbRkayyr03rC/EK6/YLz7hvCS5C+EgCQkJuLm50bFjx6wbX73KF+pd+AJJ7sIiUjhMCAeIi4ujadOmfPbZZ5a9ITJSZsqIbJHkLoQDzJgxg127dlG2bFnL3hAZKTNlRLZIchfCzo4ePcq4ceN4+eWXeemldO/3e5D03EU2SXIXwo4SExN56623KFiwIPPmzbP8jdJzF9kkyV0IOwoODmb79u1Mnz6d0qVLW/YmrSEykjVdVrJmjW3jE65DvucJYUeNGjUiLCyM6tWrW/6mO3cgJoaSPgWhpO1iE65Feu5C2Mm+ffsAqFGjxoOFwTKTVDRsaXhjli61QWDCJUlyF8IOvv/+e2rXrs3mzZuz/+bk5B5cQ5K7sJgkdyFs7Pr16/Tv35+6devSpk2b7B8gudyvXFAV2SBj7kLY2AcffEBERARBQUHpV3zMSkotd/nnKiwnPXchbOjXX39l0aJFDB06lHr16uXsINJzFzkgyV0IG7pw4QJ16tRh7NixOT+I9NxFDshvixA21LNnT7p3706+fFb0o65ehYIF2fSTm3mBCZcnPXchbCAkJIRly5ahtbYusYPRcy9RAk9P8PQ0Jz7h+qTnLoTJ4uPj6du3L+fPn6dTp04ULVrUugMmJffPPzeevvuu9TEK15dll0IptUQpdVkptT+D13sppfYppcKUUjuUUrXND1MI5zFz5kz27NnDp59+an1ih5Tkvno1rF5t/eFE3mDJ98WlQNtMXj8JPKO1/hcwAVhgQlxCOKVjx44xduxYXnrpJTp37mzOQZOSuxDZkWVy11r/DkRm8voOrfW1pKc7AR+TYhPCqWit8ff3p0CBAnz22WfZKzGQGUnuIgfMHnPvC2R4f7VSyh/wByhfvrzJpxbCsZRSDBo0iKioKMqUKWPega9eNZL7cfMOKVyfacldKdUSI7k/nVEbrfUCkoZtfH19tVnnFsLRtNYopXjxxRfNPfDduxAdDQ8/bO5xhcszZSqkUqoWsAjoqLW+asYxhXAmvXv35pNPPjH/wMk3MJUowW+/wW+/mX8K4ZqsTu5KqfLA98CrWusj1ockhHP54Ycf+Pbbb0lMTDT/4KmSuxDZkeWwjFJqBdACKKmUOgeMBdwBtNZfAh8CDwOfJ11Aitda+9oqYCFyk+SKj7Vr12bYsGHmnyBVcp8+3fjRFqcRrifL5K617pHF636An2kRCeFERo4cyaVLl1i/fj3u7jYo7JUquW/caPwoyV1YQsoPCJFDp0+fZvHixQwePBhfXxt9WZVhGZFDUn5AiByqUKECf/31F1WqVLHdSa4mzU+Q2TIim6TnLkQOnDp1CoC6detSuHBh250oMhIKFJCKYSLbJLkLkU2hoaFUrlyZpfZY0DT57lSlKFQIChWy/SmFa5BhGSGyIT4+Hj8/P0qUKGH+DUvpSVV6ICdra4u8S5K7ENkwZ84cdu/ezapVqyhhj4ucUldG5JAMywhhoRMnTjBmzBg6dOhA165d7XPSVMl9wgRjE8ISktyFsNCBAwcoUaIEn3/+uXkVH7OSXDQM2LbN2ISwhCR3ISzUoUMHjh8/jo+PHataR0bKNEiRI5LchcjCpUuX+Prrr9Fa4+HhYd3BVq40pjbGxmbdNjoa7tyRMXeRI5LchcjCwIEDeeuttzh9+rT1BwsNhRo1jASflWtJa+BIchc5ILNlhMjE+vXrWb16NRMmTKBixYrWHzA0FGpbuMxwmtIDMjojskOSuxAZuHHjBu+++y5PPvkkw4cPN+egISGWV/5Kk9zXrjUnBJE3SHIXIgOjRo3i/PnzrF27lgKWDKNkJSICLlyAOnUsay9Fw4QVJLkLkYH27dvj4+NDo0aNzDlgaKjxaOmwTJqiYaNGGU8//ticcIRrk+QuRAZeeOEFXnjhBfMOGBICZcveGzzv1w/Wr4fz50Gns6Rwmp77n3+aF4pwfTJbRog0JkyYwEcffYROL+FaIzT0/iGZHj1gz56M20dGQv784OVlbhwiT8gyuSulliilLiul9mfwulJKzVVKHVNK7VNK1TM/TCHsIywsjPHjx3P8+HHz70JNO1OmeXMoVSrj9qkqQgqRXZb03JcCbTN5vR1QOWnzB76wPiwh7C8hIQE/Pz8eeughZs6cae7BY2IgPNzy8XaQomHCKpasofq7UqpiJk06Al9r4zvsTqXUQ0qp0lrrCybFKIRdfPrpp/z11198++23lCxZ0tyDHzwIcXGWz5SBB5K7PaseCOdnxgXVssDZVM/PJe2T5C6cxq1btxg7dizt27ene/fu5p8gNNRYTemJJyx/z9Wr92X05cvND0u4LrvOllFK+WMM3VC+fHl7nlqITBUpUoRffvkFb29v21R87NPH2LIjMjJ7wzhCpGLGbJl/gHKpnvsk7XuA1nqB1tpXa+3r7e1twqmFsN6VK1cAqFevHuXKlcuitYn8/O71zH18jOeppRmWGTTI2ISwhBnJfT3wWtKsmcbADRlvF87i8uXLVKtWjWnTptn/5IsWwblzxhz3c+eM58liY+H27fuSe0iIsQlhiSyHZZRSK4AWQEml1DlgLOAOoLX+EtgEtAeOAXeAN2wVrBBmGzRoEDdv3uT55593dCj3k4qQwkqWzJbpkcXrGuhvWkRCZFNsbGyOar8EBQWxYsUKxo0bR40aNWwQmRWkroywktyhKpxKYmIiXl5ezJ49m4EDB+Lt7U2d7EwvTHLr1i369etHzZo1GZVctCU3keQurCS1ZYRTOXHiBFFRUUydOpVOnTrx7bff5qjXvnfvXm7evMmqVavMqfhotjRFwwCqVHFQLMIpSXIXTiUsLAyAN998k4kTJ+b4OM2bN+fMmTMULVrUrNDMlU7PfcECB8UinJIMywinsm/fPjw9PQkICMjR+2NiYli1ahVa69yb2EGGZYTVJLkLpxIWFkaLFi0oVKhQjt7/8ccf0717d3bu3GlyZCaLjAQ3N0j1H5C/v7EJYQlJ7sKphIWFUa9ezgqPHjhwgMmTJ9OrVy+eeuopkyMzWWQkFC9+X0XII0eMTQhLSHIXTuPu3bscO3aM2jm4JT+54mPRokWZNWuWDaIzmVSEFFaSC6rCaRw4cIDExMQcJfcvvviCnTt38s033+AUpS+uXr1vpowQ2SU9d+E0wsLCKFy4MI8//ni23/v444/Tt29fevXqZYPIbEB67sJKktyF03jjjTe4ffs2+fJl/9e2Xbt2LFq0yDYVH20hneRep072ysGLvE2Su3Bpq1atYty4ccTFxTk6lOxJJ7nPnm1sltq1axfPPPMMnp6ePPbYY6xevdrkIEVuJslduKwrV64wYMAAfvrppxz19h0mLg5u3rRqWObXX3+lVatWNGvWjKCgIJo3b86rr77KyZMnTQxU5GZO9BsvRPYMHjyY69evs2jRItzc3BwdjuWuXzce0yT33r2NLStRUVH06tWLkSNHMnHiRFq2bMn8+fNxd3fnxx9/tEHAIjeS2TLCJf30008sX76cMWPG8OSTTzo6nOxJriuTJrmfO2fZ2xcuXEhcXBzDhg1L2efh4YG3tzenT582K0qRy0lyFy4nISGBAQMGUK1atRyXKXCo5NIDOZwKGRgYSOfOnXF3dyc+Pj5lf1RUFO7u7mZEKJyAJHfhctzc3Pjuu+9ISEjAw8PD0eFknxV1Za5fv87ff//N7t27WZBOpTFZuzjvkOQuXEpUVBSFCxembt26jg4l56xI7qGhoWitWbduHWXKlEnZ/9dff9G/f/+U2vf9+vVj/fr1nD9/HmO9HeFq5IKqcBmxsbE0btyY0aNHOzoU62SQ3J96ytgyc/bsWQBatWqFr69vynbx4kWKFClCw4YNAejRowd79uwxPXSRe1iU3JVSbZVSh5VSx5RSI9N5vbxS6lel1F6l1D6lVHvzQxUic5988gn79++nSZMmjg7FOpGRRsGwYsXu2/3xx8aWmeQx9vz5730p11qzcuVKunXrljJM1bx5c0qVKmVu3CJXyTK5K6XcgM+AdkANoIdSKu2Ck/8GVmut6wLdgc/NDlSIzBw6dIiJEyfSvXt3XnjhBUeHY53kipA5mJtfoUIFAA4fPpyyb8mSJZw9ezZ3LicobMaS356GwDGt9QmtdSywEuiYpo0GkgtPFwPOmxeiEJlLTEzEz88PLy8v5syZ4+hwrJdB0bCXXza2zDRt2pSyZcvSv39/tm3bxvTp0xkwYADz5s3LUU0e4bwsuaBaFjib6vk5oFGaNuOArUqp94DCQGtTohPCAocOHSIsLIxPP/2URx55xNHhWC+DomHJ098zU6BAAdasWcPbb7/N888/T7Vq1VKmRoq8xazZMj2ApVrrGUqpp4BvlFJPaq0TUzdSSvkD/iBTsoR5atasydGjR10jsYOR3K0oS9y4cWNCQ0NNDEg4I0uGZf4ByqV67pO0L7W+wGoArfWfQEGgZNoDaa0XaK19tda+TlFTW+RqWmu2bNmC1ppSpUo5T8XHrNih3K+fnx8+Pj4A+Pj44OfnZ9PzCfuzpOceDFRWSlXCSOrdgZ5p2pwBngWWKqWqYyT3CDMDFSKtVatW0aNHD1auXMkrr7zi6HDMY4fkvmjRIpseXzhelsldax2vlBoAbAHcgCVa6wNKqfHAbq31emAosFApNRjj4mofLXdGCBu6evUqAwcOpEGDBnTp0sXR4ZgnIcEoHJZOcn/2WQfEI5yWRWPuWutNwKY0+z5M9fNBoKm5oQmRsaFDh3Lt2jV+/vln56r4mJVr14zHdJL7mDF2jkU4NblDVTidrVu3smzZMkaMGEGtWrUcHY65rCwaJkQySe7C6eTPn582bdrw73//29GhmC+TujLt2hmbEJaQwmHC6bRq1YpWrVo5OgzbyCS5371r51iEU5Oeu3AawcHBjB07lpiYGEeHYjOHwsL4Gthy4ACHDh1y6T+rsC3puQunEBcXR9++fbl69SpDhgxxzjrtFti6axeDAPr2BYza9FWrVqVhw4ZcvDiZ4sVLAK75ZxfmkuQunMK0adMICwtj3bp1FEtTLdGVvFW9Os//8AMXf/uNU2fPEh4eTkhICBs3buTKldcBqF9/KN27d6d3796ULl3awRFb7tq1a3z88cdER0czd+5cR4fj+rTWDtnq16+vhbBEeHi49vDw0F27dnV0KLY3YIDWxYs/sDsxMVEPGXJet2//i27YsKEGtJubm+7SpYvesWOHAwLNnk2bNunixYtrpZTu27evTkxMdHRITgvj/qIsc6yMuYtc791338XT05N58+Y5OhTby+DuVKUUM2aUJiioJbt27eLw4cMMGTKEbdu20aRJE9q0acPu3bsdEHDGEhMTiUy6QFy9enWefvppQkJCWLRokeuUisjFJLmLXG/GjBksW7YsbywuYWHpgSpVqjB16lTOnDnD9OnTCQkJoUGDBvTp04eICMdX/ti2bRu+vr707GlUKqlYsSLr1693vfsScjFJ7iLXiouLA6BOnTp06NDBwdHYSSbJvUULY0vNy8uLoUOHcvz4cUaMGMG3335L9erVWb16tc1DTc++ffto164drVu3JjIykldffVXWaHUQSe4iV9Ja07VrV/r37+/oUOwrh0XDihYtypQpU9i7dy+PPfYYr7zyCn379uWuHSfHr127ljp16rBr1y5mzJhBeHg4vXr1kiEYB5HkLnKlNWvWsG7dOipVquToUOzLyoqQNWvW5I8//mD06NEsWbKEZs2a8c8/aSt0m+f69evs378fgDZt2hAQEMDx48cZMmQIBQsWtNl5RdYkuYtcJzIykgEDBlC/fn0GDRrk6HDsJyHBKBxmZblfd3d3Jk2axPr16zl8+DCNGzfm0KFDJgVpiImJYfbs2Tz++ON0794drTVFixZlwoQJFC9e3NRziZyR5C5ynWHDhnH16lUWLVpE/vzOdytGZGQkb7/9NiVLlqREiRKMGDECgKeffjrzGT83boDWphUN69ChA9u3bycuLo7mzZsTFhZm9TETExNZsWIF1atXZ/DgwdSvX59vvvlGhl5yIef7lyNc2qVLl1i7di0ffPABderUcXQ42Xb9+nWaNGmCl5cXS5YsYf/+/QQEBFCxYkWOHz/OW2+9lfGbM6krA9CtW/bjqVOnDtu3b6dly5a0bt2a//3vf1SuXDn7B0ry/fff07NnT2rXrs2WLVv4v//7vxwfS9iYJZPhbbHJTUwiI2fPntV37txxdBg5MmzYMF2sWDEdERGRsq9kyZK6WLFievr06Zm/edcurUHrjRtNjys8PFx7e3vrSpUq6cuXL2frvWFhYXrDhg1aa63j4+P1d999pxMSEkyPUVgGuYlJOJvg4GC01vj4+FCoUCFHh5NtWmuWLVvGW2+9RcmS95YQLlasGO7u7rzzzjuZHyCLnvudO8aWE1WrVmXjxo1cuHCBLl26pEwzzcw///xD3759qV27NoMHDyYxMRE3Nze6dOlCvnySOnI7+RsSucKePXto3LgxM2fOdHQoOXb48GEiIiJo06bNffsTEhJ4//33KVy4cOYHyCK5t29vbDnVsGFDFi5cyO+//55pLfwbN24QEBBA5cqVWb58OYMGDWLnzp2S0J2MRX9bSqm2SqnDSqljSqmRGbTpppQ6qJQ6oJT61twwhStLrvhYqlQp+iZVQ3RGJ0+eBKBChQop+3bs2MGpU6csu36QRXI3Q+/evXnrrbeYNm0av//+e7pt/v77byZPnkznzp05fPgwM2bM4GFZGcrpZHlBVSnlBnwGtAHOAcFKqfXaWDc1uU1lYBTQVGt9TSn1iK0CFq5n5syZhISE8P333/PQQw85OpwcS17LNbmeitaa4cOHp/ycpatXjUcbTyWcNWsWP//8M++88w4hISG4u7vz3Xffcfr0aT744ANatWrF4cOHqVKlik3jELZlSc+9IXBMa31Cax0LrAQ6pmnzFvCZ1voagNb6srlhCld19OhRxo0bR+fOnenUqZOjw7FK/fr1KViwIMOHD+enn37izTffJDIyksqVK7Ny5UpOnTqV+QEiI6FYMbDx9M/ChQszb948Dh06xIABA2jUqBGvvPIKq1evJj4+HkASuwuwJLmXBc6men4uaV9qVYAqSqk/lFI7lVJtzQpQuLaIiAiqVKniEhUfH374YZYtW8a5c+d48cUX2bdvH0FBQQQEBLBu3bqs671YeXdqdlSrVo1HH32UhQsXcvbsWZYuXcrOnTud8r4CkT6z/ibzA5WBFoAP8LtS6l9a6+upGyml/AF/gPLly5t0auHMmjRpQkhIiMvcBNOtWze6pZmQXqlSJV5//fWs35xFcu/Tx8rgMIaHlFLEx8cTHR3Nc889x8qVK516OEykz5Lk/g9QLtVzn6R9qZ0Ddmmt44CTSqkjGMk+OHUjrfUCYAGAr6+vlIrLw86fP8/ixYsZPny4yy6Zl5WEhAQOHz7MiRMniI6OJu7IEco99BBPZ9DemuR+8+ZNpk2bxsmTJ1m+fDlVq1blwoULUv/FhVmS3IOBykqpShhJvTvQM02bH4EewFdKqZIYwzQnzAxUuJYBAwawefNmevTowRNPPOHocOwmMTGRLVu2sHTpUrZs2cKNGzfue71ruXIZJvcrV4zHVFPosxQbG8uCBQsYP348ERERdO/enbi4ONzd3SWxu7gsk7vWOl4pNQDYArgBS7TWB5RS4zHulFqf9Nr/KaUOAgnAB1rrq7YMXDiv77//nh9++IEpU6bkqcT+66+/MnjwYEJDQ/H29qZr1640a9aMqlWrUrhwYfI3a0axli0zfH+XLsbjb79Zdr6QkBC6du3KsWPHaNGiBdOmTcPX19f6P4hwChaNuWutNwGb0uz7MNXPGhiStAmRoevXr9O/f3/q1q3L0KFDHR2OXcTFxTFs2DDmzp1LpUqVWLZsGd27d6dAgQL3GiUmws2bYMK1qNu3b+Pl5UX58uV59NFHmTNnDu3atXOZ6xrCMnJpXNjViBEjiIiIICgoKE/MzLhz5w6dOnVi69atDBw4kClTpqRfWuHmTSPBWzFbJjw8nJEjR3L27FmCg4MpUaIE27dvtyJ64cxc/1+XyFX69etHnTp1qFevnqNDsbmEhAS6du3Kf/7zHxYvXsybb76ZcWMr7k69cOECH330EYsWLcLT05ORI0cSHx9//zcDkedIchd2kTwFr06dOk5Zyjcnxo0bx6ZNm/jiiy8yT+yQ4+S+a9cunn32WWJiYnj33XcZM2YM3t7eOYxYuBJJ7sIuRo8ezYULF1i8eHHKbfquLDQ0lI8//pjXX38962qQYFFy79fPeIyLi+PYsWNUr16dunXr8sYbb/D+++/nqYvTImtS5k3Y3N69e5k2bRr58+fPE4kdYNSoURQrVoxZs2ZZ9gYLknu3bpoCBX7gySef5Nlnn+Xu3bsUKFCAefPmSWIXD5DkLmwqPj4ePz8/SpYsybRp0xwdjl0cOnSIzZs3M3ToUMvXE00uGpZB9cUdO3bQoEFnOnceiJubGwsWLJB56iJTMiwjbGrWrFns2bOH7777Ls8snBwYGIibm1v2yhcn99zT+Yz++usvmjZtSoECf1ClSiX27fPOEzONhHWk5y5sJjo6mpkzZ9KxY0defvllR4djN1u3buWpp56iVKlSlr8pMhKKFAF3d8BYS3bDhg0ANGjQgMWLF9OwYSNKly4tiV1YRH5LhM0ULFiQ3bt3ky9fvjxzA018fDyhoaEMGjTI4vcEBgYSsHAhZ6Ki8ClfngYNGrBlyxbc3Nz4559/8PLy4s033+Trr20YuHA50nMXNnH06FG01pQtW5bSpUvb56QrV0KBAhAba5/zpePChQvExsby+OOPW9Q+MDAQf39/TkdFoYGzZ8/y/fffU7NmTXbv3o2Xl5dtAxYuS5K7MN3Fixdp2LBhyipEdhMaCjVqGAneQW7dugUYi2JbImD0aO6ks+r1pUuXqFy5sqmxibxFhmWE6d577z3u3r2Ln5+ffU8cGgq1a9v3nGkkj4cnr2iUqZ07OXPmTLovpbc/j5TiESaRnrsw1Y8//siaNWv48MMPqVq1qn1PHhLi8OT+yCPG8sHnz5/PuNGRI0aJx6eeony+9P8JpreYTYcOxiaEJSS5C9PcuHGD/v37U6tWLT744AP7njwiAi5cAAeXNnjooYcoXbo0oaGhD754+TIMGAA1a8JPP8FHHzFp4UI8PT3va+bp6cmkSZMeePvhw8YmhCVkWEaY5tSpU3h4eLB48WLck6b02U1yMnVwzx2gWbNm/PLLLyQmJpIvXz6IioKZM2HqVLh7F/z9YexYKFWKXgAeHgQEBHDmzBnKly/PpEmT6NWr1wPHfftt49HSeu4ib5PkLkxTu3Ztjhw54ph52CEhULbsvTs89++H116DW7egenUIDDTmkdtBp06dWL16Nb/85z+0PnPGSOQXLkDnzjB5MqQZrurVq1e6yVwIa8iwjLBadHQ0M2bMICYmxnE32ISG3j8k8847MHEiHD0K1aoZvWY7ealjR7yLFWP6yy8bvfRKleCPP2Dt2gcSuxC2IsldWG3ChAkMGzaMnTt3Oi6I1DNlLl2CkyehfXvjed++RmK1h127KNi2LcNv3OBEbCzXvv4a/vc/aNLEPucXIok7ywlXAAAWCklEQVRFyV0p1VYpdVgpdUwpNTKTdi8rpbRSShZqzCNCQ0OZOnUqffr04ZlnnnFMEDExEB5+L7mfOwc+PvdeL18ezp61bQzHjkG3btC4MYSHM3DuXA5cv07xV1+FPHJ3rshdsvwOrZRyAz4D2gDngGCl1Hqt9cE07YoA7wO7bBGoyH2SKz6WKFGCGTNmOC6QgwchLu7esIzW9jt3RARMmABffGHcPDV2LAwdSgEbjO//+9+mH1K4MEsGSBsCx7TWJwCUUiuBjsDBNO0mAJ8Adp4DJxxlzpw57N69m1WrVlHCirU/rRYaCp6ekFzT3MfH6L0nO3Pm/p68Ge7cgdmzYcoU42c/PyOx27DUQuvWNju0cEGWDMuUBVJ/pz2XtC+FUqoeUE5rHZTZgZRS/kqp3Uqp3REREdkOVuQurVu3ZsSIEXTt2tWxgfTpY0w3TL4h6NFHoWJF2LTJeL54sTFTxQwJCbBkCVSuDAEB0KoVhIXBl1/aNLGDMSEoJMSmpxAuxOqpDUqpfMBMoE9WbbXWC4AFAL6+vnb87ixsoXbt2tTOBfPK0/XFF/D66/D++8YMlcBA646ntfGfxYgRcOCAMba+ahU8/bQ58VogudCkzHMXlrCk5/4PUC7Vc5+kfcmKAE8CvymlTgGNgfVyUdV1LV26lNdee42oqChHh5KxWrVg715jKuTGjWBhIa907d5t9NBfeMG4eLtmDezYYdfELkR2WZLcg4HKSqlKSqkCQHdgffKLWusbWuuSWuuKWuuKwE7gRa31bptELBzq0qVLDBkyhBMnTlCoUCFHh2NbJ05Ajx7QoIHRW//0U+Pi7csvywwYketlmdy11vHAAGALcAhYrbU+oJQar5R60dYBitzl/fffJyoqioULFxq31ruiq1dh8GDj5qf1641pKseOQf/+KSslCZHbWTTmrrXeBGxKs+/DDNq2sD4skRtt2LCBVatWMX78eKpXr+7ocMx39y7MmWPMgLl1y7j5adw4KFPG0ZEJkW1K23NOcCq+vr56924ZuXEWWmtq1aoFwN9//00BBy6IYbqEBPjmGxgzxphC2aGDkeBr1HB0ZPfZscN4lJtd8zal1N9a6yyvaUrhMGERpRRbtmzh2rVrrpPYtYYtW2D4cGM6Y4MGsHw5OOpO2yxIUhfZ4aKDpsJMFy9eJDExkTJlylCzZk1Hh2OOPXugTRto186YI79qFezalWsTOxg99+TeuxBZkeQuMhUdHU3Lli154403HB2KOU6dgl69oH59487WuXPh0CGjLkwunwEzerSxCWEJSe4iU5MnTyY8PJyePXs6OhTrREYai5BWrQrff29kyWPH4L33HLqgthC2ImPuIkNhYWF8/PHHvPrqqzz33HOODidnoqNh3jxjkYybN41SBR99ZH6tGSFyGem5i3QlJCTg5+dH8eLFmTVrlqPDyb7ERPj6a6hSxbhg2qSJUZhl8WJJ7CJPkOQu0nXmzBkuXbrEnDlzeDh56TpnsXUr1Ktn1JZ55BH45RcICoJ//cvRkQlhNzIsI9JVqVIlDh486FwlBkJCjF76f/5jLG23YoVxodRF7qSdPdvREQhn4hq/9cI0Wmu++uoroqOj8fT0ROXyGSQAnD5tLIZdrx78/TfMmmXMgOne3WUSOxhrkaReJlaIzEjPXdxn+fLlvPnmmwC5f/rjtWvGhdJ584xpjMOHw8iR8NBDjo7MJn7+2XiURTuEJaT8gEhx+fJlqlevTtWqVdm+fTtubm6ODil90dHw2WcwaRJcv26MrY8fD+XKZf1eJ9aihfEo9dzzNkvLD7jOd1ZhtUGDBnHr1i0WLlyYOxN7YqKx6Ea1ajBsGDRqZIyzf/WVyyf27KhTB/z9H9zfuzc0a2b/eIRjyLCMACAoKIgVK1Ywbty43FliYNs2+OADYwGOunVh0SIZn8hAo0YQHHz/vr/+Mq4v79zpmJiE/UnPXQBQvnx5evXqxciRIx0dyv327TPqv7RubdxlGhhorIwkiT1DjRrB/v3G6FWywYPvrTsi8gZJ7gKAf/3rXyxfvhwPDw9Hh2I4e9a4m7ROHaOg14wZEB4OPXu61AwYW2jcGOLi7i2mvWqVUSdt8mTHxiXsS/6V5HF//vknr732GteuXXN0KIbr140ZL5Urw8qVxtj68eMwZAgULOjo6Bxq/nxjy0q1alC0qDE0Ex1trOk9ZAiUL2/7GEXuYdGYu1KqLTAHcAMWaa2npHl9COAHxAMRwJta69MmxypMFhMTg5+fH7du3SJ/fgdffomJgc8/h4kTjSmOvXvDhAlQoYJj48pFqla1rF2+fNCwoZHcb982EnxuG20Ttpflv2illBvwGdAGOAcEK6XWa60Ppmq2F/DVWt9RSvUDpgKv2CJgYZ4pU6Zw8OBBgoKCKFKkiGOCSEw0xg1GjzbK8f7f/8Enn8jdOunYsMF47NAh67aNGsGyZfDjjzB9Ojjqr1c4jiXDMg2BY1rrE1rrWGAl0DF1A631r1rrO0lPdwJSmSmXO3DgAJMmTaJnz560b9/eMUH8+qvRxezZE4oVM1ZF2rJFEnsGZswwNks0amSsGFihgrEUrMh7LEnuZYGzqZ6fS9qXkb7AZmuCErY3bNgwihYtymxHFCwJC4Pnn4dWreDyZaN64549Rq9dmMLb23icPh1y4y0LwvZMHWhVSvUGfIF01ypTSvkD/mBMvROOs3jxYo4cOYJ3chawh3Pn4MMPYelS44rf1KnGYhl5/EKpLUyebMwgddYy/MJ6liT3f4DUt//5JO27j1KqNRAAPKO1jknvQFrrBcACMMoPZDtaYbWbN2/i5eVFmTJlKFOmjH1OeuOGMY4+a5Yxxj5kiDHGXqKEfc6fR0RHG7cFrFlj3PMVGuroiIQjWZLcg4HKSqlKGEm9O3DfmmtKqbrAfKCt1vqy6VEKU2it6dGjB0opNmzYYPuKj7Gx8OWXRt2Xq1eNtUsnToSKFW173jzqv/81euuVKhnXqJ94wtERCUfKMrlrreOVUgOALRhTIZdorQ8opcYDu7XW64FpgBfwXVLCOKO1ftGGcYscWLFiBZs2bWL27Nm2Texaw3ffwahRcOKEMbY+bZpRklfk2DffZP76c88ZX4yEAKkKmWdcuXKF6tWr8/jjj/PHH3/YrjDYf/9r1IAJDjZWPpo61cg6zlAXXggnIFUhxX0GDx7M9evXWbRokW0S+4EDxgTsFi3gwgXjounevdC2rSR2k6xaZWxCWEKqQuYB165d43//+x+jRo3iySefNPfg58/D2LGwZAl4ecGUKTBwIDjT8nxO4osvjMdX5PZAYQFJ7nlA8eLFCQsLw93d3byD3rxpjKPPmAHx8UZCDwiAkiXNO4cQIsdkWMbFBQUFER0djZeXlzkVH2Nj4dNPjakYEyfCSy8Z1RpnzcpRYt+1axfPPPMMnp6ePPbYY6xevdr6GIUQktxd2a5du+jQoQNTpkzJunEWdGIisStWQM2axo1HNWsaF02//RYeeyxHx/z1119p1aoVzZo1IygoiObNm/Pqq69y8uRJq+MVIq+T5O6iYmNj8fPzo2zZsgwZMsSqY8Vs20bTYsX4qGdP8PCAoCD45RfwzfKCfYaioqJSFgeZOHEiLVu2ZP78+bi7u/Pjjz9aFa8QQsbcXdYnn3zC/v372bBhA0WLFs3ZQQ4dglGj8Fi3joqFCjGrQAEGbt1KKRPubF24cCFxcXEMGzYsZZ+Hhwfe3t6cPi3VotOzZo2jIxDORHruLujQoUNMnDiR7t2788ILL2T/ABcuwNtvw5NPGj30yZMZ9+efxMTHM2vuXFNiDAwMpHPnzri7uxMfH5+yRUVFmXvhNwv//a8xU3PTpnv7Tp6ERx4xrhHnJiVLyvVqkQ1aa4ds9evX18I2Dh06pNu2basvXryYvTfevKn1hx9q7empdf78Wg8cqPXlyykvd+3aVRcrVkzfvn3bqviuXbumlVIaSHebO3euVcfPrpYttW7SxPj5+nWta9TQ+vnntY6Pt2sYWfrqK2MTeRtGZYAsc6z03F1QtWrV2Lx5M6VKlbLsDXFxxiTqJ54w6sC88IIxJDNnzr3ascDAgQO5ceMGK1eutCq+0NBQtNasW7eO4ODglO2zzz4DoE5SPff9+/dTr149KleuzIsvvsitW7esOm9GPvoIduyArVuhWzdwdzdW+MttpXKXLjU2ISwhyd2FnDt3Dj8/P65cuWLZG7SGH34whl/efddYfHPnzgyrTjVt2pRq1aqxbNkyq+I8e9ZYHqBVq1b4+vqmbBcvXqRIkSI0bNgQgHfeeYeJEydy9OhRqlWrxtSpU606b0aaNYPWraFTJ9i/HzZuNO7HEsKZSXJ3EVpr+vXrx4oVKyzr4f7xBzz9NHTubHRR16+H334zlvDJgFKKnj17sn37ds6fP5/jWOPj4wHuW7dVa83KlSvp1q0bHh4eXLp0iZMnT6asEtW3b1/Wrl2b43Nm5Ykn4M4doxfvI+uICRcgyd1FrF69mo0bNzJhwgQqVaqUccPDh42E/vTTxpXDhQuNIuAdOlhUA6ZTp04AbNy4McexVkha9Prw4cMp+5YsWcLZs2cZNWoUYHwL8UmVZcuXL5/S4zfbggVG9YTatWHxYpucQgj7s2Rg3habXFA1z5UrV7S3t7du0KCBjs/oKuDFi1r366e1m5vWXl5aT5igdQ4ujCYmJmofHx/dpUuXHMcbExOjy5Ytq5s2bap//vlnPW3aNF2wYEG9cOHClDbBwcG6YcOGKc/v3Lmjvby8cnzOjGzdalw7XrZM6z//1Bq03rTJ9NOY4plnjE3kbVh4QVWSuwt45513dP78+XVISMiDL966pfW4cVoXLmxksf79tb50yarz9e7dW5cqVUonJibm+Bh//vmnrlWrlvbw8NC1a9fWa9euve/1Cxcu6DJlyqQ8Dw8P19WqVcvx+dKzf7/WxYppHRBwb1/r1lqn+j8lV4mKMjaRt0lyz0POnz+vV6xYcf/OuDitv/xS61KljL/mLl20PnLElPPNmzdPA/rs2bOmHC8jTZo00UFBQVprrT/44AM9evRo04596ZLWFStq3bWr1qn/j/rvf42Pa+NG004lhKksTe6yWIcTi4mJwd3dnXz5Ul060dq4ODpypFHQ6+mnjQUznnrKtPNu376d5s2bs2nTJtq1a2facdPat28fr7/+Ordv36Zq1aoEBgZSrFgxm50vt/v8c+Px3XcdG4dwLFmsIw8YPXo0rVq1IjY21tixcyc0b25UatQafvwRfv/d1MQOULVqVQCOHDli6nHTqlWrFnv37uXo0aNs3LgxTyd2gNWrjU0IS1iU3JVSbZVSh5VSx5RSI9N53UMptSrp9V1KqYpmByruFxwczOzZs6levToFTp+Grl2NJH70KMyfb0zY7tjRJqsgeXt7U7BgQZvNXhFCWC/L5K6UcgM+A9oBNYAeSqkaaZr1Ba5prZ8AZgGfmB2oMAQGBlKhQgUaNmyIAuqFh0ONGrB5szFJ+9gx8PeH/LarCaeUolSpUkRERNjsHEII61iSARoCx7TWJwCUUiuBjsDBVG06AuOSfl4DfKqUUtpRA/ouKjAwEH9/f+7cuQNAQmIig377Dc9nn6VXYCBYWm7ABEWKFOHmzZt2O58QInssSe5lgdTfv88BaW9jTGmjtY5XSt0AHgYsvA9eWCIgICAlscOvANwBXv0lH/2rXqBt23BWrnyGK1fu8MQTD46Hd+lym0WLnubw4as0avTgkMrrr99hzpwm7Np1nueeu/zA6++9F8uECQ3ZvPkEBw9+Tni44qGHQlJeHz06keHD67Fq1WHefvvuA+//5BM33n77X8yfH8aIEQkPvD5/fiFeeaUqU6fuYfLkB79UrlhRlHbtHmPMmL+YN68AcK8ODcA330C5ckb1hOT1RlNbs8aoqphRjZZNm8DT07hwmd7Y9m+/GY/TpxslClIrVMj48gQwYQJs23b/6w8/DMk32I4aBX/+ef/rPj6wfLnx86BBEBJy/+tVqjwYjxCZsWs9d6WUP+APxh2HInvOnDmT7n6tE+0cCbi75wfMH88XGUv+z0UIS2Q5FVIp9RQwTmv9XNLzUQBa649TtdmS1OZPpVR+4CLgndmwjEyFzL6KFSumu5BFhQoVOHXqlP0DEkLYnZlTIYOBykqpSkqpAkB3YH2aNuuB15N+7gL8IuPt5ps0aRKenp737fP09GTSpEkOikgIkVtlmdy11vHAAGALcAhYrbU+oJQar5R6ManZYuBhpdQxYAjwwHRJYb1evXqxYMECKlSogFKKChUqsGDBAnr16uXo0IQQuYzcoSqEEE5E7lAVQog8TJK7EEK4IEnuQgjhgiS5CyGEC5LkLoQQLshhs2WUUhHAg3fkZK4kUtIgmXwWBvkc7pHP4h5X/iwqaK29s2rksOSeE0qp3ZZMAcoL5LMwyOdwj3wW98hnIcMyQgjhkiS5CyGEC3K25L7A0QHkIvJZGORzuEc+i3vy/GfhVGPuQgghLONsPXchhBAWyNXJXSlVQin1H6XU0aTH4hm0S1BKhSRtacsROy1ZmPweCz6LPkqpiFS/B36OiNMelFJLlFKXlVL7M3hdKaXmJn1W+5RS9ewdoz1Y8Dm0UErdSPU78aG9Y3SkXJ3cMUoHb9NaVwa2kXEp4bta6zpJ24sZtHEqsjD5PRZ+FgCrUv0eLLJrkPa1FGibyevtgMpJmz+QzqKDLmEpmX8OANtT/U6Mt0NMuUZuT+4dgWVJPy8DXnJgLPaWsjC51joWSF6YPLXUn88a4FmllCuufWfJZ5FnaK1/ByIzadIR+FobdgIPKaVK2yc6+7Hgc8jTcntyL6W1vpD080WgVAbtCiqldiuldiqlXOU/gPQWJi+bUZukRVWSFyZ3NZZ8FgAvJw1DrFFKlbNPaLmSpZ9XXvCUUipUKbVZKVXT0cHYk10XyE6PUupn4NF0XgpI/URrrZVSGU3tqaC1/kcp9Rjwi1IqTGt93OxYRa62AVihtY5RSr2N8Y2mlYNjEo61ByM33FZKtQd+xBiqyhMcnty11q0zek0pdUkpVVprfSHpa+XlDI7xT9LjCaXUb0BdwNmT+z9A6t6nT9K+9NqcS1qYvBhw1T7h2VWWn4XWOvWfexEw1Q5x5VaW/O64PK31zVQ/b1JKfa6UKqm1dtWaM/fJ7cMyqRfefh1Yl7aBUqq4Usoj6eeSQFPgoN0itB1ZmPyeLD+LNGPKL2Ks95tXrQdeS5o10xi4kWp4M89QSj2afA1KKdUQI9+5YucnXQ7vuWdhCrBaKdUXo4JkNwCllC/wjtbaD6gOzFdKJWL85U3RWjt9ctdaxyulkhcmdwOWJC9MDuzWWq/HWJj8m6SFySMxkp7LsfCzGJi0YHs8xmfRx2EB25hSagXQAiiplDoHjAXcAbTWXwKbgPbAMeAO8IZjIrUtCz6HLkA/pVQ8cBfo7qKdn3TJHapCCOGCcvuwjBBCiByQ5C6EEC5IkrsQQrggSe5CCOGCJLkLIYQLkuQuhBAuSJK7EEK4IEnuQgjhgv4fRQ8XBIsqwCIAAAAASUVORK5CYII=\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "from math import pi\n", - "\n", - "arm.plot()\n", - "label_diagram()\n", - "\n", - "plt.plot([0, arm.wrist[0]],\n", - " [0, arm.wrist[1]],\n", - " 'k--')\n", - "\n", - "plt.plot([arm.wrist[0], arm.wrist[0]],\n", - " [0, arm.wrist[1]],\n", - " 'b--')\n", - "plt.plot([0, arm.wrist[0]],\n", - " [0, 0],\n", - " 'b--')\n", - "\n", - "plt.annotate(\"$x$\", xy=(0.6, 0.05), size=15, color=\"b\")\n", - "plt.annotate(\"$y$\", xy=(1, 0.2), size=15, color=\"b\")\n", - "plt.annotate(\"$r$\", xy=(0.45, 0.9), size=15)\n", - "plt.annotate(r\"$\\alpha$\", xy=(0.75, 0.6), size=15)\n", - "\n", - "alpha = pi-theta1\n", - "draw_angle(alpha, offset=theta0+theta1, origin=[arm.elbow[0], arm.elbow[1]], r=0.1)\n", - "\n", - "plt.axis(\"equal\")\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "The distance from the end-effector to the robot base (shoulder joint) is $r$ and can be written in terms of the end-effector position using the Pythagorean Theorem.\n", - "\n", - "$r^2$ = $x^2 + y^2$\n", - "\n", - "Then, by the law of cosines, $r$2 can also be written as:\n", - "\n", - "$r^2$ = $l_0^2 + l_1^2 - 2l_0l_1\\cos(\\alpha)$\n", - "\n", - "Because $\\alpha$ can be written as $\\pi - \\theta_1$, we can relate the desired end-effector position to one of our joint angles, $\\theta_1$.\n", - "\n", - "$x^2 + y^2$ = $l_0^2 + l_1^2 - 2l_0l_1\\cos(\\alpha)$ \n", - " \n", - "$x^2 + y^2$ = $l_0^2 + l_1^2 - 2l_0l_1\\cos(\\pi-\\theta_1)$ \n", - " \n", - "$2l_0l_1\\cos(\\pi-\\theta_1) = l_0^2 + l_1^2 - x^2 - y^2$ \n", - " \n", - "$\\cos(\\pi-\\theta_1) = \\frac{l_0^2 + l_1^2 - x^2 - y^2}{2l_0l_1}$ \n", - "$~$ \n", - "$~$ \n", - "$\\cos(\\pi-\\theta_1) = -cos(\\theta_1)$ is a trigonometric identity, so we can also write\n", - "\n", - "$\\cos(\\theta_1) = \\frac{x^2 + y^2 - l_0^2 - l_1^2}{2l_0l_1}$ \n", - "\n", - "which leads us to an equation for $\\theta_1$ in terms of the link lengths and the desired end-effector position!\n", - "\n", - "$\\theta_1 = \\cos^{-1}(\\frac{x^2 + y^2 - l_0^2 - l_1^2}{2l_0l_1})$ \n", - "\n", - "This is actually one of two possible solutions for $\\theta_1$, but we'll ignore the other possibility for now. This solution will lead us to the \"arm-down\" configuration of the arm, which is what's shown in the diagram. Now we'll derive an equation for $\\theta_0$ that depends on this value of $\\theta_1$." - ] - }, - { - "cell_type": "code", - "execution_count": 5, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "from math import atan2\n", - "\n", - "arm.plot()\n", - "plt.plot([0, arm.wrist[0]],\n", - " [0, arm.wrist[1]],\n", - " 'k--')\n", - "\n", - "p = 1 + cos(theta1)\n", - "plt.plot([arm.elbow[0], p*cos(theta0)],\n", - " [arm.elbow[1], p*sin(theta0)],\n", - " 'b--', linewidth=5)\n", - "plt.plot([arm.wrist[0], p*cos(theta0)],\n", - " [arm.wrist[1], p*sin(theta0)],\n", - " 'b--', linewidth=5)\n", - "\n", - "beta = atan2(arm.wrist[1], arm.wrist[0])-theta0\n", - "draw_angle(beta, offset=theta0, r=0.45)\n", - "\n", - "plt.annotate(r\"$\\beta$\", xy=(0.35, 0.35), size=15)\n", - "plt.annotate(\"$r$\", xy=(0.45, 0.9), size=15)\n", - "plt.annotate(r\"$l_1sin(\\theta_1)$\",xy=(1.25, 1.1), size=15, color=\"b\")\n", - "plt.annotate(r\"$l_1cos(\\theta_1)$\",xy=(1.1, 0.4), size=15, color=\"b\")\n", - "\n", - "label_diagram()\n", - "\n", - "plt.axis(\"equal\")\n", - "\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Consider the angle between the displacement vector $r$ and the first link $l_0$; let's call it $\\beta$. If we extend the first link to include the component of the second link in the same direction as the first, we form a right triangle with components $l_0+l_1cos(\\theta_1)$ and $l_1sin(\\theta_1)$, allowing us to express $\\beta$ as\n", - " \n", - "$\\beta = \\tan^{-1}(\\frac{l_1\\sin(\\theta_1)}{l_0+l_1\\cos(\\theta_1)})$ \n" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We now have an expression for this angle $\\beta$ in terms of one of our arm's joint angles. Now, can we relate $\\beta$ to $\\theta_0$? Yes!" - ] - }, - { - "cell_type": "code", - "execution_count": 6, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "
" - ] - }, - "metadata": {}, - "output_type": "display_data" - } - ], - "source": [ - "arm.plot()\n", - "label_diagram()\n", - "plt.plot([0, arm.wrist[0]],\n", - " [0, arm.wrist[1]],\n", - " 'k--')\n", - "\n", - "plt.plot([arm.wrist[0], arm.wrist[0]],\n", - " [0, arm.wrist[1]],\n", - " 'b--')\n", - "plt.plot([0, arm.wrist[0]],\n", - " [0, 0],\n", - " 'b--')\n", - "\n", - "gamma = atan2(arm.wrist[1], arm.wrist[0])\n", - "draw_angle(beta, offset=theta0, r=0.2)\n", - "draw_angle(gamma, r=0.6)\n", - "\n", - "plt.annotate(\"$x$\", xy=(0.7, 0.05), size=15, color=\"b\")\n", - "plt.annotate(\"$y$\", xy=(1, 0.2), size=15, color=\"b\")\n", - "plt.annotate(r\"$\\beta$\", xy=(0.2, 0.2), size=15)\n", - "plt.annotate(r\"$\\gamma$\", xy=(0.6, 0.2), size=15)\n", - "\n", - "plt.axis(\"equal\")\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Our first joint angle $\\theta_0$ added to $\\beta$ gives us the angle between the positive $x$-axis and the displacement vector $r$; let's call this angle $\\gamma$.\n", - "\n", - "$\\gamma = \\theta_0+\\beta$ \n", - "\n", - "$\\theta_0$, our remaining joint angle, can then be expressed as \n", - "\n", - "$\\theta_0 = \\gamma-\\beta$ \n", - "\n", - "We already know $\\beta$. $\\gamma$ is simply the inverse tangent of $\\frac{y}{x}$, so we have an equation of $\\theta_0$! \n", - "\n", - "$\\theta_0 = \\tan^{-1}(\\frac{y}{x})-\\tan^{-1}(\\frac{l_1\\sin(\\theta_1)}{l_0+l_1\\cos(\\theta_1)})$" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "We now have the inverse kinematics for a planar two-link robotic arm. If you're planning on implementing this in a programming language, it's best to use the atan2 function, which is included in most math libraries and correctly accounts for the signs of $y$ and $x$. Notice that $\\theta_1$ must be calculated before $\\theta_0$.\n", - "\n", - "$\\theta_1 = \\cos^{-1}(\\frac{x^2 + y^2 - l_0^2 - l_1^2}{2l_0l_1})$ \n", - "$\\theta_0 = atan2(y, x)-atan2(l_1\\sin(\\theta_1), l_0+l_1\\cos(\\theta_1))$" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.8" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/PathTracking/cgmres_nmpc/Figure_1.png b/PathTracking/cgmres_nmpc/Figure_1.png deleted file mode 100644 index c15112dcac161a5c262afe0d3e2c7b069a59ee05..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 33823 zcmeFZWn7ir);@aE-Q6vvq?DwxC?%!4M3e^U?hZi_ly0OE>23u9k?xZ2Za8y2``!O{ z@83D+`}uHu@L6lY&3(@~=9puSab4FiLRDD~2a^&Lf*>3PdDu$`LiC3qghg~z@Ew8S z*}vcg`Q0-G4Rr9w8~s%{_>AEoulo*y@J!)<5eg*>-hyw6ILqibtJ}YJb~AOdfNV{j z9c=8KZQh#EyIMHCduwk;&&LJ+dr1Gr+1cREo+LJ8~!PH=mj=b2Y zNXSnQTt&bljbbD)x0_YAz2bYC_j1i3c^PT(>U8_?YP&oqHy2qt6uW)8+M3s*@1t^a zO5+cu>Gp*ApIn8>I!C70L+LRe zSXCI=**7E0g~+j?*;c8ntSm#ll+LBLSQ^pypFW|MYR%-$oXPBH&rg;&v6mW4d5HIy z8dpt4cXh#r*6Rq_pFk~_YbovtM{7I4=& zLg>^}{F$`0#bK{23;cfe>jFj@ ze5OZN#X{65tr_+NZ{NenFe!r^zja`gj^EyKEG3+BO${b~5;%9yvlzG+oTr~?HD#e| z$(w{GCnv*y{ZbUWzd3%?GxFz8h1itZxP(ep+;avZZz;3EUV{wumQr2u+)}qB^K; zG)}|Bt|{qp3b?(=f5T~S-Lw$9QQIOTG3yMtx_WwQ$m3#SWZu4g+gM&Xvs*E|L@Nt8xk)@oBAyeNYSB=prHKU0Q-|uyF#amQh zLbxtuZ~a%o$}WAXtq=nA1P}!{HXd^zzZw1gRs(&sA!GZo)dtt4gcOrhvDVWZC%@z( z&1WO$yD=EQi&A=!5sKFEjO#36U)Et?SmnN0DtwWApEB|0?!9Y+fw1=lk8CtGLiKYb zwFcp0w&!~yFg2$k+J+>70X9LOg(l^w_0msK*T?Cci5m3(l5* zShTA4J-*1>ZiJnCHHuXW4t+H8E*)WMx2dET7XG{ZWI!OibgMpBSzFycX|PE!&PDcE z5COx%@VIO&KyRY2h;?4Rs+r?m`TT!fHD`TOf^T!7WjTLYXSzG?`XIACBA^l?G>I<~Tk9R+pWblT20 zT;4o)nfN#=BJTOpa^jb#(QNnL-JyUa*^JkYN!s|z9yEV-`YgqzTWj0Mu90SZe2*_{ z^}@o4+sJd{>9P69QA4(k&CI7Umixhh5-sZ_yCFJuK}c3c=4q)`?dM%iPEKon&Pki@ zND}w8&z53CDR_)ZFJ5eaGKWS+MtI+?DeBVL4-=em+RyLQ4zp)hG$7P#YW>yJi`UnU zYwAP&t2v%iH@9zL2E|j7MCYQ5 zXG=S$n=gike|$EKaIn|7FKc1JqE&7blaN4&P4k3!rp8v<$>|%oE29CnS8t@1V^bk1 z{3ZJb_KTKng}|VV>ZZ$5M%T{pYJm>ZefD_VATBi zfZ(gYhHdky&v*L2!qk+cQ(O|5PRTz|$5#F%AWtOjsgQ$>;*diTg)^f%RF&KXgbQix zofC3nY%{fu-A<)?ZNJ@_dLD$CD>@0wvW7AB;BVwvMTCD0LU zq8TfFIhJH#IpnilV0tL4xI+{|bqzB!c#a&1=y^ie4uc`1N-;JlgGt|us0Y|r^;Pf} zQ(KUFMXlbNOY<-YAR>&dA5Nz6<5NtFyA3cfW)GS}%-O|Sde)t>AM!4?VC*fD+9>NR zWP0Ohg}h(wiSzNo+fM?9H!QFN!C6;hyN*xU6;)11aES;WwDoZ|($m`|n|Ma$ zvo#HOt_eo;wiq8qUcX?Bs?d`_wIL#*@bJH(2=C>e!qhqfW;whQbi-|XpPSe^dwhyf z#O}Nyc<_sA9*cLj`2~#G8ax|QRn?-q04=Iw)r8@wxFr2>w9sT$ux*T_?2oe zz&w0qiCK0e)MMlBK13N#t)?H={g(RYhH)=~*&qIhA^~?S2TwjCI(2205Z4KhJ6l^e z@DPX2D}97cqk4Q+J~$k=k-r(`;MP`v!S4JK-v8(&(a=3C@Ts5ts0Kw1V6^!>*!PQ3 z>Qb>&lyzd>?|cD+X@`N!Do6V0Qy6R_0^AEt*nm+&(jYpf@!fl$ zELy$tD9t~Kwc@Cf$neYcPsGvSMu=Qw-_p+4fphN}QyuogEjg_rX(aS}}6DSn5Mp5197An!^(J_3=UL zLi#E7%7oAZdgqn(n->W;nH*@u)N@T{fj(2J3PtQ zm!dz3JB;4JHTWiMgk^a|T1F=&eOIKo*3Fsc)4)bteJ9u8Sp=887I2a0>qH3n(6?{j z-p9uW1P3D%laZ~QY>rgum7?RW*_Qn{S4aqkyEvHAlFjGqC%(ti~;j`VD_1&XzE^B*b6w;D~C>Fn; zT~ptl1aDTmn-0=@Umw4%^D-dpq$41>q|Qi2@V?%yt#sMe`jswD1@XN4fln>$0JYw% za`W0wKc3um1->&n4u1dUEb7CBU@pR2jD#QxR&Z~i_C@bDjQmoP}ob%#7V zJ6kXMZM9z0-PLxokbQbm5u=qc$YHHpC4waPhk{;w%v8guv-c)UZ>p!u#(83&BnRAF zMuGs+4{Lp)l=h?=jgw(3xszqN9IV9ngr(TTQ3@{`Dfcg$;88Z(;^$z4b+RJT$CqCV z7GrbYZ!c*9xU!H@iaV>iIOdM^j4siTYsmmGaz zFlIUsDU|f+)`fTmeNq>4Tf_$AK)eh=cu!oOvvT7r#`W{vwjd~(MNA>)ZmWIa)(qw6 z-QcFHA*sM?#>pWC$0tt)_d`U2-gm43i^(H^Z>hPbf<+)eqGyMJkuU~1QXy{<#JL+n<@KH_Gbph>W%J-hc$6pU&(&`i@Zd zP7yKgm4H;{wA9hWb4`t?#qe39D2wbhjZu`|*x7NAsu$OnRk0DC{SBxCQ_9%HXhAdr)}zh7~WAFyzz#^Y+ap-@fx9UFVo>=T z2td72zb=+_FluNxpZX?}7}IihgG?t&3xnJWv%Bsidi0B!w!$tR7?ty!M9u>RLd+sc zhr&!skPbT*W}>o24md<4Skk2R&|IzIx((?a<$|+^asTBB>*3Z|@!=1qIQR6h;9&R4 zFPzpis4B!Mhvhje7e{qo6I<~ederPC-DqBeNDju&ETl>hki00~gX|vUB*`6t_;j?$ zLCPbW4s4Nx99uhVU#qin$3r`;I6*Pe`I!%E@Z(s!nYCAs(?T*nJSkB}gPD6SUOQ5wUgW1~DO^u)AMME}=Db-pGRxecG0^GkAB z))08Mt!VmmZd3%Uq#?HqTAQ}94@v9gfc^XA+KqoW;GSgtmZN2cCk2jN!1A*-AOa;EZXZrDg{g zUGGvL4jSfufb5eK6i-NkohCbGcbn!?eS0Me3dbGoyN}~l zvsZ~P=q9A!Gk;zAN<-nbU0TcIdGaPWENrDM07<9P48^W-SJ3;Q9gU{t^=e3IS| z@mQqSeluBhbu~H;&Z(=25koOFsV3E^AuEg86H7Dm+PnYLqq^;~MpZSnfFD18xEjyQ zW1E-KlG~AH=SaP5j7pLL391Paty!Tr8X6#|!dX)d&7h(1EVXg1LYkqJv64O8y z)mRrlSu?ug{BBnI%RVF|{Mow*#vp zbz=RH6bqu~?RqXPHLJH=uvw-h-o9{t?ghm0Ia>ZX!0vVk}f19#Hgswx)k6$f%GO*-z?I3>reGHG=i`9Tj}EC<9~0Tl8ZPo z^YQbG_k)Pqm&j?#_ZgpI{!&*2kx|LTv`Cur&6alSGb<~Oz`(%Yjc)cOM$MGj zY@XwX=e}o9|4gvUzB7O8sNl8hiX83K= z_QaCIV*Pr0XN74eJ~cJ=ho8Y{wC+%MclVYCs5ucupTQCyw{rlt5 zi3zW9-5MJTiR&GHo9XWuUS~T`4Gn3)tItLH6#JG4m+f%|;D{jXC5ybvUvHVd`#Yv> z+}*g}5(R#=H2PKDeYbkz0HE0`X>Rj}B`f>4;}a9+UEu^ewRVP${h}ia&FAw`ond(9 z*JrzvEk2^SbP~}rQKY9DSlX*jw|b>o)MD=V+$|T3xU^#7z~PCfrlyi5{d}WN|Nhy} ztFfDl+;6?7eemJy0H5Dhl3x6ef?0=7oIfDh*NeuX7FPAVyIgP9P&;Smw}4)P-!PMcbjz# zbH2Ylf04l4>Wd(s;dAzR-NW)q)Z-`@S!%k~uhlZm=lV(Vf zN0#dA@BhH8kbX-_O8Wfp@bJ&!N^joZzppk+Yv+$19FMHqeD`!Uq1kVZ`7UA1ENq|nyraj$-^$9WKlORcx`89 zV0Y^aj01WN|M+<#e%#+}vEw79(OA zP-}IX@JQhYZp~5Bb0A>(>_d8Qw=2e0+Qr@79%*2VM)ODT7K$_blbZhakY1tiVG& zU{BryYv#R3dPXb*7F+zs&z}eofPP7vL&CyxGBexuuY7hYdsVfxLJ^QqrAoCrSDlvf zl8icL>))9QrdUjHFV5pk8@O3s^$!flfC4YYh>3|QJ|$)Q_#QRsZ05_r>rOEJN{6Lq z(0hwk`=&!w$mDRj8%zgZhCnc7pek1KoKt}ioC1muh%`7X21D4dl<9#5XUWwxoBzF@Vnnt#3P%n7?)! zhYMJbn~W7{+V;5ZOd>QJEj&8SD=2X5cl9B;PORPAnqWtCB{O-4aF)Nn%hi6{bol}~ zH5&@sFj`;`5RXg}d)~pafW$?BzvSzTfS*Fg(#C?2?OczChvVSjS9`LZGTJt!KF^gM z_BCKcuGtWV_Xq0bD{s;xOG#Yp*y$=0*Bh{^cHKO?i8n(s(a<0swQ@;2Qn>;W@9z816cSR^DC@^39_4(Tu-c58czT!=A>L=SO8}Q6HwA;vi?vDL} zie^=UtD#R*SSeWJJ-;ZGqu#V5==DVppI$0hDz@u|l!_D=P_PFY~Q_&*Zi}$|C{30ZVKa*5cH`#%MA|N1;^S{Ra zGcw``a1pN_z-Bnk*w$8GQ>H1SrIqbI{;pNLTZ4DFH(SFEC%h!Kb%U@-sg5{Gf0Tb` zEH9!((ZpdBnECQ714pp88s!NnpYhXB+XsvhtdO@KqYuBuC(e}3)Iv#<#YxNGR4Z<{ zXqFv2nZ5P#mqjVn^OwyF1hy)6m9)}8e5^$4{M6&$T7Z>3xvT*vaQ52H)R+#Y>JuLx zy9iS&-NtIdTHEr(RWx8jWY^6Kq_=%pVcURdM2CjNj=Ds_nIwtMY!)bpTEz@ zh+}#2$-VJ0W9zze#E;@{jK!mYA7lh3)ABm@hwjio(q7?a*2AS(E>psQ&ztoGhKxpU zKEzbDNK(A#jadNbD7l!`i!DQ#)xeIw~Ga&#_Ws*{v`>3fu%16CR5ZS=$wij zzE_aCxLT&127b3X0c1vNGQKe9F|XgW@JS4B2Qeu+j^#GUe`OB=lTfBe%tFmw*6n7= zQ2{6jih503*Oe`#QF2oIt{=HP(TeDuChBa2ou{f_gY#Fyj(GCyiQ}3X7>@vW0vqK@ z=?rNWA(5BV4YgM`l=|E~Z|3p+X&9V-@U~)>WeLeLRz$Zv4G+HoND6_+BsJI0FOFV- z&mZh=Iz1LPNVjN5uu|M33sLaNaWK!2KZ(FqJCV_d2*05KsC7p@4CC5~<1nsMX3{sC zm~^Jw{8F(;>K8e66h)93Z;KnUGi7@6Qy4QE9DvsZbj5-%TiaSRBJtQ`_Z}|_BsiX5 z8_Q!F&i=8=8wTS8Kt?WoHk+xotH|AzkHnqNRp7eBw;uXOYdHHMmrRP}NrVWAky&x! z@`G@eATw(ij`}R)c@3_3%QRcwgpQ)mdPx($#)(;RIS&sf4h95458!og-Wqe=eUrok zl^sO?ST!iboXBwqM`44CXn771!1Q?rAZj_ z_Cd%&H(HKz|jdI0Fl~m z5uahan0rqc0B|2uvwivWp8!XH!~+ptRsytoe^&yILLVD^zXXGRn9{xoewPN0+e_mn zg)32@xL5z%_zcEwf(Yb9qRz(6Ue{R>{7bczcxKP}e!2l6^%1&bn428fmh z`=RBa{lWI71c1W3yFa%VlPJZ*4$%7t?eqU!f&-<;6Y<_u_JtzR*byZ5`J91j?*58+I=7_39hh%Uy(b^ZnjcJ-E_RG z`}m0rAkxKno4I{m)$QktlfuIruz^d({rFYf6R8r%c>Rn9GO@aU)6`_bM#ywxR2Ka& z!skc-LqRm7ne>oW?+i2rr;NGlKczvyk0KhqBEk#xfqgyHu72{B+%11!XO3&^VO|6v zCO$3o;%Xm&G2w30l=-cNfX<@W!F|CLl5)zWwYH-RrMf=iq6Ns+Ex5pQGO73ZLC3gx zVUhOJQo@6(6wj5fbf+r{@C(f07s$K#Fd1FlAm4f9l0&~aLxSD}j}^GZfs~z#X0gOmbAIMZ^VxQ$jqHFUo6t-%{wb{Ts!e`7JeWSZzN*KvC2^ z8X-uh$(`4Ae|~qDFT4R}8-z4;w~J1D)k>%Ox-thK`Vt;HvSN~6^eQI+s>xUc`~qnd z3doq{6&1Tw{I1k*{<2Cw_4aP6?PqMTT6mpk+WpBK918U4ZJi&~4*|%F3YPGQU4j>> z&Z3``n1o~ro-i)l-?@Q2)#Pkv>f-MQmAc~So4~2Hws#rS-71oOQeUS+0mXK6I~?I| zx@Qs!zk>(>&JpPO_y|?RPl<79o&+PI;bz(|wCH?)LjY2~bl%?6}AbnqeK zr@P&m)CQ9GvPvX~{NKEnM~bw|jX*+sKKl+2ms;2#)Cx7a>!0-Pp6ci%lNB*F6oM_s zX`J4ZalVcK5q1O}OdEDOn$yj9f<15(rh?oCI3p}9GA@{jiAmTt96GwWJQmj>QG0Pc zq-l1^DyOQtnts~o_l!{M7j3Xfn#v6YfE--DsCYX)()<2nh6Uf{$Mi;*^-R@4Z*x85 z5750P&vggIyto+6vA@`WEMV>b-p=xZea%>J1&G>28k`gd(@IV+6z-=IZ-3f;}s zM5`S|x)&;sIkdDSnii)Q;iXa~zB92>Xo>RNUs%}bW|26zf1n-l5*Aico4QVH3? z7FvAZB$n9G52nKM^4@*lb5Rg1=icm3VT#>v^8VGXFW+{%E_82tY|qm{0q0Mi5>r5y z17AXPt6qDgpYP34>FVlER+u6oWh#yd3Rk?IVYlgHgP`Q-fQ#MTP97hV=p;_Ki97(b zwEMNRR0akMuI?+A7L4%*Flhc#OR72DRz6^ z#{(|E^5X7{@}^4TOLaXsV8-QRfcG?k`R9y`b7CT=wize`k_=e^=waR)dn(4w#nl5~ z0$!Ib4LGVf@%{E+VCLO)WIh+`^S1Pt2=^SS?R$iofx#(Cgmwz}1es^9E`Uq11wbK? zqi|bUTN6-HZtXfXJ<~#{$j(LtH5YgQ3kym>KmatmWPf$CNiOLtc6ZS$`7E#DMqzk& z0DAD?0jPen`~3o_anV5X3s>;GsXkiJoYK6do`mM)%<~IDo_IFjN%jr}JnOYcgs&6M2hv0g` z8}?Gm`V-DD+Onh)L=#IAGBWe&?{DRwKktD1%g3Z7uTS0Ghq(B6Fk%)Paf9IdDOXAo zm%XW}8M*G2q<5$c)4v5vh=B7wLs|rKMTfH;-BfWeQc&YQ`t zcuLA4%AHkW0BkLT#Us4GQBRwTz-ti=i)kFpYF`SZhumV6+m7^6=^s4)J+lg;%q0%0 z)RBi^7?$6y1l@M4cvPR~`R$k92VpA{wYcpS$T>;Hz-x~r0RdK(%0&Q_5r7UH%B%xC znS2apPu1I7UN;?X^uYb}Igkzg?FW3?I?zRWdsd)Rxvl;ajDTpROI>m+OthC-s<`Ed z#S4tC&>Y;5e}`+a^ZxI0PP0dyiL3D+7K8F`qJQ&cN62s{tgH>%$VufIo?$sjJ|;Q6 z7@0qw{Py(j$I`$&4_ASa-bJl*6ZWo2n=M|np?J=QOStFu)l z$;)m66{^g7@{pV)?z)$iX)qIByxd6q1vJzpz-H)(3pLF*Pb9(%e?BWK6Os_oi3a?t z;GUB)vThC`&m?hVe1s|aEGIG2GWG_YwN%C6wWM;@K)|mitDE=wAuFx_%RS(YM6IVee-;ksQ2Eb zJ$i(NG_|}$Zo89Io$<8J!{nhIEqRdR*QF*yAj^nP;)SjPKxqnM`_eeU1NnqtzyVTo z6t)isQUY-j{dOSADyb+?_WUUS#(4WTgtUC32nEh+(PT@*93Vz%XAsl<8B~$dWKq(z zaKQgd^-zG~c8PGw#`F7RDnJ5&h$q0R7>VqcAhDKEX3=IW^{zt1sJYE^4*i2=)3?Fc5-d_M8Hbt@+)GU@Vhvq2ojEA% z#WSNk5)UOZ%{>m(G*pFnPwZ%{?lxg0)H6O469cwvoCYo*I~UV;G)* zbib&(?!`ydmoxs^Tc{f2LJh53JB3B|u(UahM)lx1hK@bwtYP+NIi#6tUo&kzv2p&; zE7C!r)CJX&8TJ$A;B5lH=b67Be=!G~V))bq`Y2NUTgGI+y&%tU{)2LIET6S@1s@3P9Z)uh%e-q&#v)MOt*J(0K^?1A#QRHvBHy z{r`ui!DnXaUD#%hWQ>f8GUXwsM>q8PO!6-=H8C+U{o}{qU;IntSZVB`uGi{+ zOacNV;0%JF1})cn;DjG#886Wda$M=Jm2hPe!4Y=FEd;f+j`#Ub#6E7 zxn0WhSrI%yzt+ySvWfpzQ(M~{s6BZoW55?Ys|G;7=eHQ;MuS$s%nga3Q-|VEg#soB z5MW{lZAgGGv#Z3ZKbe`%iIc#5ieKTnJ59QBH_Bbz1#OrM+RsN@^nY3kAv0SaQ_X5=nXelBX3>8DL{O$6b)KxU#M|21 z;<29>1KMnEE#F&!LLUH{#q{D}=~2(>sJ)AezyqZ($fa6Q+^si+tSaeURQ62)6%{-~ zPs*FmDCfP8l}hw$aVaP$!lR-(0pu=zK6b_mH256zKIew;9~CI4by$}-hfWy#(d;)J z$6C_(?bo)n&@#zJw>7wIPaDpEzT0a)H=>sCCZDOb?*)P*$BP3~z(*Ap=+$um3d*W_ zd9gjn{ji(N@nG?(_tj>>kHNtnkap{ruqOF(R|C0`H{ddWv28zHs<)0t!X#EhsqEf= zdZ_!y%x1AI;Lq`pO4W=UT}-O5fDgYas|8&_gQa{+T_45w(Yq^@?VhQx*dsr2&$D+}}o5Mbil zJ2SN^i1cX^J`L-Ut*E8fwnG6(Xw1+{BcpU?g`=I?iVD@pxVR*s660cFWqo1aeEP}q zvn1ecx+tXR{`^b-4_3CCT;;`!PT+*i8k*-IAw_|}-iIK-6D~Oj>z&y1edclAP;K42 zhcj=05#R;nB=Eg+E<)1HiRU#E$A z@PTd%s#lhlNKh=bNT9ganaNWSNFR^Z;-`$)lN>Kn@E&!2S~oY`S&UE=4nK_DxK{Ef=( zhxOgvg)uQPZ^{;WX}z#5EG)=*OrTLK0RZ$Hd2X`&N)sh}U8U=Ki?}zJIp6|V)7e=A zn5=BgrU0m!>+9i3Sr3D?T}S17HN8P^E+iWCn)z84Gt5OQ<}k-2_^^L&3zs+5KZHO8rk! z4FCc#eZvM@<1XLTnA^UTKUXLpCxF61AY}j`2PfXKoCM%Bcr(9CMM*imicnEmNzfqm ze|lg*!0{BnPUQSw@_o0K6L;ZA+qY`v+Nvx@2*~x&1Anhs@6FbyyMXb}zP<#~0?+J3 z&Z}D?OP*z+1rzGu~K{xA{Msd(3}lKGkV-eMCq^1jwdP z*9jn*lLAENIww#{0C|QIG`i{hXxzGmI->S-M<8gjb6r(d0_TX@`QarrNixxM4O)Z_ zSLp7^+uPe8^|991)YB1y1s5h9uMe$slNomn2rWc|zMKu`2G?2(I3Hy^%RS>A z!}L#?=U83p!uDkH*8FQFl3*j>OOxYPW9>W9E53iu^#4_>O*{aI~mcgFpVWvYbF)wgm#fQnRto*!ya*PU;=k!w2l0CFbsFsR!TV6xmqK`S`RKM z+Q4C1IJPBNI%8pcUE6w#;M9+)$p1No$mz$=|dfVAkZOQadC0ExE%6} z1++MWkPsP&FkOK121!LBDZ@yLqU?DDeRnmEQCTps=--}oOVI22|JH`V2hmGPwhj!W zR#jD10-_pVWH|$8Aku(3GF0+*Q>F0h*Qe!1%{)F=&NlN+Q(8tlqCWC)A zM~pGD6yy$8_3&aPuC~!;eK5_o=jwbvE_To!0~50Yh_1#GS6%9bb3`H12|jrKq&9IB zW!U!ol@+Ex3jlTiR@x1;8pQvkST1CsC>is{HmM#%u+ACj9|LJvd@2ug#U`Ce8enzK z8{I8N0H0U`J}9lQupA^wCk|fnz;EJmv-Z%01#?1y%@$v^!y2J4eQxtv%vgYxHB(6p zS0OTj)l(_?OjKS}nn0Hubrw(rcB+ujk3?`*N684!N1A_xt`{ zw=KL3br$ju_sG-yC59Qq=RqZN$qh^~E{602+As!CHfV1!19XS0MPg3j*bujTaZkmC zYVc#N2>_2DE+Ak(-6;W#t}f~vL9T+`TlC2>hi zEnP)oiANVV2L#-0y+~=lq()w|GBc?b?~S(rHpLJA)FEt>Qk(?lr})!@xbbeF#-|oG z4zX8GT$(B21ASHc4^;pjFnTwfJS|DN;w2|V_xng?fT5vm`!>e&(OMjj=^Z)|P$5pH zs`mPU;>%BJ~c?Bk9S5 znSixY+@lJ~dSKqjYU{3_sTC7eaMIJk8{xiNJaTa%B>|Tw3l(si01ULw_El5u3!o+A zHiu3eADGkQl8qke`5Sfta2K?%e0%=r2Waxy%m)1GG{lC}=kebitM@K=lO>JF9a6(BlhN)bYB$y=eSo z>nZ&XdbqZ`IL)F!2%uOv08uGDFekQXobm!V^Eir}e!sh1x*LaR`)WAaB9Zsd}x{SWbWp7vmZ> zDB1H+%++2mbD6X)5jr+>1+H{g|KO-zbXH$1u6#0WC@Ehodq0VPVo!1gbgtb-FD+qa zuapQD(mNT#S<4>_U7B_R8@Xcky}cc)y=c2{5hz}gamx6 zOxSwPW804PW0%@4IevLui#FY^sDbU*2Zt@y@HT3oIv^n00W~X-zys8v@}LrCfm0UghzE0vX%Y>ytADyyBf{o>bR zcb1A1|cq{_m7gCW5Z~mjNb+A(BMW`hLXbO5yea6jat_KMC{}2u>9f0d3H|D zA*cz>ekQO0op5v6ZuOm1!)zMw1I1*2P(rz;(Y3wBUHv~Yl)*=u)Gl742z!Zp3 z6jO!cf&Q@e0`?vt65sV~KZw5rnW56zqG7mfj_KbY@zkIk)qDp;rBx3N>V98N+6WR6 z5lI7CS}~HHxmIx^aC1T;*5mOAnpBRG%!&8K6z^mvT63h+>%R=0|2^n#5sM}HD5NtX zI-A6+9n9BYiLTv^va+Ag`g-)<8=xWHKfMs#f+^aL(h78MRte6C-xmHsJK8JBf}vf1 z|9O*Ex^VX3wn0*5dur~gR5Eb==kz0JFqt=qg8wz7s;AcnWPKMyes`VliXoc~2RF|s zIw^?^2u@i=L_X`=)pys6fj2C<@obmP?1 zOgaY4fWGm2e*fK)rv9$CmvDxPn?>d71;u)v&UeZXHF4>>GGn2SsYt(CENqf?57*xe zEu{4eSSqSqr3AWP7_(FVPnn8P8iJ@0p$QY)7ydy)&XUSOOd;XBysXXRebF|jh zEXniOx7X(=m<+)VX|7oQL1=hupr0)`IM`u8VB!FPGkhR80vMCas|@U|4*>cDC9Wdq z;{*IniDBcX$w?hJcryHEFpXO6&aw8hE|B-hKYYH&CMR5m@d zB|ar~-_3x#{^c@*0>f}ine7=m16K*~b?_`d*G22WCXZv#^=4GH4Nkks#l!9L)o$Zpfrqv}ZeS#NoD0evh1XVA9C+&FZ&@hJm$4 z{noA29sY%o(bW~t{d{8gPkxdnuk*y<>&B_i^3Twh0^nYmA=%oTeGM_D9yr>lgxd#_E@A#l=(rpXsFz~5fh>SS&woV?OZlYJfo2h67hGxjB8RpMw{9B zUdw%Y5M!e1oLSsY^bCC%bN7n2t)%23z-6Vu0WTmRfHU5FHf_CI|F)J;y%w$Fm)VMq z3{IA>k_v1Sy{ITb(?I6AEU$hn+0kvhcjQnbmfS0UA^uR8^%~B`5z&qX7J;?j@$Hm{O2J{ak=NARzvvRk{KxxQB$s=n>0x6pCxF<=ODpVJ(&^Yy+1 zBhzmQ!;u?0n2gkj{hN6B%FOukGZq7kY}5_`4!o`c3=XcWy|}(U1|JD%X$N^zIVLi5C2|Mm1AK533??Zj^7|LbFMl9rxZI;c1)Q&>Ld%cQWLy8+3yewCyJ`2TAm-zBLq` z4McQn{j+|1%dn>+Lanz*`@dQe4x1b6|M7=MzwHnl0I+!jYGrJ49)Bvkx&YR6_rTlh z^D3*cBGmIul1KcRToCOLcfqt(ul|C!d({+8)9IY!UBeP`5$3!n&UtjK`Czhe16uWf zZF8{yG=FnzGCbsPhKPS=nf<>C`wnm{+xP!R!^}vekP#w;D6)$vl#!LaBYW?a5rveB zBqK5(dt}996v>voWjywN?D0SE-uHL>zrWvc{Qm#<=sifD=f0oozOM5+&+{{`jao8a zp&UsJEzQ`|HZ>afRNr8jk@ooXbjh}d9&|mYr>C=Z%cJzGJWFP2eUd+apkS;!B&B+% z)gP}lytq{EsDO62_TUulYCmDWp?pqBX)Z)AAkl(-0&kSt&z=f%e1JNZYx?7d5ovkz zjbFb^hKKfA5JkKe%yi`8LCf}};SE}?LQ^>}n_ny(FY93SXOF&ZoiPc1cw*cwWW!_q zcNLYU_L{(~`$Y7q@&_Ta6r-Nk@F__!=~Yl-`uIVNDZnr#VYth3^kDhc7-JJQ4RcgOAen||Kh}Rs!pl8; z*j%%$<)%-?+Su;oEcNm|*trdkY`C~wO_Q^-&is{6QbY5h=cP0dyrskT-44 z_k;;M%^32>B3%?=-vf6q+tDTWg%a*h!vy}N)uL^Oj7xvq?+6?D;vYG*6COGLzU?vg z-oAW?&p@M{uAX-<*rY(%{Yj5+!rmh4d?lI-E~JttojV>E7uO6HNm|fv*3OBBatpyM z@XuUeVh_?ytGxGPy&LC4v?0*ZI#zRNGO2aEbMqkCF9>e5u4zoCecwrTb?9n|8}aVS zsP2(nVl*t@T%L!7%%_&zDMNcK%>c6U-kAu=Hozp*1`=$*los&XvOYMpS~*u~{DT-N zHyEJZx5Zh%1hatUt>@a$FZ#JWGNEBz7F0727k~ULqnP0xdRRSBXX7{2w(*<55&QE( zxmq{`2W6N|(Dwt*1}M)=VU)l*q`2t=Y&r=^Nl9CrcL+O)!ox|7TEBG;?~iWN^E@-x zSTf&O6ZpnwLQz`{mr){Q7JF2A>4fhguCJ-7X#&~W1rP85c6%Eg-J84%h>VoCx7g_D zD9Cs|UDNrhYrhEiNc+y(BoP_em0PzyfF=&QV6HbVI03;pnL|F1y!>_v#S+W+zOeE` zdNJX0A(4o>!9x$$>VjC(dnCGgA1S2Vzrb>nlaq7zDs8=4187}Sz-bcq<#H?nZ-GF; z9OjhilP7|rzM$b~`6T?7luj@oKqJr1**nI@mqD^a+VC)zKX`ap7uyJ>+Rzt$=DVu2 zr+s}MilMO)shVYs=D)aywROFbp2&&U1U-6Fe~*`F2n0<_hT=ZoWFa39Bm4qQ9H zV|N}rI0O5SZPBFU?$kMuFf~H%G1r&J2l_PZ;m|S|g(qWPS>5h{|;p5?cH58a%Ag z9I%r9V6peCt+@fRIG7;!t9erNCMqhR*3iN=0kl+W2OI4|TGb#J3zwa2UsNV+*Dwp@ z6}WluAulO;9IaZ;)>a$JM=h-Kn6Q(9lZz`BfCFeVpE`A_tb#sfcGC;BaI@MpC@bq) zMfi8Fyl;qzXQ0f%BygJ*ItuY^dFLo8FI+c11y!Rru16DrWn0^DP<9mp=7kK)19)6u zTxN4bVp^gtr>OX3eX0qBHG=V#0#UvrL#caJr2TKT>Q;`uLQPIjA1nk#pW8C@6)Iso zOgRv(9@mIU1bczvgpr)FJr?(b?B4`6e~Xc89v&W~(KJ+46lWdQ!WfUojt?0TrP!G7 z{x!%)t7rRRtr?q`@OrvY2G({gj@|*~hOHmPlCYaOD?FPpoL3L^$j-XZq=#Sg)zQ7> zTSHwh%Xdd|hHvse4}QDf)r#2_--wSr@E%D_$1U<4R!EcQ^vo%pSX*B=2Kbhhon7d0 z!lzHerKL-&RA^$OLi)rTxvCx4iBq;0 z=!3KB)-R>UZu-%AnAZ~t>pUi89=xAU?vDakYih;sSd`Iw6%P`L8F=dK0s?PC7(5C6 zA)v0pxQaAlAj>*9+Qwj^%g)5Z^Xl6-vGw(J4qje@q;KCou_t;*<>-_~B_y;pM9`Jb zrNt4FkW2yv(?Kp$D%8nXD*T(kf;^HZ2d137TH5c9i%Zen_=SH|Jx$f4QC^TwAyq7! zE_v!q33v{2avDP_1?<77*RPQ_3v3~$nFIvRMa<|%>lK<3LC!hsyT3#_v->;o=sTEp z0BE*2hDki$K0ab(V`IB3BXj*}7b^sfxo;2SDe7>t4Z*9s-wM1FKDN@0F(9ef@qUld z(brw7jVt=K@hm2Mo-Qw9t}_SCs#UabVgGxQ?%?UUCxcyITbqEA?PZg`BR2H4b*%pcj%+zc)?f4W`}v|rj9j18u!JLmjDx<-odbDw3IlPS5N znD84KTRA4d?)!47?@NU~8G^6LYInNVK#aN+JErhGg_JX~-V^d93aQ&mFD@75y_(K_ zBYt1vU1L{kIwTf#=~uP9KSuq4%>Ri#b$u(ON#obd_lTJ9IF6QZj?03U%t%{;@EmHfg$iPS~9vq4oF6=%7fY8q;^%kJ#3J}rZeLy6LwCMMv@x2 zTND1EzL`Dvw)N$uSbAO#Y*>}BcYzQA_9qq^rmfG1$i$C^w6>3$n)A8m!M|(ZzgY^E&7Af|nZS}PZ^lR9b z&Jp=b5tgQK5KEf`T%bMoeI*TN-acns-5=Ln8nV&EnQPpF<6OPf_gcYWZsxcyX`djrKE(AP?KIG~h8< zYCc^vmSp08)&E)AZTycXE*KIgLGbs?(Yw`N zO4rmxvwNP`D+OL&E$Z)2aE)GiY98Od(PbG*B0$MFqu~94QM}&!#mbCABn1m(6ayw4 zL9>p3-!2-evy6n#;qw=X{acsEA>$x$YN2nrI&JtWwqE$jFK)qC(=krm82X=fd?AV{ z6lcdDswD}%c{chXz?<;q{7-J>RbkKPws;ajJDz7vHzCntUlF2$c|nN^rbvFJi2m%S zhB{0+QRd@*1H2IAUFE3LiMj5Jsw!$5ordp_3Tn8E)7oXBNFj^1HEsIsTQAzSJeAe$ zUZc&f3G)u48x~fQUQgF<&aUFRCMHv5^3+$mEISvdz7^Ac0|-K!R9~CaGajEeCqN&4 zCxwH9*n%o`Ic4j$+hL#lVPOTXtpIzeRU?D+3$DCaA|atUlSVu57UPh$ATgSG(wa?Q z#3uzS^l9Y)HSDfKlNGFxEs2SqnQ`*96tg2q@cJxaEl40p@OX)=;}(xz*eSoxru!%= zsnD}{ef$wg>7p$wCoE)V!V%b7vdyJpBk17 z6pNMa?++Hl3~vRO_9U-ieGV6h#ACf$sUOat&0&GH!0dY^UPD?fiCpEGM91W?Bf96; zV2Kv+govxET_YdE{BSTMHR}=NbTbDifF4NkBG0ohv_34b+gX9b(Hlf2w~@EsPl(JywUG(Zjp_pvA;%f1W{b7(aFmp z3Cqp>vebh=TJj*ywMt;smCF3K_0v#s-n%#3bZCgPTU(zNY41Mq;eYX#Jq0bgIMPKi zWG((M;djPY*@?Wly@o1X?}Hy$%RSw=)&>aSv9}y9Yscqy?#WK_UiX_k8#B-Ly$`)x zCxb>F71Vgb1$ET;d-)!8q9DCx9gmnM3j1aQvJ9@y=OU z@>*IKK^GsC#B<5IE%8gK{()(gEat#BvN)za@-h8YqoyXtoQO zmoAA!rbq18psr zC-dRA%`OF`P4DODS65#jd));8UL=DJUxRVM>TF6R<@xi^^YVB>#m&ye)ht6@niHe% zNhG84IN$J@Q*0$J4vMc4x3Py%9m%G=0UB9URMa2cyev*c4Qm<@`yp`GsAML9R%Dl7&2|X1 z>bLLSfmVVEsCq!$fnHkI8=K<(AA2R*ISA~2hV}-bfq?<&OF$yR%+8)(OAn1-6U-4V zPlYO2Xw*HWc0IQ{&*J_GL-r!aX?eioYe4SHteX<>g|GyJND<&y;R+fVRMmS9_k5rZ?*Trgo_$sQ zgfghbdnAu{+uO`~dU`Ak4U_hOC+Kqbh0Q#0?UbRkIl^zYt-@*GfcBt)y!>=GFf>FN zOTS>GL&!4yD{O`Yu^%Au%kuYx&ipH`BXf&kJ15u0{?8{YWo4gdWi1cbX=p?bLS=yi zXwA~vI(rYS8ASVBrhS96elgT2!azNL_l^o4EFHJfg9lTf1aeeSUrH}7rt$}X1NG?9 zBM2&_dqS}fza1w7mZoO$qp@3X>|D7bYXv{EQW@oS)8y*m-Y_(9NycHH++us7-moE_w0QUlMT z#Hl4iC57O&R=;T#)K5>R97l5ig#zh* z?bsNjjEc6n0koWf*di$@+47{w$phXJsYat+T(Yv(Vfpe~c5^_L`fR{@2H;R=^8>~a zs4p!o-PF>u77PfpxJ9B&naILc{(8)~=PlpSSod zd`7O#fx~P(*vMR|dj9-5!s>L-#a zDh7qqxVF(*oDi%bG~A$VAEvqDcH(I;w1okN(bap7L_Xi=5TVXpy0kRUuPe2M`Wk@2 zNGk7>P*G5Hq&ey2XaKQH2?}0>=7n7jhy4IR6(OYs8nHZcw*~M708nT0z-{=P9LhR) zuf7^&*GrVB2w4{R#ugl(uP%+`Wo3QJ$zV?Z^0Cg5#QfK_cN*H6u=DoA&P#TK*nOe+ z!X~Zvrgnf&72$>e#f*7U9Ol{W#II-t-|FRudoF%R1-vzM-fnC@3-Y$olq}At!PJYt zIG!jyA!^)czU7eiDN5c7Jwv+Ld5*^N%e@R^wo-Z1pi*g=*Gyl%dKng&|NeEJiU#;Q%w}$BZo33pd z-M6;SN2?EUf+0Ol)E&4j-hwC!g8T|O?%$;|1FVeN3R8dtGyJs0^!Xjg~%x%zx4YD%> z^87D3n>ezVa`FS}%gyMU1XQ(5%-x<4RSGEVV85P0T|RLpJe0)ft~H;DS8%83u+oXo za5Y6~xSC^@T$-uOJ z+jH;|jNmkV%k?5j^gF$aKj?q*u#H(ypnb}{OL%EANP{LlT_!(D7=pZG7#0!f`(QGV@i%nry+ZpSW#3ai=k_YxNO`-4Y^*u02T9S>HOnN0$d|~v z@w=^ z6GlF-&*lC;7~3kb3XjJ$&YySl;HWizaw^1rBGn3~1 zj@hrJ%b$=`ObE*yW24@I4XW_9fp-r4Zwi!V#7op3C$tsla+9zR%}O$j}5$q*;2 zJPt-W%c-@6J^RUV4(GvKhYLMAd1lsmgVLCG#b5!m^MVXblW$4)Z|Uc5ro$A4E8!3^pTc+L`>4VI>VF94uTGNwq}B_hG~v_T!W$l$oLVYSM>eeyV02 zS6$jpU9n5|;d*zFrXnZi{-^J`Em5&5H~xzY@FN{Uh(bZr8gi7L@p9~?>MXwP%wQToH_*EpRKKCKz?ueaJ|0A%;VeSu9;Y&wNT@F zGhW%#&=)d7q)grI<9~h)>f8JzF*hEwKXQ{jK~UJ5E&8DuT6tfnHC9_|y{m;kMBYg^ zdNgLAM*1p>4|xm#}cU%jX4B(7sf=x`+SAp*&Z#I_T{lr$rwRRh?j;+c(B;~ zSy#Yn8!J*j-bb*$vv-@}2>+5Q<>lDx*`g_)&y(L5y?|V<*#92E?M~qj=$w}QJ_g^G zz9f$P)d~qQ{>&I%+SFIc9A|Ev=I>CeG+%`>k9TW&RmPG`IJE~U)}dy1-Vm|}luh7y ztgfRRJ>-FUA*X7Z4GSKFw4<%@iPKVSCaCk!B`({sHrc+_UlU4;nuIi+R_bW8PF zjO;Y8+Zki|0HVr~=OfGW^MguOzSTbU5t~)HG$eUd0qYYebD*qE5cyOivuDNzf>tSG@!0=_F( zp4ZjY2_By=)XssPmH^~jfO^NZja;0HMa%6O(#*-ccP3w-NfDM7F5Vz01^>~lgI$fs z*4|!a{xG&{^-Y%-Ukyq+$UN&@V;;VB>*WGL(7Ey74rAtS$3C_X{tfOpE5SG-5|WKs z6i0|ZFEFla3@tn#1pqO;R5Eny(~$bQJUVv6NM3Je!|2Db%H6#M;UKRquj@;lcCYo@ zmsm{7eN4H7r_c8;w@+g-g(2Q-{LU;oaGvLesoD}$J@P@~`*)W^7Li3;&h-r!yM$g| zcYPo^j{&EOpqrV(-sQY8u>Cf>eR{I{>UYpSU717vi#h3sXI?}%|AO67 zbPYydMAr5xwcE83Sy{auo$GE?owbxlA}3{3$_nrCX>JkDkPDF+4rN~M{W7zPd!|d= zR+;?(wwk#4I>SUlKg}3`#ggB%qF%bX`0j)eWsYpHPvkjuSyDA@5t~@&@ttqK@Do5W zWW-8C)?u%kS|Vk4_o^p?z54o1=9ig)m*?mvc)jqUdqNV0;uw6WC`ThB3eUESGC)-aUJxE5sClo|JyW0XGyM1~-&es9@Q?)hebV2koe4?5n6% zY}&yYku>t_*L^}?WYLPoy`qM(6{{B2y$v`~qmICiyA{4K{-sIJU`k7s3+gJ;cVFxJ zs}nNoLY`qE5K%w&vOI-PZfAo~LSH+L_3m{xX5z5cwn%p3-I?1GW0$Tb)ejvTh=#BX*`>gwKx_c;fR(cuzjuJm>dcq@DS_-FvP?QJlGkjMB8 zq-IOLZuWCaV6A*)q$zv7lK-WL$H-Yv=>K$=()Df5H9!|_hjxlh4&ai2Z-Xy2L?sV? zJg3z>8q;wfa^SWp0Cq8Wdq&@9GQvtiY;U>@@h#3`p|RLd4uBc{n{{L2hn3ave@Ff zLEx(e0$E3(YoNMFxGd|(p^KToot%-};1OvI?x-v&f21$E$Pj8ahWzro0n?fqrgb74 zx-6Vh`qWup_2X> zjZ?|{cbmpv<2j9C#ci3#M0tFT0?x#Nm*#nt%Ck|(BX!;ECYhjBy4LknclZS~q!lSq zKg^!eA8E8)dT5$dif*Q~<*CtW|KdCGV4jBTwpPh|y^FYKtK0;I3QgB?X8z6hP`vTa z?~I(h$e=?<7=k0ba{0EeW-!GG_`uEfd)7-vV~dnTesv`WRk#Q9bZuX%OP=KyHZ+X> zPF-x{e&PnxK_KjEZgEtU$^&`Xf(?(61JX0|4ELqBZ&Ng(z^M?iTD3wr+C zu}{zK&AWHsp^u=a7oEW}q2zq?WirLzmN0KAX(WD9Rzn*k6a-H41BvPg<>?j8J5@E6 z`ZN>se&@yTja^9C^(TCR>5#7U1+!6fRe9??G4rrAT*az4`}3DCL4L>kW86Al!=Y6Y zSnad#2+kM+R=wOHPSe#(Zj4%G9}bR;iH5m-CX&>Z2mN(WI7+kO+2SKI(-=pNzLtUm z{;V7_vY8LUA53idLNIskfSHzEb$@Dy2RBRv=LIkAS?J>&DyK?g*K^S2B~69 zcFn%fXuQ^Vd`Da5bb6bbvbGspdhy3kU6#ILDr(zjuK7t;Q2XCz6z{B+aAB0inybDR zdV@E5imqzvtD96PSg>49=9`k$BOyG9Jt`-vf*n0J!g0z0yk4CQ2j;c64&O zc*~v%am@q3*{;vV)s^xn$l{km`e(Z@l0GblaoJqC853$gAU(yZL6iUY21jF95w(Uq z+ES91@lkGiA7{|M*SWKXO#B^{%T{)mPmi(MzdN!Op8E44s{C z!2HtnJH#C<+4)VT#o5*kRUV#f1S?Ra(WMa0Z3KD}NCBIKblUbSKAtEFhVv^b zrBm~VrHsl`e+>0;l=MA3v)XxfJSUGd1S`I^-D|ShWqiW|?rLIEeSg5B!#MkRP$8^S zA*58F#rzJ*#1#=4)F)9l+Yq~=e>zQ|Yl_8hhVH`dTzcY1pI1MOYmJ4s>#PL(7}^T7 zbAY5Gn3IQO;M-FCZ5mOVwLE}8%w2pkmAD z?bzu?Eo-uuTvi;Mc@x%VKsd{W-o)p!NT4&nRIkLjr zT0_Hy8`ZrQ9hOw@DztC77^wk7Bfqr$NOe0{_UR49OwxK{`4nvLR@#Xy&sh*9cj!PB(OXW6`{r>gPd3DJLZr>$xs&yw zE8W(-veB;^!n8BiLmPNv(*}NyUA^AEeE^I6XLGaFmN0MCCgnfX#zJ3S zBUBp-@zCU5;$PV%Mo;7sl)UTaxVw`vOlS3^FM4Irr?Pb})K~P}Twhg*ImVMIdHJL` zh1#|Q1NtPVjj~xFr>NS%yTQh-3NyiAOM=IX$|eM1CoLD{N3a#sWEl?KX{_qO#9{Ho zVO6m&sT8BBg^Gsb=a^h7(P6WD{?T+h+%NQ2#kaw=jz;_CMON68bSor z)T_psUzsQRL_?A-!U+D>(B%R>CMy$D(!+)SC}H-tDueDe49G7ZH7d$ma&Mm5m^Rps zgtpV?k*{vdmwN2XnW4u8-K}Ni%)-IUtO8XPlX_zp!-DwzjKc1GCpS(X0#-v!YRg5J zh53da$=rg00@0c$ZiY@7{g>uF65Fp8iK=C9ZS;xKayu={1zhpUn&0jc-ZplyU3oWX zQLbG|lXXOmIZDMGjiIIw%v_q=kNawEOF#F`0f+9Z@AvZZ`9wckUb92NcN<%3mh)FS zZuEO;Nv2KkN2Iw{4`RD>Mg1bvyIRC(r-v){#8csmVB0mTvQo7a|6~>AOJt5tj-fA> zUumG9@+R|vSrl-crKWl)h9nptSFePq9Z}oF$^@X>=O$Jt#wNR@EJf$m{^Mi}`NjYQOkj`UC6Lt1r&7$Rft!;3^;wyjIY8 zyhbZnX~O+M{z~UDGq_s1Sc`_}3bi}K_mq?4z=M)gQ8^n%!+S+YC6NEX8E>n@28BiZpab_=BZa8bvKLOe5ASr|f+M88&1XCjNU(R*d(UEYYGV+Cu2!5h;1+OC_UPQI6WxMo^ z-PaEGWY_k@f8OIh%2_qN?VVF!mkl7{vvd>f?Bx2_CV7R?l+}lFA8nF{w=54q&c=WqbF(YI$1?2kipH9{AWcjum z7?uBX0bK?nf4z>RD6R;{Lwj2D~8zIWfRTH{V#1l>6WG za+2dx<@0>HJ6`?f-&=hm=1Oj8?wZz8M`FNudi=B1pE-u9$v-cVXFQ<@|2W=m^k1E# zqKhbSqVKV^DOwW4%%Fa}*QlUVpV1wuf-ZXYyw_%s{+&G+x2}KbO9pOpDL1Lq)zvj= zIyDdkQ>@sF8Fa3uAlYtfgnK#*jv7f{zD$|7WBy@lP1AVeomO96QKhwg;nXow+L}fU zbNH0QbWYbmOb3ZOugDc19x^*SJM3gLn8YpNg}-?5IX^$Y)$duh1{Z|% z2MJ;qfd`f5+!>({R@X`~|n#US!`fG~4;>e+_pDORV;0Pfob_GKLR82E$%$ZOpRKqz7+ zaBz62LY4Y(0WJB>dvEh;WWV?|2;{I8d1zzCJ;VVT%F22KF3nA*QYmXKB+2fJ3^kDw zdl@}_sBViJckkUReRzk4f`VfFyr1R9 zWI|`a(E>S1P7!$1GS2--lI78xzrfMh5qR12>kB^Od8I-Vh|rR4F6#~ z0SzTKZtgRH=%y(pDgv4p#%ZgAY~C-E5oc&992SH`MdQGMJ+7leIb4)w(LLUR; z58%3D6a7XFeH8Y%czCWrh_0!*ed6RvIeGbHa6x1lvM30{S(Rve0Hk^Gh6P1+bv2+- zh%yB0asbdYkhYJQkGJ+IdHgH-m)1dS9sTxJ(6bSCe`Tk)1@d_@^2Si~o1c9KR z2BEv;VVodBcFYH46Xftv0RdC`k&4O$eGzL3#PFD{j@Ob#SE^#bOh5dR==m!BcCbik1q^xJ^_-w3h4cQ4*0um3z z;jr#*wcZ?^M&JN~?uPB^)yx#_GH#lMQdlq}m2Mj$k_XS=E0E$j0rqSFssvrQQ;cu> zHdu8R`RuzsxT5;j1sR!8PLcQM+zNRgICzzo8#1!Qy%vG?vW(;{Rb}O*6Y~JYL$A08 z&K^|H>qCQR%l=hUTbssB+K39<5fRPz1D1dWTCR*%^}w#{QWr!tZxShIQT&Y1HrdkTiM(_?+`lH{>8M zC&>Vy-&Mj^&JT{%dW7c!#~!v_2j!zW9uE9`E@>XLca)9IKz$^Ax;s4ljJoH&}k*ZV!}2sV>A@=#SkPi%R&$2_R(_KwB#*y;PJa`9^EaOs z1y2joXfQ5)9TS6vj}VfT1)8|mfbYL~{Tg*!U!MVzAz*3?T^M@5ZvdtaaLO6Nb9mTW zu7d%X+bFzb8t!0003mfTe|2;>t!Y;ls(4Rz<1Zo zS>zI;JN>A)VteRGOXMH_8q{$N=&V6gElnZ6BX2MXYJ~07zNtX3XK| zCOHpsfHGL=pC%z5kd&+Wwc-YQFa#hI1o{9;NPR8%L(pc!ico#@$Q|@D1MrY!tlVOJ z#oy4MSiTD=1(eVakFaXW${kaF19}5s+w==g{y>~0J3Bkurr`h&;BYJJ>JA%vYc5H$ zu?52^$%v(?V!Cwt?}DeluZ(&wT!YUJkIJ^k4!qP);-9g|&-Ob$YCHD<&Q!r0p4r~d zOi%a|Yo0Ixqy}R!MFCa~;sUYJrNE1~+-GM3NIgG)6l`Kw+Qq?lG3JoragK)XZnHsD zbhIo`Je*b-%QP`MU#&kUCHX^d;FbXfOrPBUykG|hr<22I10`0x{B!?9QH&kT?M5?;L{#4jlHDq_A}yW^jP0Yu*Yp7=~_;A#|!=)9e0Aw3>%d-UA;3$j~LVRv&&CJG4#k z915ndY1L#6mh4fJ%App65c&O0K|u}N`uZa{8A~2(_NYQ6X&@4oS%)wLXZd(ZziL`a z%H+MBoeYGS^%3mRDw2mDPoiewtPXJJvXqhvu;jbY4F{BD!UhKqWx_tgZ|`?vHym`) zW5}1$r|T3^;dksyqdp`8R!Ycu72PlcGe8ew*`6TY1EY|8=fdp#p>2Qu=K;)s*K+wi z^`2;)rkdK9wghn<-1fHS;o)HqNdM8WYx2y_bn*1s!AT&e4eAB0`^P`k>+RVnI^pGW z;kalY!4@QHtOTkz$ZBTkp)mO06CFT<|9`pAfBZ^mK8RnbWT5-{rM@(WgBUuxR8-x` zYq%25mvwNO@L;(JbC88RBvi@G2saYaW{Z4lSVBNkr-Y~-^%0zdq+u2GCKupJj@Dx^ z*4QlQ?|UGeUEA8`<}es92?T2ltC^j!M za{_F2uEB=i*w+_>&a3_ir)geHCwYQGoqQm7_l}yrYdq|WX5bb9O2u;&6g8_8^#dhV znmRsoaI@;pxjeT)vDyfIyCygk0Cqn_)QECk=#4<`#stp~kzFAFpE`ZI zz;#JmF<#^cp!p4D4wGeIiHlbTnwa}aO6IUeAumHxCvX7h$M{J?h_!WyhXC>fq9}4I z0BkB?x!1XXvso8MsxZLlf@U8_mJLxEe@CrAPyXrPoNc3EKsO~TGQ1x8NR4)Nd>hHR*t3w`9{ zg>^8QivOXKo86#|pCD(td^w=3>=p!DT5c{54wND2oI$3YDB(lfVp8xJ5%p)=@WL(& zhbH+WH-TgYNG3pP34p04a_{y!5#;5ZFS{1`!5zxKe&RM7@}{T&4YUp4@?AUxwGUXi12OVVA=)H=G(F{B%H24b+Y68at@DGDrbw{JU z51f>N0%eK?Rw@@R(zD#S0aLD@WlLa8|V@8sM7 z!|~)E%ZuQj2J}W20fC~{nIpI|xId90z6ZcGGlQE#I{65ZHHiJ3>4kK%>&KZJKPyvif68(-mMAfeZQMA5AR(L1= zleSNC&d$zZ4YpwQ2E;mv-Kn>(x$=a}AKASSPW*etPq*;88TKL~BQaAuP$(7_6+Ig) z3gdMVmxkfALWUC}g;+TKiStOrK)AR6{^b8f&;8$i<-jlGKt(!3(OC)w|H;WH-p!RV G4ER6yV)g0( diff --git a/PathTracking/cgmres_nmpc/Figure_2.png b/PathTracking/cgmres_nmpc/Figure_2.png deleted file mode 100644 index 99ebc493d01b13310307486c625f78961777bbde..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 30942 zcmeFZbwHF~*DicBFmy;GT>?rf-6*XBqI83RfTVN@64EUqjevr5gLDX}v~&*L-ObtK z?|HuG{l4#g&%fuNgEBfZ%)R%$_gZVObzRpYfidzMC08=X61*tvB&+50!p_{u)%cAW zWMk}PZ*AvfZD~U9V)n+-($1Ft0T=kgL2u#YWG}+a{huG;vU~H2`+fQl4g}FdiZTz? z+)_5D-MvW6Y9%i7^G2Owx1$4?nbCsj*}{T-MPZRLDCCFXA`dca>Ur57_%X=~*#^ry zz}0@3T?%K>((L8tI=+9HiHZsHGgfs$d-T&>Aa*-@aC%t%=z8GEAMLR}pFO@e(oN=h ztbbd-=zWB6w<1h5fKs+w%;c6{rkpyI6Zi(nqrKi0G^Y) z`oC}gA6u5h8ZL;OL(4aYNuE(y_%`_Z#Aiu#yfvBQtc9GE{=Fic=E~QjCg+E1V-=Rf z*x1;!M;v%JNfB$-A;5u!l-f62$Qc%9SyjV+@d1<3xfXfsA3p| z`}66K8*zJWtrMCMX2nMjAEI~b+=%-;GMA+nUOKmK5T=q*&<_f zPZwzs z=*+jEfg$4p1(`2l?$Va!CRg$Mm|Gw+aG0P_ykq|U9r{2@`alH@IU>*BmxK>X>{17_ zRGGm@Bw<>R9DOmh$o$H@J2J44$bqXy=L}Uz(EgT(wK9Glid9tN|OJ@A3{Tgjnov?xoTB@fdP`H$4N-AyH=0_nI z@($C>CHeP8l;4Ax`y9`oHg_Wq+g?pR{#@b6E~S1%8f;}hE_qbV z#~oB8AG9GlW|;4ivgtxoA61aM`xE=49eaE49}kX;g*yrYRg@yg-R2^Wha1`0aPIH# zL#Mqb`GtjWNbl|0Qq4}|MFlSB=GQ1;9Ntd6ev$B!=Om<)PuA^kZmiqi{YHO!wP9W_ z>0C2njI_>(TrsSTg7V%+s;Y#L(QNa()5SOy=u{5<#q;NU;o-{f*|2LeGzBmF8ptz~ z+kMj?uixMB@$oB2bJIoIMLoFdo!Skq&9PEch{ttXk3+wfge4BE+`OlCbG)2CGE!Ni zDcrQ)aYfgI&WC;X8}+pB7qK^cq5%*+%J4Eg$#?ar{umQ`YcBp_D9XQZl-V_w;Ort)8Ws~NcXrO0;iY7RfP=B zw{Ge6v%_5y$Y0#l!sA^M{#j0HGG7waZgiTN?~csp+1k%^Mg!^)lYVm5nj0lZm&L}B z3KjYmB6qn}gcFlw@uT;-DD9~Qd;J^Hs7DOot_E9S(Tva24`nW!MCF^UZ7m=e<7_9Z3YC(lZ99j)y>M8F5VX2Q==_DMx9?pZjKI5$ z#s}d=;zvK*WJl4>2;6#=uf1E?S0kVFV5P5fAxg5ynQaKpg4fm3RgDWSOn3DxJm|(1 zgV})Mk&KL!j>%UD&9}BzWN38sH4VCR3{}w4k4)X(AZ3!>v#RG$FEVZ^(Q5x)z)WQ| zTG-p8VNL0e>guxY?!pqMv#5HGJ^YlivaedRjfE8iHXLq(boaJq9#8FU6S%GP#+2Nl zsKAc^`)>uDy~bi7Gulj*WT3&*b;^Au^^>S;5ips={bWbpy%uruxwMliqbCFRr}mfS zfYo9ye%1Ns!}q|4-A;Fn3#I8J^gktpn)%eAxn4W-9$&3DXOA{@>b`jYQYKyPZ`Kg% zcHbGFzCGdHxQ3VT)dSp3V_BsvjJTV9R0(#DfxqS(+zE@$)Ny$XlW5o>(&J^rq1A3l z2TQVi^HNaEz<}W?Sa(8TOh+7Y;vcWCVPZU0bkOYd4#C35YJtp(BE^NDz@8Y1fjwbm zvdzxrW6W;dZ8PTID7~_vVQH+zznQtnANdRnS{7-OFZMCa=F)vA13!z~v3Uo-(C|Ba!HWwOw040L}UckiKlq-zfQ#t1;P(919JMrO48N zuVNsGNjKw3SY~5R{mo$>%*W(f(k1I%);kcLSLPcby;`TcAS@XPB;WTswJ*@ER^Eta z3+LKMh>R~UYPJhH3CKI=y7hg1sZwjtQCLlVSVRoO1En9%C^gpO54ux?iK8UW*{WYWH8DF06v2k&Yi11-E<&XO&*wThJP4g2qJm<_Usj~-LegCLfclXH`>5W}5$=;e= zFCv8+4!xRNCsU3D+YKiMQ1g6y*xu2oA+Xw+WR5U?KW-xjc~rn0RTt+B42M1f+NAI4^vbdZl3)|^m%>s4zMfp|L> z=O$WiyEzP_kZgYY(Wx6bAGYKqzPtu6v>6nBS+5k z1GjT>edSTa%IwyURm4MYSs(oL6&;huT-%93DaKa7o>fOf@YPI-9p(8_KKLl@N&R1s9QI4x%uM{x@TkyI0O5wVX!VQ{UZIKL`1B{gcxE z?CT@AAc$sGWMgA%u5nl}`X|xOHftPICxv_7D>Xf0*!*U1ZD4s;po-j=n3R_+atwsuU$R7m>hI?)@8u~7%qYs%08hP;a!zk zb%q^g&L)$?Z{CEtr(#Nnx%eylDj%K zXB(5rwz#sZhaleMXP8;z!jR)yyZi^CG#_#<2EPj8kp1NS%FmUwd3g@lZ8{Dq994%#ZPwb5i z?tRspqS7SzjeQ~c=<>Rw>f>2n9(F=@Mx){*{Wy#xWvnA58$)N#i7h3f^~)EX~>X@(K6aq&LG~k^2z_Tvx!R*{&n} zeY0yo?{ye? zBL7n}hmOa@REX*4TZ;OC$3+TVfUc1Auw^AiRPdYyTPjvD z%CsCskwrYV`+Syfe8^1}bO zAfyfQnEfURr??MG(0hY5^Y+4qgq-~4M1`eJkQ`+l4>u|K@|VoanZPIk@`at`Fx4gd z1v{$H-D*79pHEbN97&fu9A$8%Ofn_58-+h3A$3+FvZ9>IwX)Cp%J6K={n_AZvPQLq z-Qmy9@np=Q3h(o9WfG$&JoI;3px1saf_8gKlb&C+!og8#q}0#UlCjW7Nf;=rNA6oa ziu)qJt&?vz2@4W~Z&dQ7FAOcYgCf>eEq8wP$m)v9>e+uE@Sl()SbQNiWHl6~ zpu)!}J|0jZ!}KTi>FUP}`QZWo8m}MEOvgABl=v9i=h>HuA~@!Q6+9jEAy_j=w4*L| znhZC1*jjHpne6V`XHABw*Rhw(uV5F5J_{`KAeR_(LZh=5fn_QGIQxFL=CnXfZ%Po4 z{BRw;{2km_=x%7}Im@?clcL{}g_hQ~lBx1HU$k&rOo}{Xu`CtkvhSRKT~lPqW<4AE z!g@Q#^iTEORc6K3P|_x&*0XUj>c=vKcein*GGD}7{8{KQ7I#=ENwZgcAV6Ip*RuV% zU|cg~--BF$eAvWMmDAwrgu6cshHiRip*~F@Wt0~#{lw_g%7fu_o=0BIM~m# zSu^t~+0auvj=65%3*;?KK(Dk@45==wF4+-Kw;SWG|fz4L@` zEyiM~%^GtjJ_VYMCl$JLTZtCYwH7mX=w|E+w^f?Qo5{>>RJ0m2m|T4rH)QZI2Q`w! z`Lq!|^%iv^4vFKmwA|(;Tt61;TL|?RroWY|jK0h*w8d;@de%EAqqy5B&92-vhFi9q zoW*UDBi8RrJ?*ITT;?qbiAi0^#mfA^N`ky5ZP617krO9UYMk^uwT)y)%gOY)hY2H* z#gmZe5bg!I>j3oI;UzDv@mUihvCCl z{EiKx%g>i1`L^XpzM-8L_l;YdXJuir1sTAz%W7FZjPQT1pIMR&pseXj z*|E3sjw7KqexZ(*z7N$z9rWfXlR#mr1mzEdWa98O${E~5iFEx?G|G1bSl;O-YV|Z8 ztNA#L?$2W)WC_`Mj9Z24+5CdpU?mW9=q>crV36Itd7*NtXDO>X_rX+X+JMi)l&`kI zB6cwv1JM-uSR z1VI2dqLc?ozf8{WIs0bwa!Z=`ENJ{`T?pmpByf;4C@ACKlpAfih`w=jbU0j9)hZk* z0jCeRUWeC9!}_IeudL*}JbNMPpS`{B**aD@zX-v`Kn9G2()7=fr##Esab+?9I&}*k zx9j$H3wpF~{4|vE`q%&lm2n9F7dku8lPqYLHuCVRKCb2n*^ z@fJu+Glkmz;tnzn|1+>lXtDO^%g?SZ|8eV%-MO|>+i8(PY3wjK4w=#7&lm+|WjQ%H zbQYzg0Pl;fl$&wat+H;Jv}=ku=oRJ87XP>}?y^b2 zRk!(o0vG*q!|iB@X3-A-8s9hj{ed^W^{%i%qjCyCZm!c@a zYu8wgjwkIj)%mO5pl5IyHj34FJ@~#g)1V8_u$`#5JN9a!BjO(93;>x|T&IKmB8X$_ znR;z_2CeWL8TH|@?&|DpnVw(2R9&~Hz8!B*>*`lnsM_oEtvt#5P1uY%zvuQ$ODp*D z@-q7P^3uzCtmI)U)4&rb@0H!&4sAMN+`_IAv+_-BdS02KG-{Ev{D^}PH? z6E8Ut#f|6KOmgAPJ%Whv@NisQDgj)dvo1rw4FWoe@X*lEXfGueV!0?fe%g5~pWXa(ddH~2S8MjtVmz=#2e0nQj zmd&+bDW47d>(fNP@$y$M`!gQejCATW?!B)**hZ68eWs!D9>B_&e*J4#@d*jiAI+HW z+-b3`#+bAbpnCk|iS$HfYF-}Fm$@2GO%4GR1*(W3d>X$NBVXkloL~H$oOtc+?W&14 zIq7dhId!XydXo4{CbxDy8tm()?hlzC1v-`3XJ=VkRhKSnt{zHS#N; zU`yp#v=nm@q7Js!?I6llDDdb#k15u76Jx{XqoAmqQ47E(rpYV5hsiej^c zhQ6v=AIZxc09-mZ z)Wh}X{z=o25u!N8XF&^u_E0YXsjDgK6GOB0X&Q%HX_!#1U2Fv|_(-q`8bGcq5t0+G zE^L+)Ul{*ReD1>(=}Adt#7o9xrTY#0B*yHNqOZjst_iV7|mB8CQl9~om3 zLKT>$we=4W7F6~0aHBej%eGZ~&g0}%Epw8;oN;Xc2$4D2yQ?1i6PQu!!vmN-2)Lhk zjA1Fttdvw#F-b|G>+4qF+yIo-4>OccM*Z-W7n~rYy^R9#fR8lUTf^v{E98G~!HE_E@<$zkLMZYVcLhBsfF-I7*Q&9QoM{CtOGZZM6Q{*n;6 z2YlQR9y%&o%SrcSclT3J<)8x2M%P|qM(>RVC2hJJJ}t#+-6~VNk8(!pKP&}>#asN@ z663aA5N|VmZmuarT{zO*=CRZ?H5dE|B$}fcq$}`Mh{3@Y8Rls$yQK{I^0yd5wQf`t z;4at2dgP&W?_=%5)d5s!_i#{!3HT*I=jlM`-2;*EHMPEJNm8;rq^>Uh&<=UzFARF2 z+5ZS8Y&ip`%ggpqQc5}E!~(2FyEskN0p?#VuTY5ru$GDsF1+@G2v=lP7U3Ry%tDKf zBt?1$yx1(qN{m~=q;!bTP|VA3U!5Pd0oe4u%cd4yW*Dv?eRGnLluZ_fOF{rgvi8Pb zqYAZ@fVuVXkIwdgmR5NB^ao)1?t{Y}1e`e#B`Jj8F#qoAau`Ih z@s}qFjNIG=U~ZsF?yPm*5ZSz_Zo0zrqpxuPu2*FLm0X~O{hjt-j)>LL0D8Osi?wE} zYI36DX4|!?jWyj11|gr9*dZDhwqK2xnSrc@h1UB})q1iDFH0_>^>l9`%9HzH{%|Nj z0;3bgsS|@V{WW2Af7x)=6<|F{J?7wW_^fpC9*@ee{Zl3zPvX}`;2bpS&WnF{J$cxY_Qu-u(U{3k6v9bxNmyT8BR zcc#G;M0sScg;mU$T(}6-Tq@@}hF~YE=oK6R z`6-#*8Eh{BNyV1N%D=+2LYvY)1u4Lf*gH@Bg4{81DSSa}Hv;@B|(dz0+|$g(adO3-E^!0_!ET>3rkJAk^g7uWldvTGQ1M$!mf zY?e=Yr@J34&wa~Dvl_e}kf&=gDXl1%J@wLNo<}S(b{s$B`4;u(%Z@AnWV=8_U{Og6 z2jr(#p+;fb0C>$em6Qzx+)!u6eb?7Ew`Zx-oC;Os}#T8wy%){>;P4!5{#+}-fgQu){lc1W>wR;V^U z*;$8Gd%ZjTcicZbJOo5Mza$ziqY_2%j2 zzH|0}%Mw312$OnyzQ%gEgP`k^yb&|-+LIj`9!7yaavMf|cU(yuk_eY$dQU(X>F4Jc zeT;mNZtcv@fOn!B+p33aiU^naj`-;+f(d+L|*V9fQP?l6Bw;Su4WtEwQp!B_L#K* zGEqW!pU`mC@3!``4#WRN=w`a3SO_HhSHG~dL^OJ@&NN)y-P*Xm*y#lL31YjJ|Mf@! z2e(cIW*8Z#$d{|vAu2FrOtBxhytRubIOThGu!6DkiwP4J8Wwi{RWJ2rr_W_j$AE0) zGNBZ=$!x0)2$+AOm*KMj<_-8qBa!j#8x~ME$ThvaicU!hf0gDgx3SCkzDE+q#(pn_ zR(rt$d5k7mzQr7~sx$%7@${tWCITeV=sTURAjDbH=*ZlslA&;d0Wf>|4#Pn9Sv8Wt z%T)WJMyP4vey6B@|8Zekuoj4o@F(y~{!os6K0|o--vSt1mK$PKO3HS|RP|^2D@niyUZEm!mOa8C z6EQ37t3;%xzC=2RoPrMcSyT{$OJDWTf)M-;6~hD^i8?_f4lpL)P;7uaFefrDPa0)}P#JqV1g}FZ_fXJEiO9T};ka~vI z3X8X-yFk%lR6SYxdXx)fF!SKp9Q*Fb3R2qZ!yHLK-OCW7F$iJ*OnwM9ePHd67pCRX z@A%W@WIOxq??!qun)oqaiUrhjjhVQ%BrCBi*_|^v6 z%;i4zgr|H!JM264SKun}+U=aDxAKiFwz8!!BYC%_$ z7n{6d*QX1}n&sVnvJysI`m>Z0Mn$hDUIzC~ETRJ%uk zXFY@M-X<3o=@Hk5Nqx3&Hm!|@G)Q#(oCPa6%&PQzu7D}x_AeGg)m3iH3m26~wt4Wo zENKx^z=OX2c#2YEKlcbIP{eCaW;{`#Fmmn=V5@+|bVCJDk;R}7a{a)bFZZV6K!C{R z8Y$98=1U7ZJ~tP)Bd*kzzUu70P!tcfqHJs28TMqqe=$hY!W!|EA~w)6>%v4Kax0r) zt(N&VMm}XpaqBy8QvA)E;dfU}0vQ!WSn>FR07V8sI!#%`Lst6sj5gNzz@KGz=sAA{ z56K|dIR`Lb`=MX~21m(5D_jIg-%vR9Z?wJ;x)+MAs5%?3?zXh-uBb7quI6S2k1c4; zKg}tFX{$0+>Wt0^K+&cnZB`>pxG!DUdi#`wm%J14L~wss89%Gy%$}Z$wa+L+xnTE# z&s`hRu;p3GxHsU$7Gypqd*)oS{9&dmgP0y0=9CGg(o2!RLAI~PiuvsGBUNvBT0vek zDQO<|&ug<`#Mj)M6myEzz3#sJ7|Wwn>2c9vzxqR&MQ4>(?X{4f%8I_qi|!w?#le~! z{scsUm;pTYCW;C?jUiPqfGg2r)kR|QY!(IJwjku+$!jpctM|Assx7~7#*-p;^42eC z)YXP>_OC9o(I#PC_ek0ibgTn8?Gn1zwK!6{QIpMfy0dorEr>toc7_jcLF$3iMQysW zR1BDpK<3Oz2CE~4BP7tEOnS(#2@fVSAV~V?{B+s-h8pwQ3{k~-0Y4Aeu0HcdyK#Ax zFEBu7c<^Rb0*>OFIcroJe1*7%r7Dxxs#J^>_cLCTdBY5=Kc1nT(^I&LUZC>uOinBx z1c<1BLKGl*3|+Cza{vhK-#A*GthOtGQpDWf1YH2Z;CqfP8|)vT?gLuAiaI4(+4j3f z7*O>jUUl8sF}q8hIE7=4ohtE|q34BoUER*3XmPXSlKNszja>x$@myO^W89f7%>Z$f ziWmk<1I0*vw}_EK6f^Ex49Op^U)YadQ|&GZBAD_K^wf?X4&8S@R}J{<K|Ds{-vOU{?wV6J&e*@OVhh zAf(r*7b$$FrU4r~Qae80B0FGd2)<5K6cS{=y>hJ3@m;&o@m}21q??JfvV|+LPDajy zqu-%7uL_5|I6n_eUy2Sb#?0Y9)vc=hWEbmI+^ldMvgX?`S;yD(lQCoHcBAAEru1O- zFG0Phb=Q{GhKDCU+ksE&FLj;7l6+!8G4=n5ZdA_v!bgJGK#jU>-1TCs$*2YP4}-2* zr~?nXQ!kl<0*AwGCam^T5hI!OV3;Rp&y9S8BA3$FcV$z0|Yn?E7*YZ8O+&?+vl~;ZwDkWK87a z*b%vZkgTUAjx(773A-Q5A%V0r`WSjmdM@=N7{4A)}RoHq}iT=<@SJvp2rW zBV-#oPm?byw+20?e;umoaA3@1cIU6}O-@=P%6z)aeEk39HMn~+m`;A2tgzi-i;O-a z=B(Di;ODFQXc+aet21)DGnDk=mNEd*3NFIrKyI^Ds#Ew$(nq4G;aKNs;)A7ttHHrR zfObrT&!}r?xVVi8v9oV{I7e+fK%?_m{XAPXZ7XkU%e8-SU|jkB#02-h6ib*_P5`+t z-Z2bIk|XfIZA4?ba1t#%VJmi>BcQWxpQ%OvgvUsBeJmDE^@%WYS7m%}KSK7M7pszm zq@lK|s@}$r8ElN>527VGttaQh+j5mpq$-~@SCPqgIX>^E_+ZnXL92oLTe)M_n*GnE zN<;|S-uabHV)2t$)ioq*?f*E4sxpEWSa7bR$0bwCwPhAYXOdTzb83vyEn|Kv5RI9} zeekU^Rd+;vMslV79+Hb7tiCr$bSzv}{@QV{4y*J+mEWD$mLcbetsUe{+f>x zsqi5oAqfblBqJf2eNSa;;hGGpN;F`L3@a!_01r$s@URTpd5M(vR$e{hr@+-e#u*rB z*@>VHqg^r&qdIJFo?C)J(V2;~cYGNOW=U;9^ z@n`UTxT(!fAH{2gp}M;2%7tooysZtdrS@+i0}Yxho10)16_+4_Zrp*<&O)dgA?r5SDb8R^#boGm4Gw39Ic<9 z%R%C6=zTOCZ3adGX%5H>p-~`EQ`}iW>bn8Q!ejCSQ}4~MJ8lgojI(y4J zF7s+#UkF2prESA4x0Y&UWox&^oNK)auSoM~!?0}p6Jtr4`ljn>W z8aA1UxL1dxj<>y#LdOc@?|h{5)PwN025~KGBGAa09(N7YN;zmQ*<&Q2X1M~3i4<1ZLfaz=LjmcVlZpTX z(|CA=3~F8!?GIA&v?$uUA&oBiSie}r!)zEsF_V1u=_I^_tS@SBt}h%w-Bw*^3(8ZQ ziMJP%hTiw0t*x zG^K4a{6{Wx94*sDwux!_kdbbjd`B9#s7w609G2_HiP9TQ3~F2MxA(qvs@$9K*ym*bgBFuMD>;u?LKbg}>sV&v_E1Bfxq4c$As`}D zJb*M`}w#-`s`}2^|!a% ze!l*gTM2p=hEtFMiG58iA%Z5iRr!Wf1`Vag%#F+3kQZ7bbaH01?8+WJqw7kTGS>%# z?E^A@xbD%{r6Vpi!5Y=U)s|8@g8ESG9QpU)-1T!MF0HL+E7-%}idEQ4=S`TGOyIgR z;5#%MNZc{|Q(s3k%UMQdFBoq0A=yRNkk8$;{&>f*+_r!v8I0(HoHwzrj;Eiz-Df8aYvpJ)Ctr!T$}Vu9wFRn2DVzbF$g}Zq>D-2@>em9 zCLQ)^vmr!p*kPGKPu-CN558zww2CZx4wn_<<+4i6kJTMUWL z1<>K3Y%k=cDYv}5Y()h;PmO`PdUvuQ!T9*Nf`URbU@J=iR)WX0O15B2q@ z6Q3?*({LLq#_s-PiZTK+e86AG0DS`TOamQKftySk`!-uqK9@{r50P42>4~hnhSF|h5L#PApQX(EYK^uQy+b-_4@>1LN%LZT>!w@ zE%v#>0p)%N;84QB8XBb|*(w}zE+j}_V%9}wYG!6URpZdIVkMuvlI}xm*LcSAkwe>0 z-1B%AsVxA)iC_TJa3VDowt$}lWDU?7#JY^8KedfxRp|imZYkjFk)i=m_jH2OzE=%9 zXVL8pG^|)p*OEp_UJF&(PKN@xj~X!6od6)D`@;>EXANAr8E`eeo12>g8<}?vtz^Fh zzX2MBJaG3omZB>ujzhwZ%N8W6qu&Y&)KGF?j}`&JfcnPzx|)AW#@oxi&K3y(J>{{5 zuK$i_uf#4Nq{a{OI39nM4>Ga!)q$*G3_7o8fWGfKiIJyO1xdv|{wRBBrn#BfHvmZM zmGmsV`6iI8ZGWUh-G9UVcwLqlqi6yRx?6|sLw z0__SwC?nS|b5znJ0f0K6mtTZ!8CB`kbiU4xR89&aym%ixc)(*l#&fyE?SoY$>2=Bj zpsq*z{E1H~#66tUmT@4^D<<4{b*#IIXrhBkUUuRa7&g%ovpj`vB@1JuJhi0~v<(1a z7+G?Cl1)c|RkfLy%X(k??jU#`-tx}hA3mVfP19Oek6W_=*3mM|B`?ne_;StZeAqy~CimEu z3$=(7Cb~b0NGcceDA4+V+(+K*I{oeW-74#GKY-3R+g7)29JOw_bec9|5YYbk^X182 zGb+Jsd7p$dSQ_*0Pbh%0nY5`!5`_>H)=m@)v?!ymkE=UPoC>+D z&=1o_B&`S;tq*+z5{73aaIOS);08#+GiW^o(dAbADK*YQoRrAt>})h3^ZF;+=ga}y zTOBXY88No-WAaS}gaB^y394zOPFt-VknRFra&cv)&4?$!8G&r_6IiCYnCE=8Of?NK zT%ZB-PhZ$u4JYxHkD_glQ;`U91q{d2`sv%mLYuEEb?UOA3N4Njox=NjT`ow)z`u28 zW49s)t22jh--TYke!Yj}67^6NV%pi+*@Q;|GLz&!P``ep?bEiTn`kv8<8vnjJO#=gxFDKqE2Py zW|n^_6TT71LCMNXd#dD8F;&Bhd_I9b&`g+tED+i=a3{#O-WPoKrU1)t^_`~b=iGbs zWj=Yi(WLM)qS}T`03TI+vP*kkbYhnU3(b6le|XdJBe^M zz6$|&%3mmw1Y#(mnfGi88frkj8D!J$eEKaLUow6qtEL01m`I6^-GgK5dudxG5MFXn zM~D!LsQS`F;DPOQ1&*j^!@dO%=-#;Wo?z#J9kjHR`Db6xS_96irkqhI*e~#aIU6V%jjhOmGQDr z8sA@!F#@7;wpQ!ih>FS+$8UL!u)ziO*_ilQHSDKmaNFXh=}EDjiKB1zb2E#9d=IMCDVP0ugY~Q@*+|h@u=b_pStLz#_nUH>0!mU~k z?4GU6V3&!c>b;&UrR2sXffn}wYwpm(lMu3tLmO0|7*6Pxtdwu@Pck&a0nTQ@c(dC; zxX~Uw*9NjzhSO@CaRW^2$$EWzNf_j#D>eJ7a!JLyi_Wm6>1%_JmC6t|4|m0wr=zat zh2^Bmu}7)PmQFaWxX9wI&;90;3!Rjl%*6rx`J+bNWA}MhU#>)3$X9faT18$J7n6bI zI|d2}z(k4wDdN!f`PO9h%hTPtIXCuD=_WOi-J22exf_=cEpxWC`alTIlj$mm+oROt zE^b2+9UtCp>ZnF763>jqu2Ik&fc4Uk?qgowqgZvHQVJb0kNU@9(ix2d!e5r^Z%RHB zy~!P_R$+K%k)b{?$1M{u0$0rFkt`m?YRoKDH~wnJ&mFo&;(TpWZ%{0W$bY$h`8iS{ z7VRuJG{3heILr&hu-B8wxBl=)%}?!E=Iq3GQ?_KwPgL)6z-N)_O6QFce4J+D2z;W- z6(e<21A|I}n+a_~YUc5CgMVuQZf}fpq6ns>N3i$(YVJ?F+rMG5a;*gT!d!AAAT)ol z2lGaDAR3>2NCau%&jUSOpc|vpC^n#ptPZ8xc>ApbN7QMRe<;$}`%eY_O86Va2L@Ni z&~@4NE#`5}vn7J=A46T|v-9;8xfFAtPdwBVIF5V-rSsHLNJt3stg-)|oy}ad)9C$R z`>h>2gmUt>gfuWJYEUGFcUhs3n1Jg7tM0d#Yc!o`hUjv*Bspr?{E2}Q$dBi~{&M(= zB+LLuECgCJE8H$}O8 z5dqq~7AjAtT{Z(`dt&j;HSDnDjs*=FU|^okCoU6m+2iYROy1<9p7>Ot(#kfIzRH;^ zyvr10G-Ubrhq~t#-Bg>`LZ+$mMZ^s*=dS1mW{)%N%0j=y1(lwHJ6$&cH9_;|yvX8` zNSD5=*W962DXYf33u!11o_bs>fSlQxUrEBo{rSzekl`0BuJOYQR}u0M)Tc}tATy); z0q}O={n^l>EPak#pD+ zoc?58wd6uG7{+suS6+!91lXyf0B1CNz!BE$|7I8Uf-f#FKgz+m3AqM+ys|(A+ilK^ z2u*h_4TJLvL|A=elN^a*tGc-OI7QsaSj^1^zJ z;s&zkm#h7sTSlATq0a5Ol{jx`;NE_~oMJcJ@h=)l?0hwAtjdN;E`l;}Z=o}*rlw~4 z8e|VY3ae*A@4ono)M_9T1>5gSWI*abpijB-%WZ2Cm7z;Ca>SBEarD$g_wLAMzMlcf zZVtQfIp9K_z6KuM+Rc;=o3Ke2w4Xf4k#LZ0K}h zwY;BITy=pBY{7irZDEXEppEJTS#K~v@V-4c-uXw^39`_Dij|d>mu>IywrtBC7Ua5< z_}R0!*7J)yKyokYMTbQ5Cu#JmCcXReLA;11X_T+J8~W$#R#DTr919#1Q%{Do*;TeO zFYno0osL%EdOGZxcTkjW(ZLP*l$>fZ_it6*LY#5KWOqXhgajauNV$q(3CwLET<_oO z6nEV_AzwD>_*Cv^SUobR)#>$8w|)udhar%9*S0^VO?8mNZUzZytF?gZ_;r4MK10`o z2fVz}6TG~7kTRWpkPvF+CRQ}&InF`}R$bgP)%ePIyNNWl5l0tVz-y9sSuu{FFrA^plNtoL16Tp#1*JGTIHeQ}ACntYq?*ErDSojzF z)yl|xH%1EM9Ba@AH;ypz@MPb-c>vtwm5qwBatA0F4R&6Gk}(MAdXo>3sSZ1k1~rW@ zG$c;MMSF14MIqIs`>Km_{XNE@IS`cdQt1-j{l$io^#Hp=wlo640R+Xw#8@C28;(L} zS63~>4*R7+ND-z5vTZLAI8M(uih%+%&y*6%<2uY$1g*Z{I;Po4F#A8*iZyO~j32r5 zLxDKjX=jE89RJeKp521zSy?eCm7E!dn|yqbsy`rX?f{XX|GVQWB+Ut=0_ykR>`H~V zn@2lbG+B^3ljnDaNqiwBr44#!%V)erUAGGc1&mwKo_^x_oS0=*Kk=lw0p|Sy3;C-U z)Iwf|x#S)b@qp7JCdHH!+DJCb>Zof;wE%AhCp{g3?E)d0>`HIy9+*Cm+-dfHPW>IR zEsJb>A3`oG=&+D=a^e#J%Cy;8qsuu0pXR3PBW}Rt{dA`oetCuzbMz>Vz(A}V0Zp#> zpuxdmwizWLAixN8`CE(@(Ey;rACz#v-Gzqpyh;C=NzxW$v_XRhvRMJCngh!-hn z8A7g06t%G5aK7dO=&$!RC@!v6k&=R*KYzX`Rz{oYr-LUXBm~jDJw=joJjp!*7vSERPUh4UUu3~>t+$Gdn8A42 za{pLs8?dR2(T%x{jn|G`$;?3BLY2ErRPufW6&$BA-C$DW+y>!**?-yM2k*By{WPbm zUcNl|SEIz3_)F(Y{D%*-Kn!TIH!4%bn}dyxY_Q2=e*J}vlr#`%0T6HS*FMzzl@@~y zx-(l-BLuQWN&r!SvPv9icdd^*J3G6O+aiqmv$GXxB2!>gKszWQR~R@eWW{Y(7HgTC zB%A)86!{B|egTW&k&vJTKtwxeYFMNmSsN;d|NeK7H*rVQQkt5YxD-56y$q?bXk34F zZU-@yPgJ>53`@5jo1++~xN`c~aT@S6ya*#!sAV;Sj z6KTCkaRu;Up&0XUY;Pw5h2vRWcG7X|BYrxj}E(AWL zkZPKWQV-mX46NRV4}hj3X|@)a1i$X#1hFKRV&#B^R8J!>ZRF-AR904Y>wgvYCE!@D zYunFj4uuqj2BN5F5Ft}CCZd!=DO#q?Gnonz$rKGpNJ*hG7NIC4N$wSGu80O~Cw*H7Fd zmwsI`AW;qK7oo>Ba`YtSL{&p$owPI$0&w6@$Zhq9)^uSndM#P|-|rl|UWbm7AA2p? zEUgve$)&ljsbn#GG6Pvs&arNbWMFBjuY##MD>pNAnEMB>tAx5~>hmh2DOU(~j$uN>ivOU&~X{)HHW_>T;Cm;jZ8l+FT1gwsm=p)z6 zPidGu^h`Z>vY{}sX9eMfsK9QYetgJDjj^jh=wquqG z8@zF5$-{>aomYQ-f)(_@d)x---{|>Sq7=n-nVOmTi2HTq!3o-u)$*a>_=ZYvmy`(f z_xCs3)qWg?`t+iDn*1V4nzy!EHd`V0Q;kp4h3U-XT=*VVB^Zrbv1)}5B-_h5_E66& zDqx9gU@Ehyi4pNc2!_K4%lWz4&y9B?-DZ%sf?BkdiDUIeqREd4+XlReECz@NfdQ4O zzsQ5P%G1+x$5+ptkACc2lzihY9o6;4P^`TO_l1GLp|38B!DALwSXlV3S2R_PwVc>* zR?B~oGjHbPl`ts}X5+R0a0g4%(Zz*c@6hkXtK^p9V0r;)k&3wO#4E!l*z@&k7*Ng+ z-n$aoz9!Jv+1V@cw@&%e+r6r;DA5U_Q5rlPSuRRyQrr0=;EW@FxobJB+f2t@3KFm7 zm~VnIEjc;)AaB4U37SLalO_vema{l2g@uJr0K$sktA$11&(Cl1*8~*UlszHjq`-lH z+Vv+hiOM>UJ6r5NoZVj4)U-T1JKL?zO)lwv87E&vLF>x`kJpBsS95;J!WY=G?XF{&Wvz~=x#!NIR%$lShwFy-IF)Y!44QKR{Kqz z^g)c4XU|#YDB#=sm1dW%)3_9roV?}|&JJEvA1*+l_O2;y0-lRlP%NZ29A#6^ZQVTR zxOlY5(6qPm0=JA)AA_9h=M%Ya9zC(!!RG{A9XEiYup&#R2lz|ib}Mr3XQiX3-)8e( zv;-5*Tbq2hOAUQTNR82##OF46jD%U5$=DnVS?J&lFn|6cxoum1BrWX|mzs<7<1r zM|N?uKUT&2MEro;w{9INyA&B2a^(uI;_s0?c{WX~%1w1C1cn6yDmAXB`>|KTj-rM; zj@xq6$Ic>seSP;|tf9!?z+UmrJ;r!n-L9lFs?<@`?96rhu4|}T8PPat z!o$KG(E-Q}xx*GP;(DDsb(@sX`NibaOfdiL(! zJMvC@%Spt!H8YDB7Zt7DxRKT2={S$Pfwa5{Mzey!7j!t*oS}^Qk&#F0%f(TDL45 zz+AHb$|%(RV`Ytw{gYAn>C_RbEv2$jm4TVLqONXnN=nKU1mbZ^w0NAHoQlx*_V)J& zqwhO`W&ri|s!sCgs560vu@Oi9{=1UIT@Acm87vfUXksFO{I`AkF6QglO%L?<3(Ct2 zl$Mr`jEpElV;L16Z_&9Ws2p?)CnqQ6;o*UyngQGP@YcTDAT}xqG4tm%`FLs9_i|v} zC#4gzd9RqEOGXNKhq!on&Lfb|Xr{8V@&w*WbMIai^aeKO;FRw-52gLp=-rjPgm;YE5Y5w}^HtE^-F%CM! zZHw|9ighYCBOqp)sTOt23w5p%9ja~H6W1?718LRbg?O9{mfd zDAfZ8V)FMNKYrt_)eZt)?G0`{1^Z(k++|B^YHG}o9U&wqXT*|H>H{7621u_xJ7+C& zkK((A|5Y1*v>p2Cpl2sIu_ume2Z@C6UIfeLNBv!6}y{k0$P7pvm)yufLps;3u4 zgg03;0Zkb7BvisTS1wjBr~D-zeMB0F*FDAG;x_&)fMpP|~)DDXL|STY!97AYsm8t)J;#8)XlvGpdr0nLg;Q_jv5STV?9 zFuOQbxJIrvtH7tuLJ}2`lb=7_9;ah#PJvI-Vu!&_hJO|zn^8~V!o0SRc(n8k3{KhY zT)_^1dakvLs|pL*xa3F6xqk~yO%;MRb1Cv)jIx^78=9J$qC=56HAhCQi67mONxM8! zGcs7=yDSAPuz*J zE=*_7p542kHz-^S``9WuS3Nm)HBo8$BSuDHpxN^5JNb?kyXUtW!sJW3&CrV%4Md-u z|2aBJr#H?tIx!LNW}DU!O3cV7Po4yI_UMvbL!td35MPfXayFEplIU0rSnDp+Rn%-{c2$envU z3T^yvUv%>`MGnoYunOu~>`2Ra9on~j9jo>xeG>~+{nq?9>2acx*KbA(TS*0|uiL#z z>#dFO=RCe5E0NDT4kaJUH zrR~k)w>DBOetrS!F+Hhq*|WAHMOK+*%_i*yr3EibGo|1272Ehf9lmaqQ!IU{-{X_| zk3oJesje-l>Isiuo~hWJsg%G->CcvOKj<_a%gtzdBWGXdesboxl<64w>yJnkO)T54&}aCYF81hx_rw-I-bvsa9p3W{}&rA|BANxu=! z46EK78_;k{J$<^(GFCagl^qKpVR6jO=o3i_nZE+uCaSityA_>TAhmRDiVgpPCfn=6 zG?lB-9s}%hOiagTy8k*I{nhGzxaD2d_IBgkA9bZ`RH(RkF)>Z$tofomhKQiA zlQ)EqcKbKm)r`*Fw`blwbJEw8KErQI+Apd2hgrS=hlTYFjszW6WU|`9m+(;Jy@ExZ zQ)X56+^Pq|=CXd{KlJM!O7XSJ=eSu%-F|)k>T8QcMK{*nNpib4jcJXmuoNfUwXXLW zj*gk0VE_BE*9My%7+Nrr7ZrV2{ma3BhJOd&VlojSFKZK5e5d3!#?tA2dFn)e?9;bH zZCliwu5mpsyVB=utrn4PvM5`^$g{Y(yoX%rB{#gYI%m1^xAH}NC=h2}r{R9^#k9!I zgKXQ(2?&O{jl{<|`uk?w(h#Eh3G_9vF&$ugh zY37xY(>%wd)t23oV~kyz=~vpm)%jE4lG!o4iD6p23LDha^xo8Jg?OW$)^1dz7@aW*siJ(3xCav>f%Pl zbTq~9zpDa6tCxswcTlkJkRk5cE?=NySE0TSPb&JRxn$t5g6YFEXXx|zW)f>iyzva) zvrX~BB)7ST6=@oh= zeqg-TmRITYYNETSj+RxWRrmL7oDTkrqWlAkpOdKD=yfikbWxc{EUCqb3sy7ZD!RA3 zuh!8GX4g>#W4#NIMyDK4z>>bn7}ga!bTJHhKb;TB36S?Yu|%J08>$O8e%HTr9aY}0 z!<@t|?-7GHyB@j6U}*^pgXrcg@7D>D%nqr2I*KMJ>+aszY*OH^7BXQE2caXI<`i9HOvbZKuN*hoN z`q`R24I(}05ZZ0o1fvi~4a?~Xh-O&T(&e9OA3Ap2I@`YZz~Mub_hUI!LwxyDRm-y0 zqgQ|gA#Jy&CJOdA|8>w>bAq!Ne;s`L-~i)Zq%4eii!PMGq(@u&{nKj6NwxPc^Ec}0Jsp<2m=$7 z88oylz7fJ&Ba@Sb(+`;cynf);XV-Tadbgdbj#?jiP+$Knj{DciO5L{=ke>ryvGn^8 z>Cu56qZ=Wq9XU@Y_>gGk+c^hR27OMUJ@4}6v<&Z{qy{TnGoGfr47ur?cNgV8ew9*b zHg9Fq*0p(^rHCOdQQWkA+S#J?l8(67j$q-S49gpL|H3s%0Vr}+(O2$<-!E%?&aQVd z1Up9y`V-#In@BKdo`9%^8}P8;rB%BQ4@zOEcmd%0ZJGwhvgONr;Z}bJ9MW;5XLkog zc;l-r{{{FA<>f%FgntT`o$>V(zZ~VL8eZ_7ZoaWL=(9qT+pkxpagO?RCE|bxYB!0A zJtL7m$Xju6a7eGv4@zb1!6hXZ(D1k|s5F{0HYrX}mk{L?D>|T(>NAa+o1?k5L<+Fmya|JB|1tW|x82 zyDco%6Zs!8(INzZq$h9zXM|+4%T-{3EHWaE_3fvyMM5}er?(lD60#+ zIWTnfebkX%dRaJzr_bR zsIr`ettszx%lCMfC~e=!bELe+g!eJtY_O^%^fTraAyHA5UGCqMRaEF;a*M=xKvpsQ zyE|7|f^3=^RGPm4@}mzLwP$QwN&*rS1u&V>Q=BVTUO<@Ckr^V*!L4G}y&-=A@20Az zCMYS{*k-EbJv^R6&~zc2jcQj2Qxmb6Uz#F_;X|_*tl*hCpL91ia>Hc4=Z%#1R)8j`M34upe4M%mt zC-Dpg`iy8wGJH4rnisIN@cjt-DgU#QyXEQUb(ogK#KgwG-?IbrK{BnL&bWW?u+9a_ z=I{|vzr8_;_=^M7^&kd8hUZUyK{M_$_3`G3;C1A>N$KTLzhTm~Z>xIof)SLF{aLGT zA-cv22aldy%9(L}Zs^nCT?0~CZV81c8E!_Fh0^a4dgS+?kZwOdz7;-ol)m`W5&W}< z46bL@mhs*Fp4N+_Ba~0OfzGk>i5p4n0odl_>nqqK>L{$`+(xJ8AW3g^zW;Cp-vag} zOs~dPPB<5E>40y~)-m$c>!wBbq(!fof}{Hn==^2b|DOdqk&Sb+S-0~?mz$OQQtb5 zZOq7VYSgW&bN>vpj5{m%Vi1**|SVjYb3AR)9-5Y*4^dPz1a#88061WIEry znk>n{RK^n+tq&YL*pO?vU!>xJw!K7?WI+4{eV%H36k%qyH?(i>(%F#X6vzI|{_z*_ zLF&5aIuZ&W6NkSGr8UV=!Hn1oS%c`tjgO`sE${=H2GvFdlo#Hi@Bc#N;9^+HGC#>A&ZSFJPpxpTsrx0& z*~LQmoKNYW|HJ2yYl)-(q2-Qig8%xI(W#OF2y{{hCu?SI4#OLo$Y|#39>%Oy@Qf-@9M7XFFRT+ zD4lZ)ELik?EWW^V=Pt{a9LtrUCA@Ba9yz{-v?;qA=tdyke$qP!LW(D>a?W52jqP+o zx+t>Bg=|={fk2NZ*kO)_Ug7gNp&w*CXr9ACWqV_l`}0F+#iqqO7ao^#P*g76^~*bv zgh-^V^`OQPpF0wgZ=SLWYkZ6!dxh_w#CfNd+=VAJ+|DhQdQtrS2^$L9J;`04ZC&wc zwIkMF%@(IOwqHWl+WTehh7=t#$X_7ZD{jdieTf#Nfu{xcR&y*tv>T@8v%1I>l1eaStRL(h%P`AZ3b0;1m8|j#gN~4 zLXo}@fYOwChy~oxb*a-|hs)5;v9D1SfT>;iio~%8#M+9!YQ^tE|e4W6z`+2kidhNPeWqvZt&?XhjC!Bx`_uwryi$Wd&N_ z(c>gxQbd6t!P(fBR|rNB@`!trQuzI}fj@;-QNzpYvCePhCdrEt>gItT?O4(pSo}G9 z8moQ;>fVX<^*Li+vwzsj=%3OZ>HJR(%dk#xGb#`QLHq*pQ$2xH0B}Pgu(QBp9sc&r z{}H<(sHpep7+<@Rgv1iSP&P>uh>$CUp&y1nCtg9P1C>7e2|{|Kop|@1! zFzjiVn3yEZfk{?za@vNAXJN;Wh34bqgPn7pX;q`G^hey4k@=jtq)Shj{xX@vq5H1JbHN&Esrn`ND^l=-0{@_7BEL!ZK+(_dz(F-V%J3=ja7U zS|8-XMj)y+j;hsHt?s|y<3 zq0T~VemOgs4j`oEzAn3wRHK>HV~>ywk{)>Tmvz1o*+~)-nVF3_;s5=4V%Ft`|FIZl z^vevUZ$T+h{SP7Z-&77LxCN%iU3A+vu4m7lfvnwwW|hQDrSFMR14Hv2goLM;SBg%8 zG|5uK=C^3P15z5N$$2afP+%l`3@EC4N@)LbUS4Lc7*1|(bGw7arEm+eaBzg=_I!kqYO*&1l91VR3)>=Adbh3VmuAIn+qQiu@sf;*iHSm#9*(3FAl^|^S=GB- ziE)SIP7hw#Y4d6l6xF}N7)yVTY759ZGvL)hk&%)4Z^D*u;>6$@6vRNxCfH{yU;>4? zY5B$9&Elq|0w6j_R_h2zFOt?m_9y9}7p@IH1zZyw@W)>}yQ4ZtL?s%2(j^kr4#p!~ z8KaHC>W}qH(S5=iRt2$G)QuaLa8G+734}xKqK;DjC*wvu>4*g9;d0%qSJZfQ#fIyY z;cCww+BO6XB@{>;dlCxU*QRCqV`8GBoKz)ta1f`8NvY3KbQ4(8r-oy%T-ksj?n9|> z@qv@lN1dD=77b+=t2#SBBI2jeOP6?5GPZOhkL&`tjpH6=t+u455T9;y!J|jp@vy2& zl%tlVg0Jjx6!cxQyz$VQAMGL55wA+dCQHf;VqH?7NYLibwnWu6ROBNZ8xCH7$@AU@md5_Mt62HHRb$fdZh)k?Bd& z7cmXd=~>qEEUvM`R{=RG9r?ir012*!fTI7+uMSs*wVIFG=l7qMPQZRW`{Bb8SI8LZ z{qp;VY&~~5>~ijX&Io)0GL+`qPch@lczjP((U;;7WFS=!S2`6%h$3yo?wppiL-!6# z`>v9mhvxj&ojc~JMs5>##k=82BOnRMhMB|jl9&NORA5^Zkw$g3=4svWr)B$-6|+>U zb)@k`25?@fU?`z9z)JVT<1)5_)S>kLBHv=TE|NVltm%Gq7|P7LkPN(8-s|2|>D?fq|%mo-GVRtt$Jg4%hOwP|5o9LALr9RaY?ZrTd>Ub>1X)3M@@uiVp>}C~ zsCKz~CFCSVSq1g;i5MQg{@&6aT?cxMFnW9UvJ!=c-Q?t?hMF29Hp;2SZvCFw(S>&{C=UL^euN8Z~4JL5zB?b*k6xem8A-5$Pi=KI6r<)421;Gief$?+eGdOSt5ICj)X<}%}rY(49!Rh&%_IazRRfW z@WE1gCiV;$<7BiZ>i}U;oB{&u{{H?6KIpfIn>6G#Z^o1D25ApxB{Q3BvI@`Yo0Bz@ zWm@J3Jy9hZg!{g*C~9DV$(@>u@B4umqZjyhG5E%WS({fog@ovoX8(?@>(0ShP>JgV z?L759F6ZEZ&wboaE@4%JU#^^=`!OE|rA_G7t1EiHd=Ud_m=0!s0uf1z0-vn~ydVY_ zVb&TH#AZc2T8-fq8ljLH=6o}Ve3=LVn6 z3y~Dr^?eXU7PdM_C%k~-O$bX7sM$U8T#8DVRqyNN=>WzMPEAWw!>tKUNJt=uc_px1 zJ61Z4dRY;X^seq!Y(gWJh6f!I$4f+^f7@76QW69mEJB7ei(J3N(6x4SM2yze*Oz|p zegHk@5IMFL$Cn3Oy1b<|CWtdt#DWhkCwk72g$Y||L&bt}y1E7t_BijHw=bwXLlfB- zBFp}te|#Vq)U`^CFb=ZEFCxXYmI`Z~i;UbK_{-P~o&?Cc>;^uEhJH1}LpqmO!m|uy z`l0nucbO6iZ`rzH*#&FV7a3$c2L3WK^F{n=0@}3HUk~v?4k6YEh;xXrR+vC{RTVQ1 z2x~o4?fd9(>I9Z^>CYnLG>d8fK*e2z)%L(j?E_mbxujyJmrxZXg z$?PSXXKX#rBsn(~bT3<>)I{YUnu1Ybs@8Pw9QxP_fOkY`2V9$f)gaCol2wit4nlr@ z%ytOJ3^3_t5=vd~q>smvroQwXO!6S-5mA`q<}y+pelx=|ZeI;1a?IigZErTgc3RNzB^G{&OomI^7HdKPDnT znmpbPMpfl|O(Z@LR_FL1G%o#vA-G(Ob}NpKHBIRFtA{GVWnH3oT^3 zMIr=DQ@?&mfBk?1luSF}P`#{(lpke**uaXLjVn5a+(nzFTiGdSRdF;D zIS8VwzZm9P*@luZd59*b5V#f&Vb0Q=l2KOlj9cwHij1p+LN$+L!B+QTe~ zeKW^Of>xpOwoXD6Qu$|RCe6_xV;V6ItP;Z`1Bf&OOP_Q~Q@tT;h?s~($UUmmf{K6P z`J3!PWT6?ZmY%?S6O@^V7oqkh`39t51D=-lWY0Prj_f(1?c0~aeY^99 z&!`r0TjSi$v~|K&2l2tVmwC79r)oSLWuPvBfA&ZrR2sd&k3T&6OIuP+UDZIT9=gLC zl75S6Yfs=WKWMOtIAsL&R@%itRdxI$$UuGWBpD|<<)(KIj*cTbGgso{NlLMDQ`3u` z#mR!uq%WigW4QVM%Gv%s11*e5|EJn*ZcQN93PZ21l;?OBF{P!ZtD3EH;@p1$By!_i diff --git a/PathTracking/cgmres_nmpc/Figure_3.png b/PathTracking/cgmres_nmpc/Figure_3.png deleted file mode 100644 index 4c7d020734635c7f9204e1cbe7c5a65cd5b5b312..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 25270 zcmeFZWmuJ6w>Eq&N~94Gq(e{vDd`SH5m8V=K|)ZZTe@2jPz+F7M35BeE@_dFl$P$0 z&UajRKYKs>-Fv^kzaQUy9~{V9*SccPF~>N^d7g7URlRwYn1Gf5K@ei4YnN{$2$na3 zU`Fxr;1!{c!3p?DOHq#URre;C9_h`2rc8$%RtzY6V ztjt^H>1-a9sLgZz6(nFOV|wovr_qHuEn@6df8$bBSy@SDzXZPTgKbQrY-|bV&F`jc z&6gDU=ASl~W)fSUs^~3=l*4C{y$t`AjIlXk(0_E5&>&BPgM%FcF)!fPwa5SepZ^~k zjrvyT7nwsieXXq0iF5OT=gXko{5iei9w2PF3 zNfk*FK#=ix(XwI)DBoXJR5v>Nr1J{3iIojBc-6 zx_sliXLqY{E{lLb=fRP!lp$h)>CLmYvH7BfWnf^y?Ca+zv|8&ZwV*Z7m%TZg`FJy( z*tNo4Ii6yKQ%mDch}WWYShoGmnpsM_NCmhB&RTNWH{|jLzaIDZZT>Mus^Ug|ux^Zb z3TRz{cgZrqVsmVUQzp6A?+7uM)`U;(ELo z)eZPqYdw<6dNZY}Cn*{6UOkX_@T+maKzL`&L=uz` zU*9+67;7X`F49eW={n<`gQbr9|TN_ zI()tVV+}ou9gdoSlOxQZ?1SBOOmrxI?_EX^>9+5Y$vo(_sE@C;j*C=fK9FM^ICqrD zg^bR}u-^YFpI*?If(?5Y!G?-l{#Hcd4b$d&8jPiSDri{3RhA0$EdQKnZ=$z zUy6?uZM-dD+;ev)q8S;%Lbi>)Y}0!c;mPM}kknJ`laZq~1X26$WX8fmeKKQq$e`T> zC69VH z#G$fU)r+<$wR;X8gLUHpqW<*GWaL#O8s8hS@fx{_crzS{)tVZ>n`Wo56RyXkiQo>t z9tkMCQW)lw`uU0BUe3=<4O((?^3O!@cF`wqx>C%yIs?8U>VTNvcS*oaw^cOtt?! zH2`#;WJwPaHg z`NY&K_JRRIV`qLfPiQAG?*r`~VVhg2BszU(VESxSj%bOz#YT5A?Gw`>rLKV(M3`yn zjvU-#BL#K>!E61DQfyJtDt!I;z;GY)?{7>;PvKV|-$98lMiqBZ#9Pp4xA)P+vXxI| zHmRq?ou~S@^j9=Z(HW74F&HhuoGm)@vyx{DVGA7UAxBcs;W<8ckriTUzE+ypW-mo` zHue@SI!UfDELBv9pA{c6JitYdhyA7U3w_-rb@|^BA%j~|hi9JhrX%z&j8X|+{KbeE zv`z~0!CZ91Jo*rJlOVD$nzjOEw!$M*d_?SNqu^P1jNq;2=olV=&}`X5@| z*R-k8DMX+1ev!it2iXxFska(~U;CvRqM$pYK}pHCBhm2V{D!1rQJe9csG=*wYiE!9 zSp_eulfuXH9um+XzukIOupiS)goX%_G#y9OlTLMnn~SSf=4j_uam$MsH-c>rYy&1` zKJh|xKV`>rj{A1n&7Ei%1PD?gfByVg?YeWTNjGr9%8|u{+OK-F;>_9DmTEF`^4Z~5 zc7k_(76s-@*{P`}$=9{D9;vi^^7bj2G?3njAKyM~ywD{cv+}1~ee)cQA6-Hk(wC(x zK|>VCu|>#|Rji-M$(xPsoXh5okWqItGWhP>W_`tb*UN<9PbeRkNrxL67@N^5 zAH@45+g0I`O5IXNGWk4XB|WV>^Or+wPa=HL&o7GiZXcfBmq;fYp+8>}->~7^v^<5) zjt+Zd8V^pipy??rEUfo~OyuM~TKXROR9tJ)y&GP#Es6-npwBWf7@wqShf~5+wB|}8 z#LfD34a`dMbX@KCcbB3EnHU+f$`R+CU71($w?eE3S2p-Zt1+<{MBkXYphy^v@pBru zRdn5j*7}r`l#RNIAw_S!`9~)1$YyO`v(QBbAvebqt6pppgL7Zg6=XodnPf;xhlVE( zySmf|Z5tT)qFeC^32XgGrGw+W4vVR{$|~MU<4%|r2E6N#`O07xi={tJsbqH(y%x2~ ziK_Xg#>T4k*`GO&+ZgX=YIgPXuu4lazIpS;E^? zTy=ceB}8BdFT`hIk9Ie=v|tbhaR(CzuP0B0($cfMNr z#G-LQj2$m&BnrYGPBSgq{B9`}u*vESOJH;wT^bo-?Ju?tOdsh;x>{>u(eK-9R^^$m zVts(MJOAz=E!rIKR-5`6Bt0$dz0mIhyUFYRK|%UkMb!H4C=p3p3GH*ST5qCsvDSO$D_27m zHW(^-vON~WM8?3dm>FUHevilCq&1f9&d*69OyR`a-|iZr6VtG|Ss&eggnWkp^FK-P zA~rVkDw7B0;y_`;Xtm$VhzQ?MIuYSL$)72=8dBmtpLM5e)mjKAef)^S&dy%sy!wGU zy^=rc36fk!*q0p6jw8kPJ=IopwbjS4sqGeIf##3Ri0H#cvX37>8vOjEavstbIuf~$ zZR_Ec7rPLlF&x3=#hpZZgoJK;`k`%|@Xz9s~RCrACv~Z;j z_9DBkllzI5Dn*4_qQVS3)zof;t4HC>i*I_Np0G};PEy)jzKp|jzsP%k-+f|wI_b+7 zGHRatFG{(yi%hZ!y)B;)x6FkPsfiGmdFr#6nI-F(qpiSer8gM9bLUQ^+>EW+-}$4a zqZ5KlczX1$j#YJnoZpLx2v#STh>{5c@5A9U7#wd2w?W?(1B&Lfg+9B9*S&f{=qcph zV8~K+2#jm|Pe#djN$a^xQb}(188!a+QLkfN&hBIyQ6hjfQ;y6`&yQD}nIIe{l8374 zl1Ah`-<#c#aWA*M(#y*~AYd$jT2J=TBlcmBEnRw18`-6`vrlH%QVydU5B z5^T@!5<$GV1pMPmjCvkYFklhkoY)4Yrk@Ad^PXv|QDb42!x5}1BionT{LAze+n>pP zDh}Z>G5PiCzk)~9j^|AAo-cJ?Wwj8FZiv>ruZO`y$l3`oHWni{`J(qc2 z^s>RZT~Y-QO-)V1`sZgLsVWQ*J+Hu{@hCq^HXC0KkIv-;@)Zwxv@^3IJ(bg4m+S;^?E)(S2J39})1(R?8i9dQSGVF{U@3HxA za8jwB3eg$gm5FR5@hPf|$3?!F?PX_fmcR{kxk9>ViBMN=-3!Hmb@|RC#C`5_$``LA zPo%2M<tTJ-$i_JAWVa-Fn{Q5yyKAVVS4u-|a0#EoN`OTZ zNK9ul;<1H6mP+P%=%rjKp^S-r&CTUE@8N#O^*W5c7b$r@L;g%J)>lnqyeh@*X5Q{R z1v&Z4tyCU_HdK*b+yNi2_RW=Nkj0(_F?rG)>}^Hn2+VdjIuJ7>G(>ne819J>Y;Wl{ z*fuQ{{df$^{-rj26ie37kX8C{+o-r@MZ6U9yX;U+d+b1d^*chLyOAEZ-_oM+$2HBJ z^1g}+vGnc?8$!btWr6O1q&gB%p_lk0|OhNnVnq&Gv{6A$8gheCl+$ zCNew-0_wID1cpKo$%A7M0u{++Azel&!%^##_at3vtn<~ghr0*7jnIFXTb*1AnLVp> z5e+9|_*AA&VY9A$`j?hGq8lD^95QD~p4Pa@?4MY+KA`eiph*1u0w(X{)wD7^Ro;m* z!lH^Jp**@@G#<7q55+u1wK>hvGj-V!c@s=k;Hd_dde6`I_4t2FR71QU>3I5($@jRz z^QAtbL8xvl!Ml6ePA-Xjd$FH7lRUd=FgvbcAeDfv`I2xeTx8|g+E#!9^5oSe|) z8QAgQ3`KorvkqWCi=1oI|JM9`WP%4xDOS*p_!ci=y)|d3O3z>2sw>MWM-VQ7L%&zk zyv_Gv-pPlE;LP?zI3N5k7)070h>wwWFxWILeT$|GZ`LJ255R!~a=9!BXi{}d_PSTg zAMha~3%v5i!(zqCaBCmv0PY%GFFEV`TCMaGt0FC~6V4dYVRjOO2XMfKXa1hw`7Gj-x2|}B(1XqLN^GR8coqM;W#q#w zc!=QlAsE#}GlrXe0sC!O6>q<>sLc$B;S?z6M;&#uNVE7uU_kFlmG*V2S-xcokvYR< z`aV9J^sQtksiHo1MsdnY+t9fQ9>8qD?|tA@oIKrF2-b6HzFp3(magjh4y^xWgm}?DDEe(0@8cuwo^r6q?2K!&u`%;T!(=q!o$AJv=k!Yzv`UKF8Tad!bzSGxPvVR2BbGjH{|2Tv)|)onD#aoYlF$z_>8~P zK&@@jj;wWgL|opN>L{SuX_rOje5;L5y;uC@ew`=xpiLj!#3?`t^PNwS`y~z+;#{WA zNbW7<&UB|!zrCmv*w}b2<8F?8Pl?4w+(&-q+e1)I34NG2>K{xE6=IOXih0rc%0db^ zPYJ@5SA>d?wDN^Fe()BkLPGia^()lq-#Jo%z9Dm&t=p%ir>p7eE*|z7=VA~5k_(Qr zj9!ivX-h(e3b7G!T2{Qn-3f@p)b-_ioTy^Z`bMFZU#e3{%(r^}2JoZllxl z*nZUr6SjfuP;4C@`pe6Mr!w4inU04k{q#*1o06^*`tdD+;c_Z(M(8)wJybR<+D(pb zrcfj&OZVCE&`C@GVp4vYJF>T@IC@w?9uap(`N+EbUJ0@H;~z0TwPUi*&P5HID=Rjy zU%wXI75n`8^W8iXHNVB#*;#xdqSqM(9y`*AJJ}2&WXq->>6E!{SR+$=%=6DNLL{RT zJIaw;G^%$^U*#9{Ok%%|Ek1nkzS=YYmbFywNYAK_8j*reUM^s7jfl8gp$>G2Zr0(v zI)2B5e#W1vRs}n|uX{$(t?0OaYiM8-6}|iQ{f7`Pz7JoBQoN-6kI}T?bw{gYXCm3m z+NXD@xLYtL^`d+;Y7(Up=#$&?A;CF>`77bG`ZQ;gXrMeBSyxHm&Y#+4|eGwfU zGFePggriZ>w56!*|nFwB|?c9B`=&cv~eS2x0 zrKv6RtRh?c#VUWR!Y<;5$Rk$1PuW*;4|*OK4y+FK*V0Iwe|BK@Vt5yqXUlzwub!mm zYTJ{8DZ_6$DuGE8?;Zd&$ChqTxW4%1vO7+6eAOY?0t{#mEb`ESgjRo0O; zVZN?83ybcFs;3m^elPUrIxpt;s@}is~orA|@|^^K30HlFLxF38be{HfEn5ZU!y#0LsL`7BY2 zH=33IcRHQw{KbpJ9UUE@GRRt3a62yau{bG3TvJi0V{jV8}xXF6Ug z>~mIDeF$$waC^Hd4leEkz|rTqxnF-aG)?~Wsm6eh`ND;!auxG~I7ydNx1@K@iaRa@ zS5?UldhRVYHaFWXQ_CBS)dax9oBaGltQblgP#Z+ra@V#6y7J#`UWb=HBqeoxQlWEL z9%jfc-=vMXnX*SCv{mM@=lGmShVgU=E}kDo-(%xV!{O9A;MPEYe;j{*f9A7iaZa8* zDGGFnc|nIo?_94{q0!P{@ytLWudlDKLC)P5QBlDkKCp({nKISx{`G4xH>u3twRiyZ3_>E|^3SVr~F@v-eXWsk6<9h_V@)w8M+uZsU^ln>AP>ygE!xy^*eB4cKxQU=~0o`FFTHtjq+ zF)@Mmi+y>f6n1uYFJ8Q8*SDepe;W9ObIf8vDpFC$deJLkNy|(?L#Gj-!6vRonJ$wC{@*U?|TxaKPjO@dQ z5Aj+2Va&_;XhRKQ0G5ny#z|gqcX$8xNhNxMGq;YDlk;*oqm+NQ85P_)Wv+4SDS4CZ zkz)JlXJfTNBE=)K4zPOhSEr(_OA0|9P=cupCY9b!5W4<)@L+3%H_mg{G~AL@X8()x zTGP1zvR`v&yzf?emhX*Et-pp zL|OdXjVl8J0zTMJ|M(5*f|Zl=dfDDm>5_-pQl$SVeu8gTR~IuE7a`0iIAB2#*&q@I1Oejb%fKSzfe!cSZ{NP9mK@FgOc_7iTW%=d8lKP5H9xTG`+~8x zwRK+axJrKdbRY&BZ?u+F#$mawrA0wW>FL!E~` z;Q<;m^YVrA}-R%6@pnc1)L?R}5f0QY*X?mYkxh4Q#^g%ro^aB*wn9#)sj9Z_9H-@ByuG}hW$Vg=Kq@XxW-+ld*=1`40+%lF z+fUtyy1{XlgQLXFY+-Nj+fxd=*Mo*ImRDR{#9TKQPU`FHi_(*n9q!IM|9*N7k$rXi z7!eVtphXti9)!%H;ThiRG~3CJau}T-mGDVO@Dj>Bsd@E?WMpK%$B5;29B9vLS)-uI zfX~^T+u!7i%A)c2C?6o645oj?_DX4H9#B(K8uVn`yLRi=RasftT$x*$2ja0ep*0x` z6&XelA{ss~@FFu~BrnXk7+Zvb*wEqmZEO*_o8>ylsC&wV~cMsz(Jtnz*`}WHA zczBZaNCniiDyT;<-@hmLCr)6|#K4-Yo{p3D(9S;?SadulFea zpce-mI8<2)E5RpH&-EmbTG$Dho*N)k$n75-kkio-rgzWf44LH{&a@{AXs|P|;Gkpw zWWEQuFHczqhrEWvzP`IOp^D*$At52QGwm!In_g{FTcbd5!I;`s*45QLSes~C+RE=* z{_>!fmV4fQp^yLal`9woayb;Bu?}k(69EAM^?qJer^l(`;nUe_5I0)_eA)~B$ztWi zX9RF2Cnp=fe|KQ|1L@~OS=s$J2c`J^`AQ8T>)ErH zf$dVEq^2$%NlQx`Y`76Ct^tMjibem|D-Rz(4k=x(&{I@xWCSqCZg0vVruAxqngjXZ~*fz@i~k-w(=>Jgn!=HH^`n_biKyxU(4=8u~XqJOx>o5(?W|-?D=^pq2_w zXjRbHorYafM4eX>ZgdyKv>H>O2_F;)Dhvkm0jiqe;r1b z-uDjl=RU5RXnGaUZ*kf<_uh>-$$PKgylHB0-Ox=RDJv`E@CvdVD(Uth$y^_Zs>e!r z4-baN;%^fAQt_glckf_+Of`m2fmM$k>iRGlvy(6T`%GK%#+iJPx8*sRrF)Tt01oCA|oI zpcgbGvdWfi1W@evQV`CU;fZ8CLe9ddKZP#xZvLOn zL?fOVV~zgGH-8CuXXnqf5siMGoUL)T>2?IpqurzpPYuL^DRfD>gR#HjHuY;UcV{D{v(XnrF zGdi`*)UkBPh+x|=e?2?#Y}RnzppnPFX$mE#$>DF?FCz~8G?MXexS)Pz@+-gPuAYwf z3bPz2U}0uXXd1tL=T44E#|ONDpWt+$p>ZC^)eowA^XpQU4Ip(09g`b}Apz`($o-rmA$6Ma)tQ$Mxp^l}&-=kZXHFOOPIug~`` zzi;>vEkX+I&r-OhFdf7@I`*TZqtVt0+AIZ9sfl5$eC^dLY*N7;7whtk z(}!!3l?KqD28V={F3kf*h`R9!Zy;1LNz0RYP9NK3WwqlQ>ClGr{K)Ok|Ncy!@}w7& zpCbQztA>jJ+Cb47^dGpYB8#O4)mRyN<+M<_?86yBvN&xyz-g4#J+8#;P6@IVxzgoJ z7@ObUo{G9{a_hM*3PEyb259k zI_RKua@RRrhH<|m=<4Wfzk%R*oBsTS#$V_XP~p)H4GrN;Tb^w|Ozi@rnbtM71On?m2x1ILXJ0kaO$JQ3q2a9lBBv@e}Uw{l~%u(iIMxAVv>5 zUJz?|!2G3qjr_BE1JHA&ct7Go)0JQ#`qw9K7vlfCjv^w4iyBW(p_E@+K*AaHO4q5^AQby1Cdg4olpe8m@+5T(EO=k-s%OYTvinBygI})BTFbK%sTGw8ySs zaV4CGM$GQx-gt$_-iL$)Xjkq$-+dPz?u#lapBpR49PAlDTW~DZT@uiy%Km#Nswzkq z+uuAqTm@|I1{>4WuIKvxEd)xb*IMXb8fq{Z6p4v*SWv`npu|p6wZwR$jyF#~yvbq5!O& zFKFS385u+{23OnSq*g)3G8infwTnE*#X_{SC3d`kZoiZQ;uJWk)#?*WqX00zLFVv> zw&FA@E<)C~o{@wE2H~VAD~lK!8RY=7;|P~>-{w19PmxK~DYW|AmEThyctPL$&jcRO zRsr0FWIX7xHAEw1Mu}>6>x%Zn(M7e>;y=tnHD(u}|U}?bmPwd?cfg1OVh*_4Je`ASAQ}YJyI>?f+Gu zyc!ssMl%bCYXD}FylU#|6fUc23P?bgJK;l8Z!s}3(I<11Q*H6#zkX?>jdtOn9U&eu ztv`^5#<5BNy=b{4EofGkdLQSDhw)f=b8mg$@jbu_BxMSFP#ZWlpIuoGLjLN{TQXy< zA|qu>)A6u2NP?28#eK%c#-OEpnek(8&J5O3sZ2q?1%i|gfm?#7f4=C)J(;y`@tBCp zz=$H(pLXFJ|F@e!eiJG3Ja9z?U`Teg(2{rL7+pn~kL8Lz9uTLp=)@zd4OX`A;&&M6 zD1ZF)$q@8C;)0Zv6gECS)vvv_mB8JcG~M&oBah}m-n7Qbj`(nz@qK37Z{oOEXRx9eJEospD!C560w`?g@4{(r7z zdE5Iu9Irli&?&;_p>V}$m1hSqmCUd9R3`ry>&3?aM(yjH$lZ~;5Nf*bEh0`2FG7rO{>oF_(q)({c`}cexRSqt^LGLA zzK}vZ|Fnvrn(k9n>Yq)CuLrbfGhkVW-U=wSXE<)faXUTzI);zdDJV3Aa`6&QBtR)5 zb6HywPD}KN!S>2nUxi0$Omb7$KP3jBUu$Xrjqva+&Y)598Qi1{D?pnsSCiu#z~Y@~Zwj@J&fA7lcw)*z!< zrAswvGD4S5kB;>f`1~aIEytTTF=)x7Zlpy*71>A_#3xpZ3bJ%d(VQWmnfxDx!-GJS zpP!t`Yd>f3(fNpJ`F0|-be|>ekMx1Ltp=k94pgS1B2h@PE(`i44xewlX=)qiAj3Nb zy1@&W6(F2wL~WRn(Y_ob#=W^)#Pcs3@R^s7%h%IJMx@Ych|}rhv&mv2qQA+X_NzYj zHI;Gs_Txf}f`orE!!eS0hoX@S`5>>P)cHM?+Ygjr7_SGjFpywh$ z|JI$i_!4?-v^$FnrzlY$u)%5X=c7Ow=^;M!m515NZkErrDlQLr^1Mk$Mb%Cij)1fZ zdIbC6U~oWhn_DLf^$TB9fSYR;!lj>C=CWspD}EG$D?DkE!fO1B#lRSvx)$Pyc#Bmn zi(fsy0xHjOa)Tu`*kVL+>NebDoDsF<#mOZA>5=erOtp zu3s5V=9P!LTvp{9n#Y9KOk$9B&hL7v_(~kWIwoXA$(c=bshfKHz^mmpgm zSJAH2mQh7-WyST;!(FqSk#sL--d785+IS*=BsxHzQGJS;rs}h%(Eo7Sv~{FIYreOb zVb}4bX?JfIb}LR*zIiW@A19&G(g<77pm2fTsGeCwgc@2TOPhUIbo{ozFYj-89f>fy z&ahfn_;Ry5bIx@lVC53R@S;YHs&{ej^i6GyvoZxI`_Mg^w4NN}_ql#>>n)3?KT_z01YbZS3 z(HIr+^MdN_+rAJic!|Aq+DTjH2UJTA;`18=U%B|pR(n1DdQHYEBY)0bwpHR6zv5tK zTY0^sZ!0GR{oMWM!8c>IC-;iQ$_}FSnwL$5_Vt@CWUZTz_{!0YR?CvF$YNvE^dJ*#(V~n4_H(QptPsw<0oC+^7-4g{d`<`j^EY6 zdNW;ZcR$X!GIMA5x^z4(bc`r~CJDj@gupmZTU)Dk`*!EdG(eES_EqG?`}fbTgq#-Y ziv!N1N_Mt)o{$&;4D`c?GC`J$23c;s_tKt5N?ICc zvGR*p4y=Th?%GcIU~>|Uk(t&1E>$W^``_Q{eT(*(^>>H%pWN%s_B?!VT&bP>fA^V* ziHWcpEcslufL1kl-Nw$!`a3Y}1oEm02k@0aX@|-BFH(Pz|H{hT)SgL97PJ*A06rUl zBps28PNpUigLqy?+Zlm}*Zjtz&yJRiLvsX|ApieE8vKubb4kMYaqIg4iRChi5Nh6f zY*I<@?8-x0odSz$)cttyK8r53od2~&;eeWk25xlgr;ti@=xqOy+q8!6AC2@h%AXgx zYSOs3T*(W)r+;N-B?Ny$V`HPuG9B~_Q9uPYtR5Y1Rn{$g9l1Raq`d-Ix(;kqE(+ON zs;bPYg*SOdw(CVIRzt1b@AT^cTSd95@J29~B!T|lghlG6zrrF<&-s7T37=5NCw%yT zbvoqACG%Iq=UZ=JTB;iwP5?2zI%ke^;)MC{pv>ZbyW?_s`Sk+_a*ujFNYktgM#pqg z=a~`E6?tBl;+w@}XY+zUhbtrF@x3co-x4^2l)|`v-p^;Ou}~Xd=b7U|3IgMCU;OgN zahHq!nShm?oXjFFP7AyrPzZG(GEML(or0=aG#(}a+9)cMoM3V%lR4VYZQ$?j?sf(y zot&2TSwaHyjVL}02sQ#5+?n9_1v3)>{Nh5>%n_iHenU@j8HjCQP=W`nD;c2UTsn}) z=e}P=2Ff4+nCeuuB%AG(2WPmf-U0sJ-)Zww1nUI!^L{AS03hY}bJl?=X)3PJdL(Rh zyrI@Gr^6hwSTNIV@z$-v?-#WXel0qp5Dh4@E2^qw zpd*~3piom+pRfg5(k&k{7b7T>EpIRW>C5`$*#!Renhf32(@IK8sLc?_-5?;?48BM4 zqm*iC-szVA#gn{b6cG{e1yDIy4e7Kz2~{&4Nzml77)^>; zul}xsOicR4eaDVo%nk?TtHAyk04!LW$Mg4YSs59Z0WRgZ@2n|qiKG-Nz2aa2<7Kq4 zWerGsFJ8U!gYoGx8w>pCMqBm@A6B0n9H zTrCY+tJcfq3l3dTGW%nshJcqD2S7%;0Ak0(v_`k<%F4LN)}`pSco|-RRhFE@V<9-@QC5D*GLlF4 z6blQ>Z}5tngq~t|0_iOTM4?|s1EA1x$GNX5vG^Cb;xYGR>n|S`iIq=IO%Wi5uqc;| z9G8bLBEgWp3iMV*#^yZfUcGyF0STr!cN3o_uiyH?gG7|o7j>9<0mgt+&@g4W#lPQU zX94<_`Jepn?q2q<{IC2ett_Ri4D5!93MUX*P0iB_j-^+RAZq#f`O}uXcGqW%jt=*1 zm&>53BVI>R zu*&d|zDh3{w2(t*jn!`4#?v}$2^}z$Q`8|l*g(W6Ndx1Nw#<~e$6(AyGnh1}J>NU) zzzU%b_C+}WJ+upOdDq%*da4Of83D22lad0%3X~A2dZ3Jwu;4_zdWDh;(7_=H2#ur5 z%i$2hrJp1{6Jw|7%DBSmd@PRgH`$fcwJP5$1NPZL`h(3M#bSaK@ z?@-$Iw?935Vc%e}y_%k07--DEbW%g1iGQ@e9sLa&wPMbYG{xT#vACe0;XEjW)y+J zaTzk|{^cbnhcSkHzrOB(gM%Zu_owSuHh=&a^I_+4Vgv>p8%-o&cEUn$bv$qVpd8o+ z_ubi)yXCGzFkgN#G4zm|szHltetiLs==#&0)vIIVkyh?iIuzEx^Swuo;4 zG)EFXFE5MPPcZ|(6E1Toy1Tg;f@;WMSw)-Fy#8Eedspy{ReipbLhHT+^0vl6CD>Gr z!leSs$|S+nv^B#7s-e?DpATHzVewb@!QMRJH|N>p$o5Pf5#-mLRyd&SZzCg2IXOAd zlQRxvYH|gVFmT?{=!7kIF!m@j=(#<1;_}t2ZVTbSD??eIsVpj@0ge6kqob`sdr}fc z$zT}MEghHy=qMLF^_34u=!7$>ze+>SS5Q}{M3|wdz!NbZ^nhy5#-{M*0PBfU;O@5b zA??P-#uHxbq`ElW_df@qCs&1Nf^gg7mpR;KgZ&s9{gqt%2Wu_7eP16Df-7Yv2Tsp% z_AK~Ru^B5XA)!xwf9Ka4ErQ*ySy^)SXY08xeCmzVzr-S%Z$+nl}3w6ta@m7niifwc1t0N!Os$ATijwrJ;h#nLkK`5Wbw zL)|KQlk^d|v$5&vb9!C}PgYxaD}&pl_io_e;XS)0bI|4S9gNWz&@)3a{RYHb9mOq4 z7V#%@XTi|@{LM%i=w`uyNkV{G)0~)`d6!DtYI{s4jb4E!oh-JL?Z>H5GMaomVvE^(M;1>cCIXOIT4 zN^Oa6Jn8H=;J#DS_1D0MD!W{HRDmWvU{wrZ_?8~s?jn&*vW|COd%70|;OQCcp9qG= zI#}59S1_C%=w|nwXK(wuF{8p#$4jG%md`wGC6+N;2&5dbO-NZ0acNGa4CCr{2g1>)pm^opy>~=I_eb(~TU%Pp*PQy`14Gm8*DFI!xskNb`fCr#K@NpXV!R2A?9f+7_J@O*vn`Zv$~&;zshVRZM7@$sIS*~6nEMt<1;YW_<^ zRJ4x^!^g)*R$X2Fe)~Zw<7T?$g4W)8&!xR?JSqK(-Sm})vYFTBx^hs7Z%Bx@bRPr#yjtNXeX2mb1WmK=Vu#sY`Ttha-1 zD;xfH++BaX^z5W}et!OTgUq21r1fIuV?ZZZha(H7j53hQQ?s((mQwc5I_qACGnnDR z@d%$uJ2S9Yjko&A;QCFG2o*C^Wg+1y4CdBB}&+Ax3)IHBX>p=8x=P6KBgixR8;IvC*hCF z?^9AiEJE9ESWkiAq5-sqx)Gy<%ul0@c(F1{xp(4R8Nvl4zVZ6f5Z$|X?*JY#p==py zCIIgTBqX~?^zlEQd`648p`=s|m%zWOrfv8011g%rjY7)&KGW_@Trf*oZEA>Rzy+I@Sg_uHaUki+4YT4ma4(P>2mn z-nncj7|2ZUP%yPb@>)9_{m;I(icK_puBB7jQ{W@qIt4er+J~OGga?K@Q-^pmEP&Cq z;KN%5$b*d>u7-PouZccgE4%(rn+)$ghKua}FaAb2O&v}Z;C!Tt>1Z3BVCRkewPS?j z3vKt7@T(?&m`Ov>qE+y!{s)r$p2y9g+5^wfp{$T|enp1|ANQTq1z;Jv&QrJRw=HN5 z<#k?FKF@*d?(CrZeX8JOWry1A?Cgj)C@|rR&|ZrImGUY+^1rmyRkBTU175$7s=}qg zo{KBpo`?3i|Es)vfde!X0B2vobO^4Q{N{OGsjnRVMN=jN5YaDUVir()G$fx>U{M42 z)Y}Z6y+gzOd6^R!1g)A_*f%0#bw2;yh6kQOVklTnVtNh#_wG6fxfGS?K-2{U;R0UHAycY=d`m3_6f+5aeSz%QyRgMMkYd_08H^2gxQef0<@}SYd#_ zwsea(-re9(*VJrQeR+xxgL**nU^bJIl3u=g_0wRlK9sHlOk`&`Bbbhv@M~tzN(i07 z9~C9-As0w9Cr{3?DD=t))|x zDTnyX{|p3d74nh9N^pM!4DU%8JZ~>h~9{(51+iJTcd-} zWd%r99(2tL;EDkt7)&(2L@l9{Jhx8&E6#AMPy;V?3kU*r_I{Z&IVeJP=Goz2pJA5niTe^i1cFFjE{G0+iKy5dh6JM}K6F z{7?x6Zo5I5x7;7FlOY%;Xe6D#3{K|1-tQX%$I*8eJK0E=PkpOTg^-qOb|x+ z+m|kiHn0BTdqG#j!BghyXAR6GKa1JQjlcaQC3lNT<#wUAipre<AWr3jSsdl1+kHzGFveQ^0l`Le{EI}}*pQhwSk)BEeOWu7Mv@*Y@) zpnfU$@T&~iePD1CauAOlYSkCi!`#?g=i0(Wg>mVoB!Vh{m^WfX$pK5Xn+QV7dKFBt zH8nM0WmxJeh7F3$N)baBIXRm@+wb4q=SI~MJNEEjxG}F^;~>Yo4q=DIwTOw%9hl-^ z@T3pKwLBDv{Ly<`auu~=+()kg848umfdaC8wKHK?+>o&gkw>0S1t*e(-Nb`sF1f8! zu(gFYPx~U^4?X~{_ra~)I_3GIp3s}chfyO5Rbxn3Qs;i(^4g_9WnvJ$QPG|tpvGzs z%0P^8FSsaI3M&tYp_Kx8x7ylkPY2axBYE}FFFwf4?wH>wAk@JA5*uYGNDCxl?CI$K zhhL>U%beU&!WKVgi0vw5A%8ZW9KPip^%A?JzdXg|k{5W^f12Lb5rjyz@59B#Ef7|U zVD|Sus|4HWd7?`}mdgbJ68o=Yjn+l`%FaPy&QtGjQbHF$KUZW!J;*?Q z1-;SN|K{!yT{%g(t^ebDZ|Tm@_f=XNVR)H$it zIo~Lh$|u^)iCmVg+6pqJy}0t!y5OzdrrYdnRJQe>LU+tj%ex)dbNY>m`I2*IU!Zsf zW&BItHadi1aiG4<(uhI0yJNUMGp{Gfsca)#33IaAJ`r6 z(_>F5VnPHrVMvMj{xSMJXYYoIijN;zF!JJ{jm4{>I=;AYxHz5-++1pA<`a|b^mOyh z?*{sHf8S$=8v{Td3h*ju^VhFm#xj1rT0#{>&pWtB<(PU=NH1NLL?Fv@IXC{u?Qq{E z&w6B-n7sJvPuK9$V$yE74&<2D(cw?s-RC-!1sZT1cnf#u;L3WuP2|9a$TWgNxpi^nvom65*FMEUW z$>|jUaC|nSvS{-N>?wFdid_D1pk@%D{QHN-^3O0H+cL8z)VRDM?i#=dOU}q>Wll&+ z+5lcle#j{ziaiDI^)|vAj?FulAlwX~tp`2lce|dp_A|)(r7Wyle%y1%OCH}hyd(&`7^}=U`O9`CmH5NXU+{bA?wG?FlxAHOmSAnIBzc8EB#H1 zOxTHmHtEBn5Lm=7u!Uc?B|I}%{CCF3)o=~K@(;G4j%cQYp{8LQ&B6v^&(@; zm9NBgIujvaNf5cGYAu*FY$6xi@!U13cx>1}F|_)*w%^HaR|>NY<1U&TsX|d|N!CT# zBJUGlpJ2YmqL3humw!8Ov--M&Ns9dC(!f2QF*$rz|^SV!7-OiQ;n_ zj8cTn{x%*Nn>fp6+qSM^aW= zU1RX8BE56qS%J8M0!GW4FKPIpTx|7o*H`^x;(l3VS(*uMm-#*nq?0owDsF9>tuJ+v zc(5w8-<(v_cZ4YRY)JB?sD!VYcySixTKV45I=XRE5}@Cjf$qXlo*Jz1kQfHz3H+vm z{Tknv!^XUSkrDjq~Jv6F%=9gV8aes_t z*hCeYJChl*DYT#a%3vrVGAJthwAe1+N|%_QG`3R?!4rKA`}-2V{!lR;$=f%2t1 zH30G}>cT~LlF^Hu^4cF~LLuJ$Vmn+Y9!^a$qzZIIrG)Y_zodv za3_@@R!FYh42wMZr2NCwv_z9T!jzVB*U$J;j*O&Jjx1MbG~TyA<(xn4Un7x!zD&oD z&dE&8x$rculbKECN7`f!SIRfNiK%5IM~7)$o3u(;zqlUtd5N6JQA;eS`I5_lzv%bo z1@1MTr*9xQnE(x$Bx|OFfp>Y$Mc8UE7!8AChQMOD>O2Wacawj+fuyHV1o z;iC^darHdQ&ao zez+NqZ4pkll$jAuS2!@0D`hoUSiI?Gxpk(^iqZUg=oJ6^=c$4S4D0y`V;$+uRga@z z_4cxM&##yXI{u`|ux#D59()(v7_KCrS4aLJuEBs$HdAvP6jzBjw$PiAK%0MQ6!nX(G%eLiN_mslm;{8V3bo+iD?1=ZA-sfJ7mMKP$=J2RcdA^TKHhqU3p2-o(Mah+2JCZ_|PAjc?Oxe9dWr~ z&&q3+yqSHyi8(E)uImoFtaEf(cldhc$f#?=-oD<{&_~Rw;mL_wfzdBieP-qDGT|2+ z!!VpRrOHI|1t?h4w9Hsm3 zoslat60a{`;WTV0$Qbjd9eMFd&wx=Ad365I+1c)&n^XwrPCq$+un`ub`qK2?vr?t| zNAGg`V@3kzx-iol6QlACI{I7fci!M;6n9Qu3V)FF-9X%jWgGqHXVnj`icHnkRU7dy zE;kp=tfdc2I%mG|(al~Jx$H;ZXJhXtESTzV%>FK+c*o25izeHrI+AX1B&;{DALd`% z<^@>)VC~?ZC`XF(u9>zWrO~wrPUz>Zhnjm~7b2op|EADwOM&E{0o}~^SQO~xwF>81 z&mw+wN{Ze6^!}_S^2g=atW5#~4Ss;{PU)ll4efpI#kz6e*7XBho$r`t zT9>|8`<3e+uJN`{bS3}8U`bj^{!!`aB@R#6iaRNQ{c8w2hs+>C3xYp3b#-N6%n)Y@ z9WR6gKVr>;`4q@6mSNPu>4u0%wZWmt>3`@C4h0CrqNp%+9m-gbBBu{tOZw5$$cfEe zU0s16U+=;+T=H({&>^K+hDZAZPr0t70amm*bO<}B)NoG8N70k2EvFv2JuDGNC4fTD zX0aN>B0ABkO?52@{rBsIQXx0@O9!3`jpiSISk0gS$V!*~U>fcvmUo^Mate+HDNiSEdS9Yc-6lJzWc4;!P8 z)N8u}=@ROi0zczKNg1v*qHpW=wkQ3R^4M1@q)9Z5IwOC5RvQj8Ol@?C3qX%8G2}G1 zGq&yy3)==9Hy(cv;4ua8G&&X2hAUcadFRcF?0BO1k{a0`~@Tw>W{DUUTA>-gG!Xwu3C}IK3F*^(PNm;+sy9p15`Ga zyh9~g-3weX@qMeYAH=|d;R?v@3be>*f!dck#{!zB%z*t#gdX~{0~(IHHzSp@ za&mK=04|!TAD4rW*_RW(FF18a_~zh{5Mo#)aXByqf`bmoTcF->O3LH$c3WEhEov}T zyc~Tw@mo7PtHT%SCTy~k`ul;dBO>m54!r8k?1sx%>D}K(jX%qXhtWY)1hco*ZHJW^)G1jhx$Dk(j>$9&GdgZ~ja1OqKIP7U6PcJ++ z;KqpkAmJnBY`xF(oQZ%EdmZ9Sh7hkqV9R3ZZCspq3;>r%!!$c}OHkGo!=rb;6Jc7b zA&g_}M_w8&4j9DC^b*YyZM!?OsV)ql#YS3|X>_Uva*G$7hqBq<4Ep~DCRd&U|E9!< zWxsW_vC$;N9sog27&9M1$KfY>u$49Mq;|A=4UGFhHXze4@m*#dwS9U*EW5vEt?<_E z+j0~JHgyWwWyg1M?grn@F(e_qZ;ND#iC?$wBIDTfSWnBXgIZ+# zhngYXKOEY60H*!YL$_>HF(}x*RiubTp>ldi59}q4`Yprw0^a#eig!Bgb?R2fBFz$j z$vbbfxU?3y78?<5BJPN=XYR(yIhQo+iyQiV#~gH22*^4nl@NthHHY;?DE=7Sq5ji< zoQ#}Oq;c2(h>?&2b=2Zc49REFMU%$c5KuX*x}X~40~O6 zmE#L7GmH|UmfQ970mjOekN$Bmge5izcok??$0IRyKxMO7l~EV#JupJr^EpgR{In{q zkYXS6061ewB3reuVQ6nRm-Qy`g;3}Y@y-=2P3Ycfqs|pr)zMD6wV2ngw*TonHm-(E zxHnmo-(xcS>}GZeyiZQ0fi!rKWDhGkuF6nK$?73-RhaSp2KpXsVkJB}iRp#J)lt#l zir+{jPoOrQ1x1bDRKy>BSlsPIIx;X&yUZO>2{b~xF$@Br0-E98*RyY{!O+)bn=WUU z^sqNBCR8i%Mn7>ydq8S_cPawyNH?ve)e}=VVNo$1$B*8z7bS1`rTQh)!E2e!&{1ts zDiiuEk`f4dq!~P|V>qaKgyWzx^^b@9P9ti7IFaGr#k7SFY?uNd6?Kwexcie^uN}w6SKwxw-m)Ru7m!$- zetdzYF*Y?TSe+rKqGKNo9YvQ|Hf?}I;eD}|rsmE}>sHALpnpilsn;Hqy=;m)1G-zo zz(B}R+u$)9`T)NRk!!@b58IpsT6%hOi3C0x#T=FFrNnog>P0SB!X2BTOf2fy`C{cq=>mO-(ZQE(kX!(s|he@b*m0)fM_7~gEVKo@Qd4R0E zf{C%8U-&?v6&!&LM@49}D!Xr9vU+EP3KVOSNhgzbX|N<7<$NJPQMi<<+B1vVAi~kW zW#sep^RJ-#&fBW)Ols2!a<-3M+^%Y5+dD*_Z0OAJ<*W9ynZOGHP3qZIz)C zT;>E>o2?U{^GyW6Z4;ht0@4|p1>RHRLnb#`;&992i2|Ue#h0xdjYQA-EF9W$fR|a&s-x43AopPl}EcU;&K(cdre#CBGsG5bMF% z1a;LYkWb7-dPu44zVoB{yIo@lLtF3Juz*}VT6*6R{r&ku(c_QYh}37FbX*t@v{}DE z2Q_o5bM6T`o`uORn|SE38mHCqbq zQJ;z;WZ)m;K+t3!xMhkUj~Xa1`il_;K?vk{tU-Lg21K*2uJeO;H;*`4K}!HMKLOB1 z0)kJ7#$n*G8oPC&Tu0gsw-^lSRw=jmCVW$k4lW>65FLvNuxZ=ME`mmEJ{ruNI2 z>)ZwdV`Eu`arOBnTiw*EaVS}a$X_>*>>JjE@i~FJ2RMO-bk6oK2o_k^RPY(ilInj( zWa1|0{M8;+&-kA|jvx*Rv;i1E+9Cpg2%FCXYVPn{yf{zO{MhhI@9&l@RZhZAG3^c| zeF`L*{9>SJuR$IIb_+Q7caW=fP*;4*^1ZF^)fgCLgHUXDG+9Qwu(hz2lQqjcr*XQY zd%Cqdl2`bJynNY~wHjG(3vto;(yjzO4Q*{j$ZQMy_b^wl4s4a5BxXWry@yVE@Rp~_yD1z{T9%&|8S}db#I8G9=3yAiB zd0roID+n3fJwudDWG*S5HtGCvBswmq2u)~`UCWV;)@!-ec`qQT33Fj#6CvV@XdI|$ zk~9M8;!bmO1;Bx4NwUZ}t#ndn$va07S5EgOD{C7YIi9T|g*cn9K*7hNV7THqV4lBQ zP(VjxX@*rxz0Qm`)6lT{{ABj=Y(??LRNN0gkaU)27;gB*5Oz`I7>uQZ8ZJ^Z%O~lO zU72s4F;TpI`n!X`jG|~C$o~jPJ&S}E%4)~Z0^|`N=iA4{y*ekqTzTyFO}^7gbD!d; zZiN&D34zCkuh8l;F4eyu-=w?PQ3EDDn3*1v{N)HNtYf%(%&sv#7|P8&Oia6-uzKtI zR&y=*^9|BGKfZp56BWh#5mc*=JDedcA%;P~?C>uUMxXrlijQD&q}vGY3+PZI&gV0VA+Hcleb-#fvp`oGn1uir!lz2iQ;F9Lz_&+s0 zHDS2YQX@;?hV|?0{qh%2oa?IVTs|)h@P^rmr6uBVU^L6<)O8_s!ubEF1OKIpG|FhH`WF@6y9cep|Cpf6cUzj? IF>yKhPlMC~R{#J2 diff --git a/PathTracking/cgmres_nmpc/Figure_4.png b/PathTracking/cgmres_nmpc/Figure_4.png deleted file mode 100644 index 1c0406a8e9695b046313ddb60273f25a1b899fcc..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 19078 zcmeIabyQUU+CIDi6(m(qK`9AElu$|kQ5=GQ5&6|O2LE>edkv#S0Y4rT4_?CGhaW5JVG)Gx9{L|ix@?*y{G+&o z!X1a(cIFPw_w3COn|ltAAK5uPvb@jkWM+@Gw6kTu%n$#&$o|m5;jx5(z`x$WZ)a~I z;Fr)wg&^z*=K57Fm)Jl3?jAv_`*n+x7D6#U&PF6fh$oC|-DF{|nrIpBJ?t6owe|kF zrt)CA-6PG+JfVzqyHI7NRho}yR9-U6>)^gpW4i<=3TC%IYa|R(rkS^-~|C0af89P5ZM_Qq$qZ4tAo?biY+Cgz1)td!X-8M3w#0rCUdj9-ZTd*BNTqymykUb4$PVn|(S+^5Fol zRyzBS9U6vX$27;5<8G#njEpcGKaThDL3AT63|87DRyt0tw8O8&z(8+Xo0h`$>tj38 zwn_&G$G%tnISrTnK^U2tvx9?=nt#}f@vnR*4O&z?PN%hbN$xjkEQkoENG(--_}LMCVWO0oDmmk>m5dN~T&81`qg znrcaM+uNKhGOIt)@6f9D`&Y96+Wer&kocK1XCxe^G;;G26B9MFPa#O+%H|CuR@f4E zh?+6+DH(a@y&Avh%Vw`QI5<|mowj3e39K2`XwTHfdcuTklwF?VCme4|kj+zz5w#rq z9#Xodq@Z9q+f#Hf-g#@qvOWEld{k7F)j&n5vB#o9(ZgTw38Ss8t>N+U@da_w(YzRY zi8%OG$d%lV9f^JY?3eCLi-C2EF8t28xZ710+3GF@An#&hvl|+2`1<=#_OP+C=BA{i zcr;tKBtE@wYT90Cc^jXaYW2G<<9AEa^J1Ic)H27J3HPRr#nI#R^r05shK8}vo1NCbX;xMwT5S~>dZB2+KV)H!(bFHT@=i_awHqGIY`36mwPLsTO`BKB)KL6UaYp)DTTBo%QDkMv}0U;Tr!elWH%k{<5N;BI`800&~m#ym}NUk_>Y-&r$=SuhWOqFn61+Qw=O8)G>=?WJ%qiMalG>#=5@?D$j&&oHew^|&j zbsGy&;=q8V=}fBa;V;gcZNq&$bsHfbLr zizcncXp!R#3@JJ}`qRC3)qE=(>ax39Z%>J6!VWzpVwK`cbuvN|4|^K&#R%JveK*`re*eDEX|~6s zS+B%4&X4AFgtbYDZ9gTA&-C=Pin@Ap_f0jm@CPzSTBjXOl+OLZzQXcTDw^cT+vQv} zf#272UyO}*oDB$JsVA8?CtsTMT(a!o^Nw5g$RBt7w6!|>^Bn122tJpEgqCk`)6voC zYHDg$O>%K_AD?!?oRambxPSlt(x0H$uP?0a(%~4`*i8OlZwYQ$vA9{&Y+2E4xotMZ zNk%U3!scLLU9u@g6%*89sG%cnFSshhF>=C0m%`hhi`kR5H$?s2rz;dKl%Tstl$xg3Bno;Y#V z+k0Os*;y%&`TPP&D1AV_VKk&>#c$VUF>xY$|md@o^X)__S!l+phC z8P3U0pUY+`e@qMVQwF`og5JLTkQ#VwWc_*24bt-l#o78rR^b-!WMyQGXM0PU*JEMD z#>Hj$`Ev=QB*+K8n&2l(Da5t2=d*64=QruJbmui)m`S|-E#qRwRn;HEg4H{_c>SUj z>%8z20#$D!MI9hNOPPF#P=5mxp8_2RNQqn~ZX;y2QB zkG@FA&?DO`)5#F1E&p_Vgv=itEo}LoTQwqG@$D&G3LL)r=J`C5=C#>g>(9>)Zmn1E z=bSWlxmsl1+2POTl`d-2^J#_?P%lkQFfE%X*}z;sF^<)QdwR%nw!C^ft5<+r$)lmOE@Y?A2{= zVnRYRpC8ifFEjs?rPtbblF2f#D^5I=eynL{If0l^U?)&a7d}=eMq}+_-0|k z^Y2B`q37^+)!`kvB4mT#-cC&Q)n;miM2m@4=ax6^6d6~>))g^mKYsiH79(-KYCHD@ z8$qO}#Lncs?+Fb-^daV)MqV&&=;TG{rLn11cxwBP9zQJa)v8+=C&-m2YD z->+u4rDV{{{YUua*qdn)dY79) z+10+Ph;*3gjFfN+vn{RN$u#a~(f)E4ecC%`F4R|e+YMivt{1?+c+n?IM;BS<9Qpoz z%FQ@KFY%K+e+wjCaqoc&fAn3;&3LNL*!A_uo)R&6lOWcK6dKutJ0Zu7UjovW!^Fzk z8F%b%m|Fhgz#g(I4n8tn+?ygfA6Dih!j?|$f}qo*5FT#U)DtJxY z#$1`|?>;?VgAPwe(u3@P86JyM*BIKE?s-fc}o&sP6`A>8F=UfgQj{-c4&-`U-aoAO7)gvMSAso3ez*>Pv|TN#feVw*9N&e7YsWj|xP7Q0M|$8|rI z$PiTjj_Ka2m1P@`WxoV=`{xC`MS=+1fMHdIyERz_x<`k);ixI?MDUB0Jb#W)l5f0K z{pxtX!RaA9x_-@tb_wDmC3l~e8l}D|Rh+Nh=hM!b=pZ6?N-*^<5p7zQJ1*GOz!isO zk|x+5mo90}_RQtdE*wTD*5Z3Z*nq2&+wj5Z???_qBr1rH7+ z{>qbUyIZTbA3jXKCNGcXoH!}h{1&W)(;psypEEO6+jAH2uSf_JHxnWh1H+<4Azg`{ zbCFsNE3^pOwC>KI%RRDSDf8s;C%eHaiN`}e5qq02eIW4Pf!nr5nt16=xjsKcL+tu! ziY=}WzhGe*hun4dJL9<&AnftUVaTU6&qCdj$OXZ0z2i{V%T97ag4Y&CHIl!5YjvhQ zRqZr}_@}#|J=aK*n~N*m>&(9VVOm-pC?{33w2%)a30^oq>JXi5!4m6^u+*C(0;{Av z+Q#08T>vRi($F*>_Qtgp+Zg!z`B_0G^^KRb8<6t#_04!P`t8)E`!8H=9%?1z?+8yg#>%@}ocT{kzkzrcp;$F##wy*CPV1L=1;;j4 zZg0vizhNe)Q^DoiR%%DlpHnHaimJP_5#?E&$4cmRpUH77$JHGoOiewk{rZ)`t>N3- z)7+Rq5Ay&fzmWO8M=+;9H>)tAXEO~-a`j7Wa~fmBvY?pTj2H6S+3>J__4@Vg$B!Q; z6`e@^&=N3`oY#?5(y@TAijZ{EY8-G=)%M=FigP$CWhhH~Dy1gJK(*XC#svR0a_hI{ ze=Tr1WPkklp>p#k|H`}X-<2B^WKC-P>6(RRO77RbiiX|7>Nb^B?|~~T zg3Kms=pe;ifXleh(BsFB+3U??&!n|xY;3qV&h}`NkdP?IuxIl?C8qCs;?xCP$Cg{j`#%K8?_lEvn=aTP|=isM#o z%hDA9O5+-fgu~;>Iuc|aJMm_vL5R5888a*(tQ9Sys$ZmH)z#A9PV(KqlU(jcY-2C5 z6$%Op=XrTmpqgq0rUvUZ=O7UdfEn9Z{ir)%|KojMsD4u6yv+PKm!PGk6&4|2!td?v zyeD}asc0bLHABx%gA#C0f*RzC3r-C&7Pd;)m4z&#>&r+MTy~bJ5e?x4&$A-7kNjk1Wi7h| zEj#(Yunj2yHE{&dpbTUc(OueDkjIwa;+(GD59fC|B8$uuARrA9W%jz5SGO1Be+-(q z&52tso5OW@G)6Q0S-6J=Wp!DRk{IET`=)rEoId>%KDc{u&)~>=%4{BY1GhZ4GPF|P z2)h*)TG9{GEs(r{lwvPwf8A~DC_sb8*_m7+rQK*TXKOvg(Eq3$LNKY?_)^iZy*a5V z=fgnHY15~?LFPft2_gBsNV`X_$)oJj{=y7l=UnkEa>Aq_6w6K}R^e^gQA~TxwA0-d zjkjcBgazmb%O#wfJYws|eoQzuMibrVF=7K#17*maKtLW&g{}o{c?qS@{2%1@OFnt8 zmGsPghE#+1(*bJ42^Vta?P&`cf@>%Lc_~BvLgi?Y*9+ub6flarCuR39N^c~t?59F^O-3`d7yIG>KgZHKZT53$YXyL@C|G=qvRkHA3yqnw^X=E|>6zYKxr>0``TY5F=ADltW^tyBe(#f$wJY5m!!PLG1Qx9g z%5lD22892EslUVS>e9Z@ju|Zzhv&ZZFrCjhn&oA^jVs+&iKao)PTi9gYdzLb!{N*u z-X*;~EtUza+3%jBEHo9~!z1iig&-!O6sQqcBp+yHymw4ix?nwW{j3|pb6n;qVtW6+ z@S`q45u2Ws{6H~kd0<6;EjP>NmCsihs6`9^iWSF(MMR`-E>9X5@*xIrGRtUflFCbSxZ3-#HZ>iydtY~IS=J0UZ7Q0Byn#ctL{Uq8BB^|53SjgPw2;)^+$xobfIZ{A$& zu-47d*T#t-yOX0|6uS%5#SbA~mn5K=EH@U0#d|X{GF|~~4B`DRZS4O)(#E|Ug4COh z(cIM*@gbvq;!OAM{fw11I9f80`SLX_KCdJ3@3Weld@c}z0o=QHkCKY2V5|tpLln>O z0-M37Ul{zLi3>JNk+J7$J83f&HMQ2=yLaPvA#HPSk!cW@Lu64h$o=q-A5b7nJdfo* z&#MwBj@6oI_VzgOqDudHm42Op`^;OB@@VxNq}|ot)y1~`nLrg>5E8m=P-5HOkz)WP z+;prdWYI+6097sv?9#GGXbDvBUo3R=(qBaaCPo_~G=MA%(MLfQ4E)$oVRq4;Z>xFvuf}6129E4GJHgva} znjSxW+FjGO>8xYf_F^MHXX$36n1zcBRqXG6oq>0VN~>8)Y%>8Io= zFAiY0GtyFk7_lGkgCxN4Ty>750vH7?yh?bzgwyxnGr2CR2oFnC6!Aiy@~>Z-ihiz9 zVxl^~d)oWMN#s6;UqQ^x%#KfQ+)le0zQPBi*;$K$EV$C|Jh4`}u3}foeSERwB(flU zgOtSQHItwC&rUS4@@fT7G=#`(y<8wCocpwMNsye5wat0ZGmTRzaEyt?W9i2^qg^Lt zNWU%+LnnLDb1kaWbM!5-uT=9via|XoqHAx7c&zt3uTCWgWdZ`qG%U?$rd4WcW~L=4 zIpSksP<+E}>dbV@nT#7u)3qlX^{V&wAm$*3Kk+1wfucDj?N$iv6}PNxEJ>{8rlSQ<6GXt%^NGs+s!QTfZ*|QRD{-AZ(LFRl;apP^V2ve=1%zGSjj( zm6C$u`|2{F_tK?VB+DC0P8cncDHb0 z7RM-%Pue;W!e*~l`mmaAWe(%v#F;$R_5O2<`#gx~2obpgwbU+faN3~F7;WYw8urz@ zXMy+gTz*^HUs=A=BsuYu6(nf>N^(I#K@Aj#j;oT&{b2MHb}!!4n6#@3`57suyL>1A z1uRan;VC4+?e}@L=6DP_G8gfVr{67W^X_D88a~D@qS#KXq;!mm@XgTeuuF{}jee;; z9z>cHC{-q-4lL=dg|3niRQ%5H-C>vB`{Xe40dd#Q zt3p9vYL9NhifaL6Lm)ZmjA3(2C!*1tN=kScx-DTW2c)p&SIMw#c{T>?9S0HP)UPBT zV4voulOdGro0G)kplBhF-JO)9oDH|CQRH(7G4|IZAX2>_O^Ly0h~#X4Ls+sGaIOF$ z7w$_PWAmBR|J3426T7#& zT|fMIY|E-XnahW0!H806$zBQGwzeB{0*0T)2grd8T2`s_bMY?M zK-B-p!O7X4tVHJtAp=C=T#qb6R9c4QHT|)U^#akgzudVK1V;O+h>LpnZ}}oiMHWGA z_}75Y!f^MEC;AI9rz9h8$s!+u>*q1B*E_ z0CM>lc7IwHO%RsBYcMuHpBFFfZUw@gRa<({Kmvxyd%QhMR~@BHLO7NB zjE)U$7u!Yl6otmSDoVKP07bdAsAReE7)vBa2=@G*)Nfj++xB6vRl+$!i~a)hMiij+ zLq(UVk@Sqq5=eQsKOgJRf7GpV3|XD}B@b9o6GXTb(8H#EPa12$IEpM=&mKJSc>27w zv=PWmf6)f6q1h-_wXb{fj;m{5AZXw!ZM`cFn{b48_LkYiFJFG}!jE^ksPn{}9col!?ZeN%09dh9HWMb9WvI zgq(Wg#*L)9M}41e@ON@bJ%A32jA^{qOk~yqf>QpkDWw=;%zC z0t0fnNMq8u&b)+r;|suJ0QBN_uT&Lx`txpYW0VdR;R&XwXkRJCeB_A6ds&2A`Y%ON znmypP8ou(KlgQ@%u6KVYjhX&zdPBIbzDZ)_$a*$vIr%3$vH4Yn9ZqK_psON~i_FZ; ztw6``DRa!anIIE~y#br5@bU093=uR?k^5gMatumtqPzs`I|s0Xprdl`cZ@8TIW%-S zkU3Z`jsqV(G(jy3(;N~SGBig?f9qb7A`C} zI58}Y0fVcquJ+nlR03tjUBY!K1@4~;)x~rTooqu?HfiEZYI(PHBb0;vdKi1Zt|f{1 zT0mvI9zElPgHWz~`}U1jRJ6Fol)s|=qhYDNe(|HIT5S?hT<~4vIit#+KHC99sGwKf zNeJ?rU%Brhwzzoy+OO~E?2Ie*DQP2Mb6Son0y=aN1n0tmp+kcnrh!|t12(qnQ&3Ky zS5Pb~x`+@^eS-l*$hf`aJ$7{2OBO>(7nyo9+-+TSewz$&ks@XHsW)Y`_gHu;A-kEf zvlpv@_h*YRcJ=M9M25_O)aAFCH?~~38?IM;!;FiG=Jd}?))5Y)Z_yyHK@EsULon^O z+p2a3hTgLKGSkziTN!pHW{*$;0ulH|!S1tT)5T76ipyru*4FuV%A4ud)#Z5U%-hA; zKq(_(C_7-UiV1;0XVu#QK$16#UPdQ7_;))NqAPL|s%W1df+=(|!G3g+pscO0&YV+= zpa?`r*XJ@v$YFb{H>#ax zQ^W>^=Xc4FE?W3V0m!O`c_p6P)$!9}?!|@XG%%P)Z;r|lPBQrkTLc0{rfHvFI-lg< zVAk)F%7%2Yk{nqOk#tfHk~R-q!f1|un;19lm^+B<1i;hfU2#-7b?KVbuP@ZzpFb0= z^DqX*NA?h;6aco1WKHmii-I*K_urS!&wEFvs)goOc2pLTAX3NRp60;*(_xK^e)i=W z^-_CDyQ5ph$71xD;LzKAfpt+kTfgc*+lWLdVi zTc1PMW{4i9*98Y60%QiKd9lHFk?wVGg~-mpG!Ah9l@ZUrZ9o6=D3IBuLG_gg@)`sU z=j}zM<$FzrFl%AQ_({m->_=X#jD=40RCY(Yo45s_@2dy*NLX>hjp;b&l*#zeKo+6( ze$Nuu(#Rrr5(H0}Q9{;dd(%kB4yBtnM)T_C#)1JV=aT8Ssh!Pb-}uP*_}nw{emoFZ zz<1Kg;@p=+Mot^1+5RDCzA7}g+89_np&bz`EY4KH(ef*zTe#Vu6=00P~0s<}uAN)gA79YY;z55K%Pycr(~1hO-T zEU0m7aBocvL)@OP&U^Wig3qMN5Y&VV;XU`rrl%+H{ZB?ygew8>}0i@BVseS4x_pnj^ilbK{?WPiYRJ|_s0*FT7W{{!hE zVIc|jNpz|JN`V1}z)_uckJ0`L^T9ojosGrK4zzv-nV6&6q!@IM`w6d~g*%zlr{FUN zl-M%X-YYECf7j57y1ca-D7k{oGych=dvoh|mS#?!%1(UIAy4!-uw+e?kFT+x`%@g) zXlwcv#?Fb0>p@obWu*rqIx&$QW4!awly$Ik}K#r9G9(JUu=8 zhM05vlL?Wd%}2+wR zs;=1_KhZhYuX*Pkl&OXH$k4bJPT?bWHIOYb-c7}-r;T}+iXu4POTVX}u3|r^_aK58 z|C|vZA>)q>Ia9frDs29SiIjUfP%`B(y~o@~eo)jo5Ym&cUWfY8ggVV$2Fc-4=aQMz z6@=gqWO6W&BhzcWc-#Jl1>MqoVQgxl85R1WSVoc;m2p?jRBpT%j}haP=e_;SJ2|#3R?>PMtEIBQL zJF9kCV4oDZOV&q5vAr>VavCxcSQTna@G6jbiN!W(Sjd62H5iGzKQJj~6I~h>Q(e8X zF*;#t%&TpWhP5yWQg#nrML($RiBrG86*y5f*WXxQNprfaL=-{#UaAs4dePVjR zeZENMz*%n0^FtUu{qJ_0_GS_1lN*L>8XevJsV{Xd!aCt7d>$uJ)qvZl1wWXAhX0VSrC-&$76=bOoyjWQ=}+VicQ4VqvDX(XtHKkJ(AtRW4R9bmp6>Vl*T9 zjSSgHb@L)16>U}Thtjf!fdN%!Lr%Zs=I@rz2NS?KIjD$S4=`lh+u7NHSr59v&8<+q zzvtd`iJ$5zNH_hiX>A{qLHuDj#sQnY(7nWA&=XfPTt;^Y@uA~H-goiGFNB1L<3VuF zfYkEp&6_q*#iOu)YR`NC88KSSE*^YLc#siiz>E`mk8!j57gY1N)iG~RtD1P+llktt za2NXwL}Zn#SMiHaNRS04DT-6I_V+fjpuU4;;>MJXM;H{kE}KKWssez%-tndrMa61| z0qV{KE}6G^W`go5q%KXH(QlY@>e1UEId3(4yF{=d2sg-bul|g{6}j>VjY|6+fx`$#dpJbdP3)AjP(nF%R}T2 zA4P6)ZK`d2r?u^VIu9jGmQAcx@y1FyuA!&xMWaAC;RB`wER`{ zxiZ{Ve{XFxiecB(H-^da+nZ4{>vP?l3Q9nZARiEtBavEnHbPTSRpZvJTM+I8(Ut*> z)nHX6_#~D+Dn{g6eSjowOAeCxJ)#bNdVVM*mbCj8BJq#+eyD_aqPsyrLiAqe&(_S;0CmJ zgXc(h0eEK27u**WrW=?t9Idg91II6bABOQTP687R7~U!ih*bcUIR~P%g9m+Vm&2f zexpghc=NxxW>8~u6KZU>#V`Z4199wUw{e+6Mzp96FE}|S6TFQ92)0(ZE{FACD~xyc zDpq!#?HT>X9#6SEPPd(rZI@b1UwNI75T?EhHuSa@*@Wfw2BBu2vu72Vn3(WOn|5q&PQ`sX7Z{tfpm|)^5p#?TIM@LPYNuWbwByuU7#9KMK6}b~b_3bi(Z7?*VQ6_t~5PA@S;DzngidQtmWe(k^THsMS4e zIAMM8uotcTTXnmL!9BII{k`quE}waZMrvP+xUW6JfW@#cnVi+dCj^pzowBOxZ4kl2 zp*(?hBj?D`6Rf8ZDoTTsJ)fQ=gYze@Anx6}zrtxrpZ)6rukBfmN>KG<+R7ZQZF&kb z2-*Vw-f&|7(Thwx?q)5tdVtCbDg@8cCifzEhXHr&mvd!+)`)V5V09Y1Q*G>JTK5w& zHij6u(Bu7f!-!oaMr6DF7cK?#=9z+K8Ps4DA5smOE!=GbYhmKaQu*)LeqB^VL>oA+ zVp<G|}(<~4uIrmBa@ZrPIt^-J|2X8Ajm>nJxl9_LBR#hj-#e`#~1s+8F zBbEyT{!>(hfGJOhf=K})W!MWi_4A@_B|O5g`v?Bj+y#}50jv2MGq&%3n$O#nd>8@!Z08p;CI)@)|fc1*|4_m;TDw|LHVIL=ggiz-TJo|Rl---TcH{+8gD1(+P@qv zVfmibd*_MtN{f7{aReH5CzrPn#{Ule*A(HTy?F5=cJ)zx1Yg$i3px*B1<-mM9QzJX zn_D%!yR@{vF0k6HkqHi`Q(`x_MyRm8!y1)9Ef?KOZ=J8UPP><0P+hHa^IamZx-_>q z^Uta&qqE!M-cd{v&U3Ng96Qq(Cn+|GKkN;Njy#Xf2Sj3Bkglkt&tAT)d9ukd;2&lr zzTAcykM%evuva!#R^L~!9F%DfT`5XPkO;q!7H83vzT9hPZ8lhysX3lU^~G~*$>a-FYXrgCPdcYj)=o2~RVj$k=jQHb-l9 zSa>a<#2ukI&Cnmr5Q=cbOV_|Kf-LYKkTZF}2%Hz_J`-gXSvuq1hTxQacL@yb6FpU{ zzoY2otMZ&zwe70QUm7| zgc7Kzo?e^>%(%Y1#?ShvSmM!c+OJ+FD9;}X>7gmC)Ar^Br5xSnSx^oJt|!uFLSF%8Xcf7z}7Z@O(4 z0}z)w7UwA_{IxYSf>Guhl-u){E`4ml0%wDwBh-BgP`Ye1P|{%tEZmvU6G!j_+S}=O z8-~quB?M)qrqdFBqo*Gzbb~2zR1Nv!OI39DGii=qfnu6^LI)})1Fq4`ga%B4^v_S_ zh%Te(qdQIO&_dVpJ%rP7GS2zuv;!|YJA3mYuu^XDx3Ke^;qI)RcPLjSq#Tq>SQ@Vf zX|6;w3pjwp!p-YQMa$x7od|ej!Eq!rxNr^wUI`ooLHKE^0#jfXXx93`WIiPk{EtEr zS6VALEcM3p|D)CQ-)Nro4ucsdZfK}#mf6lmO-F@=!bLW{I)GPr7rOo%zonwWyHEk6 zxN!FD+2*}ZpRODvCqG%f_D`DWKea|$+qDvjeMZlE!KyFVXLQ{Qd{N6Z|DGB7FyLD4 zfLpBslLxm`OiD_EcpL&&f%xT#=7c(%9Go z-xn_!RyomW{0Ec7_qgzwg3`Y_t#U?ZE7jE0w84i8*!b1zdWpaS5GklO3BCc7q`K>h ziW44e(7Oo&5Gw0|K~)P(v8ZqKZ@W+)fK&L0{wHxgrRrtScu1}Smc?w@RP>+5uz!4bo|Ek{nzy0h{_ZV?0ZEbD$ z<$`>~Hhe7(^NlEkl%DCP2Pb|>gKGc?R8e{6 zM`tG6VZlGl-l{woE~o;^Kowxv?IF$TuuEa%p-Llc>N^@q(*Nlox!cjyv}D{)(*jfB z=4SV@?G;5tmC)R*-f4(c3otpy#r5^VKH@6zuO2{fvd!ffDedKV3$4Kjx`6#bXLlzV ze)^4G#KF2|LEXZ8+b?S|_xgW0GV*qnr$gmn2_N~Pt*Za&YZ3_iCC+(g)T(G033=05 zH$yL5+%S#*pz-lOo?V4}J;}^7{b0aTCLEl}JZSKvDYT0UL}E#Z&~{@AgA1G~Gs*XlmHgQ%(`Cx@hHo(C2vI5w90 z`Db>Ai{+wHQg2|f4v>@A^!KwsUpx;#zu&Ki3=+{i;DO{26+OYq%DS+$bW9?!zs!D| z5>)Fm;VMU&m;x-C;}5e0G!RH1$~VPJzXp6!TL+@7Zy*=1tE=lBNPjJtuFK;!lQJ?6 zLyakq#R@@T_5==el4*BQiQV9RFE3W$=4+v#dc3)02HOX^@#Ur-zP~GcDkM1A2mD4< zEVZ`N4iXQ{%#uEQIO6H)2`w1p(9=s*X)NF%eEFyynJFg}tij>ozEFTBCBGyB{0t5a zeLgW^e*OCO#JoH@6};xuo%iHIZVU{X=eGfv@zg$*3 z2RP?p)Yzpl3^Z+0UXG%6t7LVa>pLoeOQ)u#eV>_0sh^`W#dDpJjjgV)k9o{~6ZfRl zFc8`p4u`#Js3m=<0AWpU?Q>wYtZ|jcVdQ&L(>Ex(KfqTbfXg5$HT6(uo=M%;uP+GA zUqpB3dUUk4hi5wTzBf0Yl*l&{9FINd)7NLXvbvgt#~*BJYP#aK!t*KXf%xst;|TR3 zvXRkIbjctqKE?IQU^^mo6gfgJiW}d#b4OIMILIBzdFbK6JUTkMzab3;POu8T{+p7b zVxk65OMm}cXb`bhC^V=pFZQQn`vxuD5fxV&8yi1&cQb)a_LJ*!YEg1eczA39o2=K1 z>S|dDNy(%1^rks4oqn`AiZD`ZWN5t%3{*5SVu_92Fy8gPG#NY2Dz^;t4fNj-SP8B` zZ~cgix%t_x?d`>}AM_-xAsHKNu{q!C>d0keWXyLTnV7I45GC2?kcdLbC6(py(*AB7P~uBIo8ndhMP0s+4&iX%a=*RReYhLr0>&{=i~GHcYcVg zrap0WRCw@!OW(jCl7Z0Cp@SCxga;33Psp8aX>a$Po3l;V;)QP5LjuMXa!yWbBc2`K zJ-kh1)z#GzIb~%E21?%}A=i^iN={Z*R(4f+N_ONLy-rFx0}aM!xVT>E?&}cl3bOO_ z(?Yq)BOp-M)zvl9>EY>l@WxqM*c73mp)E73?_y#MD%hsL<8#8~^i;z5*ciLGI1|u- zF9QNT158NloGDdrr~QcZAYx)-Qw|c)7IYUv1{AK!>gr0y#_=t`UV8n2kN^i&@yU}* zRi4|2piSayU0w3Wk4J57ZLif87=XEuk&zLSJRx6{|GnRU0E2GmvUQqSiAftFc9?2FQgDRv!BD~O`VInaVY9W@rWx-;Yahv zQ&e!*d{``wW8oh^UfS5&dY_&B=t*{38hLJR?n6tFK98)1K>O)j}CKJU?&eYjOSh1J??e zjrRqBY$4=uoGDM5 z>pD2>!9N~s0L*?RM1OSmJj^$jioCqMAS3m=goHXcu?_KcwY6qHK3?b89PirMspzhL z{&Grv6jt{bOY*OmfR4G&p5?fBks93JF1uSIWA>%6yIwvb&4V#aF`PJY-_7k*czF2t z`g(a6mn)jLZ~F!+Tz?=0*-crir?(fj?bEF-w`}9eQ#WtkOwY@!Tb^vbWn{$XAjQEE zLy#q*4@v)8TRU7A#HRWUtWAOGkUETVKtL z>lPN1uO=2(R=)oElii&lb(SMv6c*jyh0>RFez2Mx`BYk(<5IP^=Y{N-Do`H{;lo{o t9}1Rduti_)F?&(G_" - ] - }, - "execution_count": 10, - "metadata": { - "image/png": { - "width": 600 - } - }, - "output_type": "execute_result" - } - ], - "source": [ - "from IPython.display import Image\n", - "Image(filename=\"Figure_4.png\",width=600)" - ] - }, - { - "cell_type": "code", - "execution_count": 9, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "" - ] - }, - "execution_count": 9, - "metadata": { - "image/png": { - "width": 600 - } - }, - "output_type": "execute_result" - } - ], - "source": [ - "Image(filename=\"Figure_1.png\",width=600)" - ] - }, - { - "cell_type": "code", - "execution_count": 8, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "" - ] - }, - "execution_count": 8, - "metadata": { - "image/png": { - "width": 600 - } - }, - "output_type": "execute_result" - } - ], - "source": [ - "Image(filename=\"Figure_2.png\",width=600)" - ] - }, - { - "cell_type": "code", - "execution_count": 7, - "metadata": {}, - "outputs": [ - { - "data": { - "image/png": "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\n", - "text/plain": [ - "" - ] - }, - "execution_count": 7, - "metadata": { - "image/png": { - "width": 600 - } - }, - "output_type": "execute_result" - } - ], - "source": [ - "Image(filename=\"Figure_3.png\",width=600)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "![gif](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/cgmres_nmpc/animation.gif)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Mathematical Formulation\n", - "\n", - "Motion model is\n", - "\n", - "$$\\dot{x}=vcos\\theta$$\n", - "\n", - "$$\\dot{y}=vsin\\theta$$\n", - "\n", - "$$\\dot{\\theta}=\\frac{v}{WB}sin(u_{\\delta})$$ (tan is not good for optimization)\n", - "\n", - "$$\\dot{v}=u_a$$\n", - "\n", - "Cost function is \n", - "\n", - "$$J=\\frac{1}{2}(u_a^2+u_{\\delta}^2)-\\phi_a d_a-\\phi_\\delta d_\\delta$$\n", - "\n", - "Input constraints are\n", - "\n", - "$$|u_a| \\leq u_{a,max}$$\n", - "\n", - "$$|u_\\delta| \\leq u_{\\delta,max}$$\n", - "\n", - "So, Hamiltonian is\n", - "\n", - "$$J=\\frac{1}{2}(u_a^2+u_{\\delta}^2)-\\phi_a d_a-\\phi_\\delta d_\\delta\\\\ +\\lambda_1vcos\\theta+\\lambda_2vsin\\theta+\\lambda_3\\frac{v}{WB}sin(u_{\\delta})+\\lambda_4u_a\\\\ \n", - "+\\rho_1(u_a^2+d_a^2+u_{a,max}^2)+\\rho_2(u_\\delta^2+d_\\delta^2+u_{\\delta,max}^2)$$\n", - "\n", - "Partial differential equations of the Hamiltonian are:\n", - "\n", - "$\\begin{equation*}\n", - "\\frac{\\partial H}{\\partial \\bf{x}}=\\\\ \n", - "\\begin{bmatrix}\n", - "\\frac{\\partial H}{\\partial x}= 0&\\\\\n", - "\\frac{\\partial H}{\\partial y}= 0&\\\\\n", - "\\frac{\\partial H}{\\partial \\theta}= -\\lambda_1vsin\\theta+\\lambda_2vcos\\theta&\\\\\n", - "\\frac{\\partial H}{\\partial v}=-\\lambda_1cos\\theta+\\lambda_2sin\\theta+\\lambda_3\\frac{1}{WB}sin(u_{\\delta})&\\\\\n", - "\\end{bmatrix}\n", - "\\\\\n", - "\\end{equation*}$\n", - "\n", - "\n", - "$\\begin{equation*}\n", - "\\frac{\\partial H}{\\partial \\bf{u}}=\\\\ \n", - "\\begin{bmatrix}\n", - "\\frac{\\partial H}{\\partial u_a}= u_a+\\lambda_4+2\\rho_1u_a&\\\\\n", - "\\frac{\\partial H}{\\partial u_\\delta}= u_\\delta+\\lambda_3\\frac{v}{WB}cos(u_{\\delta})+2\\rho_2u_\\delta&\\\\\n", - "\\frac{\\partial H}{\\partial d_a}= -\\phi_a+2\\rho_1d_a&\\\\\n", - "\\frac{\\partial H}{\\partial d_\\delta}=-\\phi_\\delta+2\\rho_2d_\\delta&\\\\\n", - "\\end{bmatrix}\n", - "\\\\\n", - "\\end{equation*}$" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Ref\n", - "\n", - "- [Shunichi09/nonlinear\\_control: Implementing the nonlinear model predictive control, sliding mode control](https://github.com/Shunichi09/nonlinear_control)\n", - "\n", - "- [非線形モデル予測制御におけるCGMRES法をpythonで実装する \\- Qiita](https://qiita.com/MENDY/items/4108190a579395053924)" - ] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.8" - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} diff --git a/PathTracking/model_predictive_speed_and_steer_control/Model_predictive_speed_and_steering_control.ipynb b/PathTracking/model_predictive_speed_and_steer_control/Model_predictive_speed_and_steering_control.ipynb deleted file mode 100644 index 244f63c8c1..0000000000 --- a/PathTracking/model_predictive_speed_and_steer_control/Model_predictive_speed_and_steering_control.ipynb +++ /dev/null @@ -1,333 +0,0 @@ -{ - "cells": [ - { - "cell_type": "markdown", - "source": [ - "## Model predictive speed and steering control\n", - "\n", - "![Model predictive speed and steering control](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/model_predictive_speed_and_steer_control/animation.gif?raw=true)\n" - ], - "metadata": {} - }, - { - "cell_type": "markdown", - "source": [ - "\n", - "\n", - "code:\n", - "\n", - "[PythonRobotics/model\\_predictive\\_speed\\_and\\_steer\\_control\\.py at master · AtsushiSakai/PythonRobotics](https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py)\n", - "\n", - "This is a path tracking simulation using model predictive control (MPC).\n", - "\n", - "The MPC controller controls vehicle speed and steering base on linealized model.\n", - "\n", - "This code uses cvxpy as an optimization modeling tool.\n", - "\n", - "- [Welcome to CVXPY 1\\.0 — CVXPY 1\\.0\\.6 documentation](http://www.cvxpy.org/)" - ], - "metadata": {} - }, - { - "cell_type": "markdown", - "source": [ - "### MPC modeling\n", - "\n", - "State vector is:\n", - "\n", - "$$ z = [x, y, v,\\phi]$$\n", - "\n", - "x: x-position, y:y-position, v:velocity, φ: yaw angle\n", - "\n", - "Input vector is:\n", - "\n", - "$$ u = [a, \\delta]$$\n", - "\n", - "a: accellation, δ: steering angle\n", - "\n" - ], - "metadata": {} - }, - { - "cell_type": "markdown", - "source": [ - "The MPC cotroller minimize this cost function for path tracking:\n", - "\n", - "$$min\\ Q_f(z_{T,ref}-z_{T})^2+Q\\Sigma({z_{t,ref}-z_{t}})^2+R\\Sigma{u_t}^2+R_d\\Sigma({u_{t+1}-u_{t}})^2$$\n", - "\n", - "z_ref come from target path and speed." - ], - "metadata": {} - }, - { - "cell_type": "markdown", - "source": [ - "subject to:\n", - "\n", - "- Linearlied vehicle model\n", - "\n", - "$$z_{t+1}=Az_t+Bu+C$$\n", - "\n", - "- Maximum steering speed\n", - "\n", - "$$|u_{t+1}-u_{t}|komzEF&R+zkC>- zUk5MnP9l;jNZ{d(Wc&?$Mz;T?=>&mb8a_W^3Iy{lAduG(Nl{@H_tgCb4;__>r=F9k zv@eE;Vpuv@>?1l@_&U8ly;QPe?1}Tg%j(z5#K!1lMH$!<$A2q@4~!4+f0&xbz2bkN zs32-Dj5lLw>gzWzD*0aJ@`jH*+GD_^?rNakEjXF;DqW0)C{jESO9Y7`uy+K<^~Ha0 zMccnaXrJF1etruo>yoY=doBjpxv4|bw4K74AJW5W3+4{T1(+K$rT=ebW85fz2UrBkEd zx5Pm~_8)E=8p2Rm61u#+4AMzyN{EeZzdV?;SZd+l+}sS(O%pNP?P(joB3~!)CxMGG zQh0SGNI?MuPFH;7p!^n`ov&`+%Fa&z4P0h*^#^bks!hyC$>duW=8FeJZiLr8kadFi z^#{(4P3=67747F$*byiR!FgVf%q*`ULC<57iKv1ZFatv$7?3&l^f6T52sJh~HZV06 zx3sjZfZoN8SXL(`Cnr1eVuA1H^%%ot>Xn(DuJ_Vw*FA)w+j zuJ@4p{W2Z=Nh0W*+8%(ow!GZ7J(`nI?;X%Cq@h8eRr2F>qd#YCCrmYll>qH6HT7pJ zEA7vSz3fDh;0K+yhDbX)I*w0I-&fqd2UEeW+;vo^?SR)Ykq!GY3cq~q+!Ly#mtIRPoMK zS1AvI>^8IUx{a)G1=k66b zx&Er@X&*xzxI)!{ooQIhliPRLpU1w^nt6b+s5&6m5$C%2PdcgODz*) z<8q@O3@{Jst9gQb=>P942O&&NO_kw+{M@HnUSD4?jydyJgFa04r{Uq@X=rHhUDnmt z-x&Gfcs7%XDUO)4%TIJ$pBj%?8m|87@x#Z0cs4i4`Pw@=b{H_nfJZgv&4KV=`iM(+ zqDTZWMMrN^imj=s_@vv%fai?|A};msF){wZ9glkMwplunQ6`NiVK9Xgn~ZFz!DTOr z--~0R(T!=p2*&a{gpdVTTXmFT5Q(bgGWG6DpD!59gpz3A=Ni1l@91;GlG^HY} z4sT?Vzw^TjAo(fht$Uj?w+{ULfU2*rFPFyC_3b4kfq*wxdwcuLBq6UW{ZZ?aK)zgB zwqzW&^UlAZq@*OBgr!C|yG6ezAIr&NNfi|wMMcH)!v$VJSFz`Wl4K95s;o3RoUhku zbd8LU$0^mR?-(ys4p#|@l=zq#B(@SL=nsC0%UV;JF2!MB;eN6)M%2L>FDZK{Qlh+t@{!rDtKxVNO*WCws3yH zx${L!W+%DO!EANq4_vYKiHU@{T01lCd@yXyep6G^>)Tt$lhrO*XwGwrbCicQc!`g7 z%zU4lFStlu{`$VTqBxsYo}D98JZI%7ZO{ab`Z*&Ve}d3=klCCi{>Fw?PoQQ}y zZU6N4B10r3B%b#mcphI~ns$ZZ$~?}!4(9hf&-@sIQDr%SVrFKhR;;0jroXVVTW9Zfi4{btXLiuU9u-y6J4&x>6WZpU@<{{6`k;)Mp6{>$kUyO!i? zYeU2K-3e$$#U{Aqz`y9+aQ|PtQx8v{9vTwTWAw4(Tw=4;hhOQ!L-B=Nd2W@2EU4e=fwgC~yTVBj?(IOm~GP0GqY zF{M|Bu>}FAJay(6l02Vo_XH-;st}kt{gYt^2HOS>%Qjlc#&+5T4ps)~9|?C0M*X35 zD#Znh^Ydhkg141wDP|#JNQ%EfWxd&*t}vROp2l(g5U4;HNidW_>3L-rm@zBsKK-r( z{i<#gvXVQlZH)TKGVw~@rlk5$`v9I-BrXOK-F`)8{3tAb4tgmekIr`-owbX)Md_Xm zS5`*OwTe1y)T_fnGd#OR6+5tG?%{bzRSIF#)1#N>7dFtcvEC5hh+^IJ&CJx7Lto2i zXqgh_zlnNPbw~5{tD6Js8qt*X`L7fhGQWk#fS_(zFKI7pXO8KlIfI zCS@_tR(w)d*0okjc9kMo7q}!`{}TD-%b0YGM8?9}RyH=}0E5Aw3eX>(`jyn~9$)Hj z;z(5}L_=T0DDatH>`s81giS;g2EdEU-lR!qFnRGT9JHRRiA2GD&uleG-{5-ivwHC6Z0k9L0R-05-5m^o z6r0%)2`CdN#!q4=#_UA(WPWLx#KQ0kT*U}2(}I%fXuBwrm{Su(xbrxO^Q7}9wEA$- zzg16YH@-9m@ZuiOeYP`j4ZKlC$aVJNxf(mf&cKrg5jrXKTgdOi zPI=W|@=JSOs!7aQiG4J5bl34SJ7F-|XJw;M*~ks~#{sW@5h_1XP5w@HCCoCSgP9?oRdT8;NVbYyYLfWCRPwMB_$;S zkf%X5SdA8ZbT3-Kr_$bTR=~^985rL3-4ySL+;3HBdx!jUz9O^2Ntfu>wF`Pfr$T#2 zV*2yx@w)%-U-!-1ohqI_jl`@7mt-9~BX*+aNT{tcyg8C^WH=;RaaalL34vZYtcX&J ze*c*)WiP|r&eCq}Qw1R|w>6NRz)&sRoKCQ8aOBG{mn=!~EYfWVIP9RRvxj+wy>jny zaoNv=S<9r(NQd^m+R6wQKe72^I9B#_97H4Ld)&mL?+XSN#RHclR8XvpO-=tbd$~y^ zGDbEx^9u+FXtqx6ID0=mTxn=)D_5Gz=E)>?fNhJ6gd~*HyHFq!fPkJYpCJH|$q-2M zINNkM-&W*t-fja6vOv3*5oG9Lt*5)A)}Fz^$e0+cBDIoRcwR=SqVWNhNj;tZ?6~l0 z>=v3m2R69z(68N`nI{ZvKgSPcHl`$Us>~IOc|OsGea%Urj8cnIaVt$<;sO^+ z(&#hJkyIXZd?pbU9P3526iy?AD#VDj?k{Cb?6zpKKZSC{6&jo$$@uCK308eFV+T=zef={3_nOd&Q$M`KP-VwUB8u=p4F=a1-{H*f6S+=eHd#!Gd1 zt!BEr5xl&-Y?oTlpW*LxvlnL#H~a=bou44=4qJ8^W}~5E_s*9zV9CQMC~VvJM`d}v z+IA-_mf~)2JnASn+&z9r6)y+Pk=l8$@=iBsGC|wyPB&N}puCRx>rs&zV!#oC)5)RO z(1L&j*jM<6I?Ekts53Pcg|-21(ssK)2t}IFXm%IamCmf$8?f_P(gmY87x|}Kbes8) z@6Ryd4A;7MbJsuPR0T1cyn>*92epBtlsTOr8%W{VPD%bYsRExWPSly2Vm1$#X(;JU80!_R#*Rzer=>_e4&xZ%;KK;{RMZ* z?zDD&(qBqCu+uZbZSVyAx1oz?RI&AwsYND5O4Tx|4I@;04mqQrL`C31P`2hvoKjnJ z7WJFFVt+;aYMqrA;OjOeGaa{9z|ODQbap5Sx2qCKi;JBm;VG?Q@E$2;W>#2en^Z&p z%Ai$H8;m}2f*FJ*76sq-^%re@3yyXYj#&HfFs7ZIU7lQ;)J9)|X00u0W_p&iq-1+v zABulw=4)#kn`ZzWw^gcMMrJix+}_y<$3|GwvEG&2eR5dihRjEb%-m0>ygUrz?H&D3ac6vGDD&d`xohW0v?zzU^Y84G$rf;R zCl$D2kz+|3JtB-^d$>H$XnX9)Xc#|4b#i{?8qiOShJKOe$G?}V&9P|WmmQ{2uu=Py{RGoK(hGtZE{M7#DgGr^}%pV}4|A1jtO zj*g;RTm7Qujy#St9`!*dSNUK)U`QKUS662(=;h&2;d(GjQ`SU#`G|BEKtUXA&+teD z$svx~9IMIrY-5W)IyzDqNA$Qmsme?FcRJ=p=~tf@@2Ax>=gt-&%mnCxi>Rt_hU7mSTj8vn>a~biGb%-e(g`5icl~z-SE3$g} z6sM8!LKLD|W5nl8wFms0q-lsk8%hZ`D;wnIE2FDrxaY^aQ2PfSm6D|xZ{~>+Z}OWIwT=xye+%3HQg)^&XAx&j7T%@(K!=nqYR{?xtXzZxJ$Ag3l5?&cR=P zfuTkG^B4CR``Z_-Mz!YN_so+an4LZ3P%}hc7o|>v6ppU!k7-z9$?!t4R$nlKJ+aU`YW5V?ju9z{Y<%o`YgX_QPQK*-FZA&%ZG%74pvB=DLh6Cd9r+Hl4ofpIlz=9xkjT zs4v%Vp?C}j(vm&1tteuartkUHE?$GhEsjgXve%^CC9eD zVVprdF&13{L>D<6)kyxD>{4&8fAP3kC%jc$VTS!{Uq=MKkWt_*XO`Htp%%Ts0BW2- zrpm;uCD#5TX;bqCKjj}mP)q}9adK)RR#nd5r52}MUrgwaTDU})RegT(D^H|EYgeeF z!gl~2lJS+R!_ zN@^(TEjl^V-aK{b2vW6NLV)syfgH9%#LBhkaOPkgVU=W=P$eE*xsQ!MPw+1+YB|6~ zXA7l;@pS!VpoBp(#}%4;Z{wuL!cTg6pq$9-Oq)3yy836ZJ@T>oZmhLtHtKxyAq8_7 zEBIjZUo)0mV!+sj0bXpnW-nIMj8{XE68s}T=1y7gwPZ2SKPU*N#o6PqW$ zmRrQc@)&gT)U>+MACro9dAUnvK=Js|qw)0otN9Io zUXo?JN5Un;hfX*4aJNj^+#gjtryMTnc0uB?gdu?zF>VdC>|U4q!iw=drm!Bb`S?i0 z6uEqEonfYA))RRp-KKGCQ2pzfh90h%=A;wHy^_gf_^8yi)o(qoOeBXhkW%bZ=yJ-A zb)hroHRoO23#rDW)=p7d0rBYL`V)9tl0VK<=i*$ zJu4@xc%7Q8TX1clU}phBI)ac50kCz9dQC`e*C%T?tKm!qO1UV2=cIn~=Ib-9Wi!i8 zPfxGW;QUUv!I^@KD@iKhJq)u!8w7(~V4%t4?D*tl<@RE49?*mpTan@6Ie@L6o}K*- z$W6cjJyqB&OOX5gDb}pCcXiz?sa^d1H--WH(lM`GXZ+ z0-d_=&yO^xBMsquBg7ZuE+uzmiGI~uN$ki(&cAcvgg(E?3~rT-Gw6%|T3E)cXlgoA zK{-jv`;U<^%C+^e@0?1y?&0iZjUb{nzhO#Zu-Bi;%~hgF9UV9!*{z?NY$@!}aWqu6 zaFNBA6pv}}ZLsmFu@MLPHBZf-$)xX@UlQvcQp>s7+Y9B78QR!@>p=ywLttPagxRDI z2e7q?)uo`Fd~UJ?5#iy>Z5MbrZ0G+LDCQs`BO6W>sREKZpvGn*O8_vNr_)a25)xy8 zT?8DNMvFH$k1hrrtl(!rnO9v~DJ-9?^^Da!nJFnNS5#FQKi=OoopckUk?|4u1DdbG z=g#%j6Uxi%W4^lkxk~Y2KV7?3(F@<3w}>Agi;am4_x#t*SU06A@7&L1&jSz~PWH-n z@LzR+xQe%Oq+@TaTos{c`$#*CQ>UZ4G1{*Ty)Y$B52~*JP(oLm*Xd;W`hNJbR0IbW z&{>XyQ&XIC!=a&}U_Ar_l&V~$@(v*FdiRqzQ)T*y%jY{|=GC*s<(Kjx1R-GMx89%j z`vnX7gO6qmiFE21{&RjV1V|Vdc>pNROg`NWXD@fX?Kzg1CKo!KeUeQ@vI%yF*t=}0 zBKu{JP`SGsB=O?gE{fiLe2u=4a@uQ48DiG$=oS1W!7Gi>crzSYjoM4tYmGAVr(j89 zg?kCR>_!h%CL33s8Q}(j=5jYNBq2Z>(t;KJN|64VO>uH_(nBdKQuea)n^AX!VNVpP z_emGNyQk-86B9AO{z=NK3oZlk!%@{1>}AbLQ*^(_8=A$%#i#m~`g)Ja(*Wr?gaC@# zMhcYn;AQmfNKbDa@8kDt2~ZmZIS-5$M7NHL5AsHP1!yr~x1Y8Qux^<9nJjKl( z@}1^8jApl`c5|DqnRfn}*}lk<(0nfY2T0bHh^D zBmF-AD{3il4X?!%%SUH$t{G|%p2&cDv`x<5_Jog!NoG8fDeQc-NDA5^z!QT`VfeNg z$QTF#UqA+XwBpY2xg>-`#P|g=%yWYwuQJsNRVyI^mkzkhB|p3uM~(v~ke{lSKlW^3 zf5dNL$eFV!P_9+YvWR}m{$(l)X5bB_;pm&=OL0lL_ATf{#2$CZg7k+!<2rq}>Qk&$ zhYC8@I&~So8LIedqkg)6eM9upP;zaStz(kX`9`H_FG`sRc%c&lOiauuGXB1cy{USy zt3$zb-Luov&w#oH6!K5NQH|8vEm`k*y1O&mFAD{u5q5xdfsBf31ZJgJt9rNMcgyuE zD)^hk-egJrxdCK3|M+swuF|;omGAwD1fzb-0HE8sK`q1%F^H{=D1h7Dbe)dyha{bc zidau{Lu7XBlO*F}uxP`m!MyO`45fbI_sW#O95G*x7A!v+O-$r%?a7X@oG0;&&E))= zbld@NnNSk6SYQUA(c;`AS^63OiQabP6PX`CpsxcI!o6vp`8&`on^$WQaoR?NhfAxa zw6vxG83bg;Jdm}XwF7*8?^wVhn`oP@bOfF6&&0i?6bHTf@Y!aH-S_zTcq0$MiD#*o z=>g`62fEf9w>wovPVRe60TyVMUbAOlP!Nmx$ZL8AhKwS<*jh*IKja6;iY^Mu5WVpO z(>|QH@L}1qikV`l8qGu<9R~OA_RfLF_5{3mvQ%zFgWaz`e*YgYfOcoqmV~|SHFs%5 zOUFF^*1rZvtE#XcXSKs@9!JKO48>xRWme25(V?lK0+fad>!@9{N5%O+Vq*LQ0^k5; zGW}#zKKrarb#xTy)H_z7k%L7BG^qW9gHiLat0!bInVmp`01Dc>o~5TTt7jz_Acbu( zF*U9sd2g7m{N|$^ynVNw7On2dD)mw?%J$^ai!olXIlQso#Tkd@ryGWbQW)e>dHS?R zzA)cCf&r@2usfQPlEIB*5zZhCn@4=Ps-}*)&I8N zd-JDq#5~i(_DDuVJUmI2<-bjKq;#8ayLqu7Z;ndOc|sZW=R2RQy)wfBFW( zmXi#q57R#-c&I+t`xgF3hKhF;LCtR21i+Rdg+oV2=Xy9VDI{MXJXhn%N>x=X9RY zJ3ICC#$LB%4|8h0vu5)rWiLQyN(T$%#JI}f08;HN+4(o)?fQp4zoE$?NZ=p7g<}CU zQWR5D`{UQC{3#(Hu(OdIT!ZBWRRfj-kqyl9qZp=hLWtm>EGe(uz`)Nu8i(sIhdyvL z)qIIcCskCKc5p!i?OK~pDQ}#s{F^rd*;uYpII7g75K2nQouyVmlfL+8UJE4nD00Dc z8WX|o_ZfiDr`ZU-KU@Cr{#_?Aj+jkR6^wz~wJj@pvb>&9z2oi-mV%icR`y#b$FCM+ z<0o)}j|BS%6Mo(e&WgMdBs}qJrlv$}4QhLRKYX?8SZ`6tTaGDAZ2Dd$5Qu@^n6Kr0 zc_V?zY5Dfc*9CILx5@iDZ50(2*Ect#MXGeZPY-U-BB1vTD@b%hai`T<47pMXt3Ygk z05TaLIzx+w00#^Pzw+|%?i?Ubp`+$+fpiYU$!Ew=rDbENUihbIPb=}?kKAWQTw|T( zXWa*nQ;|hKa^DBs9}LP80i_BQM|AH+6<4@h{^8t5Uh3>#j*@pfZeymvclN>n6hi8A@V- z1MQ0M^-4%_&wKUK)coO<-CdLzT-b1Iz*kC1p#U0=>ajCRrBF$;Ea5M?R^$&3)!Fjf z;fejahP547gB|7s}aeb+Ngc7Cs=rmqI>#{}=3!?WQI+uoT!9?fA+jy+2GTe+c{DZmfS0Nz8c) zu=VLKwCuOrk=}cif;ON`yPpkmp6zqvh-HDS8_%HqBO+pT0*RB7GQj8Vauk5;S3VZw z^Yc1G_qZ{xsSL4#1B1vIkxS)(*SYJz!7p8rLg){6z zao-}nVBu}_n{R4xa=~-a{j>ffE*YCW#4gIOb4J^2r?G~K{OB>MLbivsVCXgdVA#^W z>S}MYHKfV&;{CH>rTJ>ns3Q=Wgx57(#Q%C1_2v{4~nZQ&i5PRLyGp6 z3;pyTy+bdG$99e{E;dFeBQ1a;KUiVZ!{vQ#A2lbF&PV9y_tZlMh)M3r$;lfvbqc94 zLqCi)wOa;(qWhQVBt(3wgmPO$E1V8*5ZKsUeJ*f&85uovq$$E)=DbWa>M6K*xSAH1 zfWz9`=&I*jdRt>Tp@SP+ByY0SoL1c0oZd+222)_H8QQ*qs65qT+oIacOhrR8R%@pp zmyS9O>_&}^yr94u0X<(cnn9;7rcgQm6(M2r8V7e8jI)!|+TlVY)ggL3sJT(3yyjD- zx}h!b_jWQ51nWJI(f2-Y!{r!0#~;y})@D46ZDn zK|v-;Sc~ZA&Dp3-M%4EtB>$C*sZsf~pL=<)fIx$nrX$++1p-J_xaF?*Osv&iDsSY) z@D3jQL_nv=1-7^|gndT34K%s%h=^uh^l#t7ySag?-`&vxi;5cFLk4yq6N?{?pZfPJ zhT7+`Z9KMa-@JJqo71-GrgQ4qdE}7b1CHyV=-Jt@d3W?vPkM|;*Z2|~uyKW5voLdp zUW;GTiDnDl(^ii z_v+v(&K9u)aMP7R`Lv#}TV}vaG)+{Qu!{;kyJ;UbF^zrIVGL&g)HMwtThOT$XR4KG z!NbEdyB+EPc&k3GikqU^p z)7$KtVDOnbtjY?{kcWTfawJbTe3GVv@Ngc$=?(7sk4}{e z_e71a*+OTSq93h_aaOz`G0KZ{5J$jS}Wxr z&h-fSSQcL=Cvi2}Ncb8h6H~61f6~lIT?;kwk0tgS*Y3m1bwpw`}=m zo>2kKj+q3X7{6n+8E1rU;LA7dw3kr1bSF{%sGqZ%R>#ps2cQ_bewaYh7f80YW-A(@^{=56;!!q=5 zxc5#+*<6q+s#SaV;4Z!&KR$RUOH#-P@BFjOkIC=@WYfh_zOC+bEz^`(d@bE@OZ%O< zdM+tw_MLS{6U1onHjHw+D*t1jRnY0!|Fq@`LY`S@%l(ObreYgy0v;7zGFH(8f;WMG zn_GNVt{nfjYYoE7#YDyCw5Hf8;$SKlH&ww#!+LXHojX1f@f=jV0a_FIMnqTrs)-;_%D#a8Tp2j}-?8k4*os8KQt!!&he>7kh0wI+yfikF(R7Y>}kw+NI!X ztBKY!mpy>p-aV0SN@*vUDrd-YX>mKgJw*!OMEjB69whqTNOv`JXqiJ>$ zpJIy3A>?g?vZO?&)8#r>1~?-3;iiKIXPY5ru=-vM>ZBh9j_>@#E^+Je{35x9olr8f zR~7$T>gnR6Sl5oPZJUzSCLD`9G#lra`(e6k!3t?geCF(Z%SuRFpyB0}$X? z(FidUFLr;on`c(3S^#p(zQU!wtNVp^8Ut{-U)thW;hExDd)rW!6?+DiWNGgJG{5Ir zmXo92Lqk^}iG6*p?Bbp@nvV{vZ@+^GZ@!IcLLDvj~ygP5rn8auzf*d=W1jmxrBbs5?A%cMnd(odCM zql%ok`AQtsQQKtKJ~8!do2Qnv8*#dv)V$PR8g8+=oA&b&tc|mM+T++Ha(X|j{zu#_ zAh{dODUuu17Z**d^oyiy+COi5?CEy!YG2vK#>a|+QvRRwDQHW>6_jF7E3n8{KYB!B zDvMt)?`(&v?LdI^}}&x%yDd>^c#e77Ex1)nKzrw)e!zHv9( zT6^Rd z(!^;=7J+?B^HJ%Qv2no*!pL2NLNzr5&8W9t(zf-}j{UvgwQ~pR zRkb93@u#wdugG}98}`ONi@K44#F^Fzl*P9w)&n-?JEPw(hpTCvwY@g|lp^0LuYY_g zls{3C-Gkz+McO~ikbkwiNPkch?^}Jh(Gr7r0F%P0zV+eaEI={mwCtZq(sy~mjni9H zcilx1?>$>C9sZKX!L0vB{Rn~jO>VM18?xHJ1r#@whb>ln;wyE@hQJFcekP0*j}j-_ z2pJPBKfRY)9b2t@Sd=ph(WespsctFfbhUZSqtdgw|ANaChl8xs-Il3428+FZd+^fE z+W)=Zg5xVY7&EIMD>BtesSa#r87x5xy6lo~D{f9rIrJCN{5y>~OK+;oCW0=jO8!l* zGZCj)3~0>SyyGc}Y8(5~)N<(ZY7Cojlb8M~h}{B~&9v?A2s)-cQ36E}rub7iYI(v_ zlbWx(0p z_7DnAuhZnkvgbf!Mf0T@GDHnZ0`1FxtYg;< z>zuIih`&ELTd9Sh)3MQcj&HYvj@M#m^p&hu1CQLqz2>fuwe{uKzQmAV^ekaGR;!8C zXzg0_4+fA;JiHtA8?UR^>^LGK%N;Mc+%OL6oyO~Z(|AVRl01;U4;p6hT9=g?-JNaf zluNFf13!v5S(jg#po{L_zo|y1W~tBNj+l;lkb8~IL;m3$ZF6aOFu_oEgc=b=}lVJ() zVRhpYV>?rR`+z^iT$IJ$`&a%IM6BXReEOdz%CjUFcRZGNn8TSLT&()Qb$V2HL%B4j zJ6AfHFJv{EwQOpygpyfDvf!$0(Mz<1H~KVNSxt>&ew&2P8on0f<|)dmH0&%6frT|# z{Kd=8hT6e-#_aPRVU%K*mQ*Bexz_p3fx(?qc|*;Qg9P-{FoCYZZRLmsmLHpkgFDJl z%xC7cclMp%o}MUeSO=g{94g(6rt=J+-GH`>t-U|>tnAC3ua97@Z6-WqiP`-h?j|Tc zZw?JUg`pb4!rEeXCZanV(=C~xeJ*+u7I+j*S!-yvJb$w-j@9~j1BGw%riK#^|NQP_ zMmuLuYr9hm4fbP_kc<@C#zEgRjg%;^w+gxhw31205UT#RIc=LMz&BW4Lp2m_&Z_-d zXS0lESP59)YG2dIU=n?bPG23EjbPl)m&uo!CYK?_M$DIM?+8+HFT@P6qxH|N^xi0Ox-U}7>UyN7-LZDYQaMYlq53rAPecwH zRti=(V)YUf>BORbec!?;GXOrRVPKedu!EMb@V_+kM{;)z_Ab4`iaEQ*^gI)+L!&>9 z2C1l+AOb;6S3_*D%!<|f%sv}Cr%`f4j@0U6kFBxgssv@krLF2+Zh&2`gt_MpfS zF+{EfbE`E`eOe%s^K)82_y;CC*XE)Lhyay%+gZb$y-&+_FO zPxqv6cpP!Rg9A(iFT~{gidKh9_W_AS7gOI!_byColz?vLo$APLVwpVX@`@4)yFul- z_Bragq?-em6#s6dh5y$tgUL#ohU@F6MRBB)q#l9cV01Wg@?xd6>*jWv8Np$)QK&c* z1k8>qGwugf@sn}j{D|~t5fEr8hkoAzF2%^bsWQ&I{Cs>@)rfYtfJhr(Ya?S;acZNg zG+V3lr8PU5PqGT?pQKoc;9w)fwY75;NrQ&Xtw-9-b!vyq2L`-%w-}^)mP2Y7LINd(Y=+Jc_qtX5 zsb^wTJ$d}|D_0(EjcSx4RpqBH85tFcl%*=3t{tAi?BJPLSuQ%R(NVzQv^-d zTr?y-P6l3Ldc26Ho?J1`u~Qu9J^ig{OOHHJRT1MIr7r1CRgT76d%T3pY>5-QlwtvjcLdJqn%@@7O4Bpd=N=^YIqE$Xd!o~Kdk!X7-`y9zGY66zu zEbd0_lf!|aClXVVaYWB+D0a|1*I3Jwu9quy zd^Wu6Zkxv2AFmg!gj1kTZgQJ{Oc0M+oWKr5L9*+2X54dp(jcgxAMN|a{i=5Fl(b zwsn9$R~sOQnBfhZ$SAzjBG%xeADc<5(8#f2<{kOez|}E#-<{~@{mxIHqJugvwp*63 zww&ke&MUUT``yooCoW|*8IX>Fz+>%h0|!W`%fO?o(N%GsCZ`kqS~k~1u-RHmADKPb z_ZM{`)wtP#R?}EoRSLtfLn(=C?-NMg!(hc?DaL$Ydv|K{E-V7v^+3LV?O!83_sT=? zJ8(NYUPpFDTo8wgkG2h_jO0b$ilu(fj+%3OY~o3&OHegbZ@nJ1tk^w%m4i>R*4I<3 zsj%ttK2Otrj7;1sNaI0HLt|%a`bf+xGY$ilK_XOz@8Uc*5V` zAm9dBYHxGQ(%W=4$9u6CkHl2krR92E9PTn1eI9>$MI)<(=tjt+lJ-w_=yroQO|2*9 z*6uWS_>F+g!@J8(*Hn5;2E%QorlH`DW0@Pm5OWmBVg_Q#gPT$=e7A=7m7QUM&ZuEN!97iRwB^V_ej*Bx zu1F;S>T9gyvV2vBNDAK#mhM}GACdO??t!8%#*|d&?Tp6HC z3|fWe=#RR|>Vt0jymTgI>GnRjWJv8{BNW^6y3w0(eqn;;0Re-49wmhfq@|X_`wwPI zJkr36XKWrZU;&#>u5m1D#DE;Kp|z4JP14%u(6wHCWnXbZ~z4X@}OOM#O8ItBLYzG6(4 zjAm{GULXAntv>UeAq*yH=(7i9FU{^-cITjjs`JNi(Gj8MkFU5p0S6ezTz*Nl8~kG22x!Vf|!Tq-3vS zihz1zNyM(;d$@2nUdl)20oj2aqW=yFqc>trA!sq-!oHM)7V+{P4 zo8@A)VV8{FjoiRf_iCK`TQ52domfuvu+e?j$)C5~d>$XuHn1xROZ$7Eac*g&F=r`DxHI*K6M?!P$xjJ7 zS1>x~Ga|GRC_cEE2iOD<=pSR#CZlSht%Ea$W)`YdxSnz8C$;K|6?6QTcFCxuyzhhZ zIqlSb_!TL_O%|`z)3s?MMT&R!xCoklyh5+zt#hJ2L951_1YTZj`Nfe5Tn<|m>X204 ze3@?*-#cbRj0xrCX_Z889>xo4To8c3u+H& z@0HZdE0e}I8M(Sz(!LLjo$S&&>ml}wnPcIcS}jxb61GuG*SlGdgoR6ZJ2Ih~+{@SLxhI)D=c6LDu zdq)Z6WvRs0p!Yl4-^;>$#VSPxKXJSrdq_NtnBhjq*<~vw43cLJSeWt$d@~CXPc6z ziGv&VL+$bhzN@tYt%`3YUS^YtjyhW?FY=#I6=wJrzx`Ti_HnVv{){?;tVD(Ycuezm z{WVcIc{zO#Zt2J;AF=#_e@HR~*QPGxG?B&6W|mLxe$h|A5T7>Co#iIpkx5j5@#_08 z`BmYczgOkt)WIG=JGG!=9Za}WH?Pb_?+rHoiElBKs^&x%ed9GwS}^tT>ag74%UeIS zU&8GO&ud>}!Vn@O$ev~?sJ14vic26s^5#wa2O(7a;AxHPYopxtVNhqTN{cE4!{wkx zmTQIdM|C7-yk<4x*15OQ6Ts&0<(=cU_=VzQJmYdYe}bd9$Tz=4-rCbMri~mjmnWVX z?v)kVwRW}u@6|9F2f+;ihQ#W(JS;y?x%(@N&ff1=x%Le~)xljlCTJQ^wQ~0gR;ZE& zF1{Cji_HxKSYdyLyP}mx^9xv8QJkU%+O6#{?V4X08kRf1i>EIf$WCJxmW1z#P?Unv zOgc1aJd`b~p zbl1XEZv~IBZA5;_Pdv{`uY@Z4C1(hCkg+FD6QJZn)^yn~lrfM?Z=*nt~D=HEK zZi6mp5yWsx@oF$7$|BU^=yRNwXIC2r~0_D=L}#DB@*2)Xf~AYNqo}In)p>|in2KXmzg=>n44QjT7?;Z zFn*feI+Ow2D~8udhGx-Vrzlt{e;Sz*&VxR6ZcL|7FMilaJ!#G_xm;V%qVn~;D8kKE z^q0ss`f!CsLh2D)^tgm>jWn~J_#Jo!IU@WF*R~q$4^k+wj&H| zVxh2RoI~7hmgMATQvyB&D{cid9JVy+c!rg0=Z4zr)qEsc0rsgKUA2xNFApJA*^?yKUo?o zP8D^iK??eI3}6<=EjU3Tw(^l;RqnL8dNr>J8-N2*lg7VG`<))075mxqRAg@i@LVj3 z1d8t&6bkz`-Fc|n*4|BP`j}l!@=RI8US(pCD8|PZt4a~E3VBvVBg+5E@gi*pC-mQ& z9wD#zqaWioCa2r&P1RSVsE_ybrgkEG$jg;t)4YKdymj`B!am**#1>psk!;a0vU0q) z>?u@!Z2%G94?sV3Hx_)vXUbXY*@QKgm=N;myYKUNR>I4CUYsfKkXl+QoN|Y5@e~S) zHRFt7BE~BW#jvk_xadvBVSE#AGh~0~V;m-7sV3m1swJK$OJo{47u|E`31%zui<1o382Jp7bpB~yaU=Xuvsy7}h?zEbCW9GV&4^}qy2Lu@qRLyjo9V6VI&O_Ke$YULSLEs*io+&N8 zn0(>0?arh22@LB|8>cq2{nciDTkC{HY$hxPg*1KUdiUB0>FudlZvEv@(m>*SJPS@@ zp|X3nR+mROurK~LSd<@ztNnhvqFG>IV2NfwJ&^wHbu9l{$7=xB%; zcd~sr5w{ItsdjCa<3`U*{r9uS0suiMKc8n}KUWM&mCt6+9&m7tlw9w6JRQ|uD<<-qIQbNllXpk4Upb~IL^`PJ^+gfoGqy)P=U^$vc+Jl*Jcd?OAe>^Z@C zEbrqhx0_|T{OMFgP%8Fsy#ZG4IZ8q>dpt!T_>VXWYNNX_%Qx#xn@1mr6FU3-?UAV1 zI3$Qt{4Y@@PWIeKqmzzJ$H5rOQOjcA!Pbey;omyRhM+JOz?PDPpC52&X=wqfSRoJ@ zFOki-hr?d@%Yz5aJ7by^z=H#7-un+7nB~7we5Ke4I&Hi4`|{_0e5Td*UkihQkNE0W zn69nS(dF`1b@eZp>u};!;;eTQCdWj_YqmSXe?^Vy*OfO7PV(6Z`|7L-x;08W?nX!< z>la%aHs$&sG)jwVNX#l5|229$-l4Ei>4^k~W2Fh+ep;tVIbM2`2dX@M&VMus2MkXT zqSkmly1Kx_v|ntqiM6INSL#?CPo}hcBACx#&`?tYd>O|2`ugc<#c=Mn4L4M1XlM>7 zG66WF{D{ZjXQuvi{ zP_z7>RI@9qL$B+ul1U?82MB}u(7+hSP)G`lb>8)vK}e%SquLR#^F1odH4Bq%YwV1; zPV3*)n3(aAB>(H;^0CEM48KBkW?7Xy!!oslK;ymw=g1O;JTUtuLiw@|p5=<tc=*ZW3STZaoS7pn&{A%CvL_3)eP$n&XX#_$*qQYXhA1pfUZ#aX2m>N#^8q@BTxa9)FPDpoZ}XXGCIo>hN( z&HiZ|M)cdPAKBV-SS`?n(rknX`qlBsrWQ?Qk?<-Kq0~EOS8Y42v^ZQ@ZIiVbfNi8_ zmV7kpI;3KDzIy-ogp*7oQj;J@BBMgD(H+LHOeL5oIBvOaZ92%@>YNsrI~mf@*r)ZU6RZXQV^ zpMPj02y1~D_N)=PJm(5n_9SQ;@UUWT5BqbN$Feh-aWLtlcK-x>gH}V)$MkcbzsuGF z0M2zdYml>jzpUH$bqW#pH!VGq+Yz*(0iJ>UGXIb2R1O$M3{^hX1;c8j3=b~&n6F9; zl2EKo`wlp8!XFj;W)?O?YA9iAfU9FS+6oL#bQ%wqmw`Bv+q+{1B8 zW+3X#SVd;l$mvj$^j>0li!yS8`B!+jR}QPCFq=0+3IW?>T)})*!Xj3%$girc6VB5H z6C&(CaYM%HybYXqcND=lyhd6zIGn5A`GX@8@acH`PfCbja6~mm`t<$bS@_=MS_fQT z(&TzC`;Wt7og_P({Yv`g7X9kn;reu^=PmLAE49CWR4i-D6yIx!Z+2qD!8+cZ_l8WG zXDNTl<(+!QRCCtY3TKIvu(#5TQ+WA|Dko|PfxwixSba34Meos;>rE9sxbYIiN5;1S z{}3v1$`E^b1OvrfQlcZ9_~&GvmbV^9R5KUzV(jX2yEK8-<`-fnD-qdGLxaMR5-@Vf z9hJrdk%4U@^=@ch*8u?kw$g$c@p$6&XY14GtIrl1O{9g|9Odpob6=IDu?x;8+(b=^ z0$^{iG$3XP3hkju+v2}eCdzXLzRsabLAp_reQkt5eYE1=MphUG43DObCHJ^W64!kZ zkm!P=vymums{MQ4qyM1y$me-L-%tj?A^h2ovrj6@+qD>Xk#T4{EZn5FC9IP23*;b*- zd~^$xU|moY2C23P-Eu*U_e0y|?<>BIwfGFY(kc$LZ>{~SZPxKGc2q4*c=^HKJME6w zcjuie{uISK?uTjev2M7Ya5Xbj3^G)H()qAgmaLy(=iQe*n+$zu#w=Zj?AVe=U(qq| zsp$JdjR>%zk`>5mVs*?9rJ}Ueq``SaUi(G2P@C@6G10tyMTi)_^F})w^b*XTURhn$ zxQ%*`926>HM(hkGB?{gZ{lL?gd-^q9|1dZK{2Ceo*Tad_Ymq`_Lf^-@M;zKuUpSREvm;`EP|75j&3}k`iu+gndqF#; z!dwi=!pju<27h=kb_ZJ&Z!*saKIrD^&2X&51?BLbVwV5B(i{m`8Lir`W_St5dL6xU z!BBBz;g1}Iu^3{0O4+Xg%>X2D_`>7GG?E}&y!E;+T?U70U~ z9Y8uJ4VC;+WuV8c;&M(NJQLaB7MB2!&SDHQ|66Stg{Z{tso_Crm-WxpNXl7oL;KPn zZRZ~krW+W-BC5EXgZbXONJj6QQk&<-ttGv%|2jB!hRQ)hJv>y!u>j_l)n+Yq7_aA^NRVI)rq*^R2GT`f z`2k&F@6a}fW2L(iutCtSM;T+k2Cv8CYd7u2-sw3Nl{o5Z5&ERH%^ZC{(RaNoI?x={ zNU(HDqDiQ=pLtZvfXUIFgna6bW%DQERHAxqV0nH0>@Uscw&=z=W@sdcuJ`yxj7;Y{ z6BbFRr8#S-j^&uOYz@QwPwwvd0uZ%|fmM7r8!j-=ae4H!?oHd{8dXHPZ_q2AST&q~ z*J^KhDV_ooVrFrq3}dL}fXRDrztejBH}J1RCP8$$X+YV|=Uz09;dH^C=p45txA=VF zK&OzjaIGcvYYz%>#m@OLs;3PFdt5t&+`BE5xS}|Nh*p5stTyroxz$U{D$zne1l?~S ztQF@XrrG-CQ}1DJS797nRB3rB^vANPDn!eWfxk29;b>g8-1>`8A#a*turDx}@dO70 z!*oamlvp%yr3l`qr*~A_8UL=+l-LM~EZ`dZ*J4)1#mb)NfV|n(xv(Dn- zmdr?Z3Rh!nu=|_qINPB~cfoqv)nC*AAL zdc|zlHH^T+ae|bZ8V9|Hg~jS!&#q*0VMeE;u4P2U|4&%3$vXeorsNjSw(~U{%uzy} z>BZeJ5pEME5fkON`u_BDFY~d34ClfT)S`DEj|yNx^E-*YpM)Tf43}cX;|%_b`LarG zE%#;04_e=CI!31>UMy>@_%*?aUJgLocF}a3oyYuZKb&*eMg`O&p$I8F3Q2VAme^D@ zE$3naVP5H6Po29?@Rx*pgi~Kj34WUyo{E}4s);T#zM@)159E?Wu5bv0?JuFs0EGgq zvH<`|APMIWMJM$cxKiRSGbo=DxwsCZ5Sv0%{H}qyi`7>q)QISUv3Yn@&8agVS|3|K z5Me|(iII?WpFCMyt$M{frz_;c{81AvX&L_1K+c#n^!KEH$tYZ*1L3sl zBjIk`a8%)4h)Ed*%Dr{vL<{7xMb2W$!yh3cuA}>#PJ_8NDQseQd@cpbuo~ZO3NqZ^ zyIs%yNDm?N}(<9Woz>#a#7t(4)%o>XKYT%d{dyH#{OZ_=pM1&&cZ zA>)znBUj#pP=TPp+oPe=u|N;Y1QtiLbAeEcLfzCw2X?OWDMcQdGl1Fc#)-a^V&bcX z^)qW3jt%P#Z$D}EPfeYA#F^7aTET|BLGKyt4}pn7u&Apdr4NcN@pLN1Z*bR8N5A`L zeR}?FOwnSQp`O`!lTt+^ycpG@zD3^S@JH_*$ zj7-AmR&soe!nfp9L>lJ-F9i{AKq$oc>;0adc05;=08(?YO@H;gKcxg;fnp@Sk5|w; zUuIo7JCEZ+^Bw9Hf+4&4&_3zgTnD4AkeN)efzQl*L^KLPqJgonXX5ekpYLr`{#_a` zNn1D#r&0M}mnPKFyyJd%u|WX+nmzi?z;&aTe_%R&{%sC8iS~P_(qur`(r)7}EQe5; z?pHS5*5hEdoQ#-&0X@Q-Qr`~kTDtjfaj6lXrwN z5c%qf-Q(g1waw)EUl}FK(u|;5DC|fRuvulAXS#)2b4nc*bhUzn1q3qzyLSdLH`1n# zeF@UnDyD^!`1BY@)F!G~slVlQ=2LtEm3ZEZoA)3jzT|g!7>h(fz(R*p`S1`6C{BZ= z;|!1H&1t`NhgARWzqzGuzver;75ImVO)A=}Mk>XX19qrT^7JjqHzk^vwAmJM&a`Lp zioL}o!mb$6pGN2WtkU-ZpXZmod++mpTEH;&1}6*apmR3HOg1~mUP}5tt_N&*U-A`< zXRO9A5AxkSL`{CYSA&lNj{E2K6SnKRO5TGM`hWrJcz*s4ffKs^)uAL-TjGEKk$ic@ zBHU2YV%gVsg9$Ypc%Ro!tuagO?adCz?+P^p;#OFmC8qoBG5L*%aA^D7eWTd0@rU!5 zjyE$i-m!|sr1(mBxUnSF)Pw!1oh*knu*7`L<(m(-rXLN6@%ZuL-WcTR=q zEib46pkHcA|B|;hQD86C6)2q?QO$jFZ&CRsHg1aKhAjO{(Rn3eapdg+xAxJiuC;fo zwr-yWS69wl&(s8%&c3N0&FX-fAV5#})@i#MQ_W8MylbbTHxvvEBIj<($$L2Up(NVJ< z&fzq;tR1~QsC*v9ntIxhQT|8Lsk&{xI~C&Z-Ko$kbD^GFHzkA}6-G@ur*L3eI+rjS z8ay6u3*)9Tl%F_n^dli--u%8J5asOh(tB-TG?^zNg)cW=(F{Z%>lGZO|HTEk z9*iyi5vz)bn1H4W2m=nftTlVsS3HDIJwwT_R!qch;cGj+q7xD(9zS0(45b#!VoJ#d zkbm)`k!xE?pWh*Xj-2(z3qDQrUS4&EEH7XGjt#~tXS%zTntvMe6TAzpf8}Cx(imgq zX_{1bC{YVr0cbIK`CD#zzmf@ht?uvt`hhi9#!T=VGFG+QDgMg$ACjMS7;*n5hEX*q zFi^mxhQB2a0=#GfZ{LZKvpT6^<&p7%S?Rn?WT!h})#s ze;)!_*9n|9b#Wc~EgEoPU)AmmvI?RJ*axuBH|Jp)K4;fCM3XNE(S7-mhCqq=qy;Fd z&edNXP97rnjtzh4cxabQvhs-dfn)T*%N$q6L=)_c9=`If%N19-luKlY)e@;{_}r z=B($de-kdd`2Vl~O0))~nk^(lX0o+bQL&5(^J_?%{HYSX(QYyp`Z;_cWvk6(-Tt)? z#wz$Kf<|tf&B4x;LH@AM?}QQNbT6OPk?Qw_4DC zf6NuQI+z~99sBTQv|;j^1kA5QsXZsjlYdxqJ%<4LRte< zm$+~Bb&nKnMsSu|DJTYbDG?B4Qw2KP{lQipu;ozcZsZ&>T%$7=o|@n`@ktAXyQ$@? zL?Ce?>AcEQ;n+ns6|0nRYO}@-HvX#~omb22vv#cm3HE2PiKiPii7GK0UoGqRxJv9R z6X9!_O(dFb6_~P6>aC`WK1fIukp>O_N%cs6qa+EjP|6YaIv}^5_j74RIl~1(ZEm-f zk0F%IA17$Xy~M45OWJ@%qOtzzq~oVNqr(_q1%)>ZqkOrd0F{vuOZvRz5qXjGA}!jA z30iyU?3iM-aIq0s34pS+FTvo;3r`@g+aV!fv-Vo2Wbgg`-8PX;g+c=kTF;q&;~4^O zlsv2yOo<@Na?ntkZF}|`oSqhqRm{mF_R64HW$>%ZbkFdRUON&M9zr7}dD3N(Qd6|= zr>v2}?cs%Yw90>+Ue$JD6ZKIx_yKzy?hYaF1S#doIuLOhGUEVL;@RT`pIm0Fd#O!J zSMbHP+m@R_mUpuc3eY=}Bw@x6kB>x6>#0v}B#=Eg9TV`wyHXW6W0Fd{DGJmi#Ahf# zUbhK~Y<&#K{afeCV(UvTof48%bwfJGyX!6=w4x}$6xGg@1qWQVFRCS)QT_-RPJ0v7 zfDq)NOCjnEd;wTIP#H$;K^0bURoTXp4i1WMSt+WJ5K>`)|GIg_UY^afw^!AG0zwqU zq%$%hKO>-Dj|nP*7O6E`FI9e#5sIc{CpEY){^jA1T?}L_AdT;X#UF?ExY}3aw)ra( zMJYao-fgDatkAC#|r7QF9fJxrZ_nET?)97+0&>ZAe$3>}DI4&0bJQK*-MY(cw#BO{xok%+g_jJGSCxxH|$7*0|jr8Z=t#yt^a?j&m7Igz0Y(`sQ0jAIz^%rgjvc#c=zT0vK<~ z6|LVhyXh`wx@nG5Ew%nW7;R=O;4VkbJeJy&9;+ztkd=C}2^9xGAnT)+5|`(hAr+jR zs{v()8vD0Pt-$;LB-G7&JM(^jyI2Nfq(IK!WbxP$oB>nlM@Z(MMj#W9*4AIN-UWHJ z3x0QFQ#wwAkCvtdf=t!@OV(Nuwi7t)_kAATE;P76Y&Mh!5y zZ4|lP`o3HZ22_}|u(W`?&UP5Gy&>nTq1~ZSoAIWy9t)pM-;y6G)0AoM|LUPM zCJKY^`LgUclF&*uN2a}awHCp))32lDV;|iCOh{2TWmV78E@REV*OBx+f{;*YhS8vMO2^SS17Igss>!gQxRWiX3b5SV z-r|b_@eCSClUE?Y`8_n^L-DxsQJb2n@noJfHeEm;uAYp0uKtr3>Jocw?amCl-6-!D zwEH;mBLXFE^Esxlt%+tCPJ@}0+bIt)>VxOugO!uoUEU&5Qli(TS)D;?y4S3$CBf+r z%USpJ2;7TQO^$@+JXl$)1K*9y}_jozIVff zv3nG$62SdgXRKG;9c%qp@2DaGuHyTDUJMY&hyW}>g?Qn^yo7~Req7B19hKA><08fC z43g9Vwm`h0Nq^gQpP*oLRnA|Fyd@3f=Q~CzggLV25tj>2;mN|ulFk>;3eRdZXTE)J z#CnN*{Z3mrbvhpa@yPv2TA|g)v)aTxH{!$0J0FAiX7@;vuT|^uike+atAJ}9q{>9c zv&56wO_6!*`m!dIwvbA3q-lZ^0vuYc7pu&_+w z;Pu+x-X|HbhnehNEJ-zp0n`8}BPJ0h5O%wqfA9BMBuFT@f+VWfebPbJFZuy0T`@v# z((dCqZJHr4`SR8$X&|Q{7KBPcNB8~V?qV`a97VlcpV=DIEJIa{q1TQKCS$urW-u{WnldficuQ6++P@mxDI70>fuh7u=l)cVxE0!)N5pZiwHyLVCI(e^8=OH!_P z%RAV-V$%p@C4?1W9o^PNq`xW@@naxDP8Zv9-~9cN(9tFGC&#NyWdN%Iy;>2j0brv5 zDig{AT{et959umcoc+PCSuqD?wqL(h49KqgbZP2MCO%BFF?!PZe9X%5>_&fwTtz zU6AKQJU8AsJQ!4)4Nw7@9dY{TY{V7L=b#^GG*y>V%IK1$H2d#ymClqFJskY&r+Bd^ zun}8vLzrtC~*&a&*U z8baVeQoaI~$NKs;B&PoZ&|?7_4~TdSsvi5?fXA_IP{yp}kszYySxo@9(8gj}x7#8B z^SNhfJe5K%m^EiVlJ+-k4z&ZwXMo*l0!Pf=+i##Yi^`Ev!#D7$g-qD^F{TY zH(HIh#iHg`K>%iX2cRDX=Lg-kitLf%2XzkOyQ@JSA{SpIwmk|A#YnUfVT;VlQ&LI6z;E&05{z8jewa7tz9Z4BV#0iq@Qlf zps9HpO&XD+3#HNhpMn?0usFga_9xv;mnwna1{?Fs$nNNe9|>mF<%utRn1GQIos|EB zg99tbujk1nM<*s0xLG8v|3w2n$T_K`saUlcgT$Kv%=JJ(MR31@Iq;wxmixze{Fh;< zq)fQn&rIdHJS$1sD*BLJX!XwDwhL+XPZy)Y-~&ei*NVqc?X2ogh6|EbR}w$zeB(H@ zXizyG&>bRtMSC)0*BRlN)lT}8`cFl{AiI^SW%z+@)#R@3LQM+w4UAm4qs_aoEW^ENn|K(dZ0tee;XX2yl7T-umBdHDGY$AKAp(hFnv&B@Bn zi!Q+NQBMT7l=0=2C_{%s~TXcq3 zQ(pR(&=sLd4J7QgE!?eSeoUKZkTesFj*bR;Pe72vac^teCJbPGA}PfFHn=kSKAa(V zo^N^{AEix0C-T_qe=;^^{s&icvM)sZ)>^g&m$pn^uASG1KX0w``Aq14;D_dBTNVnF zgPpdS2=Yx5zZ96h24}(mkymVQOgN&k^7bLx!r^L@o&|)(sURd z;V+TS0I2dBXY}jbP+W#5>KxxsTTc}TUCeg(0~uqX(!5iTwa%n2(voRs~^`S1;UCJlQZieheUA55j5 zKEzkf;fv@b-D8uzlK;hqR;NnmKyEQ6auf+v$Y_Y(u$*>Iv4mcst?4V7>X47l-kz7n zZ8~8n^6(ltgYMMeJ5u>)mJ<^5cuKQ6#8R1|2{mhUvA2~o28+Y$z=M#EDuG|xofj<30WU!q9;4P zX*796DySN-2yMuqcy`T;f%b9c4JK%^)e?|5l5A>And(r>y&JT6K76t6C*|uFcBUx?`u>b6zrILC@QaOE+5FxO zs!#+yspMdjzDw}FX|Hx-u80w?!xS|sh{YWlCGHK*TsgJI60G-YeBUc+3eQos!I^SY zT3l9AK^BdrSt)t-EWIMp;2VfZ`6fwL*WjEvrY>x&Hw%gIr{4%HjC1WL?~`V1-R-;LSx+`Kj;A zPmpGXIYMHY7!RJ2DY^!KqVe^G-r2J)Jd&Js$J)kCdM8bJ@ef;HMt3QgScA?KO5%th zFT&LEUrnP)fZ31I$watY`3B{E;uQ2j*i@$lfDyK9nQ!*7NZ;w`UM6W&vT=tN?yXBV-5P&QcnTXU_PZ&QJ!J^l%>idX(L{` z60p_a@`*qt0e#JU7G+m3&Xx9%IsyvBkH+rPaHus}|sDSt-=P=Gjo-#55^>&xOI zEtQ}5x3kxBnbN>3+i7%F0tDwmR#%$_t^I#RyjjX03fJ+fj zK?tt0f{g^HTfY_Nj=gXecA8vE*aQ8Wn%I*9_O|ZZ-ibWK0jMqOPxW!W+w!qmf z>LU>oRr@OMeEO>;iE9{)#@Mfn!Nm1`LWp8Z_6@1iF3;IXl88A&$lHV(K4Yi@M` z5{dvtIVWxGkZ(fk2OJlFc2iKxR&#>u$Z(BZ683P5CMAwA0~G_o`0YN7+d^<b%#I(Ds?w9_?4Kb>_NNFkOH+7Fd_L7B-Ff?Mr_zPUcdM%!>YwjJm-T1apDlvUQ0=kwhnXkMRPNeeF zL^l{heQ-@+TD}rCBTeat6ENMANkwYVbu?0)gHpZs!me*DCdtK&m%W|r$;XO{g9cPK0f{WOXp4Sj)PjZ%Y~KP*!8#gHGMe?UK8S9Riv8l<96TI7D^ z<@1@yQMOEqsDiGEMO0m+l-4V0wD9qWpv&=zub%bQJ;oz$zygT!s%L)U<4#?TT^DxQ(`$BA7ihZ(V(YHj%Yx}1Rw zBnt*LWj<+&k`OAtnaxe9k$bvUd=$EDJ0?-YGmLfRbxo{>(7VsAYaX8hs+3@IjSWxX z6uhQieVuKpYadkr=;8`xVAWU`XB&G+hK}TgZf^rBn1B^LM%~{zKHI3L8c4EBTc`U& zHKYW#7n&9>eP;SaM4Fqd@m&_!8{Qw!f3JT~iv-7iTZWrP2V!cF?^2;gXZ_+2^}gI| z{ZV@hGTkE2)$*4tvnVS_Cn7|9e=sSFK_A6O3 z#hPbHYYiL>4McZh^=fiVxRjHtp(Vsjo5#UXiBFrtCIWPoQYa0Do(Dq5U=2Z`P<1+= zk-|@XNZRTpz{+k-Z)u))-Sr*$VTb3n#%2i%%3MChiXs9N6#s}w02ulhf5}J#VzR1{ z(f}PMf!fe+N#D(>=8DUsC#11Axc`U-6o2>9C61%%>ZygQBA$H*?X7nqv1}@SVg8j} z&`^m;QKJ8oBJj%SK+D@3YT@lk*KI|}Y&+zrBXiW#{MYnh;Nw&#sLC1`N2YiJ>1%7p zbyzG6oHk0np9QZ%Fgq9owKI(!`zXJO#^adF%C2Z|VE+pc;aU0TaYF_0x9oQV76z$qd|IcBM3-#y%nYPp@8vk2A4w+OEI?D`=81GG1l@-Rla_I=43 z-5&!n-+~GYYePxjFc0Q&-Ig?zEM@fk;!E z=K3(sYA8q;5wU(y3&j{)21S|AKSsT#kr4(-KrEpaO|R)cnNO|&i8?l*=#u%!kq1g7 z1Q_L+jm7?YVaw6)-4A?VtoB$~>X$n^_8<3o3UWC^HlhZnKYV6pgiKo>sv$*JE9ofo?Rl{_-G9gEFU=n_upzBd;W$u#w z`Mp29AuTzI=wE2hd~csg5G3?9-#|H zUA|=@H*eD%igpczmiFo!o@jw6cH80cA|K__aL)YK=9x5rmzxUzh?x1U;xDUuFnr~| zT}sgymVA46R*^xJF~N=~fEwO7_u`@6b9Po?)20ZRr-B+fmQR;YhbZ?oM#lPKbp-v_ z`V_J{xt^@WdEDiZn}mfE*o)or#46o9u6EJolBH$RF)33`Q0DY33jX&<-)M=@pHRie ztIMN3sTD5w`8XSe@MXa`HXn3!1_{Q13RM7kclWh~ihW7@=2tB2Xg1&LsHfitDrQaA z<DMqWB#}IR76m?Hlo;Y!`DW_}Hv-~;z=nZxFf&Gi9a*B9%}2f^EmcX1jg5N? zlQAs;4>gP{aU^dVMRTPyri%zmF)16PU|9u1B7zTQ$?G7}1QnQb@c@K-`a`Z{g(Jbh z{#m|WUx%4nGm`86jDO7%DqpO^Lk7H(P@XK_CQmXQ`Eui8w$P0)7&>>}apa!Z zE;Sqk*?N2OQ`TI#2+xq0h4B|PSpl*$l+;;cIa%*|fDck|=73~cwOC#5s6t;>Gx25G zCc3&Xo2>;GBH$~pp3-e@LI6uazUBgQwJaxJB@y_k}A*}_-&w^hz-W$!DDQ1by6XHna2{FFl@j! zpu+6!qfotTNWjv7-mT19X z9!}fdWIhMbYgqQakb`WGqz-Nm|CgZyEaXaj4ZczF@K{*71tq$}-(eN={YQmVzC0hS zDg4T@N#{Ki77oP3KUrBum|SW6`sI!Vom{tbB>8@B%Q0BYvuzd4L%799+@G8oMnBs$ zm8VcWFR5e#oF;VK_vG}<%wfj8;b-HLY#8p?&M&iv?eN|ZPm+O&<=o_Ad> zCD0rekxXW~Q2N>13m)4?io6#=v2XYNo7R2KvWYnOt@*W`{e0;Ma0pYrloN!7bz5*o z10s6b-(WIhDk>_>mub1U;-;piE)M|vIb`?B3kXAR!`-9)8dDtWFn!AbfqRE+@)6az zM?`epQpl|g*&GUu6`v-_Xu@QR`&#=m$q|X;1mBuTzV6Gv+#Px+$8i*B6#%2+nZsop z_#c2md`BV(VzeEza|FH`z5osESXp-%jUO>$uKsMx94JTjT&iP%PP%?nze2CM!6Scy zVXpfHCYbU4{z?%1{jU_uUA-vyErE#)7i(ls0?3;hj*T@wy#OVODKI4QNVR($RRs;Kq zY=y}fkq%!kGTKrceK&oNdCzsz=hOVu1gFZIj@e}b^3UW=hs|S_Q`W8k=dOPAhxuzQ zSt|=4QADxE+0S~Bj%k$u+91b{3n+w(wjU5yZr}6k7I@l$J!GY+a%5_6hUgV~VeK&d zb&5knLZf&0A=$MRGqdf36(BAn*P9+2o8yL91cEzbv$F)L@{%qtmpBXA+1dSZjI$gk z7ht)td0p=QH!+*T$q67vvA(tzRe1K4YB$Z`_Kpckr7It?RHt^NqW8($i7}Bg{+n9@ zonb@Yso9Q&<|%aEcND_622@*SRE2JlMgF(~ThTTc7$mPpkdC*`DOnPDZhV%$-?(kJ z6o>Ol)|X3B14neX%R)J3dpI6Mzng8X3Y`yvf0%mf*INO(njL8KADvCB*oe_rnV=Uy;sQ5PNdMPoS6`fPX zJXaOTzK>j7>OCksM-r07pqtp(nil<*xGYb2>Pqw7cgH?dEWf*!wz%y2{y z5D);5_0Wrm9MDOF(8T-znlfzOx2NXIz2oCpl9IjozZVu3%pa2}-@R*wm1SG`M0EWS zL(|@c#A=rk^b>E?dHoXEr4RxkCY1W{UiE`Dznlf2yg%JL4CaxRSMPZp6x?}tF|aj$ z;(iRdA=iKEX@~lW+pb$edDe}BtumIrE28kpJLUUt847;3pu{dhz}@rbZk1+sqx=Q$ z9cuPwmRxt|pZ~#Vm`?F{^nxJI-Mfn@09*urxnI&@_KC(OJ4suW@DZ(9IovQ!mEKAN}bk}EXdE$fR`%~^>2zvH$r%J#^fKt9TCsS z$L^M7UdJp}9GcyV&m)J1I+3ON2uWQtqhGm5TWd*reT}M-UcacR?=9551sc?u+O<|d zxxv4ytLsv$9e>b9-3ro@2X;52w$n|U6*gm8n>lFX-d{jzW3QSL5E47M1+kmP4z4Wy zxiAsE-Q5X9iTs6ZKAOe%8DF6d=VQd;Fd8zRGD{$eSf+$x5o^ykxbN4Fn_kkWF9RX? z#1De|(xSJgUaH=>UNJ(C{{Wm~^qmlfWQ4CQCd?v?NuHUT5&L@+suV#K^ASU#&p|o_ zV!Y0@p(IYFg6@!#9fU-fw% zfH{{a=Q|H%WWxa2`o)}ix+92yz3_;?#9Dt5esU}`2=4m8a{Dd?D&;*Apsn=Y_4!Bt z;Oc#tjUkYI21nM_i(oaQ%Hr#L+SivK(|PJ(`dJh@g+EvKNfcpo#;QN{E&23BOsA+~ zJ#p+?)VmAg^J_{l@c_0Dz`O&1v2cL;N&DXwsJZ;E5VqqoWGUa9^2KbIKP+4%qU|z( z6&T9xUk^?!V&r>Vnsjp^P*iO25b*Pvg$s|xAm}?H?`QmrIgZ69!j8GdwG>B%wGwiG zF0X!ac>7#UPC3?|AnjSC$X6b{tA83AnK&)3I-yhZ75q_`V*?u=vNK8nb3^UVpK%nl`0?;IZ8-v=_K zKaB9Tl5Q}OLZ~h8&bMX-HwDbD^m28NoIfIeIMNZZNF|{b8>JT zzkiV1&~Tc$_2l||gdv2uVqoyL`D%viZE9pn$wL<976G2+OaPLyQk1Gou2Y-gX!0jFy|usi z-kR&FyqTUEC@59B*n2M8Rt~fJtfLk~F>NAUo1`q)GNu0Rc95zs5BmgmiT{}6pUrzq zs>8dc^ka+$tVcnJA6v&c6e|s>V3Ei-)e|(|e2W?hh+Iq}om?uhzR&<`PPKVCIl7K^ z&d7)ZUCYR&VAb4a|LAN@ho~GQUF7*i?l)-q=i}3(QCzy+LA4Npg2^LuN~p>wEOTTO`b5neU?vKWZlhf z874gN5kJbwttlOFnCAq+yQUY;COLCi)w@We9hpx>I*6kcDvSMcVUQ~tjN?c6Lzivv z4O=x@IcM*VgKLRLtZs8LYwyn_7ngMrHtB3yHVUL3ABq(p^zfexy#>dnTfJJOvZ0&! zn_e@N;FZWF{ z)99?oFfl2%5Y;`1J(`{J;4;U>w7%22e2_6>()gIpn3Ygywz^hLkXf!_Vj|;uMxxfh zW+re@&dSz$=I$E5)=f{*diSSxOzuU$a5I9pn(Y+pY0mrx%UJy3;uuXdJ7iay$IPlxg(HICZUmjc^O!$7jb4>29{5k!){dl8HZZw0Y?&A37-!6)5^GPJW;i3-gq6LV(kO`-e73NE39+Pev^!w(@ zy*-vue2uHOdrdZSzNE&_Bs#R5t8bXo9Wt2d zV_%oADVvE_Ii>6koNdwxa2fE;i4XLrWsumHRmD_qUEHcBsuwW1$JahPKtW=_)X7N( zPyH>}Zz*K{^z_hL*|8Vf6Nd8ENA#;7dh1;t@=2otlEx^JDdAeWnD1*F>lhXT^m1XZ zM&HKlH{NBRR@V0qr|QGe!>mtQbEYC)Hp*$(sayqe(DPlosa@;;&G;+;8W%&1;KBBI z5mApw`Dh!r#!ZJlGxv`_epFG@48$i=B>*atPgS~7WPI354Gx8R;xYEo3&}JZRzXc# zchdbt<*_M_=QR0@-EoxVgRicn>Y*TSLLh|JR#sG322hJK5KjML{It5U12lu_cO+j$ zZW(q)Mot^*c$#3L$(N58eqUWP&|@k_59gHx1UQf)Ay?aV&Jfnv{ArO&J3P{hdeXBe_Cu#L(GCl?>8`6ArL}jXhWvL zGW7&8{?sYvA6O#bHJsoz%6g>@sQndE^kukPUQWYhfR(B1HTYHVO-zrq z{`kH>zUy*bu6bwPXStW(bHC4f-_K7Grg^XWRJwh}*IUoFN<&AIF!=JSOj(pqLafW? zSU9(waeSbX@b=@k+t2pK!GxkXw>3J1?@4#duyr}uWAR#@v=2dqpKe~)4(0p%&Y>To zH$js59Qh1ivw1)dX2{;Jm#+Z)ZaK-l{l{QxtBZ`LXHnJ>D-TuobDD168s~vw?^0`t zut-L@k+`w_NNRX^_;jPygN!S3>f9h;d>V3O5TnJHJT#7~J}~q{-<+R0p61Hv-jw(X zr)=ex*kfCMUO=?4%O}DNZrmY^bkz~>#~tiG6;fOSn ziV6=;FYR`c%RS2A%18nep8wsX(}UWbF~%shm>7f$pLTGCR8EU?$#P`m3zJ8&xE?mY z8_@$J7?FXGo5B-u??%pIu{GzTKZ`4>sASP+2cZu8QN%2ovAB2_gTCt~jBp{HH){Vv zbpnf=ox&~(5RTZ}+7?6B)R&3}1-8eJCupDl5QxTn9khrb+0S=OmZk3K_Rf$$c}unm ztIBt6tP24vOOWFMZki87IIByi?wB7%R>C001;SPxEo69>qS=3fZ+rL}UN%MifSjBk zYwhn1srAkV3XFActtYbgq_cCLhNh-w z63AP`&3wT|Mm9n9_I`Ry2R41zR$llkw(Xs!QWhT9C@^T+<9}Xs3XjbmtlsX=n7&oK z_)Fo5*ek`<>a(5<{fC#Ca%+agKgq61OVXuI2klYJa}&kW%uL~a;v*n=6W5=B=ZakI zAhai`w$=tPsi~)@XK|sBy^in4GzI4u;Ff3sOLHIEoV&ZbO_bL3Bx6>%7)!(BA-oLI zXqyOiXbaNWqX(P^UrN#lRaMqd+V7q1k=QH{S5;Nj8Z!1|yObt~r^Q9Z0@52Yp!KjJ zOym^R5sNZ@lA@X@8ORIU6=x><3)7|z?g7W&Kz;x4c<7$#san6;;d_IX+stMe1~(0* z@AdRp;^vdEciv3xr7lY)c15HzrNnByTfVL4s_uJNgg$V}Zy##5<{GunC9K+$`cbjODJ z?p=A8zv&h$0#t?%DM`|hfn zNTwa<E;30IrMaYF1mwTddo`R`Ir(E(E;4?5rIIUyvoshWpI)LUsjkLTfsLhl{#Bj`ci*%|~DOlxV&#mSzj zuxZuU)uavPD0{lgV53$;L*tc7kbU5Ag9Tvd5M+OqLm8I;oBP(6$FBd{5JcCmw-Q&E zkdVmLy?FoJ<*72GxmeB@;a?rvfTs2GT-)+r^HB{jDp)yFLd*6~n&Sp&v* zP9Ruzuvv5AkO+xe?Zs*r*_vMGa`76hbb3+e)w_@W*mXcbK|u{v;_Hr@(2e}|hfFu5 z4HeSLl3SOSB0PHT95naxD!Z`!K2jV=kJLz|Hg@OE1xIfz6zY(K-i*YuSuZGMR{S%} z9>;d~L+FN=rHSU*vY&zXH!U#1SZ2SfYX1s3EoK)ja`n5{esy*73biK2%lzj4ZzVXj zyDa9iczQCBC#Tq=ZpfP>BIGx3N|r}su?v&^X){(QP7FY1DdY8Tb9c|?TpAu8mbJ*q z$&q)|ScA-j`^>qH*v<}q;>w%CjZzB57RMlBQD9KP9jpk}jE{jPsnP~EhWF0W>W?2d z^~Wt)76^Tie!inh6*pxi@93SHap3ecoPNO*^DBiy;g~3Tsoq8)R)089yX?V(Jd6N7 z?qHk9g^l$~eAkRtquaTdIQ>FcHN9<76WgvEqgz7DV9%ZCe7=o36KYPaiDd<#P^hWS zcpmR;_r%s#y`a%{4A8bxz%FqTM?wroS6@f|7247eHSb>ED}I6KSd%q6Hw14WJe%md zg|;w&U^D>IdA+l}6YG8YEh+a3Q&`JR){c(ZJ-xjQMolbcbCJ0wBaLtm)q?Fw=!Tk} z?_f28z6f~yma4P0#+jL!mX?+pq`h{(8_Q&7W%)x6XL>128w1(V(UQ;$I{{8-Z)6lNH=HIe$jgmx4k;3PIsn{&eJcDW&tzOpJ$-z7gPVwD zWnP^dSy{h~kB{frXX<9DVyksNM413LEEPDW`&4}F+t?dSJ+LHwCau3`Eac@_2yAlV zhFimldv_#UeSD85m)g9(9{oPFSD9z&ee^<~9&W9{Vs}dQT+A{_QB`$lsC`L`@<`*>5OrD{fB(qn$d_E_P&A}mG;BTIbs(2AZWGu8LtV<%&7YJu><&Dhg~@Gk>JFKy9if?3ipQv*dN0C(Qm zM?Qf*ukM=O37Z6R}QAf|#*0x%AlKgpIK}o4sW71fkwfF}3c2l8p z<=%C{UpZJh+;Z^&FoOC;_?3Km%rEu!V*jxRPhcCTP#?oy8|qlhC|oy%gjFq4gUH44 zp53q#n>L;=VoYX+L@V|aSXWN$~Rr>91Sx7Q$jgZG8@Hn0QqNPYPC4S2rv_( z9yg9rr|5h*qb8aht?%va-7_AVgVM(L%=F$;Ukao*_9-YTYPhImtHT`O#FSAjfQkKn z1LK*F=hR7u?VN(dM4zf98?aaVUjRwCzpT8x7yuj`%5z6Eoz4=hV!F)|hi^zd%KKe$>^Ual6cUwHfOUEf!EI#55b-rQn#oR+fo z5yIUeR`dudvW8aXu{97c(q%`2DB`2oA3Xm{bIeTxkYdxuJQ>_ zi-08Dts|8_3vqc??|7my3Q?;Q<>D1?LOVNyF+JEWu5G%+g6Q*3?>GgrDXW=Bp*VZ)K0?rySb%)DTg zbJHoPHnG2Qg(MlfenA=A?gB_R?h7DOn#9fZm@L8D(es#>PqD-00wf8 zU1?NQROGBd7L>%@N)4Xf=^|AUh`9hf<$d}9ZzQR7I&lcj!Un{#b$9>Nr9at74^A3c zT8&OGg@Rt8cSBUFT*s&s>nfM)?;;4-v$o-3w3e3E!Ce9s?d=;sAM2V5GY_T*Hh%pk zc-@$+v`_61JnmJ*wp|qOo=(C$YQwIm-53Zv^uBi)s&Yg@7!#X+9w3vvrL&#RqxH1X- z=(Fc)91U1grxO@@Fz0kA1~b^0Py1mK-hUrBge0{_%@+fapTfbTeqm_z@GUH{tqr5B ztejrDxESW;<8!>s91-32BPJW;>`MH1VenlxzlLyY6V6|00s=I|!t9i3wXy5fe*m@R B`__ - - .. include:: cgmres_nmpc.rst -.. |2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif -.. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/pure_pursuit/animation.gif -.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/stanley_controller/animation.gif -.. |5| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/rear_wheel_feedback/animation.gif -.. |6| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_steer_control/animation.gif -.. |7| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_speed_steer_control/animation.gif From 049709fd8b38817842fd1d93e02a1c745c0b8dca Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 27 Nov 2021 22:13:55 +0900 Subject: [PATCH 425/940] fix #581 (#582) * update docs * update docs --- SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb | 682 ------------------ docs/how_to_contribute_main.rst | 2 +- .../Figure_1.png | Bin .../Figure_2.png | Bin .../path_planning/bspline_path}/Figure_1.png | Bin .../closed_loop_rrt_star_car}/Figure_1.png | Bin .../closed_loop_rrt_star_car}/Figure_3.png | Bin .../closed_loop_rrt_star_car}/Figure_4.png | Bin .../closed_loop_rrt_star_car}/Figure_5.png | Bin .../path_planning/cubic_spline}/Figure_1.png | Bin .../path_planning/cubic_spline}/Figure_2.png | Bin .../path_planning/cubic_spline}/Figure_3.png | Bin .../lookuptable.png | Bin .../path_planning/path_planning_main.rst | 92 +-- .../quintic_polynomials_planner.rst | 2 +- .../modules/path_planning/rrt}/figure_1.png | Bin .../rrt_star_reeds_shepp}/figure_1.png | Bin .../state_lattice_pathplanner}/Figure_1.png | Bin .../state_lattice_pathplanner}/Figure_2.png | Bin .../state_lattice_pathplanner}/Figure_3.png | Bin .../state_lattice_pathplanner}/Figure_4.png | Bin .../state_lattice_pathplanner}/Figure_5.png | Bin .../state_lattice_pathplanner}/Figure_6.png | Bin .../path_tracking/path_tracking_main.rst | 2 +- 24 files changed, 32 insertions(+), 748 deletions(-) delete mode 100644 SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb rename docs/modules/path_planning/{Bezier_path_planning => bezier_path_planning}/Figure_1.png (100%) rename docs/modules/path_planning/{Bezier_path_planning => bezier_path_planning}/Figure_2.png (100%) rename {PathPlanning/BSplinePath => docs/modules/path_planning/bspline_path}/Figure_1.png (100%) rename {PathPlanning/ClosedLoopRRTStar => docs/modules/path_planning/closed_loop_rrt_star_car}/Figure_1.png (100%) rename {PathPlanning/ClosedLoopRRTStar => docs/modules/path_planning/closed_loop_rrt_star_car}/Figure_3.png (100%) rename {PathPlanning/ClosedLoopRRTStar => docs/modules/path_planning/closed_loop_rrt_star_car}/Figure_4.png (100%) rename {PathPlanning/ClosedLoopRRTStar => docs/modules/path_planning/closed_loop_rrt_star_car}/Figure_5.png (100%) rename {PathPlanning/CubicSpline => docs/modules/path_planning/cubic_spline}/Figure_1.png (100%) rename {PathPlanning/CubicSpline => docs/modules/path_planning/cubic_spline}/Figure_2.png (100%) rename {PathPlanning/CubicSpline => docs/modules/path_planning/cubic_spline}/Figure_3.png (100%) rename {PathPlanning/ModelPredictiveTrajectoryGenerator => docs/modules/path_planning/model_predictive_trajectry_generator}/lookuptable.png (100%) rename {PathPlanning/RRT => docs/modules/path_planning/rrt}/figure_1.png (100%) rename {PathPlanning/RRTStarReedsShepp => docs/modules/path_planning/rrt_star_reeds_shepp}/figure_1.png (100%) rename {PathPlanning/StateLatticePlanner => docs/modules/path_planning/state_lattice_pathplanner}/Figure_1.png (100%) rename {PathPlanning/StateLatticePlanner => docs/modules/path_planning/state_lattice_pathplanner}/Figure_2.png (100%) rename {PathPlanning/StateLatticePlanner => docs/modules/path_planning/state_lattice_pathplanner}/Figure_3.png (100%) rename {PathPlanning/StateLatticePlanner => docs/modules/path_planning/state_lattice_pathplanner}/Figure_4.png (100%) rename {PathPlanning/StateLatticePlanner => docs/modules/path_planning/state_lattice_pathplanner}/Figure_5.png (100%) rename {PathPlanning/StateLatticePlanner => docs/modules/path_planning/state_lattice_pathplanner}/Figure_6.png (100%) diff --git a/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb b/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb deleted file mode 100644 index 53364e3276..0000000000 --- a/SLAM/GraphBasedSLAM/graphSLAM_doc.ipynb +++ /dev/null @@ -1,682 +0,0 @@ -{ - "cells": [ - { - "cell_type": "code", - "execution_count": 11, - "metadata": { - "pycharm": { - "is_executing": false - } - }, - "outputs": [], - "source": [ - "import copy\n", - "import math\n", - "import itertools\n", - "import numpy as np \n", - "import matplotlib.pyplot as plt\n", - "from graph_based_slam import calc_rotational_matrix, calc_jacobian, cal_observation_sigma, \\\n", - " calc_input, observation, motion_model, Edge, pi_2_pi\n", - "\n", - "%matplotlib inline\n", - "np.set_printoptions(precision=3, suppress=True)\n", - "np.random.seed(0)" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### Introduction\n", - "\n", - "In contrast to the probabilistic approaches for solving SLAM, such as EKF, UKF, particle filters, and so on, the graph technique formulates the SLAM as an optimization problem. It is mostly used to solve the full SLAM problem in an offline fashion, i.e. optimize all the poses of the robot after the path has been traversed. However, some variants are availble that uses graph-based approaches to perform online estimation or to solve for a subset of the poses.\n", - "\n", - "GraphSLAM uses the motion information as well as the observations of the environment to create least square problem that can be solved using standard optimization techniques.\n", - "\n", - "### Minimal Example\n", - "The following example illustrates the main idea behind graphSLAM. \n", - "A simple case of a 1D robot is considered that can only move in 1 direction. The robot is commanded to move forward with a control input $u_t=1$, however, the motion is not perfect and the measured odometry will deviate from the true path. At each timestep the robot can observe its environment, for this simple case as well, there is only a single landmark at coordinates $x=3$. The measured observations are the range between the robot and landmark. These measurements are also subjected to noise. No bearing information is required since this is a 1D problem.\n", - "\n", - "To solve this, graphSLAM creates what is called as the system information matrix $\\Omega$ also referred to as $H$ and the information vector $\\xi$ also known as $b$. The entries are created based on the information of the motion and the observation." - ] - }, - { - "cell_type": "code", - "execution_count": 12, - "metadata": { - "pycharm": { - "is_executing": false - } - }, - "outputs": [ - { - "data": { - "text/plain": "
", - "image/png": "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\n" - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - }, - { - "name": "stdout", - "text": [ - "The determinant of H: 0.0\n", - "The determinant of H after anchoring constraint: 18.750000000000007\n", - "Running graphSLAM ...\n", - "Odometry values after optimzation: \n", - " [[-0. ]\n", - " [ 0.9]\n", - " [ 1.9]]\n" - ], - "output_type": "stream" - }, - { - "data": { - "text/plain": "
", - "image/png": "iVBORw0KGgoAAAANSUhEUgAAAYgAAAD4CAYAAAD2FnFTAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAADh0RVh0U29mdHdhcmUAbWF0cGxvdGxpYiB2ZXJzaW9uMy4xLjEsIGh0dHA6Ly9tYXRwbG90bGliLm9yZy8QZhcZAAAeUklEQVR4nO3de3RU9b338fc3mYHIxRsiUrlbRIFELpF6QxC80DbldliI4kNwaV2K+LSlpaJ26bE9dWFt0XWqtsvaLuF4Q6lQyql1ISCgnkcIMVoCCpiCCXqQi4AJRDLJ9/ljhjSETTJhhsnt81orK7P3/s2e7y8/mM/s65i7IyIiUltaYxcgIiJNkwJCREQCKSBERCSQAkJERAIpIEREJFCosQs4Geecc4736tWrscsQEWlWNmzYsMfdO8fbvlkGRK9evcjLy2vsMkREmhUz29GQ9trFJCIigRQQIiISSAEhIiKBmuUxCBFpWioqKigpKaG8vLyxSxEgIyODbt26EQ6HE1qPAkJEElZSUkLHjh3p1asXZtbY5bRq7s7evXspKSmhd+/eCa1Lu5hEJGHl5eV06tRJ4dAEmBmdOnVKytacAkJEkkLh0HQkayy0i0lEUmrH3jL+sLaIJe9/RtnXEdq3DTF+8Df4/vA+9OzUvrHLkxq0BSEiKbPq4y8Y88RaXl5XTOnXERwo/TrCy+uKGfPEWlZ9/MVJr3vXrl3cfPPN9OnTh6FDh3L55ZezePHi5BUfp169erFnz57j5j/yyCMntb4lS5awadOm6umRI0em7EJhBYSIpMSOvWXMeD6fwxWVRKqO/aKySJVzuKKSGc/ns2NvWYPX7e6MHz+eq6++mqKiIjZs2MDLL79MSUnJcW0jkchJ9yERJwoId6eqquqEz6sdEKmkgBCRlPjD2iIqKk/8RghQUVnFs2v/2eB1r1y5kjZt2nDnnXdWz+vZsyf33HMPAM899xxjx45l1KhRjB49Gndn9uzZDBw4kMzMTBYuXAjAW2+9RU5OTvU6Zs6cyXPPPQdEtwweeughhgwZQmZmJh999BEAe/fu5frrr2fAgAHcfvvtBH1L55w5czh8+DCDBg1i6tSpbN++nX79+jFt2jQGDhxIcXExHTp0qG6/aNEipk+fzrvvvsvSpUuZPXs2gwYN4pNPPgHg1VdfZdiwYVx44YWsXbu2wX+veCkgRCQllrz/2XFbDrVFqpzF7+9s8LoLCwsZMmRInW3y8/NZtGgRq1ev5rXXXqOgoIAPPviAN998k9mzZ/P555/X+zrnnHMO+fn53HXXXfz6178G4OGHH+aqq66isLCQCRMm8Omnnx73vLlz53LaaadRUFDACy+8AMDWrVuZMWMGhYWF9OzZM/D1rrjiCsaOHctjjz1GQUEBF1xwARDdClq3bh1PPPEEDz/8cL11nywFhIikRNnX8e3aKTuS+C6gu+++m0suuYRLL720et51113H2WefDcDbb7/NTTfdRHp6Ol26dGHEiBGsX7++3vVOnDgRgKFDh7J9+3YA1qxZwy233ALAd7/7Xc4666y4auzZsyeXXXZZQ7pVZx2nggJCRFKifdv4Tpps36bhJ1cOGDCA/Pz86umnnnqKFStWsHv37n+tt339Z0iFQqFjjgfUvpagbdu2AKSnpyd8LKN2PTVPTa3vGoZk1lEXBYSIpMT4wd8glFb3+fmhNGPC4PMbvO5Ro0ZRXl7O7373u+p5hw4dOmH74cOHs3DhQiorK9m9ezdr1qxh2LBh9OzZk02bNvH111+zf/9+VqxYUe9rX3311bz44osAvP7663z55ZeB7cLhMBUVFSdcT5cuXdi8eTNVVVXHnH3VsWNHvvrqq3rrOBUUECKSEt8f3odwet1vOeH0NG4f3vDbQ5gZS5YsYfXq1fTu3Zthw4aRm5vLo48+Gth+woQJZGVlcckllzBq1Ch+9atfcd5559G9e3cmT57MwIEDmTx5MoMHD673tR966CHWrFnDgAEDeO211+jRo0dguzvuuIOsrCymTp0auHzu3Lnk5ORwxRVX0LVr1+r5U6ZM4bHHHmPw4MHVB6lTxYKOuDd12dnZri8MEmk6Nm/ezMUXX1xvu1Uff8GM5/OpqKw65oB1KM0Ip6fx9C1DuKbfuaey1FYjaEzMbIO7Z8e7Dm1BiEjKXNPvXP7+w+HcNKwHHdqGMIMObUPcNKwHf//hcIVDE6NbbYhISvXs1J5fjB/IL8YPbOxSpB7aghARkUAKCBERCaSAEBGRQDoGISKpta8I3n0SPnwFjpRCmw6QNRmumAln92ns6qQGbUGISOpsXQ6/uxLyF8CRrwCP/s5fEJ2/dflJrzo9PZ1BgwZV/8ydO/eEbWvfIfXBBx/kzTffPOnXPmr//v08/fTT1dOfffYZkyZNSni9jUXXQYhIwuK6DmJfUTQEKk58hTPhdnDXOye1JdGhQwdKS0vjajt9+nRycnKS/ua9fft2cnJy2LhxY1LXezKazHUQZjbGzD42s21mNidgeVszWxhb/p6Z9aq1vIeZlZrZT5JRj4g0Qe8+CZUnvtUEEF3+P08l9WXnzJlD//79ycrK4ic/+UngLbSnT5/OokWLgOhtve+77z4GDRpEdnY2+fn53HDDDVxwwQX8/ve/B6C0tJTRo0dX3/r7L3/5S/VrffLJJwwaNIjZs2ezfft2Bg6Mns5bXl7OrbfeSmZmJoMHD2bVqlVA9FbkEydOZMyYMfTt25ef/vSnSe1/IhI+BmFm6cBTwHVACbDezJa6e81vuLgN+NLdv2lmU4BHgRtrLJ8HvJ5oLSLShH34ClTVExBVFfDhQvjubxq8+qPft3DUfffdx7XXXsvixYv56KOPMDP279/PmWeeydixY+vcgujRowcFBQX86Ec/Yvr06bzzzjuUl5czcOBA7rzzTjIyMli8eDGnn346e/bs4bLLLmPs2LHMnTuXjRs3UlBQAHDMnVafeuopzIx//OMffPTRR1x//fVs2bIFgIKCAt5//33atm1Lv379uOeee+jevXuD/wbJloyD1MOAbe5eBGBmLwPjgJoBMQ7499jjRcCTZmbu7mY2Hvgn0PCvkRKR5uNIfLt/4m5Xy9HvW6gpEomQkZHBbbfdRk5OzjFfBlSXsWPHApCZmUlpaSkdO3akY8eOtG3blv3799O+fXvuv/9+1qxZQ1paGjt37mTXrl11rvPtt9+u/gKjiy66iJ49e1YHxOjRoznjjDMA6N+/Pzt27GgSAZGMXUznA8U1pkti8wLbuHsEOAB0MrMOwL1Avd94YWZ3mFmemeXVvIWviDQTbTrU36Yh7eIQCoVYt24dkyZNYtmyZYwZMyau5x29nXZaWlr146PTkUiEF154gd27d7NhwwYKCgro0qVLvbfojuf14NTfwrshGvsspn8HHnf3ej8yuPsz7p7t7tmdO3c+9ZWJSHJlTYa0cN1t0sKQdWPdbRqgtLSUAwcO8J3vfIfHH3+cDz74AEj8FtoHDhzg3HPPJRwOs2rVKnbs2FHveocPH179bXJbtmzh008/pV+/fiddQyokIyB2AjW3hbrF5gW2MbMQcAawF/gW8Csz2w78ELjfzGYmoSYRaWqumAnp9QREehguv/ukVn/0GMTRnzlz5vDVV1+Rk5NDVlYWV111FfPmzQMSv4X21KlTycvLIzMzkwULFnDRRRcB0KlTJ6688koGDhzI7Nmzj3nOjBkzqKqqIjMzkxtvvJHnnnvumC2Hpijh01xjb/hbgNFEg2A9cLO7F9ZoczeQ6e53xg5ST3T3ybXW8+9Aqbv/ur7X1GmuIk1LvLf7ZutyeGVa9Gylmges08LRcJi8APped+oKbUWaxGmusWMKM4E3gM3AK+5eaGY/N7OxsWZ/JHrMYRswCzjuVFgRaQX6Xhe9zmFoLrTtCGbR30Nzo/MVDk2KLpQTkYTFvQUhKdMktiBERKRlUkCIiEggBYSIiATS7b5FJKWKDxYzf9N8lhUt41DFIdqF25HTJ4fc/rl0P73xrx6Wf9EWhIikzNqStUz860T+vOXPlFWU4ThlFWX8ecufmfjXiawtWXvS6y4pKWHcuHH07duXCy64gB/84AccOXLkuHYjR45EJ7nERwEhIilRfLCYWatnUR4pJ+LH3koi4hHKI+XMWj2L4oPFJ1jDibk7EydOZPz48WzdupUtW7ZQWlrKAw88kKzyWyUFhIikxPxN84lU1n2PoUhlhAWbFjR43StXriQjI4Nbb70ViN7P6PHHH+dPf/oTZWVlTJkyhYsvvpgJEyZw+PDh6ue99NJLZGZmMnDgQO69997q+R06dGD27NkMGDCAa6+9lnXr1jFy5Ej69OnD0qVLG1xfc6WAEJGUWFa07Lgth9oiHmFZ0bIGr7uwsJChQ4ceM+/000+nR48e/OY3v6Fdu3Zs3ryZhx9+mA0bNgDRb3u79957WblyJQUFBaxfv54lS5YAUFZWxqhRoygsLKRjx4787Gc/Y/ny5SxevJgHH3ywwfU1VwoIEUmJQ3V9k1wNZRXJvfP/W2+9xS233AJAVlYWWVlZAKxfv56RI0fSuXNnQqEQU6dOZc2aNQC0adOm+s6vmZmZjBgxgnA4TGZm5jHf8dDSKSBEJCXahdvF1a59uH2D192/f//qLYOjDh48yKeffkoo1PCTNcPhMGYGHHvL76O3+24tFBAikhI5fXIIWd1v1iELkdMnvi/1qWn06NEcOnSIBQuixy8qKyv58Y9/zPTp0xkzZgwvvvgiABs3buTDDz8EYNiwYaxevZo9e/ZQWVnJSy+9xIgRIxr82i2ZAkJEUiK3fy6h9HoCIj3EtP7TGrxuM2Px4sW8+uqr9O3blwsvvJCMjAweeeQR7rrrLkpLS7n44ot58MEHq49VdO3alblz53LNNddwySWXMHToUMaNG3dSfWupdLM+EUlYvDfrW1uyllmrZxGpjBxzwDpkIULpIeaNmMfwbsNPZamthm7WJyLNyvBuw3nte68x6cJJdAh3wDA6hDsw6cJJvPa91xQOTYxutSEiKdX99O48cNkDPHCZLmJr6rQFISJJ0Rx3V7dUyRoLBYSIJCwjI4O9e/cqJJoAd2fv3r1kZGQkvC7tYhKRhHXr1o2SkhJ2797d2KUI0cDu1q1bwutRQIhIwsLhML17927sMiTJtItJREQCKSBERCSQAkJERAIpIEREJJACQkREAikgREQkkAJCREQCKSBERCSQAkJERAIpIEREJJACQkREAiUlIMxsjJl9bGbbzGxOwPK2ZrYwtvw9M+sVm3+dmW0ws3/Efo9KRj0iIpK4hAPCzNKBp4BvA/2Bm8ysf61mtwFfuvs3gceBR2Pz9wDfc/dMIBf4r0TrERGR5EjGFsQwYJu7F7n7EeBloPY3f48D5sceLwJGm5m5+/vu/llsfiFwmpm1TUJNIiKSoGQExPlAcY3pkti8wDbuHgEOAJ1qtfk3IN/dv05CTSIikqAm8X0QZjaA6G6n6+tocwdwB0CPHj1SVJmISOuVjC2InUD3GtPdYvMC25hZCDgD2Bub7gYsBqa5+ycnehF3f8bds909u3PnzkkoW0RE6pKMgFgP9DWz3mbWBpgCLK3VZinRg9AAk4CV7u5mdibw38Acd38nCbWIiEiSJBwQsWMKM4E3gM3AK+5eaGY/N7OxsWZ/BDqZ2TZgFnD0VNiZwDeBB82sIPZzbqI1iYhI4szdG7uGBsvOzva8vLzGLkNEpFkxsw3unh1ve11JLSIigRQQIiISSAEhIiKBFBAiIhJIASEiIoEUECIiEkgBISIigRQQIiISSAEhIiKBFBAiIhJIASEiIoEUECIiEkgBISIigRQQIiISSAEhIiKBFBAiIhJIASEiIoEUECIiEkgBISIigRQQIiISSAEhIiKBFBAiIhJIASEiIoEUECIiEkgBISIigRQQIiISSAEhIiKBFBAiIhJIASEiIoFCjV1AKqwvXMH8d37J+vAuDptxmjuXVnQh98oHuHTA6MYuT+K1rwjefRI+fAWOlEKbDpA1Ga6YCWf3CXzKjr1l/GFtEUve/4yyryO0bxti/OBv8P3hfejZqX2KO5BaxQeLmb9pPsuKlnGo4hDtwu3I6ZNDbv9cup/evbHLa5hWPPaNOY7m7qf0BU6F7Oxsz8vLi6vtgr89wm93vUjEIGJWPT/kTsjhni43M+0795+qUiVZti6HV6ZBZQVUVfxrfloY0sMweQH0ve6Yp6z6+AtmPJ9PRWUVkap//TsPpRnh9DSevmUI1/Q7N1U9SKm1JWuZtXoWkcoIEY9Uzw9ZiFB6iHkj5jG82/BGrLABWvHYJ3sczWyDu2fH2z4pu5jMbIyZfWxm28xsTsDytma2MLb8PTPrVWPZfbH5H5vZDcmo56j1hSv47a4XKU+zY8IBomFRnmb8dteLrC9ckcyXlWTbVxR9g6g4dOwbBESnKw5Fl+8rqp69Y28ZM57P53BF5TFvEACRKudwRSUzns9nx96yVPQgpYoPFjNr9SzKI+XHvKkARDxCeaScWatnUXywuJEqbIBWPPZNYRwTDggzSweeAr4N9AduMrP+tZrdBnzp7t8EHgcejT23PzAFGACMAZ6OrS8p5r/zSyJWd5uIwYJ3fpmsl5RT4d0no58e61JZAf/zVPXkH9YWUVFZVedTKiqreHbtP5NRYZMyf9N8IpWROttEKiMs2LQgRRUloBWPfVMYx2RsQQwDtrl7kbsfAV4GxtVqMw6YH3u8CBhtZhab/7K7f+3u/wS2xdaXFOvDu47bcqgtYsb68K5kvaScCh++cvynx9qqKuDDhdWTS97/7LhPj7VFqpzF7+9MRoVNyrKiZcd94qwt4hGWFS1LUUUJaMVj3xTGMRkBcT5QcxunJDYvsI27R4ADQKc4nwuAmd1hZnlmlrd79+64CjtcTzgcdSjOdtJIjpQ2uF3Z13X/x6pudyS+ds3JoYpDcbUrq2jau1iAVj32TWEcm81pru7+jLtnu3t2586d43rOaXEegG/XDA/UtyptOjS4Xfu28Z2g175NyzuRr124XVzt2oebwZk8rXjsm8I4JiMgdgI1z7XqFpsX2MbMQsAZwN44n3vSLq3oQqieN/9Q7JRXacKyJkfPWKlLWhiybqyeHD/4G4TS6t4yDKUZEwYHbrA2azl9cghZ3W9+IQuR0ycnRRUloBWPfVMYx2QExHqgr5n1NrM2RA86L63VZimQG3s8CVjp0fNrlwJTYmc59Qb6AuuSUBMAuVc+QKiejYOQw7QrH0jWS8qpcMXM6OmMdUkPw+V3V09+f3gfwul1//MOp6dx+/DeyaiwScntn0sovZ43lvQQ0/pPS1FFCWjFY98UxjHhgIgdU5gJvAFsBl5x90Iz+7mZjY01+yPQycy2AbOAObHnFgKvAJuAvwN3u3tlojUddemA0dzT5WYyqvy4LYmQOxlVzj1dbtbFck3d2X2i57qH2x3/aTItHJ0/ecExF0z17NSep28Zwmnh9OM+TYbSjNPC6Tx9y5BmdcFUvLqf3p15I+aREco47hNoyEJkhDKYN2Je87hYrhWPfVMYxxZ/oRxEr4dYELuS+pAZ7WK7labpSurmZV9R9HTGDxfWuJr2xuinxzqupn127T9Z/P5Oyo5EaN8mxITB53P78N5N/g0iUcUHi1mwaQHLipZRVlFG+3B7cvrkMK3/tOYRDjW14rFP5jg29EK5VhEQIiLSSFdSi4hIy6OAEBGRQAoIEREJpIAQEZFACggREQmkgBARkUAKCBERCaSAEBGRQAoIEREJpIAQEZFACggREQmkgBARkUAKCBERCaSAEBGRQAoIEREJpIAQEZFACggREQmkgBARkUAKCBERCaSAEBGRQAoIEREJpIAQEZFACggREQmkgBARkUAKCBERCaSAEBGRQAoIEREJpIAQEZFACggREQmUUECY2dlmttzMtsZ+n3WCdrmxNlvNLDc2r52Z/beZfWRmhWY2N5FaREQkuRLdgpgDrHD3vsCK2PQxzOxs4CHgW8Aw4KEaQfJrd78IGAxcaWbfTrAeERFJkkQDYhwwP/Z4PjA+oM0NwHJ33+fuXwLLgTHufsjdVwG4+xEgH+iWYD0iIpIkiQZEF3f/PPb4f4EuAW3OB4prTJfE5lUzszOB7xHdChERkSYgVF8DM3sTOC9g0QM1J9zdzcwbWoCZhYCXgP9096I62t0B3AHQo0ePhr6MiIg0UL0B4e7XnmiZme0ys67u/rmZdQW+CGi2ExhZY7ob8FaN6WeAre7+RD11PBNrS3Z2doODSEREGibRXUxLgdzY41zgLwFt3gCuN7OzYgenr4/Nw8z+AzgD+GGCdYiISJIlGhBzgevMbCtwbWwaM8s2s2cB3H0f8Atgfezn5+6+z8y6Ed1N1R/IN7MCM7s9wXpERCRJzL357a3Jzs72vLy8xi5DRKRZMbMN7p4db3tdSS0iIoEUECIiEkgBISIigRQQIiISSAEhIiKBFBAiIhJIASEiIoEUECIiEkgBISIigRQQIiISSAEhIiKBFBAiIhJIASEiIoEUECIiEkgBISIigRQQIiISSAEhIiKBFBAiIhJIASEiIoEUECIiEkgBISIigRQQIiISSAEhIiKBFBAiIhJIASEiIoEUECIiEkgBISIigRQQIiISSAEhIiKBFBAiIhJIASEiIoESCggzO9vMlpvZ1tjvs07QLjfWZquZ5QYsX2pmGxOpRUREkivRLYg5wAp37wusiE0fw8zOBh4CvgUMAx6qGSRmNhEoTbAOERFJskQDYhwwP/Z4PjA+oM0NwHJ33+fuXwLLgTEAZtYBmAX8R4J1iIhIkiUaEF3c/fPY4/8FugS0OR8orjFdEpsH8AvgN8Ch+l7IzO4wszwzy9u9e3cCJYuISDxC9TUwszeB8wIWPVBzwt3dzDzeFzazQcAF7v4jM+tVX3t3fwZ4BiA7Ozvu1xERkZNTb0C4+7UnWmZmu8ysq7t/bmZdgS8Cmu0ERtaY7ga8BVwOZJvZ9lgd55rZW+4+EhERaXSJ7mJaChw9KykX+EtAmzeA683srNjB6euBN9z9d+7+DXfvBVwFbFE4iIg0HYkGxFzgOjPbClwbm8bMss3sWQB330f0WMP62M/PY/NERKQJM/fmtzs/Ozvb8/LyGrsMEZFmxcw2uHt2vO11JbWIiARSQIiISCAFhIiIBFJAiIhIIAWEiIgEUkCIiEggBYSIiARSQIiISCAFhIiIBFJAiIhIIAWEiIgEUkCIiEggBYSIiARSQIiISCAFhIiIBFJAiIhIIAWEiIgEUkCIiEggBYSIiARSQIiISCAFhIiIBFJAiIhIIAWEiIgEUkCIiEggc/fGrqHBzGw3sOMkn34OsCeJ5TQnrbnv0Lr735r7Dq27/zX73tPdO8f7xGYZEIkwszx3z27sOhpDa+47tO7+t+a+Q+vufyJ91y4mEREJpIAQEZFArTEgnmnsAhpRa+47tO7+t+a+Q+vu/0n3vdUdgxARkfi0xi0IERGJgwJCREQCtdiAMLMxZvaxmW0zszkBy9ua2cLY8vfMrFfqqzw14uj7dDPbbWYFsZ/bG6POU8HM/mRmX5jZxhMsNzP7z9jf5kMzG5LqGk+VOPo+0swO1Bj3B1Nd46liZt3NbJWZbTKzQjP7QUCbljz28fS/4ePv7i3uB0gHPgH6AG2AD4D+tdrMAH4fezwFWNjYdaew79OBJxu71lPU/6uBIcDGEyz/DvA6YMBlwHuNXXMK+z4SWNbYdZ6ivncFhsQedwS2BPy7b8ljH0//Gzz+LXULYhiwzd2L3P0I8DIwrlabccD82ONFwGgzsxTWeKrE0/cWy93XAPvqaDIOWOBR/w8408y6pqa6UyuOvrdY7v65u+fHHn8FbAbOr9WsJY99PP1vsJYaEOcDxTWmSzj+j1Xdxt0jwAGgU0qqO7Xi6TvAv8U2sxeZWffUlNYkxPv3aakuN7MPzOx1MxvQ2MWcCrHdxYOB92otahVjX0f/oYHj31IDQur2V6CXu2cBy/nXlpS0bPlE78VzCfBbYEkj15N0ZtYB+DPwQ3c/2Nj1pFo9/W/w+LfUgNgJ1PxU3C02L7CNmYWAM4C9Kanu1Kq37+6+192/jk0+CwxNUW1NQTz/Nlokdz/o7qWxx38DwmZ2TiOXlTRmFib65viCu78W0KRFj319/T+Z8W+pAbEe6Gtmvc2sDdGD0EtrtVkK5MYeTwJWeuxITjNXb99r7XcdS3R/ZWuxFJgWO6PlMuCAu3/e2EWlgpmdd/Q4m5kNI/r/vyV8KCLWrz8Cm9193gmatdixj6f/JzP+oWQX2hS4e8TMZgJvED2r50/uXmhmPwfy3H0p0T/mf5nZNqIH9qY0XsXJE2ff/6+ZjQUiRPs+vdEKTjIze4no2RrnmFkJ8BAQBnD33wN/I3o2yzbgEHBr41SafHH0fRJwl5lFgMPAlBbyoQjgSuD/AP8ws4LYvPuBHtDyx574+t/g8detNkREJFBL3cUkIiIJUkCIiEggBYSIiARSQIiISCAFhIiIBFJAiIhIIAWEiIgE+v8XlbT44BGi/QAAAABJRU5ErkJggg==\n" - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "R = 0.2\n", - "Q = 0.2\n", - "N = 3\n", - "graphics_radius = 0.1\n", - "\n", - "odom = np.empty((N,1))\n", - "obs = np.empty((N,1))\n", - "x_true = np.empty((N,1))\n", - "\n", - "landmark = 3\n", - "# Simulated readings of odometry and observations\n", - "x_true[0], odom[0], obs[0] = 0.0, 0.0, 2.9\n", - "x_true[1], odom[1], obs[1] = 1.0, 1.5, 2.0\n", - "x_true[2], odom[2], obs[2] = 2.0, 2.4, 1.0\n", - "\n", - "hxDR = copy.deepcopy(odom)\n", - "# Visualization\n", - "plt.plot(landmark,0, '*k', markersize=30)\n", - "for i in range(N):\n", - " plt.plot(odom[i], 0, '.', markersize=50, alpha=0.8, color='steelblue')\n", - " plt.plot([odom[i], odom[i] + graphics_radius],\n", - " [0,0], 'r')\n", - " plt.text(odom[i], 0.02, \"X_{}\".format(i), fontsize=12)\n", - " plt.plot(obs[i]+odom[i],0,'.', markersize=25, color='brown')\n", - " plt.plot(x_true[i],0,'.g', markersize=20)\n", - "plt.grid() \n", - "plt.show()\n", - "\n", - "\n", - "# Defined as a function to facilitate iteration\n", - "def get_H_b(odom, obs):\n", - " \"\"\"\n", - " Create the information matrix and information vector. This implementation is \n", - " based on the concept of virtual measurement i.e. the observations of the\n", - " landmarks are converted into constraints (edges) between the nodes that\n", - " have observed this landmark.\n", - " \"\"\"\n", - " measure_constraints = {}\n", - " omegas = {}\n", - " zids = list(itertools.combinations(range(N),2))\n", - " H = np.zeros((N,N))\n", - " b = np.zeros((N,1))\n", - " for (t1, t2) in zids:\n", - " x1 = odom[t1]\n", - " x2 = odom[t2]\n", - " z1 = obs[t1]\n", - " z2 = obs[t2]\n", - " \n", - " # Adding virtual measurement constraint\n", - " measure_constraints[(t1,t2)] = (x2-x1-z1+z2)\n", - " omegas[(t1,t2)] = (1 / (2*Q))\n", - " \n", - " # populate system's information matrix and vector\n", - " H[t1,t1] += omegas[(t1,t2)]\n", - " H[t2,t2] += omegas[(t1,t2)]\n", - " H[t2,t1] -= omegas[(t1,t2)]\n", - " H[t1,t2] -= omegas[(t1,t2)]\n", - "\n", - " b[t1] += omegas[(t1,t2)] * measure_constraints[(t1,t2)]\n", - " b[t2] -= omegas[(t1,t2)] * measure_constraints[(t1,t2)]\n", - "\n", - " return H, b\n", - "\n", - "\n", - "H, b = get_H_b(odom, obs)\n", - "print(\"The determinant of H: \", np.linalg.det(H))\n", - "H[0,0] += 1 # np.inf ?\n", - "print(\"The determinant of H after anchoring constraint: \", np.linalg.det(H))\n", - "\n", - "for i in range(5):\n", - " H, b = get_H_b(odom, obs)\n", - " H[(0,0)] += 1\n", - " \n", - " # Recover the posterior over the path\n", - " dx = np.linalg.inv(H) @ b\n", - " odom += dx\n", - " # repeat till convergence\n", - "print(\"Running graphSLAM ...\") \n", - "print(\"Odometry values after optimzation: \\n\", odom)\n", - "\n", - "plt.figure()\n", - "plt.plot(x_true, np.zeros(x_true.shape), '.', markersize=20, label='Ground truth')\n", - "plt.plot(odom, np.zeros(x_true.shape), '.', markersize=20, label='Estimation')\n", - "plt.plot(hxDR, np.zeros(x_true.shape), '.', markersize=20, label='Odom')\n", - "plt.legend()\n", - "plt.grid()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "In particular, the tasks are split into 2 parts, graph construction, and graph optimization. \n", - "### Graph Construction\n", - "\n", - "Firstly the nodes are defined $\\boldsymbol{x} = \\boldsymbol{x}_{1:n}$ such that each node is the pose of the robot at time $t_i$\n", - "Secondly, the edges i.e. the constraints, are constructed according to the following conditions:\n", - "\n", - "* robot moves from $\\boldsymbol{x}_i$ to $\\boldsymbol{x}_j$. This edge corresponds to the odometry measurement. Relative motion constraints (Not included in the previous minimal example).\n", - "* Measurement constraints, this can be done in two ways:\n", - " * The information matrix is set in such a way that it includes the landmarks in the map as well. Then the constraints can be entered in a straightforward fashion between a node $\\boldsymbol{x}_i$ and some landmark $m_k$\n", - " * Through creating a virtual measurement among all the node that have observed the same landmark. More concretely, robot observes the same landmark from $\\boldsymbol{x}_i$ and $\\boldsymbol{x}_j$. Relative measurement constraint. The \"virtual measurement\" $\\boldsymbol{z}_{ij}$, which is the estimated pose of $\\boldsymbol{x}_j$ as seen from the node $\\boldsymbol{x}_i$. The virtual measurement can then be entered in the information matrix and vector in a similar fashion to the motion constraints.\n", - "\n", - "An edge is fully characterized by the values of the error (entry to information vector) and the local information matrix (entry to the system's information vector). The larger the local information matrix (lower $Q$ or $R$) the values that this edge will contribute with.\n", - "\n", - "Important Notes:\n", - "\n", - "* The addition to the information matrix and vector are added to the earlier values.\n", - "* In the case of 2D robot, the constraints will be non-linear, therefore, a Jacobian of the error w.r.t the states is needed when updated $H$ and $b$.\n", - "* The anchoring constraint is needed in order to avoid having a singular information matri.\n", - "\n", - "\n", - "### Graph Optimization\n", - "\n", - "The result from this formulation yields an overdetermined system of equations.\n", - "The goal after constructing the graph is to find: $x^* = \\underset{x}{\\mathrm{argmin}} ~ \\underset{ij} \\Sigma ~ f(e_{ij}) $, where $f$ is some error function that depends on the edges between to related nodes $i$ and $j$. The derivation in the references arrive at the solution for $x^* = H^{-1}b$ \n", - "\n", - "\n", - "### Planar Example:\n", - "\n", - "Now we will go through an example with a more realistic case of a 2D robot with 3DoF, namely, $[x, y, \\theta]^T$" - ] - }, - { - "cell_type": "code", - "execution_count": 13, - "metadata": { - "pycharm": { - "is_executing": false - } - }, - "outputs": [ - { - "data": { - "text/plain": "
", - "image/png": "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\n" - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "# Simulation parameter\n", - "Qsim = np.diag([0.01, np.deg2rad(0.010)])**2 # error added to range and bearing\n", - "Rsim = np.diag([0.1, np.deg2rad(1.0)])**2 # error added to [v, w]\n", - "\n", - "DT = 2.0 # time tick [s]\n", - "SIM_TIME = 100.0 # simulation time [s]\n", - "MAX_RANGE = 30.0 # maximum observation range\n", - "STATE_SIZE = 3 # State size [x,y,yaw]\n", - "\n", - "# TODO: Why not use Qsim ? \n", - "# Covariance parameter of Graph Based SLAM\n", - "C_SIGMA1 = 0.1\n", - "C_SIGMA2 = 0.1\n", - "C_SIGMA3 = np.deg2rad(1.0)\n", - "\n", - "MAX_ITR = 20 # Maximum iteration during optimization\n", - "timesteps = 1\n", - "\n", - "# consider only 2 landmarks for simplicity\n", - "# RFID positions [x, y, yaw]\n", - "RFID = np.array([[10.0, -2.0, 0.0],\n", - "# [15.0, 10.0, 0.0],\n", - "# [3.0, 15.0, 0.0],\n", - "# [-5.0, 20.0, 0.0],\n", - "# [-5.0, 5.0, 0.0]\n", - " ])\n", - "\n", - "# State Vector [x y yaw v]'\n", - "xTrue = np.zeros((STATE_SIZE, 1))\n", - "xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning\n", - "xTrue[2] = np.deg2rad(45)\n", - "xDR[2] = np.deg2rad(45)\n", - "# history initial values\n", - "hxTrue = xTrue\n", - "hxDR = xTrue\n", - "_, z, _, _ = observation(xTrue, xDR, np.array([[0,0]]).T, RFID)\n", - "hz = [z]\n", - "\n", - "for i in range(timesteps):\n", - " u = calc_input()\n", - " xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)\n", - " hxDR = np.hstack((hxDR, xDR))\n", - " hxTrue = np.hstack((hxTrue, xTrue))\n", - " hz.append(z)\n", - "\n", - "# visualize\n", - "graphics_radius = 0.3\n", - "plt.plot(RFID[:, 0], RFID[:, 1], \"*k\", markersize=20)\n", - "plt.plot(hxDR[0, :], hxDR[1, :], '.', markersize=50, alpha=0.8, label='Odom')\n", - "plt.plot(hxTrue[0, :], hxTrue[1, :], '.', markersize=20, alpha=0.6, label='X_true')\n", - "\n", - "for i in range(hxDR.shape[1]):\n", - " x = hxDR[0, i]\n", - " y = hxDR[1, i]\n", - " yaw = hxDR[2, i]\n", - " plt.plot([x, x + graphics_radius * np.cos(yaw)],\n", - " [y, y + graphics_radius * np.sin(yaw)], 'r')\n", - " d = hz[i][:, 0]\n", - " angle = hz[i][:, 1]\n", - " plt.plot([x + d * np.cos(angle + yaw)], [y + d * np.sin(angle + yaw)], '.',\n", - " markersize=20, alpha=0.7)\n", - " plt.legend()\n", - "plt.grid() \n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": 14, - "metadata": { - "pycharm": { - "is_executing": false - } - }, - "outputs": [], - "source": [ - "# Copy the data to have a consistent naming with the .py file\n", - "zlist = copy.deepcopy(hz)\n", - "x_opt = copy.deepcopy(hxDR)\n", - "xlist = copy.deepcopy(hxDR)\n", - "number_of_nodes = x_opt.shape[1]\n", - "n = number_of_nodes * STATE_SIZE" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "After the data has been saved, the graph will be constructed by looking at each pair for nodes. The virtual measurement is only created if two nodes have observed the same landmark at different points in time. The next cells are a walk through for a single iteration of graph construction -> optimization -> estimate update. " - ] - }, - { - "cell_type": "code", - "execution_count": 15, - "metadata": { - "pycharm": { - "is_executing": false - } - }, - "outputs": [ - { - "name": "stdout", - "text": [ - "Node combinations: \n", - " [(0, 1)]\n", - "Node 0 observed landmark with ID 0.0\n", - "Node 1 observed landmark with ID 0.0\n" - ], - "output_type": "stream" - } - ], - "source": [ - "# get all the possible combination of the different node\n", - "zids = list(itertools.combinations(range(len(zlist)), 2))\n", - "print(\"Node combinations: \\n\", zids)\n", - "\n", - "for i in range(xlist.shape[1]):\n", - " print(\"Node {} observed landmark with ID {}\".format(i, zlist[i][0, 3]))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "In the following code snippet the error based on the virtual measurement between node 0 and 1 will be created.\n", - "The equations for the error is as follows: \n", - "$e_{ij}^x = x_j + d_j cos(\\psi_j + \\theta_j) - x_i - d_i cos(\\psi_i + \\theta_i) $\n", - "\n", - "$e_{ij}^y = y_j + d_j sin(\\psi_j + \\theta_j) - y_i - d_i sin(\\psi_i + \\theta_i) $\n", - "\n", - "$e_{ij}^x = \\psi_j + \\theta_j - \\psi_i - \\theta_i $\n", - "\n", - "Where $[x_i, y_i, \\psi_i]$ is the pose for node $i$ and similarly for node $j$, $d$ is the measured distance at nodes $i$ and $j$, and $\\theta$ is the measured bearing to the landmark. The difference is visualized with the figure in the next cell.\n", - "\n", - "In case of perfect motion and perfect measurement the error shall be zero since $ x_j + d_j cos(\\psi_j + \\theta_j)$ should equal $x_i + d_i cos(\\psi_i + \\theta_i)$" - ] - }, - { - "cell_type": "code", - "execution_count": 16, - "metadata": { - "pycharm": { - "is_executing": false - } - }, - "outputs": [ - { - "name": "stdout", - "text": [ - "0.0 1.427649841628278 -2.0126109674819155 -3.524048014922737\n", - "For nodes (0, 1)\n", - "Added edge with errors: \n", - " [[-0.02 ]\n", - " [-0.084]\n", - " [ 0. ]]\n" - ], - "output_type": "stream" - }, - { - "data": { - "text/plain": "
", - "image/png": "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\n" - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "# Initialize edges list\n", - "edges = []\n", - "\n", - "# Go through all the different combinations\n", - "for (t1, t2) in zids:\n", - " x1, y1, yaw1 = xlist[0, t1], xlist[1, t1], xlist[2, t1]\n", - " x2, y2, yaw2 = xlist[0, t2], xlist[1, t2], xlist[2, t2]\n", - " \n", - " # All nodes have valid observation with ID=0, therefore, no data association condition\n", - " iz1 = 0\n", - " iz2 = 0\n", - " \n", - " d1 = zlist[t1][iz1, 0]\n", - " angle1, phi1 = zlist[t1][iz1, 1], zlist[t1][iz1, 2]\n", - " d2 = zlist[t2][iz2, 0]\n", - " angle2, phi2 = zlist[t2][iz2, 1], zlist[t2][iz2, 2]\n", - " \n", - " # find angle between observation and horizontal \n", - " tangle1 = pi_2_pi(yaw1 + angle1)\n", - " tangle2 = pi_2_pi(yaw2 + angle2)\n", - " \n", - " # project the observations \n", - " tmp1 = d1 * math.cos(tangle1)\n", - " tmp2 = d2 * math.cos(tangle2)\n", - " tmp3 = d1 * math.sin(tangle1)\n", - " tmp4 = d2 * math.sin(tangle2)\n", - " \n", - " edge = Edge()\n", - " print(y1,y2, tmp3, tmp4)\n", - " # calculate the error of the virtual measurement\n", - " # node 1 as seen from node 2 throught the observations 1,2\n", - " edge.e[0, 0] = x2 - x1 - tmp1 + tmp2\n", - " edge.e[1, 0] = y2 - y1 - tmp3 + tmp4\n", - " edge.e[2, 0] = pi_2_pi(yaw2 - yaw1 - tangle1 + tangle2)\n", - "\n", - " edge.d1, edge.d2 = d1, d2\n", - " edge.yaw1, edge.yaw2 = yaw1, yaw2\n", - " edge.angle1, edge.angle2 = angle1, angle2\n", - " edge.id1, edge.id2 = t1, t2\n", - " \n", - " edges.append(edge)\n", - " \n", - " print(\"For nodes\",(t1,t2))\n", - " print(\"Added edge with errors: \\n\", edge.e)\n", - " \n", - " # Visualize measurement projections\n", - " plt.plot(RFID[0, 0], RFID[0, 1], \"*k\", markersize=20)\n", - " plt.plot([x1,x2],[y1,y2], '.', markersize=50, alpha=0.8)\n", - " plt.plot([x1, x1 + graphics_radius * np.cos(yaw1)],\n", - " [y1, y1 + graphics_radius * np.sin(yaw1)], 'r')\n", - " plt.plot([x2, x2 + graphics_radius * np.cos(yaw2)],\n", - " [y2, y2 + graphics_radius * np.sin(yaw2)], 'r')\n", - " \n", - " plt.plot([x1,x1+tmp1], [y1,y1], label=\"obs 1 x\")\n", - " plt.plot([x2,x2+tmp2], [y2,y2], label=\"obs 2 x\")\n", - " plt.plot([x1,x1], [y1,y1+tmp3], label=\"obs 1 y\")\n", - " plt.plot([x2,x2], [y2,y2+tmp4], label=\"obs 2 y\")\n", - " plt.plot(x1+tmp1, y1+tmp3, 'o')\n", - " plt.plot(x2+tmp2, y2+tmp4, 'o')\n", - "plt.legend()\n", - "plt.grid()\n", - "plt.show()" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "Since the constraints equations derived before are non-linear, linearization is needed before we can insert them into the information matrix and information vector. Two jacobians \n", - "\n", - "$A = \\frac{\\partial e_{ij}}{\\partial \\boldsymbol{x}_i}$ as $\\boldsymbol{x}_i$ holds the three variabls x, y, and theta.\n", - "Similarly, \n", - "$B = \\frac{\\partial e_{ij}}{\\partial \\boldsymbol{x}_j}$ " - ] - }, - { - "cell_type": "code", - "execution_count": 17, - "metadata": { - "pycharm": { - "is_executing": false - } - }, - "outputs": [ - { - "name": "stdout", - "text": [ - "The determinant of H: 0.0\n", - "The determinant of H after origin constraint: 716.1972439134893\n" - ], - "output_type": "stream" - }, - { - "data": { - "text/plain": "
", - "image/png": "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\n" - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - }, - { - "data": { - "text/plain": "
", - "image/png": "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\n" - }, - "metadata": { - "needs_background": "light" - }, - "output_type": "display_data" - } - ], - "source": [ - "# Initialize the system information matrix and information vector\n", - "H = np.zeros((n, n))\n", - "b = np.zeros((n, 1))\n", - "x_opt = copy.deepcopy(hxDR)\n", - "\n", - "for edge in edges:\n", - " id1 = edge.id1 * STATE_SIZE\n", - " id2 = edge.id2 * STATE_SIZE\n", - " \n", - " t1 = edge.yaw1 + edge.angle1\n", - " A = np.array([[-1.0, 0, edge.d1 * math.sin(t1)],\n", - " [0, -1.0, -edge.d1 * math.cos(t1)],\n", - " [0, 0, -1.0]])\n", - "\n", - " t2 = edge.yaw2 + edge.angle2\n", - " B = np.array([[1.0, 0, -edge.d2 * math.sin(t2)],\n", - " [0, 1.0, edge.d2 * math.cos(t2)],\n", - " [0, 0, 1.0]])\n", - " \n", - " # TODO: use Qsim instead of sigma\n", - " sigma = np.diag([C_SIGMA1, C_SIGMA2, C_SIGMA3])\n", - " Rt1 = calc_rotational_matrix(tangle1)\n", - " Rt2 = calc_rotational_matrix(tangle2)\n", - " edge.omega = np.linalg.inv(Rt1 @ sigma @ Rt1.T + Rt2 @ sigma @ Rt2.T)\n", - "\n", - " # Fill in entries in H and b\n", - " H[id1:id1 + STATE_SIZE, id1:id1 + STATE_SIZE] += A.T @ edge.omega @ A\n", - " H[id1:id1 + STATE_SIZE, id2:id2 + STATE_SIZE] += A.T @ edge.omega @ B\n", - " H[id2:id2 + STATE_SIZE, id1:id1 + STATE_SIZE] += B.T @ edge.omega @ A\n", - " H[id2:id2 + STATE_SIZE, id2:id2 + STATE_SIZE] += B.T @ edge.omega @ B\n", - "\n", - " b[id1:id1 + STATE_SIZE] += (A.T @ edge.omega @ edge.e)\n", - " b[id2:id2 + STATE_SIZE] += (B.T @ edge.omega @ edge.e)\n", - " \n", - "\n", - "print(\"The determinant of H: \", np.linalg.det(H))\n", - "plt.figure()\n", - "plt.subplot(1,2,1)\n", - "plt.imshow(H, extent=[0, n, 0, n])\n", - "plt.subplot(1,2,2)\n", - "plt.imshow(b, extent=[0, 1, 0, n])\n", - "plt.show() \n", - "\n", - "# Fix the origin, multiply by large number gives same results but better visualization\n", - "H[0:STATE_SIZE, 0:STATE_SIZE] += np.identity(STATE_SIZE)\n", - "print(\"The determinant of H after origin constraint: \", np.linalg.det(H)) \n", - "plt.figure()\n", - "plt.subplot(1,2,1)\n", - "plt.imshow(H, extent=[0, n, 0, n])\n", - "plt.subplot(1,2,2)\n", - "plt.imshow(b, extent=[0, 1, 0, n])\n", - "plt.show()" - ] - }, - { - "cell_type": "code", - "execution_count": 18, - "metadata": { - "pycharm": { - "is_executing": false - } - }, - "outputs": [ - { - "name": "stdout", - "text": [ - "dx: \n", - " [[-0. ]\n", - " [-0. ]\n", - " [ 0. ]\n", - " [ 0.02 ]\n", - " [ 0.084]\n", - " [-0. ]]\n", - "ground truth: \n", - " [[0. 1.414]\n", - " [0. 1.414]\n", - " [0.785 0.985]]\n", - "Odom: \n", - " [[0. 1.428]\n", - " [0. 1.428]\n", - " [0.785 0.976]]\n", - "SLAM: \n", - " [[-0. 1.448]\n", - " [-0. 1.512]\n", - " [ 0.785 0.976]]\n", - "\n", - "graphSLAM localization error: 0.010729072751057656\n", - "Odom localization error: 0.0004460978857535104\n" - ], - "output_type": "stream" - } - ], - "source": [ - "# Find the solution (first iteration)\n", - "dx = - np.linalg.inv(H) @ b\n", - "for i in range(number_of_nodes):\n", - " x_opt[0:3, i] += dx[i * 3:i * 3 + 3, 0]\n", - "print(\"dx: \\n\",dx)\n", - "print(\"ground truth: \\n \",hxTrue)\n", - "print(\"Odom: \\n\", hxDR)\n", - "print(\"SLAM: \\n\", x_opt)\n", - "\n", - "# performance will improve with more iterations, nodes and landmarks.\n", - "print(\"\\ngraphSLAM localization error: \", np.sum((x_opt - hxTrue) ** 2))\n", - "print(\"Odom localization error: \", np.sum((hxDR - hxTrue) ** 2))" - ] - }, - { - "cell_type": "markdown", - "metadata": {}, - "source": [ - "### The references:\n", - "\n", - "\n", - "* http://robots.stanford.edu/papers/thrun.graphslam.pdf\n", - "\n", - "* http://ais.informatik.uni-freiburg.de/teaching/ss13/robotics/slides/16-graph-slam.pdf\n", - "\n", - "* http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf\n", - "\n", - "N.B.\n", - "An additional step is required that uses the estimated path to update the belief regarding the map." - ] - }, - { - "cell_type": "code", - "execution_count": 18, - "metadata": { - "pycharm": { - "is_executing": false - } - }, - "outputs": [], - "source": [] - } - ], - "metadata": { - "kernelspec": { - "display_name": "Python 3", - "language": "python", - "name": "python3" - }, - "language_info": { - "codemirror_mode": { - "name": "ipython", - "version": 3 - }, - "file_extension": ".py", - "mimetype": "text/x-python", - "name": "python", - "nbconvert_exporter": "python", - "pygments_lexer": "ipython3", - "version": "3.6.5" - }, - "pycharm": { - "stem_cell": { - "cell_type": "raw", - "source": [], - "metadata": { - "collapsed": false - } - } - } - }, - "nbformat": 4, - "nbformat_minor": 2 -} \ No newline at end of file diff --git a/docs/how_to_contribute_main.rst b/docs/how_to_contribute_main.rst index c761fd9928..a4ac3c819b 100644 --- a/docs/how_to_contribute_main.rst +++ b/docs/how_to_contribute_main.rst @@ -1,4 +1,4 @@ -How to contribute +How To Contribute ================= This document describes how to contribute this project. diff --git a/docs/modules/path_planning/Bezier_path_planning/Figure_1.png b/docs/modules/path_planning/bezier_path_planning/Figure_1.png similarity index 100% rename from docs/modules/path_planning/Bezier_path_planning/Figure_1.png rename to docs/modules/path_planning/bezier_path_planning/Figure_1.png diff --git a/docs/modules/path_planning/Bezier_path_planning/Figure_2.png b/docs/modules/path_planning/bezier_path_planning/Figure_2.png similarity index 100% rename from docs/modules/path_planning/Bezier_path_planning/Figure_2.png rename to docs/modules/path_planning/bezier_path_planning/Figure_2.png diff --git a/PathPlanning/BSplinePath/Figure_1.png b/docs/modules/path_planning/bspline_path/Figure_1.png similarity index 100% rename from PathPlanning/BSplinePath/Figure_1.png rename to docs/modules/path_planning/bspline_path/Figure_1.png diff --git a/PathPlanning/ClosedLoopRRTStar/Figure_1.png b/docs/modules/path_planning/closed_loop_rrt_star_car/Figure_1.png similarity index 100% rename from PathPlanning/ClosedLoopRRTStar/Figure_1.png rename to docs/modules/path_planning/closed_loop_rrt_star_car/Figure_1.png diff --git a/PathPlanning/ClosedLoopRRTStar/Figure_3.png b/docs/modules/path_planning/closed_loop_rrt_star_car/Figure_3.png similarity index 100% rename from PathPlanning/ClosedLoopRRTStar/Figure_3.png rename to docs/modules/path_planning/closed_loop_rrt_star_car/Figure_3.png diff --git a/PathPlanning/ClosedLoopRRTStar/Figure_4.png b/docs/modules/path_planning/closed_loop_rrt_star_car/Figure_4.png similarity index 100% rename from PathPlanning/ClosedLoopRRTStar/Figure_4.png rename to docs/modules/path_planning/closed_loop_rrt_star_car/Figure_4.png diff --git a/PathPlanning/ClosedLoopRRTStar/Figure_5.png b/docs/modules/path_planning/closed_loop_rrt_star_car/Figure_5.png similarity index 100% rename from PathPlanning/ClosedLoopRRTStar/Figure_5.png rename to docs/modules/path_planning/closed_loop_rrt_star_car/Figure_5.png diff --git a/PathPlanning/CubicSpline/Figure_1.png b/docs/modules/path_planning/cubic_spline/Figure_1.png similarity index 100% rename from PathPlanning/CubicSpline/Figure_1.png rename to docs/modules/path_planning/cubic_spline/Figure_1.png diff --git a/PathPlanning/CubicSpline/Figure_2.png b/docs/modules/path_planning/cubic_spline/Figure_2.png similarity index 100% rename from PathPlanning/CubicSpline/Figure_2.png rename to docs/modules/path_planning/cubic_spline/Figure_2.png diff --git a/PathPlanning/CubicSpline/Figure_3.png b/docs/modules/path_planning/cubic_spline/Figure_3.png similarity index 100% rename from PathPlanning/CubicSpline/Figure_3.png rename to docs/modules/path_planning/cubic_spline/Figure_3.png diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable.png b/docs/modules/path_planning/model_predictive_trajectry_generator/lookuptable.png similarity index 100% rename from PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable.png rename to docs/modules/path_planning/model_predictive_trajectry_generator/lookuptable.png diff --git a/docs/modules/path_planning/path_planning_main.rst b/docs/modules/path_planning/path_planning_main.rst index d284c4e06d..8033e1a875 100644 --- a/docs/modules/path_planning/path_planning_main.rst +++ b/docs/modules/path_planning/path_planning_main.rst @@ -11,7 +11,7 @@ This is a 2D navigation sample code with Dynamic Window Approach. - `The Dynamic Window Approach to Collision Avoidance `__ -|DWA| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DynamicWindowApproach/animation.gif Grid based search ----------------- @@ -22,7 +22,7 @@ Dijkstra algorithm This is a 2D grid based shortest path planning with Dijkstra's algorithm. -|Dijkstra| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Dijkstra/animation.gif In the animation, cyan points are searched nodes. @@ -33,7 +33,7 @@ A\* algorithm This is a 2D grid based shortest path planning with A star algorithm. -|astar| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/AStar/animation.gif In the animation, cyan points are searched nodes. @@ -46,7 +46,7 @@ D\* algorithm This is a 2D grid based shortest path planning with D star algorithm. -|dstar| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DStar/animation.gif The animation shows a robot finding its path avoiding an obstacle using the D* search algorithm. @@ -59,7 +59,7 @@ Potential Field algorithm This is a 2D grid based path planning with Potential Field algorithm. -|PotentialField| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/PotentialFieldPlanning/animation.gif In the animation, the blue heat map shows potential value on each grid. @@ -79,12 +79,12 @@ This algorithm is used for state lattice planner. Path optimization sample ~~~~~~~~~~~~~~~~~~~~~~~~ -|4| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ModelPredictiveTrajectoryGenerator/kn05animation.gif Lookup table generation sample ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -|5| +.. image:: model_predictive_trajectry_generator/lookuptable.png Ref: @@ -92,8 +92,6 @@ Ref: robots `__ - - State Lattice Planning ---------------------- @@ -114,24 +112,24 @@ Ref: Uniform polar sampling ~~~~~~~~~~~~~~~~~~~~~~ -|6| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/UniformPolarSampling.gif Biased polar sampling ~~~~~~~~~~~~~~~~~~~~~ -|7| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/BiasedPolarSampling.gif Lane sampling ~~~~~~~~~~~~~ -|8| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/LaneSampling.gif .. _probabilistic-road-map-(prm)-planning: Probabilistic Road-Map (PRM) planning ------------------------------------- -|PRM| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ProbabilisticRoadMap/animation.gif This PRM planner uses Dijkstra method for graph search. @@ -151,7 +149,7 @@ Ref: Voronoi Road-Map planning ------------------------- -|VRM| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/VoronoiRoadMap/animation.gif This Voronoi road-map planner uses Dijkstra method for graph search. @@ -174,7 +172,7 @@ Rapidly-Exploring Random Trees (RRT) Basic RRT ~~~~~~~~~ -|9| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRT/animation.gif This is a simple path planning code with Rapidly-Exploring Random Trees (RRT) @@ -188,7 +186,7 @@ are start and goal positions. RRT with dubins path ~~~~~~~~~~~~~~~~~~~~ -|PythonRobotics| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTDubins/animation.gif Path planning for a car robot with RRT and dubins path planner. @@ -197,7 +195,7 @@ Path planning for a car robot with RRT and dubins path planner. RRT\* with dubins path ~~~~~~~~~~~~~~~~~~~~~~ -|AtsushiSakai/PythonRobotics| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarDubins/animation.gif Path planning for a car robot with RRT\* and dubins path planner. @@ -206,7 +204,7 @@ Path planning for a car robot with RRT\* and dubins path planner. RRT\* with reeds-sheep path ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -|11| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarReedsShepp/animation.gif Path planning for a car robot with RRT\* and reeds sheep path planner. @@ -215,7 +213,7 @@ Path planning for a car robot with RRT\* and reeds sheep path planner. Informed RRT\* ~~~~~~~~~~~~~~ -|irrt| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/InformedRRTStar/animation.gif This is a path planning code with Informed RRT*. @@ -232,7 +230,7 @@ Ref: Batch Informed RRT\* ~~~~~~~~~~~~~~~~~~~~ -|irrt2| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BatchInformedRRTStar/animation.gif This is a path planning code with Batch Informed RRT*. @@ -249,7 +247,7 @@ Closed Loop RRT\* A vehicle model based path planning with closed loop RRT*. -|CLRRT| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClosedLoopRRTStar/animation.gif In this code, pure-pursuit algorithm is used for steering control, @@ -275,7 +273,7 @@ This is a path planning simulation with LQR-RRT*. A double integrator motion model is used for LQR local planner. -|LQRRRT| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRRRTStar/animation.gif Ref: @@ -297,14 +295,14 @@ with cubic spline. Heading angle of each point can be also calculated analytically. -|12| -|13| -|14| +.. image:: cubic_spline/Figure_1.png +.. image:: cubic_spline/Figure_2.png +.. image:: cubic_spline/Figure_3.png B-Spline planning ----------------- -|B-Spline| +.. image:: bspline_path/Figure_1.png This is a path planning with B-Spline curse. @@ -321,7 +319,7 @@ Ref: Eta^3 Spline path planning -------------------------- -|eta3| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Eta3SplinePath/animation.gif This is a path planning with Eta^3 spline. @@ -360,7 +358,7 @@ Dubins path planning A sample code for Dubins path planning. -|dubins| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DubinsPath/animation.gif?raw=True Ref: @@ -372,7 +370,7 @@ Reeds Shepp planning A sample code with Reeds Shepp path planning. -|RSPlanning| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ReedsSheppPath/animation.gif?raw=true Ref: @@ -390,12 +388,12 @@ LQR based path planning A sample code using LQR based path planning for double integrator model. -|RSPlanning2| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRPlanner/animation.gif?raw=true Optimal Trajectory in a Frenet Frame ------------------------------------ -|15| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/animation.gif This is optimal trajectory generation in a Frenet Frame. @@ -412,35 +410,3 @@ Ref: - `Optimal trajectory generation for dynamic street scenarios in a Frenet Frame `__ -.. |DWA| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DynamicWindowApproach/animation.gif -.. |Dijkstra| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Dijkstra/animation.gif -.. |astar| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/AStar/animation.gif -.. |dstar| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DStar/animation.gif -.. |PotentialField| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/PotentialFieldPlanning/animation.gif -.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ModelPredictiveTrajectoryGenerator/kn05animation.gif -.. |5| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/ModelPredictiveTrajectoryGenerator/lookuptable.png?raw=True -.. |6| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/UniformPolarSampling.gif -.. |7| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/BiasedPolarSampling.gif -.. |8| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/LaneSampling.gif -.. |PRM| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ProbabilisticRoadMap/animation.gif -.. |VRM| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/VoronoiRoadMap/animation.gif -.. |9| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRT/animation.gif -.. |10| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTstar/animation.gif -.. |PythonRobotics| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTDubins/animation.gif -.. |AtsushiSakai/PythonRobotics| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarDubins/animation.gif -.. |11| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarReedsShepp/animation.gif -.. |irrt| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/InformedRRTStar/animation.gif -.. |irrt2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BatchInformedRRTStar/animation.gif -.. |CLRRT| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClosedLoopRRTStar/animation.gif -.. |LQRRRT| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRRRTStar/animation.gif -.. |12| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/CubicSpline/Figure_1.png?raw=True -.. |13| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/CubicSpline/Figure_2.png?raw=True -.. |14| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/CubicSpline/Figure_3.png?raw=True -.. |B-Spline| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/BSplinePath/Figure_1.png?raw=True -.. |eta3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Eta3SplinePath/animation.gif -.. |Bezier1| image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/PathPlanning/BezierPath/Figure_1.png?raw=True -.. |2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/QuinticPolynomialsPlanner/animation.gif -.. |dubins| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DubinsPath/animation.gif?raw=True -.. |RSPlanning| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ReedsSheppPath/animation.gif?raw=true -.. |RSPlanning2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRPlanner/animation.gif?raw=true -.. |15| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/animation.gif diff --git a/docs/modules/path_planning/quintic_polynomials_planner.rst b/docs/modules/path_planning/quintic_polynomials_planner.rst index 2fab8a51ab..2bced07034 100644 --- a/docs/modules/path_planning/quintic_polynomials_planner.rst +++ b/docs/modules/path_planning/quintic_polynomials_planner.rst @@ -4,7 +4,7 @@ Quintic polynomials planning Motion planning with quintic polynomials. -|2| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/QuinticPolynomialsPlanner/animation.gif It can calculate 2D path, velocity, and acceleration profile based on quintic polynomials. diff --git a/PathPlanning/RRT/figure_1.png b/docs/modules/path_planning/rrt/figure_1.png similarity index 100% rename from PathPlanning/RRT/figure_1.png rename to docs/modules/path_planning/rrt/figure_1.png diff --git a/PathPlanning/RRTStarReedsShepp/figure_1.png b/docs/modules/path_planning/rrt_star_reeds_shepp/figure_1.png similarity index 100% rename from PathPlanning/RRTStarReedsShepp/figure_1.png rename to docs/modules/path_planning/rrt_star_reeds_shepp/figure_1.png diff --git a/PathPlanning/StateLatticePlanner/Figure_1.png b/docs/modules/path_planning/state_lattice_pathplanner/Figure_1.png similarity index 100% rename from PathPlanning/StateLatticePlanner/Figure_1.png rename to docs/modules/path_planning/state_lattice_pathplanner/Figure_1.png diff --git a/PathPlanning/StateLatticePlanner/Figure_2.png b/docs/modules/path_planning/state_lattice_pathplanner/Figure_2.png similarity index 100% rename from PathPlanning/StateLatticePlanner/Figure_2.png rename to docs/modules/path_planning/state_lattice_pathplanner/Figure_2.png diff --git a/PathPlanning/StateLatticePlanner/Figure_3.png b/docs/modules/path_planning/state_lattice_pathplanner/Figure_3.png similarity index 100% rename from PathPlanning/StateLatticePlanner/Figure_3.png rename to docs/modules/path_planning/state_lattice_pathplanner/Figure_3.png diff --git a/PathPlanning/StateLatticePlanner/Figure_4.png b/docs/modules/path_planning/state_lattice_pathplanner/Figure_4.png similarity index 100% rename from PathPlanning/StateLatticePlanner/Figure_4.png rename to docs/modules/path_planning/state_lattice_pathplanner/Figure_4.png diff --git a/PathPlanning/StateLatticePlanner/Figure_5.png b/docs/modules/path_planning/state_lattice_pathplanner/Figure_5.png similarity index 100% rename from PathPlanning/StateLatticePlanner/Figure_5.png rename to docs/modules/path_planning/state_lattice_pathplanner/Figure_5.png diff --git a/PathPlanning/StateLatticePlanner/Figure_6.png b/docs/modules/path_planning/state_lattice_pathplanner/Figure_6.png similarity index 100% rename from PathPlanning/StateLatticePlanner/Figure_6.png rename to docs/modules/path_planning/state_lattice_pathplanner/Figure_6.png diff --git a/docs/modules/path_tracking/path_tracking_main.rst b/docs/modules/path_tracking/path_tracking_main.rst index 3f86da0b07..725e4f04b4 100644 --- a/docs/modules/path_tracking/path_tracking_main.rst +++ b/docs/modules/path_tracking/path_tracking_main.rst @@ -1,6 +1,6 @@ .. _path_tracking: -Path tracking +Path Tracking ============= move to a pose control From f8f10a3ec8421bd9fd2b826716fbff97f5c2f32f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 28 Nov 2021 08:13:28 +0900 Subject: [PATCH 426/940] Adding all gifs to the doc (#584) * update docs * update docs --- docs/index_main.rst | 1 + .../aerial_navigation/aerial_navigation_main.rst | 10 ++-------- .../drone_3d_trajectory_following.rst | 6 ++++++ .../rocket_powered_landing.rst | 0 docs/modules/bipedal/bipedal_main.rst | 7 +++++++ .../bipedal/bipedal_planner/bipedal_planner.rst | 6 ++++++ 6 files changed, 22 insertions(+), 8 deletions(-) create mode 100644 docs/modules/aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following.rst rename docs/modules/aerial_navigation/{ => rocket_powered_landing}/rocket_powered_landing.rst (100%) create mode 100644 docs/modules/bipedal/bipedal_main.rst create mode 100644 docs/modules/bipedal/bipedal_planner/bipedal_planner.rst diff --git a/docs/index_main.rst b/docs/index_main.rst index 7cdbddc71f..128a50a58e 100644 --- a/docs/index_main.rst +++ b/docs/index_main.rst @@ -42,6 +42,7 @@ See this paper for more details: modules/path_tracking/path_tracking modules/arm_navigation/arm_navigation modules/aerial_navigation/aerial_navigation + modules/bipedal/bipedal modules/appendix/appendix how_to_contribute diff --git a/docs/modules/aerial_navigation/aerial_navigation_main.rst b/docs/modules/aerial_navigation/aerial_navigation_main.rst index e072707acc..ea6c4c8e30 100644 --- a/docs/modules/aerial_navigation/aerial_navigation_main.rst +++ b/docs/modules/aerial_navigation/aerial_navigation_main.rst @@ -3,12 +3,6 @@ Aerial Navigation ================= -Drone 3d trajectory following ------------------------------ - -This is a 3d trajectory following simulation for a quadrotor. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/drone_3d_trajectory_following/animation.gif - -.. include:: rocket_powered_landing.rst +.. include:: drone_3d_trajectory_following/drone_3d_trajectory_following.rst +.. include:: rocket_powered_landing/rocket_powered_landing.rst diff --git a/docs/modules/aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following.rst b/docs/modules/aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following.rst new file mode 100644 index 0000000000..c3bdc33cdc --- /dev/null +++ b/docs/modules/aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following.rst @@ -0,0 +1,6 @@ +Drone 3d trajectory following +----------------------------- + +This is a 3d trajectory following simulation for a quadrotor. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/drone_3d_trajectory_following/animation.gif diff --git a/docs/modules/aerial_navigation/rocket_powered_landing.rst b/docs/modules/aerial_navigation/rocket_powered_landing/rocket_powered_landing.rst similarity index 100% rename from docs/modules/aerial_navigation/rocket_powered_landing.rst rename to docs/modules/aerial_navigation/rocket_powered_landing/rocket_powered_landing.rst diff --git a/docs/modules/bipedal/bipedal_main.rst b/docs/modules/bipedal/bipedal_main.rst new file mode 100644 index 0000000000..bab316b0d9 --- /dev/null +++ b/docs/modules/bipedal/bipedal_main.rst @@ -0,0 +1,7 @@ +.. _bipedal: + +Bipedal +================= + +.. include:: bipedal_planner/bipedal_planner.rst + diff --git a/docs/modules/bipedal/bipedal_planner/bipedal_planner.rst b/docs/modules/bipedal/bipedal_planner/bipedal_planner.rst new file mode 100644 index 0000000000..2ee5971e7a --- /dev/null +++ b/docs/modules/bipedal/bipedal_planner/bipedal_planner.rst @@ -0,0 +1,6 @@ +Bipedal Planner +----------------------------- + +Bipedal Walking with modifying designated footsteps + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Bipedal/bipedal_planner/animation.gif From c99716d6920300b1ae0f49652f06db97d0621d63 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 28 Nov 2021 16:00:02 +0900 Subject: [PATCH 427/940] Adding all gifs to the doc 2 (#585) * update docs * update docs * update docs --- .github/workflows/Linux_CI.yml | 2 +- .github/workflows/MacOS_CI.yml | 2 +- .../inverted_pendulum_mpc_control.py | 0 {InvertedPendulumCart => Control}/__init__.py | 0 docs/index_main.rst | 1 + docs/modules/control/control_main.rst | 7 ++ .../inverted_pendulum_mpc_control.rst | 6 ++ docs/modules/introduction_main.rst | 39 +++++++- .../ensamble_kalman_filter_localization.rst | 7 ++ .../extended_kalman_filter_localization.rst | 1 - .../histogram_filter_localization.rst | 22 +++++ .../localization/localization_main.rst | 88 +----------------- .../particle_filter_localization.rst | 37 ++++++++ .../unscented_kalman_filter_localization.rst | 13 +++ .../mapping/circle_fitting/circle_fitting.rst | 13 +++ .../gaussian_grid_map/gaussian_grid_map.rst | 6 ++ .../k_means_object_clustering.rst | 6 ++ .../grid_map_example.png | Bin .../lidar_to_grid_map_tutorial.rst | 17 ++-- .../lidar_to_grid_map_tutorial_12_0.png | Bin .../lidar_to_grid_map_tutorial_14_1.png | Bin .../lidar_to_grid_map_tutorial_5_0.png | Bin .../lidar_to_grid_map_tutorial_7_0.png | Bin .../lidar_to_grid_map_tutorial_8_0.png | Bin docs/modules/mapping/mapping_main.rst | 51 ++-------- .../ray_casting_grid_map.rst | 6 ++ .../rectangle_fitting/rectangle_fitting.rst | 7 ++ tests/test_inverted_pendulum_mpc_control.py | 2 +- 28 files changed, 193 insertions(+), 140 deletions(-) rename {InvertedPendulumCart => Control}/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py (100%) rename {InvertedPendulumCart => Control}/__init__.py (100%) create mode 100644 docs/modules/control/control_main.rst create mode 100644 docs/modules/control/inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst create mode 100644 docs/modules/localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization.rst rename docs/modules/localization/{ => extended_kalman_filter_localization_files}/extended_kalman_filter_localization.rst (99%) create mode 100644 docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst create mode 100644 docs/modules/localization/particle_filter_localization/particle_filter_localization.rst create mode 100644 docs/modules/localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization.rst create mode 100644 docs/modules/mapping/circle_fitting/circle_fitting.rst create mode 100644 docs/modules/mapping/gaussian_grid_map/gaussian_grid_map.rst create mode 100644 docs/modules/mapping/k_means_object_clustering/k_means_object_clustering.rst rename docs/modules/mapping/{lidar_to_grid_map_tutorial_files => lidar_to_grid_map_tutorial}/grid_map_example.png (100%) rename docs/modules/mapping/{ => lidar_to_grid_map_tutorial}/lidar_to_grid_map_tutorial.rst (90%) rename docs/modules/mapping/{lidar_to_grid_map_tutorial_files => lidar_to_grid_map_tutorial}/lidar_to_grid_map_tutorial_12_0.png (100%) rename docs/modules/mapping/{lidar_to_grid_map_tutorial_files => lidar_to_grid_map_tutorial}/lidar_to_grid_map_tutorial_14_1.png (100%) rename docs/modules/mapping/{lidar_to_grid_map_tutorial_files => lidar_to_grid_map_tutorial}/lidar_to_grid_map_tutorial_5_0.png (100%) rename docs/modules/mapping/{lidar_to_grid_map_tutorial_files => lidar_to_grid_map_tutorial}/lidar_to_grid_map_tutorial_7_0.png (100%) rename docs/modules/mapping/{lidar_to_grid_map_tutorial_files => lidar_to_grid_map_tutorial}/lidar_to_grid_map_tutorial_8_0.png (100%) create mode 100644 docs/modules/mapping/ray_casting_grid_map/ray_casting_grid_map.rst create mode 100644 docs/modules/mapping/rectangle_fitting/rectangle_fitting.rst diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index 4e2e57f8e4..ef773ff71a 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -41,7 +41,7 @@ jobs: mypy -p AerialNavigation mypy -p ArmNavigation mypy -p Bipedal - mypy -p InvertedPendulumCart + mypy -p Control mypy -p Localization mypy -p Mapping mypy -p PathPlanning diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index 9bfb4b6fd3..f01d85e62b 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -48,7 +48,7 @@ jobs: mypy -p AerialNavigation mypy -p ArmNavigation mypy -p Bipedal - mypy -p InvertedPendulumCart + mypy -p Control mypy -p Localization mypy -p Mapping mypy -p PathPlanning diff --git a/InvertedPendulumCart/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py b/Control/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py similarity index 100% rename from InvertedPendulumCart/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py rename to Control/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py diff --git a/InvertedPendulumCart/__init__.py b/Control/__init__.py similarity index 100% rename from InvertedPendulumCart/__init__.py rename to Control/__init__.py diff --git a/docs/index_main.rst b/docs/index_main.rst index 128a50a58e..79980c2bd9 100644 --- a/docs/index_main.rst +++ b/docs/index_main.rst @@ -43,6 +43,7 @@ See this paper for more details: modules/arm_navigation/arm_navigation modules/aerial_navigation/aerial_navigation modules/bipedal/bipedal + modules/control/control modules/appendix/appendix how_to_contribute diff --git a/docs/modules/control/control_main.rst b/docs/modules/control/control_main.rst new file mode 100644 index 0000000000..7e13ab1eb6 --- /dev/null +++ b/docs/modules/control/control_main.rst @@ -0,0 +1,7 @@ +.. _control: + +Control +================= + +.. include:: inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst + diff --git a/docs/modules/control/inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst b/docs/modules/control/inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst new file mode 100644 index 0000000000..328f9f6b24 --- /dev/null +++ b/docs/modules/control/inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst @@ -0,0 +1,6 @@ +Inverted Pendulum MPC Control +----------------------------- + +Bipedal Walking with modifying designated footsteps + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation.gif diff --git a/docs/modules/introduction_main.rst b/docs/modules/introduction_main.rst index 60cb085a29..f9fb487297 100644 --- a/docs/modules/introduction_main.rst +++ b/docs/modules/introduction_main.rst @@ -2,4 +2,41 @@ Introduction ============ -TBD \ No newline at end of file +TBD + +Definition Of Robotics +---------------------- + +TBD + +History Of Robotics +---------------------- + +TBD + +Application Of Robotics +------------------------ + +TBD + +Software for Robotics +---------------------- + +TBD + +Software for Robotics +---------------------- + +TBD + +Python for Robotics +---------------------- + +TBD + +Learning Robotics Algorithms +---------------------------- + +TBD + + diff --git a/docs/modules/localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization.rst b/docs/modules/localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization.rst new file mode 100644 index 0000000000..2543d1186a --- /dev/null +++ b/docs/modules/localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization.rst @@ -0,0 +1,7 @@ +Ensamble Kalman Filter Localization +----------------------------------- + +.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/ensamble_kalman_filter/animation.gif + +This is a sensor fusion localization with Ensamble Kalman Filter(EnKF). + diff --git a/docs/modules/localization/extended_kalman_filter_localization.rst b/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst similarity index 99% rename from docs/modules/localization/extended_kalman_filter_localization.rst rename to docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst index 507ea972a4..9777258e3e 100644 --- a/docs/modules/localization/extended_kalman_filter_localization.rst +++ b/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst @@ -8,7 +8,6 @@ Extended Kalman Filter Localization .. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/extended_kalman_filter/animation.gif - :alt: EKF This is a sensor fusion localization with Extended Kalman Filter(EKF). diff --git a/docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst b/docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst new file mode 100644 index 0000000000..afe689b9a5 --- /dev/null +++ b/docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst @@ -0,0 +1,22 @@ +Histogram filter localization +----------------------------- + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/histogram_filter/animation.gif + +This is a 2D localization example with Histogram filter. + +The red cross is true position, black points are RFID positions. + +The blue grid shows a position probability of histogram filter. + +In this simulation, x,y are unknown, yaw is known. + +The filter integrates speed input and range observations from RFID for +localization. + +Initial position is not needed. + +References: +~~~~~~~~~~~ + +- `PROBABILISTIC ROBOTICS`_ diff --git a/docs/modules/localization/localization_main.rst b/docs/modules/localization/localization_main.rst index c665eba694..b1769df163 100644 --- a/docs/modules/localization/localization_main.rst +++ b/docs/modules/localization/localization_main.rst @@ -3,89 +3,11 @@ Localization ============ -.. include:: extended_kalman_filter_localization.rst - - -Unscented Kalman Filter localization ------------------------------------- - -|2| - -This is a sensor fusion localization with Unscented Kalman Filter(UKF). - -The lines and points are same meaning of the EKF simulation. - -References: -~~~~~~~~~~~ - -- `Discriminatively Trained Unscented Kalman Filter for Mobile Robot - Localization`_ - -Particle filter localization ----------------------------- - -|3| - -This is a sensor fusion localization with Particle Filter(PF). - -The blue line is true trajectory, the black line is dead reckoning -trajectory, - -and the red line is estimated trajectory with PF. - -It is assumed that the robot can measure a distance from landmarks -(RFID). - -This measurements are used for PF localization. - -How to calculate covariance matrix from particles -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -The covariance matrix :math:`\Xi` from particle information is calculated by the following equation: - -.. math:: \Xi_{j,k}=\frac{1}{1-\sum^N_{i=1}(w^i)^2}\sum^N_{i=1}w^i(x^i_j-\mu_j)(x^i_k-\mu_k) - -- :math:`\Xi_{j,k}` is covariance matrix element at row :math:`i` and column :math:`k`. - -- :math:`w^i` is the weight of the :math:`i` th particle. - -- :math:`x^i_j` is the :math:`j` th state of the :math:`i` th particle. - -- :math:`\mu_j` is the :math:`j` th mean state of particles. - -References: -~~~~~~~~~~~ - -- `PROBABILISTIC ROBOTICS`_ -- `Improving the particle filter in high dimensions using conjugate artificial process noise`_ - -Histogram filter localization ------------------------------ - -|4| - -This is a 2D localization example with Histogram filter. - -The red cross is true position, black points are RFID positions. - -The blue grid shows a position probability of histogram filter. - -In this simulation, x,y are unknown, yaw is known. - -The filter integrates speed input and range observations from RFID for -localization. - -Initial position is not needed. - -References: -~~~~~~~~~~~ - -- `PROBABILISTIC ROBOTICS`_ +.. include:: extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst +.. include:: ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization.rst +.. include:: unscented_kalman_filter_localization/unscented_kalman_filter_localization.rst +.. include:: histogram_filter_localization/histogram_filter_localization.rst +.. include:: particle_filter_localization/particle_filter_localization.rst .. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/ -.. _Discriminatively Trained Unscented Kalman Filter for Mobile Robot Localization: https://www.researchgate.net/publication/267963417_Discriminatively_Trained_Unscented_Kalman_Filter_for_Mobile_Robot_Localization -.. _Improving the particle filter in high dimensions using conjugate artificial process noise: https://arxiv.org/pdf/1801.07000.pdf -.. |2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/unscented_kalman_filter/animation.gif -.. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/particle_filter/animation.gif -.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/histogram_filter/animation.gif diff --git a/docs/modules/localization/particle_filter_localization/particle_filter_localization.rst b/docs/modules/localization/particle_filter_localization/particle_filter_localization.rst new file mode 100644 index 0000000000..55b44e166b --- /dev/null +++ b/docs/modules/localization/particle_filter_localization/particle_filter_localization.rst @@ -0,0 +1,37 @@ +Particle filter localization +---------------------------- + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/particle_filter/animation.gif + +This is a sensor fusion localization with Particle Filter(PF). + +The blue line is true trajectory, the black line is dead reckoning +trajectory, + +and the red line is estimated trajectory with PF. + +It is assumed that the robot can measure a distance from landmarks +(RFID). + +This measurements are used for PF localization. + +How to calculate covariance matrix from particles +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The covariance matrix :math:`\Xi` from particle information is calculated by the following equation: + +.. math:: \Xi_{j,k}=\frac{1}{1-\sum^N_{i=1}(w^i)^2}\sum^N_{i=1}w^i(x^i_j-\mu_j)(x^i_k-\mu_k) + +- :math:`\Xi_{j,k}` is covariance matrix element at row :math:`i` and column :math:`k`. + +- :math:`w^i` is the weight of the :math:`i` th particle. + +- :math:`x^i_j` is the :math:`j` th state of the :math:`i` th particle. + +- :math:`\mu_j` is the :math:`j` th mean state of particles. + +References: +~~~~~~~~~~~ + +- `PROBABILISTIC ROBOTICS`_ +- `Improving the particle filter in high dimensions using conjugate artificial process noise `_ diff --git a/docs/modules/localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization.rst b/docs/modules/localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization.rst new file mode 100644 index 0000000000..bb6b5b664b --- /dev/null +++ b/docs/modules/localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization.rst @@ -0,0 +1,13 @@ +Unscented Kalman Filter localization +------------------------------------ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/unscented_kalman_filter/animation.gif + +This is a sensor fusion localization with Unscented Kalman Filter(UKF). + +The lines and points are same meaning of the EKF simulation. + +References: +~~~~~~~~~~~ + +- `Discriminatively Trained Unscented Kalman Filter for Mobile Robot Localization `_ diff --git a/docs/modules/mapping/circle_fitting/circle_fitting.rst b/docs/modules/mapping/circle_fitting/circle_fitting.rst new file mode 100644 index 0000000000..1892d1f8f7 --- /dev/null +++ b/docs/modules/mapping/circle_fitting/circle_fitting.rst @@ -0,0 +1,13 @@ +Object shape recognition using circle fitting +--------------------------------------------- + +This is an object shape recognition using circle fitting. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/circle_fitting/animation.gif + +The blue circle is the true object shape. + +The red crosses are observations from a ranging sensor. + +The red circle is the estimated object shape using circle fitting. + diff --git a/docs/modules/mapping/gaussian_grid_map/gaussian_grid_map.rst b/docs/modules/mapping/gaussian_grid_map/gaussian_grid_map.rst new file mode 100644 index 0000000000..f78f2c95d8 --- /dev/null +++ b/docs/modules/mapping/gaussian_grid_map/gaussian_grid_map.rst @@ -0,0 +1,6 @@ +Gaussian grid map +----------------- + +This is a 2D Gaussian grid mapping example. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/gaussian_grid_map/animation.gif diff --git a/docs/modules/mapping/k_means_object_clustering/k_means_object_clustering.rst b/docs/modules/mapping/k_means_object_clustering/k_means_object_clustering.rst new file mode 100644 index 0000000000..e098ca5409 --- /dev/null +++ b/docs/modules/mapping/k_means_object_clustering/k_means_object_clustering.rst @@ -0,0 +1,6 @@ +k-means object clustering +------------------------- + +This is a 2D object clustering with k-means algorithm. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/kmeans_clustering/animation.gif diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial_files/grid_map_example.png b/docs/modules/mapping/lidar_to_grid_map_tutorial/grid_map_example.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial_files/grid_map_example.png rename to docs/modules/mapping/lidar_to_grid_map_tutorial/grid_map_example.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial.rst b/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial.rst similarity index 90% rename from docs/modules/mapping/lidar_to_grid_map_tutorial.rst rename to docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial.rst index 64dba26d4f..2e9470ff6c 100644 --- a/docs/modules/mapping/lidar_to_grid_map_tutorial.rst +++ b/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial.rst @@ -1,3 +1,7 @@ +Lidar to grid map +-------------------- + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/lidar_to_grid_map/animation.gif This simple tutorial shows how to read LIDAR (range) measurements from a file and convert it to occupancy grid. @@ -12,8 +16,7 @@ a ``numpy array``, and numbers close to 1 means the cell is occupied free (*marked with green*). The grid has the ability to represent unknown (unobserved) areas, which are close to 0.5. -.. figure:: lidar_to_grid_map_tutorial_files/grid_map_example.png - :alt: Example +.. figure:: lidar_to_grid_map_tutorial/grid_map_example.png In order to construct the grid map from the measurement we need to discretise the values. But, first let’s need to ``import`` some @@ -65,7 +68,7 @@ From the distances and the angles it is easy to determine the ``x`` and -.. image:: lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_5_0.png +.. image:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png The ``lidar_to_grid_map.py`` contains handy functions which can used to @@ -86,7 +89,7 @@ map. Let’s see how this works. -.. image:: lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_7_0.png +.. image:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png .. code:: ipython3 @@ -103,7 +106,7 @@ map. Let’s see how this works. -.. image:: lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_8_0.png +.. image:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png To fill empty areas, a queue-based algorithm can be used that can be @@ -160,7 +163,7 @@ from a center point (e.g. (10, 20)) with zeros: -.. image:: lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_12_0.png +.. image:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png Let’s use this flood fill on real data: @@ -191,5 +194,5 @@ Let’s use this flood fill on real data: -.. image:: lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_14_1.png +.. image:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_12_0.png b/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_12_0.png rename to docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_14_1.png b/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_14_1.png rename to docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_5_0.png b/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_5_0.png rename to docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_7_0.png b/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_7_0.png rename to docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_8_0.png b/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial_files/lidar_to_grid_map_tutorial_8_0.png rename to docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png diff --git a/docs/modules/mapping/mapping_main.rst b/docs/modules/mapping/mapping_main.rst index ccdd3198b1..7d2c4cfe67 100644 --- a/docs/modules/mapping/mapping_main.rst +++ b/docs/modules/mapping/mapping_main.rst @@ -3,49 +3,10 @@ Mapping ======= -Gaussian grid map ------------------ +.. include:: gaussian_grid_map/gaussian_grid_map.rst +.. include:: ray_casting_grid_map/ray_casting_grid_map.rst +.. include:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial.rst +.. include:: k_means_object_clustering/k_means_object_clustering.rst +.. include:: circle_fitting/circle_fitting.rst +.. include:: rectangle_fitting/rectangle_fitting.rst -This is a 2D Gaussian grid mapping example. - -|2| - -Ray casting grid map --------------------- - -This is a 2D ray casting grid mapping example. - -|3| - -Lidar to grid map --------------------- - -|6| - -.. include:: lidar_to_grid_map_tutorial.rst - -k-means object clustering -------------------------- - -This is a 2D object clustering with k-means algorithm. - -|4| - -Object shape recognition using circle fitting ---------------------------------------------- - -This is an object shape recognition using circle fitting. - -|5| - -The blue circle is the true object shape. - -The red crosses are observations from a ranging sensor. - -The red circle is the estimated object shape using circle fitting. - -.. |2| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/gaussian_grid_map/animation.gif -.. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/raycasting_grid_map/animation.gif -.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/kmeans_clustering/animation.gif -.. |5| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/circle_fitting/animation.gif -.. |6| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/lidar_to_grid_map/animation.gif diff --git a/docs/modules/mapping/ray_casting_grid_map/ray_casting_grid_map.rst b/docs/modules/mapping/ray_casting_grid_map/ray_casting_grid_map.rst new file mode 100644 index 0000000000..cc5a1a1c5b --- /dev/null +++ b/docs/modules/mapping/ray_casting_grid_map/ray_casting_grid_map.rst @@ -0,0 +1,6 @@ +Ray casting grid map +-------------------- + +This is a 2D ray casting grid mapping example. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/raycasting_grid_map/animation.gif \ No newline at end of file diff --git a/docs/modules/mapping/rectangle_fitting/rectangle_fitting.rst b/docs/modules/mapping/rectangle_fitting/rectangle_fitting.rst new file mode 100644 index 0000000000..c0949ac4c3 --- /dev/null +++ b/docs/modules/mapping/rectangle_fitting/rectangle_fitting.rst @@ -0,0 +1,7 @@ +Object shape recognition using rectangle fitting +------------------------------------------------ + +This is an object shape recognition using rectangle fitting. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/rectangle_fitting/animation.gif + diff --git a/tests/test_inverted_pendulum_mpc_control.py b/tests/test_inverted_pendulum_mpc_control.py index d88d4d7915..9519b45ec9 100644 --- a/tests/test_inverted_pendulum_mpc_control.py +++ b/tests/test_inverted_pendulum_mpc_control.py @@ -2,7 +2,7 @@ import sys if 'cvxpy' in sys.modules: # pragma: no cover - from InvertedPendulumCart.InvertedPendulumMPCControl \ + from Control.InvertedPendulumMPCControl \ import inverted_pendulum_mpc_control as m def test1(): From d183a00a1c03c448ba8ae7ab75f3b9bd2331be9a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 29 Nov 2021 00:01:06 +0900 Subject: [PATCH 428/940] Adding all gifs to the doc (#586) * update docs * update docs * update docs * update docs --- Control/move_to_pose/__init__.py | 0 .../move_to_pose/move_to_pose.py | 0 docs/modules/control/control_main.rst | 1 + .../move_to_a_pose_control.rst | 11 ++ .../{ => cgmres_nmpc}/cgmres_nmpc.rst | 8 +- .../cgmres_nmpc_1_0.png | Bin .../cgmres_nmpc_2_0.png | Bin .../cgmres_nmpc_3_0.png | Bin .../cgmres_nmpc_4_0.png | Bin .../lqr_speed_and_steering_control.rst | 13 +++ .../lqr_steering_control.rst | 14 +++ ...predictive_speed_and_steering_control.rst} | 0 .../path_tracking/path_tracking_main.rst | 97 ++---------------- .../pure_pursuit_tracking.rst | 16 +++ .../rear_wheel_feedback_control.rst | 12 +++ .../stanley_control/stanley_control.rst | 16 +++ .../slam/{ => FastSLAM1}/FastSLAM1.rst | 22 ++-- .../FastSLAM1_12_0.png | Bin .../FastSLAM1_12_1.png | Bin .../FastSLAM1_1_0.png | Bin docs/modules/slam/FastSLAM2/FastSLAM2.rst | 16 +++ docs/modules/slam/{ => ekf_slam}/ekf_slam.rst | 8 +- .../ekf_slam_1_0.png | Bin .../Graph_SLAM_optimization.gif | Bin 114966 -> 0 bytes .../graphSLAM_SE2_example.rst | 15 ++- .../graphSLAM_SE2_example_13_0.png | Bin .../graphSLAM_SE2_example_15_0.png | Bin .../graphSLAM_SE2_example_16_0.png | Bin .../graphSLAM_SE2_example_4_0.png | Bin .../graphSLAM_SE2_example_8_0.png | Bin .../graphSLAM_SE2_example_9_0.png | Bin .../slam/{ => graph_slam}/graphSLAM_doc.rst | 21 ++-- .../graphSLAM_formulation.rst | 4 +- docs/modules/slam/graph_slam/graph_slam.rst | 24 +++++ .../iterative_closest_point_matching.rst | 16 +++ docs/modules/slam/slam_main.rst | 78 +------------- tests/test_move_to_pose.py | 2 +- 37 files changed, 186 insertions(+), 208 deletions(-) create mode 100644 Control/move_to_pose/__init__.py rename {PathTracking => Control}/move_to_pose/move_to_pose.py (100%) create mode 100644 docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst rename docs/modules/path_tracking/{ => cgmres_nmpc}/cgmres_nmpc.rst (91%) rename docs/modules/path_tracking/{cgmres_nmpc_files => cgmres_nmpc}/cgmres_nmpc_1_0.png (100%) rename docs/modules/path_tracking/{cgmres_nmpc_files => cgmres_nmpc}/cgmres_nmpc_2_0.png (100%) rename docs/modules/path_tracking/{cgmres_nmpc_files => cgmres_nmpc}/cgmres_nmpc_3_0.png (100%) rename docs/modules/path_tracking/{cgmres_nmpc_files => cgmres_nmpc}/cgmres_nmpc_4_0.png (100%) create mode 100644 docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control.rst create mode 100644 docs/modules/path_tracking/lqr_steering_control/lqr_steering_control.rst rename docs/modules/path_tracking/{Model_predictive_speed_and_steering_control.rst => model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control.rst} (100%) create mode 100644 docs/modules/path_tracking/pure_pursuit_tracking/pure_pursuit_tracking.rst create mode 100644 docs/modules/path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control.rst create mode 100644 docs/modules/path_tracking/stanley_control/stanley_control.rst rename docs/modules/slam/{ => FastSLAM1}/FastSLAM1.rst (97%) rename docs/modules/slam/{FastSLAM1_files => FastSLAM1}/FastSLAM1_12_0.png (100%) rename docs/modules/slam/{FastSLAM1_files => FastSLAM1}/FastSLAM1_12_1.png (100%) rename docs/modules/slam/{FastSLAM1_files => FastSLAM1}/FastSLAM1_1_0.png (100%) create mode 100644 docs/modules/slam/FastSLAM2/FastSLAM2.rst rename docs/modules/slam/{ => ekf_slam}/ekf_slam.rst (98%) rename docs/modules/slam/{ekf_slam_files => ekf_slam}/ekf_slam_1_0.png (100%) delete mode 100644 docs/modules/slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif rename docs/modules/slam/{ => graph_slam}/graphSLAM_SE2_example.rst (90%) rename docs/modules/slam/{ => graph_slam}/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png (100%) rename docs/modules/slam/{ => graph_slam}/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png (100%) rename docs/modules/slam/{ => graph_slam}/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png (100%) rename docs/modules/slam/{ => graph_slam}/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png (100%) rename docs/modules/slam/{ => graph_slam}/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png (100%) rename docs/modules/slam/{ => graph_slam}/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png (100%) rename docs/modules/slam/{ => graph_slam}/graphSLAM_doc.rst (95%) rename docs/modules/slam/{ => graph_slam}/graphSLAM_formulation.rst (97%) create mode 100644 docs/modules/slam/graph_slam/graph_slam.rst create mode 100644 docs/modules/slam/iterative_closest_point_matching/iterative_closest_point_matching.rst diff --git a/Control/move_to_pose/__init__.py b/Control/move_to_pose/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/PathTracking/move_to_pose/move_to_pose.py b/Control/move_to_pose/move_to_pose.py similarity index 100% rename from PathTracking/move_to_pose/move_to_pose.py rename to Control/move_to_pose/move_to_pose.py diff --git a/docs/modules/control/control_main.rst b/docs/modules/control/control_main.rst index 7e13ab1eb6..9eeba434d2 100644 --- a/docs/modules/control/control_main.rst +++ b/docs/modules/control/control_main.rst @@ -4,4 +4,5 @@ Control ================= .. include:: inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst +.. include:: move_to_a_pose_control/move_to_a_pose_control.rst diff --git a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst new file mode 100644 index 0000000000..c5bf15d970 --- /dev/null +++ b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst @@ -0,0 +1,11 @@ +Move to a pose control +---------------------- + +This is a simulation of moving to a pose control + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif + +Ref: + +- `P. I. Corke, "Robotics, Vision and Control" \| SpringerLink + p102 `__ diff --git a/docs/modules/path_tracking/cgmres_nmpc.rst b/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc.rst similarity index 91% rename from docs/modules/path_tracking/cgmres_nmpc.rst rename to docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc.rst index 6f6a102618..5092fa8e2f 100644 --- a/docs/modules/path_tracking/cgmres_nmpc.rst +++ b/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc.rst @@ -2,16 +2,16 @@ Nonlinear Model Predictive Control with C-GMRES ----------------------------------------------- -.. image:: cgmres_nmpc_files/cgmres_nmpc_1_0.png +.. image:: cgmres_nmpc/cgmres_nmpc_1_0.png :width: 600px -.. image:: cgmres_nmpc_files/cgmres_nmpc_2_0.png +.. image:: cgmres_nmpc/cgmres_nmpc_2_0.png :width: 600px -.. image:: cgmres_nmpc_files/cgmres_nmpc_3_0.png +.. image:: cgmres_nmpc/cgmres_nmpc_3_0.png :width: 600px -.. image:: cgmres_nmpc_files/cgmres_nmpc_4_0.png +.. image:: cgmres_nmpc/cgmres_nmpc_4_0.png :width: 600px .. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/cgmres_nmpc/animation.gif diff --git a/docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_1_0.png b/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_1_0.png similarity index 100% rename from docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_1_0.png rename to docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_1_0.png diff --git a/docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_2_0.png b/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_2_0.png similarity index 100% rename from docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_2_0.png rename to docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_2_0.png diff --git a/docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_3_0.png b/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_3_0.png similarity index 100% rename from docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_3_0.png rename to docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_3_0.png diff --git a/docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_4_0.png b/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_4_0.png similarity index 100% rename from docs/modules/path_tracking/cgmres_nmpc_files/cgmres_nmpc_4_0.png rename to docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_4_0.png diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control.rst b/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control.rst new file mode 100644 index 0000000000..68ea9c88b2 --- /dev/null +++ b/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control.rst @@ -0,0 +1,13 @@ +.. _linearquadratic-regulator-(lqr)-speed-and-steering-control: + +Linear–quadratic regulator (LQR) speed and steering control +----------------------------------------------------------- + +Path tracking simulation with LQR speed and steering control. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_speed_steer_control/animation.gif + +References: +~~~~~~~~~~~ + +- `Towards fully autonomous driving: Systems and algorithms `__ diff --git a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control.rst b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control.rst new file mode 100644 index 0000000000..bf6d6b5854 --- /dev/null +++ b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control.rst @@ -0,0 +1,14 @@ +.. _linearquadratic-regulator-(lqr)-steering-control: + +Linear–quadratic regulator (LQR) steering control +------------------------------------------------- + +Path tracking simulation with LQR steering control and PID speed +control. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_steer_control/animation.gif + +References: +~~~~~~~~~~~ +- `ApolloAuto/apollo: An open autonomous driving platform `_ + diff --git a/docs/modules/path_tracking/Model_predictive_speed_and_steering_control.rst b/docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control.rst similarity index 100% rename from docs/modules/path_tracking/Model_predictive_speed_and_steering_control.rst rename to docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control.rst diff --git a/docs/modules/path_tracking/path_tracking_main.rst b/docs/modules/path_tracking/path_tracking_main.rst index 725e4f04b4..2a572ef6df 100644 --- a/docs/modules/path_tracking/path_tracking_main.rst +++ b/docs/modules/path_tracking/path_tracking_main.rst @@ -3,94 +3,11 @@ Path Tracking ============= -move to a pose control ----------------------- - -This is a simulation of moving to a pose control - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif - -Ref: - -- `P. I. Corke, "Robotics, Vision and Control" \| SpringerLink - p102 `__ - -Pure pursuit tracking ---------------------- - -Path tracking simulation with pure pursuit steering control and PID -speed control. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/pure_pursuit/animation.gif - -The red line is a target course, the green cross means the target point -for pure pursuit control, the blue line is the tracking. - -Ref: - -- `A Survey of Motion Planning and Control Techniques for Self-driving - Urban Vehicles `__ - -Stanley control ---------------- - -Path tracking simulation with Stanley steering control and PID speed -control. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/stanley_controller/animation.gif - -Ref: - -- `Stanley: The robot that won the DARPA grand - challenge `__ - -- `Automatic Steering Methods for Autonomous Automobile Path - Tracking `__ - -Rear wheel feedback control ---------------------------- - -Path tracking simulation with rear wheel feedback steering control and -PID speed control. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/rear_wheel_feedback/animation.gif - -Ref: - -- `A Survey of Motion Planning and Control Techniques for Self-driving - Urban Vehicles `__ - -.. _linearquadratic-regulator-(lqr)-steering-control: - -Linear–quadratic regulator (LQR) steering control -------------------------------------------------- - -Path tracking simulation with LQR steering control and PID speed -control. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_steer_control/animation.gif - -Ref: - -- `ApolloAuto/apollo: An open autonomous driving - platform `__ - -.. _linearquadratic-regulator-(lqr)-speed-and-steering-control: - -Linear–quadratic regulator (LQR) speed and steering control ------------------------------------------------------------ - -Path tracking simulation with LQR speed and steering control. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_speed_steer_control/animation.gif - -Ref: - -- `Towards fully autonomous driving: Systems and algorithms - IEEE - Conference - Publication `__ - -.. include:: Model_predictive_speed_and_steering_control.rst - -.. include:: cgmres_nmpc.rst +.. include:: pure_pursuit_tracking/pure_pursuit_tracking.rst +.. include:: stanley_control/stanley_control.rst +.. include:: rear_wheel_feedback_control/rear_wheel_feedback_control.rst +.. include:: lqr_steering_control/lqr_steering_control.rst +.. include:: lqr_speed_and_steering_control/lqr_speed_and_steering_control.rst +.. include:: model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control.rst +.. include:: cgmres_nmpc/cgmres_nmpc.rst diff --git a/docs/modules/path_tracking/pure_pursuit_tracking/pure_pursuit_tracking.rst b/docs/modules/path_tracking/pure_pursuit_tracking/pure_pursuit_tracking.rst new file mode 100644 index 0000000000..5c7bcef85f --- /dev/null +++ b/docs/modules/path_tracking/pure_pursuit_tracking/pure_pursuit_tracking.rst @@ -0,0 +1,16 @@ +Pure pursuit tracking +--------------------- + +Path tracking simulation with pure pursuit steering control and PID +speed control. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/pure_pursuit/animation.gif + +The red line is a target course, the green cross means the target point +for pure pursuit control, the blue line is the tracking. + +References: +~~~~~~~~~~~ + +- `A Survey of Motion Planning and Control Techniques for Self-driving + Urban Vehicles `_ diff --git a/docs/modules/path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control.rst b/docs/modules/path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control.rst new file mode 100644 index 0000000000..70875fdc6c --- /dev/null +++ b/docs/modules/path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control.rst @@ -0,0 +1,12 @@ +Rear wheel feedback control +--------------------------- + +Path tracking simulation with rear wheel feedback steering control and +PID speed control. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/rear_wheel_feedback/animation.gif + +References: +~~~~~~~~~~~ +- `A Survey of Motion Planning and Control Techniques for Self-driving + Urban Vehicles `__ diff --git a/docs/modules/path_tracking/stanley_control/stanley_control.rst b/docs/modules/path_tracking/stanley_control/stanley_control.rst new file mode 100644 index 0000000000..fe325b0102 --- /dev/null +++ b/docs/modules/path_tracking/stanley_control/stanley_control.rst @@ -0,0 +1,16 @@ +Stanley control +--------------- + +Path tracking simulation with Stanley steering control and PID speed +control. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/stanley_controller/animation.gif + +References: +~~~~~~~~~~~ + +- `Stanley: The robot that won the DARPA grand + challenge `_ + +- `Automatic Steering Methods for Autonomous Automobile Path + Tracking `_ diff --git a/docs/modules/slam/FastSLAM1.rst b/docs/modules/slam/FastSLAM1/FastSLAM1.rst similarity index 97% rename from docs/modules/slam/FastSLAM1.rst rename to docs/modules/slam/FastSLAM1/FastSLAM1.rst index 6e26aef72f..f1e9dfd8aa 100644 --- a/docs/modules/slam/FastSLAM1.rst +++ b/docs/modules/slam/FastSLAM1/FastSLAM1.rst @@ -2,8 +2,7 @@ FastSLAM1.0 ----------- -.. image:: FastSLAM1_files/FastSLAM1_1_0.png - :width: 600px +.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM1/animation.gif @@ -12,6 +11,9 @@ Simulation This is a feature based SLAM example using FastSLAM 1.0. +.. image:: FastSLAM1/FastSLAM1_1_0.png + :width: 600px + The blue line is ground truth, the black line is dead reckoning, the red line is the estimated trajectory with FastSLAM. @@ -20,8 +22,6 @@ The red points are particles of FastSLAM. Black points are landmarks, blue crosses are estimated landmark positions by FastSLAM. -.. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM1/animation.gif - :alt: gif Introduction ~~~~~~~~~~~~ @@ -527,19 +527,13 @@ indices -.. image:: FastSLAM1_files/FastSLAM1_12_0.png - - - -.. image:: FastSLAM1_files/FastSLAM1_12_1.png +.. image:: FastSLAM1/FastSLAM1_12_0.png +.. image:: FastSLAM1/FastSLAM1_12_1.png References ~~~~~~~~~~ -- `PROBABILISTIC ROBOTICS`_ - -- `FastSLAM Lecture`_ +- `PROBABILISTIC ROBOTICS `_ -.. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/ -.. _FastSLAM Lecture: http://ais.informatik.uni-freiburg.de/teaching/ws12/mapping/pdf/slam10-fastslam.pdf +- `FastSLAM Lecture `_ diff --git a/docs/modules/slam/FastSLAM1_files/FastSLAM1_12_0.png b/docs/modules/slam/FastSLAM1/FastSLAM1_12_0.png similarity index 100% rename from docs/modules/slam/FastSLAM1_files/FastSLAM1_12_0.png rename to docs/modules/slam/FastSLAM1/FastSLAM1_12_0.png diff --git a/docs/modules/slam/FastSLAM1_files/FastSLAM1_12_1.png b/docs/modules/slam/FastSLAM1/FastSLAM1_12_1.png similarity index 100% rename from docs/modules/slam/FastSLAM1_files/FastSLAM1_12_1.png rename to docs/modules/slam/FastSLAM1/FastSLAM1_12_1.png diff --git a/docs/modules/slam/FastSLAM1_files/FastSLAM1_1_0.png b/docs/modules/slam/FastSLAM1/FastSLAM1_1_0.png similarity index 100% rename from docs/modules/slam/FastSLAM1_files/FastSLAM1_1_0.png rename to docs/modules/slam/FastSLAM1/FastSLAM1_1_0.png diff --git a/docs/modules/slam/FastSLAM2/FastSLAM2.rst b/docs/modules/slam/FastSLAM2/FastSLAM2.rst new file mode 100644 index 0000000000..9e79b496a3 --- /dev/null +++ b/docs/modules/slam/FastSLAM2/FastSLAM2.rst @@ -0,0 +1,16 @@ +FastSLAM 2.0 +------------ + +This is a feature based SLAM example using FastSLAM 2.0. + +The animation has the same meanings as one of FastSLAM 1.0. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM2/animation.gif + +References +~~~~~~~~~~ + +- `PROBABILISTIC ROBOTICS `_ + +- `SLAM simulations by Tim Bailey `_ + diff --git a/docs/modules/slam/ekf_slam.rst b/docs/modules/slam/ekf_slam/ekf_slam.rst similarity index 98% rename from docs/modules/slam/ekf_slam.rst rename to docs/modules/slam/ekf_slam/ekf_slam.rst index df520fbdaf..a79c2737ae 100644 --- a/docs/modules/slam/ekf_slam.rst +++ b/docs/modules/slam/ekf_slam/ekf_slam.rst @@ -8,7 +8,7 @@ line is the estimated trajectory with EKF SLAM. The green crosses are estimated landmarks. -|4| +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/EKFSLAM/animation.gif Simulation ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ @@ -581,13 +581,11 @@ reckoning and control functions are passed along here as well. New LM New LM -.. image:: ekf_slam_files/ekf_slam_1_0.png +.. image:: ekf_slam/ekf_slam_1_0.png References: ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -- `PROBABILISTIC ROBOTICS`_ +- `PROBABILISTIC ROBOTICS `_ -.. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/ -.. |4| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/EKFSLAM/animation.gif diff --git a/docs/modules/slam/ekf_slam_files/ekf_slam_1_0.png b/docs/modules/slam/ekf_slam/ekf_slam_1_0.png similarity index 100% rename from docs/modules/slam/ekf_slam_files/ekf_slam_1_0.png rename to docs/modules/slam/ekf_slam/ekf_slam_1_0.png diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif b/docs/modules/slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif deleted file mode 100644 index 2fabeaafc9cd4ad4b71bbf451637bf2560f1be5e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 114966 zcmdp-`#;nF|NnP*ZgxOBI83Nv=FCW<)O(xb80HXiYD6ij5v5XXvyC~_oX?t5A!fU?vKay;lXfsbc#*~tAc-m zKoAH-RaI3(Lu1{#btDqW($aFnh7Hcn&aSSmUS3|2k&%IcfxC9?N=QgZPft%xP3;41 z`w3F{1A=@9A^(LTSCPmCi1s(M#tIIonzzYkNL6_g!@K8sD^U#m#*+Jp7M;;78ApY0rc2g7&V)$Nv`_zjFBSr})E1!J=4D zc>=sVS*<(`U+x4R0)to4=v6#^RabYFL|V19T(!4fb#`8LMGv{4hM4%Fz_ml$^@buz zL$MbB=ZPDJQk;iUorlt0hFn}$natIopw)^A#*4zP`1!wWFis`t|FpBGGDj`LCk#51Hk?8ABNvt2sHVMMbMsRjc*&tF5i8 z9UZHGM-Ai*jTa70Rt-IE7@EH@^s;4W@ygJ*>;LBi0|R4YV^5zxefaR<>d@cj>iGET zg9ocmo~*ul^=ff(@#V|a#l_Wc|7WXz4fOx18T!4P;T60zfl|emZ25K%wR_rFshXz%c>1&g$IkPj~Dv$K#;Y=hECKE@=$22 zc~B}bsoXXSyV2#325=+mbOzpYLJ4P-{Zkgr|h(m zSwR-T5UA+jt4GsavxabVf6r0 zvG37jY&pWa3Z!J-IobGmtOrKv*~s<>gYJ%bsma(pDDTGPktqn@tl*!x8(0C?2#RG< zk6Zv`URKCu<9s8i<-B}1R$U-J1>N7I1b@|Z1(6_IL3&~ptLbMsrZoO~8p_py3yyeN z5Nrjt4;V87am%z$IF1HT#b;7}dV-!BJ4!&!sw6$5s|00<5k!vz%7EsJrb>}|DWEK* zIL$i~Vu0D5RcQclc~E;I!D#znfII|bNvBqcHZFm3xdnn~+8QEtr}-%A9^L$Y@O zoaQ5I!#TXaon3)&tANsUYH-j z#EA{gnbQE`=9V(8_s5i=h;0GXHvUoO&fDwH@3p;Q8bZ?D->J#o-XZ?7P@hYLH$q9tDg+wRS;#fI!X{%hvRNi<1{xQwiL%LPH4^Rotfu+Vw)#CAiF#=3c{HI6yl zCUwHe?pa{+J{Oe!@dW58Iwb@RO&K#|CB$W(EC5IB8z?#O!i-YmakabE|NZqH8l?*z zrv#{wT*@#1+Ah-q>f%)uo8MNsj^WK8-aV~Dfgh`X`u$buVe{wP!;pi2zO#^Q`Hz_+ zpZ@%u&9qrro-aMP@@wJzrImjdyFRV_w{+X4Zy6#Bviz}}k$TGOzc-&&1OMngU4DjM-Uyz|`z`eUW1cNEDQo%J*G0tUF ziIl!QJ1rcUxhF?Af~z9y<^hLI!MG|qaivuPScE!i;JxOtQ%Qooh?oKDTTZ6gtic)+ ziqL{d6xPYyFqxjNHTGCTPv<+h4ZA?@Fh8hsFIVH}vS{NX1>!RmJ%s*sw7a94xDYm@x4sLmz*h*0}=`lfmCyr}FYv?TMvVA&q|H(?icN)VI`VjIpCPz7 zXq<1X#zPzk0BKxY;R;Q|ni zeEu4jnHQvF3X-cXkZRJ*8Rm0idcAg~dE>?~h{1!MCA$jo*SJ(RXy%|Z zpy~;Nu4u$~{BKlX+Z{t(w;!fcz(I$XZ8*(9xWazC^Yjd!)oA3-Z{0WtH;YO-=h9^E znkV-$yQpmPs`iX^QJ{8eO%naSL$&u+j9Rh_A@$R@bl-qf*45D3tE#zc)yHnRl47bo zJy#(3ZdPW%G{0Er2{9x^XOU!=yVl=$t#^Oa&Ho`7<1@Rs_J|qmKrl$-a9X`tvzhN! zUkAgfKUuURrbtn@;WcLWZhg@LiaOAaF2N-34D5dP#=I!=L2*os*^UR5hS7~~G7=6F zeUEO+D{YUY8wwUs%=Bnv;vWb(f|s?iW)8L9jjm%k=hf#+mj&n@uoIU(%}nVwDvq%`)-kr6u*or_t$|YFHQ``3@hsY9<Nh7WXuJO^TKbZg6l$9}QiXS3l3j=Rzf@m?zTNij%grCE`z&^1 z;l?B|swxyg=A(s_VTbOhvO$Z2EwctE!N@e_RpWvsR0JJ&9xFSz#h42(S4;o_z!mF8 z>D_RXezZUiRoh1u%w8-)xC|?5wk*$y9v(M3=6Gn`%kYdu4>{(bbiOl_C3Ff?Xf{e* z%_1zrnaUT$&ZX}jSZ7f%@UyH{b)i6NU|i4K=> z0g2!>*L`*-evu$Nvoeg+%sxgs(D2`OfAzqk7^nL}w1$s_i~u=eI*D8_ZX5#xUl(_1@>^0T<**m~RJ81HzZ)!#ir790v10rE zDyG-`@MkY^e&PAb27JB=vKj>2zVRr)i~IT$V-<=5cez+eclu#qx`)vf5<&8j#AxZh z^XHK=(BbvPryz5vl}nr8-ZDUa8EBKh16;wLRQO5=H*q7nYZm6c1nW=Dl%xbcehqDv z|4rb~6CeccP1drDXhRX+z#Uw-33ksU1{R(4AOzbT%djS<9@0RyYM|ci-t$8Rw#Ea^ zAi}+gNuo4#`xGGKpvQh3$DIeH++CU&SpOvOU>bE%3iwdb|Czw6X1R436}u20FDlF- zHE`xONA1YgR!=X-e1y9Q_N~n8f2>GI^x^e`NrVX$NCZrYVA+GowM17JHbZ~u@>kpz|&7k8A|DYgDN!P`m1T0Nyl(Ukhc+VFDkk_)^8itXC27TLfZp9yf=(;!tN-hl5!%2=oY3E z6~)0Agd{fIKI1)$Z0L5`Ms%&ua^ErlzNsDI#eryGApa6JA30j8){n~Ej_fY?au31$ z?&cG06K_8Pd}OCq95I!WL+?|)TuNf`Y}l8SglL(cy#wYzCh#!UCw4^&_<_oRq?mpo z(r*@~Ws=0loJfBgw`BlYz68^Ko1jm0yTWj|T8=+S39~Uhir@(jreVJvi5uB|n87Mn zdUBx#L9SO%;5mprQr>R%-ku^Dm*UaDVKy!Sx-xex3vj`}o`=RfdYpOt5z+@#YR&~a zEcsK;705b0@p88-O5`pjY}(9i4;y*3%Y}onGKCs`Od7}v#L;=j?;H|Pu;t0UPxVUnd+m6og83u-UQ?Z=eOHa6(t8l(Xj3X9%_8TYJ$FKXW;QhcUOs z(S*{7^{_yu9NPJ72}#Gt-w*dd0#Hr_XqU=P+B&|s96$xGATa#x*G1E z|9)-wP6_9o8JH$xl*@qLSXelGg&`(k63XdLL~on!3kQRmEZ3^7FWmmve zh;sv&C0Fdo}?4bXoK z_z^J)rH5g>Vb1>tRqsbpG2)zSE(ck?O>bbk zB*+@B_(6xu5Icebqsx`B zCO6=4&drNKDlbI4V_Fr~Nj*3voOl(eecy3YE2=pJORDO{U*`^W=62|%J1!r8Gc@L! z*3_hu-{qm$#lDMacb6w(lHIa=D2TJukn^1`2{O6UmcSx;7sYPK#z5s^k;-kYP6#$R z*EDH#3%1iVseB1&J`xj4J+57Os+xUD8jdMvpVB^pe1<#{?hXH_hfN5I>{PBGqnD0F za*^-RFi+5h9+JxbM+cZ3WTmdFiF51bcjHz`7oF!-<|8JcU^rsvT$UGh*9b7OvAu$w z6rfui9TL*_7?|8Maq~@rEhE2t>6jPj{@TwsG%1)Xl<{yhyh4VIVYN!KLfvP}F1>+O zu{w}X9+V~Gf5Feq{Pd5Mj6$$UCmav|9>)x&B_@XTUXee1oNzdDiF1*vU{h~gVT)-q zz~z}3To*9;5B6j#`XUwn%^6<7Me=|9?_?i$y8wT-+sBs(AK4yTtg7T4pR#YS#LZsc zFo@FFBt2XbH#Z5p8GK*WfP3S1Y8eRTCEL>>OM=)Y;!1~H7i6@R-`6Z1;N>?Sugkx0 zvGqhL7a1+f?^A(qbwVx;!1s$%{XL<263F{l8A;fMJMpd^I&J{(VBbcIisrqZu#Xf~v9%r}PZ(@!-qCfs3*M zCg>@14Ef|wLNo?0SjY=R!mHS?%icg8wZMs-I9r)}s$<|i5|8|z?o*#=?VEz7+`RfcR1m)heewK!`hLuPtGwH$q8j3`k9>jGjEtfbM`7UC zF3$UL*_s#cVv>3^WILD`Xuvsd8)^AA%%~ry_senYIw;8B5Cc!vLbSgqi;F#|0kinw zzim39%Ja>g1Fg9BfzlBm^fhWO5xv_ZKGNMm%9BK&U`j`rEZD@{!`y^V_sNuc9t+L2qxOtgkrB51~IsVd`Wf z8#ao&BoWn|&u9Op<@HgDJWQ^|sm9;_mF)KA%=t7C`^XB4l(>*%jj5z6{AQQ%wNEd- z0isx3FC{Dn1SeejOrYI7KY;3Bzw)7=8)fOApP+7(#FbONgU5vOw7M;Nd|NS# zJGg@kFOxm$`w5G?i+%FbozFoVbbVLranV&mG1?PzR%8FxV~^Ni)a1shp!H?#TX&Q2 zn;Zg9H_zV+u9Dvs&x&8FtxPPY*ED$CnZC%53r$R9N%slL=c7RA4h~Ws0qb6m#XQe! z-}ZK=6j?=qU&{QqEDDS8Wc2S&4C5C30HX6xU}zGs{cM8oEC-b2Jxk@o)YiF{vF7L^ zgql4mODZ1_p8?i+8q0V_JXOne=?MRM&x}^GrI%M{kP0fpKBE21K&yg-nY;U7y zJ{4%v3toY5P**0KA)8bTr;`p$Ol0{J|~c zVMh(WJ?OBnk4GAW@%G4PP1_+44vxo_2cW zB7^;C#vz3^6$##AYdfABF=Uvv9Uly<5*FI_E?|d@tI}Q|O`1a2O!XLg){Y>;92sMz zPFIMyI4dh3X(C;MsM_8nzDE+jnlIY$LVwMv1d~4(gcZ~km+YxVuEY%9GfLmjKx#(v zr_K7~`Az8Fuq5%d)Z5h2TbMmh_g}EiqQ5)O)jbBo+g*PYr0O@jwyf1!RsEorpY<<= zC1GN}0%`JE6D7uR+NNWyXrg>XoeiLe)DDYBinTDMF~&x93)e?bCq=`1_E?>-lAyj4 z9vk--E_I?sh123%*A3TRxg~84L7_mkqNLG^ySSI{h0dQ3d~dLC-@3ng`gCqda8a+W zdqvnTL*>gV_O7kykJm%_NM=^=MX!jxgN4416S2d!FPhK-9cLL;WSFiw)A7xCx|^YG zc`oORh~igxvie@r1ra;%)Lt`k)>^0wd+t)W5|U8k%}-o8Fo$npHYRi=Xwl=_#U~;c zkb4b=Erw@->ev@-BWw*>fw6cw@;<)(xI&vUhYX%mJxOX(U?g(DqICe0TAuMio~&yT zBs~^sM=RuqYU|mLs0_ZlKR@4v`A@%De1G4%|5%jn78VS3$6&Nv<3$HI`kmwHy@PKC zu4>L_8Svpq-SS6`)ob=iG8(>0Jq2Az+Z0;vbteN7OOU}jDaj)FJ6A*8kV?Dk<^63{Nn(NB`RXM4Di(p^z6@>s)yjn}Rq?FK$@>Ax0w zq!_qQnxX<7EgVn$EJihg8o6^QH~zEV3#QPX?PuGqkS zp`O~Fp>HlyS=pi#Leem>qc;b#Q9yE`%0yt{Yi~>#C+3Py6odITVf4Y;$uOLRcWip9 z03F>{YCTa$yXdLqVMa?uG-%`Pz}le^bvL|i-_R5gQD?m4^%;Ho;3yZ4*^_{nuI3t8 z(!i+2?%O9zQ)2rcuYW=* z;YYS_BG%ombp3JehQ1%AyiPsBaTZr2v7@BX4qQy(Yb&VmvnkogD&oj~5j9HJqlftK zew~=zqO}#Yu-O5-Yc^zkXl$@ zT=A2$7*doy?@Z8xbw(DBr8b<4(`%oxY`0atm_B7aXhG+xusAXJ3OPU?riduqIdmjf zfxlSj!MmrHu=*cF$G%_OdxVakoO8;pP{Js=2Kbt4p;ei(MCYLp`lDp8Nx_y2YE{RD zvf+Us1?PTvDEe9LYIbA2$-{k{d&)qTY|R5s8)`#yEe?^+Vm2u94b%^{S|Ll8&0Af^ z9NqtOsMke?PdA3hYd$;{Fy#VoBGeWHHI2U%-?HtPIKSuG>B)?Ze`<4nqC4pEr7ssC zwx-Q-mthC}A$Daw<<}gEOH@$R*`t-`A&Z~_2H%^AZAemooUp=gPUG*8HXBIzgCK`< zF=rCRP?z@`+#Yl%c+-C+!StI^wiH@tnD#A~wVLTh*RP!ho)lY)K?Tte8v@j4!6=^# zYh?3Nu3uXR+G?yyCF?bsd?kp!=xNNYHw}dtQosaag*w{d!7Smet&94+qnmTqj@hE8 z%aCU}H8yfx(`i9S)(u;Xby%A4`=JUGiFE``?UX@=Z+x#HUO33%TjCK3BRqQzw+xKj z&C=@76RpQNEiYN;t#$a0yVj`dLRg5wT_mwgZr^wf8>Y+)`KO|vn5B&@wTt*}+dllMQ)4+u#ep=%Bb?-_0BNP+iLpLW1-mhT(2XDx>dds!`r7L#f8#@X&P$6|} z$O+ZFjrQtfQ1*2v?Z1Uc^?i+PC{&L(B-Ko?zQQJa31D*bo-RP_*tH@#@MjAlxXk_+ z-;*3OV0_GOD@T1}og(Bv!j}bILiZKb9E(D|>Q& zh-*P_23P2V$dDyN3NCwONQF;Wd~Ys#tC(9y_mVU*ejyY*-_Py+T@pIAxd6)VU!iPhm;zQuCw?p$P{zZ0{`A;h!qugI>WGQvdf6>Qeg4zZpK(m2EC zo*oi%JfRKb|z-fX6@ee(W=lH(4e;mF(8ijC$E^n3`CCG`)I% zCXdYJ+h8)h9s7dQgn1y|*0?WJQ|v{Gq|aH`!~1Bd`HOEJ)g zSQNS*tt?Zr!2K(mC}qM&rgq8^fklEk`E5a2*sb;*6BLTmtLANm27MIFgU8-Oo4ahSg#2nW{;ulw0m&udU|No3bqn~{KQ&&^Fzjk`DI7N8a`PQJdUnUw*VVPUH40EVS}?7 z!LWROJRlCSUtbJqKyS;UBR1wa=e4c<9ArXlD8t+hKcT91O~4IwZf!vlC;j@oqVLYdPyed0Cj5E+MWRTwuJy!D4VJHi5lful$5P|^$%NO(GWI~wUJ zY*9ZJd+*V%DUd&Eo&P$A{|Grdpg)thRe$*#Y;Krzp)WCGa$2nrJUsL718e1ug~~Dm z_V$IfPPTI3-a9ve68!g0rbaw{R*cCj=lzU6>pXZ19;V&ae_5h-=3~=86$^pUZP#MU z^=;)f%xSMv$u1#W)bAWq({8|z3k#WF_bTCL+cgDR%-X=|Zwd9cn+E}o6Hw8u+w^k}0=R(*Jy(1+dC_rz$W z5Qlp?U47RG5$GoS34=dSF2zGa8|@?P+x z>yl0XpgS}{=B&4*mXk8tFt@aHolXu{To-m^PIc8ZQNac z?VYGS_{Vbg+e&_GnabovhAM>(u{0|y^@g99USqqnZm!I z$y$H@bH{5hsXDb*&AzjyOCPS;E@xP`^IQ{5IQ5r&g1zha{m=4;&5-8*jMIcoEvGN! z&>y`bju}6^+T@~&GgXg)tU*?P5B$5wsV{#hAZ?2cSr9OZ83ilo-OXN%!SG;F*~8ma zr3p{*6gYLS`_O&!I^D$rLqbtA%q&lUd`an^4M0(p(QX|uUl4Q>L=eefXQ#J^Ei~F9 zvgw8>W@tOPmKz}5b6hLXsmNT@N9WpgK~Lr5cO1SA2>RxU)4o(lq)!d-ATCjJu;Dle zV#Z66I{zGR*Cm9l~ww{9b&NK|M{@fz`6-OVi{c8Q+L9Jm3VimR|3{C;D`6 zQG66ormp|h>0OrXS1UXfmP=DBG+yRMJl$?fcz2;n_{l9;Gi;=LLEx*CeNUKGdkZ|J z^^z|^WSfGvjO03AgJJt%XJ+TgiRL82r$e`RRvNnI zY*6tT8=G=A5-04apY$%df7<+sja>*iIQjV2`|x|Zmi?Ob|LxfxQM!05`%T_~8XPhh z#CKJ_(YQ+hl_lPpRlV1}=&o9VY06P6%P3jetue`v`}4ahw!Z#iy;uignF?Juz|L22 zO)&zRx85gnC;6yR6)ZeS8IS*z*?R&_OPv-^aAr&V==>UM4Z&uj zFtGv9B|==XGTiPDSRkN|gpiLFkS|iM1bf_jK|qz%lDQMCS!lpg6e%skER^s2eCH3I z0(X>u_KAQR@icf?pzq2keagugUa;6T_|>h`|5ZnW5f@yR1!uq8eDs&`z8-{35RQPT z6HI#I!7F=iSw)=H?c21@L#sOk*S82A2z)Dm;s9Yr@oP@3ojiyapItu?ccnea{MJRA zIjA1JouaDM@nGOng=0=Lk9D%YXv6<-Exi>(7@Vpe`jH>N|haZWm5u zf&SMGYx*TvSD#cAkNgCjApGK6{A>C?t7n>5wqX}PKaBd9)afvPa?k(;>k~c!VNO61 z#(omj_JZah7*f+csT{+DSOjYtGKr>hFC-)vYcIlOtWg0HXUfrgoUv<&WWL=z`f_X> z&X`h2;Xz*CKNo!Ez>R-M@N8zWpCUFn?!DIihORJP{$t>QZ=>gq{9I*5@x#`zuH+9Z zJ(JuiSxnz)tAxY*=*YqYd5oBx?d4i};T_Q%zkVDqP1|!g`tqiQNaJJ0j(h7iiSaf& zd#O(8T_fbi&WN~okSj=n9bE)1 z7W-7&W1n^W)GpF^`v*mhSpS3E2so0?zejEE#2z7L%a6bn@bt87pNWEL#h39ct^#hSU*FLwf2?ip9$8rzi)en1#^|Gg94 zt^cdutL*hZqZXx!Gl%fN#|1ZSUq^VLw~yoJZ$no8zmf>PP2b#1&P&g;t}WJFy*L%d z)Bh1%L(G4s<)ciV*6yP6gd|-KX_Na}@SBN)`X@Aa9;U+iPtP@B)>&E}aA%rUFs8~V zU(a6vXb7ikg*>KYVw4=49(|S1%Hmm)ZLIE8F}<@Uyn;t3?7Z*U8-v|Ux)yo3{h|$- z2KXp$^jo%N+~$4ENcR2FcWtpaQIT&!*snbt&bJllcdu3ah^aoq-i9 zAh)GXagMV=sP}Q_nG1J-R!le7pNRE94(c@#TUR6I)K22X0E;Tv#G*yhFVppKpRAzu*k_dVFF-<6q?GFqGh!3WFp z4@uZ?i?AeA@P=v4KDoHQS5cPxuWs*B5bj%2ASVYsqfsX9J5bP`6Sz$7Z;(J%z{tW| z5$p%lUpjvTG}RaxM#nlyY%AzTk51qSlzwDLH(g^pm_D`mZCH>DD~UQ3Kdm5M-ZuOx zbt40!Gb9y+FW^vK2CQtRshJ6}Q4^OpviGL6_q5gSMoVyp$*2JNnP`qW`ttd+*XO%_ zg3qf(b6&d5&Tjj+|I>=+*O%cx77pj@nHi|*UCSUlBst&xWxcmH_Vj(Wu#}wDkGDu> z<7%iP-!v18&IP1SFQ~Un^%cgxJL}l}jmXon(#+OzlCSB9BZe3FG zr-PcFt_DiR-PEW7K>Y6-Y>D)&P1YPPMy}3uF17Wy%0q_!Pyxji~07m=aH0J~B%xChex%mo3-C+2w0^s|DLD4bNRE z!aN9{u0yVj#ElRJsJD*T?Q!?49V7>tTWVvX5n)V-0Vz7$mkajyW;YNzxXf~Zfn*U} z_1(c}Q%nQOHqz8`b99yi6D(nP_QL}xg>%c^4e&1%!eMQVm&srFezOt9dN1dW8y=)v zBBdsh=3tzE!^P;F;M{T2Xz~owV`nFd}%pqhbaZpR+5t>)T5tpPID!rB=Kb`m3 z!BXeY$9RyIj{C^0$7y6&JFw;+Loc?Ica7x)y39UR$CRBwkC_Duu71h|#&`VN2 zhEl3EAC!M+z@Pt|bKrS7*>?}ZJX7sfMlb}%l(uNf6Vx+$mI_Sf0lZx82xmjWBcElY zZFKkDm{n@qXgHCVcaIEWzrG7KYV>IdLRtJ^Bkf}QIn6~}bk>P{ z-SO{+h3r9u^_R%lGa-*t%rAkh^1Dz>-lh7>xxlUhjdIgy6J~@j3lzv}HQ4ZKCPq#Avji1l-!7zEaa{SZ2=Ts3&xl z4U$2&BRL)1y%$l?FD+LC$SDSAqgmhcngx29_kaymS*Y#qUy>)Q_#}-odi(OpeUv}!^nV&&CTQ6HZ!9Q*F0&EmqZSz#75;y`1_(^3;m3@X0r>A zAyBDfa3W>1IP2k@F&17Vf0__TmV5f5?u2XHISw{gVsJt^RF4&PhThdc)p zawp>?G~gO!yN-7C+d+IcpWLd+Ues(gfIaIE$0vbQgVu&x@w6qh<);u6jVjS1$O8oS z*rA4}j6_C6`;XIA^LW~hYt_Fqq5GLbI@&MqxTN7BoLbxnuD!#b+Ws^-Jz6U`SZW1+ zq&G+&1|)w%MZJ6zfd+mUq|yL7?Z_jL6#7|o3&g0KoO?Q5ojg-fn74hS7!Ibd2}o2l zIrcZl(>tEJiR0<#`sw7f{)JHQB1hiJ7m8NYc%_A$Zo#3G1#ms5yAIKE-JACp^4DFD zUmY0-zL%03CU~tX= z%ynYTZ|XHiHi0x)EK}qY>08L)Q%yj5gio+Q!^GYVKLbHPM3+nva^xU04csEKE91^fAvR8debpDgJAJKZJ?WduodH1nzN?pn>(eq?O@K2N$jo2xDh2NFH>U znC|{fTMzWBVfw}2!8ih6<8+QGanL(A&H|xNF$Q~+g;?9#Ef>|~k&p)wC57o=%W1{< zQn8h#KA~Gd`l!oG@84thvM|O>1+&45oZ!@4O-&Vrw|NPw0XAZ_TOcguA zf&dzW1qu>f=!TeEY{jWn$;TSq)`7qmPd@VVa=&o*e&s9EO4x{T8c9_EHdu>|At8Ex z!E`i&vpMI7?+(13J#R8JKv2?2`uLY16%@uJV`HfK=M|rt5&%U6Ux|chH|cSDLAX%$ zf~%12d9)onUU>@meYLEXb;5EfgAnv`tY)xdohS;!D|t1{&GlG=XaQ!yO8AF`ybB?Y z><{e_Jz{@2bKriI0G2p7w#-;tz%Po(8b0x^Eo2==h?EzC{Igxs;U_9qN;knhdos|fQx~}epAdi#DyEW zmV`zHJ`CFPI_6l!CoKwhj8H z@#8TJ+;Ny?L}U)}PL)-n`9YWkMpZv$;aG3Ad?>e419F<6e@-bnI3O~X^WQfQ9F}U(_D${y>c?@wVKru8>#Z=xz>q=(5m6zh?~86)t~-51c7XK+g5q7FC-0l6)7+t~hO@Xlk6 z%9Y#e#<`U#^+nM_@W0+KHR95QDHcyBwatamIwrc`EMd+AFA*`ph-%B~HLksUuc}Xs z$9KA=;8UUQEN=gJ)=)J>Pg-^cZ6i}jX)>k!g~h+3GhD46xa%g;n26`WDT=<0zAE!C zar(9#!P+P;kCx|6HnL3bP%y=mf1*pxmN#^l4ALJf3ig|MP_dq$lD~aR4tO|cCFd*l z2d<%@4x7PlbmS#ZKkQ}?7NrF#eZ-1X`N_Nw+795y`mZ=F?@jIW zV)OJhcxRSX+rK3^;`5fN6%PrDbMjW@QG5iZjkbR%mKY8Jd<>7EU=d*=)0#mCe|;whfye z_dPuK^Stlp_tVR@;1d?bQQ|-psncU|E_{E0Yc)K?B4U| z@Ph+Nd+s5lH+gLXR!k}nQhmjVeU|8)jzbHr;cb-M?2eh)@U-Q_JIntoEG403FKFx4-jFH!W~)ybmnrl+*F% zG`9toc799%Nj)HcFvNVAgfd1@%L(_PnD)?hU4u3~9uzvvRQ%m;1mZ0mPr`4;NO^iS z5Zv@wCSgF2;}N_2hr@07078K2KJDBpyzmm%7%@?kPxKX*jq8jiiJ;w^E^MRkuI6Y~ z7W1COr0I0$&jdhTLu!w1Mftk7nLXvdH|~D<6r3&{SzH`_v~ueFw+D3EYxJW5=9qR* z;xhmW-?p%b2_Nu%$5T2FWU)_flgminG)*4tl&#S7^k==@?M#faV~S5r#?Ey!}^^4waXr=YQrHmoBRpAn_Wv* z*Txn=O|Mln953PIL^3*OF}YeNyGtDQo3#nC$-x|t@?9Zkw+&?B% zB^W&5pyjTL4j*4e_{dzDdu!3D3+x~Q1!xEiVGR5HQ_|pF5-P2-*c+7n_Tg%a-8Y|< z1;k*izyrY|ROF2Kc$~(&S}~jfWYTSX_fF}?loXlo3cf*FjB* zYD#%#r;Dl*__;=n@J*lr%?$dAp+HMJY z+nxurQ=$QdB^^v~c@624uV~97N5i5(S$HW=uq2qu5oIxFnlByWa(AkYkuEisDI1ID zDtyhJM3bIh6Ac=YSkgkt8q^_mY_P^x086@sXsBPEBK`s|z_( z45zT*uL7fB&Tpc)O-vma$?S-&%QT&6=a-Oc5uc5$DO^`<#go9CMk*Eg7r4n@(Phkx zEPg#!9<$rq5452=n3CSW4&SsDkaENXgXlwzTf|j~+%Pa@`9HkPP;G3Zw_VA&7Sn`( zcJlCoaksOIGKF^rV9g--z0urZh?26bvel{V^PJOnQtr-#kS|90Q0j|A zOgnuNjI8=EZ%5bMEO#t^_qb`W_Y=tWdp83o(u^nqA|{t7dVXM#rnL#<{|RZ*068MS zkbJrMr=z-Jo*Ab_kLRo$HmS;eSHN4G2|L2|=Q;oL4$pr-0X;p~dps7hk5dh=kNzq& zS%mI!9g|HZKvgXk>f+b$g^sM8ExX+9ii)8L_DlD5*hTL$JVseTq;b~>K0=m<-Uc3q zlb~wPW^tzDFWjp_im5%`q;7&+l2$bO&2qzY?GFV^5$<0?vaLgH=g_B8X9ad2hgCTD zgEJn=Gp#Z1`+*iH{qrc!ugo2cG!t+TUr!+M;vz1eur+X?*uz4$5rLRo^+yM*#x{Y4 zN`}-aP<+;z9b^UtP@f-0@5!+g;`og7W|MB9eKg`=qMH_13;OfZuyTi_PAlHu&YMam zW9md`8|fNlhcV1*tyP<3`&Gk|-+~)ehZ3_Ml2^x*4&nH)XCdnSr6WsrQ<@<43+goE|~D1Qsz`!(Lal)j^pJQ z0K|l4;`qG~(pYIegQlJ}&sS)CN5DB6nFOHm(5fcxTH%k&WPxH|++$mOY| zbY-iFZevbg9CGW3Q>~cyFwV(km}WslVPYtFKng4LkwRDcWMY4RxQWjk#OwWpWzM_0wN7W6_FhZ7daPA6{ zi&_;`d|kJ5I8*y*HEVPoMrWk>T40gUChDTWazXoGsQQ8|WmsQ1hzylycC87qT?ZB`cV4ZaWNN0F@R6cyGfzVV$W-{~ zEzU&V!YvJu(jhCqzB{PuPUWMgCvwNX*=p6=1C6byjk`lfZ`dA#HR>ec+%CInH7KdA z%%=htWo*Og!|JZ|&1)(~Xm!aIv~|XlN)D)K!(Fkcw7U*Cldd_{gLT~E_ey!XiJWqb zjtk0Fl9BSFfIw!?qmbyAYq9d1$Ped3*!*oNib4}hh!LuH5P70uI^3DFEBxtul?6+! zQe?Gjh2C9>o&9?cYsb=U2w1jh(bsT|z6o^l;D@Y_b3o_%N9!zQrA{jT?dx?-q~F^8 zc8^9+IUgJ`rw+dU5uaqDwUiKcF6N4|2SmBU<=*)Zmp<*uZjAp{<34CiQ+yiSdD$X5m6QylfR}m5S%jtbL#Amh07c_{zItC!y_eTeV>=3Qg~^ZL{)2UDp&GSJ=LZ zhol(O&lz))7Yv~8TH=9f@noVPnK0$1?LC^e!J&10$0?V52GTJim2u(tMr(hk$ zb|ny`(~ObrEZ&AsltJ)RzG)3d-5lnK9LA6Fh@^Uumtk(^bvwGv3|4HiU2Nu9L`XuR zKV+yZWaxb{rc!vY2?mTV!!jdZ4cC)w(CX+{=IxVS9WCZIsz#V0qu-}7F|HJz(ASx( zM&++8Rnd4ySuGG4+s$cMvouUwG@y4^eagjsCtPf9Hy^y|NM+s}^aTbt=^akI*}kB6 zROZ2wz0|0~>G|C3734C_k1~runLxjMLcyK23K*ns=dY>Z5Mqe<5LZwL5S{9*+u;YR zIH7)t_(M@3mET$>(pHp0x;_qTRJ&gAYfQ6wXP$7&gCg5YxqDNq(+pZ@!W=+@gVREk zmTi%lEqpUEkC@wO&J>u6@0wp60;`AcSs9?d=TyB={jt#3ekSC7^BO_4mrbM9x=4I_ zlWMLB`O7dKVpGGe(@gd&vfHD3&=qJ6Sm+4Qvy7aja#Zd!cuc-cnkdHAWwD8C+$4y@ zyfU}>fHQX`w{Y#pzTyj+;H@OHW|8p;f-%KajZ}uhH$&Fb7TFK90!|hEsM2U7{bi?!Swezv!TEAOdK0GJ6k0= zuk5C=p(?3F6&k~g(;(ou<@NIIq42@3xCbnWP19-8dq=EGp}TN$&Qu*Dj^e&I^AX;;bm$w>Uu&q zm(jC!dr4R8*GVMMp+Ri00KBNiIJ97HXXtQ+)>l7{cZ@^^&8k)rd+ZaE$~bDU$*u8G z8;{-7Xr2zYSo9;7bd}uaHSfFmvty3b>2NBLhm2HD;i@BD+*db)D0lL#4_QNzxtcNy zT;*cdcN(RCFz2|$)=Ge5)3{g{-=INoYNTU(9l3&|7SA{si1DL%XbR4-Xzv&*Yb}V~ zR_Xhl+fV6!BCW@{s&@!bwUSM4YxcPt-zAT#$^yaZV)McY?NPVbL79G$324jjm~XKIO7OtqbB~oqk2j+E%U$S?I%%OZaW+^69~B!cOV&i5%D=nceU# zPP99cRlg9VIdh396-EPT=t( zG%JbPe@k}$9iedwY=@|{G{hUrU_V>6de3h#cct~unTijX#q)hG%W}#P_RSO{<^@xm zN8R=3H+Q*ztXgwG_OCu1WwU*d*#Tre+WlI)@E8V{=ZEI3D|99zN@V@whu=)gHtVy_F1 zy?3zJ>Par%0-BG(y`@ODuDj$*;Kl)3B<@1kTpse434lnXGga zw!)l%=7zu`AjyZ=q9D@FWghl9kewvHzpE}k+a081_L0)h&ryy(SFIiw;$*#+Co37|?^ zcC{0gT`(7KJCf=Su09{u&(Y*&Z>|h|X0^p8+Yw!vd}b&mWc(sQf6$RK!!xlucXRDyjHtSCROD?-U*BcX}h@4sXEn0*pXO;cjSzbul7%b6CJxfys za=Rns@bAFGy^Yvb1Cr8L&UQ1Jk{+<#VHVp^&3i_%s;;L z)=l$9g5j?{3dB6^lRZfNE`tN#@aG#2Ke*{=#y3frbc`UV&2x&&LN6bX_Wl$0dw!b! z0l?e(!pKRth=iD^*=>7|8M(jPbSmjK?+JWj9Z+H|yBa1P3>z96JY`G+y3c5)Taw>P zTr|4PWKk%U@GGYRpUI50mb}egJ{}5t=!ajnBHvqLvh#P>5;gNoY8*Ay;?4bL)Wg*o zrw4act@*09LbPW_7yLcC@Xe14g(7HpOqa!LyEh7WEcKxDfZS8)22&xT6a#| zy}ega>AaG^NqKr3>p@gSk$gx2k~9{D5cqPjggOZg`n<=?pymW^04|+4GxcUX81sV1ZX={xB!*WTxDNU2+3v zRaRcMR-Aov_^q52c1w6?ox*(Z($HIj;XA+m$WV9p^tpwtueP2j+P->^bp7L~m9Eg= zZxkPl>Tdn5XBhImB&hPvGj%iuhS*>{A z^P=)}`iK4#ANDCej9iJhl>YH%MA~)5#|O^w_tHN-R~#Nve0m)*5BG*>y!pJ~{N-Ev z@&#E^e1UG1qdn!|Rk_MbIr`|Af1DR||9sZIy0GHUg5jzK#yjZ2wFmvUD1tg3@R2z#~o5CjB+5N*3V_~V;0rs^pAXUn#`u6wj-5UqK9H1s-} zb{)4}@$1s6pK)6wxib*OwVzi{LIziD>$nU-NYDu`Xz8|}1&49LGZ4gf98!XZ5b^vl zKvmC4M4fR_$5G*ovz*}c3KGN6*1V0viU+L&H^L8mEA*ZhHH zPTNXbryrQ88`VH?-wn{VnN_3`U1M=j71~;-dDP~J2nluZpr3Tsm)&V~3$g%*FB-GV zT|0o|xxQ6|k`SrVZ9Sh|56?X7L*&~fx{C)+^;v>i9C6TRBW1u~?ewn6vrtdb_zMgR z_4OIs0;j&Tg5A*y?IFEH$`0(aR7r;#Ie$XC@E^4O{lbhXPl$Nr6Lii>KEKOb0Z&uW zcFzB4{4P7nbU%WxaAy@Hpp&m}1; zsGyTP7pkfTkwNmu1k2xuCO<4@*mOlfH%w$AA#J)4hJ~;5yWk4A4hupGiul2;+1W9^ z{aC^ka7S&@Eyj-HDKBz%oH+D(e8Eot*ye@dC}JSGsXVte{jzi z|ATvOfQ9vGZ2nK^d0BbRQ%b49q?}TVZN*xDQn33>qbKI|(*k$qgPfE(C?f=6)r=b5Y>sep_kCD+IbMybPo;}pAd1L;y zo`Vgpg&X}h^t}H6f}S^TUY4c*L`D4zJ@4E1=kVcwq3101tbFYMD9;tv|0>U|Hd)g3 zxy!h75372_C+o)MtOwy)LtCq#MQ2UKR8Q^u*LQxkGwW0Gzr^#mw5*x5e~IV3fNSO9 z|KiRKyZ-f^mvQHw|HhqbYHF5o=Z1!cwzjr&=guwT&Wfz8uld#g={vs@{_8sng@5w% z|CE;g>pM3z{6Br?`^Wwzo}Zoimv~;j{*!qA-v3|3^Rn-}tUNCh&qG8163@%p^Rs9F zMLf^V{r`e^URIp{&(AXE9P|Gf=FC{eoFT0b+SoB&n0bi*!?T=9JWJ~?zb;era+Ytb z2-D1khrKu6TAn$w@}UYNTcqcCI+6P8@rP|txw1cQsoYydGHpmqEp?@ae! zYe^%~o_m8SRKN6nzD0(4$H4dRG++NXhlYUu=k1|2RK)dK)qJ5ycG& z=nLYm%(D}cwys-lJFdWptCilMyPI4D8jCcg3?0cGN(DwpOYA@fB48>w^E^X=dIOzz z-Y-{dx(09ikrp{of`E)oxSBUl=bCk-LbU8^PV^ZB$YLRcYpq1l(nL_=h38DM(p`=F zO*D~Hm4T<4zP&+x7sU*9N=4T~br7&7ob33aXG=eK785@Qg%PB*#N%12t(6fIHb|)Q zbNoC7rpsfG)tjld(JrWC7L?gpw|GY+Iv+w#}`(xVs$|;X_U#yi@nrb@V69dVi~b;{c(V zYj-A%DYi|Xxh8||+q1)+dvZ`?cCQ$ z*5i^E8|`XHSx=H-RGhQq*XJ(6>~ zvz^fNuo))kp(!2!15-5Se%#`Y(Wdx%tvHNFVc_0egu@8Y&jn?fw3iU^aTeb>FE+nb zl&`rkjCU~1_G{o`wU)ILf3P|U{(nUg&g38~RjxLCgG$iVN6@l*4 z#YwgT)NcyZP=5wdx_HXiS{J%ZAD32_(R7K$Io4JsgzY!zW*PIj&H*JQiIeX7=94)= z?JzBzmCS;|qPiNIphQ7JbaC5dx@{aH*YP8?^z6rI>XA4m z-|615=Zi50`H6rHD*!QJOR~isWKyk4HBUguMkjc;EIGqCx`Ms~?mVN+%pFiYig=4Y z9f}q>veXr6BWo@tGDz*S#7?>ZJq$r^ds6}nO&zpxSnwt2B@5(%6HZgw)RKsSS8&z3Utjcpv6Cz!-s1ZCdF9_P2|)t#oq)7J?G0y}-tZ#@}>5u|t*r@dtMRZWK7(wFieV6DKmr zKro?<{f=aT$?{H_X}PG?qjThdO0elBPE!Re)I32{U@~MqHlFv$e#j4KNJL1@&j;KnvC%zN45Gm?gBvSF)9iy+Q;3 z7UZ2aBg%r=h8xw_EodE-2x6?)qo1$j%aj=K9YxYi*!pOkH+io+K0MQ#In#9WpE5rs z(FuO+1YyOk+orQRe4nW$!z%Vy1)5?lW|!f>mMW3?p~DYNi|*h`?T50@;RDz@GV^T_ zhAv3-K!EOoMtZv}aLrewReLhX#ElsTKY^R9nZtQco$>Hn7z5=qH-3Pou$4_w&~G~B zUdbcn%MQ4Av#uKdlX*axS}|L#yiwaBQzu{S_a^JZDb?7T3s$v}f#;Gy`V%#(x_y{fQ8n?rm~SE{x4?!0b%uqD9Wc86b3m9UqF)3@;TgALQQSWg108HAB9c|O;e7FnVD_n2A9rMrVj z(#!J&W8Is=i|2@u=)N+DK6hoJ%86Nx0N$ErH)2ltO6ZfCt#RXq0XgMe2Z?RH4Y;JZ zfQ=R_ENr}dA$PXq#4DxIgbZXdwXrk6W!U`DB!(*zZNTENjoz`Sw!Ua|jt3yFA*d_+E=)|uhO z*{Z=m;6;d0sspe02)z6SwtJC=a%Q@%%8pTi@rZv^Hxls{_#BL_m^{)S6V^GI6yhZW zBcnOIJ?b72kOCY+h?)tz{ygAy z$rBY$Qz(}5=I?-KWlR8v#q+q6WnG+=n3`=i1MZ*#_Up1DQTz}SFslkvE(Yk3LtjJo z)5|jvor%qFQHMuE8%KRlQv-O9w8{|JA~|!F9O^KQh}Kr|M_>ff@B(VSQYUisQRqu! ztjYnv7saP@z_!UuwO&*!LWDkz>XZW1OyH?KYLyAp@Pby~JZ29Y>L3l;B2?Cu?KCz7 zpOMiAWA}&2a;;pJ*Arm>X?Pn?bkt)P0=MM(-#N%rO;ulEA5oa|roTj@DKOi+2( zbkDTV0l(wrJ!=Mi~v30la-ryIu6kp>P-gK zIuEElI0~Rs%&N2EIhB646_zvLS@&Z24CpnFu9FmpKztH@pw2={f=A&?shCdb0VYJu zpn-cw0nO^@Ci-sGI|bh2xCg-~v<^}`2Jn%UyWS}^xPw@iSb^Zj=HL%wAEQTN>0SrX ztsE{)tm3e2R$-LK< zIFxG339FP)v>2{$SadwOn6i+$uMa4h%r-)+HZ}sq@||0!fSWl-%^##9(WQqgfssc^ zbV%A+9{hri*2NZd41=L9Mpa8-PEx@Z0O2WBt`3bzO@w>#;8o+8v&${FZ-EL)mG0gn zUUE2X6kvivIG6zj$ zZBj2*Dl1cRm_c$NxjYIedxBm!1$>(d-Pr^;I+)QPl)=eNyY&#@wYXPyO$maA#Xwh78FS0tc8*!WmY)({3=tELbElzy!x;>{HatgZ_T=V#_ z{S@ma9i{mwOnnE+x*EC06xEqnzNS@djDv%_PUsr8!6G~6cg7o`8^yUfFBX|W6DTpY z4!IY(N3H-^;`$9})lzCDhuKP4$oAzS_hz?;p?Hmr*^uoh=iCE#n&8hz19!Ei(GDGU zuFC4RV8&zb)~O?%IjBwosF~7bgAUMN(X6w*?SffQGNkM@PidKY&HIVk zV-Jlbux^(jqr|aae`2XwiAP^=Ae0IST&29Y^NH6=eFCVa0>Mao0v&|e(^WlsW}nx}P^0P@FD%M`Mc z+I2;A8VKy#e|!76E>y&!W+3QsP;ny1OMZlr80g0XEHf*jcK}}xU~x6*0$R_x`-qqC zz3`GAof#!RHk^TCrn^JyQ0F%mBO_SneZJQl_?Lu9k&AEpErQbGnt(2juA4 zNjO7((Mxt}nuJuX1o*PkCjM7-tc#0SC&|-7!3S<01X&Boww{I`m=hjr(<<9?K>anG zdkAf$a-n51Gx#*{9PBjAFIQTApq><5(cV&smwZ`~7M$27OwJdb72nh1BLgK}=FcYK)``Vsed#2XHrlb4n2Bu- zDwV0w0y(lZ5fsRjL!^M`Bm+wYu4}=A#L9-b967T^pD;n7u`b^>`Gu`D~* z3C|k*@VLF``_T-lM`O^Wh?6M9^%wxZ6}le+CQPbqU7jVf;Cf5ovD0)d3Fx?lY~g?< za(EbRG~JTxGYK!JPI)O7kZZgL&Wwyj(VJR0(ZQp@UVJO(Vs4l8z{}BnDi2fXtjE|p zyKwL)pZmLJ~xZ<~hi*C;NtM*@n2V9l)zHxLLf1`td9(!GGR;fGGp~WN?@PSjqt_Su@DB-ZWHDA|2|k z94$^vWAdit9~e#qM6u+Vuk0Cfa(Ov`7qh@h>6dHNtmg zJOC7}^7JD&-)4_RquJmabJdRd*vRRNE@{C^^fO>R6!l!6}Cq9vdKKySG29;LSwH-z(nyQBE< z!n|}jIHH2~mRdK_-w&j;SF61SG-IUZ#tQ?lfplDH`9IseB*qC(bc6l#4!l6%tU6Jg6fT%{}rt@(MgEVeZQd_*U9t zoyJ>cq8vPlJxc>=X_8;>P&-wtI;LC9jlr#t0H?~hN^t=v_tO)r&f{>;Bn~k2?UR|m z`yL8(Um}>*j_ja)L8BW#uq#G~J+9%PX4D%@3DD;7m-)!UVj--o4CW{Q@-^Xa%nY(6 z5$sO*0KW=E-2P(z`O(@hi^xrww#0i0dOyP;w^a=;LV%cB3VY7<(HgiDtX95ETw$fmvS#?o+1V5BzYK2<&?=o zJEh3T)o;A1OLYyfFY{iykheAm=LU-2l<}4~s%4LkPJ>sz=+pn=7YzVk`k4|q;^mK( zd%+*)qsF!nAZdmxprc~@F)silUN06DHrz6Ihk&b1u8 z)lL#!M2LK;Qw;)4q)>zhezuR)&x0n=qH#$$7T4K?dH1f6F%%_}qWah5W z{2t%?DJFOp$Zrg?Hdvp&HV2#$GG)!&KIBZr==`SpE{157MAfbL06vX8_V`_$M! z9$ZfIbGEasT^p8>(%#?v8|K_f%1QaDI%BhU@U^!Nvnue;oB8rUt7?+k>hm1#m7h~d zbZc*!+2_tcQi-MEP?e~`x}2=rjL9G*dACrtxX=v-+@ZO~A0<;n<1SJaqzti7DdF0S zoq?u!qbd9GYi07@T-Y-^$3_jKR?3jbiZw7?vYNb}*lE>EY0WV%BfvH+`i*@)^SNe{ zn`d=-YV~q0s-?lq%`J+7aB{Se+X>Ve zY1#UyG9wraoJrv{>~5fP7$S#`an#)4kBI`yktY5vbfa#_B&$3z5JwL7cg!S}Zh76@ zRC4H9bFs!my-Z|Dcs_<>klh4%-u6ginB_Z36cA%7SIS@AWIMt9flrPFe>dH&f4cK* zpf~H&<>4aLi-RJ7BCBDso(;=-qss$VopKSZ5EMk`e6sKnsd~RDkGV%GEQoPGZ)b__ z_h5xHwh3(mTS|m}EZL8Sgok=KoTydZ*<4?E(PnZ8xq==Z|7BPG&W0z)pX4ml zmAyu&8y72$0xzw7pOq3=XG@|9|1kL2@~mZAgK-~B9$Oi>r(|U+cm6+4Qcl zm;cnqnj-{BoYP7$%-858llIC#El&)HixUSu+jma@~M{Iw`3l$~;3VoLx1H%H0=l!+p z85bl&qI;&E-b=Z=dU+h*C6pvy-a->pdJp+0zaMecYnJ7%%y|vxO}0MkAFOmUdSWJ4 zoXVYRa5eE698Tiw$g%z5j-mNSt!TM#X(F23slVJR^Pa6UG2OX2J-SXcSSld0tdLx) z>+h1#Vyeg(|9OQVROdjsAql{xei#cdTR8r#od^c>4q5KDWxgZ{Ab`&BwTjqMvs=yR zd27ZvV3t=h&f#zQNgE+yuwIJ`W|z{q^f;VqNJBkF`L3&AcF}hcg06+kLC``}=IY)e zuw{yFeB(elj!A=qp@N@Qrg@%MW)a1c>Lw_Y2@{M=tBXQ2O?g$tLdcohzT_BZ(IyTvYQ;nN{kO9-9Y zttG?_q*kNL^{R|{b?iCW_$(@Lorojz)VKpF)EZpQKj1}i_qRP7Y*nej!kKejC7Wvp z5S|ooc=F>2w~-1=u{{b~CUF|9l^&zLcGWRkST!n~w%Ev8{Vo0av&sY+&xa$hXe9`V zGDBpz+;?1&2>j@oxYP$dn>zk9wD5V>)t*QW-sc)xvFs-q*DOaJIn_PT9u;m-suz+T zuATmw=oNNtvnUpEPiW;%jCi)8>;z?jL`q#WlUN3gSkWRAH6oW^Bm#6aZ>7r(k!^a_ z0_{t7=*^__MyJBRv>)~VPiFk1Z9h3 z-?UOwVQS&=Vk7#X(OL-&%%|~@V-5`pV_R*-+{5#PNYHOy@Lq60LYA3=tF+WMmr3Ez zzdkgAm7Ecm-;CYsFhCCJll{YdhzL?t=xvCB52}QFKi+y<^q|O^;)>J5(hx45yw3>2 z4OhNH;0>G?Wz3W7pRp)k-X!Cav;!tSZeQ)9dgp|@vBlnZPq;|XM}jP`<(ZP>T?Se> zn%m6onB=r2TPing!d&6$=AJMH>dK{;ZYDtkZin^bL^5Ea{f)y=bzP6$huZ-Jb3e8X zI}AcRykxL zicA;0G1w~&CH#I;;s8@}+;}~1-)0+g{Q5YF}XX&*j&Zi<)rrReX!Lm=~SnXicr%D+!*@{#*hfTB?f0pg-VZI zG9k{F=x}dP>B$Pk6)Fw>IT!9jlNm{EK$){!A7IIYEQ+C4Jc1SW@-sS|EI;>iZ@wnU zag-`pi*O5KwB0xAwn7=`^qtkewAye?pV7ME&pB0})DvZdmiyR2sE4*C4>bMWi`*a zd7v_N<5jt!co*``3?4mLc3x`#oGXPaT)ete+C=vdN+gIe1dD?zS%dvcd zUd7|W+oIFw*q#+j>(wNb;yB>ga>x%-a%>0@p(g3SuKwX?{%R3?MxOE6)pL}6`PrD; z&0P-L_aVMClXrnyBx&KNr=|xTl}xFEb<(O8mxcP#F#Ej-$0R)?w=R!60`FSeLi_&v zVH?b!X^>xOI^8*b=(1NbX&rg0<^{&eN9tAUbcxJXU3luS<;VJsxebu7LZ%#c5o(f~ z4+btTt5b%Bv=Tv?+wkVq$EbEiOP%+l9Ae#V6ReR?@9}R>FDCr1R!`+$nXM&LVKI+A z0me8JaQFwc(kc<#B)QrE;GvxWWS2)1rO&8axIa86P%NCZS9{YrXe<{nCEW@)MkZrk zurIneIc}nfV+tZXS1g!ExM*Uf;tD5z$mQI=@Eo=XXoo7bgrCi-xl)*{=ECByoCYr0 zZY;^qdwz`ka$nw#dl#8BcgilOc7%jTgKa!UO1)9Edb!A1Yv99fyU}n7XamYtFdwL@ z?aDac;Nx4->k?eM{xJl5uQ}g}=3Bo2r%prg8i*FPzy{lebRTq{K5mX>odY1f0U z7p#ZWOU}WP+BU?VEB%y4G@EZ}lR`~WbGgS>`t^E%RT)cbn2+QFhREQX1@os`|9aE1 z(W(IW2Ej?KT!UH>qj!A<4bG4tE*#5yVx#uxsSEU8Vcu7V*QZY84iK;Y9MrZ~wRb9` zvQWnNV6V(^b~*y5-XZ7LW6>7p&)F+k+27aOz1m>1Bs5a#TysWg4fNa?&yd$<peXS+h8Y;rlwkIQ=)p&r&GM@B19Rh^lNrN+&R&4YU5owyX zy^NK=1D!gHeuKeHVDyAyFS4-ncv-#^j_iXhWv zIp>b#Z~vOb1ZBm+=)@acVaj}fDHd=S(n zSIc+&cX8X?s%0~cu%35{pp7;H@3~wOLMccNdn^JV5g>)0K}`;RxkNKVZoO(5N}Y5W zPBb@`2=ZWlWPu>BKZAe{zNj^`uUp(ZHaaqvm(nj@%^GCNAM;0~1CtWcvGA6Uh>$Vu z$FZTtrPn+_C5C;srZ3{<;whxgt7!M4m2#1Z20_0HmKh7vPJcc-Y=(-+S?zocad2C~ zH}w$KCh1U3Su||tall>QKa*eXu_PR)o!czM)omXB)Dz`d_-uj}sT`Qen1;cveQk4u z)&JO|xmv{T$4(o{ysM^sj=jiDjW(99*WIq_u@k9P#XJA4Z54g?#dNFPb}K8!2$h|S z3c>-~!61dz^sMyl^v3|k*dsTkEA(Df_s@u*YxBZ!6Xp>8!S#ZTY$1!VT^ZVUznLuy)Y^^QDydL{sl6&|+`UBn|gBqi$l_H{|VyUTFS%IR0 zBhEPEn3k5BV`Ty2JcRR*6`HeFR;FgQHxQbom6@8h8?sL*W$zd`CRYobve8Fqg{NU8%$gwrbOK1*BhHlsPT%Y1sr#6*d$0(Oz-hUEX_7 z_%0vP$JK699e&A)fAkuDanQCf5YPsB`MU}5wxM|qAY;&@_wa+DOsHXEX zW0T4XQd7@=)-@FIeg;bzX!a3>IOpeZb`=$QI-c*tFer);HndbjnC&I>*&FRYqjA={ zh`bm2*V13NHM333aAr%lAWsBLT26&kf$7laXQkyw6V$3gi(VtbHfe_GxNpi93BS)H zw@NykiPbh?XeV39r_7w%L#G2VnyWMA{&!XP9`4vHg8DAK_+_N8#YLhcQ+WU&u8ygQX0IFUCuvWQ)J@8 z_E;*xHmQEr)I9xcFF9T7K7|F}7F+DhSzgN0()NL)E1=l{D0KL_Qi)Ix*7RD^<#^oR>f_Gd#7Tq-JRq7K4Ux6O+^;|T#u-o|-6F2S2es}dV7~7I*pP3mD%d?+_!)U_a{>FT6O({Xt z>2Q-kO?)e{;IZSw2T;iM=Im`mC6UZsOGg`poGGf;n%6QPHB>lEGRGub5}D5i?luP~yf-J; zWi>g!Z}=&#S^vE2(ie-$EQ8J2zah11KzL52r-wsnZ1fk3_)jarn8pfrR?ToWKxQ82 zIwv@}0QU!FUkRvWO3uuj)NuyEO`Tv^Do2FCX1i9ZFv$xU>;mI$%~*>?&Stj{BzsnM`?{B!#oNdk z$aAr7FTaKNN1mF-`o-^@e6{t^Y40#UQ>4`nH-H&kWegg_gByP5UmEWf+&=i49vM>D z-11VSy8S2jXmmwhd_}A=_P8AZ*ka^!-o?KI=^9B6^Lm)_>eUqo=UhGgDZzp1P$i@A zI{G33pKI^r8pXzyAu5IH%yt1X%6Zfd!DvCmdXgR6(PvpE`IB(?LV;a@!~0i#qb$OJ z`gF2HmqY_Wh$1|A9UwO~6dJ#`mKsD}z8y^MV!s>~Adk{noSo)^87SEoBy_=PTxM*n zk;_P|^if$05W1#;(l5jG=IC2pNY;sV^&yR!z_l+!v$R-vF&)4*J0#!CRrC{pkx&;L`QpSg<^XAfG6#qXCU3{ z08XW@q8+Sf`}QJXmOV*I@9;vDV@(lehe~SkvZB2wj9V@irC_1H`;J?b=@e~l@TOJ- zyI?fFOgB5}1IxeZBR=iN1v3SAuOMH@XV8bbcUq}!pmPG-Ee!* zcCE@G6B}!Ym*x6Oo{-7YS8N&ejs&+5&6zDX?L>`N*crfY_TL!R`4~BQ{X=xzE#t0d zH@-S{K4VN@c*!~5<8ss45q7{_Ut|BTJ{LTBt6$ZL6u>~6ejQto>*_jb?RI+O6g0Mr z_hH!hvqgP#hipIW6GQ{v)VP(=inyegPnJysK4h{=M~|D+6W_9jK0>SttGt`mcCmD- zi+E={Lei{*4ePViLDe(^z%Cx#zw7*ty9N#CpeKJkFBB%8ACXKAXUc5?T4fga7T z;_}J@JV0WvC(zGvZ!b2OLa?#FarY|XSv2OVAZ*4`w5|Ikp*$miNx^j7=0@;Dd@cmH zSi9BL4b{~S->5jW*B`PYl+k4$HS7xLAyK5TrTptKEUb#N-bC!(l#d~D`RbLhFvkqA z95#JT50AiAuG(+xwbEN{0^4v@I|`c;>z(!t(;#=lhVw2Z(s z5bJ=8HCIQtYR4_(^ynfG>~~8Oa#&)Hac*m)srY4})}V^93ZCdXwbcVszTrlw6rJi8 zV}1g1OZk*pf#ceKqSry@>MrcX?H7`W7>jUL=jXx{H~BW}BnM-vZo#(raD;{HYiwwa zbAuu~>fcT(j?e7Z6BMXAR<=t7Ry)iJ5P9SPhJJaaX{7d}5*A$P@sk!;|6n^J6BNv( zdTuu$x}nm%CIq5+q(3^AUQsZfOVd%XumiKk0>^3c<9 z`6@Z=^35rL1Edk~i)ci8>~@q3H!bc)bqPt2~%-nGRYCTiu}lt z?M#ZR11W-%8xKqAsC|PmGq1y3Y%*_g5p1NT3s)M5P=n=HMh)z;jy`2^6)0OB2Hf;= zq^le`h78S#aM69XAGNV$t2^YfbA53O&Lsn~X&nvK)o3)SBNpm20yX}eHb9ioh9?@h z2$c{6Go?=gurjuwN&ho^JupA#&|gzRrse@Q6Yg@a9<6>ve}Pmca<~C#Vog*2f^(rP zT=9O*yIA15lIEQQBpP^+C>`+z_l~SFuzN9~rfT*~*E35C=uX>>H$IN(x)Z~VOibxj z(uN==;)>8YzOx8lz|api9`q#}U7x)ow=y|sE|9Cmv5MYbkD>=m_*ki&uHT>Fy7{7z zDMN_gC;GE+7op}tH`v#0bnBi=@OJS?gFvWtR*_Af=j3JNTz+P`fJ4si9GnT#aSH|K zl4GmL2WGum7P&a*A=fzaaW+}IOUN98NEnaU8i(q8YqF#z6%yPu#lq^0=G*kZ!423$ z21PGSDcG)cQT)K#fMI|y2X$Iy`@5(4wy)~|h<^Co^i0laP@O`mOa>Tj}E zE7S`dJ^KaQjKsHtpv4lX=hW8?zT`(^_(x?f#g2*^{v}*K6*aZcMsj85^t=y1C#P!c z`}^kjmbjyU;b_F!3ihxd%DV30H4}mg-3}M*c{j>}e{^H-JtvrK;Uup4p`z;p6S0%O zp)nek3_5g*;i<1j)>ReZCPP4H_SBiU_RQQ|b4#2n^G(zxoqk>^YIV%f{z=3Kh@FY8 zM(=JJFQASs3&t50u9H4w>{7C;A{YK>E`eDFB;{PiTKG8xn(F2jI^3Wc7HlQcTUhAz zKS4T^WE)j8Dyq}4;om6W3O$10OT3hsU!oqjEeRtAWotN-@;DitkUJx)_nxU|MxV3O za}kpkP7RnKe}d54{*&j-k6v95I_HDu2Y7rboWEd2+;$sTcZk3 zepD{d)J1K*u03A2{X6f%i-dO2>pzoDAT>pD=R-(j4T+ey@0;-UX?B3fRJzBCKXm6& z-@M=SLw`PAh!bmJ$pzBG%ZeaTGdqEBa810eTs8W3#S!$*syw`&>D`CQ`$IxBr!NzdnDYWz15<=r2#SS{-EW?NzZ3@O+UeMn|XASVN9Nq8w>Tay3N*Lv5G7`q+ z&b4EdmcWl&_$o5VkX-NVqMGLbWaIpLFk0G6s*}*6n$~2z{bB3Tg}1c`ctd^75k!h~M0IYI}x3oRVR#>(`~2yLNi9 zo6yHW==_Hj33p8Z^1I_wT*C{_@#1AwA+86ny|d8NqHsnu5=!P*18(PjmSKIK4u=b! zEq$POWKrXcn?82uIQdkv?~U;yV-@&ijhQJ$3r0yUrjo|`2Fk(?n*ea9t)5jr(x=1I z$#&0=BtLGm@i_2ubM1ODjnxBs$0+KZ_2XY$bSim4T|kjJtpZE*dryPo@h)^V#>Ow6 z70cRK%cok36=_cG#9f9{&s{hEbSMLvN~D`VmmjytKe-dU*ZGbi@X~kntV3|+CW@|O zbnJKnCA~w1X(l!NGW}ih)aWVSpqI{S&jn(6gVHp7%varo}Smn0`wTMFWl*UEj8HUS=8Sat@H!ehfeOB#^U5lLdYk1gYg{FFibs{CA{&R=Er?AkOr{N>t*w7rw zU~HT}vpy5gH<8P-#QOyzCw&S(ZVvS|<%fWUYjq!&_(=8*=lU6YLX<5Ox`v^fAr;oR3MHK|-)2BM@U zl5(mh9ly#`wS92T#?5yN1(rL);L*>CF&hWwqS+fhVq75q#@LtTT~|Tlh(N`Nw>$fM zRKXi;C3p@5wJbFmqk{LkOSFUiQ@%$3epjGm14_d4sI@ZCw|Bp%F$_g+p|Eka4@EFJ zV`K2r_(0k1XHqf}jOT#=YTylDDb30+QvU`W?0NHX$Q9{FXi@=2X76O5SzmGH#%)A5 z(QHso=wXn9{Pev7jGWh(%HT5d#tywgn% zlpdASI!L)9o24VLFDr}GT7Kh5#Sg$W;nhrtcVs$3w>qRsM1!sU5sPN zb>a(kYoQ6_F4jk0vX|pIe}+EFb+_goVzj%Czq@up2eSV3Ao%!dspUmTiu|uM;TJpq zwN8d%J5ROQ*pDj{pj#+C?MRiFy<1caDjn%1o}s;knIfIfv&P?VHa_4u#@>;MV&Ms8Tc_HjtlvCnHm@}?4-uHp&?bhB*da0`*Mn^oDU_d%fJ#lFKQ0e z5{hi=p%#Ztt&Qpj1Hbi3Z*#G%RY{vG0=~!#kpvrv=$Tb~m0Ag!!v6wQU9P_f2;1`7 zc^IZlD`4biCIe!m;rl57Wz-b`tmSVyoHuPl{_O6P!tx&Q=OlGTumrMvbNvRTY1!3cZSn zU|B+LTJgu>G6EL(jRx*dJu{L}s2WkyJyn$83mp2oys1UTBT4nC3`i#5Jme`5Uc^tK zKUiLI_TkXQb{g&I?oRpYP%?W32IUDh|E&*JktlDM{HB&*zW>s5HovvcNgvOLPMt$n z0MKzMcMYtg5{UV7PUXJjz_=uOw)JXSm@D~#IG{Us>GR+odC5u4$J!=0tDdQ@^Qmk;&^RT%REb`s_BXbLThzGfIkuU>V>NmU0~# zoZmP+J1Rz#wOQlqlG$$(9Vbkn3Vn%+Qm$uH>x9czu)W8G*Uh9k^>uWK6J6?ZBbL!R zGZsrsby5*!5lrYqEJ#9%JEsl{0y}^4eZTVA&Byz5YfnwYOaCswP$jUlPbIU*GBBUQ z`XbT!<8JWnJ`uhb)&L-*J`XMz+%CB{du6|B=}1@?<77C>_)EjZt@N8fSX)R{kwE>jif64gRj!=Nc zAOBL)@NMIWr3}gip~sWbPRF^Ev4r*!n2J;=LwIS)_aMOs|8jPncvX9-OrF~6B!6>D zmrjcd)_F-`cmJB-aw%(^wh!#Hst;h_2sF%b(}_a#wR6xAhE1 zL$2dd?(@&xxxrT$+BBJVaN})L+16)&w;kVfLFskC<_M?mOqLmiHA-aJx~@xmXsCj} z56U4#ai7>DXkzQJEcoG22$LcHW@UlHHT_>53fmcBkg93Tl+#z&FX|2eI^wO|0e&)@U8e6?DcM zq%{DXsjAVil^Pf45NPzXPbAP@o}is^gU#PCrSlt;)faRpu-%n9`+4x=1-IBWqgMH$ zs1KNL^nVPb+U?^Phk#3C*T-(8Z7Eti8f5DNxDeqU_ePazI_uk_cS=nfAled8Y1YsH z)h44-p64&on_Ug65hA#U6n2>w^+9Q)MDnPaI)uhI$T#uqLY9XxKVNh1YBepbH2XL# z>qgG}d~GBI!Gxd_kE~jTu3z;YDk|I46(+@eq5qRBteJCbKD=_V;pM3W=jP2m2kuK* z#dJ!$iXyd8DLirZ?>+P90N58gCYE>56XtMlyKUt@!)&aYL`~uCoPkxgEa6 zIZKyDprV`0%ERCOm^8LM{ZG_}rGbA-%H$gwf_zYO_kvHJev;$3dKuu+{`SY{v`c1t z(KO3?Vz`|mNNUVvxA#DVIVgHVx&FH`OcAp(wr*hE6H!yZE$x0{lf2j=#GJ6Su#x7Q z1SneSNjr~3wQ9n2_BLOy*za*}U%D1(SLG6;(V@)1Vesx9j4o1->h)uL6}G6#I=3*q zN5BZUSk1xjUSrmBuDCzsXh?JA{=ud3h}22s9cQO<4Gc+ts>!?ki&lZ)O=W2Vj=H$A z3-gG>a@tzrlPWCl=CEwnZKIV8r?%t#0~!>wQ-Y0l>iE?T)?a%#({<{%YPY{CU(|Kh zb9_jY1;FG|%;D|~#@Jjz6U^`10^v1=9Cb>A|Iq$r2OpK`>PqmNls^%ag05UZoz$41$%UZuFVxQBwkJPnkOF2z$AvNntxRU# zJY~hG4|#GBeQRckJ8BZZ4!7IkG86=q>nZwh`+Uk1OXVeux^Uf&2u-y?y$*tK|yt_pxt}Gf+E;p zdbF&MZy>RAD0c@p3J^QGA6e}-l~-7~Y5$yOGHd-wp1Tn z*hVg9)1i7zkE&a?L&$KL)5S=>>ZQG9*%dCthkm-qV&){`Pb%i!SP3QbfUd>;w33KpF{|?+!ZRp$?~`pJRdW|d*A$V?v-!4{d+ff#-FE%; z_LZV|C2$F-x5;QOjartyZ{C_Q`e#8inuIn>-u>jmt$@8x6PH+|e{?O#%O;5ulP7lg z)0t1c!?zxFbWtOyckxpkIY1ZA#9V+QH5LfP#Yc0p6w(!k^hBW+&wKCYG^iLU8SA zqZezJ-AZt}(7UlQQa>~QStuXaHZFImxihY5lE~MNlJ3mXSWsQoxQ&BVP$ml{FWVCV z%4`q$gJ6+qW`2F>;RwtyBOh5F3DdO=XU=5iZ!WL2K?vuwGHM?%LoWm5&2A9SQB?wB zwuL+-!(F1X-doGg#T_E6cP?(&P-fTaxCXXyCmZxGa@vI2_>&35>~&1#M2-e^Q8n?d z(zZMM>r6RvR30E(S39CO$&wy$nb(>lnE|>QQdHY2dpqB%yu{IP=h6K88jxHd*s67R z^h8 z-ht1nHP*`JF`T49EGVKcRG}!`YsR(O^FzvptSNG%;yS*}ZVdv1zPg`_+SOh~U zAPC3242Bkin&g1gs zp*RD&fC;v`hY#L-haq5<#jl=V>AsY+Q(liY{Rk_K#$0frfcSHA$&Ax#!~`ul z`h{1Kd)ja_z56|QV$oBKp}KGW0)r5dt+OZ@srW9t---x1ORXW7?BsfeUVgae=jW$O zYNbXuZZ^#xha7OJq_2kQo{)fNTc16qNCpv{ zztV2}u{M6S)w)zv4&|A@m*tztC-$0ixj#(7B-iS%?zMM9dTO)8 zPg|0|t4#jsB-^pBv**RDh}M0}{uzS%Y{>{&`V#ZxFxdvS$|R}RigPJE{d`G?tuEg0 zZZV975H;IW$`I9D!+P1*&{K%<_v=k<>$Vd!>U>Ppd@Y%$)Wr0xU9>%Fw`@K7n>xRy z)DhlbD0>-WpsmEJK1?xCN@!?5SIQfkc&S=mfFSZ;*-Z#nwjunpBmH2LP!y^a|cmMAkyI%B_&g_*g_!@##re-g)mxt z9%#Se6Z;QZIH3L#AV)(W{5=dcwK$UcEXYs}a`J=VL2Ww)B66<%$9$4{R2=EJcn-F{ z4K>K!P->JedIkN&{;RqNUm+`4bvjjlkJQOCiQm6+bX0Y*)NN+?>6BtlhM{G-1X*Qw zE{cxti^Vm0Kt{O;M^DIeE}>VIaQY+uj3?kBg>EW9{*b_SfsBP>#JBmVU5&VPCK^V9 zus=fmn&1?W?hu4rJ1?LX`wgiYgYUWymyWhWkveKf*6%xO;=4|Ml zkL`)`I$)1$poNoY@Md@2&yoUzKj9ORh(iS*X>LZAbod&P>I&0&kH-A^)baB&nf1UL z%hZjbp(oh|>N40bz7Bt`0Ymfvzu zHVRVu(BQ86dS1EuR<8l?$XiDRdTeOORa?*BS1Ga4R&c32dCDdx8tI=E8rJfa;?3ZaAiUIrIpVaWWoqmW-lEaU!S1C`9tncYKf|+rNNtRXoJbZk96*n8@ zysHemi~p(~w|8M_Po97VwbXetzspwqBR0Y!ce_R;Ws*!&m5DX#ywx}KnkHf&Z4$WljxPY=mcW%fz;Y1;wEufoXj7?iOt{y4}mF#+;~3z>Q- zhEzIkaCXd+G2`$jcj>BBigS1AZK^xKEU26k`Fv?ju~)gPmP}F>tvWAXa?X~y)IdKB z+BpyR-jjTJeIM_!vZVId(s9QZw^w*a(<5k*{M&4j&Iy-vny_t9qT&fpz$`nJFZ(dJ*9wnV-l4fE`yy&UB9wj{MHo>UO-?FHh zw)XXKBDvXr^|h+Ba{gaFCl|!wgVA8GTX?^$RHMd6o;WbrbvzM5n-N(BRHX*gT~pja z4OW3IR)LMFffv38c6|-JHXU#^HRz^Qz>Tj#zgqm~6F^D} zFz^d7_Vd`P?qMgw%In0#OLD_wXbNZpkWGK)fwrs+NPQ-7Ie5Ax->jI+&w zglH-HZZZ2`zXOIcu+L1wg5M#NX1p`sJDQ&Km%2TCeg!GUuSDUQy04?8;O;cEPoEt} zdV|XcIZKa3gHt-3z=zhJb*FjzTG?oe5Baa9Vu)$k_F$&e^Fguyjwm#vJ3VfzS4|q& z>v3Ar4jZ-kX&5-uBnm&%m-z{JZO{a|Qbf?`cjx%uyK8;y;d`(OH}hHQYsFdd^&;@z zZt!UO`fGt6#>{uxhmdRp#CW?sf7!o3S`R$onq}B@+?;XzcK^xr)VMKMbv3$tMR+t? z7i2Bqzmwwukort2X)`Bas>BD^2x7#iE6t9>GK{xoJVQ%gZx)Y#^H*1&&#oc~FQ72) zzUp38&pFvSsQGMPfA3d2jAAo*%DV4&&7P#!`c$NmK;MM?3~RMUUPZ>yo&5sCZ--U6 z{^!0GKn=lx{jZxhrs>$czVa>2D9Z2PSHB>7#&!S0k)_22{?-wyi8pLA_bc)K_?GFi zlJQAMu&FtAx!)ZvKJ;n!SkMUinH`lOhU%it7TOEg+sf$Vq>uX^8H z)_20tE}8JXB<%emRGppiMs*d?5nSyNPybZ&C@^~9$i5vZ8Lk zG^p+%tS%kI=s#q$ z_t;2Z)<|w{Zc$Ou|8h3FySvYyKmWg+&0h*aQC&e#whQ?p2N`oXy8)N1ip0D3Hxp-T&ikejOSa9UYyXp8h|P&9Sln z3)y`4?%n@KkWGcEdHDY|RnvRR|6kP{=}aA?pYP`0+G+|iT2yjG=^Q7Vp5PhxC7P;H zcKaU+C`Q2m%IcDs3J%6yv_O}Yfk7&;nFt#9a2OvB0^l@aBNeKcI)EK8rh~wW9T}RI zSr!ciS)wYdh+ks_T@WgIw*A13;m#>dPxX<6mQ}ymD4s<(h;m!G~^P7O-t?MrMp0e z9KP^UUx|w%??*RP0d~pH1TZ< zNu_c$eqE`Tg$_e~9*H!Ds7y7}fT7oVcJQA}G-&zRXPQz0I`?7w+P}5Vrq_6LPn#|v zdq=@!h6V`KdT+PC-rcmS zhQs4;>p`u+otduRUfzPX)qdT5oLxPTIaRaL$_n;SPH)f0{x?qZ?IO*EWR&5Z{SSX2dRp#-;W(GSg z?GR+Q#S+#oA_~N}^5W4|gfZyyerh85azIdn=1|xR0k7NSAOD(relgvl$86dtPuEG` zp4+A07fspG>h?o6e>GLvOtYjbHY6a>&wpP_GL-b)d#LHGptXgMnQbpYz!mG$)Y3$U z;4oC8`?Wj>P14{!u-WBP$r{%-TL!`d)~s+njofOW6FoBF@0n%NLD z9@2kQrariuV^-X#vY&ZN>&a@a&3L0)`sgj~AFB#gQzb&>$hGnlXIAr*%t_9b`ErAp zoB{)W6RvFuZ&WTX^cg34^-!=|4}2=J`$S^O;UgBGg~i(R^O}!iaaPtn1@u)K8YwGe z_Q;6cqf%u9sbj-HlHN%bE}Bf_!@m%5brL|AMC2n>UScD7%|tkhxp(cd0e_rna3me< zTnIvlH$(LEKzG?*UJ#oBvO&O=I|F=PIZ+HXjpr946+~zHX1Ixa9Lx7^bCo){buf)J z8jNf%9hqv;KDIno3$GwOU??IUiP=%sILgCHrge+F5Wy5fW`<%s`Vg4pABNbXTE%mwFMlagCLJ&oOQY7_Bq!hP}Uv=y9Pv{ z%!yJ&GdBt-WedHrSX59xReea4Pfd}c!oJBixwH6oQFge~OAJF5dY-2wLjCH{u-9_C ze@LHSL+tQ+oJT%u^w?dYy5i_%W4yVtb3GVdTE)|BSQQ#J(3@joA-L)u0BciS*`jh# z?-cr3yL%(TEm45Gi1wv1EO6C{Mhca*;By}Yl}O1k-L(vUtd=Ice68GL?>whmCMUSi zWCpPq7^!y}zSWehd-KP$q1R^#m$!d0v8Ft{NSqH#(|!k?d)Wg z7QDW0V-c|IE`e0`f;Rq~cSCYyxQjffsn0)w=n;S7j-pN4^kT{i=}K`we|IBgeEf?v3GEl_8=v z>XZ`%Ww_Lb$onccWh~s=rUQoV5q~f}vGUGzT%dp9o1pfz2oab8M!2;Lw#4oB((?Fz z7t%OvvO;6o9G9XtTPxMO)B(nfDs(;X6E)`FrPld5LmTm;a_A&NpDcasGApMIB?@=; zG~xYQK3qK`7P^w@h%+>VsRek2e7unWxej1eOmg{ht|a?H|ABRB!mGpOGTdniLt}2zu?9w!mZ5Pyh6<7w!RLi9_raC=!ob)-t^iR3%dSAYEIetr7s2>ws(TQfUep8G zkevacRDo99YMOA#Hqjdn{9AGCuSMm`pJ12Zqyyv>usV!xs5^ZfFjiTBe^2;g8rvu| zgv)W??=hTgA41uCb>G42phxyU6`I23>R#xBRrK`;l>2er-}7!V3>l|{rud(wXSoN* zEgW7gXsc`9?P`ba7E>L_6^!G|HiQjY(T5 z=rA#GwGSG}4%%*}gx0|Hh!DXbXO;w7zZwsOqaKey3-frjAm{G{SYKks7LHSsC<~Lw z-P@SGQ;JNA4kLx5_&xawh$@+@L>h+GeT7smLJD7Tw)a4XTMo6v0HxFWRXlUMI42r- zIS45t*a_`20qyTe&0)v$D44!^L^vpurVcyHErozl5`zR?%2^5#%r$VVmfTNkr;z1b6cgR7oTXjH=03 zRO4awv+L-pzX9*Rk;<{Cu3RJ~QR(yJgsOH#ILuj~UZMODvEdD(hjz4v7}He?g!S{8 zJ?YRHrap%ui?Ju#>YMA&by%fluR#{M%Sr zWHnN_L-892oZ0(%;-IojoID?Q939M%0R9qKb`RpB8LCCB%vlSJdV_3w3}F1z^z(eL zP9W>wa5hRHg$^OGo#8(f{h(Od3_?pe{#9neOddK{F{{|d-9HYOiuO0H0h{JQoVXEF*ZdBy zLBq}9FQLdwW`~=5V3Hl8sJ7F$@!T_xEDQ}03wcm5ikVydxF50j78ybGGCojfhG-5wL03@rHTm%S^;H0&`|g&_9n@$5SGk9`pCXinemjBQRb!YK|Of z!|e%B8fP*U-k_%gQ2T^g|Ad*41F8H1iKewwHbY{>P(HWzQp*`SnyciOf6y%2o()8c zT>8X_#W&Dl7G`M)s@$05DgpYq$SkLji!;nX+6m`*sF4lkq~D2Nkm&3(*Hr`rWfUE2 zOLA#Lr^Df*CwaTVv$1R?eQ~o8fP{`9+r`RzX{>}*<%2!dIY5i}ZF40d1IGp`3Aq>% z1pkD|F@x@3RX!|XZhei&qOoixNMH6P?7R}WBk*M^kS$V9FH}tHMjl&2SG@s_e+RCQ zLVX8e7bg%-v5nh0P7)p-+_ZlkWnT?Q{6ZD9nenkAhVm7rS$(eod{aNJB@Wlf?Rm^( zX062rTRrQC5(N69Bk%BXGz{8HD1z42p zDw^jA-xTDh`w4DW~iejSeRDalsZp|4{(5Ps=9%9#<9;_V9_O2o}jv6)RP z&QnA2_?3=AQ4NWRAoj79*T8{{E#bg^tOPUX z!+bOYQ`m>N^UxqJ?7UEdq2)VshwwCb828j+hmhEvT%u%<*Pam~zN$<|bt#4v)d4j< z(PLFXgR$sv5pb3gb7l$M_Psp;z;>)!Zm_%lxeE8)k*UjuTuX(A_dt)t_Pee^Popau z%{m!0R=Nb?W>)C@cba`Yx{9V$ZX?AKA)09Lb<}MV(a(hKe4yvLHw)YjLaqPCVnuUf zOr0V?g@E4*r(F!&PK@qPEPDNqg7eMff--}}1zqq=jRWX|#%LE&P|y+@N(BLD- z%5a;NgT;Uo=ynk&pLC70-2^(rVQ!^{V7ZNx(JfnpTbi4}($s64GnFq%;@egSVC}&5 zVLrn_JG;H)p z{%{T8uf|+7LmvIAh|3# z01S0su~};C>M;*dAVLatOGE`p4!9@sgJ!rrAk?K*?u7~DSuXU`tdEYa&1aY2PgLM4 zk4p8?%Jys|G8~yOf9Zx(TAv7r?U~bDU*RM^OZE}N>|L0fxIJw)X%~Et?09_J3_Zy7 zd*pKf_*M@MP7I(rF%?~#@ovnYJNv+$53y`uJZA(e0;_8cZOF^Vtttx=m3FKuziAB* zmW2QM=kVFgI2W_4MKS%@y$jJ@@}Yk*r)VI1-wDq3eAqvTJeqQ=S!#Ep66|0t5*%Ou zuh&)3XgV<;&jpgEU*N_Yb;5f&U9j^9A`VDkLJ2}lJbh_*6~T-tltX^sk(Xc?v*yNR zh!iIoQ0GI}rm0YAVTk-Iu>IY^;B_c>^;I|#R+fUORVPLQzIu7nq_`>LENcgbtBYmWF!Ync^=#SNiHVgUf+^JY|LP+7=Vx zD~2X;;rZ;qtBJ_3noe{s>S7|IDLww@u8h;Gr+ug}j#rhwpJ@=!|(TRwz-RM#{ zj5VLCx^QL927+TNbrNcRGxjb!`e*ugF~a;QmY5H51m`_3zUbWeRcr43Oa$Ky-sW>R z>qOR>d1%HTOmB9?^a^KT3(kIh>Do1zIBQh=T#Dn+J zA+Yf>4m;}lA`mPAf_WE^;i%ISwM-E7FH>-32Eu6`mT=bb?>Y=Ngy~PXJh~NK#9$_| zAv#>Z(QF-3IWb5eUg}SAp-GUfW;gN@5hgpFqpBea{xnFj<6cA5_7t9fr(DfGcX1w8 zDFnAMPHqqHCFhBRmdbS?RsxL`HxIZH%k+vR*L<0ZQ5)@CR2Kz$@c@|3hHMhU`a~%h z32eYWi^)T*9p|4lD^=KoKm9))_F37C$$4-Mpx7cAf5$42i+zc;(so#A+AM|*}mgdbKKvCjbB0wXM7yNjq{2G5rP!oF>_FgO>BAU z%G`m57Wx9YXs&|@2sDHF@&NX2C~N`g=d=*z$UL};RE<+M`}A4^^Ja6VOVYXoX6)hY zD(=Pep5}#uAFPiMR!6X_Le7Q2z4H*NnNoe0N8Fo3`YXy2_hJ6qvY))+oPB{M?fBIj z$4%AYR<0)V?$@L;Ti7bnD84ZDNB6>z9 zLhznt9IO9SP3LOUkmnYwUawv2%;TOj>arsX^z8FBifMF86a8Q)yx2?*IBmj^eU{91 zWkM3ns6mdnyDTA=?ac}xB^BxJ;T*pFgwyC_;ub!cDEvq1P4Hmq`-@T077u7TaqM^p z^M!d#;btev7LLJ`$o{H?(LnjcB1&;rg0X+?cdIgr6cg8Xk~ntfj07gNH%~u_IWXNF za^+?ITY{mDlBdc}Y@i*`Mu?D9S-f&mm13eM?iL+2=r&K>&v2cL#$Bks z_}R_24_B`-M|zteE#Ga*@+F9OnEp$yHp$pgdze~*tvRA%J2S6GlT!ZiZD4}rG}2O3 zrE|gzb)k)&l+(u#*7!637R(|XuHL7`+*$9ec^>|MaCe_UO*L-2=u=iIplLv;h88*k z(iGGrw9rGZLO?)3)F53^lMo;jF%*$*fPko|hzKaCNd!btpP;Cys6kP&Jc=C~?)=~L z&faIwoH^h2m%Sz*^C8J()|z#%`}$qefZ4Nh|MWJcVU8K&tifs(o{a|r)-J9+=j(mF zE=%;)O^)r43LSkOt@*iNpunCr`*B6$(%F^;x0RVO8U z_SQb*t7PsCm&Usd0VAf!)oIL?Lwvm`VcVf$=GM=KFb#`!GO$5@4LN!PxC8aL*oAvl zLcVdc(D6B(JSucFVk9e|hSA0`(DA+*enW7x#cjBfY-%NLNKe&At#Og*ZN0x= zPLC|v6?+|r1QKTLqo1v??!Szl{{$*L^!0IWVp@Z$Nwt1Till${jt7uZ|IvO<$Lqrie*2YO@tSiVMp{Xg z8@nR7Y6OHb@vM?y)8M~RPi4$Pt%&KZLaar@Yb8T#({p&)yV;++qW$WGA0!4pprvFB z4Vp^BzX?T$oWfL1cBE+4#mwa7Zgnrm!ghHn8;+XPsIDs`c4XbzUS$5oM4ofGGq^`{ zqHqmsi1Ph$&Hl@JU5_bT_z|4pPm8#kL`5oIzPC$SDFM9y_m; zKI@I#^a5q*63>b2@ZhKZUZEvTqo%#7*K zB6V|4--d@8LVT1d<(Nm1WdRbl_c&q*mZ% ztF5BqXf;tEb@1Uq!bmSFIGqRaOriBGwNw2yZFVnh)hy9xYeqZip-y4$nhRdHGwW)s zsF>SWt|8|A+%v*{q1doF&JS3I*VFFE3*?fPz$hR`D>p)L>{)m5QoMiF)5!0 zkV|Xpbc`rqB1!46#ea}WF*I8rqv?C*q_JYuC1#j!MixUZm7WMW$6pC8y}QfVEFt^9IgDtAW`QzOL|2DCyApha5%QM?uoFRA*y+S;wjLad@VqZPGQ%m}$ zR>lBrkL)OXU!-ILy?zkAA5^Ax&%t9Ok*^|Pn!fnZhghbZRG|#`fkux&9)Q$t49gb;(!h;!o;IAT$PFZ@l{LL0S2ENj zv3Kl0;rVYCrRY$J(Ip)5szrAZvbru;vj5zeu~{KxWhfD37nGm8->@3^Y0W|T3Ai(E zV{OMpOd6>`hAP2=}Eh>ovH_aYiXU_@f>Ww};!M+&7_%FC3reZ z3TYUF*9zm|s#nG=nq@S@W!!^*tcJ4x$-!tU8G8M!5o6dp!B2Rf4n+jvbexXp`CIWv7_-5aO||G5rzQrXG9-cZOfQ1pkb%WciD zu`I@f(XWb+Y^pi8^~1kiY?yAHli=FpguZCGfoZ8V+;mpI*W|SuPI2RHBq~q}?fv?F z_x_VGKYd&c$R?*s$Q$=sp#YJKT=is@!`apJm@P%OpB#tnL5cQ0ZrO~lYmEIxnwUqT z?Sc!-J{Lc2aNp-&4^ywUp40JB5a?U^&DDm9NH64!>JduN~D~ zzcG-(#R)NMbieO$G@hNDu02Khnv_tr<=vVuSNeZldD8CQ`0|R;?cs*SwquM9ANP`c zoV0#3xVA*3W6C;;9I4DdI1Db_?n4rvwQXLf-Zxyi%ci_uv;N#8F-Q~opw#4|tGKDH zup9;RU4#raf-EP1*hb!|Aq>YFdhjBwE)eo2LUd2d`A<1EI)bCL$i^*!XYxiim~eD^ zLEx;W;SDMwvnv->zciI=@#_^~!g{DBvV8gx_fh;|4x4-O0xZeZHJS}^BvQCbS&g}=Bbs>mwJCegeB zTWryR3_LDEHFi#gr8HVAH!IF}NnU7t)Lyl1y2=`P)q+)vOwqY7G0nXw{rz@)ZT=@(b37~6fg1GgQ{AL2k9^I{_y$aS)S{9 z$nDar`zx?rsdyFZB0n}{t@AHR_i{Lc!M!J+o~t&^tPK>k4C}YjXVD3O4@zno=0sRa zhg2+a@foEcLbYE$dQI;^d&*d+$mhU9Q!z_%If80dK@FLZ*gf9*GSCWA2;PRT$?m6p z-*6-IY-gp6J01eTf3&J4NjOetLFU&UcXI`zbv5Y*|1#7pSYBZ)SouQ}GuE1hbb76v zSM_^xHnG%M3nG}}`N?_yOS~{v5qj79{if2wcdsn}#TyX&jQ^#5IgCMo~B=Cg30b00r zNx{H+OP#pe8`x$;5dY&4BT5}~%Vv&{_xE+Bhsg>EM2FSV0SJk`zxp&0tE*-tI!@so z1{J9gkvziT_34KrOF>uD1BvVVEJf=7%0NUStP@h`Kq<2U9VCNQD#fe+NFct%PT27- z{UBH7~T78-FXlmt4$|EF=Gp=SBKBOfqJfgDD{Jmc@Y7Zgfe%J*--b7!6}9WIZ6 z`iDnwjghpmW|)6(H+dN{$+MHmG2M?0FETrzj2SmNub4h#nZ0qQly~1n1=xTs`>i^( zJb5v}kV>BnJb&2nrp}%W!bbb!zD|%6>3m<|p%K)ks61FeH&nBYYbZOa*9*~XE8P+r z0%!4xnQRY}ljpq6;bmSfJ2azL=vT%oDqZE6`d>IB8P{i;yQ*5zWgq;Ztz2va<9b8L zrbYDz-Ik2AN0zFe?m6;K5O9&yBQ*ouh`a3DhG780UEW*>1G{4E#;R2l?INrBG&QNZlWt4T<|? z2s-XMDMv#C7+lMV!Q_uE{>}sbu!mRjEn9Z**HNmCQ%s%r4tM>#s(J^~<5E%RP!O;S{#Cf%$6xT#XzThJf7XRm>3yv>HMi}vdbJA$g2MV)YNDr zRh>A>d3|!))ne<`@Wp`L=8A{693!_<8j*XWf6L~CI&EPi{lVaqKMdz{Xj@gJF4A)A zM~Hb_ks(9>uQG|F6g__GNpaOCJxs^?=dsVeR604~&i*SI3WC&nyDshX49p){54!vP zW_wl@TZ4r|v*H5ZK5=qa*3X03fR2S@IxKswzt+;IHZZ+&MXx!2(EUO(p07%Wm=L)e zx*xB4bmIfbmp=v4B=Q=xE?LQVKJv3ZONBkkm%*=rH!kH4PTcBlf2{w(o@pv&`N6Am zaXA_*M>sAjQF5SHz$f>1o96kiy!4rJtBJ}4aji*I3YpXaMnH9$EB!U4q-hgv^F+PN3(8R18h_WfcmC!irFs9&Lk4nw z&TYR+87TU(ikn=fx=AU`9u=s%@bNiDf$zG>64jCuh^bYM#2^9^IB*UY1!8)s9c`g- z(U%w|bl)r&e00i~*F~6VM4{`-!UYpvnj&4Fr)%f2@V*x|W5F@av-AF4h##V49QZh%DuU4xhM$;!MpNS-sAr7U{{D zC^jeP^r+gmO22(*EfUv-bPX-$8s9I%hS77`?m>MK2WiR>nWS*ZQp~XC9-+ zUUS&LG*F30khQI{dc2XrjdVkK5&2q6p4+6t*%NFhBG&}E{mS~GB$wxiE}i2xvd1R8 z8du%gUSCcpe|-70>K3i>C7bQFq&^oD-=r89ODEHn&dCiS>!(5JjW0Xj z70*ZOBi|e!Z@8hWN^GkLJL_%F;t(h>?n8h~Z;s}7<7%tuEDO2+zi0pWp%%-EimwK* ztRjoKK7lbJCz#Eru!@x(_g8R4;mcYE}|BmGk)UFC7>c+pO_f6;-cAx>n9M(0DI zGFW=1mWOXje_x5!6N8?}1=;ze*<#fFjw!uB z>CER1-&c{cSM}7gZ85hJ-&eY-+#B9<>V+=m!gw7_#1EY&|De<?a#o4W%6^0tepgK7}gnU9?pE*VJ zj+>!GcNZmntMn3sy@vo3Yn=DcfFA~GQ>OeKgIrzDTXo7&Z4V@}#BMDTx;C%;3XEE| zRtoQA5g79|CgSfO0h=i9p)*e}v_#d4zaO?zwL1u+4#T3Bpqt#e_nu^oSeI62K}Z$6 zAWX;FUd6LS(3&BT^eu;Ava72E>pDSIi<>yyy~j{dBLT|4nR&1#*J{M*WZp|>?d2a8 zuNkrT3Imq_|9WVpfXmObTlqoxWw;$>oW?D8M@92bl4rMSS6$wl&oy!?xO@y1dF1?5 zsAEHF(TPB=Pu?HBh0iztor@OS-iO{&y1(>6qAGeBx^@Ec?SGH=r~OsU)MK)=%51c}LA|Q(sj|`<_D`z~6wX{RLv`XRGUJ8taFSQGoARk>{W#M| zTOY&8+QF0zs`Q1(yDGYFw(LKuX7h&JPw!rTHkJvU9;MV`IMUT&rWu60^^ogWRb|tH z_7`PSReFUqG;AeJXdY1;mm8ZBl|i3IMXvask_lAJwM-1%gWjA#&DeFc#<&I149d!* z1tyY2rF%G|GwJ?P8&ne6(8uM$7akBid!x}Y^ZoCdy9aT~bXhN@}Iu$C($;;0LvS#-=qy zoW1F-xzXg(SM;v>MzcYaz@xu5{$BnVd9ac#MP5a}2oCFG)N)NSMcJcir>HOBTYlva zG!@v`@PjeBKpW0HyKS^AT9vdLMNB2;RS|k_7LVc!lZ04=55?Y%)NH61X{;($^)lL- zcnk|$!9PiuQl~qC%e_yLGQ0{E8S}(|f%?E1WyKE5yk&1XZd`3`dlF`qcf1KWsHBIN#GtCH8?Fj{;jT@ObzE)KFJb(|hPCV)!4jI>k zbV^l=o|r=}_?b)Og9wkXJ-Z#8%I z|7khY8cBl_j*1u%L~d+95ARptO(eKtY5nnr83X4`Vz{?rH*G;O7{%(2hnfxc3|Pg z6t2zpC)U2U0JE)aMUzUQ+jRy ze-m(nw0pT0zk#Y0z?3SL7NXIyGX475WL(ED-Q~-w7Y#~%A!?X8z*mU1FVIuw$f^4mhL>EDe)u?Pc*%s;N@-i%XR2S@XD~{Dwa(gAy3_jH4Fy zXkf@X$iWJ+L7z03Lngt(HAMRRj&rqERTb$mz^FgNdYbdkiy(m{^kTUf{ZsXd{+{;Y zDj7YsmbmH4B?v}S1F(ny1H>7h0JseYPNqPjzOI0<3VV^7Oo9<8>5Ky#Xu99-blL63 zne?y=-GM-LH)Rg2uYrrJWn63G(?W;~k8snYjzJS`Xf-WA-Q0fZ+a8d;<`UkWFYdYL zCp_YD7UT(RJKAU}K?hgynsV-6PYp`ZSEW8Mi3skdXF*U6;!-sRh!-y1eQ3VXT`h4d zGB}Y=?eCUi6lq@9o9D7Ura{e(Qb>OwuNtmF4MS%GX9Ago_YVy1cXcBUR!|MMPrL$@ zGn7(LAJn>8FI2W(*EqPdSar|R)pyE4ni`=ggy23d-=Ep7#Sk*4Dz*gMf+XQBmihPy z`tF%dz<5ML@^VX|ZAmUS=hIg(J-vlCMi?HQ2}ZT{R*=(gyIQ@teL(x}jnJ#R-O51R z78Nkf#6b^kIb(rJlJU`ujx{&!7gmP|!avP?FAMVxg}6pYRl8C!`FBf_c|j^6=G->ReD#BXnYvpVb9sYF<}sU~zk1THjOujY4g+N9v}Z z?L@mtkWRPn-WDb*1%MKiJ((OB2~=dvY{#9stq`}VCj%1ONqhgjb5x{iZiZV7EtI(# z$5PR$XEPrNs-aqbgLJy2-he^8M=L?Ro}gvY@Z?;!c<$k%aB;#mwJVZ)bsyV zkjooT=o^?H~$wttXG$c0ro)r!Wz1y)TGq~-P(aB8=meloibj@9I{YCwc0O8!D z8ns6f|2GL-b*W<2@{5z?UO!)HMl~MwyEFUjZqu74)m(#-BR*+MT=mOKh$xK&d<(^m zys?=PjroG1BgZs-f7I2dKv4HhKUn&60_~FRE%y1BVytA)0i=^i{}Sv_wt|diwNF~T zzg|bSMz0}^p+9KW>bYc8ue;7yYZTK0odd%ywNfVcoZlAsY5AI)A& zk5^py3bK5~Oj~mIHjK#&-6|gB6J-wt9s zzPBExf7|+uDG!{)Rcv-{pelylYyy8p;)c9it7kZ`tgK4ty0M#w(J%yPtj2R!?>@Ud z6RC8j-R*XG^^nmV_fd)e^P|JnU!&O|ds^{7VIPI`pc(l&gG7%Hl6!YjnLm46_s;p7H;L}xQ)g)wi?{fY1Kd|j03cwh^|Pm zK@{Fb^EMdLN@(z-mli^ky*sBc+cC{gjC)?;%$f5jYmFB(F54j98D4rRw0{b?IwoaAHt-XF_L52oQ^-94}IOg>6DU`C3B@b@(R8DkG6+-w+^v8 zVl0N&GZL|<2xiFVL0!a_-8Arw)C|M^5gJ~;QTg-_o@R>MpX{+eHcwat8Zl2&a9$^5 zv_gHOo;yK89Kv3j*9xfss}+FB>0EODVtT&^}mH9@L!GzlkK>WIhwv9mrkOX%>l36(fjP&pwHGYWNeQZr2^K&_rk}f zH@N1r97U}VnaAnrk*F7dAK4edEA-sy9DE8`n?y5bhlh28F#@k^Gmo^AIK)J*-U8Un z*#0+;vHwBO= z;N}IdoDLFP-yzMwQU6(qDj1OkYN%MK#845wx=%?2bC-MWE)ol(*GB`;Tb@Wk%QkWqICN2&;bHw9kv_k5IlkB0m&LDWIlh%^jPYvR-2Q+C*RX$USSC*vAQr$DEOU--}0wLIB5A6z& zkwwCqRfou$Jf(?Z0%QD;{xr6>0(*mvk%5l`9V9-VVDchXn6B>C#JEP8{_HY0b48G4Gp_9Q`zZHdmjP45VJgz;tkik`NZCOj~=jbFC|dBxzVr5uI;fZB`F5m zW|<`|_k9qoNC(-&U?I{|ZZuOO1i=&F1TV*m%g5i3-tm97FKHaH(5Yg%MXSO~H(T1S zxZ@g?Rd~$k*-hZN8wmEoOK&$NWb6nXES@9QUmjhaWf~&1*SWH>siTwe#c(%f&`~|0uqe=5w$| zZ*f8N`}Cn03C6-am43pc!sFX(3amg}@ou{-a~Jr@`} z@r9fc+#xRn5DhsV9yC4Dhr#|cxB|(g2Nb^?rN4n7WpsC)(?LWC1vyg^h?xYI!XM@P zHC{&icryOOW66KCojOCQcnDYs5o&xx?Uk4%(FpCC`~#8z#w~NSFdSVW1XuCklIA?i zm#bUw#wU=XEe5|Ox@qvJ#@%(x`)>_;TVvwrZQazghdj%rMKz)XnaN#4$oTYamAmZ{ zAw+WKuGQuC$BNm#M&g4&me;Gv@_ieu-@!A0nv<|u%6uBPGi=oG0b4Z}PNsXT%vDpx zZ2b0d@<&O%5OgU-a_S&wjf`Wsz((Xzus@eXF4h|639?gb0(v^BV!xM{GPdP z)(llEQIcw3WXLTtD<4}iTWf1B6L~n<253t$0`9KYeak%R?}{CP4BPTB{YwqD^(#v@ zO>2jLcrZYbt1IA+=PJtU!-9XW9qRvtVBRGj$V~Vn-&ZW%@Kk30F8-69^^klL^j5q) ze$M6Us~I>9cI2(f$Ct-dK0B(PqdR?}Ohv3d2~?y3$gH3?2F1_fG#AH6BJbYeqClfjf7p$F_E%5ApUNg=HB;U)G_ z$Lwu#Js>g9%_u8h!P@PP+zzJ`=eIol8hOOfyDM?oh)th?EO$ylqn&<8kdv-Mg7H9t z!8ee_z}C$UiJk+Ajta_QASupa%hrM9T>}Zh4%-emB=2=dIh2!F{!Jk^B##)yA9IVj z=IQzBd_LrS`qf!cZ?c7uxBWC1G}IMwCnx=v!^e>Ue~R56O$xYYn?bV(Tzho;uXvWT zqdhIxZLL%#a8M=k`(NhZ-xSA>EXUXbj(H`6d50YHj|}D?{qAe*2%0!gs$7#fd;==l z1|Aula*;0Ie6ch!$m$q{ASvNbxfUc4m;~BY;&b3{Zh^XZw`aduH*Nb7FNC13OSjVMlJsRAspv zNH|*e)``3BLd~_)UhmI)YhG}$Vtac`)^{Wt484T9U6`U=pj$u=ul{Gp6b;;)JC*pu zGV6z>aNtP!=#Fjn&8xG@pE_-MlP~=2chKPCU(EWaOY6bQL;Mfx1?9j|&o6~nyLiJl zgys;RPdAIU4V8cQvm8ybB!a^B{ygAJDLUfx6#2tad4mD(r=z131Y(0`^Y#uKKeZ5h zk;Oj3&jD5|fk4pJ)%~AB!p4moJv=-V zHbQW4@c+Xj?Ay05J3IRdXww{M&36#u4+#7fg!&0X{Y9Z(K{WoT5tpE=AAt<+fK2C* zrvK$6tiQY3=`F$duc6@|Q}Y#j`<0EG{xx<~I0?hh|2PREX!Lnx;2!x5W?4zuDOyW&&M2QRr5_xk)dm2fAjSh}TQZfo&$dc(W_LK2>5 zR49am|H&gXC5(%moBuZ(;cD4`+X(ks#^*Zz10%dVHU745{LAq8@|E$W!ST`2(W$Aa|9>Ij?c2X! zzkdDl<*(uZ{au+C3J#Eji^3l8dBV6Y#^%G5%Md)$$;DcY3xW_0V-iUeE(ZYuW_<)$&ZX|1 zHht*9{;A>IfA3xDHtRJ5A6F(v2^se|q1foBLH49?JMUkD>C+iLVc>p*#`*+Sq#Qg7 ztbrXGJ6{Ki>^gT+)C6L`bQ?@qF~wMeez4tOpgEdoP<;RW(_N24vq|hO#9+`9 zt~f!kqnJWf&I_j;a8*mC94N!6Pwi8W>TUxCorZ(-0k?Z=psOlUj?ugC7EOYndb=Nh zXipNv;l_>2NCk3GOMwEL7TJxkjh{qR(2x-Ws%%Gz@aXo{Y$<~rPhjV2=r2%;j{{xE zL-QJ_1+ao}`n1^6zo+&Xr6Q&HMO~3uP-NA<2lQ}*rpdJUG$MHvv>PxjeY>qLxgT^6 z>Srzk1x&V6db(&o^`iPfOC*D)+mUZCXg=PfWCjpxqbxu?a!Op$?V|4XiYIxg$6=PF zNGj50=uwmM#(@WtXx)V~RHc$~Lj#yeZ4VX6HhwyUjn*)^sJ%HWyacK$;BPcMwGt!$>El0>s|9U_2{r#^GV#M0tOHNyMia$;mpZWdihU16d zpJkqF|9qJV-}UF~?6zGL@Wb2>f4>_ z-oUQX-{tFNm^LxK?k5A1o!;T|%mllsH4$MyCke1(d14ihnj9*QuF>n8sHSr(H)}|A z^2K<v4YCU_|~qlzBk}c-@+{J+;k0 zqRKtt8&A!T?ds!0LZ@rm)&KqCWgLcq9)2>a>}x%0ZOZ1kEccf?K1R`uFoo+_&y1a0 zB!Q{6O5_R&&PVRL#@d=wg`RHTh@z=%6$4~Du<~J6k$*&EP^*B0I=9T#i~yI`1EW=abd2yn{><}1BSoFQfdn#_0`;5NZ-Ysa88yZT{lY5bz+{8FB^g-?aDV` zKe1rzDaTFd!{8aEzA0Q>4yMQwc{`@8!d9>WRftc?P}X#IO5eaqn9s`rO$WXi587#K6Y!xIB_ z5<*)s=?M5OF>4n$~r9PnKNI$of`5tt6fcH&2L9SGj`6_)ubwSOSn zo(Fbw%rISmJ249PAma~`OB@HXJ?Ok#JFu4+Ldo%5!3uWkzl3K{kPULwUNKrEPRq(p zo>W(BHrxxL?j?8P8$JD7$jI?)m@`7SQWv&gfHJ7xA0-dTS=zT&T zh5sKprxt|TPX<$Em>w1)gbB;cJ*Y8{K5Pw33We?FCo0naK}<~6T_}m|wPj#etb#S_ zjY)i&;?)ajdX;j}0sP!Pu`~siB6r0LfkJqqqtl_{98WkZem%2Pzt0=k#(JEB?_|Rx zNf<6Ol}d>`R1_;B?b59(+sashd9bQB86uLthUiYmbqGpKM|qakzF0Y`1B9vq3A&G^ zU(2agm4g{!u-Aitt#yT$kX4LGYyqKZy^$+cI1VR1C1c`^Z+=D5%Y1j z!d?WgUtyv}8rYsCuze!EDSsQWs{Bz-tds~YlA~R(R}ErN`pkVfvY-c{m{)X|zZhke zj|*o4=}e$ao}aLU8#0aKQQ%BQyp{USmv>{CB=~+%t@$93!U9$^T&*y$Bq8d?eZV!x zlOTYR-2KnwV@}CopCj6hBn>COG?)VZPZcP99bo?jJfIfjo{adKh<@h|7Gdy=^&ty~ zId+^T=nIqrjH#CwnF5Gl5G)mw`L!h0M-I`TK#wqx`SQ$NV?bGP;%cE{1Pkmj1?Q5m z17cLXbtVRm06XF>-WSFH&WqN|SjIR3couzg$f?mLfff)OOUim!8T04)LP6iT5 z{-?WY#|A2eVpOA8Wc9t);Dlfy2}ULJAnssKR-unItVPxWiC1du?V5ktHXQ~IkpV@N z6UNwMCfNG>_tUuy=q3VWPyk~ocEM%rl?bGt@c3j``x@|(=ij>Au)Au9Dyzk@SjOSk z+4;C$$n`~6^+uXC1@>yJ^7vxGd>w2DE9ppYOow%oO=-vY8?0h9=w@2KNd!H1Jl)1R zu)8ES##-suaYfgu|Fai}sIxKJ_Q2k-7$@(Y+23;?CFcNb%}d0c3>N$VyCV(+|E{*v z!Z>cb5VdytwEaA4H4|(l1~M3~>tv^1&DPm{1mZv|sI1=ncSzM^FW`)PQKIaq`L+_g ztk5(Bif~5elaTT1I|Jl^1)}(y8a!Eu>R=sC+4E zVZim&&RKxb9xP;|Y&IyiX-sxI^~m_O_OkR3S;R4saug}}k{XDlRP2Fb9xmx!c1)kC5_w4^|CtYX1F zZ`l*{{Cf8f1C#_x)&a@LOGTCR?;0 ze6KY;*$D2#3~6Ft8f3tIL9pvesxA$U_-T0VmzdlTpWaE#v89Y3uPz}9E)=L1hD{z? zYonw&2W+D#ZDGTsL*OBx9>_HMgVq(F`G6}6af|L?!zFl)SG$HD@^d%M{Grrb5~#xj zYt|K5Q0<$2`zW;TU5l$2dM!t(j@h5U*arOw6NDlS_a>%Bk891L zeKUM}HbvecZ8tn-#7NVMEsNAKF-=RLuAeav(QL_bq z)a!=kM|6ZhP$fo8*t&O$+ceQq!Ty(X9iOos`=N_iU!JQCHr$TCOZ1cEGNGbGq(Q z{AlocES|BymYEtyg4&b(>wzPftbL@fDf#GS&8+s_iSO?&| zn-W6~3=}-N?16udL`*I|wVFnQRxpR$9{^Ty`w{U9AwtLZ*@J`lqvl{w5EA14#QE%O zsI?3uLHP*NF1m)N%U$ISG-L5u^%=Q=B+!GRe)ybidC+_LiRU#v(_3D) zLITm7*)3)Jl|-y##Y~h@x%aESm@_O?0vjfKc;e)CSdc8^wqe|zR_v)PGUv(bO`~(& zp*W>?u4`o_kwSnhPO%?a+{;8J$N_^lE3UQ{`bSxVx2(WBtl`_(s1{jtofufHfGv;1 zcY@}~ZC=cC$kxor^%*bpyQEL8aF55tdk5Y<%>@q%%8rJHT`NMhi{JdJSLOBJ`i4Ta z$qM{sySFpphv<`2*NWpQXwR3B6KcqaTXNkh(7Qqq6JKo?uTYja`>%`}9ENHxAgeXZy7#jW__EB&x;jIZj{<5D-QZoe+pTn^qWTZ%J$0nhkiyao&USi%LkP@@oLw$D7RSVdV`CDPm9ib*V61&CWDhKj3!wEb zTrT?MaJ!PO6nV2b`pEp2usx(0448{N=^R$y+yI-ZX$d&xwBw-&Fo6*q^u}KNBxHKs z+(i|yh$Kf|*Ya7Yg?Z}ZD z!L?|s->bd5(#j}@j_5D)45MtZR|oXsZRZ`MW2Z%<_?C46Wj43OqOo#%19U_EbbGkzAPP-PQYI?c}^y5WV|hE3MDhBkjQH)Wvs_5Bg@%M@2+ z;f5@J4XME?;S{Q%S$J2+Qgu~y*M>-?wzcHU@*3OZO9wlwH^lb|@OF#$9`czF7OEqz zzd)jzBKY7E(p+{5qKszkz#NK*EQgRi8{I3pVb+{>Tpwonx_4pWC<&V8WYXRD-Vd#|^?~3*(CD@$dPnqLnQPrOsKEyA$LQ zr8^-)vS7d&r5|AqnVG#P>H6>t7Y5N4K7)4Yq`@DFj?N}^)P#@QdFF9LKy4Z04hvD+x zJMQd>B2`D!z=5Hi*KTj$y{VI1YJHU;5W-I~a#@>6nnRu&t&8&4N~s$0JeTB3Z=0JR zODe>V^$Z0gUUmBI|0o38M-3UOB=Ec0eKg}CJ0j!3|1<(RMYu+?7PG|&mWhPg>lIe}Jt!V@`1(AEcTnmypU zRmfXk%W>Lvl>t3T@%r&`7ulK~Z>tbDB=>zcAD+SVXHtf4nFRHw#-UPMzlbAtZ0F)K z=^V$bp)^pC7~F@_-Brqf)t)`0MvQ}7`V8(H#Up_6_i}95@&6$9!1T143EPKv;7+5s zmN5&en+wK@Ev|s&gYY~^BoJEwC|y*@1!awe`S#7Ktc5l3XCAwyH>!&|g2acD6y}Nz z`GhDJ7X%Fj*0@8-^-YMUZ|?wmkm#&d^e`$x!eUQc**<1I0FRx0{`XCi&dlRP<(i}s zt=e6~@3g%^{jzS7&pKMqTRf)uV;)3f~$|L?@7l|sNN|i zOoc^QDsl$l8?AZnzS#ZHpOk#;47nJ0PJA5I0>N4gprZ9hRjY9@C_pFMTqOr;_a-Ui z^7J}5@2k+Tn(h9O*6FniuEU8|jQ;vHw@G4eiPhpY|M-y=M=gK{()RuA*v|^T zJd(whqv;M-#wB)%xE5{%9rMis6W{*COJSAx{`&sXmU7b=oyM%G`0;}NNyXi|tFxC@ zs6{$^Xs(79R8>zE0HB2m(}j^4+uakcwx^l9z#LlI6>&HC?av_}O{D(XHDG+?n9Qh< zos#CE+DZbPJWzuG&%~=jRu0U&BCrqlkM0b2BBmEp{9RNERL?gjyV8P8*XKb=S78#O zE~*9v5rTC8j1_WQSzAM}qzJxqDBob3j-UD5wT?lSS3xAIe7P$pHXB zJXzk zvB8Up=;?!R=e5<9PVFy6^_x%)(q`Y<9XS5w6LRm0t;>Q?+v-KtR=Gd>ho=-uA3wY! zdcL2e{|_VE+w3mNZ_Q0MK1$yBz+pau>pwQxBS!Ry<+d|YwS+M#{=XIC{N#_X$C3&ztIBw~yYWULl&)E@ZKE zR5lvy++y+VxI1fDetFsNsMFolG|p5--pYcPXuoNpHA~aN9e;bsOr#=Qyr-5w98jJa2 z=U&F@n7CfVHE3q5iMjW+Z3>^_+SEj+lan6M*(4mwPbr zAC%b-P@Uq0^Ck!?4(_TzgfItgTQovUU5#wun#*L(pi+^LQm1tK7U z!eRk9z7j~_EZBRU0eP@@m~y-~{b{i;6{Jxs<4;GUz1oasA#sa&zxp(=|`tQD_ABYU`^IKT^qE?zD~S;A11Ff_EgO9%sL zeY))2wrwc3Ew9a16YMGihx8QJ+uW6spn4Qm>)W<*m1_MMTyjMLMR2?5iO=&Gn6sYe zvy=((ylI}0UWvsLC(0TDM?a8>| zv0TlqW8g|D^PvXGbecFH!<7yXkqeX%R3OhKcVjaE%~PyIaSU&g9KF1q7u8kSJu0KO?W-i4q!4Z1pLvo#>hq?9L!=^(0bN5y3%{qg$PmCL5|D%*NT!PZeS4m_ zG^8Hq>BF@7h3DGLf?OE6+Je?nZ3{}Kk(1(pms7Q^gtd)a5#9_T(v^r5Wh=_26czX+ zadU{jvo1=Z<4x^#6f|HA;tPZPsd3LEc{usI9rf85-h+Iu>lCx0Fu4L?Dh}#i0nN?A zt-XZ)fQRsxmrBR-m7WcAXA9vlP;k;luXPfXy3BD{fsBno+yn*Na9|=IWCqYITyYT2 zY3<7bKdD!uZslRun9+W>sv^~uW(^5=u>Y)LbPp#oleOX3^c{TehBLCknPI~~P{J3S z9+77wswa|BhmS#{$eQdRFBT05W8}gZK(*!ar3zFujYY<>7}!VC6$^)UbYrdgz zhR68z(fp))XGXNxqVO#QoDY%XyzN2?ViatbRz3=S@f7WI+8%U`wI;Uu=jg z5j5E!-3;Tp#sJkN43v-^FajBxiTzHMfrtoc7MS zqno@JV1zZ6y@c)D1FXY=Hh2NONiVMP*zIH`B5zD&AC}!SSXXw(bRHDd46F?e7LYuU zghGC5T;c3}$Ie>CJf-x0TDBOZSfG?hSUx_99M&i$Ho z#62HaG(M~wMztokYM|K0IMdq2QLTWy+fl5Hm-i}x@wq@P_%4D>dJ{4b^dcEV_5#;c z!lTS%e`RnD8C&IDYsy6r+C_1jpM#cdK})}P!G=c}^N?dYu$1_h7o(Xblrl=s&Qc+i zkim-VLAp@d_7`x9u3Tf(BRB8PbCJxu+ATh7sF?qTOYS8EE|0zgvJFvBxiGLHotwSJ zwxP$ewI|B-UzYw;)KQ`T*O$Z+0@#o|%xzxu-OVHNKtU(-%_Q@&->0+8%T1HmCe&?T z&0t?_;eMv<96C307t9z2PI{GRC+^5oYoKINc*HB@&v_=F$I*rj zE=vIN^8hs}a8<}iIK*6F08Cq3+;b=4Fpi&;vmQZ!-gMsRMdU_`jrYePeP$sO285~Z ztqpw-s^wm>*&J6oXmua#V*|%i#|I{fn_@DqmNOhHWApg)xDkR817yx)YD$1EJrF+$ zB!CX33ZT8`awBDmP$F33*zLaRu=L>lpBl~sV(f7?*Bbxo)v?!4_9J%X11td0$(DB! zc&fb5J0&^_&A$$|0IE8tj8ypyba5H6P@1NMLjmR8;>S%@w_%u8Z}P@R=NxbZf1E- z-W$LIqX^uyK(01^gWRL)6DjL++WrUo?IQ#$8mR^*`b5Nr6^P%*@Yfw-Y!TCiDA~F{ zXjZ9eqD#?;Z>aLezy|T&=qYe3zw!PVz!tt?g#nC2V*BwIUt>;(Q(3mOE73%@euepB zOG@0XR3siWsUws1a2+YZp3_V(<^9_~RF~Jgrydk00TDQXf};ee-5gp)wmWzNi1lJU zB6XXg*ggbE<&Jh3wOmqgq6;n;^l(O3RWM^5Z0I=UbGYFvOq#jd(P_QpoTg z13S4F8f`jkez;OU@UD0JQBW^XD+4&53#binYRs%0-<^-~O36Gx00%su6R}v9kne&= zJOS5-*K9@ShV#dX!p^1Ww5-F+^|Ww25lq?!GFo%*R5`>GL2+kCdE!<$Ju#{|kvR5j zN(mmP#R{Qw9V93h68QN9&_~Ky(+YFubMk`&^2Qj8EAPNf<=*!ZhfZlS9AIPsczv_E zU|SC)f^Hqs39;^p{LD~0x*O)75kVaLSA|>6@VZW)qJ1XFi>#r|+?2V?>zYBA_!^3o zAKDaNTTwnmpq8i(_n|TIB9O%xc!=7TTK~X%y-m;*rXyfh=N!b{Lr_mpqY))5_y9AE#G@nFs{hLEk^!x|{I5~@D4S-Rv?T_6%xL9zJd1*qw zSjrz0^Dsui?MbV;qXlTiq?xrOAz1!esA_Xpp4g*sg9D4cEMedFGTjqwbCm^#S8Rwg zZ*kkh;=pT?Fx6uSjA`!n(!DV+gF#SqacWnm%FC7^4HZ#%^Ex2xzP9=Hn7#DgcsL~o zTTaw?M;tG+I&jdd)#Metv_E(v0mDtF)i^x{ z1lmWtJKo*b$1GFL$$DKJ4v!(|D}n0K(=V60H2Z6QGARj%NVDW;m9wlbHam zAGq2W#Ix|AF!yab3FE5GLK{ZRd~~{owd-e@s-f%KiOg_H>MCg<(xI^{e1}EBEq8dJ zOVeD`wpQ-b5HxaLe`8$q>zKN=DS)^-tN}u6&Q(+yA7q$; zby%?E#<0-$qM->X>cWZV9UQ#b9e(`PO8=+GsSOxhs(f%N~$NkIY`a-eIwgb>G$N8a< zf1J+@hL{|m&uVn=6sg{(|Ly#K{nqr?yv**fvXFBO@X(i?9yh;%r#yz$LTDhvR698f z;XI-Kx;D0vF4qq*_57>KBfWeDS`R4Pay|G0IZLL?(KjGkR-A><0ogVM{;2Xbw{|sK zsC5!ZdtOD!m!PNX2SwQjJ2Yey#cWmDXq4H4xVnkcy+AqGe!E z>8deMb&v)RTx5iJ(pfk}hrGuxPd@VV65fF21;<(Ca*&PvZ$*$mSWTu{g+5kE#{wZ5 zfThNfl}XpSRlx-00)b-^u8$i`WW-T7Z6!)UP0YfTX}_b|(#R49()!je}<7_jfH4(*uYOGOuXu$w-^an1<_HB@HQ-&y(FmK%iw2_C+CD<9l#4YzA)fIDM< zMnyAehGuKY`;wWgG-zm>NrH~A?8&R3YlLDHP}zB|Qxxyfp*i2W|7`w!fkng>?#tA~ z9|q4pD!F624vxWg59;K6?Y{o*jCrOtc*os4k52XGUrwDhj%EGK?_d99KsdS7_7s5a zAu#3!GLA`fKEJZN4lSHxY%+^`%)3T7+}V00a4T!ox#yI$bT>jkQm>Vj_^&-HCz zP`#3&hu&{lu*+=M>3ZCt^-asdw3wHL?@70u*H`nIutgo&aLwu7SaE*)qQS982fTM% zmDQ!b9E1bh!f#rYUuj=b*w=e|$GVlE%aK7W?Y)z@@k+&X`);$k%)9&T4pqG{+e5td z_%;Z?T6($fq2u(?`zMyZ;DP_dZA%H0X#8!>S3Di>3J#mJPWxKNZ0B_aM75ofd)uH> zne6Y|JAHoLrrFK>ZBS|7Orx5u9syYpadC3TO3pqWhWAGmQhtgH&q(c{roh08zkNb44ie}p5a+hnL) zyB`U=_6Ntj7Hz`3s)!@qA(;T(sWb@d_lsAJy#>nWKSkfss=ym9+&HTgbo5mJi$6*v zw7he1({0j{e(#7kEBULtK3*{Q@%uG)WPa4sS~a=mINQnFCq7D=9X^6J{;rC@!vo5y zx@$^z+t?L=>pJ4)?$K{IAC;x(8ZthCDI8I*)8|2B@oFCKI8cSQ7INt3m-Bxdm)$o1 znk>EfwQ-x%+mOq@9$dNk?b0cy_q#U#{rHD1{{MoIfx%z}1%>|;A(KUReSCZ(BO_%9 zS!!zP$&)Al6Cr!{FG42w-x0D`K-{`IZdDFF2h^Vim^_A<$PlvIK$~HR^8*Fj_iF!> zBKtSEOR)PNwcUD9beBA(Pd!>jkyV0|F2Mf{?w*DoIjj6{aJLnkbXhyK+i?GwiuVHo z<(-|^ZQJB^PtPA@&oyt#e+GAdghjt|kC<~$n)W;LE;Q+Vc=Er^-K3-+w13OHANTw> zoJ^r2OZ9)^WLWGUZEYFd_P@t>eKG&CWZ@hB#mRP={1;1h%XO{Ygpr zlb-%ZR^DYJvSs)GEbpGt{;%?Gu71T?s|s0mx6vxE-#xp-uR>Pa9SzQx)pnm8uDG+O zVktHIKS8o@$FpCa{I|AS81`>!_e{*_f3jq<&TiN7e_68Z|F^SST3Y&l1<5}A2S~=@ z{Q2*Z-L|$rSFip@WVc{c*4e#N`oDB`U$%~ZxcXl#+5ZNT4G;ghbLY?W^q;3s|12#n z$x^#7U;cUj{?FHcZ~y-U$z%xGq5rQUyA*><{{tbbKWuuIy*+9u&m#&S>?MC%&5oWv z1!(J_*C-Jk9>vF=ZU<3qy;8`JI9C+h704t2Kn|p;AUjK&6oUaUENYqH^7OXfI}9;; zb-yPhOxYqzxbl#B4SN78EvP)h2m>jT3^RPiW_Nmu_J;%TpKD{TU|=}D-6Mtv6tEcV zF0)^B_n*+(a{Db{mlwE5UGn!?+LGKcR3DpV7JSO?i$SDL7#iS z$X|T-n9Pp3h+EDJuE&T-2egX?X{7T!K}C$1mGgBexjhaeJYHVoOLFVpZ>~5KM~OH zB}hE))L9)@xUW1`zo^W(iG1|17s_-?_M3S!KDZkvP%}OVa7C(YM}bBxrQ~Yi^LmZq zQq}YbQ(&{Mgg33Ixm30ucJSd6IUhpQj>}d`e?e{stjxK>RKjr}Ios?vMOA9oQkw5f zgsQiJR7GA9?cyU5mk(Hi7`r6hJ`6Uh_Q<1loqO?@z;H>tBnfN}VD#ZyFyy0G9j8<| zvy+(dD)g)1xqWx#-j@jZX5Z(`5dCAjGT++^>%iYswZ#VxhaHvW5-ff!lk+|=MN|PZ zc29yfPQ_Orx-uEhxQKimTp=djdiwDy)TUNkV%lr)PF!`ErbcJpsDp%E7+3*{0netQ^m^uxDDv>fyAvk7PSeSe(Pbn*L>)N3EU&(Tkr zC*BKxbo#-RwjzbR4$OExb?q5L@7qyNu=ton$~3Z2Sx`sQdRz)jE$jn}kCxlsYYVva zlX4~`y^7n481{PTxqp9FV0FYVQsxFYxQ|qw->BJZ7p}rQ$VXQ)-W1Y5jGS)s70I8qxHWQLz;o)Lg*2{1@ ze!TC3qh+QUYRG`b%-6EAI_s$6rjoGA+3Gh~F{Q6*E8lr9FD3+J-waX_%9b27T{Y4= zP|xJhX9OW;0qe8I(Kqw*F!wxYROh9K**5^Uro^2O#=9A=R5;kPLX6`1Ad_?UaPW@M zy&t~L1wsZ`+PomOD#DP;D{rWEYONY^U<5PPESnnYU@>Lxx>PbJUCF#&=L}49dj=Z; z&{69^d2IC4$#2YB!0ez5Vuh06fOD=GyL4zcvNr639Y>|wZ->fZ7SfagRKG-S(vd{k z3V+o@o|ZD8<>CpLkO2*eZGadO!wAcVK~y12^`>|N4%1aUOLA8-^J0c5)VE>Ly1HqD za6+oCdOghr;2$j69aKI}9y!o~h#8Lpz>Cfd!%T>*i-Yc1igeg?89(Poz$gV0!AbHhSXCdX z+|#OI2V(%j4+ervTw$u5r-9xW1{OZqun#iW+7Fj>T}_rXh&yHTMgKnPNAt#U*t z=qd`vh7AXaIU(sGc=1Tb2}@SKG45>l>Cgif6ZSAd{XlQcjayZ7W}w(rE$P{6 zRxTWADhfrMyfL&swRMn824clXxIS#f+~PTaQF zDQNR$>V~q4XKn+&IiHKwNXobzYxlu1G9^07C=edR1MQvs9kID!K!HuOFg}iqiAiuh zPvNsJw5>o5%7{&g43;5T69cMm0hCQ>2ae_D9BrM%cS#|d!~Eo|Jm6^a#adHg%wXtK z7p1)!t}0^;m^Xoxx$%-Yikt?6?98|`QzeUp<*=|Jm%*P42mQ|6;uvvyuljji0lqk% zZ8I~^qc;z#IBGE;uiK&`#?n>SYfTRLg}P?y(l$rm;=gFlq^J%@6|(m~Ds>|;RT`W3 zDSzLS-&7da@b&7ThMh}LpnDur)hlbOQ=FVI-vt|S7-}S5p~Lxust|*HkVO&@d-Nwf zke8xqsc^)A)E-KBp*0js{&DlXgm@2o4vN}jeETj{(=U6HNSwMEJMCKFYwHq zK#_IUj-}bwA?*+r_&EmN&Nkq zI!J+ZPoP+i13>oDd}Kw+K-7VgVe)4Hr&P%x_CxT5H9YEprz#Qty2;VMJT^)SwGziC z9XVzujW83&qUed^*yD#IsB7OL!6K*)EojH#Ef0?Ddu$lI)dk^0lm8wbZG-o3Ain7QoUhazxG#(eBK}-puXT9S>w(|X8z{prz_#xim@hcz;z>&iq$BuPDg1OY*0=o&em^$^`Hf-mUjj=O;?452FD(Dvact{sWm)E!+f-tqqM$>()BGhYA!_%MnT zG_eari(qxi$4^+pa_H^}1d?|nIz%6GN}MP23ajGbc0b~VY*8Ju@r{164ii~Uck#vt z2H{yoH97hT$ZC4pHM_uQaZHWuytaE!MzeepF^fDJ5lV;KQdnJwBTB|V*S0|LOt31& z8<2ilBh4em?#QxjQdV}3t2pNMu+y>tS&f25NrN6_ppTGGPpU!B3o-VFMRlTec(Qos z4;(ZcAlG*WCIbd80}z=E#54Vqu|f!oaG?HL(9=?2Q(_ra?4(RN8jq(KWuk<_y;`Bz z``^&&w7BS75kCcv_H)f}HE-j*WbS zma}uMwXej87RG_`+K#SQh zYf|>Gz%gY71Xn|t5g}Z9lsg3ZYAwvx$`tksV0Y0CONI!z85MV6nae_#dSOfS$70B+!W8=1g=Hw`QlDrIK z0_F}&`n^y%76mN)iue{uAu`J_G+%*b zXyajMJ^f@o5w=efF#@k1=R)ZKxf4Etyxx@k8BiHi^|U@m_mvR7Tyr%F>lF#i1crajC&RN8$k?X_g+lx=@`$_%1-w z`{Z+otW!(h)2i{vuURNe8P@?1nqXhjt+|vj9>nEBdx+rD2biiAN`$m(d>ULqt2ql* zr_Eee(m{gr{L_}!K{9rsY010TqfWl%sGduQ6rS?J5sJ)xA&UOdum zEwYCW43?xyoHXt3hIJ`KG0AEIdKak zVq}L1;g2eiT-0tXAV7o<+)e3?h(q*nDwx9PP7<(?i{_|B1YSqSnmTQF2dC0#n*p+J zI5L5s>N6466$Yy3An$rZFAG)cg+MC@^b!^r)9UE90@*34Q4T7cmG9Xz6jN z4Bdp^UL%A)F-TC9(Rjq_@gcciS%VMru`T(sbVE?|*}rtqv30hcLRE2L}-k=d`pf$M?Bg~LmZYszm_#&$q0+I8|#aQT$+VYGgSBs0>)B1 z!iXPRrwU8rQ|~~_R+kV}v>mcMZ`(0X_H}d?K@dwLqs5S`zJ≻MieUHv{SR=GG|% zu~~87I5@lOO!;PoA$Tgg$7Xb@L9U{)b;6T+Istx^PxIC(a^ZwkGoXD-d*cmI%?uef zlf_#*eM%jAXl^1{8+!y5&ayu@&IWgx4SwG}^!;Jhj8|fln3}_v+f9_?Wt;;0dOLtS zF(}Bz1en+nNaMrL?Yj~hv#}hsUV$V^p!QMlUOhOx%u$yg)|+{79GV=el1 zZuaZF$eFOoa<~<6>_=}wtO!maHh%gW<4RixZsZ5>!@P9(Tb&g zOW@Q8_FfeUG@9;XyL!T?8l|gpkB+Xyh)>yZWLW_@X~kWl3u2%NVmeo0Q!|OOyj3z` zqgd@YT;=E}3R?@4qrRCK?4zp)WwbDR*tQ{va4EFUx|Dci6DmRofX0h&ZXTHa5EAVx zoeZFXj?l0oX#@&^?mGngMitNV3y$ zq4SX*G5wb47W5lb#D)^b_35x0v6C?!v{~3Tc;fM^4nUC}b4!qy9|M`4bV7{_X99+=Y?0SRQG-#r*D`E%T+E0F^=y!Z0>%pk zS~+~}Fn{QYEfD+@5<-U_KMvO7g9|s9I3f|rsDsV6@(0CEkJ88XY`_fZ&4oJNwih1t zGDpdUgK8=r9K@-d9@@XrlFhXz_A5vf=pD0V`wmK?rB*t=)9ent4vjf=jm|zJ6 zU<7ocxnNN*C122hD=@9PeWaR>Zz-pyV$u20QM8;me}3Gn_Y%^PlQn#~cyR>=1p=|l zI=?sVr9syd7;-su`FhD73grq$I+!kooD?oCd_f~bTiy&VkR~B(jnDx6kz>E`} z*T!PhA|4J=SSu}G^wWh>`JL5^&E687<+iJ(~-5>acfd zA(C_VKSQrQ0M3-Ynz)jz9txlIaXQFI4WjRV8i7(Qd>b_x)E|QErXx<$5obhTZ%N}0 zKDglP)Eys`Hxjx_czGuv^Hb<6SuWyMs`#rmaGxpAK)BR^54&*Au?&T*BExL);LH)e zuUL+T3cHpAdVCaqneteG9zu~{U%VOLdJLtf1qEz?&4fUH?t6UQ0{u_jJ4L4K;rgeu zO6c*ez-E4~pT+(NK+?K;eES`${)dal%v}yBOI&qfp!M+`~thG@U~h_>`dEJRjQnodQ5H=Nh9JP!QKTeLgQR&_#E@>8xwqUr#%fs|{y zI~%-Sp!Tc-)zj+JByyXQpKHhvGRHy@1HQO>|Btf1EWCA(U(Y)A#*4QI;}gKGQmG?S zF6%^=uTn)f1z8vkFDdj5R{r#9Kf2~8Xa|28>(XLD{tH6~#WCRLr7K5o%UgJ4j^s~F3`^vS5C^9re6q6#?n)xX4ZrAjI7brD&;D+_TP(1*zf^&`s z@%%8FoZ!|kdEo7ErENV@coHKum?F115%qEILD-kMPE}|q|I1+p-17TES|Tt&^eyD~ zYDm!%UK^MxMPW<=0ILZygbZrnHIdjBQfV11B=Fn;eahSALbY`<}bM*-PWH98I-lhs;6_yv{;%)r&uRubfmpWwR2x zceFWVXWwVGfzo|=ppy6Ayw72prpkAZ=*UKUF6D&8eXfTR^;L}Hr|7NRN!8%m6r=?+ zc*)Nw+NM}!i+T7qe)RN)I)$OpFoc4$o!!W{JW7>O`t8*9tsVm}<aE0moZc;@W3|(8{>f^eE8Cd|jAo5~IrxF?`o*E}uocQcZ$u3d1TTGfrITY-o z-*)4ayfW5L%jatBlP95uN3qz=G_38W^Ig9M7lYdLNwqmo@Fx^b1TEweuEHn^0rWHj z5F*c4BAiZ|Fe|lcW`Lk<-L-|12zsVZ4$ED**&TgxYP?Q9j@7_t8d4WHEGlKN2OZma zU{rI%A#PK>+~@oeCP7rEbLa=4O?lwyp30K%o9Vp9_CpX!|Ttj?{(-Nz52!np5ELUxGjjO$Q|B$(BO6# zfgcA~JLx_WSa7did1~Zf3>@XwF(VTkm39K|R~k;<4{=qjoem0dJHC{Q|9EvAqvp&w z6vUqCsV8nXP*jeL&L^hyzRy3m)@~!iZQ=eyI0^$bPXrC~C{(#D%ObmLf0pjFKKgaKlC()L3$5nUQ89 zA`U1vefWt52>7c${3Khx{z{AUq^CU#ZD^cPu4~`(Y8DfNfId z6IAy&H9BtHf~+-e?TJ^gx<`Il;%E0}QPmkyvgo5k5iyMr2n}}rXbok-!_*M7v}+V_ z;d!98$?UvpfKr89p{fJB7R>hKf6r#Er8@mn;A-qu6d=29m)b~(yA&+jg|2zMcQji~ z&BM)Pl74_Qfy5;3Y#zj}XK|o4;!&kVpVQ0DSJ^Cqct5lSh;Sy?KkzVB+7P-Ec6U1} ze|}J{gTXZ-4M4PJfr`<~B?{&0*Udx&NZnjlMMS6Et8cQY0BJ~vM)hH-3z5Y0=Z!nlKXVeQr zp+emOzoGN4vRJSUt<~RJ>o$K7>E~n}Wrx>7J3j|dT|)?_Rp z!qgxYCo~N*NUIRFF)5UpJ_8$2^Uqq)w<^zYWk~q>VQE-B-SH=(yN#J2$MmZM?VFF1 zR}EPzGeOBZJmt6cL9VL=5L!T%IS1~?)B_QfGzE;SRPu{BiiQHjCKk0Y5DJeWdN1$& z-h-JrArFC$>v|mC+pzm!JY1Xn)MG0UYE3GzY^RL?Lo1QtDpIwJcz|E-!$53>3H<5f zZt?%f~NKG*Et*beM^=>q2iuH&NbW-($TmSt=F$U=E z-B;d`vM z1@CDk2UX)JH?@%&wOvEj3_xs3AijU>0i_>q%haW3TLAmo}w1#aCjFK zIoROx!N_8aCTHHkGV;za3DpYS^><5K`v+)_A%qFNAh311z7iQBbtO#xTs;SL+**_* zeYmQ6mnG7FpKyQd48{whA`qi_oS;0dTUB+UF){~&nf6^~3 zMl(~-&OQ5TSqV8W%syWA==Qd`(5r8DMfb*! zl?UdUNFgM$BTQu%O@%`XIesa_pzUTXfkni8Q#uU`91$i_vYWvojx;%ZV&hQ z{<(gE(Kybc30J>p{N0lG?gxL!bLZKj-y!a4&8o}mPOC5GNdeN2#o-aj%0`kQ>D`A6YvI#DgJ_ucrl(zOu~5pwI&i32aRm29Ka`D-KOC2VFpYQA5-T2}^Hh2l(Vh|V`nQY>P&_8r!bK1>+ ztoNcdGgPl!;ra7z0!U6gU=NDakT0z&5N~6P`kd_{KKWgL>duqHV50MiGz(p$nUpIKn3c-YwYpl^w>SLUr z#03b<<(7LsNlKfd&m&8!3O<*8g#te`jYOv0ywP7z88w)Hbq9BKBP}f_DLaIWdNU67=YfoqE}nL{+)xSC zcLemrZ$4l>a+>F|tHPyn4LCb#+ZU&0Do`{_E;~Eh9Q(z6TV|twByy7u!l4HoB7r$C zgK9NhW`=UXf{Ur`7h`%ZMhm$yR4%XwI?-u%r&T>PiK!$4C^7&@JX5m{?)s#rFH_k< z#5z`{!=kWWKZcMcK;!imSsa+b!e7|+zSMnI#j{SZF^;8L3^rJ1;T5W1yXMZh!lhSo zA57O*)0pPXxy%yA?ow{WUa(%i60rwlNHb)KwFnu?_EuviaP}DmP25+wk9fq+zWkCD z=Q9rJ&fW! z?*l`FjVQI~{&7QHSfsJJ9MFej)dIuhgTX zAXa!%cT%%Rr8uDspu}f)&mg_=Tt67ZF3GvzAhVvYikM|%ngO{7Z?Ee0CAQ<;B(|Dm z@b#O;E@*dlBHSt`B)d_L_(gHIyHm z3Nqk<&qgcWPSby9Wjz~n+KQn$(hLnCu{$$(COB~KSd~Ai?KUwmMxRHqx;Bk%c?(f{ zDR67YLjz^4TomV1@fNn2u_+lOiyfK7Y46eqcxU5gz|iz&K;bp05-+xY4+K%nvKCed zL>_D$Wf*%mUzS2dfr6LWAq1#14!WwF=ROAU>w&nC$~KEH{P|guBe69g+w`^o>;y6v z4*bMdV1%prrbl`CyO_menBg?6#1QIOffWvJD&g#{hex28_siB11@(wZF~I-veOB%n zbvS>cF3%3dwi1B<8e>z*s7vH377yqY%HKT8x?hF%rGOk5)0@62IlTd>Ewgf)p-LTG zzh)4RPiblUOTga_7X$9b6es>>5y!fn=svABf!+XU-sG)zGoCtyCGFQkzv;s<{2USs zI^6{M8BhZ*$nfx#>pz1Pd>8!{nK}yUQ){wC$U45)S*CcjV6e$}PAZm5ZRVC~RRw#w z>6|Wvqh$CAhk|42CFO=)2b_&m*tTXK^sO+2q3Qf{ntU2$&G%Y09XQLs_v82N_(@D8 z%4#bPY$^Z+<}vKDct>?*?Pk^wJ>GyGPi>vTiZRDomXd??M}8FKQl*e=0ccu>oO+^w zp$Bs!vJLi4Wz|e=cR9WGHMiwXH)R&$-@~z#@e_FP-Ggovzq~{Uc9zE`I zD#$kw75YkQ_U)Sen+QW?u%E#qvRY>Ir9FPb)Y@4VRSNX1_x3b{8AxoIdR;6O-#CLU z`(QV`89sLyF>1-P7~_PUDHnFZI=H!~aWX6uWSFaImI=OZD$o=H&Wiy~Jz$41I~N#) zodh-^`JFfp^F2{?ZtBVC7zb>t)oBo2!GjtTh4oT~5e-aX$lyG%8sPleZ=8d1A(b*4 zJH+*&HVhmtFeLu9ep6d>*r1XsVX*`Ntbm~eC{?2abhTTQ9l9*2didE}(VHAxh)J6)?o|mu5dQTw4Ip#_bqg_F3Edbm8gsPnl1+ zhx6W!z+wc?3&>!??2b_e^JvhyMT5#Q5lM48xC`gmglnyR+xVL)v}|U5@5&1%#5xq* zOlvs1DmEfTvJ7OzCKY4?m=o}2@2Bl0k9Vb(HGq-UuJYPt?a6Q55D*YC zQ~^;#Q@{o&f;}oK)*B0ow~8nC^Souhdp~=hebzer%UNfweB={rW|En?e%Ie#HAoD% zWPxU6#1}&o|8ig%!;lLU#O@Q^ii24?aDBz*35MZOBPSP*Gwg2)tMWJDzA8sIw4(sX z<|x7tshVHLtGrLZlmW^DWx`z1oRp=O&88X&6a^ehG0fo}S6=xfNjblENNGt4O}(t= z`{NN`>D~^!0R1Q5Iv{*fq;ubG_|@M3FEDT( zrC$Wmu$y``z4Z294nA7B=CRblg?(U`%H{o_xkysDNqfsF9PeC*j48C@S_}tNXS0kC&4#uTP;g z5Pr=5z>z>j?bG=Vd;^Er{aLo*4sfgH6(_72t?=YO%MjWUZXxlWLpm~s%UwN=NWZ%_ z&bxGF2H%x+?jo_qp%=CcfZ<63Z7JN1$or5KX##gg0tL+lfZ7OXAy8HaRLm1Nb~7AH z)-pXQtD*Mp>U_R!IPD>;gB4;F|L< z3c8h4`(mO<-0B8aY^%5EXr;QK7==w)@<(s=-$FhjgSFjx!EA#3=5OZIV*JZY9bTsT z)C=hv9QkgjgA)1*a@vsbOodExtV+G*efg$)10*l_^+WwPT3EV*ke*S%{rHM~Nw13i zQ#n$W_RMitBu9_T52xtSkf1(E{x&C8ey_&iY#FBTBX@2e7QH?{$}`VKntO5iLXNKt ztD-z=_U3J)7l<8UryPwm1K#b)+g>i=+w-23jTax4@)zpBxk_Q1lA6ZDv@`oJTgk7x zM_CjNUfvaaeCdkQhlf$DRWRfHZNyiE$b zlfKI25_%>a^c8t*=?ga?!p!btnvD`1rv>TTP}3dT)Q_>07&RS)cN}&vhnB3-x@rIQ z(|;TW>>EIH)@ogRnq4=z+AA^i8Nxy}nyR z?^Y%idAa%H8uBo3|HU;g_;OHSLknvL2YH4$v)7=r6$Z;Y~&ma|xdc|3}oq-UwI*Z*3s zdiTD)?5{{s)KRYE41B#;BnJy~E`zT-%%Mnn4k7u7c&^>-$~W_ZXdmwH_~SeuU}WrU zw8$c}&*BbqK~RA+t3s`x$HWFz{YcC(UA!0VrLuwe5!egH-bN-(DsaZDrbVj;8t59*OIt4-4RPD3CtRR zb46@ZMwXGr)~v(RX1duEk4roX`2s%2n(@;+xnOJ{vn$g)Vkl>?&+VlHllJ4Fe>Qm1 zVnyLP!muZ$Km_l4aK3gX0X>&z)38JSO}3f@4b}T>Ojez)1*kG+4QZ#Pf5eeF=^PVA z>sZUlk{|O2W|Ne>NUT$St3pl=(^BWl(YL2A)yfy`07z0rCT^#liz{S+SJNuA z9Tnihdg4<8i-v=(qAPnz6Pcr-F5Y<5%S@x9#L;4e$!kjHWC)*6bxj#-rMc!B(Zm)# zJ=ozQ=fovN{#i}IebkNx?3uYnk@bfSAm&jrYOaY;aBLbsMp)Fgc z+g^;lO6C_v#{|xsHd;RJGsNlC5^c9>k^HT3B|C2mo^%Jn-Edrtdc7&f&V4Fpsy4bT zJ#cs|_{(5LO^xT1pM_^`mzww>r`q0WrQV<3lW?u&?Cv`*sNxx|T=QxB^yuI|?F>E7 zI!#ijSZun7EI)KFC)x4a8r3RDw3eM<%U#vOmAmbpR8ddZ?nSB93UKtWfnuB1zH9aV zE5H8w8NSXrBk=jR(AoWx$^&hhH9Xz@qx@?cfdw#k%^vNVA=938*um&y?-KbYNlZ@# z3n)HGgdh~yj{18Mh7?uOc;{(;ue}+A8ZlK88e++Zx!GOMOxRtze?twSR`ks%9##Mx z4(HJb*l@$B(_f5qeY(SO?wJW`pAajHonHA^UUP}d)u2%`JW^?)d;xyrNRURs?iXM_ zf!_Ce5Lz!FSp?sun!~0VDGXva?O5c=&nlh`WV&?NgMTF`9YR z-^2;WSLgePhXT$VSo^weLuizF>6;chu`+CC5yJMvDSv( zt&*KiEQ&xx~Xx|o#TiYrO0DK zeV^th6Xd9cyRLe(?&_`^2bv=gu>q+eCJ&q^IJ6I(2HOzB0Fk)5_UGD_`-`4^8q*%# zo8jTV#?(63xRVkcHTmtuvMzd7T9suf<6CHdK0ZCN)R6P6)gUB zDw#mg_aJQiX~9+xn%~*FH793t?{mYojmL&D-ZwJd5{9Z}p_>SiP0xdIHvPBcJK1|g zgU_DbbG3RmyC+a%`k>{Teb<_o!cc1p0sA|6me>X5o^Bqpa?Ml8#peeemdHoh4n{Vc zcMoxznc1sPu8TVRwtgB~6GQA~x+|8gFq#i@f9Cq-o8|H0IpeV$|IZI!ZD==)L70t1|Zh!#V==<3>w-5u4-7khdK9*Yw(qfSYIBivblZ8 zBD2u^Q35imIlN!&zR%b;=k;}F&<;5ZGPW1)xe-EvW&{Ga;DtF3WxPFmQIn z9Txu70W2$7+TIlI?xQ0Lba!ASc>2E%SZ8{>b>3DTN#j$`pzTA53=7Q{4}iR}^P#mR zK>G+}nK@?NhBs`gqDuWV=aC!>Db6Q&C`^qQn&%h~L+s&&FM0q+->4*~-Ed!n!UKb@ zcIR^34M3@W#D$mfO+6y>7}Na55uYyLFsTXt6Wx9Z&%?2y2N5ZOK(pCM(1yZxyb3M5QPaHnI6pF}GN@?&YvIweDOTxuksJ$G7~``k zjgRh%dZ@2{o@qLx{1!N2Q`(AfOtotA_4ZT(0C3(i;yP##v5a7Id`-hK{KLCGS(lv% z!7KnE10I5s+9PL6!TakNf2m0?A@`Gc1{P0I!QBIDm&m!Ro1ZS*(LJcUL>9PNJi`@t z4;e27QhYqMHUYVlP>2e~Jnwt6_m8pM4gfxHS@xNB+d{V^!w@PRfT=O>( zQYHNznj)FWLsN1h^vTrj@6Z(Z@1d#xfe6V%Q)Sq!ntu=>iB9STBW9af)~Jg2lv&Vw zd(Uh3De}tHxBnnQ^r#P1x||5z@ymMd&y*{n&(X{u|0quV?-L{}I3@r54Tbjq_e!Xy zrl!5U{lbL{zjJf{nVXU;p$nWV|5QTq+*D=d@7mhm|5QSKeZPkau3Rhnn+Q!+{hgbd zJ#$4)gxp~1m_O@#ix+M1I4pk4pxd{CQBI^&;-san48F|OA?d=NwK zgN~@JW$m1#{HG5pKmrIPMaHm%#i;bI#TNFn00qNk`w{{9tydv(KBf*+G}T>p?CwS1 z!uDbKVS;_U7(2~AzdXY+z0NlXxLayuo$Zu935<0xUk?~jcE5b$f$|FiDBBHUI@IJ) zD0G_T0ReOIJG+6XXIG9_Zrw$sz=pw-OX^4oah@`c#<8Z{#jFpZu*dr3sEM^MinX^6 zS~ci)|E{i_IGqnuo_m&;{;p?Q)v(tc&)QZsL;OX%J169A}9DR%)S z`l6I-RZ5(p-q$rWFb5?G15n!3YkasPrIG^Jy0U;}h`UnwZ`JR?EU;ByN-1!%XB|ZB zKmCZZ<7`_k1w)v7xOe&N8mxKe+%x211dLS?w#nceLa{=WZih0$o-)rlHbfx@_v7|vSHdOQHr4pZO#xHY6DtoLp_ zAjbW$ql7ghWcR2oa|^HbDigx0j`rFD@uJe0-1(bMIh|W!M@ZvueYP#6eYv@uDBn`= zvr_JZj7&%Gvk$p$U6=~r{O>+U8^w_R4?gIs<+q1Br?-B4l>O@L`K9||O?0~%mfON^ zPdI@lm4SM?i_g4GTPA>Sy0Z??OP1R?dLXFV#$S}~eys8;>yY!-XD5zr+vC+c5hNAF zA9iNFmi$Jn^(fE|8-LgO>I41*{?~=5_)2y60fZX8CTF_Ob2jg(nNL6oN`<TnKU&` z$5MYe!@zIv)~Ngn8Dg33;Ungzi&v(d%R%r^poxu3iDcv6k~tyNwV8d=P;akccr;{S z<62B2?^Oe20l6m5$WOD}NsOM%XA!GaL{+u)g5l}i#ozrYxl7JC*mrRAU@pPh@LU7s zOLn)4uUI5p%Z~fvK^a@PEPgWSvTqnR4K%2356$@dZSK^o$Sa2Zfxyt^cE321g z)gr|SI?MNTIv5WXYnwhtSo9P-ryVJ_^M(_gupScjQalsdj?mrV6a(+oacsSATrEZjVi_X|3xKAMM8Juik4< zVr!svtQt#)I0ZAH1ig8VXUQnS82e?Khy@&D(o;_#iyFwI`}9QkTCt_oIOr&)U=#H) zL9(ZWb_w5-QYc&{?=%E9fLcy$w9ov!YO*CVvb0weB$+I5>H$@ET6@MB51iPPU>0ly zI)92`p(^}bFw&-LC>qcl$O3gtC494Jm{PtGPs^qs*#BKUw+#}(r&h>^%lH*#_9%-iT8Gz61{dT6JKv#wE_Ud$t7-E&4KqQjkpXy|1 zrq3Fz{7ano;*x9o&POkxB2k2oND3M$YRllt zp{^xrQl7CAj*}GNg6Usq5yY9Z&-)w!UzbYdWAuCrNj1t;^jM`y#-IPxhAkf-GG1#f za1?WngZ8`~YuBHy@fi>+G!8Ai z2nXJ7VY?thYKVmhm@(p-?)uI?q`#NZPN|}8vDzhsFiOrNmigK5-=&_h!wOscgr0S#3tH;mYB%5 zVSrfm!@7CDG}Hx@6ZS4 zIk7JOV#H?NYqUiQ=hH5oP}yv%|LH)j(y;H zM6$C)${2lnHRe?4;^xP(Xxno5I++V0l*Q5g;5%E#sr?9MAZBxxT8gJXXXf-9yBSle zqj@`39;p`cwQBZ5)HLkp1X|j_ZC{v{^y{TW554bx*OOOll%DU|9p3gLU4K`FhsFI>aIou^NoEzNfSl@F{0s4fybzijQrZd*~Na$17OqM#OPz3f;%O%z2M85y*jFAs`TvY^~h@@}MfW*O$KuntZnLX{fM zcEFZkGRDi0v0p0m6~(GbkagG{)+W1h2w4x{u#NM(t%%MhtgOy@u;;Ybix6bqd~keg zOlF6(8>`^iEN93Kwc%K7uqU={T;VJoe_n!okp%OZ-xwt2nBcNZcVbS?XH2MUjwa^U z&_WlUA54Y>IikH;q(4*vC`5#^pN}+47g$P!DyGiv0Di5!sY9m(ci|Y+^$8}hJ>!b` z9*HamM2>y#ix3V7LkEeV)UqYK+dMT1OOuEwV5pxO16DhZ+QMS|(x8Q675X}mCjhj3 zkae##v6qM`mqCMzA>v%9)oc9ah`WKSxufF`!z-qXyL!3>{St(DF>yJDTpQmY`B73aPSG*6#3N z8nlU+AH_K6GXt6toh@jJr$iWmI^@3?87G0v?)t{PMtxLF{e!Bq`5rEa>Lk&uRFNvc zkkKZ|P9YI6|Maa2)o2VIwlIuOF+>1KI~;LLVIu4_5hD>RP6jJ7X$l##vLh&nEQL8r zHrFkQ6=0?1=U%{QtG4sEN<#BcU`%B;>bA-fX@b_ zYQ{loIu7Rz^ zdNdI8?aFFQV2b8lr>L!=R8?nJiGr8I=0H(Ch2*?pEmk5{Xi}ufdq+!LN%$rj^dY(Y zqMGwg+KD)Hy}dQs6f6G$pV7udUH*=4l^$+XRjC(yH#w+HBA_rDIw%aylPUCF5u96q zO_f3!SOuXL?WlK}HXqt7MZG0tVS1|Ziw&gKFic@3ua4O(hHCl9KjZMO{JUI+4Li?m7MHb3?QK2_y06$Cpl>8VaspF_UEbRb+4pBRB=Ct_Zba ztT8w=pLh?=lC!KcAJega_cQ#z8}+h!Bm^!hujPmDFdxd5#usk@agqxD0zFfewnp+;yK)D9?lNOXI<;b`AT0W zfqBz9IgA-C=tBB6_B1{j>Okg zqPTS3D6fZHMhDQkD+r2quoZBveJ{6TP+3ofgp8J7y7Bj)Mv zp|D;tdN&2xq%KsWpiZLD_}Wp6IK}OqB1+?B3$xq+i`*T8ZHpS{DiMk)xiu)iBn!zm zy-%m*BSlH!aZ*(6`CQwp0}IVpOwV}P0#Fhl!Q6rG+=pW>RNUiLrOqu~oP^)3&+K}P z;#XCqe68F1E$aH$W_$_{jGd3Lk=`QrD{7C!EPl20%91q6cP#x;jp;p;28zKJ*c2>O zE-louTpu3_+a!Uy=qj()^eb9#h&@C;=Lj>E_&V8^F~?7Y=&01CC;QH~Z=tGeqtUT0 z?WBjRl?|Qmt#Ec0g(8v_468;{Zv@v|36IXdV_JxbZKB6GPi8z#B2w0C8q?U8GlfG} zDuxgbzamT+iuN#!(7gzofe9ibogS_}M^W^XOphIeO1IwAehS1J7?mcgsMBG-08<>P zQi&DgKJFNLXty5`MPv=rAK{c4>rR%a#40HEiag?u<8_uCq$s@|^5^K2J5UaBZk=#X z$3l;7V$9&9#?`pnsxnsyGrfDOZK@G^_LThjH2lgI75iC$KL}Ku+IZd4*$+roR)3`M zKsdpLZ($*Gz9!sj!r0xF9(GpiA)=>-|5!yv_w9QqPbOVYa8PKyyk`t#KI12 z>3Yx(PxC-5YrzB&z%l^cmX7w6CPii;a%hTsl%gILqyIdO+`>}0J?df>YnfV#X_cVj zXfgU`e~4Zq&WB!7lN|Lwv0>%Y6^F#DAMRFJ`l{}1&qx4taVb5LW;0kvee7d*cehZq z?Nr^835Z<%@Iw8GiFSoBnnH>gnN36U)S%^>&Yq(C{*0mI?>IEW0VR3@&zQwLMVNO% z8!1O;FXDQ}Z_AG5kjUBRhT+T>RHC?*PE)9)pi4y4Dzuls18;6ghuS+8!dVJ=^LI@9 z2G-Mau>p@PR_{+frnzM0Pn9TS>Wi;|zu?arR>Msp&TB z=uw`0z~-}(4-n>*Gfv)__Fz6nZDuuCZgh&@XO?B*Z0)~Zm8g)=GXDDRxjl9&l~5AtdsIR&Fu zl)&zx1^c=~-O^#2Qn=|7nuS$3b3S;C+q zYwEmCvRMDhOQ7qViERj>DO@`;_{0LcG4flu2*rKdC%O9rsP>gnIM6a(Y8mYxi7De+ zTbE};Lf_hO;p*1I#{QLAw5sfi*$Nnc0~tvC19$uW&z{XUFCU0vGKbjR=Z z*zDM9YsOdav~FB)PWf7YPt6)9}xhyI+|L z$g?=giZ2Mr+{2fKQ7f4}Rd)xk!}AP@RP&?RWlRKm_bko~ZAeK4)m8Fdh|ZH3AYT|6 zUL)02Y@5GK8qRBMF(@ZaoGpLX?MBcsb_G52s`fP~=82HLokFucZ8vnSt0*0P8l0te zzM7#(N+!J|wqG^<@nf|`FQv%Z78O}G=c)F#f_39qY&rAhF` z#u8b-W|^0A3!Qvca)Z*}WE13aphkcU*Q}f4tY5ho5(W%%cKXx*C|#yT;!$o@(;|WX z`dPIkw?k1@F(F;dl~bKXLp4p*vtg2DHbEl8;V<~*4#fUI#;qyyz7dKJUN6Gl)F5BM zbdgzu9+Ue{>M>h3ddFa&+<@~;0tEKGm`(ep0 zZh3!t)XzV;RPy+v8Y$F4WyW_Ozh}$FBeibg=(H=2=;M1n_^C%>>r36;DZ)A|{;G82 zSkb1?#ED$?R4qzdyKC*AyhM=z?CM?G`-HnKjuV;}DR8}pst|zr8^NPrw-!GFe4g5$ zba265T(gl>>V8aIQ{cZhxxt~^EG435`OyN-vOLyp{J>0^aemfIPys@VL+jI*H#sWC z5}nnco7Scc5-{KTx`V+XIUE{N3IB_U3s@c`b*V=y>v1u8M+NahqjL`2;y|X_wXa_u z+^Gh2W)7Rc?TWxi{th9 z))ap7*(NE@RA0~P#9LJd8RZ3e;h8yvt%1^( zE(pKv)7zvIELTi2z>Vwj&ONktv#XBl3O@>)nlcWx8rp1Rvl_Nqc)vs}7GK+T!kl0c zKjHDn7NPcwQf;yjST#>&7g@Llv;?{l9Q2MF3MjSc2_r)^0E8;>a0sH*5I=Bj1`8v} z-UK3zKY5hccM?m`c~(ySyybH&o0Eb8&FtE1p&icvXSwb|voK*;M#HLN=73cl@0Y{W zS@1gndaTb5nsX&&S&Uj(;g{^sAA(?vB!mHi!wMnt8YC`5fj3N7L`jL@n*FK4@6$nJ zCm7^M;#z&7;CyBW(81)m$&pVXY+E88i~|hO&ya8p2C%9a?&T^8zelWr?8RFX*Mu2i zv^>;mrRF2+pKdJH76VtETMQAdkuhazolSh@p}kPiLom&+cdHrQNP<``Z`SFK^qU8i z3lF#Pde}N?ai@Ne8$71`OWL%vrkO{bgdSjwz!flRJ4h1s`%{xz!bi7+4pyWQmYF@T ztIwx@*9|5_L=LDGcqrzj!%hy#?+5>mEE!UW8q$qNwVW$EuTC{P+(85NLY+M&TvIsDxJNQrUx01+my3C zyRqpM<)9fVf&4PoYQrnZ>xxq09$sG1p@>_1^G{Lbf$pK!@0a-p@OQFK%c$J%6QQRF zIt6Ou1T6dJUdJzL6Gljnz%Tx0KfWwe-D;92!3o`D#@c`zXiPX{YSqV5 zFzRu&+$Cs?URQgMaZeO4e63)Dt%hnezG_{Tfe&BSnB;%jxyd`X<+TqFe%08x`GEd~ zw51&Z*Yj!m_q27YH-GyaUEAP$;`i;x>E|mi5+dM-i~w+d{@ojweaxFr60V}Dx1W6I zQYYLM&-<>_4)J8rFPFP166hTJfddXlGF?Jert6^v6v>rkhf;J)FH~*a%U7T*@Ell9 zvxH~dNY)O4TCJ?^da~n@igdQHR;Fx!lFnr9``lETgW5#CiS7vhn31E>udA`#+C|l{ zboE95^dgpnAFEq*LRXD7O+YJ4O5h?y+?d{@{Fy!}&7 zg3J64ag=rlb!E=AFt^1^Zc5Kzo)Dk`_Ll|C*nT1m_9DU+6_<7Kg4X zKmB>UoijDCccJqFgE*>^JR#Wn>?ue<+$X3uK9W?S_m-x+hzU%Ou zIx^_(8n7elr_`+eA+ZD_iqq@(Q;|Z~B;+};?{}9_DJ69mHqgEChrHEX-y%%QI051d z)3QrpSlA{lLEJmcpm966T95Z+E>w&vk+i^$uWlfxLq_lM0^aLImhGae8!qO~QTIPdV=juxK zh-*C8ep#=NU_CQn&E=mVuHwS;TjH(4NI*{hq0HMbvtp!mH^-h_HF6ss_nZ>#g6V({ zF3ocY#7n|w)izA+ei)%`@eC<#aQ4D+rH+!&jFQlvK~=hZ@R@~^8qlOXMNKGbuE5zA zxqhCdO1ikgNw^Y@UOxw?Q*d7<_{b{xrl|80hE-(Q0GxJi0lhkW=%_BC{y~(WpaPK5 z?A5*UOeLH*P^h=KS~O3}(jK%Nh>Vz|Bp$P#_zOB`e3Ii`W7CIb%=uY`?2QDie=I=rg7 z)o}N^LQyYOn8Mt9aExg&OmC>@}4itt3PAiQb6rOHj z!byu{fAqKbQanl{tr5Vm467|vF}=!x(ZZ_x zWEcgA8E*v1zzZ|-PIk?y8hH6LNTNdh_6!WU~fk@u~x z5*r*of~#g+M=Ay1kvAOf1?Sx3hVDc6HEV99!EMAG*WPuzUZ{S40FPY=(Ws^GeT#uT z3hSOcAzx${Fv4>v6*!RK+P2zr%@_n99A?99NN`&Xgw_n(MR2Q@0cwlj{v!dtvop1o z0xXLwDi7O<3g(FVfra4#85l)Y8T>fvqhyq1ekC$rh2)@Ht^>OJ-Y@lnMDv_Y`^y{n z_{`wTrebhhT#9CK66w`qye*>#j!{7NkpE5S8&n1d&Q`lU;O0K+cAElquCWzj0uTQyT5G2U$wZ9ZwXYZ zh=J?N8q^ymO=-O1&KqG3CT0}K5Xj3_Z?%0b#Vg!bT1~))5*E&POK1qdpi3q9qL+l2)PWlUxCNmF<(g!-V@} z$G0j5D2LKgso7aGK~w{1MxokBIDaLff|-woYNr{_$AFZEo_Nq$#!_Z*%*0Q4axT;j zYW$R8bp>?{hQphq9Pa(k%i6D20{(-3A`XZ@Ac*b;$9<3+N6gN;)TyjT`MieRWXH_J zAb&Mc@r{n`{@ACH0$b6NsagSu{_^yo27icKuIF(qdLCgB{sdJ93qCFwFJWm&I5tGY zTM{InRV+ewtga1@A#zD9NXKfzG#P2ljM2NNZLw4uR0hX2fmCe$R<_(A0zq1bOpB01 zn$>Riz*pWp1ozAknPHaxOu6g%vXT|Z!!qM{g;C_9@{!&KFAfJM@S&M`^spYpln^Av znkj4z;%#{r+f>HUk`UJe{Eb)~{2}Gt!qbj1)~mBx>th{!ybzJ`Pc|t$)_QT@h2FR> zZARFA5217+AIVk3@%Qg}-hKnp@YpD`P9CmAk%>^}OlbrXa(VNtE~dl@hFVu0Ask8A zd$f|UM42jaoEqB0Rt!XJ6hL?8UUniNOaEYJwRkn2T_DWH##XFZc9G7f0;&H>qwXb!uw`vfD5i;giSDK3$dJa z6rL+_Qwu+!;t(M30=AU^>SD2b2D=h!G-hxu7bn!FfEL>@(_+Yuk|z^@f0iRxvO>~J zWYZ&j-vRIX^;|zG;z?b&zo@%V#MLAw8y$eO3w((epw;7e3H zh~#EUgTvnU&*{cs=3$*!pFHBJZ2QYWdL=%65zoh2I;<0JSdN?sMJ!g+NPh-*^M#gd zrJ05^S%>Jzm}%Ar!<;bncOiCwrYUnn4DhPoIBnwrl#yJ?j3jSq0f$ad8QTO=61Sf( z@(|Y`lNQdqACK$;#(XGXoEC^EW^tXb$#s^SjM>eM9gN^C@Y&CEkGs319y%^Ra-%Cn z@_4H6pu~iCT)0XKTCmo3Yar}qc4`raObh*)GbQc@)2MS3`w3O#RP7ZPqkbF1VBs8FPy_Htn(eQdHT;ex?K;%sJ zWkd)Y%x@~;Nex*lBygQZDvH68pO(wJ0o865VfqWrLO>&&u*YNPK@JW#f)f{=LVw5kB6#3LMWCP~)+(5#+RI82Y3VxbRF*L)_~lcDtPuNghPwvDxg0Ru{^cqw$I+VHybZ5!jve1obw%RqA9e9YbV(y zWpGWHY%Ofmk|_Y)w7vTo$g>yBvz@=#OEr^D$=MNipbF3?a>-(WrkJy36Ij~v>iwJe z{as&gx8w)wX=(oW+4t1Q(}A_?;qLx7-(m>C{DIr)M}yXkfB`J9Hf`-&QSr^w?i>;K z!goU4C-gc#=lV0tR(E)?!@YA(Nnd3Cm~fu_8a%nQO+@P-Plr_;FOC{PRP}&X7voz2 zq&LKTZ8p;cScM_bHfc<;-q61#rk=z#meM(B~+p5w{+j~PYTJThC%EApiAHEu|DK>v?=c^%pX4GG2qdYPXaFJ%0}RHt{amjw=E>{*)&ImGno>P>kT{Rj7jz6kOlBvRu%tjua^^3|6z!s~<)q0;zV zLSRXpUS4;dT8I(C_$hs5Ku0w^Nom`VtL7%LBoOjNq`2#`3&IWEG;2u4WtEor{@tb* zGkG4WRpBq)8)k-rlA#xwe8Stpk0`=kdi-tku7|3_nl?V{D;DXl9V2*}VN?F@@?jfD zRk+0JUycrS_Du{y!mQ1RP-bvfi6=jK;q%$=KE*6CzH`x;wah5RU zBHJu`6f{gYyQfggcQ?XuI3}1pWljyIJk9m~SeQ6jTk3&06C6`&i_x_>4!9FGVY?^r z$r&(abLS-btWV1Rh>5d12Ubj2M%I3%?!}I}LaJ3386TDqDjuy#Tff=Yjuf_0S`oC8 z^>1*^ijk~5la!%}BB*R12dQk)Qz*1}nETC&MKX^LG_ov|9aBnaQF@|HE79j+^5}$o zLMSxzyS8Ckqn-u|cIXn%`4L)2993ajG^V-wPzF4^WuUOrRwU0pV{H?rL`Yu)?N9NV5v z#uEC#^}7Kgm?H7#ERJaLntblz`|TYrD&x~zKAQK8;6Fq?G9UXj#yNjnn#eNJEGyql zf^TSIUd2Bi^be49NR?f-uCbWVO$53xDn?QdKxjXFcw23$DRQ+*kBh`%1WWIJkr`8* z|8Coj@~&{q~DT; z2u{;q_WR(l<$7aPG!=zy33oF;d?a5Z^O)vsLDA@(p^-ka27NGlyYQ#I5_vFDmLYH2%ySU7OrieB$S< zAqF)TSQJ!LNgXxyZ5#{f^38AFXJp}6=Hq&$?PyokJ&PmRavwBVnvQ3|IREB@v|0b~ zK{oB>BWcFAr%Z1!*6*me+h=TjMtEbZPjKbKpD%4LHu}MsHhX&LRo`y*xZG-NPkrxK z<9J(hV^-6r!9ZI;xfTlc=jvLJ(l7 zDtY_CG}>(xf!lyq$c&-FAhHKn5B%yt!VxqU=MD%%P$-rkN+(O-aByY|Op~aIJa{-= zUD12Q)&9QxZ>3ABy(EfxuRW_wYpZIr_%+;POrZGiTBFM@Da~^4Nb`|DKAAoa5zhU0TJiZO>gZR<`DNl{e@ zixIUGVKfW56a)r;h8#kYl#&;k^3T2*Xvv;RE4RwO2U0l1-gFiisy4%MsF8RWAT81I z0e#D^)`F1mw1`NNBC@M^r{$Tj&Fk8SLra_O-ZwpztZjezCjM+M(>zhn^`T$pS7I-1 zBoi|!xYN?y;OYP7dO8~uBYOs{yr{n8RAg{d&9VCWtwZ2i6iWUN0j~I8k58^=4H!y0 z+|k9nc#&_^b+kq-1`7ZPnc(Q9j<&qD=^UNbP4F*kYW^oaXuWk_@ZX84?qO9F^8XwZ z()gc2p}WiEQ0N~mp?`-$A4&fYpisLuvsNdo@87M^9n+xqYrOs!R%rIWTA_bY6k7IQ zib4d!e-?%QTP`Fo3ei{m{rS5nWd3hOq5l;Z!sN1%|5gZiOD~ zD!;M0TyBMCQ~y_1=+u_~_o2|E+W#9U^dBvuN00tXOX&ZHLf&n)qs64)rs&bOx@*VC z31d~>?e#Y*9d^8VINE;t)=3H%t>e?tFmcMO*eqtOqw)4>n$iCR3XRA^LjM&CJt`kj1BJZd;je4luQ3c1&>1?}Kd{H(VZDZsJUvrnsBlD)qvju} zZUw7bjalQvC<5i=u(qy~B4v4kinfzy@+Y2xX-7;pMxCEx0}x@!^Q11rMaEXtHgy6* z)!ATO6qKDWO>=*T&=Gr_yF}!C9fUOQB!7J!&w}@MyRzc{%m|4}DMZk;Ht)hokygdm z)sDkD?gUZ(fWxFn7~D4fF$EO7jN02vkP55{k?GPu5Jp%E06x@^m%S%IAQf~JRZ{ee zm^GATPDEMJ1{`VJ46ZbU+yZBL(XxAK4yY3OA``~Z_s)`&l=Ycj*I=9QU!GHxZDlN& zmfkqU#Z{SZoWfLaG%Vitj2?aTt4opg;dS6zTI?E7{P^UAKOR-(@?m$_arjhC14Tsf zq2<9{GBreMmQsV`Zjtw6>%GkGy=t-#VLmZiLTKzfW)Az3B;Fg@B3Dc3eU7hBFybRw zF1BcS!6?O&N2ytRcLxWmc5b08M#S z6tzx0<_jD-H|aI$vF5$4PcsszsfRDD>&>%~nZOFGoL7d{MHVg% zw_4Wu_4wM#=fE}Z6iJJ)I%HGe+Q4621#Lh^XE)l zfK9)dc#6<=-tezek72t(-k<#KZ0kKls%?1DV&DWWuFR|eL2*>Lx8clH;>wW~nx?6hnwpiBHm$3xsH=UI z?+?8{=X<{2pT7S9KX7=R^E@w}x5wS_+*lI`^DAG2X6{(O&dXAxsQzG;u-|HoYf0Au z;HQ0AZ_h~6J=weEuWn&?dhrV!*U!uSmXnbe7hmXOw|=~Dw>{r(5As>wlw)EFF%;Q|k zTaKzV)(N$bW4Isci?uE<#C#F0&6bV%sILAuk|` zKd_c!D0Ff?U$2eMl@GxqQ%P+rr-IQb5$Y8N+76mg#f9~bbaDIvEE}i7vGSj&eYTxe zVD=ugipwW6MkB;?JOM{6`|cQkoeo9&KoK2VEHe~)sb>!VTYh5X%lk9TO90*VJyYN z4qL|4)R0?bslDhwXn3Z>(M`ugiAI9=iC>F;r4jH!EB8$!Ldnq>5G6WRlU`JG?Clv+O6j;6)yax`(NV6Q6s zM6C^`96b`ck~l$XrGwtOl7>V1K)k+yOI-)`B!_c%9SA86qXAKw9KGNnK=APU`5x;x z<4MzxAXBIAit9mfG`|hdM4&gwi1PlMFD2srlir=DDA2S6AA`pZe*(FS^fbscAja{V zMqL$4ixw&I+$<7XU6&)XED9+M>CLhv9ngq62=qv3LaWf?WQQs1A8Rr%W2zFrXm3Oy z^eRxH^cz@T%2n+!pyb|P5m3qE{P_$PI-TTX1zkFzy63y=)v3#&5t{+sf09H!Lc2N(DnqPS&Jn{J7t0;aZNQTmLbXV7-jU8!2p6wu6hE04} z;ihDQIpng1W!q#mmxS{Ux&;TF-DbZ;I@3{*7HNB#tqSh1u1nT$rjShC-@0G{sP;vl66u`W!f>mDS$y z4MJ!?UhIuCkRgy@rh?5KE45&`?QT+%0jUBV0vH^ebBB6{HHjbg#E2j9Flf-SS{F@G zEyDj!gLab`3OSuUO&5kSzDQarCCDuc5$v}h8UHO7yd#kpmTfPU-@sBZFAfaIjFOZ; zPa+f?kCI1)Aq^M4Kw4-|J^+1dFtiicCIJZjVzt-e<_)cwNTjwKA002|nIV*jvF9~^ zGtV^cPN827qx_5g0!FBR#pYWeUZlggO43&!1-P>|yxRZpL-W?*I zgjmZVPi%ZBKC^vu;?{vDpN603|NT4+Y8>+nd)JAq^8Ju>upshtFnMxW)+cvba~-kk z!g$h;&^TO^_f+!DL(6Jm!fEQDmilSqs`l09K>p@p{6 zvbMH^J!y#+TcIRDXtkNN7(3)@LXR-uy?hjl7^;JZCiAGr7|6&NpoTDEKgFh87pWv~r zw*g8DqE1Xly^M{(EI{vnfjw1&MG+-}bECZYi83NKcr9ba80@eRn*)6OHIKnM!>#y$uKru!b-_8{0n{0EZ#04N=w zn3(uKP$+4E25^N^iLmA7q6QH{fJUBJ2>wuope;bWgeiUTgi<{sAAtIAvW5^Fw9taEgj68-HeD$*yxEn2Rzi-eNZ19HF^O$gv$dLqZ%lu z1z(-_9E?;t>NN4WMqmLvOkqq8M%{8KmlZ({Q=B?P$A3;?luaPu6@+72Ou_#uA%Vn7 zs>C5WEOmn>`6I&@0N%w1&)tN9x6`YcFM)%yDPG^uBMXS-uZhf7i7tevN-sn~kaGme zrsK{mKZgRD?luz(yVSJ{4z)N@+EczhI)MG)=mNkGF+-> zpnfEn)(AS4+5jm}IIwWKs2tiXDt~LyL|8oV1(rAX*+yL$e^Pj=hcDr~05x!`*`-pv z>?h%_l3;0>Ucm<%1X6hc*%Pg9M%p!XX=nm28JwQ~s|_*2M>2@WLW)E*4f^%+#J;cjE{h7a!BS#x&N{;Bw5H#GlMozZK^XR+9gm)=o4TLG!eiW zmV*Ut94>p1xV;=Lv3aXTY$}?0AQd4{_E=%1=y(qr^-xOSD zMSOryt2whae=uQG2<<3``-#)m zA%7sxRV`pTBTL)>T5g6rYyQDOguEh8Q8tlLbak2vb`m2Ss3|o`h5>KDqvmyJJ#-Wo z5Ui$+CNY2{5+=kAt2`hPgz%?{GGgeclgBYbLa~p6KK+Mht{@+2;*J#KAR3Gxcs@_Q zvG2{{uP#8g2$3D!CiX#o@wqlc&JA4`#YCtcP}C-SW%tH;tn_}&HlS@K8sdwG;U1xXyV~qu0F!834a1?( z+4!M$u#y1ckcjD{qz2&m62)gXspx)EavbjzMLOgJDn!*0xJtI!C-yTSL0BhH-?-`d+q+6%qlf7!t1$c(mFk*ZQ;Un$d*K(zdj*P&2W+{w+ z`i{<+qz3Vjk5QN%zcAbdNH!pGS_8_$k4UP7E~|l$(-6t6rKuYbec@%e3Mw}j_OrHm z3p@#CA}utL;rxi}5751QSTf!-c_D8k_5I z1fj%YdEp4UDo}*@ts}F2*aWz1(=G$huTO(N4n-aVz#vYrUB{3P&#&w?4DZ~4l42@V zRVJC7IIWDNTQ}od011nVs35#x8A~HeJ6G0959&Z^8^^qbry#|w;{3z{I%-H%)*`~} zTgUve0w%*J)O-*)y0tqcPEK^_m`TJ@V#=g5CF!^eSBS6>*~Fk^VuofFKL(x`K<8wI zTHUBlz61w-f_33+JpwtVc55$FLYY)g3cjuhWV=YxGjU`qg+DUr5c)19-&VQ9c;3~< z3GXS(gO_s>qXmfWed(Q)RQ0ht(POO~C$KLa_5(?_72fRjKwNs@VwL5w_E(OxLxzm7 ze)--u=yg)ZVgYQu!tUKVMwtzwkwT2{ca0YR_@MhmmqziS3JdqTCIUOqQBNHtJgm`) zL})b;d$n$VbRaNt;g1jcD}G$k&ULqv{3Qz@T-%|B2$gxYZ1@<{D$4d0_A^bebH?V_AQjd+s*23xSASnAxsdSS9}^x%^Pw<$x2d^z;?UZekx4#N;4ChVEy3Hck3b zz3_Y=Iw7n z(!UDQ`-kQt9LkwckdMcz@}exDQc!3yN4lL`aD$D=MVm|xl;*%XO*%h1hIq$(sUi3eNEw^hBQf217MCqP8=!^h2g zsc`6J*tMX;FBBW?#~0z1n@o$w)8hZozyB@%sszbez-`$v_x^Gx=Rl-IY%9nds45_K zY#ci?7@5POwKRAf^=_HmSpoXKN(LW{>i&6W2 z+g$%w<2KZs}{AyRFC;Rg64P-K!YWaS<#gb%Cbtke)Eq+4=Pwi_L1 zFq2o&p|uw??!01FU%ol?`s5CW9Qs9rg zCIm0ZEHApDzjdXb)P_w20edH(FGZ|Mf1KWFxL^}%qe3cplmy{wz;5~@M$o82A=q>S zTCPw|TY!oeM8!7fx<1~1H}LE9HX~UC?WneuP?_-OkAdvqPfHC}_2VZHFD z*bMUnmt)&b(jl+v7kq$;oMWG39zMId;@7d|2aFNC1SDTir^2H2(ErJF$!8!gv70izUQ~UC=?l`I+Jz7b5yOsMjX8pPJW(^S!tKAV|@fEaD2achi zQaKu@+_;AH^5=K)rE0F#0#%{&71sA02oWOS`u-JoDg5fGlTMK=PFJ+-N}1|q5TVF5 z#Y>Q3}RlMQE|5`Xev;Oj-6HYH^fz9)g|k?dgC?u1wDL2w}46w z%-%iN?KIz)l3Jl!m6F{&^}ixkFNUAi_~%tQQi@a-cN>b7-c9i9LtU?I@-aahbtqtt<26Uq@tsz{TtO45a`8<(vg!*bth+It))Xv@{7UVdbibe zrNjEd{&Q-3^ro=a@zN)wzE-SBCmLCRrQz=MPOJWPq~(?BWP<%_cMXHRCqfZ~cA7^Q z6zJFRn#52Dk=Pv+@xw#w;vM(9IV^SU7@eLh{C}a4PnS$%EnwtajGdz%vW~>$e}lb~ zZqd|T{veA-87(0&_i7j*>(B65308@)7q98_sgbY#*76MBts$o0Q}QTFq$U}fux$sb zXyG-TH9SASo3QJ3 z?bKUzk~3kuMa$VfdROUbQWEBWpSUO8{M9HiyHQZ2b8QW2Vs2PnrVzR9q%Vd-J~;)1 z1zziPS$OE^bZ86lyL-xBAHTS+D{epcQQs4GR(DmVuHP#dRQtZu_ zw7qcbBX?chrl`7i)+S#RvupV*w}^~)V2uk2&HN{VZvLYloeQXM_qU-=1$9Xmc;`Cz zYc(|6#01Sp=n58^ij0@2YT{ArACR*BXKyUz$fV%AK#ud@oA{b-3HG=2mNsH!Y6&hQ zx0Up^R4Tk>I&yZXov58iXOZzi5-hxa1i;V;$r1r&8aCLP+vr}HiMZzzJj{|Us<77c zVW2+DE{%mSt`i(1@iI8DT#HBnnPzwN#(2(~l>67TuD*j5s?A9G0ziAE_6DU08Ucl` zuQUCp)kcP=^rDWEv}fX_4)C#3la*rx`lb|38!X#S2eSs4*+Iny!iz%P=a9`ypLKKQ9mx$f;*MuLaeowBa4?eMd}NkHc?t5MO5k2pYPN_=iZd3i9U zjaVZ){1_;!)dRYm4okvnh>WFKq$T zQJC-ATV=0M64me5>Xi>IMiX~^E!a&5q&9*k4J&_)#DRFay*?aIvO4OxC#@7W!jZki z(<`%fH|^n)&A-H&dXpQW#*FbE^{E?(?v(nSf0L7lDp1VTr6BOgYo}T9=JrBsHFoCi zUJ0FkO7<&bl`}HZwqOYNa+*4!59_Yi$IXvrOZja;A}a8pvQv)7c-jB}l_~9vW&lb> zT=j52Nb*IW{VI64Qn+QnS@T(^2Kt0VhM>mVLq*DSDO@+?D5LRhlPpxo(S`H;yTU)y zN}@og+AV_^n`{j|0>{9yciW|Ko`no6`yyY~ce>jRI__T3 zRJQ?C8fz-AMr(yPB~mAKR!5EcI}24`w$G;@tM?u4ioPaJic03~^dmaZ+~;bx8cZ)H zhIh|9FXBxP2Q_|8@6f)q4B1Ow+yVUv+F$ywEcwr@CRyktKCNB8`3@Zuiqo<{gYxWg zXRkKfq2MYq+s4`{_|ufYtn^kS>b$OYqfTZ(N z&yDgx*ldg2=XJy2<|GN7q$s3f>4&=Ub-|%mlXrjHaW1fbz4nev2Kf@-!}sid1++?n z9*OKrG-~y5JH6zS!E3Vfqp&H)o{PnblU+t`v4_h?mx3%f¨k!z_aNFW=6G#yxJ? z-Vp=8czN*BHE|}Hs*bwyF0wsae<>w-t2a5zX?GKmEyq=TFejOV%BV%v4z$nL+deQ? zn_$LmyS#NV?|3|vo*C!l5sC7dGaem(OFVCpb?tT8F@Vwv%+p;sclA_y?RrR}S!^e0 zRWcLMUu#L2^r}a^zB_QGi5*mLWuHm1)3}MRwD&$X@~rjq)46mPz+~I{BVmy888&>{Bd>iD`zr zX+rc~ukIWB1Q`b#U2x3$@*I)wxfxtt-tW8QP8!ek9w&H#)m**bcahY? z7~Q=9+U-{FD1uPUp-JNvLB)XWe<}<8#>tCdJ42A>El%wy>ul5hQGib4=(d;)0bU&f zbcgP6AzX2c5(G6eRvs1TxKB`2a)|TBR0i_%(!L&a*H#J#^nLIpV^m4lhrs9P5u5u) z#%zX1W-3LKs- zORCB$;O^srNC0KL0Dz%Nx%Y8Hg?*DgM&jSaQ(Oge2GF4B_8-3+-QOz@KCoy_+t~}a z^w4#RI8nIcUm|1y$`@ybs4kJ}@;Xa$)(bc7-@)x1=cwAP%wdQZ30$blecLtnLg>7c zpMze9w`z-%ub0D9bNwm1ao}-Yq+lw?+Fnq>S((PsY^`bSx7s+}5cZFgr6k^Gq7VufR za4AZmb^^#g6SLeg^JV>95FISjEVe@I3-Dqi8rXY=&F6zm$u&<+y#97XY&~}?=5{gh zEMEY`p9tNLhx#z~IfCn zrC1HJK2EtI?qZN)M$>#p& zxt$oW5o5>}?LM&X?Iwg&C~!3s=9mnoX2NY|yE-ybx`GE>^6-CWDZ?A*8kpAT3B5nw z@ZSt$)jt{uB60T9yUYckf{@$#fE)`v+kr9U!{dZ*<#Z7_*6Q%&^;P=?wilYCDxO%| zDw0IkjG`g$M_2BXpfWjSp=%H~{l#L)D)=+^9}mRuZg}T5X|7NJ)$0Nq&xpGhmp@7u zuodA%Kn`&?yg7U4;WWwpPExiaaL9a6a5cw^3O1&$vP8GjPj&=sf=#wo4(Q9vrI)PY z7ouJkzDIDpHrO8gd(5gF;|;t0MN>l*inYQH3o#cWgYEf1WjtH23a>Q-v|M0|9Q}E% zC>MlymaEc)f4}slSGUUT^4plbRUD&_4$Utn{W+K2!EVz$kdA;=tHIix@^F;Q;R3*= zX0K$rHh;M*T^QxFaX7V`0b_Q&{)nJcjvlw8#4G%vI(mxs9aVT_b z4I=e&*A-dW>SB%#gEb@qi0eg^D%Q4r71-<|JZhjiX}mx?S-Nlr+PPRU`xvE-D{D)~ z-Clt{Rzd`Cv65|oNO1)wi>Y^!oJUfaXVT9p1db)KQJ3_DOO@W@ zGo;9^EIP=%o)I^RLC{@IXCTuBW@wK&_{1~p`)G!RjMS42LQz?$c8T5_%T_9jIl^^g zbOwz8Hj|5G_}Fh;rg1$0&Ij#n2X4FtQ@=x`BS~I6UY?BXk9gr)WbD>e=+l;vcPL_fUE@lF(IT#g)@F+ifhzH1{P)f|f8X&-_K z+m1whYcK5szF@9xvdF-IWVe}emOLQLNyMgVpGk4P^H&wfOe!Y*=JI`>|2~RlK!PL^ z0B&YpwnB4~ZvkYvbNKw12so2oU+Fl*&PtI@o`2BC1acc<0s;cmKCbRj=gdDxg#=6a zo3lEvNKr2LQ7JivOhsbctMpd|ZfihmVohy1xSes?f|Bz&^1|pUSzAAJFCJSI7)92+|?4V`oF&1&@_+6EtvG{&oH?$yJ{J@ z@9ULYAcAk-!KFu>+a<&WkUnozj{q@SU^|fx-!ePr1=ubo2w5InPHhd#bmKzM@Z&uU zwa3Q+ATfj+o|O)rms=ss2;*J|*j%v^O5oYgD~bo%j;gzqPgU&6Y>s~*=h^*FWI=o( z@lKug6}dfJDMk*9TxV=%l~3OpU@BMe>D4|VOOIr-PkTvciDj~O$Z_y&4fUMqe~A#p z4t%eg;}#!kcN5jJ#E}r6r<)uGpG}OSfdu1sMHIH2h+%7$zi!FWCYD?(IXn(SG6c)aB~O9 zG@&+Z3(`*8bw2Zsdb+I=OWl}Jxm1l(EdCX{B536&9 z1CfEq+_fRlS@p67$cKDF!d#%KcAM^JCe2-^`meJC#|da(Q=1Z%lOW6{D0hY7li=9% zEc$M+B7|n3ALJs9GJNBE@qCW~@hJ)~1jxQ5U0V`yfw#=K={~7B+F}`G9;zdVx`yBB zzxA4#nPY20-A*_GhA_>nNaFj5^N1OsF)oM2XX<8t)np_fw&F#W&k?u;X!$`FK(@(H z(HH=&pGJv&(D9aUH~PNOJRamd^sAnfG2a4t@jxBfmV=qR{(4aOB;0bQ*2BWNdq!rQ zlvBny+aE4&X1+hQB0fQ(o)0jbM6+tHe~S#b@YBdPIrz=s1}77X!BO~toSY&!ng{Xu@MN+;>E{Tp zgNA8r6OG?A&U!@IR<3Z|%$?=U&XV=4;4#rRy8Be`30vQ0;Ml ztDq*%JlvSb+4|}4Tu|$9Il=foXL#i1>xByr>R*o9x0YxrHMcdG-Tg;T&HLF!C7RN#5TFrn1Ks4^`~@oL8BK zeHE*cJLURuLh7+=3?BX@0loq>H=9+K9G+Xf*_HP!K-#UWda}M7y<%7s zM^H_hlMQHxIeQQ|0Z=(zrSe4k05UL->|m=|*ivL08{tdkn7Av;*W;&TXpuk&%CM=*2>3_ z5c5hZfk|i(7)rRw(LTAVT7=2CX!Z>}d^(D)NTNHI^BqAEW>kOm*`8$;CxXK;pX}I6 zVLGYq@!{E{Hr`I}nQipcjFumzppHhV?V^I^`8R{@aD2_AzEP*=D^*Ua^NQHoPoplt z^R-T&5waoVO;D%rul6r~vSbo)k8P#z-)Wa$f@YPTuo_`OffeKV`f8yWeaE;r>e0$^ z&tA4){ABsI#i`h8649;|2AO##*|EgNDu*sR%VMI;X;5yN9Y^Lrxjr1K?!C6}X#;z0 zW1x|hF}IvXjpwY$X?)#cT+`2oKkT>^q9Qb$dSZL@_{guLi>Sy!FS)t$2T#_&hB#cS zM97z;`(qU70G5{`FlBMaheJx-An&SETa!I6RNaRTDK(gW!UE4djxeGZOY-M^hMQ*6 z^%k!`{Dq3^OHn**P;zxD?MMcy4E{@Js8SJ!@ok<0~7TYcVjhBhtJW`QDqmJzgpHP&tKySaq0W)0p$dC3T%# z?!#tPIc#&m;%;wMQdJYWRr{Kr?-nP<`nlt3P-zL5pC|uo69VTtmrxfusbkTSx1BLN zEbnk_w(!c$(Kkt$CAwO$JYw=E_k-ET%%V*KefaC%0`O1c%Fio^S@9CtgUJE zCnRL_Pt~80P&2|K-mSl8b+@KzPsi|P_ORRd`3l{QucXVq~>NEUb zYZt%1qtlSm&`=g{eK+6R&k}U}_q+A|z_)jq@B73dq5lho(*JiQ2_Hj*5{t%nZ&VgG zC1FlRLe|X=-7O}P08n$XzW5F~WSJGNVbft?5&{6z%1SOKOaZk!QB3qCULhH>4&OkA z%kZ~lLw1qe3oj!Bg`a`=*h%o(pnsJmpuKUvgGTB^LAsw^2nmIP`m&Z=V;6(#q{St-LQvWYEkC?F>gC|W9QIcr z<918f)ac4;lU}c{RF?s+F<^Lng*G4}gsjZ2hW+@8zul@H2W={3@%0AI;4Y4{-Ta%I zB;|+2w}p04{4z9FJI2rGT#4&K{bhhJ<>AB(2(Ugb1B*p|cL&+)?sY}S4U;alcAu^u n1bp8i9={4d81rZV00i)b-%LrT_UQcoLPCF_P*NiU0I>QW)2;|X diff --git a/docs/modules/slam/graphSLAM_SE2_example.rst b/docs/modules/slam/graph_slam/graphSLAM_SE2_example.rst similarity index 90% rename from docs/modules/slam/graphSLAM_SE2_example.rst rename to docs/modules/slam/graph_slam/graphSLAM_SE2_example.rst index bcc797ba3e..ef5d05bf22 100644 --- a/docs/modules/slam/graphSLAM_SE2_example.rst +++ b/docs/modules/slam/graph_slam/graphSLAM_SE2_example.rst @@ -44,7 +44,7 @@ The Dataset -.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png +.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png Each edge in this dataset is a constraint that compares the measured @@ -122,7 +122,7 @@ dataset and plot them. -.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png +.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png .. code:: ipython3 @@ -131,7 +131,7 @@ dataset and plot them. -.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png +.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png Optimization @@ -165,8 +165,7 @@ different data sources into a single optimization problem. 6 215.8405 -0.000000 -.. figure:: graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif - :alt: Graph_SLAM_optimization.gif +.. figure:: graph_slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif .. code:: ipython3 @@ -174,7 +173,7 @@ different data sources into a single optimization problem. -.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png +.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png .. code:: ipython3 @@ -196,7 +195,7 @@ different data sources into a single optimization problem. -.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png +.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png .. code:: ipython3 @@ -205,5 +204,5 @@ different data sources into a single optimization problem. -.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png +.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png b/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png similarity index 100% rename from docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png rename to docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png b/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png similarity index 100% rename from docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png rename to docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png b/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png similarity index 100% rename from docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png rename to docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png b/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png similarity index 100% rename from docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png rename to docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png b/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png similarity index 100% rename from docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png rename to docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png diff --git a/docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png b/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png similarity index 100% rename from docs/modules/slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png rename to docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png diff --git a/docs/modules/slam/graphSLAM_doc.rst b/docs/modules/slam/graph_slam/graphSLAM_doc.rst similarity index 95% rename from docs/modules/slam/graphSLAM_doc.rst rename to docs/modules/slam/graph_slam/graphSLAM_doc.rst index b17c3b18a2..4367f770c3 100644 --- a/docs/modules/slam/graphSLAM_doc.rst +++ b/docs/modules/slam/graph_slam/graphSLAM_doc.rst @@ -142,7 +142,7 @@ created based on the information of the motion and the observation. -.. image:: graphSLAM_doc_files/graphSLAM_doc_2_0.png +.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png .. parsed-literal:: @@ -157,7 +157,7 @@ created based on the information of the motion and the observation. -.. image:: graphSLAM_doc_files/graphSLAM_doc_2_2.png +.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png In particular, the tasks are split into 2 parts, graph construction, and @@ -289,7 +289,7 @@ robot with 3DoF, namely, :math:`[x, y, \theta]^T` -.. image:: graphSLAM_doc_files/graphSLAM_doc_4_0.png +.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png .. code:: ipython3 @@ -420,7 +420,7 @@ zero since :math:`x_j + d_j cos(\psi_j + \theta_j)` should equal -.. image:: graphSLAM_doc_files/graphSLAM_doc_9_1.png +.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png Since the constraints equations derived before are non-linear, @@ -494,12 +494,9 @@ Similarly, :math:`B = \frac{\partial e_{ij}}{\partial \boldsymbol{x}_j}` -.. image:: graphSLAM_doc_files/graphSLAM_doc_11_1.png - - - -.. image:: graphSLAM_doc_files/graphSLAM_doc_11_2.png +.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png +.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png .. code:: ipython3 @@ -546,11 +543,11 @@ Similarly, :math:`B = \frac{\partial e_{ij}}{\partial \boldsymbol{x}_j}` The references: ^^^^^^^^^^^^^^^ -- http://robots.stanford.edu/papers/thrun.graphslam.pdf +- `The GraphSLAM Algorithm with Applications to Large-Scale Mapping of Urban Structures `_ -- http://ais.informatik.uni-freiburg.de/teaching/ss13/robotics/slides/16-graph-slam.pdf +- `Introduction to Mobile Robotics Graph-Based SLAM `_ -- http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf +- `A Tutorial on Graph-Based SLAM `_ N.B. An additional step is required that uses the estimated path to update the belief regarding the map. diff --git a/docs/modules/slam/graphSLAM_formulation.rst b/docs/modules/slam/graph_slam/graphSLAM_formulation.rst similarity index 97% rename from docs/modules/slam/graphSLAM_formulation.rst rename to docs/modules/slam/graph_slam/graphSLAM_formulation.rst index c673bdcbfb..43f007e7bf 100644 --- a/docs/modules/slam/graphSLAM_formulation.rst +++ b/docs/modules/slam/graph_slam/graphSLAM_formulation.rst @@ -213,4 +213,6 @@ Using this notation, we obtain the optimal update as We apply this update to the poses via :eq:`update` and repeat until convergence. -.. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/ +.. [blanco2010tutorial] Blanco, J.-L.A tutorial onSE(3) transformation parameterization and on-manifold optimization.University of Malaga, Tech. Rep 3(2010) +.. [grisetti2010tutorial] Grisetti, G., Kummerle, R., Stachniss, C., and Burgard, W.A tutorial on graph-based SLAM.IEEE Intelligent Transportation Systems Magazine 2, 4 (2010), 31–43. + diff --git a/docs/modules/slam/graph_slam/graph_slam.rst b/docs/modules/slam/graph_slam/graph_slam.rst new file mode 100644 index 0000000000..a1248a01cc --- /dev/null +++ b/docs/modules/slam/graph_slam/graph_slam.rst @@ -0,0 +1,24 @@ +Graph based SLAM +---------------- + +This is a graph based SLAM example. + +The blue line is ground truth. + +The black line is dead reckoning. + +The red line is the estimated trajectory with Graph based SLAM. + +The black stars are landmarks for graph edge generation. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/GraphBasedSLAM/animation.gif + +.. include:: graph_slam/graphSLAM_doc.rst +.. include:: graph_slam/graphSLAM_formulation.rst +.. include:: graph_slam/graphSLAM_SE2_example.rst + +References: +~~~~~~~~~~~ + +- `A Tutorial on Graph-Based SLAM `_ + diff --git a/docs/modules/slam/iterative_closest_point_matching/iterative_closest_point_matching.rst b/docs/modules/slam/iterative_closest_point_matching/iterative_closest_point_matching.rst new file mode 100644 index 0000000000..a30b1fc99b --- /dev/null +++ b/docs/modules/slam/iterative_closest_point_matching/iterative_closest_point_matching.rst @@ -0,0 +1,16 @@ +.. _iterative-closest-point-(icp)-matching: + +Iterative Closest Point (ICP) Matching +-------------------------------------- + +This is a 2D ICP matching example with singular value decomposition. + +It can calculate a rotation matrix and a translation vector between +points to points. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/iterative_closest_point/animation.gif + +References +~~~~~~~~~~ + +- `Introduction to Mobile Robotics: Iterative Closest Point Algorithm `_ diff --git a/docs/modules/slam/slam_main.rst b/docs/modules/slam/slam_main.rst index 41210fee4e..f4d10feb9a 100644 --- a/docs/modules/slam/slam_main.rst +++ b/docs/modules/slam/slam_main.rst @@ -5,77 +5,9 @@ SLAM Simultaneous Localization and Mapping(SLAM) examples -.. _iterative-closest-point-(icp)-matching: +.. include:: iterative_closest_point_matching/iterative_closest_point_matching.rst +.. include:: ekf_slam/ekf_slam.rst +.. include:: FastSLAM1/FastSLAM1.rst +.. include:: FastSLAM2/FastSLAM2.rst +.. include:: graph_slam/graph_slam.rst -Iterative Closest Point (ICP) Matching --------------------------------------- - -This is a 2D ICP matching example with singular value decomposition. - -It can calculate a rotation matrix and a translation vector between -points to points. - -|3| - -Ref: - -- `Introduction to Mobile Robotics: Iterative Closest Point Algorithm`_ - - -.. include:: ekf_slam.rst - - -.. include:: FastSLAM1.rst - -FastSLAM 2.0 ------------- - -This is a feature based SLAM example using FastSLAM 2.0. - -The animation has the same meanings as one of FastSLAM 1.0. - -|6| - -References -~~~~~~~~~~ - -- `PROBABILISTIC ROBOTICS`_ - -- `SLAM simulations by Tim Bailey`_ - -Graph based SLAM ----------------- - -This is a graph based SLAM example. - -The blue line is ground truth. - -The black line is dead reckoning. - -The red line is the estimated trajectory with Graph based SLAM. - -The black stars are landmarks for graph edge generation. - -|7| - -.. include:: graphSLAM_doc.rst -.. include:: graphSLAM_formulation.rst -.. include:: graphSLAM_SE2_example.rst - -Ref: - -- `A Tutorial on Graph-Based SLAM`_ - -.. _`Introduction to Mobile Robotics: Iterative Closest Point Algorithm`: https://cs.gmu.edu/~kosecka/cs685/cs685-icp.pdf -.. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/ -.. _SLAM simulations by Tim Bailey: http://www-personal.acfr.usyd.edu.au/tbailey/software/slam_simulations.htm -.. _A Tutorial on Graph-Based SLAM: http://www2.informatik.uni-freiburg.de/~stachnis/pdf/grisetti10titsmag.pdf -.. _FastSLAM Lecture: http://ais.informatik.uni-freiburg.de/teaching/ws12/mapping/pdf/slam10-fastslam.pdf - -.. [blanco2010tutorial] Blanco, J.-L.A tutorial onSE(3) transformation parameterization and on-manifold optimization.University of Malaga, Tech. Rep 3(2010) -.. [grisetti2010tutorial] Grisetti, G., Kummerle, R., Stachniss, C., and Burgard, W.A tutorial on graph-based SLAM.IEEE Intelligent Transportation Systems Magazine 2, 4 (2010), 31–43. - -.. |3| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/iterative_closest_point/animation.gif -.. |5| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM1/animation.gif -.. |6| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM2/animation.gif -.. |7| image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/GraphBasedSLAM/animation.gif diff --git a/tests/test_move_to_pose.py b/tests/test_move_to_pose.py index c6a6b8bc76..05cfa269d7 100644 --- a/tests/test_move_to_pose.py +++ b/tests/test_move_to_pose.py @@ -1,5 +1,5 @@ import conftest # Add root path to sys.path -from PathTracking.move_to_pose import move_to_pose as m +from Control.move_to_pose import move_to_pose as m def test_1(): From 4b9d05dde18daaa113a30aaef857265f2c94846b Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 30 Nov 2021 07:18:13 +0900 Subject: [PATCH 429/940] Bump scipy from 1.7.2 to 1.7.3 (#587) Bumps [scipy](https://github.com/scipy/scipy) from 1.7.2 to 1.7.3. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.7.2...v1.7.3) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 84f663cb83..63bdc966cb 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.21.4 -scipy == 1.7.2 +scipy == 1.7.3 pandas == 1.3.4 matplotlib == 3.5.0 cvxpy == 1.1.17 From 2c077225a7728a18152b2cf63fffc329069af989 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 30 Nov 2021 07:18:43 +0900 Subject: [PATCH 430/940] Bump ipython from 7.29.0 to 7.30.0 (#588) Bumps [ipython](https://github.com/ipython/ipython) from 7.29.0 to 7.30.0. - [Release notes](https://github.com/ipython/ipython/releases) - [Commits](https://github.com/ipython/ipython/compare/7.29.0...7.30.0) --- updated-dependencies: - dependency-name: ipython dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 63bdc966cb..2a0135cf44 100644 --- a/requirements.txt +++ b/requirements.txt @@ -7,4 +7,4 @@ pytest == 6.2.5 # For unit test pytest-xdist == 2.4.0 # For unit test sphinx < 4.0 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 7.29.0 # For sphinx documentation +IPython == 7.30.0 # For sphinx documentation From 4d60c3c0b152eca35a6a244819d7d6e7664dfd05 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 1 Dec 2021 23:00:39 +0900 Subject: [PATCH 431/940] update docs (#589) * update docs * update docs --- .../Figure_1.png | Bin .../Figure_2.png | Bin .../path_planning/bezier_path/bezier_path.rst | 20 + .../bspline_path/bspline_path.rst | 14 + .../path_planning/bugplanner/bugplanner.rst | 8 + .../coverage_path/coverage_path.rst | 34 ++ .../cubic_spline/cubic_spline.rst | 13 + .../path_planning/dubins_path/dubins_path.rst | 11 + .../dynamic_window_approach.rst | 9 + .../path_planning/eta3_spline/eta3_spline.rst | 13 + .../frenet_frame_path/frenet_frame_path.rst | 20 + .../grid_base_search/grid_base_search.rst | 93 ++++ .../path_planning/hybridastar/hybridastar.rst | 6 + .../path_planning/lqr_path/lqr_path.rst | 6 + .../lookup_table.png} | Bin .../model_predictive_trajectory_generator.rst | 22 + .../path_planning/path_planning_main.rst | 426 +----------------- .../path_planning/prm_planner/prm_planner.rst | 19 + .../quintic_polynomials_planner.rst | 0 .../reeds_shepp_path/reeds_shepp_path.rst | 17 + docs/modules/path_planning/rrt/rrt.rst | 118 +++++ .../path_planning/{ => rrt}/rrt_star.rst | 3 +- .../rrt_star}/rrt_star_1_0.png | Bin .../rrt_star_reeds_shepp/figure_1.png | Bin .../Figure_1.png | Bin .../Figure_2.png | Bin .../Figure_3.png | Bin .../Figure_4.png | Bin .../Figure_5.png | Bin .../Figure_6.png | Bin .../state_lattice_planner.rst | 33 ++ .../path_planning/vrm_planner/vrm_planner.rst | 17 + 32 files changed, 493 insertions(+), 409 deletions(-) rename docs/modules/path_planning/{bezier_path_planning => bezier_path}/Figure_1.png (100%) rename docs/modules/path_planning/{bezier_path_planning => bezier_path}/Figure_2.png (100%) create mode 100644 docs/modules/path_planning/bezier_path/bezier_path.rst create mode 100644 docs/modules/path_planning/bspline_path/bspline_path.rst create mode 100644 docs/modules/path_planning/bugplanner/bugplanner.rst create mode 100644 docs/modules/path_planning/coverage_path/coverage_path.rst create mode 100644 docs/modules/path_planning/cubic_spline/cubic_spline.rst create mode 100644 docs/modules/path_planning/dubins_path/dubins_path.rst create mode 100644 docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach.rst create mode 100644 docs/modules/path_planning/eta3_spline/eta3_spline.rst create mode 100644 docs/modules/path_planning/frenet_frame_path/frenet_frame_path.rst create mode 100644 docs/modules/path_planning/grid_base_search/grid_base_search.rst create mode 100644 docs/modules/path_planning/hybridastar/hybridastar.rst create mode 100644 docs/modules/path_planning/lqr_path/lqr_path.rst rename docs/modules/path_planning/{model_predictive_trajectry_generator/lookuptable.png => model_predictive_trajectory_generator/lookup_table.png} (100%) create mode 100644 docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator.rst create mode 100644 docs/modules/path_planning/prm_planner/prm_planner.rst rename docs/modules/path_planning/{ => quintic_polynomials_planner}/quintic_polynomials_planner.rst (100%) create mode 100644 docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path.rst create mode 100644 docs/modules/path_planning/rrt/rrt.rst rename docs/modules/path_planning/{ => rrt}/rrt_star.rst (90%) rename docs/modules/path_planning/{rrt_star_files => rrt/rrt_star}/rrt_star_1_0.png (100%) rename docs/modules/path_planning/{ => rrt}/rrt_star_reeds_shepp/figure_1.png (100%) rename docs/modules/path_planning/{state_lattice_pathplanner => state_lattice_planner}/Figure_1.png (100%) rename docs/modules/path_planning/{state_lattice_pathplanner => state_lattice_planner}/Figure_2.png (100%) rename docs/modules/path_planning/{state_lattice_pathplanner => state_lattice_planner}/Figure_3.png (100%) rename docs/modules/path_planning/{state_lattice_pathplanner => state_lattice_planner}/Figure_4.png (100%) rename docs/modules/path_planning/{state_lattice_pathplanner => state_lattice_planner}/Figure_5.png (100%) rename docs/modules/path_planning/{state_lattice_pathplanner => state_lattice_planner}/Figure_6.png (100%) create mode 100644 docs/modules/path_planning/state_lattice_planner/state_lattice_planner.rst create mode 100644 docs/modules/path_planning/vrm_planner/vrm_planner.rst diff --git a/docs/modules/path_planning/bezier_path_planning/Figure_1.png b/docs/modules/path_planning/bezier_path/Figure_1.png similarity index 100% rename from docs/modules/path_planning/bezier_path_planning/Figure_1.png rename to docs/modules/path_planning/bezier_path/Figure_1.png diff --git a/docs/modules/path_planning/bezier_path_planning/Figure_2.png b/docs/modules/path_planning/bezier_path/Figure_2.png similarity index 100% rename from docs/modules/path_planning/bezier_path_planning/Figure_2.png rename to docs/modules/path_planning/bezier_path/Figure_2.png diff --git a/docs/modules/path_planning/bezier_path/bezier_path.rst b/docs/modules/path_planning/bezier_path/bezier_path.rst new file mode 100644 index 0000000000..c630d54345 --- /dev/null +++ b/docs/modules/path_planning/bezier_path/bezier_path.rst @@ -0,0 +1,20 @@ +Bezier path planning +-------------------- + +A sample code of Bezier path planning. + +It is based on 4 control points Beizer path. + +.. image:: Bezier_path/Figure_1.png + +If you change the offset distance from start and end point, + +You can get different Beizer course: + +.. image:: Bezier_path/Figure_2.png + +Ref: + +- `Continuous Curvature Path Generation Based on Bezier Curves for + Autonomous + Vehicles `__ diff --git a/docs/modules/path_planning/bspline_path/bspline_path.rst b/docs/modules/path_planning/bspline_path/bspline_path.rst new file mode 100644 index 0000000000..a8043122fa --- /dev/null +++ b/docs/modules/path_planning/bspline_path/bspline_path.rst @@ -0,0 +1,14 @@ +B-Spline planning +----------------- + +.. image:: bspline_path/Figure_1.png + +This is a path planning with B-Spline curse. + +If you input waypoints, it generates a smooth path with B-Spline curve. + +The final course should be on the first and last waypoints. + +Ref: + +- `B-spline - Wikipedia `__ diff --git a/docs/modules/path_planning/bugplanner/bugplanner.rst b/docs/modules/path_planning/bugplanner/bugplanner.rst new file mode 100644 index 0000000000..72cc46709f --- /dev/null +++ b/docs/modules/path_planning/bugplanner/bugplanner.rst @@ -0,0 +1,8 @@ +Bug planner +----------- + +This is a 2D planning with Bug algorithm. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BugPlanner/animation.gif + +- `ECE452 Bug Algorithms `_ diff --git a/docs/modules/path_planning/coverage_path/coverage_path.rst b/docs/modules/path_planning/coverage_path/coverage_path.rst new file mode 100644 index 0000000000..828342a294 --- /dev/null +++ b/docs/modules/path_planning/coverage_path/coverage_path.rst @@ -0,0 +1,34 @@ +Coverage path planner +--------------------- + +Grid based sweep +~~~~~~~~~~~~~~~~ + +This is a 2D grid based sweep coverage path planner simulation: + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/GridBasedSweepCPP/animation.gif + +Spiral Spanning Tree +~~~~~~~~~~~~~~~~~~~~ + +This is a 2D grid based spiral spanning tree coverage path planner simulation: + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/SpiralSpanningTreeCPP/animation1.gif +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/SpiralSpanningTreeCPP/animation2.gif +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/SpiralSpanningTreeCPP/animation3.gif + +- `Spiral-STC: An On-Line Coverage Algorithm of Grid Environments by a Mobile Robot `_ + + +Wavefront path +~~~~~~~~~~~~~~ + +This is a 2D grid based wavefront coverage path planner simulation: + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation1.gif +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation2.gif +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation3.gif + +- `Planning paths of complete coverage of an unstructured environment by a mobile robot `_ + + diff --git a/docs/modules/path_planning/cubic_spline/cubic_spline.rst b/docs/modules/path_planning/cubic_spline/cubic_spline.rst new file mode 100644 index 0000000000..b1973856e8 --- /dev/null +++ b/docs/modules/path_planning/cubic_spline/cubic_spline.rst @@ -0,0 +1,13 @@ +Cubic spline planning +--------------------- + +A sample code for cubic path planning. + +This code generates a curvature continuous path based on x-y waypoints +with cubic spline. + +Heading angle of each point can be also calculated analytically. + +.. image:: cubic_spline/Figure_1.png +.. image:: cubic_spline/Figure_2.png +.. image:: cubic_spline/Figure_3.png diff --git a/docs/modules/path_planning/dubins_path/dubins_path.rst b/docs/modules/path_planning/dubins_path/dubins_path.rst new file mode 100644 index 0000000000..5e14820f8f --- /dev/null +++ b/docs/modules/path_planning/dubins_path/dubins_path.rst @@ -0,0 +1,11 @@ +Dubins path planning +-------------------- + +A sample code for Dubins path planning. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DubinsPath/animation.gif?raw=True + +Ref: + +- `Dubins path - + Wikipedia `__ diff --git a/docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach.rst b/docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach.rst new file mode 100644 index 0000000000..0ece6e0054 --- /dev/null +++ b/docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach.rst @@ -0,0 +1,9 @@ +Dynamic Window Approach +----------------------- + +This is a 2D navigation sample code with Dynamic Window Approach. + +- `The Dynamic Window Approach to Collision + Avoidance `__ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DynamicWindowApproach/animation.gif diff --git a/docs/modules/path_planning/eta3_spline/eta3_spline.rst b/docs/modules/path_planning/eta3_spline/eta3_spline.rst new file mode 100644 index 0000000000..ffc3cc6451 --- /dev/null +++ b/docs/modules/path_planning/eta3_spline/eta3_spline.rst @@ -0,0 +1,13 @@ +.. _eta^3-spline-path-planning: + +Eta^3 Spline path planning +-------------------------- + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Eta3SplinePath/animation.gif + +This is a path planning with Eta^3 spline. + +Ref: + +- `\\eta^3-Splines for the Smooth Path Generation of Wheeled Mobile + Robots `__ diff --git a/docs/modules/path_planning/frenet_frame_path/frenet_frame_path.rst b/docs/modules/path_planning/frenet_frame_path/frenet_frame_path.rst new file mode 100644 index 0000000000..e9d9041e0e --- /dev/null +++ b/docs/modules/path_planning/frenet_frame_path/frenet_frame_path.rst @@ -0,0 +1,20 @@ +Optimal Trajectory in a Frenet Frame +------------------------------------ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/animation.gif + +This is optimal trajectory generation in a Frenet Frame. + +The cyan line is the target course and black crosses are obstacles. + +The red line is predicted path. + +Ref: + +- `Optimal Trajectory Generation for Dynamic Street Scenarios in a + Frenet + Frame `__ + +- `Optimal trajectory generation for dynamic street scenarios in a + Frenet Frame `__ + diff --git a/docs/modules/path_planning/grid_base_search/grid_base_search.rst b/docs/modules/path_planning/grid_base_search/grid_base_search.rst new file mode 100644 index 0000000000..ac4ea2f6fd --- /dev/null +++ b/docs/modules/path_planning/grid_base_search/grid_base_search.rst @@ -0,0 +1,93 @@ +Grid based search +----------------- + +Breadth First Search +~~~~~~~~~~~~~~~~~~~~ + +This is a 2D grid based path planning with Breadth first search algorithm. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BreadthFirstSearch/animation.gif + +In the animation, cyan points are searched nodes. + +Depth First Search +~~~~~~~~~~~~~~~~~~~~ + +This is a 2D grid based path planning with Depth first search algorithm. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DepthFirstSearch/animation.gif + +In the animation, cyan points are searched nodes. + +Dijkstra algorithm +~~~~~~~~~~~~~~~~~~ + +This is a 2D grid based shortest path planning with Dijkstra's algorithm. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Dijkstra/animation.gif + +In the animation, cyan points are searched nodes. + +.. _a*-algorithm: + +A\* algorithm +~~~~~~~~~~~~~ + +This is a 2D grid based shortest path planning with A star algorithm. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/AStar/animation.gif + +In the animation, cyan points are searched nodes. + +Its heuristic is 2D Euclid distance. + +Bidirectional A\* algorithm +~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +This is a 2D grid based shortest path planning with bidirectional A star algorithm. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BidirectionalAStar/animation.gif + +In the animation, cyan points are searched nodes. + +.. _D*-algorithm: + +D\* algorithm +~~~~~~~~~~~~~ + +This is a 2D grid based shortest path planning with D star algorithm. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DStar/animation.gif + +The animation shows a robot finding its path avoiding an obstacle using the D* search algorithm. + +Ref: + +- `D* search Wikipedia `__ + +D\* lite algorithm +~~~~~~~~~~~~~~~~~~ + +This is a 2D grid based path planning and replanning with D star lite algorithm. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DStarLite/animation.gif + +Ref: + +- `Improved Fast Replanning for Robot Navigation in Unknown Terrain `_ + + +Potential Field algorithm +~~~~~~~~~~~~~~~~~~~~~~~~~ + +This is a 2D grid based path planning with Potential Field algorithm. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/PotentialFieldPlanning/animation.gif + +In the animation, the blue heat map shows potential value on each grid. + +Ref: + +- `Robotic Motion Planning:Potential + Functions `__ + diff --git a/docs/modules/path_planning/hybridastar/hybridastar.rst b/docs/modules/path_planning/hybridastar/hybridastar.rst new file mode 100644 index 0000000000..a9876fa3d4 --- /dev/null +++ b/docs/modules/path_planning/hybridastar/hybridastar.rst @@ -0,0 +1,6 @@ +Hybrid a star +--------------------- + +This is a simple vehicle model based hybrid A\* path planner. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/HybridAStar/animation.gif diff --git a/docs/modules/path_planning/lqr_path/lqr_path.rst b/docs/modules/path_planning/lqr_path/lqr_path.rst new file mode 100644 index 0000000000..788442ff63 --- /dev/null +++ b/docs/modules/path_planning/lqr_path/lqr_path.rst @@ -0,0 +1,6 @@ +LQR based path planning +----------------------- + +A sample code using LQR based path planning for double integrator model. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRPlanner/animation.gif?raw=true diff --git a/docs/modules/path_planning/model_predictive_trajectry_generator/lookuptable.png b/docs/modules/path_planning/model_predictive_trajectory_generator/lookup_table.png similarity index 100% rename from docs/modules/path_planning/model_predictive_trajectry_generator/lookuptable.png rename to docs/modules/path_planning/model_predictive_trajectory_generator/lookup_table.png diff --git a/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator.rst b/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator.rst new file mode 100644 index 0000000000..07a7ee9b59 --- /dev/null +++ b/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator.rst @@ -0,0 +1,22 @@ +Model Predictive Trajectory Generator +------------------------------------- + +This is a path optimization sample on model predictive trajectory +generator. + +This algorithm is used for state lattice planner. + +Path optimization sample +~~~~~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ModelPredictiveTrajectoryGenerator/kn05animation.gif + +Lookup table generation sample +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +.. image:: model_predictive_trajectory_generator/lookup_table.png + +Ref: + +- `Optimal rough terrain trajectory generation for wheeled mobile + robots `__ diff --git a/docs/modules/path_planning/path_planning_main.rst b/docs/modules/path_planning/path_planning_main.rst index 8033e1a875..61f8ea2113 100644 --- a/docs/modules/path_planning/path_planning_main.rst +++ b/docs/modules/path_planning/path_planning_main.rst @@ -3,410 +3,22 @@ Path Planning ============= -Dynamic Window Approach ------------------------ - -This is a 2D navigation sample code with Dynamic Window Approach. - -- `The Dynamic Window Approach to Collision - Avoidance `__ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DynamicWindowApproach/animation.gif - -Grid based search ------------------ - -Dijkstra algorithm -~~~~~~~~~~~~~~~~~~ - -This is a 2D grid based shortest path planning with Dijkstra's -algorithm. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Dijkstra/animation.gif - -In the animation, cyan points are searched nodes. - -.. _a*-algorithm: - -A\* algorithm -~~~~~~~~~~~~~ - -This is a 2D grid based shortest path planning with A star algorithm. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/AStar/animation.gif - -In the animation, cyan points are searched nodes. - -Its heuristic is 2D Euclid distance. - -.. _D*-algorithm: - -D\* algorithm -~~~~~~~~~~~~~ - -This is a 2D grid based shortest path planning with D star algorithm. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DStar/animation.gif - -The animation shows a robot finding its path avoiding an obstacle using the D* search algorithm. - -Ref: - -- `D* search Wikipedia `__ - -Potential Field algorithm -~~~~~~~~~~~~~~~~~~~~~~~~~ - -This is a 2D grid based path planning with Potential Field algorithm. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/PotentialFieldPlanning/animation.gif - -In the animation, the blue heat map shows potential value on each grid. - -Ref: - -- `Robotic Motion Planning:Potential - Functions `__ - -Model Predictive Trajectory Generator -------------------------------------- - -This is a path optimization sample on model predictive trajectory -generator. - -This algorithm is used for state lattice planner. - -Path optimization sample -~~~~~~~~~~~~~~~~~~~~~~~~ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ModelPredictiveTrajectoryGenerator/kn05animation.gif - -Lookup table generation sample -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -.. image:: model_predictive_trajectry_generator/lookuptable.png - -Ref: - -- `Optimal rough terrain trajectory generation for wheeled mobile - robots `__ - - -State Lattice Planning ----------------------- - -This script is a path planning code with state lattice planning. - -This code uses the model predictive trajectory generator to solve -boundary problem. - -Ref: - -- `Optimal rough terrain trajectory generation for wheeled mobile - robots `__ - -- `State Space Sampling of Feasible Motions for High-Performance Mobile - Robot Navigation in Complex - Environments `__ - -Uniform polar sampling -~~~~~~~~~~~~~~~~~~~~~~ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/UniformPolarSampling.gif - -Biased polar sampling -~~~~~~~~~~~~~~~~~~~~~ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/BiasedPolarSampling.gif - -Lane sampling -~~~~~~~~~~~~~ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/LaneSampling.gif - -.. _probabilistic-road-map-(prm)-planning: - -Probabilistic Road-Map (PRM) planning -------------------------------------- - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ProbabilisticRoadMap/animation.gif - -This PRM planner uses Dijkstra method for graph search. - -In the animation, blue points are sampled points, - -Cyan crosses means searched points with Dijkstra method, - -The red line is the final path of PRM. - -Ref: - -- `Probabilistic roadmap - - Wikipedia `__ - -   - -Voronoi Road-Map planning -------------------------- - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/VoronoiRoadMap/animation.gif - -This Voronoi road-map planner uses Dijkstra method for graph search. - -In the animation, blue points are Voronoi points, - -Cyan crosses mean searched points with Dijkstra method, - -The red line is the final path of Vornoi Road-Map. - -Ref: - -- `Robotic Motion - Planning `__ - -.. _rapidly-exploring-random-trees-(rrt): - -Rapidly-Exploring Random Trees (RRT) ------------------------------------- - -Basic RRT -~~~~~~~~~ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRT/animation.gif - -This is a simple path planning code with Rapidly-Exploring Random Trees -(RRT) - -Black circles are obstacles, green line is a searched tree, red crosses -are start and goal positions. - -.. include:: rrt_star.rst - - -RRT with dubins path -~~~~~~~~~~~~~~~~~~~~ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTDubins/animation.gif - -Path planning for a car robot with RRT and dubins path planner. - -.. _rrt*-with-dubins-path: - -RRT\* with dubins path -~~~~~~~~~~~~~~~~~~~~~~ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarDubins/animation.gif - -Path planning for a car robot with RRT\* and dubins path planner. - -.. _rrt*-with-reeds-sheep-path: - -RRT\* with reeds-sheep path -~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarReedsShepp/animation.gif - -Path planning for a car robot with RRT\* and reeds sheep path planner. - -.. _informed-rrt*: - -Informed RRT\* -~~~~~~~~~~~~~~ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/InformedRRTStar/animation.gif - -This is a path planning code with Informed RRT*. - -The cyan ellipse is the heuristic sampling domain of Informed RRT*. - -Ref: - -- `Informed RRT\*: Optimal Sampling-based Path Planning Focused via - Direct Sampling of an Admissible Ellipsoidal - Heuristic `__ - -.. _batch-informed-rrt*: - -Batch Informed RRT\* -~~~~~~~~~~~~~~~~~~~~ - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BatchInformedRRTStar/animation.gif - -This is a path planning code with Batch Informed RRT*. - -Ref: - -- `Batch Informed Trees (BIT*): Sampling-based Optimal Planning via the - Heuristically Guided Search of Implicit Random Geometric - Graphs `__ - -.. _closed-loop-rrt*: - -Closed Loop RRT\* -~~~~~~~~~~~~~~~~~ - -A vehicle model based path planning with closed loop RRT*. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClosedLoopRRTStar/animation.gif - -In this code, pure-pursuit algorithm is used for steering control, - -PID is used for speed control. - -Ref: - -- `Motion Planning in Complex Environments using Closed-loop - Prediction `__ - -- `Real-time Motion Planning with Applications to Autonomous Urban - Driving `__ - -- `[1601.06326] Sampling-based Algorithms for Optimal Motion Planning - Using Closed-loop Prediction `__ - -.. _lqr-rrt*: - -LQR-RRT\* -~~~~~~~~~ - -This is a path planning simulation with LQR-RRT*. - -A double integrator motion model is used for LQR local planner. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRRRTStar/animation.gif - -Ref: - -- `LQR-RRT\*: Optimal Sampling-Based Motion Planning with Automatically - Derived Extension - Heuristics `__ - -- `MahanFathi/LQR-RRTstar: LQR-RRT\* method is used for random motion - planning of a simple pendulum in its phase - plot `__ - -Cubic spline planning ---------------------- - -A sample code for cubic path planning. - -This code generates a curvature continuous path based on x-y waypoints -with cubic spline. - -Heading angle of each point can be also calculated analytically. - -.. image:: cubic_spline/Figure_1.png -.. image:: cubic_spline/Figure_2.png -.. image:: cubic_spline/Figure_3.png - -B-Spline planning ------------------ - -.. image:: bspline_path/Figure_1.png - -This is a path planning with B-Spline curse. - -If you input waypoints, it generates a smooth path with B-Spline curve. - -The final course should be on the first and last waypoints. - -Ref: - -- `B-spline - Wikipedia `__ - -.. _eta^3-spline-path-planning: - -Eta^3 Spline path planning --------------------------- - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/Eta3SplinePath/animation.gif - -This is a path planning with Eta^3 spline. - -Ref: - -- `\\eta^3-Splines for the Smooth Path Generation of Wheeled Mobile - Robots `__ - -Bezier path planning --------------------- - -A sample code of Bezier path planning. - -It is based on 4 control points Beier path. - -.. image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/docs/modules/path_planning/Bezier_path_planning/Figure_1.png?raw=True - -If you change the offset distance from start and end point, - -You can get different Beizer course: - -.. image:: https://github.com/AtsushiSakai/PythonRobotics/raw/master/docs/modules/path_planning/Bezier_path_planning/Figure_2.png?raw=True - -Ref: - -- `Continuous Curvature Path Generation Based on Bezier Curves for - Autonomous - Vehicles `__ - - -.. include:: quintic_polynomials_planner.rst - - -Dubins path planning --------------------- - -A sample code for Dubins path planning. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DubinsPath/animation.gif?raw=True - -Ref: - -- `Dubins path - - Wikipedia `__ - -Reeds Shepp planning --------------------- - -A sample code with Reeds Shepp path planning. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ReedsSheppPath/animation.gif?raw=true - -Ref: - -- `15.3.2 Reeds-Shepp - Curves `__ - -- `optimal paths for a car that goes both forwards and - backwards `__ - -- `ghliu/pyReedsShepp: Implementation of Reeds Shepp - curve. `__ - -LQR based path planning ------------------------ - -A sample code using LQR based path planning for double integrator model. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRPlanner/animation.gif?raw=true - -Optimal Trajectory in a Frenet Frame ------------------------------------- - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/animation.gif - -This is optimal trajectory generation in a Frenet Frame. - -The cyan line is the target course and black crosses are obstacles. - -The red line is predicted path. - -Ref: - -- `Optimal Trajectory Generation for Dynamic Street Scenarios in a - Frenet - Frame `__ - -- `Optimal trajectory generation for dynamic street scenarios in a - Frenet Frame `__ - +.. include:: dynamic_window_approach/dynamic_window_approach.rst +.. include:: bugplanner/bugplanner.rst +.. include:: grid_base_search/grid_base_search.rst +.. include:: model_predictive_trajectory_generator/model_predictive_trajectory_generator.rst +.. include:: state_lattice_planner/state_lattice_planner.rst +.. include:: prm_planner/prm_planner.rst +.. include:: vrm_planner/vrm_planner.rst +.. include:: rrt/rrt.rst +.. include:: cubic_spline/cubic_spline.rst +.. include:: bspline_path/bspline_path.rst +.. include:: eta3_spline/eta3_spline.rst +.. include:: bezier_path/bezier_path.rst +.. include:: quintic_polynomials_planner/quintic_polynomials_planner.rst +.. include:: dubins_path/dubins_path.rst +.. include:: reeds_shepp_path/reeds_shepp_path.rst +.. include:: lqr_path/lqr_path.rst +.. include:: hybridastar/hybridastar.rst +.. include:: frenet_frame_path/frenet_frame_path.rst +.. include:: coverage_path/coverage_path.rst diff --git a/docs/modules/path_planning/prm_planner/prm_planner.rst b/docs/modules/path_planning/prm_planner/prm_planner.rst new file mode 100644 index 0000000000..0628719176 --- /dev/null +++ b/docs/modules/path_planning/prm_planner/prm_planner.rst @@ -0,0 +1,19 @@ +.. _probabilistic-road-map-(prm)-planning: + +Probabilistic Road-Map (PRM) planning +------------------------------------- + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ProbabilisticRoadMap/animation.gif + +This PRM planner uses Dijkstra method for graph search. + +In the animation, blue points are sampled points, + +Cyan crosses means searched points with Dijkstra method, + +The red line is the final path of PRM. + +Ref: + +- `Probabilistic roadmap - + Wikipedia `__ diff --git a/docs/modules/path_planning/quintic_polynomials_planner.rst b/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner.rst similarity index 100% rename from docs/modules/path_planning/quintic_polynomials_planner.rst rename to docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner.rst diff --git a/docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path.rst b/docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path.rst new file mode 100644 index 0000000000..81e565888e --- /dev/null +++ b/docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path.rst @@ -0,0 +1,17 @@ +Reeds Shepp planning +-------------------- + +A sample code with Reeds Shepp path planning. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ReedsSheppPath/animation.gif?raw=true + +Ref: + +- `15.3.2 Reeds-Shepp + Curves `__ + +- `optimal paths for a car that goes both forwards and + backwards `__ + +- `ghliu/pyReedsShepp: Implementation of Reeds Shepp + curve. `__ diff --git a/docs/modules/path_planning/rrt/rrt.rst b/docs/modules/path_planning/rrt/rrt.rst new file mode 100644 index 0000000000..1afa17b144 --- /dev/null +++ b/docs/modules/path_planning/rrt/rrt.rst @@ -0,0 +1,118 @@ +.. _rapidly-exploring-random-trees-(rrt): + +Rapidly-Exploring Random Trees (RRT) +------------------------------------ + +Basic RRT +~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRT/animation.gif + +This is a simple path planning code with Rapidly-Exploring Random Trees +(RRT) + +Black circles are obstacles, green line is a searched tree, red crosses +are start and goal positions. + +.. include:: rrt/rrt_star.rst + + +RRT with dubins path +~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTDubins/animation.gif + +Path planning for a car robot with RRT and dubins path planner. + +.. _rrt*-with-dubins-path: + +RRT\* with dubins path +~~~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarDubins/animation.gif + +Path planning for a car robot with RRT\* and dubins path planner. + +.. _rrt*-with-reeds-sheep-path: + +RRT\* with reeds-sheep path +~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarReedsShepp/animation.gif + +Path planning for a car robot with RRT\* and reeds sheep path planner. + +.. _informed-rrt*: + +Informed RRT\* +~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/InformedRRTStar/animation.gif + +This is a path planning code with Informed RRT*. + +The cyan ellipse is the heuristic sampling domain of Informed RRT*. + +Ref: + +- `Informed RRT\*: Optimal Sampling-based Path Planning Focused via + Direct Sampling of an Admissible Ellipsoidal + Heuristic `__ + +.. _batch-informed-rrt*: + +Batch Informed RRT\* +~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BatchInformedRRTStar/animation.gif + +This is a path planning code with Batch Informed RRT*. + +Ref: + +- `Batch Informed Trees (BIT*): Sampling-based Optimal Planning via the + Heuristically Guided Search of Implicit Random Geometric + Graphs `__ + +.. _closed-loop-rrt*: + +Closed Loop RRT\* +~~~~~~~~~~~~~~~~~ + +A vehicle model based path planning with closed loop RRT*. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClosedLoopRRTStar/animation.gif + +In this code, pure-pursuit algorithm is used for steering control, + +PID is used for speed control. + +Ref: + +- `Motion Planning in Complex Environments using Closed-loop + Prediction `__ + +- `Real-time Motion Planning with Applications to Autonomous Urban + Driving `__ + +- `[1601.06326] Sampling-based Algorithms for Optimal Motion Planning + Using Closed-loop Prediction `__ + +.. _lqr-rrt*: + +LQR-RRT\* +~~~~~~~~~ + +This is a path planning simulation with LQR-RRT*. + +A double integrator motion model is used for LQR local planner. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRRRTStar/animation.gif + +Ref: + +- `LQR-RRT\*: Optimal Sampling-Based Motion Planning with Automatically + Derived Extension + Heuristics `__ + +- `MahanFathi/LQR-RRTstar: LQR-RRT\* method is used for random motion planning of a simple pendulum in its phase plot `__ \ No newline at end of file diff --git a/docs/modules/path_planning/rrt_star.rst b/docs/modules/path_planning/rrt/rrt_star.rst similarity index 90% rename from docs/modules/path_planning/rrt_star.rst rename to docs/modules/path_planning/rrt/rrt_star.rst index cf136d529f..546e9bf6dd 100644 --- a/docs/modules/path_planning/rrt_star.rst +++ b/docs/modules/path_planning/rrt/rrt_star.rst @@ -2,7 +2,6 @@ RRT\* ~~~~~ .. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTstar/animation.gif - :alt: gif This is a path planning code with RRT\* @@ -11,7 +10,7 @@ Black circles are obstacles, green line is a searched tree, red crosses are star Simulation ^^^^^^^^^^ -.. image:: rrt_star_files/rrt_star_1_0.png +.. image:: rrt/rrt_star/rrt_star_1_0.png :width: 600px diff --git a/docs/modules/path_planning/rrt_star_files/rrt_star_1_0.png b/docs/modules/path_planning/rrt/rrt_star/rrt_star_1_0.png similarity index 100% rename from docs/modules/path_planning/rrt_star_files/rrt_star_1_0.png rename to docs/modules/path_planning/rrt/rrt_star/rrt_star_1_0.png diff --git a/docs/modules/path_planning/rrt_star_reeds_shepp/figure_1.png b/docs/modules/path_planning/rrt/rrt_star_reeds_shepp/figure_1.png similarity index 100% rename from docs/modules/path_planning/rrt_star_reeds_shepp/figure_1.png rename to docs/modules/path_planning/rrt/rrt_star_reeds_shepp/figure_1.png diff --git a/docs/modules/path_planning/state_lattice_pathplanner/Figure_1.png b/docs/modules/path_planning/state_lattice_planner/Figure_1.png similarity index 100% rename from docs/modules/path_planning/state_lattice_pathplanner/Figure_1.png rename to docs/modules/path_planning/state_lattice_planner/Figure_1.png diff --git a/docs/modules/path_planning/state_lattice_pathplanner/Figure_2.png b/docs/modules/path_planning/state_lattice_planner/Figure_2.png similarity index 100% rename from docs/modules/path_planning/state_lattice_pathplanner/Figure_2.png rename to docs/modules/path_planning/state_lattice_planner/Figure_2.png diff --git a/docs/modules/path_planning/state_lattice_pathplanner/Figure_3.png b/docs/modules/path_planning/state_lattice_planner/Figure_3.png similarity index 100% rename from docs/modules/path_planning/state_lattice_pathplanner/Figure_3.png rename to docs/modules/path_planning/state_lattice_planner/Figure_3.png diff --git a/docs/modules/path_planning/state_lattice_pathplanner/Figure_4.png b/docs/modules/path_planning/state_lattice_planner/Figure_4.png similarity index 100% rename from docs/modules/path_planning/state_lattice_pathplanner/Figure_4.png rename to docs/modules/path_planning/state_lattice_planner/Figure_4.png diff --git a/docs/modules/path_planning/state_lattice_pathplanner/Figure_5.png b/docs/modules/path_planning/state_lattice_planner/Figure_5.png similarity index 100% rename from docs/modules/path_planning/state_lattice_pathplanner/Figure_5.png rename to docs/modules/path_planning/state_lattice_planner/Figure_5.png diff --git a/docs/modules/path_planning/state_lattice_pathplanner/Figure_6.png b/docs/modules/path_planning/state_lattice_planner/Figure_6.png similarity index 100% rename from docs/modules/path_planning/state_lattice_pathplanner/Figure_6.png rename to docs/modules/path_planning/state_lattice_planner/Figure_6.png diff --git a/docs/modules/path_planning/state_lattice_planner/state_lattice_planner.rst b/docs/modules/path_planning/state_lattice_planner/state_lattice_planner.rst new file mode 100644 index 0000000000..3ef0c7eca2 --- /dev/null +++ b/docs/modules/path_planning/state_lattice_planner/state_lattice_planner.rst @@ -0,0 +1,33 @@ +State Lattice Planning +---------------------- + +This script is a path planning code with state lattice planning. + +This code uses the model predictive trajectory generator to solve +boundary problem. + + +Uniform polar sampling +~~~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/UniformPolarSampling.gif + +Biased polar sampling +~~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/BiasedPolarSampling.gif + +Lane sampling +~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/LaneSampling.gif + +Ref: + +- `Optimal rough terrain trajectory generation for wheeled mobile + robots `__ + +- `State Space Sampling of Feasible Motions for High-Performance Mobile + Robot Navigation in Complex + Environments `__ + diff --git a/docs/modules/path_planning/vrm_planner/vrm_planner.rst b/docs/modules/path_planning/vrm_planner/vrm_planner.rst new file mode 100644 index 0000000000..92e729ab29 --- /dev/null +++ b/docs/modules/path_planning/vrm_planner/vrm_planner.rst @@ -0,0 +1,17 @@ +Voronoi Road-Map planning +------------------------- + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/VoronoiRoadMap/animation.gif + +This Voronoi road-map planner uses Dijkstra method for graph search. + +In the animation, blue points are Voronoi points, + +Cyan crosses mean searched points with Dijkstra method, + +The red line is the final path of Vornoi Road-Map. + +Ref: + +- `Robotic Motion Planning `__ + From c70add32a15ad7e662185fa816ba152d244be002 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 4 Dec 2021 20:56:54 +0900 Subject: [PATCH 432/940] add visibility road map path doc (#592) * add visibility road map path doc * add visibility road map path doc * add visibility road map path doc * add visibility road map path doc * add visibility road map path doc * add visibility road map path doc * add visibility road map path doc --- PathPlanning/VisibilityRoadMap/geometry.py | 3 +- .../VisibilityRoadMap/visibility_road_map.py | 21 +++--- .../grid_base_search/grid_base_search.rst | 2 + .../path_planning/path_planning_main.rst | 1 + .../visibility_road_map_planner/step0.png | Bin 0 -> 322560 bytes .../visibility_road_map_planner/step1.png | Bin 0 -> 289363 bytes .../visibility_road_map_planner/step2.png | Bin 0 -> 795677 bytes .../visibility_road_map_planner/step3.png | Bin 0 -> 791560 bytes .../visibility_road_map_planner.rst | 71 ++++++++++++++++++ 9 files changed, 87 insertions(+), 11 deletions(-) create mode 100644 docs/modules/path_planning/visibility_road_map_planner/step0.png create mode 100644 docs/modules/path_planning/visibility_road_map_planner/step1.png create mode 100644 docs/modules/path_planning/visibility_road_map_planner/step2.png create mode 100644 docs/modules/path_planning/visibility_road_map_planner/step3.png create mode 100644 docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner.rst diff --git a/PathPlanning/VisibilityRoadMap/geometry.py b/PathPlanning/VisibilityRoadMap/geometry.py index c4d73837c9..b15cdb8a43 100644 --- a/PathPlanning/VisibilityRoadMap/geometry.py +++ b/PathPlanning/VisibilityRoadMap/geometry.py @@ -1,4 +1,5 @@ class Geometry: + class Point: def __init__(self, x, y): self.x = x @@ -40,4 +41,4 @@ def orientation(p, q, r): if (o4 == 0) and on_segment(p2, q1, q2): return True - return False \ No newline at end of file + return False diff --git a/PathPlanning/VisibilityRoadMap/visibility_road_map.py b/PathPlanning/VisibilityRoadMap/visibility_road_map.py index a677804440..6458cd882c 100644 --- a/PathPlanning/VisibilityRoadMap/visibility_road_map.py +++ b/PathPlanning/VisibilityRoadMap/visibility_road_map.py @@ -23,14 +23,14 @@ class VisibilityRoadMap: - def __init__(self, robot_radius, do_plot=False): - self.robot_radius = robot_radius + def __init__(self, expand_distance, do_plot=False): + self.expand_distance = expand_distance self.do_plot = do_plot def planning(self, start_x, start_y, goal_x, goal_y, obstacles): - nodes = self.generate_graph_node(start_x, start_y, goal_x, goal_y, - obstacles) + nodes = self.generate_visibility_nodes(start_x, start_y, + goal_x, goal_y, obstacles) road_map_info = self.generate_road_map_info(nodes, obstacles) @@ -48,7 +48,8 @@ def planning(self, start_x, start_y, goal_x, goal_y, obstacles): return rx, ry - def generate_graph_node(self, start_x, start_y, goal_x, goal_y, obstacles): + def generate_visibility_nodes(self, start_x, start_y, goal_x, goal_y, + obstacles): # add start and goal as nodes nodes = [DijkstraSearch.Node(start_x, start_y), @@ -129,8 +130,8 @@ def calc_offset_xy(self, px, py, x, y, nx, ny): offset_vec = math.atan2(math.sin(p_vec) + math.sin(n_vec), math.cos(p_vec) + math.cos( n_vec)) + math.pi / 2.0 - offset_x = x + self.robot_radius * math.cos(offset_vec) - offset_y = y + self.robot_radius * math.sin(offset_vec) + offset_x = x + self.expand_distance * math.cos(offset_vec) + offset_y = y + self.expand_distance * math.sin(offset_vec) return offset_x, offset_y @staticmethod @@ -184,7 +185,7 @@ def main(): sx, sy = 10.0, 10.0 # [m] gx, gy = 50.0, 50.0 # [m] - robot_radius = 5.0 # [m] + expand_distance = 5.0 # [m] obstacles = [ ObstaclePolygon( @@ -209,8 +210,8 @@ def main(): plt.axis("equal") plt.pause(1.0) - rx, ry = VisibilityRoadMap(robot_radius, do_plot=show_animation).planning( - sx, sy, gx, gy, obstacles) + rx, ry = VisibilityRoadMap(expand_distance, do_plot=show_animation)\ + .planning(sx, sy, gx, gy, obstacles) if show_animation: # pragma: no cover plt.plot(rx, ry, "-r") diff --git a/docs/modules/path_planning/grid_base_search/grid_base_search.rst b/docs/modules/path_planning/grid_base_search/grid_base_search.rst index ac4ea2f6fd..1644ed00cc 100644 --- a/docs/modules/path_planning/grid_base_search/grid_base_search.rst +++ b/docs/modules/path_planning/grid_base_search/grid_base_search.rst @@ -19,6 +19,8 @@ This is a 2D grid based path planning with Depth first search algorithm. In the animation, cyan points are searched nodes. +.. _dijkstra: + Dijkstra algorithm ~~~~~~~~~~~~~~~~~~ diff --git a/docs/modules/path_planning/path_planning_main.rst b/docs/modules/path_planning/path_planning_main.rst index 61f8ea2113..c3c5c389ec 100644 --- a/docs/modules/path_planning/path_planning_main.rst +++ b/docs/modules/path_planning/path_planning_main.rst @@ -9,6 +9,7 @@ Path Planning .. include:: model_predictive_trajectory_generator/model_predictive_trajectory_generator.rst .. include:: state_lattice_planner/state_lattice_planner.rst .. include:: prm_planner/prm_planner.rst +.. include:: visibility_road_map_planner/visibility_road_map_planner.rst .. include:: vrm_planner/vrm_planner.rst .. include:: rrt/rrt.rst .. include:: cubic_spline/cubic_spline.rst diff --git a/docs/modules/path_planning/visibility_road_map_planner/step0.png b/docs/modules/path_planning/visibility_road_map_planner/step0.png new file mode 100644 index 0000000000000000000000000000000000000000..4e672720f65ed20c8746a2f6b1d2e32ae2334720 GIT binary patch literal 322560 zcmeFY1y@{6voMOg6Wkqwdyv810|W`~kPuu4cMb0D7J>(NcNp9WJ`kM2CEq;n(R=SX zKj5zQ?X{ZjsqX6DT~)iwnkWr5c}z4?G#D5dOhpA5O&AyiAPfw=3knhxLLpL}1_OiP zU?(lDp(rg)t>NNmZD(%<1EUa?s*9|byu93Vp&%uNCr1s(({CJn%0d@PASqGyo0dK( z6xTuu$5~66pc)@{C`w0`?eovTcLX2*u%Vp`M}O9S|EogwqxPF1eAC@uzwMjcBcY4e zgALaJoBgf*E*LPzb;+EsHc=p)Vj&y%`&fPkK#1%K>^m+(Vi+cg!>a>L4=E|OKpvhq zE#qyNNSDr&qW!1)m%s0y;0klFVR$fi*@ALRV4TTd9;~~ybx>eF+O_0qF@M?}!XXPYedj6@ImSv9Rc)_!46#EL2{jxx+F39>Vn z$soQ&^`xJnWFH$tP527zlQK>CBTP^A%m>%EzI^`inZ1Kpb9bZnAT*+h(#OuWzcWiO z+nNcr#8GC*sqd3yncn}20Cc7bvdTqO;@m4X?Cz#^g?nkRY1~u5q|j>0lvlid)auTG ze@4#0=|J_`;l|09B4-(kk6B!4Y#2&3jNEaMj2Q~su#EgpZOoV=PjBbjJYmi7#k}zQ zDi4-{h4@Hvq;Og}!sBeY3YZ*B@%>p68{=;bj!(H4$f2emShtI;;R?O+5DVqB>E+&n$M$pQG^cG#oJ8 z)KvaD6*`J?#iha9g|aWTV9^TS3`a5TgO`Aocs+6bm07$W^~`d#4Q_IxQMiLn=6u{q z;K=OXeO}a*==p^j04MQ{fRZ@%x6qMLwSMV-cPYW0I~C{3(-=0UAcs+^%46B3qpsdF z>T*HKaAZl3(O6z*{NKSoeIM*a5#;W|b>bKut#tKFoc3OjJ%(jc zQz8QDlGjh^dg~NFF>I83o+8P8-%jG9Z}(!W zHE>`VgS`?k=K3&JtZ+Au zc({-!k(DJ#Dqw!}0qaoh;YIq4F99DAvLskPp!y>b^$|ExYy@?bBa6bn{^lo^!U+wX z#X&NU)uV2XA@$Jyu{$3Q@p8*tCU!x%}$_Dpty#2c_$Q=BQKn| zJ_=t#&1&7BfWT3}s4AxwEIy=se*6{{xiI=gC%+WyWcN~ic2*uM!E5M?Y=Tf7P8 zb%TM=5Eve0<0hKK-ZQ<@LrVKTRu`rxq!YGij;V+Kl2>cKsYi83$h3=*6V}m7LH@n` zx38~2H;ze=WB>i`_XoR|_ir#4BjR|r2wK6sG=aSgDm42zhdARXpF%f7=|Xug*=})+ z@uOrIL3v>G8FOLo^bhf^!L4Clfh%&S^kTGF2@3QUNxUqP@6>k_(G;ypzL&g~;FoY{ zV%upb8%#(|NV96PN-GzAs`^y=OZ`u)PWlr5Pnrgf)iiR6I41N_*Rda?9i!~~6Z@3c zII{8P>ZnEZS}rWg%!?^V<0RuoCre<;#jZ+`f{|I*<(OsGS%bnB^^49eEx)Ah zT>sE+iGa#CwO6gDcw*v#tUj|#5)*C@?rAO{MkLZ5l3|Ep2wKPmrZC16<}GFyh8AWF z=2wh(5)WSPGK%DhNt+sTO7kt#ZZZpjaDdzg>&J|6ZX=5=;_v)u{CK3PWE5QO4v^^# zD{`|Oo6h0Zv4=cVhh0maRm-?Bon&4{KMTxZq_~54b}Ap+)7r9%%4EBuW6}BCvUC;X z$;qjr$r5X_DYeYoOx`K!Dc331src;s&s=Q5?1O}|W~L;okE-Y>GbnQQ%gfXD#X5tG#S9nf=UK zcYR}va^v%G&DeQmS0Z4!d$4=!tp z@5$*No5$AfhEN>WbU==!;aO`ohc;2Oa-wqA1iWt9*Xpm8Uz7jbTnX&)4%d7&&-u+-@?pr?$YbWj#**k!-XR-^A z3v97&F`j&+d}9-`ZI$h*ZoyZK7rYmphuj;chloecYscFFvfua`#7@k=YbDZqJA3_t z)R|V)anx4$cRnV3!r`=)*YMg~C}Puy0o3UP0~V3C3@x6G`vNe-)i% zS0VJEKgDDUYz&+yj0=+wOONoB0n3-j*hjZg*%4&o>r<^#9Z>LdR)o$|jjukvI8{p-T-***MjgX^2KPaW1baS(yD7$F1sTueG(N zbC$hwwhR~UO?so8tsKd5g{hTXZZ3ZFlc!3+d}n#8Y6thGKky22!>eMwKl4FA%ZAbM za7RVT`txD;vUC86 zmXi5YB*rb@srW)GDC}u)p56J-3Gg0xw0lHGYeM5ek5hs$cqh#_PTCO6oTLaVPn2vn z!dutoZ*s;Yo~6-UA739z!9QpQDDD(Ie7-7RZmlS@by7RY85jZ%CG9G^<{on7KbO!q z?00xSh`x2+J*M5HPX^QlcA1VyS(+{N-^nh;q;Z_+lmGI%z#C8MWavq0Ppx5peg4r@ z`#CL(-KY}+TK;IVoDQ0>v=Zz=eX(BW@y+zoA90yEAWIKmBT6x;aQabE<<%41v)kWt zzO54=(#hjvHS#|HlYuV2uCmUy9)5%M#pkYH3}2~!W;fN;CwdKE>nX=(lxDYYn44>LQ}zZ!&7SK+>yBrU zYaqR^x(2_JTN`bU_KYe!ru~oZjW!*UHwik#PZLj%x3XLB-Etj`HpS-sew=`SvVIqD zcF(oGRBwK+A<6@B@RRTa$bFJSed7M3FFV798PaDFuULXFw$FQqbg^^?-xc;YhTj-J zYI(W>U5`Lf^6Lh025~R@PxE;?6H8eZ;UhW}<>V$n-v^nos2~A5gYB`Lp>3r=N8!gREEF|$mKNMTd_^gL_olHBZT|Rc@aN`$z2_g z*L){;XZ&b!LIs#9nF)Uye_MEVy>X2=5`QCjS}uKKc?ED1or5*)^&zvWdg7?Slkp4qL~|)_cI)?%K@5hkSMrf`#t!~BwYEqFU&XlY!@fo! z5Exe_x4)W4`GwtLrdLQ##v{sZyby;b+E5 z3qx$i7~MFxuaHL49`Ya__{Hmh*uStaiiy0ordS(L2PE1`PtjUc73Mv(jRJ!JOA3Ps zZNWl|7%bU;w&h@%Vc`D-hl7EMu!BMP_c3bF`kyBOTK>WLw;Dbv90nQs3lCbn3gG@@ zGy<>y{y*CAF3>(0NiAtbMQE*M;bLXw;A-pWcIqx{2?d}!Dd@Yxzz{P0Q(zS}=`W%4 zFWYJBx#_8@2wOOQ<1n*yG`HgL`sVb{JTRhO!qDb7D>pN0uW$AauEJgb+JB7@hPM9! zbJ9}(Ylz!d0Ii;?2DP-Kixss12Nwqytr!|LHMOXVrM0l8jNHGYLw^BiZQb0QggH4q zJv})*c{v&;g#m>pi&e4JT zpLxy99o^jkw6y;$^q5(x32#;>L*t#7iq_D&^6t} z{)=D#j{M&{{~b}3^PjE%H&Xl?o&N=e5?TyRl=DBCCWclLAG-_XBe|W7x;C_iO4&aT zY#a0s^S{;5Hk{rAOXdf27#Il{MHxwLFWA#A~akSPYf#s_45O zr+)SLE$Q3j>mB6?n^D>=ulbx2^a$xb-Jx037IYi+-E=OdQM(&QifL*3C+)A-8@=p~!8aUQNug;;9(aGt}^+dagg3mZ4TA zlIq}EE~BC$^>CC?$E83)*D$nw;Apnd@Qpt*cK|O33UitW(+aoXs zWX<9m`l`8dHs&9wKG_Ox#z+J?qy!e}b!qj-be(7*6bROzYlz!=*esrPD^dn7`ACr$6WgTbk69RmI<^ zp!($ap4uCnXO^+5k1}{G&wOzyHp%}oYr-v9=+kk*hG4!bjVuND{k(#)=|)JKmQ4&h zp2g@6d+w#4?6Avq+IE9W9CcbKzEC(VKklMnRH(RmLxQrC2kg6-;c%1h_&izdWYO`t z|C_G(Ao=l#-^0e2R$`Er%!Cpe7Cvn6Rix8ZaV7Q`Zxp6-*VN38OMC6eMgfLUM70-=Jg9*|$D>?_bHf*Y6zwPNTNNKWK!fi0U+ zS}g}z?FkGw8ca_42W9J*CrdBkK-wzmo?YIU*Jt8Na*)<^!0CM6Iy&qUJ{LDuKlZEc z0*!9XIPxWHo7$<~@p>G|{L2;N+?=ZTID)tJ77LZ=k6Z~_Pj>hiT!5@hpHwQET4~mY zY4GnI%rHL&mXymMVYOihdHV%5;qN_+q#;2xhNi-zqSdJztC@iS$ikJNl8hx<>6~1l9)# z{H>~9dPWUS;WR&uBZTDDU4JcWgUu3*=oSp$G%efbqJsr{g8EFiSHcOm*{hzF)oD^M z#&~9T=-m*3CEa_kzEUoGxKiH5_G-Am3+|I5Dlq8YM15|$O!OH}ewB+091)6WQ(z%t zwsih9TytIfX_S%<=(4MLv62{)DKO2<+NyAkpmIXYRe6n#coF@s(~MBUS)7C2*Y1+S zeIPn4+N5@pTXgjIT&eO};rZE_I{*L>9+irC&%`w2w%4XFUJ`F-uaiTlZiN!KPeR&W zLQx)t&-7&gg`%HdPFTlcq-dTU{z;Ss=$)m)I?%dlWHhwQRmtg9I1m~na^mAwV%k6{ z&-ACNQ+_i9y~lcq|18eEyfnYv^>{8}iDdyXLDaU`w85{y-<=dGEuS1Nh5rP5fk0YX z+6D6~MGz1H-g|+CKFU?>tR@@BbQ{iZ8J&ouBJV-KN@@)Y7rVVw@p-mnYgIx_rnK>V z)jyCJ(M~*rF%3cP~q%ljJ2hfWQRUH%yUfZg|jaD%XYPpaw0%73` zE2m%w4gf+6&Acz#-{3W$Cb;??#Z1x&fQ2;f3Q-?LH zD0S19j7S%{CB_k0U?QD`BbLn5a)p7s5Pp*jK9MOxldsgj-I3feI8NZ6&}OkcU@~>O zj~X*`!(i4iM@ih}R^EP7{CNisdu=BQs#8bj!2t#f$gXF{id9#{y+q%0|HNLSXdeVJ zoX>v&&~e4>lOZz4$}|58Hob=kF3}_~Tb2gbLQI{yKHm z*R{Ghmei0Y!25&Itxxe1a`hc-KTtU)RDRS;UB@b0-!)57^+LCC)c{kNa4f-14Xoos zpF9~$X4(vTMP3+$2%!*7ibm4BNuZdesk5SF*;TbD`f6kbnlXArBFhlJqx9&7b!eUZ z?jU5LRFC&}$Ugyb({>M~ADJNE5G-!DLLU^3XntoD0wbc4V^t0$J&D-Z!v$K1OT*kM z=y`@kYItf2mWj}a8hPfQNFoZApKJeK$Z5ibTcd)Fig=Sp6rT@4lQ?l=GV7A`Lpj?$ zomaJYoPnwxy^DAA*uT>2iQb%ZWCwS-^@Rme9k_UY5Zn%U$$@|M;TkAj8b0U%a?16*(Bm>tYn?=X@v&b zQhWP=jmm9Hc%vt5)psRk`uA9#)DcdFi890wX4?d*pTJ}19eA*O)_Vn1vm^{=_4m;U zb#n<<5ddI{rOacq$ueER#J8|P`CPoW0?KMfjpg5Sa)ywJlWd&I^R^xg0FDvMJ-T~& zj)Bj%F-qM<&_UjT|7R0Z#}8k>j!Q0rE(&=oM7S7bdPtr$syWQ4hSxIUbfT(wM}WwT z&kWAgi?L%L1j4$VSGlcA3%2ch>=77M^Y*Q$bB>>$o;KQjmf8#)+GHurI}3|Ze;yqu zj(Zc1@se7tMdm4_F-s)qyvIm2oCYP>_j-L4aNlfoPJS-`dqK6i^wVIIe)ZCQwqw!xlk{Wou@=kG(wEVZxvdXvB#! zUg1bMkG;-&wmf3k(ZP$hUF1Wd+_oYW(G{;857^DceoAE18K~5avyF4#skC~59G}j| z$j>iA0lFn^gn}=mW%r*~epY+N6nO!zzHJS~5Lw|L7M2*bSAWA+ml`_`mml^V?t1eg zo6l66CE4zg4k)P`2zr7)!xl%Q?Ew?*l4hTd6}=)|txdiuG5y|}_P!KO{*x>rzw-Bz z%nSS2G@Hz`I6n9ZL41*@t5JM266S;?E}#It^@DYP5FL14N>?Mlpa*UaN&L>w8C(46 z%IJjJ@!}6lXNZY-IB9lV%V5M)Ayz+ye?7(RdCjCs<4bjGr+U^r$-z&s>kUUiz znPV&H=jUHaYC2%h1U3&~=VLVvSWfjb*K5H7Iu*Qnlni=?F3yTiXCb&_$AzVcj3?VeLZ0d1g}2%8u3UF+ zM;yP~A4}dGj7mlzG~rauSz(>&x{hT5N&Kkm4*vNnj13EhUlXc4lU1K?hXoPfh*j7y zP7rn5&6g?K_?XY>Tl+-b&9tOT;${OR^AUAlq&q^O3OJ?FW~L(h7@Ar! zk#$3GkA&!QSp4=Nxs6z);r7pcVtZfg=M5ftygB;y22(jd&ntP74Es|{BYiT1n+|H! zZHM_Cs0|HWf1-r_OLJ0`Gy-Kj(@J?RuT5MwuT9OJyFQh(Z*W4_ma{K-#L_nYMMT_R z(#x4_sQ%sAN8PaYQJ;+5mz&4?iQin50I$n}=lx{$60!XA?#C&|_FCTq*0pn2xp#H) z;z5n2k(k`&iqF;=auCbH$!TKMc3i)1<`Ve#$LYqvvDZs^akuprM^BTNU80S4_xqEE zlB+!?dI}gC;9x+jVQ62kar^hrbxn0BigZKjYyg^p;Jvd!XD_HI6TiY@22Pqpur>wSG7f zU06na@}XMgY8~?~g;arGPZlbrC})zev6Fp8=qb7$%Acuz?@7G$=dI(x#(sl@9RYB z+TwL(-c|R=c^9cT5?&-?@gPZB;-;Z%=aUjE_^C&ua15L7!$V(#6q}8_m;dC^NLir) z23#UmlCqt-$Z5C*VBb~mZuj+f2=+#8!0p$mXV0Ezqx;+103&hokftyL!-t_)={QU~ z0sOKWCLnd}yN5a=!YyRHk45s`3)Ln)TY$eWH|M_#L(Vzh)=gT)U$65S5$Vlta5!E| z1%=QZ!+N^)!e`tLRNE!JTJL989bOFDB|$$uTdBPt=BxUau}ME(Mytu$ONl+e1^=3S zD2hf?A{(+8DG32gP2~#eBAe7P@j1hiIn(mMU8b7wtSeboG~mK?#`1_}e459B5kkq8 z9Ew#Uni+|sNdJ>zP-hxsz`X252h3uO*NIb@s9#`BxAYkHu3Y9WMsDQOm(i3pm99#{k$d@9$0%}WnG2xcAD7;EWG)SjgwrivQ&Es(95Db(^$(#DQ;?} zktwD-kGbWYJujH*Bl5%;tUDTF%TyG$IK-eR*$E+dIa#3~h#F>F`+0y$k zzVFHV{k6>U?aax>0Vp0(NF#jx+O8yx#`}Xl1Y-BmvB0m5ZC#IC1gOI4+i6&5Tj-Ax z|A)R=R(L$NDhpy{h^+WPJW+YGZ^Yda$r;zkb$j+Lq;rpU=jkxpu|59{QZ5YtGRBne z77w_~IG;f;LO$m@9PJM!p0j6sF9(rG1fk-?9=t-CMF+YWXRU3`f7xd`UpUq}KfVw@ z%k$br75>=x2kAxjavZ)?4O>2*+#OmHNdRwukh>FDhUNzO7FbvbRYGtj!eZ1GcLwA) zaN8sxYKpx5FtaT;mg(XtK5|&As>(0e|PCO3Bpx~N57Y3RTRb{oY4G+Vw-48po_|%k_ ztJu$0?D}hHg5c3qfk0xqowZGl9uIn2ucL6WmBl(>-}Xc;diI?|3Ou1oo&&E5(j`c_a| zSH`5y4IQ2vLSi#MCq_PkPSKagR>f4Ido5@EGsi&L;3vu;u)o{<3#T6e#18vZKHsA% zTimhR-*grrUP8e`P)YEJb)6m?u+m+i_Axi{)x6H_>sZo|@ZN{TRMSpv&UY0p`a7lV zIkyecr;&ijJRASZ*rhXiU>%77$1AQ+tRjzpaZoBQfFxLh6)nbk7Yh-i5y(}HtlYxI ze=oBA7^kug)Q&q=A9-w`*D0a7az{>u%~~9r+>QHxO}$RD4(vw zmS7jNLI*q2yr*ymdO0W+QBcV8ucyNr+CbVmZAL@5c2b2P%o}{vnaKqlVWDtG{s^$@ zF$T++bu~H?Qk*X#F?L(shXiwVxGgYr<~ zUI$kb=XNZ}4;eB*9k(~c*zv#|7Sq@#72vU*iDG$-dRD-i0f-hm%iHv6;uHyZ^F3Zy zOaA_s>51Wxn2V5v&x6rC?T08r(iUf8tP{*c*}w*gMUL-o%Q~{!mhYT<-IZD%2KChVw{@$-y(x0hR1>4Opas0VJY7(2p{ysS)c8kc&#T_LjBqFnk3X3Gk%hp6}b|mJ1+6^k)_I^ zdqQvnPbDFNqQjCft)>w%GU|@%wI@my*sa+4^5RTs!9eQX_CUsg&}w(@G@L+c;N>EP zPk`AlQ6#1Pp;}S-zKSH0t@S!xFOYUp;Y&K?)58_svzmFDFtmRz)??H^9OkL$PP@$1>lapQ+OX+LR-d*2f(>=odJ}~%*?9?%m8YX zTV}6r=+#g1DMd!B866i}8DzZulcHs|8SbC&&Ru=NzVd9&SuZ9I0p(B(e}$mf{aj$Sx+gRe_I)|d}!C^J=4g^J6eRM$5%DOz3SDJm!5 zRg_h+k%J(VAW4pK=_}4oI%#f26Ch6wB1h%{R*ISI-@zA^`}W>Ce{|j|f-Ez6pqJ9a z1$*<$s1G%;kyLis6Cr$nVFHEFHP*YK``kJm6AEvvB#>Z=+I-Pa2j?@MDIerJD7V#n z{)~XxM|zA)0awb%XXX0LkFDWiA4K_>lANHaSpr)B7LcW2Zp{OLpUx9G}%e3 zRk#C3Mdrcz{lFWA`+FvqMk4uim5AI}$yHo#daOeTg0JTO5y9(IHQ1du{T<8_VXcWf zuP=fNU@o~m7k&5c1tEj&nN4I@uYN38QA^ZXAo`~Ygt}4kiFLX|sG0({PXwxWC;Mv%}+0*nwZn{yT=rHz@m7=j>h|Bm^+9G5>U%AY%oBg{aqYtDRVN zsxPy-1+&1gG7IZV5v(F%{AGU|5=1jpf0+#c?~AG4m|I9(>q`wHbLp|CPT%owEJfzI z;7GH;4cQ_WG1YRjr1y|+rK9(3JS!EaI3x=%Uc!-B3Pcx6Kn5Qxbi4PQ&f1g^l6c7Q z03V#uE#vdr5sQ$S-XVN18mm!?UEdHwzT}3AMB>bt7=Ri`IFVR-b2!7Q2x$_+NP9uU z(J)FBMsy!kNORDq(1Kn0wo9*^Mh~1d(JngLSKRcm(zyGZ1@NiK=KtD^14vFe9m@jE zGwQck>O@IYu$md+#j$#vZ5()9@XWh0-3Xc7fk}*U zxxVp!BzBh&0FI0(Cy1{2B>8;?6T8P*cLlPL8mCMHhti3#-0Sn4KjG=%UDPFrN)Jd& zL7;l>6|C8j7*{&TvT|>3i%v zf4)%WkM8h1OPa#888x+!`uoHkErZRvB)6l%>TmRilcn|p4f2S_wbw1wzuqQc>lTlGXwR*de z3$OL3q@282@oIyQZ$C522yy)u#{#P*5gOF`!Z$lSFVgO8G}JD#%gH*_a|PO%K^6@a zq}RH}SWgNf z`m|D9)6&uc)x(ywSJ|2QjGsN|LDHqw=y4js61bnggU8-`HO=S{raHzx>%<@aT0N-#WTJhnRl0LM5l$(6*<9s zDpiCWN^MQGM=y>C&?-|)l%_8O%Om;QnttFT%XC2Zal@T`qCcNkdTy{7!D0Yf2ZIx} zQk;|wl-V|=)@^z~ved-Sp)xalA;@kz>Y~bk>g*Gv@)QhC1siD?*76v-sGby)D54B3 zOw2arbWzaF-ci0M)JJqx_kUhji^|KRT&B|sybnAc+SYIL!e;#Xy6NCefaA%S51I#bD~Pe}fn0sKwuQ&oZ;#;xuMf!6{><#7eg z-Wm&0t)c_nf#5_2Aw4umSaInh%SrUeYfMRJjL>nd3#K89gYDEmmXVvP~n{FoaDPVbBm;e!#yGh zj859s)hsj*=;M8jFq`GzoaDkRMS%4TTGyck_KPCn@IeTP4|i62SF|01yM~EI3&=sz z-hy0qh?0Wn$-$9RML0n+Hc(+XCKOm<7br$ac$)zR3Hg z2=yXBGphb*Doi(5#K-tOrP25_M0xsaTU$a8vj}*lAEMZr0ZNUYkz@qC!n^7u!_n!TL=%Xr49il@IBn=4+ z`-~1(#c5&nm0*=~XE!Y7m=bW%?Z1GR{%GfjkfjKLVOc6a`~La9B=5|)91l>Id^>Li z9#@E@OqPAM1Xa;MovdW%2wcF=_w|HI>9Ij_*`%fb<0Y}J;eoh$W%pV`+R!jUdYEnzm2kQRxInPE0xV zJGEV2`o~3*6F>QPgpYkZ5Zuj?{sM!n-Ok*|Jhqo2@@2?Mh11?(s0+pc)P9Lg0YsqK zW~P7FswZiLUIXCqprSK{f+L~ex_mPk^~mT=8yXlRZYa%28tLE={njie&1A4~c^aAF zc(C}3M$}QvI#jAZFhbLNaJb0rO^h%a{zrodL;{WUu!eZV z{-iBp+FSVf4EXnUbiF3iZUcr79q{u<^PkCO!D8QdkhqJ= z-7OaySQ7oewcrD)eeA*;r2NR2$98tuJmQ9E$k?)9lYn0v1k!p>11X`B^Acy6}~van0U0o71`Sd1Ni}*hLIjQ z=usS-u8czU+GoIg`eNEo{pttSv5y6_gjReMcyG~Xf-XmmoDG_19$e=&T#TnaUPw;> zSMG-fQ=@d8;UPrh0`^AYm!~prz1*9`=T`QJT0~O&2L*m=-XGTR;}mp)#Di*L_q}eH zMn7^8lqCzXRdt0J51wJ2%1J>6cRpn^x^6$A*!tn!*(F~^4(x`qkT(bmSE7w}f-#}cd2bkX zjAuHTm8JkJT6}}Bgm^c`+y7A{Af)GbfyF&KQ>fHmamZU%z`Tp?SmFqSsiH(iox3Nh z2jZS+yA}j4qy?$mELaO7em75gbCFTcwrV^`GN{J;W-awYRXV6f`4KZJPdeh|>cr2_ zuco%gB%b58#L0@lQSxC5p;&qs%}RL9i-(;X`W-t6g0qrf~ka+H5MkW&v%E=&x5Ny$tWpxL^`Qh z8yy)TDo)8v>dwiGste;d9yn|qD7ZwsB$T8&;g~yyDReU_%y@!bU0uM!-~|SQT@#U; zC=*P021dd!I$?wziG0@h0QC;0JTJqoCkS`$s1{v7B-2}%$By4=4MiS0=@30g4#H;) zbhZ*EZP!*My`D>dht2@xFm?%X={)O$rv_rRc6W;r;Q>;qGl@JHC?{1J;Zkf^q5tqB zD~3?u_rd3|TEy?9iHw+dR%VAfu#V?^d5%*?ZL#I28sRrOetos8r^ET#wzOQ=0J!^Np}Ae)B1h2}u9;f0@fCh*vM%{X z9SgO?1Z~a@Tb`a4YoJlP?DxDrWursKx3)6Qxx(H`-Lq6K5m=Ni@^O?dOlp+raKFoS zr?LgNr}D*T*!5a_p~;M*au1o$0Nu#! z!okD#WV)5{ERH3isq$hqX8<+|=cE6YZa@#nYZbqW!EY>r3cAFE`viou(CC(_eS1O( zV6Q7L>`iIN?7{_QFvIFtmcfD8oTbHg|x5+Ht ziQ79!nY+@7x?6Y;m*H9%<7=qL_fC1>cxh$gRg2%s$88)xEey1k9+_>Y`)Q-K5olg8 zFB@RfoGt8LmHnQITF8qUDFt42EgO2D&6Y&oQ)k?GqkJfQawnD&@^KD(lN%%Pe5m%% zUCxj0Xk`6KRR%k@!xk_5)UHbUeCyBiBbwypU!n!-2eETgX@cVijN}MdPu{K$MaD3+{P9=y>B)! z1-E|d)OJs^8#k@6C!w1KvbFQMDW>{9H=muKwQPIz{CyS3q@b5c4E^ame#{I#cay$0 z7__;RcD#lE*=(?y*f2!J=k*E5q z#RK4nf@uyH&9g|niS)}>ki4VcWldXF4dB+qzV_{~PVj4wVQIC=n z`T)u+D9@UhFp4rkq+Bi6#Rkd62a-YytWqVL!!Kh|fj@7YBkZU@I;6%Kk8)v=g_sgv zSFcJzMjM1ID7SCH>K~m=>-q&J6!e z@^^a!-eQEsXdDd941=b>s^}l1Z|WxHRCB$*(w$aqa|`vh(JAyaaesQme5UylRj0fmd=))-}5y^&UgFP=|n-YfRkFlEkpHIG?xAeUJ zeE;VWJw*5e6=#TB-EzfB9puaH?Q+|nnvSKPpWVM3{BlY4HKM3B(F38%?>$bZv7hVq zJpFox%&Y%$4f6|p2;t&t?KsT(x{<~IbwgEfvm|t;Ul#qCo`1gfy#i0V3nH9Ogd(L= zd?$_XzRl~??Rnc#-aN!qZe}muBA!y+EzoHevw}ZxE+EjLI%UXLLSHM4K>msCSf}H| zCJMcRk8y^+!wq?gH_Cu&zd5CC_%R#)=dG_#>g+UR`()ROyJ%5)R%5Z0rNKDY}^ zh?N$^h@2;;L0%-D#Oeh%$IlC{pps(QMOJB4*`%G6o;WNH_qTFOLAa22py4mO zHN+I@dS@VFGm$Q0)8)~rt*A#`m)|foK3mpGQ(9P$b5>=Z&J4tX(Y*4^)>7DGevc7v zoz}r+zd_`h-OgHu-4yTkaR9%At>|dXF<=C6w_?$6f)W8s8EnQ?h!MkhmTe#B6`#k| z1%qG$f@S8kB&VNwzUaCTd%2WuvAL&gf!<^Z4Kv(fRLiM=ck_iM;e>Zj0Ay?l8@=z8 zZGe2)>6g8xgnzB)2|41u-|{io9HH`KyI*&gJ|uJO{8;{zh9WZHNNpz8VpiO0{GI3g zlwh0q%Yb+aiPVpqFzVict|S06NozV6J>yhTH$Iu)+)FPo7K@zbQdgjJH!tALd-W^0 z)#s$LJQVyW9GpOP=a;}>o<`_rA&1>h~&;h>cdcf^uYO{&8{NvFl{qu7|Yhs zIj%97>5m_|%?tT6>OjmUp=eB=sUt^1!%8u7xx?`?_9Xb&fF{+YHbpz-LZc8}YOIl& zFhJ+cOn1`HxPStJGZCX70_7)qHe1IE)c~6{ZR`s6X+yspv8|`Xqy_2~^g_)%y0ULN zyGhwZKs`B0Nb3tyi5^;~UrsnQgJ#1#G?#9be~`bEA>@J($yr~HYJ?g^xw4nV!L&b_ zhOI4Jj0}p&)n-Q&9&zeQF1RB1PWp;QqoS?~>-K}mj;Co8B^#@4xw~YPvUOM3f46nL z@oUQhd&o5`{y!O{6lx$bhm-7ztaj*=!o!b5i_>)Ijd4)~O>e}fM&-1J9r&_o&Ge~^ zdWyaW%Ew;zGn_vpCx&@{X@xagHY`Kq{k5LZ9ke`=W?6-Q17SD)~ey1N- zV_J3F&<9iRrLQlGkMpzMTEt}3;Rx?`f@tBW-SUJawppJoUPgNUM)cK_)rynpr_{$h8EwmZ0xi6`jRg03XLgx=!VyhH&hdxvzoj{ z`}_`?i7|Z%pIE^qTRz|HuyXQT+4Q}cIw#wH2=9O%!@hf&DEMYo5(mocXvlFP_u}~^ zD>N$a;{``f80Rw>dUIQ@+%H77VSn7)?rtCR@J@rT#xuH=1}0YbQxe7%c-^$l^R8w? zpFj7r5UD@pIfF2^Kl#LSIeF*chb2ioRC@>gGNb{8;G>nP=QDoI1Tm9>v{=p;Fth4= z%y(d%?>hV?QjU@{4WJ5_q$f<@0*R z`8Un!fl?FwWx3m+ivNt||B&^TQEhc!)Gq~!6o&%Ef?I*2#e)}$7b#lYAKW1jq`14g zm*P^~p}4y{CAbAC`kwyZaqk#++zapQP`l}WP9(0$4-*N~ zS4qC`CwQ6^r-%G$)~>q@1Hn`9f`e&|U|lqrEY=ROi@&Xg!bRnxZ>o%BI$xiS<)5PA zS|7d{Q`eUz@WM#8}p_e;-k-x$9i)o>{q=A z7YeOB_TD6^zt^YO$GS#B?MNsUk^3L`EAL3`>W&RJMk!|^_^oj@Hm51jij31`aDtEYNwcfd`II@YwAI_leau)GqS$w(nEwCdGNg6SqjZ zL&7?@Hk0+FMg5wrXMoV7VT_|FgQvrBj4Wv5e!g*)Hbx}h*7rw)f#K_eMXv=*6lszPNmr zigqJLM6=^8*q51j9;6TrCIN4_8Y~p)hRx=(#uMogQE6EgVT;SZ!;kk>$}Aq%*cGU$ z91KlrrBS|ipz};1kKv~)>_mt`uA0@~>|Mb5wn%JLdfbgH5nED9jaLxd8;WPCk5B^& z<}A?)Np7oBozGL~br>09avAxdR@cMh2kU+orh-I+!11`?)G1mioMP>0DKi#XNqW0! zg3oaO`+DN<=qI`-6iDrg^{889DVrHr7AMz~ag zP7E=92V~9 zB6gptHP8JlyP9%n7E1|4FHu{vNsPu{p=Xo=^Uc)3fXcb)>(aM8Q%!Z>wO%eEw*i!o zVnI*!1uJVFG)70e2@aUw+gLO_SuO3Pksr0Q@yLJl`|HqIf)5V<;R8nb|>OA(l z`&Y`#G1zPFEXi}bLVYcyzDZ43W>bS6;f1e}xGB1FE~IeYo5LbLti?NROd6!#220OM z_{V&YWEqAsYtvcvx43(I%47h8NLO4D{80lAg95{WSGHomJKtv#VR5sZT%$Ew2Hw!% z_#^wm#j9Tx-&kQEJEImFaI1B6Ok^_C#bjQFC5SL8X6_0tZ8KKU%6d+XMs$G$317|9 zKHQ!zh@1+S%D8yu+z2Fq=@lsjzrw%nv(P~t{4hoIqe((UDwt*G4Be_j%DAQwOuoW3 zfn`RmSB~&u>#xP4eaa1XG%)4)sy5wI!{3*6GeVlmFnallvBu~L<#v>N0tS*@`&hup ztYt{%I!th*9(S}@V`4YZKv7#Y?$z>&`v!J!cD9gU?=l}9`#$A$Q(oT4We~J2J2{Bm zWbt!zRn^2;teNgi$po(IpYJ@$#A~82SE8-N`X1tZtPc^LcNn)_0XQ&q8P>DuH!6XV z(TiQBuWmCo9{ZmXng%Wcb6y^wPMsS!K5SLu8(Wq#Mw=4hp;6Gg_E8?HjgpdrK$qMI zfvi1mPpCcn{qVMSXjTB3tZ`eH^Q6$*GhHD=2~}U~W=j=4K0?Sxm6!5+je$OsCZ@qB zIb!$?w@yMvzwY?A(oAyOjD)(Z$EO~AM0HNK%a+2A1!jU_0$>WTlT^n~&>V>l)n5k1 z^u)G&oEDxsVMM8w*3ltw{e)(Ey{aP8?U@PO*~l{_&u6NvAJGimN5D4^x@RROyf}lA zboq%oUi=2;gmK`(-q&GJ%PEAm=-nQ!MoIT$(bgya&9}d8gj$WApJLBi{?sHpAc+?F z6)}We!HMTp_!Z+QDaNzGWhaOz=cylm95Va`MH&SDJ}C8QFhj8<(TaMJFE`Ju>};m9l4mX;gS#q+&DjCF&`ui(xQ;fmU_h zMjJVsZY!;J&^>=i@-Mn?5G2v-Xy*IAw`enm(+#GEg;xQk-$mfJ%&Du^ji>Rar;V3( zAKYWXe3@4TkJN8p{mFHSVX|LJvPcr)>9;ak}QBPMpX^UHnJ%b(}dvu7oX2k)zl4VQoE0lTJ1IXsE( zAZ!vhx&hT1-}@3@qAkqU6}#543hh?u-fzGD`zq1rHyfA6=alEC0L#iHYupaiQ)qm|!DM8`w%;a(nkGJ{(I@V-CeE;$H(oy`v1`khC-e!ha zIsTlCadh~XZ>VkpS#Tp-*16`vsGq5Vr3R$c{?tl`y*OAj^K6`<-DGFS1tESJHL`J2Ijk0+mzHTa!7@FUslQpg$6f0etpX-8~QBo zKbLsVsvaxzXKpl(TFldGB}!0gmzS=^QG$2=37(+5W|0F;&W;Uuda-NXBLc&=mgg1@ zH*LP$Q)-1*qJBo^_T;pF*OKt}N-oVHR-KYdZ()IJuJImag)Pr2Ey;)R-eZ>H^lNEf zO})Tfs(>QOc|y^Lf741=bjSE*@h6!b+z#Hl09-M!AI{*a2%-tbD8uhzl*msGVpt-9 zCclxENnz6Zt^O@WiNkE$*C&Z+bg~0lit?51#say6(+xQKmT9S^phH>Pox5c7-KKmQ z_`Xvo51WmzbCvh~wLo{BofR5w>9+okOzoSii5sMr0QpAx*cygtoq=QaZ|_?}^Em@y9iY)#+gYbnNx6*Cfb#h%uoQaG_wF9ON;o819U)AKTR zGyPGgeC$usLj>gZk)>fH@YEeMt}i(Z4;Kn=334Hug>p5et*oqI9xXIl?F)D~P`ZIyIbY-$~V`~@9 zN_k(_`N(ohNDV>xm=*9dE}u+CrJy&}z@h#A=cNjIsTs#>$&YOs_aQXCy$ z*^n=(!X)p{O^m*Woxfv1WBckMi#u}&-F=?6w+!&gA<7g<#$ewsex#@y=ec)5`%8!9 zyeZ1W%_9ak{7HjiY)Sr6c`tyM*bF!KI5#wpyiK1@E`UQlrDtD?4BsnQa;cOU?+356 zY}ZyRhc;Z-nlv#{ahT%0MJ(V*av00xR2$4r`}rb}&lm|l5*aLMn`iv01Z(`MpIn06 zStw@FVyP*gV_&!)!9^RhOvK?UpqH;`Sv#(RMKgQ25u&T0j2k>aDMB5}G5h%NCFO!4 z#V&`q9!YDQEdJ%LB^CF%r?f)#J2`xEL zw&x-E`JY3aeO8XR7bzZMEP-$A>qF+z!QZG%tbbQ&DSbumVUmBFu1d!b1su-(T5V5k zPa7tnN)JSh>yQYy2KLXC2v6bF9dJm%(zp{RKBx0#q2bj!${CWfYp2<&D^3#&Vqm4% ze3SY(jS+VLmz+#6qg0HyO{TC_ExtcNwTt`*d~i9z`&SXyrj_|u_upGakMK>y?$Pps zT97F(l|E&$pJife#3MSZ;UK%@esJxp9=#tRBKl#?(IK8gbW7zqS@K(qU;>xv8o3rr z)^wS;ki}s1b(M8ZE_Szidz|RAh-hu~hfl&fAKFwQgrgDUMxHM`&i7gS)jc6nXK8ev zQjoVLbXZnm+b9PMchg=SW(eMP(LRYFjMp6u$jk@O{t};6GHo#RL1{A~|}ue^HeZlnn`L`zvMs zyY1;_<#glaX=5$fy`kxs^?b|6#$o!x5uIiZS|mnwqp0_(wI?eL^rJV(w~W4*v0kve zkif&&#Vc4<9}fD8?l+t+OD*OHJ|p^|p^Cbsc9}Yp zV4FJ`*)txyMZ*UvT`hdy%XG<)YR3P)Cpa<`X((N15bSE4#Rv?-*b5RJ#M8`f_b8-H zy_Q2dd|QYMymF@5Wymr0=<`7b;!d2W!uTPMdnilFasJ z3Dv#65S&CB|DjS-|15e`;IjWof{Uk_n6mVqVUXznAMG6#UMM8WOLNjg~LN zdzRcG7xQh|AmYLE2gsX{TKY1EFj-;%GQESAC6OuOwy|*OD(?mz5*&I+?qtgku!0Ca zGO$_G@MAKl@ZHtKZ%n)`L!Ue~EWStn8ybdWC5C)}BN%)y`C%~bi7ClltBUSjzHdUm zru{cHin(2}r%NAF`|V)%FP%h>hDF+!2}p0&7yiqGM2X5G$j&;F-lbz}yDyO1wm;%^ ze({NI^qC~mHt_|)HBsVYQWncxqHW;Ve9P;(yb|qkBZgV=8X{e+#5xJGkhdE=^fe;8 z4{$JD)5VQUWwNJ0dEvnlaUT?GIFjF0#{&2j1LScSPJJJ`Nx2GrR`gh z9m< z^yrAW_eW887E5WYXSug(cC>W^h>w#@JDmx ztaw_t8Xko29GM;>s~M5+X#baiJixFwGC&3m-~e|3N+@o{NK9h&PtNftH_s_ zKNAZ6h)jfqjfm@u4I#PkP($i_B89N?a{AaXUhDs*L86yo6rW}Z3PHkx67dNhNngj^H#mqCz{w1LApTjc#DKU{Y!#M#|ZkjWA;Q1Qji7Z#UP(4A*(j^wola zuijvGh22C4_%xQ4{r0l;&;mYK4jL8iuvi1zP4#?QjuCseDBo=WOWD20u~PbCpPLT< zYWANkpKY+1>O>w%H!3GQ=kZy|#0BHk=wp8uCijHEgEzj2Lb#8mXw1@_o75rR*EjYg zjbR;1Lvsl~>tu7Vu5q@_NVm<|sqOYHrcJ z`^odwO;%)+PzuQf$s<5a`XLZ!y=fZCXhzg}(_D03XP{?RkL3tjFiDc?x#1tFNT&6~ zi(xk&-E91}YLyj!N#l_KBT04?O}6zXHuUV}-|h*zI*sC6cK}*=BL^E2^{y0C1>ePY z=!5i=SWDX)o_sQJ`7;9F{w?x)X}?`d>3lT1En6AA6Y}yz5KO$+eZ|&#_h^OGeMgb6`8la<^()Dv5$Q*|GQ#{+EsI0GV9@+n&V?&+ zIrAmbR*2|g-qr1`@9k~RPwb{M(I@EbzVGwCYMXb^2#2I-n@m<{PKzR_KK^33Fj3Gpd>c~u`qJt`4#(ZYyaN_vekfWa)}d0L+NjFU5h7ExzDp8hseX{iPq;d>ZQG#m#Wky(5tqF?vmyNzuy}1TS&{y zp_ww%Ns&hy78w+09a;rqAH9x=|1)VBMCT{6n?GAynoqt?9wjiib1C?8;H#5CLbdsc zU3D5#Dz!&<9o)qv`of1sQz0+Wde;G}6&pY|P**uKF$~7$y-ARK=xHIm$Tivg$R{eQ z5U^nDS>h?-6YJX)WRT-@O_CTP(YT)VWD7zpm%l554&0oyxIBQVJ=US_Wyd3RdKPaa zMJLhwToCl&hVsN2RZjT#_y}ECB@MqK3Ay@tXpXP6 z3eK?4@QaILRD3E^DD(qfs|Lm;X7i@YHqrwQOzU5A@4tHz@Q%~L_i?(~V9F#P;}mB) zceI(8p*p)kq-{+zC5b97yM_u^McpK;&pYEiT+pReGPbgKoab}QT2#spH8}+LEOe+q z3v>zlwNxzeCsj)1XOeNt)YsQqufsn7*PxJsiPN(4ps}tUNn&%r%T47fMr`~>A1!7_ zAxoGl8I73O{NAv6-rn~?_jWsieZHQAyJx|LNb!q_eq=L5+ZeRPj;tFXAx>Zz4H7zZ zL-Pb$x-UDT&yq2kzIR(8X2s*Zc7T5ya*bvkMcGjd5^>Suwei__DkCq5X19zHz6^ax z|5mrRo3P}R$jocvbJJ|$+Rkl0xyn9JHjy&UuOzMVIwklD$e3QzpSn1;-LogMbsn7x ztu3$2w;WaKvdK(c`!~!;69v8vEEUc7>rpB8qv~XT`a^%q=X=GM{-^W#sMBrZuAk54 z4?0@NPoK!f_sU^ATnFX!gKp#V0tqoj7T=gkj7SoLHdYzB=9rG$Z0boxpzoKer%ws>fGq@P$LnmwxO+MUK4j zv>bav1M!IfyYF3(=aQyF0y))1IN&SZW@Fm>rPeRGyD5zPT5C3Vh z3*cNWai-da&~)w0O{M6ydBkNh3F$Q^bVVXQkRVDSP<{}H=jME`P;t1fI$kJiWIUYF z(UVw|wv*F~nxpHLxUq>1W10|o04$SpqcHJ}SDn$+5FXl|9CD%e17-4z=<*E?tA81D zylEazy}O}X7{1#Y@Z09+XCDFAG8s=op74KhG~K-;l4Q#*Cbw7t{swY2nD`&Smk^Wl zQiFK?8hyXA^~{OoUZd$#1QD}QfJaRyc1ONp3}_UV#^815eG#$F#_OkFZJ75GPm|l* zu5^odZ{w2CBc8YU_3nzIheZzlnDcVwdl(n0>}y~S_uiSfW^z{_C9Mpkc%D9|%Pu5) z*HL+pO%a|h%-5qvaYe+a>?%hUB%6;)QDP?XF5eM2n62NM%>MLMx~`AZOp+nt`_)lN zkCjKs=Brv}xI_&^k2F0-5qqs5|JInyvn1=}F<-~EwzsM5W_1hnzM>%9NUI{75ToSX z=uZ}jyBre0jmQjN!*?6%?i@^pH2>$|?@JR#_Q3wCey zyxOPd_MF7M*XY21;sgIsOs@EY(Gn!jH$te2tBY{F(yE!Fv+3aq*Q{ow|1d7LAgul+ zr(Q>&4NNN|HUgb4xu(o_lQ(c{(WMKSQb^H0OwH>Su@!IscnKQ`HoR8V4o%;uDy8Kp zlS%<-ScEoFi1`+K!%22~Ka;F-8uWKY_??sL&1!P)npMFcO1(byr_n$4p@(Iwbvo*m zD>hTTPxu_XS13$g?}sBc0lv-jc`OZvh2`5EnygvCnG6x+ff%QdJCOP?K4a$RuR+YB z{kHJUtD;r9qg*+W{b*APMpQTn97Dc`>mo6t&rQ9r<55i~CVVfPZ+n#WC$YHCI*veK z-lt$P4Iy0VRM`Nf{%v%69SqG?Sk;j2^mt6YDo1##xv z?a4~X!cS`r&wLprk*V9KkF88x2` z5da1oZKN0_-cS(cx+CU?XoFiw(kQ~%8`kP8yB&SWO)xMm~%7^JwKS+;g?(C+SmIM7FT2s^|yI;SdyhNa0!7 zlcs}TCXFQ|Re)rE1<+#hQB(dklQwtE3S7`B*!C zJQYW1$MJYk8A<4yD64#12Mrk)pnA%!eNGyyhGca_XLb~g z8eI-l*U&DKb?uVHJJiFSoRZyUcP-(zD-F$hs-F7JV;@hgYZqc-MkpOi!)YXDUF39j zC<((D*2}(!s%?njSo=KR*!$+bJ}E8f+z0t?qnD-*lt?LOOVF27^`Q4+o?TQf8|ahI zLF{55;{KGX*Df+8(?B*m>ak9FYOQQ-?X@%$A!+Am?NW7#LqXSD)wqo5drKI=SIC}!b+Q&GxZcLWqjpf9&Rnq zw;NPRz?PtN-jTW|U`Za>1aB!2?T; zD%@Df3-V6}$bWOaf^VFpxFKk~uiyqers1tF znJWHU;No@@LAdYpy{IdaiMO68;2CG#x+iEaR?I10`uiCz+u-SNVR>o#Afi_3I>O*F zU!OGFrMf2VD#O0*VBPlxO7FxGfh6Aqu$@YTW_MUv&5@pTwk7;i->aF{@J*z2JeFXa z;=U6aj6Db%@-iM4z7Y8Mn|75(^sXhM$Vl|An_CX6jcM}+ub zA7>F?L_@aNK3lAwTnfeFn2BF~GbcWwMv+Lzf3fe3>u#viDuR&6^?gs=Pp>zgfMy@% zpvoZxHvm`MdQY9ro2lir613+9>%Q~T7`Aj1%;G;-Wv`A3kcwP(e7YzgTX+|lO zIg;(qWRnFTm`PCN4=w&M_`%p8JuuBi4XJivp@x``#*zT7P*V+@PJHVebr;%4&g{wY zQz493hu9DGd!gAXBhZfjqII}fjm5=G^Q2-Tb82SErEqvnPk~8f1UDpCS0iNCS|Jqm zRQq}JJyb@oWQeo1{=jm=ANo~FIj+W+)W8Ry?4E}vAC(y+>5bv$cZvKHiC~9W!DzqU zOE#BWx8ub;dHduMAAx^))uT7`nLAup7LDFd2&pU&52g&`@9C}P%k=^*;UQq}h9RqW zi&PgUjeIRTPLH0QOn>py4hOlZL+Qp(t5tt?W0gv^Ke z=A$rX1^=abe8gGQ^m1jMD9aKcNUned7#|6|1dW!3u`#=*D_FEzg3O4VwlzL-LyR%s ziJtUYtkc@Il?ZW{$xtcxZ-b#ko;x6Jb}EbGUv*x$cJ!VO@qfCJP+bi`tb{U@uj@RY z@A5>Gp$NoBGECmFI-Of)&GY*cu;wErK6^VTkmmBezO)O*84hZZN^smEA--pB`V7w$ zA{&Eo=7+?(R>-ay%gt(K3pz~?8`Ua)LII%dQ-TwHBK??^BZf;aR9 z#e&}9gum~HuzHXXRQsxoxR!x$8JnOv8j{mGx z7pgeoU=+?OXw?Wkbv|8xI3=96ELt40LQOCWd-tBL`ST@5yT>>|lXU9SK3BAcqB&e$ z3QqM7O&Cvb8xtr9?#55Sh<%|^`FP-B5>7`O-Xnc&NVCcO7;p6pGH#LWk~wC zj6@BY4Biw&poi>6kcg18CJ{VU4`hIvvv9#i@8Tyt8$}`7$YX^j`2ms*d;~-N+Jj z?OG<%NCdOAB9_o}sLm;yprngwn71L2_2~X?HLzLq^hSBDCr|Rgd{i2qn8-9jJ*F`5 z-F`j>s6(y*e~tMld)xVUe6X_5{>o|107xyKO>c|<1wZmh^2mIHFBEn`LE-mvASwdg z33;SJBvBjObWUiSay){xdEP5M#G*NbGRB3mFW7v~xnf})BZ?xhB@KXMD0q(d>psm7 z`aVt#v?POuD`(8iZg6i-x?Qi>8ex&Sf2UO_`7}OLd6v+{6b6Y_cqdd#zD8r&n*=?_ z#^mM6%kew`kc(;BUHNgCENuc=7z?HllrT=TzG^mdMys^b&4GA3=oLvNkjxU=9hv5L zLjFOP_uQ+LQ@7icn{Rq&hT8`}7y4jM|z#+SRQSJ?GEP;~@ zx6>mM@U~1^$R-ic>g3R5f3RAg!w2W-2i}gVxkVqDko9Zk;0lQ*e)-TA5>^%qBbkkf z;kFo`CTJ{H%Gf@7TdH}Eae;FtMEQGs+=xm35Y2gXUm;(npMA08dj{vs#E(>Qu;BX( z-9iCmDWZ42*_6UnD>=a86597;uDx+(Cl-UAl9ISJzpY(;>#X^~mVSeH>KcfT3}phL zlZ2c{DaJJ6zbE#sGM&$Mp&&-pMz)H}4~K5ROy z;yUB-$24xF%WHU~Qdr1}Yy!h@{cjS;_vy$3ZWjt}b6B9--qvaOx5b@(fS5~4G)P-s zQi5=;j+91P#^^ehMr*LWt6sI6!ytw1Z}G@@ht{|nvt{CjKUj*z<@z8a3Yn)6@+pT; zv!O&XiNWtg>p#|!B2zW60<%_g_r zXVsXCpWpaj!F&E<2wDMYe19a=MA(7B(wV3}!-=6*NZ@T2(&s&aQh}GQZ$3q#+4e>U z^95Qh^a-kg)=WUUy;3y&HFmm*ie^5ltT}!E?!G_fW;|wr%51Po7>+1EnGiNNuW6k; zy>Xu-v%@aMc296PF0yatQh}6`ajDg?z>v-7G`n<6b_LN>P6y<&Mx$Po+g0a@A}O3` z{{i#K#aQhfrNqE34t7VK>D!O%fd^%rp~<(>X}L%^HW=pcSXi9d_rB&mZZq_948&P1 zlwb=s0txu$b3D0>r&4G(l&cA8sm^ImPP713Mn$eY&o#>9G}uWhaukjh*a8&&b)F7= zyvg=aDQeEi#?liKq5xvVL~ct4oKMm+R*SK*0zE+!OKv(Jp@kH-Pm*X$%x)Fn?mhsx z$6@o~s)GY<{;aFXJW0EY?ca7o`Sf;c?ME&{w?DrwG?~@9;7~?WHJS`W50B=I*%cgP zg+6)qfFVFC^$Vlre6*OYhz!g6vg!(H#}5kytQ@0!<&2Dfe*PS9%X6uTND?XtLy?s7 zw~|!WP|N+aS-ip2TaG9I)S=DCDl?s|mu#!@LBHt-<6nx!PJ^&)puw?pDHWPss628< zrjo-$qfp$any|;{W^h}NzJ8aNjWXeIkWcvlWa!=t>Vr2y-l1bJy6*Xm3(RPFMH4+-U8MS~gkDCX4hOdF=Gu8f589cthU(d9ud1@GKw~7R+D}Wak*O z1ehot4(G2XM5|^RJ051;od?QxX4xL&S?@x2*^$=~B_`z6$b`QzNW<&>tEH*KW^tsV zyx8ib;gR3zbcBbimCV7ILe16PTV18x5X70TF6Ol}wg{NNUC@0nd5EplJooW=#G0q> zgODmR6Ha<8V@+^aRqmoLPT}}NZRbYoSqClMgn1+M!HwSc+!40!dfW1F+CEXy;qyy> z@yI?rR#qYV-B9-jVp z=XwAFw;)FBr-iKQ9cCR-KBN4+wp&4tv%EMP+85Eylv^GEI`Dex^b$#L>RxR5*N6n& z5v!}fkp0Uu)b6F@sj{XqP8!C-!dC8KH4TLk-Qw~lhx^02$5;4Oj+q5qkHQ#13kT0T zfWkq0>p42exWiqC`)ar^G+V-Ew4YXt!oSpPJ`|)Dh3jv8f_%K!GsKTnGBN0?GYDwl z+6~?QNKganET6~>WidtV~oB3PHk z3$BoI!cyIQCD|qJ~*IzUxo~$if1eqL? zC*BHmle+<&nw+jkP-aVzEU3YyEGSTUi&M4~*NU29ZE}~TsmQBsCo&rgfVq4&hX-D8 zc=ubGiy(HrNjYr?s0SkaH@hsxQ#jA{!X#6Y{G-T-(}w#`KR#5aV0ghZMfPs@N#5~i ztwahe7lgQeJhB(r56Zd_bLZjCO#K>#Rt@!Yw`DxvQ!8%DNerNL*jjWU&*`{suW*vO zf2g%s5a5Fzy0}+lp8gGD_f|3gBfJR!k*F7(6knP3Rre#yHy(a0K*i$(Me#tQH>RS} z3StmOL==nBCV;aIm&nxqlJVz>MKDBMVEO|uMriiIjB980fz#o9Uzk%Dny7wl`+uVR ztiP|ts17=J0p$Ko7V?s0dx3TgoeSh0YsP4aF=JD&2pxnYoiY6D?{>O#3YuZ9-)KHr5Va@(%Je~;lH1z#jd%REUb#F+7lWbEn zwgm!5(LoT9uLJ&sc5zN%i6aPxP%27)x1fcDO1o!F232FKX&M6vvD5j4pHA#2WVbK@ z_tVT3phUPCnr0*C_|CExsr{4j5H$94`#^O7_)$8H8B=@LLqYk|e;9%k5|+?0-kb^) zSQG-ApGOb>yQ(w+<`7<8oZ@>~FRgI(=k1(o( zmyb#Z!1DS>^wH&AI*E?wz6XOkbzB3VExAa{qcQ!fj|*(OZ~|;c$0f+3jskE*9L{`! zv6no?qka6Ij=^2eKUD6~s%u%5^N1#^rYdS5wh~YG0cn%WfM;fA2a2f7-fRWrbSl7w zXy)}Iu@|cE4VfPDqI<#6?B){i07mAa2(I+JQ809s+6Pu-b&EnP$&A?S7JB(H$9lmJ znN3OVhk(4)=1Bf!vQ#K(8*l^=d>*GPS6a=bae_2Q3vtgy+Hiutdu2BLR%--8n-Ld* zTg39ZjVmRWVrCXn%8g}`;?Jf3ch6AsQ`6M-z@|d&X2Jz)EbMPm9#9MmjtH5XZh-=9 zY*fRvg#g&mJXV5%=QW}G-MNwb-JlVl@4ENG#zGah2M~M&{hNHgkK^;YIpz@nt`M;E zuw0Cy*s*{+P|cTvX*Rg8vmt1~`S({y0 zt)C8tzaSpivG@lc&(7_ZGrgU}t(yV)E6g8`{&xdhEUe8vHFdz=uZ|(}qx1Sk*NOaI zT2xm?X{v{-LiD~s)Cq7q%w1n!GhfWitn4tH7b=8dU!&fLcf~7>Zhs%;cxOFpKKk1w zKNadIb*xy2i?%}6H)JtKF(nJbs8nNAJ{aN;2-sgM*RETOB&l1SwMsDUJsbL|``a8n z{Wybu=+AG0!_Pms0oH>uiY=v@6x?u$sPgMV`811ui`n&OS9}YSBKF_P9GVZnQ((3( z72|=?w`*emVj9(Tb&ZE+o0nNu(tb^b)qo-C?3qMiaeIWt$qR47K+J3DNXZvOL(%jF z>u4UF`w~F^*7KdQ(}m>e@=;}i z|1B$@+3;?UB|g}{?Zo3+!ef*H7DHzkD5yOWncbuxnuB$9BSSTdw;MbG)KQ%_8Sw#y zdfPzol^HD_6=?S458T)Pk_|MA@Aw5mIlY6?LZcv~Fr&pW;O&sbjR_jHKohd@IQk`{ zT=#ly{6d`QuB4XfmkWjz4ywaRrjfkY99nf-&+O%YQp$7h-0DNPq;PKbsHdEj<~vPH zZWCeMxdt7xJH!pIlZ4Akc9oC$ye)2lJ0rebv1JP+pn72A;2dQOJ^(b>9Pj(I%<}7O zpvSVX7DCy!-~Nqa$FBLBsPWIdt{KAwDd$2{Py|tnECFLPI+&nM*klbiM;ean$ZdjL z>w<6hBjeXN%-?q&k7uXpq#2BtJKhH@+zInUafu)eWKxEiw_qSNd%3W;R(3-Nl?*tt z1bZX@@8h{d!K^yks3U3tj;6y~v#SJ4&S)+~)+&x)ZKPA&!}wM;Fm9A9xi`J~fW;6A z3CZsK*boqEX5yJs1P!kTjhgpygBERp#tjCZVOl@gdhaY(bW}=_ZE%}XHh(GIM8Bf0 z%g{XF%!XkfuN)a$s)3|B9kMU}qPU?7*4` zsv-hn#u)qT{J3D?6iA)xEz*^S&oW>o%ihlmzH3^E1W8Okn=|d6gL<&Z^Z*19`;j_G z6&7ySZv!y;Ue8Eys>&Gt=LsORf(mC4Wn~5B(wO7i1@iYJ|K**y#m(WYZdYap8i2l7 zR5Jaob_z|-v8w~P#aCFZWwrL>gq$^$I1YWBb+IFrYhJ4*InVmHdrM6hwvDzcXL~Lc z;!7zO<*hr;jjb#8oof{x&k*+~tcBKtf8_V3h3oCZlWVW5K1iIf$;;ahYZ94JK&Q@| z*0-1?52bz{%EVF_Il&<#0q00z@S>R#F#kb2NSFgi8*&mp9!A;LKwca&M3Vy|puzO7 zyA(+dO_mKVyykG=0~(F>owC$3rqSC<0F6|t*ptC5e_&s(dt^0oDKz^Jdf{u6{OGRP zH^99LM2XW(49o{iX2oLb0IRK5yz0YRI$sq{eo1_{HoYC!%)+N+D}nj-qzV3G4nLHo zfSvJy;i>)oajaoirR4vho9htkf|WMUgjjIK+C_oPnsD4wI3dd_<6;e;jfI`LQVfnXi*OP*Z)G8FT~vQ9eedFI z-)wdZO*1tCD_HzgQF^|TU_}egFF+305Qr6 z^yh?#z!kYTSsQ?%DF#L<+VjWCC{THx2ebntBW`}Qe2ed+$lB#~l94c#LeiTMGh(Mn zL6IcPXG_}swLjirQy1g{2Tk*(felLhWBvDQHv4v(`B)Jj^vmT5GHfFOfw zzC((D6Ib}oNkl1H3$>Y`;ot!JgVG7O)~mN~?dDa;b$ zRhKEIUp$mhP9JWL9ldUke_2(YFs(ug1;__!g=ry&{{QLq7%oMHWtT06pvpJw&T=<3 zdtAh?)LArs^I9dd?>JcZ*uh$hy#zXBcIn5Rfa7qXDZ{Q~X$^Y2W*3!N{n6x)0-xH4 zQ2mY!>-JoEdXA4we~WCr#^u69XDP;33qlU^(uyO9%o{KfOFQJkxBr2|q!rkba1YTH z87f()0uoFwOuY7Tj_n(%W9yZHLs;qjwHd(^^53c()#qc6>wcq+`dDVu^vHJkTF;usQ7~FE>J6% zq@&JjBW~I$gVh9$(;tjRT;IBQwW~<&;n03{Dg@C3b+C^7VrZEw(`?Oa%M9H2N2 zCbM^8(X52md6=T$e9rL5mC~LJ#4Z$V9`Jh_J|~>R8b$nX*L-v~jfX8h_FP0UWvw0= zF_Bo2LC*Cny#EG9O=FJ#>QFA5`C4HJ46)ge?XfVQ76B9^|5w8$Q_N))jMHiv%I_vG zn);r<+wZm`P6Js9U*;P-_CNqKdF`so-I%@okHQVN)t_~qYrE08k$8-UA_McCSzsE64HPPvWV7yB`rvI4jZTptIwY-Z!aRl%z77JkmE)-8eS@iOTii z_QYMt?bOA-?YYHE&-{{H(0h;qurMiqIyyUY=NnPTUO8)8Tcawm2G~J^V`)M%eTPAn zm$_{p)n5h%5}2foVPwsy&3z zF;x$h7Fhp_QeA#y3Np?W^HJIqFo1=feoo)4yirB5l?E2xBtfEhsC?HI<@a0&K*rC$_4CJZWTT zLaZD>C6o3iEm2k$KrN5_mVG}@#jE_G;w`XWnQMuYP0h%ulK!rzqbO>7n|p=n)eO+Z zB#W7G1OsGD{kS5I!pU=@p`MTSk!0k;jNInREfhixts6rM*-`eL6?G7|)8&KvhljP{ z=cLo zXkr>$F%v&~8(dfd`%ejwB`Ev}b4CC{PrQh2$1q9dTCmu(@2e^2i=IzleF~`9JY_X%)cB5f!ES0mD zO}kc#cP%r|nl1?@UR$nWlkK2G_wS9b$UT{@Ac|9nprieFB1^B6OeKUVNU~~cs3^I1 zCnsvJ$)IupugfXsh?OpE&<8#ha=HfGebgUi-wGt^I0Rg+wQhErC!o*I6Rl)sqS@A( z21kF!)5^TAbFmEXKDW)kmi^H4(B@uaHwZXv;B-SH+}rhk+UrA9K2goG(*b+5?ZNzy z@M1Gs99OzofSRbIVOo(?T^L0(MKBHn*u&R&gd4qGytyb>5M6!pqz@e)uO zxUv1~CET9)()!`7Zz@3*(b^eEC8(}qalEJfeN|P;AL)d3l4D)gyo?edIwN1!BHGF8X8H#5Vp14AL z7rF1hG%0qr-ky`Id{s|*u%7aeFm6OSuH5u+kvU^X#*xjIF|>IT$cBV6k!)ild!x7U z^Kn`wuUz%3?AM>=I#wkbQl{pZ8#v~ zyQxp?T>3oBRbe|&jf9NUb4|`R#m#!kgwU{eljN80vBS;A$|_J80diM3o>XID#cscu z@O@V65WG%;!{LKr*#u5oJ)VE{ET)ZBcE>V!SDMX^h?ZJh%SN-oy2T3FG!$7a#W?U% z)D{2lRZaTD2Vyg-73U4#71}(Es`iaXKbJGHi+@-Rsi7T3A1bI#uH{d({HJS`iyqEWORdql->O$O@iJpC!X%d`|S(pF5Fi*^Yc_NIqbAcFJX6JzEHm6R7fIsSs72CqtaR{CU9sKJrFtap6@t4v%ss@ou zC+_*F+6{l8D9ig1Xb6}LlodUjxi)5;-#jr72GsjDJoJ(w6+5vj97zNHi5%8QlNOz# zb50EI3wydp)awGii@SwAITn^V?KFJN>-8kk9{pl6 z#q2r`vNG>iOU|Ma&b*;wGo;3D~Z=A)l6Y zUc(bORc6=D!8RTvSMYi!f*d0sJV;VBXY6Yh7@>#JLXu+Z)O&G!bb1feyb-pyv6*fa z9ICLwUbD$9Rk~>ED{X~7G41Zwx{}NOrOE->jpGyM{}eFJ;h^A?dbxOjSguAKZzyHb zt*noi$n9IrHoOwFo#GUAv6|F`@brOUR7A~O@5_|oA|*SdMr#t9CyygWGgbP1>u$Nr z^3vy(>$bD>M$uLy`j5AMvR<6*Bttxo`=~tTV?Z17fv5~o2uArun$V22Zb;yyUIu>?lx`=1oQ+#_IhK390wDqg zbck|oeO>WFW_f5PW}UxV1YU$Ify*cN;?P*=K&gnw@LD)<@yK8fso`NQ&2i55o?uMSP=mRlUF)hUc#<1_>^}N70-J%wAdV^q8%=KgsA@E{9 zancf5oIAagJ4^OCBXd7nNj8}~cdqh0t8y9#(J@B1156H|#Wg6q}bKB*eRk2n+u_pm%PH9@CI!1PZtMx+6n?G`GF0jlIEX z&77oiSW}`+jzu2!MPRWezcv|YaKL_O#xO=X-iaPwwq zcz3AxqR|35j=64+o3H-CFZsU(Z=2Z$20G7Ozm|*n=DH2DlVuz6k4!Oc0eb{eDS8gI z44q+_n7?1bb41k?HFM=9Xx2B=^FMOtG|Mb3d=-jn?~b>oqF%q*kff8>D>3(;gUU}g z&^g2Tuz z7Q$fUyHAC_ck6k{@N%Ou6QV;p#Mu-P4bw|FJ6Ij~IBtn)xxYEvs48gngC2*BD*@Ek z`+j9_e-{uo7q#=-EWST>Dt^u$er`1+x*tj+|NM~pse{b%)(mUPxaxbk=tQCwrRh)n zc;Q>{EMc+3u_571v6XT;M#7C7-n3slYGeqGRNziJzj6Ft3rc(BfbFRdqlum^tjoW8 zO@z#2LOfvh04r;4<_a1$kE2+>3Al$k$JuL8MSQt2?Qx}lbiBUF!X~gNtX%lkcB)PW zifdJBe4eveImTR)+$cv7nyH|87$~1@j1zUW(7FvqIyVtsQDZgr%{mW+Wh!k>Gsg(t zv^c8m6o8HR_ByxdKDI1zh;w_FGlkEng8+ARiVSC$H&a`Zhs0iivEO|&MkRjg75S?` zx-3%z*Rni$U`SqPb>eW|vN)oRC39_O0~Au77%1acz3aG{%4Zg(lqIgq0!_8DJP?EN z^RoaNPrTE!L^K@r6k!oA`)@A*@685k2p9mjJ!845K?v!_v%hzLP6Yu+>rAn2Qnb^@$j-n zJW+H2SWyg!8t>Ih7Y&PaltoKoVbh3i{qF1EGSDUGkxlkdIr_3TwdaSwR*2;_ded4< zGutT%**=}Y1JFCN2y`6IE{4l`vQyj*1uZ7s?oI?T?P*R7QPpFLTA{0@b-RsV z{04g|QQuitsSc~?bN%VX!3xbx=#s}D0RB6pW*fXUR!yF^)7*?7;$DD5dhuf?fX{wFp%f| z*N|&!qj6MeQ4R4F#tR4ctHmu}H`|I!+gfm(NwnHnkOBTx$Oa1*JU zmLw@cY1vwG1z_3l9;Mz=Jnxn9+9JAp zOZn<}{?^Iw8yMgfKAJK3_Z6}T_dtQkvhUZ|?AocH8P_T*8Dh-6Q0jQc)nRz6$H^8+ zDX@$WfWyjqZ$&vx5WYE8ZL(fdJUWG>kWW6>{5j@}E3Z+sR#-D*l!krDj?6PaxmIpW zJkPQj$`X=bE{tif;Tr8u;WkN`E3MpZYEHxP`*Dm40byOE(>Q12U29DDT<}s&kuMK^ z->Nh83OtqtTa`2NgiFTI7#NO4!`z2t2zpZzBHXC+Ng#JoZ+MxViPZ12!a|jnn4H1H znWe`FZN(a*=Yk`4qR4n5pctAmLv14%QT0~((0Yoi5KR#Uulja7VJM23G}z+q8NQbJ>R%vqA; za|w6bFP4w{#0iDKpmKj_mv`S}qQ!gt3{oWW(+aPc-a01Ui?(sJji)DEf1sI5HyW17 z^6GWG31dy{h$%Q%cx43)Tn1fge5526WT02~yG8o%m+JR4+|X^R+j@&YEs)2@{pU2w zP%O;n&fc`6zhg4VpBF;ZR7&ahhShxYaPn;yQdJ<3>*~fnM?o z8y3s+(V}<~L>mzau?=(-YuBc&Q6i+rA*GH<`tQ%~eYY{?5?3x0_e4^4! zJtMs=KPx~4Id#H8u&h=(aqY4Cq{#QPs?Uy>Vh6gAHCr;kIvqyw*}5#Zhk0(+#G~^C z{S3iJs~}&H$Wi_jjM@{-7r_I$5PKKYzTS@6643O7M9*niVc2V@FCL}FJ@v2Zx~IBD z3E_`>jNh|W#f$07pb{gda`+}#Q*=)D;$3Q4`57f7u#1^6RBw3<{jvqo8Iie9++^2z z71O~dBQW0Xn8J%$ykh)TKrU9hL=1?RXQmvhQ z6V@%)6MNM{lbz#Dp5TI=^RPVsy8JPB1% zkXiM-b1nlI0?(yAjhPs?Hnty1c0Md~-MOTT#^d=KalBix*P;0*!op?Tb)q}DC@}M` znVxJotA4AGfJWSy&%Io)_5H?iJ>;Z|Mnd%s!pI}^a-#72^TSGr;dKf@f2n6u6Y0;5>pgj2Sb=fWFOV~sH{cRw zmvw_p0uFRDhIfK_S0v}50IOA3S4S?*7v1jw)VOoJ5T*AA(asDM!=tCkVC#pIs3*Oj zK;`(^y`%2^#;=nk|JANE5S5xQLohE3ZUh4JaNPp0N)0u{XAr=aPC_64@aKiaLT9kS ziN^<1+(`Gz9h$(Gg$y}woY>N?Uk>MKi@BBM!%);F!psWI z_#TwJGi8+wUP(W&US+K$f)uOPa&qdUSac$_6lDsW&)!hp6f*cZZBV^9y%+H{EBM19F%>Z3;*0md{9vm-W08f3amLT~*2C<56UfqmicM*)qHIUH&G zG5ON;+lIk6Y(mjsN*D0lz5XbJ%cUHWEM&ZSqN1;mQ?KH}VVT#(F&wloGajo)H^_DW zbJc$DPIE>)3sU9Y-f2YU{b((kV)2n5iCTF;aY;vyz|oPAzsRl;*^q&jJB$2Ijn-S{ z@+Kt3o~$O4fzBpJxKnK0H_)os)l9nX&Bii_4t|^`FDi_=A+VWy1lYX+aKYioM8`qe zFZaVU>UQ_{SE@ieHTSKfNhhz&NM6@%u?#q$>ND~woT?r$*sQ?rURP?7gDn0|uNT-h zA6Ii3_Zhtt#=P^9b@_|mQb?>e-6I3mUXd0Q(*~>dOwRrE#15<@YnFd;ID*fXR&kh_ zr$v~Zf&MnMMyx8#22DqL)xapPJ~vTf#@Ew`Cb%fB=(o8}=TeOWN=WGAR8QZA9%)t( z&S*s@DoG^x$6vn(7bIDLEcH^(Y`%FTS+}0kS3GJyG9#B<))QEH?TunDb4)vJ-I6%e z-nk~n`BQiF>DgbaM+FAwgk8OHfWB(`*xhyh4XE6^Z14c-G$UpU+JS6h@%HQEl0($C z7Hbq;GCH!g*w{jG(r`9ho^MnP{2tOaz8c#wM&`=adBNo6 zCYJ8(Qy5AivwC$r@|MLury}28zI%TY%0M~f#>Oo^ISFGf8EEOB9|#cbllhIvy}Wmx zfr3}4P$fE6KR_QH34q6#o6DGfaPZsuZY;TGmCC+KmkKyQxBAha%4{S$rVITW)0vt` zY6xW6P#^<3GOx|3Bh~CU^5u0So*$l4LdvqYKlVSP@~df5V?Y|U|FHa^Ct>Liksy%e z*_Wl5w3L;B{(+>?gl@HgkrMhT_PO16teEQJN9dZu7olQ|x(HYyMd!<+O**FY>g8v1 zlBwtC7c2D}lPj~0j{7TqJj*{~86B?u%Yk6*U#ij8IZUSS`ATmxD0#9%ALyOGr}4Gv zUz5`fCd$+6lDVPou|)@kivOp zKmuj-Zj!xapBsW2XUW029a_@Kxk?8XL1zQ70wpkGHj4>$oUSl!J9 zSg;JVotP{mBi*zmvAJ?B9orKaW=P5H-VEm&!*Wv2R5*9%RS~`4 zHP0adpZw`rqW$TlZ$VnWf3k_2pkCc)t$=K$AXzUilBb0p?K6F6_K1@*b$A)M8WvuA zpl~HiKKz&<2$SQ_fZHDCT!J$rjClVuaW1QMiT~wWJ&|_D7Q#^LIPX3rA;gAYsQ`Ii zL^X~5Iu8U<=SDwy*-^qle6Vxpq2~D)$>6c31*+trjIf$N9kIubT&kz%WP#3c>=eP| zbdT~IeuK&z{7VFS&(NrS{2WGG;g(l-4`nEmTO_KHXZD>PhUqTtd-Py*y@Ukfu4>?Q z5RNY@c5jJ+hR7m26MQ9fVVTSziSz$pc1V9-S%Do-wWj51%XgafoxSwi!H?&elDbyz zuYqwAcJ2Mg&-cFQ)fK`1H@^Uf%^$DMt`F-+XFL?{R^4{FUMQ33o3U**(f-7v(eS)b zDOKk*{b`3pclcV)=IJtyJh>^x+snJaF$K>>Ex z?0+s-DcrNQOQ7F1lT%s)950Tys-zLA)n*Dp)8^ltAD+Lte6ff#W^}buyD1g~O>p7E zpOq9c0kz?8x3lt1hER78h<=LMx@j5W*GvKlWcm}QSZExUy;-?bmV{CubNY_mYIyA<_L{X8ZCoe92*HT0q;_edR-9 z)y22DD!@BwHk+2&~CQgWnH(YRQH-KAOUYQ=UjCacVx~GaZhB zw{`Tn6_=ci4$;H7^_z^dZ0&*KLF@CgRM)vQFQVhz1caROmVFvs<&nw3ZSsOc}%5yQ6|8tD)Z6-2dQ{A$B?)e#t((_cm<-(P6fku`rrAC%nu1(%>O;sg>+5%+UutT`>bgc3R?L&!CWvrp;q&F?C zuzhMfDeC9ZW+~B?oEDj#&s>GLZhlc7B>+{2vCq~ze5BLQQ-~rgGEjGk>|I%ID*WL; zG=EMj?)FKd21N;JB6PI1wLM=;0?XR>mby=*AFEXV&bD}7NX)W+kD_VVBDgzb2=Fj@ zqeAwYsVOkld%`kfzr3FmHD`=bn*_Oxx@sS{>*2#JB`svIrtKt2mW|0UO0(hXbJ~`} zCARUX_$urAvG#8|uWr{S9aGtb)${`##%#I&Q)!`Ms9NSTVrItq#*%c;aN) zaA~(Gk-m9$7XP-%+&Kq!wn>fexcUyGxP{B&T+p4k@=*%F{g7O_EVzMl9>Nlh<?3LEK zCvmSdV=<-xr0H@dJ9EwIp!*@C>Tw92H``A8AN95L@5QV6tmcoZNVEDMN3jYuln`Tn zB4LF+k}QGjazuxEg+*WLZz{E! zNYieqo8FeKAm>hY=DNY@>+|a?#?##uj7HeeXPv8~&zyQS8WS5LVrkAS2o>G5)l{>r zM0dwkH~?fz-;~A|e9*ur(4ks8d%edi7LjG6h-yKFUIvGeKx7FUi+rD%C!;@*`Z!KZ zbJj1^_LE!y57ke6@Fk=c3!ELxK&|*b)C9k8Rhr$P-7q1U1?v3{oW;h9q_@$xC?yI_ z@TBLffDJqH;4Z!LotLK!RAGibrA{XITDx>rafg zDX2Xt_E@p_`tO#s>m*8t;KO4X<(E^o%blgj^m`2ZX_|(IC#u`+%t-Lh5)^rYC2=4CbSW)>vT0V4zNHVe7{9dZ33l-9%dNu$*Z z%(%U9Ag+yxZ!oD=e(_(lSpc7Pk|$bhDDbNq>&Uqy0v?N!wK%>?hM+F@P+x+wD1qgF z9)>?Pw}(R%{)}BYbLaivH${;Ktsku+mj4mmJ=rr5eeMq?T@fh&5fw>{qEq;HDI%o80M zN?L;|$6AaP6&_(Cde5V;8hWEW840Jc6{Y@!%0zoJzmrg`Z0{Gs&AiYe0wI#h;rDyL z`Ve10{(z1OCLlToKxJj=Wp=`0H1m0KK*yUx8Q9^zLJjPrZ_k*baedy)@Sf96{`XzJt; zyqcdd@6@Sbx%&lpVK8q+c{dk#XDM#8@0ri}$NCV8eSOv}GB=)AiOnZId4B#~eROP$ zQ9ha`(YEcX$K~SLpObZtibov>pIa)|Zcpvb-a$_SQ%dEPWpP${)bjOxdZjKU3zW^IQpsA_mV-) zMEk#v{$mW~uX-`k^3@v8 zDM*F@42RldVf$c~qld0;@}CohX1;d;bgQYO#qv~?;x^p7N<8Ni$Eo^h^auK;C5obu6muc7}8HW}{(f{cLSD%j$}zwBz7d)OLe(-6vt(Qf+2c3rqlJHzs^#kxojt zEKJ8R@1#1BhI(Q}f*Zqv;CwzRW}x)=7{d-tWT zY?-mqVQ~ne9^4X`wa1Mi$C4J#Ws132=I%7s25HE;JQO{FpBjV?`^=@OY2_Jh8S!pi9`+%9&hEq=+Q0 zw4>Qa+I2RuU zx^$R>dB<%(wy@`ie-wL?@MHq5K0;)?lU`(fa`QL>b0We}1fs{K$Lf2rg*3Ws{pwCb ztwSL<4gtvUG|&f>3>O_d=yS^$EzsrsB4;O^inx>^bD=<&j<8Hvj#vw%{#wf(>)I`P zl_^@QUfpc2-fcrYVlX8Glo)b|*}~Lj*9_0q3M>ybbimi~a)Q&3aTqwwIC~YUHby-NflY$zIb<)Yd{H!q)R z|3cco6grwf|El~aow-lp>dK4cqb{V1$kqw8Ol4cReg9!hIC#LvDIcYlSW4Ru{8jaC@%Ed1XJ zW3ueC3%1gnlidYr^kjmdd7c@=9m|RGSdbzrs;egx5g*Se|CmgS{LVv+F`;~3)~+^4 zBo1uzOEl=9+Ft}nt|r|9kE>v98ciF3qKNUHdr+<|<&sInEN;xP6GJZ*B>Iq)i7?wokR{1 zOS2}igF!yQv{j&#R0+6)ORj8222lk&0(0M_cKMBdCMB{4r$%fs?B8Onp{pH4fox4j zcJPnD1hZliHd_Asp+13ekzZ!2ds2DH@Ju_b0N@&9D-A0e7oQ%YNi^bIGawuZ=CRUD znzOXx6|1P0rg?r?!VHZ5fP&lnPF0dNo&jc){mu{1m{p0dc4-6OR?9_$1^FWQ53oTM zRd)R5J%I@Q?~ccPm44-*xv7}FuGuWN_6ZC;@h?boDPtP?@mugbgsPX@Fbzo$`9p&-q#MnXzXhuOM1TR)C!VLk#;-|m> zmCLS9r#9v(K5JOHt7ZryJowcn*07}m&%>Xdt z`!G4^XO8Qr`OMcjmK+K7 z6HZHv-zHoqV#@4L45JKBr!u_KW>jT#H{Z`Cw+JsHC+^{A$bFj4KoAHLA;)~6ENd|R z7nS4(m+PUl`I6eWV*zEs$CP?hFX{_uk`h;B+IFF4M29~&lC!+8HN9KhUg6Vah4yYk&mF%Ss6sBzhU+FR7gAa@n>vlyjWbd%J7H)ug(10IGPZ<<#SOUR%{3ld5)H~{yuJB*LC+Vg&=IFX*kmcdK30*V@<$?yGWO(*R znrZ$Cme`R2M{U48^yt8n9u}7p5>`n^;bLEUD-PqsIM)3UaT8Bt%MG1YSZyU~G&nKe z)W4K)+5A){8Ho4-`sx%kTLLBFy#a)FlgT9O;q9zcrA)D@i5|yTLf7N zx@OmtN^QxzXb)lzrtE)U0**)$NM!x!8#0kJtXmGOFv^MmQ)uj8ghVP=-m?AySLxD_ zo*F_Q5BvW2%VkNIHV{sSqL3EI_`|U>W^gI^qjI*=@UT{7g!}G^9yXUWyIw5U|MZS` zG(+@DUKwws#EGr)=)~ZV@$`Xu{Fdid?c{QX>--l)ttleax}7)|K{axl-ku(BbK6g! z!2W&#&FPk5q)*J94aTL4C!hIg#Sv~shP~xx@65IW>X;|Xb>m5TRr)~YVZ77U>asmm zEkFO`Ab4}WRoi8A)*zp}PF=_l_Xn%>D~(KkFVp8HY8rM^8Op)Wtp2Iv8~4AD+YA)+ z=R|^NE1vDsRCVm3G6=DuuS(;UfW-8xT$)X%Bo!qYNNvlze+Psm#9xh=$LR1!?SQa~ zSNBqxdprm%8kPj>U)Tif8CKShmM;YZlHFd!((rU14RRoFc@%BUP?{>n#dP0*2ap6v zxA^Lf>WbV8=gz96fD}Qqk|gIOE$!aD1bwO)(2WW~Z^j>H==>rEv`LvFUDs%M${cZ@ zd$Z=-TwRLGQ?4Evxl<+2$i0Mnt4CVKQ^FQ>Vf;D|n!nJ)Lf@vWR=MA`b#fg8i3bm_ zJUXRPE-EkVduh&?GXysM{dJ3LC8n!5G_CLeO)H2~Hh?7i`92SLE&`K~0ABQa-*`i& za>!46nV$a~NQvj`GEf!%$!x2A*-UsXFEW7ly?f*`Qoy+~{KwWz{R(i3B_bsL=qO|^ zIjFeKbh7H;kZ~s5ZmK3XE&A2HO`{PATmN2s?5UL%s{K&&XYMa0+aErr^Mtq6JbVt_ z*2^Acj)?na)G?-H1l+=;G(Dv5EwYi1>M!z;;1bQlLM#UT%vA0n=zH<@>`T!Vldo8FHv#vOQmgAu+qRmJJg{DKjb(j&I9AB&{31+-`ipM&wQ2X)gEurFq5P!) zDl*0Ry>)Hc7tE}%bu$d~8=f|ZzyW1)ujF||Cgvd;OWSsmJbZU=a=z7LB`;b$ zj!MX;?_X^|dooAW=eBZm_p^6w_F`+0ZE_;e^XZmN%h%H)ZAPgH7oib3`l)AKkWs_I zOm-u=(%0EZh6<_v{=dO|Jn zT+D5^xtzoCyLXCkj?A~U9q7y^Ehlf}TrKE9=iJdG20T7BBw3bw?#EsUxI(8jHg93O z?){~!gsyH7C$l+;-v&8eU(3F6JcO0&$7e1nCeT100c&d5(E8K?tVRxT=`M(aZNi|& ziN!Q$l<68>nS=eZUMayFlp8`n3=o3C9H9y*CefoK}VFIOlcX;f4V1GRi3JH(4eH3W*5 z*?VhA*AKz@0hF9o&)hD2g1=7=C41E7ypcpCe&ux~ICDGe@!O^iHFD=9(QWyvZ3=eW zW9vGa+0e>EJ_c*5g?67mZL^aIS#JHd(pBb*WfbTk89%;-h8h~1V@LvFgU%CAw zBj8_n2Z9YAlm2S{bA5HO0_p>G_7neVj^OInY+@yIdAM@G@^m<#v+0L02tV&m01DzQ zp=%R5Y3EmwVig899WCUpgK4j@`sW^oC3Xyum?0~HI{ViyU>>6DR2liKA#){^wxtF1 zj3FY(Hf*0u*b6y%Wjgy>@VWN0W}EJSrgsPF@UAMzXys3zb{;ctVI$Uw<)=u;PSfMd z{Q(|c%io;t*JrENAhM`JcXjUrm0pwWmPR%4?jj=vNbP=v9sQMJ)aw-!VH0Ni@gr~) zf48;ywrm8y*%=@GiQ`& zx3WY;L`sEk1>6$kSo=zbwLEYOYcy5t#A%3OnT`p8ZnoXeQPJ{nW1=j6WgvN`+AVX> zZ`qIT%y?Q;bE)?A%H4|OrlL1)YA|O49I$2j+7YN?(e*|p-#TTu)L%B*j^g1z8OVQ* zj5~Af$MD2ql!2J?crUN2@*_>5R7e*$IgapOVO5$r#D*;`@%F--<2J7gpvT`?6CKB* zY<>;mMsx~-H~QR>SsDNx=o{6M-J-=Y&srY&${*E1Dd^?pnz)HdFd0aO`-6RZ5tu7H z;MVD#KWN>>T_8w92%)Fnl?o%ln(p>E*@h=(dB@?9arbrbv?l~$5h&W)R_JWEasr=7 zrS(|7&D0~F_Wdd}`7@X%1UwCy8HFJYv=VZjBw+k_7$_sG1w0Vu{UW7pGx+v45&vQm z`mHxaH^@QHp!I}UM=DdHxo(t4vcAs5#ogOTFuR8%;fO1&cb@H^+*GB6s2f)MYu3JIK_X#2u)=E>Xvjfty&dMc?XT9M9703YWr}JoZ^?FV1rW=}K zwo)Sve2N@T?oLQr-4OUA_s#F%(7CtDh?d#6v7MFb zp%N^tD%8nKFnpkA0a>f%aCG1=KUQZm_ozg@f_D+C*>XWuefciylGI1B_i&ypJd-Im z!`488i819XzR1UPb{o#WaA%%fSD0}3=zK&eC^TT|cfTUV`rTzR#`skP9x+OwiGw7W zk^NsFb7X(xl;S9Xy&Satx^m3pt_;G2(Yo*r%HV{+ZEq=cyt5@Ak^~alutjPI~YQuslRAK$awS; zKu>gdZcz9#m@E3}5=ms9)U=;gc)T0=?bebSx#l^2;4THCD*5H^X{r|mxH{Nmn`WI~Q5qk#u z8v&5@yhs~w6qH_l3d0?;Z2VARSi5-rd8~YG*p+QkTDP`j5T}pwr(P52FUJbik${9m zD>vjDpLU)ZrshzqDdHnf0aoc2)%T3r$D&vpt4`}?CL+J9Z)tzZ5_5m80(c;L_qOZb zmhPaQc_C>yIjoB=Zcnv&HCxTp4VkhkucsT^KQ5Uld~ZC_^M3Ab^!t4(akAzYJ@E+) zZS4%#i@6{1^4A{f!!oSz?SmNLgUXDkIT@z^U&_NR(>W;4qG3=7#GlzrK)H^$Z58A{ zndSkW{i5kpE703^_e@PVuXiSTU7$+@&WhLdUn}r0+M)Dkf-!=z_i^NliJWkvu*~gu zk(u`J0#=dCzbl~Ym}@3Bj`XzX&A+LC2(t7iNJn|ILnjm^q`>U3(s#UOV|+IJcsR;9 z`$;wv!LSPGM6rB=MPQ|yi3VwpH(>ViiOXjTg9M`zma7Kq2@X$^tUc z-@0zo2+&Hrm!=;Nk<$1Jg}lF2FPoYB9~fSiUsUc}XqtW-3OFEQQ0%41yznO#8fp%a znU&B_{2?ou3R_9Q)E=>k^jxG=@of4Ql)`hOheXs4zlgTUx(1AtljzZy;^nN+%+D(K zaI5JWg*vOLhiUaz6J&#_qvPWyMP);IeExRbXOfggUi6W|8T^qNtZPAcgcoyz-Tg#6 zXr4-5m!u-4y(FtH6Y$tlSzno9F2bZFmd#BMAI~sv;Mm%wiegGpN&a2~J^WlhQ)l6_ zUa3CK#qts(u$2y#S&4IwgOUe#Xng%k%_}ggRBz> zQ^TK#B2{TVak&Vg<%?7j2v_04D^gYpwt_FavUCeDQWA)3yZ|hCr|FwuI&WmfP5DMM z^Y#`jCW34BW~0#w7!sj&aeh(IUZJnzbreZ0?)fH)MuMdX7Byhou9pY^uzMh2$ zboZl@L9me;;eTPe!)*VKR_FIkznArWkI_|-WvL)M1b||Shs;I0T&_S5OMl0n2#P9W zIC1I|$6%#nJUPnpqC%CITP94oSS~%@!Bxcr-(^ybXiSoDC8BQM2Vn)k$Cwk9;JMGH z41)f5wo-F`FIQgwJ1su$bAu577Y>@P>|eJrEho!rr|?ude=85<_3?;o?*0lF?>xc< z`nlb#AGAIx5uB}`IL#zAhLJezb>40~p0PcDJ;F6pXH%U~i%#p(1Z}I5gDIdxl?|0P1dAO5 zw?Z@JXf;=CjL#nwB>u8I`8;#jIn|(8c@~lR;iXl0TIV?p5VS0CNIo^i)Q~93`99$S zUcAuIfjDgQc2MtCaFX*f(3tz~>J!n-sncr+h#<z|}59euv6w(U zG8kiY!)&Bd^J0zEh3_L@A+x1N2$!pK=e4KvdD=hd5~1Q(GU9U=#hdOB4-e;-O;!El za4+8AzT5Z@ZcVfaN!1Ipg<+zlQas>Vu6dxS=a?Jvyn!>wcS?y@4%kNSE9Mcno^A&BU@EzZB^+u+DpXjg z=ESk5zQP^u#Gp*ng_moSlKDIcM4rAPxe0ouKmaVpJq{a_I=jP%YhXGk>M;p|N@&O<#NCu`7CuLAoCeExDPp1j^3!X_o;Ltfp5c z*3roQ72`skiHI9pNpVCSXj9|gz@0sAdiX~~`|B*5Gc-1`t>(cle|TE1oySKsq17YV1Ok2D_zpEI@4g8-j&y`kcT#N@f|f?kRcqHl~isTcq(mt}7R^XJM zbp~7bW9g91TN(l9#>XniuCUCT_(!J$P4I@Y_TL)MHnKsU{vRTQnKt|BKO6;kXvz@x z`Pbmm{QJ;9DT5%^BqV}dZiXHAB)j(WU*lr!gk^o} z9FSJr#a$qIQvEZGR{`r($Y%EY?PQ#AZaVS9g5mYE*CH$~KejbRT{dHc=H0qTb@f_J zYdLi)M@Y%#+ce+gCl{u+aPf~tWa5VQ@PuYFVA+*;y^|xD{aTsyErsimS5jP4<&8h_ z+L#(Xnm5iF&?W_zGzM$Ir;qnrHC+@_ihDz5SzE24IBrIkri+We5!5_4#q^ znv}q1_V2^~zoC(0Huo6FU-@DvO~_gf(R%GMTFm#}3TRDd!1=?jn0J$40^y#Y72=1Y z7@dNg?EIX(oQw8t>di8a481(`uS zXi6Sb$QCg=w-xMr{6ba+v7)!uS}F=J*UZbZsz5t-zn8aURm=-(u%6``kVoA11S$Dn zcGySwnKU`T?Pr0>HoZz!7j+-jl8_!3FVl@rNJ zwVT$;vPJ3A>)&dKTmj}hR(-FdMCw;@t7$+vmc*kQIfChVpP4}PV0#bZlHBf0ilzN?{Q<8D_&WbxP`N zQj3Pr=7T25d0wKlA@i(2@j$?TN4zyY+?RpsTg5f;uSa9O;%mn73%h%_?u4gYmxZV|+)w;W)2*jYEn5_T{o(Fb}wSZ%mkt%V7AcY5DB-UKFtWunU* zFFQM-4^V)1P+;s(>*HTg-48(LSPrE>L`)(7nAVCJQC!5eQ&GnXs7WAvXT8>xPxWt= zXWJ$%-?{rgVe?D^O+pD899i&>(o(qkgy;8$4w%(~K%0$eJFD>`bGigIvl1qlud>dh z_JfK#PIa{d9DLdZnE$UvuY)@H_4PHV$@171xXe-B9e9|gxPRkyaNUR1@epKSI>c3_ z?d&(z)2RSw_bB+;0htvU_u!AIT94$-`C4t)DVQ9>%p_^p5DX^&42Ve$dKj@k$=Y7T zfm%ZHsbTX4(CzBiLcHpapVoRd1qpw`>30cfe9*7|#`SHl7@-~xvTKz=Q=a`lR<+ds zwyJ^F7WBvf&E8Y15_O56oo3pno+TwEI00d~T{E!{h5KO|LhkVfyn0E~l~;&y_cds5Xk5s;cy@JiAs8xLm}Rl` z^G|A=SnmqxbY1-|hm2c?twg;n$>*ZpCtl*u8G_g2*h*AXM1&Kk(rcJj^2X>d3n3XF zPM%jO9uF{nU=TQy9nDQA>9l+6!lF+4ka_Ye@lc6a=!y3u4?Q1U1f&WK0-0*GEE*g` zT*|<6N{>IKtE7|;c+%gvTFf>sU!dbc1~km7g_>{tr(XsQ&14CaDIfea2jKEsi5&DW zwTe1$!EJ?KiJ7$SPblsYizdMa;S`Y5UD?)0iHdmD@!8b8@Inf{mFX+ktoZqAg;>e=>Pn7*ZV4oV2P z)6fO7h}**OTQZ10U?$vHlJyyw<*+<=GGF_ILOhSo#m-#rZ$v4KjQ^zsK!j^IUpci3 zV&G?_)b@PTI!c6GXMWtRnS@%K(5(l;+mXU4$x}Js(@j7c^=QJVZD&K{0GKGbf=5+xm{SX)pgG>{;S z7ECtpokW9Sbt`|av;HswTb#+p!R#c3IA0;6Qh!a)=jyHd+Dfu5V$nYPPTj4@LCMy;yS^g}=~7S>94p64P2%KT%4R`>TI@0YFZPLXRKRvpWxIhs&sJ zYEXAQCdY|Eoo!YlmL>iiNPxTirF$HZ$`5E=o4^>rFNj;GQXSa3YC$)SFaXcH%r#-z$^JpJWYHgyAkA8$WE%@s+06c+Om>#R`RLc8og=}Wg3$$fXTo>a2<;)hV`6^Ab zBdZvI;||O=9>lyAl}hs>w#|8Y$XZ|MzmTwY+cgC*|1n$Ni0%25bD~T%BphujWr|+P ze3)*DwIR-obIS+N_?sLX*+a&<2bG@x5tGlpuQn`eT@)yW(f)sIy=7RGZ}_fDsDpF~ z(jZ7EjWk0Df^`l%@;|)N;;Z&1qL$TNLT#X-!)B;fcG&z z;nQqJZJM~Vrc;X+1K5L`pS)m`iU*o0D?8@If%x?xWVlS!yJ*ogC2C8NQTTGJw{sY=h zFo?c(@tj6EmY;pLZW1>Oaoj7;3VrDt9dFDeXv$|YQ+13liOAIqfM?q10FM-L=3g%q zgBpf#P%26Q!AQ*i7L0seBntGaed78S78Twx{hi0`!C8n>6NgcsjJX3!QOFMeLQWuQvE4uQnxPQ6(F=>AOa*F z*N(FJE_-4gT%(^M_}X1QnXRpg-naV(vsh9!-Pr5Xvo~X%j@4a@@y7eDEhmI&`$oIou~&1tV)0*g(Bv>9MME>pQTgmWKTP z-8A?{RM$XRZVymFRNB>Se_Hsw5WO+U^47l`TSlZdYwEcTn|>qn{|nJAsK=SNDNAh% ztRx`Sx@XQmn8vG?8O{Pgnc;LY}hfG;tB_wAl5C0(4(B;@iP@b^vDi4u}hxKE;KeMA0S7L4eF^5vAPu zJ>BAJvBO~v0B$NQx7$ir|8-v?9@|k_9Cu}BY$Fxg{{^Gc+`0jT8Sz{qsTGQ~*i`&h zRj%wQX6yHXl?Ll5ZkO>ITh?#gq0>o1)W3mn1U;$@()?gHJ{TyIrj=)t-wLH|CTet( zQh!}mQ-gVoYIB?~j!+keiR!x&<+JrHxvPI_GU$J@F8tpBG#w(A0Q?q@bP{91<1oe7 zuk;aEC_?U1ny*$o8p*yV0vBDQKYq6oJwb_;Q$F>76zig=f6s*?E}0Z$yOWeYAgznmgpTR|6yzLkQC2zA61f6Lfsrw6E#<5q5vQ8TADJ@_Xxy z5-@UEq^ksbtvm(1x(7h%(JSVgw9XBI>b5isTqPgQR+i|xr zLh%s;00gYfP~wSxdtsgC14%H-tPM^H;N1+E1g5?rF-@{>qG5^(FvgFD`nve#%6e!k zlk=r!CF2)$t&h4ZceapUHp|V~MMajbE3a|38LPe=ZVG2Jh(%(tnG_;(n8A(~>lB~D z9E;zMJ8?wfu2vt5roLS3G^+nd^v1L09K2rHi1w+)T-~Mur>bXf17Pp z>lVKM`$AXf(%ih+>~xU;(>tl*F{nMs;r+2=mGm%0n8f4tJ=1%0QWU%)KysH9Ie7o( zDHkC2zx`ED4~d`da~iX%FZ=(69pAEN?e1XR+(GVxo39dEKNE*gw%i5Zh?7eTT@D?5 zwg>hP)Lp=bLCs9?&G=-Ygkr&-5~>>C6LkF+@AK1WM>>1~@gM0{IwMvu^))=HicV(w z%DK13WI+Fqyd?7FSN^PC;ohHm1Ln4_vMM+KR|=GAN>cc{9gnIQtdZH?SF!x@Lp(k{ug7zdez4X zx=ps)!!HD2@>b;;k>0nec3BL*K~J9#bd`j?aVHAkM>IDaPsSFdJFz;1zB&5oi$Fi6 z@WU8LLi8)(*)X^#i;HYR!&HtrIP+%T0X__2Uw9CE^AZ*&7U?{fG_gH22hr9E!m$<{ z=?umm6nQwq0m!!c)Q5-arDiA9oxQTV!35UWr@_X^6ZH8fzUb%&%iS|fx1YCYc_3+C zo6dGmWulK&kLnJJ@K_c~(go1cPZ2cXxfkq3fqTf`y2xTqh@>jF!-!`^p6>e=ZkMxa zZ2-ISWCxmhW~L1`u8o0-E5Hg4I$Ii{3DM#0a{!zPeE07lefofe=zS6(jEgV=t~onS z0rdbGj`XclmSnR>ESUhz!FhR={{*oZN3r$j0PeCllqVs{JNhqsVZcATO&C*LkUF>7 zbGl=NyvJC+0QfvvYM@okll!#`^-$muZdI`-%w|zKVMeGQn?2y?wW)mio+6; znPJpV09qm9yu|XivHR8r3^TndMvRUCfMr>LPd_`@uKpRy_6v|ZmIM(0Zgn|@jtl^z zDCe0F)co7wotV)EX7^(NvC-O-0|78_%#P-^oav)__y=

=Y$0!KY4_~cOq~4*-gU{*Omt4xFRW(au&gl?% zM92Ux)~XIoLa@G`&uv9|0Y<_9zRscs;edlgAf1nXdgIM(?~uacVaJLao08`u|Bz za**4|&=A9x;cL~zRUPuFRwXTONI_F!q|!EKP5$)}2XLiC%_WMO$|vYx1~GPAF+J6E zN1AxHn6F4lc@7Axc8qr0+5<#&z&xeFV4goR|D-_Sc@Fl~6M`wWMgq(@L|aGST1GGp zbs4v5t7;OL5nCy6T=#Rx-}*|FVjeq}ITl~~!ayN@^D40Ngf?l_GxOPcX+1I9(+1)K z->r~?z$xh8yt;-4iq5y{GBmTlFTuQ`Q$%|0u&wha()G_9Bs_J-!g=Z^{#ltPTcgRB zFeg{5r9NpSqKsAJsRa7EJy@~_XV1WZ9%0f%{4J{0C~xCSo|JMoaXVbvopkk|d7~5z zRiNg;g3Hk`KrH-1G!~RlRVp+_?jkw)I4h+E@)&utdQywqM2hb3P(Bx}^VE(5W3*SdALQ%6XWZNhU6|0>Aar4w0Ww{gP!&fUpXa1w z*}@TrD>zayFV^lurJay0fpMFnWIj0hw28H9d_s*^g9Mx?@`+F(_>UIK_6&Nu)m??8 ziP=^_o(f^V82>`(rKm2gAv}x-v1-k-o+fT+LE3wD{QkML-^}0it6^(wMqMzEKwSKS z&P{fd-*&XmKC}7lUs;rE^Gi}O=XXz5$VF>Lys6U!?Bh6xf9z3b2-PY?<-J)MZ0f?_ zNf=D#TCfkbUy3UCeo-Dt0U5CQ7tDR3V6+iJGg$cfU#_ISWJG9X1Tk&N4fhgJ%lGWP z%fJ|?C79Z1In?DVVB&zsOR4q7=R`51s($t0@JVN51@sUOY>ah!RsvyQ3_Cb21e*icfhk%wuLG{x@$q zl$`q2;?5sa1)A%Z%D6m-N3m=8AlHBVy3$Ma^>4b!k|=G5n6_@REp@qXiSlCXzBk1-2t z+_LNkJ-k&OwIuAl2f53rucz)tY>>0!rui!LlwW>?Zb$FnMH>fatq|TB;XX9K38~AG z?88KK?L|8|A=eq1lPd#$S0?z3_oMn*p9&wV-SI3$2QJyhqR(4%)Yr(={9bPHH!H4P zPP(`MXg~}LQt}R4%W!Tp%n5H0P`^Q@vRip3z zk}9V(H~#ar4?k|#g1x89tea;&+% zAzqhT3fZ0gv<9V_;ybDvF*jx%^dwyyXHtVX@mg4q;_1yM|M-VPjJ@_uP@$LlJhL$5 z7DBkgyKbTvLc@JH0Dqpux^DYjVk44f4=0rqWUq0oPHZf;ValTMe9vcy7h!lvo&aHE z81KkIo(6ynOzOVz<^d zN1j|M;7_*o^#G)K(%ILq{2qQpO2>!8P|y>wiE9LU%FH&>)A$Zyi7}JL?ZStEF88s?)@N z!cNPTi-fly~^32#hW??8Nb)K+c~a{LH0C zQ>raNvd)T^#z0*$BCFu0sds_}<@upt^da8)l_ELzpVif46yXackGDT$E?01Ku-$dG zofs2Bhbe^zH`Ri^f;z8nM!X|w6=vmrobavY%_ZLDoQ7FkGt9W&Y&lT(j3a7(OV)tk zDJEfbLDN)!o5nAx<&!!SG%7RCCkUC3rknd7oHOi6^qWkq6Tt1RN_1-;(M7s^+oz6} zz#pL9Q$Wylir&}?275n>Eq$9=a$9r%;qOBgxUEa^jSpR)gfU+%bL^yt@~occYQT=r z@~O!0ms`OCp7P=RSprU0p7KvC{#XU%MoOeO=|m?<_GxcK#PdVJ_Es+7M_omY$3wVm zMJ#oTSbB&vXllz3t&$@eG%ZZZ{#}kCv-7nVJhiXClYJrO=CvFu)#Xga6hm~?OY5Aw2{Lfps#n)xIn!4KD(e_W+r}5cYmWd*@+Ej@(FZ*d}lQcm$^ZNaU4`N;Ob~oFx zdWOZp#FMP$C{X0jNE+3`-v2bkB7XH$7g)>rfgni4DIVtBYMHg5Bes>5`^g3$dS`cs zSX-xrc)Q)n)asq~GiUep0{+40aEU+G19az(@7J5Kv+GtoAfWiCcPjiYB8qSJ(n9o^ zt2=en@;p9_XZ@X!YrL=~)#T1}Vv9?w=b>;0**p(tn19^x)Y06)i8Q>#k+ z1a8*lFar1SHWg`NG|oS>ljxA4smG5e>dQOB=;Y{wX$B8xlb^C_;gO1Y^bPZ>k#;>QqdU z>y5nM)v5?N|9*C_R)blImtUxIY`cv4e=fexDIVW-7~p@jUsm2-iy&Aqbs{Y13{JFO z@5*fP!Js3K`QchRWlM2P9AVQRx#$ zd$%N)RLjq_jx$s~=fB&$TQ3G5#-bdPVS5R3=O`>UN)&x|e<1C^yM8X$K5w5hqYuS_ zU*)~eC!5r~^zR5V8(mfzyd-7k$DfiPUA`S&9!L``EmRK~GhDJhAV~`RmSw5rXqLGV z+I{uQqS;LpDYmPef8w~KDJdPpZhH<6@nCeCxl177x*hvmJtuUSh0E{;|*;=J=}2a1rht<{@M4JeNK@ zwl_sq32SfTQwNsEKL!L}BY`w8x@kjvOkgs`NQBI>c#)r?Nr^#&z_psB3>*{vF@&!} zbMbwN93Hx*h96pJRO;1P>$ZwUJtT$T$!E@n3TOMU(FgsZW+~|R>K4>kCs{{^5h?#; znW9ABK{-I_?0Q(PD@f;m0k;qhxTvDi6KB-V^Qu10JK*qKx}Kh%{LHyKMJ|Ej^IRj9 zLHo1}6skbtAlKy|N^&PGp~>l<%BcyCMnT|SfNERvmBOemaJV zkVz$nIa9shZ6(G#mU96Nv4@+rJ6xX3ww6O|7=xB2wCZPsN-cEHl9-Y;UYIX2PtEwB zANGU3{KgG%;cVrOh@qNhin+jvi%mAYs^(fXv>rr^_(mwQzKZi6)76+9I8?uxaRgww8EZJZ3Oq zsFqWp+s%%by`y8icCkkPHlSTrazj0iI%U$M+?0HXVU|iOrm)_s$9IJ06N$K4VYsKAPh}LGnkepl;8kvmp>b2uUo!?6`1Ney5 zlpEX%(u4L6yZ8XJX@UVn3>|77 z6r8#9KZ@+RE7!ecl^`dyCpZgq`}^Kwo;V3<1Z?X{ip7tLZ=}54WBGdS>mT8NRc(ux zQ#XjEU2wQ?Tm}UEo#V1Eu%Q>pz%MY%rnU=RTmt1Cj~9i!B`7eRQ*j%Vu}e-SwfU{* zk@gP0eqqB6T|`D;LI^iGJFG!|wjxYbUcw-PKnk@gRP24L4L(vL_Yg(EW4Vw+G1XM7 zCuGYlU;M`3(D0#oAbqw9AtI!pkCvr!ETX0&VLt7Bphf>qMP|$TAg7VliJ4G8b-gVn z`Ua3XzLJ>*ywWYxrw@%Vzg(kBz}Uk9wvgnEuI{;G7uk8?#i{U*`yQx9n9~E09kG1;=}d zHS5nKe^NyqlT=@Y4!#yc&+RzK3-@rrvajFo3~BNW|0U(yX?7u3|DZwCcbSNK>wWJu zTs{U+vvt5S7?7m`h@8q`RPPI#337~w*IH!KYom<67s;-@`jt>Fr8q*eE2uhrgC&nX9c073fZ95(*b6;lJqjh@FSV4c|BJ%DK#O~wQH&TaR&dT(tr zDqZN;R8e!dN+U=Xr45pOHQ}M484=jfcJ=38K1&qKw+;La;0tXNwI|YPOP)s56~xUP zc$P*(1m>C1Tj!oLw0l@#O!~>(X1baU1|vW^H_FcjW&zZOv&*RFgKp+z#Y79TyW?fs z6UBqG)s|kkQ#f5^S+DZtcU7}iQF)4M$>NCW7@^PV({s}yZrJl~GyX-WhZ4RQbP#xc zPYP$r5j9aH30HTO2$GpKP%QlMsF**^$${$^I@C>DR&>Y%{0jlo*SxqTTE;27KBoh( z1!X&A?v=^|!$yty3e&N`*X0r|E}3XcrB>5>26!1G0+n%@7Wotxcn!e5w4fn&D& zn(XNd$0q2ZDIp}IB6miX+Ky2{Z7t<9c%(I`c1{=(|v5W||`0|+@ zMI38=CKWkQvR*LIYe?PH0gKp)NcwYHP3otSQx}Q2HCBJ0O7(@)vFF*6b3Y|0X-~&P zpq9L_93stn8Ivtd6UkUX>=~nd`pjRK^%cG>I8si-|v2zL7EURp~| z%@%}%y1=H2h+1EKHisefbn?Jex|@jQ35y!iK9jK>+O^U(zT>G02y$J{YxG2vL9DQl zV{7S{5nvYa_V(HjVpQ-7J3_=+DI)15wN~ohF=xzK%^j-&t~9d;8Wc|=ANzf-%h#l` zD!k5=`nLqkdy90$@3jeO)(lbohw8cy3}zXq#qCXCo(9nt2Ge8tHs<6)epQ2{Vh#H0 zd``1GOM;GJT*GPK#qHD*@AogKU_oSdds8?`obDDQ_cU#Nasesz3yQx<@6jc8_xwKVwQ3V92k#S{in-=6YYs^>n?QEM>z-DE^-?BHI^(bc zL-qE5XW~GnAf0P?mmUIPNk-AKW&3zFk$s~Y2>z*ThTi;79-68wrQPf$r^UvgxD)#= zcryY}P$YAP@E4j2iX=_gP&~Fb_>uQYyo-3GEe#^qitQuc1n9%T$2`Ro>^e_DZgMbS z;g?fWM--+7#v8c0ejbI1mf_A{O|^|I#htt8_^nC}oU!$D z%9Og_(9{jnOBs+9q3WP>J%)!iG5)5KN67C;949j|pe8wL-uI2uNCz#ob=%xe%P7Zj zC0`N0|6}<~9a-!abo^6^J;E&TvhaR%$>ZY4VnK<>yYjZT@;2gnN3SCe)uDyJ7Na08 zC_=BYHkyaeSoT0fq#XeKSRtoBdO-sCu@m%$^)Ns-&YL4?nHm0nAEW^ZrG7r4r6DB{ z*C)`Wi4%$ccvrG3UMD>sMBm3TphyIx5aS+ARofx$D^{t}`A<W2X<9ne2KMCAk~y9=cKN zhszzKSc%EpjY{cRM{n1ry_SjsVkajjS^D^OA4Wwr#OuDhvHLbNCr)TdG5Ic1r*w5K z1ijQ*lzOc}C~bpwA8U-dEt=?D%wunzK~a502H=`+Uq$h*2`r6Y)EK}v20m8*I_+xn zsoY+k7zZKY;bU7j6#8Ma1?Kfve z3wiEHKH*WGQ1Dnb9V~>bj0Vr>G#jyi^+cO z1e&=fiIF)7$ChrpA`&Ok#7x>U38^EWXT`o|qCyN@Drr8H5?a$oE4%2c=^`G;=w2O$ zWXam8ZiJ)0>+0tN|FePNT_QXP(lPf{rTrdt+>x&pIW{3`LM9~6w3(|ER9Idn3=0&i650ZZ=%A5r8sots_Q5M*knOl!wyQBm@P|KmhB+FkL z*jMl4t=~%%N4C8YBHlxq&rKJ+Fwa+j7)3lWKFR!3)Y)rlhbv7BW-8K1x%hHyPbp9! z_)uE-qi8YS6cr!+B`V2v!3Lh*J?f|J?WN-OOD#TngC;!xHYUGm>$+NgL2ho6qN@PQ zF{@hNdzcL%4qrb#dXD%;r}3u7`LBe`VYMf|G+t7a4lB;NCgBgs@l>dxdHG)6B5-Z? zM!PPuZ9cKJe>DHwJD(dRr#C5tZMK_{37)_IcwKf5&ds_@sd<%4dEGP<(EHza{pHf= zSUSeb6s*r=pOH!5O4^TzsT*=g6?0n&c7jtkHMlG>EC=1SWr+IAr;!S=9<^!emYXt_ z5JwP^JLEh@#&2-3>ea>UdI>8ru)3DWQJDe$urLK$&j<>aA0T+FzJ7lncT0NplUEJE z6#`*znGi+tawr@eseQpuRojiNzQT<2GNmA z^_>RTk{mpXUiTJ_p{cL1Udfob)u=W}6BF<@)@3C3ypXlU_q80dj?KihAi0Xghieyt zu{=)0H(>kg>p`#c)Mh+W3>10S)G@g(NBhrMUY_XIqHmYr>aruVY&Q)QuX?m%Psj|{ zJ8wh1v&4O-z1tlf9c!74pBfWUi|IHxIub5+anLw@9jOJ45haBJ<^(MsKBxJM!GYIv zzxSf9B0fnC(*ku?IEeSB+pD-GB~-W;FmnE~@z}%=z&dV}d2)x@k>XnTc`x~o=VgaHH2weWzA97DEm{CV`^7JP~mq-~R zGZ^+{MxV2LGb9+wydnqT8=F5jGVgOTXTZDO8j>M|y^Bjj$a87H!Fx)_91n4)CmKf& zu;Am5uz4~F=hy~w81A7!PBv#b9uDbz^UR6pRQHd;NUXF`DhrhjdMc4e&_y(AlG%pt zuMY-Pv?(Q=J&bKlvLyT#v7-M4&T<34?)sXKKIS;yDO|tON)`$<#@~VsFnj=!A{X^2 z$gJ;ne6o&9z^P5&87`F4Dwy?-A!74?y#Vxomq)n-X~Efl%H&{sVW6;)Ay5^%y@adA z@)f=f=Y+^CT8NLH_t|FfhDF4WE{XNEMR#l+eql%5Ox_OPQ2>(Zd3^@j-nVhbWz z{OxSCItfkhY7Y1FgQeq^Hf;qQq4?*M-w^ajziL4XX)w8H1!Lm^dG ztzaN!8`8q-wJN%Kuq%)wg?4FA1FHYR1eL;HUyNMJU+Ls*ft1mP5#!#FK$*P*mQIO~ z@ zNxT*-zIP$_Qwt+Ik(sr&rxI^%%O@%< z#Fc@3Ww5DwjX|ywMcM5Qmd4%pTT<-7+Wp4`{3LPFRnCGuY}+y+E-5aFghT~%m{3)D zHvAzD>OyIadWwh!#xt6U2NF(qf^!YaST#h4Yok=Iw>5p>5y09g^bDcVQ(bvNE2-J= zFZ`@_j}hCQX3AiwN6zTe($Ouj#@Ckox5uCU&gZ7b%Wt)rZ2be7siqO6b_3iL0n2Se zgBRw+fAH4x&YJ5o&>jm5@7Mjc{49ErEzMP?f?Bs7^gJg*OyO^JAYEZgaUvt?rYNgc z5+_`a)%Pan*|;`HZ6xW%2Z%?3Ln?*|4%X7z`m811Zm0t#_ULg1t5I zGrTs3N4D1N=mWampRB3X(sutX?UkG5 z^OPLoP)ATs?qKwdKPr;=5^DuFg4}c()ggw4x3edh#&%nmHc`!tdh!j{c;74P5So8H zB$Na#*S%i%SVZNgO`O9ZyV0gpjCF0pB z$Ul97+b=WP;0eiw%7D41ZT0UT{9tbiqS}7qx!?Jc&xXf>wI84r)~9AnCy2G@N5>|J zCbuMh!0KCeyyW9Q0f{&&EM?mS(07vaqg5oicTGqHeAXHDJ!wX>!9L zp29lvy;%O^NwCtqjB759E`N6y_*QiBDH8HpViAuZP}qs83d&|VP#wQ8YAglhN~~1X zv2%+&=peV8uFIa8u#vZ;h$yW_Jj=n(>W+DsK%MbN!I*5(|6J@gtAo1&Beqy1r4e}4 zXgVPs-NLU(U%k*=3B8t$Dd#Bs_$Ux%{9v|PuKo7PajwoU-syJGCRNBQEwgl{>?`dJ z0yCrwxwC^hu8|yq`c$5p^4SX+15B&(19;dgUDND%e*QS%^bv=-cBqOrNv!o5v(^q( z$b8d81%FSy!OlQ+cFyb{*TL#w27458CV`jroorwQ0lg0~Qd8`SZ0hzjT{t1HSazRX zK<-?Vdw%Q5h`7hbz>|B!?Tsj^C|)vIRUO%J*)RiT3w@d#?gC7%9RmBUp9=`qLSr@= zQ%%!T5KZYKeqVnPd&ZojfEocz82iVqRjj8z7xHO1BT*KEWi~%&j>%!-4yp;vuD5CR zkqpl8)Y^|`wZYg&O$(Q?TTT!UIcHZwILm-YZeS9{WFV6KjVhVb=sBb3f~Qe?;b6wj zt`}(x#hV7PO!t<@=$b^b+eD^)#7nR*V(yGfcIWO75cZ5kBaD1 z64x;hM^vtjOaABce!t9;f-%a>@&Zy^a*Wsc^A(n3t_0zZ-*N1HisG%6);@buzT>FM z-R`1$*vV;wxLG*79o{>gj4FAQ0R*(x)~lV;W8{QJI(7NZjzj4qx=`jUoM4M!37)f| zBk4BDbdfyTod>;Spqu!NA}IHv`O+UebeD{=cwEHajp0P&tr?Cl1xP}2mKm1d?aQZ3ZwTw+eyZ=7$c+?DqC05XDQ_Tb5ii1%I!)zl+? zU==jl&$(oczhMVokr}Hnn1$d=kFNK_USB1!o)M^YRed3qrXhH+Z{Au!g5K(8w-|F$ zVxF8vBrfaVp=q$f@(doYOlB;6KF@G2#l(oZo6I6S8RdZmEi)^Hf&huOY6r(vspmj8iYs#H)GS9eBPEmEHC0nO~`_`^4=7(&oD zXLZWY&y_<-?vD8pjXpu5dwY?a2k zWgPTVYDxLr-A+kNbS|`0mBw+L%=_|;;%9&jQiNJw=zHY&YX;bcGCqlXh5K1T5GZ~Z zjVQ+YiHo}*A^r+Mp=`_p99eGCAFW9nU6+I?A=}L*sot z@*0w`xKZ)UXXV}bCBt|fBi-mrV!lMwk<4f;1y=-o-2_=e`$JS>o{G*#RFmWq{#J*- z+hCq5wsnY4(Zpg|Q|R9d8;W!vehTCC3%zbqyNackv#R16{joyaN+;>#Z{rym=lhX= zKs~P8Xi-JxkR*G-W=;39XY6$jbJksJ%nzUAs8NnLciLM2m1Z1dIS~QOiNXpq7M9G4 z_)bI+0mfb0z$5I-?g-lc)Y`6x!`~b}lD9nMGB}P*I(^B`LTSGc;=L{z z;?fbx{FrMOQ?}BK9>PPcj+kz{_zvd&@~qYD6{v{t##qM9IfAn;B56<}4qo+J_p8~u z!sMwRqCkiR=3<8R*&;t2&$c->?p@g=&*fbJU;CjP2W{<5lg8t*#DL%Q*>jqXmMbLA zM8s&%Dk!r)94JYATPRO&#Aw+whRuH8DE!sFliv;rybcTg)B0|!A+eMMR(>%XUJd)A z+eZF6tHg-gQVDy{uQQOM!Gb7B81vXhfzAFwiTiu(e>t*QCd%!pMCS%R#*FPe>PISB zB(H&U(kZvn2+^{eEmZ~W`TXAlZj~2klZ0>-s{Zb$wYeE-bO@o-jJou3+(5O)MG+E+ zCv_0s(GU4#u~~DEQi{ai4c6%aZEqvy_b&~dUqvNt^JmpCrAk3>4N^sS?dvDBt-bx= zQt~2!@*0~%p&4%aZN+|H?d6H(B9FN}k4`a|wEYr*K=Bw<0Y{g617KZJa(ROE=(45! zXlZU{mldVbw;j(gTH?kd)}5z$0B9X}Hit?0W|qYp4|%;qXp|gz+V8zWO;s{F=7J@) zsneJJhDDA3@{ogr-SdCg>j#XsNKn0HDpit6;SbU{As4&Oc2+BlxZwObcPQvC^o5{H z)uxZ1SCIcUES0(BLp8g)EodF?V7BXXn|v37-jfXgam(dW`{-Jk6*IDaqMq*>xkw!KbAxy_H;XvZGkv3y@IFSmPuQAP{;|qIUx*KV)hfgDPrF4fhrBjKvTXijMe`fW!r=jkjJBtQqO zgJ9d0(&s)5I%+33qv0=-0ZU=HI(#>t*c(nh3&kR=shn#FQ`uDp+GF2d3=&Wh>v+hY za>&yc#teyXHK^%d4%GY)#eiKA@R#(EUQRE%g!u2ONX;1NUc0ujR$9z(nlxCqxcvIZ ziqLMl`MfvBR-ys$_=n7VM7B*%I1`&%6qdk-`?=EQ^&(!zz;8UtV>%8n@855b&~}J9 zMJDta1uBwX%=@*9bJ{rqjly6GZ;3XM9d!>6{olh9X+CtwjrAAGZ*s-UvmP7~$hhMjr^WQ_c=i{*Fil%SE|=ZK26gTugy?dlNw1+3&lgnANM7{y z?=(;6so&d%k+sM0j2BXyt|@Q@t{q4#+_qoq~53uWX9##?-RB?Y7bcy*SVBgHI1OdkYCKyaRE0)@YvV-`C6IyDf?EbUfRYdaAuaLwa0p;%*woHXawJ4RR*z&K3Mp2megg$RD ze^_aD;W6n((`|9jWSdTlsofd<*fXl7LX6~%b?WKsUXbRalD6{<@ki`a#i5%s?nA{2 zU?QTG0e=SYOq>Ku*?onWz-z%dz-*)$8dS5LT=_wAqO#gm$%B@XOEQXkzz#t}Q)JZT z7$Nnve(?Plzfg;lYyo>7OG2q+nhtE=E4O=>E!tF!SGVMjJ!%k>kX-ElEL<+9{WTpl zSQiHg01pUq5>ODqCV7#-b<>2=Y^=?cN$wSH5+1m4?kMfW|c)ozLMk4JPjFtFzW(h)ZSL><{7fB=29~dA^?? z!ak(}QbU{mK8RV2j)e7g|4rZY*llO!dtRh>qxI^)c10;0_7La|PB~H4eBTw$<^ z+SR(GT=5yHPf|h@2=0*qx&C2QEWq8=b=}iWy%k1%F`Nt-B{mCH_@^C)x0reS*L=JV zuXkK6CwTPd!XaJVv(CMzN1=O_sMzWkAlM0coa&SF=PCkKOh+$G{`J1A6@p8-p}zI9 zE)VUEk>-u#9;c|Z*!Pq7@lhbQRTL=jtDGFnW{RWtun_~db;hAuX;OD29CQTD(r299 z((gVgd|EuiC(Q-($bbVVhaO<;`^}d-kIo)$lHL4Ge#sB;S9ZnIQow`IFko)rP-a;N zybArPDNFI+l2}th`cvI#irm4@$l%Xn=2R+r@@dV&F;cuP#st*x?~9@O1&H=v;mI;?Rytj_dD=nX=&p$-@fr- zGsTY$@XaJoLT(M)PGa@;OXeGig~ZKT?Mrgv15XO7F^RGy!+K^Jrfdunwle zc^dDmpl_Bg;K0pt!s1{v5@K|+k`N9KXvR65NS=UE6!voJHY(ovhf%FAOrD9MEu^Ob$p3T!mm|1gHMA| z<)`_)+3X-oB(B-T_@6FmTv)ee`5O>d-bvL;vuL4GWn08$27RW{fRYI(RT=|2Zu9O& zVX!qXs1_aE?Z`$QM04+et`Kk|wfaUb2XnE@mCFVRhSsU7o+7zZFB76>-R7#GH*5Gb zW8VUrLFN_%J}OTu~+(M{N1t&M!zfxf0r!2B|=nQD356wp~qjx|aN8Yr_wa8XXZ zLGjmMe&u+MG7nJKd(TkMUnl3#s`$DNF-7G|A06$Edjs0|JY-AhdebU<5THG7Lvy9! zjWO)Y-BaZSBj=wRKI}b5BrRKA>RwxlZI6V6X9{lxW;GGtc*`T*NKxg!cZ`9A{=<42 z%DF~qj_2c!E#1Ay>F15Uug#ha4$xT#NOGV;UOOU)~Lbk~_(c?c2<_E(Yq9lWuT=AAk0(AX5` zfN@x*kY(@;vuQL{VW zUul+ZVD`LA;p~`Mz1G_>eYbi!PhkY+)GUuEp6Z5PTNO?P4&I_afrYh^Nmky_abVimOJ{R}`lcDon*J!=B zUACjqZ%KTwO2VIsm@pb7Z5fa`GD4@_E2@G}dys{yqMhdP!0@&h1F-_J(;DRk=Fl=* zVo4!r#rVd=|IOKw@}janqrGdFAIkPt6DS?%?mQ6sElK6r7Xv&KLw2)H3yXod7Czg{ zXZMDSEmoD3LhcLhv)v?;0eGohT4GgtRqQwWi!SEl`^`KaYqn{5yk0=9i?t`XvM#8UhGB$c^q!k@1sGHn~U?x}gO|C#cuS_H`MFNKZvvV-XQ0-2$RzJB6fnW*GWI_f*j1DsBRBd{s^P|CK)rN)&*jdgW1lP zzZ+?K6LcJB$sXt`Yz8!lBEhuI!{^G=ov)qK$JUTz7gwg( zfVpG2pQzX0#FZv5Y5NrjhxAN49`1b12XFE`*_e1I$lDtrt>Na#uRGH7+Il9THGn(^ zbc$l=_0?>_uWA0EqKhcKDVAryNnjZH@OX1=;GXzSd|bi{&r8Z@E4|g?ZQg)kui6j# zU{TH1jZDS&C>8b)aNr&=7A1TGqg90);lsbDGk#xGA;~6t&OaAS(sk&QGGjRLX}Kf* za=wGJ#r>d$stMyc`D@NLM0_it%}8bPluRz^%rF#BfJ!nP5!ibP#j08Y{Wc)*qFQbM z=zF=qNVVon=ytT1!Y~4`(b^v58l?m080Gps;`K8=T_B|K8PNM~T<<&CIdd>Mf5Bbg zZUQTw8OLi>fQKk4>O(zk1McLgA`YVUMD|M$ZR+9ID1n~2%d7VE>OsfLtTmThtRC%* z&ui>%9gGx+5WXl4D|w5d0)2q`l>!u)4OW@-0@-A4NeaO)#!DC2CwlidKgeWm95DA5 zuY9irhhp|VvdnL#-*Jh7Cw!brwhj1s!J6OXnA|UZdHZW5|F9u zUL})^(zJT-RO~O-$~_r8Ul z^jpMYkZ+HLi7#RAVYx*Rk7Xtt$mkaKrx>ox;5+^^9001P08>NZW=|9jqH2tzEinls z2Y5Mz>iE~m@;sgf+p5&TP6)!MQ;tH|^9<%d%MZZi>wQ?&N)YL%DrL44A)>g;Bv};> z7XJjIQ)F}*KnMAtr%ECyW|D>u4OV3i04WO%V8;#wfHIqr&1wZ#YDk-|))k*bStOWO zjslo1t>M$aSz$;7E=;!#LvkW02uZ92{`EMN_xE}?~L`}r?bq7_%AvQbpEX|9;SaUCvg~@rP_z0dpOMldkSKu=6J#T7C3a*1L5@7 zfgP+&*iBC_QUFM$Dv9;!Rl=}-iQbI}L_ft6xRqXnx)bpJ?zn-oKG|mgzKnJ>r4ZfO zzj3YL!!z^k-$^x!6H7}=#{bGf&m_A*-%My?ICi_`gl@S$^|})CejOI1&Ivo`zVfJy zNCQ!OZ2WgK#^rzpKd=RW0szwTkkJFM7}D<+O|PFua!U)NKiziWy3mS&?k^PEgYW;8L<*~gyeNzhm%(|ocUP`cD&df|=O zT1ieIy_FwfV0qfX)!_^jNxm8%|GcKiDN;o4l!-_th1LRqsntN63KTI&qN2x|;@iBi z@IpM@Oqqe$Q!-}i9tT%A*Kjhg@mwTG2Ohwn=TUDKs4Gh1hM~4s5aA5#q!j|Dsu@#@ zB32WbvjzGoc5UKQf}T+0^b%gxM#X{CCr9tHu8|R^8~xt?Voq1^{s{HH)dG$5p4P#5 z-C6Dl1k($ney_^5*-z7u2{U0zNrP&0_xs6+kNJbnO>NpF0S*&$RHm5HDa=7p7sY9{ z_;pU0b>3b1=w5HSoL+~q5c8pinh8HG{1=so`%}`%)^#dhfkz?57I;oR&WYWYjZ@lw z?*s)LU@gO`ia4ZJrz!Aq8eube z89@FzmYb3jKxL=JDPg_JuUarJtSjf^BWp8mlBeo9mUoP+B}wu-+FIT*ScxW*pmPqXi)|I%&M5HYJ)Jx+s2~y7B;;xB{lYfoIl-%$U|M#4(sP?d#@_LVOl4yX# zX&+yJf0pZrpty8XfzLO$_r0di{Fn*Ul>iVLozwY0oMe2s9N;t>rhWDj@q+0*rcNHk z@@LMGAlCbwhn{e6wq}Um0b~*L`f&Nk9MJfJ*u#LR!tBDWq?f8xmX+IOx%G76uxEJ! z25XZowRU$Mw=IrD56oAb;J{petrMTU1m6hCx2KdY5fe#auQi^UP z#ompf$l#ieaxKrcc{{@F5eQ???c^Jn)ZrXGg_MqiE;t5##>(oH8vP3R!LIk!tWVPu4WEE4N4aj>@V<&;>@-j+$HVQJ5&sx3iZ$*I%^^Qb8r-f8=DlXs*7ry@VUiB|T!x{*F>9L;aeH_hkZaNo+vmk5F{^k=AMw68X&(B^g>YyEx4 zgD0?n^|K?!$IV=8V@h!)p0LjBasf=Zi}weOr#)-bwrO+C|6KY}k(k)VzS`RIQHWxr zdltfk?*Wu=>V}1FZuGPz?w2}zka(>3u!QG9NGb0E!teT+*EY$-a7J`o zsXM-?+21KxuMAwroY-8G{UfVj2i||?s8&`U61I++IN-R&{>eQ+{ZT$5QMNE@Qu;{a zQ&qI29&$#Wcpsa>0(M|#*1>Y)NX2T)_OgS=-qgHIjpwAPZo5x2a9w@}&=rCpSVQl{ zN{ZOEEN;kjIe#Sv*CPv|h`mVIj*#|_gMn2vb%_I0eLF2lmk<>e{AqVF9uyLe4|9n*L$ zem^C^Q@*M|*{9`30LIKLNHz+0IhFTOSwrwGQ7hlSNImlQY@B zKxDxr(gQr|@6APJ#CaM}PcO}#B6!5@m*(#|a;gy$*7`p46=`q#3-s@Iqy`dt81R~; zFP$JUHx5%LLA5&zG6kfYfM8)w1xYngin4ZR%CWiVIfknFVAmem1)xX5jilmeJK{No z`DXv~$yZbLdvil-ey3*TrG*Qpnxy{tYxn`68MU_aoI^l6X#6Vq&$ZQ;kA+L;EbXBt3vZcx5v&5MNO##k*E2WxF$15Pqk z4~piqLPU~scLTFDJ=eD7w`{e5D!2MIU?vZ*>(Ae=;9JH>WnS=a4BXiN&v%hZtNC_t zpJUZ@fw=fVC(NJ=$+Z_LV?h%W9Ua$oGPCt>F!@z;u2LNUhBc}67=Kgjas_=U)btoj zIh7_V7fsbr@B)i^q>d{XlPNNjpPzrYOt&_%v3V*7L#_H7j-M@sXB4${KX$q(l20dv z)p4wm=CR2+3l-&X1A{6Rr*+Q(;j#R)9C-l~s+WDB$kl_nC8{=OW^({RB(K+Y(>;sx z`4b;BZ?_gz`}-Wdd}ZL`5=qb7{qJuD8W&zwT&{Vmt@%HSl}2#2{3%E=jPJN9?Wlo# z9jv0YL|cQ)mb(N&0AYE~zWB3?E+pg*R;P;RJo=d2j0OZd6#ff#%n-C6SlfA*_j-ET(aEv^t)ist?w|qSz5|W$tBe~p z*rfk)DzX3od7&|lnXHmD)qdVczH#GopH8afY$FJuf$5{tkLK#t@ADm*Vp%qt*QRvM)KtHwyMk0!Q*z{*LhnfI)m|%RPe;6c`lJWdwgxulRJ+I zdkg#86aygcc{i{(xi1qLCj4!ts;+`jPSSbU(}`;u^m=)C7EpfvQ3nv5lW4rN(@RO3 z#sO=0*Ei7L{D-*YSe<%)?g#mkM9Hy)cFwUP@E4I*)fE(Nn+!@Vb7u*nUL@7%P2%X71x=x$Afy44X4C zsI=1uL5r{#cA5Ne0Omsuab3e%8mg*(kN-IaFY_N;pS;D^ZN6^1;m0+$a$x$L_oTmR zUl7GCR_z0PB~M*-7VbPeU@?bgWn&5m+z2hlU@uAS@%FD%*(u%R?$OhUpZIV}5ZpZ| zZDxHQlNDo@sGFwaTD$M^8ujl#V+-77W1Y@)xh=iB0H=;`xzBPCN*hFAG}7e0{N zO@VnJQ6?~kK8DxY*IJ`$(K7YmeoM4Ws_Fd-r)brK_>&YtYRG^+;?>UjMtF@Q^Au2U zYCjso^K1!tdUwzfU%+{%*alC(WV~piM0$80FTInFF4hR@;pDhso3pm~Jwgjm;rtVQ zZ!d=)P;V{PR=iHTaX1Hg0i0W{D9l?r{zNbwp+ebV%>~}` z&zXvBfPGctolgN0qA4oRJ5viX+*!L_2_&zJ6N6vj#RAP`JcGTaRiw#4ogxs=BciAO zLCpk@1_MUwH#KFzTt@yAd2CCR6`WUWpjxdSk1@c-6=xhYBM zINWG$4hU6qsa<--+CuEevs-qp@oCEZPxPQrj2P0;J?>?jlx*8|=DH5SM?AH}V5K;B zASo+MFw86ZiPJHY1e$kawM_*6o^T_lr}#_bLA@v!gkHIoe$TU#_pk)9D79UNs5IEE zGXj;Z^$?r2RxisV+wI|`)2&FR0>zXBQxeHi`nSrgpX}Q-6?YG14U46L52`F}iWl_h z)D9@hArl{-Vl_=}1X*4Hh)F?ev)iTZ51AT7t7+~#bTT*4e?hXdg^#X8<+-rw23ccR z=lpcY&<-;*xe4VG68&MFq+0TFDLpQw*NLeE<0BzU#+JI$=D2xCG`cX#Q%+=RFeQG6 zj;$8BwXI4uwSi5YfBDX{vquB>Dn;>1NSf4tSSIaz%t4??&DOC7xK-)q@PkK>i#b|; zMS*G}t8}x|DSk7f8&|P);j*u{I9zxDHJz6IN!2npLqN~xLb#dp#i(wx_ff^lv_S)4 znSXL174DX0rm0ON_V>$LL&?N+e!XqAZz9tLsf%^meqNwaq7NR|6Cr_v`P9+qP4tsA zfw&DR-cnt@#|d~rHpKAPX&j*;8|BT|4-6IKkA^K{S{eRfOak|#X8EhYmoJ&Zf{5!p z7!oG{%@el3!~%}`Xbi79=MN$^@ZOM+q8)t78x`cP#bnygMXob!a7}xP<2=g|80zdo zEdUC4K@zxdiy4!$Prr`eq+ArU9I_~u4&(XiOXL;(t!Wy;{uLcdCkfbib<3zwa(ona zyO!>%IJ$YC4lj67IAdOfuCL4eaH3jrdng-RVS~Rms)i-zU}@BDyz4h^v_I%^m5gdG zp_8g^RZ%jbr=%VLt(OphC&bgQ|?&wBG z0+~4NI>O;@n%#%Qk&in6Krwx`Ep_%R;*%fkNHTlv>Tc*B zhg*pyq6#z>|1lXHhci7xJHsqr0r0Nl43CbLfcgAy;HZApTI8cZ7F>UAfDV2^dPA)G z7_@Qun!SnJ@>#^p0p(xv!wcMV3Kk(sCt96VlB;drRx=Zs%3h;)zKajh6b^_A*=>ma zN}6ByRVQY*0&tBZby<ucDJ)=6DUoIQI77x)$mq}W_5f-W2`T&Rq8N1IH_O6CmpjaN zD-iFu@eZan@&f9u=z=v4MoJWBgO)L_3cc#3V|L47ll$G0@kp~r8&CPaIbF{~rIL#2 zZ`s2(jm=MsQR6O0@6J4xMFf=&%{+!}4GTG+kytPxKYiQ;pusQ2pRUOvb>H%X`1BS% z+OtiQ>EZN9{DI|FOr!k^PuRt2HNfDU6^2L6Lw^>PK)&5a;?KsK%$c&Qx32OvBNYvy zqp3pp;{B1}e_uAL>r6G468d~Bdi@-xlJaq;Q$qwEVA{^tPd`E&o&KB*?$jwt;0Xfd z1EG~zmOGnGW4SUEE4kA+j+X9l19^LZ#2AGkTz+5g5>c6oiit;fZ)p7-w+G_!nB~j< zwrYFaZjX;1&m2p5Vpgyeb68SrQYf0*zP~Tq4NT47`zKFb68|sjdlR;1(p_J@~nLW4( zaHss9Rq+8(gs1B?U`>cjE5(REITucSs?_NAx$0b^aYceg8+5p@24qebsf~E7`!lWk zUS=LtpnJgR0?0@;`PJnB8R-J%;@S^AUV6!6dWBU|QeHi6dz{LpzPp?2w&qLqVRfGU zFYtcv8yHu`=69G(M_m4*$7O-2dE_4Hw59*`(xhArO`*$p-L5Higxx6k7+sd?mqK>{ zY$D;2%=dzy+dADCP{ov4Z;UV$zbyvytxr=mA|W~tRV7x>V{-ZmRnpA?qFT-79#xIY zyeir6hJj@9TA+wWmo6e(m#ub|i}z;7vTTjr!=x{OU#O&l**9r0O?o(q=ZqKZOl;EE z@#KXGdV1Gv|M$B_>J1MB@}Jn~CQ-=3-NjY9ft#8ky*(_BNmRo9l8+`Ge>xvfE$d#n zW5MBYSC2Sr9_y*ssJ>94{y;9{rdLLClX2n&JKG~E2V{4h>K4HjnD(~H0AsU?^VfyC zKihch>CXw_Jb6rVsyqGo#ITIOEUsO~;8Zr@2$6Ivc_ohBA;wY7Q!}36tGAgN|C5f9 zVHm)14ZR7HeJMhQEN^dZJ!!$qe)G0kgPZ`H!qukW*VmBlRYSSN&q1Qn2JuKwxn0cV z+==XtP7H<#@fKAeF7`#lM68K=0oL^gP5)UB27ukkQxTr`QAN(0c9vbvPfk871fst- zP@&$KKxnZ>p7JH5a;otGVS{Y8p!Kf?7lJXv5B~S^$j8;cJIGnG7%i|L1jWYbJF2feEg8 zX}f*v1dLtVFkmJU%C&;2lLSa&zV#gMsLX3|h+Nms?m;4trzstSBoyscG3)>nDpAN~ zXZUPFqEe|TdH7FP@PWBl$j$Rw;z>~6gOYBMcI;P;Fu*nl%ciRmk6w$NTK$h!nnB1s zLJZ3#Z1q!rwaW}d#V4~FV>o;iHPgxI_9GG^ zr=lsRg;E7j*pWT_kp_P&0q;wi5A#PhXxQffkZbGCXcjO|JL42}&_^{>m_xPmcl_em zwV$~+Z->b~Bl9H!%19;dtW&{!g^DzICw{Vk%O3Naq98Q6Xynf8%&lZD!7`_=-LGy2 zx3YTY3w^UMcL3!vWu11{CkI^cA3%fA*zAP4t7WAvJg;`;(VjmTlT8tK)2 zI>-!?g(<15{iYy|eKJsS0JQ3FOO#~g*WvAou7VqGaAGk8$u=GEnbu*X{;EH%woFJ$ zg8{A9_Q>uY*8K8D8V&PkLIUY5WjA&m}MR zFPkZkP^Zoma*>rf;yvAwcwDqS&k%Q6y7~Jw*ZySaCzIuSsQVPHn~5rmSX##o|E>fPFl&xb1t5lD{#ceHM1215{3xWLAnfyYlFW*87X)mr%25jkw9` z(SNs27K%g$4fb0pe9M=^ec6B~?8|QOlh*ngx@m_iL{AZnQcI~ve{$M{}B?1YkL%sCFU__dDwZ(6UlaY zuso5>9Z4ZDXL|_zRV}ek5a$5SW4zv>xRaHOVAD&oO>aA&FAL^N0xA6Dhd>=6J0 ziiq(l5NWsPA_mLE-$>^QT6dqhEjNDd!Jbapvq3+9QdPBLNdoCB;z(c;fclfutezYw zMeV3A$KoZcrioEK`UYJv$~Cyg-_k81nn2)*sfAL=8g8=x7CVms4g4alSd>7mC7WblnO4Hi~z zNZ17qo46*#BQE~a6bHs9=gRca{{VUf_pDF)uCuQ8D_mW&S?A%?0NKf8`_)$K+Q+-d ztoXq~kOhix91aw9b0C!n^5HAEypYqr=)%nn~jp@KFUu7s%HSw@2mW$P3e8 zpo8wW-$rKuIyI}~uY27xCd*^xEa6$(W8-jcTiw_7&u>6WM5C|`lXF8)=@(&;sJf@_ ztbnkI+%un;#ErO`&#_ZtobU#RW{d!E>w;XyBdJ=Vz(Vg^^M3%I*hEJXb6GPQZ+qxp*>!4_p366n!{$d z8uMLVNTN;g*x>d4^u&|bDk*}5W7zJ#M%djpn7k%~GfLPD)BQOTrAZ;aDk0jp`mg7T z*VhyN_8Wb?&_gqe@94paX?BUv^|66wyK5EGb{_|}><Tj0c_$@h2OSA&ts9baw)a~AjBAdxmht=@ciy) z=WE=SKQ7i-M4X>li3&+utxhBov3^Vq$4J$Yl%PI0Rj*`*nw{$ofNK)n=svAI9kYkD zo!fdO&Vv(6EVGGy@fVPKpB$RKaN^51@*+nVI=N55y9Dg(W}Z=RS+z2Uu4C_bV)xyT z3nl%CGr1+N=fZg#GtM$_6CZ%<;_lO?6~$@PNDzK7U6k$X<24UYH|RYBju?#5whN z+&kJI3B*pM+Kr{tT2Rl>SL+xnd0}avk5vOhit~$s1C( zm=LW>)BTALK)QkNuW=z!90P0KZ)!ouG1-@)>jpVR+>>80oHyi3ozIMhwg+D=DEY?@ z0HOPJ-`h;2ePrm_^-gyB+UV4F2fzTETP$$Nmy%$yU2iaGa9HO+@~ry2=ianwR;6;o zWepq)3?Kl~VAuJZu>wkGwiINawARP*UB?uh^aKAKe}DsJzI(#98pIQ(`qRSkCBDKD zdLQF5P5eE&f|C2*Zp)KaR57}01E>W>yd`{_d8z?__q8Qs5*QML?W1j+n>+*-h)B-q z_&+|)*pN3<7ta8g@=_THNd&3K$ZMO(>v}uI;(g|!U~y5JD730vM?9KDm1*i(bN)U+ zjpb?`?@jpN@9}R^f)yK^OHHAR@V0IdN$mLOj8YSJ_oPRNaI|FDA*$3~YKBtdr<}Mk z9WdrF!9JtHy7-h`>n4TzM>9D)R_OE*lqI1H#*xpdK93@-+ZMixq!=^L#TeejvFW#u zl1IRiXB*zbvmdXs875O>flaqWswL!fX0!+~VjVn$A-~*(in$H#k`7|fPSp#!e7vcA z)UzD_X(U}i?JBlTs527CoI^85zk#USNynI^p1G5|e-@NHlE?_&=;9n{-v+!IQrEF-ud`UWTUxRexWKG;xnnfe-=G5I*&P)~7T~IhaG=i@5#PQ5DWLTw~C5h^0)vlc83%Be`h- z@!j^LpR+b}W}^#iy~DKUv4l4OkHPdjXwE4X)p9OxECjbo`Fv^CW^QL4aBQ?*-d+L) zg_+KmYX-G#*R|OX%6_K_+45$2<5eok&pf(tPk&GwL6~+FnLZ5TxqS^gn5|cf;Eq`2 zbY2Sh?(NIOQB-{JU9{e)_r5{m}|ITKP(TsfTu`D3ZCEXjg%LC+`z^f0p#D6yoyrQSu@Bv6#c7TNdD*@d>E8h#yPmPxsA|`MTvi`M2+4KZs*p*y-=LB?-Y|kxw5emO5mgH=r9S zf`(fjPb*r_4n>~Ei`UB?_x>}X-6)x_BzU;$%1UHWT?`xR?X2zN@Wrnr=PHdHrlpO* zy9{X}4i&~q`lN?4VcC-SAu_p48UnQ|He*}?njZG+F9CXSc0Aza(Pe=4U`eJ;<{#Ep z7`EKGy)D!9&OUud?i6}C_XZ@v(G>{-93x7o$uh^8no1EnMYjwu{)th@qlldp=tp6* zt-`5i(G@Ze4|k>ppgpew?kRBlb4YyMUUXLu7}M)O&NKPfg!6VHChV;E7otdc%)duc za!)lNiC4DNn^3qdMWyD|`X<97H5bxSx%__3#FR9q6$4R}1mq<@?Y((h7~yhaM*QBK z5w~xlA+P9K%gOQ2M8AYDpOzvkT9p`A_@>H>tVOAuvM3kjoX7h}T|~uBjyEUneZ3SU z&j`SQ1os~n#%dUpmLB)2_L5P=Y(7;cX_tOnjIKfgmq`Q@wt#gCg-y3nPq7}=FLNq< z93KPEQ#=kAm>SaTznxXx&T?g&roFyZ~QxY+*VCgxN-WW}J9`lM)D(dzfmr0uN+`1;&k446}{v z(|W0onK$>d;muH|{(B}pN?K-S{oK;#PefiRj?^xrnU{K!$}rdGw2&@YReQb}vnkk9%19en|~A+Dj)dA^T`H0_=-#u^VtIs0}#Z!tss= z;U(?lyztzGxZa{O+{01*0ii_=F*G~tKlGjhlw(~>T-+ZV|Gi9T32cm_M%pv-0VUaRuNv@Kis%c7Tb;@o@pIX^bw5qODvLeJpvAuY{2V!63t#@sgn5?= zt`cuHK=C7c#;571hDYTT%AHYWKsVc~{O10u%qbK4uzz9(poh_K>fYABwah0sdqz+| z;eqg*_h{~9oCZ@+;C&YB5?Ad7^EmKt-B!LqfS z4{bxw2lVSA{~M;;XGrlkXEbvx(3?SzX0FTZA zmZ-g|%}|#55|bx|3MI6s$t(NEQcJWY+EM;7HhU!1KY@Rt`Yr>JjK>9-&jbs9nW+Z_ zz96^xc+N=Tb_5{K4S%4R&=OzCEq+u6OR@Ks!%^GHcxC24`-)h zr_qnd$TpJJJWfdmvujz}SS!$p7NjyePDS{iHw0FJ0# zHK~%0v`eZOfmE3{<(fpIh}H|Ey5;P~Z{r9b;HhmzCEmSz?80je+Po6Gqv%j%7t5t? z3iMCZ+iG9!Q6ptqacny3jJos;C4Ujtyz4zv3jEvqyRWUp(cs}h2XYBzvth?Bp#Aob zfC3)#UF>6P4?~BtStLoq$2XUL5L_y^Z2(KNZE6FAag07pl1R0ksV|cwTv*Pr;DqIz7SR!|uwI|q}f$6VqwNJs}R^yC&QYNo=G@|mb$m+N{@NacHlDWDp z<{7D%rDV!Q;Nn10G^K?5ifx7o_WVUxI?G ziaBD(pQ}TjF&M;GqPja$xXyg@J^C_(6SetE^JG~+DR!;OWVTpIDY2Ccpdwk zi0|XsM{Men;LM)=O!kVJMpgtI7Tq^kPH3%FY-qJudD!Su*x{!ryw5d?kV!fRr1nW4 zme(KVZemg=r)>g36yJYau0f^d3g(oY5rY~w2)r+Hbxd zLpD&U!ytK4txsHbin`UD8_YKfMGiRYj`1@GXloWm`2hq0Nzo!A1)kq|L7p)9e2O`jq)SIGtl1P&(aCmy=xT4-3Cb#|7r0vrN1981Y_HilP%M0 z1SN}Z=in(Zfx#HdBpxVY@S(fEOeiul2i3$nm!9vs=qZeI2(TBAp{{a9g*-!Sh>=g3 z>M%l$;jvS?tq?DyzWsfJ{O}|#YIL3@R#p`)j=OjY->~hOLgmZ+QAiplOezUQ3`)fJ z9m%_@_tlR4Dl)be5z?Z1f^PdlGqSg1#ClKL>T`>hd(ffi#)KG(nDh`f-uc(y^9%1U z7;E@{86%yvO zzTbG==J0;Q_c7&CI3UUw*{qW>cu4*YO(NDa^IS?vp|YAQcuAU-YWAX#*Z853m3RJH z*6wb_Va0DeK-BnJdpr9}uEeZ+rt}l%G{K!@00D?;kND3^dRaLCpO-fkMg7bRub7kwH|f7RVkZ%c)%gQ>t=0#jDA0^ibJeM#*L$TFV_XgKfi`s)eVJr#gv zNX|oGxi4SLW%(|p6bF;i^!W)}b@7|t{rVB}Fum01vSu95@bZ1-87uTM=T%xY>!$)& zj$f^vO-Xy*tvJ+|srnXQFztvpB{Ieephp{qR2=;lsT9#3KH046iaiSJW7IiEi(doo zdC_^Q46t+hF~NTcKh_z6hYG+y*9(?nK39Z=e`XZ(K99|6t42}Qh7;*3#B{cs|ZNHvW{U3^!egB(V5o66g>g?#h*^q~FrFyZ#7!{~O-(V`)GRccwt z0EMEnaUX{4`>pz}oy3h)A`K(%Zd}~l zrdRT}c<=m8U6#~$MuvV^4?0{)WxsDnJC~_a9P8&iM$#kg#eG9F>Y3-qhqwJb_)^}+ zEUEC+wX0>tXHcH5hu6YrZdTzIW1l$i&X|dqbv9UN)IPlkmyGBAa`wZEm#?Hnqt$f3 zbz@${?GMEN-NM!Co-y(hF=hMSo_1`P=frbQc7qB_3$kGC$-2F?ad7v>oURy0tKf8=Mfo9hIcP zMO$vLt0fY1*%`0*93T=C$z`=M^xQyqarrkI7v^_H0YFEC$RN0h?2>&adu*x);EP2o z^yS8%KYyBE*cz~uUiff81o>9VWZnze(P(U-4@Y;&CrPKQPz(9I_rHELOwq7U1ey+d z8`5&6x)||=KkGB(4F5n#YMnR*Xmx?Ewo#n{@Ra`5F7H>IcS(4`RGeCZV=3Z2o8lCi z@MOb4$WrFoU#h7Vz`=;YSIcbS+;BmBCzV4_uawKDFz>rli2nxjInnjTyCQACB7qI> zTY+L}%bMuM9mUZN(3SXSqJ~Os2}4t%M)-c*Wi!w@@4aE_;BBX=?d1z(yNY%S zuA$dBEs(*s$i4e;-zgzIS0DU~Quh%TeejKEjmI!(@57{SuC2+n4u-hgu5^2|Q|;QW zbgUKOSBv*qvclC5Lq}f=aFPAh1OMcK-iR)7e|98)6%85p(W!bU=7qmd{=ltnDmgNU zLHUl9BR{amyHsF?f4;yvHCh9O#fK+Z4&N#H485kR=HK@KQFVa!mzhe;8RYTCgHW$g zpg3Z7-ueJ*TD_FuddyQw22}`&P5Ke}@=0s!5k$i@Amefjh*H~$kuU-}=kf?jXnEd8 zv2DtI_p`hbbNTVH(*>q{MN4jOeit)B^CoSWF|x->w7=)?M5LA~dA^0P8p+C+F^AAN zHJ{KJ9PrF8+ug!(F!F#-!OOw+1ag%Fd)5})r0R>2Ca#j_e(K$+Q6*;gMlcgGdy^*L2geWAun67A(K{FGfEKQ%n7U1sdOT9WU09KOY|VL{9Gj^)$P zqmkRkul?g<{jnhsc@QkHU2Jdqk1PtC`^5Z|Uw%1J*zk%y`-Qa!oj6@n*$0_7huUH` zrXxfS9Vt<5AG!!%O3t@=^0CY^Ir39}mGE2zy&;HqBmv`Y=~181Tz?N@%0iy+XVv`_ zGkqHQWtf1?V|W>Mvn%XJJFPu|a@x6S<~o%VY8wZ!^nWI4NR}W3905y3)D&$#!cuua%rzu5_ww7oKs;lM#lNwBC|M zQzy}BU2^?1d@tg866VVVb8+d!Z0W50=|fPB1bj8|=AE+^GCx0PzW5?o5o(sK@1pAC z3V$G4Nt_>e3p5XYFINMC#$FevqVk*J)gg#A#-}-(k7(Se=NT0)?*4dI6vLD^9K3E* zc3XaGm3V@>$~r$xYY&(+2DMccfc}b^$agRSbq6_gZ`zf&S98muAe=ps!w3(|`ej&T zf}xM*ySZCLS&eq;xA?aN`ETb4VlU%KqLa4ZQQ^i8OwQ<)14mdCi>Cp}s#B%s2H-W& zpaZ^`Gq6}f+&`>2a9D)Ky_-BX?H71Tv?|bFSdI8H=`S@ZK)QdU8IKqLcR5b*?VsTk zTE6cSdKYZvXWt{hZ=1eWwc+4<%F(X*^5trl5b?z`JWaHu&9S%qL&I#a;HJ#RtbeWF z2rDOT`NBIMq5U}Ft#|K>@9l;bhpTPEFk!~#w&ICB1n4Mm+wudTG*ZDsRCNo6Qlgy> z$s;uBYgR5zB-?1epY6r^n;m=II6jW={#fkAH;6DyE!z+^b-KqGk;@z@jR~q#Zx$K~ z6)VIvepf8Lc~%K-QhM6nkWN^0OlcxLI+ghD%Dw>85&RhOIx9bKI7R#9BU4-16W(x~ z`T9I=UYGjw-6|$-py`;=eCze;jNOqSHzAtoV4HqcvV86N>ZSQPDp6cE!zyY8!t&t8Ycxs z=s6kpi@@wpfvV-Ok$c0UD}ztk;zHw}yP_$<1**&>KKUp~o zHgD{uRf|-(S6Yn&>b2(v9@D{y-N{Q@EJ3!3)X|Ik7J7sEhoOD%0Nb|k+J@WJ4mZ#6 zD^ExY%@uLMhFDg;+gH2qlx1?8L3T}-u`yd|hIgITL|-(ntmi9+oXYw`U(=mMIVW6g z;lX;@?&IzE@ivd%ScjNpJ!-h#*eS-W6(02atk*cKK20;BA7q&?^QRKat`Ju}cAF)n zWa;jpF|>X>lwaIr1sWd0bYqlwer0y{Vt0y9Ea=;Zb-k*UZ0vLWT<$EAQJpQR2)o7( zEzAocA$@8dI?p>zqKhyn>hb{*7QU)Y-X$m5yZ*Ui8 zX;X0}-O#CLm*73^^MQowDcWxl(SY#r7rD2!5KGOFFVogLXN6;8mv7?!HMdp|$a1aI zMB-63Yd)+H- z3;Q7p?4=^2U}35z&cxIH#9?clNZx(r;L!R`^~pJGhT_(8fm(hMA^jkr-kHmI7t&_} z%wf8;z@U2`23JDYqW4dDIAe=dLzi`DPe)YU;nI=zqX92^u2!)tJ{xbbbhWErM)XXn-qn`2zw|A1iI73-1cd(O*zr(y z$bNgW;(FlqM7%+WT;y~KrBzGM}{bFmpFI#i|8F&&Jmp?!b&8U8{>_8FD! zN)~Rp%$uERxXL^h08ko{?k(RTb@nfNR9?~W>#CEu$?@-V|0B##RKs6qi}G({~6!&|UmqhftQkwcTtN z7?Xd0o_yJ+qIeKc?;tS>yTIQ(?jkX@%87u0ta0Z57#&mJL=W{4ic;S{$#wk*oK1K!_j&Qqv1oQlB zFSa@7^flu2P@6v!auy%>vi0dZ(p9sA_cVLG_rOEOe5=T2Wl^};pXD`;S<_j)&}t@X*}08IIp4dj1oK9H04zhZR?@5oBxDfw4%_}){x--P9lX77;`T$ zq9LpKy6v%Gm4BPhxeyXNDO4wb+OEjk&YrF!=61JFgVxN{LS>$C+=X0LPS=fKLD#L2 z9J{8Y?CGsb=Ybqt5fdy)WtQ03uI1n`-iJX(q^%iURN!{GVffV%iKw@IJEaRLxgN~K zprbp);a5<$Of3m|#Ooe-(t3>BOVs9b?(YipSbcS2==N@bkI|?jYBI>{RTp=&2h;0A zk;*n4Pwh52$Ob39aSLJ|F!C{*n{p7oHOhasmY}kES(GSVIhquC9}wqrvZfSBMcM?` zDM$zLtp-T#C`z*j#ULz4Bf5;6mHSt2&KKk4q3)ThNp)2G{HC!tqgk9EjJ}Zu#N!-V ztG!?v(wPiWc)>E0G~qUW#wcO7+WD@tBBSnr@oGNd_wRf8UPf=|-~-Zk;+Wm&y)>K2pTHO;=SOHAdD zM}Cjt$xkd<_mgcSx#XvLc)>(I(1Hg#6=)R9;6_DjfAPA@?%~8$X_L0NBJp*L^c6mB z^P#0q4-Hk-+P7)Kr_-ij8n4l(V4*?E%22EIv`MTc1>^-69){%ShB*j!^YpT`34@?4 zlzbK^NuIpJ=qS`^FGZyL)9v?#;8>m1*l4ji>X$tC)f%1qE-tLA!h7mZUuU&A9O8u< z!m_EPIdaK9Wv_^-k?KlWB^XYFD~6@4HjG(R;b7UI2j!mYU~iWy4z!?evY*v= zCNdLB5^PF79O6Av3gx$6t#$6g_RFn(@#w7!IOd^82km?&oydz$H!>Le!^G(eS7)-c z5nO}p&x>|LhDb~#Hk=4`a~{R4+Xt=4f|&Mk9?bQ4g?`9n!tav;Bz6F&Y0&9XO<2pe zaZk8X#VG-!y;?sq7bUK~c>~@UnBt+hnELI@Bq@<#NkA*mv4vn_QvrBd*@0zxPeuJn zTtkX#&#Z)cCG{@Tq-VAuo$(yMu48(5lv-Fs14@V11y2P9Cmc=cDTw#=ZyXm{w&Tq| zUe=O3FquKUf6)2OiL{FR{Q7mOD$6#|3%sYAkPS>kiy)LySPWTbE&%M^NYOEjO_5^u zXl4-wp$L^f5i7fVOG+NFA~QRQ9T+W`g?7CV*$JlDweH5m1mPFMo2)H@oQ3#G8`pyM z6hyauSoGIo#-rj)G570&iC z-nN%?SL#y}ax7?$-Cm;$$oQI3CZWVD1f4*r?Nru{Zu*%aw|n9Y(SH(cf=$l_B&0<7 zi9rKKLSHZcuBycEoO7TwnDjnC;Pp8fPbJ`l;=f{LlO2H4Il%gM5$X=ZA%2!yA zgT{Z#b1yf8Y^1Uoc26ojUu~y%rWx0C31~Ps`7$!)gk#B!(TQ>Bs>0^m(_+`3L&aXF zK82D*1lIbD-^}uLxIrxFyPv$;PnTgA+s9%|12rF6-wm!fzl$%g9U(MeqzbNc^A-3)*(2<&7(Ku`+M4Pb&lS~li;r8C%%b@)>^tprH#=O$`bbo&n`&5k@io69~O!)7r_p= zX3GgJLvg~RU3?1HVhQT|tem{Psdx5}mZ>IwXMX~(H!aIN0MCU;dHxZ9TT__mWJytN z9?cy~UXd0nA34pIhoO1t0I(3`M&kfB;f?@DKasuhstG88>bK3M5obGe`LfE zA!&(Q|K7ktI0&v3Ub!C3*VUZACg)}d%0Hmy(qZ$yXlEj+;lW1-^>qeE4Cav*mH)xV z!1G8dC&Nhsroxj%%{`(AKK(uePAJ9xn99FiVEV~y@3&ByepUl*0a7<1U>Ki5`EQMST*nHgh`+9Y^l~aN zsZT@m-hN8XO1T>Ru?#E2E;x`uRCTIM&&Ig~hM6+)j&1ZfBRbofci&7BPi238L)-E< zrN!?ZQKXa#Bv@39Zsn*=Kto|gyj7rnxj!oGF?%6>EZ|zo*T=d?u-?m7udXKV5A0$O zBfG4;ydLGYp1KZ=OI^JmM%U(B6xl39tYu)*Zj%>?uH-`m$qX^|(XR{|~FHGQb z*+vjdR;?HaxnkM79L9-v4z1V~GrUsOuNGe0_N0~G<~`1mXDPjXVi4f=g#uRZ{#6-f z$PX>yi01WNIME-M=k#tZZ%3}IwBCUC*w*ln3<9AiCdcck`|AP?z4#zQ;b4MO*4vM`?j`w&{@V`PiK7vV zResq(US@qFyg7?=DQ(Yy&0|FM52G%h!qH*K7wfLpNp4YwVlw(H;NB+m3RP{%cfsn3 zQIW}`%C<9i`5HeD#J2tQ3>_DHU@1%`*^eXsQCc()f`Uu?$v(4>f2E;O{z6FP*A``k zm_fA5vxAy~u}F6o33EiV7mwE`##SdE8=Z-A)qyIb*F)#x5VrdmANnP=Zr0(THD4o? zZ3rh7Jxl>#$iGtjUT%Z06j86vW^pgTHQ3iEXwyCRWwZ#_gz*&+58q>@G2HVU13v;RSEbNCQpMkS@Ek7+ z48#BB-J6AHM(@Ts6|%yiJ}^H5Tr`~xqPpY-?c;Pr;ClgH-#4}H^$lMvRS8H|%MqEG zeCH_n8dmQWm)G=CdCiH&9ZbH-8yn`nc!vp``iaV7Ly^R%LKesu)o-KvUWHVfor|$I zQO0VrzO%3aZz=dWOxT4~CFH$Fei3s?c5y0uDxFGv6e9375wPYJvw!28jJJI@6Aw7c zF!5aER$myWB$ShMe`|0RFlCCx3#7avu68ruv=M;~c)w4~vrm0;LKR?3w zjZi+U9vPXMP^mTXbvADJN2fj zye+RBU-u)``&%XY(~bhtLf5eh@8`~cc~qwiearTwp$0P@=1MC+n=Np?XZ-zAvT_7( z(K_}I&vLMH;n$BPjGZXvpkubHZ5L%#9E26CWo{ENufw5nTU92nOT^1@OJ-_R@T*NApD#1i?1glhLuyX>5DG8hMUo^t@>xWWT#3atGSEs((^Dux>J+f zLY<*hum~yaCkI5es#K1it;6hb6B4d6d}5A6uBzp1ZC^2h=j=W4XQIr2^q;W=nHOQJ z+Io3$GWX5+8If}N1vbBUpwO^+A+{L`L+Z6(eV&6lexUQdo>DUrFNhpU6w?6ojCsw` zp<~Z&GOP(rl>^j4-{DVW6)F;0=1R!kMg*7u_txr&YNPb^h&AT=th$+M3Qw_a3O-%i zxmt5T4#rETk2}cY8gY8lJ^HCmk7lK7?C&be`es1K>PhVb{m%UHh~9JwZu{ot1kw!x zG6thQ>Z`o)spCyo0;KBDOG#t>Ik)>xDN4&UTQNVgM^;#l$UIxA`zh-vR?#D|)~WK^ z_gr^oLYF4Ton#U469fI)Y0_&^On zNP?X_)~TN+G?)k2t?f@_^CT4GJ&QVw-Ep2-D&rn;ytNcv$GueCAzi5m>$=2yA)aZM zQ(fP%TJi%DXx4`hv?6h(C0lE*CJSeG!M#+Rv3>td_CE$&YZ(Yw{!E7ES6P}5#eObs z)RGHjFh1ifU2it#IlS-m=_Z1hNm29%iQKQd+wsNqt(+9$)pOCyL!KK48tHfdxekR5 z3a4^el0j9iZbY>27R1e$ADkTp)geUP7ic>n6I9o1g!3JNVqV{-0FQ70Ng^6b0BqKw z7ln1Tr^_%D^-OOU_@J5?%!Y^Mx@YPyMIf!WGJJo^8F$K0(|5HqqWsnm5X;mJeoFOT zTVD|5N@1#6{>yf`@SG+0aY?)*BF@B{$o%1!^w#JX^*T7DYQr4Ra?VSBnRkgxs=?oV zdi2yA%_{fD)@Z^9N-d$TW%hXAxSN*qW1Z`SAyD zbKw~yV{-LeGGaIZG`5rEE6hyIg9oEM)Ui`0hb?dc`(e3U4E=bq?4jHm?;xLO4?UV6L5t&Lm#;+0RMoT3xxOqyXFPSP#CapAE2Z0BO2yv zNcz%yoZW(u{@Sh1q38<*%fx@K2{B);&4P!ts0-Oi5WkO`gZjG} zqz)nM9*;UWt8Uk$S(WP<9$Ai;8d&;xPc3>MM;Bdu?jgna6!R3%Un%a`R?G?0v7#%~ z&Z(pxlcX9O(Y=U&(Faaqa5wMxTmtSE)xP34(!YvU_kotM#wD*2u__TaT1X!JBLF|0 zC+tco^GTMobW(<`+?Xqj_WnzWd6k>=G|Htzfjm(b*lv1VlCM`B5&d`0Xhy<87s0i>2*vge8dg1p({ z09v~@iCFgqdzqbylm;{9um0Rvs_mt%9MdCLydNl;Kd+Jyj%HJ7s=yz{qpmr1Jh&YA zA#}jzYawMN&R~>6ajw7!hiG-;@T~_Yzl1|Z<;vt16U^`E?GCs;d0fOq`vdmX(M&fF z{!16ZV3U4HmmQ$k`(eNCs%uo=fj|%v6}hl67ZW|eu2frX1IBzJJi;-7N8mmOxz}wM z(=2|@X-3VG3B5W?D(v+w-5}->HT<2BVBJCH^;}l`8k~#kXO@78E-G%iRV0ny11yyE zo!yyt&qC>D8ECWBSKmu&vKFiRUD`h&W7uC_ZioB#bq4SWKTO>4>#TyGZ!No>dcq-= zwObAc2K|1REoQRC+N0HT+v^JnsjjW)sDKK+W?FIEYsUj!FXdEVgcJu&CuC(>j{`fx zuC0Q19;i@yEBnbMn#+3#L#;gI=%vWP$chxWp)n`2O;|a3OeMr{eK;d|?Ok8%v)$rR z4m;*C9K#+&b@Hyp3ZNf>w$VC`217G*Jkj+poaW;wL}*Bv7OEIh2aU*Z^;@T!B^HCB zRXtOQ={8FGS#zS&ZLbvW;tGd$oBzD;{}VOP3f?hEWqqPrVz($Iac@atg2uYCC9nK{ z0lR>S5P=&!Zet)RrwZw1&Z%pE_{Q$Wq0F{8l2>;<@Xx2kkh+z&;H(?)Ss#$2J@>wv zUBry*!?g6YFZye3!)Lg$d2ee!1}EkSTY=7KrG;$xwb>nrM>4L7I`Y?GC*Sd47b8Cr z)rX{hNf2OWv4W=xf#sP80*=P!VjeJ?1-5&jQC2$t5#Hp(V2TZ+F6Lw1Cfiy!rN>{fesy2&VUbWzxZa$03SLSU}M(8T(7Z8_bB?+$SGSc zuawi9^Cn8$G7zxF_#OOQInmGZ;;%S~DIC3y8a>J2B1fyiEbV~6((KIGrVD2~W2;D5 zS~6vr%3GHcc?^PC#y&J-%O=hGm6H>bfHzLsxg>ZMeIGp%WqcM0gleZW@Q5(oy1!C9 zLl=UUtd|B%KWo&ljK`yZt006v{I1flokA(T^V>wy{kVA4yVnqR9QRe}&EJ!}pBRsr zm$JhWY}UoRO8$apfJeie%&5yt|A*Ivrgjgv$l_CtoOdz6xa(qQbM>~iUh+SIgE>ca zRim)*b^vu@!^+$EkfG#wUE6RwsNV25Y#`wwrtY|x)2!_qA%W|wXKi9HQldQ9aQ+2< zQTP#ZUnxXclJktUBI&C|C@(;8erUbbKFLjM5)eU!J6A`QqtPR{Bga(HEg@3yQ_^$h zSQLKq{VH?A7rOpRU0RkPW~baR>tML2HXT5Eki}8hrv2S`{}HWYUB;*!I=q!M8c`m4 zq$Jdv-SWT(y6dq&gC8(Mk(qYMmgQqRwT#G#VGv@|)HCK|lLEh$R8OpRXaXjpJbzSK*=!#svHrVvc~9mGJ3xq zyxf2a>HJF%dB1frW8|6EkAs2ByS0W>Zg5{C3VNGm8h z8wd8GNe>`+k#3c8dCEx!@P}RTY{6F7k5@5{9r-!-$M?MW;VPQqzQ~U{U@lIVdzxL1 zm3WmdpMdj`F0V~wt5I(-JHcnJ;S>dw@)P!Wc3SA9*ATTf-Q0L@e3fe}+S1*M6&bpJ zQgsGV0Je^fF74&Vhgj9;3R)>#>+$z7sbQbVjY8cY_$2Sw4d`7_hRS3UyKNN*Y=TU~ zOYhyhVLXXKhNI+qdYFcvMxaj^`=aH%lI7ePQn^;7^4wG9 z#eR$rMaryW8S;VaZ|V+Ph#=E&T=?mWng7l};tZDvqk`3aB=FLn2TpwTnmtH}_%tmB zIn~?B!6dp@NAdud?;c;vStZMQyJXbE=OiY0Cga`ONc8=YVP#ej?5Gg&RvxL4#IZVT zp(iCsnsRcP^>;u%hkDVM*B-!Vz1|v^`!(gdgg}6XGtOC+@4<&$=Z6|(=h4|Lmg<2) z&J5_h3er-NOxb2((KV%IN1w8`IPuQ7kJ^~EpO)&PCrc7oTd`}DjgybSUwKx{y;W&# z3_MxXm=MtkCWQiw^BHP0Y}Qy4UR)S6A$;h3aYt>%(C$GZhmid+Tmpw0{JrJP31@M` zQ{Lw5;KH+3Kn_v&a~+t_uI>LVq=Y=%&g=Z%PC54y8-L{p)hoYw6YlN;jLDSJA*KKu zQo+mXkfF7t>P5}^*9TKFk3b$pO<1eTt-Es#z|8N%3n{@y{(6~PoyD{p@HTWD8pcdwn9!UV`o}+<+A_cJ%J@u9j zIM=1cC#18=sMP~7O>LD^DRIevp9*%KR~BL)a$|^n-t)!sd1LV=-xw)X1sJ)l8$7`+ zF$?khOl(&0|JJ-t=zP3y8DthiFdU^c*zb3+6{lg4l8q9D{|AXhT^Nqlio+vNo@l|1 zlm}EQgK0 zZUT8MctC*H`U4Iu7c8Ng`O(jeHf1%l55=O7T_4R`ch08o)rMfk%c5tht*x~W3%Nfb zI#BGwNDdoWF1)Q_JHx??xhPS%ZVWNzAv0p5wFVQ_yV`CQg%|x~gXLoQj1y_4p}eQg zF(}9%_^n;A9pgH*4>LEV0nDv;&L(8#uxI~dWihu*L$~d7G=^SJ5Y;v@1dnm@CdwQ(5(Akgd0cUR3}GzDLn zv9!cX!_6(vabTh@A)WElkgQhXa9NB(f|(*SL?uI#OqKf3{XiY?qjt=QwsVbhzucd; z8~d_q<>mD{qA&90xzR_mCu(`itS+J?^3*js?SiX_u5}^~6|XmO`CMl_TM?to|2dG{ z{bv*VVi?bnjj1C>AEzUD2Kx90t$;W>1z>9VU`wU>G4CaiyLL6_a{Orwr#8U1^L{p8@1kA* zg3|1Fvbf7CsYrJW@(~S|`07aA(zgi*_Gn|nS6j#lU*FW#p^dMKIhyf2XZ*UgCn{$R zu(yq7O?G=JY&TqPzDc)JR9e>Mt=A;YbWPi=9HJf8qIVX^e+#1<@tE? z^jzA<2{_nJCHBh!Ulrf7pY-h5-RiCSOd)9qriLVMX+hK4^($u8lsxX}l4rr)oHW4w zp`Wwk`fKb)KE*>^WZB9N-d0!p7}8erpyK|&2aLV5crc-7(T_NZX6ZaX_bq=b(@D+A zJv026lrK~M_vr;%Ocai474?O%&7hwQ`^kdjHgJ${svgqCQN&>y7n>MTlOK{|zWJnX zQAzdQOw=%>y74#v@8+AtM;dkI88+Wm`R5zn-Ighn3KVO$_a8K!7d0Gp(tq{ZOmrIj z(Z^!Q0&p6O`|B+YjG}81+F6-#qt&hSVIda49$MLw2KFLhVVAtiJ*y+p?JuZ&t zwmgrd8f^a0emZWnb!=y#JW&#za~jO6o~o;~G^t6?u`@(W_)*Sa&zX#>++Fvlj2{m< z4Z$oB4JAm6xf%z@q51RfcOvu8WC!V<`c3?3S`HvX4WyqHF*w-(X3M^zXS?M?z2z#> zoQ9r9wKm4GH=B$6i=pZwA|ic2=fNWXH{UrPX;Hzm#u*d%Ek)_vlI&mN!Zrc1w~6mnxiiJ=;A=M3Hp${?T3UZb z))b9%O~PLNk@m8VK0O6Gg($D*6;@*0ZUmdY$sc0XuVTaYh?*+Fv?h}t5-v)6IMx%Z z6V*1;90Ml52V8b$2E-58ny97sT%&~>&(`ft)|FB0MCcJirwd;ho@nM-$5B4%gK7vk zm-RIsY-ZC)-J(qS_lqhOAf5UCxx`vA>W%Z~RWs4d7b^R3}`Z-o+9*xx^KiUl7 z!NPbkL{@K5z@3Eub{C|O#|n^cKyAty!Plz8mX@5UIbWD&>n04VZC&=$m;CEGLTKoR zkAQq)+hH{&fA9C0W5;@2-#Gi&+VJKkgn1qfj z#%1Q)@QH1B8a*!q%N!>Z=~DBP?Ehjzw*=RMIeFrUdF$AgfPsh$qc$+j%(Gdu%3wpA zy2R>oo?0I$NUvtJpm-~CG*e}UE6NOgR{_-Fh=Fx^@ZY-pz4|E{)$4AaqPUo5ETEQf z0VqlNv`3G&Q`?V6zkI5mumMnVHXUqz@-a)H(8BOe0)ULiP;5}>SXN#{ee)r;ZxCRi zRz41!;lgvd*HlSplV8K@x}!Byc^s8pA@-XGwyjhPSINsd!m4s~SusnUW`0VQmwvT3 zdYi)>I#Br}>k)_lNm^v1i;@lI+iW%V4}{)GC$CJ#W~{)l*#KZeJ-b8R7?vr7QHX@u z{tV%1cw<|C<665{g~;+ahgwC~cy#iWN6C{;NY=Am=gR21N6 z-PLQ_7&33pw3oUqn~h4qf7nZU_JqfTqtW8Og|f)66&ecmNd}G~yGa@XU{&mjN-W#^|=^Rb%z5+Y%^D){OQ zpwEPb4@=FeY_D&=MOiAPcJ0Vs9$OVhk4Js|ZIH^anzi zgzF`BdI0Vj(`+aH5-!#ubNxGmq_e7aWdmyj>@1$kut^V#?q!bk+giJT}RGhq@*CrxvE9 z0K<3@W_$F1Spao5?mNE8>NSOmk;DMZK9o2tDoHeD?{&;=jk_j$h%0L!8L+^6Ji))Y zK&O7d7P>KTJJ0-98Hf*NLUf-V1e8z3>pRKn07o&1xdc4+i+)@mUygWG=zH|m*jP_BA zjBZAV>Foz^%)Gyf5iz7h0R;3}yLm_FKX`NMOkZ!)T$nki&^Ud$pF5>6^p}QqBptYjG#7|n3%dD&MX7WiJW>f`v<$5JIm30)(>s~ zEH6A1Q(aHY>oe^3(h0OM&Y5Sr^)o;81hy3sxGJ-2yrXHSlz5POO>KhsC!%Lpip!=AV4 zFx^HU0TclkBwXKihSPIGV3^3co7H-odPGVS>K@YvdxG$ZC&PFFWzx%&Fv)hC@v&*p z8D{6-P}N>*S8#HLFZ4_SQ~oVfic|C9P zQ=5!dGzNo{9ZeC+zh{=Ty14OAp8=Aa=~3?%5FOA23j|OGn?@gjNFn}(tDds3+W`Ns zzy`)&^>7Fr%8&$QC|~H>_;K;cFS&&g@YQa*yY<|FHz_kLcw*&pWnu`+poY@p@;_-zhQ zI63YVR`&uL(_a#1@F8|Y&zP=nGIC#q5R6VzSbl(s5q&a{wv(Axl2RJx-+Z^pD8qyPE@2^yQwN zH>Wh9TP-kt8LyV1n3{B;{}Pk_^^Z(>Zs;rEA9eqrT3qvZg^9^wzp z=^y^Wt^hwVa%HrTf%V{HjCS{OIRCQ=0n|=T=|QfenWf?G%OS~rc!|TZ3*r6xso;DE z0uowUI+IRt6EP-H)cs|66+?{6&c7ZF6_3le&%{+494 z_D9xchOE!^M#pL28Ss2$r43_3Fwgijn7Fh4mDt5> z41cpPFDeIfaS1|ijpsQnxVw_S{#4C|7DNMd5ZaZ_9&0GtQiQw`(aB(^3OY~5cl3o$ zm4C$>#sjBzRncwH{iZr}$k*SuMe}5gZRoAqA1`3pD0D*u0$R;|lj}|cr9tRvW)QL_J@9M) z^S3~6Rw1nR@6$>T=W68%HWIgcz^_}`SMz@=V{8>cjg!%z14m$Dc-d;$n#8iwn>&~H zEGcc4HJrirhb)+^#}^N5dgqIBy*}zzV_u(2ll9vZrQOv`af|u?(J|Y}v(&D&Jd+xm z`A3r7cJo$D^z@|G7(L~RjR_0MThZj#4|d7m7>72@gPsn`Yi-vo!@R> z(zkxMtk1M9ldwvF4Hv13%R01+t9i*z!!&12*Tv2}^KfHCv{4KEne$eCzU&O!Y!LTf zlB;cqGMgL}_spJrpy zT}*5t_0c{op9+k0-JLQHn3-ijTdFkX$}Nn0U`=ZXpNb5hEcrnQ;40_)qmA-kL^SOq z%Cs^X3Y~iCfgO17ti<=ZO8^KMLMrAZrsj&4zCDUCw+Bim^IsNiq9bFI+;A;D0`233 zPn3cU-^MHD$6uU23~cZP_A&CO-fS!trCGJ?>jcq4N(-*)zq}c2I69iOzwr8z2ODq}^#bPJ;Ycmre=a(HKmO{ZC!tnlHgA`INrP9P&t@+uF)r zTDl4kdzKP#&ni-`C`dw@;^m@Ga#+H{S5i;?sP6v_hCVV02aE(DTk-xAT!3>(=~%Ut zPSx93RL$FLy)<}W-LG=Jqxu0)>PBr_rP&Y82)l%?+dV|(Y$;)9X+0aq=`!B zf;8AUS`a0xxhmi)$adBQJ5B%K?#D~mz%Pbgk@Zxve?62DA!W6A3qtNU>?k8pag=Br zm3+;Or|av!$&qRbVZoBl^gTV4b)Gxlcox-DH-E@Oe>8fW_j=!MddmT=)W=@YEYH-@ zzuYJCQzE=$CW9(~D3zU6LKV4J!VfTeir^8+$TFMyeT#)E80&D9u*FZTPsPb0rgsx` z_3)~NhKpbfX>t~LYxnP$r|b3)~LqHyhlc~()EzPF%Uo@KnpZ)jSC z0?DA`nlO5^|E$5UiHGt$WaPpgJ=XTTzG4M=Kr2So-1whwY7Q^V*9Q!sFHYgEGSb z6||1m%W7rN+SZ@h_rqsX!W#LX=^w1jfxJoqXkW+El-vvqVk9j89r>~K>vr(_ew^MA zDZ)DVP?3JU>A#|+(eXL1j0qr@7Gm%&qoFtL5$7>{piE>E(9zu-FPf>{=amRq7VLEH z#<_uzbnpTU*4yh%Y2bl~HT#usZLNx-gM>Y^V&ia2MY34qBYn2X(SUK;(o5!@Xa&ju zxfhO-fvwLy9O|A^zIlS%&4=3c_L62# zPA>6R>O9*TuR~V(2Dkm5u z3`eZC7|rmRBtcWgJ@7TgBzEU#{nBSj)*{>8tNC?jREnmxbsdq@y8W5Dx# zo`-IJ{8`30@R-xGn_zW+{at79c4emd>791YQ;4jIIC+^uh++6=M@WNit@c&}s+tUT)7porIqIma0@Y64FAHp{qyu0R6?G_KZv_Fc0B)eo-493Qvc;(QdW5(>JD}7ZFVZ3Zw9~f9i1EJ zYQA3QU0d`%I(TMmqxso#sCLHYVQpK2)rh>|SMMbp1|R6T+iBB{Kxh0Iu6yVr?LkYu z4=T%vRi-nG@`zn=88l0Ht@j^B9~YKN+BlF`?=an!GT%n^^UHs0FJAL+GJakvT0}34 zIC3-hY~Y~zuBi~sejgJlf|)J71!&j54un~>p}M4U{$%eVZJj=UsbK%h)5@`(r*xU| zO{>|}gjqW~EDq!w97MTwA+yz3hXVo1=A$`l)kh2kQ+eA?{BTIET3%BbFkfgnVgX$! zW(2M&_5aGrd)--uiZ3t6wr!)HTdTi-Q|H@XQYLkJE)$vpNX#cZ zq;iTl_k7)#@)+q({&0WGl89AH{tAkfpCTB2f%_&2evB{%{=0pTgPDd$RYAzp-RH~! z5vr-1amU0!Z5A)X!>x?5DxV)_SyM4q2euKdzK&V5aDI979nG-_I(~)=BU+*xj%t}L z+tCT~%G3=n;~eIveEG$Qnc7Fz^R)`l*>v7ZM^q1IzkJA>liaz^2%r*P{aTnB zK!}662ZyK|9}+3!w@{949FylP@E&pvR#)uY!$Q#t3HhY2BK)W%G*LVRXkUX;o9rIa z;R1sB7kyJdEMMQmY%7QXC836s|4KrC=$VcqoKxXiyUf?Y$+)50M#Vs*OczzNU$}f|hX4saQ=uL=Q{n9!YA!t^+ocv?$JR?4 zw8DEqvxRpjrYnDgVhOfNlGp`Q`%5G7IVLt~A7u;PK%}8cELnS@+KDP8@;C0z{NCJw zh0wzs!)CAJ@|2tR`;F&0=3wHg5~EPMCF;$YPH76I>0%!lxn7b--{c#PeR7rzqDoRfaGp%&XUA8qT6oE)~d9&Jxs0%H-`eAuUP5ik0q9Ny$WJ!6x+gnHl30KF4} zFZAD7z`U-1uya6hQxp+lQz!G{sh!YN&eBy@p%1he;{JNnoR{4L>n|WDSz+>DJ?ecI zQspKsVy3>X%zPqmHOE(#(KKpb+Xq6or?;> z(+5^=KB&I5YVb=6RfpM~&_E{6GtU^b+!k0X*k6+n>dd#5ICcueiL6B+geMt~mSTDI zIlM3X46VIT0Gn4(6y|;F>6?LSPl{N257^zMYh!$R)@W|Z=nQpV0tVu=R8Afmw!Kb_b$V1%Dw#$0cJ_oA8SZ9tG~d9qJ~Y1^;=B*(L9du zzLuqKYF4eXo&Iwc{K0g8u2$f@vsS=i^wocU;wNy(FWs+pWuRstBE$V>#rCInf7}uu z`N8?M$`3e1aY*X}XW0#%3NrnKKmni-QjKie?lm5PnL=FiL4h)(w~(In%!alq*)5i4xAaq{p;q&c+6* z_r0x{QKz@;0Z&(6x(-uf*t2HP?9Yoo_O7m0K)_R8tH;hM@3bj=fXD15Jq(3Q4-@l+ zdVbr%7mxqE@~{YiqH7v>ZBbq7*_>L>l_>;RrM&Riu>O?>9~$S(>HS7XBaeD0lU*kE z@L*$Q2>*V41N{AQXwTgF8QFxttkm{okv?Z}^KBj1hlV$R<7-Y15sDSai$*oymaq5b z7e(i18?uY~?pEL$e_tE{F0*T9m6J=JJ8tgIdLp1o*%w*td8=lTB6=cVEUCFPRClqFFlIVvpmFJ)*640k8` zsz#y)C%HFt?Yt5#{)e!)4vNAH|3(QV1yls2QB=B>P7#nsx!pBz|JM=_tx}%%!RX)RH*eHCeI&pUx;k>&eK#WC{K_vBJM;=<+Y3ua zjItRF1*ugZEG-6hNN3P4J-g3kL;-Zo!5JDys`;q54-fXyi#`j_J=V3r`v8d-6S7H2aQ-l6r=T z61y{{zCD?}&}VOel-J6ywb$_dsv8P_-D-@|p`dksJGqlTo}eBYc07C$$ewygU*yi! zo@{VKqDEMK^`25BZlmp?0e|XokW`{B{L{6;wt9+veb6IAutN=C zMs`Y%sP84Rcx7u$9~P#gTGr(2X-FK}z{M*u(`g3l!*rNzD3-LTl(v01(BKI(%WBj9DBBOSY-_4KlHOWC$usTS+1W zgJhL~s$`8~h$%2=wC8!|1*66)8bmW}_TdCXYdtKTS+gz9PKHn=6p_W4%Yw^tH(g$x zM1VJE4Ff9P`YD7KV&sEL@J6jA9j)uxcgb@!L1uV?6Aozg*pq;=U*nDdQZW*gz;35A zSd!q~mgjW15sPciU_6)E_)y9v?EKDjozKXRz9)$ziOkSjB9YbLd7on6y07{1rfWwFv>$AP90`w5EHOT7ooSybv~Lc1?QAtY&3qCu zj;~HQEVoI|q|=8OIA#U`M%rnEmm+HR(4O;26*jcWkeTitmqqhvXtfK*JYG z8AO8$`u!0*LQN==R_rI{%A=_&pC7>AS%e$$Dd@Sc27%aeGB2ChynVLR#E5Jt<_ED7 zOiw*DFmD}>(bH95_K_B?-Jyputl7+U%gi(t8WENfeZ3qX7wWJ@R`Rw3mFgl!0C`s4 z2$OISX%)v(&|Y8l{A(|fQiG8OFL!bw^P*Yr<36XpHxmfb5$C?8tiOm%Bg{XrTlw1M zkw0h7vj22tq~{hhZyv5WcY7Q(OH9=`CxOIk)pU;|+`?l4$^J)wF8At`_b#h1v;A(- zt^D@GhaYZc7A8+)AS4tSH^zT=)0#NpWIZKdc+=VKgy~{WC-xX@=*A% zRU;F8GqKN?oLt#)9B%}7`*7Lzc-L-Ve-vh3Y1aEt5+!Kiga(o0JpFqDND7@<%r*al zdoA2LdqH~P>brJ^67FZ4^8uo%*wEoM>nxS5n;{EqA8A*tyrjy?%FZgd-k5CP0RK-k@>uvfbQYOPxctYP3#H_$FC2enTcFn#dL*t!UBS7uIn=#xcSa;yvr!9xF`J z_v-s?-fF)5G7b_;!BXrF28ARids7T|*%o4ACk&oz30m388KT1g#ynrcY>LOG@emJr zKyI=~h(=>GQ()e-)%}tH#XD7yEIW}7HVT$C}^+}^)eXxc5?$*BzXVw9_VP7lGQ?ZycY2$LQb~VHv_A*c=ljWr z+)?=p5~P4FCY$z~Kr(ulq;W>V^edl#Ivfp(Oj02XJ0ubD#BS%V0fQnl(l&-~j{bL( z(Wj<@ou;6>MM(*tF#XT^OpiU=!qtp1NmqR^*t#;-#p_4GYs_jKM41_@3^|;^RHzS;v!V6~&k> zNIDv+v)LsqPW&`=Mi2s&-S;ly;NWb!pA8+F8qE|o6`udD75jZRyw z&OH$!2wqzW;u!v8UtkTv9^(=a%|=T|n!_))PlJ8T11a9sVCucfDvA`RVu z6T(D_u>9Tk{0c>#^X1bTQ|v^jaIa;kR?Pc>n|m;S{!4WYeIp%3>m( ziMUg#*(TWYd9!4|Z+n%p|8}R}nZf`U6x1jj*XdZ1udDvY`qWqT$?@RI(V1AZjQ^J8 ztxl;OUF*e9?|O%#tFNXEE@Q)jo;zh?J>NJQ7#WmPWH-7lg=XbrwQH28O>?XdKIreE*++SZ*ZmBPUF>q z$EEo#WNEqspmjm5f`dVgTzBj&G)v@uQ7(Mx0#*%xwDKIS^fphf+pl`>eiqApY)dC z)V@Lz&cwUzPq7JA@5cx4bHrPudrIHMc3@&Xi2pz@({*+3-bw8~`|SGSH0}oTVy2rW zaO6ELN+?+LfO_!XQIuGPirIyYv(B1hH$+(dQpm{rCRq4MjviOC4u1CZlb&jbiKi-=|ar*B%N8i31U4_xe-!J6ZbVua(F zfm535cxdeLekZQF-MJk{?SVoxcyUk?s!-L!AuOVlMM4vWpk< z?Tvt0$esE&S6QG`avgxIonOQ42_&$!PnVn5LlV4{LHov(6cmvWxl0O;8|7dY)~Ioo zMcp*Q(#kG&eSMKpZu-50>sSLvuyt>SrFfpcZuZjkmLpwk65;CELqVrMQiRm}FR%%z zq5<81)3GfLvid8=YSHDFV*1(8zsDr8w(rCg7EuAIg#@%mvauiPUBWGnSj?rOlyD9U ztCQSQ<05XoFOZw%fX->OeDOZ=5kkNP5sgk$s0B})xIuj{(*50i!QwA|yxt#I10t7z zR|KT@PucSHHm4wB<8@RK%gLwx@;t}f9vw?&Z)57La@YeU0b>YxAr#HKzTm`j-t&@r z>R=bkt8smLdv)4+qcfgKtJ5sW=y?$8MTPN$fhTz4LquZDDiwAaYK`&EQfBzX3|+5i z@+Q5DZgh>ZqY%skpd4q#rWB)@`J$&b!Z$_nfIVo_A{@9MkDO3Vqdue#F~KN z>qqZ3g&b%PcQoO3h#8bxE4=)#jPx6z;0f_mAwo=W%~0eb;t8(x%a^>=si3N#wn>#l zBq#=Zq$)lpBUobF(ET5vd2uQSut367c%i=-ii>ML<02Q0(I-pK0bXea#-HUjQ{3lg zaZzTMk-Jt|8x$2IJg(E~6;mUH795zC@6{|+x&-sDfyrUIc+|R&+el}webl8KlMR1yct0SeXW6VX6mhQkhS$Ec1tq#bi98^%&O_LJGkx>=5{5+-{uae z{+}(XoIX?nq3c!Yn+;$G&nLI=q5BjSY_G)vJHiV?qzw>P)$Mh#hJR)lsNSmMQ^AVB zZ^0k_bjhu9gLM9_(I|rp>TjF1B&7!u9Ate}CGdeVHhz^ZaMaf@Ra)U6^?2>M{4LHw z7_JupbuUocX3L+yuCMEh$rLx;K!uj@u?c^X>I!;hCT>dV;v&)w$DoHNAInVD=yn=})y@%l%;&4=g(oQEwy!tJI1SEmrAH{xmt` z1#_9yalXS|pGmyP(@uaGaq`dXw_@?KM?UpV{EJ)U!^czYk8NuargvCfYbfE&SG~P_ zJ#beGPz_{1DN=w+(_bcwX(MXywP_o_FSVHfJkM?Oo?La7+xW&LbJ7{MAFMIud0PgLeRr*? zSJ*V=k-KQ_;J~t=#{tZCN;glYOYHROSa)C}r$(nb=gpfQMZSd>?(?pBueTe9MqVFa zhQjp(wMNH;(Y&Ig+HgA)ugEr6UT2mkDX?8ROk9``jU82QjWP=>x+dJ$Z6}s*W zONtZsV~XS)7iVR|2&FIbs9*2RP#_##7aH~%oqi=jRgIj`MG)4~0=&@f`%ryqhyCqf zH5O+BI zgIe5ojqZ1C2}?IdJw9g5n`C6@!4s_K2qhiX)~RgFw*IgFjqe$1m)qE4-e3CBXuQp- ziTu?k3o13Anz)5*8{0IWxNfkDs|wVYj?d~e9EIG$C76o4cYIj<--)r_49Melc z@~Do;YpbvtR4BBeP9sFUBt-6Lnf79z>{m3JuOecsurq~Cdu6Xs7t#L`PH?}i8qs<2 zrGw-%&cdJuH&;vzWqicfQ{ql+!i!LW!LKU}tDv$v>YG^T1f&bgJO|tPa-Gr~>wc=a z+MK=e9*!j7#`Xg9W2yFtQ%*R_9nbJZpzyDERFhxD=#}o1d6JGjqE+2u)vx}zBzY1) zJr$6azS0rd1?bajQBhYPXna;b2r1e$`=i&|ZUY~H>&$QLvFQy^ysBUKrBg6Pe|o@( zO0iv1ECkxH(tZ`KJ^YeWR_=fO%)krO{^9b}r(DH_9wAwc&C;oG#L!8U?cLFZ);`{7 z`0a&MMu=))fr~C`Vpp1p9a2qaCj%hwB%T%@(fQwz22dPCD>%9?^B`q=RP160cDNIe z9tlIwnTV+c1@5rt1P;^lbFyFIcN^<|@>q*uU2Q-CCPLyVdWuN|7eiTJnzQu2q(7Q5 zj{ie{I{8G_m>k+)EhZuX)@ua`fODwT8PAg2*_&cj>2bm;V1MSYIbCCo2Aw4P7We?~ z>Dco@%u+1j%DC#v$UGDhzVEghD|Wr9e3xIR14Sa9&3U;bQ5H8z?A30w|DNKJxFA4S z6ei*zA&1OGFCdSTG@g_+6Rbuve#6*wYN&GZfH9DH33_|zE9cjZN>=)y5u!oe0pM)c zJIOUHoGXAPtT8dvOD-1k6OE(0A>J*^&~aX`4!eXI9oo!#P?UDQ9;FpZhs=!L#Qq7V z1TO}-#3#7)_Uc2?nv2F7c%7!&P3_R?Wxh4PKDGJnPl0 zG1@LY`zABss-m-4+(3%;&HgU=TXtYxBxq%PXk+vCJ32J5z%n540=-D$ywVNpBz07+ z9e5fGd2Z$Bt?v8XdR3ZOffCc{(zdz>mBWHb*s z7#H^b=-z)%*@z8g-msuob#T3hs^Bf8-9O_O^F8`pNhQF{?}|@I7X`5T5BPG0#I9JF zp3h*|9dt7??|1`gALq?dAK;4_e9X}8rwd+22F-?OjDwZcmTOXr+pr)bGP4|%S%ErfDejHMq%SEEVR?(V0mo$r{mn%kwDEe> zN2cjWc_trytekAcFl#fMZNll3qBW$r^5bej!{oxO`p|(Y6KCD~&`eqmk{$F;9=BO- zQ0)C;U*+q1Ixxh?bUT#f0SisdH_ZSAPQf2)k$H4PK=Z=L3Jt9f^21b}dx`MXfxYd3 zgWLD!WiiT6>=~9@Q`kn!-trZqcQEhknrZFIU-U&Jem)(L!_Jt*#R($nC&%a_3O_>j zPbe)1k6#b3iDz>pyO3!Qtzd|--oJDfB|B;meX^`F(-?Y1Pt6$pW;x|bT^W=}{yNmF zzYB#9y^su!FpEK03%7BzIHo6b6OR&&5=@4T87>J|TN8p|QM-EBqq$G392$?Ifq*whX< zos7ywMr~I54IN=Ly(J6KZ8i`bSiNTbruV^0FTdQ)ckAMW{E^)6)X$%$RpFbN%{i11 zo^vT*NUSd3=z4~I`_7Xn-`efZ%+iTzF`%mi<}(nZQ0USY{SSQw0dQ7KDQly~ofZ%F8F-Pk}t;+A6%JfGNI5j*1HiYi0X;Z6gW^7wN^>9P{tzGf zPQV9qwCC0n@Ps$k6P@QP14-mO=AGf2BWnelTAL*|ru4e+la9muqW@($zhd3H-?QH? zO$qa%wRZdk-pNp zLZ$ieJ4cD}2=DRGT%UQ}&bk5C-PyhWPxMOuz4*c}PFNaZ1$FyqLHzN)o$=2jZ-k_ z?WV;0^iw(Ad-El?^|(!qApwt(LrbvWct*Kzt^5SL+p3^wFAnlgC0o|xn|Euh&lFpJ z{Q`e9UU@#fv@xaloF`ER6cLcVWqJR+k1Bj)TJzB!82ab*`+%uMVJl(Ez&n)OTx}aN zyCbCM0E+73xET9|Z3*Zg6tlJuzqjZQy>i#2_W_$VsIv-hOgsalBdYuXFcmqOI^448 zLJVc?W??|@!9sni^-@hP9ow_^hYwC|d(a~pkoaqMP*5$rwb|m_&*yW@cwn4S4%GWo z<(A)UscHD5^{Q3Tpnn_j&p#@;9F5AJZ}pV)wrCRBOfLpKl!+Ngj~w*W8xis$gZXNCHuXUg>sm%$8h2=1`?sdVkCLHXfEknr>r|)#RL5RU zXHrFr`bq~;9@VRqC9?}wzF0j2PP+~eU^RZgQ_H6k3f&)#%9x4-IsyYJVFg91^o zB=z6f-RC`%6jHb~`uBz;YhCwqtHuN=&w>+(dcO(NPpNum!(aFabFdJ%r$!fxutd$6 zNGY@UM(-cKUH4Mbp*=Did$jOD`d6J-lm$W|AGmWsHXQ_FaJ=fuZ(EdU@qdx zbSnSg?X!7|0=)9hdw!f24?Kw1*6P{T6E_iLak(l~g<_B~C2?g<11eE6W_M&dcNoT% z;&&?JOEkq(nt^Bouv(kytnLs0jx`@CFIS@!buH=(pCGtSK6+FT z-d8J*pc(#hY0GwCwJKw%5ybl`@D2efXj{U9^)$v|#)yL34t-TOhxwgP;+@2!;NL36 zE6T1Waq>A2a1H>xar9kKVgb(kw*VLU$5ZNbI@DFLFmA2R_Zq6xWY>_U8q9`ur&0jZ z)Sf%+9av>okBL~E3hDvU8TpG14_T8#i;%q4IEz&5nNan=lYKj!A;5cHMR`Gxv83@R ztX9hmq&!-kBEE#viW#o=r?CKBU<|IGwF-vS1XVUn{GV<0Edm(I&V@Efk90&Y?7YWY z2v}T{1rte4m9*KtG}Eiw!qR_*uev```Ky?K%K9Ap8Z!D~&g7{}F5O_(HBs}^Ev@Hq z^;g7GZ$*!De(N0Iv1&9XK0x|EoW|D|G6D>z`wz*uGgb)NF-72S66>w5bB`VlhXAH* z_xb93kiJaH`7l$EivOzigLvdlaS*^WZ89>vwrMw`p3-EyBxLY;b#7?9Ad zSMInXE#P?dIs7S?>iX@c##vaNI>C@_NKoj5DmEpwFAr=!N>hoQrH&(eH_KFQ_7B;P;B^pBmUOFsq~YYcm~h88YND9LUQzpOecSPuX26YqqR0NiBWFl$v^Tn(l!5KY2BX7`aH$?ckAczu*hxCu)KmP__6rx73h z))EJ|gL)!Pn)0r`G2t$MzXH|egE~P4sw(G;Uw<~`Fa~)X7U^aTM+@CK?t4L}nAj~- z@yvSLJHAYppD%^-Ku4k9sK&?G<&)TB_!hhkKr@%MI6&A}5jFez^i|FJcWcPbWEp6E zb!uIA&Glf@PN~mJGKIP9oOi0aA-908U-2GNYxpB=8S>9MDvN}MA17B3 ziKkTn%-rZcG$aab@Gc};%9b$4H=#dL;SqmR_vf>^CjyIGIQvVIp^JDxuR*kEa`i9M z^PHhP_-b9=y1JX?b1Su$&_^?JQ>+#@J3g>qbL5_lxCh%}5Mc@rO7=s%c|R+>uXT?H z=NDj`k{?zU+Xyu>L9Z@}ire9Hcn`<>sDJ_xqucO0S0ZHw}nt@K4 zNpR7*3!H*e^re=8Yl6ZLLB&_f=|v102Fwjm6nE$thplUjGHZ2!FjXBfUcecey~<6L zW(kljX!gXul!pv0pXO{#i4d#;s$NJMGw)`sJO)f=#eFy&Efa|6H=?fU_sI#PqaAh;eL5@D5Y*x;30l^H7NrK(ky%J29Vz#%g} zjTc)idZ;@XKnHpAeCns0ZRu}ZH(Q_~Fe7BpA{f@-G7xnCP$c0hyfFMd{!H1hY&O`R z2I6&rB(G?wu-nzuDYR<|JY9|8TX^jc8U82#p!vJdzI2Uh0IN67j2x47wMFGzqD3A9 zvyry_=~M$p0-L5^xWIIV_M9XPTd$he?n)Cq-Isf({^Pp)gxWuwZPJa`Ip&Ehjpha? z32r*w?C(uq{h!4JMRZphCY#ijynqOQ&?zyzPeGIOOxt%)*q)M8{#iGdaEU28;b#w zPT~ z84~UU&f{<+i+wBtiWkT0eLVE-rH(u%t2lZBAOqkwZd&~NEJI1AHz&9j`jcW32^L9a zf7mxLaWo)f1CM1O3dhXN7w!sOx*7G5Xi(Bo4h^w_m>anEKcWT zRY&1tw5E~WefOcfwitsI9{{{&ZK`DSduT*5D!h7Rh%+xhew#UDq2@@gf~w{S(Y$0s zi)_K0l{8wkQ7YV}YVWMJoiQiWJeqIF3x|9TF@)Hq?w7+O6>Ql#(g#bd`BkeAMV; zBb@di6qU8K=qoZO1)6Q_6FnnI7{f(^_Hp>O+?9Y#axLNRmO~UJXFhG{)D&$1nyXZNu8kyz1%A7ES-xHptRjf%`MBw;XmnlI#pt zK>*Ek5_KtDucZDetVq8`m5@rJPpkq3WWrr*Q2KMD3o;jSl2zyX;x04GZmxC;d!PKx_s9hC zyPkwg`qcq1DgCLbzEX|p1)rG%+HR{YJzaoBKW%B|lam58q|HL30npw&E3JNGUW5(p zHg?yHa znk^_vIlm)xt7aaJY_ex=y8p9GS(fmG>}gf7rIb4m2f`X~J8sbSe|E z{J|ZKZCbr9D{3O8^kgp{y?JWB!E4P7KClucW>-jVT zo26|vGk#NM$5Q5e;KG`r#%P4ox6${TlcKYN&sZt^ToNcAU|@F6<}p&^qUUGEDF zt;4Sw15%v{IQ)_thD0uDv7X+>YrP^~V`;i3W7lWA6G@|_K)^L@)^j4Q>VlAkNzcHB z1F0wV=?5C1lX~X@I_dRzGbddznTp6C;C!J>1IBa2C#^)cntL@HG}5>fW;XVmlm@d= zkHVnf*EJ>B8O|3x$FaM{xEMq1T5caHT#c`Qf-B8zVmc$ z>!)3@-O^v);sC1`wS~nP<>AK%lfuH6o;s~(EWJsA^atBTTm zImYYH8$==^qj!WUg1{@E)=EvDsaoF06RESURGAg@8t_eR!y+0wO;*^VMhG~|Sr1BZ z5JR-x!8}A~xn1I^N<(Epx<`6%o#B<$|DsK@+J%lGphL+nJzazX7aD^X8^$XCV!mjv z*E(+yUZPCZ)#Ac6C*TqO=`Pk=`8oY}Jk@4Xuiz;_C$`AAVV;+jj-;_Xd5j^>Nx90D zM|D`1O+_K9C`h%Ktoq>1zu+CkxxKaDx%g1_fPMXRz^c2X$QrGT??IH z4C#C>#Qq@(64k6rZ&RrS_k3=qEXpskq98+=QdNIDTyz$$uNp7cZZ2;WLx{wbp(m6mIj@PabaNtbWDdGMd%X zUA4V0{+>K3@%Jcqe2jdk{9A#TY9zh1xZT-LbQWmXJ!obnRPurptAS-BaK|>*Kxuhe zQF8vDr`-}L>r4r?H^XR#EqoVoS_}Hp{v)y`10riXAhQ0iTIGL`mTaR3gQnNfyb6A< zRD`9HgzYeg%>uW&Y`;&^LBJVY)~=9jU&1k6!pi-fo0xZ9T*IK+A^U- zLwl+%`%Xf=;w|B4Vn*OS;>XoK&NjIzVZ?KEYq8&5Tf|t7O3cTLE`yLV{lk?hCF`au zlGZb~$0yV>=-DI7u)BRZaa2QczXiJ_5bn?YCX;TGIf(a*)HCfTYCW)qrnK|5uVI3c z>jIuzDz49;u{`H_4lY)q+$*JbJDVeB!>h7G#;L9M_(nr1ToX*4BAG1TKWBFV?s%_< ztu4uJ-Uby0r4?n$I^3^7T0v>wDq-hbvY|8p@72L$*S?um8gG9 zLhN)I|CWWL@ho=MXTZQ})3W?K%LJRg>sfMEYBTYfnb+S6N~|mN^V8Y`!+j7EKh>b8 z#c*dcaFSo+O4T2pz|o^s6rCfVv{fT{diSr}^-Tw1DK-+Dh+>u}!;l>5I~2qLDRJ=_ zQl2{YVM;oDWM>&4-+(C_ueF~pKCsIzt%ZC*9V<2%cc98hI4S4%)A#eaE7UV5JOv@O zLY82!Z&AGcY=r<5s*;GFd+X$6K^ZJsfCV*4DKo-^J9$2biWHZ+vLrH7k{RGp$~lrq zs&m-Pg}s18z?7)PR+W6374eZO?k%<^xQOO2xcem&#araKTB{v#3~TYaOrJ8QXm%}V z1QmcpeQT)kI6is7eN|Ryus{)GM{B1;@%sJWj;B>vsbVGA+$)^s*RE8WmamjjKaq2Z z8m#x11r*cvdpJn?IOGiRi@B&PDT`Wsv94|9D8Qr15S?R6gA$cTbxNF|`^|jDHQz;? zQcmX~NL+U19T!C_*h%g~eFs~UU8Oe94p9PG3^B~2_XwDnycq*Ik_~QATP0P&)+2R4 z9?+d1#?x38opzHH?)XCb>78ydD^R6~vXf^WQL&%hB5AtuUQAhNz9=!19CGk@vxkXI z*a;-fWcXj zcuVXEzZxVtLzhReBbD%x{?c|@yfN>lr04YPSns_he*wGb#z4jw<&7cIYzU37>wJjA zdU(T5-+-32*&|U7H zE{yK%ys7a%FHcp6ZFCSb5UiF3Z9hRsY(&(yK@;;{i&xON9Iuw8SiZcjA1Aq@h>R-3 z=PZdN5rJX?eR%rUxL4AqL2mZ46fzFQkxLw;*hAnW`0PgP@iR}g_Gn5{c*F<|>OJ(? zA^~mt0~aiBK9q}04ej#T(S31r(n8Uz1IfF<_P)`JX9i0=?)~~HLZ=_@2JNgm<=VMh zr0kedmHUMgGPs@?QTZkO1vz8BX8@cpI}UO4u9d9vt<*4X_ib4@HfssIUv7Liqj&ge z>sV7fqmR=*eJ+{L6E1d?ddA*Vyzn))+uE!-S?wO8j0f5tJ_dIg*$GeoC@6DSZI{#i z!Z!N>^ZWPfVtvZ*v6abj|J4@UL%y$1F0rA8OYcK$(Y7;uh`)7%CH~|1;2z=MewU{_ zUp|<-q)5=#q9eWr@3N!}s8r2-!WbN>b5qr9kUa9ly!ZoFI!YK@IKhLi2Lt)XR+!^_ zG|1er{*6#t_P}thiFg!EJC*HBSO5)GyLTu}yRZ)2ZnK+nW?k#ur^d)@3qIKzPCmnf z2_uZJH!P60GVIzy;DZy)`qn`#(O)mhjuh5G#<0a!q~UYEmQ;Rwe0}ossH;lZCE>%5 z%1ybfyd<_bS1SQ5fZ-J0XGeSB=1KdC(HidabWI~tX^6kSgGsZ=+vm*sj(FWXdcpLj z{GhWns*{%HI!O3@G|t>ygc)su-wb;i-jIZr)qS|vGw)Yb{;~JaKOMojzHfHd(3o|{ zgRc`45uD}^4_%f<;9FBMmRm^FBE9RnA{E!Th5#(jOk18?nMqHka7ai>%pW!28!BZ+ z`TJCNub{Uu=qY5}xaK~LVZ5LOA}Tp$mxU{?%*xsEvnW-o1}Z`8js|ri*=~MGN(2G^ z#ebNKe?w$5a$N7zzU9=KhR;;hBE4zQL^(ew6zWZ~1IJ9=m%h$9%1EOCwn!0PA{-Vd z^ZUY@z-vKJeKtRYGb9%_Q+a%pQvP9T=#!0NKxl3Gl+7E~ddpU`XO#2U&d*$>+sxNb zRk<28KsDg@Y;iz4BDLO|LT^hvz0-^^p=A)n=W)Y7kagQ*;&E5nRr^R)Zy{VCq+ce8 zTj(4`Enxm?g|D&hLnO7>EB6K0YT>iypmL`*yowjR>MhLL|~@a&=Fni9k~jRh#)%t>Gf-?r<9%}L`bVR@nIuNKvnqnlBXmRu4gcu;|_6U(H%0? zyIQvO?H$|An03cBXbhiIp%o5zeHLRXN5T7W0(tk$En9u(x6`xm3AENs$66T1L|9ta zDGoG~b5uuCFwxsn4_Sy4B{&)oy~3KrWYMRbpEBlS)l3uck|t%>X0#qJit#*N?=o;- zAW4(g+-iNdfO(Kly7RL)43)8(P!36b5m6iO!I5xqN8)pOxKKBHM|sg~DO zq~qRIpus}2qm!b|hZ$j2^@+#+=pEU8BM&Aw^e;T=0PD~uNB9hi#%l>%N z;0&w%5dQJXRhaQHq9)q{x#&$p)fs;5d9f8v)A_^ok0oS58Sgt%OIPbTOoqrbasaU@ zNc%%eORXX9m10$6C<`>Xe}W~0eD7PplFRkM!L0jZSR_KToBR;QHyY>g)cK|58)g1& zB7^wZEx8Bp|FA%(r(c06)|L{f>EoL*P#CjsZL z8FId3njZ{2GZqv$OMwFVeUio)X7F4NdXAi7o>cbbp{SEk?$qn^)Bq8oQT?ln>WQ9~ zAZ**75%v3CV1meY$I3snUD*w3V=JoUZj@kM(X{{8l z6s99r4T;I1#?=XeK5k23>Z^mGi!s zSslhp{tYbBmc5!w8lia4^P{z+K}n*is=Q~CA@As_6LF2Z2;SKFOGcolFGicPSW6GK zZv57+dDIahBX)*8=-gPS*PkZB;N`X-1C;DtH`f_6GLv5((f`-Wi`}04L1NS4yq?_< zA^q=qtF!g*E0XJHJ$(89b_ZV`UR(5#nG&w%-r}aBK()N8w>t*Ty4BR)>842<`CyhN z1nBr--RHS+=1o%3a*p*JLCS3k;kvL4y8pF0Fn?oW}3JrV>(+V?JlEQ&du%eF>)EalVl%VdpzGNGWlM!+BJZO7+ z;qcLpTFhh7_qdO5w_QNwt~0%}!34@YvkKi{$rL?Zz1~!T_AYC_;zG*}O7r_xlhHq` zL?S$68#C<7EOH%NuaMy@b@!m`2I1o8*GAsYXs>QB%Rvx;P&M|N$Ibc1TFu6Imy1D! zfC14+CN4C8M`+CwA!Z6_c4 zi^yDJ*sgyu==jrQvuWHu)Z8>_Oju?L<$Yy17_?FLd=Xwf&kf5vR>(tp;kg)qy$b9R zW2CIospz`0yW$?huuV5zub1u_cc~a`1|^8}^5O3*tQ>9SxvvZoP4tVZP6cX(Zv!Vd z(xRe;-_}Xq*Qg1nlUW@d;G&`l*JV4McQ2VMrIUtr40nK`4TEhG*_n^;ti$I7eD@X7 zW4(02O-_nrZ{y(bd7s)$>~P0rOut0@tB^vj$0}({Mev^5x76+QXh$w?>7>0Djw>DV zh05IqQ-Zqiy$@UHMSe|U4l|5@LH(3$m0?}1&Ta5Gw0usQ7~IFXi>l@>2A(7)8vB?A zv*?I?!w^i-m)IPH@9qX7S0r&wzQ!1zXwAxukA78vwGLYMpU?}!dv5@YF8<-70cp95 zyNqV_K_O=qnnMDXw&HM`chU&g3OC^#7Ks34`@MhdPdz!l2QtIz;sX)CFfkfbUsLl2 zR@2J)y9Tm{EnX;|0#Wro?GD*lqi|Lzs(%glX2Eq^V`+}993Y06UX1|g0$pOZ0x%8H zx#-BbBa5V5BJ=?|D-Rlfmn(v_Ac86lk!mzVi&n;sg|DT$PG{4@8Rh+srHU?%8Iq&6 zI(nJN&b$oYR~bGhDLeBG^1doMVyIQMqt#)C2*3EBzjNN8LzB}5;@C3`CN^+Cddo~i zWQ^N;Zq5GtWZWOP_ZBF!q0O8d3I}-&&GvsN=+VcL&_!zdu9n-r;T^dEs;}jo#?~~a zIy}Zietg6V+5ecx`1N5$nZuhsWE-ld)5OT;rMc7)^`*i+!XORTey3bdezD79AwwA z1H|d{$NSL!$n>(H1Oa|^mzgSCH}iqUfzzoPVWO>q^bQ&?g>=Izh4leHeFm4IW;q!4 zCf2qa_top+d%xzjyc%`1MrH)k#e~dy#@UX>ewIL5uI_W+ z9-d=qvO!H^!m09eccvy-g066|O7^@m+%q^%r%;!h%p!W}Pn|0toQOnzd~ctud3$rY z0{w-2n!@cGR>Q{DdT-+e`BU|;4sVuXtSWNCL;GyLzTK&R5nY4;1+3w7Ma0?vtZn)` z_3MchmMONcGiAV#DnVhDgQ4!fb@ll_>ne-S@cbh6J|ZA>)-64B_9!y<6NbP{At`#WQ^)rGgia*e8yz%I)rHVmHV)~z|!xG z$tVo=YgXSZKr~pYT?D#r%@t$Hk)bRZTa8}8nOOTTcuKiCpZrX~dA$>Omb0>G7ICWJ zILf1o*wI*C6&J~&Lc=AK4t+=9ri&}2YZj##hhn!^6;vWl3P8_CPswW+ZBSdVu@p*E zb*Zd;E1M|NpdcMZo`xJ7k1C`Z*6)lvzc`d{I9(y}s^b2yWmxHm!r$XE?dYzY$x9*O zDiWm0Y}TD)?@uX*L@RmgFoygge*p^k2YrLPxhUHPYZvzavvySe z>A6F`>w&L)NMFriA>UzpyKSDpj}4l%jfnlzdrfxva35c5Elx&&&5ifhD${rz{|~a_ zjE`kdZL*exAhGGnNvS{WQcCn}5%Z2iNO0EjaiwCfUd<4?`BG%tJRzJ~NC~*><)M8G zWaaZ68571U=VyUxuUE30t@Y<$SB3|j9`F@*~EKsjUCO{xAk;gW@4jc)Jx2;%z}loJ@vVG6dXaGB|h-_KJ*C;6scUe zyr*?&$Wi56yQU!hS>CYH0)Lu^fBA5m3S(3G)f|Xv5%>pD5f3IVebJD6gKjmUUg%2g0NaHVw?^580hL|!u2{~G_+yCORPSRwpwH^ zW`Bs9qd~W{?oaY@Vpm5zFM0*Ten&a!hA~KNogkOH%{;R^i8(0Q^+eyuJUDvVCz}A| zxcu&MZdP5)4o=G##Rk~1Ro!}EnNf=XZh}9}rTAdf3;jLqMeYw63EkJXdDbDbmw=(>Oobe!r9Bx>T{!8VQUa?YyHJV((yyGf%_nTuJ)Z{9^p<-D;vCQBBepM6 zMB&y*&UHF_NYqEEeb9I4;_|u+(;@=K;N-iz+@`PKc9z#wVH(il$Jkm7@B2#%<$cuh zO!OGyY_d)adw`*nTrO=Lc$Z1!X}c$f=wBdTCiadjPbcjE=s3b5$9%W8zF4xTVT1 z*$nuDtyfb~$2GB(TaqtvQMMk5T=%6@>_1hYrPT6cq{faZ}Q*+-mk*f4+nKty_;mR}7mG6a9Mzt=o1DgUY zx2hvscNRi`W6|2%?rwxgbhV!70tUaU{W|X7Q#`a6o)1d$Y_FmhXV4y-P=N=8M;LB> zZrlsr0^OK52EtA3wHV^mjZSM};DtmWIElAQU(AT|U_hg*OlHEr7t8ZDWE^iJnJyF+ zjP}5KH)_K2TAc1mNUQfRN6dCVmn$w^VElI>K2JKzoZ)$$!7xlHt}J>)1&DYaWs+kX z(wHLAJeQH^Ovk?Zi~y)JJPb%@7sCxEYk{f){@hkuYG=1{pQB(9T1k&s`h;Ko41k)7zNgUL;8C3vY*buB6f=TeXw( z`S~61m;2rN>XGxfcB^}$O8jE9jIO@{rjNdK&-a8MEdmRdNY}S`(QaGv6GgR>Xb;WPe1Ughw9?@|rCDI9~Fk za7E-rC{$~=?cDYEru{PTyVHSCws|2vXZtX%gYD}NL)eZy0P+git^GYbJ#8h1@p`qR0o>f}@{@;GXI}M>t)NL^whTQ@i-X+{PFXJ&|aj@<^<~9CUf5zrP zTjid#aKl$OFmF+RvvcD{P{lSY0eN z%KZ1w`__yl=0dydq;IybfmPq?c%Por?(`c0->W~tTP@GYVQLRy$`6YT8rZei4Pw5Laai(m48Fm{CWr?xYtQxN>Do=hrKV+a#?qxt zav9Z%%~~w-NX>r*cg6e7_f%sVn3L1~jfjBjR%Pn=p!&%7&E%09c?-bx46U@9lXDR@ zTWsF=JaNvb*L2Jz7CuA~M`Dzx&+jJz>;+gSN(_>K2_Eh`%dTK$+{y0D)TCsZswJ~{ zMh(BIcfHeEd6C{}nm2MthIFOT^V|B-RlO(o{<$Z&$AK}y{GYEIj#J(&80Y#<`{R@v zk>}yK^W9s?G{RX;`?EFleD<^PlA(k><@Sj^VI(YO+vBv5nJTuhWABvzi>|kfit>G< zMhWRs0qH?RO1g6Z9RU$!kVd+@Ll{XFknWTk=}zhH?(SwNsiEsU{ND3_*ZFe3xRx$; z>HXYsU3>3qZwb4m5E{Y9Ohb+o5mz2?7&k2!Hj_5=i)X`V!e->gy=xE&a(vfFl&|V4 zKR*QcTlxT8B?}S|Ca~qaKk@lXwXKbqe&Y8x%-K(OInUQ_^JliBPB1>BoJ7hoa_2NU ztov&N_@Y9pm<63!j+9h!h?$Bu?lMj$>ZyeM*S+nJtm}chp<30p6bH>$TU1x;v=8Qo z_rL&NcEjaZ@RU0Dy_t3<*?I_CtgLwyIZW(bbZ?04y?p>(g&a2$g>g0UX;~DEI$AfR zf0U$60Ux}XZj0{Q+Zv3kdPod`qOaOeB%!8!kFY@0GLv!WDng*d6ny3ppX%sj+*mUH zxsI}^gjY}-kx8G_my@ixwF&7RFfs+gnP?L!b;LIVxUu!i-$91`@EkWrp52U${Iyc& z#RjHlOHeRuF3*7yop4ldP`{g4w=QY5?6M!?%mW$kU()z+T??x^jod^O}!f zJnPfEfbS@kf2#F0o0iC)w3iCSS|>RlLElaSp(l;D$W+Dx;N)*|6{K2jxM`_b?HcP* zZTna3szdo?B3dE}pdNZ^j@L7_s*6p3O1ZZ=?P2R*OKAA-{A;}VedX7s#xw^%AmhV0 zB_#-i=P2R|>^nw;muj!2@?g{GU5R;+A5vzyi_1vfxp@A(|2ig9`qY#!^Hq z(LqJ@xjb*S{Y0Kapu#NL!v;?GGTak4a{|a3SVpRHbt@d2qACl4z9Mpw3F&!w$MsJ0 zH`Z%b7%rW91`B%aij@01Ys{zoBu-Mpe+#B3Mn;N;$YDMe!J@h#ZZ$)bf$UH!lY=^! z^4obkp&%!%N$>#h)oc3g!Jphzx-AZE6gJq zl@&LjQp6!6UTf&?VDrWO^xS3@`m0PjZX}69yTA7HlhwYad9@yzYYRh!L*Dacz<<3c z%}VdD^FfB&1=c~Z?&uG3-G24*Kiy_1i3159IIJ#(2o{sQ7pp&wrj*mxxdzv4@mA7$melyV4fkSLE z))9CzQ>e-FZOD2D@Hkm$a#B~PU*v^^+tgc6X(#bpy$FqdC!^EBlsgTTImpt+3_p-m z=F%Hg#DPGiwLFwwOcD;21i_eDw3#t_=)3+oMYJaSr^cmnMUjFp>V7idI{>^ z2Uys8E*)m{u+EJ@zFcvyQY{#ogCMgVBkRPG@-0O-q60AbaNkIcx~XtV!PbL{^%mTkwvB#Wzg;~yX@te1$b4r zzTgm}N@WT-WTE6})UZ2R+i7?T*CzL0bV{zC`L|1iW?f zhe;eIEcJRcd?J2bvO7FOJm<(@!y>yY^+U2p5=u80he3m4_DKJ3TS5k3g=+>5+>8{X7nc1MfL6>_*NjTTqx=gl z^DTo8A{^>>XswIB`7Eq| zU^&Q#si;qt;=f(%__+qP<*ZBKH=m{zQk)yfhtd?6hvPfc<{_#%s?7LiTBj8C;WQl) zCx;Jq|25fDQHznU0wLP=-(<{S9nTFuYf~R4&?#&3eh}BJw1?9OeJ7R0mQXV49hZQ8 z=?bUie8f9BQtA`nSf!<^1g(B@39D7_<8VS3Z7IalFo`y=LhgSW&Cv&h_x#hTHyK@% zDt9|Jbg^7`D^hv*@=;whkRqxMxRukTh!p%-S1Yp7Jwm~(%^t+Jn`%vP;Wianx84~T zCe@nf+WLtP#v(+Z(o>4K{9^-bL@Lmw?e*U~@k@7l30JaGx}tlHawfenachb7yb#R) zJ`iJw=#}JM^~RKqcq(;BNdd!WMp>6R&<%ul=XfXdHppx{l70hz4~fRu8{V8PmY<2~gPH)T{8#&(2IEXs1?oO~*hj&Y5IJSh~Rd*2vz%bC= z4G|U|V^5DHpyQtjTenbqr;5ZTEEi@wDPeBA^m%H%$8E9RQ{VJ9sg1S*qnV5cclpar zL;e3+85jA>0)`nIveA>vgDOsaA*xJ+zhO)%V=PW2@>QYS{iO53GR}+;Bo^=d%n~F06YX109BWbx|UGU(g(;=wJzO}Z= zEd3-s^FfNHkQdD4CnwYx@y!b8%7JrwKPC%Zv>a`a0-lVYxdeqFtPi)JH1Vlm3MnEC zKn-^Arh2OxTl8^Z<3cgNzd?Mvo+RuaD$#4^=nex- z+OrkFnQZHRo=Gnp5xencpt!sU5p$q|<(6pU6T92zeZFb#1s+@mP^ z2E=Nt@?&m&U%A$qW^ZUxoQ&`oxBFZyf6{*YoCXZK4@#aGua5I5(`eronWBx)xHi}> zOXS^@T68=|WQ2cwK)uVVC{FNIHZ4T>!kMT*tIiiocQjqB%Z-2a90bT)XgPf-$JCL) zOX1;cjeoVzYO7^{X!UqeFr$zrUbGs6pPwJ~c1}>M${e-e{RnMEAInDZL_r+Ei>yC7 zJx&I&if|>`MWuEJ*`b8b?(F02+{nx4l8n6B`aZL^0l;IPDgVY)=0g@>eE0aYACLWQ zeRqmgenX^>s5L@g|4a@GqyB^sCWzbVHQyf=#OgYRv3}MPWG4j${5gwQLwm)mK#&coO{4-ii?8-!PArT}K_>_vUG3DuP3Ljk~PT z5^V4RyMui|Bh)u<*UY{>oEBfbbZw?ts*g&0%;)V7sAf<@JqB`2NBfXnu^N{RX){v{wJZ))jw*;PZChGTB}ltsth7Bb*Q zKtp_`NxUP%eZ+cX9e35(xeLS8@hE&-QBhAxetP8Cu5O~L$1F%?bxNVBZ{b8c-b+e^ z=})#Ch<-)RoK&2wV$t>l(0VbOon6d2nVBri9G_e!cblwb2J-Ai24n#SVy(D|*}KrL zE%VCD_a2>u(=?L`aR&Qw4&!V(XM$rRoSb@fZ2j?oHD0qO$DUwe{NWk06o;6x=XQI$ ze}hHYxTEJ8>{<=#Za=(EIv+MuM8E7=Q;5g3Y}XEeO1s4L#O9gs=R*nT3zfT3CD^HP z_^j@w=C}#8?2Gw`B80F>0nAzo8f%8|_1O7fVqei`(f076PPv*Z+H+z|^5%)%Oj1 z#piN8VzcmgIqU$(G5^^Qto*=6uD72f-xztOr&$26CNt5pLP|6g=+v|mA(Tm%RqmS zxZVdH*~DuZ)ZM6STLkK+OLkV@$9=y1--5P%0I+F%nmt&@uq(%V?Yui78!8Gh*$SaJ zSvVceJ2noXptn~MPT|Q3{YKZ0VzKEcTqI_HwEc~3ee2X+aIla6tf|IsF89(_&7&E4 zM5Dt0A^TIJDUj?tkZj=35>qWQF@v6psz$C`d}9wfW_vAg%l-IzYmA~xfN5fzgqoU^ zfhNA(q@lY2>(b(mL9Y*531{SEuKl<1wzfcel4{zi1X0GZ-!N}_l<$9QmusDFYj86o z!>+U0WDX%hdHdk!{Bl*D$2Nu)rtM!&%oWO=*y6DS^d#jb{f6^(og(cnWkYq;#9zA{ z);_{e1l}1U0;B5)h~s+U5|NGs;O=mmXkyCJfxjOi4EW%5E|VGqrTY7-HzVp1q@KQ< z+f(f7gwNe`Jrn5;DYo0OH(RQes%&drUN;QO>|94eQ=`%vN)G)&R^gQLGsU8Ho_JW~ zE0uj;mpo9=R}B=z7Vy21EM4161~t+9OH#P}FZ#i3LG0ca<)JOj>K&*=o> zOUoB|8@0>+w$ch3JZS-kh>&sWs&o&KZPK5OpZZ?!wK@z5xo^P(Kv6)h*OFSF%1%B7 zb+xT{z|kvgAx$-yBqYjH6rXt!L;j&)938q57iReDq%@y-v80d|gw zf5c(-1J^)D{zU7~mnw6MreDt?;r)TP&7oUE{Z0M#w@@Yq%lD`U>b|^NtV?-Xz)Qs! zl)XbZ$xySvxA5Egrml2}3ifaL4BQ4c2|fDr=M`{mk_>En))IgVbHqChk~%|0SIGxalX=tDIK9@Dduam#SknJKTO6sHC|ZNyX5&T%Pc&#>Z2(z z$;4yP_gaVl)V^;d!-sxv#Cfc*=(kB?_Y6DneW=-jBjUFkPSrTS%kT47oi2db+x6YE z5E1*n+vv30_bEKkxUf3*eBeX!131H3z%kx(&fn3rv;=m1CshK!VgyUJ!b%J5cs^BX zF*o5>TKZXh>xZprDaFDqsn7uN=2DkE5jEt5KV0UjIH`5x?^aR1=+haQHqT&Z8CWeo zcvYldDwZ*Hb_9a?qvo}c(enlNAC-=m2pj;--jma|y~SyM3JI@&U)(gp*~+VntN7MP ziU=PpI5}cO+|n^Z%n9EU=0n5+kJ50W#;a>;WnA}#jm-BDq7^b_b-K&fCcBszLV~Zo zdGW#9oY+A0aA%<+gvfx0abHMFeg;+kB8#^9m}9$nVTG^Y+ith%!Q9_+*E34ZM$^9- z)}A0ySfTusQUA8seU1E>a!pb@MFpmKIIPXZZ+?A?H{8KTuY*XuyL@Cl{Q-l&c(t;^ zFZe~@JDpLdwGN!xKb)OL-663UK-$qZyc-%x;hUTn;G-?@L>a(Woms=9-Q`SWw*uteCzizI| z)}lJJauvhg$1tys(9LwBg{o|*t! z)JljZp}Ye{J1IDj*EIay6i&KMpS|zD4Xm|y1Yi?M22{;u=JdKs4sw|G;^*ZLGZDvG zx~-X5oH(23qv&7!yQBQ&m+Ka)47=H41efxXUw0Qwn+#16+D2lB?eSck8 z#iV~8_Rqa(a^iB$cD#fgemVf<9{ye|H@g67o^(FH+8Bpgi+)j6jSZm{{BIPQm-e?s zf$?0G%^nSJNrCSOp@_LD)d$uEnZLYR%kO8khj|``7DcOcZYqYwKZ{AkrHFpr8Qlyp znP|`0_&e=IS7A0B2LgZl08BXVYq$-Mj87cB4*OhFTT|D(Xoh=bW7Cq5aZpBPJE8@F z`=`F!Wv;<@*F8c96?c+A`?}tvrU5sADZg&2nEP0jlA5Zz?3q44veMd5wnQ~SSz2yY z^!F+Pi;+KOW|GsK_$GJfbr$RL-T#14=EtHH7=cyR_1KZJSgiYNgALZlc%pfurE8xvpgY);lF19{wqC`h`!Qc844I7 zjR;90qIW9;t9(;;^_w8)`SOlxPD{WTG)0U7ThHUl&m;F9R{E|gwn;-xUA>=oSd1R9 z4Cj#mH%_V(Re3C`%XEJNW=zZcK`)>F`^^EKAyfX9{ZL*Wbn~Y(n2#+c6oxxpRW!d} zS(Mgz!kfrz7KTsGB?*LxTL`s{{FoGL8E;$=iTt-z|9_Ue{Lkex=*?IOrwa-%>RRb;+On=`u5)1Y287tI&GiFrj zQlU;j|6Vz~B5yxqLZ;ewiAV5hAUuF1KfnRN0I(_+6{5*uJc)8&Otw0r+rr`s5rF}z z1fU>^h}IGG2Q>RGe3^mTWbS%TF^=mPbW`n`$D(UUNi(p21U+eM&AqsxYbg9%eTR2nf9i?obTzf2-`P<~J7dx>ZD^eo5AwP`o9^Ez z$m-v?aoIC&_df)>h9#cETKAI#%1jWX9eT zUBMNY)Fojk4{trMk=zhyfm%^Rkv)ob7@75i-o7fKSWqXNJMO|gc6?+UILY@|7s)(d zaF=CIF$cWI!akYM{&lwb3QWYKlbfscJIetbfHnbd;swwESO6~~l#A(AQF5k+H=6ik zu@zfLK$aj8kq8Hx>)K**SlAxf2XYu!Yr$Aa#OnIwqBw}mpbwRoV}VjMS<)=85U3=& zm*kkU^Au zDxaq5P?CjKjk9M6rF(-rZ?|MeCUHl{b#%6rj%{tOhhV7v53jj_d5$W_NlMK!r8^t| zx3^L&i5N-|nXO{KL;#Ooq~(5Vf4pH{7-9f{E;!@vh1RSx9a&2IO6uhmZtx;!@RARmUTGH; znWci(C`CjHh`KG}Ay*Pb=>DUK*c@BLn3AJ{7hr>;4WhFJR-61*J;(Hio2|BSmJ7 zG|bs#sH>j~(#MPc#F<+c9(eX_%Dee((}Pzd+k@^s#$JouVFD8Ae8@)0vkF0qV3UydRLUolS#owCTBEsda`8|)*yq3hXpzx1yGuwxUM zH;yJjdf0FiW(^E1J=W^LWK4|Nwzw4>INW1^A^UtC#$s>(q^H3$m<{rU#}p>S$kxG3 zC4jVEELVLRmmi5mnCWo61qf`7+cJnZ0+~`HSd_Cr>Zj{nFchj za9w(jF4~?I==yolJQ`#;(5QPbM^e=#R%Iu>hZOv#W~$lhP08mIJ>`VZ2q#i2N1&yT zb%qQx)Vl37P{baejET055O+@7e?eKcdv?-p@@8r#^AA3*y}SeOpUZZ~uI6`YNPQEZ zd+6nXQkB7jsa^>H%Ep2(zIL*ZdEsnS67Epif1in!Q#XFhG0RJBI&18T=hOpYNHs=J zH=?0^Bk*=(M5zG`H^NKaH*z77s@%r*L7#HIPrUnE2lINH0p<7s#etitpWAh*5%`rc?J=!`=QdO`mFMo}F5mzgKSoJmvNa#^Yx_v`<#vesh7;$=}! zaM9h9;M-#iwa&-ical(lU?wy_`6>k!NR`g2Al%{}>R^=3Y8QX9{J(uYoZC&H5p~UfW|9aPLVppkS$f?K zr54N?sF<8R?vRZ(9^2^M%AHjkH2fO^#KY-RJv*%?J?SqKGZaj#bRCZzc1C_)ao)O(V+121t*UN<+eBR`>5=yax%!#*Uc z$R}~T?!>-Pz5aiJr18>Ga31uum_9J^-|hoJ~lrD~P=bJu(D9(QQb-P%R zyaPOjoB^9v&py#2LTAetB97qvw20J@MXwINmFHe@Laz>^DE9%d&br3)dM9T~9Wk~k zHwGACv~uqa4|*!pogo+>bFS`jYq$_bLnu`87aG&84pi#l&r}wR?!@yV&4{88@DqD3O`+<>{@m#;EVB!C78(uOAI~;Fi z2t+y%fQ4{hv?gk!*oS#J58*99@m!F5>|o# zTdNVao)M>EWl5iS0#kN=;k+t&V5{+IK*Ga{s&=Ke^|LuutAP1j*2n%iy82OUc;(tz zJys3X+ZnG9Z{T|9K4}a0X7jv0k0hj-lO=Wu^N@iyHFyxF~P=9i7{{LiY|u>4b|z3!6+(j=DEtj>4G`|-hUQ);X`K@5D) z6_Uyb1{&L3YTfWo5+h0WGH>B@4Ja9I*#0;AEyO8~|&`TeH= zsl_&x>hM>b+{g%?Ga=W+fn}BbkWpYsqkE0V@Psc9##k$yk6C_(2MVAul4I*2gGc`- zJqbZ~;(1C6UGYD9!oSbe zobp&-D((oTHvvDH zs4}gO@rsXmK%%byxVC{qeOdlU*ej{(n6!%GHs!6_vcf8Lze*7u+3&S_=EeX0WMO$E zsrAdp{|A;s!!>G3zbg+q#ecMBYj0o77lYz$kEN|QQIXwOs?yR?ifXu*4Skk~(eU`9 zFN{M8R&D6&hbUq5GLZluVfk)Rcnn91GRmMI9#HbNej%fPD{g?(H+7~KaFmEbwZ$p5<1DVO3GUp zh1~Eg7D|u)piDv(U9ua5BJX_}N}n z@H_hOwf+K2M!rg!6(-W}gNmM|oC9K#mZq$PGj+^=v#e>A z+jamCI!^YfmP-?`>`g>`_n{wPQb=GP&wh7Z6 zAc^?SnRUuXzJiG#$=oQin=HVM?09>OiH2VOM?DiRqkh`L@V4MZZxAT_W7b_3XnQ=H z=oYv)qwv8fn4U_~DepX-I(v_I#a()gyIxZ!91x)Be*BNObVxAGOHR6bwcvAq&4ANv zf!Hb3lK|2V&sEmbgMVz#0q>XkegT+HT8=;Hgc8o~&h{T*VRn(c<7nZe*yf59EYQOpHKw zC-YNRggzQS1V9+-}-`h!&v z#-ZK7Ow6bdCBq~ib-doyb6J)F2$!k=n40R8hJE0i#L^gndS@Bw3RHSz`T&}-NjX4>N&E>Yt^jJ2aGWhxxkB$J)rcM`iI-8} zUMo5l2EbC^-OQ((>xBT<_8_)yTH4l%lu7>MW)14Y&zM z(iAMIg)&uuelrY9JT!>$TtC~HtdDoz9~r$}Ir0m*j&M-)JFm_Sb_R~HK?t8UdwVd) zrM_2`^EYyQX3?+vQT$eF{Xnp^4U-)qjrcohab&4{nt)U`G{sOnTEy9U`)2c)h6^3z zNtFa8gNoLKiH%}{zo7oj+3TT%;8#ZLto!{2Gb2vB6D)c8#pR@6_Q{cqDfNudc}|{R zo9%r7_fD7XrT9TLmScUFY+_K{5}@9J>eM1E1}+Y)WC2RWtVIMCgowP!c}M9{=zkX6 z+<{fyt?7%(n9}{ppx-ii)+?|7SahbSYaczPE1-`b8l0)fh$8P zC$fvWLFnm@CpRE?%G)}>t1$q2&HwtPLrxLAPZ5aUntHJ6b3pAr-F1w^%wz^VYPShqQ ztKTw3jo1{%>wuAco7Fb%tu(LmyurZX6j3H%-gJxq97KFilS}`EM(=n|WfB9djp(_vLRu~T5=16Z2U3&!#rB$Iopvz76+S9F~guI%g#6+!o z^dyA3D!DMdd4EtuWVsft>|BHcAu_fv&lPpF`bgfIvNypVG(94Q0)rv#0FVpp~e680(Zfx!SICvFd$3 zTW3>XJzFOQno{Kj_CC9E&Zp==V%kZvvA340&lOEfTp4k2O#BMfR5nj)k*Y1O`bfeUh< z{diYUU|d@|WI!t=5;DFp2n<**_s~9E%J7;4sOj&MH95|Yds9UR5GZET|74?={;AsU z4xXmTo64X30CW?+s+<7Dx+_`Y_TD(TFYtj(6co2^c%v3Sq%%QL0V*jD+Z&Jx_tFWa z&Rmya@YR@RZt)rtFM7OTin;Utt)P4QwQx3Tk2-zU)8Nn*vy*$kBBW$)ya6^VVRZ`) zRh#=ia6h-}Y1DFT7E1S#a%nCS)gIHOGx|DV=|dmGX@(qPJ_?;{a*#Tl&Id z`1RGXqNF?KgYtBV(<6cv7*Gm|`R^OR9x2o@hxRw`6W@;RN-^@DD}nv?-|&Aqiz?Cr z`F-H*%G9Ff-XWa9o>A~6tGK&4?{8|n*`FB#qL>+SY&+lXUlacDTs$03$N`Emv_#5m z9p7-kt8;=S(LXhKxAgS;ZW1HfA|U+T<&Dp9*w*M2s#AGGy2SdiVUTeYvY9}3xb#=f)k34vK9UWnY4tuH?pP)g zS|So(aW*5%i}w>Py+}o!5ic(e-Mfo2^lG~cqvJx9RTLgNYw3*IKOMK@QQ$L?-yH4< z$hFvJ6NU;}FT6aw+XQQ#5Aw{Pd*2M%@FE+IFG}Xc%7agG{EB~-di|qHLz~%Aokk4J zWw}vWj}QaOTvC3dkOx~8x4(q_Q~@>e_$8A!JxjU=FNCPdHqVaDdj6vt^1V`iX2<`Q zmL)Kg6qftcZ;O>3xX`(uROt8tNHn0KDsy>qfbXEoF^H4q4v;*)7c&! z+qp{+d}+E0fKFCLsl5SaCic{4p7LSzA>c8GO z{_Jzh`Q%j}u&iKxE^Yzaua~L zl4edVk6MF3m!p<{Xt4oD@$9ag&T@|{$JsKY-!{XZn>lzJIh5CV&8bbWOyMfMl}Zk3 zblMgd*3eVIq)?R6QN_;?qPe%?YhU4H_LF!>c2UoU{HSI++$XFsY6y`B@}-+NEJje= zsp2G;WQmwa57TWv!m#J>H;Ow+)=$#9vOw?8LsO_F)#)`oG*x8%{l(je!jBC2^lP)< zV-v;YfW{fCErsED6w;Tu#x;Ops zxsR+jASo%;#a>pADWt{=$|E^7y9*!{JEHqODTXI;H{fx$zgVq)jr>O+KJ2b-I*>pI zFbeTNjFQ{PUyh6viKWuTOfzx}!4wmUdGf6_!elO2I>=Y#;h51>JiC^`d>???7Kwz5 zzZxF))J^^NPnbf??H8b@nNe8&4mmUZ#L5-^q!`=0-v1+j%rx^Q`Syt49rM=ia$vMb zki%>jY9g!tbUSrvXJL)CP&n1WnSN}Wr_MuzY;4ivNXLR+x4Ipk1KPAwn__)haAqtm zvDe6h#%GMRaw^!2P&GR_$wGfj*(jef+OY?TLBzi{)R1&-M)K-9K*bu?`mWG^k=191 zi4kaKM3xS@26^OSQrFrrIY+L}50^Qy&I`hUCE7Pm4%?LS0z8tV^OUpu026wXfdp=mw0$<4xvFE2 zv!AKMKh%zA$(^1lhWme{fN9TBjCHiyMoG9NqD9;Rm2`4l7VE5#9(_r>XBVIr^pC68 ziwRPX+m>%O2U$dBB`{R5^>^4HP#5rZOUrq>O?Z(t@9`d74|`EM@O@v_y~FVPDK~y3 zhN((Mc)n&Tb_iZ&QMo@isHr}m57=va4?`LEetA5)PTUsQ#^+RSi5&OC6Q9WfM8wE2 z^+UG1oArsJuqvYYb67o(a>iVAz#cz_iUMT?oQd-=7fP}2t8}fvGQ1&Ge2bB;^^_|C zSn`wc`r^rzF!oye|9Woi7|RCtm`Ei8a3=M(P)MTg=nM_fiE2oBYXgOo2|+&etMxK` zKEt(VtR%h9aRKu=3Xy*H|r9J7XTSsi;q^MI=#Fq*{v%X^L?;$1l@sX6|WwcA=EFoWCYLc zmHzF-qktWryU8l!KCI5s8y=4qab~SmouBU_1$_Y&6E9Z9qdvcsLEHEX(lO8+%u?p* zn{t*SLTp?d&M|84`=|P7ypcb$LTT-Y$^jy3wS2yMJ$bsIJMb2jeIA%LvKY?}Ww$vf z1RbrG5~Lpg=C?Dow=diQro)`=4mwc?LpXAYN&%MI3T`E67s%H1iqCFpfr{|DDfu`FnN^` zI=B7E563d!1r*xDG?+}E^2@!;8#X~z58Ox(XC^=cU^-4AM)K|gqu&S=>XIea%?u_s zr>lRgqhXn0CrT)e-%)fQzuZ_|)4LpwygWG80nuK}$FbMBqGBAz5VXx(_lm}m72Wo{ z=$ws>!03}nb-mfht%MQ-TQyZ3hDX^kQ<|F+47pFY$dAB5Tw{Zfa|&O+d{66IrYI9P z9fpN}oBd~(d3lMN190w1WoB2^{U-fHTGmoRYJL)@NZykH-rk;l)Fqy`mkzwwl1HEQ(!@R4W_Sk5j0Wl@@MXA2 zOd3CUg!=xtQ@?GGXMNd%fnUO!V_W;3x~u;Ag~RmWSW;=Ezt6XyfcHT{G~{w?XS$@M zR{@y)SQoHR!&#d46VY~;ZI^Lz29(S-2${rB?Rm+9$zm_Q$k1)_sv5vY_Pm61zlEsY z>k~>)UPjpOjF}LSfg!^_sACoC(8B^=1*gE(zBeV@Eeet((!Pc_HN7}pFJnnP>_z^Y zM?;Y*8AM`KRoGr3iVILzme*UsP=z;34|rBErF?vnbg@`N#A<~>)_bN}AqCc%N;LLDd7Q4_7E)GpXqu zWRYxq_Q4x>pU4%-DBl<$;Dyfwt8G@r;&8hC;_xKm7p6ndR!9K~xi`~DAaNk>UmqA= zYmzuzOLxr#{OWNYh9O0(N?_}Eq73XXUs1398o=2~v&v>ZpA#XoFV(18ptiLM8k*OC z+E&ghluspOpAG~cNOgtMG66a9754uY+}~clH7L}o9*SAR0N0&dpIKe=Yzy~x$Vs$i z0({8HMlX;43d-Y14Er+%US314r}16Jd`6t~cbrdrSYdJOT8xkLiv%z28qbEy^;^HE zbM^5bgD{#g;h|z*IP)$?HL6v3H%mOOz zJ<_awQpQcL)$aiPA;qfV(yP_jhz~UkVqb3QSTQI9_B6oUknuwIIqzv#Bigd=;eaCl^ z1hg2b8{MvoIY&(bYu~%ryxC;ip=T@#wLG+RbI{UPj*D|Hk6scf&mcgz-Rp5yIWjr(*(Us>QOZDtPzcc>eEn`&y;wVvH)jYTimkBx#aucU@M+Hb z{1Daf*ard`9!i*mV?V$mUn>_ex|BUr&q{TJaU|HwdZ^k^!YIorVKD-(aBTvPK6COX zbKPQHt317)i|HtCe!}e3X!YF%0V&*&R7C+L*HMx_U6#RoICY$oNt4;jYKJ~sNkN@L z!{$*_0tPDBF3O;x)+q7QIkHz8?ddaRf3_E9opvR^rWLjMMCgu}tu?!J?Uv)6UGGBc-;n_TIl7qRKe`VS#i^)C#rwRdUZ=ym*U#ia7 z-=8CX%ACn*UFMK(?%?{DNa0VbkAIU1aHUgk`nm?hX6eVwne#;RHFCemZh@u|FfD5BE}&J9SDxC+ZpIao_Q$C)AObjy zjAFc)2ft!mCoJM~cQc1_V^TIHd7XBB;@vo$`zt4Yhg810-YePM$cqjdm%Zw=YL3vm zUGv_#>3X^|S`biavB-$QMEkt@9_qTur9f(p`{2PFdP(($7x z5F+#N*r11F+6RMRu_cewPwvNAWJM*0Qg(BjF8n2jIVLLijKH%HXf&w!YO&F2T5B?6 z3JE}%cpD!m$Xdb8OVgLEIe7hH>(m9&rm4d@IKPlQrqhw0gUsROId(OMB<38oN z8SkA}F9OEsn&91TQ!P7@!3LpkK{NM-o;``;Lprg2 ztwjx1(nmo`n0@I7J8&3?8;PU+JR#)BT}*kc)7=+rYb*y0)3H5sKGCRUSvf7JA^=

0=N(;CDh{%HH)^vdPjg&W3nuh zINBUAFyHZZ2!L;ohf9>Hf+7C+ajWezh~ofdXR2wHtCe=5%{wA-mF>R42_mQ+Me)tI z?hp!_`3ikLprQ{DC|-U^C172u3bDTzkPCOvKI%iG$Tlg%rx`bp5t5WJv7(BBA&==x@fm3o8p>tg%}O|YScs-ELJ1tYSR9x`|#V`^6LCvW{VBe|GWT_ zc2fat8UG#-tL4Oc$r`5-Ns!Hhuf4hkI0O)ysAW38u73N$!=C{;%OQc8SJfvsVWYeO zL$8uUg!}`|F$X@rc7ymNPOV?3`0&AY0cd4jd8^{sG==qhRtQ5xP=#O z0jH_V=NrI^Xx8Pyb6g6h0t+WV-z*zVzxpxjJ{{l;8Im$U_)>j;Y<}xq4+dt8M6x(` z2Pi`{i&H!7$cH&|jcy1;s`V=E%RC3b-m49bVvSsf7_B(kKk_kWaXmbe{owe!3A7*a z49wHRJ;4g-Nm&`}b26wTMvIH}7yBJkfXCo$pgzELMx@lc_BCv8_ujgn+K{#U3Xo3l zhVmjwzDqXow6G4CWv)7ot$syDV0xe&7BI!Mj*S1wYW}#$s*};oVW%yb4y_Wa);_5x zRFvG@O6}uv?RC?tR+w$WwgtpJyK{$b7@j|H2>3YSZA90YlEZttj34){`bSH8%h3mQ0WW^M z3LEUor~dhH87`58VRLz8a8e2Dp%t_(#0OXd#|SI(;PZb=^ne=+H#&Zt$&mZ4gZnzI z7fS}nYi52bgZSc`WoD}!A=Yz`*)CUFY+OH#0RnPr-|ARZqtR(SPxgoFk_Stg1HJoA zz5QTGk`NTN_w&)2W6UTyut&plW#S_qOf1++hNhkzdZO4Q3X4zgqK(c$zyVw)929FL z6PAq+-lZ=r(@A(@#J^VbyIP*;ySN6bg~Hz7hZP2z(2LZZ0OoEE6>Xw@%m97u{qBc-w_&tCXhJk3URUY0SP-IeuYXT zj2lW3g^|dZ_mFi_T++6Ye+Ts8YMPfj?^-R?gl3+en)8+J(JxVmlAmBcq^>iC#Q$4#s`>V^CBcZ?9ni&* z4_F+$)^w5c{Tj3Jky#RVCJ2<0qg@aCM1)Ub!{*}kdDE^=UVxR)K zXntr+7WG!}y8FHC25_7zM(Tk&BY@k@F(S09*wbe=Hpqw{SxOheJ(E~IEz8T1*=`rE z+2ve9bzZ-EA66UzeDN$;djM_dYJ0%9x9aQo)}$_X70n?@`F*_r1y1>H;>r>bFh!2 z%7}&uTsF?%(nD#*ETvYv!B@1{zJ3qCJP2FOlzN<$@^aUAe5#b1(&NdXPQ%{wAsmj_ z929&CjRPzo%2gM-k;C{^OtR8`wP1Rv0p)&vVY}2+9Flg{rkNHO~B@%5$SJLce0N`H-3j zfjYipt^$ZRxAcxg54K15Dl5_?i+Ij&-POuyOfMieI{gocPne=_>7?kz*#tYe`_q|b zk$iM@ByFKmmz!Pm^EAiRo1f_f@o3p(lRf&5aB0j!!VWPET1t_YP#re2&*@CE8h+g>f#+MbVFj2Oydf z+gDxC2#fKYJ|xAsje^Ay*McyoIY# zDpD+vA;Mo?T2QTja!=-rF??ySUjXcDV1zRE;dc0ePn{2=2=Ue?4CJu-;^zl^zodoc z0(#|0vS%329BMB}_&PoW{P|vnMW$O=ynEuNL0`6ygBqq(Qn2!Gu|hrep9t|9fQ9@& zG@S)kRBhXa=|O5hL^=coq`QYyP-*FIknS3~l@O5bmhSHE8oEnr=!gvLEZRG;%;+*ISI7erZa0`@d3}0rBHx8pB?v^R3`^n;4hu#>UAZptSF&E z&armqszZB32bMXmoQ&qcT9ZFJ8T?&G5-*l_BHu>u%9f1%U+q}}PkbSZ5F|c~yKC}s zSa$*^=^JPLK<)0RjY2kWZlxr(tom}lro8GXZ@=f?4)aJDiBXVTu}-Q|o(G&u1!#SC()yj0^ht*h?-Xr24ch1aQlLjjh`RJdr8%2=>T1}QLS<9OH zivw8ay43Jpi<}4$&(O?otgT{#2AXw~!%zX^wxZzlVgcID7mPaV4QWpYZe0vf5h1tr z!7tT2@UGgH1{Gjgy!-++KTX;a=Vj}guL!aiz8GD)5iag{{XZoY;FKvU1|8h;&ablm7c|~0_lCM{3A!g&Ka&`L7g@h` zM;QpdbNGJ0-b+rI6V|S*huWf?^u|_KNho#eSCcs6h$34?ppc<($Q_0;vA6BR)j|H! z(|vNud}y5{&uWMN*}AY(G~L0qcll+P2~_o>R7C%`ZqEbnZt!7_DO_=}T(kDu^RCZx zzp76+Mf8jm7}wXL2bIjL4S|LA?^&C+{RFV0{z|n?J+u~%ZEhWdCldit=%D+ZR-qzj zC+wn-z-Z`zy#~Qug}KyXt+eWqNahS0=P+8pg=Xr<%Tjh z_*oO3%EmE(&O8&;=R>ew8yPK)lOqf5l;2M49LPGoO`LR1e zdEMN~NkCZxuPCR3ocwhc?&~#N)*s*Nt)ooJ)8Jw7as}9JQ)o`L0Z|Wz$N=6w?bh-^ zLSn;xFvVzqko}*Ks#uZomi#FN%!jXa9G+v{1yw#-A#55gIrsY`N!4}#>;WX)f8i5{ z`;m|QdBfftyht%9d=zCQ${&#Li}gs-oQytT{#Yjt)6}FyhGdEm!(8N7weR!mqc6Y8 zmkPR4tbL-BuRjXtmVJWzvYP%7q+M3$PCUwHG9H$nJP<+6q`;-3bJOVg)S05MH_dvS z?!#!++bQiiO{j87j8dNAcF7ip&uRWzBRnY+)j!7@duzY87-%!uKuo=wNz&rAIzl4Kbee|9yiO8%ebRv*2k{F+R0#1K+4&mKcgNSf zNk%k=BWCXy-6+lT(JEB;PcVZ&)?_7yox|~Pdb%Ic5QQ!b<6o^2YNBnUBe!EVs;gaB zQA8|zcbKWG-BMI^nQwU1KtAN8vjq(Yo*a;91IulH1Z{TPAh}KkYm||hQ!$LYbltPt z@ZEpyL$8*4XE);#{*=m{<2#6Ibf_PU&WSOyit0jIcLvok(p@7pzdJs1G1VZLhu)y0 zlpuMYwBA^y-|m#J=SZcor|90uft@ny*9ykUU*9UEM~6Io)2_5yp%&8#oFK|w;*c5j z?dqDlB42VjAP5F|a%1=7oF4VOC-9-Wy z-@5F4l@wK;O7S$d%k_g-s+dnIPmeA6+h^zgMvIlBmeU0x*8G2Y(c#0Xcxvq}`UmlH zvtQhVBJ=Fjb!r@DzAe<)8&&lB>Fu`Gt=9V;z$w(zt4vp{gWM!9r-!CEeBMkj=&FEAj{Bxik^X_VkgJ^n0~MV5T^k%Fl@YOwDw z?luhf0D~eWsm}MML{f2u<>tBAXKL&N4q`i1#xvE%<(Ppc95bv@<88j)k%P4N)YomB z+vNCsBnGWwndx{`pr%;RB?0_hs;R@>If0f~qw}!pLX$}fnNTj>Z!%$hh4oKw(JI7{ zA^nML_v?&!;RWco_o0LuL@n%{2rHsWCng;+A14JdnCr*m)TBPoqzjgQtjjge7xg&) z@c`qoLX{+0j3BHz?Y(xZWDMB&Gw9`&FZylVjkWv-n0AiH$E}Ob5ap700Go9Hw1X1G ztUYkPp4VqH^g6@dsKa3c2a;zbN;Xv+85tyd0{;@C=~ zDSK!8pS5E@dumIPuVYTOG_`;^DN4VeU^GY(pAesXo@U(Kd(-hwJ6oJccVrsQr!>Yf z-00l@%hoGI`kR5(*{UO4xF;pdK)COY*e&9^$oPysLTNKPCUH0a!Lz7ws zdGsZpFg9^Ei5ND78|;FzMqoMYO#Ah5Ulb~UP_@FrGsQx+Yb5cH^=i;kc?X*nc_O!E zeCc9ic5s5FgY6w2oJz{_~NzFcE!6=&8P5Jw)bsC zCC7PIbR8Duw#?p=Qc;T&LRGnw@J;KsUBV%eD--8Rq3+#8^y!sfFolOQF`AzEQk^ZQ zh*vO9S?(=^QVbo16| z|HUp@plHw5i};?w(>!hqk?gNw5E?C5!C^lA&!5I+H{uls!a`u;`IU-Pqk{MM4AN3n zCcb>t6>>XirFGk*rRy0TFQ4_MjXqiK8IobR(}7yU#>JVwYOw-6xDG>+4jm?P+K+5B z4m9nZh@Wg08r*ZNmTSb+Dz$k@IuK@+B4%5!`0U~OM9?AtoKRFW)J9}L5IZrV`gwm6 z3U7ktB5~~!T=t_wOp<$;M?x&#p{1j<1#h5sbB?W5alzhC+7}I`J+Y_#z-WAH2WVq) zQK{w>@a|uSxAm|V)={hX->Eiz&#Cn;=o%*8ew8RTR+^!2v$>yub@$5#^kA=SBT0#& zkF>DGAc&gDdpf>_G;)P4+}74Rt4c(0iujrpU3(&cpK1V|Pkkgt`3bk(-#`A(vQ#Erhk_iz1O` zM>h@Fa0-V+LL?KXCdC`@@CWro_Adl1^vZ=R+lat`|V9vFph?17Yd@j~^*7xL1kMPlyDZ5ijBOr-n4Mjt zvBf&NlRlPxxb&0PC>J^!iqTP>9(pD8jk;6|PI>8kX~w4zAi~BJalDdWk1CU0($3&O zVNF65RKpJgMR~}qXZD}=p04{LyEOF^?%#S35=xKgV+drO0Atwii*@Ff!czM4?#gLv zG(e3<>jwa)h~rF5L@>my`BhYY!KQGp2258ozFm8h2B=rX8&TE^wx#NO0)KXv)P|rV ztqn$r7qn15ZH`7;g*OU!ef`;CyO1^XAEcie1Ik=B-x?CB=`4hlWM+KQ)%Y_t)a2Da ziVh(i$kn2~({aI|uWuEIrCe`a*|$95S6^#^?Jmo-ukoK~Izw-q5uf=}1 z`w8vqWy%bp^+!Y3)_~rfe}JgCHkWPz{MtgMnHerS;qaO4`L3%AHNChE8p-+V4`bWf z^LdXvWU-4Bx~mwJBd^wJyM(C@aC{wiop*iHGcOLS$A?ILUV`th$c%*d*OA|_x-I_v zUW5ZdCQ54g5W$uawDz@x=XeIV!yGKXWxZj6NFZ?9%08-tew1@BmL^E9;+gJK6qpmA z4u>RbNM1nL#9Eo~-y7dW`zP1>n*JzkIIG>?=hx2I`6+74^wU?^&o6|9$xeVCNfjH4 zC1cNy*^BvwHhd&|!I5J){?F^zoXB`(oZ7Uhl+y>Mfs_~+?lnQ4%^cPa#p9g8UIc91rht*nR9S?Xn9}X->#&?10Qtq7 z;dx%^`8d(PpRoJRT{6-zBnyP2Zh)Ja6{1y_{RLBdiX~%$7J&g>d1N@ACC2BW-Y150 z|Hm;PXZV9!&h!QUbpT>#XOH~LOf6>D!9SC(Ln`7i$CHJ+Ot+uLVo+@n&vRni8kSqv zF1&-=Z-Ip0v3}ngqJ1XZ0oJl_o2~48`h(2KgJU||1;Q1ED=h{^i1TBz&1(i*|S{B!-eyc3|cqi%j4FBtxvDWDak7|anZ!!N8V2l z3-NUbtUgTW$1#)Iz$s5ko z;FQ?pwvkPKdVVbEQ#S)q-?)f9CUQGE(dDeiYjsj#>=UgP4qSUBMDPA$I`;Vt9q*gZ zW9B_$Z%ds=xgABNKMQ4A*Lx)Z68IpyNRl4DK9HomPK}zfC3u=&^T#cZeE`CxZh^5dwg2Yp&Nop z2odGas5hp}V?z?*C>V0TEb%F=!IMlYhA+B#uURqXk?cgVh3qELP96!BUu_N(dmhRp zb7|BYcAkuRa5w`w*Z+{kmx&W~+M|zj^oVCj0jzX<8av%!k*FIHH@&_{(sDY3r%!sS zeT!$E>cJV~Fe5$&7Q|6S9U**hTZ&(^w*QyBOwMCiH7P(g%lEs)aJ+ zsMQKd6HPjwu{T^!UImMv>}VuMN}LL!M2`34#eliu4M?d})yM@r`MLoD0mO7->^u85 z+raODc*Kgum*|N$^w@!^pC!R@xh<#={g#ejbZ&nAl||^tpnvp3e$R7Y0^Jzoyzuz) zay1yC1h#%tt!xUYHAp2Cy)N5q@U^o*yA}>5zZJd>ksQ0mI-&Y9jlT1CL5S3XeFI+> zCZo<`?Oc@wZdKk&)-SdL8d*qdMxm=Xyw5cyB5t}_PS`#u9A?04NK}PZP}1?MT?gj4 zC>O5QFwfI$|Eyp}@ICm^o+5JF%s)V?PaVD%%e`@(%q#QZ@8M@#M zm%i1tWJXD_+B9>Ivf)!WS#3-(h4Yt!EMTwz=07%+g9{cRwp)Z5+g@Y4jB$JGgABhY z&rAf2q|Ne;vR#A+$TFNC-k7itY;yjr^&Uq<$VlJsR(#_9x7D%s@@&2IL0_wWJ)D@4 zJEzWO@4|)s+Ln<#t``;{NmNPh)rT0!incQ@NjIv{l&IYOrP`?91(2(y044BV)m@>B z5zac>w~`crfSF>r#r@)tk+V+!KY(&_!Ho}7vk3Guk(?4ZYKvN&58j50m+ya9Ac8iz z92jc7UJpSG_P1h$`jYAfBMrCLAqODWx#|0~$zF0%2IrYH9bT>h^ZC&%GC8CG3EGzT z@9bUyy7e_om$s&HKnZ8)E73 z4e;3qNToQko&vZy3lu=DcB${fKr25xVOUV#=0_z@WY#UB=UunEuOncrM7IbZ<}F*P zXgwjqHGmTXQG?QbKcha;Ha6r7lg75%I3bh6f00~hTwvt4k6E1nF7ku^tNojU_5^HF z-b9gCsms23moP{Aup=9@@icDGU3Ul$Z@YOSmYSMcN+n27Xtc4wCZM`g;VNG%BU;%x zbYfwS*+2*Wk97Bh4KiR^kHfe*j3H;-oJrT+F#uTF*+{@-T(G)3gNpv3${bt(NreGl zha_Lm^?nF9)9ie0iy+e38Pm)M7xm_z*_`S0DIpUs^&_m?PRx=@OYX+q8lzOF{YK$% zmhMcwV@vqfTdLDoV3^k4{UgHadsZp z7RyK0;Ds!yK|S@^DiIww9R2K4BGZ)pP{oqu9#4ukE--}vKzEeP2QKQs=zCDv872fU zyXD)`>=)q06?O*U4y>-v`+qli7r&Az;EZ=U_xu@87$B5x!xbcw1cwj{7#GN-ag5p} z3VS7Q;0CLVv`P&tzsO#xjqpyE|EJQyds?4V>0kE?KugN%mn)q!v}vBoI6p=bHe_;y z6R6bvHCJqCFfZgWEia7XSjezh=2us7I3n@%(V4kB{EC?vsbcP{M|VKsO*#1aqdZUR z>sZS3N|v(_zDi~m8z6)=K@l@+)^hDGkTiawvAU^IuFW7xtgWu^%k1cO(qA_Y1fNu& zPeVi!{qEJ;pCeAfHM}nM540OB9~`B|-eK!AKmHnp;Rgxo*4PxIVs)9zCDqmn8U6{Z z+g3gIAC==KRC`*iwn@rQ>+$EV56zy^z<2%$GX3J5e|Pfh8fmxC9~X$ z&ke&_$C4O7@xD2!%idMvGsJ$lblQ8nXhzt<5EFp-b0+Gnq-G$oEAgt5>GWd_@i<<2 zI2N5B+f&s>XHQTXp$N#TEQ3WRCyU@(fGu3;zs=`%>Fxd`0RPxz)fKoS+kAAcuy6eK zHU<>re;$NeN7T?b{O35_F~R1x5x&VrE5WWerveb>C^~=O6XPujxX!SnarkCV0@peWL4H%)&Vq&O<+TSLOA*!l9V? zmx=8DJMuf*77T_=A(7g=Z-IT86yMZ^O-bEyhrEA7n{Yi$`et&AT2@m0328i2cQ(R9 z`xT4F*Nz>aw$p}NVUon!HGIRA*5qyt$spc(_uV4JSP7^qm{Tk|PW0Th5SQ89nSl35pkWfAkB?Mo%@P2~??T%_0Y3kxSN_6zE5FFtBN zWOzBvv=PA=^8Qrwyndvn_*q_*Wj0g9U8UKbTw82%m8|k#-<+5eT2jW6{7(J}{!wd2 zg2D`yEZTrWf3JYERn)gSW8@)6$^g!vEl40Bz4rWc6cEO1BhJ3nKwb5UvtQ|hNh60m z!tAU90CYJ6siAo52G2>|3jV^(L0E;@YPXxW*|e5w(OGY^s}^pGBG{&*X6Glq{s8_+ zEL%>vr?@>Ot#Zv0Zb{T`CtPtc`Tc3!3$6VQ%NqcEH8^VkJp%5z)h8fhEUmRQ!SVPb z6#Ju#aeSfZHz3SMwaEMg^^|Qd=$7vT05i4xU?K3v{)be;I@NXc3rg>KYCW&BJev>m zMrbj|kS1U|(3kGI<~4Uc)s-Mm>iqV;K)^Enrb`GIC5M-xS=b;0mKr@wvKIIFvmB1y zU;W!N886zBMUK2J1zdBiuk=}v_xs;d#_;MAeL3DcXNvWk$><|zJitWJjjiDL2@rQ) z`>tgY>Om(s4L=`E8KK7ge5Y_1$nfn>G7oXhvjT%Tz~O`TR>B!dK=b)w)Ulbc+j=H3 zpiIe}*HwGBe#v!;xovmWc&PGsSp3?dcgHQ1CS{WTttR`n2HmD%x;47Vpkqx2m+zn8 z=T3%-Zi|L5T02F3=tG!`<7WS|KQEtRbTSsnO`@`2lHcRTk8fID^zTm{w!d7inN}Rn z*NB*6Djr=;j|wD_Ta`b)6ySCrp|{nyMg1NkyZhQb626m0B;-I!QiIx{hR z&bYTV(=$q!dq(&odQy1h;)^O}935apR+HNf-x;AO!WR7wc`{E+eeKNDPZNXDFwWo1T@Sl1scvRQIPOuHV)2UUq6wQO zcSZYm%vyDWsw-lrGjn=F33^`d(gdC30XFnPVY`U;87grx-L+vq0t?}bwhDn({5@hY z1uVC1`j&` zKtA`ir$P@R{2xJ^>R6Btjr^Nc(Oq7IPXXH$&n~B^Si`R?y^yr5Mu^k&aF)<3YObaS zryT5F5SLWhzO*+0Z_)Y3L(zpYU_)0=TvGLD1TAqVtc4np0`D9z6~r)zQGe}0^wFaO zhrvG-t(hscc0MBxQyH!|N^f{+H&Ia&XqN(4X|E`zbo#V3tYe4+YO0y1ST}(5)QOeg z7hO{i?${UBls-PKh=n(Hd=N^qF4h{dVM1aMxr(*JIx;q7{sQ2op?zk0)fZL}@@*eg z*p0_Bjay7uhHYIcC^{*DAc%-lJ1GLsY6a=@q-4d|?a>87yMbLp;XP`xl0M3q30#b3 z^RM3W={FOUAAb61Rx|FWl!*D=dfs<=p0^Vr(ESbJ6a*vEp+G6R`B3ul0xx-&kQ`rt?nE||(&BmrLztJqsZq@}}NlE;;i^fuw3GLq1AEa2t{|cm)T-F4@bq^IO z-fiWm-a5r3IY-uQ2q~uPUaA z*w@Ai;72N?RE68420I7dtof{URT}kM2@*VZwz9pT3R;jGam(RT>lB9U9e3U%HB0d{ znzfDFbab!}^7)+);BoVi^V4Q{-dCbpjRsYk#i!3cv_C%+)&-5w#tLJtQy%+RDXAw{ z<%JB}%Umww>Bm9o_NMB~`+z{^jX_-kyS>wDcUMDGWdF6`r!@qYGmO`NDDxDkqGg+`RUPwY`c!0twmag3&BJ&fJF00wa~a~HLGO+Un249x8aNZXWC zu+<#_n9ax?(usxjDSO^{CK`;rle4_N~LUM{fEVv$Fea8mjBK5xZ{cHT*XhAf>zP2xVPPnuSB3K%9ID8o=-tHqD9_+@z9rQZPtm27 z`;UykIy@`Lp4{MSe`Y7qeX}p3%JoI}A(YQ@mMMv6=0Z_HM~8XM=cU#2W<_A(u^U_k z_%Tv4yKyILrPcgS(l@##0l{`b_l_bsMUV8hu5*@;-Z>luOG@{?c}(@|>j`1EA9c}F zYQq)YK)Jf@%Lk|!i(v~uBW5HYzs~P`nz*gL*h+6ji? zGtjX~cI-W|Uy-{51imz90uO+U9_`60f%(zaen!geQ`}7^f%nu4tuXES7Nb=L)M|$* ziQT9Ph`WF7k5&BZkrm)B2680hbQ=P-EK6PoC{X&h%buid{yuu&;IN%65d2)-@{r)V zU6P)SED}|{GZJ6_-0l`u#v4+V{MABn=(oy z+Q>9`?uMixA@ckbdCbDQhqM1P*W>LH-N?KsR`@pz|NLYTo>Or~T`3_y-4!;MCRoo* zX+orVP*wf=zH3#jbV1>`I~a`J=B+(jUZUn?P8Y9Xqu$;b_^=A;@N>)+ye24(pwM_l z1QZTAY4AK5JMzJ8RnZ0tfeqnFFxhGOHh<$bg7cSC4G+mFyGSvRR{cIOZ@;}i!Zd8h zCdOMzi&hLknbkqY<){2GMq;!yD@Oiig#a?&wOa;%$8;XaK82@ry zVC?s@p4It%z2%<-@DVtW1QIU{h@i?~0}Ur5j?2KkxA8u3w$yKRfNPI)t3w_smD4B= z{9Bol*Co}KE5npAtAg4QsPq&t5KhD| z{&am=!_3T=G)%h@s-U!1fYhsHw)Lhe+s)vCt*v7Uh8*&w&OA`6#dV2mI~j9h0HwRZ z4gvnLx2Y?zoP3+Bee)#}>npzpjvXM(N1wXx;EiT}3?7qCt@+|U4C;3mzS9uKI1TDh zW#ySV%CvxYzIz8KjVZAp)8@Gfxh3q?9eh|ZH;0&Oo)-~Ro;OdfRR-N?Px^B*yU*Pw z{{nygC(;4TX_Cgw;gdua?Qj?AB>MVVL2!8_UlET`V9!fcFtO)2s-T=*ZPJ zv{OJWBlPFoZpB3o3w(r$Cm*jSro?aP+q^eEz-pqQlWrz^&nwZaSd zBSVU-jNq5S{^pCsS8A$-@vzqWhum&8l!6}t#(D^r|)PYTvQ2Zvs0E-T( zcAq8D6j@M(n0>Ez+I$r%&@Q*rnJRDTXl!Q*>BAHX7a}^ekIu-YJ0b25Qbo$QQ9$sN zMDTGWflepHke8P^be&rvngp;^vJK!^vN z4~{<$a~u`^Mo^U<;)%l>>~2W^9SbHhHe8qaHTuRv`B)^0X%p9l6&n z_5p^#=V9$0vO7Y;QfrLRrFqjUdM1*KOiU}R4;QrvOH!%J9_wKqyx7~{gVO`*zLOVE z*>|AJz3KCaCWb2DI>c*7q#!XY0bl;X_wWf|Tyzek`W>|?vK7=<#TQ(Lg@>xbbMA>Q zve&0oH7oflSzqhbiIlefrVz^rIX-(Ezs%Epxn%3nU)*gyEWIC2>_rg5ZlZlyAI^!P zO#6<967p&8=P~|ZY&L_kr=p1CPRX5XLlIJFUdgEE=U1R$s@HYu&d1BWkEL#OjZ8{Aggx(q*$BReO~=6JY1g)WaiN;plMR4J^#LExA?*6~M{N69tU zcdrX#pZtjO13!(uTM8UMHgQq6LEdYHRP^bvuKe{?T+VMR>(jf>5@6L!ELZ}&OeO~V z<)^G~3qOY#xl75|Fgt@dG`}naEA$;@a8_6pX z*-l6OCSc-I_3RxYXbOB{y*42T#=iV``^{}5h;Za1dpO0e^DvX@^&t@EbUB>=;BkG( zzByir-#3S{6Xk5e&d^?# z_qn!rYaxrYEi?n-q3YG^_0Ddj#pA|i>HD&t$Slk49#WE^YuSCto)M64sKKwuSr=UC zp^+*8uc%RMAagzTcTTV))kkj7^kqqe0Bp&u^T{yQL945o0Hf8)pai<24Sr8}P;`Fd z?+ip7@06}1p#gahI=KQ)Q|#5ybcU0_CiF=KTTz_5C1%Mxr;Ah4y%8h#daS8^acz2C8;^O(^^DnB zSfT|~YH!14<^Ji!$M!nh|M4QbIlsxXG>Xwh0<4LM1Z90wbbZPDX0vpueha`vb$$Oz zuSwH@@tW+zrX~9u&EdDDPI?S2dz*Z^Yldag`qtlbdiovRC{REx%}ucwblSebe403+ zc>M_7Rp#SS4Z@qgN@$&f%JHLJXc$O~NdF-g9y4Ax?*QS=?si6-)s>XyRaFO*v_rZ} zY~I*6gwM?#jMy)ctv9EUn_tF)!;(-O$F}^bI#UCBQUmCJWmh?!xSIKRkH?>Yq1Nrs zX?Yi3ZGyw0xnF+0`LL7fNZXm}D3{#^wb;?P#BuRk=|xgUfEeePK}`jKW#x^ql1>~p ztefFGRRePRjRQf9nnRo(?VYkoGe@D6v(RwcCynFAiA)M)NG_^TJu6Z~x*qmcCpG^0 zoBaY0mlJldHk&87I}u^mY&7`;AdurY38s;ZU|V>l#bYOdvt;>U|HK6IpguFR<9^5+_k+flQ>i~%yBr*X8>ZKUnURRn z3`+k*!CcTca6d1U>WP>j$;jkFx)d|$y}4pb<87;%50qQ>mHHqkgNV;UWm+OqUE z((_2~(%r;2y@^^PyM?l3wzgh;(I8z+z1<*L36-9+_ysENwxg zB$)&98apFqrJI?@81BBnaswGGRGFNwxUTJK*XjKx7cosv#Ux~kEu8v0gj*{JstBRN z=klxACT`bAhTFcinv&)tOV?kqquj30*1kvwK}E5Bl)v~zl_PTfyJ77cF`4O;gfH>Z zvODWfE7uQ7fzLJE_s9eX)3;mU4|h&!C95TRm%3HgfDNzU5oY<@OD%`aC=*2BV2pgA zrehz606|dJ&IF<4iaL^-a?N<~q3>iG>9)acu8KJWKdy#R;!Z+0TqxG6&Fqw_t8uD9 zo3{HN_u$N^9mUno|0cXnHJGB~`!fj8=Uy(T@ZA2HG!h|! zwy&(fMuq*i&k%wt56C`MIFYpmhXr;4@1&W652C?;?S}1#IBMY(9aI;*!?0^1vNbK3 zknmxnKm>4ex{*|fjcezYNI0DSd%ekyWwymkzR;*U)}VsOUIfa!Qkttk@! zORDzrmJH4f{USt}pX(bM(7=!6oNND8WI$&Y7XdQJ4b6TGX-Vo!Gzyusxog?|yS?dN z)s&MyacO)6I4$z1)leN^-wENJQi}6$q&*JeRj3E@!&A{?ifM+3VVkdGslY}*YkYtD zLD2M>8*rA7_ahAn;u|DIh3Apw{`=Z` zN&FlgK8Q%bG3GCnd=^%FiK@2Ku-ixHj&wQw-drcS;Yt)rMHlyFgD>E~{l`@YJ?GoD z2W2HQ(HF$Y_8-0@>6}_SKYWkU<4ZLcn_*>vJHyUb%1FfMk?+uN888Ay<)@LUf6F!H z)v>Am(EI#Qs45@rP0l@TmK-SvgRzFu;Pw{|+nFB6!b+B7 zG%e$iW!fE%6 zE(^}IkfGVAm8m}jiZU-!&%U^g?+C^*Qoz58Gi4aRS$_eUIe#Iaht%VglVEL>j^q%j&%eWi>-$L+d>0)NN8LbU6L z3tpzr{*|12G~)yTiB5e%_9Mn66bGYZokqS8z1qX~W!m3Y^`j`L*iids^u&Q3OSx^J zg=AHG+AndN{5kLHqqIGv)^Itz!;uAsT&|^7u6rRW|2c5@Qn>jizC#BeqR)@TLZ$qz zOW+sYo5=^DHuSY?1Vrz_rkchq8IhQw+NQ~px=ac7B<0ilQp;^FmXq zeSo@tHufW~4%`QP$v6G$w5{~a`FI`i!B*`uptBE~bVQY`<jo(MBY$684I89GA69xf9A{-b5WDY^ zEUJaonlo=BCb*202!68KN5?+UBRG9W?fZPvb*Yc-_+-=(t6;B(&-DoR0mM2+M{Y zg*K>Cw-20ZQ3S6N*2daUwWIJs9}f&G=G$P3q!J-gHcCebpSO3Tv)dqj{$a;qoaPUW zTh*uIWND3g#6rNohL_EJ?OZOF@}o#g{pT!~{(0uFKuy`Ae-Ycw7t#*aTU*ggoHivo zd5s@)ZLOEbq(~5fJG!T)??E#%an4OGvHMR}QyMIrRu_fLCyho6kos$n%>Jf{Jj~Z_ z*d%!HPJSUG-ByR0<G47;tk^ zXs}ythJ5mljvzd!a>sFZEXjqRrK8mN-h@*>Qj6;PkLvJsdJ|muzxB(}fbFm)dOtQk;4>1zzFMfJ9fV_xs zT#pOPA7yJj0)M7P?*|Kt}A4fkagOKuuizU5^XbWI(!+rmG7}O)@@+jzWt6?Sydk!GXg+}-UDfW zu%n!~l#J|^s}H9$lgdt}w!Zd`-~QKv*O?#{IzL7W$tpRdEWB*sCCN0dJkCKmJ6Njb ze)oY9*_^AdPO@G5WerB;=m}H+zS$d%7{@9TtEfP+IhEy-3CxinMo^*aclll*1c;Yx z4oJ_P4R5y_v90J=z&1zOF9BtzVy2+T-lV=~A|oa6@z6)Jn*OiaG~R%a_{ z#~Foc9N>-^zxX}9{VShBJC!fXt8#sY-zS|vmUd)Ge=f#`Exls%@GlQaGa-)9Mk(N= z4tz*uX?4~WeS4(k&nvp)ONOgOrbD2biCpG?WK;#wPaTlP@kUjcDfOfgw|Hkh*LXG7 z*1vxFwA9nAan_2XQnLo!cC#aM0Dm=NM((CF=E+h+=om6LC-bM2&2q<2h%pk;wV@{1 zN!eaL57*X>cDk)Lg&WG?%fL_Iegr>?F_G~rBg7gLm;KbUnFPJU(uRn-54V*zh!mVQ z{=sJ!yk^phm(;P2-!LUyO8bCN-Z`$WAk|2P!W6i$kQUkxV4 z{RZ;J8f0GafxrK5>a2$C#Eez%3E_|OLL-6z?c3#C!N#PIO6Kl;t^UE=X+U?`G4LZ* zESpuW-}!$JoXA|FWz7ke^^!H=cy3G$n|d$L1^s?zCI|m6MoZsJJ6xU#k7#T;FL z@RA_F72i;VNio%I;O%F#G>r<&w2P}W+gQ|foa(AfloXwh21c>yoTht3+}odpvBt4g zVWkLyfLuyWY$9y7RL@M3-9VYRW29zpYC1R`* zZ(i;W0S}+y_aBkyNvG^5M4HN`B)Q<$c!b`AVX(CpZRexKg*HzkAzqt;yAY#QjL_)} z^YH3y-t!w#@K^Zedw|0J1-M{cpeW*3b!SgdItL@sO4C>pSZdQ(zxGSNM!W9l(_q9- zOhF)Okow(_#IHzGjo4=x;bJ*xF#U&o{n|+ zO2MX*Cm3#xPG@xb8VMeXKngMOrFfdqSmA+|WW;dss6hWnIi@SenC!N&6BxsXh;EjD zWVQsGhRJsj|JkN22P~{qV2&eKreUj5_`yUIniBg+x;9&-GS2Tn;Ecbp0v^ zj4-ae-HE`LLfl=`JVn9&1?+DCqcc-{^f)H>_g8911E6<_Z!!i(Q+Q>$DJU9eZPjhV zTs_5lRaxg>#Nhd&;~kw6BM}et>@<07vr=LdOk1Q{x;zU_ap3WIodEcY&I+eta1}7&#E317WW`{q9Eod%At3+Qki}lirf;bVv|#Y`FPMlPLBg zA&O|Eh1fY&1{Li%JN9_Pu4n#O&qf2nt>b2&EWgrs!^KQJpQqYUVjTh3Xu#DxBzV$B zb5aNi2ciVhV#7#&!Lq5Uv;&Np=noj%?*iurkPU$Rzn7ngbFb4IKMmm z?YS1*^rqvUUd}PIt!`(t*g~JV++)>oHdre(GUJ@Z3K$itd9OP6M^vvavc`18^-r&7 zNL5pnR{i8hP7R2srneH+7@ejp_;SltPsQ~poVP*M9uw^I9z}HAeTLqP>1YWV4)ot4y*5T2s1!MxNo<`AttGmC&rxTf| zrXthJn8)L?`{x4u*SW7_MAb5sc>G5Yu}3ByT=<2T8}*-1Za0-uCaAG*4ID;w!Y)}g zoU>u{HODDK`rd)yeHC`NqDXo^!z0C>Qv>c;?T=)z$g712Kj##eINna#=4< zzYPpVsaoF;C;wYCX6UH-cF7mjH$7(!SJWqP5#e$xmcrar@;>*@t<-0PeEgUnj$p+8 z#p5rJ-XH6gs;6rln9<2JG&I-7SDI2N$ntO2k-DfpV%U*Z6zkQs2Uaq4QwbfvF~PLLx^n39h3K{BsA@z_c7Mx za+!3xrsgV78rVuy*1{9e|Gojfes#y~?*8vc;7M;(wb#mf3V#N{9G@TEn3>3uE@5?0@;Os!f0Gh#Q`B zIyg11-s5puCL)HI){w{?6CpqrLDxA0`e z%lgL(V8j$8`ZksZ{AVVIVbTHZvLTLUg1Gs{jp75t6la9e_U7Macgcgm-E8yY3n4S_ z+lh0TZjzOztMZp@5{N|(u!79yfp)y-cGyBxQfXSTLjF>)3#UZ6L=@M^%r7lEizhLX z%NJqPk~)_t@?>br*l!*BJEzy$l*#|i5y*ZM@u7ojy|Xcw8g69foJ$m z8-jgU^t?6Y$q4S~m%iv0IX&Sj``PLjeVwR6EpB4PyRa;Yw>T8S1xtG6!)Z&dBMO`~ zZqS3d#di{D#lhoLADI}q6bb>{oyAgioY&XS-UA8lnsY;EXs41D>I?5FD6Q`XMyn3=m1-Ti3aP)HzoqVn3LLBtkh z<2n9ZyDlqy&hf*U!+FCA(-CKy3pM6B0QXeBTep^gS0)&n+@fQ6M1vE+vFq+UVK_$q zp5!BsihKGpbqV+L?joVk6q+w013}+B@;kvZp%4DZe#}*0$wA@guMNDfGtm8$6W0RwkEqeKiw!Pi_@`Ip)c8Bgb)#?~~t9u2Ms*1}WlUBR`^Y zu$h|~XUC0zmiSY=$R$frBuDgP!Ho|TJN`&BylWg;2jD759J1o_mQ@&vHj4E`^UdRZ zoge2~-XlWc@%_>6(&{F2st!E!t!c0bZICXvK+M9=df+`d>08iMQ=5-2ul*o=+(GHy z=TG6W)BZQ30;n^MZ99pQ1PvyH-;2c=zL+{a?Q1-iVbf-6j_$+Adi~ zSV(uWlC)6N%4SSh!rwRG3NC@4DR6^2qI7u1yMBU)^^O}hnZzpW-2=q*OY z4+s!ELr~AN&7F51@zu)I3210&M7bBPZ{nzNNB=DV{cw6ss2@>|zq2l0k$hddnvj`o zwQprvzwA9HosNm9AL*K&JG3ITKx~h4d~VGp=*G^gs8H0lAP+=?Aic{fL;5vCpvxIQ z9pWfp@kVJx7X^IMlz|PCf9Pe!{^JuUObx0`+?PHk%y+RW)N6)(sk1RyGcGC})dxyz zzM}UZ^faEbotcsO&1A0AqH&Nzha3LdMxXPVghsj(ZnH-~-N;|n+DQgL>B>KrFFNhs z@NfPA@^t%K?r(vvm7@)ylS|RCpa3z(+)`yeqCPanYue`jP+LC)3)?)HCHrYFQT|Fh&<&5d(WZ$c(|zQ{nQ;8e|c5B*fiq>tiD_SaBHzj;iyj425&eXX*fuf9=uXb@UX874@;Y>WXu_t4H5rSJ#1)(>22j`# zi#s&i)#KPAv|RQz^4)q_DX;vELu_RxyI1Pl_$;XP-nPP7(}5n-xHA$UuF~!T0*eSr zKv>-O*L$3NJ?ohKVtekQtcd>hB>`2fhx!nP5TVH1IJU?jkqff^MxcSgr+%@Lb@2-sjQt}K1A!U;ETJw1BXtY9CFAVF zosI9Xp$1S4*5-QR4?m(Dd+`$7l#Hd@ziv4I1M3^&Q=Cdzmw1Q`1@)qshIVpLc zqlA+N_KK`XPbV*63QrS@Hwr}eq4$G~kN&KZzjq*eGCe#_?`OMC*}_`|wlcYv1fQhy z&~DSSE+QP|1IB^}Sn%!*Fn%Jecd>7?AwXau>etZF(DfQLoFRSjlQ!hB0{cu+(oe0i zUsppf3mi`V1HP-b{gE&E8S zT>+~I8XAXQC*R(yQ;eIL8)6R0ksMJFl9k6ob_9j5#anwed8JN)%;y3fbR1mHa?biS zj>s3@X9v8SH+SFXB7z8e9M`)0n(EJ(zGHlvarDY=dm-E*u0kl{!HzK_l&f0xAeNb2 zF>Reukc|NiNZe6#EqhAszAkUQOY&T{D%aM8?_MvrJ}#ev9*;qZgqv*ZU3ZB0e96pf z7F3WgKrJT=d|WqxqSciV>&>2J?5P&nwh}EtQU^de)xHVq0^S|v-hp^SwtQKPaM|y` zBpQzzK1O3TYO&d)B4 zNjQiK<`{Nr>-MMR{&+tU*sg_pS=%6p10PdT zJq4kPHQey+4!MPW32P%22VuxqWcf~@I~j{FdYPzz;dfabEn4Sl3fP z9kV{1A(&tKxC4Zn*)}BZzK7M>X*~4!-AK0!P&(smk_skccwhufhX)nBdWh8^(!fM0 z<`kq0y~aK!bWK9(H^vf;n%k-`LB0c3^h|D3z2rmpI9NNS_jl}D34l6TNFu8bQ*%R# zvu`Ai8d1@k2{wU;s#0!G?)gjSbBZ2$ zn(KB>nRL9*0~rl9R$Gx7PlB}BCeNw>5y|_|LB$O+SFoVtzhW~%j0*_nf!Bcu@Bx#l9XaT4-}IX1{IL>GPR4%nw9yvB`4`SvdI_Q+2K>?>wXw%O9PB@L{@5|@(Zl{OAcQ}*E27s0 zH|I30N$i1YIazM>y2qcQ<_rZDiqxZm42BgZf$|W4n{X$deSgT@)%F7Fq|hH8n{Ld- zkjSwvm^3RyzvGe;U>I&+EaVlOgQlKQ!8@Zu)=e%br!RoG%jl5@L<&jZl8Lhl5bL<^ z-g=vHC(?RfT5UToHCJm*%7^AK{cD9%pA+a%82nA-{2K`sy^qjv^YiZ9O7Q)}wXfZjQ%=$OPT4cd~#UOCO zD1p_F+nvzIIPX47(fwvaf3=qfbh! zVGBv_!P|pLx>DwBiODOEdFs>l-5g`GN*!LIWtbA`*_E18!^cPpu$2?R?~BdSG$+~S z8Q2I3uayn-4~?9Mq+WBBngUa&TxWsWp8A+JY9z;X(G=dix$DGlM}R#d7mZ3Nuti8e z07iz6nFH!v_P2|u;OlXF{&Jc8&aoH+r6qR${8RMP-6j;ULpg;7!llAi2hdGf;Fx|` zORp;@Fxeg(Wg|{VfL}B@JOl;<{aCsW7uU;!LDX$fpw)B$aCR0_lF(qAi0m7uN+4%Y zi}tAM)LnIkZPXi+nFOluWIiBht0qx#DQ5z`9`8XmWqY%-xZ>8LB+GTesE-bd{X{b9 z=Hm4u*4^oTLU7dnTWVsoaE1`RQ=Fstf#!5YO!^FS}xF=8Nu~O&P zeK@HU?9kF?`K9+N9R>WJh(v`HG?mFN_>Fx|l?9%IDddY}6#E+$B~v`paYpJ_xvOIwYD#lqdm zgdTx7|~u#jsb z-=CD*BJmpt>Z1c7D7xkDRMz#VMW3Z`>Y49K^TQ3$7u6B0y(vmRT}Hf% z4?jCa%T+s!n(Nlxcj(T=oC|0}Uh&bUvm1dl^xd$(%uq?={zjvJSS%WUHu=SFI!;b$h4 zk4m%@VK>wRVALIF-*}!v5u|=(h0GtPrI1IJmBzyyD5ElCe9~FeW?)-wIGc^c?2P9R ztYk@;R6x2=X6F7FQQxM9y4z5ZmMHhDPK#2Yc^Jy>1Y5rR)gZi7`Cx4^Utgx*Vuf?- zb9>PTG~W&3;MBSyV?s_5KYjYhIp~gixou_~RMw7`n$zmddNeff?_XUPOB2|}A_E3! z4Eq@n%Dvckto!zR3}m?TBQ!(f4ZyWv3TH{twXusr&B;oik9o3ch=R_-5;w}Nf1pJ3 z(wnIEll)?$vj1~$$-x@$HH!qMA1Kb@<-;rWoC67os?7ZG%37k#+_|tGlmrUnV<|Q6 z>44s{#JB?a&(e!!z&nMH8^;x%^s+PLo2UZYqe@PQXLi_P=grWL^pc>*G0d_ID2Y*u zBm-w_-%guuhNo~y*mg!J;f}FeJ#TX> z$=zq(NCYTKbp=om8OwJ{Dcn;jZs>%vhn{pPl8Y+1Mr@(0AtMwE)u4#UBvh>7J%@2cT*-}j8Fdl?;mn)>2ttpu7F(YMM9@J`2r@7TAI|&M7ptpfsE_8)at%G z42E~=7kO1O^1=m@wsK0lz)P2+3h@H2YjamrXkdyt5dNv|7>HaK?~bA@rzA7$XDkorecM{;i{M;g*#{L% zzW2-3YURKG!8L*5{Cxk+5Qngz-}NRwoEWSv6-7c_Wi~R#rlVclT^Nd6Yj>b7Xb}Ayhy94nK4bZ{Psaih`_=wG;z{dJBJR38jyh z>S)Dh@|HXNHX95LK<<6^DMv~{7!_RNRnsLyGx|B-;k z)A3RYd2`za!}Mr;b}#3XC%ZJB?j|FO`XWtLw{-^KP7XPc4oA`fV@9MstA#|8gJ~Mw zj}l9DYDrd}K+!7jC{SCeRei;*Rc#Sdtpv~eVtxKC@4`p7UMqh%{fZ5B&M*F#La?b0 z`Lh*}-J_LP4&^Uoahp{E$Gbo2s^z-03hA*`Tf==dd(-QO&4TK7d+N3m2Zx$Ecb$gL zC2VG{-?A*`)R20EP)!XvFzC?W*xKSqkl(WnUA6B3;M1zdWY>`FB&JA|$92?$ct z&fS-MG+tC}R(pOt+i1Wyr6C)&ZniWP0KPB<@rQ?OUnNmbW<6L)lWr@f>h+W|lzNyR z9#r%p1|y-|5yI~Qqs>)OMT+w#VmpKZdJp=wzcMsRTXvfTF+kjlxlfkJ3K$;8FSB<; zdU#cHQnaZReNhq!OlCMed}l_G+RBrn{>V9(ii00PFazatYX%x2i)P&>51BgoghGrm z^88Uup!RH{&SqAbptX5MJn9hqEK6qGa6Z09gafLQhYZik#|8Uk>3SGcmN#f8?M;^# zvv12fJ?!(lw)##9Ig^9kROOT6lSfsEgvoPjNzp+RHrim+NjC)pwCo1ABZgyWV0jyo zn@w19|EmFmfwyo}Qg9T7Q2&e+=o-V8n!Ge)HFK^PWOu)J!|zFPU}C@#alaD)6&OTI z3AIYF1ir0cp$nsQv7{f+td9Vhqq8mOJg@)s#J!gg4A zS1ZFJ3!_aMDzuGbw!|b^5uykbqXSWZRgJqYH`*Rhe`_x;e5DHSy2$B?GI?maCO`*_ z<`NU?3eJn&sWu1Jh_0(mqB@o5r!ct%*3ytEWGsjSDY4B#+Z#cf-GwGcmEm6+Y0cW1 zs8$+TAJz6{U34@C)R~9gI?MSX;a^f3!bTKb+eyRD)zW}iFyUG=ZY4N|>)&@^JVapx zv>yd57BTQpYI~niyC|K8)Zm*_m=N$>z(gL#7aJsf zjdkT?TyF^Sd>8~4{EpjdCp+ARKTlTk19s#mBS^FDn_fT@YdV%o4=@s#lgGp_z1c9i zd2!`r#@fl2-!crBE>}NRL=aNq!va07RGFnZ6DTO5eAXzE@eZ{y~X_mSykk zWiujBHxP2S>f!#YVgZkV1MUIYdK()$;_i&5>9oe-30v`2Z-_ zhQx1yjdw%Vh;OR7E2eV)l&{X_0R6_d*TqQvJMCft-WkF8w;iZp{yevg-taYo$}dj9 z+w{jkMxv$HnuxO-rL)PH-X}}ARSX(~3RhWM zl=eSfH2QU#%N(|@uf{yPJr^?7snK*POhnitgtUlZA)e~Sao$QPif?}=7j3();h6gb zZjFu*0FcJZ>;45^h?NMEN6+K-iLRLMH{gZs&5uYknXfHH=|KWf2rE07mxPn^>YELx z=YNkY=px5_3uMOCZ;>t2VQlRSmYl2xzr;flzTa2Ts`XB(p195yMa~06Z3;_%M?Pm9 zv+@TW+}1_I>f#u%d)HG%?!$j#O4=B0c6 zV(Zy~?78+YcPod3sQk&uRd4P)2)t z*`cSLdGq%(NV0%u+}&0<=z<_FRzvHd;gH&pjLg z>=Two?bbN!HPiZ>-0n6zf#zi#7(MQMwT>d6-7iVDFrWDtdda+&;}KFD(czWQ*q4qX zOURLq+)gZeg>%J$Gl>mEaXoOJI7$-Ei2D>~c<0^jyTx6(wBMSY4r%ljq7G8qKvrMOLHNfdar$N&5!*hE zZM&tqKT+X`X)G7)#2qqm1k5{U>RildjiP>O^rs=Q^6s zpX@hVS9m=t zY}oRQ`#yC(`_n=`s-dPFrZ|1 zivc>)Z>|Y52Lezra(x={us1Igc_--3_R3q!%BBTBheVRwv?z~sB*vV}@wJ5|8Dr_im{wiWLNqijV>Dn*kZe9TLRR8(;eeE>V--uTkCaGF z-5(3K#ESi~-Fj+K(0z!LkYK21Qg9kbXj*S7;_HNhmJW*MYhgZI4lAO>g*puY!-&Qb zi*(iYmeapjzu8MBsZ8(rItuOrq+&Qc=W^j@jd%g@Ex7yWp5ec>&!O3;&97vw0=_#T z>z2G0bQyX@sZSq#invC#lHzI5&3UGpr4-_swDg?!S4~Ni<`m!!-%6Hqcw7b<6TAO( zv%4SarU;ssAt>R?;ws!z;ZgX#JvWjYYY5Y%i+)J(D={JC(V|Gg1zql9Yl=vpbxa+PEh?0Z8?eP2;hZGsZm1 zzDEL*vkp>`5EVjG!KNG;(?71CAF;b-o@`x4l<9 z<|jFqsSiJS1AT`-=7e~+^Q9X2G;jWqg@s+b<`T%7M0)EtkT~?)b)JViy=egH9@yg3 z(#`>4=YU5IsRle7_WVWXU2?0e!NS^~R`2Ujn}sGdo?pxj2lG68>Kn{ves*KIeO6bV zvEP4QP>H(7cP)$QdsB*n_9xhfBAAsPJzyd6$By;*m>Y382;H$#9n9eSCoUGgFBwzN zx3;mlW1pCX)WZU-Rq<2`2MQ}lMuP-K|9dp%4WFF!zd-sa1AC{n6#wrxBphQr-CcZ& zr|UHDYj#fHy3--)3i4%7#&`YtH%a(#5o2|M9m-6l)RGqE1+|58pHg%KpnB)YCmnFx zUp1y8fm?3w-li`RU+v<^8{K+=DIs76tF3qVcj8QL*i#E!6Fqeu`h=< z=QcKM1_zjtm1@_-3j5pwL1?m=kJ~ne<{OhSBaN<-+SSb7!#x1$fOvBofB%;&-wRf- zdHbv1D*9t&ypB3uV=w7p)e0pbbHeW%;_spM-T#+^YSU$uc6f0x52OHbI~~KthDeAI(z$zDL5^BtR3<@%Swk^5%sR`hNaMw4YWAn`E?l>daW-hTz4LF?n>+y zgYH6fmT>gb?B}}*PeSjsr2is$ZYPA9veQU1JcCSJ`;&_$T%|_sk)nxTKWphxcbTDl z&IMtiEwQZcigMQUp;j@S--|Q=_TR)*&np0zHdY^{vArw80{u5m=zgZ4t$g)=ZolKF zlT*Q(n@ZA1aA%|c+9d1^6OFn(&j|%oke1d5CIcsfL~HD1A+?%QF5acz%!^fM@jogJ zrDXcvXmu(iM!Jopa7r(EJ^By}dnZ?GoV%gWN#(GKq^m4R8GFe;zR#h`{Nl-4!dvZb zsQDTv`*n}JCOB&~=tjTQaZwy7K!28H(CTYeRS*&gR_qC>+|*<;n{SdsYmIqegCFQ@ zBn$}@gvL$sPF4vwL+Jf|BQBW7lMe%+y9aSr%n`p?7R57MvGkFn9K5M701wMIxikKQ z%oT~Cxlo)P(wR^}=6U!1X#19HDIU8yx{A)JW*v9Wz0x`+(a1WR#j(vi11QE^A(9~p zj}1QMQ3-Mne}(rx=66ANB41&b;|lNlAq|q27~$sIPXOFCg!e+Xl<=JKw>KNFVKXu) zA)Yj15+>60@!uNKnb{!602(Bfp9gXk7_~;Eu!Q9MK+!dq7Bw)?)q6ms( zsw-TK4W;|{nr@|=Gm`rO(0z;KY5RJVZ1D!JRY^f`QOQ|GMooSRMp zIpK8*1Rzy4qprCN*0K~nJ?Y1B=s1Qxl-AYr;z0M_qL&Kk`r zzsZ5Byd^_@2BBE+GkmLn0?)D5J`GL!FnfYyiUeGUCeocvzF{50S|1k00C@O4e*f2) z`1eU;@8xZJdGC~dJXB&W0X_qlQ}bVdWFjbdb$n}N9nd#9DdC>J%SC}i#|RFqn5REv z=x!zX_Nm>zx1pRRltUYX7IzN<>fMdK@|HyVmIrMXePz)vH3i>`eV|XWHlWJ1$Z&)R zNG4NgQcjm!!-B+qerVwO>shoFodhP0k<|Qzap;tp+Q8{g?=RdFNe*xkJqYOzvD+*p zd;Mbv6g5BZH{BPU9@~NKUuJf977N^uC5e}MIw+k_I67|tt>e_Z55d;|NNsvjsUnaq zXHmc`tZep_Tf}JZoTxMAh)4MLUN=e1BGt#0dAXiqthw};X^edH>8$)j(z(dLAh*^@ z8O~9z)2NP1ml=1qHC#Npp2A^G6HXJwLyT9djJk?m9LayF8@x{Nyf8A-l!v1!b9La7L?iFd@E#oxEKtFwLs`it?1B7BZ5$Oh zqlZv@4Nu57m+!d3y@;?IBct)}5kSug&1}7O0UFWFQ~1bSXxe*~eEAr_=#jc$M>Mx7 zwp>}By+*c&js(b77^iU1ybSjaIMFnUptW(njy)cW1x=O=MJySr{t z!KFHN{hQ2bXgIq7X5Oc&XY#n|cP~X#h=K23jEW;qWADkTCf7jY!y7NDnA8(MiLObu zy2nKD@2=wpuq4fI`2s0us09~C^Q>MMhcU&|Wphh#=kn1yO_kwv)Or-2)RNSaU@kRbfGRqm^ATREaIRIOqUxZwcelGpDz2|rg`24(u`LB8aElumK0zOk1ktm_>?x) zP?L0>4J9GD+g0ToO#ctR%Wa4n$P?}TtT`Yw${buRn1Y1ZPDQh3BJ*vbPfDe?pPQL> z4CgBl1$_?hO^;6~3?!x4#`^gg*mbKn{|@~R3Zd&J>}+S|NJ9LA%$tXP7eohKgJR=1 z7on%Q7?7f}@iiyqo#!t$njoTLS0~bX7R6>DA)R*IL&owZAcy19&)h&whs!?8Kw{F+ z(8Rkcafe0zO1BBm2wkq{!>}i%fe-HXC~FOyCg$a?5Q|=uNzwJyt0utL<~-}Ag-f>7 z>Sxft*1efxT`{*C&1=|w5r33LgdsqKTE#k8HC&1kvbt1(Sv z$}KcBz8)9{uouNdF`y#;TyIJS`FwaqAH72&WvUr3GSl-k#l4T^rPbJ`{uX`F`??z4 zBI-c9Cz2x0KFOOAC=}+#CG}8G7xrm*Y8B4+M77{#bEtPW7|o5E*bXjrUK_*1+svYyDGzBmwHe2h~Nj&Wc1 z(nu{nsWux*JDEgk&w+t3tagUTGT0xg{xLzmR$F;{YO}V*R3V)(_!28`8%B ziKupof;mo7B<$WjPH z4E6sA6jqv5n;M>oqWYlYQsj20HO_)U%!X1e(^eeONF)M~<<@M%#Mu=(dsME+V{U=s#dxLfQtF)IqHz8{>TGC zlgEd9r%jumx_?~SeLsmF0zJMRMBHQHJnd_r>kb!f_ADgOa-u>0xqw8PwBnh=ub9Bk z5vrV+wc+o7GPKUC`{_I5zm0;Suk+`}Bmuu!=X;fn59STu9j895gH9v+2*{6i>=yrd z+39W^l$N5s-=T$5whaP^$Cn(J$s#qUl@(-uk8RkjW{`^i&vJRLih^=LtGvIZ{G%%% zjOV)>u>#tO7!cjvtFw4~%xmEf@Ek*sFkixI`DgFuv!(QKGD*TV2P0w|`#*NhKUICIIR28CvHZgT8 z>=r7-cr0eh46(w=0D)^Z*o%RW!z`T1*Q*jDk@5!R9oz|vORpq>j+IZU+joW{jwvccyz(soV2=cd{duhIPx3c+urlAe^9X0O>Wo)f+CuCrUr zD~G&foapj>e2`Smbz~xlJKQZDI2|{Cg=Z=~L2CG7F5Tf92Mg7ZfvVttV#hiMUI4>m zG2NZv?>3?dsbX=wMqgV1&}5D*GqVu^pN&Wb3v;{qTD4A|**}hPKu^u6FxPWpp}$Qc z!@!FA9gm!0NT+bq=g$xtOdcT$eddKU)mb&oK6xSJcJ~KGhS7ARpK{Q5-eR#E#~hW@ ze28n_b_CkY=HFWXuws`lmDWcH*rrxe&o*Z{&DZ7nh$mmz8mDI4&ec|uqZ~i`$z2g_ zLVQ(yBNh<7r3b^f@O%NFTb8oMI*|D3F)h|f5K8{^XLuCy8MwRP9(}SDI@5 zI6L>*6pn9~AN7}fw+?_u*An7uMvl`T)bX9PuT&S&F(*|Zm~O%!V7I>0oSSOY*=MU;LVjbKft zPTT{^hhq%S$DqsCv|SD_2fT@@#ty~1z+3mBUpIT)9V7gMg}%ydA~|gL{R5Eo8?;Mk z-*tD<&ojlvy|SxS4CiI9gBxzKwxpHrq8e0*A%LupKUwP;sJ0v*)JJV+w7P^HwBDV* zLxQ;I5RPdP+6exjjQ2cw=BJ#2|JLB+fXg@-U<%~P8{B%n3Jf_-eOP%(K{OA{coMPe z!cqp76_vl{^BfExJa6`Y4S|z`5?LSh6PXR{E(P4SEl9veO=pp_;nwqIrPWr83~afS zm6Jh)GnvRUXUg0HnW2`?44UWw6ILET{3R82%?@u?)5jI`-d&%$2p$>UQ(ei`LGH7c zh;<4F&I4h-GN*N)g8?zrnsR4mK`wx{>cY1A69$|l53nu{NI5HdP{H)Sk}hzEFMj~+ zE6=ReND%&ExR$g0f*jxs1vuIime_QSIH=R&H}4FzH%}Ck%rABO*Ze%hK?;SVsMJkS z6kzo)xQh*WQ~+$6B@;&zuqyCo`@%c&SBOyYyJa#BPWRbhj+InM=@YuLwnP<1 z(M`pOe|d58{_5z)N_&vg?t~2guhrd2YbT&Z{?-ad5bR(t@bwCFk%mq6rZ68QK9I=F zjj#D&@oraNDyJtQE#9-FFse8Lg+<{b&WFq=0h`k9M3%KXQ~o&9lU%&rI{x+wITO%G z*{tgbsFga8@cEd|m%GGZ&b4p142fWO`+;EQvrhAoI4>x*!8n90)y#E1#y)wCbD>r4 zZ+ACd>a6><=|p$ehI}9I%Sp1r$=R!V*xxqjkMKqb`0K=_v7N zKb+A4HTc{xKnLDOM0U0F$+4Un15S7VZ54c79+!GgkAV)XN2)Kh0kL5pwA%IjOQgg+ zTQVMep*-K>db)0z=gye|EEAq$0R^u-Dt=RYPoGX-u3d*jnAZOZU&5iJ=lypZe$7^1 z2}hqnl^A2&#ILGksFXiBY=#qTrVAW?8I*MWdVmXJ1&|*iTyZ@ia^bh}D zEZvd6-;=x5K75ZZ*m<7mLSqKhOLp&1*@1}!No0hh3WAZgytZq#ZAiP-83(~#s9~KT zaKIM|_w*b}xijT0bTWrsq@epK7o6$Vhxu0RwuWrLpqo#Rn3}gwQ8(X9EFGFBtQIhe z8#+(`+;4$RU^ptnRgMrg(Fh%5Ub{}VB;J(g6ghGNjVg{uSr4YmTunuOQ}`Sn7g|?bZ6th#pcmy& zd>{>w`f-Yhclu(Q4)|I6N6!j{K4g;W9OVx~48RgjE+FrCN9u&sp49XJd zmPL{CPSx&zoiDQ;Ro+6n@cq-x1(P133PnaBt&3fqWdaQB%vKvGQUn3B_WN>qZ?y)u z9V@#jEmrrz#;x@?buCL$Q8CMpGUCX`VJ9FDb^s2dhrf1bQ`X!DFdr9LUV3>0ALOm) z_2>{q%DNJly`-?Mr&;eM`3gl-H6O|oC7Bbxa1U(S2D zazVzBApj=M7^*4>tuNASa0NvAbG2Fc^4`)zT&X$vQ$G3mntcrv%Ldk9_GcgOFjQW zaY|xiU(MFpXWmEi`TqMedlf*VQpd7r(=K9#psSkY)Lg6}Bm~8~9n60iq*kZw=hyxA zdwA?V)2aaJx}BNG^7*F`g6&^%PHi7l_4o?N24KwHoWnQI%CpOvO)6Z&?%Mf+7_Ouf zP{?wwYz)tSj6Go5bdd|c(<~?lWI(m+7u%!Mc!PtPPy|+>-69izt=^H?G}j%rCQqm%>rOE^tW5own!Dfzj=dZH+7=Zk#Im| z@F&BxDagg*!QxmnN|xLY8jrHl#T7uoDjTa@(ed{W(>$i;CBHTQLn}b|JBpjM=$&P2HJ5FI@4VYY_{JIMu zq|bdLSZZ}#`>xyKqSc&f!-blNBni`A$a5yVKJEk!=>sVgwl>zP)QfZ9Bzbz=Ss3M8 z455eI!?sH0IJT&eLk76>Q5lM``I7OAL2-(?#ua)I^^tBRQiX}6T({op zyA_a5#JuctnUOB&K5XIx$o4H)3`q%V^<7mXzEB*J{q_Ck-5q5;2&z~^U$GcUoeV5( zq?J#PrT}~Ol1<8I2$}wVPAM!0=m7rJ`Yk-Tj3_}*BD>$9fOlWC;fb(5b15A0lhFS= z#q8_Qalw2H1WmXy_S>JQ*rZfvI6ZS5_NP#VeeWp;25}Y`AWPY7^LNCE0CYpdw8Q_0 zRS!bB7Qmr@T9x`^OIiw^q(djERPZ?Kn-~q}4EuC5_jf=av^q zeRDX25sb|n+^e~|2g`re+Y}6tj(Xc>m2x~Fb3qPK*6Ym;{FI`g4L^=b z+VCT{$^0)C)f>Ub9cTy8#YQ)P+rGtJ2pkwEKx1Y?Y%h(6b4C#f>*{-+zd`k{7%G-L zBWQnTFwh-^B}jMaunNU+zh7p^Me=yhBG}=SECu8eDZFtL{bD}Eo@@tB2S^I4D8)l_ z6vT>8ONg_di9GVyauZom1mHf;%oOr0nh#OSLEIi~w6&vdhLT)NuszD934FPEa~|j0 z&`c0X`~rsije3dj#SlX#G9sC$z-|#}5G>fAsZ_BYIfy0~bpK3>c1WuLrHP|ah}ED8 zk2C80UdYRu@WE=GAF7Z{duj%DjHG6U^^Bk)SMJ^#Y)Au{7&UVKCr|E^qCD4#b$R5$ z(S>Hj6kXQIoiU|$UY1eJbr*Y#Zw^Vee;9v+C3jOeKq%h_O969?Je?Zsi- z2ie5loAbR5fGcoX+r)k9!1&J2VZ7;*!tb2lkYj7Qmd=IR8@q?tK$kYJN70PM|gBFQWR2JAPRVkH;M~UeheIjpk97*JL8Tx`v&rn+Ivi@a#6- z6FhPrIlT&ngcxdRY#~>%s$Y^~0r=H6MzfsDd~FiM+XROr#o;I{eif|AQZ2waB*e6C zato|s#){hca3&iM9qet`eIqo9KQQd9@kI5#_FKIklTQx7K z;A==ysq|;mnSTf9?f2BHHpl+_v_f3f`>z)*SN78pZet1c>Bnm_ZE{1L{t^>qKIcb< zD6)nxlTdU5z@W(sY{PCNClrP#E&wRvkWb%v*XPN-Lyv)WI_Zojr1Np-uLppT@_U}< z0!0q`kjsN&k=(h@aot~BWIyKQ&R+j*Pyl=be`^c-6>~yxDs`2M7)}RG?|%;$XP-o# zkO~70;l$kCO?p5Ld^YsY)ciYQilP?;tolr0%lb?i0&cP0McI+T^%0JGx?8Dk>!8|{ z>0ka76Ct9Y%#Fq$O07wn_$$^&Ytpp|IH^Lk3WYds3133+$YUiM@^E$^uKL57bsQL% zTmAgFu?4ihgGkF#g`4vfmW40Wc=7C%F4*00&bQR0kP+;+DNQ~9VLko524}c-`<@p9&2>BpZ|(h z3I+1i<_K79)&d93MY8j0FvMG~Hi98%V@*+HYV#tg1+x!Y^~wX5@7M6TQm=MDrU)CS zh7$`)`9&D()4f?)$ErJL3OQ5wObXVf75rS~Ty?T_{u8A?%n>F{9+F^|Iujb*4r9w(ueE_}MeF&* z3Rf(t6u+~ys`xhG0`&xe2Y z>Gb?L-?>Nn0n4pT<6QmO*7Ik9<}BW}-^~;0Rq}TUS7fj+o~x)mW;y1-D%2)E`SC@g zmlQ`814La9pTag-P>`kE2>P~|u&Xv6EWma3(}$6M%e4RahMahvXpAK(1^&Oq**XC5 zIks;t%J};9@*By(a;<6c9b$Z>$kB75*3xx*Mr?B=jrDA6gm(pF1++<7#;XOspe@fz zz@8TZqQ8|Bne?nyKuw;_H~owp))zL!yhedThPWM`FN9tVp?WIiJ3JZhfuHah1LME7 z8)@VOCBQ!yD3pY|y<=?{1)ygmum02b{1O76v0yyudkkG-&|y7|8nmt*d|{Hx??e8| z%3A^Aginqg2%WlDeH-PU3FV1edCVkWTlK_cUQ7Y0duTu35NNkSy>EBBx18lZo?1m# zmFmq}QnuB$17Qd26(r?%>dgsle4Aib13bb_;8{_UNOZOl9DjQ*KUtgLTw9FUPXW)R`=uLpz6Zv~rg=|S;9a=@iLZnCfWXk?%O={AvlM+ORLm;r3w9J(?6 zce#`uJDz;%jrs=-5-=T|@Dd}_q=+H~+OY)D+8ZbGwKu0%`2y%O^~OmhS4P46>TB2T z;^m>vlRr2%DTxLs`7B^ds?*-R9owCDV2kgGJF`=WJ(43Pd18`qJ<{)>#93BW@e-AeCHqWthZlCIa|6xJ6n zmuh}yYn_>Sb6<^i;0=GJQc6|gHy>tigSQ^Af_|^+sW)woVKdz}mz~}?93#6ZU0O_a1V#P(L!(-*)E;mN2*2VCZpsjnUc>{ zTplW%rIReBl`L%B!2D-*IGy3B7HR5|{ejU-(}xSlU-H$pphbmj>yw8uy0;&;L^)T- zT^}zQ>;0hGS84ebmZ^PAXDb!Cg(E-Lfjag!StZoHy4P(J|gsjVb1 z=2DuzJ##ZYB{aT-ij*g#tYdY11XX_ohBd|~CgR@$rKc2f2{#9Sx~ojQI~{0ja$Br& zoxeLpwMzsC1zq*+m6Ye*DPh7Qi6NuiuVE3k;qZD4!;yWhD$}V!Ee^<_#k`XmjAz_I z)2~G?oi%y+K&Ni#VQ$*Mj~NhW{CWy`XmHv6O3Aq7bp+-_=)zysPGgto4*J01>$N6H z8j1vG=RkJi>QizDEc)lWKW}eM~!+*!4pRNo*qz= zC<_QE{{Q9!0MQ2YKUu6V{*Q<*1`rTO%#xr(;Kb|Gka>0iU)=YjU55b7W(qhp%~+A= z>!!*Ktml}Jcq>+X@6V^#kjPXI58#)iBtHU&2ce-X_8*;B#Tz+9L3^ReK6qb#1CfG6 z70#Rc!~p?jGj4Q%AauHX`NbcL5GwP#7eu)RaTp*H8-qj)Kyz=X0Fd5m{!z0>j_ZbP zYfQ41IW8UV;FKvUFrg(;yFVl5z<7FF&cy#m)?0>E)%IP#irZoo=6r0% zRBXF`Ua%rd41}KkZf?Ao5L|<5w)oWFZj||Rc-w5(X8XNAxxYE=`-FzA!c~=1ZyTzc zkqGhP76H3NjPTHBWJf=|txM(10;34(1eAM(q!$sS`M(jeU}GK@sMbVM!2(hnQrC|N zmkcp2JtU}x4e67PxhYXftjyH=p%J%Pq^ot7LJ$bu0qRZ*j`NukRaSr?@9gv!R;WTi zy1?6A(BEgNznLEk$;8l8r2c6=XFXjuKXdmGMrVyN{7feCdTZy!4Ty(xWTG6{S4`ik z-#G=h*yMII8a8&Xi=usu*Jd~g`uJ2ZBHtNFpDYu@v$Ey&kY!tVLI{Fn&TZzP-eo6- z62R_eMvbk?ud3(B1X<08i=i2(=6T{bc*HBw)}Q7)NCjL9>+gfz!Twxn3t<$Wr?DW3 zzXuA?v!KN;$_?}CV^1fl{h;JR;+?LB*WahmcA64jf!N;r{*!5*cY!ujuK~YfU*RY| zm?bcsJX^GsF~OKPo^Ei>QsdRhh%@}dIokT+bJvO%-+4F9JeZeT5g(gP?EA~3&d3dr zXHZ+aSyUyIgzAnma@}Y!(4bgVE6@mgSUArXsTQvTJ4M1B#(4@uAMly=h93Gq1EO3U zuvz|Gz0*6v77AdRLCM6RVOJ!X64X;2By?76Acu}#Bt=H540$EbuzUaxFdv&G_Ix6tP#>=O>4{8R;#opb3oIgD0I6dCUk z7w%1!oquesMoX&3zC&hb%(p9{E@abdqV>Pq(+98LjrAj~rnrYhY{xWl^0gp{`l{jM zkQgf&pW{JpA?sN>jHMqslC;ZE{iHmK5Xi$SsGyc`tgG4%KHm`ht(p5V^Q~AW_RVK; zR_BfclqRS4md-0@k_n4bO@5#CsNe#HjJ|OOg*;Fj+?|1fj!69T$LMR9(O8YO`c7d0 zX}Ef4$U7#24w^Xl*3?1NR_OxPcAR1@d4p7ee^HSYTSg|%RB(kh+ZeELQ73Y`Zl$g< z2{XA{cFZ zh!8jXvga1mQ(gQY()+PyNj?Cl>G;h84_N34^h92xak@@|?}7GD_{DNrlx`7~%PvCN zQgh_(l8G-x&m8BlcOQ`Iyy&A;Se{h=Y!=6>FrA&QSEvASbjaUTxZ=75cO2vHGu46iU4_ zPM%Tr2)NE6qhT+n@Y%tqujvrLR2?moI9Z+-@=$SvupF05F`X!k-khR@P+gaKhHVnt ztp18M;VfsM5a_wl+WXe!#vGB32%tthCVtc~$>Kr~c`MT?GY?|>Jl+PW*HeS@P8;y2 zHS<;4ZpFAX9=o3?ye$5$SabT>;IL3Xw%H)(e&-)RBx645^XdGf_#J0B+9NFQD;ZIP zggzP`Ol~9nbwa{mpJ;VetQ%}sWRX?I{nn_V5AFexKv9UbCigJtmn6B%wing0m=E$i zBKzGpws3Rbgbs%8Z%uQA-qEoBRwZH*&8=ku*II{ z6Zlu6bCsi0@70B~KAh1iN<82%C$YQ0WwLExNh5$Jx^!t6LCQ(uG-Y#dF^6~dqTX!Z zYqr6*7_>ylWO!$3N14wG@q+m~SsoHO^v7xD#;it-a@K6;bx2LPzXf|<=qDW2K0go)H0 zzN<7$vpGY%Z#yWJ{O-C?EC=05tj5b9WY4Ec^j>1Pyqazo$1ok(uHbYV&`9F;j3MvN zu%aPj&$yl_5NisVGmN3ubGGJEpjd z4YLC?TEwX%F_GfAb6`3)iHgkKEgFg^7ErX&#QIzQ3|&14cNtn49hgBJ6hvtO5221X zjytzov}%7qKqIP*OS9_#^1A-fu1zhYd5Q$Br&aJdPU@Gn7Sp?pAulU>Nds~EtBTKf zbG{$TW386bcxKi>hj~s=uIMMOJMkxsvHB(C#GukPSO48&kV{@kzK%o2&+XJh@;BMo z$8c)|DqW>r-M2)f=VoZnIUvs}Od)ogNIp~|ZnBHzG>JKqk?>Jt$w`e<9?z1ZSqtwT zytG`&3u+0%k-Wq?zwJ`qXId~T(`5Neu}|V>@~n95ABH=#We87Ja9rV4D860yMl_re zJ3s@klJ7TlOe_UO@0ZffM(({Nj{IREX^{#sfo-1?B z)`^2q(0Qh&*c|4vv+#a%FtoI;)-=7ncY>tV$5nC=aS0e5)H`}YTv(osbk zChG6gOYDVvl*q`-iqA1&CTRc~^JMWC0<^GOT>`-R};z?m1zi|1=R zw0rk!_NMws^nDDIlit4%wvzJyGPmm~^FY506oi$+D3O43c-K5qOFR37Js`cHT<|B& zK)EY6Jti2c6A@pRYS(Y8_hO?1ROhE`&jd-Iw+^2LiY#Jb_fadW|9KWNeQV&u;7-l8 z^}``i-lqAFBSmcf`o!uDQ}U|7~MPXLQ1^b2HOHz zE}`G*6=n#>^e^okH@qp0To3U{Y< zCIw#p^X}+}pcxC{KL!z|$1a`{u3UgQ$lya@iH=@~E=kYpb>dc1X;|}S^HTLEupR^d zBlXPf>7=@TQu7;&tA!@lkMwfMwDwKMA>lM4OY7F=cQXMrQ=5;T*@&1x+EP-mI>hzL zKIRO8Ds=yGR)bI#V)yv$>=#_{+f534@<;gPz1^)ZPaOsYJTnW3xzt?MbxkMO9c;3? z+mJNS_X=gkYVBpg)AD>}8h@KA{=tOUScem+tXy-G-wK#K$g0LhF@cK}%w^3hq@0%6 zyy4OWS0UI;2<(SRx~cT$#}`D3OVUM~T6iObR5#I-Tn+2*`rqUvT3>bMzBI1oe=YC% z0N*YR+p`sf!D0K_s$m_ahibulKDnoUF8?ptyghly`Wi8A1uI7o+y*L1~{{<&JfU+K!AR3AgB%!VJfeRzLMSL_K;O$Lt;l6kSv)a zIVT+=PnyZUeW-ne!0`NJoL~v80}2fjCBeh|#$1bYAZoiu*b>Bj?-80BG}U8_=9J|- z-QtUJbBxa_^j)b%GTnH9) z%S_K3*ohqeunJ?_r9Jujl}L)T7S2anHEEj@>YCYPkg73$ z?TqFXMK2^NJCgO=<}9uk|CL`$MfX|@syjw zUB0NO4qMEh?2GD0Gt7j_8hZg2d3EB|ruMwA?+8Dc;`4Pd#9yXuJ?atU0bn>6#hl&! zIoBw)QfLm$J%7}E9L^^-k#*e^H|~f1>CN7gVbfT%Eyj(uVj;Kd~O<*ZwB~lS=)L_`)b;p`F~QpFXBIXI{B{v?T!y(n%a{Fu_xn zPZcs;8BP;)cgeUHKgAn=-`tJZAD0Zlp)#X3_A1go2hRH+>c5BwwWW+FzrCmnp`pP1 zjon{7_2r~l3!Am|b)v|uxva4W*e-m?r*<2^idWs{zqyrJYQtV9x%U7I zMf!yQ3?2^Iw{n-S$WSnLGhM_&>45~HW{PjCZx+xj#-?1NjsYpIHVng5BUbk z?F_h2=CMZA5*umyT$&MF#u_)R=Pd^ex+bvAWXA0SWM~|_g@`8|-H5nD-)jACehND~ zKI3CfgAbXK(^7IN+-T18t0x-N6D?CJft-}Ua%3e}o2RcNKNEgM|3A}o_!|y$F@~SY z57{zy`pqNjR}WiNe70ShPtt=dsD5Vl&H2!^*sL+dn54#l#t|7U>R5xMA84vkPepvn z&Mn+z`gW?!tj*vcqeSUkDeGYh`XFHCe)+t%<%4}HJF0A_nK~=30vvlrb&}r$(@i$C zscId90W;l^M4b3qt1PDK%!G-uDAA%!L-$d5db$zc*X91VHEljP7TlSS{S0 z_mYmI5Hv6JzQWO*3FiT+ovG%O+3>b0J`@iY$vc!Qtq;QaYWlKQdcJgO8ZrF^AR!&C z{@~6gvpz&g3J-nsFGi%7{q`6n(S(dK_Kgt)ut#ezAL9iG%d}`_pL-=RDmrU?7)pz_ z1E52qnn{$k0Ydt4b%^g5WS-WU^H)A55DV(^wlefK*k&mO0)53#LK=UJDpfSJuE=w#Otsbiv^D-I)rH`^`{vVOo z_~B`S!zG$X-QAP2sPEPYf|jC|k$nw}^TYA?C&aT2Xs{U$L)Ke%Ij^EqP zpGn*u<@|;jGQCFEhSHHA(UGO=4W)hL`^#rH(=^ebO0oE2OsqZK$hi~GIJ`4`o zr;*4>N1mVk`)JllC|V=Pe~fyP8lP*|p5!*xM3zP(Bq@w~eZzNLt*84Nc=k-Teo<9w zi||5v$qHeAx+5qUPC-9~`lMOp?6#68Wv>~U^;=CmK`T%II9hKVcH6XR9@`&#hSEiQ zMv0j-M94!#bo=jbGln~*WDFbm6X9$ml00Me2SrDNMx5Ml=o2TSuK|?+}B9gb(iybEYKnE$5Hrz1*y`M&;O5 zz(M%f>X}q|W@6LOshbNVf3*0bDya{S-odoSX#HLFxWXxv;LijaMF_Wdvl~;Dfh+eH z;nfp5)1cSgJ8y4kZANWo>ckQ{)R6bb5PwHMqMy?+ViPyLI($)m2)X#w$f&Q{90w@ zgatJS@s2%6ggzxLH+TG`N9KckLt#;P?m&$*!5Kz@K%TFZJ3SyC)gfHJT@(br3zWSs zt>K&UFFl;`n5sa7v|A%c+p%czJZ;vrHdxkI2t0gP_9`{GOnoGABALHW=L zfPw;XPeQho(yu1+An*3~LZ@xbLjdo_@|7A(Vp^jcypCgS!gzhJ411K>JJq}TMzR7Rtb~dNV?|Kr4 z43&(eiU-UpX|ixG;n1`k^Ve8&*wp%7X9vNyI%_6>a{H81r3zEF+-&D}!?0~7e_L+C zn6iuKZDN5Bs&30pk8crLR)oW6&zg2xzZN>$;RhPkQs3fk3&i?aM^fxDPl*VP7^5<` z{kY|!4)R}5f@|gK0*h9s*4#I3m`)A-4pN1EYfI(!+IxY2E>jm>V#oUMzK)#d zvzYL___cVlA7gI{*ksp%Mr{E|yY+ii7O1Z1+wz%TdYo-U?$OATVQ2$z>EcloRy8zF zBVT#!Q-5-Nw2l^Sx{*##oPXn`FUj%SE4`K7hla67I?WvZP90yKY1ek#8^qRh89I&0 zppJuoW1OQ=ifCGHs=RSf2YN<}$I3<&J0G{~T*XJpouGY8s-v!4&2h6MwsG15tGmIo zL}Xq&vOQW7Wau#NcD*9KsVNDBls1>9jT$(tc6v|NMo*#qn~hD^aH_S48WHm0=Of~* zaiJs1{GZE;to`*E1l|6|jTgv^if_OMl6fS}22xoGyCb8IA91r$22gF>atd(4oQq%S zQr2KrhK21XFEwQyY4`S6Fn(Y4D4 zAIi$(Hzw;>%s&T~FLL=@KDv7g#agQWHu`VA#vbEPWI;IqPEcaoO<`S@|FMPZ zv*#7X=`7T3P-sOoD)H;i_a8nAiKU=;ynb!iWXDDZ%(o9+`!{Mtu)>l5E+a~gx+Q!lp|uK zKa>1vF5Vzr@HdZF0oWzh57HWsd|aeObOSHM z_H*4vSJjp9m89=U&hX1H5))cefUV==ufDqr3R%$*|3ZHF4{Br4U-jaQ% z^=*Rq(zPDBC}~25J{_CR+3#v2(dyA@7$}~5pTSaO;hBPstWBiC(O2iHwzmK;o09V! zN~xM39iYsW?|tG`?$*-05WsP{Tc1|B$^%wf>y7}q-* zlXGNq{^;UMi_HkGH^_1UH94~#g)W*g;a%&ycY?1(EJy>-%D;Z8Ulg@{k;RgeQBwxT zU^>EScg7%$gvRF0R(WL>v?cwJIW5UBR}QHXu4q~9o<#G~pu0&uYm`l1IaQHEI(cVl z)l~Clu(T%&x8D9xc(%?m$LbTG3r;UqB0@26@+fd$JP^j>%^?I^wLS74uGoSw8%k1IyDt!8Tg~w~`br%B$(W4tX zQ_;vhy~W;5({D;Is(u*Hz10h(HXrIOp}QK~;PHCv6;m(7f)|^EIWs1gV-9j*fE4@1 zgu(Nht)gPx>H>N?YY3PeG6?Wx8rk@8g8Ds30Cmi?LiI-4fX8p5^zo^7nE)amjz5WV zszL0Hw2iC6w_wB&li_zS4RSMIN|UHm(EQpzp}kd5Mm(ErLaWwXIY~gyW)h{Dhb4Vq zIz|+-MsWm}j2iFr-q4_Wdf0{9J%7|3&5?FG{(fes{_{Sn%T>Pv9?Y9fw?3C#jC)4v zI)a=ZOCnja?+vMCJ}!+F21mINn)@X~DxoIHycpks4-+O#2%WY3T+@5kdf?u`weXEA#*JPt~>1f^4WOUq3w8E5>+{d~84r?yzkl0}?= z5hwUW7mXZV^r>gMOg9n4Re#>Bx8CoUJ(TP+S!vQjz0RYS{~cVM%rD=oiEx4-lEl?5 z<-8?kn@G?i6?}%qU*{FYw0+da0)^+PDp6ZGk$z|we_uj=krYphdnwQwEE73#k8D35 z8J_@BSVe>5Ld1Ov@itQkKk~rx+}87ql40$IH;>|OKF0VFpCBV<8cVwB`8bN70IPM3 z9LA#|R$i-ajBglT;hge1U8uY31Aiyb|8tfUI{5@b3Q5rw92=F6{Te-BCB;g(>n?^g z1sKYNTgn$z$2;sz*)s7fzj)Q6{d^CS|1dCX{m}xTy_|;;dO9A`x=N4etOF%gSuYOFaqgy)dbj=jg7GTTDo%;$8qJ**}M;_UU?i zmoir}tMrv38X4v1+R1qU4dZZ?=-jXDzJcfpF>ae;kS0?i?&%-Y=IdH0c0X8nFJNTz z6lvXZ5m5J}5k*${7kP>kM- z+Qvh=)M3uo;aOzX{<=C{R*DRL2|2H}omR8R*+PSO z`u#9ifw2N>uQ*j^*3+<-J!B{<9odtwpJ~5Ye$Vs_W{}^#dFpqD>4;V5+=AitXTlOP z4f|0wL(L=%d_CZh^5+A+0)zTy!8vuOQ+*~D$?7`V1Kp9q)VR-bEurGOCO(2lXs_?p zC+IoaEgH8=;ha1>J$JaYH-_Yg@7u(=53pgx4%cH+g^#5~i}257f9Of#4w=&D##qgW z_t?+Swxws?F8CdWg1>$uC`U3}s=rL7qoXSa(`a7tMspOMM;QUny{*J*Y(|y0ZBKLmAf}Q19w2sI zozT^Tf)gwLi_UXv;3M$uKM-wKb4;F zZJZ8^^uUIKpANz_ex9>gSL97Q{RPY8r#*v?`mXNKOVMM|NTu$t1!EZh?nwNPT}2<_)a$J z^lbz?tD6oQR7Qrq7x2tX{{{Lwp^|?zA5LwbZtEW_Dtrnfs{S;X{v41q49J8~kE7bh z01dY$^xfKY(O?k!Oi|!QTuPB{$@my6%#Fy(rn-7&uGGZ^@(jFi%owL5zjl8as<@z? z^k2(OV8uP1-UjV}T-;vF7+xjI?>8=Eld~Y6X`hzilI4hjo$=SbP2#W))oY0XXtgu% zk4nc815b?f>djU`{aV7<9=VE*AKGPhOLbpad%P!G7KUe>n(P)89%cm(troHw9J*#h zKbUk4Ztt1Gw?2O7?P{)mwZ-FQ71D+KQ)NGKyDSbL6>MYYkd@=S%CH7G!RP=9{7VD5)2uqku{_6|f2t$(C9g*DkZEgH^%m3FmxyJ`>}-Y&Hpm>h zUC{HnM!us$-EREIinZ(4kB3>E%JE+&iC?kiNFWfiJMd##W|y{cu?1kjf1={wwp zHPC#jeR>VqIP25;;ileae7}!jb)H2xIyFhlbG96NZW&*9&QpLU7|T_ollU^SsDxi9 zL!;H<=FwrEkm2hx?Z~$g=`Ny?XMADBCClc$-;m+#aPRjQX)lbLS|j#56AiX(riXM- z{@tDVulMkXbT}I_;AZ%qC*598wLE>+s(Yf!AK*CHYl;jFN%QeI8X}D zEUlCst!7+2JVzKA%Skd5T$5H&lOhMIcl5T95p^4tEdE3w2ifR68G$`bH?Vz9phvjw z$m0b(okc|5Vy|^f)l-*;c&0Bd4A=gGNz93e{|$|1ja9r|z1KHebsAqpv`^EKaTc^H zy&37;fPxx-E@sU~6?s1+uRj4^nb)7oE<}00H?P2>xa@ahYmueAmz`tvn-0Qy)zZBU0m#53qBgJXru$f zX`RgaFz)f~Aub7i6{)LedzrQg0sz-@YFoVz^@?}9zv z%UL2c($o@lwNr{HPW@gL7kMW|hQ0OTS(9O?B{@n)e@A1KarNK}2j%4DbQR)me-{As ziq5J(^vmPL>5GF&3hnw3_>o~JrM(mBU-$Y)PtyvDJTSziD za1J8Rr?8HEq)Bfbxm4QQ|0zqKXN7aqf(Q9+C}POFcNoWH7Cwst{rN}(V#zj~=4{2P zj2%Nml*n=?p;mS;R@;)0&K?WKDl$ucd$xBYuZ<=iWi8TCS1&s5@AB{mu~vW|zm!F@ z@?8yW*tc)5^#=o#Hm^8wDys=aPkE!t=dx&-?*UaAvC1}G*>?vDrI0?wCc#rW; zfTu8b>UfNJ@~beTGxM)8O9x_4QZor5NBfE0dN3J)Y({EJ^k1fo^e?)MTzdtIh9y<>$%vv={PA(fRjHM~AJuGE+X#0iuqLK6Wh5PZ* zBoJ&QF5uyE-X(ymcqPsH8?;i2zH!+u_iJzQ*vTFlbl?h)1j73s$1{hc5b~1Y45S#oDcJVO5{rZ zY4~qx0J$k|;#D|}Zp*x9ueulaT(xD8&0G@!ueV##T^i;Z!y}NuM-tz1x+U!v`SlK+KK*lXCiO97C}jIg zH05@*mnq;L5Wkc6QFxcRhA2il>8F8;B&slDZ<7t1X^53ua04cqoX>>ws5`V9E>=OG zHbP?Au8f+1)kc28mXa?t_C@P}DKcU`g>g##RM#$unVp{RO}E^AjGszY!S$_Sz~f>+ z4Z7vBYrPt|C%%N7u5;X^T|Sbw&qmacaj{aSiI(=Le|i|6O@v59&Jznp){c&Gea(S| zCXFXP9V0||sESdK(9z=dXRcbegfBIC%Cx>4XB)Hg*qUqcZPaOYQav4W8@6`nT543V zCqtV)&yn~Z6BvYEYh^g=(VK@-9NzAxcg18M$x{q zx3{jNFtSbp&N1}}VFL8e_zHljXJ13V48O_>==48{<;6LcaENy4WQrd?+Cs8Zpf zs&9_}HNImTs$Hj5ZIe|QGQaM|WljP8={4gL2B+jqEolQc&pB@E&W&glUB-@CQw$hoobCjJDGvI7II*$T%g=Z(13Y{qq7RsXtuySpD z1y?ijGxkjn28H^mR)Dun74g@*-)sFRbAR*iUf*NZiW#`02Tv%HW|y69xKqN*_p{g381#p?zmC=Sf?qO#01Q- zux6$R=)70mee_uEn+&3WaHl|OawE1zMf$Jr-hK-Ui*2%-rA!#!r4ZKyrzet3a5TIu zUE=^}+>RydF#fPk6J1380~uBVWJC?4*W;A^9zKIV3+OagZD^oJwqSj|FLn$FsM)QgAX@&`*~0kR!b3p_00-p^NP>v z#&5McrIVT`f!pwo2Be42Zwsm0rdKXXXj>QOX*N6@q+ZtOsM`ps6u7~e;-PiYH+XQP z*4k3-g%_Gh-mZK0#Oeih8GL+LGc(^4ku5W|^)0=(;2ZrXXVYP($J5IJ1$^u1)z3g< z#OJFmssKJh(?_rxx4k7Q@|fYto2leUk&fb3^4?+b20FKs^}dr;j8;%9LN89}6g9^` z9{FT~Tv2hve(~G*vVK7(Wc>pwB2!-vb;Oxq^U?L04CBn2*WyVfE!rKYl+)HNXl*K) zU$W-1kZh>}4yN2fOrNlb5z7CRH9Xu%oHc0q^Wrk*0>F(#2IVSSAKnH~q;awE47!hP zRIRB*`b}+9r5^&Q_ZkjJ71%g#iorI1Gc^$@`0_qDTuG3toCgd;$v@Xrx-aYTqpDs% zu#X0kxJ<9BcV5GVlom^in}gK#A_5GBD~{WYaz1G**rGs>VHzn`bTGVOc&hUkb=^>* zF7>|*mz;9Xd@*o%#s$@-rN5HX`(AE8UuX~x*iW|`qhjZ+h8_cML%YT4W3)xf-?JVD zrma|hujPt^{<2L3-L+qTKJFP~fl_1^jAS$_UV)t(o@Lz~NPSKNCqnZYif8^ZSI;Fh zEq0poNH3Wb@qW3Qq|?#x?$=aCGl9B=@w`z?$7K)qFB-eWCe~&Df6XOYS3#6eyqvS1 z4<;)Cft;o%L^Iz~ki4N>M3?jy&j0RxH7`yDH1SJ&bsOFLhIAWE5QU>BQz`cS6F)zy zpnP%j9T7(^3RU_LL2ZHgo*W9JxBJ~>g^2v#5`zjL2lct43LQ=WZ~Kv^5sR|(UW2;huaqb{vHi|w4hb}6g?R*tn#&ls>x2T_saH&e*yo> zhj};KAQHF6r)a-T-}HxHW17gyp+MWYQ2k3;i5pud=RCCYkpZE9a|FQrmg)GXgR5%V2w+kSOfFS#c74P*nrHF?< z++1OjJ~Z^$>BQ64x82BEe**vcOAixl#F5^s*sXg;QLNlue=^>2G%pYA4a^>?d~nB6 zXmE@+r0{|LWinV3W)5^lzHGk=4WMjKNfUH~|4M5#>CBG+@O-bk5z!<*D58)D&=M8} zP7!^^Z*XT`Xg`M81)(6lAz)-X-!4m7g8dR3^VT-h>9fQ_(9Td?hkzUlX5jXkKM*RR5;7T~hBg z2+P4pwg2r_99#S5gET-gs+UxA-EE;iQRy9Vth>(0NcWTdPKS=XECbM%$1BQuFS+=w zCxI>#cDou%18?#?U9X`ovwWS@zC1pY~yjq?Im%sQfRtsw}JR;yog ziFPaA{CPv6FW08;R$8s;dSSFxVyJTp74^Shxe~t$8x!eD9 zAbZ$}z&$=NJ+*K?(;oKl+y4rnelmM)9YpVeE0lUH@7afj*DbVv@=#L(Tft_kb)kfDd(N`eBSu4tLK(5u>JN3+q_sS%gl1 zzP+z#F>q{h$)C3e%KOIxB;CflvgF8k{LD~Q;#8eNda7O5bCp~C@j~c_oLZb>wf38r zFh@t>?5cp(&X9iKz|PDZ>sV4xCoi+dT0|B^BqBY>Zw=IUP*{UE zf3d>!M6~X|&u1ntU=W&0b9}xAfvQ>~H28O>o}V{H_JeW==o&g2qREHaj)={FO2T;) z4?>|xOhK?9B>Rdn6C=!^DDlKUjVcTBL91|Uj?|l4zS^hBp~4nBOExh54ZE{#LTl@5 zrj_qXYxQSI4d`B2u|{V(s@>v#U0zqnNcu9Cd?DD|U}oR3zi%ki%MS6}Eczf+BMmf` zENpAPMP=Jehm>e&#TkC%6q*VZGW6*jAy0{!{6fW_DT8XY6e)K7!hy-A=Thg$mZ+Vi zZillBjpu)Z=Wl{W5d66Y_@3ig#u#M$KDptP{7+zv-GGQBHjl18k|M zfiShX&P}ASakGJYjGWf42)&J3AcadG1$dT{`gyU zY(CxKhU-a25Hh_groKI0rk7}aR9ItphprhZI&uRzv{qmI=xySEme%#fnyh37S`DPP z4dRR3J_GlHyrsIr9TC5UHxHK;q)XWZd0l~GNAKd7A2WOA>@KeAq7|RTDMd@*M{uYc zzqfP{Ni)BLk2c?##IKvq=jH-gdTN;890C zpgq7Y0=c&7IsY=xY0~@nfqpfR4#h@KHph%W9!C>wM_Vem>omdY1>Xu&Cz=W?GIUCv zRo+Slw+g-+u5N5=P{LjcnR38tcy7+UrOEXnJC?3dPb9Se8-U6wOyL-y<%T;S=Vv{5JfNAMH=|#*gn~ z%EwD%&%7V`jmzVAf?*oLdEfW6c~gqb3}V*g{uz!nqNXGs@9*JAZN4P)x`!Rw>mNM6 z-X1g_uAjueIyo9eL2D!Nt9}eN8yR0zYi%2_Vo_MohE|A=_|#a7uR#z~+i z7~0>(?`eecxv7_EyYDCN{ic^R5=HBj`7Zgkqp4&wtpyctvJiJ>Xe?W&v`3JD$1{lc zRN4Hqg5lHz-qLv~Ky{l?>*xr^oQ3FFVStJEJU zSS7AlBcpW?F&Z~A{)?+HA&)>F^}hubzI&vw5vssDYCF|8?gyz0&F<t{=J4-}ec5-MUws9Bdn2c!$~(Rzlv_B_Q?!)D=BenFQA8 zP<-m5o>E8Sp3bT%ZRWjXK5K9d;){JCsRNN~{qopYSxc>mhF17){i9FR4_3hF36VLs zQ(EIh^U9{Um0rt%T$`XG+9VXna5$U=4PQiqjm5-xK<~TBG<1Q#l|CT-uU7nxF5v81 zT7bJvMD_oBT<(+}mG0Z0AYNrjJhee&6C42(Wqow*^JUw$>1$bCB&cKkXq2U1>@YDB z6cs(W>4iF*egZ%(6l28ISo_C-s^TI!D!a*SCE1X4sP~6qJ*X?TI&Gs|{^y7qKj0B^ ziirQBh8OY4@f|LWUCpOkw3&14ni7Y>Qk+CKJ>(-lt?vnxUD$(;XiIEu6uloUE?zqb zQq?-)QVRfD^=JZqtrNkQm&4n_qlCQNimu{Vw0Zc&^Z%-WZ!Tw6xS=F#H*3EU zD~R0X@_H9eI)e$L2e+prE*CxxhYk`tTierTnK+KMYNGktBCCfy&91MO@WGqkhfTp? z6Ex436WPW5MT{j1PeLlA7~8FzTg7V+#5J6DzO@um3b}}WkE4t}9Xa54KWJ)bESSF$ z_Pv$@v;I|IvpPF_(g5dAP=MCN^a%SDKfMxroD6xaUs-Jnm*Q1scm8MWEUTf+EC6o& zZQ#|3Z8nhU&DRgUFhNE*>=_lv{|uz2a3>~Vi69s2bSVicBVd=6kD7iINduh{#sAC= zAMo7%lNWXbo5#|wG;3!(bs^)kBZ4_cfRVW#zPHn!$uzJ(g3_lQJlymv`{6{*Dzl$k zte>E6iZa{a0z8JN73G2~ni)!sn<9{2&r%ji!Gt#Q57=j`n%uX1fcb@`bT8LMdqC4B zV&px8dhIHRBmreBF}6o~V09u*$I&im*kcv&aWZXDS|_{9&d9)jV;}O0CN0rdZ~WQw zW)a(^CQXnV$Ud+c?zr4omyQMPYSI8Ugpfsk-KsVv!59CHma~zCBzd1jQWlgEwzOC}T zajQom<3pdX1!rbj`yp>C!|yhWEiy2>`L8}Hk9j``4oEJ*cu=%N2pQyv{Gu{-3|?RC z?^kTpkgOYdLx3}w7f6-l!aQ&jgc!*-SmaNZv29w+fphS7ymm-N1u0TZ!v>dA%x3!G z^!vuKZpBgANzj#EUH3K=+ind|wwzwti?_@JV`m6BCi#s2zP4)Vw^i9t`sH9qb<31E zDAnq5oJ}drtvNo z#&(%ujvd#fx)Ky&tc!EKUHMka20lCd5qxVKTgS$AMy+V-e;peAh+y6ieVGgj?Nm2? zAD#ZS`;tccFz?UTBrY|38Siz7PW~n1@Ts#?-5#xyG-$+di`NURFe{#)%R{$|2r+Cm zsD1XYQo!arroFr*1|L*AlR>_3`mcX zu~JOA%m(5(*1DOa#7n8H5RdGxbQ1OR+fg^!c!~@u`!9=oa_i^P?`)T|GmVpSiD%ezDW&?D`7ht=#5AW%7+#?V>i`pt|O zavJ`5=V`n|!RZMnI(sXn@EJ_pgwjcL!k&@G1f+jhDE8)$p}P3*+y2+$KR#I@7FhS( z+woseU}|vq<5MPQLonp@--RWRI`sUW`ztc9U+J(4NawqKs`e`70KuoZp2=KDPs>a7 ziEcd8KrGZ~5L4Po$b91AbA3KgChmewa>fa*r5Scu;K0!;X?aLD@t+sE@H- z9ggK2ML<+ZsdI=WC=)F(8(6-6dh4>4FK{w@lW&I6*d=>Y53A2l6Hujo`zQ824686GbGKUNuqkX*?HQ=?qzzJPUH|z{C z?0?HXdA>9AGl!fmkCzx9S$MrMLBTJ&CH3Wk=UZpBwa7(^r4Do07Hq4WTLxeo4WFu+ z@n~&VP0^z<lzZ zi0SeXoY2#ajMru$_7fFHMs&HZ_zSLasvQ3hQ)d}fRU39|x=WF6K{}*!1B#S%cT1Om z)TSGx1?iOT?gr`ZP3NYO?mCP2JKs3x7sD|a{#lD>J@-B5yyh4Xr<*M>=vp%ZZaigO zq|E<(|HraWqea8tputxs&i9|b`g#~KDvrtlp#^~N?^q30;jArGGfhq_@|is9 zsZrODdHr(;o4U)X%-&{ixalib{CZi7-}O1o(^s5_VDa*r>w72V#%2neKCOrw5L|Nx zh9&9V3pee@#f&`G%}^|PXwg(!W}N($mXz2?9D>OJ$$6-@pf3FzArn5&+sgKLNnKAGk+DCT)x?2 zxGvn*39Bpt&!eh&H`4Fg-Af|MOQSrHqYDw-xZaN8dYI?Xh`o&`iMIWA7TN%49$d5qjR zGjS{Wl$E{1(WqDO=9qe-TL2*5EowD8Tm-***g9-(wi2aV5ip6lq=Gxi1dmyq4;S$y z>XyXW#?eL=tmbyY+(O*SqfHT?%QI-DLJ4nmc`S>N&uiSjy$tZyE!&a(V{%9s^k94Db2P^ zJX#Ij>2QnG!O=Lu0Nh@5k(pWQ(d8`}j~QDd5Sagi1CY$GGKX30 z_OkxQ%#Lb8xD$zIA3DIH&q`820k)OE#ncuKYVtmR8sC ztq$>H`WRdiUOPcs+1^x(^Q8ThkXE$2JZ-+plH7TzEf-cKI48Pj+#~)!S)}f+0O=gC zCpCL7?1W<({CW++0C0nZH`E*H=%Qo|!EIO(0;~}955q0hv`P2hdkA5 zvta#q0_9IcX%+$IB=M=w!#33lrhK=y=f0iwo!Qi|23A)9+fodGo9F8{Haj2Z8;&j6 zcTk_SKJgq~#&`AJ%k%%ZjUnyFSBG0d0I%v)!lZyP+dU66KVgIRnynbUt$IJM8_!qnYlnJehTKDv?a!p6=|2=^`s(?5C zI@fm3brDi03_K<9$XTNHpCr7z4(kN=Vl(|%aAMG(}DQIjY zB%cAWI`Zj2z?A3y&tjmd*JoH z&N(3800HS&){O%VZ>tOXN_g+oh;`iWt65~#GNy^!oqq7u=MTTD0jE5-^2^a3r`AUw zKV~;q*!t5I<+6+(7%-5c%cUUozS;;m=Mkl}V#6X8k{ZkK!}!bdZHUjV*K)qR3~q^$ zmsCrwgML>hRRb;SrLA*u7bvYd$3a?U>$;#1uj(<5AFqE(#rqtNyU;a;MgU+ z^)sZFfL?fz!@;^hs<`q`<3BX15KY!G+tXNVpv*Ij9;#scuF}EAix${Rk!@AIuW2t0 zRm88&0Z!n*s7cD~mZiADv$t;9c{~IXGKp{1SKE&l%pOKJEyBgjs>D{&GxCY>QYJusx)6vHGj&W1kQ}flE&XZnnbc zJy(}wbJ#9ki*S3=zes2s4%qKJr=4BS!pq*CVI-09= z(h^(Qh9%E&;Jb_&bMYGcBI6?8lm7I<6;AfdsV*)8??1VF02u&DsHXmj+(9Dgp92_b z(;u}Io|S7tI^pQHA0`mAo_ehA9Im1rQ4HjYXcbs8Vn3b>BHGyi-E%BrMmKrx7xG4BXHPJ>6+;i0v{GqL%jnf2`Kor}EPS;5Knr-v#; z`^;C09SBm1VF&%gU24X(;~j2c78#?E2v zxM}lvuD-erMM!8O=bJ^6PpOaU?*4x>z~>4bPrrhC38lmLn3Ho7Gv+3}n+IH7yJg~N zniN%pY9c<@x^<6ipKFYPWLLGx1J*)2{Mi^8hsPXgGN%WY=)MNDE8wBoZUvsiQ6Uqg zw&cK>Ki;{_rA4cd0jDGKod%{-(l6r+oXg-M?J%>3-RvgyLor$)oKYrcR*2IsU`&Ic z$r(-nOUE{AT9V3QG}mrB5KU{o#N{a+gW)pLNG30R#hZ4@Ev)D*YM zE&%tHdq-M_)QfUkpw^!46+`|xU`0_D-u6{YD?-j zqQK1HPnguQZF_G-QCL^>p1A-`(*{EI9Ldk<5kztJTvj8uMD-Amn=gyb?PvFczo@?t z0sP*tCkR@XICH~}l1B*JAc7|xe8JYY^-e#u$67`!#OILml^(?3I+^G5zFBCPCIS9` zb3K4$Nlj<2jUV}HDnnV)JcYC9EAwpwlnevXYyJ_u@)0<d_lR?92RRbOBA*X1d<23R#|jZs5Z`aNZ1KHnRj=zEyBjYN*mC#ZR8v0 z2FgvFR-k|h%KIBLHsC%0W;ZIvaNEriW(8;Oa7+{uPfw~G7+~sl4qa$GUj(j3z=tAu z&}WM+Gs@9V#~*01$~C$>hgRF{b2K?WBoqro1K=9rK)FDmEPK!z1ePN3)N2TcQGOz9eF0ncd)g~$?jl;l3Dfs|M^5jOp zCVBRU84G;R5*ZM{jcRlscOFC&SoIizInq^`#5B?Z^tard97a|1AgM*5MHvcATkTH_#f zB|e53jQ_y+W3PFKm(ibY-tAX*3lh*hr8Dmf@6p3 zjD0L(=Pyzb5BF+VW15H?N%*>?h${k)%!n!e?+<1>7d5HF9k2~<{as-GmA1r`_UcLJ zqgx@eVc&j@s$QT{A=*4@XBNq1g~*-b+K&Dh4IRh9$=@#sHyQ{(QTHrZZMdd@umNMZ znjl*otz3eoO2J?$f6X^wtT?|MRKY~pAp+uWRl-UGPu&(IySl=QHd`EFSn(HQr01ty z)J;A&?P>h3`dHn3oDE_}t94|-DcHrl+>1B+v$zt;ZyL#>Q?vt4gIbYm>nvIdh-#~5 zG&#BIE_<1uDO>CL`@GRBR<14UzyI540>&au%#SYj27L+yt8r{uAy+#l5vI%Dnd~NL zUpU?fDg0vCxSyFT0se+p2e1(YQ@5O%eYo#fLN#WTIn zZ4U*Fn`K8K3=X&SQf>BpnWDE6PcKxhkL8Al1Of50))tW5z$1FM2Md{oyG8~$7$gn0 z&*n!_B2&N7$N`Pz7hnnik^$!gvl9=G7vrWI{pd`L?wXu7%i1>kb)*23hNkg#sKZWk zTNz9oxh4ilq<;kFiFZuz_ox0Rf&--6faaJ&C>tpn~5q zh0pc*!-nB-BkJzw%6&|irlR0BmrJy*-MX!Nflqi57!$vSe@R=_ko z`$xNN#D;@XI`~wYzUB07;W@g9u-h$+L~_F*7U8#56pce*mYE{>?hl%2%-X>|9y|-G z0x0e09nZHN+tEIcImDSA?!Y`5(l+>S#XzM(XJou7%-NzaG5#WQ3>|m`Dnt`K&+iq@ z>UwrmTCN>t->vh#nrMpm)lM9fC>tQ;q69hDZ~ea5M=bomcRU!~UcOi$Hu!ag{r_I_ zluBUo=s6}HvK|QCgMvI&>o%M>b4&GF)YZ#%i>%IOP6>rQ8}|qZeL*Z$y&q*tQ3i4`&JsN@AACWwdp^e7M*R}`3m%{T~1b6UMq4+ zAbq`}ol*6u_aA+8&!;=;@;R@q(pL)UFO?``b(nbrR6Y(lH#D*?=+3as#PqXSZGft?es^+?@O8gGb z1xpI9tqTEKGPfEmDD9As?tH>oiM-fORvhxb*HGF4mU_wB-ai_y;s0@c2HNx+U>$u#FyG00o=Abav$46xA5mRZ?6Cy2L)SL(4xeQ zRaIRZdoPbfqygjBnIu8sIwJN?wi$L8Ik7;S^C3?=821!)87DI^VZ2DC0Qy>t1;0d< zvL#+DIi6A6Ck&pE0v6VUZn6zEPq}I(>i7P6=)Ai*k4oeOg+O8;FRpB^pX*TC)I=NDRKLNEr2n%?0_ws<8_!ADH-!5zrUD4k6XrC| zoqPeze7U~L_Y|k`p%eA)tVhIw3LQpC)kC-&#e9e1(?8J!gZ=0tQMYSl9=!W2Ee&wO zqbb}fqvCNYb$6}p<#0LwHF|{vCpAH%54D1K_SlpRF3)MKkrq8GD1tubJA3)N29-A0 z{bp0Du~RAM-SIk1K>d zg|)e034(%T-uO(yRJM)u@YWdu%Ym2Ob%qYlX~XN)C**JA?eLCVEpnA59R9)W?!*TW*EJ!ufv z`UPY6?V*ULv|`q-Zjlg1o82U>%wGU%Cj%RYT*|!}cSWQlv7SOf zZn2$dbagOGY{68%Z4tKI=A>bY}5d8a&(y~0Z(hgs-l(N&M0 zixfC&cFA0xSH}S^swwD~y6v9QZK~IDG+C1=z>)_yam-;(gPAqdoPI(A0^!jHs!`0d z`nNw5_8%6>InJN}RD`VnNYAJG{ZCW{yApwvS})rAH{QFuXaz$U%tM=i)!0q=X7Rub zSW4T612OjEpj|wznD;8&ze?>Zb<^S~`cz(n?6X;>)WZi+D~YH7F5aP+OGc9;5d#|p z%a}H*U)XLRAhCZ)~8<1i6SWzH4rNnG7~i(6i)CC#R_mZ zW2XNaH|dM|4H&cbu}ywoLS~Ch=vJx=E*tKGD$Gm8N>GV=*UG$~B89BafBFk+lp8J) z`je##IKT4_+jS9Llrntg^Vynrsfb1ogtNRi{#_=PxgoUW&$A8eI*W64+lCd5bPM)5 z8QCV-co#8o(v}gHoDrdX=A*>MF+2 z5;0^r20U+iKEGaB0U*b?!6?@_+tP+n=v?5B3jB5V!dp1hqn2D9PLX~+<Yg&C){V^S8c_kA}J5{e*&7%dC01ArB8gr=s^w%i6vRsa;K0zLf1E@K_@T zPP6~q&7||vU%1;^Zc_z`V5NtP!64pqr^vSuU{fIJaExaN=VUb1+pRG6%adxP63!ri zF(u?I5u7nvOW#})3D^{3ka4IA{5Zma@l+=&u1a)vZQpIWVyO>$3Pe9X0FdPu2h+DA zh|;i!uE|`idkISN(|jiWSDC=2{GXRn_H*tjgQ9pQKa5-kJTle*EupD?hj+l@&m6$7 zaPr3@XEfuLD72@PQyH1GB>V97)m-tVs#&W*FEf9X(TWOR*a*0|%KQEIL_l_Lj-=n^ zjIWDHIJvEKf5}&S;HPuK+PjBah%{^dM@cj~h&+b5$6ldB1Pii(8%EXaE)fv40w`tp z(z;20W|}nOhS=p-=qRWIY?cGrN>WIv% z!3Bs9J>kEGWw!rj<2V8mYn@-0V~_A>Z_SQV;#VI>)$%CftxBO3ZV<2%?STrI!oL)G zW=SZ}a{{(tfT#rs(=-NNSHF*f->hkDgcUgzjGd>hJxahE+!K+*ay5EA)GxPqD14%@ zyU0#m0yHM^r4ZTYZ(pTTIhCOmM-8fXB+A-TH6a}OnbEr#RbqF;Wvo2NeA5rMkoHC- zlTo1C7~bcmGyTlyRV;b!vzjMtHD4EX1I`W}n@_TJD~!C5iQ6+()rIQ3X>TFr=cp8lvE7AT4v&{g_=X9I*Cv zJTvhE1&ATUooJN*+Jeb$I=%$p;X~GN{Iz)V*!6#dVFSsLT8!bdN5#hd0B%|^W@dtw z%*4Hv(c7+uVs(0)>$(|H1qYPNi9>ZhjWbgS1(A}klh8a_?4w#0sTK77N+sITsMyT` z0@!Z3@eSXNg)9J(W&RL<#fB4(OW9HC@MiU$9h^Z>B!ZxnQ1H3*FLeI5sacA+Ea6b` zzYQck5PZWg{ddre*|$g8&D8KGDo7ll0C{_N7MBvI6J9f*eR2F8u-_I>jo&0dmu0U6sQy%RpqH~lSF~1ED_}LCpHm-7>ZG1CSw?tA4>e^FA z+nzHHlqffoFA#%2B$cjKd4+ghU1=0c_`tK;FvJnG4wvbi48>51eLJ1#Y9^zH1F!pq zv%PTrOh%uG`^T_+N28Y!oRZt&@O!7DuOGRC!mm-0p-dkz8Sd zK2Nj|X8ZQRuwi#foVcVlw=YQtzb+n7&t)9`Xi7v7QUUarM8KN-RS?o`0pB8ggu57> z23}AvNqk%nVZ^@Vn#o9ha{66i6i}Cc?Qr>9$1Fn2_VPz;6q#Vc(%yzKfwq+kmszqQ zSD|awAeA+rDatbg+ZhQaAbx%~@YZdU07`@~JdBaI53Wki*Pr3j4Ny25Y^U*EdKZWO z>nYBaW=t(~AF$1@r6z3BXb|vR<^zZw+yr|L4R%*dtO@vgY)O^z!kF3_xrDC!0zqT@ zW6{5-KIpTah@}|e&Gea2PV~6?0NZ-ew0@Y*i9<}b6vK_u&*2>#A2$&hrzh@#A}$7* zV~Sar?$1nkCd_Pg?!fev^tYGdNATw?$TgCOpfAiIrTh7t=r}+~g}#ks-x5Qzy_}$|0p`o5KTiC=2vZ~K`1t9{ZCW|7 zc70@W(!B5BqV(1g<3+LMU?1JHrIt>wqo;w>HD)mr47q0*W0f($&tZp&SOo z#_-=8q1OHvA-3nD(PB7)&Te+n{JpSDf8Gz^ZV_}8X9&1|mCq0g^BN(`!@lNm?bKK> zlS`FWku+g$UdZIqM*FVp`IGG#`&7KHv{aV$Junr)x*}^}DFp}4=eaE`0%eLeOU-g~ zrFztt{!<-|A{dv~i8pH=2CFaYUfIM?VuZ)}W#q(WJD<~tK?^XTG`gu#>c_~CUhw3= zv#Og*qP>fqlPIC&<=>Nk_}@Q}T~L0+Zm`r39(J~y6>=mDPKhQ}ingYc&p@%c5v8r| zPbeb?f%ja>!*FSfFf#!^7|i89ZmXxx3Nufdho%B;UlQitlV^wq!Y#UN9*tivtj-u*j89-IwZZtG)VNxJfBq+(hkTfLf!3s*mI%j@weRG`6en zA?jZjcA_O-KcEgbXkAESPKg#d$k_%R6NmU*e<$|i74dc;!C%^M8)Z0!ZALpGdqxh3 zj+)8%f<%n);OEQn7iP3e-|Lx)8twuoLASU1T4|Ri$GY1TdsQw0hRsrNkeoB7K?O@$ zLzlN}okY|>^VwIlm={3!7y5`EN3;ofZ+VzGTjyBpu`hClKEG+Pt*q|6Q-ef_QVly&xcC$gZGjII8tVRFd7g%;On ze-Vvxy-60l8Ls@Q9e$^sfe|83Qv{&195I{%gU|+@Z+I(QXesaCtb_g}p%b0k$^o$j zLL16%F=R0as_JG(d!Mta(&K6+i0;5pi%T(?%nb6Fv~&QlHw`I3IA65sT#C)!} zxHv51jxcMeiL5aPfrE?4F!b5eyH4YIL!m^yOcgT~dJsrbM(R+*-bK~ujMOkRG**HD z))w_*5(jDL=V_>aqV3>69;fk0-iyOQsmQ%n_unRfg zjqa0%jeE1GF;U@GW+0-PgDg58#4&qNgt0fs3oVtqW1UYV$nhPFRXs=S0J%SY`M1(R z_d)XOw=*CocXdDkeTFC03w{c0Sj(s|!a1tD++PW=5r}xur{2j4<}mO$t}`6l92Slm za?@V0ufpeDl*x(h{fe?>z*wBSX(^Nm{lu?pu-6O&a{^pooCR0!0J)Y_w`v-mq`@(r z4Mfo-kUxiy`A4}WTw9-OQ3zm|BR;=w8tWBKD-&JkC9pI7z? z;=ZZ4HdhmS2v`!Gi^GZzz!MwhKk+VN=>WY%HcRbtwjQh9F3N&7OlR>7-y5PPYBUtQ z2sS+;$bX+M4i(n%sriI8u&I$-8wyqAnd9hmxYU@<^skU8rxh^riq{LsOqnCd>9Jf5 z!{AsJ6l8*J(0zg56}B)o#rt-2&2~w5&h|Va%h|pNoGCm?woe2H>cKbCZ zO-#8Z3>K6!q>kYTl{IW?%`BwVEnN+Q@q$r%(Ab+r4=P4W(FIi zy=^DUn$?qOMwMWgiD?f2ZP8;8w2`f zSP{KwhBd|C=phpqyvxW4zYJZs82|n`d~53yr!S3{%VpKcO01Jc?r#8%4>VJ@`>P$F<5k(fAiT4VX`VR$dAkzP9&k5 z5F5+gBbdXED8Scg?rjC_^B&gVbBejCB3*hu-|bdcvb(Qv{IQTVruyFHyn9X7gk?{t zE2L8ShK5S?g3xbwX2;SGQJJn0_XxFu5ae`qVe64T2}I>g`3fM8@gF5Tp(#=V51>j;x~hy&<_^spuUUHWVEfAk>tx zj98f6t4g(IERU)zE#mn*%nk0Fc4~6T#D!)8@!zfttW)Dj5*Iumf{E^M_|oREQ8o_) z);ESNe@NbV^0z7{$Oh=ktiihUb8J`l%EA4vC*uU%R)0o3>&ia;#!cj9*UBCz-gyPU z9WA%39DlG`ZdBs2U8NTb#)``p3+chxk#*m?YC83u0=6<5&g5D7lCBn)dtWMuf#{U7 zO7!Ekkb+$5kD|M*#ZD`WYSNqOf|L!9RA~b0^^=Bhm8+eneUUqe-1z zUdo}ilv-<%qDo4jCjS|?4e+A%x~-CYaE#W|4t@-U2gUQIxxOwLT5gWi`(YBy_hLl< zwLae;o+9xZ7_9Dh1}}+UeI(aO^9Y|#To(>c4R_drVd0cBH$o5e52p~l3=8lDn&!1q+33jgCU!|FuFE z|G?g^110qdz1}1>|2w0}$Q9h4`(2t9;AH%Tg6Kav*EKt=5oDl@4IrgoF|Qt|swUe6 zJjGmZ1GCi?c#jg<$UmZl|H~GwmmHj+3V>@UEX%?g^$Rtd^1zCfC7#p0>S5&nu@?ir z0{d0iJi-lkww3(|6Lda!N4e$X7jZKuo`yDZDy`P|o^2XK%J{BB)Hc(!G5~?>PugLt z8D&mUUOfJuw7I*W2#vhK*VV?P_Mf#K@o@~c32EMy=IDp~PWKW1AYH?ogB4^$eZh*! zI9$KOm(eaa%)pimpw+%Y=kXpE8}U-UlZ|p_O6ncmkRSOa%TB|?#n-SDasqc-8+bO1 z)~uE#4x0@@q!t#Rmxnbd6GHpI&C#sP&R8;f;^B#OVtM+k*mOxH@*GKZ&;=@;`|N>I ze8FbF@A>l3pjYywUCsV&G_bQww#dKzeXE_pcG&xHwu-_T_ zr`J-&!=HQj7Oa=Ek`Itzi^?L1IL!)Mw!XZlTJDxSrUYZjAzuFQlfd>PFQ}mUa2Y*@ z_i^1aWhdV>;me0D1)fW+Lzm&{s&yLGl9O-KNCo9-@=n=e@_2&4mLAiH2x;@QH&v+7 z5&Dxjc&*Ml@eyeGF4nufyi(-VZ4mOucCKo{g+Kfw!J5yXEq(I2YFq^Gwj4*ie-3l*$RzS+kax_psQ6H? z=q|?YbRyBu!;8oL)NcT;cBL$KB+R3WN-Aeecfht)idFxX5(5EjfpGEIbb)pbG~VbN zR9ZBKrm!ny7?ZrC{baWfhSMQd$m~#zG24mQ=Wy7(6%{P7CUCZu_?(#0k(EOFa6{o+ z(oF{01+SqxcQcu#@nAzR7X0SF;Y1I^$o zG_I%n{dtbM7>XzYjnkd;?`Mve;sCZZTVqL5Z_ajHTguk3W1aMq4#<>%bx6Yi$c0hI zm}3BzO_iKh06no-Zyi8T6Xn))LY2nrR)LrX+4|6L#6KAJT+D&C*Ery8;Y&6*Udwup zM#qSJi_SV=Forpa-blO~?1EjdfO9DrX4{!Z@U`kYYcCI5ImN%jgf>`sqyZq9^lA}T z28vNGhi2<^2%5YO>#Z17NScT~3qnEny1>o`3+)2~h&+nD#BDW3Ax*Wx9^(l-Tnc`y&3Phpc~@5M#z3_85UuqgPM0WkG^ zbT6;{YJ6&go%D^}3OBQ6rKmUNE=)iOM#8{h0yh(VUpZHlTL!g=T3_YgAJE2q`Al@; zY@gwmM)zTr=?wAlPExxCBmUT{V#kH|awg-%h0vVtlsMky9+UGOF9eT506Mb^ zh>(9o#|ttMg0s$M$0@RWolp7L{Tf1H0BH*(~C);wEz>1_?)qxW;5-3gA1pE!ex~G(OB9Y@>SRNxuVX zgd;W$$aXh$yB&t^9@vGslzPImM!9YFnHc!}75{W%b4TC3`H9|cr`H0zM?^y{84&|i z2n|+l^r*_5qP7>-``UhDJ+-J!*3O&3^2Q3m-Lr!51lNhj8I~m0vyAE{)Qfxo#Rz}7 zZ`Vi{-mmZZSHq`oE~nda)dHP&CMnfBbI}Ah*K>$mP(qr|XK5=}5LTy`4Dv*yXHA_U z+=po6ao@0~O+rSE(r#@2g_}w@*SZgF=2AEqU1>Evu1syZUpO4knLxF?{@Ev(xt|lY zTxm9`8vtglH4~w1{NVO16VT^}Kjvc@v3SFYgDG_)-6Zo`flgET&Lp$6o-a=~(3_5z zHZTmcl}he;@8VzKH*EuwVN&oXSC!t|j|qcCAd_a{?59-3Do=Gh^?n-i`{gRGojS)H zA-+kjf^>--x8&9kYL8OPuJOf$LJXM_vozI^S(Q-^D}feaYHk@A+G%;x(aec1 z7!fz@zuKk%X9hA0Q=vmO5toq2y)wZ()bN~IKDs|uCsN(+wuZiB2yK=tt}cD|NGC@m zn`8cTe|5eq@}l)y==ri&Bt*YqT|YgFWb;O6iP?ojC4AQ%8GP%Q_ZK0w$16}*b*(w< z`yp+;5GeMGgNQWE+ku_}Pw_DE0A(E>``8aMi9>2IB2Gq3Mzk~eA`G{;^8)mnobOQxwe1Fe|V6~0fgtG$(~(> zrEII%CTDH6=BQ(=z#s0V8+Q6KVx%aIP6x-iY!P#He$61{B*7}ag(pkuY|$xy_$R;W zP-0L#d~J&(nV|xOuaMW7X*++rw<=*y({;9+Pu(+_LItMxjOog?C*l-RGfiIW?kB^{ z@LV|(-Y)%aTAP)H4*;|zSj<=5Dk71!9;h^>rT%y`5%(6vs8nuYP&6TO1bgh~rMvfz zvfpM>_D+rH3>I?b9Uv)byWH15v{-?++%2@esL zvosyYwbF$SV5f2MPatMFNJ8GpE;jc%E}ySB_Bg>~m!`PcSZCxmv1KrLM+z{Fc#Q-I zlnFEOO1Y5WvoSXu7Lw!UHl9$)?k(0<5<;O2~+LLL}>b zQitzoK;yr8zi}uGh^lvbuqS!z-_$&wyzKf6{~p$WBe16MVZOW+R~?6;86EF_jMYG! zAiMx9@6Of+4h~h`a;@AwDOC=Wfqd4*u$2MSd zP#Ho1I0v^F?Cf3_I^hQagFb$vOg^j%9Y}SJBlPPXzyPSttc8P!VJdrNQ}AH$fWbX3 zx~_H9k~)sWKRhh>co8_ijB+g|rud)*sx*1wsbNNZ_xcQ|g&9H#Jt5HpvDA{=e+O|L z4`vvCll@2~w}`&}wK_qmCTIXKKpj9*NLw;i9u^7pc9>bn>tk$-<6j=oxD%|Qp@X2Z z8UeL}=8k;gjB>r8iC~+I1!#bcEkM9$9@Rl=I&tJPhB)w1=aUyj!eTl&t}Sl za^aZ|?u_!WDIKgQ1cm4)I7bA?hTg_&t8K3dgTT>=kDjGQ&w>|F-j2ISSwfLd&24jK zp0?JbvXg8a8!amtjOEn|fBS8I^5in|+NS7`4;7a_DJ?B~Ec^G=tEva5f@YiMV#^;@ zd1sV}AKtju3w44MT1*@B^Q7VIR*V(RVLT0b-%OT8Eo!G*MY{g3Z(@8tt=e+$ZdbC@ z*}Taej;Ib*!5PkaKiKi|&{6WMe|Nb#$koSg>8Frgi>W3Fvx`qj?*%a&IP1zkk(o7O z|H?ny+Ft~%FpxbmS2#$IoHgops?KRw{_f=EzT-g7dZzFV2O8t$79GwWQH6hO_ZhGi zGW>GEbX8sZedBYofNe4O@J|{3T+h?_vbhheP8Xmaloa1_{keSwbeoN)d^i@UowgPJ zYJj6JnA8K)j-$xJ3JFI}{RHzz_E`B7)pFs&S%{tX%ecXFbp3JW^M2+xDvUy+&K`5+ zI$M|b1&=A~C78cb=mjZE)dk#s3qcX8Tk$ebwUY2p*YTdtzY2nuwPU3w@{zc}j~fg) z%AyZ%`pEm8*7cv>a6NuxfQ!#_a6v)@3-uBsBBG33zjNrz9ST1+MT%~-8ibj9z z?7Ry~5m`C?+(&S0Jn%aMGS*ALWw#LNOFm)=4n!|r?|v!6ezz{$!yO6-(yVmY=(G0j z$nIxBvbsw9L^m<%2X$`CoNhe>mPw7HC z&sxr#l8HaeitG{l=<*Bt|IU+KBXoxNPSC-UZ?B2zx>D5Ix zXo+`n1|>%HZy0ktXsZ1)Dhj6B2?++k=+xG8kMvv!3R+?XFyZ)Ka0?vz^9(a^Tj-^$ z6fq+EX;-t5F7HU6$&EA#%Z0SS@z~L_*_lRW3z-RSVmSK29AUbn-+Wmb_LRS7!FQ>Q<<$nwJ?=eT1mi?+~e++A^nK z$c|U|<{+#7Ezkzy&yS5x&-}BA`zI5_+fd3OnZLS*lYH+9#$mr+fA))exvzL3cu*TJ zJa~NPHu{J72?fDBte`(lZLQ*0MTdTAhT`)E#q+1*+wVS}N{4?esN^+@Fs!LW6OB^| zFt4UM7XYN#hF)Gl@s^52mwA`q`DaS_cnrc6D20q33oD%^z+taY6y* zQpg=cBVN;Dtvhfa$d%WoKl{w3S>H_9hszTU5)QgsDOOwO597!P&+QE-u+GAyv%0VS zd%Xm7M-)HtwnHw^g-)hL8RBNl;fQ8W86Y1s6r1ucP&>&7ko4Y#MCXf=f9qQjbe#=D zXh^&04JY;+k!onWs_5V6IyS9{uXpHO|z zWe}=^tPR>@99lk#5LS15Z|i;*qi#9E*iL4(VZ<+I*q@WIG2@7?;xSGyOtO{0{l1s! z+hK#F(k-y%Ue{(vz8$ph=oO{AxIT>Omi+@okYEkx_G};a9%;U^#7C2*#7CE9-th3^ zKGK@Qq5F&b;b_A*3>PNFizIDB-HY?|&su>Z+nj5ezwS#M`Hl!+TYBP)sgHL*xk?X_ zUJ_hSQwEapFes=Kcp~w%ryP&eva*n+FZW3mKO7}rE^HBXI~beLKRc!ChH!cK-5mB; zV)vh}Z@|}a&Ld)lH;$$`5w2CJ2&<%XHG_Xwqa%3^%4L}L@LuC#GNg>~DCH}shFm`Z zL?7DMzIx{Zr5r>s-^N)eN(gL!&^RY$>`XjWmHxW!@q*}w6mnL;5Az|l!A6~pKJg6t zG|Ia>Sh`SSh~pH4LCS~1x;@roc;T*v7@5%<-l22}SSq0g+mXDh6ON(Z7P}IgmQbu= zx|#1>!n{p$jCO&5OQ9Tv_vn0uodAQ0HPK=T3|y@rAG<+s;_B2Cx-y(SX+bvk`MbH% zOptqSw>o!R%nLt~ik4P#vugp>x(~3qct@;6ZIM?`*)5*~KNgtF{W02M0(JpaMQUGY zF3wg7!5t+gPjLBKM_)Lch4oTczea&7KjED%#d2`080+8g)3Sj9Q=0XJ-YAx;ARSz@up%t1LFRw;3GRG!ZQpWd4H->T4<1WR zqnot6BY}pF<|WXP*LaN#Pe8EsL;`pdo7HHu+vt5{pNop; z)V-(=BKu@_qB2@_IxKimAP5m`{6~fTTXIif&S!u{&wx__B9F*8>0KXW=|UL2^4xje z$U6P(_m~jky6;47MxJjzjby;;OEiV$N%^FEPi!yc;}5c)f2OfEs@R=^hC7~3i4zHY zE0j&(J&onM1tf-2;;5CqHEzo=7?U%2{LLue!;0!#}pS=(t8r zi0*U})a=mbx4hQDslnd2ZNxY+A#pG@q2u@QE{|Vzxc~dpC6nb^C1|(w)I*OZ#x9rF zLQarfA=}rG9d^6^xT*y9q;}?Z^5%oJiPXv0yI>*k7f;#IhFl?c=K1E5a|GLULUtlG zGI#uOYnlNXTHDmq}R)_{j^5BJ$_Fq?%?O!evx7c><-dH%ASj0 zV;1R;zwlF{_$ZKN9FV^Y4~^7e)b}r%2F%KZCsK@;0Nd99987_PFq)@oKh$W0P0QsL zya?lS8KRC~`?1C`eTNtGn3-@~!9>2*9ijj&ciouGBz3Drr9gg)$PXPeO6|HMg-^9U z@M-eCgLOiY=biwm+w0RbgaW z8?}aV^+DY7xSY4yc9HXy%9Bbzctu=)b)pUApjxc&=a?|qgS*2LmO4Ysc2=^U#ZrwV zAE0E3zQBG!816JWu532~3KA@Zm|0fp>KR5#?o4h@U9CHwqw3G4G%{urrOBBB+>eE2 zWL#GuLmxm8UJEmSHs~^uqGRoshVTrKlSG4cq;E*amyST7o5J=ZJXmzbaMbr6fQ>EmC%ClMPVfN$-FL{Fxd1#CLbK&se6 zwNuNt@&5L(dT_^;Qr=Ci&bJcePOjoKV&`h*Vv5HKjdL#4W_q$UJx~)h_u~v%jMMizSm9-7@7-<6>bXYs#a-fH8hsI9zr&x7xpH*;Ez?O3DlHx<9Vw3c zwz=atf0E{LGFb6%vs|x*mPtb-d&$&ihch!aD9J~;fu;AJDTyiiuGHXRaX!Aa3vRdr zz#^A_i7wBi>{!2Oq?#_X8z>|#jd(KmdEOOx_agEb@=|#CWca2Rx7rLlFv#h11RvqK z<}vwils*wDgwl(P^b=3X&;p9E4hx#M=U5_)Ki+~~?%~Oz!nwiT(sO%8O-7XKHi8gE z@Xw_ka}@FzEphYsN5@*3Euwow45MB#WK{m;)-a=TUgJOJW+8h-a7U#mPt?9(v^KGp z!2Ki=juB@Q6Fma;Ud27Y4rcW}I+wg)Zu+?<3yk*E3)=%nca8w+=RQCwci8M?L*lz- zF2U-G?je1RH#d*gH01>1LXwng`CCb5=@BhuRHWXwWo z53L)*-iorWF(rvjLD%=;|B&_N@lZzZ+qR;tgDlC6HDsp{#yXa=OhvLJd&pkKGWLD! zBqR(*S;|h9v4t#IVj}xe*0FD6-`+>x@B90GKJWWqf9RR>Jm)^weO=dmpL5o3XfK6C zlR91|j+yhq+ zew|BvL6P%$9JF;=`NjmvOauK?Xb#}AXLe#95qDCJ>3u5y%45og9-r)tCcki3wfUCW zDb~n^xgKmBBqy8Hi~Q_cf#_-1SuW&EQ{z^DU;nbPTLjGyuFVP|Wfj8r;HPJA%jEA) z$9P2eW8HG%WzuGNiV6z-`+sPZ`g{KHOe(RsbKvCvsb_(n2}k>9G}dShax|@S-Xl+U z;q0Mr;@{Kzh}bPxyC6M*@)|gXza1fN&%xHw&Z490O^N2z`wKl9>}D=-dP!mZW@ zjdIr;H;8b*6mgi_&xM?8vTp1yWu=&P%=;eOXQIRQKw{9P*d7%EDxlZqEJ^W*;Xq+* zg&^%eCv6=y(yzAti4MvUR%UwQZ_gjF%^dJJT-AR(Gx5roG6ix?FjcuasVwJU5dZTc zTwq=N`}7OI?^(Gka;g%cYld|$rn2KO-?}X9jTBnfp6{eK7YVvJ94$akt?%(1XP9$* zqXUmW(5xHC$ZZM3-$fSRogrJgTI^yt%Tqp^&_8+-Pv|;?5c5c6q8{BZO;Nw79`eWq}Lq|oj zFhy74Y2QQjCdSDEXe5G^WhUV(NGxi1XJN#>hSwJlNozOgs@xGA$Pw$i&e;YRLK_?sb;Xv+VjxRGgAd zw&+?2-Bk_6b>!QKTg;k$HT`rSQSycjs6-F)me{iaMWUs4!bTd^MMDTMl3SaT-rw9I<2kt8u zT{=_2*+i%S6@PPbZneQhZs+J~n`cGMzjixzbZW}?zX=OvqzV`)&iT)BLx#;d_90$R zYVLF%3!eVo`x0>Ul+)$hFcN*Se{m{(u&a2nn+EI8>ajyB9)>6;{M<`8IbBlRR5+;X zuhX+Fi|&5R>%G-eOb@O2#uZm!5&cPM?h$KEF^DDj0{CI z9Myo_Gd(J|P*qRtE;0F)7dZbI6M^n!e?ayz8Mk@GS2Rbo4!Q8TNENA;|0hEp@npok zb)!-CHP^nJYxeAZ!jTdyMl=^Mnsu`Av&M|@Zejmy6yZ;nEy{ruGv31X1{=L&kaNyV z+RJ!rT4RjS`~H=AZqB3b)8S)!TaA*s)~aRICa;|7uL_opBak5LA%>Tf7Cs2aKjLp; zv0{ zOqSnR8|>Xc!-S(RW@n#IHUmy)rqTv&8UJLRjb;62uPL+Pjd$2IeY4qkf_5}Hd{%+( zhpe`K>F-iF$U2#{MKnSZNX-|N=KnmC&5#*#)tI0Zq&=`}H8xx+un1Qy`w*}z9Wdv= zDjlHZ4|*}Y7pz3U4{;>`$Mt;X;ql{29w}Idr&91QeuH*^AvU9#)Pt^K?6l1dRt_il z5r*Pq(>(L(i0j0~pB>*=dj|WgRH@&AN1Ne%wNd4G|x?YFR>pb z5_6NmSM2ueVr%gy)&pU>gGb6s_V0daq?16EFG3)h!yk2saUl#dO1qTYF9)wP{lMk; zw>NtIlH#-YCBmay{rB8qJZhfW7=;$~`vE-(vqjule6g0t0`6s-+VWF7@TtB(R?|;L zd{q-nCyTqcNZPFuu0r?|SRQl5z4?4ks~a_Cn*6uFV)aL-;`y}$hz&Kn&`T7phhuVa z+b5g%1exL8#4W9gOetMDXaGSY;Nz}gR=|e$L0!Pb{fOcPvB|{Fi3&X?T?*3ka&Tv5 zzxCISLC`F5&(iri zjv*GW?A_A3x+TRK!oobOgcmF3ajx%zDIp$2L~l^#YeXDYyT=@ct!4PuTES@jo!U!F z#41eYQ&=k-Sq#V?^}Axw&P6jLnP*BnLc*q=luOK$t*ycIP&;zFY?G;522OUO%+}!I z`0^V%KN3CI&IUV* zqRWJdk88{2VSjA?{E6n;4yN=Dk|NoUEg|LCJI^Nbx{^LST5cu#gw(HDp_iLWv0VPV z4_;2eL*g83@aeiZazAUIHX${t=4nS_X2kMYBJ>&wT{W*q;MumEVqCRS%44(lG{+xf z^gB09ZeGQ{MZ9;m<{WHT%KR>bCGl%1x{^_51J9IAc9aN)G?4p!{2c*A$Ivg06H;hU zUlcLJfwfiQC$-V4!|m78eWDaNZfv#Pl z8s0R=T=u1+YkTHwYNqbe2p_?*XvEz@WS!3QP1!1*7}=C3dx31iiLVSOe=yf_atw*y z1zmWlJAAjjOWbRPtPe&>+b`=S$30>{iknFs)}$S zM}+Yo9XwP!`K|40zGXtP`QmGMwJ0%yl+DADk>+y*C(^$@3}|7$F8(PhD88$DOZ(Gv zX(7G3!ell%v6%3h4S?==EA96N;?v~vn}f|K_Qa2DraK!ZGmO>{>O@Z0@)nAEI_0XL z#-q^fq4<_k8$2T}<(-jPcTD}y!x3>8|A}w=>`0PeFti8O55h>*(wu!TW5$juhCwb?w8-*#n29&#ptyNI-BDgN0zb&I%&>vUo*4e z98~$@m`$S+FwCy#%-VC`i|MQ#|T$KcmMF2^}rAyp&8et1p7}10|$nJV1L9 z9LR*3s)mz=venlhC7-|~Nh_{&sShgJ81fJ<-*k`n6LcxD$Op{*-qev>AI`Uh2yM12 zeC^?bo8Flc%P>b| z$(%Rzs4v9l4!LPVh*<^?(tTyv#ZQe|Ar3fE z7_6w<@wbz;X>&p03)SCU%-}k2=~U?UE*zMFS-BlSRuq^W$Gxjp-e`Uo(`j<6B>j8u z<|9s`sg_9W3Io*enU%lA3td(m!^QFAmo16paw}0vLmGuKFzs7?q@>p!WdEwJ1LrzB ztLGhCJ}eM<#Il;4VkeEuYb?c9*2u%UNBC&g!aQK@CReLV?TQ96(01Vvb+3 zV6{UI7HMcnno73D`G6#34ujvssa~{&geQMwBO4I;6XQ6(ci7oufa$EUkNC>|>tV< z6AGNFWgah_gfV7mLa+und;3f2i`N&I+cebafPTAfesn-7A5;Bzt|zx*gLLUB#jH-0 zd%Xi@uW2tt<-z>s*e(XomM;z=6?!8VDIf*UdDRP)bNTt^`Bd}o%qosh7r#}L4U?Hu zCY~i4i2S_5d1QQj)=5~_8_01atyPRU#i*6-3CtS$Yv&?FND zzGGD2J2lVQCpxzvcYz*J%l}c;?U5KTpSeVHnK;st&7PFgv3gVyrBkQGO26qnA=u=^>M)FUWv(@^b8QnMNfB2o_;92ZJP!Ze*=GZ6x{(zA=K}{koa>7%HP;dTq15FZHMtLNb&* zz>5REKMzs{K{=zyf(sF&k}i0grb~1Eh~Ko`>{wjrKFO?%6O7i8X}oGnu}FflXJLf4 z$;vOMXURS2)r#DV0je}o00pLcZqJE);bmbP3pTP-+{>QQkp8V#M@z|z^!+n1R!s5Z z%|iFngT_t2ev8f`m-9C1B(>wRWtuB(kThnRep21=NmD>v~rGxF;~)OF3t~nL|!QVRX8q>mo2g` z-DS4IbTWH^QGX$}r7$@9?#|(Z9?x;f@5y`ea9PAQY3BI-@-GwBaf^}agx&&lC=718 z<9x(&i)6r$t|H_%@@hojrwnppC+<(GBLXHn7FS8H`(2}QTsN_HiiM6VYpg3Cf34ACvUzl5x zU-#zk7g9WY%ralr3~Z;tkS{+W#~*u_uP$;cnO>X1f}oiM(V>e)txxxPAJu8r|DwhX zX8c;{7jUIOFe0M%qBgzYsr}1b?OUc2?=^l6aC;~bzFj5yp^8}oP8F5Yt0`ltq|!}$ zo8$%qeGl+s!z`#Fq!;L*mQ=aKZ5xcKqGlc!s{v<8C(+G^ln1mkr{q&oTi=q%En96% zOTq%b-j!O&rGmVatSI{n&@ZR`4smac%CosVtu-ULdXHE9wW6lA?YWTZX1fl z|G1+uyen^0oCMMD*dqIp>pVZ+R9oRR{fLrnN476D= z?cS0rl32oMQQ)dgGvs#9wqzmHg{`uXhll{ITvKeti7tsh{P zd34AMZ#Ev3^ro5_yrd47WpaG+-prMfatSzj(KdAJ{#;yFi3vF^yS`?FZ z9;)Qkjr`cJ(e^_0Bs8C?_5_#o>lz1YM~t1NBTSw zAq|VCC7vL`p3BvjFq2e4@GlocR-xA{xRDhJY>i6*);L|qNh0aLJd6A~lW^XNLU;Yy zIe9!JF#P4wE8mS1+Ot2?0q~;VkhiKcqDyDw2Z-uNDuhXT4Bzw%zlSLwSdZ6#`(X9;`-lmJ61t4__`Y8Gf&^Un0#ZSA&GlZw65)^ z_y~OYes&7IZXcsl+)(Pa>Ns}}q*}mx1h4G1a&<~fx86nS5~%NC^2c5m-#Hi;(Y&yN z#Rqak%;(P z6j-IXa&oX*`o*h+gky^y6#k@`q6OGA!_K-~nWG|uoG*~Olk4@Z#7(xpR-2nN2bRN4 zd;WD%V2*W$(M@<9FiVQvIn#3D3KNZ2WF@W=5L+_WDoi9t~BUYHkUu(~hBo--3 z9cFu-C0>k{M352BJYq09P$dv0meE4!--Va3R7qD{?>KN@j+bH`kDQRGf<%jJ)H}2P zUjKd8{(djj@+#wqdmE`$mq;OBjtL)zPwS!rO`C>#Wp=BJ7}&DX{@%eX8!SOV|yw(_ah_9G|gxThsKL7OlTuKDEiIff1sF?Jho-b!?HqpnMWg1#g^S38ZY^_?)( zmxE`mHm0dXM`-7MA{iQCsiG+dQ`^w`KUFq6vHA=pkUjw%OXXH)+Cb6bMhviRn>@Wr~4ZRk6A|DRA5e$2Vt4DMem7Dt6oeu zhcjQ#8sR{Ke;BLa_E(xeMN6Eoly1b}fltapJ}Kre%2p@B$_$M-@GWr`v=%PCiC|cz zEo&PC-fMrQf@SxxHo?)5|My6``i)-_CU;2+^4V6|j{i2**5XrAQ{BghPg_-%9SCJF zehFh8nanmR4xL;nah3GNxXL>pY1Ko}3U3}VkF9GGIM~{L{oJQn-U^2Wv?{307s28k zi_vwfObXM>Gpb?hM5dd`%Wz5-QtX37qx_5krXWZ)UqW&BGXj}NB$%LFSs}R=;|Oj6 zL0>Vj;RdhG<{&lLbDFlM`7Wm|g;NGNSK3*r((I+Aeq$r@)d^49Po#pr$}1&{9XjZM zaF>Ij&0=cw9!g|-TUIN>{_o$^epYmKP6ziHDU+qTNnD``Agn4xZVbAuFr6@B=|QtE zWpBEu1>E699#VFcgqM?3x!Msw-ymk1ZAGCwSp;}QZo-P%LsVN}Trm;hUcPYUU!_;0 zE)F-hx|pw*Sm2>=|GwcsHtnPXK;5wXnFo2=z@_L9oSlg5dtK9LHyUE-{QO-SjJ8?` z>ZywYo92=a-ig86zqjt`DZwkqsm1&dl)|Eciev?WrJIHZaP!qcEjnQ z71r&*xmebGV{JeAkf*LsNjjvWos;cNjEPCA>@|FW^X`}*#~bF8e8*z<=G1(vsPEA) zLzD>S~wFyXh|?;%M~s-!u4}KFpd;+Q*m# zTPP5=B0W<(Wfs!qz5H)#<$xq@h1SE6v**PEpVG0X+qvj~!v-PvkTu8c>=-a6n3Cr? zaSYWD*jJy#dkb^_1Xo(N$diqBR7$$=A`Rw1Pzi(}4|0H(TD5+~!XlNOF5z6GS932A z8zZ&Q@e2^%nr5M(b_LvAwZ~e7E~0rob6KC9Q-7s(@@fwOUH(;XqoXn}J-P&sFvS4wJL`D5w3R?WDl}m1F5**cYHR?9f zA=8>!On1XKZ&%-YBsR376eUonZp`iT+`Qr;#3URUb{aos1LYwX_W5lu+RN$@s)gZeIxPm$i!ScH|8VUa|jrw3sjX z1(oW=qd7+HSp4>Yj?&vW-T2YRM9^v+<=f{HLJ&IN+J;3rEC;e+)X9IgYTLgi#D4J8 zg_y46wfL!~rt`hh`kAB5nIAmJggnSI7TUSZ4q>i1=U-o<&Hi*Tc)#LB&aVG<5?{ok z9JY>7tBo@P!SjW0@ye#`zmH|TuGsYl&G;X>jHP*UAAHvDaeqKCzuV7tK2&Ua3EhGmwA_aUFyw_lFi)u1GbOsl+9!ASl+iv{ktsT{AQPvC~XTy!HwMc zD^<}HtP6r{dq<+VR_zkqVvB?*?|6-t>`tT5!9?I;yMc&KgPSXFL}73Pxr9Am!<<{y zuW`2@jMI-t{kl-9Rwq!UfA;ufW5KW#qW%jRpNQo=&BEJ8a<5NdpS575SKK2JI5gZ+1f-Yta zUby0-qFPF3k=iA6KuH)r=MifbgnUj)8bVU!_5BwL?OPjLRGO{l$c<#O7GD$?tJYVy zSIRe(US@t5h?-!)sK=o3Uzh}4D)Fb+f|i{$IjM0puWEo)n$Blb&FxpwM zx^PXJB|nUuWufx3C?2GC{D(rxNL`e0aL9ojLzSr*CO<7$SbPM)9bVjE^=b+T%KI=k z=rOsJFbcfJRbN%bzq;F7e{_W#8I^Eng%3WgLw`>eK{@foQz!s4O;Pp-?h zE7L*0Q95ai`rp0Y$@!zGnr&Od$dD%s54bQz-6-^Mp~)@WT+gp&nz^czzsiC8M90}& zkzfw%bydkd9$aKF3cR8si7R`)q|BjZdnj%XgM%40M&agz9$ZKzZNr&g=_LaOp*`69 zjIjRUIdl92mqVVMsJnqjEiZP@(2{2Z>`yj;jj2>!ns@*xsPKLT){>#T6 zPYBVv!=X-?=R~sj^S!LU=|NT?$iKwlIi+$uWc7SP+>oqdoP-|AK?(q~!1LPaG%P}U zf_;6hk?Xx9R4n}PEmDsOC;5GV+7xHF#E{9KfM=C0D^e0Z3rP97WhEhsYxAO-#wm03 z<@Ko&VrW#_-!aPM`fpoL2}R*8rfd|0pYIxp^LEAAz!PEdW`S!w^*%{gVefT8{w(CC zixS#`n>V31D#S*h*s?`Ijk``peUNMFdKsHXnPZ7)>Gz=Vz-YWT$#!Hnsg zA5WsV$%;Z+!QkBO&kXaV{YVe=Wu+G zOs*3ETtxJo4j-{BZ<>1NcFK`t9fDya zq@gv3-9qlx;%!k}NHuxIUGH!Tngi%w9t1-!+veq4rJdz__rn_Xclj& z26uskvQ`$Hs&%*LQ>Jp<{CDa|w7pRbD-76K+abSvTMW}lqnfRn@8$dg$ksi#k*ywW zp%R8<>IXTyrmy1JLhbRAP1Rg)(!L@k=ZEWSr`0{EKTG@m(y~Cd^CR$KUEzbu*fjkunuv%j}Kxqu!#^tUCikH=?#uM#*dWIn<%3(K`Z#Xc0K7kV= z$wX3V6-U~fAeNTqlJzf}@0*%g==RA{#?= z9AI!aOIYLl4=eyXZih7Tw}A*ro*D`LeqwwT3)4Ntc3&n7{K1M^Gur^TxmyZ3j7Fe-s zw>`oVL?a~}33e2-)T=p8;+#O#7Nx5b2od(hDwRNJ^oCtcEB!#=|>y?mkGg-;aFr=l&HM{hybbU|p8hmR+sVJnZO${(eprJH z5VWn3!8G|Z0Gcmij5-)!4GovLhm|4K|2q>0GQ(12Y%i<_n$>N#1!F+a-;oKg1OLM6 zzR4h0i)#o&?e7do3=xi!ek^5tt@`nJs{&wMeq4>ac%KG_J%yIZLH z`$eGFlFj~j0xt5@c4-9U$6o{KG z>RJ9&g);j}CM$Ko$AfQ11t0%NLJR_&aJ$GaL~N zK5(TQAFSX0^w{n25sY9yBD_l1!>m1}M&9Xk_viZ zD6@wbr-S++2+XY?f1hm`c`2US(P&&NWU&8~vxX}f9V)&Xs=mvLxa|%A>H|WTv77&e z(QSD;J zW6S5Ab9%%p@aX=E_)o_`w^g$?mR)KIfHXYT&cj@-u6phIROE?;FNS>8?pDf`H8B-c z=7;RAVU|sO>>MNj3yj1E>4qU13NlXC)gQYV%QtfVsaZb%3MUj570GB%wU*kPqrkmB zF4wGh;4Uh5=KS5JC!9xKovoAJC@|x_qKo<|X*zUbpTr&)8BzaNMWA#O`tsvup=eHY zqM1*}L9Mh%k7aLZbIHf;u}WK;mEo!hxqCL;NOfa}hE{T^VnBwK32f2tB>@<8g~TMa zp!MqeqhGocl54SePKn=jO^&YA81kjw-WWNc4TWt~BK`lK1;Ckx4WpI3q(={m^#FP# zg|SsuC!j#>Aj?ytToe7VsJPMs-&jj|f414wEEp{Xm=|fCj^IVkrw&=if@65TC*T7K z2Xp1Ce_jw9pQ(qjz1{;F<=;yjVZXvrW*>_e&=7v4=zSBXN7F$Xn@lYx(c*CPrTg|z z6gd0QdP`JD6Szi)P%T?-=}#vXJfGFaw$mfLn>C z0E!CKFt!;gSOD0~Es!vNx$;ny8%Y;5bMVb#;Ql z>%62D_OtZ>yM3E}y`IS8k<~Zt+P@QR`SW z>)t&?*oZ3wMne-g(MePgCn>FH3yUw*79#*=DMQ{;gJf zisX}+8}Sl5k!Zjl$EsGS)8;vk0TO6o;QeTbE)Iq6&@8EnsaQ8BX;{)Qnivwchr6$& z0D)r7z5E0o#f9`WX>A5SaAkX8w{kT)$S1>5F9wLB#k}R~kCfSn{D^x!-?$1{%KsXsv zj?xXrLNut$fjl5{b@n)!mX!l18GY1iYok!PhP_9F(O{}(a}T>op_F1L2&^u<%XiK7 zTB=z+zo*!p&HX%gX}Zy;Sg%H^W@>oYfUx>yggJ&QF4q8uc z3N_)!g-lWuNg}meTJ{^A2+{n|~-U4pSRQPnuitoFWX&FnS+&D$Qx`Yf;b)n!#A^TILv9pJ0-{a~8&Q8r z&5HYq0Wrs$#5y{e127wa#0*4ZS4o~ovm_kY9pC`*t7_d#4GJvzqi=c%44oUQfT&G@ z_3!Ldlq_4r;1q@~2Sur_vG`@`Hsgq3bGHGTmt%Ch>?rif!DhWysz_Zlv*=3cH)fIN zuKm!9jE!Tm1)?|k+g?;?KLQB1VQT(^AqV*1;I_o;AonN^QA=bDD?_&ze*%H9@w8*X$rIEMp~AQZvEm7 zZ&D8TtcwK4FeQ*$*lpo#CKne~iCA|2#|n8Ot40r9T3kwAYZ?B;vS@r8M|xWPllBEA z&f`z^>Jrc`0->&_0cHQR20;(Av(nN$G~(Ic_#CVwCM5c3Ej+#)_`;>NM>bZYl`sr$ z^|MR*Hli@v@f#($%BJeSakuVsAtmPa73<94XX0YjARTgFGL5+pvL7p$ecDlIT!K&k zC+%{3aYPTmYhvtPDGh0%f#xtCFMM8}F|aEUX&EyHyavGzbr#2x>%9Zm|LS|+K}T+4 zm!8hIDDoMAWb;9sxmN{00gzy8{gso`tF@XP1&~K9GBJOCh&2mu^upLf#_i8pOwkR` zwL|e5mzk#b^3%|lB$t9u=EN| zX{jsUjCDDXlf$}Mo1F|V2Eo~EO*JRSTnTvCRUB!W$}{JwriBs;TxAZ>$wlZLN1>0S zzJADPufFC_G0fcrXU9p3FW>F}ep6lS9-Oy54{#^F(ze+cN64~Yjb^_mewvZ&T5gs6|EUq8;IN9 zWBMvKM~ze9HRf_HMmR}^SOZ}2$FTUXw4CF8wQzT?Xnf0%a5*a?77WxnsB#RFwfrAi z(?KOGD_XiH?@LQU*Yoo7hDvlab3X6bEe|mOXm>e4ahz_b2@9?b`@+}bO{bk+jb%ZF z?B)Q=sz)sNAyB61@9P8n6i$!PS(biHg85H56xgve&h&N1)~W{eou?j=YdSU**?PW0 zuzq!aOa#(E9~}MPWb3Gfrw3YQP@#496pzdRMqV)Vz1K)V!!90?<48dTayB zrsual^nV6r>vEW0+&s9Wx9sx==trzpr!8Y`Cp}IadV`A|QbpI$L3idBs)V-U3bPrK zfIeKg){_*?*fubY;(v0TIM=}{e~CAf4uPY_-?)8V!AuA+-ei=C&Rcx${(7J)40enK zLq5GKH6m6fH0%wVU~B)5RjL#81;fHWhU=C`7n&5z7453M6LXY~LJiL1*@GTcH%Mdh zJ+(DBdG@}e(2o;5nk1g^;n@yklBCRz!Ov@Srz(Iuvqm(r7>2Y6KnC(Lu=^{x148Sv=vVo-U9Zbp$3N`aD4GE?@m#Giaq|k{~1V!3vg?7wg9SEAo%??8CeXjwi(=y5sE;^Rd zCLDuT)-_%ZL+=d3IRI25a2VclpX-#%^gQJd#pP~mzI)jV`mtf!E++MX?!)`0qs4R@ zzUr?~pb_Sl$Du2vrkKB;+?z%9Bhd5;NHB6fg3Sas(h%NuJR>L{Q#!K6RANZRF>-ed z03D&9ZA@$k!2RH(W~ibaR{zL3SY+$??9Xk9SSKdHrW7(V_%Jc5&Pfbpt50}o(Q-qx zOI7Rc@8b-xBSTuA{qNb)*B~#smK)~C0qo!8e(RPt!A^1~Y1B?7q5!g}f=SGvr_;P&o_iE0;3?ft9(p`$19<_nJbYfgDa5)7P%f^;JWeI( zGSJ{-Q2+Kn)7(VCg3~h_8UyDXTW{2Tz{Jp%PUJ)Gz= z-tW4vvC;wV5h2@w%sltI$Mx2mxWRkDxi>iegT6PE0{Q_hIJ?d66%(m!3+w-8(?V4M zT(blCA;3c@gWl)pD0n=Abf$JJ${lElxsmc> zYZ4HWe=kEEga1K3(RKW=+&(phiMlU_>LpDOkD4CC!e+xiivf8Tr=+&mtk zNhQmTe8nx899d>Fd&bnEzg#;2O#z2gCO9e_W6dB{6c6Yh}YFF}LFgsd(LM zu=o|T2Xg1Jc~w{SUU4I@hWIe(Q9Bu@w4lIT7S4A_OfUJzN3Qp)oPapwM!r@a7J^^C zA>4_K*(2&ytOn@0;Km?devH-yt=cF4$ua3yF)Bf-aeQ&o@C8zS)QVlGmU|~RG9@*I zUH6t({1hafU2$=LeIiv`befvI`kuSzuFK|XbRY=2m#j1O8t7Q;%>q<(>!dyz_7a32 zsELiJ4#9zRJRe+Sgsvh^5gN4FP*shocOCScF7_bfxv~F$P`f!Z=(!KJI3Ub*U%q^ZEZ3l7IMSJ*xgI0} zvatQ>0}yFV{khLU?6fW;*ZJQ(nnA7#L-X6eDfsMX$oU>7IHy7tq+aOc2_+-B2h=Wk zd!w2WY-2QUaBmK1F4kx(Q6(#oG=lZl(n0YN!1~(`tqy@m&*1iE#t>(qz!#4^fLS(s zf%uVA%?JET?H16Nshd9Rq^4#$F_b| zukU==qR|4AB@>%Suuf?pPXb`~K4q*5_)yk%>|0H*aYxdVtfz2cs3a?c2S8sII* z&_jXr78Bcp0t1r!hBmui4^Cj5<_d!Gxwp6F2`CTfX8ykm$X)0k)mnm2t=t7Z)gkby zTIv-sFfld# z%>eAc$-2KDmnE}NEmebY(we(x6wW3fm>I8xk-kC?z1zBcygY{31wbUxdOf+l@9&v_3xgY|L= z5#nvvEj6jIG%#8Tzl(D}s8cL@1=bZ6!RV%gu{Egvx(7JyH2f^pcAY5hgxt%OROSBN zMfLP8pnU%c1B3=d^Q?`-^P`#(h;v{gQCSNW0f-+^4Rhm4*Hb8q0oz6uLkb_-UmQh zIXcICIbFvjviCn`$hG<3w=vYN86N|vRePm7V(^6qBAT%`;$H)43(0!-j@l|C8*j-S ziJodw`y+si=?D408O$yrs1Oc4Na;q`o9g&uJ$}aGS)GnN^^lkGynIz+my)bEuNX%A zzdxZ85?8o04TP?QOe$a`0MqJPVF&9T7LZcWe){sQ6ZznLBYR`s*C9L2E@d=?|hS6^}fD@k%*KjQf-A4?dV9fm8C zU$Y$iDcUP%;#m=pi1EKPPW~I4k=bXY9q(Nd#(;pxd{tt!&Cd<2&X&gVLU%kPutT~Y zg-?6!GmG6A+3ZLelb8k(SF^h>kNwLhH%W$=v+#ACJpHi?Y|dKaw7&EGy+5&Yd~tPt ztUy*j`G2yyunR+fvIro*mizklI@@!cF3+%93$VhXRjf>Ui2ws(VU^yoq2YUIB_JZGvl{byqd16Xewi?hyxNhk2J!D?~5cbn8+@FPC)`tY41q&h$=qvc;f?sAyeX-F@jA zb3khoLH3etIRQKhYau5E2bO7sf1;J4R72%o$k2y~1d>96&LaS+eP%VKMOEZ`>Dyds z0bNhR35Wo$%dz|}<>P#mJ(JAoF*~%pxhZgby2AQrol*nV6Shn2&qoHA6 z+g0h;K&$fT_ouY6rub`#qPA=}?r3vhN6B0#;x4TQL98=R6lPgF1#|iSFa+)B>?|7q zv`P%)iDiwjZ})s_LF`SxSaFiR62f0#|L}pSp^eQYN{8~Tt+)4BX1W|e!<64@oXrFE zE#>TCfe+uaSAnesfN3z<954f1ZvDfw!Rv9rl_uA}!9E*DOYiIgUkBE;MG(_SE*>XU zoWH%3``Oj*3gh#C)TCUpWenI!_qQ$LT^~S+6^kNnyFUbIN&kRmO@46ME)D4$SbyVh z9~@8v8=H&Aw^Wafr;s;y7}kTi?q?iCnhucTlESG7o$mb9X^T+F|1Z%2DgmI#?GNNY z&N(o+xgt~6?oV;R-C)W3o(=qUWrzNu)EeVa%N}sofNaJf(BYZ(#&+uNFg`8AodFn; z%JPs*;Xjgov**ivkX5Ir=i9RI8+_upJ!oXEL&kYWhRf0nt4I>CIxu}V(nK1s+1o=aAi z7w!&ZHXI0<$_uPHt#9h1K6Zoj*Z)}+g%ltEL#==Rm)#Ps*g#47u1<--;)Oe&XP&m| zmUH7ILGk!P5ucPNrXbCKHq)1~?*3;66LIhSFyztVGmUSg#}KPAYk1Gu@7HR+)+N(H zt*j*Ojl?Aa&IdaHN$QJJOhYKNGlKZAeo4I zJ)|F+>1ntTicfU<4cKn%KwJzJKS*N&6c%cvV2aN}8ITyURBSX(5*S;Vc|$dUQFQi9 zQ}pXMFx?n_D zt_VaFh-P2fxQkt;>g(oqiOKs4;GT5Ai^kaM4C7lqnAuuuG&8^fdi8i1vJ!pz)3)9@ zwt~x@ALxx{|5pA?n4%2&z;S%k0ALMQZr49hRdQe0w&Fxe0ZwH|{)nxA=J$UFk$*%- zNtSM@_xe4c0xJHRk;M7Tfg6c@T72GCcSwKF{;x`@wbbhl{<}o@=c!#~5?YY`eFD(yBxP zpycNWW&rp}5uj)Ud+-}_{96=#rd!_mW=vV&sp+P`h5)Tc25p7}^7L7Tud=cR;58&} zT7uKZgcg73Op^Kn(0BIR(Rr;~nU6MEcF+4ub6Tm9!^^to1F-ak6IL!~OC{XLtwys< zeozChL+PfUahCpe0~KbO$VnGtFLOAEV*rvxK!CqQKFokqebP|P<4?ozo$p^R`_NDUp>V*ZBmCiAiZ<&F4r8KDY42s6h5A{K5# z@w>HYz7hXdD=nzRJ!hUsPFF&->G0e{74f%*7+G!=i(L{C}*Z&d{wb|CJT%O0C z0+to#s}UdpAVeL1^$!dZ{Y&xl5l=qjW!TAl%MV6MQkbXVTCabJX1)Z=dWJD?Ed_Qe z_>(5vofJREFvo;Jv6G-GI?LIZ80!#JD+weu*V;Tc`_4evp!uC#F6*c-t(Yq)@i5+&n>h6)oZ%YAe*)rz z85CNvcFy6awe8goiG<7RRnFup+?M~~ zUfk{i1v<_xkUtPyV&;RR5nvp#K3#g04|$1V281|I_8KIGzbMU1hynLNDdNR_S!3(GCM3i+ERww+w*RW1<4q7i1u49>ITS1f^-+ z1k+7Qa1jethoIBw}RaTpaFffM)K=_IVI~6`Fo39pjK@ABs9ulmnw4lwz5TRagqaux1H^U zffUvk6X0zq&wu-x)@_F-^m;Q3JaUC4a9Nu04U>IW&_cca2d)1FDSXH$M^_mUMS0nyUF3rEHr^kmxZiR~b!r2Z-Qd*b}Vv-MmGJ(k=AO=nsYa!;- zX_zcKgU=ox0E?EkNL`6Wt!!Q?Rmj`z`XmK~2I&N&yfcm1LX9bNr_q?`-QuRE#G1eisvzP zlGQ;SRVyjUZ2VvRoq>;S>fO#6?Ohz~y#Gt3hYZok{L zm4ZInw`A9s9(RW-vKNAiVPg)?@7mh!1Dm;TJQ@eJyOV?_scE~wlRQ?P3kscqW*Yy+ z2DmJ#D!o&`ZMC${-y2YFiIB9pE9h(oZ}p6RE!=Di->^;S4@p~&w;;|LJqJ3?D%dkj z2>aAw;98Ii2>o|G$WfK>;*dDVf4$)7^ziQoQJ~sXz;z@9PS0NC#tf#?rqAaY+$T2n z7Gsc_2Qk9QMz6c?(U8gc+ACLjcQM%OaBEsOl9z|p74w;txQQ3QTSV{r(KRhWBxANA z@nM4sC=I~+ZxvknH+3PY#qOhl3jB8o zSD)k2bV-6+005B~pMUjVWIB+6O_4zS@g{s!&UabL{oHo(AYihoJ^v=*#=3SX4g?`V zW4!0)dRfmD4+0!Fit~a8fby*~=`y1d`~OK>ZN@q|K!*MOI=cRESr3R#>vp%3kbmov zMpfvX-ky#peuEt0wpdz?0}&Bi*R6I81C0=XFIC&%FBlJW|Jn0v6b=%A2xtb>+lf&Rz-?}+hx(-c`KV~Di=cG(Lg%FZ9AUTx}{BB1XMAh`;T5$Nq(qPJd|jDr0~IwU1GVDz->k9 z0Zzbla5KiK4xE5Lq<`|iH)DuRN+8qCqj8T~aD5&u6Nm%juI{vxfcImGn%>I{QbV~B zTdvqeBV)XoAe;LxSDs?2EJ`EUb+~Q=IeVL%@{EZhqAG*eqbQ-cCNq?*=Z%+{H%0=IL(}Z|fa?~C)3kqF0I(=m zr3B;87Z@r5tAK`PP6D`auAuch$S{wT8=FiqbY{4d`D>`dqg-H(Z3K2{Aj9<=QT%M3djv$P6XO!>^G5JNh0G zIY31|&Gj!l2C5{v zk^Z8>n?7%=$pJCAYn&aFF94HrukroVesB6{A3iyl#Wz3P*90wZGV=t=NgNb^Loynd zrv*Ts@{x;2Npu1qII*<_fPn&B693hI0V)Qr&d*YRCmvS@;|M|CL`$$zaW3rKd8MTy z=2dlJvl}h@F?9~D8?PXHXQ7d+;lqB6oMkE(w^$0xHt>-0ZCz6X`Tf7dIb+c=dtLGoZJsE6I}W8wT5r<>9o zj(H^B2WhJ4@hVynLt$brE~~E{WIxhJ;Wm_2?pd=e+G-gxTlNa-S5$BxT!yaBAm=E| z%Si?!V$Hu2Jum#OM-g72RucBpIwS3EBFFc0WZmzs>|?$0e1%uL zr0|cj2g?6^od|#y{x7(kN~7bovb2rfN`i0|@b*?>L*nq_tR;9|%G$8g$pQ6JTj%pH zaKDsMyxz0)+2+DCi~g+~MLG3ftP~x^vHg4%>l5jSipaTIj!*u_`;+VQsQpfG3-wOh!rA4SH4|xn%w-SD9_VCrt~dsj}cT z_dhagE_!D0zT!V+$TxaRxwiNFeznc~7mZ?VJ5Zm^wX++NoRnmD^JA`rQIG|gSlVFe znkNU0)s{-C8?W%%K~zzy%2HVtGEHRI6<=bNtQ|6J1HBd}GuSraR zQ7#*r#xHzVoijjKCR%x}e1pwwcrw>4#z%^{w>FRUc`}Fkk5eieo}nqI9043-rXd?n zdJ{|%7QlPldQ`UcvGX9Kx*MtKp z<9&xxb5FNnVo&>p9MMjb>`MKlozJT~Q33#yV!ru0dTZ5|LAFnU&iWG8 zA;Lh-%jx*mOF>6VYivXqbe?(uG-nT!juC>L%-DL?Ypu))(oi0+nlZLZCi>bic97@b zHb6_f5~s^#TWS zD-RkU%6|0Ux&RpKEC`8wJmlg{7kP6jup7O*vVISL3XJcK9f^HI-*bkUpQPDkDPKmW z3&S1LA~13~$vlKM?%4*ltSR^Tn%UB@+(x~T(t@sbBqC&*V$!-9-`^zgIq0gPd*4b1 zT`nySF6$i%TQxqGJwn~)GFT0g5B`rsGM(I~Sl{=;n!xD5_^+cI;YQn|EAln$2x0l$ z3e?4}GGE)-uA$^w56t{6x(>7B5C~TQ{{#ua+vt7dqm5*RKEcEEa~pXK=jU^@jjdBV zjFYa1^C4*%Rl%ik_v!RIkFt-3uQC~f{E^5gscWXoPe2L!z6V zCd;o_ma@ZqGf+={EEAQ~Ug5lcsZWuK4D1k?Pp?|Y@PtHMTO`5ll;4{C z*p7!StyB8`s9yGmEHN}q%J-PiYgtBWD3NrL!d?ql17%@z_IxIs8>HcH4Pm>| zl)}_XU-O-4-2oSR7C)VC-@!|t|B%TJ>OygJY@UX5DuL?oRlw<zJEG?x7z?vWJ6RkK4OG-xmEfW;D_xAR*u)P9tz zPZC9F=zQln%j)Us(Q4JMCF1k?DYH@byP9(2;t?R@m$wwQkmBpj8E^`TK>d&|e51Ls zs(Cd%=K?r(@FddwJ|IUTl*=BpckojV3u+zfH9%)n8t{I}%D^mZZ@BWDbSCs_J@>zB z)t;vbx!yMjUBUd4qw}?9lW{4M{GyhzR@8tBL15K3ZiQwg1x?rJ^S82lyFuly%%+u< z_Y}WA6nJaFA&~7G>eOlJ_sV$ZAwsYvWrf0&Mx~O8Mh_GSJl3X4XUj}tICjcDsmqjt z7LNJH=z%7r*4IasQ!ntYSM3bZuYC91DzSZBUk2kqo=8LlK6&5%pMJC93N1 z7~tg_;On6pZ$RU1cWA>+=j_BOcLTL&Q~cZ_L0GH5Z@|h3`RbG*+}b_ur*q3TQWY)y zIjuaK3{M4D7GQC5iAH4;dUViNCwRd}$ykff!_7lYyB?1-1DcnvM{l+KA$uo6(tP`L zguBU9A|%ZW{`Z-?h4uQp^L*;Xf};{@kNwH^Dc3cc6f{7LDv}ftVbRiTG?IZznRT2 zkY;{W8_veKtCfNYbpFTWa@LguqB)~X_C%RbltWPuy5^tO zHOYs%j@1EM0u>x3n`^+@^IGP%&rjr+9_k35N$)-}bdi%gw18e*UqBqQ13vbm=)%2n zxM&Es#EBCdG1f`99q@-@Qo{h^Gu~lCG(Ej1PG#V@Ta&UCv7bDoRXqblK}dA%Uz|EA zL^nTBn>>;w``E`+NIuh4eh)2?*eQbdN!b-B!AWX;;V91?EBUx&h0jz-I6Ai-Xxy4$ zE8&WvY57ci^o(tE!xaak3c9N9%FLO;kyKxwcjDilHp!bM^3E5&vd4qi1sbJQtgO1* z&*Hq(T#}R*lqeFjGXXjYc>#m4@8wKr+UuXuoWJ@J$VV!Yo}0eU9gp5xreg&lRoJRt zHhERzJff$T)p#h^-|7{7rfd{4m#2m2s;^evb+J~0GUW8sbbhW?fRBeEb%l0>85^?N zijp7ZTiHTPDFLYVwwre8H1W5~Qi8ffwHA=}XrLkD$CAvIrE1i=t5hEpFN~XOU-F#6 z0Nnx*V0l7Z1P|W4U)0Wd4^MZqNd^f>2>?>{cgB04p~z8k53#}rW)*B|`+Qo5P!t#< z=nZJE8k)8Z3fstN-2hFenzbM18D>&a17a*CWO73$hUMTeoJ0F3;-Ks~CA5Y?BDI$botGC9ZA#2E;Zmfd$K-6Kf zn5Cz7Yw(A6FNAedH>qx&0@_tkl__kAMxCV@TN+}7#ZR^#ek8KnFAn>8Leq7OL*FH2 zkL)8hIw(0vb2vV(_UL!2cfTmsip%#B8S#&zV8q;Fy77ZIo{cReg5P-~Dy8%>K><4Y z&b*U*2l30U9`}Wr5|thZ%8=T>cy%H)!(S)$ymflgvSb0eEi2n4@}2Ua8}a9PN@(IA z)6ubO?Pbuy+8v5R|4XmT6Sa|~H>=Q)Q}_Edr%Pg02k3=)uas*Y`Emq-z76#$+SdpS z?LK?T5Aa{Tex~g39kn^b`Yv6d7alUruG&F)$plDXA>)GN1%^}!XdXblJrZD*z8n>c zsGGB|@YqrrnF}~vj}N}@Ct|J$H2J!&z;a6$CwJUE)+GUxuN^4L2Mu0ji7~MuAA&aT z{ksl!W~=9*i?!P#M@_T`cZWY5Zx}A>IH^N2M|h7|9#(nW^?&*=!H-nPR^3TZWI4fK z!J*=JKwo`{+=_XJ8+WaEf2mA|wV(MCY-Ec4xAHLkMjmX)?!^S?D$s4j?kTTkQsEFL z>Eq_d`_yf8|9nSNAme^`;KX!jHyBhfZ0Wzp?0#Mcya>#nY?*49gWs8Pk8R%qNJ;iq1`^y1G8UnZRo3&iY4ryPhq{$3B@Sh&8k zk%G#?;5^j0d>GTq4BG6;ST9y&>pHidwx}z`G_#mkg-YIzQO>_;_3$PpoUeQr0+@(b z#=Wk&>xO1<0iw_h~*hO+G-9HCF2t4>>8aUH8haSH~&rd_Wdizw=ydG z1|046^pIe1siVCAU zL+UOQ4I3P?P(D7;U;s4E$#kk{B2Mo2+UT()j$ucwlXV|%8lQdob-Yn4(h`h@L| zxawWE-G2+Lh{OCpAyqVs!Gz<_4Rms??WBfkuV@eEZVQEu0t#cH`)_lsTHwzgnf@raw`j zOxz9JEk}KVHmG>1A^V!5WD6OPmf9~jRrNHp1+&FkA`)4yv(y$ej-&ouc& zMGr9nP4_)4R&8f$Zt8j4xo@FBZB^9<7z6=dd{O zWvnxiW#D@8D8D-|03SB|S7{n&RNPgdim_ep9HOdZs{YiKeiLEpnh-6va1;ODT!=cm z^uwgJ7OH{#d2B}#c*jWOiyRg0Z-I$6b?XIu^F1nEbNORkbNBvAHTicc2c;#}oZ>@3@Md`eoK`qq0aEnPZa(JE zJE${ETcHZ`pA&9-d#y4F-+1Ha1Z)DXJRR}9s7-kgJ8TU6CEqCWjUFJDA#8Ng53 z{*I@8p#ig-T#<`0SoZF#%B;klzcZcYQpVj>Y`*4fd8AE6kkpz#*J~lb$ zgPPwt$zK+1yP{HTyP&;>{oKfN?JzuR%R|KH^7&~Ah1A4r(x;sxf-bN1`r~jQVmao> z05@`Djrfan*tFg4=6;<&Nv4Dci|OkXO0gsVw@G>*<;VI^%vB-UlfM`n$QLiQwu94| zL4{p+;#(b5orwp~d}ZlWo=(yp5hr9ok=9M>{8dZ1Izne(9YH;)myK9}@QC zO)mf5-CT@I&zU_fTj8(zHe2spqDw1$n&FCP!+PNrgyWy>>tDQp=#AY(3L07!sLY6S zIg!$)U%pva*?Wh&8U~DAl4^9;uZ=i6pLEO*;^q5%L*i;VXVEWmhNgx6_!dnN|VAuC?o4O@c5ieGpTHV{TgZvZzjS~{RJ_$ zig+ak$|XP9YS>@kY_gL8+N_Ig%lDq|Saxlzr`f$NeGj12=u3PF7>CFX*1Q~=NhrP_ zoJmi&EfjD6jTEe~U8Q?sK^s&MzK+I7WWZb{rqn+XuVNZ2p%9IQ z76)U^A)pJy)dpJZ?v|(jt<%!eQ+faC0q?ckyx3oMq@y{%Ylr0p~!RWJteG@!S843>u<) z_D;T*yf@z*a#3*odd1@HK7r`*HXnIsTo=Y^fO`rsub=g*mD!8K`lAp>R*l~0u$**T zM0JZ+~=ye_}V8{0&%xYQLHUap+Dhq}>(W`d98!xz-Tbm#9=f z$yav*rGx%tS)8q?^pd94^jR)qCxs<8-I$2gy8^F>b;Dm^16{1<@on_1sro^ z$6F&t_4=1j;Jc9+MSDMjj?A7%l5N0`Nt?;2%Uo=dZC(hc_IpS=zIKvd?90-_i+G;) z5H~*txb@%+Pa|_pFS9!8`dfqSlLU|Up&H=t-WB$=ZU1=K7UJjL{uOyh*p72Y_;|!7 z#yU;-Jh@ufyj1=!x5LHBzD;+f*}64Kf_v9bGQ=1~S^%2h`azqaz3%2MTO{dXoW_5UVs)Nbm)H z#EL>v+SyTyB(;Ne--NGCjq`%57HZn8#L4Ytm&P2_MAi>9?x~ME895t)diHy6RQ#|z zbYHwNPKq>Rr9l7DWtcCRq8l{va3m}0uy}KDF;{=s#B5@<5;L+CzDm4Y4?134&g5NDb zuN7+vCuKQIEQIzkKZBJwY)CrlqU^M``=Qcr3yh(R2smnUovn=EV4;pnJZBpFS-O$1 zm%rXw4d{x57>~Mnf+w<@jn3cZdXqKg{2%VV&)zR%&27|c%+qRS6F0Xi?Jxz5P_WFf z&|+YbeSu<;+uaO_?tc&*Dm=rbKjf?tKr1V&o@Gadqlyj?ULAl&yGVr$vSb!+AjL& zjW^y}+|V)nBF0GE^k)0<;d$CN(zJQ~{&S_SrV`d%7;@^0K84Vgcwy>EV%pB2N^aRH z-Q6!0lKORaNavtZo5!;57!Jg@*k>!$X@19RN1e!dGsU=hKLAz2Bqxr*ny=aXus)Qr z{(0MRXIJoKdoU=;_8J%(0;lC=8T@YSufdT7G14l zC@Fd8S>Iw2+uRyqlu6#T0kiq#IpsDGF3F$x9kTfZV6n(g)`5)eX3)85*Xy#4vhJ%; z^;~Lw^&FT32!#oQnel~zww;~_6+i4BCO1Xdr3SjrDy-yNm3r%l@lG-v?`9k!566@b zBVd5SqAlpnAn1l*qtsSY=ylw^4lcNSb=*upo@jpf)`z6X><=)?kH>X zc~$*+@<<+lv@y;6*WqVu0A3}7S^IfFYXCt1~oV?oyO2W&S{i6Gd zUOQt4V0W%n{Sa9>Pf4=F)4G{ktFlxRpr;Kw56j4*ydV;wqeaKbT9YoPw}P&{X;_-; zbQ7T-$wJBW;m>FvF#&n(Yl_>+bA;_a9%xJU#|Pjfv1VH zBSK1P6cbOXCdBBS>_^vDQ?G?YjXIA>Ci$6q4&hbec+w4=E3_Y1u15FUot>$Nfs=cW z^?O;a9KX6KN7|Yw4OAQhV>Vo%4sn$oPThj#qXr)W`cC5T8Gks3`5$f_Bq)ly>XW3d zbh~wx)~`cN26wNIY0wYsu0d1w5DE-t!C=~cXCj-mf{SK@+X(Y&hg;h{S)vK&ZFW|X zrmTloq8@zx)*q}ND2PmOAtzbRjC*~Zh0#@8_*cL|)f`25~uoIDg=VjclZ_ zNXh}G{Td^3Qv0f@%kwmO@ylW?UgVUxCO5)bzxQ3qL*C6)*S!MQzPX&tmVEE)R2%P` z*@Iay66E0br0y6i3RbruDdknSta05Wlfpqp;lt@QsZCFP^_su;=sv#R7Wa=Ub1?ty z;#7|2H$2%UR$G}ZO-WCeMxhkP)C+z51}U0_HTN&U;}$@9nX?xhkoP{0{2I7CJNgY- zImOE=fsD%ca>;RPXP4aOxJY=3`{hg8XWH3){Qeq3L!hlRRq`_T19@@Vh1bYdbzCy8 zE@$lKcR>EHdT7a<`s@kN(NW7-8(4vUVy#>37_|2vdx?U{jf1E2w`gxLzqGt*>BYCy zOZf@CEKsS=j*@V4VIcikk4oH2yZRKg>K%n^KCg4XogqDd#1eqoU@O!UW_Q*c61vg2Xh(u&dadsAe6#~44<&-LX#w8 zd8^EkT|<}*sUmD;J)D=taL+hcE84S{}01lKE5Gtv3>2dH=TFy`&#kXu^T6 zlPj+X9e16{Qko^KL4`@j-7>5)dM%(Niq6K)ykN?aXDJh0E}qfLGWLQ5Cllo9kGeS< zJbzI|H`Ba+Djua?q(Hx~<*xWV3HXp5k0+Sv`K%$lc!_X4r-QzlWvu#$7H={%%L__&Wd!+>E&*U7&zB_Mi=j2AYfp_6L+Ovwh9dzv68~(t?eBW?& zx;nEj*iU=FLq3AXBH+W*3}*1m1hFu4u)cjRU(bjooS!%IEmM@g{Dds`$0TKIpex#H zuYHNhvE^uXlkwJtwK>;=L!5BH8HejgX*e8VvmQoSOCywB=I1Ku_SOikwSj@Sl@>kv zQ*R8?b{!@z8p>v@!dF&rStQ`Nuyy{RCjkHaZ)J`p_(zAq4tj#{2qlSO|IE&GslKL! zd&V{E@#n^Pr|FX9fPo(a_QxyI^SXC$*}Wb|qp?eIhpmymGN&aDIZI&sp|M9G2cvTh zrdso0*`uA9Y*|U*h&Tv^_gw470fSdd9%elEE%f3>Aj~HPQ$`mtSl;b-c@MB39d|#= z6E1TsOXRzfV#)39ZV zzFTxFv(;AV!Uak4rn6q=5;N0cm1;3qH~Ry>n&wK-99HrYE#a(qL$^`<5IO5c1;;}O zqetgWCG0YS?e6+&nY-@3zRKbgr|LrCrWMZK2~`C0g$Kj8LzJG=b1j>KWyH+QbYMZ? z8u*0X?B()RwXd}_R)bY^UZ-5Ygjr0?g!aj?F*7U@7vh5Q(R9;i8nGOi*3H2~{^av& z$$cjz`jnhAo=wktXn($DHErSa54miEkaC3vz58uJX;&h&|Vn zHBG)_l^^!268zBS!;m!Sfl^%;mhn7=Ii;8)6wQ}ApDwD>3YTE4hr#$;392h-(vXqI zA#Obsu%@!WG=ji4(PH*lLv>2~%#v{uqNDuaOXomo8e43Pu%G%zAoh&L9BmcKMWW;k zc|$0tUMZ!z^+Jx@@vPmsf0;%waO=1o&3V}!FtD;u z7qj;bnob`(>nugU^)uRaK|(}}SwnxnDAD!Q5be)3sfd;g#_GwXMV^DdGQe|s217<} z<4!ti>KJ0X{$lii;Uj&0}! zS~1goE$U+d&PX zxW#@dv_4UkEXUjbAKQwiITei?RfR!SKFV#B)Q4NW`|z77SQG=nz$2dFn?Ra;_+uW{*%WzB29Wt&CP1cf;X9`=5dd7aldH z3h#G4Ti1uT79QPKH$Vl-~YAhu5~$kFg=9a z(m{T?AI_u>2yFhuAAN}&jflIwfL68i)G`2m8BUuP^_KIfT6@*PNU8xz@5YdW0U1G} zwHwLcY4kf?t3g-i*1^5Orsl)^O<|oo`3w0W@N?0x!mTuU`d8&R1&l;b-BcZ4uw8=n zaNHOwO>wLmevqMK`jYLMAKw?to;u?w-dA{S3{Z;bY2qHc4vt$%1DkfkPF*Q1x4=;c zpKWNOU7@d09^SGKSyLpp&>>^Zm%Tqe5bI1l)QD7OS6A~R9ryj4=MXwN1tD04A^FZp z#Iv>BIdUr`%%y4#WTYeUC-BeuC|aiEidu|Nb zRx?p?^SvPJyqkNCvOBC_!XVS)ogDr|i}!Z8-m?!w`i*vzI?mId`X;sQBR%Z`)2Z*X zWa&KKz}-xG-^pBd@--PG2sbkpq$S5MR_)L3^;y1Wt>=-B5)7QgFwW90XD4j$PMnK& z_&hX3dFASI)Ph{pe{*p2`m#;*R#Ho_9ci>St8LtF@Xy#}nGJ!P*)nIOsLtU$(1CZW zwz8`_-V${6xX{F}mBJ%yW6EBfqO2>_i|fCxwj=u_fmMSz{!PFTqK)qPaQS=q6#76m zNG9-H@yyxcAuZgXw$PFw@eBh+DTac(zHqFPZD=_EW3PRu$^IdasWpFin{>B!Y;J3RCNUbxG$Y9}4DEjcpp>?!q zRDl~M1S&{Q>bDVyu}(I|L$!-C;yh4;!C zIA0)excIdGwWO-m5 z_i}TPIPR07nWC;2rDX3S2{y;ywafe$s8;1Ki41w6SHho$<=aaqxSpmmRLIz1e?&S( zxw_n~+&cXHTnFhl?h_o0ar!lvsFsnJx!9cH2u`*AU*3A@=|Oeun=j@$l->%lrwCHG znUM3VJWIbC9q4B=R#7WG-{-WTG?UJAIqOfu!(`XR8!Vb5<6ZP{pUSq-->0c(8QYNpj;$s?k?-E zXO9mz_JpjE@|%U09K3j1#$QdZHS@zX3Nv!aVJb|87H?Q>hQx?SL7fKbq9HG8=qG`= zi+1}V)l9!oJI&_3M(jk99wuos6CLc!F5=Cu;<dO#U`6er1*eQ=)gJf6G46k?ce46W z09o1N_)b?{=gA#9W?qda9-hA(jA6%sAZ_uoD$^A6HE%S8OKohLc=?hn#GM_d4Z$3tV5&z#{`^xlMrQ zfuuwh!fDT&RC%}C>@`;Cmatt}lq%%>{cLEzdXb>YYEeejz6u&Hh>pNbjv|{U*5a== zyZ~`;<5m(iB5_hYS;@pJn`Sr37+<9;Bh+&ld3ET0lIKmb;B+ycp%<13pX8(#B1vp2 zWw=h4I`NFvJ4o!0SW8Q#);(=q~L9@_%fco+liQn zFB6<|d{96}`j|pc9JTZ}cszLD!sc~pRLY>wM>HNf6I{&2nUYqm6W!e-I@j>u@+xH# z9Ltlvt`40XQ$;P3`S3Kd-~Db=;uNKg7VgyFijf}5kY;Y3HrZ{>-Jc9p&?-U8<734% zb8=~ZGA9Z@g7%0rJD?GjQYrJbXzZ_fv1~OdvBTc9KI9iI$w4kzc|WDB8)Gs!j+dP6~>&JAWlqd#nBx<6x_@gAtS>3E3}=w zf$(duR`GOesIjrp>GV?lMYcKSw37Y{N^jXu9U=dzbquK zckxr?(OK=g=!?S{t0cm*h!aIW8mrRQl)2rCRhmXzQk}`k_G*Ym1JHAW>|37k8@}o7 z`fL_p2ewx{r(5|T9Er~jVhu@6X?f!y-n+o^kY|X6htJOYZ4wWUA`B3Fjm$RoYAdQ7 zpB9kR(N)wG%<@4bg0CHK{u0fqti}B);$Lj%cuEU(!B)|8xjpV`t8O}D)#`M7ke#lg zx9+rbhdr;)hdLfW%hFaACO%3-kq{AS16IWYD6Yu9MRg3m4x?E5BC)%4MdNqA*H?E? zvl?}j_x_juNQL%1s$|@mTIe63hUbSPplVisS}O5F({6` z+E1qliL?@MT0*3UW7=dbRVo*S&ytUBPX&Kz5{P&bx>?zN^7+&nkQqEb=)6B;qUVu6 zHgDsuRr3=*)!9L2H(kJK#U9AS#If5($Rwi@>CL-W<{=?0TVjM1Dwxo66}o+qR#MkOe7+Kc_3HJ# zz$FHTq#Y+UMru%?lr7^C(qv38Gkyd@3e91j-R>I%3oQblN|89bV~^4?wd%AHC;`xXq_&4+d9qqwpIFhgP;lX zmN9FTOWp(KOK&?KCb#TcWul?mr&go#!p6pC6G+;i%Z3ov>E@@KLA`W$wmRG}^c_6c z=u_HjY1LM(E;A?T8Gg~=Hu=?Y?zTT2@T4`%hkp=toAvLXD6DLvRpSSeU!<-?tnD#w z+pAxFcBAVy&;2xuF2l3vAhq<`7H)9?67D(H*;%-IjqJ~V4_nha-WW(Wb@1bOO(|I> zDWb^d5f})?`D9c+jC0qDlKN+Q5kddyX&;pAO11T;kjYBO=6?4y7!tjrq)yoT<$I`? zx@bYlxQr-{ZKY7%2WR6}10A6@Y72%l=NkKHWJ3NGo}#P)`OdntW1I!Q--L0O(<{ss zbOqRbVkTBa#@}1xgZ`p69M)3*Tp)CO80R+N zP2;}uvwl`9YX4tz-%qi_i9cc%9bfb2WpjNCqNZ|yyV3l9!Qm{UTl+$@*gIYHfYIe# zUKLiVWX?N8eRzFWz8pKtYshWR8Hjgvg5JE5&QJwi&f>CHJSe+9*xmiD@~61~AF==J zaPq$4;&#NnReKrfp5o^76G2nQ1I7}DlPaFDv%*3-)hZbevAp791&k+7N+4IWj^1QmaC`*yh%ym+|V#~FS z^Z;Gspr$pti;#D67#|*tYzQp@3F==IH zw8*)Ewkw&L&P?cd-2{OiJ?=*MvsYYOSa%X=9T5(PDCqp`ck^_`(Mu?N|P9?9v+Ai`?Vn4MMNFP?7B@R=(nMQK{v8Qeu(=vI4eLS+~_U&riUyRi) z;&RD3sL7D9)~ExlL!wDZD| z`NzOFli%D%NVka6a6@6V(pbx|o2d(?KEt5!iVP)085flHNMpCRRUhxN(bzb}EObKOXed_?vLL ze;&@`cX_Q(KwyB08z+`_GRVk(O)4Nm4jNOqm!^@obPq@_n6Xb&AJE`fYs#fNj z=*ehyb4tep0@0S8cno1pT@gLP3B6OE7(!;=>8K6(f+tMT;s@xuNPH&@_RL};+vwLw z)cUC>x5EBNHW6%rvgLdxIgy0w^6IjUeZ5g5x`p%5H)S;XD6h?qvYu}#d#9?q!~S&6Pd8F1tJi>THDMG;9f#hBH}FMM zp{pb)IZX8jg1kmvT60;l>LgS!SkD;A3#DLokK3!;>%J`+w20e0e7SfS;7X#(XEmK`qRSUFX*2?g0#t@Caj6o^%=@>6kNC#% z3@8I}+)v3Sln*}OsmWjIl!p0V+5EV-x@@`d);|Bk#V)Sh$ChaD>H%V$oSj=XET z<6$Y*85rI8&Yvb(-*D%d&T>SHiNmHJv_%8qS0im~v{;%0Fh2i(Jbh(YRDaYhB9cl- zNeu#0(w#$y14?(Nlt?!WEiuv}-7u7NcY|~c-JL_%&~@kk-uK=w^I@Jj=Q;DMv-VzV zuPuhw5zY)oCkbX(Lm+~OobQ4@(5NzTf-YLC z3X^lL-+JW1W72zny~)uk47b{wX>qXGD;lc?OU=0q6?dZ>m`qMMcy6jHAa;YE3`<c=F^^2EH1C0cNyJFQUYIN;MG?+VS}^oFM+6%_!*4krhK=;)gG! z-mm6VcWc`DTDfggvT?SVJVys!rOb=?fec%ohBT->6Ls2}7RCLDN&v85w zW{AjtQ@g>BjbShD9oiLDNMKBK2yj_&9C{bwE)QRF_j2A=SGuA};P2Ak>8tx8{SD=jKlA-cST zsqrhT-}4E{OFyI(hifnkF6Od+y!>Ia>i5v+7sBCpdotpEY)XBfR60o~P6X^}h`FIl ztd|6$t3Q6!q8JALc5?JMGw>c=72sr=D3eZ)AOF6E6{e-(Ck*w6NDRf~VO*WmZ+o(6 zm2#Wo9nj4`GrM;vbPPEn-$m=#-&vn~CF3j&R%%dD5iILl(6|=WlFzTgf)oaX>c|IA z`^>%$k~ICi+oFHt7I^p5_g3$jyi1^+;11!MqqWYHcbr^4*|5{UVDVwLyah~LYI)o> zR_|omP-CU1{oJbsskLw63j(Pk91JqpReZ$-Yr6%tM@M~uH! z$KO}(In{Q+v6bf&AQ$wwZ(Yr5kwE!uAygJ#379<2Tc}8lY`!IjdBu_{H%aKp5)S2N zVr59%OVq{$Fv>~c>LB{{HX2ASemS<3tC94`2l3o&*+PGI&n61@-bL5Bb?=IdJD`wO z9*xT|oR#nOCmbtg3KL(+DVh|nh7m8!84!A?A-?A<_eYz`_mvi~+z}@UQGVoleX>T` zk4+l0L!MnK3y2qiv*t%$s%3zOoi9>l30c0%G=%e7)z*M#!ZKP*FN;dMzde_!k2|Vj z5xk~yv&uTA8Xd!${nI0dntH&l+tS~g<)(@tDl!zSdxyG0t$Mc+_@dAIdOr{~)t!2R zVI{4p)_jO$v6r?gfXii!q(1Mc8UibfouJM+*QjdCNYA9bZiMcxK0mH@|M!vlYNbX4 z@j3FFejSPv7cgj`84AG?nvM2FNU2>>ia=wXYE}nF(`SR46~>)&k|nZv_k>m%JDX>T zfSLD8fx^IpyVElFR+goYAiRIAs)39-_+8V|? zD7x}TQX^(0K44SLtW^d@I8BVM|8ng@j9S>9z0klDe;iQiHuBpqcfFg8IsK0b;16}{ zi78-voRR2=)-s|6t%gKWjM!wff-SzDvKugdl4u?NAbG1&Ob3cu2ylHJ254gXsTwD8 z8)6kA#sFk)IVpao1iPjS)rhC<3sE$o-*-E)RqEnjvh%&@QvMR-GkB9W*izwOl~lPm z$az0l+%@>@rlyTF%gVFS{g$Ztg@vDxKTf{s@0a)-r(`)hQ}S14L$GgjKYA|y<%#Ry zcl^1CNC>K;5g!B)0n?@$z$5!N0Uhy=%;`C$aRXi8@WLT>3C1 z&VBN`J=^!DF>!Ys{wsDr58DSTYYORgr>;I&s3G*}ddBYF930^k`MJZ>AFCOjY z>TLBqmJg0!3k*Vc2aC&IThEkm4XX*XjY1DATV0HEzcp#@(hv&%8ABhq>ix|VnThIq zH<=mo{5bo(IJ~QjXhA+hABXp=;1r z#yPVN`m2>7j~rqY7U|+t{KJiu2`PI@wjTP*D?Wqv%8cG4W7D<1Qc0J0B3&i3OK*3| z4XAg@3G8D+A0vW=UB7xcXVqjMlHGj^H^&?59zUMe;D$#$Yjov)r)pp; zeI!FxYmg!eNaiArIbHXKE2Wp8i&;1d^aW!Cgn+XrGoSI_C|B%)_qY_#2_VEBL$}F<*M)Wk@+ox95SYD z?!c(pzJ>dB2zA2Q0I4i;d%qYHR83cqICDgS5d&ABM(b;=&IOQd!3y$R8d-yf71r@q z9+9XDABMsPebtXAc4K@qY$;|+fz-~D^p#XA!Rl-mZ5}Bp`l#moI^^fuF49lX$|&qx zRJ@+PIJ!(KsG{3cOjee>9W1A9(2}<+ET>!W+32fx7kw+!h!B}&L{a~xKvn+fadRHKp zkJHXGvOrtA(uA1EaM;URHi6}|V{$wkGMbE5KAPMw4Vhe)fP>19yw!Wjbk1EyrT`Sx zI}nh_C1@*p6=2bNdAWX$b-7L`ylzaNc(tvZx#Qrz`27~@5$n-0Om;Z^(r6QnxNNvk zsgT*lXPVEAlju{>n<7!ZZjaPUEhV+PSo9Yj*wn-oTP8g64*(xFXArDty4VS4tl=4S zNjjt0lXEekSn5}enNJ{yk0B_@(obFnKNGGHhmjwVC9!~~`o3-^_R0A`n(z0T&)axt z)^6N{wzmdi8+OG+RC z;xb+I{6irRBPg*P`vgTu`tST2IPrOI7XJ3wtQwbwzkUU=HXpyhWd-LZosAqByBzLa z9NGIUj+Tn&@xhp^3@?kcf(6=dN7fgt%csAhUntywH_jNlVwFV6GQ5r(PY&qv;^+%7@-$VHir@0#6`jb@1-p06mbJ~rBE}A z(%|lNOyFNe|4cLh+fw%u?+?7jvj2+AuxKFgqo6VrfM%%W7%Ld63Zrnk?Ret+>ysMw zc-&ZVQfT>Uwr$zusIc2a5|%uc<6T?ooRmk{+{CWIZ+V zRUfx7yDU3syb~=TRCjS@`x8G$%j`28M#nB$tD%hm%_NYee_PKU5U<&jt3eo--wZ5# zq1NDTK7ZPO!}Rzy5M_|U1Dgbx478 zueYbQjHp(guIiKNanXiwXK-pW$arRr#IFuc=S-u6jULan*0tL2;*YqWaH%YxQWgzO z6NGJ)i7)PB+V1e?3YqPF4)nV3SD&98dWeNJ4P3LptVfc8Q5R9BcyFG5qk{+;9p@+5 zn89;NNHy?-ncX;#*+mV}K$Acoo-bNdyr`)L)R9SEz#VE9o zLQVc)y-*x2WN+x)_tSd^GSII{b`P1G9w>yn`jn5f3zc?_uh5N+%dj}V-zzd}Pipx!L!RzB< z*7D{9N`|55785imO6!Ac;NHJ*X3v4#oGN0!J=lh~DJdD9SjJnw}> z)C2n6VHvDcvb1TtCk+wVgcpmHAf>d~*M(ef0y%|7%wWerH{G`kmiq0U`vU9C21t=M zHc)u^2eQ#y(`ABQ#COtzITuBd#=D~8ZVfFX;;X}X!mHzX3cOHRZ#!OLjhKhy!-xEoU6sx&j!i}PD!*e(--_!$_V4+EfSy# z()<~~w!D#B@i83mexrXh%d}q+fAu@?%dX=xtSZ8gic-C2FAjocfnHv+vT{bQg82PG zL9cj^Z(W<^8`%sw<}V9{SE&=n_@HQ3RFx~H{H6>CS*XXK$OC1It2At$CZ&)z9$@ya zixDOU9;C6^Jy;F{H+ZsO6yhx0Xz#X~%vpS5laxJqbEw-WJgnWyKfKt+%-UulmsIa* zi-}{VDsFVosQ(89%PZs5lS!?j#-CQZ<`Iw@q;#I=F1hK*@_*ZZKw9cv;+uOF1~z*L z>YZFW_x(n*7F(q{&Qs}d5;rlyg{I5=5&WAufz60Sz_ctIPG%QDc5G14QBY#}3Uy3Y zWjqiR%>veL>ZxKY0S_0o7>{ov)_m!A&&wuhexDPx_i+#d)1&5Rrp5CJcd-hgeTvkh zL_j95eB^bVH0d0?FCUUwk58{yOIh1s7ALlQ3Aj<`K(Ni;%;Po0YsERb)3;0!r`(Bs zvsp=VK(y_nT{v}0IXqkC{ij*_Qc1w?;E{DHh!`o9?7m9ndvfguQ{3({+iwT>aX&n)`k7#-$1+9*U+j*OuNfyWK^o># zA=b!xyE;!EO-W44UUfqHXm`r%@GoVr+&7%SNz7oRv~l%8p~@wEB+0yxmmH*2$}Nq3 zafcf^YqLSE+JT1tfhtgyN+3rAA#WTx1notAF@A^-!iyNIXCL!YJB5F7{_?4OBVK3H zI1S=tzLRHnbTCPUE~F4Wt+PzpCC}{6PBr0pz(I-m*o+tCaO{zkZN1a0V6u}xvfyQD zmDKpn5w6=TIIP?LVOYOTJLI!IPR)^1;+$4uoTy~ter&uPAv1?Nb2|80s<1o0K(bK2 zOEi9^=lbgxPm!ROJnLa>~-bb)7npLd2!gqQNM4G50_u)z;v`@e^$_vo| zg*1qTN|ZUzk3N3=A+2MB^M1`c7oHfFL4x8HW|lk=b`hjL?yM|R+zf)bjkv3UqWdyw zv;Nvif0WZ|CtFlw=o4uH5(b*6lB9B7BL<-|1$LEWJYgC4;&&1rFs~KUd#lQ4hxjxl z>86U(qKmbhnm%CqwmtN@^g#;*$m1)6aF`d0*F`UuhZ^lx9 zzoSBN)(Vi?5PpEPz&rd=y(tCqpam}-g+9esKZdbX2HkrXQv~Dgn@-EecB%~`Rl+~9Cm!Ri|og{aKRN&G)PzU1 zX`=QuDzj2Rc^nCl?WL=X1BQy>A7XdHGP*2=rA;+nf_A$aN<8yc@3l9@D$edz$JJD2ftZ4kYa+0ZAHm93 zHmhyRWyo*w{&WY?gaJW>4P+nnp5M%D9*f>ZpMl?(S( zo=oF*&oDr_2kJW%$e&lSjQsiCVUSjEgNJ3J#itw9&ZH{Ho5&aMu&K3Hm`JyMh0 z5YB>jN}gWk6QV$2o>vpO6{}i?b;T}En_hcncKGx+E8_gk>i%);@I!rk^Gu|4ezK}f zx*qF{#36cSx5|LYu>t?j$KRjWGsw^ne=6t$;xvOf@&aG3I~n=C6P>0)SIoreQ=+P} zj#sqOE48jm_&)Oco2T@wO?pvYWP)qZ-P-HrgDx`hPvg!)i=6#;hIvbO?lmCS4o_h0 zP7mpPd3!lFD>VZVYL`MaF_8W_S^0Hc3+Jho>B&1{V7Erav4@yG^nAI2hLd&a;Ou}v zwp4gas>bPjYM{dY#E=;bKK#d)a1)seKcfvP&6N507!@EP%#eG1R0MbI5T&&Tv(G!4 zZ#USRTax9<51l-=-Ww*g?8*BQ0NSuw_>Hq| z4V_PPRL)^5K5n|;J6wSHJAS(*e15wHrZ+8$>zmq$A>HS^kywRLwDR%o9+p(wv+P43eE)!SBBfazGw#3lv(h1|r{kdRIu8zzof{la&ve11e)!gMb2JF`MJW zOK?5^=|5SYLNN(xQ1n%RTFb`SzN>lj-mhHdu^pmJv6Y6C5f)+~Zs-KZrw*%Et5${T z2%_w%F3T-n_Y|VJrxxApAm}c#tfAQf0k7QiY60ihJDzUE)~Sbfx3YMg-=OC96z0|l zDz14-gY5~q(5HFrRIvWE%8SUo1-4&401cm@y>A><5XRYCVSt&vNUiZr*S{*cuRNE3 zX$jcL#$9sn$DI;Y7CEo@Vl9lx<)m`C%Q_E%8St4l0I%$&7tb_4!O`H{;o_|J56Mib z_y&LeSV)8cSf6nZ(8{_YxIrU&^>cjgQ3>BoJWa_zz|`8FOob}7t7)o?qhqIPS4uf9 zimuyUXS!etD!o`8(L~6DHwUqK-=L0RB}TU9s3Ukw-(vY=?G(yzWRAW^B(tl$*&K<-rjpAtVt zWNPQaF$&ILHQcNtln9KUyfm8=B!}x=9eHERlcZ7mL;Eq0_gynAbr812dWffRQ=Gmk zKX;($+XWtgGVkcu6&6q1*)M4e%tK>XKm9M_Qo;Z}0hxSW2_^0P`@DG?>u*!N59AbU zIOAVwZ+NFUh6pr@sZb#g$QV+)4l8kTq+Ms#W&ON zU=;g6xJ|?n`4K$9n?CnYHHw9X?Gj0!HGgi-`|XbE6Mj{^4L&{oAejLx>Cs91_kt^` z8Ll{)8pq|Cqeb~~9`~rL-GMO2OqpgSI7f6`4T5HDKDJ&icpTyku>61dyeE~z_pe^2+GyEjoH%K2EUyXx_ z&aC~Oems73dJTuJyT2IBf}R6`PeW&~qSCpOg^}4!@4Z)uhIyB&GJJl=sYY-Gcl#Cp-i04QCaV5z1N%>$Yc2iN4k} zYc)SlDv+SMG}v=_iH|)lETd`6DwA}@Dx_GYRB)wJlqw9cnp2=7S1)=Z?Oh&y@0sF= z$>a$*a*9LGv1<4_T_J-RWpfnN(jQp+;XAdk2NR{ROMjeb zBa|_R$6RL&0Tf>QQif)j46zBkk|Vj_+}gkZZW}g)e&32S?$qY6mTS}ExE5Dn_WRZ z?~(q`-*Qp^2o6(D$=XGRACmrdj$Bp+vf3=kJfRfQ(0FvnI*cA7>t0 z%=4g(7$8p`Ura%t#*&S;UHy+>%C~t&LH?6r(c&%0*#I#qj5!k$0i%?5u?W?jS@LiD zij~ZcQneH4I(=Z|xw*eOQ!J}k!7YGeFRBr0h`(yQl8ERB=OQBNr%Rs(wfc#hqp`Ru z+!2WXq~EJq{0IhQXX%jLRvpBbX`ZoYXaOVTKd21pj3^T_)&hZhB4T~YEf%8R3L|Fo z#6j=Z8eXk7A=4(B!0HP4e2Y+tL4935w9m>ROd`jomlK~;%tX}OC6!C-W|A{Gv7CVt zb;W(Tyhvj3x!5q`0j2Fg2XO-c9>TiMOP%&+`cDrL@0fjrI2=|NHUIxV#crEaEkris zvih09$KGIm?ZI!V=qMz~SN{z;%jicnYI&Gh|IO8?8Qb!?a6{${*EgpxUv|-NKCoH` zZ04&YT-aq(RW4|cL<}1E@L>A?Cfna#Y>$bLm5(HObw^yf$r+D1W^bo;X zVqhlb^~$~P(E;bsmD`s|t)t6qQq3p^GDAa+B@;jk?(uAdFfL7=g>NhYoUkI-2BKjA zf=$qy;8tYL^ZjUG=!vVh#SQpxSaQX#0nx}ijZe~nqV0QaNPvrZaFe}+$pv+|fNfNB zU9n-9*ZL|k&~h{jE<}jbv%AV^*V`GygQ6!B?iIakXWObiDFpgo5cOt`Q6_=BEiS@^P#%fPMJA zE#3pOvSb0_HPw|XF;L3}&v|#abb~m<0^8s8JT=QPTOA=UM&4`i@vL;fM6se(kT87K1!LB3;up#|}$Uk|ow;BASiVg+Z9K6?VxsLW|pPusI>rK#(_bVlj?u z2Ret#{@R=(8mCcS><6WUrPxQO{EF%&KHyHNNv9O(3l*m5syi9)cFd!wHQE0|uZ@&a z=M0cJHmas6Xf9rWl~iB(cdD03RoaR=dx{5e_2uaayM}L0`|QnJeIJjtufQ?D(%f{q zY;xjS1fTV4cqDtU;&bW}h&zH{^E{TePQ7Sv469rz!ZI%FGNlz+Oqu`6^U%Lv3qzW; zMTO+ZL?@TIo$^O;K1x}u zTH}cV>YmU>@F|WD=^;@jVv4OAZlyjRiy2_p`~9JXo$oF2fgzpjBF6L&>Z6TMV>=6v zgLX)kG!K~tUufWBO@LauLE*{6(j<<`-Wk7|h)o2i57v&HGq0S_mi)Lfnq1*)lD56x zoOZn}1_gGZhOBL9&VjQ`Xm`4T>Y=qibH2^4s_*y#RPSQZUT8IlDD8=@QjKPaF@j)) z4zi@!_eeXEkV}eOcz|VK^IN~zpwa<0{#_PwFYP8*d07BE_u;9`t4K$C)_63n|X)M%c;HGa^Uk+!%!JyBmuUtiq1%mZIMwT!06cxMJwud z5T5FU(-BuqTOu7Wf-e`(_7@@=k=t2_dvTo)KuLVT)YWz)no+f%M^%V>Il;%%Lb$)y zVEhSv^;m3`a5PzwqSrLy^5Ry*HQzlGm;Jes-?6=1 zc!qx(ul{OL7EX#}e)461U<^i z0TBvr*vu^Vus%q0r|8{16NT*j<%CzO=nxWN3Uu4o;EpgA8v@cbAyDWp(iziYI`G^w zTygmu&knNLO|pOdx%~jDlOpgkOC`iz3@xpGxWb$$FcG8H=HR>C_{&xfqqbpI@XkoN zHX`>ZVJ=B5;ra;ug-rB)PN@;?Y~BME2o~^&F^rmq%<^jq>MloVwYvzN$Ca?c|B{@P z5c4nW$Dc8hqAC&|t5LLHM<EUEEpTM#FiERBW+%q0_N%MQc2dso`_79nHqIRRY>?N~bmJPI~ zSweDtaL=1{NcXPzv!@zj$$iylefhd&aRv@c7pNBw|BP8d+OxYqx2=Z$q7O2suU|zk zZ7DAwdx30bxxbJj>FAjc*I}jc-oOCKB+O1{%K3exL3wC29%GIL{N_`tj}zS;O;-~K z5-6q#64co&S_}e)p{d#MuZ}0?1t!cN_Ja!?2k%3JB~-?{rH3s?t7KsEgblML288Um z`cr(rwMxEN-iDuB3`%y~vkLb8P`6>Aj6uc)c=s0$C>`7iqned6FmEKlcZs;(PBIFT zy%%kE>U*@9lD`SDLnhBZm(FfS4~{5eFLVRZ-i+&hEt76~|IoOT8O zi?;!&AdhVrt~ZbEXdt4scqRTVGtTX(5*Uo*&ndBqS{ZKCn=U;vnJu1M%Q1rv6f~IF5GWIl2QI`c?-zZyS2a7EYl}La{CrW z;ugby{}q-QSZAuHd_B?A`|-GRFio>j;@@yLA8{~ZHkI8pJV$+ZkI{8|vFoaTHSh4y za5XLH#(UUsuF+KXI!)O@h@hr#dW}4^P^m<1L4Xnc$;!28UDY#oBCu}&qfWLaf64Qy zXLunSw{A(3f+GiC)LGcB*L#2JD-t$>yb#9Yfn8%nz#>l0!F3`EWgE>~(fIdSz7ayA zvgz|SZiTz1eNn+VO%6PWVM9k2t#a%O^Knxn_}-3AeS1kw%o8$`kRW->bBq5jfsOI8 zwJ87e`dtUNk{OX1p~FZJ3X23Q7#S7XaGQ#{S{FuX8hs}Lj;ZIq8UGz`q(Hr8V8Std zQdFcO=7NSsTPiprA^553X`N*(N)J(@-}uR^80+Lv6bT@%y6 zZ%d&mY7p%9OKi}MPJ1u|CAp3!3lWX zkt`ATwU>&mu9Vh;w;gxdQ_b*f2p!3$l#Zh(iMZ)oA;IF@=k6TsW3zbb1A@J5O)7nY zolDzvaZlG@M`dx*Pz-B832zi7u%!G{rfXWnJtSSEypj<6;Q(?yi!4!TO5&uZZ~2@Q z9Vo*yRFtXpilj%782ro80FjI+CJLmF?W*H(9N-O||Wf z_+u%d3CwqxA=O^`{LRt(ltV2V19c{vevON!deb_7o@*Rq5Wuj1`kQ_zAtb(7GvpNx zNsx{z`RJ4k#)OXU0Ls6MHuF!L9v{{7)3q@%O&;FtoxWY`EcfjZ|0fmXegi}}Ae|!A zaJ!Y>Icp!c+vwD}$nk!YtN&G8OrSNPNT>YcS#Xr_FS8(Di^Wq}VvhXKo{xyzVZ}%i zP%*_0s!L|IX#P{S5MYSKe4_gzAX_kc6KkdisH@_1tnV)9y`?PZwB>+Y{8}Me2A3Zr zk-4ESnl!dsWTk&~Tr-$~^6JUcd=6riQhi#GY*hncL!-F!r#~L|-FV{P7V9X*9YvR( zJ7lUGpKTUJTW17K_?&~4D$fZK$k3Gh6)$gAaRLa|_w>mNfh?@B?eg~&z+FcH;Zbz$ z_jaW`nl^qsnb|UIu8TQUKvZImlm)u-ofvc|yucj2>R}Ds6hm$)7%RBWX8A1%n=TPc zF`N)55=}Z*$4xV`-=&oHYfqIP8n(X`3gE6uhbC4BgJtnP@F6^rJ>^?MIW=YJD8YgD zg?=a~x^1*MYZ<#inY3I9SI=RsCLN>hIG;dY+b`RwCu$aPSL;Pp0hf$dB66Ubi9tFj1sQ*$XnjA2_PToUBZuB5|UN})_VN( ze{JP&C{+-D{d(-|(=6^#>_67Ti5Xch1-0wl3x0rB{R`phxeaC`OW5#`pr%ZaC2Q~) z_*Q+>yT2G0bh?bL|5fA-O5scByE>kx7X>k8h++t^d9y9nE)TbK&a0LsYMgLZqQFKL zA?&fYCxXZFNFpKe?@!mlHWRBG*xY7}P3M)+E4j$m;)nUIp`VI4B7QiK;lC((Dgb<_ z9iPZA85;ou08661|I_htc(3EQ5uF%4Z5xGLx1F>)(i&5-eiJ_V%O>Sw_$d#{)>b@L zvC7wu8=vO$v`16vD1%FlCF9Db)ARwE3eaS@z$wyQejwK{UtPhw{9Z~PRBGF8Hq$v6 zMI=ET!Zm4$_iYEfmX-d!vycRdrX(f3^gCotxMBoPWec{w-udd1M#qNaIre#-+>%~= z9l8*-(&l>d$N)Zn1AN3=iTcWJG^D))=|M-GMDlIJsxO7l&pLVoz5%u`;({g22x2^z zR0|Tf7n^RH1eltV1?&yA-$bFcE7D zx33^>6_jxU^QsCiLaRWNoPgwn1ZP4(fB-r3&HSf$^1-%S-(XgXnEyuZf} zD1kNz`P33Q#iX!ot7uD)v9Sq^cyH{Zn5`d)`)%z85Y|WU`zInbt=;Peey3%BJFXu+ zP2)etvx;f0$j=!R!V6#iAU(X8JvA%sv6$#TXH#6hJG2z1!2KTifzhsYo6SD-lcDVH zrwSgBX%g7-XO6E;mxTTX{;!|?nWe=O=0s~IJ-i8=<;!vH+2zJGJ;FEDmZLvDxk;m5 zJydw?ZRp49S}Swoqt2x?RCJIxpip%eSP`v7JxgyUp7r7d#Nqmj6M7_QX9)VzmW-+N zv((^bsMW(^R!e7zqP!5A8^~|DSvUNOfn*OHih_)3q&h3ermETF4BDUBNpU!rh+h{5FF*f3|12Y8?yM8-)_g*FtE zZjy_lbdqY(N)PzfFgy2?UMc#@*-U8m=c^0bYP+0J^a#{aetO_LpTKu(<9m-?e}{VU zYCkN(2AGd?8ID*fEN&S$ac2UgWq8|MCP`3xPkQXLUd8>ZcnYwwf_n}yFYk_8ufv!%txzD4_dI~#iO1TnRjKZhchR<9f|27Z{};+7IsnkZ(t6;wyi#EOcoQ~ilxSo?m|iSqug%*$cJ zVVF!mpz_wsSR+Q|piYb`>^O&PsO-r0*0DM62mF+FQU!&Fa|$5%Sz%y}V}CvFc#__#kkOtGiay z(|Sh6#^t(el~%sFnTD6=&8TF$8GPXziKpW`7O}hgF#IaE3YVaa5FMkJCQ?${>YZKi zEM+~yu5~vVsHfel;gY~Wv8zHvuu9cXOFu}~>M3Ytg^DD2Xfs0-GLwZ!#7EjdT8dux~N)x&B=j;BnlzYjc3FdC~Ihb0Q!#zC+m2 zl%!<-E0eb)9yzyJ7=?n@CLNMaqBAczw`Kg!zTcc{wNYkxY=l-g^~l<0)C~vuL~ZvF zP-hR%$YWoW)tKzsotvG~vcvxIpqE>&fVPz*HgEC!f`i^M?!;1*t(O?(aySdzGsA6*hEm0)B-T|YTR zK|jiqOI#q;yul@*WcT*cbs)R-%7=fwQHn_v^oa>^zZrEG6<6x!G4~|TV1``huBSI6 zr}%AYP~hf(C-%_&Tu$F!08s1UU#VQ+VGRED#n-c~8(KX6PknDbvR}IGdbNHQ{wt44 z7b%^#*yaa)>0W7PFvu8XkdZmbXRdLB=%W$ha@eLasUTjbxzwgN}N3-lY> zzDDnfyjJd{xHFa02-fIzHf`$ae;kHLb)I>Fr@HLlB~PFn_*a!dLHCQ{pK7PRDl%qL z90)ab#qZ7;sHF}+@u>4ECi5Zk!AGcjUam7tx^7QuE#2<5Q=0&2V_VH?O3k8GEHhL6z^#|5{rFCpOUd zOFJ1Va)5ViYawOvr)uI4Sf|C5;= zH$37}@M3(hktD@rSt(DM=PqD5=OrlR54W<2F*kf8fujE|8edGAM2aO1>SFx-f-2RA zH%-`ckVv$C$w{tZzo^(oh*Yj=?Vx9%`67k(acV=rur_9ez`o`-lK#!*7c1VBH36x~rbp;Gx`_$_*EhNIhBni8E>*;!eI^IFCvhPzA3n^fF})2rE>*+Mjo1zE4Gcy&iSpxD(x zUzce#kYuJzhoUS-zFC)Xus1rX`psuCi|nyWLY^2shCwobdfK>{0YmD6ycrckQR$Jo zVoh%Zb?|SsHLhi0{h&NwG2GT2zH+Sky-%UT1InkiBcCE?zRMj-9ZeNomEbs#<7%>Z zH^W*kqD1WQkXY3 zSWH*K^j^EJd1})UySAv=D0M0%9c2OSFCVXNxjFAZM_ z(j`SiEeyNKU$!K*z*0qEC7e+JAi3Mgime=*j-BU8>vf2D+jX=p?ds&BDMN*$&S&S~ z{6Crtse@~&rj5m5ZjDMmAN~Ap$L(Xe@1ObJ9iLx0w;5|+$diy@#uUHn~nYNBn{w3zNJKq|fCQQ)N?b z$W}LX?I_Y<=|0~cDy24^4rIB)@ykD%0^0|$JuxHM7k?@&(fsSnj6G$_zQqE*KV@SB zRotINoJ>YlE9!=c4;HF^E--EWCoOl|m@lngAz!&(x&G?k#K5ZE@P74mu{q}e8h4*9 zML=$eEb0sN&q0i6R{VlX&F=O$Gxcr6ZI?&(A^)L0w@TJNR`5HbqXVlyl7x0ZrR&t+ z=E)#J8kFd@pNjZ(?k5S*UH9?*gGS3t0ni%t<2ZHj^ON|K7eDg>>=qn4$v_Josdf?$ zD0shSQujEf6&LsczwOv+j{q=pVHtw34e6xUud|M6j0 zoEix>HK~q&$~RZb=F_t$pyl#4rAqWSP0Vh`7ZOWSm{++^Klc)|D@@9Q|)R(=MRO( zhh1q8R1>D#@Fm8bkB1v8>{p*oqn~g5y2T$S#X~T}?j&yDePTb1Ru}7c%tsi=QJax! z|3hb3$f_99-r`@Z(md%c-oqJ2*U9SRJ)uE-RSSPehfuo9x3G*%O;)g>^P+W^-@W~_ z!H_e5jpN8rkpdCg?+*lw)c4cnUE+_M;=zyiSHS|UdkWka?Q}LvHI=!sp`Siu#H$U~ zPz9BIE%``IE(ml(N{Z`>)(?!H!41z(_uVg%0yoWaLn?u9c4dxtAL{B_!*>Fsj`o=H zeAJH_@2v{=LBUbt&Eheo{}F>V2A!L}VL`ekEdoKcIt5{_k+Q`#Z_?fEcX*Qdh>W;t zTLNwi#4Za@wfru%)<SPy8U^ zCrfX(0O?X{mzUQx%uDZX-^ zP+`&?f-hi7qO@+WO|sTvI`_qsY+J!g^8FFAXRibuw9~ZxAzqC0A(j<xkuv8YFa`8w@NFeM%|;<4>b-8GBG#I4mI?3mb+ADhE8tQ zL@T4~h1p>7=L@FE|7syiUj2d?7yC8J!zrE5h}(!R)T9ZHzD5BoJ%qoDMKWl7&slW) zW2J(i1bXwfJe&`${}($SZgg)OJ@gm_#p_BF;hmchS~zHTW)6wiqRm8=V?QGEwQ}3P z-!v@cRd9q%gLfTuw~=wd>#CLHWe(I9O+l01pzs*RgXFXK6hsWg*dwg7j2bh^A8aOL zl9C=T3!WB;fbK0+B?EKl`FlG)GNJhrCf{^Aa`74z> zGnZoqfyVViCraKlXd?kZ+MH7GCSx=eki>BQQWmK^e*(=4bUogkpZTNrn#(2Zs}q%4 zlHdwGvYSuj6e|4l3PZe}wHo`*&AM3!K*h@3Qjbm6ZMxjR;Rs>O^pKU!SpAW+Tu>|C z_4Aa`?~XAa-k7VPcI#v+OEW&>ku>14`KnaL!dlK>eC{p9rDejc>$MAn`tej|ebpCX z?}==`dsVy6)_$#NTi1+C2jz__IkqP|uH_o`tylfsF{P+7yV5W{Pvzy?Jr$0-}u4{#QYuPZCVt@65_Azk(OS zX0_jfcFbR&lFQI2Ka`D+^k(Gsd$tsr{-8^UYm;2-9=-k%rzAc zIeVx1#E*r#k45%;<*R{cg^_fpst1Hr{r5geq9i+>{b_h+aMq}q5{jFnc%)rE-bFLm zAEVL;?VFMOVT|B1%!z9`d(kJVtu%!0f%v!jWxg(I_1s9AOs_o^4HRgVWd}i_4WUj*R zDMHo-|0k9SP?XP)hg!~8ncpHC+cdg)^EnHLH-6UrRg;FpHC!15h#+jXB4}|S|sx5AOfla!t*Dh6Q}&D7ROAOs4JUR z5?iRJE~t)suIWg|{$V1~*vovn?nk2D_rFecPbNH$99FShZHN?IKJ@->=uAQf@heW} z4$tx|X8kRv7Wh9*ePvJ^T-R-Z7B5oVf)#fu9w_coC|ZhBptu!>LU4C?Ew05qxCM6) zS{#Dgm*<_iGxtaSWRl5DlC#g=YcE-IN$`0#VsOz$FEUjw3_i%ZZ z0EkPU+dI+|KO!rhZ9;1RYpX%5G(=-LBc$jXqbDKjA4X5LONZqThHV9PB{cXkjeqHE zBMD6s$Z{?MFHjbWW}XC=3F+X}uv`>Y#f{7PCaDMj+HzqnM-7}?G z#)A}e_z;P_=$2^$_12BdEa^4CC2)_ zarVYQJk9hdt&({&EF-i!)#7@gEOd}@PFSUbpx*+UhWh@uzo2^55gUabvVg9W#BNTUj6j z_`t+^{r(~5u&`9j)-a)Zp*89#z#pd+=H3WQ#LJf1!HRN!U-??RF0LV`1=0 z3DzbM=#`{BoOTLdA~^c$Z79l*?k|w?xvu6ywtbuOWs9;mrHdx*CYY?ZZT-5c#(7^w zxHIhpb$f91r(oe!JZTg^`TC5=w7c&H>h~g##M>zG+_J8)uJf_dZ-X%uO+E~MFj^mn zyC%vYZ0}8^EhN87|NlxK3P){@{*GdFPMJ3;OKapOWK@B6pw)#(p@ZKBdKVmG{{53} zK$E3HW?CLQJ=BvBt$E3u@QR=oYbP!zMAr94Zn4$Yy7}a0r5Db4P#We@3~;YM zQpe8g7b47=acL(z^&xd*URA}%`c2?Kp$=%Ek;YD_g404*y6@n6J9z(R@cMA>`CYN0 z1P{;KSf)jantA&VskYTRbNGjQk^snIuql!R%Ij}!cFQ-$k9}cyTjyKgt?m~jp(5LA zUF_a(RUJ2ac-b`v#!S&C##2UZAxBr>4r|Uw?qvZgwY6%~oT{Yng$Zy2nJI;?|`cF)#n2J?XqMBO7L$VzNp5&K38Y0WX>K6xhOtZ z%F;dJudxORZD;E%xF4pc*Lf2y%S zCuOQwbrf*q!!VntBfFd)Ty$$11a_bP56_w`m!ACF`|o4U?55UyJz)=DTYDKdF{ZKp zQf_F>(so2Er{-#-&o`YqvoKp<-K461;@k?EQ8MLKLTxXJI(t6gY`F`%pYqC;CB2CJ z`M^$^2D;h}mCM=k-_f^rfp#}WX_ZC9N~^WR5mj87o-L;dd>s&OmJYsAC!ftZQ-c>TZ3N)IvzZSI1Z~j1mb+Sww!Odut;JiX~UuWIbNcf zKxe*+Z%q^UB8qVPkr#)|*??Ul_VJiU*pho@%Pz}7m@!b%si*a4A^D@mQiCUMZ!^?4S9%Tc+xhd4 zycTyDF1^L0sWP|U5Aak#fhR@9I3GK9{gtX7WwI7}o_W7l*1&u`HuO*h0J6QHK`_H< zZep)bhmT(GT#7c%JBUb>c%&*|!!Z6wA-9a@nMcw~-{&{ph3*yCne%<;48G!|C3w9P z*+4QZN+EJjPfwfe=zchokMXgImC6aQa77cfTlD71(^U>U;{~y3_tk4$2oafiyh!Gv zm@a8{T=am8=>koY-|~2f`Mr1xEcl3y#pwsoVT<%*q2s8g$?aeFl~fsQG+FcclXtyq;E+S?@BNY5%XrUBLPLfeqfj_ z)!M)2tmYZNtl56%RL=fTEraxGvWoxXdfmevpnV59qX<~?&TIxy<|yNkFxKvf$I^T! z9ZXob?7+MYgWlfxo>_IQdO`pO52m2s;5JkXY*ptAbB{9_b5Lq{<>bLW}**`X|$ZH0jWPEeD8{6kN^SDOjDqa(5h;<@uH9zUwvaCj@(t{Po5jO+tDH#)b^~Tta5tjf=!+ z-pU|}h1jRlv;Dqphhh)%z)Z;gF|Xe4P_JGpIQ;X_b5FN&GCax(X~~h|uxCI(41RoD z{WXu!j(p=3ui70_9}*|)iQAQ}IC=%^QwARuv4Jy?{P9n-O>tiUCB#?|hOv!=Y>NTX z3VB=5*ZzwHhgef}*;Sar#*%yd6vKUq`PcqYfQ+Xhi!!MUFr59p;#tH+@s%^~X?H1c zaxY3}LKl&Nvgj1R$Xm_`vo|he7kpVYMsT&;GIDQ9Cx3lp;@xrWi8;*Tp`9duqsHP} z>8?SINi3K-u#$~$*Do^TrWFmXSIGlxTz=925{aYN!!#^{b=!XlZ{@ZN*_AVboyAt$ zOjb*u^aHcN{m;KFz2L_Jg)kfyAgg7rF8;=STJRDJ5u#2!FO2ES=pkUThAheCHQgK? zF}t5V+>tT+*rtWBa&+RWrvk4U&tF^Ih}*=}+rk~>X9zat#v>4_7`x3tYekB44WLO| zLLg=sTBW1vlGS~`1xG>Z1X!6-l|>h)ar)_!*XrrAlN$AnYzU=qI1i+I3!8z7;_QLTfbn)4tzGGgE%%@Uu5HQj8W_3vsO>Q1_zQgw~v(Cj78^wd%vM220j{A}(MCwvgZ zg7HDCK1QRHNFTsc!as7(;&-I`!$qNafv3`t)S!LegSRTx{vmTch8}YGp^4B=WXy=l z8+|lCI1+H@UW%PG8Pmm|9&ZxjPK_b6z8fw=H%)WNd3QcKLhTn6mv|=w8gUnKFE8_} zFnCA3|E{@;;%AbxMKSC})l>1M#vz7$$R;K8}W(1_k ziE?I|XYSXHQ8CG7PMeVQ6{H~owXrnrnYu~CJg7P-!>Q!w=4z(U-n54g1G$!*7UZ<6 zsUNc<`X)$N#_$G)gTTyx2*LF!rcb4FX%WW#`&@)`T*EXfu`aT|{u)VoVz{|r;ku9z z4+}p`zD3js@MR%3MuCetD9Ao56KfYMD8BU9SqG&ARFDF0G{vj3f3G`PoY9FY-xmIH z?|b4n-0k0uoGW?nuK@0FXLzJNv`SH|!FB$n|3q_;=2U&Hf;m1}IJX6RL zGvJL9LZO4G5Y>@TRJXm{s55zni3u3HNnf5E_}*2QBBYa;R6QcQn2hZWNY8;7y^@r= zH{{A=pQziuS>z<^f^Zil$B2Zovnn6N=ad}~$+Ai_7%K~R)nBlV2=Q7r(fvEZF~F1~ zzN99iO#k06X(rLdDjf2ghZwoEJz-MYNYBLVZs0hc!$N5QndEI$-o?AWy_is{(a-5j zo{8D+Oh}`nW7b@)WYr~)**OcQE-lJgi&!CBdOMEfzu=l=ijVHjnep?gBijI$YTe~> zvu}I#Hs3fX7dYmoiJyyj@t*_ zKnZee=M5-awkbYp7ern0Zer?! zvw7S<4AdJE${LFTs5hK)Mu^AEF<;+3k*ZFiC|mkppm-`JfhOaxa1z7&6i0&$ST`!{ zUaA&VA__j=Mx2fA-voVzcYKDcN^R*qMo#qcoIJhbf|4Utrb<(tzUQJ?F4@`gqG#jF zl4IkkDZOPQYGop4tPmL>N66i3$^Cg|r#&yE6rUq#P-i6xL#>zXHkkobz#VyyM|d2e zgYQliTfrN|qr<%^j-nzVgROp(I?Xwng2{3}=!G%*q3F(~eb3myfHtadyU3d4Z6r6h zK9;szIGEWpEYL_kk0a0yuaVn-nchi7F8tlU?`U7kML0_C*h{juBQ8C*si=1RO}nN8 zDD1blgUzzThzR^1YGQHU;|W^6T{lHHt7nZ=Y>XsKD&3cU3DnIFwD7>QtJ-;w6()bx zQ`?4b4@kaBiL?uaHuSVnKZ&2w+REYD6!uABrBA(8;niS8O0V%AGW7G%t4@A2puV@t zdIof*HZfcXyhP>)JwEpR%c=09NiSM=ua0D z6`i57qy^Z!rjM#4)!q)F-eAXr9dtI=dlY5vJgoLYy;jPA8J+JY(Z@1)Zab?&Lcw64 z*(f=O&w$Mh$G26E^f5o6n2wn##2sedeP{9+LYKd*Q`J%RK1{gt9nD0pN6HYW0M3(E zbv2nuJjvD|(8Gblp=a24kB#;J{1Q&0at^<@p}&SXFp7e4Jiw|CSTYu4_GZ$mW6dpH zf|7Q2jT-DtE}R!VVDPzZ{P^dj@4=?$nY2JjAHLLG-rU>5CJ`x=Y=-+qEFXcKy z{W$a^YnJj(pP_)V)x@ehdEHblt|pwuu=rNRa8w{+e5gV1mY4fVjWRm}gOr=GW z*V^_Q_N-R-JGvC1gy5&|GV}M)hF1A4?5Z`viEA4N#lz3WSk{X9orb$Z8sdWOm6%^7 zsWU~IO@2;MjZgt;p$4;o0AIwcLdEXL7b#HjXSqu7pWjIunh6is1!3RBQmpO=9PI^u zk()KYquN9z{{S(=+?w+6zlu+^a}r|uJTp=%&J%3GJt@4c2ADXU75k+p5+NfMVR8Ze zzPm8$)^%CjZtaE&mrDK`oOG!&Bww=O3`F=o(iwbxbG;l~T09nK)c3+#|3h&x8^|!0 zCA<*L`H5OTa=bHKen^4jd$~9|Eo+*wsam7B!WRv9u0?6_rBhbgd8(_V?R=%Lw%7!$ zu7O_Lr!EU=20#l*Zhe?A$ofvs3%5I+=C0}UPp59&kPjqw0 zsF!S-Ae@tFE->y`&dV3(Oln)$vP88kH_NR8#rdsp*ChZC!$CntK9)0W>aLOJ>rHeR znHtdlHC7uf6dmBuc$R_>6s6{W@#kcFGHn0z#N7(Id4iE&rt!OF@9w&6!IVxk(pA1e z;TPhi?>5yN6_oDMDhwj_#bLQgbfV@U`X_E`l z=}Jn}r|=`EAy(ZFD~vshJyNQ#1BOzPKJmuhPvX(W@uDb8(s;kbs6UVfsHU+@%II|w z=UsmDPFeWw3NAW(rr7d56E)Vf<2C)R*~@gfDewlXm0$0?_>jcot-%{r@lFTb{s-6O zV1d=T3Tyz6;pG5ayi}mcJ<=V?vDi%eGQA;&!V-8h3tquX-9Q_45r)WB*pXO9_P{`LWhHbVb=kQG{>3R z8*zq6$*X+`zb=tJsVEPriy;1z*=LwjUYCR)-+CyY4f%}D&K325Am1Z>^N~d%9Y8X*TCq&#VO=_*%Q_dPoQvHuQDBs389tE%@cj^%fq?`cWnfxf3jB69omTu zTm8&eTaBu|M5Vaf-nq)Zt&mrW%lL_W(1Dels)FkC?aj~2*%`8lY+oVDyfF)Xp9`VAk!2?@Ls(&_b{&8$>)%?6g=7akZ*+aFZ>cblc5peF|ypGnu@;2E-WO z;3}b83=DC#1nvza`jXOLitarRS@oZX^e#}i6pFbI!4(wX7U%umQVj+$QxwDIYXJK} zK&@rad57JJ9+|dMOUN~LT`)VO=^GTHI}9vQu@VvTrGeASWxim3=L)XWYZ*Ds16F55 zS>>7G>4WEkeA(+~MbJ$os#5GKvBnM}>%r)r4;nH6e z(V7VX8gD?-C6@SOA^o}cCkyp=rzj6g6>4}6XoILDaC$JOXiwnJIC?GA?VS)OY;$e} zX-kZ)qs<;rehTO&^87t8S6>Fsl({Od@m+hU(NEyTmu-#<{8>O9TIG^}h!AL;*e)C0 zjfAxlHURc0u09WEJwz^tRXydex2gu^F1X@|1Z2E)v06i(}H={pg z!#|4(aXP})3*X?_dby7egCXB&W|ogn$;GY!7t=>hlRSD3Gd!v;erwE&uqxd+ZO&3L zw;O%;t)PAI6-12V1-CxPpsMqMS>tkiyfeS;!{&~>@(wSqu*3Q9gCBke^YFx2<8D^r z)b?uKHhP)B)zMbbXmX(TNi#ECu%iI|bWW~~ zoF(ciL@w&mXO;va^@^qx`(a6oO@G4pfj?A*&vw}?T)YV}A~~Q=KUpFy!V!H`0$e`> zu{=MpQqN~P3kmvtD|YtHqYH1fr(+nU6-Dg)oja-%)8*)}#t=Kh2@)bD<=*HrhWWb8 zaFcM=D(-v)$5@6Kq~cY73eP+fL!F$mzV_f?svtf|H9bBKTlb3hN2Otx!2)stg{X=+ zQ58PyVJ|8_oBj8`|HZ({S5$V&74rZ6zj1jf%2T)j$eJ(r+?W3mgW=n9ZgN~&VW+#A z&mfW`xQzw-QlE`~XRN;KoaUBh^>!<_ekq3UJ7?}6EAX}txSBXt127B5Mp-}>-WsC_ z;Ow1#@p)8AU1!Mg$L+_~`i}V%&MuQ|-g-C!!!GNMg(H_{utfih1Znm*H&Ndz z<}so4yW5uqGHeCyW}YLn)2r))^hQ1vDE>IE+uJ%?>_^D@K{H5HWnJCEr|*37$@nUH z{8x{x!z3b}K!wQ7=^EL8_ILj|#S-1^*KyqDm(rz=*)P^m!%d!m`few##&AE_M(@cW z&pX0sUMAHm@9mXKHyY|U0Gu+v+cpbum9_z)p+J81*`TChOtRCBL8yqNH)xpb2?-&M zYd4%iJCN-mv|Eatj%vXfB1)9)bE8|3fRx^_LbND&RVTk@l*(ftJ+(Ap{cCT;@~zDx z8Sm#8fm6i=1Gr^RL|H#DSx9NGhvYef&P%EI?f^DKi+%LaLa)mDHyzIo9+rL%k318# z=`v|!^2?(e;KT<(!cUu3{*?nM*|v#4iqes$Ru&B^_1d*w6g!;!T^JZn6V*!_bq^br z3?%SSh}3!Iw@nyyT4s58=^V*9H7mP$+*xK5%R{O7k^6q<1N~8q=)<4yYiYY&b?@RM zUXcEu7XW2WF4^YThbws1RZ!8T*Yj{~-c8mf%i_$=Wi>hWfSU$_@l-`{f1UZ#y~>$W zvP!vOe0ih5)Syu}0Vgwl4bm%jjoH;&h07-d$c^)8DZ7@Zp4c{uPqL@^R~WaJ&l+ zJT8iePFk;A-GYS;-L&1uZJUC$H*S9NIGUFdjD8%7={ddMhs|j&Kx4$JyaD_IMl`A| zJA-d?#BFOUxKCTJCeDSvlbK)FI?l+9hFnk2jt0{I6UbCVzA3Z3?)^_!8}+&Sq23_` zX>h*{5)$J35c^%JtY$g&Q`_j1))$kn^FgU*i^Rn)M!5W)Fl5Vg)Wah2S?{w zO1n98;94JD4LKg|6#=Eq?F_5S^Oy^50P_5Lk`+59Oi>QgtyRlqiwYQjZI7zJNjPm$uQfgB2XIH?vrc$dP!3aNyiyspW z$|N;i=bRy#-V;e*iZFX5QFd1)TSR}{f>)`WH!%{oU|;(vN;ct_q-6E90WbsvS+FU+r= z_%abE12a}%FuxlQc{#bdF_3@5TN28~v&WUa`Httu7^=_X_1`++-oqnsBV)#WH$2IB zH(Ya%xcdz)2vlKq@E#zewRvs~?v2fpl<4w(9@|Rbn}$C3`FJP)J5RV%BFMsn#5}qy zwLI(g8MK&QT|{MzUAmf~`fUiPnPTKXmUooK-h}?%!nX?cAS(vBA+{!^+~(Bi%_1{o)7wKJ+H^7COm~G{%!;wUImTa z0njU@;?S#PrkYi`+1Piv4j|Pr2JM(7wQoiyJb@HR5Zqw;BlQ};Z;?U%)cI;Xmhh7D zGXBdn03N!4S*}%yF1>&sl%H>+C}~r28D_XcvXM80f_|&2;IZ3YI#V1}s!^=7Oj{bG zl^z%FGE3MnK@P!Qf}j8Jw8!Qz*+KOoEp!y=>S%9?aj%QcINrlW-bwkq+>!BhygG4T zF`3mfDp7(De!nkx?T|i8OWea+1gIqXiDR&6SJgnbxDvfwzrNDrvs%V;_pY_Mh1hrA52!=G zWDg7p%Kdb;F!$F|^kp8LmFa&#@*s7OX01*h3-=v9i$RY5=ybq9GkV9zX~oNHxe(V3`j`N zi!%zrYSG~7VMpltM2HEz$9M)}nz!E~vZ+@KLCW0=Qo(g_#rTXMcAQ18Wb*BsI4mJWi=IaZ(TyD(fDs@6+ zMU-+zXHBH(GCn4;L*=_-g`HzAsNrqU6SOH_T;qH;*&}(DA*stHtH{Zw?2i7qiO@q{ zLN>ooJ|>yA4YhU`Yr0_ zhGIiN~)M{xQq!yK+)8Eo)XXr!%VB zqq&9^j4SgF@Vwg~;j{LcpKHQyCpJ^_snh6YfAc112R>cdc(V9pG7>ve028M+L#aXg zD4*11;(Fr17ZA}~oBy;vy$|Bv16)UDOO5}*tn!NTtr&`i9F@NvN}zxJ`o!!*)j33v z+HzJdveZ?9?k~qN#>Fe?k|g+~H}IjunX|^yMj@OhT6{0UfEhk_V~vXH6?c-3Ag|QX ziQH|1_$>RB6C_5s)at@&I^e|NUt>G+3B4bqPV+OYd9lI>TjuLxMA54|AIb#L>=TXM zz;|R4rI{fDII5ur4(u1;FI#&axzzi3n&UPnezFM)BeX-Xf>J(E9SP=XFdwO&$NK?6 z-9R&h>D2q2m=}$K+pjzWqOZr!1-K(&D44`J^s3o5?I>Vn4I8JQ&#kT_5=kIkZZzFM zB^qH=k6C?l!bU;WKhJ1lF@~XVw|f4HhG1i?Glp-mHe!)Hd%pE`z0o;pXy+GVy=ZiS zSt7p7m|ts*Gr7aPVE>H0Q3to5wD&`b6xSi^!-d0m;KJdAihHpo(iOL3bV~UfZ<_R# zcB=yN2^8?g%Z*!|uz$ z`+k;NZ`)aC#@k$(sKo4L@Cay%Nr_={qum_YO4W)>RD@;Wi^lrG9t2x;+;bXc5cvWh zMuV;RRk2Mq(TD2(DIm;nRfpUQMduQ^404?l1?V3@1Q=R4ka@{?yy_l8?==4M@2k!Q zGXqi|-3V>d1sL7}hTqWDKfzTu>P#26dliz=m}>JAf1OtQ-veoG-WNIwdtyE??FN{k z`Bpm4*u z+xVAhl}~5A!_Ewb8*FFBX0NBd8$UrVEWf;rl1}1sj|?s>&_v2HGbKm+kFF@)D&+Rh zrrdVQB}tRxpzHGC2tx^%lIKQ9da+t##7FmFreti|S~W|qS;wsT(|e+Y>ysy(&|a>E zDN`0h`7oL?l@`pwJYs03$K@~sSOe~tD-%hKD-%s@g^u0(L6XvcC|tLTnfCY_lOY87 zXp;)``b8}KtKwRf3SCADqJTn6i$+#*G-SYH1U7AXnL7$}HxM{^lL{qGQSvb0WPIO=JM`Gg* zsMd&Ln8(WsP!~*T*Q*|Bx2e6&O*tOY5k2>|eCuPDrSP%QX6dJ{0Lm`Rwv0QIUKyTy zl<#qB;QX`&>)%pD-ZU_O9m~3EPfD7$Bti1M8^Wb;$_2q+_N{S?PcY_Sv`#J>kyK>k zKRXS067=Ye{T9HahIu5{*=K&W>)ph@o}*${bk4mfia(}4t|Dgv^=Td`FTQ+ajW2Ubskzcy3cWTClX+!Fw;Gs&(jG5bzfy6#?0i|^{S@$8>3T6Ht! z+8h@Vf$Z9FEGgNqy|-@2@<}OS9S*bv8^;6p8j|s-re%9)oIGLY0wpCP`&&-ytrPJ` za@XrJ%W`KY_KM8~*1iRuendFhW7mtIU|c90*7d_2O)AJNW*NoUl|Xab2v7 zWm1rD)%$8Zueo`Vdpg$RS9RL`FHyA)k17t?mV%Pbv9JEC47j|>1!8ciQ6Be(icXD49hJ~^qd)0TCBn= z($EAh=-)$+o8Ku9*gKYF}|gL z48#w_?hECzD1&iRrnmW~qZjW=Kv(HUSAtBJNluTJJD*8OX!+Y9lNdhO4tLVB*mQhm zu+2#i#b=#$-y>V$lzWQOKfoM~PH8lh0Rd%pUHaQnh8%7S*x%MkZl#t0MjGRT8on4<>uZ`ihm_JXS z{LQV#GCeE~@-aENvA6~{S!^b)3zzh%m>)%Mo5R-)hgt}}bL5DE_%JEsBu{Tb0;EIy zRO&hi*}a8X6YE3P70ni6{gu#&p4;?>h9$M$IUDNh+tlrFPZ9YeB@bqoU`{b)d-uAe zhERG6C}nciu7*d~FmP*=z^z3wB8WH|r)$#OR*hAtJrQcdKihAPcLH)2bR`CAa3A3+8mw*n0&DUmIu|hFN-4xkZh8_wgMcZZ}ND{eCxP96pTupr8%i7;pDo zsJ9Lp*<~SeiU|M_vl?lc zWj8gM7(VXb2VphR3inS72K5aGC;;zn1=p%p1rl=R!CW)Y#*=OlxuH*yCI(I>Gl4#P zk6a5D$O(g6v`+aK9T0bQ$t#LKtqr0X@3gTGI6H%2_%}$HH{ey%v_}=gsGX%pcqfeT z3xhC-mb<5}hG=6_spq6fKJy;?%5F@};ym=UxGm(I*42@XfI~y$5F`YNr*4UI{HQD7 zpx)opO55QZ`2_lieWkh$MSR=mMupKxt?8>AUy8GZ+fU(dTyUFU)|P>S;`6a2q5jg1 z3ka0~fg(Mr^v*~nlxg`P*smty!H40$>n?}ewUdym)yYQ?zctyJMrViN4Q5;gt7}vt ztmW2-J&(<7`9Yo_TF3v^JKCZt=$1ZBXjy|qCvqd)!JS=yPzw)fFYz*gj&u1sLhX)V z8J?QMQVqT3Z$%##hVm4b=FiZvDll?1MoKP?$^D40-lE=EGF>xdrRYLUMadx~2B4?%;=t)v`zp@(GIBoc_9Z z2`etLs>mU&i#=kCx!BOF$!KH}|5452u=N_{qP+uxj=v_X?^A4D#fEceogQAwFsrrd z;PktuW<8%w&+C6o6j0_-k-gT;F5_opsI0*Aq$Z{Bjfm_Juq-JHvw65(`4U9@I^9&#}Zz z5nGQc$;e_Wg%hCTcyj{P%}Py+N_rctG(OsV(^QlfG8Bl4JKAX$+c?61@(7ERHyT>B zV$?)cwnQR`P~yO>pNR%cZ_1YO=|%&RCS8UEJUNdKmn2-W8Cjv?3a%e9nI5fa9%>$3 zNqk@icb-Rl(%(88ESYiVE}(-b3hWAVi&gOZEd5VxIrxf+yP&j0fmX+)qY3kt&*^yV?{PPg z1d(7w+s{aHL6KF5XPr+y$41fJ2M5M~6W}Xgy=0~VB2(DGloR5gjf6;%I~~613`H`F z)doMc3{>J*IYHz&es4nft@-SLL#xPVziuP4DU)=88^*x=dfiw#g1Tl25+xI`3DnQ70&@p&73x)rDNbA^U$SFO(3Q7mYO_Y%iM`&(RK`p37+?@m#lpnI*%c)7a1}ZjiL#3O zWo7=TQmfE%r?;qDF7kN(i|(bVJm>F!S}I<%7{M=^{a3Fl#%~aCDxYSkE%>ZwJry!< zJ1eDIHyF(AJ#=Go5j#~N^X(N7-LETmNJR3xVj|c8oc}=pB~HVPMv}FGOu+Xk^<7P@ zBd^^L*vX1&bY9pV{y!(pls-X55`0&Bv(z=W+3)|bWL|ekKf~+&r#JbA`Fl7+uCN+! zrVbrThlPddtjFLl1%F54lap-b8`98tXlgj;vV`519SgY!Y+Ff})SRm_KRqgE9pwPz%VJZ8T%v~B(#>NOciS)d_&_uP}7ayZ*>9l zkyHHY4}?q4d6%TVNT#ZvMSke|T5doUTHPf&On$Uh(!{h2yAmv6TW}xs@lzqX0zra5 zf2~*?jOv0rt?68~X$}yl`B$j<*CX#f&ac?LZ(8%sD4NC71$$i0XV~lgAX50iV%Hrnp_bd>7TG)Jd!|(HV*_7?57p0J7|O_-S^E5~3;yaD3o{ zo;-90fHXPidrDd*`FOCTYLLSm%&v0R5bM7(7IwUSjn zN5FcB#nV5AlX)55>Hso)=T}XgHwK-(bEt5v==cr?!a!icjwFKEgOeuZwB41?^(yW& z==8S_zTF6qbtdGWsN2r zOJ>EW@E9up$|w!Q$?grnHv_n})+LZU94PIQ14-yXN_CYcmrP=F>;)rGN364HKZ{@K zWleXFy;F5MDneQ|tAEth>J-pSZjYB(Tu$bd5dzD5tMij+oi6{204XD790pZSrsw8( zD*if|o~v^n5}}7Xo$>kTxgXaKj`b+{Dfs3@x>_duX4v(G5%h^Nv$5fwMDfUCt9-2U z-2Tzy>;{t(xHLJ7&TdZ~c=8D4AqReopJvM^f&{geGqT?wY85rk-6(ue1_3Iw7RK z{xxwjsU62Rb?R6H3qsN|TzfI4)zgl{2|2rRq7IuV*Z$V#SlR2_2m;6f}os=G_IPECq>-Kn%2Yra@{MQl#_@PUCiN&#EtkI;PG7tp)qr6Mm=F zBpZ{N{cJ3w*KP`7ggzYya}732vV0*G$Cf}Xv&i~h+V|_G32vUS+?-X<6)jJ?T*4wd)t}uAYhUZ2MA2n{ip))uqBp-sI*FS=%3O*Aeuq6n_4z;M91tlZ_{qkN+u}sH-m&k3Pd#Zv( zM3r(aJ!DE}ZpSC7qgwD&ZQcGCbHCc<)P)if=E1B)lxx{L)u_x&WbS;4W8{a>=G zqGKiipk!4+NH(cdvjYs4P!NJj%CbT=t5%E~z%`zZZ#Ckq74C1MLmlV{wTtA4@o$kdg9vesDG3Y7_9}3kUIjRd8P6geH^h z9S@JgQ#r8V9a71CW$_57S=#k5sq!3ZoJ={d-ba=<29m*QT8DcmS%A-5`SwE?p48;R z^bfJdgkJo%Ypu#TIp~9*ZcZLWkC!?WaqsaI65v#+*R`Z5p6PVEu0Kih2k&HKlBTB( z8b?TXiOl@OQM6j=K$zfY?$6{v#?{C?y|}0!Yik73bl?z(jk8|!feVfw=OyNi77bn& z#WsuZ-{X7uPGC%cW)#mt%*kJgYzHBDWr2Au-y387vcGt|@gLzccX)VsKT3KC#kN?z zg;>Fs=JC|k282F7g#=W?R0Tc4DpC*CybFI> zmnVGw0i3Uipk5bw6Q+h!pCC|f4_5_DA?b=Jt-j_h>T_gK29_A#Z^IT&RMwibnW95) zki7x2@7odfxv>C*A$Ra`f3~Kr+Put7ZHWO|4-u_bqS(vYJ8NJRC}tHuK$68a?HU2! zoUBkLGZRbSV6!MjYyVoB%mYh&ag4hTuV;0;;Bsak>iNyH)y}sM&%pR5!gO?i+tJOE z8ne5NbS7tS)L*F#cY{&t5T0|%QtB#ibK_y)Y(*6ZC9%XG=X|fTRmm1I-l)|hWC7M0 zy+vZc?y;R1oC5KnF7Gt4ttd6X@eh{7Bsnc?5-GEUt(xefZ@Mo%nLJWFi(fkD{NAok zX}s=pR%cT!Oi8wGy}sO5NN+#>2@D?k2e*4*`zce;MZ;(lMaKWNI>;XU&Ay97)ZnF7 zdOEZ?ZX)!HECo+*3>(YSan`Fd6ICn$H!2a6YO&GbKz=T@gt1Iw;;M}LFNf_+_O$?j zjLy#^BWIWkC$)4LEc!&a_XpEvbyp`9t409w@<5mp(RVqK<{)ZI!e&z*SK+{vx`bQ-0oq}Oe*Xbl*Q?8GG@QV z({ng5S%RY1&OF4#g;wJr%>RkFoX$#7LBTAPjn6|0q=bJ(?X<3@f@w?f_s1B+_+9T5 zNb-Q-dbL~pvtf|&$jxt2ffUOwLC;K%SrT!n7QFZF4|$<)BOzefij)*MDp%@Zf8n*4 zc(_sBCHTad5A(0{_2nd8g1gr&vSiQHLX%_|%%Cu4wj@WtS?;!>kL}XR&K6_MbdIn; zN=VQc8vr>1rrG3wF^6BCh!^w8Nm^t|TcuZAy{0a3ZZ8Dc@#WeK(n|~u-W@&O3v%~c zN@C9DIP^0~;3|&@rYC(zVpvu1!*P;uMT|Nrp z2RIr9FQ`%sk~O&0AX^?iYBxD%;~|646kR+Xq?q8gXVkXDa@zeR=K zeVEJQ_&f-o0z~jxHx~IBlx-~VWH}a9u)h)WypqW;FQdABAUUfU)5-wNBT!3n?bRX)|CM zeRDKf2z)Oc<Heuv_|GII002JDB8hgvA!s@2>#;MOCYRE~yW| z4QKvb#FB1oHCvUTk_>3kwgJZfZP$&U8Y?&yTdILqRdgk!Cbpl6+mnX7MiL7~M5`^F zUFBEp`b1AP_=8M9bx}?YGNq72(>zXG$Nr&WYCFdm6P|&wZgq}#|8d|fE`+YF z@1X~dpS~cK5H9tqMj8BF3MqjG%Aukk>@Qju>*)9xZ`orS_YL8|Lf(}@`k>7={ z?EJmTnw6THQY6)UiOa*a^B1%#6f{4Gdg)rNd*qW3qsOorPlt?ixjbL<>*#qarP(h4 zirTX>`6b!1vZvX&19N$3?$2}J!rTzS`h6W$qW^2}D!ER*p6cNngL4%5Xn%FF+|k*E*(@scaH=kOG|Qf=UMF8_ z2sb!tBU>wPbrzmEO}vpCh8vC#CmhQfNNm-)?aUcr2(oFHXc%V5eH-`7hN;EIyZ#Ua zMx=N!I78^YPW0@AzB+m2Ql7%V_jh1fM(;(e(m7p9vG& z+qlDw7-j^omVO*0>7mAS5q+IXt?$+pekTN`XCW5m@b~FEpy(CF`q0)RIOp`-{ha3l zP!)<#mULO5NeV<;vYPI<05`ccDrIa6nz@9gIeJuNYlmhldz`tV&CyG56CfgJb<{y} zarSmW<5)`N0nAKWSLyqo&Z?uNiG1mSXUjonyR?C4TeSTNOb+!msj1;r_eT?01>u!K zrOwHCUrw~rOF@JYNA#k_Mmq_toEAKLTMBIN1Yf0_7@(TT2EK+yys4zO37#t6X=NZdF%xdht;=Sir~I-i5A~nsO~M}(*@~yU92Z}$ zYOeFK{$#nzlb_zkN?H)|3tpT(+N{;jaAcQUydljQWRh#p(f3xP3>1SAtW1bJWZ^i6 zkd>9o;hi|98cos673tp7DS&!!@V@%-ljg4i{?Iss{n*m>e4odqNh5$YsQ9L~Q~$P` z-NUmZg>sOc++rOQC+o<-S*!WGcJqUWsO{er5!rU81K9MvLa6B(WJiR=3{ z**|^w$=7^>l&84Qt)qBN+tKS&t>&HTR>AlbgOgeFJt3lQfMu$yN)0`DOv-FI^yJ(u>8M6Po^>3Tfa;PsrpN)=w(CGhfqw3e>8XPqv~ODP)J7Cc zTPE4PGXBdF=r`pFC8{uQcxERsKoyBb`)nrV51WKqCH2mYatC51%PZSq)P&gpiEf)E z$CE>|+o5M841LR^uaS+t$Jkm@Dnn$2P*x1y7#Ryq@2RiA;bEgB7XlzJQK_`nA2Cd44BLOG8qD(WJF1BTpns zt;H<3uEhPT-$G5Sp7`{lB%0CAaT!LQy9)>B<}|c+O;$3re!Jh9_dBj1C$_HJ?q(&H zd+nMv^0KaCDtRt&H>2dMdvXxE?-%GlgxFMEJALAdoD$aXFgUAa~c@C9J z&_8c}D+8;&IvNogQy25z(1HdzG1i19XT1@EB^-4)&&cgo)O3h#QtIGbampw2`soji z^CNV~p)PY%Kh-3?Y7pJ75uotLDbn}W(01Ft8vzAi+)yI~S@b!@DQ?LkE~zme>5X-; zL*De(LAw5I3Azsy1|c_Ve!kcdV%K1@*)xTujJZ63e9V$}b33sFkh;LnR+QuA4cC`6eM!u7RCsr@>4}w5%qfVdj&Pvh zQL1u3^e8q7MPsagxxl0V>wf9TI`K&7!R^fTbAk_Dsm;@|?T8df$o*6iq4(s5qy20@ zK~}W+84F<(ve%V_#FO5xvs%r(I&0+*i#DlZQIZdC;tp7X|0;~|!)Y78pT`Bozl@!m z-?Q9kYS?}hWO#Ybenh)5=7Ynm|9y27Hqm$3sw0Ez)sJ%4$p?SaC^xs7;&1J7eq)Ep zCZq!>rrsW#LcQJ7@dJ_r#{7q$@)$C0F6m|L|3+-)zl;Cu{`CjAeKO-t&lOy8@yM)A z`NlOl@xD35l66LyzPZL%Pdw_aS&|Y5m#nc(x$dHZyPc$hK-ut1ziVODJQ-nS2D0I! zqh!T{9LCcx!6^)IT11Kc1fNS!Z8;<4(h##&$e2f4MMktIm$TJxP`W4yhRY!h}|w-xYHE+uc+uW z($LlUeE;{O5u#1zb#X!C*Pr^wCw@`15w*NBY2aUhEi&bBxo7q!1D=f78}_JrWGKau z3EX0WMEe&)oQp`h@nBshqsE79adBT;Y~4{g~rfA;E_ICLu{MV zUei{r%O4$R%ywqa^n8V}4z5j$ReMgB14t$To8~-Kw_QZu_L5R_M}zssm>g5m_Fx`` zHJuo4tVI}4+Lfp2qP+Xd?~E)dkxlM1x;Z&I}vZ2VP-<{Na3WLz`nfU&lD&T>EmBbUTJ!kmNf1;Qn0I0Pe+QC zNLgFbX4hfuWQa=G**y*Q7#Gw~|g^mL6#BWY9ojHw9&V~oU)jtfJEP1VkAHjHt+jI0%-T;D>EM&GP zyOn0iaXIq2R0!mGJ{WN}e0(R!zn5iB} zq`g_9=KXU$W8|Aw_lmB)l{dJ_60Rniu0ui7wcPu%fdJnP1H+$nhK&?E_=IxDEK3gmDjIrB z>K7MA1@9XAWMvk*(U;0mX1MvdXb~ra;De-MAsD7+{Na;|kCF)k7hU@8&AL$N{qx1p z&Re=+37uEG$$7GW5;*JRKnQho>cs*c*AgRe@SzW$&8>!X!SH> zvhP2)M7_PEg$ME!q&L9>Wh}L_6HoIOg4WnZdmZas0p^P20&5rfRnyjay)YQ8NOgkQ z?(b5!1TvL0VwJ)wdgE7~=BK^xN6g&-?vHOV}fmm6pcdd2u_k$n&riH@7o-bnB z-{yCyRnT=dy3}gS-Q)l2i6ZP!;Sczx?ie}=z+Z5(_%+A(46`a8hfPnPQE7M15^_+` zR&5z`hvc;QPt(W^0-F3@{2U6(SKiQ%MPBbomQIG2Wn__QFcj3Ke{uc#=3NZ;7Md5v zHFicHoS9+S1%z{T8QrZy?#jSGdS1zy9%{lOvm^JZZc3oNGUV+e3#Sq^x~#Z7ea(l| z)OXv>bsT~tvLq$YTGkAbeK^ZAbv|Zp{J=5yfN!UydmVRb4hg$BSEF40f&Wc4VoFn! z=Tk6vJ-opcIffG(6yoCA3<>1VxyJVQWNDCaT7WP)ubvwOKdz;Orb@4QmJw11eB-F;9G!@(qV zTXd=Gd3@)`I#SJF62^Y4WJUL>c_ODM0H`onHsoF3sK zJzxG#euu59ww1k{!5xASURb3|jynjkkpyH(tNP&Nf6qf>eD)3?$Fg20oNa}5An%Q# zqDBoJ<~%6=J(ABZ&}d06(@ENH{yYWctsw}SCPu+0A1Sv5!SWA8W&L~`E0ole-w2zp zBT0Uab8C*Dh4`{*%Xs_h@-?mUcWu!F*QL`-6&7hOhO4bw(-N3(+m&?F3s{VRm*>}K zKP~UBM(n%+t9^E#r@UUwh`Pt*4Q}zD;5twQgwdgBf1dmd>bTW8a!y{e7|=7YbZalT z5)dt~NMd`ycom8KTJj5I?0L7|q1*YMuSLV=Q^cP|&bNO-972=T*2Wf?WDuemm#3_$&|=P1on-%@s)TCaomu|k z7OT|RJ-QGWW!XI2C~3E&wW8t}c2yt_;3#coH@E&>;PNENyz)^C7IC{aLn5zr;GCH=0M_=ZR5d zWqFfwqDZd!=R~S%?Ocf;ugzzMLW>dB57Pg0f7t>jtY{PE-#?> z$$$$wBV&-i7gdH1*!oyR_hR6_m3u`(nb8@dIj!Q5`*iRdq~#;Ix?L1fqwrl#MmC|1 zS)+UV5G7c0P)o(>@LVUGgv&}sL!)vuQ_GNOJ%~iZFU4_78XmArf)dAVAwD8Do2w2{ zg;LZQ#p#$al<$hvY4fQ&bp!GM^NUngwJ_PV{K}aSXSs@9nD&&h;P|pu|We5h`kI+&88zT}0 zU%7wZ>i#+pQnS)pEK*L;@-x9#POgRFDw{TVdAu%!F>1)3gziY=?Qgw55X~w(Cod5p z;_Ht<6_47}%LMxEk=XDHL?}cOI7PF=(COAscxQRnl#dSsOY$5gtqbE*Mhc#e(Qhw) z*x*AxMGzF13?v+BPV*FHU!;u{{he z{o=R{bH^az*kIdHB{>n}jz*fYy1Ip;&y`}fzvkCrLG$e!b1q=f32qV*0OVcq*me=S z(c_CxgAd&v`-rF8q;uquKE`r#^TLz|_0xra6j76a1qf$?6)f~q8Cgq6dPx}BMk=xs zg09?AO`+$%nRjk!nPeu}UQ6rX)J1sm+P4`h{xHjiD<8awKW09szv)AUKTrvi(;vIn z|KygEHx>2d)u?1o?+VS)#@t#lMs1P7NGU?@We&+FsmqeIG=WVk~OuyoFIj)UdsCFw1$ zR)4N&I?a+##iV0it_@mpHFU%K92Z@AEXMcgHQ5c{MLERc%7ydij`00%(3XB6v9z|$ zGa%9r+GG!{vv7P;S~u~D$K)7x)%XFS(alU(OLYcMuS4NyQ;Tg5T*i}hyD9;t9;%4n z5dNn5O(0YMJhPfkSeO~L1G{1`Nym1jaR2g>_-~P7yo?+78BL!X&odVpbw`~ID@W-h zG{R3d7-p9ICzgZ`J1&phEVQS-%_DgxI+I(7lYyIzSMv9;q~Yhpfjvcy!f$L197Z7A z5iz#YScwo{YTY6C(L^G#eiWJ^yB|*ij&}$QBoi~m@)}F%TdL|102c)!_;D6KWtlDd zfmPbIOoV%#+^*1{hyR44hp37C`SVfz(RZt4R2r!Rkx_okJ@5J`&BvHbcEz%5T@;;n&l>dTi(Q;(+2iyjbZkaCO*9V5Tc zR>2-Hez4<-%6LgK41TJD{a*otBLs0Vwj~&etk$E63a6+KqHKqkv;s_D95%9Ym6Z{s z#b0{Rh2HXt;mGW!Iz%(ySC#`}C$JYeKjfTX?E772Lb8XQJ;#0Y#6Fk0M1o&q>vGTB z&BV8}fP0-E(#frR!%P_T?{heCOw*Hbi4K3jV^fkgW?EVNCW{9l6e$>7>z;J#Ylew% zbHq1uUPnWt>E$0b6eog(c0H^=N2M_^<9V>R3NQ1hFY+Wvx!_%~0w`^XJH6XzG-F-C|gjX<`GL)?R#La zLZ%`Cj#c@^v%coQaom<#*C5>HibtOR^bGat!Myfd6xsHaJsI;5(}hO5^Q7g-+c(C4 zxu9vyD%4Pds_bCG8_uJwrU^_^XSp|lClyB!0L-d{0&e6?6ze=77m-ntAe|2%EE3#v z#OzNQ^RD)IDbGVcM8z_PFdmerSrRvz=dE=n1uUR;<(eiOfH#sndZ)&9ZH)f)#io85jc@!Q z^#`e{;)A+2j!axQlA|CZf|p2qN&9~Ld(&tr%J80&WLqK&3_~T9el3gKzs^w&gQ~6O zBMJvIm382uMvGHIJkkSK>>>*S*{cEed7Gm_Td4*LXI`4s-al|%#L8;sAKFZZpP6k$ zUYPwF*tx(^$+Llth@jn{47nx!K-2C;##O53);|bZr=E0 z85qmsT3E5>ng6mgt>{rJ_hy{?t~J{Bi}$LmuURPKK3mE=($*>(85gj?&9NjGU|&DG zmkdK$lQyr~f)!Tt$ha1yf0&Oo9WMWtapl*>FO$51CP_vL(o)Hi?3X9Fy34U76Y@jj ze=~^VghE6@t^5IS9|D(Rc2)A1C@@Cvo4>J4%B=~S=WL2K{-kFp^%wZuboq2egciBY zVy#6meMRuq$TP_8i6NC->J3e64-GnGY1XHP|g(TurKqLzgk=Ky|QNC>%Yxb zz2@$_w) z1kj2|7YKvfPQLa#2wXi5$?L54CeV^Ex^R-%cp`n^#k`tnyeFF3r1v9kbD(f|LGz~T zJd+M@Q<3A>rK>^36_mf#9p>Zr)}aE!c6V0Hsy7cZK3Ro&=gD%8kn^`%`)&(_=!b?J zQcm7vLmv&uju-gQ$P9<=S~~An_e^jw896Vk);8-}Of_%5blX3@x&5Mws=IvcZ!iTK zI9TamoQoA>(2cu3*-Uj`m1SPN)&zuq*l6K5Uv4`&&#>YN8Ra_pjufE3_s<9@DDT!3 zgsX~T1fXft0|Ko0d7IA-Gta3G|F&~10W52>4gjEoE;J=+&m0?!t3TC|;7h%s*_wQ`=XP91_$zz$h4ZdK4;6)|L=kORu zM;(6{PC1-l3cpePC(z{vFp*eeO8^Moe=K^e*f*5PbN^uZO6f^}#iHv!mLnD{RBLyj zYig46Kj)+YU~g8wl(@42pMO6Y=>HNx{}0N) hM9u$$^1p&|$0AKn`AGNidN&UCQHSX$S1a1S`Y)-E)I9(I literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/visibility_road_map_planner/step1.png b/docs/modules/path_planning/visibility_road_map_planner/step1.png new file mode 100644 index 0000000000000000000000000000000000000000..e70395241e5f9ae42331fdbcf967472061288817 GIT binary patch literal 289363 zcmeFYRdif2vNqa=nAwS$nVF#t?U*TMW{jDcIc8=`95cnt%*@Qp%y^xdIseQ(_x#WI z<#eyTwzgECq^hk}m87r39SC8|QJ#m~>TpNk6%qlprMvvleBpHPzqei0JP-yk9L3q&;( zMzK?r`cjIH+8d_wl}@9~_w$!;$8>OKJU=v)Xle_;ep7nmgs8cD_gcTs+~+=j-Cc3; zG2L0)X$2f0T;)x9Dq;G9OXSiq(?qb7^9OuA0{hH_fd!xx+`HUWa26J(^JQUqQ`A`p zgxa?p{oHxFe|e{Q0?*Ar2CyJ*(fMWQ0_<=B4<>C&DlmX==Ji>MRLWbuD7XW9{wS(6 zc2PLz%3E~o*2<4$l=ehz;Jz4%{qeg1!FKr5QW9^Zo!s`21sM_)DZm6av>lUf54vFK zh?ka7Cmnft@B-MA6mjq)puKdQ%i*mvn|)|}dpE+sNtcQyn*@fz=-dL^BO>3d>-k=qu&`2U3iUct-bI-bA6Y}o{xsi)3NScNM z{qaRxG={6HJHIR0Ul_j%mj@I6N)C;iCdwDIR3wv)3`jxxQ^LncExOH`E7B8&dl^fO zmiV|Vm_d~w5>)i~=clE*(a*m27D1o_W1TkHUZ43zuJAYenkIn-bD&(JKOZ8lFoBz>M@xSSge4^7f=%T$u#yUO!WHu#VR3v`BvS}~*JuizkTXh7mG&ya zZ|*5wZ!b=D1sXYJxk@nD82IxLda{Rp!b3q)69i+29|3O^T$!Aoffgt-B>_Vo5JW-& z$BZ;K`kMA#6g*oZ2l53r7G*$eKB&kfC00l-W|=&e$y zA|d+gxBq(X*O!U|zCzCw8=%tei%)&Dnt=Mk1X{@-Dp8UuM^U~o)E-*{Hs-j4(DaQ? zS0V!V>|A+%TY(jyyePT1!2UqlE>M?~Fz4o-v|Z6jI31;*^#Ebf;n%tS){ax60#1Tp zXd&l;2v$4v4S$bLE=xX0(Ys)kC<+^6RW)7P_h0_wZHSSCi;)p={V||HB;E2n-pN)m z^@P^97J(zJYSHIW?94|N;C}TP{07$bZ^}9Z-iXXzS%dvQDy6WMmFQ}$&ak}sJ-?cd zU1ra4!jcMyD3Py1-@il`gcY6St(2{m&7Zcqm&>bZ74o@es82Pr*hLk_^aj5p31g^s zx#0I-*Tv zvn`LSi1|`v)o>-`+m6O_k%tZ8pofU3$4}4!4e2kB0!HEQ8iO#^iLhXdy0Xv01U&*R zC5T-JDCu;sgtdg=?bNy8=YmWVq~(J3hQjRpVvE1x*IWS22l2YWjwOr|7&w6fWe}l8 zR2Ry+<@Z3`DGrGiPDXMlP7xO%j`E3x@DZ*^aE>HB245Wi3c~&~cUXoPPweslL>{JF zSPO_b;RjBRNg+ND!7XUf3?VH-R?J~y(G0ffvv!!uui69e8dUx;9g&J(s|T!(0EiTh zz8*Se%n{^my-PKyq{zX_AT@54pjiV%HTajT3WHTO!aEGgErg7q<_>(k$bt<|PmVSe zT|b+y`>n_a^B0;ozjm8{iVk|12*qU9 z0sOcD4|6hCbc26GkgM;4=m{B+1Sv+G%rK6XI`p&LRxF%^ab9HJYaV(Yg95U-yp-m! z@Gyv0ffgk7Q@L3AcdguUgG%xodKqyQ!(tMiU=$_%fWu(PK=T0o&hQSw70TCW13B2A zWQz9GQdF}EP(#>5+C#KfR#voDKBt3A2B*DCvrEvmZEXVLp7Gc0x0^UhceQP0=f^Ez>)&P0*+4 zP4-psDH;o_JFQdy0$Z2anR$%K9U&Cz4oWLPD*!Iw9FYg%3Go)O6+sa(9MJ+H8rzwb zIUhfMc*L~afWTl)uMO9bBbZ;5%j7X7m|5F!4J(ozjvWmr5f`7S$@*q2#TZXN!?dNZ zVelaf)_Ti`Wzi^VP$iy~!pjh`4=QRmnx4?Z?4%;UuqfXA=ON#8W`43X^vKBQ&yhS6 z+)>%o+f>$3(5S;G?PzrRy#^DVKYb5IA_gVhn;v%6LaC<;`!QR|`qT`|l7fC?cU8Cj zz|a~^Z}H5L?<~K?kJ@afI;Y=G%}(u+L8D~pj~urg?Mrc1ua;lya4pA|+Wu76OI1Jj zl@Fd3wZ`(#xAnBGy_G|Z68GrWfy%ns#eV+EHq6?_=%!4 zvUPNE*QM7-+c;klUeI1t9x|^fA3`1(uWW98a5vE9v23X}Dg=`|S~|S^f}xQoxuSWKUWf{)%x@kB8nF}y!#_e}XD ztHpHbh`>%kZK62RtyZ9>ZaGZmIMpL@OtBhS9U0%l-W%X*{nGT{0ec5qjqaT$osq%R zXmYhJa^Le9W*Uzr!5V)@-YSbErIYAM*-QL2b}Fklo`=4c;Z{b&b!n;QjC#9(F2$aC zl}tNhEkkHXd~_j`nTg%t=&6W*x}_jdrkQ!w+x_z9npN6lXPk>e(UihwZ&O;>L}RaQ z>8kad#4Tbq;wz5YV-M#L;aa&RjnR^V`&v|53JI!tnd~Ypx zk4e|bBR-YBt$O{!M*4GIcVFkilNgTF@oHVq(T3t$$lDW|63gjdpG#^gG?LQjwOei` z=fCOBCr=I=8FRM7zL+etc&56l_uG%};wJmhVJ7Gn+Lja+ySDqcZ*|q5t*iL(wy<~@ z_tRu6YpSBFN~x@?p;wulYqZvqTM(9|*OdQ>Q&!h`ynjkP9#?f!wptck%vqSw#@AeJ znKaoxiah5GeF7zSgC?I!k4EF3m8wUj@GaPuJb^L1Zw@kHcJZeJ~?FddakIotu4krgl1B&Lty^ z+u>|~AX_feIGf*&;Xv#7(f3-6@j=_H>A>O7W!(L5(stK(`@HUgUzb(qyL+^6sv10$ zjs)j$hdgfVFGu6^4f6~-(amdaq`Q4(>C@KE>u4+P?!51J;kx18_)XOh44c-E{Hq?y z_cG`6Z+j2Re%9G%hR9unTJ9+~7h|Mvzf9YQeSFrdZh47EbRG?l z2>HkJ#)F@R-e#U1t{p=51>U|q&HsL*e&uI0Vhq+TcQty-X`U7Z)7&+G4*_e97U)B?DK5l)nekK+Z}W*Rs}<#Ny|j+80H5|Oo8cj zc;FfrKQR=diFo-a6JH4E-+Fx`2LjkSgdTCm%^^03lz0o-3Wro5cI18C-J^;{cNVh< zzBACYz@kEhgy^P%34RCL2(WZ@H5 z{UZ$kNP^-1pR@uP)xTuG0e}#50OY@9G(PTsKQSNI2l`)kh`3+?^v4t0#}$|Z{$J9N zaXAqGm4=A;C<6#7f+Qq9?uv%?#>UnTW;Tx4F-EB$8L+nE>JA?(CGx))n1lk^1polP zVy>j-s3s%LV`yW=pl@VjV9elZW&5`t0G}(*N7BmJQJ=`w%F^0_$CaPt9}+wt>A%^G zBt-uZakStkQInA;0@>Ib6LBywF))z;;fRQc`0R~LcoalL{{{be;wLe4bhPDRWOQ+H zVQ^t(u(3B~Waj4PW@KVvWMQHIkf3*Pvv$;XrMGq<{bwcrRgZ|VgQ2~-t)sb(HPPRC z^$l#C9QjE|{x&dr+7b9~i}U@XrTxKxQ^J zM&^IP{xko-W7PjInE%ZG?-)6I^A9uX|Lq>|zuNfEyno5_G5&r3|1lo^IoSS@`!U*p zaD0saXXFCml7T)V0DvGsLPSW(73`$dJjQ6)i6Cip_F4M=#Ae-vZX7HWylVntuu|l` za;MTiNt#JqG=)u{32P3S)}Mk}@d`QKpQJI#3cN1x(mvp0HWl6{u7*1WXO>o#6iTIx|^tvqjUGn>p>f4w#mzw9ELHNwYfGdI)u z*6H_)6kNm?1_g{n5Hb{iO7#DJz(+|rLm4;wAItuU%7K}P5fS=tu>Yu#D)3{EBuI}0 z^}kpBZy7|1g#WqqzaoCZ9}OtMP@tjyUu8Zzfc?K6_+JbBuLb_s0{?4)|6eUIf&xw= z`2X=ER0818(9o%g8EI)l2&P1TJ%JtyjIG!dk-Tx%zx}|!JcJ)Hag3=Rj>08f@W=EI z3-aZSL+Z4pI-xsmr@kuXqGez#>z!uA1n*Ovp^2{8F>iF8t5^zbIZrUnvUHT}f4Cx% zPk7()a&uc4Pum@YcwCoD5KC7jh%QsvsU>F40zT+|A_%e92zrVtsHs%mj_|!@zN_$L za1c`fa#$HkH;mXw;eFM>x&CDaOhWKWk-KCqPXD4(Wm3uW(NzQ#up?hEf6chk$o`9N z_}S`)IHknd15`f}Pdedg!%Jxn1IXfz;_~vthJC@0~wVBn7)qr*9 z=myyrnV*z0Q1O?b-{2hA-hs#)lj8 z$4+KQ&~qAV80!PbLq9KP&XC+{@@caip zg3AeM;BAOk$@GxlZzav-vtpYPc!wo0sj_Y7NqEhhmkt?0ksHY@x4qAY5WITt)v7_6 zv5BXYpSpD;r&CKw(LzNSDJ$wBRPOZ47tF-5d#^cBS7qH+=+#!2+;gib1WPlcwm(bA zP`?4W`_gi(OURL0Dfa0@w7F_J1#pG!yCr)@jE5*;-9fe4KwJCdD;G=cbE0wvE2X((1YcYn2)x z+PE>t2`u`a91mVvmjW^;-U30%n*_zYNOllgz#h^P&^d$F2WhJv8R0Eru3;oCBg4rb z-EvhbNDNtOgHw?UQQ5%+V)2~bcADIWMng8elzD2G4VW))nKg5)ykXkRgG1Pg+Nt={2UJk)Qx7V4w@YcqZl7$Q95?-~NUEj# z_9M!Mvmf`4>wK3{!&Ib_^GMT32Zx-XyPqUwGsw4%3T?oba7E~h4bpN= zH63jl#z^qZt??2v1~wjINzS*?WdHEmAFy#u9eQ6uBN#9Lf5NUaPHD*69quVY3XSq1W~0t9p(29`Oq9hYd3c)VWn0A3jHo#%^<>XY|V1%HN7UU9D5All_4`dvTtLlg#z^Nd{12R3+on?g95rJOqN|M8Ha4SBUttr zX&8;~Sv|4y^aByfzC&O0?yb5CTjctJ{(Qd)(4#zJm%vL{f3pV z^|=E5dn%_{FFn@zK1s@N9zJ-uh)YMqNZ-NG$U`e!cwRx_n8kb6rqwqBVC4EVA}l*M zTxW!W)o_s@nG4zN0NEE`1R*~^*lfO)Hm_yvHb?bW?L`XsP1tp{UusyH7mb=Uk^FN( zgH@=2XgzgN7gdPthq_y`Y|-?v51g8Lr)d=mR@m&TBGn! znr^gn`wQmUF~%`A(%t(%h;v%@!G9TO9Tzv5XOD{;dkOr`vCZ(w(6vf1kRq<};B#>6Mys5(Hm2qW}bF3+H z6tTXw`gCt^Zzrz%Gg=5M#sxh`1d`*c7$BI}@%x3P9D>`$C4wO`U3Uk;_(C7TFVw8b zPSfve3K6Ck19)a#@SBIkB~_oAC>}`|cZ$q^M=0sUNne~?6OALz7e8~^&ewIRw9=RQ zaDYESz}h1ztYljm0N&EAeUUyi-d4Mn-~Lm08HLoG$V@Szj0<-2=+*KWEi0ga3px5@ zTnub6yXwe|wZUtKV@4j#H(?==y2?R@cBm2QZF@30H1_`f>hiK+ci$5)*C6*=kZoTe zm!%@D$KgL&NO3HMK#>BH9^4(3KwKy;R5cU-eo^s&A0f_>8oKxS0Sc`zM6-(Y@MN+2 zEKyb0E*u`-THj76Lj2mGC}X-e6#KIvE~6~Y7ook)h*`MsZXSNpe(#AMx0*eRN+OdP z27WHNC2Ov9;=u?J6HEUsCJgtA_8-zy3dG)Ho z8Ws><4quEZa2)h~Eg2SUfa9UyMfDfy8U+_S(l6a^S6^2x$8A4=E0VS^gj#*Qi;`H* zJBe20#MHaKI3ywlR^9ewG;$15Q!&Yg+qp%w1ETH5)7@Rt^3u{&8<3TimSw}I4Dki& znLjHR+15F39!>eH-))~-dt)Q{OIdSJ&{wZzX{A1Ru=MC<&vC-avs+F_0fqyQk;|4f z8>~34HWXLZ~gNudc4IPFrcvog} zBcxzf`%N)7BGSoj_Of9De)@%gCTtj&5h{~$$g)dZk{}Zvdq?$N9>Eqd0w*9)m*~mV z0^-2g+4<(Gfp9?BK$9XVJq_78b#$Duf&7m!V`yh(JjmO2&*i77CpU^OU(R`sPes|P zLkWxc#>7jSmRJ;B<8IJ$Tk}GN1>)Mg8o7Zsp0>lx@HJlyf(TKXToTTDO5<+fAdF-#k1T;n#JD0xG-_E^6wWY36YX_!geI zt8^W}nrUvsUA04#dp$gwS(3Ix*e-(LjCyRIV2rzVVDu??Rm-&|WysVx*Bb0V^HFvB zLdZ7t=K5Q>vID=0qk{8vxaOnQQ>1^eEXDf4K%hY7J)a3|1E03UZsVz2dILL(h$XH% zaZfNPH(7#|$@B3QA_S`<5(RClK14n! zcv>XN0kvxQjv-&1UQl1ClO*^zMn)pCfA*IO4-dEghLO-zm~d{;34JmDSz0wn1MEgB z1ds>aKH=NDb;|3qO5dm_o)(J_O*<^MdWqiexD}=i|Dsgucyin*{Nxsg6*o7}xpK6s z>~g-wznTdCTG>)XBHBYbWOL&|$5vT}?GBbLl9F}SXiI@d4ZiW`EhQKMVj;4wy7jnR zx1C|0efF7BF3VP`>)nl=Z1e!zW25m*a+))mCD^c&WlE*;qMO84baYNYwWT&f_?gY$eotrF`VIB&I5C>qI1LQ z>99dOCf?gn*8Hu}es6S~3jH17~sf<8R#UQvtry-2V3*V!1 z3AGV3oV{kldb6DeA|9#p=>|wv({~c$Zh7%G7sgOr6fsq9RONV7;qI2x(R3P0GbCXo zzvz)_X3KmltfI!n(q_xfD}(VZ;NsN3JxgoL?HPl}NX+4l>q%iFU0#cPFDt@U_zGz` z<%@A)shFD^du5KC)=;QZtA&q82+3v#a!!?lh z2fN%Uif=0HF+zuzqT^vgv*3XVeM=T_Ocd3#veHHnzi;MeX31zgkKnc268XK{J+x2i z+e-vA?B*^wm|t*nynd27y&q=j%a%ou@MfWUlpo&@P@hW?VJtZ2sr&|I`5F=lutx@U z?e!(KeeQ$*>BgPbV_`pergWH^q0EPv{_&F%B(Qvo8U@F_=eXHrYGb=>ucQFEcX?Wr zMBch`Y-1zHufObZIzfAg+uQ??cO&9IVn_g|ll{W)JKtC^cz7%v0}S`zyV6uLlPQOUMXv4{ZyTTOIy7pdq^Tns0Y zy!JPtclXTSY0~}w=PY}P^>*`eI>~Npc8Ax) zXE$C2uTgmn^AJ{5rb^f-OqrPj;1S|3#`E0H>{sxx8^TQv^94*xDV z0fF^(QZJnD^H=Y-#g4q27*<-U^n_fHXvgRFEAfYbdgc3_$e=e#!Zi)Jb%8Jn75 zt*;oIM35a0(oipp*qT>K_8=E>ePPryQ5J0TqTm5|9gzuTXfUrqQl16RnH8j!UTd}% zyBroz1M6?rIuUh`+00p|@D*t9^YE-hqJG6N*QuP!=or*ysw zvT=A-jVC^!v2MIWlwCuccPz<1>E?oeW7_+lQZ*vClInDkeD>ni!+Q0=5t+-A-I9$&@-Zxu_#6&VikuZa`&WParr_ zxC8>z00h)0Wr_zA-~guzjh(vwqh$C_s?!g}E4K+4tn(QxBEF#ZfG~0d2__PKf8zFq zz4mNbBrC}G!#;2@O*&W5RK7HW@$hxNrCU<<846VL-D6>I(a8XopejD3^u57WND%o$ z11+@GHj2)H7gl`ENBnNah+G;(gS^w&`Hh?KrQg^y5X@ZD^(->X<8YYdcsn zucZzUalZ7FeXq z+}}**)|dCyDkO%z8N`z_HdZRT+u|;sN*^wBC1ldJ_VN}R>(ve-mU!apa|`^n&ijXS zD7Ke|5z2QEU?jW`xuxk%9C`Sq79Y~Jw8TQ zFH?-H@(wzRxuB26fDgr3gEEguw&P`Q4_r?I(v!*)$Q;Ibq9#popkC-J!T1u&-_Rg` zqS1e06qJmEBa#oyrXj5Z6bYuQ_1?iyjYpDAJibN#L^e~{owzTmN)CJq_u7JX*RHmZ zO!yo#6`IxAIw75kN)vg#De=P-xe4x%9q^GFE8Y+AKse;<)0Z(izP#1I6>g`7)nkP- zzn?O1W~!1>r~C8;BY{g$H}iJCGW!YZjh+=8cD>6xLj|)1G8-K~2MW|8AG0r?U0^=w zfvg=Ga2x)4=4w6f1)=x{^XjqZrhqpyKFdUSwb7m?fh$I-yz^{70!~~+(I+oMu0T4c zPAi-_M+m=~5+{}^5gsUH^-TMP(V=3HRLUj&;e?D+O+&umyRYZXXb?@BiEvMmGH$2- z=LCy~j9A71$xuNiDvsO7(qcHDM2by^@D}6W`f5d}@&p(M^?erClT<4us0yA<---1+ zrM=Vzi^nik+fk@Dj?PF{M)Oq@H z&`arTxH_uy3DT`t$h;JrpV!(1ahNJgehm*=e2x-KPgR@}Qm40F*kK6Yruoxt1YC{2TYv8d=E3D&?gwK$shGl zncB>$S&$B@BcbWzdy;%>?CFEa!i99=N{jHqK@FnMo~-7j3`rDMwOYBTtigS*pg1Uz zgh4|cZIbUpe+bW=M&yvbjdnwN4u^;9?Ha!OSOW}=4NVP={lFDjs2s)>!Cl%7lX&)%r9lV9;pG!t@v>UwF|n9qsmVe{xLj_~ z<6~Eq+q?#(rN5*Tid@!_z&M_ae_9s8rh=I%9NcQdpAm~>yFy4cqr?=&B(rK|*Pgy6!^AyMxNt%aKWSbCt_F_ORK!W zz_E99?gKV4@oGdHxTs$JxT@9Z7^N6e3N~i9mQXe!fAH^I;*uZ@q#YCp8|m-zH^*ZX zYAfV2u)=yuX1i+`+r!8I&;eqjNZzEQ?nt_%;5=_ZU3rwAe6n(V zwIi`fI|7Os3<5ZJJX5wCcp?Bn2)c8o{KhoLHykV@xFJEmIC0^Bp6Dox0Bop!uN~T= zL}8mnzx>4YzfhH#W{DybpomgC|H;N-eZ0dqxG+wRbF*eUD^B$*?!{emTb(v9+I(~e zbIaeAHr<;7JVne&%M*MIa?N%vF_jo141h{S4_+)#J8paG* z+4^OkQ9E)I!?3m;ZsxZESFHsqqQvP0HOhP@itqqVSMZ4p_oC4s!C38hN7erFYQlHO zxy?=Z_ZOmVH&adQ$mnfkC{1xl3QVvYuckp!K_{<#EHY6td{PbOu6>g$_$!`0!*`l0 zUsUQbNpTkZuGy5p^g!`x4S%8$++u&ri=uQgjwzzx`cEi;@zWy_S^P=Z-0yu3QK~X+ zw_3+}EFiO&1lgu`y9MxU(UtH}?135!a7I zl&l1O?lpzSHrF~-shgAF_yJ~b@rBVSFUXv2jDrmnhh;JoLxf7~m4GNMvNpn+X>zVr z1uuahmZUVkhVmmVAq08#0@Dr$87!XbL{K=jxhm7##b(!fzmCFrhV)8cFHyM8;CEzzCEp+exO9^Mha15L$#rseP?3^D=0->Mx0h~ac zlEX?4agiL0hI9-Q@mIgS`=Seu#m^cU^2`d$+F5+$5@QguoTqdReC#WQgl)ryQNeZ8lU1 znD{-=oMX^mW%^;2i6qBbBSKP9kx5~bkVVRqZy=GcsNxbQf>)Qbk$Q)#ua}7&;4!l; z9^HCDA_de4!&Xp%q`EiWML7Nn*@y0zXoTN5aGhIZ@Ax9dF5P{dV!aKkms-u(aLKyM#F3E%Z!{&Zv_?4#5H38A^X1 z1qzXwr1M9DCkZrYCrd5PHWd_G*F8WOMQ^?f^;sp8deH<@v9~7Jom44}pw}0r?ad-3 zimg=?hyB$W)psRORp&{q?dkwa#{jaXJE6h56zAha+%QN`xgQZHE|?)0FEbd)tsOo= zoj?E1`{x;D5|6{V3-?I$$0>O%kuMm2Ur;g92`QMBH2kdz-sB?*vNLP6{ziHiCsZ)}NF5TxMYi6sSDh1!7w z#{3klu*T^y78{8U3KRT_Dvo)LeOrHqB=85qNS?Wn2BzkM$AAVw+=&^gbKH4>)X2^o zwit>ucYS@?#lyoud}+;LTJyP_qA$1TQ*1_~xoX8|gID8-Ot{k_KwyxfeJz-IH-}-L zrp%`KX|FClE!*DVdSQZ%F+JVH=|m_@arz4L=80b`4jnSyItNA&Lu1Dzhn&UXzlaID z!a2+V)T*t04ICVcc-s`Rg3~WQg$gdwCp0)>KWvEwMt9@%hfwUojSmH8#>0?Oq3;17 z@~|Oi++YEfur5=ZnanDj*zEm`-^JEpb=LWQ<>m4dr-$X_Y;w{{=g)QRz#4o`oel+ht@eFFb~Wt$8RU!^%ba{$sU)a zF$nB8J@d-Stm@sblbYSmTGHE``bTZ78ov^!Wu-by)6yad>~gS^Vgj?{9TM)&tr}M~ zT~?ohXwUjI*Inkvyw)>455Qb1FMZQ_-MjF;MC4ZPzQh@!Tp z%>Y7O{!&mrc!q+}A?t{kk|ICDK!D@ULC3!bWB1;gzn?R8lShf&qG1j+;WWTKM4|^n zJ06H~c<>x#jsh>bQ(}gYZo!-B5K=jHPpD?1fN;^5ZRu8QOyEE0lN5Mh2=Izev)Dkjcn_>N6O+}K5r54To~@&0 z_WHUfzh)1&X?%4}7qRp5MvYVT`j?F=yq;E4sC-`Q?JGBzQ{HuZmvL?MUz5}>Mvpa` zADg2NQrG1ij7cPmoq?-T-dJ7UqZi~gu)^+)6Spb)}Xe2M!;?8Q;GTBdy@J(1$UNAU;B)L#gtKJue^#cg~u zs_=9D2o{{IXUCnxP#4)Q>;}c_YbuOF6&k25jldq_Z=>rA2=< zw8Iy5BFLk`p3v59#G4I+H#+t!bS+Dicq1wupEfcwHyXk0wz3=zgN#l!2FGzVs{EvS1 z*wkRbWXxLRx0kiw5hM?_6|~to$T28c<2YvN-8No`;lBibn2`wyrl(2nR{JL%yX+0Q zqw5ot9v;pp2Z|rqhclh}AT{0njixEVQ(O;v)%#sp8bBqLpdjlPl*-=VGtq!t(FX*b zXIm!xIc%*_282%jG3t*vISnI${SnW~-CYG~Jj=cs-u|HOM0W{TwNpoCZDBgUy13}* z5hg!6M7(tS_=(fWaZv_e-F6z@fUo#`sG{anYLe+&*f+^ye{Bhwv8-=kS}Lm)BtVpZ z5U&N{!DXJ%;1WJuzMt#|C3^;z_#=d(gXHQn%4Jd4uR16h9w+?9auf`jsCrEl$@FgflE_aPY4w10OuBtqwm! z@q3L;vaj8T$tGgh9I-=9eLxiecs@FCmIb|MS^)?yx|mtn?7N+t{H0U<(+{6BAP9KX zq-SxT&bwzuI@q^ip-920wA0s6A!SvIO<6|$QKntr{%5!D!>?o_TQ{uUTGg}ip5K{b zYFT|91IBeX9yfoGlH4b)%B=<&n^&FB*u0BQ3mqI-&O(hP9Ypkn<}?BW&9zJU!sTf4 zb?j}(ZvHkZD(FI1=U8Q_5v+m^w(PZ}vL;9h9*3vt+PApGt3FG#M;sauUR|}0g{DVLUuf}(6u6El#1Oz{lrUf=m z&nhpyQY@>!QIMmzHX89n#l{W+VOD1-nZSJh{rAAQ%ht9(+jjyD+Z^RO4)ct+Dam3I)x4U`0)6IM274Uw7_Rf>a+yqGpkubG@HMXyaKMsdiSvV#?EgS+3a z)N$L=LD;q_ygB6xl~Iopt<&bB!r<|k8Sf?a^l}(*+1DW`k#imgVSEuwy|sHiF$yFx zH@_6-A`^Moz}2@~(hkvUap=a8v@uwTz`vpt9yJJo6j0AFa;RwlI&SQ8yKqM9tP+#% zw^{&nG(ToB!RJyL2LCz|@ksHy9QZ9)O&Q1*Z|fQU#rH`Vn6nP&T1-g&7JODnIOJJx zQ#5Dh4I<0fh@I@0DBLmjI61vz3ta2{*JJC`%=?vEhyB&s;p7#6dB%*!b^eDH__I!A zuK}xJhP>I~j}zhN`IV*K66@zP4{K}lHTse9hDLs7Y5J}CWik(~O0~{Te`PtEA3sOG zI;nQY^>*5D>rqGC+-C^X7))`9Foi(=<){pK)jrM_-EoYiXHTWSeb!~?+IOaAYr&=i zr?28#*m_FiMU?Ogs&+7W*qdwbWr>{SMx_3`3S|aY!xcG(;M1vvsReWl}MxJ=JI}Mlh%`|~C#jvva2!qp>UEkxHAD5QT=9bT!GCf>o zLLIOEK(8M56FLq@^X=^sChD3s*VAVI$+Tz3tD@(Pt~+0|E2+0`Xgxn`*lun<%Ny9f zNsYH393y-D(y)U??(!aC=j#J>>z*)Ue(2 zCayC!1h0|H<#LU;+WT`WrMzkycHzjtlPI9~61{+1wx-)1Ecg9E4R4CBqsPM_`^yI- z$3MOOJVDcYPhx+Md^GWEz1@D&a%!rR%iP?`gsx-dOnI3E1|U)(h!ilDBi zVb+vz{8HY{B7!>Q7z3f{Gvii)O`FiPQI2bX#Z>!cG)L&*ydrf~fvT+}0u6gp9nZB) z?@MYl)P`d#nae$7GsY7qRO#)4zcftUQMC zW9{{7io@+-cHM73&rua>xu$!+QTVOoekS>Kzfmzds6q0}myahtx#fWh7l`&TZipba z+RVoHH2=8H!HYf^b=>Q(g+lT#=Uvbfdy!1gf=}97v8eaj1$C8F7>c5)a8;?MliMkK2Fsf zoKRwjdF%!waUyrtoSz5Ek}=yaI`)36GXwC|H5_Y0&K#a^)j6B@SBAEc8y*#ht)C8l zrl)^V7f7_VeIu0P7(5oJWGt|Y7;8QhE_e3Z3ja{d!}%0~N+KHfeV;35d~jNG_8bAtCa?h|57e z`1gSD>3GXWo-1&YL5=JCCAdCz%!rh9tG~ zUu1XZsug|4WCmbJn9Lw^bbsbH6kkb#6a<3Ev0W`$aAbL2tVwlK+Wwp{iK`QYl<6pc zx~@DulX@zQcS)q2a^A30eT;QAg2_3jVKj8B`spsl%chL!ZmD)Pn80(4JQOrtH_)mwesu5)?sc^5r+n8RGH~C9gOAuh zvp`N5MA;CTzwQ_{9~f}s@G=kYMSzKqiUk12Dxqc2!Otg!0F(u)FOf~YI4cKkG4C2W zVg&n9Mu5EUN@P>i4D1Uo2g&57x7QdTA??iDBvMy_7H==CJdlxy-Md$JuT|Amt(FzB zI}gz4jv*WV6oW}FbQRuB^$#KvX#pHl=mZ^p24t;B1;d{d;Qu$FO<~Hf(gAomA!k-) zyvbAGOh^sUzh1;#jgTdXkR@0gO3UZE+_xVc&SAXL@D7u5y63$7k;5@DzJITDVSVjr zs!h4$PU6zw<812_9JQ)w1-75 zrRy@Q?;7zMM;N(Lx?}5U zr;I9)l#YOMd!>jasDIfhR@dbQtcl(bc?Epry^Ndt2y#*6{k-><3pVh%4ew8YjnO0X zOE?-l2#gf;P*tu&gm&LDhgn5=G%WZcniFB_3jXUmSV;U>;}pVBodRRkf7LJsc{hn1 zCRvAIx^b^52PeL^zESGzAw5Ho32r)XVO={@e?5+x#>!_l!TJ|DXaP`N2Bw%(;RR>CtaCcY#I;Wn054yx&sg%i%9~G zrVg^{3gP1-lw$J#D3(4yMTz)fhvp2b_AB*%&q-)(mDV_NL+sl)bwAh?Qb+|>bW;$- zBhBOO?m zq$bTzp?}$c&8`>eFX1__h#+%=x4LNU1}>^1C>ow-&9kCcxjum($^k~?xr{(B{_#vl ztpzhaNkdi4uorV4laE5E}W_V5G5646B3ACDX@PWS&<~o~|7~6x?Ef*gJ zQJ64r;kuYJZbwds`jGGT zUT~!BaAO7e-v~!Jeq)&aPTF|R-7nRTeH7E^B=*bvtpApbgh0_G7cf>LG;BF;FSvKQ z5{9!#o*LMH5M=gdg2><=|0f}zhKG5y)B%W^ z;{NY9t2V;0C$xtHtG3M#D;>;7ysmqe^%CFXIU%CBSV~m6ie~np|0g}CMZxHAMoQQA!I;-g9Y{?=IcZ%*59as2oLj(5%1;KwrXgf8ekXh=tU0y3p_T z`Ljuj4#B*QM{Tu4v1QB^dp|K4ICR})bnS5S@XS^BZPs&8IZQfeIj3d+zaHYlKygx$ zV5utsmlAB4{;wAR8X{T3e*+1AAsru-fPlc|?Z^4;<;VLj-i!X++uK{`(a8V7$^ZMx ztg1jYKZ% zTSCD9-x3n2gf_}7f%w+M)@A#C5;;96Sw{*LN0?n2Yms!qyEv`ujFI zY3tVu6uHpJOahGmp-;?E+?z*Otl%E_>w-y<(clow|ND~fn0}CQ+<&GOd7(srlp?#G z&*mRFFLPC|e_t{_R<_Ow!0g$tkm&yfMKFe658c`4#8gS}s**=jQ|c|cjs9_r?m1eNMUF_I z+W9LWDg3`cOG60CsasjCm@7F?BVda~P~Zi}%Do(fanXEOBFrqSTNaYEPrK|`R{nHH@0E4Lhp&jH_#+|ZZM z?){<6rDIr*#qwF*;BZa^2CZ+%;H9K%Q8iB42bgd<)%ARIxp38fDtv2_GqRyw-_@1l z;R=6>ZNL=FYDk4ppOED0K>3#u`GOR(lm3{r4yl;+jZl-MYx&eIKxr&XR}hCSBy0*1 z>TMSEHfp{cnFj{g`y*J>kxJxM#>CM~RQI+MYUh97A5%gN8r;65a@7$+!?eal3~I0W z49qC5vibciPlwnf_!z$`_BVJ2rmXXHJxwH2eLQNu*MxZQQvw{iK0LdwI$u`ZHk9A? zm0M0u4*%l0Q8kEaPC#_VmeOqHe+T75=QBQPLBfc405tHVsoru(&1TE1B))IP&_YE$ zZP>4Bnq_@!*^FDdX)|&W0Uj5(>swmJo_=cCoQ1r~Pxbts$YJd=r?Zw?$_piBmg^o} zSdIiG<54Z`0 zLuDB000^8Xds_NwK9c)M+3I6m3riF^sYrpm0p|9r^>H|}?eATu7 zT-mu?lX&0VnSWWNGy)FEINMaURb=|sQgMA`Q%z@N&dc{-ptMg1-l?~mUC-*E`zl`{ zlv&TUsCg`MNM(_?`j?cCp)O~;Ebp6ENA1sn7_ z8C?7ulN(O0=Ca($7qc6Y_IPs|{uvz-miW)l2syYgmf7GdLv05!{f2Dq0waUb>L- zSiy)^En7ws4`W%iv8xbJ>!{@I?+E#ZZv2E*+>40gG1n-$xs^x>a_|8bC;Sl!Gug}6 zZ$8Dj_c}=YUuirfTMPb_A1)a>vq|t!<^9!$t`0F%CK=W9)ra`}T5+aI1@cPkiVg0d6D%~X;Q z!5iciit?BEAQlg{DvJ?!!bHtk;-kKTM2lYzp2I%xie}Gcm~)*H{WglbFucb)FDde? z1|ca`SYLUk$CFO;46OFOtCda4y!TjLQ@VmuDa@^FM85(n)y90{hqj6-rT~ydx=?Vc zZ+n7ulnyvLY~wf}3NkRo+_p{YIg3w`it8%fBEkBN91Y7wh`1wWCw^&w(f4k+w_J_+%n=wOq?ZxYyR;@74 z_85G7H1}zzZr_5u7%K8f;Rf@4_fPo#C=D11*DXI0QcGjJ7C_-X0oFKiF{NDIv!`Vy z-1rQWj|6A)_K|jJCvvJ>G}OPzlmsl@lZ!eA$2u3`+aD4-IdudJ7@3ssf-4~v?F!Xk z?P8f{SYW>;Mq59IP(faZDit94UUHjB^YX(hj2Oplm(=VTe&(Y^{`Q+x zIzVf4bw2#7gf!Xt3zHOblS{jWWZ~Xd$}l%_s6`?1w5ICVN(zu&`%TD8g2)qyso_ng z>oq2%k?3!cJ=`6vzk4U1u!(gy^ZsJEsljjC9Jyt;)o<*L@G$Al?tTr?m%ng}?Y+Od z7L69Y0vg_tPM0N|hG^wtyetH!B(fdzu0r2L;FuzNJBlAAUQEeb?|AbJn!hV4Mxf=Kyq;aDTWU`6}i}F#1YFsQOF`xg56`Zyr zJV#&+T|<#RV>t`MuxLT7K>9uXJqi%%Zpr!WyDG*@V~)fu>Xy7+i&(n){q$5w96c^=78^~RWF z`Hp~2AnNTT3xP}p|M6!H8G5 zLhp#tDL(M;AZ zwR!%;NYBWblS*?HhbS%lW@~Of1U7?h>3HjK2B|8#LXMA*HxCR*g*r2#StcMt&^)tB z+gw@8Yq!y#oS&EX1v~x(q8}^{R0p?`Ps7Y41_+f9T!T$X{-vZe#QvExBDC(kJ%nY4 zIRd_uZznnLmhu@sPbogyN3>zpPZG#qbD(#hMyf|IoHzz4+j6f0(b?<<3*xY+k-Bg! zwp6r53{mq~aQ=JO$xRcA>c(Aq{LN|shB+n!-a z!x_1S^d|uu%t=#In4Q=GN%<@82E&saRpzq?s6*dGSl`I0XJ?Y>{wXFvb3W zs0+Fa7e#}LdpuBKYo0}@C*j06(QC4+VI+C`Ox{hp#nA+zSI~BssVIV7e47}M_MYK; z>&cWDBM1z8Ir(@f(di{%^+0fDP)-O{k<+pM*^%Y*Wp_0$vEHRz104b9Wb7hRP6%g& zNa_?hK1CDK%3ltt+~@4v1l!fabwBUa?eX0q*ye9frr8QmvwMa%L9 z3Aw#@fYyWEwp^|{JU4A@>`rXS&n44ya@==ZE24f#Ft_s-e)TT z>w;)3w5P)A8V8-FbDp~?NP`_=SQYy+X2>vZ{}$msmLql@lHnOBHspRQ@)LjKJ}o)E z#lZABNT&as=C3Xu>~ewRFDcAFs;Ze5O~CdXbWeFJKP^erC$YJbN~&?S-f|1hpC68l zVmCi#S>EHfPBQz+Y*IDl1IWnAh~=$(M6)-4B*lG7rrB1ULhwW1S-{v`WUPB!`7#hY zOFnJXF6|6dYIj!8IYx5X*5TjW_s5BrLyVd{sv#Sf(=Ci?n%nSDH+tN`I5vA7+f7)y zUvcRv2jp}&@J3?R5*+4&kw>ut2be(|YvO8eGP=YCloqRzItoZ=E-Ee~GP2&~K!br` zOvDiKi^$FQf-_D2ok7Iq$12fR6o4#vC1`#0-4-c(Ccy#j+sptG#RLXk@ z^JdT3-ca-y{4b78Vd|+zNz}mtySIg=b)L=}RJWa8ShxGrh5FC#PGM*8@6YJXEx{gk zlJUwL#YNx~cEL_bhLWn#ctCj?3`@8f#gfOc_WQ4+7LGSg->3kiL4H8}dT126V%||T zk;Nhbm~Lg>460=gFJxq=eqI%9y~DkD%-&}^Uc;bpcacSe)Nw7!ihlXnDC1*REiC>)lwRIjsKy|pYB?XH7zurmc@jq13sG)Nq_fk zdbhJdxG&qtu;aXw2^1YK%WtT5Hk!g^$|*Z4K?}kfBzK}P_{?G~8GtH&n_wZ3DN+$@_q1QMIWTJ9{9XvJO`M9!}JlC8T4jO$4HzrNEO1g&>90Oa%%Bb<4VYy)wH;;!U0Qr%|0_(qs0s z)k7l8w^Q<1XRC`YL&kU7*7au&8UjTnQk`C?09Qwx*r*Mgb=v`)H);om_TZRV9#S2W z@<}{qeS3po4&2Hjw%Dr~n;qK8 z0vdZgVL-4roJZXd2o8u0hdlQX7hkn@df7XJ0WTCeIhjSJA6eWdRiOUZyF(qj2%{qb zV}#aYVGM~`+V^MLbz0#kL@vTCVQ*EuOVFiF>qL}dQ%6SyYF~-%BZ2M3qp@i#xj>x0 z$ALQNw5+Pt>1gsq!wElL|JO+oPFPp$hLZ2ieN`Jn3d6H97XAFaimhb8beQ)8ITOsZ@K#+;greD0d`ZL4^^E$jddQ^pibmCHITEOx_!BmB`m~F_wBNWCufj$P{a1-SB+Li-^`J*Aoc9`#_Re@3iz)3 zwXUT1>(HB{_m@kzoR{^Z?}L!?cFrC?>As|5J@yP!uK^>ni*Wv_Jl(iMbcXuyp^rFr z$0sTuhbK0Q9>XGm<1ex5WzN7@UkilngWmRy+pO-C_%1dbapCX8z4m}XZIb}|tUhgb zc!2kobI=Lo93t)}d4#`AN)c(`&p$h)hjuoTzmZQ?H}=X335DgbJ;Z#TO?1Q0MWvmy zqEQsGx7WPeBG>xw3pQm;!rt3pU zVr6krW+_*JxV1W*Q8O+HG+oYvk_i2R15V9EV)uNFYzMc+{i>}g5&P@`V+Auk=$3u|| z?K8HAHzFrN-3Ee{zUW&*1w2qm^SG|{>qw;O_73LoZeBIfH^}SG>|uyQPkQ=(a&KO* zPe@1G1J$fglGud4<5LiQAUnQ%aau$6oW88_v)6Sc(){|*kYcGzs8Nx5WqZ}q=k}M< zdhhn%`BGI43##$pcn_s*a5WMUWD=Nh`L2Q32rw3ymA8G{#|hkTjVSCUisy@fXma|$ zpKu&HI$0EAVN=hkdMESOnrzRGEb#UXFF*s$w_s4T^(fnWF)Lo8x`+7n*V=_nlj+%G zfR47dgUrBkAaYwAMps>3K}2g>8nm1I@utsL7LEEnWMIRHS3NBF zDhI@PZf^P@s`6lNf1V;KpKXVJO(u$P`PzIQ8U#@q1!hCh-kn!o&5204JnP&MOA%#L zmMHWazsTJ$`|<_xFV)JSaCDah_? zXy2|C?>%e(^j~VVw{S1Tg(Bvioaf&q`-;5DRYI?l8pn9*{zl}^K~VO+ihG;?GRv+?bqe!5JP06RA^b^0i5b``O@<%Hx}^!P%)A|qx2=V9stc%>TbK2S zQ=8Lt4fr6uLJ7dYi{RL@pa6Kg84Nn$qxUmLDpi6uQ@4lU&wN*>IDiuFe?0qM{xo+A zr*E=tu>&-oG)TS5`shZ{&c5Dlp00`KTm#;84RHHXsf?JE_8~m9gb#_bR$=Gi$btw) zq9$L**%@p5-~X)~CAYlA-<(Opt|~VdvLu%kosTA&o}4eTosWgw_6||O-XS5Ze=40> zueZw!=70<~tk0S826oVa4n`_N4V|6E9{vR8lbLY_KRnk-M0|8Db753aGi#hr?<~2b zjl`J;pZL9lilY(rUjDeEt+tMW5hFhl_x0Itu4T{2bLzt#+bLFp}{ZpU^N- ze4~21Tby#q!``vLiL%hJ%;dLqmB#_DYFt>mDD1%09Y7Snn#B)bNpmb)I zF8$syt|hXh-5& zFd8-^n%Q|BO?g-?LD|p_emo5O z6sH#w#kI)}(}yd_b>XqD^_Pr@!`kMmD)g-9RaT0g#PX;547BBCf9Jd5TEaN}$LZV4 zH1li+TC*iA=5yB7WD-doowZg8OUsk6pd1X7S<8)%H(#J6`R8-){?jAsRr0*@dyBdTX@uyREz}qm;Au^;1=|q++KGZ1%PnaAD}h@Pyl_B0 zTj_NH)42pPC%V0bu_}-_QzxY&u5V~1_J{+;w?Hl|Z=epu1`Qa9__?XVRdceTb`exD4mMcx!~7OeoBBx z2;_LA#%g1(clL6)(P{KyL^!-Fb)LRGDRLS=g-B~2xgm)G-m7Y9s7MB)bbz*7?2EH^z6uUg(cT_6FQo{M`RS&fmx&c7 zp01XnslS=9{CV_SoPEYTmOiCXDzGediFL-0_kl>MCYimwHFa$T&j4@0FNoUMR>_cA z^G!8)$epYcHKu`9$`!f(7EuMQEEpCQplYO+{)0&u!Xx-)nK?eIuUD-IUk!PleCGs%Ph?~&OY98G48CB>5*8S6BTiC_ zY{4|q{3O9fb>JV;;EgePAm0Z zy0Zj)l`K>GweI%klv{+pUTY0!^bDq2 zniu{8Y+RXS?@i|3FA5AtKwykqE()p!Q{Q|MCyi~+PrqNbS6v94O`8(hTOv2y3_dE` z7>)$Q!eY@vf7|`8`4X%|3y}Q^X@kR49x&A?s?y&ucUFU!Mxr~EAj#IRxX`3Zfecza zxRsCNOrD~a7EQJF3M@BVB8Su6u!PYT6-oLCgC@DdF@<;|#KR?I zWu6-A#p1MIopLCKnvD>?f#>0d%b~ESAFiO9^=65WI%M#eL&b$;L1(2J8H4j!sc9gG zqi)$MyJ+EBsR)1#<{OS+`pgvR1B;>JeKjSXnwGW@P9~ht#n^TJeAe|2d$DK4P`&mz z$Kt)Z(cvv)pwN@*Wzo47gk4H=yi_Vv??d1%l&6jgOZeBc9H8J6SClI5%(PHgK&5*) zP}-!D99F&lVqUL3mNV_8ej>lNw7BSO6b=h@=v(JhXDo?j5|Ev60>QxAIdY)@_Eg87qsbQ8(<%9VD@GJN~m+g^znwr7D+ z-4f?qr(5z1ZFJlnr2`H%H3{LFBd>2Ai3oSm6vc1H-eqCx%urN+T`MS-uHr|g&hs&) zb@VVB#4A<@W3Ast(6-Z|79C^XI>3N5Z>ldW%=xD*&PL3U)KgDY+Dck+XG{Z`H3ryL zhhsELpeYF#E4NMi<`b@|(x`e0wXd9-dPg2nd}1EBsu9Aut7L`1zOT4o%1X`Qbr}7R zM#0W`EEFKm`NM>8`w#Eh=ydw#<8YAHCFD&E0(g)oa$vw^cZ&rhA|B5`H}7i9YK9O zu*6N+5z-2zY`0>@BumnTSxAV(zp$2*Ia~#ra17hUg|F9u|+;w0Hsv+To z_r*k9Ftm{l6!6k&ho=Km%~DKc%)iJYsN2?zCa`ij%W0uLjTJeTmvu(-#pi0mz_=-V zw$J5vkLXK&e^|H3*`muBNkr$4FJ|%oxPKdLlv2-sZTK*CGYAH8Q4q?f5qUKHc z_T44AaK`*^#)$ei?!V(k3Vrj<>LQO*H{P8uvE+F@rUX2{{HhCUYo-UKEm#Y!O5AA3 z4Yq2sE=5<9J7d^<Yq43j*>Cg{a4A598kDnt&XG0k^?>O{u zkVGcLju?DhvM8)@*r@i#7q6)UW@Z6sP{noSRc1-04)`3@dWx*hS8xW z->wHxaA+=XYPHZ+E~l#$eGBye$jo_l58iO1kDt`1i)S52q)KN8Q<2~Sfv~8=qfLCq zrDfFXgP6xm)5Z!AOxOK_@ELRpp+=SAtNoUPd^Sg0-^XA{Del+BRFwU}@{4 z^wK$!J@^+BktMMv!9(!`l65(3j03+@*W@_lr))s??(CJy!5Z`9qqPlp&Gp38MBB?% zn}JWug~uCgL&2C#u;nek7C?vZFx&SMwyC4#Lf`YP?HBLE=|-Eay6fAvV)X?sWK6ZY zMCece*!B9h+{O2`r{)v^Ia1%x>tU zsXnoPWySdHtfep+D}rLe-;?OcTL>x@1>B?0rs`U55PoexqlJnU7*S?v2@MRGc4@v= z_#|Wz&&vY&P9UaI{Ww2!yJ6=bLz)}9`zJi#KYv>64?RF-CW#dCTH!OI&na2D0>umu zW;R+O7J8_;0;8B6GGbJ<*M5&F;uH6Oum)yCFygy<)W*eJ;{zg+z6KreR(*ww{4g!s+tLt^(joo9UFBPL8w>7^6iT>`x5I|iA1Lc9!Ux-OOJo{2=UBe?H9@? zql)s2Soax=Rq1KE=$`Z;pyXroA#yi54txxcDdfcfF+d;*46Z#wwdcN2tL}Xgfs{4- zdO+2K^NOv%06LKNQQzd)iX~?8Jr1El$RkkCMd{9*j&;t#kI(jf_W*56po9HG&D7Vo zryba+gh1!Fw&qq#SpuL+fv#UlO@PYH7KSy2gYkm?ZJ0rm47N>*ZEP6E$8AYTHHgkBzFxWeO%R_;DQZ?r-gJr~ zOs%6Mz%LhB|2dE(oCqe?;Pq!A)uJ5QXI^Sx`6rv$n@S=WDE(t(m_L{O{y9I~uiLm^ zFIA6!kxZEq`?W8d&dm-8Tim$LTVTfU_}N>g_6MR(v8wHm;t_9B^=hY{av=6`+%km) zQl#R?n`Uk$PZ3mZJ$84zP3l})8N8%>?wzj$PvorRH7rSRF&R)K>+{ z^ztmg%Mo8UP}xaAt$U9gT0JGB0(2^K{|4MdOedtllLw3m58 zl7On#d`F0>doI3tx-O#SljU=k5Qlicdd-akTO^s#jc@O{Xe}HBGlJv!^#X7nbxd%IIn0VQJX3p&f#gYK?vo z1c>aNGePBEfrBzQI!>)Q8Y@Cr2)NimLKy}!Y?)*3AWy9Qtv`WCX7Mpd1sHj@UjiHA zl{vYezDVrLd@JnPwbr*2w#J!bWfTJiey|Jgk-kkk3wd2M?PfsN|MZiLb#aU!rt}39 z$LfU;B4Rj^-A#v1b+@*dgJdn;C>t6yb`X(bWTD?-B@F-g@BH}YO0>fSi4Pw*m5(1_ zh!FtQy$^^S?D=yY7n2+{`I*EC{>1Ezu+vTE`)dFZid?m5gf8c88#(r~jUd{!&;E?e zJjBB_WlUiRk zOWr9}->I%7NwUif3mCXhDET+!8QUF%9a5mXbEvd)ni$(BBSk{KzssyT`);uL=hQ61oXfje3~nnYNmer1<4Y{#=XyXyrYs6sC4i5 z_%^*T>>IBenbttU7*H9+;dL+ePKI;R>afiqYzJlMz)c7oWN~I5OJUM7VICo@GwBqc zo_K~DBpBao7q)AU746_s@FJ4nKP(Hxz>2O$qtmzVTUcsD$KWRZV{do=neXE zf!ymB3F56<86y~UH;asXvnUhMB(U5RaQSj#Sdxmvqb7kR+JHuGJ?+Uw6`ll$u;-xK ziG;%UR}dp3xn$GsD*@jWqV%TLkz!oMFQl-=K+IZ>tX*HGSZI;vE=LUBGPKcP-gKSVgc82CV<`p6=X$G z9@uiN+YiB9_%aV$X>=Frxx^fA#FXdBbd<%cng}7o5?WttYim8$04E80u?E>v8BJqI z9>a?}isSXTG^(46jjUor&uOXBXS);B!Lv?eEc?72SXTO>Oe~U@Q?-=Q0The+64BuK@v#aOKEK)FD(OKaAH^P~;ZbCPHKV#U9b_`@<71$J012 zA8+q`vK*yhYI(gAwQ=%D19x0V|4BpBu1P96plQvkS+d< z3?-K%vn9QyDV6=o)p^EC#@|JBbbCqzYl$A}cQ+m+g&(?O?|xX>F4lg%2@5)9sA|1x z2a z0?ytZ!G3_!9xB6MK=9ARZ|jfHpCGbNDupxP{f;(VK4u#dKK&#!G~vDD$4A~|*xHG> z^h3Kg5;Iqh&&cF-tP4BDI0H@OZ3tNkwaK#!&yze8xu*;u_c0D`-RiP`A}z2pG5=iz z&*Zvj7+vKgxZ<5};uBDu5+I5juvQ6iMV(bx)41PIQO2)8=kS~4xmlOL5qWAtE;hvf z60U=B7+TmQ<3V7Qaij1N43B{ICo+)A{Ji+^(9`aS32AQTG>uPjPNO#_&#RV zZO%2@WN~Jd-BGzn_lo%4Z0EDbvf+uhx!`3K+j`Z>aXEkT?Uz0lO)|f`MftiBs~msX zg2=(#oa!Ja_<;7C7Kf*O9&ow?D0Q>zeu2@JHtm)IQs+k~MSV0nVJ9Wqf$ zf3TQ(^Ac>>HHxEOmQAzs8GR%7Xc3&OWyYw&ELoE06Yff)_ovkner}9uVHS3j_Z1D- zYl57r^tr1eDH;V4)A070*(zM9#iNS^vuhHaG`5=V>D)I`YIOsFQoIxdVa15 zs@6hHQ^ck;xhAZWD(y|3c>=MWzz-j(DA^QdgV_|(R2f4b|0j6&Xc9SADx-k#9N(ot z9<~z9&J2a)u~I|eilPfW`bI7n@%Op6X^^Y`(o5~yo9JP@@%M*M{!4lwfD*LUmn8&4 z;i?a*mcXM@9@BR;y%;t_O;_S$^zyK;kZ_^PW)FL^!nwETcZPkuE_hSn?UvqcvfSK- zd~Zzq2II(QQ{51P(~mG1dkxv1lvYx_`>^jmrzS+jAE@PDe@-^=TuG z=V!0%r65?z)%?rtliOz}Ew(rzctIHzOyQ#w*s)q!QfYyc&YMwtgc^y= z7@4Z1fn0njd(zp#!;m)To7%R!cQeo^Lsj!t$BhtphCt%lWdoW&AVD)RUh`e!@doC7 zXhjhz%s-z8duO{OXX8Z2y7RHy78A?QL=r~eq_qE z&f%tXb`P4FWoilx8H(AHFK)Q~*sz=L1T&?wJR9BC>Ypc_Bx#ixu?9Q3r+^_ykv{gM z4qk&a)YY3TiX0p#oRl^8&=bYKb0#ipWHio?cjp3CV8%UW z^0a4=_Z&$8Y`>Du{B=+fmsJY8dTH)}8c;}Z zN}pOy9m#ao41>h8xH|e}mC|_zNya$FH97E`L?G03*TpI}9GXi=-wetOv=TTOEwKfs z#^63#L^4}v1ar}Kpae~|gNK~_qdw+HT|HQwVgUW5_s&C(KwlU}wNpC>-rzns7=YJ( zboZq+rs&nU>{&jaZ z-t)2NWg+bDud?^35OA3Cax{tI^0n>AY|}x~VL)f-;zDsmX3{>9CvkNRdt>V_=>`5A zvrSvGs|Wj~Jp%qED!|xuul-3F#iVma`|plmcQ4xB&=Y`$rPxNgyBb{gvUa)O1wy=^ z>I%OUj-GlD!NU--~^SMx<_0(i$sAL`8)?Bck2Cwr%hx+b29-y5V zujQR{N_=m%wFoYZ(0rk%{e)k16tjCOw)-w;hfHSN>;jFB<5_XaE7?BJmY`i@F<8(k!TF3>RmBEq{(>jzw*H-Vww z3h46TNlE>|bV==MV{T!C)<3;;^uY8mMZ3i-%VSmz|5Y5-?pSsI(mno5|CL;gGhBu1 zKyTfFP!_4c?-0))BHco{#cmaNTw$Z+c<+tcp7GqfvAKy_ui$#s)&HByMm z@ee|y1B46P+%Bh!|Rvb1KPmJZFJ>n zr`ux?G(qY6w0P4Y;L`mlGa8u%;-g$hD&^N6Tq1DbI*#ZecB`rxBg@FRF}b`BHGkQt zaiS``XgRm`we%d)QG8G5bid+~Qy`K4xkMef(`r4;bLP|h06JTQugf*nYo@9B!ymW* zHmxYuqrd(rBNQt}=5K$r5mvi!F_FRJxJ&SA=z`JMe1DDjdCk4L$#cqf73mGu3#O|6 zfVl-aOMcqYe?gizp9B=ngAD__xf}B#N{gjr+*1`b9SGt0c~CNmJT6u^VNln_Fbe?2 z#F3WwZHt9dJu!Az&8%iEHWj}Y&0Iei6oaKBt!aLX8^ev|cQyVP*9-yUAw=R5BCQ-8Tz-pO9GyuOO zbQ@d{r}*dnJ56oxAUT+iVVvHdd*gukQF)v9X&R9y@6s4Y%lJB zUgs+CZP%JxAd$s>Q0UfCmf99}*$4I0H^8{}#K5oGSDnUZEefda)xerYdCzOmJe z+|ON}4$EP$ntbv^%))f39%GJu{&Z};rC4$;NJE@3*U&bPT1haq2yS#kgTEj!VZuIsND>oR%?z+-_LD?%B;~R> zAdkIB33qV`E}(D8qGt&w{Elg%1#_L1b~Wl1QQh~obGg_x#)U<{<5v=R11IaBJwHde zIJg@u!xW}t7m36OM>u1}f^F?MzmO<=jF!%bDf zi;a~StQInB9V9>Wxf1MCo}wx18vd>n5rY<=`-TNo{3?%B?hh3RG5Ym6u)9ze+nCaD zRr3l&b1>+Qx{im78zkB4`ys5?ZvXX;db7h#Q?}4`F?_zMC`KtuPzvCEhe;yrmC8Lb zYN7Ap=KxWa9Kz_d;&A44OKy0Y(ZU0Onn*JFHhGxM1RC5}uY3CTGD@)>+VuYs^;S`F zbxqf3ARRQg27)z>yA#}L+&#E^aCdk2;O_4365QRL;BLw3Jm33|bHxok#@>6as+u)x zR+agyU3Jp6lv?F%-nA+!)cD_uZ+f4|B1+t=I8?~u?V+p%SX|6Mv?K~(>NldPel}(^ zBeie9m~Nj(x7**|=g{rnDXiV$p7o{4zqZ?udAU&~E+|fwGq#tnRW^L2CK#(+wTYLJbEsuy-tFqwD2?YW>ZBTlY|DiQLWj zcKMy@CHkJkYnUc(NH+?x6@Y%y>GFUW=XkOH?Hhbkd3l5y!z~G3ut1*#EoW)i-%eO#@yCv6dg;?W746`4rcxNYXN2WCjL|qyj zEQ>s&&)1Tl(mWx21oRH{muTL58p=hX; ze2Y*0H8It_ssix)ZfpX)dSSXOs&v^zWDvmE99e1y%A-Of^?bDAj05O7c>nlZMuNYu zCV*qa{W)vLWGxN)7SZze?-n%GJ_m07cF2ULx~PoD=&PU?-J>bxyuLLW+dHRQn;-0t zIpph!XtQbbTJ4?%<3Ifa*tiJip7px)`!YP_Z%a?8k)Xa(L@VXwIO0&Wj8M^2KGBMu z31aI(n?%`5`dnr;NNDwVWERNXw5Xh_oJs6}SJl&;HOHdEh=f5qJ<;ut7c&sSogjzJ zdI5zT(QTL|O+&R00|A$-Z*#pDnE&m!_vu99o9Zz;+ zXnhB!r5SO~!6N59v8jg1Z>hQ6m=sLooFexW8(RzOMkv@7w+l4oRXsgH$d?mvO%m3qSdBc>>4Pp z-`F{7POvTM%#V6`ah`dtP=38TA>nerqqJV@nwUw$HO>r^7IKS9Q^)lfApP@1KU9W1 z6tjts2-WUoR`Ju^#-2p)1$sTR-~H>>%jl61-Lg%Q^jzupt^MN64wO}7SG1W&NnlNt zjjEz+lJTctun^xl$^we=8ZSP*4!_Pf9T!rHj83~LC%KRVLYRPc(3#4Iw8SM>@=UjP z4qsSXw|SXlMt91*xzY?zHVvVP=2MO@Z1TALu2Tn7Pmi1R3wETJ-V|V76p}v5hW-QG&OA*E0(e z{e`I^lGyT}KbeQu0a`j6MD4~Z5#IOsYC=g-qlqrLikV!oK36C{FO@jq7WZ#hT3wX& z>4}+BZ{5ocYAA!dAlPv54SAyz7p2^0N6YiB zlA#oLR8j3{3h2#0>YTw@y_@lQ{k^Y5`vA2B=8ws}5Xph9y<(Ij?ut9ZSHHer`qn}k z5(X=_o_v)5Zx#T4_haYPPu40qJ)l=LZ_$xAjMw?iEHgyYKeN1y8xOMx~Z^WdDms zoi{PiH|kr~`J)x|`&-W>A&Uv3R%mDTn^0eAHaZ&E=L~l`&vaP#h*}{JrkoToyOmMg z+T3lwBd#%D@IvhSuxehlxeU){~HOfg{&;=DM~TTWP6ocX-C*KkS-}(VYJT?Yx5X zQ!lammCh8g`aVyOm1Drr?!Zrw6te^-v4_=X6NAcOtA_IZZh$ z+c!}Loeos!llIH5gi33MVO>R2af)h@RZ+-dwgQLj%zO+Ax#{RX1ejqWfH`IVPge#3 zPETug%3t1{>_|N(j~mCB%3b*ZpC6nv12S9R`g$e233+Fba_l#tWXKo>=Exa^@_!t0;{hpb=c43YOFF3kankewL{%K^=O zX<~o}*C7HBdQ)>Hi^-Mc#n8tN_wz`tfK4Qb4lIjGNvSLC#0jBtxdZczpGDS-1{Uh} z{gC?OUhz*?)Wv}vU6;l6Us2-yYJ^aUnYyjDZ20m)u9TfK>`uZ3--NCyhn!iQCp@`$@y;DurYsVuyq>iWa<~nhX@eh~$ z#59RN&@&tmh+Mkf_!D>QXlpsqVk8V}4~%Y%F1&XfTA!cQ+Q)!;R~(O?vxxU8a?wkj zn)aR7tZN>Vwm8<%>2PPzd~c_zcLBB29xNo=@8q4A6M>@gH|e(?^uV~-1bVqIgpdtG zBRHlX8%QKU2Q>S@4Ta|)SZ%;k@bzh@7#uj?e-tKieVidtJ3tu}Hz6ba>?<--k@i-8A4xW5Mb{ zj@P@QGhugkD@v>D?P;s!@Hqy!Ch!yvLq~W_cvj*|xx8~nG{OHy@z*SBxQiWj?A(g4U4w#f5GU3cMotT(<{v7YXIvs~Mg`J;(-)ppzt%z>kX zZbdW8c@PdOSQpifr{My6SfvuMmnyzPT*F*)WotA3%Ze$N{C6|Soj#mdc1y0#J=5&~ab z?{#}?Yi44iS=AZfadNfO@0hLz%-m60b-skmYb7A4pu`W9!wx8F@39ZzI1QCdF37M^;x0^*-~KL^Nc_J;1s{Ix-a#=o&X{ooKF>F_ac zRD!mr_Ns4E?U8vk8EHf_Hva?mY?D2{<>%jl4W<##&u%M|4|>0$Hd@>g?t$9*adG-2 zu|E*jqBGab&5l{UZmx?vlC1fy&$h(q=;(w51gSXgNJk~CV^4Gx6K&e9cWIBZsyl8+ z7hhsga#!0k{&dFHv3px)TR^fwxP7a?h{<_`__$E7Ybo9|L{KX|>HsQB=T-of_80SB zS3~R2gdJsD21$@g?!ajtx*Exr4C(CqQ;-1q4I}*G2*)dz?_E%#Npca-cxOC3laT?N zks5O*b@>Ot8^0-sp6oDm;H$@s``)fU7GFoya;$`T-7uLu_94#k!V}F*nB$){+mo>c zn!s}_^(Y7s-R^yt24&_!`g(4ho2=(IXXrmRLAK2*j1$BRQ(;F`#)1C~DmZ9WqOdXe zcfeB?L~g?tp?15GDx;`~_avsox2lA+*^pk9lfHN@b#cnH&hwFp7UV#|k&(rRQ(k)N z$P61^JinEDT%l1m>N7j_tOsN($>975(@{#~>8-00}J(q4rD)j^=^#ct0B^NmH;n7JRjGrnp z59?s9*Wec>8CHOR6U5Gl1=A3`%S_I?E{|y;O~Cjl)L+UkDu7nP0$4W@?7qMGB|~l@ z{j|->hP&cDBofa=9JkrwCfxrRd~#OZU6j#mGkbe9wc_LdaE`y91cp87N8!sO`m;?j zKer~cv9S?&i>CT))Qp*(7tV}O&oeS;ygOIN0(aJ_31>!7j$Nmc7*S+e`5dQmL>xDr zT!6G*xzy0f_wTwp5cgOM)Hh#Bg0M6e6!fk9d+~WvGM1{lmT;iGqk^our{hF6Fbk-J z9jY?|ErmY%`ObBjR;6D{sZ-sTCo+25EwvLY68C;UpFA$Uy|iAB=SLG9Z|14U6OhAX3tV}|b~NDRZh*OPg+NY9zfr0bX@5^c`6B<$G*qq` z{G;@ZM!xyaFaD&9%+$DL!PlWo*|^PK=Bbh9Vq-!AYyNfH3hp1H?mod3j7m# zUeCK&gBjfO&CZPIuY7&sjZumzWgVY#vD zW@EoV3BR8jzT@LVDJ^pSvHWenxK0JF0~l|%{oQ#vq;rWMA&`3zTR9>2^dnS_uKh0V z$)VVlJTek%-OfKuPBt;AvKl{QOLMqLM6pszU=M`{x+ty&BbxJq zS&^Ylh102BdX!IXSmaB$j7$r@2S=0%Pko$3mGO6on?ZdSf~~-cR1{qR zK-sX({v!AWWhTOdBq0-D7jlt59vlnD4th$zod(ai64*7QPgExPgQL=9$%5TXD3+_@wz9%sLwcic+hb4Q)z1G z*frODqluff|At1+=P;E_->3$_go2owJODxPgV*O5Oa}%~P^wc0y_H#et1!sb1giot{q%r(-r)!)r>9gZo4xp|z{;wM+41qu zyxwoAV&Y;atM_M)Cu7Fs$tGrOwUS<5TE|ytI$@5x1+ierP#t;*4`+St8mX#Y%T7-# zHQdB*D{&&won;YHqyl-S{~isF5!&tWYT_zC30;D0UhZ7d*&&6TTWz=X0+jKLHmCfXm$o8~PMkeG0 zfBg6nIcy$1MK_SNiVxJ#OG#lJaf=zuMFaici6;j6o?K3J((2>6_M=g{%EmB#iuOPF z8-)AJgvf8E&*%?t=(mFqM*!mg=S}cFskJ~KjGbatX`B4e)?>WK1^~t%*dOVmLc+|ht4B4M zK7JtJ{Nd{a%-pB5HZ_~d611?iH1v|Fz!}wlr0fe|{~ij<9L3x75YbMBD9G|Jo&`a4`AE4jehcIJ`W78L25{?C!}d^=mCd=W*`l&Zr@a=0A3ItoTMi9oS3 z$S+j{1-j08_Mkm{cdZfaTUE$(Dd45Q^;8@)VJbB)3Jd>69>etX%$lix{Zx!ArINgU-Xb3 zn}0@7O-B~Z(S$qZP^U9esRGv2!dW?Hhd1?q7h=CweaAfWkSr#;a{fP#X1#8CqV~<0j z+&X6Aw<*WkNsA>)K+!)dKP7<5W-r>TFF1i1z8_?rp6#Zlb|4c`Wa|;!Mvbf_XrabT z5GV+locf-aepVbl83Qw{dXF$;uRtV2EI1({ft8s@NZ0EgYoo(0 zK_{{s^<6B$<6-uX%T_*%u(0Dry+ec3nkq>=a0mRN##bQ(od#lVq^X=j0V`F)0pOs_ zyIZZ9`EOpxCmPreFU}OvbTzh&OSsX>{GcNry9ml1}?iO=^oaT(A@~sj9 zfU)L^737-a$DerPK~SE6ko3=9*aQT?AXEwSrsX-@7IS71fhwq=Yo!1yWnRgBt(&91 z1RWyWKvj>+Mvkjl(mBkl%Z}JOapClbDLY32HVyvX3{9hvGHVV?3{!Ck=# zE%I=Ioal?Vt~6!<)DTz951mTcBDU&GE;R1j_x=`Dzo`u<@WG6a$~EYa_JMl^5CtHj zpA6m}*;B9mV+RdUhK^TmP3IREWx2J{Pu5!<9C!EOA&9rVLL^+&Fj10|CKDJpvRWPa z{c90_6JpQQr1O&L|Cz_X&}n7^7=IdA?=(wI65HL}H;Ti-f7K2H;YTrNorjz8A7Pay zu`q}WAp-mdWJg}sQyX~Q$|nt6HfSSKV`nv~2- zTlwOCvk!kJf>(65R6RE+g(JGczTRxTAt{bbR7j#);RS(=Tt9yBH#RjYN_B{;lK3SG z;eU<3Vs>b#ZE4|@{<-2 zsUr1Ot0;D1=0>k5+3K5nc>=f^cc_OJDumgJvJbhPl<_GoJG=NgWsjAMSu%w|H`jK` zN2*$-QE58D!1S9aQw^5-S1*);CYcN?O1WW=+_nVoQ?R$uJ*;GmX!i^vi&5Q z{LNG0)@M3yo~}XaMU?J4^Doc2dCuVijA-CT4Ha-!(YTd|BKWjg`P(Rg5 z{>cw0%_>!1El=tD9iIdqi}Dk9UX@@4=VHeqwXY*y zRq3REfb#r{tInww4h$BtTe~o^B7zW6B&&TDjB9W1I0l2OzZz<41PmXCU9o1#+T8D{ zH`<(}zy<2GVji%M;fm+=*;$4C;?bz!LiI!^;#}RkZOdKehpT|UNz7v2h5MyHk%V$$ zYZJ8P5UwvJ+DaV=ExlAA*2^UF z?NmUq+#fi-4wr+(D1x2^8Ntzt?B?S5l={&9W$m-o`<{b6fqw|aC2@RFagn)|RU|~x zYsvL@!|h*ShJ-*NAkxK`0?4Eoj6};v+sop~D%n0~_TI_#D|~5%k8>@n`vMMXG810( zfR1~>rRv5Q_WbkEbtcaCw+z&OxYsXOq^AMVd22rQ%Yrl&^e18n(uE?%+8bnL91K+G zz7P8V7I+@k`eyW;Pk~>8xH{u1PN68x$&q1e z2@g7o@$M%Sz}sJtT5J-?- z*Mr+Snepe}cZLxac+G*KQ|Hh!8=FztKhqs(cXj-jY)`}CNoA+X8Hp~T@qsQFz!)Xz zE|4i&q@F*U>K7WrPuf3ncb%uIBG#h?$t_mAxt39{s0`_cvxXt1DE2Z^ARInjvEJ4!7FNUI_^y;$$+4{ywzTOlVWFKKLyf@%6ZJv|-!9WvD;3Bm-0fk5bnmX87c$!iQi zMYnJmgEX3i%p+Xlil#0dUHFZ|OsH?l#Gi<<-1K;vLmCn@y&^X?L(zd(+T5(>2!tC zMNX{rFq!8`lIXv^sq-TdM=^`AD8y`@3w0$VPf($4@duYl2VN)w&Kb<`LCL}j4lewl zLjG$9%AUy+17;rV^ovLVC|3nwsjm=admR>PNTjHJln6pxuJ`|vh;g%I3D}r^q^F^>V6}hah#&7eY4V{vk4ew<+S@Ni-;jI%YE=jH>XBMfhqXFbJS%Ko zQFJ2pR*9@g5Y8WfPFeqcL<23z_~St+tC~-j9yEfKev$Vix~BqW_4wx;s3HGGf zSG`YwTh??k_<;QrUZrR5!(Ny-!RMBv1rF{6swATM3X?=ET5&Gw^FZ^A0O2@~lKbmKju8bu)?PgGS?HS_k)%Hr{oG<>|A zTd-6+=^I4MGs7=X($ys*;ByT9m;Y19W#)W@MV6-}OsTXPxS&ebhXYZ{Ag8^HPJHiW zy+nq#@sjHAy+;PbETvw~1}S3EOTUD{#(@ znvHQE#+8|NjD#ZK-sfuIaG6W>SxUYrLHs#1+SSPqgwGm@9L0vz)Zl3znmA=YbSjHJ zU&(sG`+8^%CA9z821;m|NCEe{NsQlMkn~e?8v?p{To$jF7*1Ea01ksr0k@0IuM;Z> z`FVH2eF-6$4e$QEnnH?vqz%?u{DWyC=$T-iC>#X%1kYsi5%yXY=2ADybT)csr^)q9 z6(LJfo1-wxI9fJnl7X7*(-zDGzRBGJToxfu{l|j#0Q3SfIH}xt&MMrc1I(p^efw}# z)dAHS$jmlIUFoE{bu4Gy-315Ygyrb|9RqQ;|2=THfH@qiJW-yAqPYq&!PsZV9~>Wd z8}c7}mA|f63MMRNbU~OD0WV+;J3;Bxon;x8pA%fFcf>2L2HQaWF=WtUx+|~XBZO@v zBaiEPxsghDWg&5obG~_K6oy5)rY=x|Krh$^(<#E!)p;_lRU_!hn}XMVd$hG0FVYHW zYBO5BBdu&Nw2{T+^i#^D&_}RA1W2`+?0LRtf1PK>BEIk1xoeej9d9Q{B3Qy61mv+G zY^o>I*jgHUL!g_gWGvi|P0wAV6xB3*3tj-zBpMLtb>P@oj}P5r-z$%TwhWY{{tsmP zkqZfg6#x;}P{o}Y2{>2Hj{i}RkPOT>%2&5rzy0VPt?!|ucPgGe7W`(LMR5vQ`kANv zdN`5c`2K>_Hp&$z0CaL}m|L{gGBZ2I^m^(YZur~deY&+d)fT^Mgg7%h8*gRFQoOZ; zY*;heLp*_P^}~b)Gjmj_beFk?QUy#9l(0)*GoEQ}CI1xt(qF!p`dh;Q-Te9)FcHI3 zI6n^UWPMf`UD=7bvML*WYKN;~^|gR+p|C5a6e~{9O!2 zJd;Ie{=sTTL2u=7%XE<37z1uBgM!wKX8X`Nncr~sc@?XJLu-v-0NC)0Ec7ISHJ6{d zW(v`Ya6OPJPT2&0K{SYtB?j;NKb}z}N02KR+M#@tI#eJBCikLX?X#oNk8$S+DG2|% z0DzE1Fk^frmOC;Oa0K5wf9>wI7p zesUPtT~n1ddt81*SaQFqn`0<<`oWdu)Z6`C8umEp1nag($Ol=R7+ayElA|5 z@RdeM6oaZoB)ih`2F0h$F8+|Fd;ba7bY&x8iW}HX6%g_g?Yw6|o@pKkV+E8ymEDf| z`p7P*LXNTn&h?d{y1k178d?MIuh@uY&@BW)2SKUW{mEdgX zaWPUlLMb~2$`3bZGm7^T@nYmD62vmF)k+?(+UMJX)W~c96zsEBM|(V^qZ`JUyWNpY zMDZ21;#8MrH0#YS(tYO_9_YYi5ZYzX^Kv|Kodco2Va8@V3V8jGl$HnJ0iej@$7sQy z$;W+Lq!s?V+YojwQ+eJ4p6g^vG5W-fj68Z$x|!+5(tgJT^<6XGsgIVHc6zrD7!@5o z=Jb4Hj7RvTsI*jKCTxCbNxWF2l)b55pGKwfHY4?rN( zZYe7mmDU{*5UVq=uKLcj>A$!*C%p0cpy)~_QQz@yuWu5ZOhInO+$wUdnm0MADoGDA zJ2}9lPhsNmNey*n~ z({XHC`eQPi}gJ+ z$(|oVHlZaHbbgO%hjCH3oA$uuat{^awH5*urrt^KvT~BgFH&r2D1@}gybn?H{fk-C zJP>+xYk&FG=J$OS+`h<%jqe05L=Zs&t+tc$|0|n(1-!w8KNvCN%Lct|Z&Pq*bV#n@ z+rygoNESd^E7LPF^I;89jyE9!y??27i=D8nX~fk-!?`COKDdAcQV9vAxb%4VTo;Y^ zH7)uY71i#KP^}$UcFA6mHo@AmNBI|z8lEue)IPjRK)D^wq0K%fMp4!~M6#(^OQP z0$Z*^xLF9<#RGuMBgRLGiyDnXmk{0k&Cx<*6fbYYda4b%68|nvGMpZJ#5YU6y%)i) z?Ir%yZNYPjSb7qkpU>aO(BVnqhK7gJc-ka%y`IUUHi?pwz>p=~4V^x)1iYSsd@tJ= zTy8gj^VP--x%Sbw*NS zQNR)IYDZ@I!qd)#+AnEIHK68B6(e@?uM&=J)kOh3`MgqfJ1Ka6vbh& zumUc69+@@>004aUv9v}CzTtJvTAJMHE#L56UKr84m$u$ z)Yzn%PG!wNhhMD7V#v9 z=nDNH;YFX73E(-)78Cwp-LgT>uK92OG`4!XGaf9X>?3Y0W! zyousj!g~&eq)DF9MJkD5;~;bOeCp4i1;a5!bN_T{L-+XhTx$_23?=QB7)Tc@zW}qS znY@)vK6DNIb(ke1Ra2;5P`o8W@?tjJ(!zr)qEn4*HK(l~;xKA3M{UqoU}EFIudz1D z*8o1oSd~c*Tlg9A|3Dlr)LeI3yMG=WD+aVAh)v1dQs+MdkOzzjeV`E4zl``HK`3$0 z9LowquWr_>Tz#6N(4Lr_tuLNBzQ}}hV)cnaNKf=mcU}lp#ll+S;EUYRtSf8w3W;y# zKQ0Ngd~e54_~?G^Yp9Zp7U197gkaT-f>4xS%Ha0JJ^;{`QGx8M*KI3HZk1D*uU0dJkx4g$yd@aJ|NDkfmHdCt=V_D=VXr33&uegM*LXS%^aY&*`+-5&Zz~tjm+ZN#M;& zt1s4t-YB22l;}={1>wsRi1(T@C$tOa9BBV6y{V@`Ck zKNpC^+n$eDuUviXT3=C96V1s*tAR}%G{O8RpH_i`FaN&83tglO5vwpOM{Wu2AKVz8 zHc}!rk>5v1MX+95_=^RLAFtVVL;7hLW;kgmbktLE{uBNDmxzh;zo6YeKGp;G==&Cl zDHnrfK~|>y)G-aUM!$#=FS(W_`xDOeNza6<9F^B6sxS)Sj;@xglJ~jits*%8U_iGH zScV8ycxK>W3m&moPSW0(TQeL_WGbY4jz~7?GR#hPIj`1Pvz*DC=1&)Suk15 zM%ZR4ttAt#&Tj~_atd^)B^XrDP+>|a!qKE9KTnD%Qu?XL$g;tt1rEy9eHc^klaT<4 z2}b>wyEKaDyglGXwcoM+N%O166BGyoRl@xT^OWJB$l|C0M!tguKAks_Op%?fuvCa8 zDY)u8x~Xb5#8EWAXaJv9<;%RDXN}v&B^&Ly)*yn5d#lsjjgRf3r4Q57=H!XUing{4 zjSUSoKS4ByLuH@Gi%23QK$kfP%jyZgiS={MOQE3MhW6c*26lSqdnYiwt#;w$!M9U?Pu1DX-xu3-w%?n{#3-CfW?KZ(5PX7oO3ifu4R0CEzuAst zd_QPI~jNvTbyyL2h;3S!YQ{NBa$A{mO() zAW2*eP%`-APeOAT=1!xhrIZ)po;917!=8B=hsXPZWXP3}hfL_dn^+PSvq%&pi?;xD zh?W1B`~u~(;e2_}pa&B?KZC1CD`9VRV?hrKwulrLh zq;(tI-`{Uc1TPHoXG(I@a z6nSx%o-ON~?yE@5T*!ul)Ft?q_8xe(N_|dH2itZlq)tfauFQk#ZB5M|MmZauo#ie0 zZT&1G6e#iHq?&A){Z1Ld$Y^IpJrW^*tZ4x^SXB#MY^pa~_pWY*r+vT{o9~OOZ5>i^-_6xY{eZ8FfvKZ0epht0kcURDF@Fy?{ z{6#u0@a~Q2)-yxl#&u>%8bGa0#9X-aG{JpM?>KGK=O^9gAjT=*+F=409;Y5M)3*!V z`7=FdrB#BQPpiaZ4SUtoh{5`guNu(l%9-74CirI+oYTdMQ0)b_YR`snjQa0^-v|@e zY|r~x_jk6rO$THM&7vCLII<-}5%tOJWj{R3*2d9g-t50I9UQ$Q(=oi@>H(xZ%r8EX zEhtC$^ORFS;?FV|Af3?>XUA>`QA4pAmRe^0FT~c7${z!IGndmx4J%>jiNl#W@x4XU zA=8m{clV}`+!lrcYGI`bHwtOgs;2*uc97Ws_6S-&f1SCU?@}v7{$Hi}jPSzo4tTx4 zGIFC8mP7z{QUFl*=! z>vT%rr9vLBE`eJuVv&!V4aP+fH@i4z{q4l*tcsn$_jJ|ENI2Sf2tlsV)=Q!I;Ogc)+^zh z>DD~%R7Q~qy0I8_e|~-s?(a-f-ZuiY`ef*zRh2-`0BS39e4lT!klEn{)m<;?7m(fs zE8DZ<O~v>1b%3h%SeQ00@D z@%DQg>qucB9#q7h^cFasmMq~E1s=kpXzR{~gC~;H)%u7wt+kT!{LJ0=j5N-0B}$pV zn^Usgy^SAZdbC1x86IY@wE^?>hWMfyrs_tW4(8*4y2z~KrGQ-I(JZqxq)a3Xqgj_arG)lB#jQc0fNzcqITo|Cf zzrTkM`&V-1ayrHAeBErHUtOez2;AKCR!qp^2Sx)3$>L^@jd+yHtXKk1BkF-+b{|Rs zWXqF6BvqkrsQLya)=CskC>MDHH`I-{&JBy|k$siY!0R$nNI5ZTKAYD=%;$mV561gc z_j5*rxy#QsbqYlb{p5H=hp$Bel#`OJ8*^}Ja&<7zlg?ap(L<1mVs=y-_e9cv@17+7 zj|XJh7>O2xEfB?yc2|R3z#cL0JuGllcnLOis*69PK|q+x=V3 zm)9*aRB(0{uT%&M0fgNpj?0_*E&OpH?61K%FFzpYSv}(n=dfF-i+W>e)mTdsU8)qN zZ~&u(QFSF>QzJVYq{Jw?k<2wESu+@-@1}^kgC%C&fneUapb^$Q9;x(o%kSBSgmqx& z>E)si>!ow+udXZECgIBp!(VioZ489f6&$ z*YOt{_(i``=x3fUC+Eu5s#CwG7xnUbr1Ee{7t5jiQ=Wm=)^>T)oD+9|+SaGVP0G_6;Sb*BPNeb^F(41^YIoJ>O7ppk`3wJk;PWi?ay2Ixrm30fj%2+0 z6% z!WYy>Lu1fUXzJu7nrIdi89BYA>m!r>cVlZtMkfq_4uA2#(msT69f|9oUz?i<4|Z#W zsoowjUw>{$Q#-oT5|8#b%{MNKzM4u?u3FoU4P1wE0mQ>nptTuA!)NS28k5H+s}td7 z>DR=Eo`6C=8=#L?(7r&nyAF8S*~NK3Nb%>RZQi6w*6Ai^?lV&TL00S_qaQ6$LZ?Bh zXd{WAa3NN_i-8!){72}smkD=pLs2aiYROSsn(6#9=0S1Ve*{a;2`VE7aQ)np05vF9 za#P^B&-MMx;{*;Y$kp4=^Bi?umY0;I;{JMADIMFb4?MZ#`^(*S|1JX&2+)hnZf6N{ zdB1V`fw?@N81Ee)N1U4&Rc-cJimYy*m0Uz~z5`lpgj*Y9#cfDGK~p86!WQq??|pD- z7zd$O1)@q2#|d?qz#E|^qkk)p+jc&gJ#ZX@)Nqee{*?bsmsngHaBn1-1&4yj69PSj z)E_2OK)s#CpN<0{FU5)ltg4`XS}Yzb2RKM2U|Az z(edN6*VJJOs5;}Z6R(u{qo!4JSYX~i2?ydWqN9&hR1c7fq=%*-KOhG?y``lL#=7=lU>P#z9Cji|143E3e)B7?5q25#He#WSOV zG()^WUq@viJK(#*F*sgn@vF;7yTfa=)p-M1baeEz&v0A(pIe_l4D*{S^s>>)e@%u1 zH$rXK2MS#vksS^O`eg$)|7%$qLgXU?^A|5AK@w)(Bz!(4O_@zc(fCgu?pFpY#vUTV ziZeq4%H$45p>c$4_%Q-Z_r$uV4WDmGl(k&C>#7{nR5W!|2i{Ehbht0uV;D=4*m07f zN9vCe{U%XY)POGHAtUKqyL~yzu*KQyy|i>b7U4VFuwb{ z$-UCt>TB~JxaM{az6pDxZKlJZn|pfxyx8cJ+VXy-)9!GL3oCdP0y*85UT`w?2OxcKHCHzw^f9e~(X5@S&o;QOpPu|a`7=goPJl=3MZuL5_Sz^@LO~}C(*!vB@V@bU%U6q$$^Vz`eTe_rDH`W2 z_3PgHM20Qn7g+3<&g$3bchNHIAT;@Pn$KpL;dAct#h;pcN1cc4*88`Y!oHK|%Z(k( z3{PM*Wt|nFOQ=2{RtY}^RbX1q>VG57;uwL`-=jC3I=(Y8Bw3r+D|@H+d%C7Z*wtp|>yu*>$;(cRw}5yILE#^QHS@V5nMvm+ zPsoRwP|pnHP=}0e7F`I*0ky?CK6z3{W1ZGHNxbT9k}UJ=A@8Ar;UX?EeC+bHKnE2< z{*;m#{L++x26AQ&z8p zxt(!R6|yL?Jp6AOlKfCm`4T!>iSsuVEpM*1tOrtSTS8BKVoODU%gEK!Z3mvY+hx~| zI-g?}IKpg~CBEabW-5gOqiNMeRyF(6i_J{B=5cC95{} zlAbfXY3J9}+vwkG2J;_3V!dCRy|s`@de~bXBfk=YW;HbzL8;8ckEs*5{447VUG8xE z{e%}q1XC)(3sSj~n{a@eg#d%uZHPdEK`i;D@+&k%A+fUcjSFV(8)k-Q;H@K8P*MAG zN!ht>Sb+uU_)V+N7_a=jGP!NMWaaOBO{&i4rGF-0@&Ve+v?6=fxa%YL+@Eb7xayui zsMzP}0B6FhUCxn@Fb6lW&#=xd(nppTRSevr!&FL>Fx|OGO$?(SDHc(=Wbv(wyX@f` z_6Av2og4tqH#f`^lM}NL3KY+<6RcLPZCJS4d<>c45$|ig_HwdZYskv#m<|!d3I%w; zrU`^AvZ7#Ka>>ef;yxW)`FznY6%-fW=^!`}=*sijDDMQWZgJHvI-lZ2Z1iK}{ zmAGeUXC7Cz)nYTe`}zi1I?)c1(A&JMOnE0KpP$vj(`7bIj=JVAIPDKl>SAD5n`l57 zZd|{}rU|?=m9JkNWfs10sq&Pr0I1^Yo-cA8rypyBn|xhKUG)A?-o3(O#7i#Fh0YB&wDA(iU=x<;({4Om9YwUSS z07n^zS>vw9Wx}oD?cC(iWO}|{Pm=!-E>I8DyALk14Wvh3!fTF26|rPt!Z4VC*$&~u{}?1@*%YKYNTiP`1SxxCybR_ zDu#&naBk&dHi<^f=+`8KXR55In4ToyhBRFX{(m%`b97w&*Toy#YHZt9W7}%%q_J(= zcGDz{ZQIVow#|3?{MP&b%&c|q%zW?J=j{DC0tFXjIb0rr|GJX&RrJ=j|Y?VWla_l)X48$&B}zFt2BJN(&j-GTH|u)V*73NbD= zU#s1v2KERqd&Q|xdW&qylv^_zc=!JdJR@QLmgdS*m$O2u`94knu6qYfe-nmZ@++U1 zeW2g&2`tQu`(65^+WW7FmsH_?(D>}+^ndr#8U@#S9ITEp0`KR`7(IeQGr#Ho9-@_} z#D-boE~Cqom6ug!u8^=q}J{wwryfaL{)^F9KG@Ktm$h{mH7r@xqMM+Eip? zi0H1$#vEiz1q?dq%c)2{s!q&6er+woPIGH+Chr=y7kqNBT-LqjCwX?Q+tmy3o^;Fu z&FUZhUps_z`}@VqmK(fd)!1V-O2et8=Mz49AQd71YCH_k5a02T*9wcn*=6={B@${X zh?8h7K)8vnZHoh|+g1k))vw`5II79iC>Zie@jgqNr>m_p z+77iN9f2nA^WN|DbQ3Der3`Cdo4z~_yWlx5+dfKl8_kUh(7&Mx!}RMc2S91Cqt`*4 zQY};SDWY4=Z^y!#PyLDO$ zym+7vv_4?H4#E(*hMF5@w-DKn$tWNbq)azqu|+wLIi_mgV*ys66jsSAU>wC)Gd_0qTlWr^U$eV0^IvKVihqp<$Ai+l@cnCG@CJhHQy@&<>3WDJUu^8R+A1) z>7~~&dS8d1I=noRxL`qMI!H6r+Kw{tp<=S=cNb9;bE&VWH1Hy-g7|LxoR)?EqjKIa z-{057ne0P2Vc z^En8dT{ECbso0kn)dxKgU6iq!%g-bEK4a4^3rO+0vLr0bO3hMz>63*d64%yX1qbc$ zp87vhBI4oRG_TeU9oZV3F%J(Ly=*MxXn}= zc`bx?NA79f{vhbM$|ZVj1A$&J#oj+{;P_TAEm}aENE2YBkFBdR0ZvnG@bI6lNGJmu zeTKV0O4=|Bo5Hxs4_Sl&&1~9X6DMV#UY&@i=7$tRr84L^k#+oadoXK8P)j)Upusbf z-4LT!yoKz5rtryYKxgfc-n*9T`-+7)q)@g3l+0AuJ(fH}Eh-GaswU+E*lcuu7*qQf zM=32UD{n4Ki=*D^2S=?IH9|e<2@q*0sg7G)TYH|NWuRp!YoH6VEZD|g*ZU$Vo2fZf zK%v3{X~(}#I;hG!AI2T{ds|{-eJB1_{Z;KJClQNRu=QEB^~iJbFDK6i1Gn37`S7mUSQ$Jqwa*G2?t7% zR{qci3h9hCZj;14oYW@7WaMb#uyxMZZxZ%*W0Vna4sG?qoWv*hEla3VDCgl8Gu=HK zKkXsu=j^Xhj)@XVOG_=Bos+v>UUA!8KXCp{s4=9ky6zb8d7Q%qK9A8}dyxc+fT7}r zjd^;BWl)-g(P!)oh<@|EI3X&qYQ5gRg(4C~65#2XU1qD<{4wb$__gtZik5(V?&f#p zX8ClvabIunsZ|=(Mg70nAR96$pVJYure}Wi=g6rF4poths+Xber zk!F^v0HWotY^WITvy3HggrbGwC>AE*?_C-ztuf-QIzWHd^IzW&!Vezc9`jEOpV!f{ zp|+hX3mL~47hHmGlldg^U?3OPPW~#x@^gnT5A-P`^N?|@v+Eg1kzt$o~1`(|{#oZ_x^`*jDiZ|Nxop3c-S zUGUJc$vLVa$A2y+p8GUs-`66d#B=088LQa?n8j&}8R4ixrO6;Ff67wY;*j0xTd~As zEB9M-0V{M1WbhfK17Zx+b0}RDE__Q~b@#iqTN?W5i8;I^99mh}K@WD>Y?teSXVDri zgG#OlZc_c2;1p>*jzOJGBC_73s=;P^%Zz5zstLN$#Wri+MzJQ9hM49ahpRm@2@)s$ zp8?K&+lZ7NmJ@}S1}`27go^+j zzrZESn!S(0Yn|qtgL@8$NX2*!imuAOG4T3A6~QM?4x9%%(#pWA=(9=(&M^uIsZ~g3 z|5Y8kes@v#ch!CjqJNh=6Sl^y05Q=qhjPH@uvL)IAb=cS5JNQ{nEC;q&!p_`#fOaY zeY7rcEvg>CrQn;o1hw^9&H{B+36nzvg-Vm5Ve_8Ev(eFZ6?N+{X#id z)UAmAcwZ-x>-f)RozK|ytQEBJAuP+n9dVv<$I zvE?#I0{@#RY0ICY`q+e6u$0~|m4yz63}HLUU(X)rqWyaER}Xy@HCX$3$LcOh&BTS6 zKKrn$S^SxtP)-MJ0(x-ZpF3%EaA-ATaG ziYvL;czqNb?`LRfu3(ucpSTo7((b~KoC|(*E9(M9UIWdc0cJ7}_Q~4{sZ6i;z*2F7 zIUR~5%rqRI?y(JLh{x0^K^7W|kJ1b=^3ntvxI!0wwF}2jzE?d`9{-43g z8JsDfhTnNAUX8%~FuFZ3_Fs~JBD+vljO__8ck&x~7?#U_HqU$;a9JmlS5}LY-bW6l z%E`6be$A8tQKbf;+;?$PwjvQPUshqe+h=#7Fp~X6MqOu5DfW1okL*n8@SL*Bo#}BM zUV6!wzbc_%@$!Hh`SheXd|B0CDZ|*AWO~Qht8bDQ}G0w%zpt z6%|HjjYtr0XHl<1g9&}8v#Yk^$Z@#=3JD~>5{O5p;V}f`g*uM=JdU$CzDJ&%o}LHF zbKul14j6h%w)x2>=LPw*agw^t)6yUEN6&(vlYM?AyO{cU6CG>+_lld}-@(*axhC)P z?W2JfeUJ*sRa)mB)IXz2K+V|pgUCIup-J$lil?{dNF7Bvt*lj{$IygQ%>rWk#G> z<03yoLI$hd?f_G(I>fQ_Ej5(CW}u!p9^N$7NKcu1>J3jpb=aVzc*mRS$vN2GxF7b(s8L5+BPtEa`*(`AvIV zU>N5cRuVjT|BqCvBoun@XPmVJbV3P2#QLsc%}8x8-rrB1ogIl((uM*)ww?|lrI?#@ zfc9xiFPoGmhiA=Tz|f#pruSnu0aD!D#5>)?)rvH4)1%5+uiNjBZGEeaj*LDBeQq!k zn2xaXUr8%3gHl1rvNdC=AT7NnPHwtEFKP3!iy~$}>v}}j*VnUURjc(n#aE_Wfo@LX z1Z{2Y5u5Ut;5cl-zOse~+q0tY_Vl8gXq5|ib$!xA5cQQ&vMG-nVxa2zPr&R*_1)^? zs#u=SBlgEVr62~s1keChX8QrK*hQdia6?chCZ>~@pj$}4YE%3=W#ochF{SiT{FPWr z{qNSJB2zUgKtv?(-!Kkoea9MKpN{60k(4Nc0;YF@Q5hN?Q<2rAgadQC5?M+D&;t;D z^bjaw;*vw=9|v0*dGqktOM7<|C&4yY8U+EYl8?=hdTV)xeHS3clYpe~tSVFY1 z&nijLK)c_awe7l;e7?lElvc;0X8%Ym-He^zTi#>a+LQ;A*enW|m!NL5M;d(IWmtU~ z22WgF8pI621u*7zV$iw%4|Yi zy%2}(mzly^eg?c~)2V468gvaC%D>QsA}cD)uY#D`h}4Jb>lDj58P^>D{9cl}Mfi7c zG^q~3Y|ge?8-dQ4PSG`;a_cXBU&MK7`)qY>k_8mQr?6$J(Xj@V4wCX5N{e>Q?vc}} zjRub|U!ZkRY==Nyew+*=x|eDI(6+x!P@^`dR82lfNgG>qp(tVd2YX@UXK+35uxD`% zs%0`v@s<4+5S2q(L|PY9TGScT1WY`aDdb?Ho*d5>6{e9-QEn7OC)nC>iyDTRXf5N| zy%qx{bO!YMlKm&<$7uIE+L3d=Y*{pCrTi_bl;4}1pUl^}->W(H=e-yTGWhB5uUS-J z&IWjnYXe(SsvsuJQcT@!M;KvK!x;((4}S;(1HO%EPz36_j!8om$%1A@Y9ldJJ$Ft< zbFHSTcczL*Z2XWV2?=kOWv)#E?FB2Oj+pPc#xo)*7Yi?bUJ}r@JxGz6AZ`@wxMOL9pX!I=F7$9c|-+BnJFud-X zYOy;z4>B{P%$?7snBnRs0+LH(=W_sV$7j`DB*zXOzSXWo@vx zV6=JJ{US;n82OIlN78rb-$SI{g>QsNH9+}SOy^~vUHx$#CsKv2H&q61U>N6yr4)J) z)$nxR39pa(u^&&>k-8TTz1lkR2d849C7J%gfGkSkF6$6gBDm$C;|qR8Znmg2Xm$hm zc{TDlW};;I{9)iqEh^lIP-ZWF^7n2=ddAtYQ`n7ezdXB*_uRkwoj-s(lrc8ws_1PO zreBL=@wk6zhJbI-@j?N=KiFg8L@s}{PX|$w`AB)fGeY2>$yy^63K1_~53KzkE$2kE z64)LDB2-Fzyq-!f?hO$FLaVCR)!%R$+BG4pn(w*@7M1@Mlo8+7D2PL3B!gdw=htPB zXH|t;#8g$_L0SBdV6_{Vg(o^KKtdoaR$@DA&MO#!#WocT2r@y-I!Xh4`Ye#(FWON; zGwQaKm8`8*h<^5?aDYTCohy<>3SA$9dSC}=9#(`CQ)adT7P^3SRIySlDsFa(h!E4m zf@d-=ikx3n+eXTkDgE3PAKC55>U7fk4ihXtC0HgP+KIk{q0Q|Y9W-=WBXl6kYYGRC zPg1Jm$;r#ZdfdMp<;{mgVV!)g_yo>f0GSsxKQ2gtf`l-FWE%_$NfBsw4W6?_M=%+o zAzOtFPjo~>0q0{wFeT0Raa%=BrQa?C){H#Z2EH!`JiLNYiNm43eG7K|C`?;rZleg%Qew#c>{m(Q;VVv*R}W`hzWa@@O3U2 z+?SOqkvD--*U}8gVq7RzKv~bA*EYbD@OS^z4lESS+&U*6F#H5v9`a-(gV*Eu@gR?0s{9rBCZ){|nrkGXJ=u1?}3!`WGLY z7qE*>tT=I8zt7Q&ud>A3)YfQQBt5ery?!wkWWLv=WI5{&{175q&|`FXnD|ANAf9|` zBiMn-oTC14zu*)OxTcD`C^pvDWQwck+2`x0`$Pph>zxZt9Y_Ub@UeUki22=jIzof5 zOw@Xnh741&{*J*aQt{dV0j0S~Wifqdxb*d2Zj&PFhAeSkglJ)&`LYRz++a}_rq&3K zAeaUGqX8tkIan1Va^i~kTtPp1;I*foO>OYrr$;m`rK$rlS7q^%M^pb1FRxE*0Of8@ zjDv;D<`}5Ep@ohwSE6RSuyj8IsJZ3BNffz21#f1PfRrpbAi`{{qO$#3bHN-L#bQZ7 zFx<4jQW^Xd0R)?L%)Kc%*;vzjD2W`r+65Wt1Jnc6+Lb6v&80KBDO&pPw~!q2jfb%r ztiO+>fw!$~?)U-+KKl$| zL;4u=lpXCNQ_IRMcV6HG%-VB+MG$pky~0Q-6X77fnU9oaO7NF8?kN|sy7^dQ)D+H~ zATzTtkoZZ2%z60FG;^`q8RmQB=38cwLE+yp+ylMxi;trAaI}`y5;7w>aZ&PLD$ng; zbHl3=?Sv-h>yqyu43DJthmQ`V2`>PMuK-fpr21T&mYUR8r_7pOU}RUOAdRn?XStdd zzpQtwd}Un-!A=7nHy*U2f$S*f>mK1YuPZwqFskWs4TgDO7P|D}zE?OO<*cn?Z@sJZ zjgT*B!i~{k_4rYPHXC>hgJXisZxvm{KlV$PJJeU=Tq*(GL{SSmQm}}2JOoahAWrZz zGO^<+8}Jw_J->mD24(2vw+%HKd|Z++0O5|PtjWnEOuvPGMv7+1!Y%A1Fa~Pwb~(R) zOe!tlAzct+dAhl&z>C-|!T93jn7i@Y!FgARs^+*$Cx|03CrI!^C3OwM@>SCvc|w$1b3wP#y>~ z4Pk%+t;0*6(HDh0G2vEL~ptZu%mzXHm|GounB-u(yC z1S0&TVeXpj@Lc_qSo+sF_Wo)MM+&oP`qF9{T-bxyx{{kh!8N{0$LKMrNpTOEUn)wD zZQ$1s>+@bBBT6wtm1r6+m5kzFEn0slkyz?QV453hWbXd3i@x%#O2-X~9RfxN7(t1C z45agRf9EZW+wZPK=N+VsnN*OS8&4R%f8G4vIIVD3Zd0+)?L>LO=NVks?m8-_ggGGH zB7$Fqu7yxPcfmoNuo>N5x+tLs^zq!$WPev0#v};4^UogMgX=)JfL0v`*~J;EB6d_8d7{nCIL?Y0wL!o#&3@euN8PXHy@7fMT3%F)e^tu? z2~juGudtctA*=A~?~cA9DcN^~@I@-L9lK_^yu)Gyns?>aE2&Fss|q=KwhL|cgkn%o z)C(J8qu-OL@Q5(%3V{62kWDxhwoPeUdX!W5^)cG`-Q?`_(nWf>29_i;rLqOgLc#Z~ z&-l;5ug~cU#E0t7(`t38VHo?bJt^_*2W;+c?J$dkW{@eMM*f(6D?~a0qNjnRCNflX z^DF#y8K8j~*fb@aPbiYGygQskj~X=T+kHpvQfHWJ&JZw~Y&&&-5mQtbJfmb1a*fGu z{?@CDCG|2J=Sx=nD{&Oun1J6?6v&$?^jSYF9~I62+lAkZkn$4bF(i#TmDpjl8|J4e zwrxi#uK-_b%R5n)9GbMQF49XFdO5|_i*oQTH!X)pslj9y>qX&7vFpxYKCr8Da_IocOzq->RkB8BNALHqxUc89 zlf^TQd;8DHFFiGzuM_+C`9C8^9%1n!&n4QBu7I36kGQL6q}{n zq0e;HV7*`|vM|YAUqo?}Uy}MUG;+lrVN4R+YdKZG4Ax-N(HbJyLuOXAZ`)z{EVvC9 z=pjISfV)d-0S&Js(6ul@4tQ^UA;Lg)te=6C>v&6(tfBr?yLH=kB7P09B%*`=(F`C+ zwy_%m!BKWcOyg#jL!P;#Q>6G{<#(odXZt!Ff7f?sx#qctVIH|&TNTSKjFKtQ=FyqK zw@F>HP)E3?=aJHNlys&5DP4uB>gs*`>;90inV{7$2M<@VgneMb}v))G$E5G8%3h>dl1yuF-k<0V;+RzWXPTs#JUP=ls#rs3qcOgr)Q)a+nF{PseIG+A`pFXLd7AOL; zj3a%>KL@n1=c_-~s#6%oCigPGHQ)96gM2;zTjBr&JkE|>Q*E?5h2^820Qby~r*@{M zVyk92T{!6=0xU z3HqY-Y$!SId|qDv_5a+m$|M{?o2$cVH;I?tL2x`JE4W-93&KYkXngq;A; z%pnmOj>0+g*`fvmivbr7CL3r4vPcQ~Y+*RD;X(Uq&%Zp0K%8hJDtBZB*jaV1JB;-S zSxJN6b8fSqtT+iqxK@lbKUYkT-wFQuTJ=KP9;>UDy-v$@rEZkT7*lJdO8eue)@p+_ z6k6jDR0hR_9MBF1*6)5|XJ#XT6hjKn%1>v^V+4I1>%bYKg@Xf{UP_7s2~Saj5CoD1 z($2(?rl;1beo0-zq9T3K&bIZG_qOG>wdkV&Ok2%y&-nm1PrM&xUwutKZq*lapUDFO zJjGJfAC>HGJS}$`5eB8?mEQ99hsS&z*iPW5>E---#_nYEG>TxDj%SKe9d+mkp`EzY`t ze-hZum1OLGuX{f*_)O7lb=0z3Z-WWZ3c|x7NC3u%ep1ZoJUDY)cK7iov}DVflQ3UJ zqFv6KM=|*#)xh=-Y|uXEa`XN9DcUZ?6S3SL4^L+=s=YJitHw z+oVn)WrLLuf-#x84Un^R^W>S_uInM+SMbMGU64h&LgRv<#bK#R;1rvXEAK6D3+C)I#-+-qH7!8VV7**F7WPWPw#98;xBQ{H&z zRE?veP%@IESP90E(%Z)vUqXlxCeF>5??V%_md~GZlPgFVhIf5^1U>W<002C|F+xFA z*;aX)uxzZf0I|iIPiyHp8H-c=octxkF;i3WC#R>01m_pM6%biNw^2!mu?uNmtK-ln zXYUKvy;W}drh5|Xw<(O%RhyA-NA0=Cfua5vLY4Ht#W8QAf?xnk<vbklczZu;t&30QGH6G`P69JiJlkH&p#ma8ZtTLvmDc ze@8U*y_L*WO#(6y71axb1hdvo(1=WU`+6!_xIOCuaMpbl-IH<&$AwoqrSEaAs7Pt;rR(a3GQ z*y)%J?;XcPj8W`A3L&R!&rN+;G}Qt#NabV#vuqSQOwBZTyeXaF-;B3*!~7-eu+T)^ z*(u}bY@s!Ur=6JK8!gfH%ai&M)W$-5d^K20I$aB}wh8hHNhpP!5Q*W-M&4$Fz!*@; zPBhg3LuYCDXu~uK?pjbty=$U>FQ2%&&cgSari>DvX3*tTFNplpgF*2i3m$&lDkn;A z(X+wELUW`cAB9Wzk7yrc$==@HO8UK+$IF>PT0{g)MvGv;RGSKs0}VA}=EH*vHUUAZ z{b#9tDreV8jHivGwO0j8fb-RQD=DM*2}G;s!=JhAjEvb|z!R7UKO-m^ILR1)fjeTi zSq8~Y1tV9P;%U~EZIV0((uNfRzcDi&SfyjwM_K1>B{8vkC$2wo>tc*|8S2+UyApM% zyhM%%mU7ZH%SY@d0}$F6kvAHXT0}b9ck!wW6rsXaq0zvyX67=*7Z#TSN}RU;dXRN) zZ)`}SMS)z`g|s=#ATjnwK`1L+2k@pLA?ti>XHgjM>qc(dpP#3{pX7a(dyhAJM@>vl zhfvcW?hJo56Q&t_D0I_Yd0oBjcV78a;|=D@LE!FZ$ml-z2Dvp+>ee;2)|L|r>U*A$ zzeIIE!?k)|;H>2X=4Mx8-NpAa%JNd0yDxP1Gt6^Sh#Pb!>8m2aQk35PQO2~AC0;20 zrZbI2X@U>VL?m2S69h;T*Qn^}{dMnmR}^pPg4zMT_2RZR??qD_ef>>#Ln~F9iWgG? z(xD^R<;Qw~_-5m$IKN$K(>!j&xUeJpsw#;?^?8q-v7`J_^+u|gcW`e1;ToEZj^m4A zlCIZGxK`;i7e74<_cF!P5uo;KE3!DV)TF^!JNKfS*t|fNhmD6MXc&@wF~W3RFJ_L{ zTQf6Mr=|>bsZ$K$fX4l(lB}s(m3^?n#7m<)RgxpuyXnb4vFQ+#2nQ>VzOJRyj}aGi zmPHqEkZ+^)7z_&DP==S$+PxJ}o=Gz5-vl}={ma-%BsDF~g=6kOChZ^u>r+3EP>w$t zYy+wow+yUyeyX}9D?PBSsjXDH9><!ZOFS!k1`#_8(f4x9;ZN)bk!q_8&q`^M z-<2!XB^pZy??t#NQtD|ZIlT)=A3Qi@*snWI1DVxq_U`?-`$(U8g7NlWvG&UuLQ_pG z2D#afXo3%Dw<>}kDz{T^T`Davk8XZXZq~etRARST^+{aTsaSxFw64cQ?~@S56FNDw~trpX^&G+-g3mgcO|V7 zA4=jZCY>YROVa#WCb#1_m3Z!EGVwc=L0}a{L{~rqeaEi|9na7X3&C4jMqjbq5XY69 z3{@vAqa>&(%3MUJGM{_y%WCya+R-S-!vwX|il(^~EVuC$ZK&?&xKb-8m^Xl&K^8%xhlxy>K(g|CaRx{_{uhcxV<5AEmx*q3p9ov^g*FD-ue9EWws&$)M% z#pQQ>Pru(ewq$TJ4w*=D&>x5{)iCf;1J0&HVsrovq=HOL`4Cw$>s&e!%Z=6=%*ZP} zHop-{W>*(8Mq{{C_O3FzQhd{!^GSBv_3rJaZEzbvW`{_`sjjga+1r$OzjS@U!=1Qs z103gR{bKpWNE8)cj8-S>r`3@+tm;V0HzStpg+B|`g^{=<$rr^c`$)RAU61kLCVUcR zL|loF<&&f`9tt>KQLGoTr)Yh*ZsInHyFUQk^jlB4SG3U@#32(k>njii?ZdSx( zO;^Kf?Tl4(_>E5ZXWd=9wFy0;YqeY%uU>rRY5)9b+WV39Q0~g_^T;ojyh5SkM}~|$ zeRc`+$;LVhw5bR6fITMaW+pUQvN1gAH3-g8l_9k@>EDMXaV;DB)bc8f*0<~2_0DFZ zs5nIFyFHMTK7q59RfR)l6_^Qey_geOMGAHfJ4qFhtdZNyiFK`nhY(9k0T!Z38K`38 z8l_O=zvUUY?$z9@7W*f~Cmcdg@C}|=ZeH*LgEmL_xYDc>D(Q@|te{ZsS%QAk5&kK& zGb;XhO)r-Iix~&Zc`O-mc}xOdip=0NlTc%l7SG{Pu5?k_azf*{spB)oeImiKf!2Cj zYGMiKESMNS8@}C*U#_jSO-b)=O43%)u6%b9O3Uj!k+VAu1~`FHNOPe$;82zif;wG$$)7sr$8}dnf{TdG>~I`6+jkAUod) z1hpqdGlOZJ3i(MRgjaEH6{sNz`NU$#JRAOPQw#5e=H*TE94d!wnKI zF>-QaPKVk==Q&>#@<7p;)W9F37pmlIc{SvX<`UkT@ck%!eTgyXAy9}VGi%SJe5*-G zc51Cwlh# zAsIb`2aE4Qy-i`##WHCOCleaJ1K;z$FLPABSu{uI5G0l5d1~u_t>f_QAE3v;36~m2cz1RsMvPpOY%_?;e%TqR z9K|2Al$mMzw_J~)l6|ZytbRq+OIqCwQ0#;4g)jWlzjVT!ESsYy3&Y`EN;svsdtThys+EzIleCzkMrYfT z$U&#D2Tukd%7P`oWbcg{U!$O;blHkbDw7`zxx?C@Si$CYybqt-Uoe?+)Yi=&zHNfh z+vV`^Q$D#nJ~YeTJ2B%IR)QEzX3;;h=CcIbo}2bwX%{GBt{WRzcQ1Cr{bD-a-VX9A zZy7&eM(0Blf-E-l<}g@XecrMnMZV_4p{GT>9W)8FO9rtk9WkC(BN!R?&wHI3ylQ|o z8SZ>BAo=Nzqu(AX4O*QvSNNdbGt4FUBH!d>V7V!Ry#u#(7W*}pbAEz&Tf)sQtE)c$ zf?%?xRi9nVe;zCmZom^R;By^BsCqD|@I@$y?=<@Px`X7W`B%S{Chz0i+@&XNqiiIt z``xtD_nuUcX6vnUi}uRz>+Rse-j8?a+sS|v1uCGZ-R){@x$BX=^LfVz7T5ZY2x>~v z9Uom%q5IOs5%KNXp~!ZvOz}(QrMT{g2QksH!+EgS-}}o{9sbf*^h&C@_q`KOtvf{5 zIk}CXBjw$DLo{Tfzt0uHN^R=q%&^IFABqty zKp+*{ASk#iqHSdYnn$1l^4Uq97I;0+6bVWcFb;a`%^GFwCh${bSY;edA%0ODJ3*trFw zm|@KK>MpirRmC^LsijphZ)#wvva$n$+90a=*yXF9(Ind;OUuHQc)Kc&W_rivp~ZHP zg1@`?$9AKCvKnen*{sYXJ>&i=zkc=(UlSvm^rSbs3AW-k_UauA@&)^%p>z-Z zeT)$adjS66uMUnm6wX3-@#qh%-6Awisgg9|8{-SDLK4HLE)*5A&C~_?=#u=zrpHQnUbWiBuf)NFjP%a``AChJ_)y z9=({XUm2cEftx0K#gMLT?!emj*+mOY<%i~8dRyQPA)}?Bc{(yABtJ2>H4kml&w5eR zl}54rJ2vTs72Cb274gt+S+$zaJfa{QoS zQnkk88%9;!i{!}UlAolG~N1KLO$ezf@g3?PrEo7 z5l0UNO6(UT&;P_^+^W|rF~M3kEkw;%xU8bkCEo?+)#L+c_Q72*z#IA&P-$;ukN_6y z-hO3D40W2~7TIjJp7px`<_$|Y!^F(B3N5nOj4H8a^l?4%=WYUCsWv=`W;NS|^eIaOktjsbZ*MW)2c)x>kAyN*qzUD`-d+xbX9Vu z>??H&Y%752L8)dKN75obdU|;ttjrpFQpzy|v^yRBy*DN-N$3v~`tsM|7|u|!z@w79 zKRR_D_LwW%jdXCNCcsc_FfJ2mTnZ1H#=Ukrd!$$UbyI<9u61K%9`u>cpdT70kh~*7 z4GDU3Y%X24o1n;~yFkSeprgFPLRRf7^$n{+6&l4uiks+a)L<%8$5Lyy8nX?Yb=&sC ztfh{c(_MC|VGgp!n-hC7SuBlUZSaE&$I?xJ{3T-Eh4}WZkxSEc^iJ(M&)dASE@FI) ztNi90h$`VpooFNHEyiTgAkL&Qo6pVte0NE}^ud53Wn1+0guL(GCAU6vao7;4|1=uDjn;`&N}qF4iGdador8=VIJDZ6|QP_9g9m*6b@I@G`1k zwUP6ktEPDFgwl7Ha-Y)gmeR#zJkIZa_~7vZ&{q4{dE=%1`S$i&z;v2Mndgp*Yb{6% zv==VB2Gbo$AdkVFA#6SvLqO)fOHX}y!~ay->nmn1HpM$5%ho#%r%O%1D%L}~#T||~ zk?)Iir6_VevN>pMRBJdngYE}0TvH7A?E_*9mrp0!8UI^W66!{QJ@(u9ADs1P=a(_l zm)$KNrLM2HE(5ay(Mxf{go`(Dvqm>#>tMTk4Qj%(W2DRpCT}XI;(kPtkmzbcBU?BJ z#8cUzjj^^m{|~796HXLQ!FHm5Qr{q|L|ESw#IE^ zH?&=w0Yy00%%-NAVbr+-$AHe%CLE7oym|bQh$-E|_t|b09_l<4KM}CFY~!pxL!CCp z;52x<K8gk*FObUpX`Ew9!h#?=b2Q!!6NiydbH5MHRLj`$0Z!F+U4I-`=t(em?Nl z8ht3_E~2WZhFNXwu?)CRGUP(`ukJ@*hUSDsyhgl6&HveNF9|UAYPw=ej&QN*70J*P z(VK>$!#m0{kU{FdHrX;Af!%1V2=fgfs4)uEZ9VKstfhSd3MA+@m}vFvZ^`hxbu78j zhLL2Kdc6p;9(`*X-LGoP*kS5jem{}3Z1Q?$XUq>;&GVMTb0EC2ah)0Igc5>7b6F!* z6M`YTv90sCb&@4)ISOx%2mL|yJUdzSr`&g!PYZU4S01>;P*IyehOEWnVA=O*Zz*D5 zLvi;^bb(CwWFUnJIt`6!>W8B=BMoNi!O|qIXCV?qWF#eQhPtvMMJ?+OZDImbBYsnt zBm`6%?tyQAYzo#VVJTj|5j9~O^^1>T!*x#r1R7=vh;C!5QLNs`r=bXDti6~3`Kz^uzKb{1cty{vBu5*eEh?MDbD z3?Oto1c5(Ka|CKyw)+Q&qM6Ot`7o_cV3f5MQ04Q9no?~z#2i)O9R%KZwo$cym$Ya# zrv^3>w7RP17t((Tvfci|*^<=`%~W!(Hhh zAkv6I10N4>VO3H-A-ES}f1r=0oq{$c70N&mJd(^eU(B!PwY!oTcjl@L;*52v)oQz} zphOL)M*F8BVwTmktZ}GiyKd(!sm7(-$io2&_Ih^Oa8{Kf8NC#ixJ0Mo=Dq#o*w4La z=dx>I-bV7}X6*yiN71$p57Er!nKZ4O1PR;=mY7vJBwz^mypH^0MWejYOTLL`$+V;j z+l$$dd=N6V#nz!6?#U1Y*JH%29~K<)qK{&TcAW-fjOL=yzA+yuVEzxc`p>VR@x5cn zcE}c`(c}cqG?9Y{(?hE)qY#2p{3Xeemt< z+*)Iv$}OmEV9334Sxeu;h!5#)P6|x8yJybYa{s#@N*na1TEajFNFIGGlor&5kyag> z`l&v!+RrEmL|u?xJFb)5&B5oONkk+Zvb4ow_1NNjH5if?s1s9SGwQ8B0d1IZ+iPYl=ls@`{S6o0 zWsV4N(FTsa$FB2twqLfqyu|*ASmyOgcHg0Bv4IKnFfRw}IGOR$O$50Ywge7t(yegP zTGCQ)PJJB0qN|W+sY2_9Tj2}`X1#qcSQlu76!3H1noA@8d9EvypiA|?<#fhcKNyw9 zRk}Q+r5X1s!4Y3(*ekz(*_9CIPQ`s05T+5n68cH%`yQC`n5F}ffZPtd!Ph~efA71_ z^sZ3#*V*2le7~Od|Jff7ZYK8NwIBa$!kLo-w`y;P=G%vfp?~h-zI$dC_%4tb_G~foX)I$MwS@J4Jj&1W z;^2ty!;i>PxxuL|i*K1?=D3VhZ2JHXz^3%e@Tg;B(vx@HHRaEl`kkk39j2>~Pax%C z0Z*wiMFAgALA&_c^ZKaZ9|j*U4h$P2&l(MP9XaX7{5CrM*M$nc||I!5ETG zPE~ENk-*+W^6_*EyGE#m!pk;Sd`02{ldz&Z1dNmGtby5Z9cE*7{m~z)#PA517=ij- z6`P!G#RTW`73Pa*6_|k%JJr`~BN2hv67cHXiW#7KMS8~ZF^I)?7zZ?5?~S8CxmeFU zs)(!raclG~Exj%a>G9g%t44@B-s?uRQ{VSxi_x*;qOQCfJTrGzwRCkg7h*aMJRa1% zCw)-@!FGB#acET6xXlNfBLXHG>;^oMb5LRNA)-(A#Y%#F4#?zibTmeP1o#a`xmKR* z5j(lw%kbiqMqur+@~&95O~yR6NYzEXQ6KQj3u@2E6l5uA4(Y`{;}PObQPaQ?DVPmI zhIsGu(yGYYn;!_TI{H#6$J)OXufCO=g3oz3$Ookur+SRxjx$|QQSS31*kA6p*Q-E% zsbGTpKAQWfx4=AI@HYP+QSTUDXRy5w$42AEwr$&LY$uI(Y$uHx+qP}nY;4<3`tF`{ ze((SDzOFsb%&b{n_sx3px&QZy@cbeVVFHg4TyyPX;O}18;peqi&otmILGTsrbspXT z?p5kb;C-?IaC%4H7LE-4L#Zwr2Utp4uuw4Jn1`H{JNvV0dEu=TCpO^Fng7Uqx$qd6 zP$8t-|03th@_B~qXILq~nFe_DVZ+;ZabED%)%0>ZjSRhY#;2g$|AFIB{BSW@NrP4@ zXZ%{cI*77!j$3-2f|ci<**BSFeyLl(KU(|y80oU#ccHV+A+26SXFSSDZH^^|VSTv$ z|F8hQ^ijc<-HhL-c=X=0Pg>|5g#6pHybb-LBZek4s!Iu{`S9@Zmq5WS7;2Go8-9SB zRVS59vLq|A;0MuX-tywG&|@j<{LMrR_{NBy9!e2~=unmSQC&qh{$ZRjNxw@J;(`>y z1YTMPP8i)`R#2pY$;@g2X~dBych>I^C_^SEm7?anYT-zymt*P@N)0Iyg^GyPwh+?Yl;tE^sta zG;w9+cSH?eYj8(L!&|K@_PV=K;OiPeDxbr$yXK&VX_R?94yP_e7r?LvHLbZn&;A<}8+y~_ zA_ia;A<>L$15_UY9mQc|a#$0SrgH-6(Q<#%{VIUb3hg-1zdqy zAEEY+j)5W&@E~x_^p+S}kn(bWg3|R#l}H;#sS+ z_HEFV4)(K@lAFP1{{bWSBGEjs0HQ7&D1)MQBEQ!T zW`((#Jw=kFt27z<`Y06v`MhR9_`X|N;fvylurSbnZ+f?#Kc#3b&>#jf;Nra=doUzG zK1gP`7Ghm^)}JtMny}xw0KK~i)}WjqM%w{|)hEMWA$Pn79?Vv1Rxsc+*P>~;biLsz z;c6#NgnXtVs@|dC7Z1aPvxgTXTbniz5Ac0ncR7dYGA05IUB{CEn)s1AH%e&uD{$3F zHd4NG0{sJQK`D{%x~ueDo0Xuto~hD^1O+I|ghK_j*CN{dYam5R;2dLH!4j4QRnl+m zyr#9h4`We{xqjI)k2Df^NDQ#%47Sd2uBK`o;*&x@?bl)h5Hpz&hh|X6 zeQCX2Z0Kd|*Wt`7BJfTEKAam13}B9gF`Y%9cB((6qp%WV68SN(l13XRxllyBtGk(d zcv6>;HSM&%S>4C{g}Larrdbe->Nlm>$f0(aRL!E!^a1GpJgc$;poQ#0Ha`XX$NtL}L+c7{T*L z0I*Nzipk5oW0<+f5-PC}TmvPQ0vplhSUU?{q%Nxysnquv%GpWWMTrzF8^Uz+u@}i$ zPNdx60pf9T+NXh3jHuBlQs~W0&_Tzb*>?jy1mRnc{TA6lOHY%vAs861fFaMT+-pJ0o|WHe_b~p+R@(*I55PvZ;m*D z;9nUzan>5uR@}#xq%=sQCRb%{-w08E6L9C_+USHO+?F@iZkc6eD_xg+QK6;PW7M=5 zR~MO1giWD=9^!a}Jtd6q!ct+3dATB4l@i(X`%-4%>-DeNgdyS2uUf7Zv+8zUPOxsZ zw!}WKnvxS3GWMVaeG5ZnmHDdmmKde7`p_ht>}I(Kr#OH7{e;A?8}hDKDXKLI3I>e` z-R{L?*efYK3h_GBEIh@r7dLw6DQCg)i4L1;iS76tv;M92E*J%Rqjb=*A%NnVWBiqL zWgT!;_aM+oPJixJ$l3%qq~sOObIivuuepY8=D}nyT+g-kr?yQ7deKYPb^(4`sN(2!}LD- zaRzgeV&z-z`AMf*#20S!tG6*^eICddQ>sCz2LLLGH50bb;9DNGse9;tQHJfl zEGlA1aL|{UGsviAM)EL{h-5B5n?SjZKSfiNV*zfltDz!gFfIvEg2l$8U9LePV!Ux64YG>Idhko-iQInt~i% zIp{V=oL=)`w2{3-h2L7=zf%u=wYB}5pQW|Wi_)D9{Vd_?eHLK9=ps=@6ed<1AT7vFh^X)WS4847BD{ro2upv{pGIS9(Ol z9PH(5KG0_H2xB1cE^$nm+@4KRwZh`N5?k<4h7sv5yAZWt_nN~AXqaV}HeBI&j=!XO z_1E+m1pe)ugYDmPZbKLV(PLe(yE?!R6@c)cr;u>UcbA-vTayzq{o-`N5 zee*0c!?yiC0)1{~74WyaSpIax@D>7HIt-ap>Keqn-Uwmt*Jlz=daX7n77lVFa^Ivx zF=;_H3>p-4c{~?Z#HVYp_|HYl?@80;9&|K36bSIU3xDv$I^HxK62af!-&lP!3Tt6G_!0_!Vr}jJg^gj2baCGC1 zuYS?t(0w9=vQA~93`GPF`%aO%Va#j1?HMREv6jZ^!x3EnG-BK!I6| z;9ReMRqoKT@#0)q))xr(Xbal;pL!(wRIs|rRLoDMoG1+DU%{R>erV85TYh*~hp=g; zkMdZvvgwHhKz=ts_fTY--fW_`p?uNc*gr=KQ88n|{_4-8$byO7`%vW^2OVcU2YC|a zUe9v*JG>V9bXr{Z_wX<><-lIxuZPE3SxMo28D&uyHw$jt&5uhwlF=TcKIi+I%DZMK znzLo-_Y-ZIKAj8IXvBuir7m`IN}OsTVm741*+x1JdTB+{_j5#+p1ELhTk5oJKJt5= zE~P83km=sD#;ED-q_0JJ>AWvNFh~^(d)#XEC`kt;CEhn65~Zr4iG4P~NDO?yo@5Ae zV;TX5=p>JEduAPP+gYgjS=evk?}$aoJN)kln8Esq#@|Uq1@dj>e}w9G@_q!GQdyA2 za6R(ltC4`(qOnKIS&-$0catVRw1Z#%y3Qx4y0}poaLsOzb3P?nbDD-)5M2CpURX$V zEO9#$Pm*?5)`cI{Rt~Rf62dr=Ctf9w5m`k5o3BDGRz`Xx4Omz|8ZPVi?~3$YJ_NH^%G)`29`r& zyJq0xmA2h99zWdm8w^kO4^M1sXY$me(L@pC{Wy|C1H}r?2@YULr(9~@ou9>_{ zEgvn=PeZCgcRr)iM@3keYGmd&mjg+|p5JNYghRCuU}nhXk?b?MDs|q;Wwm45YBh_y zCZ?yAZDoyaRHQL9B9|d*dF)vaJ|MmTyjU;~XLXGbAxgREDXs+-7erNx>gJ7hIe_;-C z@zHGgDaZ=!CZ6TAt}=-~)4l)J7WP2udgv}!Sy1@}chH7+dyuaTZ&mwXr9GMe0*+6Y zTlMED`!k7d*i>RYl+O3A{F{1ojC!4vvTfeklX=4xS3jcZ+|Ra;>`s2?8L$(G~_ zMF1fSHS`8fzyv|HUPrl)r0*aeFK;m+1A8TTyyJmZH~pxBTT&PZ{AB_W*jCqA2uK=& z+a0!F#&?U_=jwa!T;;Q$nF$59ZiRI|cpth+Ru_d`zhgivaHH$}RhNq$aMty>=~{4S z#sT08K~P7>occ+kktwEyuj$SKd`S|v;GgrZjfzlje~Q}ZQ$vEg0}{xJV^E7==PZ1F zyyoJoq8}E>5MFS37Gc z9lP%^`B*{AQ|e!4yN=x^3Q>k#_h-iXjv!*eE{Kz(j#zET;s5OQ&mQ=7sJ|X4l@2#9 zYgAU@vyFo1%3DXVKj(}-fD4~6cP&b2AV?rNL17vqL$)cG!L?(|D=f;rOJ}Yxp@{#~ zr>KS@?db5Dq`^t0hDbmwH%Gny15R0JR4ikaRX~6NI3$$f<#v5`RI)*6b+Yq~0|@QZ z6q#wPAdV8_)NBULm!BqgJeixpX*d3_LO@x4>M40KwitaHaj98sKH_OzG$w=EZ`6>F zN~_{tx4C(mmef+L!Anv-Pbm-gy(wAO1e*Y3+ND)GR0KPfOTj#6hM!=0K8c;~eu6f# z?qglA>+mK=80t&Y=ucoc2VQy#%$D?N!v{@vBD8l}E53}+QIdl=vLWI(^etHXdo1u)B@>cO# zYnAk;Vk*()5g3Lgz>(>DA8kozCYjey=h^IS()BvEM@lvy-dY4llMi=Bj+>=M!Adqhy?S&|uMXsB%|juK3mNxA@R{|q9+Arr*axo@ZDio48}$%3thjp>TWJ+SI)x!MN{{Rkobr3A z@IW~zefubJk7%@;l>MT;f4Fjo!6mnaO!wW}2V0xFxe^diC0JU)XXHbfE+?3u^$ojE z`Z8mJA5W8Se@0b7EgBG(8x-3V0s7l>aF>_FgKKmfS&fzYGtOh5$*G|m!f;MzzOm-f z&@(*63*DU)rOEX>`+newfmVK{lqCDDQT3MJ&HA-8+s_u=R5o#@WV$~#!W9zD=bgH5 zH8m5aY7sf1H`MxmrIlv3T}v=yKEejmJ+yDw!*VLlCcj5k40*rP!9o zjv>KUoaUtw6&=mYK^4s5pu1ha(dnV8@4gGEM&?L?ilK-wfEe#`R=@PS6oxIj5=N=T z0!Ca(dR74grkZ`$Gy^0}&M_Gc8q4!^3rC^s0E!HU>=UibUo`Kx+J)83Y7U*vqNK!I z0kHW~@(z~+*nF_INh9Yq6L!V$s!T`Mbu&D$d8D0{7di2$r>kNp9q z@aR|Ku*Z(JTP;=p9h*dLYij&)ux5coSE>uc`$Bd9bJ9NGPQ5MDeVmuL7a;FTI}`Ne z@5*!j4Niow99Pgk6?F_9VY#l5Z`P6vYSie2a?G?r@lHpfV>5y?Jxos#TvH_b&H-s! zV9qT1MAUTs*#A*$zLze&q%%7~oEV|}wiab8>`|KAEU;0tdm;2Nt6_R$?o9pbRH5ew zNf{t~_a&?k!Yqgqy1`(~_q6{b@QJdiCQP_z8TJ<#aZ!LO-nf|%4S1v_$2f*$*FyM! z?f2bk1w_l5JP6|@*&$&s#f(A)gwdljgyeepaklY~JCP1POkmMTwKdXS)gpxQRX=lKg9GRtZ3?`umfg-8K_u3u{9o$)D3@P1cRQzY=%#bE8 z<5Ec3^`Fb-$tQxAmfA<~p`b8RHc#yc<2DGgxG6ElP1OUdC;3Ig3*_pO4luWgGY1VK>+6yY2D5F<#mRv zpiLG&PwjRI1sPU_yLFqv(9YDh1N2zo#8$O&OAN>%sK0=8DZTiEnFE0_`bN@dn>o`w z#dh^&DatRqMta|l44+|soek{l2=}_i<8cE4(`W?&-{*)N{@7z(mN5+RQ`LXR zEZcvlNzk@0MrA$4#i4L}J>gY1%rE=_*CqiL4Ao>`iWs|ykSPd-;+*AszRwBvP~8$f@xn zcHTeTJNWyjD={cU>wn>_7w_Zl& zdboapZn87|TuKs7`FQ(4L2%IT6JILT?vW5tnDVfb9JKN?4~=z$TQrGpeNBcobs!Um zu_`kJ=_}6|My!s)K353L!f^z(g~6tH%kvv+f&qXxi}-u3^ibh4@h?72 zRMoVPHdj~-HI`Sp<*{s&=GFdmgptm$np=k(!m1X{>ilaXF22FbeKVG`mW>%4todqa z26UMXrtqW93%H`gPYZD(20|@<%o9TZCb9%SNRreKxcv!`;DIr!1*4P@V#JO~yPl1T z5-GTEYQjXUH-ErFP;ig>`iSw;JT%QMEL>(_k!I7Ch&fHvRiJ6Ezq%<-2U7^9De`-O zP2HzI_S7@?hP$F#J89gsg$4^bxWu z^;|NZ`m5IPLwrelChW7!ZPkIC7Z`@9fBvBAcQkp-bFrSS`lD}#tJ7@jwA@wDOFWS} z6aj-RQSEGVl7sPcg9#Xp4C^Lryh{`^SFm$ha5Bu zWO#lhS)6Jj{yUQ2{e_K1Nd>eE2Hi|ZuZn*oax={mf8I~AaCMM}S!5i#Ue`Y~G0MtX z1U*C-njV~ha{KP3A`t2hINoHf5EP*8W7x$7M1m{&iv5IxN}o(xCjCxIcEn_-qb;tO zMlXXBpV&;cDu0(U!9dJ=3o!4i!dvs2+CsZSFJ5ArIHY{&d?uio(perlOh&8Nb^?G8 zu`R;iV4Lw!C2WTCM#Dha)WRpV|b>w5b{h zgpo)#u8MG6fYUJQg7K+JKs}tlTd}Hrn(Fv|ePHw53#!wXM!CTT$t~ujp9R4j5Hf|gV>6eO$)s*4smXM z(4+1VuE+eUgRYc_E(8@x_IJzKX+V+6Tkhb#~@l~6(j6%Ddh4%{NG-qEMw=wC{umRL?E z9CD+V3LUc$9`M_&1SD~$EAJ`VV*Ve9X2jV-Rcw5M`?VKgZh$O6-d!CbOXtj8sy*d~ z%LZ%u@5yFj3!QJ^OB&?NLax_M--N*=bY6O zH?y^Gp8he(|Ij3KRv5#5w5E0UCdu%BIB2O7DdDtWRe!Hv@+N;#!jtwSwN=BqM`yM4 zdFg8_gPpOhjB2CiJb!{p6KJGfP_>`$<7ROQuC*zJUq=OlZ`X3*lbjGYe~SmhvP_}H=ZyvU(8-=4Wp~|Y zi|59+d$tHMiK__TN=_IFgIZ5GEul+u+(f9WRCc!JnOXDVSZ4ORf}AJ*S$3#oNiJ+F zH<3+emQRf!;@Gpv^?;M`KBGwKzjbb=@W$qvy0EbuH0#Z%5KP66AF?k8K#)# zNBrLR>jFC_Z?E^F3aNp&tD*ikcGJ2Y{(aJjHCZ;Fw-+M;XiP5yac_Iz(9)()-zGUn zBE5FSp8<|sp>a(8AdEFk^s}DcMvrTk-ynyi+C%OhV=;LslPpjZS|S#SyS>PlT<=+| zD;;w^csMwTCXz8@X{shHuMVhTgL309gRQz=m+an?c!^(q0#x{(%oAHv-;6qCQZ}c9 zyG@b{-Or7`{kqW!8X1=swb`agg8j6N#y(mJ%5d=$g+u1rv^B97=ityVqh)8Dx{RD( zUSha}=ExK4uOxTh(p^oYxJnC4lL|C*)EPIJmH>EHBUFHEi5zh`MB^NV@W*$W(e+A< zsG?-zQRL#)MGhxCJ7KR)(UIAN z8YCxadQ3ai+@=8gSrAOC4%}_>)s(ykd6RfEtp;UjnFGyz<3XZ2b{9Z7CywGS=;i7A zsYf?o;Kwwh6(qD)$cn`;ezc0roQkC~t@B?313`fdoeldJf^g2pdt{dYkVCN=&uYjs zu+uf!LdXj{PltDBQQtA4$ChG4}bNY=Y zu07T_0MOjkMO8SfMnc&k*+3IfXuAr3rip>XCmBLk8m|X=`SW0MM|h=_{F!=n@9jWn zrIgX`?}#x?0Sx8H z`Pi@H9CfY_*-8B{x2(x%b9(bc(pp=Wdfo7V-~$7Sw9wEuLxYe|+bI5ukiTQ_0W3zt zwy3Rf9Gsd0%${KDERAD}`_vwfdljBalR(fa=f6|%$1}T1sibeh4NXt^Sg-V8cu`c%I-2v`%%jW^N4JwK#s zN`fY%TS$s2M`iw@5oc;BPQ#C1=tM;D9WIK-JD)XWlKFDV=3$yqkebdzHNc;+DEzcM zfOH+E$jS}ldogi5(y_wY+M#{By zls>QT@jhAXNkMB=)9>lX0`~*~n-c!EUMqepmxC`a6@eh{ik)2h{2{CNnYX?NqbS_& z4w?-5?WNEybc~D>Kz`7}qp1wfpEuznF)mPO$brfONI~|Z<^468af8DcbQ3&VL|&tW zmO;%Y&>BHB2@d7=5;E`Z?U{&hjgvrbbG7>HA zk5N|EVOCyNhP~9LY%8fW*soY5)b+$w=yofEA9GkkjU_hoU6p$aW&#M&pt|qUROKJj za@e~^Pyw|?0fPjlr+R&MaN74nSko3pJQpVJRMN$rnHYjrxDKoRT*tZTAI!;{_+wOsjTEQ zk%wqm9`J_B=*X|QH9@|&8Yg2vX)SfdI@1LZ;o&lU56TE17WL|u+?+BHex?ergn&f3 z&E^Lq2!H|W-o^qg_%))ZMpmb?Sv*_U&aB~MgI{ocYg$_)$`L}m4{&w3aFa=au6 zOfBIKy7YyC17_p7xx2#?1K0s)l2oyj%&vdx75FAsUX`MRWEP1PkT-(D(R2Ofg&#P) zUyfkXJl`kEwRHL7xY^_61U`|s=QH00ujO+9Lq zM$RU?hWIN;&$^vv%a}|bE@cvP z)Y||na^SwY?3O!FH9dy;C;4??C4g%Xw(_ zG%x{i|9krQNfDVjedq&^I9PIxM3Q(Dgh%;;Ek~T~WrJI&u)qel*p}C=j`}(;13KmT zNqXD!@E%3^k9-J=xZOOqC52upDM(_~$yWC~{y-^(55`DsUGPJ2)G|)*K-uryhGeEjauQpmZ{c{AAy z6IH9IiNIQC)$l?reKv$7soH1q9?aD91>j901?0c`sNX2VDg^*@RNxB=(sdE!Hx~Po zgYA}-+8q~Hk0*!bAi+Vh>s06z-#x^Qz_8spjOxAg**Z(gNproCI&jotwj?znA-u6G z!A2kP#4AN}mxMR$NR6TUlE#U`t9O5ysWAny|33k-@{m1NMgzFOr<)t9R40vyt9i zIH<-*wXe-mPIgfvhPY|MhA)$-xDYwdh1j$}KHo?fn`Usx(hA}`@!BkZI;3xjoz|vpobisWi zha;__uDwMJ8?f>DLe(ps*R`1~4pOOMrt+InVlG=qnd_jOHG)L*Q%G%{)JkVrljD4& z6$(;CNEqgBU{&h;{JdPw`03)@Y`GF@cZHf6$9q~9G%2anjS3RHeTzQj4upKROO+LWn;`*Z^9w%EA13E}T(cV|Nyhs2y41cWIQDU1{0 zXq2WOlUxcO=PBI*0+}yM=roDW-{S4R;@xvhTi{m~#S#aZVPnWTf*~lE{wf$jFtkA< zn#Dx_nvtr|1Dmo{M~G$Y(X&|}0mD4y*b5j^xLWPMwD2;N_&Vmjny(|oKCRoDQQ5yI zAlk7Y!=Q#+J0bf)vbNeAPQbSs5{f9-emFWGD0V`|ZeF+}Z%d+7&(Y4&aHx8SvZ4W_ z*)`F@e@zSGZ4OU>Zeu+K+`ITrCEI5NndkL4@{bMgwDCguNiGY*81R|mVv5uA^MtvC z0>IfKH8wX}pid&tLt;w?r~R3Lbf;4|?m*I%yT@oS%fHP`Drs$NcFPNk30Qj|!|@*# zaC3H62&%wt)T2(W_fbK?RWd;}Aj2@*OKWW1x&vFkfFMOXGtX$vdB^k-!bApXw4ts^ z{q8^+4p<&1FEw46+d&{tS6a|B%DYX{dHtS_oP43bV(@DGl=vUF(O=TA1!Wer&=+ys zDN%F!DXTI6k6qC2J~Gfr@c-o9dL22mCFSb71g6FB4iXg4vL?0&_`Gu?3L|T}X`U&s zC*Ic5GhV+v;D`i%{WaB0+d>}~Idg^=oe}4`4}3O@ z1YpH~hBn7-gv06bd}*k%Y22S83ITz5FrlstB>0HYB0ZK6(INz3i7}|8+0O7L&#fJP zGsppfHzwqJxbGkSRjLM%W1?9{bCkTeV7xz;dATeK&Mwa(K`+VAh*+-Cz0yW;%RL`U z&q%YUC(@30+;|lL`*+Rzz%Gbq86JqkU~`?c3@)wW znMww`m!*>Z*W+(d`jQ;3bp!g6g_0^Uh?Ri*tX5Rv%Bmgpo;7}I7rblR+9>G5jgL~U z8#ZJ*ldUxo)`)IDsga5BzDE1210M;mb2CH5`)tA(cjM$`H4) zyxk9i`jO+P`Y0DcgCHIvQtuu6^=Q!VD=@bAwL#)_yRJkX+gW2;e~sLGWQCLN3}jww zR8a4uhiT*Q#LE>v50^@pthRmjbaVYi>79=gX6K4nG= zapKEEiFx~Ez)y8un%A2KO?PFj`(*P@GmV%%g3n0_*DWqD(})fXct+@0NQTkG14+Ub zw}I>@F5p*Bzg?}aZBooXJkrYKxg(bMf6$%eam$ta^8H$TEtd}Tnf(b33lU|}Eok6t!#{)va{(F>uR(UWW8cNAHKcj{dUN{E0s3!5)buSkzE|&c#M0;v zIc}43{mLfv*1e$vCKmhvoOAm~TwDY^ar|<{^!;Yk2%DERl-$mQ1=#*EF)`6T_XLsL zyxCj44&9C{W#E_7*wSQ8@qzGb^U#d#X%NsN>L`nVMt+ua4hCAG0Z$#{8>NO-Ih7`5 z;Oo?%kYbVm&CHl7qNu(aj2Q=QtQG0LY@AL~yEJLSu$7!C^~BCyLHz!bdqBk(07sHb z8a99O4$#E$J%rPn1L%v8ba^L&=yM0=M>&1V1BV3`M&ZZsCE|oT4-=^qz&j|-ruKkY zO={iE)i_F>@zgaL&sMS+Cw8b$xG ziVt@BjJTP3(y!oCf7RI=&UhSgO#f}wUGYlH3}NQE@zN(l<;>z7 zA{mXG5m`6`+g^486i~)C5EH8T1OXYZAB`9cI!~mIH9qRU?!{x9i zpnTj(5X~bkIeFNX9}gZ+RchaiDuBskQZ7hnug>_O(LNDEOMO(GyaJ>j|vZzX< zm*MT*dgu?LlwCdp5(Ovnj=PAJaos8mq8SgGRxj1z=;=E!dSY7Kfk6jVQW&OyG{MxA z3br4om)}f)&~E{a-%8jD<@drqbE9e0E2itV&CwR!`!!t+qCmQZP%Y`>!?UJ8Y;?dI z0~4R0E08q13#TmX=`m1|r?#>i)|VEhj5UI1ZhOg@q8}3&tB!TPAn#HCeLsa(w@xir zbW?@C>3!dg^>H}RWApm(Vj)`Wdy%lVT3#YxnXq?U}Wo? zDYn-EtMHM1;sGr?&&0#){x~g8vU5w1+R6iWe^HMxgZ;;REv^-kGq`XF7a1z>wzN9lO*#`BNbF6Sg64FL3JFxO(uV z)9esMYRBr3^pW}BQw||AG>E&@m(slcL#iYXvF8)`bGYkxkH+L(uKOfh|Ds?wMyBx5 zg-&C@$;~b1D#dy4r8JY9okA~5k3~?BF(DxVa6FCQ1?0U5xe4WCFnJT%`&XV?i3*MN z!-yP1`zH`jWMD4($6n$p^ipP7@XGW;nod?Xd{x}ZFA)FBulP$6t-FGWlbSRvt=6zNC|)r}3<2s| zB{PUh@AaZCN1b9Nv)}96{-j>t|1-%4kwU87 z1YJF6L_0}ROMMk%40Y_U@@urkY8z~OjusB`rlk2pTk7n+ zWpp}^f#UTrVeRl5IrI2ItHs8;71cZkPv=!%fASlC%DmD4#<>hJA(QO~| z<*Hy3F6doTDvO>?E1+b1;r>6XEQ$2e#+QdUC+*!LYI*oKBN=;?de8thhClEaYBf-9 zF0b?tZ2;Y+$Bu*<9A*i!tF3}6Or%wLbC)TDu^Yi&4h}FS4eY1kwiXOI$v`levB`@{ zIm7)+Tu%Ga{IdUQkgU6Y+PHY(=jQ+YuaXnYOOdU3eK7urwi?Ic&-RGm_Om_&!43_6 zPyvzuEWLwLN(-@~|H4sFt*P#93|@qyiImN2hMLmiculTG2JHU<4h=s`^SE7Q0y|sA zPFYI|TWWNY>wrY{?`QxZ$-}?)^GT7q!ijyUS=|5qCD0Fo1@o0qY5IQn4!tC@HuCQt z{%5&>ffJA{BL_WQDX#Ujl7q9>4K-0NwUVrCI1vE}Vf@tz>)>`@3!5-!5Vggu4e%P_ z+~_9dx9v}p*;<0id8)qu9!1=|sHFEs_ z78Lp<-hpmy8fI|w+*XbXOCwQH9b zETEJ)1Y&&iWJqI3Ur@ev?^Uy`r!?t>Y)k$V8sOga<9<*^(U7HegVI4%seE`w8&aRV z*8cC*V+p~!^=6Pu)^5eg(cBaP#Vsuw5|WDJV{;jRj~B;(sfn~SY>$VNxDDJM$`-rr zVT#S@`4Ggm3?K+0qs{sy7;fC!Sf*mQq~Q!nFWUFVZASLZ2EHe3TEc$|3(z^K*8le3 zbb4o4TXN%w46W|<$1pbyD7)PP=9~U2P&+6qh!8gBD(wcn-KkF_Tzas7`T6-hS=Pr? zl_;|Ks8ttK>uYO?obH`i1p0teR#K9Zyb4aZvxj!kmr5c+6pT$LCY7!Wa=pCgr2t7{C7Zn*|#<0dv*H*D=(71Y($ zxuT}XaJ;6RAMF26kTqZu>+sj6y#MKw*%k%=P5Lc<5~<{@PuD*+m}`fTOw0GqJ>dZ} zHNe;O&w*V82Q#zD$wCc>$m$=RGIStHWwA2x0WWE!pLly~e?s^4^g37^1EzuoVNb8F zlAD&;+q{l{cixTD0-)WpcO=B)abl-mG%-%ixq$4%|I%8VVAW#K4WI)g4k$C#86J0#vrPw&i^79{0s|y;J-Ntq1a-xUSt5Mp7>w zlDTj&xpMb86DnP|z;^^7*?E>4hgHPDb8`MBgTL}3Qyc%`1VrDCykU%rR_OkO-Mv93 z2+$VmJ=5r5jh;K!mTOR4_!8-zFoAr@Dwt6VSRqT2k#=%wD8x~f$(~pT+Ufj~#%SRC zUR+Gv$mwJRQk&cX=kD6Po~s>9?50iQ%~MEJrEaI5&+#al?#?GHs~q}E21u1kV1Bg8 z({RcF-+CKL6|-k|Tm_Tp!+?0;a_KZ}C|rTM#(@uZIjt*3qUOwc;LcrkMX-O$1RS{D z&{LWhIXgRNnMim}7S9^5simdVZ+zaPCm9~kAKE%PX25y%vlI)!C%JF^Zq@k1=^ZqzWw1~ZrC`90L-6a=>u7fYTQN|1h!Nqx}jSogv zM~12G-zH7+*_?OrK#`hSYmsk*zVVrCnCpLvAawKam&aR`oaVS)YzxTvi>~`;3 zcw4SVv3g#}+gvZx`GAnW$r{OKPVlmOD~b<3L!KDWIafTwy&SE7I+6{xPb<)tUrnz_ zzc@ zB%3)}4mi-I(a@d``$OPaSXoIom6)0u8&7PC0VPxau^;m=mRg6@k$qUAs!;b=(f^_p ze9#)H@!wO~4&lC#>uA__Y5!fzOoXWY8Af_|djdV0Qnds|i2w)JA<8SMB*>k+va*+K z*BX4Rek97VG-G#%Y8@mg!-kOCTdY_itMAk7^!hrb=#ZR$H`T_{_6=y$I=Rgj5L@;z=m!Dy3OXgb6M$P4rhKD(#cL6icT8 z&=L?qgY{_~;0bi9W)b&#CQ)ejENfxj$y6ii-rrsDn-SHn*Bh~<$5H)N;ebHcmYL?6 zy$f5FP)BNU@LV4r4sC2wiF5v;kP}LBI;u<+5B0;Sv9mL(E1u$TJc*XY*IqZJrHlY= zDTyYbH2JQ9Y@7nT2$cn!Ch0eF4=*rQS1A=U4p{gKI48YO827I9!U*Tw@R==8vD*cdHFZT%-31NwD zUQZVJK?SAQtbp8^9g5rSI z;59iY2jAC9 z2L+*psJII$c`@DPZj%SZRq?5)`H@bEyI##r;XqWyqV|eq5A6adS{K$3{ml`ViU$Kj z-B3lkX(cS-Uc0$nRBr2+>p1{sE4PzWT_)FrX!%JgZ3BaW4&JHD-T-jG)dx47l}+$;?4haMTJ& zKNJ=sS2uovZ;@2T4ICTb!GL7VX{62;8n($=cR> zXug@Wz3-`Rf5f?lj3(o1yN9vmdLtQ^({6O|^IuAXhIv4s_1`<-1Z($BeDv8O?v#uX z+J!N-3WK9;^dkO_DJ(iUMVQAB z8>b4141mN}FlqznP%Ld?IxRNz~4q~mKuR%U>>I}~j-E!0Kv;`u+DhY3+iHL5PDgKzJqN}}W< zYKFr26VI|II+VI-C&d7zokqck`N9eS{lzJ~r|lHDO(5d$2Au!#zJwce=9v|9E<1Ji`-dzm0#2g+<})zKnuEN{V15qFZGs%V!H`KnWO)rV1Z|YQJq)ixK-hII1L1^_Eo#ru zDzPkZar2e9<&^T~QmkVt&!Lu*%2ZHD1gPLbQAfZ|Z6+hl8Iz3t`;|LF=f@!xD{HHy z4UzN2Uyd|`1ylo}%m@(i>2YC?UEDuEoj?{XRD|z7N}ZZPFVQYj`f~VN>$X619~vb^ z>a`p`%2etBXlAeE^G)^IDrB=s(83l$;K2byLCQNQ@O_DZTO~og3}e$p0-$MDR@NZ; zDQBzbcn}=wE?C6I(4bNgajCOoAif9CI>O!Fcl?-gud8)&^3_IjN(zU{)!`@0DI zKb{j;$VVcB%Yua-xv+o%tT(|X zIH=RR;!%>SOWwlj6u$?buIh8!`ix{cT^>QiPwaUMK2B%^_+dElLWU@j;uZgl8FVI0 zhAXIl%iicK97TvHE!uFg%0Z-v8tj8yt5DD=%shPU^dH3jB2gJ+c;14OxKB2?s@kq2 z)>^z}HEWbH;GXO%>}KYdsoUGzIi^IxEPLVH#OC%f@d1@>nYHZR5RN|su8kfG13Km& z8^dRsWb@9B8hS#$?g|)+#9Rui-E5(kXN&B9lGinX{4Ue-lFmpNbV^W0qN8JyK zb>x|q1ss+Jq#N;a=UdL)qhcuo;c-Q1A#hg3Tu*wUXd(4TmP7&|31sO}ck}Qpk&WYF zX*EQX-Vk*-A)KS5^lBitih}%ZFl^3zK&j*LS1e)s)m=MTr7hkRjSQGQ*W8khmhFX2BFvEl+Gp1Z55 z4bA(0PgsONWsJk0*-w{DPAHi(3%dZjLal;1TFP>7?w)l(x<$|GG}Wahzb#om;@ z+YTLMA2WIxH}5MpX+)o6N$0)mk3m#&q$el`91DXRH}!QTp?FC zHvr|mGC{YWoGg$C=X{YHOnYuK_ZM9CaH(f-N8|0$q>oOOMV6^fTM#3Lg%aeiBC>m(o$7N3A14s7Kf&68E*_)I;6sD#xPiSGiQ zu+?+jB zr3x&X1C0SW#WHp*&k&)=vGM76@rYq!4&M1kR=3voU;cosiJc zF^JnMFw-D$D$xO*`_Iwlfs28Ubm-j@wNmxx2hw+U?HbRkGS(5%cieY9k!KUqMAWu- zsO#?cryysHZAL2`T-+Sf!(vk`ayxrvQyKn%tguA>rxz6XZ~B-INyemM&Clc$DY0{) z*XD^#!6Nx7ry;h7v$U=;aQye`9v9ErZ!f-r(XD1IU$E-MXvJH~e zIOE$7G7on=#Ig{xxCUCH9r_;Y|G=9nT@;4@QPN)b#B{b&*$b2D#N!>|EckMe#WEiUfIje zLd5)vGmnfQVMg_jQrCE70hm$bHTCpabHG?EUr1HYjfp3^`h&lQ#{7{kh-% z7=Aknu>e@(Ty=3HPHtN6Z|^An8qL7@s3@H<;le;iy-`Qr_1yPA&JUa?e-8ks8&hd0 zN__uy#`$~QWMW#&jVd=2@=Q!tc=w5@Al3ry;sYFjfy-y;Z=yQ-Hm>FC4=|s&ljL@! zRckpO19|3<6KX_>VMooIcTcb8OgtYCbL_Lng=4@utq-DU&7wI_mj(UQ+CkTryHjCE zD8zl-<+3FpV>h^DL}XOd(XA~q^T6AaVcWL%#rJE&8m#k>eTDcqXO4v4J}OF?KS!XH$U(=EOg=9SBQ*r56gL zj|+1n(NF22Tsk1<*d_dCD*@!mCOSSmPRNr5jerT!n!dAqp)@Z#HBg~z{Nso89d2KO zrR*t4H6A@qhq`1#kC*Wcf7*GkMYH)A`k>IS^%ZoPE(?eMguE`l4`O&^=*+_+8*c{e ztccbUMDK8ll=z$Ve{5bhEP7a@)&kBoNrOc#zixnAMtIFnYTLG?q$KrjiGoQDCgVSD zcWHWUE-D7?kEJY5J0culdB7QMBv&#NWi&j#s2XmDp5OhxK0{QHrgsTc=#Z@prdVc& zjKK4M^Oj4Do`*nwQht|keq!J}L4QM$C)uooso+w-|@&lR4B#{#^sI71%W5d+=x1Kj3>%@i)obg&^NY7irYa_jU`KmDCBG}o z&f>+Uw>*bLRR6=?>q_@_g$LIW0=mdv|9}1Oc&+8-m4_UytZ(bM?7DmEmWC5>YGn9S zZlHl2x1YH^YiCOS$R2W&gpna@dk2;jj2T!X<*CJr>6z=9gcz_-?tw%7R>(86>p}RI z2V^H8Gv~Nbo{Md&rqC2Scj<}ms0Ff1a7-}LR^GaQMz9mJkTz4~kN(WS3|k5?DgEcH z`|o`etNGZ~nxT0kJ~s?-OO+rJ_YheY6?n(9&C$aavbfWSgyYz3ic*NZfq$zwqpPEA zz~(_HV_v-dazy*malu64H9BwS>z`}Qe#GgPhO^YRtR0UUPsduF5#x=EHC&dG;5ak0 zPlPyXvA1(-$|FxV2O39U9<~?>3FR;mf`0HqCCI%H1a;E@ri!noS5`uhThsTDC)>q0 zp0hR?MBi^jSv&8u{Jw}>jb=^x+T?ccO!~jQzqMR`_iAQ;fD^fdpsR)byMeI@9!qZa zv}WkX(i@FfckwuJ5!3nl{-*gbJM74G75w$mc{P<**;+-^idgP2>)u?|vB-ex?|6pW zdnJCcEyrKqn&J!x&@#OWvgmQvVP|?oKBtA5o4HcQTSM~Qt{6+r?!bv&4?m2ws+JZm zRwi@IG;E@8pi)1h9}y)wz8U}T-)B~rJpTs|w$O)AKL|V2q8VT9$!r(--+}+fRD=0Q z3S|YDSSxM$}%?u{ZDQK{Gw%c^P61g-!Y>|iS?40AX8Nc%&9_D`Nd73z5 zPUgo;POPsaVEtk)Kvef3`i1;765Rxr4=LV7y&XvOj-2NaNX}jis1wyS7)lnJ=Da5- zdCY4pUTt;=$Pk z)p!~>wpSd_mzJuQsHf*Moc-B<5PZtK*nhp%KQgFzDCH=)F!yWuE#&DexH$}_4}K>Y zPYF<8$qdS9kS;xGu@rL=Q^%DOV2*lKDN~OkT^!+6vy%&RJ;EYE|F`g9F*t#qaNetI zU2?D6ddhZ$@{$7(Q2$%~pr7?$xOnZ_8rOieSDCy@8e89h^6J?-rus4AT#ja9m6E(; z(cOgXnBhoN@)l9bQDrFkh5IxBV&Wj^K?F0hSWlPchiW1LAHWLvt6I2ENp^~$3qw_* z0lvI|bU8+5R-(rD8!lUpSh^)~b6f|nyuSGP{u%U*k1PJau-A_|1*t&U=PzbYo?QzP zsPFYE>tBt?=0p2t(cs3%Fq87{@Uh|d!^(afT0Gb8?>85_Q1AOtUUMuK`N(k9Au*=n zUT=Y*e45&YG3;7Bcv(fN8KJPD&?&r%-BK@}9mrdFp^{r-3^r!!=#?&_y_zv_)%f?@ zDzWEwKknYj7B_%ueQqbil#3WTuLK>j)dVvIz|Mf^YT6{1QzH2<;OEB*g@XDSTMxI& zuNWXWUyOQ?>rqrqID&u&kGEuk2f*i8ry(pSWcx9q?o*(MgM({&+?}BKBw*;}Si$X&vG53C^D9J=mP5`*vS5YuH4`-A|5))(2F{1~&sC&m*fbdR zIXf}L6e0cBM4FKGl$sTr<@r7deVO+LtRb-@}Hw!AY!{& z0fu;1K{!d`bfEop1QOv$OkUL+Cs)cHo7l6$j1fPuScM^6mb=6#^SLv`enVa6@bEB9 zuf<0iMdDyljxM@L;tBDV`dIe6iRF6)0afaSSM{$;@OGg?2`uDHHn$uZ_lXt%=n{Lw zgOAGp=hV=W(ip7s+mj#fS{NjGEZ8KRY9(4nN7Ia+nH| zMWq{ZP#!k1b&|Q;Z-zS6@~*vujKddzFgd+ipH@>btHJjk)Spb{UQ zX$(gNg`&#)`nC_0l$W|h)DH{&l_3rzV=`0U%6q>Jk2;9rr@%?-H8;>1l=8r|UweMa zdiQ*4$$H^`nn~`U>b#lWjO~0o>0Hol!BE**)a9#v$a#N}yw>f!)BW$xD@Z6V7X(kV z>AX7mkVA9SXBkZHB2o~`dN4^=cuc8kR4h|SRJDss`R93v`cJtcn5?wXf3HWHqrY2v z{7c#v@-#rro4p{_zJ<?s=6jO>bnM+XgMO4A~eauA>m*eAE|>LTe8Gor$lG;vnJ9w_~887^czR37MB zleyrLO6R$cp9}NfDR63xWCYx4*ynP4No(!)NJ&qh)m;M5sQF;e9r9cK&eHVS-86=z za=#2sH^GbA%+Q(S-HT+;i>2Pf@Q|`)U!`66e^G<7468p+Qyt;Fzt#n)8m;_ zhz8Je4s>>0zuPa2OZO<>=J5%SWFJ$@cE8h)c z(;iKZPb$BWik6IpEViG!rfxMHCxzNb*me}z5r1$t61WVI3%3i3-C+xf%5&+m)aH{QH@d5X3>V6Uq|F>nz zhK7doW;#5%C`>%LvMB-~NZ60%h6+W^_OKh2(FGWRQ_w{p#9^p^)tDzC&#w?uq2JFj zWUfZsGqnA8A1xe2`QMwFeamhXhhasi7V`Awr#Bzem%h}cSXx}HP6HYUP8i*tqr!qm z9lf(z%p{>&n)BuIvH5ns@uy56CXD}>{1`g#a4N@O-qQt7F`shEe{ONJNEP7f>Z)p} zRW%qe)bmaIdcZ9I!Pvx)ki9%!bfZl0PYQS48Q7Tm{uujCNBTUDIt(73TP9yWDdcZH z&J_$jF*Y%@x_Ra1dERnxi>FR*RkuK+BC!CnlS$``{`P~QbRIUZhd1Mmp-Yit=bPL; z&T{IOR2NFeijY21b-9XNmiaKAovn3(@5_V2W~>PR>yp(O?J46NvD@1}Pcy29dL9LE zw6(l?^`?rrSFJ;(%5E>VsY{nmJkF!RE|>V%pk)!H7-&BGmW~6=q5DL9XTLD^uYXOH zz^@|xS%_RGfKaBpRwHD&AIT|Ivzk$TGq@KP1{?vsw6coF>)JYL@p~=U zsi~>moXkOsa5)ENVk{DMj_6w+ ziTBH?g=pDx&h1E0oe3&|Zq)*Z6NRz9u!&Cw@?oz+Kj_K+Avj(RdA=bWo=z{#tLk+4oC_@V{$7s?N zPjZkkqc+AN>fzMl6)ANZoorDTIMl85ksQf(s<8(uTvf0sgl<0$#dR78-GG9w*hVzv z@T6Hrq(Jbg2m?{MeOngHGT(*}D!y@ogN0KI|8doPM_PKc=BayF*VSA5J#1g$+20c; z>&=Jb3>8HRs8jFq$LFp7g6Kf;$IJE8;6mllJOq(R?~j{8wft8jA3Yo=K?2Y&QBQ?U zTSX}?k#Pea5ZEDv$=>lZODl0RQu=df;dZ8DTn z)Acjyw!6C$;0bN_7CYbWdO}sTNnc(;!(a%`o>Q4Wo{~J-!F1ty;l1bo57e17GGbYB zF!{x5OLn^)%q=9ZP8;M(eSTw@CQ)bH(^{A1+@7~>Z;Rh{A|icY0zq___XNxkTuT1K zl(R+M0Czw5U9Bv3XxfWgUkF-s{+^egPqO=i1WcGgx z=Je>cRx$MX2j`bwpM%(o znZFbh>Ls{%WZ3o_x@DV{*hxQ(Lro0mltG_cavN`x6$3W^b^59K?JW9Birk$R?H0Y? zDW8n%5i;*Oyx&Kb9)ff7FCO%8%709>w$QEN207%*RON&c61Z{UrvkQ^t@w7Nr-k64 z@??L6`TY%3x$=1Ez6^X-@88qxllnT_-a9bBa35WI%)qARoewJz@4-}CQ=L^= zpSVm0QrhRIbh0QK?_irkU>oQQ9+vVzCAD_)PqE?PD#h$J^R>C8T3#nDhY>+m*tMd^ zB-fD;Gu*eZd~DIHVgBody`Q!V;OopG!x1i~T^!wFW#o*X6ehpPvo_7>cq$$ADHd!q z(BggOt_|fnC)N$|Atz&|AAH@P0al&ZYAs|Dk%CXrVEMKW^Xnw{g1`UY<%R{d_D|}> zO8zesv-mY!p%09zD4I%5be&!8s1r#9p}sSEGhJ4CR&TUTlg7hz>V*(1YsW1Ho}4Ke z^2q60xxDJv++1YY`BqeyQMD>Bc@p1U72z2-G=Z3v)fK1Dy6NhHEvniYC7uLA_1b>a z367HgC_>aAZh7sFYo16eOzP=D#!EhpC17b*)SqkKpYnI-HDf2mAdol+HuCSth2X>&){;???C`kp-DCj#A=eZtPe9nbVk z4glWO0C%n=Z{F`+kUSlPT7nq3El+i?Q^-0G6;C!ODCldhaM(jSUk^_X;p#?jJ43M4 z5rRnQmEY--3ct%`48x?om0drxt?P(XZhb7n^gUXmwVw$m`o_QX(NShYTEwquS7`AL zGeSGBubc1fZI^#Pdkz?g5~RXkcyGS!jt)J{S9wO;h*HgREBs<4v4~WGgG)w1iU^$j zEC+i{jGtIBUxY^;>%c)69b@o!;mJPt$+n`%*NAZOo7{7wvoF=xz>8sU09(zA$%nF$ zcuvU~{ybQ$TaFoVNZ&sg`jmK5quj{qOxc@kj@j&pk9AZv?bLA>2|sP=PuVcS|Aq;h zHFXngMJe`+3&y1DISo7ufb^7-Dg?ZLjh~^sjflYa9Wn+S?PmgFQ?`i&=@Gim6ZXgy zh*00Umyi&^e}aS3Q}}h)cfaM9?7a7A9qC6n8K3Qltc}i0WA`&PDleT4xa0BfUxeAe z#?}fLW_)KJ~!!`bLsiTd|sxeQuvBO0|R+h zV`X3?W5)rw$+dt1MNAZpw_m^6HKIxN$^(}=CZ(z&v3ri%-1C@YOi^fTj}(p*-w zB3|x33s+Oyjza-g9JYL0=Z>92e3jo$*6w9auNTr(5kgtKMhg+J?fxr*&j}-@j?Aa7 zm2t~~e)b_eaxbAOVki4tz23}aIgcMtv^#q@9Sp2J#M|wdzWWGlah3X=G_H59;Hj@+ z^3=#kdeWW8nDTe7xytyI;htu~LqjW})#VI~q@N<0fb+5^f48l%zd(i#KkrN5@E?yl z$3K}#Q!{mAVZ%mg!Y7Ph+1ne#MG9!Eh!X`YW8wj#U}QpVfTYqoS6zS=qu%P8FVN0G z+NN=y&;?JGy!d9Su!}rKT`S<%A4NNf47RbpD%t3j6gH+Jx+S0T|dv_Qsh@hVL{F^q+D=7;_$ln132ytMCbbf&iMVe+txZ< zbq8n%G@2B>z5mopjD!iq(EYr9+yR~RM%yz28@YLTcW4@AN-D}UWH61DIqh?@aB7kL zNIC$h6MZN*OC0GKdj40q{xxP#Px$Mtt_mAZNfx_|{x6~hE$tfl0(H<#l8NPhea~R; z+gtaq@~t6tY#_2GxxKa;ulnHUe+D~UyzeuW}0xKLY zzga3PH*uJ~bn)rv=*8g!U^YGx>r0C6GKV(A9Ou2&%yo3Wl3mCngk+WX_@>SAjB(}P zS>6XR#rw#TwJQd)0@K5qSk&m1@QC_DAl6r@SL&9GkSw5uEV&XksJm1Qcv%?Nz3%zUIugm+0lqHu=hO2B1_n%h zob~n(_U`}$_<%tmN%A0xKazkxNjLT$NbEu7&qj}?t}f#|_q^8^Uuxh)309ml#aCd1 zGPH@%h0L1>;Lp)UsppGH=R3Q0)a_S0SziM$Fz<*979fTW-d-#U+5}YV$9O_fj+}+e zaR$JUaVvx=Y9l!$jiJOLAnsda`kv=agg3_J>J_M)NR>Y4Rq(zfae6 zp>#*Hf_lk8qokc-Oh)-rUZSk1jbqR@xDjS=H$0w$o1c2oVGE~kJ3U6Vl?BcVMSk%o zl*GCjBI{~D;p9CFE9Hq9#9R%J`id8Uu*Z4J>Me#Q4G~o-cX#N5>M1+em^Zs zny6Mp0xq#-K_rRRwgFGYf%Zhkk)!6GVtxxfh>mA>S8jfO1|Rap=HS1^=FUs7X54uj z*-7^Pw9{E8KQih#=Lj=n#`q($mJL}h|A-!+lqfD%YhrZf5Q;vi=Z4^Lg+2%iv*Gyg zjUige$8s4Qa9Xd>XF9#+#a0L8&);V%37%Ct^TuIU)*WOZcG3$R8IcD>YLxuiyuutL z$M(<)aX=n@Z2r@IwlZJlOw>f8>Kx4Xn%4vRKTrFS23mXi$y?cCyZ^MbM8R!;Ay!I*|nV6Lnj z7#|vAF8`|2p1Pm=Zd5n4RCucwv%JZJjb4lV0dZ)M%6VnX?X7e)W#q|?umpfra0=vR zFHYDfOqzU36&9M^Xw=3eK6Gbn90H|H67A4Od6BrRrK(`ue=&5pR4gK-)9XV=F22qT z9*UT3(EP`#z7QEHd|`pdst3J90HFHKv+stZ&zKHd2J=NWo!@&h5Aj5!rnvY0bn;En zezPT$H!5KxH$PdJnVH$^C9|Wcp)_A!1DmRyWGxwy4Hq0hnqQHl-wL`Nt$9E5?&eEN ztUV?matboVNCAwZnwwfbHm(iU6i+iIo8I8>X^)?aclck1umEmKVs2wcNI`P#?PK27U>#7Ag!Jig&SZR{YD9 z?60zYMGhC@l5^r!&#B-2!6NStfGeWCf$_>;OH_4?!J!f+NV}^jdQ^Rp;e4)+AOA=| zf?d#|{m$FXI^(5_$BX~3?gY#noV@@*+3F@c0B6ov0#89jTN<82!M_zY2NRiz9}~$nWiWV)k#?rJM8;pz3R+6Ee|!9u^ISjaP$-Cbeg+PS z97_L%O_6UzX00C|uMIc+%WzNmtu=)poq^7D`a?Fm?M=ooi^GndnU9+rA=7M; zoZUmxK6g_!Rrn4R3t=_zoV{n$7@S;ByiG&%&8|qX*Q9>>I2Cn}l)zhy*MJY_dXBar zHi=(^oOp+>4uJ=IR?q}y#d`pFBw=jiwI3(wM`PxACInj_i%5v+Ml$sEuR)iXkXwSi z8AqMm(Sq@$gu&r25@q!+K#tV|69%seJ84$>5DnGG*GH#<)`ka*j?%eR}wR=TUr%{k+qm*s7#Fdct&a!Q69PYDc;njwx^Qc$2`teYcrvnwSJ zMzW6$@k0`N?NT!`=Dr+t_`dAIr%0>cd!vo`K3yI=tq5(%P_LL$)O3sqmiatZM26md zwYj{Y$kfhUs2C++^V{tu)u!a4ru&Jj#dGy1O#cEBh^qn+>O&@wpCTLWv&!d&i#oGw${Uck<^sZb4m@;R@<4;D>va`aMxn z?SlFGCrk{kJkILGkX)^GLfw=Li*sS~18axPO?L;YJK@%M>}~OC$rV99fDaUo2tL%XIZqLg zuT5Z5g_H@T`@(MzEH9}{EFCHJ$e1Cc%6=32XK67s6h^KFv|@r3YuH=}@L zKZ09SP-rf<4<}=WJ~`F^k%~_e_dJ2Z7WbTgGCf$(R-ivZ4naMB*JU2EB+g=#D>H-L zs5=R5!8R#UyNG-;)S6B_?=E{txVNydApWj`4UD~)NEHUwuKSazd-(tG_?Bp&CG4%a zva+f!ntCKh(Zv|km^0l7eJTj)@GJeSehEv2zSUe@KhbGl-arL`5&*E)!(AO(QoS*O z7!(+UclWiye~!DYu9M7^cD1X54nWc-`w~c!VL=n#UZ-aVbp!9#CHAopjL6vH8jEAu z+HF;oQf>eB`wj4l;?ABY!if8EZ)ARJMcDanOSt0iZjB}Xr9VK|st^`tvON+4nBx_M zS6MRhy{~%k#GF_VVG4Gqg4>`9xADxRVVaef+v66tsCc>1A{!SjPP(pnKXY*D9JD?- zZnJpX0yJSykjOQ~0F8{1vEWOoXV|IA&IP+XPHlgKECJIX4v)EzM)LeqUyr-DyY}TE zz95ZxCs8xVc zNa=K1yW~7=h|GniK6hfOB$9q6N zyhGztv@zf>$T!p}-h%})p>m$}Gwh`0)M+5+k{Dz{fd^=WsxA*<#y_-Mk$|Lw8aKN) zY7OCj{pP?>oK(12abscvn<&!OQTB^A(~Kb4Ug$>vq_cpGBn`jIOLwuaebtEq3OAVvZv?|4divIefgexRP;U8cG> zXH_*aF1kBziLwY@jJb*Aj*FUO24a)H{bbS%axD#JDNq8}9&tC%ziG6sDiWU37tQW@ z^5a5ShJ%9f@wMsVWBWOdMBH?MqE7-xd{-&z#J#aRY;hUgIFV7}`-5$+52q4`W>pMZ zxlVd19GQ&;+j?(=PuwftbvD~m+uWix18nXqIM_~?9z3FM(SRHqEk9(7O(M^@A!TO% z_5>0I<&!yRmk0f(5=p3cLc$v4yFRH_+nJVe{Ov#hLQ0&@i=tv18!tB+>oE$};xNc0 ze~ojhhaQ}X5F9wo|Jn`E$%yOMejL}@@-T{4*U|)FQ@yE!NaE{s9iwJKMY|IaVWT!) zo$A$%P#u%lVEGhHk<|;dlEHA+Ha+%JgiA;DPp3K!q@#}#{$mLtNfE-tpKgB}wa7EC zGr3DMgVJ0lTM>d`!_PvjE!hc^U7X13%trL2Z|N%Q9agMe?G<=%j}V#alxUX?t&uC} zgQAXY^=>sIbs>ul&rerfmzE}69r}_Ho#kES-hBQd z>!ac+2a81-nEQi~@)M(q2|OJzT+3u1{V(+l?di2OeU%NS)nQC+Y3p2T!u*!kBMy|c$qF`J5PIUI51u?` zXt$jo0h*s1Hk8bRJfo+C>h&x2q}TbL<<(`Z0WAQ^jH=qF%#PSClca*`OE$46smg@!mRwJW!Ay>_!)eLoNYUz z*%7)v5ZB+{1RpJeG4>=p-_&vER9tH8#}s2e-VDqgOlLyGIz#@42%jCo%@{2MPic>Y zvyCC)bs?w0US#@Iz=wYVtpAILU+j4N?wY1`e^KME1TNe{z?jLNf+0WoSY?)zGeM)YS3IAK71zUew z`!JN=pinEYAS3tgv%x&6=UFW3s5sp1W(H0Mm6_Sv%FgI?Go+Gcv{v>QNd*Aj|{WHVJ4IfXlCJ(=2 z2z|w}H6V$S>I3$WCdP8P;x?&mWFOTjv*nW)jI>J>59Ue?@gb*_N(4!wf5Iipz$^ zRtJ&cgGsOEZ`B@ z$&PAZ(yp*5#{+*X=k?`Y!P`63UJ7*oAowafRWNznNM06;t{xK+hZ|*}qyk$}|${i^aV*d~Bzn zy&~B4n6KTv1T}9k#e+&i5A}nL8(FhOqw(nM_9n!eT1RF^w%=`H!KlPOI(5uMrYP;s5}nF4&+K)W zj;>bvE%8yPNTSKL^`Uq!OTK^}^TZBY8$?tTO-}&^%TjTw6h@pN=5pD->?5I%mkU#b zQlzU~nN3<&a`|EADugI+0fQO({Kl2-mdziHdSutOv79qTk9;?!Xd7&b%;d!*sp zc^i&9BZ>X&Z+{wEkmD@QICwcI>KG|ikwYja#D*ng-i-^_n!_{aX+@b)<%%Z%KLhaIm$>NNIWT8l#wd z?URTXbv@lNTnGdF>s%|(8jZ_~!cYWsZPcjX7Tyb9ivZlv2@HoUDLc2bM6Tbbbx)9LBd?U30_S%gwlCvT zT}fM^z9I#p$%wu%;rZjL;#`NTke;*4(m`qHQ|9m)R?J!BJ=ilvCS+T@#H`-KS}$a> zPhiCW18)k34u|52pr9b(@z&6tDSV&6K8DUWV4ij6(Xcnuo`PY6+9b?Nc!-K1h~mt9 z>a)bUY;P~`9)p7^6y;A0fcwS9d>$L|)Q>q7a|w$BzoVn0Zkd~~+lPlyN{~?Q;K~rv z)HuzEI?RryvF3U@)Hv}f&SV|GR_WDLQb@Av)%M;~H9sYidFk19+;60V8lsp)lh=S) zK7R|nLRg0pXsT&*xX|vylDK22c2)P?Y_8jTz{#bZcHpiwH5QWcq~Z|Lp_x-QF;YIk z(b6LMyxo$ccy5p?F;hT~I{M*Dq;!QQcM(_UV53!Fq~lz>wi=z zd!#Z>pky!{uue{o=V}68Q=6DnH&I{O7^dMQW8*@x)$yVUaT+?UXol$2D%Oifk`j(e zdkl%$iEkP@WEfU-@~^%oyC~g{5&@r?H#;afd)-aj5F?t{-4-Oh>g>&xGz)2OQ#(cI z)Vj12nYLxxXi5h0v{8MXzQin*!vxKv3yrX6)C>^~1QMy2QEERP$82GK9M!~lQ{cJM zgH3r+?Y}L+N~GK8)!m)$9L#5e3xltYIFztUg~rlfqnI&`5b>5=k*EeA8a~xlnF;)s zGC`ykP9nGKX+Q-L@gpE4k79Hbt3g`rZou1H5F`->@pf^wvMhE9wSu!f*YH|%5F1N; znsPeCKXgb4z0dxaTjWP)XNeshA{sNR8yhU(;geoa3HwpC>hExF3U57(7W&utP}-ye zk%|*-OcK@DQ1Y<0pp3_FD&bfRfwZKdQGc}AFpCU2$WU1f;t|;5HEC$`D@rudyipW- zk3>pD)>)Ys9pvWkRyo+Y=pGyl;*WIQO*`5Qj%kt#p8LwV#41f%NL1zT##Idv@KH_A z0ksshn4ieMQtu5pewV^sE|=OR_8E_E?gf^)%5W!uZta((G2i9xb zl#$p7d!5p`q-QR$2kd-uaM_vGl&9k6;cfK;x^biodxhh71REEGea9q>8BhxgpgVk4 zeKq3CU4A=sDmgokxx$?s33AAc^(49@hUv8=@Y=bLR+8`USgqw?rx=Z=bbcQRSWCl$ zQLEH_2L6r%#?$8S_pz7oFGW*2PEo_^5hCNg&BSEylHNgt2+B#=iM&o{SLBX!eF`-E z0J=`!v-@6r!6Yq|b|N1-HWXqc3T$IZlO>(NBc#}eWmGyEVl|_glHe1zNrb(6u9I|U z-Ogu$f_OSBF<1<2OVG{`xMtyQ;c%38F#W^hNF3n?msrEa!ILXHTWV8kw%Os!*Rw$T z`uaMv=&%0#@~njjvM`kL_%R#fvgra=QAL-Kt1NqK7!~ZWtuH_ zTTFOqY1c>j4ckLebm8<+IF+cGN^KF=%-B|*p{%R`1#xy&nIv{(5D1v3Y**cwW8t>b zuT?i>#vF|?BIvL1<9n{-Q)8*qz^;X-?j3z$G;3*;>yquc;vS*I=R`1i{DjWn4M()E zZWOs~QDzC`(;_-GK*s(jncfxB@WX_n2acJ|E_Jc@sKV?bh&+xbNUOetM3x zj7Kj}4K-4)Q?_pJqN3N>A=6qQNRcZ>6VenLWNaRdPFZ|X%pWx( zy42+1NCFp3WbNt*X3Om}^Yg()YR@lSLdW2!C)RboiG}H((HNE8m0%4IrcLL^nATd# z^WDw1VK6aE)IWZfrwM3p)2sT@^FPNB&%G0gcD+RzhyhoFJJF^r8>B7Nr~~#xJtM!= z@3$;b^QVqUL>UrkfdFYZo<6>2HDG#2Y3WHp0Z#fwqfSY?i==(0vu;wTjANcgJd?QG zm9s`&xr?e3JD!H7VWa!peq%UL7|-<9=*<2isRPSyfw~m+%GSL7&GxEsq_LyetGG=u z8s*RsVgLbOnigE!rmr4bpJcP1b!31Eq(r+1(z8M4sO->I0rH^KkR$h27LrFock?vJ z#IDFj^t)d<{#yq^tIDa(#)v>bl^{d~Nb(JU!yU-C z*^|MIKc%nqZ~J8+t(n+AQ^X6tfZ9&V3)S8`|5jewA*e;9MToNlLA zAd3$82`E^ZjYr+`3&;~@R9#$Ui5~PWxUVrNITj5IYl}wab?4Sp&{inp;t|)eGQN5cD)FC78ykdTeqJL^g{5 z`uc4}HX6l_NoxbQJ{K_X!j zjWx1@Y0^?f5C){AXR(zzbod=|O)aK(`OJ4MX^yy*XL zo9_ZJyzz{@jDB6A@L$B?r4Cs9^!XjG8jo*XXDH zvgLokIhmfVG@LjeT~qtYTtt_G`Mp+fR7!EZ3N2Qzo4Y&XP8f!q(1`P=iwgK66l@Zc z9huPQMDJHZ3CUyv_wQJ`az97 zJGlI(J}dgNz|Cor5y`BBfv;?e!^i|+xIm+u?b6&w z$apwI?@$cWn}Z>c(xog>>zwa;OSFfM?NGmSEzR!t!dd!W8SDHgy{wavTZ5nlO~{58 zWajHF=}R*~?LSz0P0{xJn%o4Qkhv128YN5a>jL&hlkcQrL?xKEIqigiQyTa~IDsxt zA$QdrKJRgkdD?5u!_x_{ssN86snV`TnYOR?phC#8>9kVo)IqhM;FO&CzePB|BI7eT zqAf?so(ozLiO$Nq_`+|8=Gf!8KEF;o2XN*&Wbur#ViI0DWfU0q43%7L)Bew}E5(L} zCr3T=^(kOjZWxE{3OZ4_2kn2qflotSHlrP9XEpOTrnv#TA17M&L~<%-{nIFtci7_o z!%RTN^_Cx6A2<`-`vdtqdH1xX&KYIVD?JBeJxCaC51g6ykr&(UIi4SrrmLHeuSj*S z+YHj~VV0gNkR<%`B~j6cj8|N)nd!al6p~j~Q#0kybGe|I&4x6b4_ajX z+1FcE?DlHVO(nlh+w)hM-bxq1dT@H)4?sa8=%z@MZJRl0Fbtr;3~y?76|3}59KMU^}9SdC&EwRS4WMkAcYd!B-{SIWL>hV2Q<_`hfL`0KZ-|7beL@VXjk-NtFG#6EV5LLCvmk^w#$JaL*zjwocn$rQ z^Pn~Grwdc=zB(E0=1lXdy1;lN@2d-2*K*^8;(1M@(M0>A{HtOJ`owyhX>K|h=JL1X z1+`POhTB$G4cm$!F!WWN@f^0Dz5AVIQ@j>)y!_esdmZI(i^Ppd| z@Hh&ZctDNW#NV}JgHO_Hh;4zANby*g!r^DwlDa>;7N`xe%AvPy=h#zcWX5E+sds|~ zKK+08=2-*zZ$m-LBD9berk>)H*+R@98p~`bxz+{ut|o$x)O_-O6T;hv?b6WD1MKGn zY~bFWR<=jk`!>pF4hIKEvwn8vc3wWTCg}E<<)l0=O&+0fm`tmWMh@Ijte+j>-v)1F|R;~`irlT%$M;~>#-?2A& zzLkO&xmXnk*X5J`_TR)1G&7_^gaVZwO)%8q4^;7)!L$kgb#(qastph+a2ZA-n@hI) z+!N5ZVeEdoxcriINo-@3nzOgP7cx;hIZ_-<2|%lAzSLj0(H$DqToDn&1fYPt5@-Vgr!@q4Oj< zcU8FHt9J$V5#Cktk@Ip6p4;JY3|-Lt4A)tLNmHL9F(8)0C8k!rGC3U6+UEqx0-jnN zt%1h^!};f606H<(+O~jxo;DJUGX8fP5nKRZ3{gCe4aU-|fXIE8f<%A)K~~UVam*;B zZ^dmSWu{aAH`A;q>Y!M+bTGo3Idn9S@(CBNl(Bf%`|TKA;{7OnmAN;vim#?`mo(GD zp5~u;KZ@|wte1kv2SQs&tRc_$x2@NwTUg&`SY<60dOJ|lGO^@-v8nU7U2()uVf@$x zLh`V8qDU97u)&rQzNdp8nPijqcj(j>J_gJ?C+^#o%Avn2%|ijlP6Kq z?Z2g5Qr7X6ys6Zxbbc2!dlEpm$`SFqlPoN7)}lx(Yp!WJlueT^goqB#^oYO~z%Hq% zU@P-+iGf&crIP7wI2&LRk}h#H?xf$|bHf;(gs0bGlmpOhBkD%w_iO0*-K~XS5(o*f-WKV;U1}13DV1jlxKJyAaL(pbiz}#$%T-OYoT78lMZ;{p)NC#|Pu+ z|0wzv6XQP+#k%TlZq3&1PEStx9e7U|3lc?+G1z)#WTgEn89XbsyGTnANml0je*IRM zk|G&+7B;8QzdbQIF?!T>?cwe72+Aa6d4VzrYipZSQ$I9M8n!-ka!f46!v{NgBZXQajufZ1)aZNwuY`5h>T?nn$WD3Z&9JTXU>CAtiWzp4}Lg{+%*hP z^CKpJJz#Ctye~=9JSOgQ;O1273TGg+S{aJ8HuU?yr4xM=ga58eH7mku3dQ!8?5e2h z4(I>X^CU=+%cP3oc?97azk#urqj?k3n(xEFt-=;s6|pJ@&E#nOj*}7#+;+j@S70Tg zcC0@=BrCavrKL1w0$uJ+z0Vw% zZQRT7rI7us-2}@swjo~r-;JE4b<;-(Jo1gxZ=?%pXEKv_XjN)99MN)(k!b-mFv8HR z&xJkwhkF@?dqIfbW+81}V|5d30^Lz#R4fqKQik81UrkWw(1!~6y^wdu0E6WlQl9F+ zu~s8Pnpl4DoZv_+|3t5;DN(X?sILK0gkRs@9zyXSD5G{wJAV>fv_{?(Vvd`!=ldIf zFjxaF=86=K7(StoqxM9?D5aS?4pNB|iM`L*Zv%v`17_>hDd{oTxkp_!F1zj_QY6(5 zPOoz~ei+svNDuQl)ahKrGL>AO#vI&;t#39`$Z^lExR{BK4jvibAAqN(VwBibCQ_|C zF8h<)a=QFdN3nmNo}MHNqv=L!#2fI5t4D7#QuT}={GWcPpZ{*(j~Vtj>m0d%Ohon= z;4QmvGmZrhd*{XJ@xgM!e46$&)^#`}9V;-5^i|cU!@?5oa5&2{IQmbENJ*FN?3n^f z>;Lwk2I29d0w`pK1lTJ;8@2H&y&>ol{Fb0f9=auZ&$>M^>Qz=8B)7DK1BlN%{YRon z5ae~(1*sTae-*?QYqvF4V%_90XrziEOEV@M?Air+Iz5}EPVfRXHfBTP|w5D>#ACT{OheY|&f-hg*!o-UozAu+o@lEZQNVlzv z-pUBUAGi1Q9NWA8T=Ok2^Kd0X9>Sw-nkEGeaN#G(`G%HKr*@B$V-JvQd|nENR|>dZ_qQt4pDc}@YmTICQc}~-(6m_~+)ZbE zKWpK=*=LjBoE_4KcXSa!L7_ov>$@=7dK<(TRoSgQr5nfbvg9S8(%1GjG7m}u^g8@+ z*KYoZb*#KJVNxpQ+jh3?BuQAm4)23SjMRUFi55_lC)f^I#Gk7GbaQ>51^LEoubaVl zW4}ui2)rJX{|CA`5u9d(y>=!%?!9UBE@eoDckndUnyQ zL?uf0ScxE>@Gr$I2M%3RZv7X*V46g(h=rr0vL)$^WWn0v)7)SqVX?F&TB4$}oQ^^Q z|LD^7?%%GrQ?+}8G;&6p+t*KwTgWQ!Oak9qDGTrYzy!kcq=Hjvmi65HP9h1QgN)XK zKbHl!7wR4-MM6@MaV~mXF1wL37b}dos#zrQt^SJ9uUTeOrUL|>(ErMZ>uE#3J27x4 z<(eG}HC!pK5*tkAb>kDqyN#CHrdykT8-{}aGPv%3XKT=5%oiGen$lVv`x-iv3s|iLadLYw2GR-hv^XBX z=L2o^RR9!yO}3>_=ynSKX0@bAl+aJ^_kd$%Sw4yXb&Y*!7F9naxJ!j$;(CUVn1R)( zlWg6^Dj2@jxe$D&RJiug%i{ozCWyF@V!lvt-#vvwlvF8>*u+lz1J6PBMi>X)c+~FC z?I5A=^1o7MCB0N}&(yGDyZ~Pt)hntoKk{q10G}|pbKc(Gj!%<>l0ULSDE0|WG*z(I zkXVvzk+zg!I17@C^Y!FnIo~l9_?1w}M}Cvt{kiB#(dN5D^1xD9GZQ2gdI!-|fSqSU z`*QpcYAOM1EB4%|biGgj%+XKe63win+hC7WtK#?;s&(T~6o^Hk?NAU}xjxF+LA`MJ zms;nIG6w9_|JLF`3NRR{pALNYf!fi0pl~z`#`S5xJa%z!}Pv#6}c=&BRFnf9vY_@l~P_xS) ztSycnKT;)(Np4yKkO(o&6+o+k{I-VVPN9113OgsK=Lz!szoP#@g*)=)d}{<(b6Hwg zI=Mm4oFs#pB^y=O?2koci8Y^Ze3`72CD2~*MGDwTK`|1)lj^DqlJd^$W*QrtN+?h+SRl4^0iR_$$el{yR7Bwncb zxir^YfjFA$F&|}sq_0TKZ4WlIjC`iln43%55~f8`vhRC6NRqNLO;;l)xsSl6N2kVq5huSN*FKSb)n`F2@9M$hbQ}AyDo+6Ps_q ze|zfgI4spVPP526wrV(1ygC2=N{J)FD*GrMfR+0yI!ZXqzr1)nP#0wf@K1@Wss0|6 zrRu}1;?V)2o(BfRG}N`HIj{ytVl3$COPwKOIL$GVAgCqMDXeF!9m6M>>U9TTd}sOs z9{jp+LU$U1)Xvce3c|rJ&RW437Vw~&0pZ}2B6J6k7ErA`u)lYoVeL+H(a#*mH8jqA zCw0Qi;GEFyB+^n+`j&d4|cK(;-hQIs?_Y5Uc)C8N53cbl# zLpSMnn>lxL(n`cDCYINS6ByekhjmKXONrXqpk$rCAC`QVcpSOg0wLgb>of$*8EPb99YZz2jmK2>nu#?G8 zSENwI>qjF$Z;t!9iy^1jRs_~4X>R`yvwC0Z<8)(sIcJ=nE#%$^!Cj30V9fIk zKatLfsiHgiE)i3j42`KNb%qDiATUbRy3sG`qjm5FM&d@l+s;n-pvi-6JZJL2Zs%p$ zhsWaPjiwL&h&a%aVXad(@hDF2$aP?TMyI zRckxDDxRiws`%3`pIeRfa1UuF9UthS*b?F}VvON#SV7BfNzI-Dm}RYF!9n}D*>g>^ ze-mcM5;yP_cS&j-#yD3(-oK80t|)j%~ur|nDgE7TGvS+c?d5+O%B(FeH<9w+fE-%pQ@ zn_wI5fS+H>Ve#(rBk-N8M1g;2EoCEZ#YJtkzgy3{OI0A_PtfJl3m`&KDW5cG_;Ks& z=izMQC{UpnM4Cs2fl^xDQ?lO@@(KOf)?|{IM%1o@-dc{b;&anQUd;{Pn~fYBX5lg= zsyrsFe!o_ZNdM zRSFq7Gyc879)>^J?pX&PvLL+bVVg>>9NWxh+?u~WrgkY@=Gl9dO4KKFwikfR`HEc& zdncByZ6)5Fmp;uuCRK@R!zk_Rq@{|r^nS6?>#f!Iee?X`0>m$)bx`SqIPqc0Nyo!4 z=;~4!w5Q)6W6u8Vb(^wweO;X)=&d>EuwMqJ9D|wQ2bHIJliuH=ca3LDth+TqQI7FZ zZtKJ4#Ca9Ui76lWUA3?4!@v2W=sL@X705O zF53Xl5|=M7u}XnB(rVE>!+KuNOLh0{iZ8%_zA-%9G(~_9QjUgFKZk?0nmm$%n6q{J z5Nb%s{`i8|aB$~G2TNB@laXTkWA6)sBWTtBLz<0UAP@5Goglj0A2**Wjpk~-cPU}5 zi3P2b!I(^G3o0?*)%nLyqUi1$`b&P%&nn#(h6*_(cjlobJ*LG!B!#On8j&PI>|EXD ze8+20{()zM4dZUpOyVi7)vx$;;oL@VZ(QuseFd{Mm6cq-eo1}@)mMuBIQrQ|P{JM* z4|#hKuYACUfj#ge(*8Zn)p+hsaX1R;{@b14bI=C9s!ftcUBkYKx@fSO+XK&H$BZpaJ{PXVup&};=H;L)q zuCIS`Z4v9N0sPI?D*;+xeoA&M6?;BZW8@sLbaujEX^ZUEqAZX_rJ5S2YvZ$`r zf3g%2UkqRdmvJA^z&uy4I~}s-Ogub-hBfQ%UNj_O)m=_e40mn@y*9`OWBQXwj9`gfoMT+9bjGEh zsRNF&DoG2F!$`d*GE-BP2J*a7ABrS}Ff-z2>VKg5dgX2h%J&VtHhsOUIl@|`r={h? zMmUBaJU%=a{ByQ2Ei`kWpKKf1oEFz-eaOW=E>YbB&vaMhhk4A_c53P;pvV` zXjLnmy(>mwyYT_sA;F_KnU3xJiHB>dAXx1erIF&#KL9Oy!j5S&WJ7*q5P&tpieEsv z!GxzWHum>7CHH*#mcls)zY!zj?upU2E3YW?9&7glo5iz;vmmXXs*Tb3FvK=45{!dB zz?#3jq9ycUO~P>{0=!(Muj|9-9&pN^HZ~VAAeWzxO_XxfLp|+{!eY9KR?FcbUKTZU zq>}N_oV#U?`Z)9ZEc1wj;4Kd@M9D(G62Jeu=Hr(ENNr5IbUbc}mgvAUAtuhbF(aT?Uk_N;n5^1t^! zu7!Ik*KWF25gJg`U4I!5V$j^FQ{b##-HA z3$lv6+U$U(nr&x`H`GB39bn(sdOd7PIB~uO6>qbkU;i#VHA>M|FIyr<7?x6vs zubndRaGL2FVt)OLR+fHs6FK1$8o&LAAFX5&N#O%U1-TKOmzsd~QNAv$KSj;7!~HGA z!`Yp@u%koga~t?2ndPyj<)TelDY;;xPt=k%5sxC{4$F@5hCyJP5H2S81BW8c{GCe~ zNZ^Bob-vr@r;wfc*dK~QRTeK!g)vfbxAb>&YG{|Wi^CUzd7kT;L7{G}Q!ZD>=cJHzak=ZjqB0I`h{3)U?2 zV6(DlmO587F~J6GTFxIb181R zRr`5hR`@aXv@8wi0e>$W9Y#7-P3i>Ph7XEoZj*Uw4wQfJ6!P(Q<7EHUvU00SWh#@q z-_TOj1nNB1S zCff^*k`^(YI3F*Urc*-n0Ci0sNR{Bj;zhhgyw|Ud#cv+*>DUS;o^HY%T6`{AJMTsh zPO*k0+5Sq}{NQSqkWC%gSO_xUSJ3evNrHb>2aq$QM{?*fql__6A{c!BrNE5Nr{)tK z&B4K_*VA>pzUhm5IrNmkJG|H%4G~hSRlb=jjQ}ovQ?piUWDQGkmW+#>k%XP=CsL|l z%%*qW(q$A&;tImx9NRK$PNBS!IH zvJ90cYxD@4zvQalGE#d(H23?L{CKk@Js>s90o}*PvmzM@f`R^Dc73_pi`Wa*juvJW z6u;^MpFevA#LXW0+%680A0GmB)V0VEpzC4cnWiDv-$Y3{$zYG0O8|02ZMHu*AY}h$ z4tOSh#4Tufy(exZQ&!K>BuUQXwjF{ni6Zzd$xMDtUxw;mR}`b^pVabR*uL^kUH%8A zKvM=AJZ+xaCJK)gT9*;}4bRxP>q9vDo8iU-@w6e7mf&lLvo>$kd7&w`cjvWBdH<1i zula!Y#P)IEBV7|^q+g?b8RVU$sMJmM^1s)C&D%V?*pU*chxf9sS9*`9wyg`Y@==<2 zCOzy_6yKMYt^@_|QtXYUKLecn>&W>~TN$sOSQh5Vxa=)5-J7`0=vLe`NhC7KxU>q_u93hV(&0 z*#cFld==X_yXK~Di;Oh(k^APkGBFU5oDe%dyUJka`?mHQyQHTvkqc8d+vmMr`Uh@b zsH@i>N~`mQWJGbc)Mrv2;y%yM)vp(;+jQbr)Kz4oYO{Jc$@a1CGIZ8+M*>i)i7U)X zfF-Wo*~OxGSmGB4fG8@r_aw1;!tgr#3@DXk-^h^D1tKk`;dcFhaGEq(*B;^>vOX8uydc z*M`Y=%e1?verzmeBKFjBCy2YK_A%nxOHXHI>{!7wy)bljP5SdSQRG&}_#R5$7w=JJ zf|2|_CkVXvGF$XIYVMbV#xBubb*i0yes)Zq!_hXSCTF9)>&cEVMAHFkLG%4>AZAa) zv~p#;s((T}u`HgI*K8+yB$uzc-FmLXpJIN zp2h7$V70H&BIqtc`81X7D+X*N^B2NN`hy6ZA!~w@#i` z!$Cfh(ChOX?xm)%aRRSZgmLr(tn$qC7ds>52Ra8)g7Y~a2M#dro$g&sc&TSCh=H|| zv!=HKDzh*;(Z8IiU7;!{F8WO1>IF5ALVx5(YZxU@ZNDd7{ zTt~tfpHd>NY@SA5Rv3eOZC4UatTi}OyVH%%8WxNBbaJ29AJw?^KX0pehsxk1iM6F2 z8Q2QB*5nIN(NrToCmVN?Wg2!SEmY%sN{bm(+~5O~ZK8(q37j50^1v&$N(q*(L$_I1 zb9JPHA568%{}L~-WN3JQmk6~A{!qq-?YEoXlD!QC)F>$+T;!LOmd}y{LaJYQpe&a1 zyuG>cW?{qfi8_L!A`1==sdQo-v$hR6h#VS#Wl!tyQ?7 zyPXe-!X7z4dYnD+FZMS`i9s(B+kR4hRItg8SB_<)v%}Z)X5rhbGDm5@uUck@gYKN7 zZ1yUTuUO&_wBHWfZ@!;**+U_N2EQe*-j4P@2LYX=*)QW}`*prI8aif&@q@b{gupRg zEP9w%v32&D(CLw}lcT^0Cm7{HgKoLAD0}@xafA>N6XUYC`}J;b$)0dRigQ4&$er0E zuWL^L*HRiD&cJW}0NunzmO|W07sMa_84BE=F}fDVQ{22Eq&m>O+?RyMr%6M^zUZYC zgE^+VY|;0d$)NHL&IMlJrr*K?3LuAN=#K6;{xC$`2l?jg%urDZKdUV*0AI5hWJzD& z37?Z!@y$gvyG(_k=jY9F9&i-<^AN%6?>$I8A@#Yv=bIxDg`I1LIZ@b5f?N;O3aI|R z`>n;{HQ1A40L7snxWHc5%%2=>OPzENI2~$O=55*3B$T~z2iA0 zgp}7Go41$*EZ}?{Me{!E;PJ7aG~7CD@9#v%eWhHAcStEP$o%j?wBR6=+Q3&yiT-4e zIXf*fNI6i0XEFD6bDymNtDZ8nQvk=jMSH%^+Zsh5(jJGz`LfW$$B#ZKx`R9(ScGV8 z|nL)`6CRNm{oPThK#2F+~7VsQGf`S7cO(e6t#Oxek_>R5dUs`7C8+BqYz4aT4b<@^sH_n>)&q_C8Bfs{QvEkQ)6!|9!I@5pdlb z78_yh8l^!nka-jg!O_k7jkE7v+n>A@p>^1KcUs+A{G!%>mm^Fb6oe4vyI$aLAthlH zUHjJ%iDdxG9LE3OuYY^+)OZcn;SjE!~H2USefl85x(iqC-o?`i;#D`Q~WlZ&T z-||L`L0&$R!gxRKpMYA6Tgto3M35_JGcVUGyJ8(Du5;~jt?a@lu&8diM1LR`-zNbV z$#xGzeV|41v-?h|Db~_V@Ej&0hcP3#;Z>fk3_I1f`N7n2GJTNvLb*AD=(+W_nH(-M z)>oh&i-65EY9{og@v?p-Si}op=c%~j1@)ZUp9HQJ)^PNA+>l%2vwq{Wh#RlP=kmMy z%2KYkkdRw@A^LKe9`zZM5dA*wfsAmuIWuw=(LRxoi9i5ivgrIOWxbuNwW$E-r=LqR z7*-kj5xCMyVOvbYIK<9(JE65IPas5lq}P%|Z0a%6-QADLGK6y6+IS_Ymq53+JHyT9 zLgWpFV(o)k*j7`+N>8?vaWn*AIShpa_U^iCpZ$Z0f!UfqM&eR4w|Sg|VOc)pzivG+w|?PqvV z*G%MWeq0znyZCFVG|t9$d8B%$1|lobEDvwU&e>Vib{%IHCQlR%zp1iPK2^$iwK{g? zc@bQ4JEPv&-cK(4NZ&xVs61N!nvLWXqDP+^Jk~=rXq&m~J`N;Wq5W&1duNnoOy&Ug zub45BlWQk}1Dlv!@qD6+@iGDd@aMC47E6DUIsH&O1)pMB1nEy~R4WfNH+t|3&UskQ zbK;KIGJ__JFasf|XLc7Q8>oE@wulwq6g^TFZ6f0W%8<&E>*l)}}A32A3I zdan!Htur`eV!2$18n=<@VYgZ#&&@ok9|7OH(Ge!;Oa_sK-!i`+NVPMi34_a>X8#do z(u@?|*MYvEd2)wr^jX;vwRtPANrC3QN+F4Chs-^o5h(NO^mE^?d%5Xi2NoXhbaVUe zh1pAY$RSzfFgd*hgIc~+Fh3v!8RRNLdG#%b)VEE`$Or}C<%2iY?kvrW@?K=oQZ<7x zxPy|r&(bI4mGpx{)GUv{Gi;ekSZ->X3x}F-c^ByrPE213#eBPBt)k2`KL4(ZBE@VO z?6=KXd`hQtEK0c1~0$t_fiznPKCB^7B8- z_kB?LlE&m~n^pbtd1cQ|0{kqcKmrEdU2gClm+4J^dVapYEZ~;!%!O%TZoP}xB{d1& zMY0JsM;oQ9eEbyg&f@?y9D7aiWJ_FeGyR7lX&u~`fUcCYa3)gq%Fzwq;)EBADeLIV z?sM6P9OIPWxFlyflSAKo{}*gq4?V=jKHi5Xa!=lo4RNw=cafoLe@*X+xGbLSS-ZR?rDAPm=H4>cPUm=}8*MWs_yf-P zl0H7z;v;0|(e^%3wvO;hx=%d$oWnuStw5u>Q;Y?lVANPxGl*|6;Eb57kVLU>kK>$y zK;@s$h&?AI1Y{2o2Cppc7IBy)JuT%|Fxpyny&;FbEG2x;@d^33nJEsCKfI=<#(i9+ zJq~TCHgmMlcdDM2C30cN7LOEcl^RAu4_<5{Rf_8c7i&L;-tE=|D72vm6+5(o9lZ zS)xiy8pJ$P4Fi~S;x$@H$k}xP2@TerdbI?bOZJTrq0!OD%(Q!Z^IR!L(bjn-99no7 z___60ewe!FR%CL|XiO-a1@O{-zKhzov1AMDKoy#3r~*Z6%he9Yg4m-9Xesm-hx8|k z+RJ+*?t{2@`nXI!wDHwSLfNq;D6EP?CuoiKk}I?eV;YAOVLx;PS0W?=*i)k~M!4#0 zakI*zqNw7X^(~GS2v~GW4$}L_#5cX$?eDrDtM+>#;>`OIs4)k3lq8I>suobnJlkb|+F>y^f@WF!H4?N!W`-hU=zL>?)-S9)f4dg+phlr{WL+bRh>0`GM)F!|n zGO~2aG;m>0_n;>a^G|0{C92!Tkrbgq7aB*G01*gBC3g-uo*epZK&hS&!FOW8@>WS& zgDD^3KBNTP-jO}OmFw09njNZ%8TDt+1%3VqE0dIonq(IBtotvJyUF%to7o#xIZv)t zt-ASar9Y&BeCet&w*JNc%rm6!!4ZCEARIh9>3px+%8DB5N7D@6TG}6l=(~K@S@GHC zn>kjr@yy7&jVtkZQ#&`0Kcv39qeNvWYbkfBUE;=XAfV-ucW^pgJcl^?TK2fh@?X+(0{v$eLF!B^(9EQ%^MP?; zslP0zt+mZ1-U0)oD|ATo94$#`7+3P%NV~&yF~VxcLGTc5EyIgF-sL=V*WRNUOh!er zQ*hlmxs`Npnzx;aY`Ujp_vN@jTE)!^iOKvt$;9x=rI~HsM*hcc<9)h+B0z1;U6eL5ab*Zf@_Nq9pmp*^3VG78n&*iEkDEtz?!aS1L7!R*=2p zWp)?@8@2~a?foJXkM84ewrN|Udz$56-~4p1tsgoWV>%E3@7J8 zr2|^L53aiY5uZC!NkiFxJc9lhl{Oz2n`kk@K9XKaJt4ab^nl=Il#33n4x)rsmZvOD zBD2?@q0;-s#>m@L7_q!gcn*;+dPjmfZw@}op$->0b;Yx3hv3bj)B{umlSufVxOJNZ z@nNZB2dm2y7urYm4COsTzlkmi5-9C{96B&9rW3op>@4VL&*esP*d|2A9w+}iw&{pD znDVqB^jgkKd;NWfk&3@F?$)3Y3jzyhFFJ`mA$Gmn`D*xp#5#^H_55Dt3icmIDF_jx zl6#$h9}2UI(^l~cJO<$kIau|b_aAMd;YI{-m%y|UVmw&j2Ei@-BBj|>rQQhG<0y)q zmL62CE#*9TEhBlwv3ga#C8Ip_VXk_Nmf7DqxLp1&g&}^WS z$Evl{-NqW{4wYuhghNXk%fUZ+^ZC@JHw0l@>z)y?Cuq@w2*@`8!Rcvq){cYj8l*|1 z6i!VLv_tCM>QBViC}yN9l5FY1jycq}Lb}>)k?2D)CAPHtw*OS9CNptb?wAd9u;U_a zJzwkK%IjwD4Zd%Dy#db-iF-U!fxhp1w{2Z-ZLQ+t^x$MQdYy0*yFTwjzS^5FlWuf< zTMAd`<>eqh+x~ zLb82Jnjau(7P$%DoHGM})vzc;{fw3&*FoN*m+PI7hrH2myQC9t^=`*O5GK=r{yjsF zbnW^iH<%MNkNKFx|Lkb(uP17KiBqL&@x~wO+0;74f4#T&S2@o`s%t37OYrZf*VoI> zT$?thq=|H;!69u^W`d1emQ6IrGRD$eo2}b3O$D1w2F<5+V9{4074s%p+GeEuD-GQ*wZWzRKqv#)a z@8vj~Kxw3Ecn=l5qjwFoZ4;fPgF?+dcF)+>n&ut?68?U7y|{{5qmH)9Lyfha)6G3P zT48x&^@s=W4~s;2?)((=_&)m1J)<&0%;Seh9dF@#6-C{1dolAY2*f{JqP% zc2l~T#Z-H$bXM&ZmET+pjVM{RuwX6vsP7-Y<{xyI34Z9z0t@a-Tf*c}M ze*A6mMIt!PfKi83)nib6yljt+<+qUq}4VLR*MAJxf}6wy}(by8BQc?PDhk+HsEMzs z&2$*4M(rbmqP9}ct)-K!3bVtB@jvb;C?sHP3^HV5n$bT3p;QplppwB%R0{t_jO3Vu z{en8MmsF(@{w_KaND~W=-zbXCA{mjNMEu_KjfVh2E~sUf@osaxJ@qmxYxBw5&UdTj z>6ghy=Wm_=j)lw>@3X^+gME;tF8R;pNW6L89#o@1u3eGx1kMpi7xC!!4gUqaXF1%$ zD6_%M+SmhPuH9x^-IQi|hGe@C*o-0f;Tavo?2$#hZ?3M6T)n;F7FlSRIXfLVFLjt> zWLjyI@qm5{3zKnE11+5LqrczX7IKG+^bp#bkRFoTi}q{Y_kngJTD&-j7v3J;W$S%n zO9Hj2@Bgy^7=)e!go+_3(xit^eo)W;IPvEy5(gi0vZQozc0E?FO5<6w8-CtyPGeo( zTv5f(+M7YMKrKzk|T5Apfl#`pQZ?}EYc!fUqgeqOjo_mSyHLkTZJ^X;J z$35J~R~c(k7y_A?-a=t!(ctgf+AX|E!7WoRT+oI`#>R83#MXW8HcpMqIQ~<-RQ6F* zoJ5OH1nkE+Maf_8`S-29cWd(&Evu4RM@thOC*i1C*u(W@&HPtO$O%Lhb2C0K4nA zm)qvRaTM^b=YbrIWH&V|mOL@{HU1DjHq;!hg#`i7G@R@1N*k&B^HMMu#Q7-4%1M@3 zb6f`ggHtB7U+|Dhy#IDq^q$Q=(u<4~oAa5;NUKt^FRJ)ssy4vt!0p^LKB$C`RJ=JN zrw;oi3sWR|M^dRPt6C$8Agc-kwA1Poc7b2c8u!k9+h%{1wx?FM5%iw_7P|R@VEp^c zUk6{xLYCJu{4c^nP=UnQexU8E$e+Ta1C7A z=Y+ijuM#~ui&=K7x{EoRK0sooac~9Kw;tl>pP0@#UXvp)1SS8h*yO&qL$O2>2RCyO z^uOLdPOPyx7zyjjb|^+YIixT>D}0@x{m>8h@=8fmNd zfKACuzSqmbPWUyA(EQZly=G0&lzLZ`(a2ea9e90RZLqpESPmhdSXLWe<(1$yUcAmh zHzQXOg&#;YL2umq?9KkVdlj8Cx^p{!5rhN=>qk&55`FPpKSu{m)ek zl@lP$iTloA5r#Pb`C_ZCkrvF^&oo9>14rHl@x2f+Kjs8#_oHRMGINPe@bdBovcLbP z#QG|fgAryV4bAd?1oe_hySLq78kpPv04|ttQ*(5tuxItA@f0uIT77Q{Q!+WngOcRG ztwW&xr*s#xhTt9^?ZevB2(o==NeZ1~pBuFibg?K6L5(*x zylFPUAo^TyuN0C-c+$ABzn+czmj2L_jX!nN>O?wv0xrD9Ui|+63PJV0gnKS)7D=i}3K9Ci6)`Qze zjoIw(=5^D#{uw0Mbp*kv)d2pH)ms$h9Q{z!FJoKkkMfD@{=aK}fvWM_+X zT!&4VUL4;}`B4%%lgLE?p*w`#%KfDc+1|wIy4xGF5Bo_?ZC%pTj_p6)?a=s!i2-#d zx=rLe|Jrv64=E{^qfq1fKK*@aJLwaj_(W-7t%;G_Xh=XN2=3|W)iooxx@=-g8%-_D zpnQ(~U)#e;REaS`d6i|v;AZ@bC9{rSG`3Cp z_M-l*-^$L4Zug-ujURo}umFyJeqaFsF-C^K)4b(W>bzdSO!IdxSSX%p42@jL;=*0n z%ukxwW$B~sWa0i^{}jmTb0PndxAkJDHr7U%J615t<%=vhWhRSTPMJa1H@L99v=WZr z9jDw1#)Z4>M!zde#)F$({p10D2&OYWF~0_0k)NsylC1M-BZB^XrWzTgz)daKXO6ju zaSXFg%eJ6lD;mk>M9q^Ej*e**HE2MpF2DKaM<76YEaMa7^3FT&=*#`nCm-mYs>n~D zJXOP~6hM9A-grX>vFEY1y;aqdt-Te$kYALk=#TIZ!}%3Y87<5h@E8{ZuzkcK z1$k(Ai<(JvG|X#t*FlHUOZ6B4785B5QJN|ov{X9^Nn9KW!gX%vu=4Egrejfr%`z=d zG+nXJ2H)V>b3NUyO;`u_Qfh_#mbX4(6OwkkTv|lwnHNqZ@;rGXpsws=DKupJS-zlu z;#V~a`DPU%CHp4-_~kzs5Hvwf9thK)f@5GA&w&L0u`Vt=E-V~p3B$#OaEWgkKJ(gm zg1h#G*n(>}FsnX9Go*)xA zwDtAKsC-CLi56*qc9OI(A1-IrxXXhFUd+nc%UM~OpOt;A%Q|k1NGA+6H>XBL@Uf1W z_)+h>zvp}9Km3RP8_(x+G)eG1|MmCi*0t~Wj_*)`PZmU%_E`~UKd{}ke=;fIpuYTI z`O5uQRDkqy<|PEp&(&rQKTuN3eRg_QHS4Ll)0_-7lS2m3b`RS_OLzSmkon07ErW8k zJ4CIV2T{jj%Mse{8{S4>J5p4od8;dq#xP_B#NC6rJY7`_8A3@LCw}=8u*eiL*6@!U%am`);oMQFz5XyYR0v-+{L2HjAO3wMk4=I>_aPLeev% z4QJ7&B`g5cFlAzEUmnmIHIBNj?l7rUK6Et*!3O;*LpwtE}Bz_$+yF*kn zBNMSPd2x~d#v8AzAzZ58a)N(3^-`7=msF6$tw%g%iwi)e<%v7@u*aK5v#Gw!`Ba_V z!$$=k^@n)tiv+i)IgWK{1gABIpX^v3FS@8oyfLobSsPmjIv~RZZ4kovEM|=`pTV;H ze9lVm)(?4em1%igc+oI>wzA^xZvMFVS`CZC+Xj%lIEVCgX+wV;yj*bHyl$FeU@%`U zI4;bq=r4ti%wzP_u>wC_K*u?^z0GfV-Sp|OC>ZxS(!bsOS^iS;WC6(WP-yu%vR_1S z&TWFE5yw1jz|)vn8!zAm`pf_Omro_24GwOJrX4!0|6~ zn^N2-X<>u-&|?KMF*fR@+p6(*1&MZS#4$g3)~G2(o>K z8IrF8@gz9A|j(t3{qMM+Yd@*JW(iPrS{YqLa;D z4ijdjv5etel{bEK%OM@yR(SmO_@7xA{ci*B*?iKCIhcHz4I zxIAurq5g8gDYU#RpN@Sg+P@-1u{MeFKzgKz_R$>h2uFF5@zFdiGenqG{bY@2?I8 zPIS9E7pio|L_yy{^P+v-(CXk+u2M3!!5RgE0n?u3n9|(dEM3E$vatq(#S0zS#}V|82RdAiwonza?M%#V-b0>rUS*wSc^R4)FOAFokVv+~W4|;RDs& zdiT-0YIl>TnZ5Omx76n5wb5%h)u%Iq2J-5duly2Hp7^?rkV#!NU%I{y?b34!u%L|( zY8%ny1J~ai|0qnNUD1Xu^b6R6`1)}^CeJ%$o)=%wT4w&@{qZImD-!7%jI<}#&hdbE<5bXQD|GP@crI7Y~ zdB_NE!_v>oYzz^)36kjNDQ}$Ih6aZMLx}nn?L;RzPIO(E@P@I78Gk-5@4f$?el6nG zGHNyPlnGupVc44&zoO*QDqvZ~I%8@w8z&c=Q1iiY>u>p^=`Eah^V^G}OS@>kQ_uA~ zub-+)B?Cxf($&4Y<>|t~4Jgo`Zo2~0`(&4w0@iPpC)^i{0{W=sO;e|UJn6LgJmrFu zuZ(KP6^EO#(lm_W#Y|mW6CMuPJpF#g1q+v zC=j$mIMRnr$uJ8)6D9Iph6T<{UYP_yz+Lh35d~S7(E323x-o473Lo6s@NsSs0)u62 zWx{r*y_tDgnwpe@wK;5aI)SYmY;l9IK$0zTxV$b0iwm-gQ*w7+PRPmDv9t}`k)FOm z>BIW03tOV_bx;1rfA=G>H})H4ts=Kq{oe2Wo_z9?pDZifT)@Z)Tz67Pbnjkpvhd34 zvOIe4kt~1)@8E<-3XxuiR(wA`WUAQ%5L-uI|gWGg7!*humzH*8Bv(TAuq6v6aoss)%9;7V|HCv&?8?K3Iy{) zHmJC;>=fsFsxGX%mnVLsDMT6Q&J=ou``?#TQOIUsUQU*0$9uI29wGD@Y z?zRHsJ@m(SW-d4h(e4F7FDQ}G$xR#=X7MggAan~FR3Q0TXSxs{^_6oX*Wp63T+2x zA(4wu+;G=#0DXHJC2H$#?Lr{}U#|Jgb%cf6av&$xOyKZG&UBTCK)ICnxCl^Qvn9h8QiAz7WDl-0Qj z*_vCF#(ivOg8-@L?j7lR<*qbAn9=|N#83RKpOJs{Yrk5F8p^MK<=3ksNMfI*d4dC& zM_}7i8=m)Xy!Dm}S*Z0sIXNj46B9D^VoEx25^#4`{)%tCOqx3{b2BIdD;aeU$h>e?f>%2#AfL9)JHQ%HGaDnkK|gLJ&-8@DZ; zCJuhsPpZi)?mD8HfT3!?+wPDg592!*Ph;fajr?Fs>RFXqBE-G_5)`Mu;-B>Po z&IrtM#ZG&sbeu| z^Ul$$LuQ)bwL)XG%(YbB}cO4oUaDyVCXGo;3Ef%4dJ>@5rzGuV1p_ z%YOfz-}xQ2g~|0{r5yVvFKXu;9PF#c%@Ed>{1`bnFc=7uHa2Akr`^$R5(P;E0|P2V zqQ<-0$V6V{C1}r|`I1_xij)YKb!Qz&V+xX{r(X(f$nC=D_QC=LNt07@8+M~En~V1S z%T_;MpLhz8-#K1q8NH87%JDMBF@Lpr=OW6Csd`-ov8}Yt3&fu6VND-9pB4z`GA64D zK~ffBofhK4O*=M!*obIJ3WDI#EL5|$Gz?J2pjs|$EUCbU=@HJ0YPZyQqSGyHEXOHJ zBceY+G1;MESd!jtPX&eze zo#UwD!zw|6VtB2Xw3WcMR$zYht6vo!YwbGH=5wF@oEzl*SC|4d-B-9Sv86}2M&T{= z>YdS+M4K_|0U^P13n#R-!rL!x*KWz+E32}3+zid51=$*ZF1;P|($oH2+BQ~X7+XD) zcV3Z}4}VPB@7|M^kpXFJZIu7%AO6qsPk-@$(IP7Kv$?e?{}y(azVG|KuTn*1!R3;Z z?cdzoBCRkyO*099?$7;a@)BG7rf|*8&&j)w-iGFUyL7<>1GSQ<`OZ9Cr|Q}Q^j6_> zl0w^S-w*Ss5jIl4yJhHyTz&zuF<$6pQ#kUxI@AN~BP%6#W{ey1MH za4I4u;4B`C_W85Y#}wg%s!ajT<-9QWv;FLL|Q$of1}0gD6Ns zC8ZI<5~z1WkOYIv_m3sHD>CtNP8KIVkdu}M>1=M0Hc3g#NlH=>E;Rq=-z>?oF-aU9 z>e}kFKl9V_J>UOn*s7esmaj={fg0C~+rP%g$JM@0P~iD~zw*_uR7H@)zRHUNA)dCegk`v-p@lMq19&Cklau$4r6K|B$-q2ZREipP`jY+dSp^gLh9E1TQa z$hO|@fRXKM*G3>n8dQ6uv?aF)+fXwQByHmKHjqZw*+-Nnag7c1LiVaGq8_@Zz!jtb z=OMp-xPlE|!&R;wL6S=(u7Gklb|OyBf=&NA;qeOyW-We6q0@MT;m|isXvg|YaQsrj ztDwbTwEXC^mX!UIE!$p_{(^*khIxI_@_!!Ag)aq=7tBl&Szk9k<&SO)mgW2 zIign<$_#{nBn;C!Q7VvNcp|XvbJQSB2RPB~@IX?Bd$I+g(n~ydbo65TTeqZIJ0#iI zBuE`-dSf}p)6IH^uE|F~`Z1@p5E+2pz;-Ymh%%1tU=%D(Oa^!Qc`Yw5Ir(yXfA@EP zSC*ER)WCJ_ROO3d`}2b&kG!Y7&evam1GrC03j}Z5*xp9XByMqg`EptXFBCYnw&H}l zupxMNd8mAtl^GJ7AAg2-3pCVdM7+1RS5i$WIfTG)dwWaP)>idS`%!FNnx(M%`Som> z+r)#bJOx6&PY;NdFR|nj*w1_)E17&HWwiMdY~o#n0(B`!;;9&Pob0qiamwQY2#&&{ z6MPj3IvV_%4r!reiJMI*`G6bB7 za~aC0XAn{PSX<|;Q-n8irVArncq}U)51a+d$DfY^(Y8JxwBm9{%Qil+dvVZw>T*%w zAO8G5JO%38zU|xOTfXI6(&3z5bc)fwACB=c!??Av-O~VKJcXo*$>xKqNCB=fOaKsk zxC+K^U0B4;12H^N6?ENli5D*%({9077KNJF4mKKTDVPTu+~LPJ-TqJelN&qIxVA0r z5F~XaPh=Z{rKN)gxzX1l?fpX{&Fylsc_1h2yVw#37)?oN;NXrgc~)jH{{`jHz;|ay zmwfomH{}gnac*mCO9e_4Dp8ARA`~#0pQpCb9RR1_{LSAKo~l?aN4oH&vf<%j6`cI( zpZ=+8DADNl98S5L7@w3$T%#kSGBP@%f~0EUR+e%cb|5^q9ksA1Nb2duX?{)3YBOqQ zXGb<65Txz6{oOqkFj2@vzN03Scb)?EMgflX=>anr^6VdxK4M9$J)c**JgetbzEhZ_ zbL&+mLQLIjN07w1Cr=|~b#kQB=deQb=Xx0F-s>q)hZOkw*S{`b|NXC@!u)4H_p_(M^d$+QI(69m zaXOU`xhxb2+n8fLojcx}wni;gHEY?TMr(*P@y3P7usR{i;kJK31moE4`I%O z;rWx}1KD3&lFiwdva>KJO-R#=li3mt&FBU&B#oosH&e~Bx3MLS(86hkmP-3@uQc~| zs{jcqO6qu8Tu?Hx18jQ?L;0v-^n{L@Jg>k0x?UE>yVZe04BIA0qt;b(Ap!XzlLog_ z$&}o>bxU5k_ljy&t*orb+}yl8fBqacg+^4s)Zaf4@D1`R{{&>H8pqudwHLBZZO2)-!^c1Kx1=zQv15u^R z^ziG70^#tVna;|A{UzbM+7TqNQ3~zIoZwU?JKeOwBpqqk*hwr`8M(qkn6a=TXM~IBlely!nxwM~iE>#}Du6A%OD{zTEqEtX{j-Y)PCW(u`3(ELB@BEKdD=mxnM( z1w@9AgB#Nv<3usqluRU&x@AidhbGa<&Ym3atm3q`DOnzWPj+X2)E`SGv@8rP$6HU-!%!LK@pTOU0;*QpfMUISFSyi*mv$^jwIC8 zpVztY&I{`T^4FFisTcyV@ksm_XA>AZ8l637C3W+cgApRYt?aDeDnIyv=4^snJLRI4 z@s6c4h+K3r&Mpi0_sd6tT)c7lYI?P5^v*l)2<;<9-RD2|`DjqyXMN$yo5DwW3RIo~ zrk!WnSK5W*w$2Wm-qzRGr?!$77Z-(^Vav7vTkz8~rS#qw9a@uMhYeBvuh0e1>I zq2Px5%E*_v=+!Gt9meqh655VrBs7$uRdg`300GhqnSX)P)n?~qGtnVUH+$ve;eAQo zxg&`_9BU6-IeiPg(zGxjOOF>t-d&cH*?rk~=cy!iHl_RFLupSn;eX`pn`MMM&6|?9rChhsT zAsCNNO~T~>>|tCe1#e5qP7*{UbO=)uNcN1o8V|=C6hDOUMd}z^m5%1;Wn*GWW}i&R1~il!JNl#rhNBY? zUz5~>yAUF^OA=T2N~g51^hv`$w341T${sXSwkM}0ak3>TobJ^Gfdg@9fE^*BMiS;d z6h6-8H*d=5=%@_99@4`6f@N_v4) z-BQ>VNI?=S&H16$H6E;<(T3ob!fV6Vw5}AEEuhU;R##;bf~33m?#R*cA+j_DjT_DE zpFIUU1v~}nm;xC3b>3nXIER(RaRR&quC4@0#k_zQleU`en6==nX2HI!GbzBfDb8_W zi7%AA(nCyf5Pa&&Q^4BQ?&m3y?acN*K0Z=`U;}MJoZ-q*?ioe+=prfb3;*O7^wcLe z+u*>U{O}L|up8w4SDXUc-?h&}fIw}OP?(S=ODG)RGvm_h4o)RyTWzLG%k7CwT|6<3 zf*f;N57?FDADzZf&;xZL3}@Jyh8UdkMt71($uYL5wRQK);49Fm8M`SxLj%&-)glc| z38jOyv_YseARS|SGW_PQY|kfT@1RBYJ6mKc1-Qq1(k3m^8fqf349=1&OhVy7`PC(n zR<6uHJkd;gMaIU)SKP z9O<`b8bPPf?9SL7)wtpuxVE|?FQ+DOe*-qR0;X3UqsEo;T8&q>jCAv$>XZV;s%1dm z<^a2w0i*{}ixlv~T2`ynl^`h#^E!U;gG?PaUIcX$B;hS065}6hi303%<#OEGaC~%( z?Hbt9Xka<9@Zx8G?`oO?wCnMuFMa70jz9U||786g*L|uMKH$6*u(5(K#HKyMFcTz2 z;cI$~1AO78UtheLh-1S=EjUpw(8+c>28II`BN>kuehQJ~fPy4Go4Z#!zNyjItj5H{|Y>t8?UbpYuRzcGC_O{H-&EWL5S)AndT)KNYftT~`OAU%{?qJZ&CE#Y**xOhQQnHxZ-T&x&u5;pL<*t7?Kzp@mF z^2L=UM3pN}x|gdD@+-ayk?dv6txJ&$63-7V@v7thrC<6b+1lR9Dy+S&U4G&xej+QZ z+7F%=s!j1rT%NwnXX?jciProqSl20hz}x;w12ilfpkWDZqQpqQ^uiX-UD&}%@woTF zZrz$j8Pkypq97JRz691d2_DCWle&^ON2MLd!=H?9OD6>EiB4>PYlMIW0;vYT-qakV<-loRR$nc14ZEniu#G22ARI(n(||ZXs8DdWw6p|4(zqHvk@$VaXkL))X1j{&YVZCJWs>!uOHf>axA90?35pU45W_60B-Bt?}X z41kRkB*Au0Vt80u4ghEOP>y$YnL$rBErl1t1m|KSUxBCl-FR| zoe5n3sSITfu(Ir4X7F_fu9z_{<0p`?M9_w5cp^Q*3Y;>-tQ@JiUJ%nN**^( zLA!te6B6h>*s8~qwy0@z%zal)&4T?)lIX%oZ9UK`>VW;96trg$m4Hf73dg_)S8&=J z_w^oQeR7zD-K3V3G_x|c(K+eVGv_q?C(!=f z#z*ZdY9)1cbgHm$e;+6IZEUEa@pYX1$GQ%ib~R@9I*KnobK84XYyk|@ndp(?6&-afA9}v z6{iZB;|tCg{_z*=F@67mANT>)BuEF8;PGu+0@3Oyi;WR=gmN~jeDlRtB)u4e^#J?B z!ODuM zEwt0q)AH`S?_zt~OK2%=%KqMdT99NyBnsTfV;AM3NH9UNSq9BRmENvzAboWSa zPp>}Hb{GXo)WTYYt)xSo-p1|U+OBNm3ON_Ya`+8Rtur1BW+vQx{$6hsur`gwn=D#6 zHjOQ^oPifPZj`egbpwmTv<=mvzohj+4A14|(;6m_7bKOtallyln5xiDU#|>RZgQ3r zo-GV=-L0%R+FKq?;|u_q@F37MQsQ73e1ESE3Rv5@_c+XQ^;x#K<+Xf#AuyLKpT+xo z`6yt5B!f7=FfTv%KmMHDx_wJN`?=5ROWfDK_BB08$6 z1N(SkKBh3HPMwZdz&$u1AkY}$HY?h*QJZfN6bOVx4ZI_aN=hp1K^~sArgo8#oZ=aoqmPRDnyEkH<`C#vhH3J{z1`y6ajGJi&Q@HiWvn zyC9UlC1ZE)NPmAn?3O2l#{J)W?>!kGABV7IM%LHYy z`d9y|eCR_Tvd5C|Zrc(_^!Y5no)6BV(8a~`or40TL)rjJ+X=cjd}2#>UyLk)GYtja zFaS6Dk`NeCfD}A2F!Op8q~!P(0L#Q=p7j7SXfi(*48ikxt`()zTmpA751V=M@Qw((j6HY8Ifnto~ahnlP6EG-R(LwC2vUz zTi)7W+@IUTYR$1eIu?cP?&8O|Bh-_^u>lClZr;2hn_HW5Ff|3u&lR-;b@SHEK#&w> zbjLwthodkl!&ff+i}u?XY9Rltjj5eJ)NxRkQllb45JeG6kK>6CNz45G*9#X z8C4;FsKy=gyS!rA;=(Mh68CDCSBW~58>Tz%lpA&yJnOG^&x*V{55WrH>eRR5H6;TF z#{_d>ktxm?+wPed@2ds{bnxc{kmE8O;s#~QqiG@o1{cZvD`cq~2iwZ^_sUbirN6al z^zLF&NMGg4Qx;30&s#pbyD(k9i;o-b{l!xtmmtX??H}yR^2)M3rtd%d`JYYuy~k64 z6tI4o?%Cm-esm1GHV`QBukM^pQQ=_4x=|a6!X#=Ksa6u=++PG*N%9Jhc#>8Rr{RI5apoC^sNvxpDo53=a+KdXU;W zQxLdJPE5$s;*x6d7@yS&KV|9>Lsh3;Io1vi4a%)sw{$z-A+|Qs7Ss&txMCVf1mWZf zAX13Lz*7-HbPfGl+eA?!UwU`RDB!YWKGt*^pJQDv9;qaCqGd*(D_Qo{gY7hUB`cqg z=PFrl8DV>kqymYVZ<2L8Gt(X62wYy4Cwk9Sq`~3c@-VH1=gMc{x$+d6-{AOrc`4xO zUtW5i2U;O*;r65Rl$9%QAvom9>%-$IaF!q`E>~Aqm!38h7kA#Uv)b6@v9r>i7Z;zu zbP8mIBYX+QoL=ph;1U;^y3H(F?Z~=VAH$a@3WhQ+OvsxXtO-bgOdylMj1p+$=2ohu z143x&=gZ__-=#o~{h1fHeKkTjH#9T^?V~ZdckiC;!5B3SZZEGuYiH^u1TeRCYny5{ zxWsU1=muYipSZB$c(Hx)$GY<5wszQl;-ToAOer2}DS{-PF!WbG^;hK0kGv_r_G`bEwp-$<=_wGU z0Q+wsNaB|DD!KD4G?ACtb6u=kD75n~jG5U%Z%-x%qk7-rf!jZifOI zqe#up6WXS*lLes}x9<%N4hgrhb$55`8gqANSC*ERVE<`d_Him*yyjl*a>ZHeWNl{^ z8eDdcHcs?+QXtJ2HP-CLk7@jTa}`a2!f2PL;V~x0x#$=kCxDF0SI=QykW_}&a~X$z z6C~N);(6D_sIK77E;x?S-2o)(Cqy@o>p#0RpQ2n8u=X~1(PsuLcz= zTg&s<8+q&Px8yT_{WJ2){a4hM5?}Jp>)6KmE*HM%2bUVP=|^kgz%vMuax5Ne4QqX6 z=gWVNi}i4q$Z=~4trP1Txf)Ke+08CM2|mj64u}-2xPWVoFy+LDbb$-%jXMNNbQGdc zb7yd1K<!6};^2?FnrqJ%0bOJb(UN=H}*PcXwCwkjAw#4n*-F?`yrl|3`;M z$~Qcrj>4p_&Mp<6F%Rpvv%M=@TRW)N9@fDSGJ+n|Jq=2=x-CfvmVQ#$lUo8rFekfmim!gprEq!8gLVoI}e@ah!`@4Vd@9G!! zXqrksdw!@SbC>n3`0-;Ie?E?_VDmyv9^NHJAdVCa9l;(F*Opyf5F}yy z9tBF&!s1Jk3X*nqWNQfvWzb@j&mY~=AqzRYaPd0Hs(~0EER|B1xaNju`!Vg z(!v5wq#%alkA=Hw&+;pCo|VYQSC#^C1A$YbEs*SPQNHbr68=sKcz!4^A2c^Lmkr?3 z@{&-HbPFde@wB&UIL{B&pmJel__ipFPCivg0j>$$H68q^R7$tBja(nWIC5KFdF8%t zcVmwA^)+m9djaFrGtl1I(!2~;p$qP{%70wbBxsx+LNcCIOTkb_M~Be3IJff=|GoV^ z+1y-*&7{r14iqFZ%%_4jYA1yk1vMIuxO#DHmlK}Ohf5o+eo(I$5??5uwq^&Ho{2}j z@$Q)wxX>^Rs_JmS(^m9V%rD3m@;&G;%_X7}yi{_XNZKlDRo zhMFH-q4muV#mCk?1t^$M=|tVvr0yyZHx8Xu3GKI`Fo|iowXM6STau|Hj8fm0`}gk$ zr$&D8RMu3GG^sX}XpEa%;Z(o^p$g&fna=R2^q64fXrXz2n69yr=kpw;HIv%g+f|UX zySJ+vN&65aZEQf0w6y`Pr4Cdg6d1WL=i&Ov_?vJmUB^7tDm*GJND3>!oRm3OeX`d0 zXM=U=uJtFaXeFO8OLTQX#}eySj%-GAqmw-w>_UV{miDZ>m2p-&AMYtZ3K+k*JZWLI zP9d+6RO>C|@v902+|GMuf#;a$&xGw0cnVxa3gqfj40o>_v?<5dHW&2Y`MJL%|L))X zJ2fWjhI_xKKvgIJo-gN1O;vFAg`~A?sI5a`QgchQ3=a=Mko1b&xN$?ZlJ@rY<>?0> z$fNfj$;8BjEG{m}4z`4yM}SZ&>7(nO=(7q*LP3efkuTNm5$Xpa8Be|(9v&8Igi^bT z2DfKsre$$qQ7BxBbsW#lxqb_)@w*DZh+~;?_x-)H4e#={>n~TSm4I0;+&r8brGPVr z)HDAi>lyi4VGWmtuD@LPRRU(YaPx4AqkwPA;^k(oUuYunMw6E27W1C#PUEq^`mcUfKJ}?joePe&Yq5M}`Oa0i&wOqQ6x(j+ zE-(iG&ks2WQ%k`ZmpD$DfWd7u+Df9)?FZ0Edj9;G3SAZ!7S!lA4+wY#8cEl#4a-Pk zRJVuatCkBlU%Ilzg#sjnXJaqMU&SMVZEg^hbwZFt{J9;Nnn<+!^y0;oT)%!pPjxFB zE;#@Zm-F^jqiea~q3vl~}Se(I@u=PBSRP+?ce%sdHC>Q#o9fn_32;F52tBTOCj1mxulr2 zgs8{mLMh;Xbe;m90<}p2>(4sA)Fz6T5-TrADzaHUqZUc9 zE1cYTeYTiav|F?;Ktg=*JD^+3fNp>cb2ZU zjxb!c!H!T9gf7>ywe2o6kXBb$WoC9pwzs$C<;#~ciPIuSMn_1@&U~)FP&huFr$D(VKt8s9;(4)LR4pA&p>0sg z_)|Jod2(LR*q#TYqN2Qwq@u{>6MG7P0(IW$eH(fT)CvXIl``Ea&`7c{y=Njrlo=3+ zkC;066WAgtZEIU2P9OUFfA8fbqke{TY7&l zKLw&~lCOkv^znQ!Eh0;3ul)K~o5m89UlkUJcN~m77)j}s<=oo zcAA)KOA!IYb9-BRTRXP54G3+^wKTQp+J}b2H#Rq6Gid_`xVP0PHw|+u$Z!a^F)@oq z1y+oCna}RbX7CCGQE;+K!Oe?6g!XyU`p65Vfboa%vE45eDPMTS#sg2uA`$v+S=M+7im{dYoj1(eI0_N%`Iu~ zXp^Q?O2>QB!LIX+b%bI0>92^(0aoe20&~Ql3m1pJ=Yr!idkS1Z3RG+?xPr7SrpjKB zR1CFzT2Fy9D4>g*9E$;4_?!X4N7o1i*k1W2CdLOB5RPecx4q-wxbZbo<%*%9Yi^fD ze4(Jmk*>z!hdqs>r8POm3rJ&Y5*J=P+B&4MtrKY=P=cTdk|tb-kRL&iBncHH$@YQB z_K_skwhPAn)8G4P`SSnvWqt7}I8%uUbG7kR=Z6x>>9ctX)ExzmAsnYrD5a;Ib;=;@ z3f;UlCi9C+vbMe^n_HVQK0YpQzx_524M@o-giOJ_!uchrZY5+Ec?rn^-SIj{VhXwT z_VyuAYL%g(VHJ)Y9vjWod;~yro(Kuh$^4S(~eL1d;;?iAKx>UMeRsXj_`7 za2?|$qocV6Irv~w4q<@yaA{Ufwl|T3(k3K^An63#JdRI}@PrFOCHjxH_mFl|l50C> zQjJ?N{?X6>Bl+rAzFHL_Qa*%S9&r8n^7uGU0Z)PYq5$U-ZcjUeJ)|VGayq*pNE#ZF z8@I<~Xm~`8aBppG$@l~WN$Cxo#M`E*>ct!x}PG4e&{ri-KoaXC6Xf>G^* z(D3#U?96qjou`eBbqJM~U|4)bZ9!2JizbrxL5HJIuvRSY(Qz{ROn7l&g_KiBKBfr- zNqlVzC$vI<`!tu90)_C+rLBAoSIlh}*YBd7E8I=v{e@A$Ya|s$C!fkwz*FFgP=FH* zzaZ1`i=?}Fr=J24F7~gK6BRvHo6ySKEf8aguJOv7+0H+9@ML4HG1(Sjo8rpvF$~{?GT9BESlkyDO zn2U>x^61ecdF{2=RI8`Gy-nIW+Br00*yFEVgm(c>>yce9=g9<4Vxz`UPfw4GjEv}s zbhC4_dS{)MmX=h*iXU7k6H^gP46JO(@lQJLD=mWf=<|7B45RsV?nkd@I6p$ru?~}ZrrgLJ%^hKf8fXhT)~Ck+06+jqL_t&{W0%?yghCV~twWG>w6`IL` zo<4qGjc+e5Ey_Bycs}vs6S4x^NzBvI)~fmRg9Rod9rjKaaG@bdXc{#)H$jlp4MEbV zyqKDj{r!DeSzD0>6(lXo&fYG@ZqfjPB>b=*rPd}YJc>R?g+av-hp^}rMo4Vp*$4?3 zF9uPF#CA+O4NO0k$3yU8`Q-uVp2|r+`tw59&sVOLXT#&#oe?byfL+>*DmWF%UW(mc>1&DVQmZF*bQ zm$&6)@`W5U?n~#`P3gQdCaKPDKuOBc?t$###cOkBPG%lGk=Ykdbt7^P*x&V0T|oK{;E)%FXB>B0GtE<;S1m~ z1QAWm&3Zc9$jCLhb?cVA#8%$mq_Yi~dhtTO@zz^B+D2VnPQxTfkAGdFO$GJF+Roh-CU z*>gr1) zb9un^7mD*`NyqiMuF-W>&RSu0-iV8V5F{nrQqpm=52vt=%G%z#ti3#uy{VV7J~tsl zo9mLo=|G7iYJj!L{_>`*zWu%|zW+!jW~XHw$7v7WyhWgCmxN*4FZ}!$r*$*jmr-)xbY)y}>?FO&qFG&-0W~tuf*}I9`UlUXXMd zTG7{`x)dmV?NePmeQBNowL$?by3KAZQR0ra69(uV0Zl1M;&|+)gF{Izu1jKNQw?q( zEiTLY#7k+$3(CRbhBPN&%yo53b{;>Gt!K~WD0w1HgFVuHYcyTcp@Bj9%CCP-zU?o4 zYp~dN`m3$|`C1SJJCSJ!-s34y1`2rADgzNO2Z#o!T{hr=01A`1y{i$z7Ybddku*0q zCzCHGvBhmx78Vxd&;IPsG<@~Lt176WR#Ibvd&6pv7G^uB9d_&}NTU6x=B8#99&O?T z&b75woJzMPd%Js*fFLQ*NU~A5_Ue-hBQ#my>JRl?Rr2AU0-gdFO#zN8mtaisf}|oD zDJli_63-$Dc!iStF9WsJ*!H!iT3Gq9Awy}MFLlC%FI<$XFo}L#CygmNZpPNNZfunp zJCJUCwcmd?AqQ(4vNgXdhkyJH*=~O>eJ$OR*gKTH$#FT{Se4%Ucct@{J2EsDXe52} z$3HH=@s;0@8@Fz2F@Y99P=;ZnTijHT#P9qW=lV0D**>iTet1`Z7#*D#qR*ZevgufF zPrYGpS2)W<7Rx zcVumST{du0sMOlhs&N#`P_Raq7SM!n3cVQ}0~irx3I$SNx}e=42t@k8MiRBDKo~1F z7mW&p?~~O(1;`_GcE5-kS=n~K2poKwB~m~KmlE^VKsGN(s)0uEC|q6&cwy4zZChWn z;wUtogLhp2_w{2tlg8GhF&f*pZQE(=wDH6?8rw-@G-=Yk7In|)Zf>eA0E$EpJ&k^*_N-y{^vp=2bfB0eZNo0AQAN* z*#&Pox3)m+b24Va*<_dZfGhA7RRm#lp-9Gqe$n?UuPKFtgQIvwYEi0oT=+BSYOoRC zejc1JQgS$zCqoaz;Xv##vlb!-U%_$UtS^sTUB#x^g1VDf&{)zg5iZT&U0p`#d7-&D zcl7Y`l9{_Td>F9-SI|qhWJCmO4LiSKP*zd5p+A)o#FD@;Ptrp|39fy>)sL-eFEZ$l z^m&y`X^gW#`AcaKF3r5;YYA?UhA6F(PufRiVz+Z!Q;QdT80!j?LVuDAnVhXP+L;4K zYq9y|ipO$y3l%aSUqd%Hy&^fEWLiUFc8lh% z+g~~vHz}`yIE*jHj%jh@!XJ&4q)n4Ez8II+0@BsfGZF7n0s>aGHwRN&Q0MD(hw0qq zruJqZ3qhm^HQP#9L3$HbG890o0ipf_MOjgXgg@`&D?}`yTe>61P=mB5uJ^* zkdn9&uM6=L04U9#P0cb!UbS~#k7L44zuk*<_q=_TJdI;K?OY5W7E-BxOsq*xv;Sl6 zrWBi5nXajW%7p8Xdq@`p z6^wxRriwD29Z!rTHc?jb74|00$q0=Y&~i ze`C&D0(ky|G?%hOn647GCO{a5=qd^q2UjRAZ45uQ!==V{I=Zn3S#+)H z3nv_Ap#O;i!E3-FDQimy7mv?cK%9!qVZzS5XP6N(yA|a1OS-i$K)_M5@S^^eL1@#< zH}L@{AM$W>D;JFK(khwz`Vxv3AO5FO><#T9;~iXpE-oDBU&zrrc4Ja(>dv3}AJyvI z6FkXoGUib)tI%PMbGW-5j#d)xdXB)kFK}SyOEq+rKM{P-dH>w$T*9Hue8{zc20zs^ zpvs>381iGa^M= z%Q!mrz`Mg1LKTp+8A2w5bvx75M%OI|Kl2aXtO-Da7$)glr7POnPyj6F%~4JWbM;Uo zq>=&9XskT5=Fb3XNc>t#-Zg5~jZ~{uf^H+<+uK-U-b~_-?HRWsrk&g{cH`^cIWef# zQ_$?E{85Tl=bDPQEKc_2+Swn7Xgj(S3bsuOh$$RN-Nsp$y3)+L=#bzl3FC?YREcol zc?K%FSV9=1eJsYFlRa4A;{fS9jg5^R=%FQyL$tg}@HbQEYGeZ|JAKmU^=IP6tJj^ZYcyd` z%&8!ch6vKJJcqCy8)(~RH)YTfBygYj~XFPn)=NI>m;g@Dw>X|C-D*ws82*bg{OQ7oP z!nBtE`)cGfG(5DxNQzN5iHbq=O>7AqyfHbcD6_q%fb_no9Qhp1vn=e7R^TyIFZ9E~ zpYtP$L?SH@4d8 zpmG89_x#oRZltc63A_oaWxeIML=DLN-IVW+Xd6WE_67Vpl|^PYzQD-LHoPtPHn4mI zPk@Epg3d?tvm(-@T)iUDkz*>feH!=k?Bo8{yUcQSPKt%Tl(&e@=|!Z;IgQQP-WRTa zVkt?0wlDrMn{J4S$-?EB%3dSiUwm?GtrSS#_M+WDKDA&WP*^~j3{MkE{un*7u}jPy z95GrCF#mj zo;(-451>?E-SR~!n*@D2^tFJ}vK3^<5Ck$9RDY);La6M;O1Dtb6t#%t6I=h?#CUeG zPg%HV;#O{2{L-pkpv3K7570okn11*vhzqsbWm6^JnTNY!F=_;4j6r8Ao=n^xccue8 zBKPq~6&NNYhq4U85n{9CoicxkQ@Z@`pp*fk9RlXN9Lm>=(PCwL~bq$W$Cox+bU%xh7y$LMa@q1 zdz$*oJhKsA@x8xr8va4c#C%`RX9=H4IbzH6`lu{}3i1Pm;PA2(B zg^Poq8#gY>F?tyIe-wAyDD$JJk&z+m0ad+#JpigG-fxeRjgN~yoPKcE#CPl)b5nyW+yw-pIfp)Swe} zc~FzfaZ1jZkPVPNr-@amf~1g9MquZlsHTb5Tr;8FG1C)s#~cna zf5opx)NRY-A#hs^KCYuWj_@rqrQ*thS^u2@M%AF`K~vnH(wh*?xN+#btQas~Cg6Vd z|CB6sIXQj7w?Af=DWqcvglV^KkamYN^zipn;fv zdY0}0+myZ-zLvWS`2iUpFJ&7D`wMo(WSVy>AECRvJ(@-*X<%gIEiD{OB^T-$9rw(& zbm3Nue_=DTRs_JjN}G5T?U~dKP45nu4OGf~HOl<&7j`QLg@*B2hk36e2e0Fwy$qNW zND3{+({dX$U~;ZYO4Z2d*=6xZuynVUX*p1X?L|))T5Oi&JA4o0?(QCB)!1QV9G@*n z>Y|*oqiZ~HypTZdRYU19v#UU$DY5k|9c1&rbpvbaYR3vP8#6O#0`1uE{e-Y=?SFpI z^D&)uJ?|Pz4rogez-zhAE|5?g+dr|*@EgQ?H%O`6Oj+dj(q*RA3ycSCWRT4~v! zmdha3)k=BS7_QDCgOIlBj`qeFP{!wv+WV1#e`tTfBR!4vkmw%wyX+D5?OQpchta{- zqp`J}K27K+@o|NJE8DQeOCIy9zl#zRApVja)g0(f))@)!I`{M3X25?&&{Gc1=o6!* zX+60#SkPuL&6{T}EdmV4ZjXCGpSw&r{+aAAwKpSNedwz{J0~99fJ9l^8H!0FTzo6; zvY{@CMv)n?>TEzzr*|J0{Uf9gfaNZO_dhFSx!PaAf;IIaCt}}Oh<zyRtgJ;VA9J zbQ8o0Wdzm*W;QmM;9vP;9VJ?i9UL7iFl4MGyjWT~wsPYG_RI717I)sQeY{+mNP?zR ze&Nwh|e~j1uhp13PjYo2izJBEhlP&BeumJdcLQOi8 zXqg^A`v20P?x zZEc3epL9L#pvJPx{(NgCRa`2Mh@;p%ez;5JaTo@%m-ztj)+mV|l0J12<3YSi6UYcR&6&cLKsJ zci$y&e$85szg|mAi?NyOVFZ}fMb52LNX-(uK4BSk!ux)EgSjr?RaLIS zWQNH3K$TSz(p=je0sTyBGli{F(mbUuFip7%nvw{1f0Y_$gVHd;8qRRfgpxy=!Olla zCNQ_QmL}o%4#J*VFeivaS57)yZnXMNv9jLjWpUY;iFh6mp%p@!O-kZJxJnT zzbZa|MVC#RB}2rsJjWvfiR;x_gsN1p8zkUUgD1{!90QPQI0d2bQ<48+F*E??>i7rw;DGU} z0Q`5K&>wa+Z;owQaRDpRJDx3u2q5i9a%<|p6Y}FHy7{q9b#)Msvk6EbSMseHI;~9G zh{m1@)(BCXaapBbl+y-+ckKjGhT<9X<%>Rl$Q0IGsNy6Y-+caj z<#GDXsK*wTId%jqBf%*_B!&f(F|)&zEfQUoq-011%QOw4Z2q@a-}S-bd@5Pu$f!<0%SL^;bC#K_t=1Nk=e zoBydBcMj0|srl`IRvk^r`w zi(tYx1+5|Ed-+a;k7MV{U+746bnkmcqz)RE3_OwxGu&ziCmJ}}xKubYj%NI6i1?au zKRTt={cZ?Kgp)}Nr@sAcks2=uy1#W-Zu1NSA|y?*e(9H5;tAhY!@ZQoX~aVefx5idzc|Z52K_iKVM9Umm-$n)=gk00+EQd6*TZl4mz|XNi z6~&QZj26+Z;JX$u0E?k!;Q@$uF$qZGMcq{C8=4*U53yul29+QYQZYe5F?=}l+>kKb z*VB>6=#s#uJ2iiy%w8cQ9;5`?yPfpPUD+!lBKSOC{;?rBl=vF*S#j95FDqfEn0SjM zDe&l|qYDqIUFq5CCKE|zN_+8Oo29*?%{vwR4o*Of|712OLXBLhNwEsPwZg@4@2Ik@ z0Wxq!x&yA7YDM0Z-$7v7n!EW|92)d^u+6G8xxx=uKtOnf3XAq6d6|*}awBC;YWB4T z8UF3GQfv5lx4h1U(aS2aG2tHdQ25u)Lf#M%|_w-6nN1F~T zn~z;Z5mmvFOnmAP`+O{fOq4xollMd*RqTxPG1kAq6_sN`40Y5i*` zc7E3(#O=yU<=z7b6q@byOp@Q+J=p{~p;cDbs!hL7*=gb5)S@F7kM2+FQrwM{9E&8e z!daE_1XCvC6!CjF8AzXxq=@*VZwUgz<9Jdx7>91y;`%8jos?5T$f|VU3N$=Wxm(OS z>k&b1j810$l#J4aWN{ZTNhU;ov0YoFI~Hv!*zF>yq0pBJxPO9k`>kfxhy(D~$c*X%6ZvI6~u_E(P z_dS$%uxPyEu$owAAo_>s_gfv@P!zA6p-vOlk0(|LX4$75l0ltd5z7TiwKNoAE(Q`y z8i!tXAG=JMGk=@{;T}#3p<|;aW=$Au^rlo`FAc3zxuz`Sd0u=xQZ?>3Pc&Aee>5|8 zwE@y#zeSCprna_XPLSZ!7WDd#?1tMY z!@ffgl;ct}8qpWi0p8(R=j!tU4vLAzJCHI;cem4RD|eNiK8Hn<^AqQa3@S)Z57DZ{ zoVmBnIwE*C7SN~O-F5j|D$oIUOFjr7MKm-CG*9vv=|7lhZ)+e}9*kBe;@zDVE=QkP z=B7E%LJgaxl!Q?KC%PYhxQCjlVP8d9nkv5YhyNBf&)<8{h?Z)!u7MdJ{&8tvOu89w z?_$-q+=!Lg#P*Fj2q+n4e$^l+_&(_For1!&W6nh7uW5jR>)*0xwT?V=$iOYw(*-c@ zEGJXJuj#5YD+nGkedgw@M`xgg-Fc~b2yER8A>K z-MoD6ag@4L3&fjuoVVga z8mygSSlDFdft_Q5n_umNUwL#ehFfu zx65ime~@-lf{&|II&pb8mY)+1!8rDI(~Dc=vcO%%=QPm@Sv}_M;4MMbD*Ua7^@Q|y zQ6c#!@)Hb%Gdgi1%Nhg2cV;RD4ki5D^>7t}>}dKcwz;(-gEjBUOS#naUJ7TFo*rXz zwibK25fWx@Q72r z@K&Rdr%NtK2w&|lcW~c5Km|i^8an#App<xxGB&mhv)zA=}Z}&GwZhVs6!! zW>D_6EM@bw0xtIUo)$rIqnnP7RoNY#Z4Oiqqg{7+h=hHOLdHM~@*!Qg}Fl90#8GVU3hQAO_(ZLEQ8m z!fznSyhL3J=?-pWG~pMNZbj;x@9oEHV=L5Rngp~ID<2HOHtqgmzrog=Nx?4r>Bz3z zNpxec75`!FT169WZ2UrlD*HPF?p3YzLLqU@Ix_r&*T`CIkP5_(=ytNl*=)SL6iz+Q zrS>~T{dwK@s6NlGvS2Zs=J)6Q<|3nc>&Wn3G8g@D*Wyfc4^@$-?jK<|LU9e+$LwFr15Xb z+YIF=!Iq`RXt6l(SmT6m3wD0Ef*u*#9J@}LY0;XI#)pe^hnQ&%&n}N1|5JbtCj$F0 z4JnU92zzk@zX5w83k>1HE2k++=0SG+9(P+aR!A`u$6>t=EPc3V!)8r<9LNO5DxH|a z?eSL>bpq{V@Z*&jaKz)mXEGzG+4f0z7&akf$-9Za3_k#V*H`4qN7gZetTx@fn#3+Pmm5-+^^sn=>%I86D?C7Au znt&m=f4nEDJs$yELisD|;OelUrG;jEoW7yCy~H#BW_v$1h1sBFcV=&#oWIKbnWU!- zf-d30DVL}oP{&%XIUK7^#cYxfE(@2-hszx~*&OuSvW8!4NnrVv^!vd%zo4=flh=&Q z(0rBRe=ha-4BQz9+Odr^`F)_l{+{ki1<>N_zO$#!f+v@SzlV;eBB!~(ua0E=M(;zo zri{B7`!Aj!j1GLR+>JoODZ|nJS0!`QRs4s7*yNLA(6Fc9uL~PAj&yg-Ji1S|uEX5Q zDQ;%P1)BX1y;ZnJ;qu}-9U3ORwx#ty9;dr6j2oM$p-=##hWDq#_4!hWSMPsQ=eb!V z)b~Ddw7lgIOoxEC>*SVBuggA~nasCo()YxG?0ijhC9$l`e$V=L9(zhTkpVC^4iLsi z3Hb-MJk;3In&JtlQiNN~HAtYdrkGZK`Y#w3%^)ebz$Bx;g|j0khgio@cNoz<>v(o` zt?M8@uH?(4uYQK3AJ0339O@5f;Ng9*CHaw!n27L->z8Abd3@N>%I6m`o=WVIS4SgO z{XaUE-F-icRP>4UJBEg|7^@~nFu=1{g0iO&CREsyu34i@&$j%Z*0;N~ai~Cj*{#Tj z`u53UI%@lnq|zEsgk(5#J7*Ey4qb~tD>cpoD{~{y65zZK->qu&?qK8@}vUUB(opSe7%8lzfL6zD*CvC zy+e=7ZUhP%+MkP!nh6oGJ+>_pfh_hv2;076>vLPRA7ufyAIeeY;H`%oT%pi3WJQV} z1629s5+t4RS}b1p!jSErG= zg#WUK9OT0YhtYxqV-49(n)w?TYNGI2fp>UTUmQ2LF6tn zqkg%z$(6N2!v`Ks|@te5jP-2S&mxg@Lo3%{rtQARw0*pw6d?;p@9^NKbod&i%3BwdHmW0#I zpRnL+xznw-4db4uU}V?ViP<=oXdTWOkzCQC>cBX~@(P&tyFzHYPC%NyBk$=$bdF_N zaPXFL`GM?pjH6(rHMRY{u*SKkaFl?Q;Bxt$VoU{@Ti^U$r=@vZV%J6E&tph&<;+Y^ zu0}ynkNyGhM`#x5o*PD)Vo3Y28DT{Q-{nuPfY3mkBbJyE_B`Q)L4=z@nFiP?#u-M%KGG*C)87~XkZhnsT3Y9;|JYS%5l}_^L zfgIc_!B7rVCQs@Gs@lv98^4+7t$nMIY?>gL0pqDC8jtI@iH*s0Q%ozj-09_i;LN>TuomoLqEF zjDFf{t^KH;Q+KS|bfzXFk4*jqlzTyPe0r|dH;sZ4K4rZ6u+tyn?%^p*f07brK#g>wq65HT z&TnXN-QF1h>xK%!y4z#AeMKvGUgMOg+-MR8L=HPM61UHX{Xp<|Hhg-l>;?eLfN}}d z9_#fRMlK6-bm0xLMB<2Ra!^Rf7p0L+3Zg(?>q~7BLr8pxLx-iIpL0}IQ%fp_BbPq0 zPhFUHJU)~Cv$OZw00lYo(a>v&WiNdf6SZZFPn@v9CB$G*8za-u3LQcvon{{=o>69m z%#_WM_64%VO)^0|80$E19ZKFTI;ru+kJW~mQN@4gzl}&!x-BFNdwCO4B#@+(q)G9M z_Bq-wGQ^e$pm$DanOT_{dSh3yp@9qO1Zg9YK1k{ys9ailne`bH z+=d?4*d(7^}(Uq#;o16v{_O!b@jB> zb=WRMxp!68!qe7MLy@F5=+_$GH;bjC_C#~Qxe<*;M0#zV%U!?y0A%|GQJyQ|3Z~Im z4$;yTZFSOEpW3?sggX@IzX=3V^F>-^0B2aq>95+^NS4Oxow#~K!xw8Q@d2|V7MKtB zU%nie(A(&eh;*i`NT28YlkHD!F!Ref96F|OB>IUQol5*jgd>a}aNIA&1KtY~utii07wj+932|cdL4m9z#)b+jQ|-Vw11&O>(}_Xl ze};`QiE@nSI4AiX7oLm%eT&W>=m4C~=c){$LNlDcE>|Z9HN#!kkM}qEa=T%I6_RTw zN1Id9qa=}R-j#G~@T_*m)tJ@>9!!oXxJWnGa|ra5Lc-_jyYo63Pz>px6^Z?hmKaRC z0L!jm;gu7%OLAtJAkM#~dO^hAi#jdYAE)-5KV{~Ak6XTvS?M^LdvXGBf}I)=V^qm4=7sgRz< za3#TYK23DR(i~4KdP$?Qx|`#AK8F6?xml?r&usg0B(mb$Ry&d@-|}WV#PdX2E)>8M zuv(iTs3>h}g2YU;+b&U!*zzDL8L=O`C`8rBuGYaAGhEr;eg1NP%El)^zvzr)jimR> z=4vI}2`zlS#zJr6)?j5HV zCEchVkXUYr{ij!rmE!)f=T@p^qr#Cqbo=-|YPQ8&;sW%aOgp=PA$DFaDw-Psa*CcUC6KGTAVv(f=2p>k7!j;LDj!G-Yx}($ z1EXS)4r=9r)BnCZTVQV(a-f6>91=p`4B-<6ets_dHj;INPWf3>UL#h5zvd$e<1E1a zLtbWFAs;XNbrADK)zw>+GX5xP8d^d&`5WfUEVpC>1NyIX3z8~CJ=b*83FoTx0&|^) zYU(2dn~6kenJ-y?FW@=|W2=!gAZ#TZ%3+&LdM@__T5o=PT>idH(ee1~;z|QMC0OQ8 z@Mrim@B*Fd)Czg8uC>*#x_s`V(@zJ(m^2A#nmZRoc~ZI1^{XE%HxQ%;E=%uGRnGt zMYDYH9FIBU;oz>JJQ6pwT#u=JaE^pG%g)-yMqi^ti{-&Yqu%4+6#?L)p<(0<6+&dh zWM*li%Iv@BtmW_U^6+7D0<#X5UiZJ2v-SFAD&Q?^yT|!MF^W#-@@<@sxJFhAya~A; zoK5?h{8AV!MTYx$^I68{3F!3k`ET@S1%u04<9K1wDkfCQ!lnXA0MZ#S1x#aH_BZ%Q zDc?If!!P4aTfc%WISspe>K!dDttPEHDAe?Y>Nh<2~uq_nqk<0!c z9NI<2@P32@g!1f;=1G)}$}Q{D)8sxrE%y`Pk!eOs3eGWMGi?&8kgJd0sI?eFLmwlG z{vfXTV&(u4hZP6?f2$ADDnWiFXx=|@sVsEtnrExjrBbOg1+{Th$cWT6FcnEsz>}qO z6z-G3lM^@DL}P7q?p`AuLsq3rg^YWrO*THa=+f@y&89p8_8cvyjM7`P()!;c91r*D z8`vWXZcb%79qblggwol@XKyXpbxE*7+j z2w-_ts~zb9rELeQ?e}EBULW6>d!7mr?8`}y5#7<(y8{=&orXx@Og@j>Lrm{JEBhjm z?D+k}&U$RE-()O}qd90zI^2Mtc*$oq{-c`sPyY{O4@yQRhD_RMrHRIBM$crC5A+vB zT*EbAhQB*dU$%z*bT`lekM)!|@y?%h{74WNMGLU7O^oFRxEVJYKvLLIxiv_OXH_Oy zS@0GUfbBb(R0I^S_bA)IKHib}kDut8VEzrAeR$x2r}g)3DBS8!D;MYA73``W)2%Mv zPHWwkNBPYwn^~`q?Bg!)J`N*pGlEV&c`>EP?xLTX$QQV#zVyKq@_4iv^Fn!6l%g~w#u32+Y8QRM&|wA&i~bQu&TnatQX$o z*~uM#0$Y3l`>RoHH8o0iiX6_x8iORlf2E})Q5yxvziix`o^soRdcvhP+9=BrM~a#| zr6X&i#X6ji-w-InptA{kxmL-ab}q_yN8+xj8u>O!81G3Wxj1rHB1Ivz)H| z9PVB}Db5eu63?{{U3g9wVl`GHHZ*6E{BeEN;`6%*>lPqQp7HxHg&m6@r{U@Uwj(6H zk#R5XD4@lUiI;Nb{!)DYpvvf)-x*-rG182{o?r;Igq?z~z(+E-J_b9WWQQlr|#}|;97eic^q3I1cKtNNV0}XBpShcWFwm^E^B;AKjbLYh%Uj9kt&%1 zvDZL}uh(folUx((W?EU1w$Iy|E1l9$*iuk#$rpsKyXkJSUw0f2blyk^us^3=d{i|d zVYx--B9FLpAS`&+nkldq1GWx0zitRd5KG5SwJ4a$vAa{C?i}gn9d~e8b_`1@m?@Rn z9N8v0W3_Z+S0wQ&SZT4x^>}2Oy*pU?dyT)neLe@KUmE3d2?e|~9WNJQ$iT|TbFdhu z7bgR=Vt-{6YgoTBaRe;0`N3c}FoM&IZEW$!dTkTso?;;UA(SBX%8CVDD^cV>dxLla zw?o?f591J0%DXbZN0JEoS(lQ?XG9*7{BbP)2v~dh0c0CPdZ}_x+5ifHyg{ZHLV)ic z`AVme5H=9sL2yCr@mq{0X%}D?1T3PY=BP0$6HNYX+3-e620?|-?NfCXo`bD4y_kt% zWmRfQ2EHWZw2R5i(y=--OaDpg{ibDdJ5d&&$_MKg3F7-(K^IZOK)pR^2HW)`Hq>Vv zzKILtI#Ik4TdB)*Yf@v^b4`7A(|4wc>oL7YZ7F;XQe+y#lVbZzi`mj7Gu*Z~M!13e z2pJ{s0+a#Px_>G5B2V7N#y47}JdV%twBObN=a0Wl1J0yA;cwgX-fi6OPreaq1-=hz z(5Yaqp5x9a%zO>WR^o61ldx^*7LWIASL0b2f~I4138_wlS6*N11$o?O^gG;eL*ZCw9Y`>i)UbAQ~GUfz*0jq_)KZJEI7*Trh}-^aCi}0UpWenGx&e_WtgBuNq{LrtnO>i|<36?WR2Hje+*fonu$CMR9g+ z)-sbfQ(g^uE$b*!c(30ZDAXTP9TvC|vo7NYth3#pEGD^qdGx;|hw?wS`^DvYoydH@J4(#R$Y8b84ompK_Cm0)QV_vkP%Kagu9`VjSDG`~K(*j8AqMf0DN7 z0%O-Nu_`)}=6IR|c3VfS9ckm1d_^jq`p24TyeUkfUDhh_4j)l2$6Y^ps6lKP&Br=P zDO}WAAC$C6=GITTq)l;0UWztPy*NcdtC)89maHupem;qr{`S<{-0A&=!*Qv~33F>3 zz>s1%1kl<1D8hiVHvzdqVbGXz)Z83chAUQfsBZgPJ(Atwhrh^g6kjrac9#9WB{;W_ zHy`kUyAwP3Z;szTzrKX9!K#F0Ob}7%af-0He#zad8xJ~b~bMr~G&LOL@is>-b<$vv-awlNaF(^2_uH`HH$jixjD!Q}G#@|olST0IPg zT-lKwc~?dc$)w*euJ{{ozWq9sP}^F}xZ_%0>` zh%!}WUU&ZkP{0c|WkEQe#dQ~>gJgn+kTv*Qt)^v4N=~gj-&_e^KulTJ*Dfjz0${F$ zPh&Ii(|`GXAV-$Boq}^Hz4z!z>)e`YonxhrWoC8VftQcB&UwZ-*TG5bnA4LAa;j{J zwYky3gSwp?D;Ie+ho$p!+CBQ(q0?Q?kHik$OGZY@AO^sI!WB3adO|*=l5c2ZQ2YFo zen50x_Ai&~P;Kh?Br?dA@jU&iSs&80VK?W$GUKKo2#vu6o{g;PgP<`~Z`G5Wy&u*Q zgX}yjXPwy3td1dsie@lsp)F?>lKV_Cq_D()*1YF%_cIpmuk~&E>eTz%R0g}%dGw`Fx8s?s3OHu%3nLsf&7i3X<5B82W zYzF_*+)w7}+T(I6wQ3E+9eX?*>)MQIXlN&5v$!TE&SI9=!NmR_5@J4#@b=@A&Yirl zxYLWBoen7z@QH^H*0QpKhcSq?B$QfBP0cmdn(5LBCp%tVU|&{{D2Sy7Q;t9Ca7w{W zTfaI3a0h56{N4Aco>@s+DGkLL6j=8&9i=-V+-t7=pVsJerIN+?BIHm{rAV|Z^zWMw4@MU zum9R@A|OT-mTS~@=)zZ6G;cw-{20CSIek|98l|scL_PmDl?yzu9U;!oPgB;*)0hm{ z-ru1quC^TWyf*!{JZTsi7}8_!JsMk`ylCo;RH+v;3$v6S4c?LKSL@s=TFdl2sXaVA z5%GOs;(4<*wKOLlCOxC{^jH5_%BOM!Gr%|zE~eUSJM)KCA@Rog{N#qkXYV zrdieG8lHse2(}Q39jUKV2S zAV9j0wBD_>kP$aVKwdBz{d>fs+7(HShQdRjxj}N!dS2S^-z-bQfn`7!0-jb;?BhwFs@QWVa+{KD zldrK-`o|?wniX+xcn0|Cd(wJ%c#QqE?&?0jSnss7y$J@k9!zTU=*D_a)vIal@FCJ} z7xL3jdKO03LeZW$0aBmabP4dVg&uS-Iq;(~Djc!$o|3}U2*TMFeZaiQFKPM%q!D({wDAAt zMMDR;Qx{51LyBiCE8G6LRa>`5Ff+A~{ExiW0p>$dp?UA3yl8w^3FiFZA&7|evX3uw zjB<|lqpFF^OFCO*Ka%+w6#c%ow8rxLzGRb)^m&z(mGoJUl-1~ECT;KQ!BX!=y)}Tl z0y?%3vraT-55grD86>&15d0-G8o; zIX_!T!L=#LR@?1*=c9Q2J*PYN@`_w^_upXh$>(%npxdpY_uXZ$OJ{H}q|eLCivk#? z2SOg!{Fv>|4!~2aa>SV%380koESLfmqgiX=50>nr&2 zG7>F2;nZ`jaJ!rL?!wN-Yx*${w&#=xHyH12aA*y``Lv(?WudzOeW5zJ(soKNCW!8% zmj914&#Qkr>WC{jusk2U4LRig_>d0HZaI_Xbz(B?3L_R?w>(|`5*PoM;Oja#9h5UG zOE1QrAipfC<7Zo4pCEnG^c{!(T~{ddxBu@2ptnB%MYnz(g2O4}6y=UvWobS-M~0D+ zF+#L@zFEU(A)j^(soj3#ECjhjPM@le7EQ{dsQS|J;mtyel|snsMcr?7f=muv z^o!Gx-4lD1Za8plPT2Wpo;?-({mpn=b)10jzL5WwxDI^pWUac?j~AUnzv2w>>njEG z76|Jb5g;VRsicR+iG|7Z8cw5|B&(F=H!tnNzF)+?54I@)dzmpTApM`S^H5L4sw1 z1H|fsyT>nTeLp%uU=CZ{cz_$}6>P`yjv~KHvz-#lH&*B@E)AP4x|=L=bYNr~38kp= z1=^;Xb|`4yL_HI#T|KTyfD=5_4D0wxEE!@nr^CnHT=enrYOO-1>s7cZ6-^-6I(_5y z`}__7t#PNboh061T-Y1@=;goYMIHWU{9R4xh3+=*_e-9HlY}8eoIDj89vaP;q0tsS z(w~r11Hc%lAz-{|FOUIO(6b$wprB)gP2=Pj8X&Ucc7Z(+s9P}i0`R0Z=x|qY-?`t# zTRu1_J(B70e{E?G{OrjXK%-vH2(vzmo+}>U%E=p6s)zjY8YZqim?H@wzyv>ckwl$@ zM0m;JiQVf0JS#12ZPp8#i{j~2FCa2M3fou=&ubpIlAY{2sk~&4Q1sFy_8v^(WJ2Pe zW(Djhn3^lA0-tJ@mlT-|8}_QQaJ*_KsXotR_3?Wq{72}3ql0GaOKLbH4*o`nJy;o5 z@tL0`p7IGziqFGxP_o`b5gEy;Ud%C2x{9`)|8~~&13$r$;8B&(1uTfmN@sc$B(;H4 zrxKJ4LeF`hKc3G6UsshwR&+ViJ&+OhjmPB-e`fw|>rk14;jfDU044E(D9!9NC(v`> zV4FzF4L}pNpZT}OOM8a{Wf3k-u_48?4bs9QGXh7_9pI6`pa25M(u%xpxe1t9q9RL@ z4(yqBLQSjgZf&KNTCkoiC$oX*Op2nvr*KIFIHe$aP@kXuapAnt$DvXgAyZIK*xO-( z{CPLvXSX2{MSUEqD0@m#OlgB*49TK_P}uebvbqCyJN1{P>T#*Nx|frc5@dzk$2 z3uY>%2bFWQ;63%8*-Zs9kumSoh>&4hZt-x0i5u&By%KilwFP2R4&xkLilI@OxWVkiqkF#j3Wu|6Vl9PrnbmE_%iZ(V zP-aFgTAEBef<4{Go8zo;^C1Y|9zMREVJPUa!`HLRC;xcusG^vOo&zp!|7v~Y)ut=? z?O^+qKtpqBGBWiOxF(3~b)mhp z6NO+G@*&+bd#31WljINpTw?qC5Jj*H4l*5D9qEkQrD;WLtnYE;tmm_}u|edDa?~AK z>CL&rfz(Q{o)I^?HuiqZnZDzLP{E>KNg;>pa!SG3e9pM1Oi_ysLo?CAHqf2g z_nV8V(zMC!#-$ITp-u(#pU4uhY1QhpT1iSNkOG|4GVXIaz5e>P^_};H(usA819plL zO4!I#ssn>a!$o5I&Yg=9uTPFISOwZtYP!1(?lAsScE`qKRFHal>P^Zi=_I`62&n#% z%UV5VT~1%xPcv(^iH75a4>M~C(x)gkrv;WA?aWq_!4erBEKDJpCTqRSEhxdOB!V~aeCQ@fc2 zoX^H{ib^VxLAEC!#fdNIc@R>b2kmmjK@bF9MZa1L_Y(soy}Z6o^=?7I$^R-VErpj^ z;hsE$>01tp>7!2sGkRxL+jp6#Cj19nrgS$TR z0C~TaEefzyl}o8)e}s9>RR0rr?PHOH;eJ zft+fC(!1n>7}tMyzqNL=gF0+0Y=IzmFjyUq8=mAD=}Oj`hgbw6U2AQDroE6p2`8^a zgv_n{YTDS2_Ilwr=a#?sn;L&n!PH2k)Qs|;Z7pw7_;dyTFZjd)tU$t;fbTo&hqN`g zyWSKE!Z#E{;RmC4S)C>un3Me=r7v*nZH`V=Igyj+==yxf^Re%kA@Wfy!rgPF;=iq0 zxBkoEmg?V?%p`X_^i$a&KnTfT-YVETrTd%TD{(%H)Vm)l4czkWp}C6b$4^l*A|jR<2> zwX;S2m=`B}v&;W7S*q#4(In_dBx+1Ah#@8u1&<{Ivbu43S+M3al!jjdUu-0<&XLXt za@$tfQVtgOh6s-Na?G;tnXrrF0?Z*gn_L;R5w`aLJp~j8#{nhhci3Rnj&+L84?5A6 z{^=5kC8(MlIhvH>4E33%g$tFNE3E(=37T6MGJ zn!K0;QcQ*(kA0xmq#FNCCS{^yb);j1y|-E_cII7qeRX9vu*^<0}^+i7V z_dpM1a)cmaHPK6!HH36qnYLe2#4SKhrva~qsMTu*a@t01HXk=c{?>*N=1-!4FY@V^ z|D*T8&?zhFO(*C!?0Ng&N4S*bFvScpv1>xUL<%8_4K472N9g22GTb6h^Fr?8xX{}O z@^L`E!eKz-XrqFoMj@;c_(fik6>Bedqx5DFWW`xvWpFR#KVA7`u}r)<-tUcW$jrGV z;dgk$S(b&p88yHx`m4PXxpmYnOBj$;m)z1`Nig1`J@v~QlbTsaEU5$yKT2Z3y+ZX) zyR7t>WPpVMkSqyEqfwEPC?d87qWvvKq+3BK+Pqi9;;Fsx7CQWU$PB4_qL8IbKJc^> z)`$N)z`Zyyleg}0%64y+28;{E3QgwoLyAX1e+h~E82X=|?uD+vD@pieo$QOzzv$ZR z`uciFYHu$uNy|_1UnHmUKmO)t&GGOG`@;JofhowcqzK-){B64(vK;y5|<9 z(}mdqRDKn0p44>4_d6bj_W!)tT`%kDnQ;Y^rSH1i+S(p`yuW_8ww4=yhvAu9qC>*D zIRe+)m;HS9LKjk6NH&lBc9z1ljQInPGPI;(Fm(5h`$ONR)0qSC*x_TCx*B+2$ zHy}7E#>_d=T+%>j4AMH7W(_T78@)0x8&J2-3+)RmB-%t{ygX})2wMq<`M*aT@{o^f z1n{)J7puHe-Ii{?Bq<_sn7ATni)uhax^(Y4(cGxp4<`OCrB6W=zNl^t7F_&w+QMT< z;ksaHwq{b%*Sw~8xu2Fd5xcCr*vgdgrtl&=7DmZ`A;spTXs~J#LPEm^ybAGreo62vO*8XgXw4sfXzjp?-nCBb@M!93qWt6UGMNBSE*5RM-@!3nCQ~>|b|O!+c5jB$KGl zRij?mxVX&yUN=A7wZy4Ee=yc|nfg8ccaBo4$X+peDrL=pRIn+$5IAnOiyd!h;<#);)^d;{SiG7|5Rze#aFJgxd{CzB%>;Y zp}f}p=-spQcDnhtbTA_Fx*NXrZ|~6WlMJc!*j>KAP`LkNGNt_;m6@H*`5)uEecd{d&Kmt&4ycGt`pi!n2&IEkgSFU=sd>%Q~DrAKy8zfRfctjl0=PmX3wVUqsRx4jD`qkbg z@OzaG2m%q;F&I~A*uQ+=x0_;QC(mm?Xm`%QqqX4q*Dk8bFZWhJd_3$3&Pzv8M60U1 zf2CWN?<`Kx=83On{f2mN&_fU>PVK4MI(m8XM^iCDvZz5~b$t^DzV?jn$W; zn5T9o=r^JWxry9h_z%88_8;xr7o|GMHCX0-5@se^RaCbFVzBOA+*gTJRm=_i0To&c zjYCz2o^CDAkK2&bOR1>-YUKgDY4O>dBiFBAzYh9CZ+RD6jK5owW`yyx83`_z)uP>Djw?uqVB$s;5g3hD)3N z_VmAA5ra7WKCup`japoKr{1Q$^DWNLoZk?4hJ&n6F+I&-CR5;kycM4XQByEHb0O?^ z&Vcu`)C}*(7-c+_y}y6QC0VK7mJ9>55@i$C?Y9s_J$V=$M+lY|&^-)BChL5)=2Ak# zM1t=OO)JcZkAf*LFAwJ2grG#{%$ZO*Lf*I}ySkjh+}|P1@`~OP*`CvFa`2KE%*M+g zb(@3GXD7y}*F3lmNF!*F%IE9f(s>x`$=3&}VX4&h2&D_r;!dN8j%2h#@JZv%8T*=w zI>#=_!H%j1>wPzeBL6%ghhggqvav4<>DQ4eKK*ZhjNVff83tJ^JLV0ZOJU>yRUflg zt}{TH-LyV;T1H6}7uHNo&<+($sc6Qa^TD-stMb0agTot#IV*dlO&=9jABTtJMEtwR z@h2X1I#_<;NQN@ej)$b_+TToaB(b}NEXL{il+}YE;I})`_WOMWys5>5u*^0v-i(l% zlhXFoP&D2YBZd)sEI#ey{e4!;gF8|(Vd#>@M7aSe!%xKMk*MG&Xb~2m1{rpIv)cB< zSTgNo|4!GQDXa%XDM84vc>v;RHRxz^TPK*kcNt5(_a-*@`*B|Z5D+M}*I%y2Zh$U+ z>UfTP*+*JI1k-KJsc#y5vsJ~dT+qg%{)|^Q{8ew)yHl9H;0v@wcgi)(L{9-fW}vq1 z0%H}q98t}uNJUReOPQ8hbr08n8@{)g{nUUI^IrFuT=YC?D*2~_?}wAgL$nR*vnz{X zRpRw%xScWFt=zL%4v|pD2UFlF2%=}QyuWXOl#~Y@#=b_%2%05mZf(sB?DLyc@-27{p&@V9=Q~zuO|WJbX_j9%n!)b;0ZaQ;cBwQ%FD=S|$Ma4Cya!nc5|Ed} z0$AB-^tOX1mGQ6K|D~K>)93Cf@p+I|#N=a#^`rl4xV0&aEmeiV=UthI{c3^tZwNC8 zU)gyXQHoZaJ9shIP0BN{<@8&vNLK!*)UOn-+J8y7bU zY8h#auP+cVqajnw@_xJ=vxW-W&Co-AYMQ`nWRbmt7iT?TPtDYULcbKG=mqgXdf=XU zz6gDWVLXw6a06IQM5*;%gO*L?ezVUwuZ-v6LEX{TAsF#Lw)9X3;A|-H zw!_`Bp+vepTP(FpbhjP?Kfbb|;x-8{E-7hjT9=2r;5UFPl>v23?YH`_oG7(wWsv{V zt#1V3((CBqH7e;1$Voed_=qR2hw`xTh4$N!HoGsh;mW3NMFv`Q-1U@wE~{Nb+vlyD zedEt5Iob{bTFV*(<%*Uv<+}Y-=xeig)3M-5p3SE+U0q#?H5SeYbh&YyWPb)MpV#wN zDJ00REBH^E!ol0n?O#Y2%}u-(=9KorudE-@J330dUt!XHj(VLf1U=gbn;-R0FdY&1 z=z`{zZV0x&q>iSja5@6o?hAqEOQB>^4Zvfm`H1&8qNkz{b(NvZ_s&gD|HsaMHQV(F zOINSq{!igk`EO(S<_GCx@AfZZ;0_NK4hx@j4!~6rl&7O3hVP%azheGF#T2jJg8$Hi z__>rAmR#KmV{~uia73Zg>ymGI!@Cl#lax+)qwaRD+4%*U z%*YlX%*^rpK-r^mytTDMBK#I4_LhZ()LtX(+jn+ODeJY|yQ4$6Q2Kt-m*R=oU$RQJ#vNZk?1a|;nb5&^AE&I<;TLPGl9QeT zqB}!wAE@Pj@3ZX3aOL&mpw|b)gP*M%X@77}%*L%6_ST1t%~@E60<=-_S(G71KiBBF z>5g-=n>KKPU@ROcQ;rZuYP%Hq7hhE=V9%_%?Hf*m-7!f`n|U0nH*;3mK-N`r+a6N{6&pF5^tO#Od!g-b#8Z6g);l z5HLXwKGRp+;Ad8gz8E3Ne#!2*$n?()F8Ls`)0#J)I)X3^T0tdMhjq8Ei5!?s5fNb) z8)}abd#v%+N>^_i8-@kFAI2O9!O&mW>;M*AO7%Y#=qf0>XcX7H*gwb!NyG9=9Oh$I zSK9(64b4tVIy3#tJL-W<51xIMFil0A)3 z+rdCl=Hhg^D<$P}1X}qq+36>Ju1Ryu>f@pdNeo9BnPNskzxAPuL(G z{ea#b=X#Vd)mp@dHx?(w#N;lXY$k&Ta`;wVn&Z>A7)QT;QD7Z+U#96@>APQvDX^?RN$;y#?tbeXI=n%XQzvFc4khQg_U&?UyC1nEXR z35O~P50c$6we+p0r~puZIc#=pepwaQPHP8y_iG+nS21Q;!o$H_veVu+h(=52W7i;_ zp%8)i%Cmg3m<^Kh{QeUKeuz$w{vSEfnp>RE(RVx_nHT>KM%F*o4K)e*>e{z1H)XKf z$q1F;PQf7R^s8xs)U#%Ys%fK)TezEbb*!y4#*etdwy+u8lsy)SI5!Kj*x4Qkcm6_; z60z#k^M0U*DS4my-+mTSGg+H~@#}>`0)CZgEB0Oq$QB~IDsYest}90V57=T4EQO!! zBhL&X{)*&euCHW75Vk_7V&B2(lhhNYVA;t=eeN3g%V>;#EA8`y1V8SA!s5(#yG{gf zB6JcuM+D}sm0&CCpDC%8d+_?Z_deZL8urAnL(k(aRLQ_GG*w#Q8xH^kc`&k{tf z$YI{wD+hm#?z99wR@n8G5?gpGh_1jwg}l1<1rMIV4Sv6NdtZQX6hgDZHxbWMWWp`%Nr>J;#9gC~Ieyr6cW*j=-@(sU=!DK1<)R>L;PxNRvJu8z`Q zibG8S3nOBMk(3|6lOzK$Dj^dIs^bT>qKrby%q*F{YGaBRKC$(%IUXDwPVzgrl@X%G z^<;zz!&F#_1WfFXvl+i;gmWR+a10M*3mtqq<24ozkYSHOp*{YEf4o41I>(USy;y1w zU=Dg9ckr;xHP2`5mpnQi;($RBi1`#ML0sfuvPE^5q@b&bqO0R@Q;MBGh}DX>leeBZqcGQs+6PmL3AKpQmJ6mKoYzl74W-(!VH3?GoL6X&ZY1tY4<20A5vfWuP?`{uX~?tZ5pn>iLJ*z4>2GREHVwZ%~j*8Kx(H!Riz=ijZ<*A%XhR+^_o$Ju-s>TR<<(AFw2&I~)@>Qn z!pCP*m{2G(*JIi5BM#_LJ{LD^+-uGd84MN7vj*9XXrKy?h=N%>ZYxkY=zgG;T*)a+ zxdcWak$gJRBDW%2FAVto_c?8;fcV+r)w2pCQRZ)HY;Uf3>2lkZf-`NG7kA{d@{Z6~ zdDI(;I0J)?!N)`5!@e>yd7~^rFrDrOvT)ejRbdAYx4|{+<}#!s@>EGnw@N-d*8#yThtE1LU<$*WMc?GcbSn@@h%z=nNFeqV8!<4B|g0fs;`DfDTMI>T~-E&=Iq zMaJOotU=*BO1ZMw$=C<~^?hq3ZIi!R`aM`G%6NxAKS9j&*wJC=j83fvEKoc7$*}wH z08VBDN{S`G+xI0z?^bL>uKtG z++`7wFt(U=v02!^s`?jh_9&Bf7BFw}CN(HV5cxwzY%bf;PY>5pMp}6{DcfYV z^;lG^fcg>4Vz365l6ysp%WY@t13isl(^{Bhw6fH0HIOJzdn{y)oO^f`YKFDh?e4+M z7jKsWa!^z~q`nZ8)SoF9Sc>kp3C;@G?xyK2Ci?V>(-pioU%6X;NN@KEbF(_Z2J4pv zzVzOtN^z8T+pc_ju&H`gtDip*Ai?+{4%6;w^1j6z&)rDjw-Ywe*UMwT2aO?QYDM?v ziXpQ_7m>zpS|%vH;;TbzcA`t8n)<-nPA(UT{XJ!H9w5C_T=z5;HjZu%GMQy!V$mV8 zY_7zFWNzEMBd{|dL}>)1kPDAhOlN^&{0TqI4~Tzl=O)lHbb}v6s0HH=x6nD53STCb zaYmP4Ba-^ZEi4rvp$C{d#)rii)*azH-!HZJ`*%=}nND@N?*h1vFm`FLS(44;xU(`B z9t4Afz(Q_RGUQSXr-mtQKs1=SohqGFGbe3|dw6IpI*5!xHbI=JPhFo^z1x;IM*d(lGK!u3WzzB$`C4M;7sTbJKvtLodtkZill<3RYEFlESY{R-#uJ zTM`TWk-g=$Wv8~}ST4w=vH{Uh?5u>|(4^r+hYS_M%AoT<^cB;!ZS-<`U+~*`h5fv= zVzV2W!jEtniE62B(y{d{N7K}wNqIR8TI4_6k~AC-d{=>-vknZd8aDq0i#VCdzW*Ef zHxD`H-8~!imm)3INBPJDTW*jz5H~n5VSlFdB+$G#Ny#KRui_XS9c_^ZyVD1zluW!( zG(+(Ut@?yVenYFRIaT!X7)_vw;GBruqV=C#7GtzEc1Vbg;tk)cohFx zY-B!5@MGAYiDVvOX7bOqb5fMxNe?IfF;R{8q+pl)ykmIg0i8F5poe`G^nKzwJ4S-N z#=GH3ay-jo#D6K}7n6ZuWdxlv$d3?#J5<*Ft=}tp{kG3Mi(ihOjV~I-k>+x9NT);T zMp#J5;zDIDeKirWu2aN@>r(yjvwc%u?_wRHbkCm_L7*?p@cvI;{t==aqHH?Nlm568 zEo&-bm-Y7Bz~jLTe-~R=@v=atqH-rdJ@dxd=HqAIhr=AkrY0`L-Cs&rZS|L%Yb#Cm z>sX>zE90DlS|j+cn9NOUlqM+W0_de0=1*8oUv4X1A<<;JY2xC7w?~uY+D2wox?WGp zQ>oK$Ro2!6q+kA4II9}BT(F%Yy2J-}IF3N=*pduf2c*UBBq?Rs1XVpRZYyQPqjrTq zSMy^7%NGzaGih^lF1V&Ls**G7{T=tOzu7r#ujPj6T4>G%ICyUn3G$T&S%r-)Cgf3| zHO6Xw-bOEB{wzutN7r%_`1VxZvlcW|Bx+JWtE?o{dq2-J6$^IA06TP1p=E9JvxyaQ zTrg_0WTzJ(Mkc3A@y)f+g-W*pr$@)3?fj}JG%P#mJ}Bh;ej!X+pHP)hIs8VcJ@0pWj%t8-5St)Ie1v z{jub;iZ27N|`5d*~FD5QGdkM#6 zy`jhj$eyPxaMdmQ31RNE80#JzIdo1t1u!1&TRwR491Ld(z|)<{KZRh~<&mf{UWW zRd|Xf&$KTic-5?D|JvKg&5#yIUexfXMA+*F(JsFA$R~x12l9JJiy?nxUBE zhcLilfBX{18cD0B>T}<<^t$W}F#2`zUKPZcUlHRrD<`whqa6%J1ooStOqhjr*?2a8 z^-0qQ$>Hf*@7BA1-VU7yT){}nT33 zXDWFwBCd#6!bMe!TL_<+q5wLbB4FOgS@TTtxP*}{QrxgSVCW(z$rj6IFLCRw5Aw$t zK(csQIhgt)`g#mTq6%Hf6-=@<5l)}x1J|X9doM);B=Cs~>I2$-#;BVy^WrjW>X!85 z_r9&e6n5HIw*)(>8IKIgFs+Emi1M1kF$-)J6ES|$R^kV_#=WFw5mu6g9F|ik_M*e@ z^aUbtcp?2EhOlI$26(W~3@uRlGwWarBkRHB@A%LuMxKz`hv=r^K8NK^Ze% znFen%Gq?UC(w8*cqJIFlfQ}{|JXtEe3q%;j;n8&WtgO}v3Fx2UXQE98R^xYOx#pZ( zq5<6Cqb&t~6nA_sRGGZq>EZr?bMy)_fF4Zgvq_tCrX7e2+++Ti9M^I#EnaTtptqhK;PBRpZDm_Fg>Z)hV^a5lS9i4v$r*l?MGC z)NHZ6+;(c-cg0uZg7zh2a7HhVICK{knfk?V<|5v2t2cn15y#gQ(p7y8*+Q3^#CX-G zV85|Ak~YRn3wa8)mUwu$4%WEr$J%PNI$^a;B`@T)ZroSvO?fYB5V}@$k-` zbq?MDynksd)h!ZuGToda9D$On2k7P({4K2B$K!gu*dTCMdC^^+YQLl7ffI?I`VgPwtu8$?0pH z6Sql=!x+$qMvr7=Fq7a%8fOoFh*`R+yOS`RmFDY3lWnK{=jAft`AtIXD8Se%?-VpL ztTccls;guIi$Dz35-PF9W)9RsvIrH-0jiS^ib2m?creB`B@;#tMg<|TR3$kTkd_Aa zL7UJBmQNAwxI68_*HYV;)X|<$k(H(rQRAI;L@3WDEX`!|N+AN5Mw)(6 zq!SS6+>7`eucU6$$%bpGo!Wopey`rk?BDucrzG#$08=2GpmODH;VGq6NiFk4!+I3h z?}yH@{NN_Kvq&-Z%lUs+F?T_rkc2 zQW9Yat$%9FRk2gs@*>mo=a=D`6+!#vq(DzQl?BTGy^UL(df`0@JGQ9j%{bZp1Lip| z!Du(?g3axq#oO8Bcpe3aUcO_OE$?sd;3Eno`|Ia?bKQ-DGo0%WRXkbQ8)D|Zyx5{o zEngBBZho^{Z%DR1h;Yj|!K>-If{AOG3JP@5o+fm+*b2%zwstuI-cjcY+Yisg>ur!Q z{a~A^zSR2d+}qsvqjOHB0PPDGa;;Ek@!a8btc273Xp?E;a7(dSQAf~t+sMesIg7|d z1!t1pZ5F#RW&rOgrvOj%&BjP>8jcG|~Qo$~H(jSoB6t? z^Wu4Vvbj;s`G9evn-IWb6s1_ghqZu9UdjtH@WTk822O7Qca z8@Ki2vi*F?WUGuLuzr_M{~k7Nc2i>@5n_4PTGM1i^7QpVA)azbzte7)!N`*!fyG41 z+uXzM9vc6pC0QQ`de>>vNmFqQf=Y!@_np@Μ4{D7=6bjbj#)lo_TU!BL}J z8UIZ2Th%1DOK+pY?l&ueT^Gs#WaDZ_UiK=x0T5mNWcg26G{do{Hm9YNWp`>tTEaM{O=L0DH?fEn3Y8-elq zDJ_)+lMRDdkr+RO0bM`@O1Ft;=X*Y+8~JUgeWx27YL z4+q-_oZP|=hJF^vFeMh8>>%wp4<(_Dq+D^xAsjo`V~cvUvlQpJm!AxWdRB;w#naAt z=d&BJpMIPDh8;p|_+)#d*}?mxgNgcLlpl;erZ1)nq?*l5o*?1!q)jL!9*=PWWUv+X zkTKR~(j;hoYehEVox@sJD-uUk+)h6EF-y3*vHrx(cRJ0M)DxhkFIm4ScGoL%;=Yx= zsYm0%(*0bj`dS|%T>+j8cY(&g1d=DDyTHQYA?RMLQ7naejdb9JNj)T600;?{G zogAjaqswipv}8Voisu}Hm=pq&Y?s4y$l9FDRTR%h^^JJi+Dx!FIUCCcEB@@L5r}<5VhMrRpD`p9)z9!diCLbx%)j*fg`Zkk8*f7k@o_) zZGQ1A+%UXWpKyhVTRH)x0a5mH(XAEU2y>tz%*l&M`BR<+R^hka2E)?ob{)rFFPpIC zO~Dc*{V5dn(ZrV$5vXYLL@PijfZa;uT4U4gfyFDsv6R&-AwAq*Zzv5&QnCA}6QoMK z{&~;0vnyho1GD0{ym6l>2A?UabK!2wbSmYe7qbm5_Bjf}$gl_tao!_TtAAo?NO00VK;tR?jleHS({hC;+_9>ffB&KBQJ z@3EqDW1Ht({o5D)4GUBJMMn;bgYW^!i>E9i-wRi$a(_`r5aix{{ zXV(xSBD~l^ukA^+i29nXjJefDzOG3mD*M4x9FV#$(X^+*X(7_Oc3O|R&V$pw)r;Y>Aw-CxX2QT#x%zoOn?`mTl=lt!1zIm9 z>7JKxr2P+9ZXDDN1?zZ%HnU!sj6KpR#%aU^9!CJyMh3fLEL=qfx!iGaC?y)c$P{m| ztTib?E)Yn-pTVb1-9}_>>AfWAaV5&1Qn*bK(rmfdt`HI05%~vJ*!9rUk+6S9GMtfc zb*8`!S^P6PQpIaVA=&?~F z1mVsMoiVSFU&gS_8SM_8?UvA0cbtiT;=TNI*Uxe8tdE<=q{Zqm>vtlQ0i-#Z$KsJV zh59-8O;>M^!aADlQb)^(dY~E;j*wk!v`6bPf|#I_0|KF$-~#ennp?+06yYA1QwDhf z`7gBUD>&IWp7j$L+cX|nUzQ9YGg1813v};Rwr>KdwGcueKIpJS9qpZMHDRWtLDAW= z#MLiLy7Jtnw{XF8l2G`RXau^#wj_E^+7srK-K}^##}6PImfVrOlLesK`J4{|9Tgt` zAi-Pe#L0wFKWovK1K)`H^47R`YBcHZjI$HcINHG)4)R;ej3V+LpkZTaTqVD}5&Nt% ztomIVAh{M~1qM;yJjQvGI7i<=+R6!pzc4Z011YcLol<1N&6I~SkvcBl%#A7?0;i~E z1T#hXPp{QTGYvD0xNdJzoX;Z6o}A{=R^FIMS=Pw?XPxE7I6=|)1dYY-oJM=+pYo5K zWz@)Ji?aJ8`{M&pM85bO1*G%xEcGm3?km?WKjEQ~p5~-fG9T7m^e65+AQEyX{GLQs zAWn(1nUAG;u{U^kY*rUtVIN;(=IPc0M}O%V%Krl`?U^2H_I}n0q3!B81bj*^Z0++4tUyJ(V20E@$5VQc@N5&;{brN8HY$D$6 z^a2!--T8s?tD~0<}M7FI9EiC7w(4Rooha{vrGDho3wW^DhRHNTcDdT?31BspVQ<6S! zZDqaX2*l>ui*RCNKThSp_xRHUm7cO1;z0v(D%3~d@ldnARkSVC?9drfy#GCmfVE~| z9SmbiLYwXmcfZmFMjyim^@Bp5;`BH43Mi`YMKSV zB%dJ`1vbz=8cK~poQ)$$5^K*})Y*7uPENv5umJcn!x57EJCGO= zrtYVX4!u3yBH%(hJ?;?bTi1R-7EJ7Y81f61k@uL4FavKSjjbkFf})Av?nI-?|BnJNG zP|dzK$|v{LV}%i;9I)2uMz~ixCy#2iiGXqFTyjp~#t3BhdR)k%^H+3BWgRZH>kFmr zw_@RT?(Ov&c(R%6og;5HP1jEtgps3QLIz0i2p5r2>12LKq})h(LflSC$jK2jFp>yw zh^g}6+450zozoFhuRUWa`m}&SE^9h6ur5!lA`ap~)t>x|44RV&{DhKS6?s;@hm-|u z$^{k)B=DZGp-ybld%EL(Q)7D%JnXaKy8Sey3-$G7#KbFAx^!_4d}#?e8%NnWd z(s|mv=uHS!3N^OTE80NC@0bk~vW)gL+Xh0(JuCE)WPWC~>zhU)Wk0CTV}wwd(-EFX z2UFgd9Ae}uBrr|wS&F`L7-S+`kF$fUUNb{Rl-pvFMImycQ4n^_ATwppMzY% zWS-V0ViY(z)(I)t=xCG%qI(wC6nC=AI6TTBtT3m)-y7IU$iTHNZcUjNq$kU#xPglo z<2A&&dD*!Gks*A1?Y~2*mgJ2dG>G#j1cOFmGfC&%CL{*tlr}jFLkcKj4s+;su!^4} zOF&3@VbNZ2Pmzrhk5+8|3`_y$B|@RFOt((~)iU4m*E+OJtA(B@Ax*9UE8qN@#$@a? zXkkZL*!yS0L7JE4{izJV&>=_7pLFPdOLa&J=0r z#q*REIi3=98#T7ZxtsGhd%&Arh`(e7h5Lxsm3J4BHc0z!7s_R%C#!0^qpB*?ojO;k zZgJPX6%HIBr?||k@*S)?_SkQDzLN0mxTEn4RP+S5I;w&ZwGC5bkZQ!l%D0qAgTf&R z)_v7H^?vyuALWoNd|JIChYr>pJ_iDia#q1cRTSh~1e>XS=>Vypv^MFG0`4`to6=wx z_b9ZP!U?32IPZGclrFHbu__JrUVhhX)RK67Y;3U7h1rnD@Z{DJEaIEshx_G+PE5AaMgXU*t$Fb;z2~s&Z2V-%E3nVHP3;XvJcUorxi3zuQqvgWZoCo%og_SSFC-ffUb()f7w8 znTRMPNSL#mkDHQpW}G~ul$rL_yd3d7ysqu2cW4J5P?wfounWY?H7*R2sY3j{*+#QQ zkD4*^+p+CUcL3Q>k#4x;HX1qaL^9#HfjHefM~^}C-&Zr>@0MEk*h2r3-xdTG9D5Xd zC_eoUQ|=d%%}!1JPJ$fJwN(Gg>>@H9{X(CV&C7;lP{Kz3c;sH(aiuhFJd3*8pzg?9 z2zx2rF*w=>Uma20JFNYp4a#BEHe{>qx&hRX3&D%2Q>8!@P)mlsQ$DA9j#)gLZ@B%e zW8=JF^4XA}63E7WLPrTt>=V!pqll_V+K*5t0b zyBN<6bbKsDL~}i&XhY>DYZ*4F?Y3c&_sg9)w+prxrh(m>9}XW1snSAy`-AECDZ7fD z#r%d>IW78p3r@rN-KY$D66oovB&`kl4a`J5YbGAg`zqUQb+^GO223|XCth31nxs-? zaV36N9|Esn$ysiLWoO9=;RmG&l8m#5use zsH#!HT~cjxL-RIeEsX(X=6CwbWV>NDTgj%V(NINftevWz4q{r@fG#M-(W~*gA5(fk zMX=$0mYbNmYOK>1XqWn7jL|h5=oU=u`WnDHoY7vJWY2X+Ng|l@7MFHWef8GhcUNYAZdMZF_ELKnH0W=NSu@Q6eI8D)Kf!Hzx=1| z9$UQo}s-#gl3U5<@r1VA$*aA0aq^p)K`vm z*Dl4EnJuJRQlhQ;ro>q+P6SeUL&ZR$`>b4KoBcK8=HF`|uL;ZkoUlVi-ZCS7Ot%HHIbQnZpnlA==8&^2ODJSXI(US}ndgJ~a!(bMM(saX56q?>d?o<@r zzoDLx=bf&i8EX^j2R*gg_5O}`j2|c9d42QOpmY)MtE>hjs|(utsb^+oul$Q@S+}vq z0C^0yrxwAx8(aWUm` zdwev|Lp=Z{4|2ye^Lq83`h0eC2ot!2FK}&|9T`*lRB4TJDI?NnP`8#UPa>=JOiViwH zObNr#=LXaXk0xto5-aYEf0>?&+%aNQ3>07amG-ka^>{ClLK;3_)dN8B^7G=)_jF&G zq)%a?BP4Rbx2wfw&I~)J=56F@VOFsvtWa4X*Y%MugrQbcmaYdVuM^YGR)%y&imCy! zpJK#yB%geJe-$xCidWvpy1B}`CvgZ1I}8s`n-E=KI#BQ*T@{6juUR!wrCerAlM~MP zlSu*KlB0?wCrRA^DQ#NzCqMjSp-KCHlDRo4vU3O z5&cvQf6A`>PzBSI1HWHEqTbi9ycffAquABoIZ0Dpz@}IMUH+hJWLH||$b_EOR*ZfI z@21$C4C&{FA^NA#^c!nXy_iPO-b-Q)F&!iZf$45148>*85n6J*d!P(WU+!v=TSoZg zJej+34=m0b&+qygBEajn77hC1wtBtDbs?RV8;mY^CRw_39-Ynt_;;9*CzDD*YbUIh zH`$WB6Q9NV#~cqu4PwnC^Yb|D8x}#p`gI zMD4`ueZ>u8#B__Cc+%H&dT!j2A-sWT8O03^B}u1T<<*o+1FRK>{%K{wL|Rm#(UJts zvPo4>94FoTl@^OuddOC?#Vs1edGq1=qZj&#gz#zCb{j7`iB0ErwobjaZs55A=YJcG z7k`hwjdt!l1Ragq+Vn2K+%N6_32IyfE!uYve9vO=n7fnm2<2)YEqF&dgjpDBt%F!3 znN*0XGa&*R-56d7@@UM|ljc{b2^@#6aqQv4ta=l}_%j8g_Paxm9G~o06dgI0;!U#X zFW9gU)09{ov_FK0IQ!VtQgqYBs9a}k9xmSm;@Z?a-Iv?`PQZ~!@XCpLyxg8~feED0 zz@M+>t!r|YVOn#IhY?7DlqL!E2OijE=v&HtjgfyJWG=yS{x2dr>!I-Um% z>;gI`bp^sDKO>nrdw3no%E~AA_Fy@=xmf^hD#rg0b3u&0hZ2uPoIP_^j;`@&92W$5 zbd6!T6NxwRtU<@pJSGWT0BAVYBrDOXXQ`#76=`CXJH?Q3+XaWvnRphVQ&yf&J7fP5 zChlL390i=Z7Of}I?;}T>Bc5U9A+YCZy*pM-QEBYfE##4;N!T)#)#8AL(o9=r|Q15h9DG=}y5ETd$a*Z++?-kpffr|8+ft%*u%N%T})26 zN+C*GQAkbAO|k^eQ((=B?IPT*Q;Dr&uT>lThl%wTuYGGM$1{=ILWEH2A2 zit`uF%dMPTWT4_z3b2R+`w8l*X=uc1cCcC`GYGe1wya(Fy3*4v3w0~E9fw1;)q!%; zq-N98Iu^-5Se^;~k>LKb4k)0!JzZA9dXX+rHTXs9E%Qb_rrlTsI5lz_J4atI522@s zx2f@RoClMW*lBu0ggU(Cjk-_8kRKBkhu451ybs?Y9bA5GV}uL03`>C&ccpUiK^Gvn zD~T8A@N%BTg(tFb+|t~NcmV)!c?uLr0nP`tzDk|V0v^MK^*W32K1lUYAX>&O#|Eff z;Kc!24+LBCF3)EU63b@bhNV+}47y!?M$;r@Pw>V#2}Qql8Po&)rCmAJ5^6=RI6C zJtw+2mY_3leSO1r>cFQRyG}Ww0dm5}1s`pH2k0L7F#!GH=jKP^Rp2Kb4%Jlt6(CLB zBx%P1b(0;RksK*dckP&b6;Bfu4VpTeLK8AoQ0~ zUlNZxvmMAdos%&FAef*}NophNPn%D36Z#E2J=oDIJCh((;!VsHCUIvJ^))r2KcJ9F z`UEDT{Q=*-@f66H0#a9Pz0DVdk5~N^2zd^86!{g6@GkH#N{z%Hb%8#fwFr3*{ghOY z#MHEqQd8!nghgVN@=1G@LW2`KokqJONelCkR4{1Ugw5SYp}}|Ku}0GX;Zswv)s+G% zI{{*aKuG-XXq;9U##J2E4&kMFiH0SvblbPAVjQ-Ox1NJ zbO5V%DKnccjU>M)UvcqEisOdK_dN9J$>5r^kPN1x7X}$@5)4g$B?Ovo4omW*Ksp8J`N?^lMp^l;j)EAtad*% zTiaV=^Z48J!)bFKVMb1m$V7%m9jNb4`VlZ%;w#rq10UwawVe>OS*s+jZY-Hsemc1!t9P2=ByeD~=iSh}+7_Dvl;k&9XMb)a%lmkR~t^?cIOhi%0sCuvGpxbeb<5$uHG?x)So z4d_wbHjiha===VpY47ZS->|@y(+fx=Y;zHKHCrAY@sd+O>t)K=A&XQsUKT-pkSe4A z%a6P*w%j?EB+sI}g1jVR7|$J3M!b*AXUPRgQA#S&IRS@^2h881pzg*Vb(Uya!1SZ= zM|&9C8F3XGN7&FosS%hgbmu6X!nL*)CUM6TVe6w|6iz<2!jPR-z=;AS)UbR&`8YK~ z0rC~rIeWAwhRf7QK8^~S%1^S*FWa=X>ulp_IHr|k()lIDp*wNOH*Pw(nfzku7G#fB zFN8##SWxLIuW6<-)+q>*_OKJ_1zZVD#oMxKOhFQMi*9Xh$pnMDk$A%!g-|>y@y^Zn z%v*2YF#q+hzhQ3Ncw2->#BCDCCU}Hm?!}kPOE0}7=r-f#xNaPg(@6(~NIcpsmo(tG zo0x$8Y8k3+Ju62~O<(Owl&Ple?E)yk`jt%=&oIgCpa2AX)M}tW-L_w+-cp!E{>g{J zp)=5Thgb8~TW^`R);8h!_wPfHgvEg=EC%%V_scQ27U)dc-NWL+_Kxf%upbg7z)G+6Jo-tQ{A?G&EOHSW5>A2JKY;pR*=F}$hxA;>WC04CYxm!Bt;7>I=FXn zbp5#U{5;TSq`ibp;tx(+NTKWe&5f%t;~IT5TwEB9pN(zPcYCpHV)-zh0-gfppg^|m z+vN*7nSaxOe}a zC`IMYqPutR$fV-r$rG|7%_DJK4509bHshbd@i?vt^*--VNPh3#aYesL2t?rs`8H)bB9e|aA|^>{hM!u*_h2%**5 z>UHcG;LVDk+H6fb6GQdgHI~& zvI~-k2s;xNP`1Vnw$Z#J9fNdAILeldu`tqy%qC1a2#ROAFy605DZuI)sed(^6OVQV z3Mg+PCV8?ffAo5xan2LL zaPi6adqc3&6lvd|Qtr zkaeqwASoFg@8c;@Jrsx=(4=4|gB7^Q$R)+ce|QSyOo62OmTBOfb3z3~5L~2BoQ6?-%A(-GrCnl00e$-#TOKoczS5ujmI?o=yr$BvC!1Av8%2RS~lvjyB2)ZXA zvavTILwHY~`vQ(7^H>{o)@^M)!>*x6X5#*Y@a%zsLAk+=mn6usv!rC$l|;r-!kg&` zKOTuA{PvD^+1<2<<8mA5PuA8}u>*DslRW~qi_OGWgh(+klakNbJ%Ve_@qL7fQb7CR zI3!9cfQ(DfyH%V5N#jE<5(__xSuAEf$yMlB@r;%T0WU}@5n(;p`k;W@;YbG)9YEll zJSK+E)CU24E()eVw3A|;N;2vElHwHV9>p&Sp4%2Qj&;LIHFg(u;>u?#!=|2$A?Q9@ zT6%(K8G@vHW_ET~j=FJ0x)nM##9*M$c-+-Qfs!15fPOn3f$Q(@gYKn1DA+!4-otG` z@4WL4jx@Y4LMiG?;%#o6yztf@-u8Cw+BI2`=5dQ2-UJ6Yf+OI%xJL7!-?XEK@nYM2 zG+>V3acSiU!Uy*h@DwOJ1;`DABVYnSenCk^eVQnb;D9eT#qZD3DI4*A%at37O1dV>`&%S{R4K2+r zvWu0+m$^`}31JfTFNGH^06!@q7R_On&LoR#>bn{gmsV8e%K0Ezr&28kgVo_#4;M;G&PqM zk8p)35b}u%rC(^W#9upJ%?rP&M4LCUoy5+d(a}*nBO>IH<8HGvP{8`Y+{4bKk&#iE z5O9T=hA_BNeGJ#Ea>bhhAo@|@)QIb*d5tuWt#Ku~6G!Oyeh<5ymY0`BIK^)sb6CeQ zy7jfEvYTlXyP^gL2259{4Nv?m&a~}lKyg=k(BE~l;W<@2Jh;#}-mYH?NcqPM98+=} z@O}yo;AyIv>|Epf}oqPZhKQ9eRHm%l{A*1|XO*F0#xxJ!tF|B;aq(OEZv zW5?VjI*S|C?qgTdFm&H_<1&V!p#KH}N%*;W}w<&9?cvm z!1k;>s*v(``9coKrv%mXivcSIu=5cITl4P(3nxVf;W^khB1EDfi8rYY3=YWcI%jZ; z+e7ReTEPl66=ZW#@#dS~M%X@@0tJ=5JID-@I#kBxsalyc>O&Nb0?Mo60MgH`1L?xX#jiRyPIv;t ze33u%X$BAPfMAD5nqPV4Wzm~Qe$Qjayls<$Bpy|ctNt#11hkVzIHwET*jJF3A4k8@ zhn=d_$@dJ$=qO0yVg>c*vG3t6alCi|*aaY6pqc}3dkP%vhErOwK8E#99dob`)#n`I z`kFvOevSFtKr z2-Lq+f&xhlf--9P<1E^nx}<=%`9tlyE^~W0Q=0$7KGr2l7q%7dB;r7R@Wh}wOFM~JWx2rBMrTMeTE8G zd%AnVT}n;OO|tsU74QcS9+)|-f>Wrpwzeh{3<|fNJ$nYdOzkoWv1!@eBign#pV9m< zml`HKk|E>F!rHvTq#c)L61}~9l~MrJfqj8aTwN@E8N1Y|v-boxz&0Ii*U|5qrUb{g zFjBWs@0*&MWg%dA_>{SN^{SZzFTVA`Ezw^@-p}L5SFc?)PqACHh5bXY6ZKHrh@q#_ zjctpI4b+=Q0TOqc_Mtx@-{0Ka6hRVi3uS-M*WZt@L=aC5Oycg1rvU4pH=Y88P#~_) zF9cpK$1SNKNjm~1P*US%xFkP~TPa&{Q#&0V(fp-}n+0%-;*hXzSCp4ECnKbNw} zrp>3LO||kg7w06Nl?(2=qlhcP)T7ab;|^z`Cu#n|McE}ZH8mxJ{`K{zW_)Z+6lV9} zxI_D~c3C~|==0g{Q0&bZU1D=ObXA~fBvaIP)#-eRF`h6%uEjj4CoB7A_VDkCr4dBh> z(@?+N&l@+##=(E@ijZe!X2vWmEQlb9x{}VFJ!ei}f#Jl76X8OEWMAk>7^z11ES<@x z(FZWS))p&Bq8>cL;evtgc;)UV_9!w#aR`w(AsHDtZ7yEAXa@QRL|?|ucW;{Im1R-Fy)eHZ zM;#tcJ%l|2Wvtt>tBDg3?s8(g<-~+AT|;+1OjjQkw!Di#3!x9sd0Y?$y)zxpQwk!X zkL)Q>A_^$e2lzC?i4rAVJz#?_PkE)#0`%zZ?G?g|g6|JQAJQ@|S>SD&Q{eX#xOH=K z;v9HzGxRB)gsvnC<}D!M^=WcPp2+@IZj5VeksV1xCx_&=IPP>^SX_`DNfacFo;_oB zp*Kk&lZOZ8l#Zu*o|}gF-pfYyLk#!2?f#(T&e`cBZ)>acnyZ9=y2>!V;tNbC6lRMb8-O6h~A7o z+?;kA!k%-`kHOVw(w=%VxKrqjH{Ku>A#iHL*0atQm0b5A^trKf=0hL)knHBS;l;dpYd z=&d7A;jQdG!Bj(@8=b^4AbhFYj(siIz9`!sJ~b@Ly>H*SEjpQ=JXwOUYQkK5@fyNn zM^ctX`j#xi`e2>{*-(HyL3x9(U)fNsy2EhH$DQdcSK(9SSu}Q-Xy54*_6;c>fq(s5 z6&EDcKZ$(~Jq0`ks)Yi@=;%dYf@|x!wf`s>9S|LKmhri!KL_&M_0!wmXHIQV(dt~i9<6~o3$?k(N2QviD5Fu}QHm|<=Dt1XNi8Ag^D2V0c1nQUM zcm{Fc?Qu*;^U3r@0XV|(*q$qBB7WY~4+XT$>nBG(C&i=yg&9^^|G`ADnDA>IRx1=? zx8PPaD%PeT=_zi}oSd4(!oefxubTj$KQ2Q2ee|1h1X=|10k6dgV)9yirSN~!#P%us z!khU`zCSz+LDK0Fxs{VQw=FF_fnx6o?1EY{`}pQuPkLtlfNdW*;N2Tfff7@Ib=Don zlsGvLzLXT;*puU0EFPzrkjaoo(Z`0f?x(&jsNCox?ftr$N) zZnklZjko*Ux^+u-Ce6&uLgDt79J8Ps^=iz`&zZToIWsms2BqL+Qz^!k}ED zKt9b270B1uR@X$ScY7Ooxm5x#{fXkJwxsNTJOxTaf%tm-|Fier-;v}-wlL_u_rB=5 z*=~$xw9@K_@9ls7&e6W3U1>%$(=+Ya^xk`K`nxwWBMD|#u?))>vb&fL33CAifIyhc zq~&7G9RfOM@amfq?EHCjOrC+>s0Vk_DLF_a!$%R&rK~fOh+(EXT2N`>3d_R1E8=D*E@aWKdn*Jo$^zin>(Vv9rRO>H1=z&NU9;g^% zz;r|fgUlp9Khf%xVHLAz?^(~Wp7WhMa*KepE!3f1M_Qk`&6!KxA&~zFh_onZJogZ2 z$BxoMWF*lbHtGJ+0i=^|mpn!i=q?#TlqTiEi!_#psIDQ7@WDPQKVefD*>IqJJxZdI zZnK{Tj3l3#)ZEl89^8Wd92!gbP4F(9pu2YnJOTl2S9*R#RPNIPK!Ejp_p>|@`*{}$ zcSvD^Pzl|;SEML(iSG-s?c{`!bPvo7++?C6bYiJ->wT<>x8G-=h%U-3Ai%ngRgYZo z#(I~9thpp|g#hQe!SCydZ#uJ;>-MFzE?$}L@<}}IM#oBcTB9eO-m6|iyB1VQpcE1f zZ&M7g~e1`X+ zSx*uP(nvcyJLcW{cjn^q!t6jT;>qL_QH`UaSniZFKdfVsI>UwFpjCZWJV~E)fCuw! z<7Hn*doLfkKMnzhK;9#8N8e&+HQe80hb-1NpoCa2Q3|!WrP=iL_nFDbNl_)HlZC^B zLs2s(%`dMkHyxcFrn;PZ#UQLcO|@~>Yd!mXB%$qfb#*dcw6{Yt3C@!Qnws6Qq3$ ziKh(4uYJ6|-EQ)A?&vHTMa-izj3mG4kKEm+WK%1cQ?*!Z^g+d9>e*BC{@r`??%g{` zC%q9#sWTYj{yg(p41d4DvllO4nE&(t{U6xZxRsrBs>a!>i%gsUIU$HPDPW$x@;^)z zqG6;}nhNIntvfpe90I8$p#3t{KA7rvspmMqzGV5822wh-5vt04y?y4{vuDCU+TGtZ zTVUX?uCAC5?|q}&aEwr01yv9*frP61G?Z~Eo?0(WAU7Jc5lG%?Z+!jb9I3MJ>q9Q~< z?Cj~fK+pEOc-Q^sSRm$|zjFRyOR5G&So`|=%=2f@g^{$pyewz#PIp6M=*5fY!ocAo z!DA9xumE#m5n{{>d*n|KhsjuH$T`$VU#KGYqBwe>m40* z_T(|s*-4gG#L8Q&=b6rbGVwEyEU)I3Hl%KGe?$Fn9DSJZ|M|xsMXhZ5)3iA{J`#ow zC6!i|SIuZ-)HFf8tr`mpjf0DIS8L)2C0&OL&5N@#2**qbi#)Orm_{Smace zR|(UJJMRG_3FTy2C4DB&!=D&v9=(UL|0WtPb`0*#V-O(z+J3Y>F+R3GG6`vu>-_v& z>~b-z)|bD&jhVC^SIj`}MRpL-zNx9jn7nJ9p-T%LiN{RR@EUE&oo(98Yy9ZNtrLtM zZXnQB5~Y-=(){k-TQfQ~25F@wF#UZMH>krALk~xf85Ipvu{Q$3%Dz`qQv+sym+8T{ zvbDV>eUtI8L3Mf%HuBhCx>AqUX44h7 zizmAXur4V{&pDnr*P#Kp@c6+jY5&)AcC(o`sX0bc-c*IlNTDDg9BM8xFrjgWLm(3f z6jIw_Uc-|p$v;%hz|VnHQiUug>an=^0Cl!L*h{*Yzc5=nTZYm}3vk^$8i|;p;d1f% za}Q6ui|KV}(AM;W@A%$dn9xpBEtp8{?QLSC=?323JkN4vroN$GCJO88Yi508-R$h{ znEiu2EKD|`CUFY88&_gDwtui6y}jJrz!M!O6_t>1s)D4_9U}<~PNo-RfP5#-toJZ{ zZv}Oi`Hlc8_D&)RZQy>@#?5`WZ^Zq;1;_~ktS27YS9u?giKH2Ib$o{#@e@W5Xf9RU z$jIl0!S2qkS=t1>hcqZXcdD%;h7I~usBbYYtrtD>Sv9_)!R>w+_MV;n45_3mFscrq zKDTOicX!PtqzCQ8t4ohrrFEt8>Ddk+_u3}*aRa*m`G!DBb)Ij9aQR6u0wLPNHWIWG zc^3*`rLJR!^(e7RMp*>3#4(Z*t8N#{A#fjo*fiySICod_2&6p76cBP+Mh?8ZmNS_y z)xa{jn#3Sq-`TqOw@%xjwvTlKDToojdWQU4*L^;2j1mF=F&0e~9i!0{M9r=ww&~90;aSjHN zpC7IW=7MobT$-;*Pdu99YB**K05nSfl~&WyK@;d@4>k=(N5{;{%BuNr{ay@iuYqy@ z9=4K5PdOemVQiqf8laZLrs3fF46w3)&FUenyvD8UX753n(@WVRupbai>@ zeafzkco`?v=d?a`6Chgr52YW3R}$gJA3S##C5u4N2TB%!!Y(-HZSfA$s9<`a!Et8Y zKdSxwcI)2GpSvz11Y8{#QDugU;&C>(c;L?+4WzukZaU;zaI*bVTohMz!*pxZw#msMY%iMImoma13Li%S@B!RZKx6R_xqPUFy{=4s>Qg&kM>g!?T8jKnq zq4>OqiT#xU9xFgDP+*1|1HShiRqgnW#tPt z%fe4xai+u%`wZ{-^BC!0Of48ml>9sgQ|C48C6VUSJ0>MP$&{amy(D_btgEdv_1Hj= z?|fJ^Zr*CVV)&kJx$&$Canbe?y>pUTMB00HekP2n)#%I*1m41$1v`22qc4mw0n;`napP{Yz`67KCfq`1$LHX6BG_NNG<#so&EaWb+qsA z1qk01$>hN?lEM}1?i~U^KncrZz;FZ0W6;Z=Z>2578$t3XySdE?2Syt!T=SL#EbUU% zV!=QgNK`L-I`vd0{xp!vU1WN5qer!8&!5TSfZxy_(N{;D!B_iTxDU%cz6~!{n6H}Z z8q?j=ZT{mgf0l*K^z^i-+)-MJj4rBN?7)3BrIjvWe}j@#lvtus?hY)3X!w;!kYA*u z?Z!^;tFpKU1&M&H7yPElQ=BGQkY#k4b_gVefYMea*|;ZdZ3LsI3$%44GHRy4uwMdA zUB-{}lh@+e4U(#qN|J@x109OAloFr}as!$y@k52Kr>94*NpmTcL^ZdQ(-Tu$Ukhed ztv3iMb6@k9RN-7;hd_J;*#6jt^&I~T7a~^($owpU#7Sey;kAupJb%&1htRDA;wsi4 zm5G8`tN=Vzu7YnIX!YDFlGguFLEXEIA>jH~#-J^Ui1V@i#H5Ql%IZ0&Ax!@%d6rH&atn<^V36504Iok@WG?NAcRm9p)!bo`{rB8C4Q=rwquch*wz#lfSy_Sc*cEdH z7t<9mCjJCApITd6Wg#QBosfj2gZyYZk{6aEO1|y}IqQl&AY za&;XOnzXz~wJy_=cqo!$uIs2cvm=nU`U`26pOTtX0p_cbQ8JQVilc=^NPO;t_LEUh z$)xd#ap_23U~7allmDZ2EXG|4dQJI&TiCwiB9G$*8A+6M;)cZe#kr`q@wx>z?Y!u` zF-WRN<4&gI%7+jCDdzfqxa9f&Hfnp#P`23)?DSl_$Pmz3h?e!JKOrQb8TOQvS>XG0 z)Un1wT#02u^}Se1DWP~GU{t< zq2dPGIQ8_2+1gk$voq6>96E#4=ZtA@YlowS5jm6T#Ek}JBH47>j$W^+vew)T_2j`J zvjUn-`b-AZ*4Cz|&vk%yGY(-_Q$pX=8^3n)p!c74cR;%e=(uVl%OmKLr*;~pyogov0s1vRgA7~ZEneg zpLR1S@zV>}(RB^5n?dz9F|f+@#a#l5sh+hxXgYf4d%b2D4X@Ai%&4gkkLm(LsN1x` zD-aFEe)H`&=Jju{%|HM7PxJ2mJ7FkMI_cNnkZZ+9yJFnSo0h?yix+{Qy%lc}^P*(=fO9_NA=8y{uZ*N?pm8Ee>L<+i zluV+1yeUX;E`TXdrwghoTvu0XCMG6fOR3lNmG=oFi8Na2bU6R|PG~g}YiemV1A`-w z8r?OgXQ$$|jrR5!|IpAN#uU%d1DQ$m1tX`T1no7jmxCD5Bxk8oQF-=`XHroVF%Nts62 z#b2-pgo#VR7Q|)zQ3yyo2u6?OqSAq&B-@e>v=-AunMw@}4I;fWgq>vCOCs}#o_1)2 zl}sesD5|WgG+i*J%0&nVXdWEgZ7l70pQU=X|>OssmS;?bzKrpw)O zdLp9TBzgtfM}9wl{_J@PqM=tvD~&`VW)KUQ_V#wufH)XlzGvZqMZgU6ad~W>Qz@tW zCOQIk+ln5-J#`2;1QJ4k#FX?73pLWe)|O^th6l~a@DP3xb9r%T7MB;z+WNXUHy9Zi z5jD8L-dvQ$ozi=r*;lJDMzq7W(lFwjpZg5ENw-3aH_1rCCI#&!-GYI14K-wrAyuHk zHX}*nOQ<|9kV7Cr1l*XOAW(S_Eb5pK+GRf%dSmC6b2rjA9zLD(ZoI#xMpqmo$*z5O z?GOkdU=x$jD|hP^DH{s{e2J>(jI~Kkx!-5BE6#TG@jl~DWn`zf6 z5*ZPuP$zcP+n|c^5h{2an;RlgMds1__wPleVg{-jFJ8QWbkcWbVshLJ3=Kf~s$IMa zQ9_A%vh(#&e(b!t>&zp-x?tV7I>|iNE`=gSz^D0C4l0c-Xr1xa14-F5CUAg1q zBeSu!Azs#2mRCfov#-DJt`AZm0Ayb`5r`N`KN&+jQ+1f}b#%0u2pCjY~8v}bp7Lwa5zYR5{0^<2cY;fj_e1l+ihC7^Se3~3wZhxkYO<_-@5 z$4GK5!6D!fa0p}w0k<&qfYn8X4!)E!;?6LocE-oY%_eLj9UdNvL=x5A=pAhmY7pmV z=Q8oX#Y%)4Zp71`{3o;cPh_G;Mv_buXj=}DFCNi~XZIN!Q*Vb0e z%Ib=lot-svb93-Ov}D#+*TiEGcfyZgMEv;VNQ}w0G`E_j#wL-jV%hc3vLuo>{l=Xg z0uBL(K%pQYV<0k1rVk}L`@t-loP1(7VOMT$ehy5YE3>@3ERvlZ3(ii@OciX^(MBDO zZ|k8nl1wCSDv*xWz)3-fSm-GUalTGX#>I zuommU^HsU9AfQ(rdT*nX60bMbH{sRo5DSVLQ&U?lyUE1z_Vz|3hcv$M zIgyHvRVVtKajLOJP8zPSZ_LHnh2$j?iGTstCTeWEd%Nb}KmXg**VkhQd|Qleb8$pZ zbPKSZ^!f9oc%Y*fy0Nh_(*)Z|%~FLv_c;|V+q{9M+SGwq($w1;#&a+=a`+4-* zc5`zp5>LFpxV(@}2^!r#JUlQbrzf%*!T3ninLoR)GhX|?bZW|#G@S_8?LM9Hy14QP z0g$kJo`mCMO^o~dM!QMN0_Ibk?+Wd;V>cbuD)boA zO3jdRst*`RjLSY4ul9ZWxx01OdT8?G^3-VVt0sM(Wu_`-~au0 zc;Y!R-~S2T(5gEy9)r1qaXF9{@_{9e{3+IYj)uD(&VC=R3yDJ}1DrQ}fgx8gld#(@ zMq6RysTsy&>8|?Ovnkk7s+GJ?OiVysV;&2lc~PriIo`f|3mZ?@@FKJgyGfJqP&6SP zih6r{Ochk+7`Gfah4WzNFMJ&?W2|z8zjODo5eQ=%JES+4M3ZxeL%<ay`m$HGtO$6GgqZ*sW!=y9~ zUTfUkl;9Y$xv>eR|AlyOqslbtE}bV-R#t-Dm^Xg;0#-|mZwed<$-ZMG6+3=IvL(Xml;0>;td{GoVmGjP@>?xCNI!>B45Np}Oaja~Tqp~hv0 zwZlbw&S%{9roAK@YrO;`>EfI!Zq>p_YJ!^D)U#*892y^=5H+@6e)&bb6n*|YZPqr{ zWw)L7I%o%EXJ=QwXS$u89U|4F>3T+KJ!Tl6*++nx^_eX!Gy-HIU0+{8GN{_r!JB2bFp?r>8Iqd|i}U6Xs%TUPZfR*TwP4J5 zb#=)G16AI*alj+!qacqQKiCIJ^B6a6&tv~E5sH4D+HuXef2c<108>3hj4F-76EIDrt>b+DWz2`x6&qW!ceqG7{^E|-nw-q za|k#D90GZVz`e;A24fDqlIp5L=O5Ti z3U+rmn5Q5W5-dnU=)`)?JaR{yXOT_{m>(0p`ApAV9s--F3)lhQrxX=!PVnx8FPb?$VkttbJ?lZ$_9D8(R*le!DX#wcr z6{LvhXn`Iusq#j9N%dejv4fSvLmQ8PzF8fP&q$Xk`uW(}%x=NIQtZ#y!( zdysZQ+}sS{U}4ixi8R$eRvuD~!hM%t2yko<+E@ZvOIuq?AT1XpKM~ORnV$1Amzm9# zVmPYok7oN>#&v7 z)7>MIKvZ`K4r?->EOybt$C?Zhner{HnNUwi?4F=N;42ypv*zIpYn866!H=_KyNV=gNP)6x9s z`Kvtp%nW`Y6JQGuFBbPVQwR`xu8AGwnL^mbTPz5WZc!~6{2tJIs3+sT8Fq_OS+-UH z06+jqL_t(WBg1e~uwiDVKf!b72J9tmi*2K)Q%}WUb{m`;koJ;M1Og|WO=zKZI-D7o z%}82aSr(dn2FcMqIBVG3J2dCGRwhzRTAB>lR{F_&=ECML0&Ev-OJpV`bLe-;eB;6v z7XnICimOzKm&P%Y630qH3Ze0Lh*6h?D_O1)&~{c*^u#8exTZ%Psx?uzj7@dga^_KTa5Q;>fgQfx{IJ z-qH0mf3%%cfrU>wm`>G@FluP1gArKRRBEb+S2uWelX7i|f$od*OLKI1EM*;^7#9Xq zTWcGJkuM;X zbbfv&(xZ%oq>{r0^PqHGt3#jZ{ex#mb035!-(Nmd*Ip~h_Y%1La- zyejHPj**l?^~yk)!gubI!b9Mp0jKav<8qu$1d^c>$%M^j8Pb~81CwtuUFz!_OdD(^ zaZy1R&{tPi;u?BudrRyk(PqZr(4gu0(k)CF+PkQPBv5&IdWW%SeV)6N%FrPu3_~W8 zC!vIS1-udIK`(BVt?&|5Q!UJ~ZY-9%J7EKAu;2Xl`n7p|^;&kwXJ_Zk0d~w+A#Jq^ zPeoM8put&|y{Vk2;C*ES#W2EfI}cl2$TfvehijA-PZ-W zoI$fFSxO1iUf4<+7#uLY3q59YYt!t*RuVT5sN&WKCesb1Kkps*R%sux=OzT1Nt9~k zW<-5`y)g8}CKGJhQDu(Tk}mRsPhuX7FR8^K<8t&jCZ75HB3#$J*EX6;zWKd7N(6yW zRdbG(6x}E?n9@4~FEVgkaU22;0f&G?APoqF2HtxyVj>P@2UCVc1s4IdkMZKg3vmnm z;o}E$aBu*7Li3*845&Qxz@|_o7*Ay4@X$rYy*N|6(aEKrgJ}H43-5KpAQMlzkPA&B zn6HY;a?=Du;&ew{S6hQ~HB{bUMAr90L>JeqP}w81YzeA-mlv1fY3T6qP!>|Vd%K2` zN&HcDj^*{z^MKSca{}|2$!}0Tci|9l2si{Xi2z6!X_zuzM1r%nLL4nbU{8)xNULjW zW@E!Mkp1rcJ5hJu+uakV4Ar2a{Dz0b0kmouwOL-8| z2;4cZ5eV0JUT4;2F0T+^+ewr@Boj8T3Yo^ta7?WNGl`6(%U9n(wPD88RM%n=aB5bT zSHv|m&wagpVvDGm>R(^(c90XrI$o9;PeS#<4C5Cta(FKX7b$#Rj`CDN<)T@PaktQZ z5>ziHCML~?5AU(#{=v-6%?Xo?jI#X$crAka>*?ufGd@0UUcP)O3^l52w6?c`apn)# z{-h;O%93v^= znsxz84T11LQ)=aR<$XK?iA*j^zMbg+iouksY8@RNvTHmvG-SHFyTy$&)xPM`d47K0 z^udl2cc-~%5Op)CxOujUu%5_~c)6s@$pC)7b0Fk}o{BtgZ?xe-+etJq%W_c#qZwZ4 z>R>12`uf_eVJChY_LFvZ;Ieva%dD)dh?*NG7gXmPyd5;^)veNJD5-}yrWs5^cBDj)>d2HfPN zfGRA*S#>laae&!xxM-jX!U$YLzk2o3e1e3|^74||fLEVSpFW8yL<`i!Xg`D4iv0^L zCd$e@wTHx0OHasPhaJ&zfg^q2^HweQnhMLrMH6?+CnhJrSZXm{V3duFjF=CQPI~w5 zov3$EGKsFMSvI=ErWPIT9`n>LIUN4Z8_3I8p!VI?lQx}!)9!36kai}h4#^A(wjGLuuY-D9ORK0qtIfHs?M*P}HzA$0Z7Qqb^Z*QfkXHHL@sLuiQ}>xe zpokHWc_nrPNoVxO;*xG;gk~s>EKp1xBPmT4XAf%jb(*4g(KrMg0y#oJ`g3@Zo};`J zY_c3E6Tpzn5$-J0U^OLosNQt~`xf-*L)Xys3T46M+mPGLv`&bQjlDf1~6lB~_{ZOes&= zoZA8YBt7MiOeF6h`=4Wmf9p;T0f&G?z(;_zfg6;RC?~CwIhH?>vdGxu@hTGf;}}Vg zZwkQzCJj-!D2f09w+JbMN(>i)1iwg#ez<5^yN`pP%?K*1C=+R&=g(h2N@qhn`0VZN zi^R?hY$wgk%!qUj?FY4kv1Hpy;&|^3{C6eOxbL2%fmvX+35nlk2qNwlOEkNa||TAy4|%yASwdUXhYP1?&0GRu*Lw=Dpg4)&91AjgEZ2ZsPt}ZcwXC% zkB`mAPaj3S_r>B%(8wk*ir};W45Q%i=`dA(>D-{L&GY=Zvbt)vz&xVrFd0f@B=x{U zoX|>gkVrHA#UbNjeq37!P<0m$fs#Prp+2v)!V3eM0XpTTRbMv?$4L4b6Zga+;1F;K zI0UkdfXwYNwFgs$KiWs)ZZ(-kG+52W1wH$aaWXqIE0R3iou*2}E$k%GO>{Z_2@{E< zJr@`}#n^V{^K>wMgZQoVf@fY9g1qQ08Ap{c#9fWubMBzC43jXzz3^he{LlaVk4P^4 z{>SfTW_Cs-vX+*i+6P-7bc;>tB<{Y8cOo#MYTy-4clTB8L(_3*hd?PJp#3ji|JHCk z#|vAEIA*fU0p7AW^HiEg!APox)aJW)?@cpk{vo`st*)(#${T55Pj3&@gKO_Jy=7RG z-TVD5-3`(`q%;UfBQ+o`A>Ae2-4a80cY~yqba!`mw{*k*y1&2YdC!ZPIoNxj@mXte z#-&J4>PEpOEbi`if3RY{?IhkG9W`_GaACYu%)7n00qKL>o#pe!vKs}Av+Cs7G+qBY zNPXdccg})RpGp_E3et#mJyfVPOQwDH38V{k-YakZuTZeXoa}=mq*k4qqbd|5{wn

r4~% zM9{SBhBrRJ-afkE+)7e%Qr|UZVdD7sggD31>+?M=2T`oV$5a~~9i7gtaJE@4a;E$+ zGvNgM`*AS}QtNI54PM0R_9b=gwu7Q^SYI}W0`zLx9a<>s0RVw;N1iUZzIN1y%|tqT zM%8l9wCkOOzUAWk6xyuhm#8Zy)&{n8ad8Rj-QU{sUs?&`I#~|>A|w>sOe^<-y{Kup z^s3{x+PSIx-?Y~uv@`$k-AH=CsAGcCCaum0#DIN%`oEIIkg~G^@lBa`8%??SP=WF| z?@8RAitJ@d9$S?#n3{Tjfc)LcrqZ_82Xn4%Q2SBfbtxh;3c`hbBH2Ml|A(!MN(tjR zQ|R0MmkiVLhrm{S=q(2Igdur8LTTfq`uc`c2n6ZBC_NX^w~P1J4pU3V5yd%cpl%(O z-&y67eSW>)7`d3^srrQ^5n+=voJ)|Tt~k&k18Oy{=#?HJWvcn}BW^;2wReoPFv#!s zJ;?&kQO?9@ei;iX11dUNVC;=@3V38ufZ{A2o*Hu8YFxSEMPBHfV7O=cRgh4+&A8k( ztZsj9?sNM+fi#^Ebt&o=V~$WoNKw`O|Gs|$8Fbew(^Q_YX*1@N+5wsL0p(PyDO-jS zhz7}qDn9C~6{2*vB6b&fnI+4I`kiE00vc_w1;X9vXCx-msnh7Z^JQr^eiOz_wWoo-3!n?yFsJIs zB0|FH8W`khUv5#aC2g%#rb@~xu_q*qS*AX?qFMRcx%#-943X%EWC|1I@A1@8f88f) zTfV)!>7KNzI_>2os}b#f5Q|SjxZc;Ljq>aHY+wF|fMbR0^LHnj@R&UThI&hNxaQB3 z8@6w-L!+;2%$z*@%uxv73-}Oti8*!iqPhEDZ%@Ax>S}9pvErodz#p2Wp*?ApW@&8ZkIv|;ZgW~ZxIeC$xTT?z4{-*m;*j>`_DwY6j?_2!T5Hu;n(ex+<~ zknj;(EH_`#f+a+!wd+mjJBAiG9Hkc6aCL-%_FuYN33Um$2Z{&CuGfmcU1drH_8oG! zS5*DR*K))oKw)7S4|-%lM{RHwKZc;vDcOsq$!u_u2L2OxE=j!D_p7` zW||^Xk47tn{<`d|wHVM5TJ5#`qlxwdQyc8(#^=N#^g?Z7f)SvN)qVtWAgGpoQe-S{ zYttc+rtYCOh0$G&Qi$r4k6Dxn7=}@Y-iAVhFAr4p*Iu(1S=5^mR4k?zN{^!Fgj_oC zWOfWA|LwOq`QV6zt@&AXJF%qVHC{tg`=h6lifc=AGY4S2@-?2m3zskw@w$SPTY`v~ zn1+n#Au3HzLuzfS!2N@l>n)baH1)-|8->n{Pg7U;UNx`#Hur5n{+d6&UmfIDv>$`; zFoEsADX3V^;{iTCRjiB|3c0Y?uUV6hlFBJ1e-8h;hlFDgPN}p&Ykin8HYqy^2?=6b zL2Uqkl`Y7}3U$6SAFGdlBX-n{a?KMcaC1IjZZ4m%zt9o8vjj8&QyQ8j#noPF=}v9C z5D^Gf3{ypD^C0Wz)0d&9$RIa*ODncEHgUnvpH1#+C?5W8wSjkmaIh5N&9(BV0+m z4S)w<{&a=56@Nx}?$-CbzKe9fJx+YQ3?YZBiXEhH?H2ty60(TWUop3JojA2RO95EWcOpm2QQx<-sz2_X^7O3~=3H^5Op=eb1c(YMT&G4aIYbnAmE$EBw@UhvSUwIU{sQ*j=>DUWeh?2DE1JZv zbOkM~mRy8JXD|pt$4RidzPN~~S_K9fMr|^t$>J+%bmmc{5E!$#ra}l!<|SAN1+^D} znQ#iwfy~S;(PV|Y$q5|pg*FtFtPhZ%Nlwu-#ubw0i}ZTV!5zu4b&mPzGkHGa{8wU^I#yhGJLC8pq3VkM%6M|t z>G?UkLYBbi7Jj>GKRKA?Ku-ibU5@ZzV7a*)FP&?Gx3{jmzkjFJUOaWaZ^{wZ+yy@V zKz&TmK^=i5)vfZ=(iSI8itib&vMpX$u&Cxt0Q<|mJ2K*-TXJ{tIZlYk6XxbiE}}Wa z2vk@l{WnDh398YLzHr$`MdQ0>f-qxW_v;Tjw?Aw<-CzHb{4nffQMR^@%w>c*d#~FX z)iGN}q`Lmq5fmgr7=Luvlm{PyU5;T>1EzS>MDQ4w`c-$DHlW26_Hg?2gj{C1p!isV zdCSca{bUf)&`ji}zu?Wq@zdw|?6Vc5HMr}{nY~#KFUI%vhSh-n?BZhRYs7j~@TOXN zS-|b>?fNoA79@Hm#3`*mK+bah(1DA-&2q+qN2|&3L8ZWC_O0l(3LLJ1*%#MLF=RmA z`_2N^Z+E+!wJNUwi1hUoJTR`cwKbtkUS)ZC7|%Buvd=qGw9{i_^$E4u)3RtW%GN*v zT1Ea$d3i-z_$x|oNP2oY)splR5!>u#;@#`7W&dgMtZ;qGADEHU6P%?^po!X}Klm_E zsV5H?V3^jndM4*{=wj-qSloQ2rU7*S5KM|Gdzb++#3omC|6R;Uq*m|wu1xR9tdZsA zWmyGRo)l@FqQWNC0vmI?^oF>PHGj>`%kjm^R%6>~=!W=^e|I=gUBktRH|m4dLeUCV zkP{I2?^K=-ccGE6rMX0e`1s(7!Or`4PxG_mvuPtI-;}l<1YR{<{;}%o?V_Uc$k0zI zewo|(dr}oAZ46@AM^0XKL{}ZZ&8SSfv5w&Ep(EguL_Mzob|#8H5$VS|zvO&=tG$cj z29v9%Eu~K6xMx!Nd)WQOpq>6R`I5M&%Bxz!RuRM296U>7L32cO2AcENSck7~P@gAVV}$=sr6^5VEgAhJ{kkhErB@&lnS5nS2#xibhGuEw6d$m6?zYzJJOGpBb$+Bjqp`368xH#YZaS;;IrUgr1Fqu*`GQnE#Np~Z0=;{ zKKWa+q|ock&aIjFJX|VN(@mQQ`81|p%jVt>_IQ`S}>m52f$TnsC1MCn4RabVSyXY zQEC(1Gc3bXjSu3uHtGmwV4nZ;aWuu4PQ1QO&dUQ(T6fol4mr3COrXTuUIi zMFQOeEE{MS=PiS#&WI-e60@bD>r2@H{1*h9XhAvG57IywO{`cV=xae%!0K(2RyJ&t2i<}^6f|4=7E<12t5Ci%Gx@xpq+ zTG3*Y*I*n+ha;cM=yfR`_wF|=E%9^lxA5;{HpFuC@KksDc^<|Z#I`cPi!|kIX%{sU z-DNS6gkoWE_#Xd0rVN^+7%dR?PrccC^(5FLJx*g!<`AF6_f)yWYy) z#-`hXGRnv}+!X^H7S&JTMaYZ#d3D&XM-s@$;VkT5PdLj{vZlr4guN!%f_y-lv@E$AS*rWV$n|hK>(v7lChdaM^^nCZ=d1CeX(Y$SRR-b z1E^b?Xtxbn^kEaK1&R=D^xaWC9-L+b*t&MV_334z3nM%vSxA%MV>AUVN6R!ELbwZ4{nLE?Rzxv06Un3UQ zw~@>eB2g*c4!J!I4Y9+k`0Qik~iMJgez#P@uYSYz_JSw6yNo7enZekmR*4 z;aE`T*?&01W$d8ahwXT3hF@Hcr^%;-AX&&xv*%Vtr6xRwu~w5DdVQUMOL~nPt{m6O z!%HKU;3%TwsHVfF)ufWRDZip*3oprFz$@IO>z^jvRgl?pB^M-vTIe8)HeeV~lsOwH zYFrn8dqb2{tqQwhoC($0e`~j4LX_0^t0z82k;^--?&x6U4%BURvsljkBXME$h5O}8kcL;gar^tZ=R^#T%f8mKrmQoZ>RQgS{{w_r^{cV3 z&=37JAb+Ie{>rRvkfu_NJ5RTN*m1UVUQEMhTfvH}yz|XOXy>1^4a$XdnR6;6uDQ8A z`q=0=c%9L*z0{v;FYED0PdHV9To?iaC4)I7w9ZH%-R9jEGj4^OE?uAwtaL);+E~Cf z+}ts-Dhv??`S~~zq!0eFv$I|{WtP7sh`yVXrd*B|zr?B7I^KGBv|k^cvs<$+IaHG_ z9yPhdG6g(hX2pMc;T;rq0&zYF<6^8^@H6x_?1197Rcsim&Vplx?=7C;GjmW|7+0HI z{@a&tV$yTLT4~BKV6LmHs~Y)F8U({n$bmSJJ@FNC&Z~dUZ>E}ATF#7$^;MwoFB$_z zV2qFuQUwB-XVNNX5sZ+LMo<0?stUNC8i8wdbuEO9vK(}dpYjv$$V_Sa1uvP8Hx`<+ zeCC$F*290O5$(|8L}AP9;OulqaYji@S^4w^MST@+?U42N< zk0ftcgj$4mVa6Y0LinAoF2Y91Qq$rR4sqwGKk1n?G#4#T@)NhI%FD^60wR=Jc)Z3P zoMj*cxL!w6YKSHZqd*-`pJZy2n}*rbqnWZ|nfd0YnWvOFg@vxAWjOe6l6tqiatsnJ zIW@K3-l*W9E38#>Ok}Gmf16c8>EcYNu9>~L-*h>b|M$Ti2@|IeGrwdZ;zma1dI#Sw zuh|tI1IEN2-A)6hx85+DgD%f&to;g&`N5yb7J^${us8j>(z9Hamo?!QluByk1oeW} z3O?2TX@-Vb6PZHnhFW;Vk9a1KI=EPc#d+VNM{!br`FbTeu>ZR1%PH@p7+P>cZ>hF z4;w>ysAc{Mr_FeCUsRv}jV>*_hXo~*_P5V_C2ucn#bjzuAY@!qVl0XBH>sR&<)Ls? zuH0zmUjx|?w2V~@_*&9cx^39D3CY4bXM2_C54%`juUt&BM6mwdo012#?yon}h6kP|GN(BBWrLWZ^YD3s zpZ*x)d)Ws(hAY_Cy_>b1cOL~^T;rM3#U@mJ-nmM2gk6NdK*wLN{zctIhO$7=8?(b1 ziA0C3WTpwm7h_PnOPyH4ztl_lI;W^*9)LC1)dh8Zy2M%X#VYl&iO><5=RSLju^H_= z$Kt*?KOd%nlR_sDF6hoA>&(Mo_0i3o3}=YA=Sm8Rs*TpDG`D$*t1B4S+J7<$yM}^R z+ewM$m#`u54w|uSZABvJ7)M7(hPw&`TZTMa5$)_7R-%S;f+*Vjv1Krv!;P=9!GyI~ z!S3@eagjILL`_nibMEISA`T+7aUC%z4!goeq_ObzqN-TLD{>f%{ zpv592Cg)7xra~+522Bgga44-+RJ6g63AX4{+b9&I9JX1zx~dZ>FX)51cvfGwe5IA`=>Jq!MaH~EG5L(27#XlMvSGT!ccE13U zqy77Z4q~Em9SsdE>INw(sXrqMM+IizCq{dBVQ1H9Wk1czlxQlWuSjQDLCkoVI#XO&XUJ>A*_ja^1Tx`EK1GX5{z4MxcQZD&wYEkQ z3+1wQx6tT^^SCeA`S1o{9w9$%QMkzlF{^@I8$LNYd7<9^C9T1CMPtnYsw9Drz>jrJ zre%8HCgz98D;Z~r@P8vxF~q+?7RQ~-;rwm1Sq_`xrbw!*CFXd9gzP=~F|v9Y;R$2i z-Bbi16jL`hSpI3W#aNqxv>vmsj~dV$A3{35US^v-<62*pPSlM;_92Tg?!DyUG-h71 z(x7FuTo5)*J>O$<9|0Z7#517x22_7G#XyQIkhf=E9@@rBR>8Z z7dMvqO5}8zQ(fm6ybRsv&)hv&P_4=V=(-!);kf%`vpJ8Qwcc-TzIG zIh=2b^9!Sb0db87irt<9KQsr!rCO;)^oqm}H^jy8Q*nn2+FDoopi~AA*7Nf%rHBa3 zWmzI3GLHXj>j3P|6bHVsw6Y$VA-%5;4ou^mYDr*`2v~9`6pdu2t>~03HT^kRYH#?i zaOeJy`O!#IZ7=bXtYbM%Q|UQpRtdlQ=;Q=vg<1t?E9y;XR>+(O63#?aU%0%&`ODjX zs!^3kh5(Xk(7Wc&=(@U=dsao>DPtY{KGZI~+5ECL8$6 zDJM3qP0th<%Y{Nacz9US)G65Zpwc}aJkUXL-IETrXm5tXl5TIPC(Qk7ZqMM;8~M{> zH8)wu)6F4You@3c4)B^twfO`1=8Qh|H-qVbp~A&|%^{yKKR&-q0&)(e4adK~)zm&O zM_o<<)XSg|kBTh^C4{sF?|BFDo+Iui8~+4lW^?lA29Gk_qi?*VIUdB> z$%*Qlr==GkDZ?tk|96ni5P2a5bz;XZ#KWbDQq#c zjK#a;Z#>;P-UtPcj{Xi7X#u4+Nhf&sYBns2;eWF;Lw4kG7A|f&}^=M*-3R2hDVdmoEI;urbOY_~r z*}4y~hcm?DVL@q-FBzGG-XS6ozAuO~4-M=8D_E3RWPfpbAU5ol9O)_Q;2e*7KHA(T zJffPU(;O|*Ikh3>mkd$px#`T)5Or{qG_yx|FC6nnSYvEOrXcAy5}>W%b2%TOlIoP>2yYFjRcv*OM{RdKV`>VcFg2#w zvh768Gt0`#(q*rdV>RjqcLxOAv9&+$6E_`f2kH*mP>#W-(tWkYe8-oB_|a8)Wc%yDh?~rZjpE#Tl{)k&}*qg zZF_@FL&pa9hVOeDm_}(jJe-T;!2B0~>&MpQg@4eI_fP&=7v3>##M|-adbsd$hAC}K z%?Z=LMDlJkigvZRN~t=9J^~rA;v>A}_{n#{Q6 z<|Z9XC<7AxChUy=)Os6-p%)_uJ+oXR^3p2rv$Le(Itb_u z(UAZPMpUr;uyZsv;<6cpPw;&x7PP@pds^)LVHcd*IzYrG9%1L3fNUF zi%1LD!5MD@zAqAoI2MA|yWVMUhy&0SU!$A#Gt#%{YnIUUPtm@p0Ujad&;0ipr+Oqc3HBA7@(}|0pR0TL1-SL=)pUst42A$8z)YTP7tX|N4Rt5%1k(E`-Vw^bO8@J#Tqv zs*TPr?~7RvY-xLgR^k{GSh~Mr3-nFNa>gX@8}@jaqp1Z4D<580bvGeAhKuAmXLiug z$7V3d{hLs+uJlj9BHXA;yh-kO>3ey($R0&jv2ASN*7ti3f&+;AWccXNd>=>trieG(wt$4}MMT`Ch5HOkREd$#z7t$rV8 z6QmB4%l+#Ca^KM9m4}C47S@({3zMsJ=qU_CG_Qw~O(|YK`DaGsYx3hwyRc=kvLGm_ zGB1%`1UzVtJONF;nO+`t>FL>=EiEnEbCGen+D^a#G<{7_fL|bv&pgnB^6a~Pjk2+X&1TjV};luAO`NHJ=Gx65&9*8!$sbzdm@&LE!a71%CAB=NaEY5pS)M7$H0 zL!ZJr4TD@rWchH}%En5x&sw8Zv7ym9w3sKja2AxhJ5XILP9$55dh;N8VQows>n{f% zH`o&QjpW2_Q?*=S_4-8=*v-Fh21~u+0&zu@F+4y)rHrh)MT^GZr{pEzN1Q;53VbMxqnonK z^HwrlC=ZM@tbI#(o*2a;K10GO`$kcWwuKKiKvIE}{v;41Qs>+|75qDzk(yavrj=}T zb-C*l*M!<3zFX(x?_>Wkmu*2EU1x=({4FAIeFYr@J&3`_*%^;*`cgSX#=gt6y}OR? zT#7|Rh$3evYd`2d+JNc{UkB@?N|S+eC8cg?P^+i>#o z0{(H&V^>!kr}`xNTXu+eJZ?9af=x<&{@6Sm_BZ%2kDcPfbH*w&c&M;=6fj4*e1FF( zE&sKWPKCOwI^%($%HR$F`2xXq7TytvBlf4zd`j&MrvcO1*?H<#tN|x47a~$2`em6^ zPoqOl)-Q`a&T_7^I&Nu}^RM9(b^RAq|FP8$fghf@kGNC8#=u;+A?${lP)3244k(8M zcoBXCwiPTjX#h?w5H@DT73*N;Hc6lg4Dk6p*l2cOrWm;XkqB7a!xP&zW>F)s;cZW2 z_^uA3A+o6chjJAo7UaJJ!|{xOO`3B8X=ycRy3V`USn29azm{Ya#Fi75;&|hG;srBz+S}=Owr;WmBpXI17o7p}>pI*ycR}6Sbrm@CJSNq=gUE#gECr|>1IRXkG$}1MB<0N?>T+AM2z$;(!_3&r*4hTLL+8ztk4j>{4hJ~`op1vb zHl0+?G@`k`*4;fHx$#fK@B9;gKY9&WCbtz61lxSeGnzqNanf*P>b zX#Tyi{)Y1rJ1Y{+!)|2HCT2}2AvS(YqBOI8Ugd$1CUo#}>l&G9ohX-RdSS(^jPbWD zOf_xM%*>1_(fZ|}xMpzdwR=eli6Ohx>caf|7~m$<>oUFgKu{20!hsNsO=n&5&4l8T z$-?q=`!k^`6xoyZMB0}5!4HGMUWX8|4~V~3nqX*rvGjEqBF$J}_$c=yhC4}q1|{qw zs-!>5emBA~e}yb<2(l5Mr03kXbWawUO(^kV0)CJ|f^BM$z$lo8#)h#WEJEqz918-B zYQnAm@X4G9tiL?)cH=SOkD}#GGX9+x1k%8Mg(V%hfkf=7DR4}%=IGBIO#e7(o5v6; zsjFka{0=m=b=|lTMTVfDl<6=tv4pOn5<&L!@`@_qTb4-RuZ=(xF2sL%ARak}^h)B5 zivoj-xjzwoSCDw}M!=b-*f>RYrxf>6fS$$9Z#(!y?U3 z>lmlJ3dW8#6zUKy0uyXtF$Pl1JSX(_jn=t3jL^E zva&Jlm(M*ZE`;VjdU_p;qIo!eMqshZ9;i+}f~AC%0@!0rZi2(63bb{8AbYHLXLo!& z3JlWG)ee)I5TLIZ2>|-(7z0=*lF3>*t8Dtd@KTeQXF{fRO#RPRIe}B z9li1ja@K+>4L>_a{YK2#M0V+OS*rfltn#I9*S}`mbNze{Lg6MMiZT-_7CpcF;{v9M z6r(9nwxXQcyBj@4wMrO;JPkfQr8TuT1^=3c0woKj(kWykUR!)93km%30tuu1myD#9 zT25dR8!GIeNELR0E!h32aKn#Z$%U!^Jn2Hx(ra$tEo#{Et@W%gYNAb=2b!!;WX(@r zQMCyP2^9?^?V|l1UG)wQK(F%VWm)6L#+aejEG%sU8MULE{be9O zvG48IDRO?%+H&l2Yy$w6xP+f~B5DXR6Ri2CQoQgW|8OWA!pIc%4f)_y&TjA%QbYlu zwki18sVbbGErnZKS_eUBFi(t(4D=rt+}0%rFms#c}(y9N!?vax;X2cOas;-xZlZK zATwkZ>R61{xjg}UVj zfyEH?bUm*U6FHQg1CtVbP*E!cOX=yCv z$0d>tV70wX2{xfah0I}Wrc>_g`=mwP-Gfd+_KnRAm1?Je$HFa|%F3NVhuPe!h@pkO zf%K|)l_*~+o=xt`vR0Q@*@XM!A3-QIg}mirLU{w>w@7{{BscmJ>2<)h4JBWHfC(5fhh&k%}+~9lPNk2$Npd+ z{F^RwLYeDYtD?mH@|HsqXo+wU*=6vPpKrnaivm114e60pZhl+O>DTR0mt`TZ7kye< zx=|vlzdAbFsY(0Xi_?}L8HRyt_L8rurUohT0N(A*>J?dPx|sv4e>LC)oU+hhkx>^S z=4#I*M_8v;jD_?`9OaKPbOzMnDw5_RyaUlX_yTv&c0LYv*^ZLR2UT#roP{Z&pr>n)p@D%#i3hKsb`={MH88N|!ABy{6Q8CV^PlgE2=a7s!_ z8dFsRBx;ec_eazI?e0Gsepu&ob0&*-N5S8o`M~sh!LhiN*Z;hWPA26idf1*ArB@hw zPA0Tk*kAC!qwMUh-WHpIIAVfBLdNbFU*G?21wI~hyjl1>-|`qxOpy&0D`bnGon4Qb zT@PINru>Ix6+xqR9y9*E>QBWskqtxo_d(Uw>>udeY9AAX){H*- ziQmK;J0i*i`(r_QWB0<(l#AOxRy;aW-#k8+OP!t0W%)2MQg=;l2pr(bZ2;kV;vJrTb|13=QvI%UCt(t8z^Qu>|20G+&Xa?w7ZZ!yU+WH3(AZDwi7 z0uWyI*>Sax%Lt)VR657yZz9V3$y{!ymf14lr-}%etE9t^Nq>55t*9RZ0#}GRqUU+$ z$NKw&37YrvqRv|;#>Yo%4}fkT2R^^U9q{$ktPDQ2g(teMezoFJ7^6Gc0^SbW_ z{X1*>cTW2WKu)`@)v%+K_1Jr8V`oy%*dV;xle1XWm&M}Ls*C2H*4Wr!ezrey7;%7S z!u|*4(sV`Vo$YGUV`~y(a23lYKq{~AyWh1owTt>9sG>}f#w8kqza7&!=$T^sJKa3W z?oae(lEQYM`56VveM>=U8gT0l?2#&Z^5tcX)AxTF`a%uiJu>Dhq3kFMIBb(xElFa3d_C%K`NjD;cPzN~X6;VeEsEbod+PhQR|{SnoqxgE#aZ1u?Xxevk$qXJ z2BYZF3kfXSRFS%IgW>?)#`)jWHe287`5@beTloDMpo=|za&z;HLPgm50yJT(*JJm~ zg70hc<5mdyC`J44vPyQYc>!tzl6@ljJw>WYRys&Lu z?lrk{%!e{zK}99KAUUd)=tpjdvGybz^pJME*+FJ5u`4^DJP8P_e7DJmt_^sEHZ%21_hlGF9cF9=5< z?xEuI_CX$4aUvw#&iZh#->KU}3Z-=wvKSc=*|LZn@$`{g?Cb_EHTpk(U7i6A5+{!^ zf<+-26K@ev#kDMHhtj_tjq8;^7z$2Egv)cW8uVjb|Mb-gCiQ;k4jk4G+*C-!0l=C! zM0}6l)Z^fryhaRZ|G9cqFIx~(VLVlSzT&qCk=yEpn=Pp#T;I50LA}l0C{7Mv<^JZ{ zYb>0eNzgdDYt>uqM>GiM*^fA-yT+}PUsu>~gKHaNA}2fRJ+L;02HECb>-R23-zb#u zLHvl-?~Toz0+?F3~t}u=21=QU@8?ju+f|mkc`qMsW zJSLmqpIeAQruB@EW1Ga03IXBNqTCbgifVSR&GhxiD5H?!4` z&)kEq#)?C^7T5C~=vU*OpD@-DYTn^D*cro!G!U-!&{ybHRaLve+uh1N=GgZgf1i0f zkIrLTWU!(7_=YAxe|;<$0)>n|JZtVO2yIqSDn8qP#EGERC5T+foQdd!dChPNE~^91 znUkwC%8rM(wGJqXC3kp!dYURV*WM;J;#b+(%ZosYT#F$m#MtlF1BEq5z)cQ`=1toh z1qAm>r@7%P>rX=J29P1Q6$=Z34CXQozK>s7>kFVB6DPceN@R`-Tgn{ zf4rJdN^C8OHXIdiru*_3rbJ7(>#|yxD6R!|VircBo&IoYrmd|VhC7NJQN_|3ED1Z! zdUMsEX|=7uPn1wnN{>>iT1Y6%pN;KYN&885K~JEtB2*|O=q7GdfMuCJv6qtuda&0r zM0B-3Skhn`V26jl+Q2Bop8P&xi$GzZc>&HlHq5&Bt9N&3ng4LQ4B}eP1S^bClM(3A zJyeyprRwPO1a_4keu8*jf>_K)d&6IE&p+&24vs`cPH2`E>)HdJ>Zn4==`_ju-Ci}a zeVhrI->RUS5K<*5X7QUSCzs~n@ER%E5;nUk@<&Jvul*X9==Z?1w`eKi1riCNyS6w^ zA;hR=Z0%!jx-g|6L2$@nuJUr=$pi8?(X5^O*8rxZ5vMdv#k2_*s&`&;@b}ewz>(H| zpYFc<;7IO`EiTV*Xn1rW@X_HHJ-H=qxcl%#QL4lTZRJbMLG>p*)(yCKGVl2Kx6REw za;}!rQt1MjV9DUI!w1l*Nk+HsbX3V_J35aK;b_>pKfM7U#&qLR47eRQ7$DlXsJB5>uGvEuYF9+EV({W61V@Zj+M1tXJANtxq9V> zXqS0%JxFMR3fk+3-RCXUNUHKjSs#Xl45N-7vMy`eWh%z4yd2y!na8a&XpQD+iyozrevEficNEgty$IeJ+7`VGV6OQ6N!2jv%*?2&7)|tn+R)2T*(KY|%xn}1wVGv=bueHDXy*2x z_W2%ES54K37&=5{9nY)(#={AX8^6)xl;9{!1B!lAfTX!_x880$dpXrk@mg6~F^mA7 z8{dyrGREhmq-0&eLxo^GMZut-4#sy7C0U2a?r@op)Z^mJEIa;Fd1y`f)qss^Ra2DO z#O3klbx+_dUIQD?NT9?aZ5V!%nVDKLpvuRpZEiPcaODnaAn$tMrio|cN+}y=ELoce z?+?`#r4d`x#v-ZOPp}YC_xt0dZfC$W_fT#g23o=tMu~_5!|>c5$@I|0iPIBhTkSqY zANA}$#qcJEKui8hdj)>E#)G^0`mu*Izs9W6A*9+ryteBi75-TsCCYQF(^l=T`&w=n zOE{iFDv=MvT0dT>Xh;IisL%EkcyCb=ZWgrD!tUUfdA5buzaNL+N!i%g$T3?{IEy-L zrrUOOIad%!yuaQHZw{RWE(tHaPaMmC~AQPu|GyW& zsKUeKOHsXGFpfQ7mX&ixzlC84D@&VIHM4Nj(A3q_F7JO53&$n&>nx!F%6&T-cS?HPPkHN0-777+Dh2bm; zSawd-3ZH1@8|qlUy)r;SuH}|>eFfp9wPu$hN)8F7VQ1u!YnKYbsF`V4q8TEIe~<-c zJvZQD4uZ*RKH@?JyA^q-@y}YHSyK&t4g8(AU)@B>h?Z?8l6 zzyIW{2ruIB%Y6U-Jw~2r!1c_KDU&;;tcw7ZGpPVgJhgSn5!QsZP*eV1#{+B9Cw={g zj+I29Na#9>_mmKNKQ<||Vnr&Kuen>VtiN;{EYhsW%eZ&`^1{MGOw_MltZ}Xex%`y@ zseyg?dou64$-Mg_))=tEHdtcDV_FlFbmTT;eo)7lP@*#n#+WOYDx&qzBEpe*q}WLL z#f|QXdiIHTS5}kTc7YDUTmUn8%T!>s0l5*>mw26bv?HO+JaiYIax0}dpkpDp@~}xL zSQ8to@?DF%GIt<{sJ^Y%I!Zojlp(@)VstcRK1q$e`Soh<+w)0;cI_%tcot_II4>4D z+bI%XQ&_V~Q*t7aB}GE$I`m+eHPQ8m3d5;NZo(Z9#L@kS3~|EntCc5b`#cS4>*=K5 zqPaP0X~A(?jCs8Ypy4F~>f2>($xZr*V?ZYk(UieEP4_DO(Ei4fpMds*P2pwWAWcCK zhjGj?ubKv%1;?H?t`a4lA67fl48ilLh0>$yHQj7FrTK}^fCB>^<3Bl9>mTL-c5k?z z<(I4-Xc}s1y@c3awBYm;VgnNP2-HuAQbfV#7yX1CDV6QD-#1DN3}^0D+7LxB5gZo>5VUDTH^LRg878}AQm8J%Djw8Qh$(*Ws3I^nVk zJ1l7oc?XIwWN|FxB=_XQRj@9;B+v{Loi2&v?k30@^lb_v{3bRNKJt9W(NN{#X=#iz z8w-}Y?QS+Mz{uambeRM&|B@l5iM7#x5AA=kpa%FL013Y6`uE;cvN7EQvOq+0yiPL; zF}z_aa6I0h3Z_XorJ71(J!drc;F3|Z<6tR^0`_vN z$$QN1(Qel$>k2B_&As}BS9j6;g7kb!aVXlX=9t?j)152G@Za7Zru{$x$9&gc!$O>s zbY*Wc@_SH>QgfxFwgtta&JWkLD>#1B0CsY+=%tPn{~qe(F3N zzswaqjh%YE#C6)-ui;TU6ioN8Bivj)pYJM4+U%kJLS4vCWC`OuOV>Ge!%+zG2BFz= zDx|S8|K3->m~kFgX+0X&YwyRY%=Q{HEB9*hhz^o9&Bk#pq?Cn-K@p0y39eBY)bR>i zuKT~m+lvF4TJ<#*mp%ZEmNL`QVhqZJ6ezg$*832^KV%RZ>D!=OFQX~1JH8+LYzz_?>43tQ~! zLrZm$i4BEa{|2uH#!2~|joO6JV1SW6bUsB%=_Qb`XS~4@ndtxEZQ?fe$J)Ch^HEwa ze#V-a3AEWcy0mmNUIhG;kf;rPeaW$z`Aq>AAk^?^Q%p%s%V2?pNh{*iJOt5J!CZ2gQt-KfCvER>8Rsd ze5+p*=Q(%vXw1$j3`HIz=TKnG$2yS+BdU(0ceq64F6K{lI_+$?@Ze6T; zzftQqM!!r{j2Lhrns+pIOg%-dWs62r%hj`37E?FrR;F{M87;djy5n*%Ky4T8le11Qp@NXVqN+Mq zgwJTRDzX^(w7frG#1@@GwSa!JSu_eFS~G3gjFv6>^kV)E;;g4sF#0w?t(U@HEq|+L zkkq-yhXcrfAkZ_Dpo=mM*x1o4dic}Shqd&{be6@%QvfsX;7=D7>#iOI& zb^Tbr1EI)|_kR0sre5r3m)D%WEU$ce`=T1fHKEsLhY>~&745&v%=;p#b?ROBgK;j8 zeen%zj?0F^$<;NrW=g4q!!|&d2?-_*HBZaUB;SL$tx2gq^=^L9sWQkB{`S}<(hhIY z4^wB!uxlt0sK|k(KtZU;IDs^W0ZeSN4$QQ%>}>l!>hY-@w1%bRB+l|IR~x4)86T$#lPg8ds?x!~4ry-;oT0HnW-8ZQN-rx;+BJ@R1MBoi{;ac zvveR>SIJdNLzn%`?vsLKFbCP+LjZRsyh#R2)~|ZZ+vXYMT9~JNcpN2N5~GOld=RqyV!*$p01>dA zdS8nTLCn!Cp&DsFdA(PEbR&`&MA?K{A63a?bFJmxP&}Et%A7azr;V1@ ziay)fkam7^^YG2xUDz6p46VIS*G($M+X1CT*%LDPv&p~p=8h#13Rd<;0$hyxC9BPy z>Cos83n*4n)7eMXXzwe_%fI$nS(($@*M({kdX~BVGDm>QB})4H+5O6F3-FBjt`Yma zX|ONjT`7@Kp$K7+nI>3TfP5UIh*8m1kPr<;Z9f>BYCMzp<)8~H1vUTo$R|g8drI+i zkD;3!J2$t@jqET2eh6>hV$;ds31B#mrF2Wxttb2c0MS4$zw&fIC)0@oz`?-*+;{Hd ze24|Yu>|FxE{L>tb#=j5XQOAp6O%|G9ON}Id(7hllSXZHL4@w2Xc1sraP?iZ)f*H{ z>sV=szR>4-A3l?Ah*YD!z!Vba5xH=D;qTqOhd|D7BEtYxMMeUpTd3kT4oQ{g&!3BG z)W+t9s7n3u#~)&IuL=tabwf|dRvz)%hy=o)a2dn*8ZLZJG+g+*e7k?B98uqST}X-{ z8%OL{9Gm?^`W>$MjCH|!p>)y2sq0}k%kjMzHkV8&KZFg12|+YWl&Ma|Qkb4Y2bUyifB*w$e#+wo{IdnC4}f z*&ZKi7b%z6eVA4R*mZq6FZG3M_HEMpZg_AT7#uJou$4qlZ8W@nc6ufo+FYCLAMBas zPSew`IYl2$k;Ty{lM;)qNn zsuYlrZ*OnIHpPnAr=aH?il&o+L>ImzBO~T!>_#U2B;wR_4#shRuu#{+G?qsrdE8Cr zB$B(4dOUsl#G54c8dHOvOMdg^My7&Z-Vm4OSHE%R(nUatOz9#}+$Gn(ZqucxB_@sG z&px<_#O|fU!O1EP4n|=*=e==%^9cc|Gt?(lA1I|-S6L?;6*SDe0@bIp^HVcDGc8g{ ze>DC9Bdv9&ufNZAki=#V6KteP8HjmRHLdwJhO&2A*9o$&)_k zGj7<|V3eGUr0N>aEjJf=LxV%YMCyg4!CR=g(RKIi?2K7iTQMt`Uu=``4)rsVDWi=deU}8xLX)>$IAQ6pZ9z4SJ_h8^hywr5!;ulIozk3k#&^PYZ zA&_qfq}+~uI?sNr&JxH-q8CRpl4x|BQi~fK8)mnBSH^QX>Ny}IX=Oo}Nd5f-0tYv- z`2&&g=z>4)KZKR$`=Kz=-X+`5qs8%sCXzn&BPtZ0MTcq+!3D6E~19e=86YMZd*a@UC?kQGLfT}iT&NE(dJOok67 zht}8DF|nHm(OxkZ=P-x~*S$1&$1s#oI)kno;lq)~yO zA3>jaAI3FjW@gOqzyEHQmsSvm#~8Z0gvSNMNzv6sFqpXWJT>*y^z`%?x`C#h1vwrV z7?__255D%x_Fy=D87Ddo_Na5TG#)79qtYtYkBOnftSD<&X;Z8LC>XF<|9%?~uWgWg z6qQ>r6hu13?`LEpxg&7|;?mT_qe?1dkgi1^xwse`o4`170*RF^Fd^QF(bcuJH5sF} zp&C_FRU`E-9>m~|UN$1IA#w|*!$XHRblfFo4<)uh8{^P-d>*vFhaxY)cUndcn0MDw zdT$KnK&r>ROOH{@ZYF*026jvM54KBmk;qLZj_Vb$V^R+WASIbcA|qxNbBwk1HIY!} zqLJUzu=@Ijw}>1X8Z`X_{i62LP~RZZ2h0NF)gSA_t`o_FJoD-*Xjhu|G@gZ4A%%4w ziDICAmwlNgGgy_atu65CI3a4UOHgwolbP#}8%QnDJ`!!K4GoN#>nqqr;s+E&1rsTt zSz6x@)S>p($r@BHxLeA{#<$eVtzY1rxd*Fjk8 zK3YGD8h@1d((;J;MxLdNkDx7VQyPa|PJN!1ycSR-f`#9J?D|Z15ft-q`+ZEBcKxM0 zzr`M3Rv1YHQ7fJuOe!A)nT#Z=pV62pZ5ogP)X-QD#!fxn-7%8LY`TVlJMIDx4Gl@1 z(D*6ip^XH#TgH0;mAHlZ1@rss-_76u{&$f^qI+O^csYZ*+bO)ZP}H3R#TF)zm57gV zswWtUI7AR7zkdGtUK*QEge1KE2hSgD$c&pmey@jptk=>;z|nZ{V7qxRz`d8=+!oVq@8aIO zV!HAA$bD>LNdb9%?>>mchiWLCOK^@r$s|e)kdZ_+_8zFOL?RIr0TZeB!zau$-kCRl zyf(AT%fdt=BT%Ff);C0@@i{iFMiIWczZ$CV^@2a+w;4$R{_N}jKYMQiZ`oDV39tL^ zee-)&uU^ensY+EQk}wE_DAIn0(NBShGRR~@8`RkC@3YnZ)J6qEE2I&-Rct@n7C|sT zAR-A6K$HLy8HFT3sEn1QDyeyVL)Dw^d*A=R_F3odbMCq0yZ63n@AuB#`|Q2;+H0>p zt+V!ohcvjy&2(G1<}FFC8~+WU342j}O4K)5oyw#yi{7+f6Lc>s3g})`zMD+k_{8XJ zhHe|PhpZA`D*1a+V<*dm@KM>s{=re113rI!x6ecKkNlkCg6)(_;i8)W0MplF#{(5f z+_k`o1NQkmXnPJ5&tqrD<&YeevzLu&-@^L9KAbwJOyj5T12B#ja^y)kqtAzH)E(i_ zdJ3HE%My5vo^)D#_i6CMEe>f>bbg>mpbw|$;Nkft+N+_k@Otp3<1h_2!n8452A>YE z^zNY|t(mwh#ZCFUdXdDjSe&UO>UvG^ysj8+0J8Eh)E=MBt5tTK-$u*65&@t!##sp_ z_-AsUV~Qk8-5MP`9e#}U_VnqwN1O@d%>L-c4LCe=#NCddvjSs!b?@U4{PyqPuZkdU zSEKMpL4ITdU@#)#7h?+@57L`f91jBz58k}{?z>e8 z<#odAF*6Z&grLnj7QbTYf#9Ht{TT-o_Ov>%Smt1Jkg~X*cW|yU4p1-&<-9Trbus0J zrmy8rfwTw>LM~dZU^v-dn0sY%XN^(K0)=6jam)13&>+svz}3(=Kj&#reJak?;TG$Y zx@zT-NB3jm0_S5udC0T+bn6qwfG!H~@N1=UWU-HFCD!GKD;`IUw0K<2mJa>#SjTIC zL9MH|>G4B~x9U-j;C4mAa%;T$al!}+rXfsH4GrK7CCCk2iNuH7>VL5B2YN=z862+5 z)k>G(T|9b76Jkgh2& zS*Q5K^{*05^sm?We6579UR-Mh&gZZ1X8w(bY5$lvl-J#vYV7alu!@meVK;ByBp2@9 zja%FE0ZR05d)9mphCG}!*cd%GCJ!)k zs(pfz5y94uQW;s3Ax-h2$+Q}ZwgkLrh`s>a5)O1+k)%{dokBN+J_>0(%b*X+oQp2L zNIP{ZfY{OVk2mRz;lS)~ed}Ag!iY;xIXisl@FA!C0YV<0$8Bpo7wO)6?^QT%Q=lOD z>}Nk)p7D%l#50Ot`N~&RU_5>Lw0!&9-`3k1_Tr;~OW&Il}UM(IZd;&4S;zTz}>y~L&A9I-yhX^7SE zZpDxo7)zctv&c55ANkm7%I_GqJ^f>0;$K&eLC)Z+W8TiUW%EYaxqYi#w0DnAB+cJF zua|RhH8d55dQ;!Q$A#M%d4|#zI4_Hbc&i)$Y7{?k^Bg7O_laGnYGI1j7apRyXYU?8 z_rMzZp+koh7ZpzT-+w>OQF>fwBzao{Z*1Z0rFMc|=b!>!R9T3}7a|!}cH`Z&+l5gahJjsq+kzc0W$%hHrWJol;}+od@P@${!ZU2pgLKE{giiE&-& zI*5snEt|LDFz2m0k)eHh+z(V2IOF|@Q zN(V(zV;p{XMSMO`C){2hJCR&E4fYS(M_?7I@mgV6Wz%KmRbwBIju*a%MomVJaaX{R zioUj9t&LR5wUtGhcd2)i%~c_Ua@C_P(3W{r23Mh;!ipq*BXFXc+nU)Iu>I420t%%$ zd~2{QwQVGe&&dQvUn{lP8ZZ~KXCT?$&~%L=&y z{&aotc%^kVde1CR%6Iyoh!iIj*ZJ6|0Y|NVtpQX^3EDYD5*S8?>mFqk423V&fj-Re za=QRKb`~N9J)TK0i!+jDW@l9R@I!QxR{`}cWa ze)V7nY@&nVJO5C=_|G&9qp`Y>2^2g#$^k2rbfQ`QS$-(;gyAX$ZimwL%#X^by&GI8 z`vkkHzLW`wRiPIbsLFf~h4s;F)htsg3ASz9h6#f%*|+aLj3FaBJ{&msIL0chbltHF zH;L}R*?XI`KVM)UkFw_k16L-vq$#bw-4pKPab(>zdV8qJq{c=pxfzr!`tB_hoC^*FMIb~4A_el zCs#RjLm9<(&vZDZvrgG|x-v2=X$es8NbSSmqkMqSK~!EeA<0{zJJHv8ML*UhB6+IUs1a3A9z#(AG*~TO=hPFiu}v) zdT<)%y$5GG2egjUoBT|-ku>kq?{%Mr7Dtc=RiB_HsY$aj=xC95Le5W(t|*+v(Ow5o~7ws=Y}{4#l4 z711gUv|_Er$Hivf%7GQ7&b0jcpyg#Wu>4RbY2x}9g%OTn8Xl#|B-18_Ne9&X&OBt` ztvC8o!*x!P6y=oVWlZPnFK7Dlu+ z2XnKtABQq&9J2-#5P8_j0O88V{qig%`fuE{QD-Bjr>1r5+}Sf{b-(l=&dAWp zWR=q^Tz+Ke!w!v=iz|#s8-5W4Uwl|w zjfLgsZg8AL6@%dqxTEAb8q4aN3sls8m>)++C$A5)aaB`r32A)(l)_lI6@tEPp&?Cg ziIh?sBL$5b$_sAN%Jsp#Rc`@h#POG5EHfG^l{R8E!Y178#x3)lbmGL4drm^G7{`{k z<4`1yVdZmCuMFpECa!>v`Q(blk?8T*d1U<70~1BN^|o8(jyvvTRhrX zuo_;AUWWVqOD*_nX=#FvmP|S$KE(O<(~aUbWM!0xwM9#xw)xe>ZM-nMW`tD;;Fo_p z`4FWO*ZEeYm8uUM+j%Cke&hT3vSMpRnuco?*qu`(f$?mZ6w+y9w>jKyR)B@30y$O~ z>C6ulNu1r|YNZM6O+InrgbI0MV`G4uhcGoHn{YUzloty4;lRXMPb$iIC^+*&Omh%s?O0aMcynM>T%2_v0yDnb{OYkuV-=&qZw;6# z(N|qiVxXwNbA!=(01mK>$w%6(e;RIa`A#8&#{Aq{_+4raG*ItZ)+%5{apE$bM+o~Z zws{o3s|OBs_RGGY9^~wR-c?wghZF>nci$h zAMJ-qiYRvmh?|&UJd4B5NXK3z#{#Og2r7pO-^V9L7rLJ+cSqDgK9F zc%xqC@$#3yTweN;m&&D=T&n!FxUI0cx|+Ao(tP0yUyz^t$)A+lZ@*nvPSa2OsIFvR zL%-N~&e+d)MB!HUevr8n_{_7DHfU6N%g~H2khO zg|^5^YJOknt#2%Xx@mtN-G z;v1b+%0%e{GyK&dMhnrzxMEMw5#g^2`#8_6aol_(s+hlZB17xAGGcRK4us(28@j^k53ZjDt4$9#}?(n-_ z%o209c=IMGlCau{b$~0F&f`pjX`GqF^O9(sqG(V*`1sLhhMhwJc=@5gCF)Fr0wa}4 z7MBCRYY%7^a4OwU`cOm3w5aUTD?%ZVI)T;I0>WurBsO_&Qk7#)sQ}>}h~@!5H|K5# z;%tZs_ErJaW`@l8Zu6^VXH~|OpHFW!RBIv3_^x>+uPgA|btWZ_uPO+GMh?6*yk z#Ffkaef{urtCVo?oKD-3v&2N6QTz1)I z^3&J;w7l$RUM5#xeRXB}!DAD)Yh~xwTW{5|#o+F|^Gz#F5PdI|688EI^`tBj`B@t*0jFG5WRDbNcun&;{hq-gG-Vk5(NMoUtWRKj z=Y%u+1S*pFjlsTwlMMVW;KTtB+&%}no{A-%oW{2U<2e~WBjHYYfd}>WDYZyS%euAT zT7vvYc#G%vF)B9zjyCNx;2fRJ`Ec>g+6}N zTLIEGw_i>?&w_Be#SDc=L6$3rdht-H#5me%0G|rEs7O>q@gYrTFl)*E)4b*7z`+Ar zv8HgFgU)U;KJvyhllJf5FAqKZkgiPPzUxyENa;^nbshtGb%r&`+(~By(7dIUlzi|} zxOd}^4undJ!P)GYQ;HET3FGK>ZH^bKoo2Xse zr0jtV{r-`Ud?f9qH_blxxzCmN{muJiBevtU z(kNZ7325Gln|}4u>(hc-qhgKKMRvC2`HC|jnUjJ%Xqoccaoh~7ilnTJSoWgsqm*42 z;Od~sSBAjV310-XkYHEgfbkk2t`A{db@i3+CFA((U`qX>#nCfP(RWjM%@s&&rCE^-(F^@E^ zt&$R#zpOTDerCIv*}o;a+20eU#6yOe$;MTp!SEQo*$!n1kNH=$+3$FPOgB4i52yjB z;o^527Zy1D$Te4+qyML}@Z2O9C(P*h&o)1SF~1k}L18goI1}Za2b?I4QQ0&=O8{Ly z9B^g0pk+RZ^5<$aQxLIlpss+%Zxhrd=mZrNjgTLX;KoNTY*9GG&v79O+YqZv15H2? ztdO6MD3Vw>X4p_EfRph$6NoUK-3I^*haY1-cqpiIHt@j*AChl=^P4LCJ^9H`kt?sf zQuglMi!%*2p~H8IB;sNLn$X7*(+c5EFS4Z7rodQ)l87sy2;&q?F=QaInbbz$SDq)A(5AUg`VqzYpgYd{Msfjc=&3iysIiUaiZtQ#D++0S#5hzjIK4?J3x5UyIg`J*@M!^tkL zQ2KX2`W&_Uaag;nZ&gv~`0|ynd?gczN~_nr_BC?j+iz^CGKqBA*llfqe)Z6sMJUHZ z;xW8gFw5D`@=l%<=jSvp$BrMvYSynvwqC3H`8)3Z~4J6YPvfo@E5W!rok zN|#ruPEuBP?bT%PO0f0RFSb)Y#!GAe#A$hRX(uNd7*2nq!Q#{3Hx6HYa$zaLdvY2`0a!JhwDdXRaT%P=^PZ13d=Dt8V5CJtahtVnbcNAlIswZ zeU69haOS9-aNB~&=mNEM5of8{o1B=GQ&8A^|K9J*_rHIyUd73M%NsXslFP5STrRov zVz@{3+#%OtUH~C0Egvq!F7wf^)mgKdQLZ}StW%z=(@@7asEkD` z5x9bmicdQeD}gM$EL#p({jEhHg(!C(l3RU21vGDZq`$ioyjum(AzTa3y218OMY*;i zHd44*mt33T%tVx;)j_;kdy8p_+p`7|zy-0sYP=|p-_|SPW1C*aG-%E&e=!5v>>#he zIaGp5xNc(6E+!7tYJGnJJbraq}-m z8(~jduAgyf6P_l!$4l z;c)#;8#m+IqM$2O9((Lj`NXZCkPCNTDDVFBck4HY-3HAvjs6wC(xl@v>K+rcI>z)t zht@x&rbdHF6oULQ9q(F~Q*ks49MiQOIQhbXfCk2o+K1M82Gn8P_GV>@vPLtZ@mN>+ zF^qf=FL*^Zx}Oq#E-fSvS()%gLkX6VNK2G=zM27z$u{ra$v5MZDrk^)Y+@b)N*NM| zxHujk;t-_i<71idyOHI~cE~g+!*PWYSD$g^IaefcH5$*_)s<;D4n@D?K#L~JAC@re z(i5jxax98o*MDh(hSA3dx_#s7P>ncBd?}Xlr7F*A;9Dg$u>8pj>ISHbU}K;TfC|Sx zls)^1Qn@?+QIX^xQzRY14yRsSP*SQZQ5pI5-q@ckKJ#5sc3Txms)XWf z13v1|8K^Li4weH0Kjw(jbzZO{LqB#JGx!)_Wnm?u7Lp%^T5IsDx5(MDRjfE*WnxE1 zMUq|}j80_~H@!UdX-{=$CSe5=@sJKZ>j@u||MqYHrYou_3{vpmEpc|`DAOm6W%Y-& zL8-->s-1U~Ka#E$l40Z}(uoHgAhFwMTqo}6Wt^G@>1gJxaw|djK^ki8oeYR!YQ$m0 zWsa8v)B<=(o~Dh~50;JQfvkWc33V;c1Jl9x0_wxblh~%nS!yUFd(dI9jt=3xF3xBL zv-~+={Sob2#Z+g?4^ftGPF1n}|crskOJ}Qz*mD9P<$Dr!X7a8XIAM3M- zz}gOZLYarW<3t?errVOiYJcSQRcsV0=O9)NZ7h~$h@WFG`%8S(SRa;#HN2#UrVLga zT@=Rt6SNv$=gUY@+lN!bybmFx*Wz#$8n>@q!qP?^P#maxoDkZCb6BY~ zddm%OmAmi0J1(bVSf$D{TzBo-g*uP=>(ybhe%m4`#uqXhzv^9P8XXT}Ug(sqmQS`$D;m+TQC{{-e z%+d)qINV;O_GmZQS}xCWm6vEsJd5`EFeJaB>p;dQm?dxblo!-8e(Fd-pCK zpE&Wrr^t^@)DI3&Ha00D(2SZd6a8G+dt(Kt}dcn(T%d_IY=*t0_cVtZcx9^eD*VP+b3_6 zFMjch@drpP`uTCn=f)e~A$y^uy!P6c;`wQL_OqWYpa1+n){3s-JUf!{KJ%H+LK$^M zU2z-`D;DJm+Tgk}J_@1St9=tVLOFyD0)~+G;YeAAtCGk&&g3f!mRkg?@MvRNrt}BA z8RfV2eI9-nhxMS;_c2jNOC%Ekm(qZA%~(IFu=MxCBK$5*<~K4%E3+2$sih!Cuf^dO z7xwW?QO9~r9MLct<&4KW4M_cvCBTUI%p2U%J1|7bj8ug1+7t(juf}H&3^zkJ55oW5-~HW0`(Sw4*g~S{&-hV2Ta;|?&?!D`7e*KB z6u(#4CN&*4Vof@#q>HbfFyR=NU<$mEU2Y)ReFAnoWQ>)xc_*O6t(f4~<-60QH z*E~LG`-B(ecYS)WFa`11Pp}`LywA(Is3*{GeDXXpl=~<%P?0nX`L7>33M!h-5Jx?R zbx7%`2Y8vmbWD+C406mu<;1md29!@+fXqDPSduuSnvyB!=+}CeAi;px`YH zLxV%QI*LLOsME?rTK&RRMFKk>d^AuwL0uoHvw?C3jjI%>m1IZ7rIK#tmBZTw zc-Aeo_ygn8a=0Q7qKl0}MX&%)g*kkV1XM=GBCH}v!o~>KxFfT1lV8d_T9JcZI?&Mv ze_94EjAh0Sg9-%eWY#!amv{DAY*DeY>=KR0r@U13&ez%-qu?nWvKc8CG0;%>WL;2! z0r6dXW?RGy@o94SiHu9a{W7o=VkEk-WC+7*$0^5Wagrg<*TRx1`C-YB*3w}7=%k&_ z8=G`Ircgj*Sw;0DH=mO~{nP&`fBBbxDX)F)YvpyXd7Yk}K?UNv_3JQp3=vr45J!y1 zD^cTcKhjmLulX|`#D(W zAK{8#9JCk5fMEM!Y=fl3{lHdQ2xDv#oq%SFNlY6tC?~>7<5FF<=ebzTVA5Hl0g;9tC=_;o>_3o_{>~^G#L5D z2bQ(@MGQ=rg~@J|#$0VjeS$+*LTL4YN+c?ixHyFqP&EzfO9_pFYdxwN zarpt%k=w-+%|bE;(WZuv>P*_1&%e zl{q7%OUST|OlQMT*w7s+UJmqB266is&#@RgJBHg8+=`$+oM}L15tk)%HNm5gJRo{2PX!MMfF3x1SRVx-p z!HJU}DhucUm=56e7Y+oeF?jb@`qf|qDtWszG+M>SZBS}7e1UlX>+v#k8;z|VTh zKMLH+XTN?>k$?yFSrvv5G8;Cf>eX=65TS7nSbKJ5>BUDmlmtEaN9B@eCv0XYYn@SJ zTXro?kr0k;8?`~>TD-D!q9k2Y_9~!P4=RQ+eJ@R;ktpkqL*O`X8k0ZHEC~%B4~&iu z*;d}1(^x>COrw1CNaE!R?|ILAbX(K=-~WEO`R1GD6)%5`O^qJ!7DK+# z6yslfj_l_tBTyF6SxYF6+3y=H zo8~aiLwprJJo#{f?8{&NvTi-Q?Y7(Wpx$~&Yeb1;__*cr1uuBMP>IEx;@DGIJ9jW% zMPd+T5CV|@cwGO%i7`Ip2-kAJ)^-8g0mLYYjgLlWe7Iv{N!cPKdyfI&@FS$dtA+VE z(r!OqE5d+}WvhLAlz+NyrdsnK`CD?vr$qiNFxbnB16E&9kP8?DqR(=zn;gr#yKsIE z6bG+<^{eI2{`}8N?Hsvy1m6*Ne&tSi?lsR%_`B+0hyiGI8(xWi#{2CRum1T;?Xk1Pnq${g8h7=uScMb>xv5R%s$_mlG=_#@1PTFn0z@q_a@^?0@(X`O=rZthcjq_0CqDOR;y) zh4SPpFPAMiq?*ghPt2Xrg5s7luJo~+6j*2!>IQ}eu%~&GZa>&RyI&4qpW-=O+sdtO zTy1pj{G{Htbk9Ba;QXR*X(ic!TNy6EN+({U%RP`ZRBo}dq$`Zyh_r%P!Lx$l&pIJ$ zv2D*J;Ytr@|6KJlKc=T>3>Q7xV0_vQJ!#1Dx9~M#SKzyrB^W>+v4GUZyDAD$|F{~# zZGCKzhZWLW6TDsynFRm6EIwKDuq?@CsCEc zD*0E7Q!T6+d{yGq(O?kq*Z`)O=?%nbF{tK0RYulNFpQHv9MieQiRT`x zoJW2D06+jqL_t(gLBw(1W+FAd)frZt$Z!_>1sX!WYS>Km94W=EtuA-V!aYjyolhtK6uw6n`xo+9ARj#_~Dn0kq zKxn`3eea9fndcj&;rTdcC4Yui3ajK_EsjgA^ji%_3930)t8mxCQ!Bh)>LWaHd9!@A zkV|da-dXNknc^l4+8k}BZabtt9N*)*%MDZq30s;&`KU)$5lu?&}s^| zWgI(tM2;MCOAIN%@q7X*em3H;YhJ;*J~skCEH{S#7OXD1{7Fxe*_l}!g!zDOVSDg_ z2iaAqQi;l>NA~ZRQ>RX;vTDzTdt~q4z3u>Q#AljrNqdP}tz4)KX87(KRy^&P;7KRpq7`w}N!UPd^_I4+N31)v4Au{8mAhK{NP|4IwqtdG zNyqic&nt1+dkwtA5lkC7;FkrHNtK6|CH!)@iIawHpKXa3==kR2AOE=g#k>DPS0VcT z!M*%BU~QCryY}1Gk6RmsZMzK!OSiT4tlSYt+W37!IxM^|FAg+SR@QI8W_&*ED{S(C zRYE6UI6m4K$vA#hq1*5*FP1b!O-B_;#%$f%1@2KWb62UKkx8r`ItRtk$x|nFH4tyc zc>vqpxQv{ug9v*bS2A+X@)eg~Ay2yONkT4EF2!B)m?S*Xs@rt&{HFeihap zc<@0S;Qa#>GPfsTzdO#ex%lEs^cJ`$Kl#aW$)%ULGnBNfxe|$GUMgwdT`y6x9zS;;>Qx2E2`MqRrcP)=HBT-jy~Bx{Oyt0=Qs?Qk*W8`|3P zsvK6nW>=!_#{Yg}*%jTU^3c@+XY(ch8-un8+NVGLX;muS{+ZiV)-im|*jzPt?N47T zw|w*#9K?OCLlNhZ@&z6UygA%FnJaPyk~6t(4mj{fNQ6A~|4f#me2@+mV@e;%*1Ms|lx- zZ>2mPJa|z4&tLzavf$Uf?sd9?mBMBt0%sYb43FhdAC?0R8LVl)mv-hE$eoEe2M_2WPOvMX?s?@oN}F(X?DM`bHRcxl6%u6vUkFH*|m ztTHxS!CpHY$f^f^TQ|4aK4&<2mfk+&hd1ix7W>yi@p%pkqc^1P&|*4rH}o(#7_A?MtsM zQzU)!o8QEahkbG-CZ>Z~Iu2ASw{}y+bhG+$-_Liqo1TE*aiCT8fq1x+iI4wX*m6Fv za9vf~6-jJFR;a2(q5vM5L2OeS92nFCudlxPYUdjF+))6HqjbVLRNqo@wdY1qD(sC-1tQ?4=ik zU{K?@ri!G~GV{=5GWOuZa{9rCWNyo-OBsUcJO|Qc)p-hB ziligm$EV+ying_sZnO2FQap}crbueb=ervoS9}p+{c`(_b;Q*^vZ);6LDzG-@@UrG zjKV{!?ZH9V>P9$ENGJchpfutQT6tW<%hg7@#mKS)0980q!Nez33wT(v#?}4(i~sts zR1qCH6vUXu;?uG0)niwusU8dgCU78dpdB0tZL=L*Z4J&p{G&hALzR7OBO@d7i@*4b zI*zdH(&d+a_u~fl%I5$lnDl}Lwc9g}^Wg3Fm<9Py|M5S`pZ)1y06j%M$V!lzazoh4 zHqtNCGAU=z9FSxC?vuy9_#HX+Zx6}&gJ)!ZY)0m1=462~*u<2~9v_p5gGb~flt|-8 zpTN16r-5ol)(!Q_df@8j-Zm4ARpjB#N8lSL51V0`#i4Cadl*y`D`ibSlx0I(ugR`e z3-Ib!zq%}MfA@EPSGIb!3@CWCjRQ;F9+x`(wlQ{vB5q}QaMG2Wj9l4~5Sh6h>4g<)gw&;LrqYK&Rq}hhsa$6!cx5^bd9=V>I}<%&$@$^Y`PJpKtr&_2Ts7FV^j+ zzgS%Dj30Q@PVTM@+?}oiE2V9$jM8hIN|rav!0ZQb+viOmx~UA&ul?Gu$?&>i+%h_@ z@NQ}X0|^Y{TRC!EF+X*LpJmU1y4pPINf)+k*=?P5#mUII)suAm@$qrFh{yR3ypzKAAo=DHEp;$k`u^VY}NAnZ0sW2A(-0J-GqNkDz@N zx@3Ob6iJ75B@&fL6X#AzUv3)?A?}4TsUOD@%Fn#)XN23Hc?Ox8W5%vzx;8=gbUA010rFAx3w{@o`a;zv@N0&4oYvt3ZV&qR*Tt?{oHEd##PyhEGG2-*4<* z?CfSniC$lCblVM@-!+`)({}=5Xwz;t0p$X9ToujT!?F0QrD4$8=Sk>fM)~R2X220# z%bTT1U-e0UxfkYrpOpq1&t~{ZyJo1#Jq`VUTHP$<=K!2gzyW8p4BEsm-9{Etwly}8 z!zqJ0K4I#&4d3(=;-r#r*7OZ_vK!5IcDK{0F(5Y+SWKtG+MzCB;h`aT;FIRitu^PHGGXk-Mp$u`K*}vjdqWrd98t$L86sxH_pXI`6-mJ|C{+`y7TTl0 z%0HJ|9ABEEIjHkfi*Md&6Dd;^YC8`^k%G81xSJolils1wR)TH{fW707S_3`dGf_`h zYi=)F$CJ+dJH0=73+IAL2Q9B^4e3J)4u>OFFa@jrkfAV28}5-Icx!c-nw#d?5ZX|d zLmaf0D_L-SPLZg+5^bAz*aQno$+5ntd8Y7w2X4NSaG`K}w;z^_g1%h8Z! z#P^!JN)-d)INwr3oFwhPTRUT^WF~FzjPTN%Gq{~G*FceXHW6PyQU6?O+pmv5wO*u^%nBNPC6?Omq6Ko3L0v_Nl| zLBQDX?69$;?+Hgbt@G$ z%s2)mmpq{DdkbU!XdkFo*IBCRAtCD5t}&D3wl1W4UV*k|6bn}hKVWe|r`4~w(@!*= zEIeW}Pcn8JGsk9BfVnihOWUV>Z*JMB{qj>K#>%t>g@V5gBLJV#AO&wHZB6?-{$NUl z=+VOft1Fd+xdw&NX}w5fEkF=a^t3n{Jn4CsoMur|AwzKl-GJ&R@}lbOeVe*;V-z!E zPS@T>qPmVhTMj%B9(c+1*W?D#W@cv#lUM80sh^$u3d;AFUF)?LHQzf8KQ(5vO)k^D zLRXl>mnVlHFBb=YkW5PTb0Us<>;{9a{L7fRz*n3kENicab2afP91TO$DI8T?qXLXo zQ6{+o30Fg`wL#$$YQt%uH}-?ufMm z3bNr9w_V`#(7oO_!2DI&{{38usYuWTu%5?t{Rt@ zf!er-6*GiODes&U^=%48ugE%)HkIy8VUI08aTDUjmu*4U2_>nqb$7EnXum+x(fcxp zIBDbkYy%uk<NpTBE7WVsb6GGT`SLy(|MdGE zBjz}m+VM!q&FiY(jr0@<=BO#BM#yL)m=0Xotz}zZ9gj}(YN$Z8*D95`%OzrT+qqEG zgow-|teX76u&yawZ(ZoN;%QdE=vYE*+wB#D9G!GxTr!(1khKw|T)RNUR^Cg0w>weiOj*xDgQ`*s$r=mo&TR#Zw0FmLVSg zXVIojWc`$HMG^@vfI)U~Ryq3!jJQInAtOLqNbDBAeI1k}^f2t-u7H0_tvjG`{c^s> z`*gMWYXx{J_+s{3sX#pDFtMP>20^W*3l|qh(JowPn@;+$ur*TaUS8wjF_}K=dh|^s zKBqu+A%E@}kqobyOs>+sJ>^$7G+T$0l#X$of|nkxbZ!ro!YY~X&$9?e8T`yout0{@ zdVi;Q2@}H|&m*tnulZK)xRdDHTlQ^#gX9Cg18$Te3^Ewhf2&Lt)matX zd9#FQ4}sU-V07%!vJ(W^Fc5(tp^7{Dmdm= zB(Whoa@by;xaa*E72AblAg*TaY}czP8DJaL8uik z>@-x*wx+7wUWAmnf&;JarcP3okNY5NQk-*yOPl252nqdDDkNNNSHM1ZmD`2B$NEhc zwVU@<3=C$4%=bV1)K$T$65tG-Km9iwZyobJJ{eU4ZN%!MpB3q2S;I+Fp;9)%m} z-)I`=ulU;?+FjC4x=cjGzbJK9`MA|{9aWj_6kJ`le_}!^8mG1z4MH=vOv`TPG;V~F zWIGDs3V;rPj&>rkvbO@thQ;>>7<@zOtv$b%?^X`Abhluy?ay#Lh!ju% z^>g~Bt5|8oC`0eFhNMydG&brqQLi-o!R44^?TQE_V3Pc|fGUWVN8SjsH2#yLll|9R zG0KzzMBYFr*TgnJ?}2$COq%p^iJ9jJpj6;Jo>O=xIsgwM_S}tn?3& ziTA-Tw-K=5DwtgGoU-938_g*3`jgRT>RAL~ls^q;0+L>v-poQ~|8ov5YqWIqsn$v* zT}47tUGq|B3LLMkoN}?z+?2U~{HrVilSafrQ>?7qq{J_a zgP6Ws1wO#4nws~9gf#&~pjlqt+7Zm_9Jk?~QVCH$xG|y4ir=3ibdg%FzYgLmc;LCK zGq!&<3oKcdYakzv9@a)fx`d=Qg*N@^f~roMcqY37C|8ON}M&sWwJx zxF02@NjU#F{k(gqrx0Jq!X0E|wJA#>onRVcquTC7Pl9?lkd03lf2vFq#MCHk6lJM( zUrxcCrZyNLW5anOnwZMcc3)q~xC05snzbBUN+lg-(W{kNy5C>)Q=rF3Hm|1X6UYR< zERzuYFu?1_C`Jb3k$+2*0T8iRxRX)ow{vp+`{PC2aonjg{+}#AmBV}9B-(Mi$NXe? z?0cfKPWQy8p#p=&Rn^0t^PC1$C*7L;z1@agV)z3TI+Fe4W(MTtEjO|1C6x8J{jhr~ z8fr=;Q}7;tSF@K8X*#Ml8Mj6J!HOrAvE+SMYkIJ!m^hx%Fzi{@q{HPYrm*%#$nEjr zAA};tIFX~n(WQ5oY1SvqkOk}YNF|m1hilV zIIGZ*Bly}a?f?uPkQSaQk2`J*E|LJm-c@584{2FhpKOD?7FyT$yZ~TOQ}#|&ckmh z*{D(c$|E}}qf3Zcb;*{CB~B*8mOg2;iD&$5z;MF6Mh_kcB&}f=>wFjWsrK(e=5TyH27O6z}l6c))_xO?KYlwUv9k+N)?i#|-f~ z6eUiWF;^I6{+MP??S=u{^R9piFvqjf(dvX<_L`KEOlG-P%eG4brX>C?!xHW|{rIH9 zgX~VFj`3&~&ev{~^G~JD!G~);yXx@B>sATS*aD*h0=&ZrbkR+wV^QU=Qv_4REs#Es zj8kF8RR?CK&$qPPZiiKw{2pQhg9<}kLvdxT_KDVu^M}BBv${b`?rQU z#UXN;5G?LTfIRNYGI^aO3Kf5)+!QGczYbO1-aQ;MhTb%-MbqcBRPmIQA~iNTZ0MlU zzoIWFO9S*2%JW?VeVO4W450u#-2pOZP3qZ`YSNugAMa*?eQ3UyLD!OgkCH7lci77S z97$D@HJ`~fgr>8VM(XumS@0zRUlW-fAtj1At#5@T3}7TFfo%BC?|`>BZ(cS$#_Ui? zUoQ1WVjfH-QB`{P)4SYruT9<<2TB4Ko{Nh^1cS?&P^)}a28)(t6GgLVu&peG0>94M zgMkNoi~^mlOd%H=c_MY}XgW1f5GI1ojESy<+j$D1Vl!r_m0kRLGyz4Yt&j%!mJH{x z-8v1wj}Hh2Rtb{YYLfr8DziHxUkk{@@TfEa>1$#l_6e>v$GV5jpl^iQ+G!_+WA!@3 zYwOaV$kr?JPBNdCM=zjGC4Ki@ZAz>q2myG=4#2k=75umnWbV8%@RKyl&HUm7?zQ6a z!n@A&ubhbB;%BoFM(}!R$dQs^F+tGR{lINmMHVIY*{ru|Re+l|)lh(^lnTbhu3cA0$WTbY(+_q%qKt*yybvfAl%QyfGa|n&M~R2cw@~WZSz-WoqN=yUy

Jgbz;4VoMI?qkvVY2Y znKA4$wlt&Rw^|yJgE@u+k+!aYy>7@N8X3RwBnx8#w2^#FL7u(u>hWUFnr56nhg45P z?6`&I0FH2u!#Djy zdRAB5otC7PJkDS8>Iqiv2oJ5Hmz6aRG13=?eI@i^)wHRtY7-e~fdN>|dP?QkcpTu| z^||oMUiH2i2XP3bpjMpl(#MHu`2IbTG0v$k;yF9S)*i1dc0F&cL(mttXN~Wgdu$y$5dv$Xk z6pvLVn4skglJpoB&HcK0OzA%{Zd{6=#1DHMiKz6+rPm1p?cL*5IYygqjTgX~`NusX zkrExbY-o>LH!g(R25Y)HS(?=uMztGMrHZHOub=5gJ*^4+LF&rOg`WI!wKKRE#Ob3X z@VbRI3eF<_l#IC-ZnKDwKeo+XrTWG=gHp4)Jz6=3dt8FXNXtp!HD=2}PVcRY5Rq?& zg9Ae4Hbo>yxGCXb@}!`U#N--rco1IA(eQQsNH=pKHm62Sp!{ z8{XO;?AA-^lLW4}Vuu>ag&!4fEXvykv4n~vslu*{=a|l|IjNwrvfaimq}fFGm~ziA7+E*En+QrslcJj^95Wb>SGH~&Vv|!ogh`~Eoq0wx zPIz$}3P*MkJyf)rQqolAN2RXKtP)7s1DoHO_i0eMe$|5~_Ejam7)V!b-<(KzXaxzV z@Z49s9=v!pUaB$@MXE|x%Ab^+o)2mfU-6S+-9&U@?vA;{r{fyguKcW0XBB87ZUaSo`Lue6y<0pv~c|CXLNz7$J~L~nZtly01X0o4(lKIxpK|; z*@Xq_i>Hru^2Sxi$TEXY0byBp1Rx74*Ii_LeYXNfP{cF7ps9hS=$`!RIrLOCM_;ly z7n8IN2W`jAskOlEfsI{DG74ukj(tKyRw)WDQDksl!xYnvdy6v;mIf$!h>{~B%{x>2 z)?>K?Ql8~u$G-|nM)5%1??COUF)0mNx>F-+(FEeEkvE!38fog&AY^HV+2CH(^}ft( z=W}Ui0uob`p+mTP^-KgsCxW}7Oo&>m(w+B2PDai*PrS4}kwK7Qe?r1vYi@ReO3HLS z*ytAap2lGEQep&p-Ii%(QWM2?AiPYzC-;AJ0|%gN^71VCR~}VK(U`^&smy(zCLxBP zCu5WB=v``oqAQ^nN-DJUZFi(zymLQ}#t>)6Jqo`euLyBjSAaEY4oDq;vV7cJ(z+`Z zXFbdFx3WUO^dJ#DV|w+WY`-#Ek~kkY_w2%g%^_?hp1{oMDQ)E5E*%cTWzx* z;9FXDqpu%$hpyPf*Fs%dyINtHE z>>B?5ac88(H!Jh5o@0$ZM#lX&%5?_8j>nk+bcfFWZ}Wt}D%UlJ^JG32_KX9rEatcA zUzl-g{)DCRx>a=XRq}8;7OSEK2`>T#j?$FhbEYG6$-KXtcCpvi+qk=H3cTi`je31N zw}V(%(9J2ipa9y#0rL+?)`qHZ$yrU+`S3-n0a&rOl`vT49D$&4`nY1b-ExXbFE^~|~Nx_LtC8E*Neb7&tUE-V;6aVd_^M|?U z3h?AIB#t+;$}IMsntb(8pFR+HiM`(b+?h{QhhyX{o?zg2Bq2UQ%II~NH$oAd9=*T) zGjs_CvCtA#vvY|(5Zyt|zH8ZS5VRBWSIn_I6$SHfY!hfPQ znb6wdliIdFS2>lF%#%}egR>6iy3AlFTo-5?K6{Ngoi$<_I2aSmZiaHChJs3v8eVRC z4n@mtt&y|8!jXbVfZpSkx?PxA_R?9n3d`N#ya5z|CiR=AmI|4;2(awE!?*cvr*UMm z^Zg)$%JF61X1GbrE;MQ>ZV38vE887HLP_Aeh!d*> zP#-b0+Bbn#X z;7@KCqYVM5xB$6L_LbMv<@ry_PS&|i8Y=fqF47)%ThbE94yD15ApjXlTaTSQ`dHQY zzF2FR6ST{#JOXnnm#Z;~9w)%w>sR`b}=u_S=)ac9IFA?H! zWQf^AeU%c_XJ0J5m;U^0ohvia?q(1~RV{_~)hwks5NEYcv#J*`Bz0n`=jwtqD_4)x zZqqv3svlVoA9HaejpB9z(fOC7pjHXnLzvP3UJfH}QN>9{Uc0S!Ei|Gv(rRpBjd+5# z=#Xlg8!wd4*s~M7g!H&ld`q$=C`Kg|fd-JFKH}6t7Al2U6eUbkk1orG^H~8WLhTCF zO?{NtMIsXx;FoVs>P}*fLkm=3W(!v%{Rbt4szVZvfeOCYhE)VDo8{a10)lm&(0GQOMW!& zjX)Akiey-}xCfGzSk5PteJ>(ze?G?)YnByE73pU*9|K(*9ejh9_h@!}EW}lQ){)2u zsAzWuT!ZXTOI{AYGo437Cm*k1wto99r-igl-(A~KUG0+Yz|w&>ulVd?b$Ogh3s)czd{ZbQ zoVG#&yk0FW7sf!UcaBvgJlnm^`~3h}*1igMKGVDC-Lil{WN&XisN`3*`spa(@awfs zUYV`*mjZ33VZD^L)!ZzzXchI0D*nQe0WAYo{DGEY3z56MYZ&x+k}R78120oWBGQ;0 zG%XureiO$vs(;s~oC;fNR3AfUJ4DKxfTAtTtrcGdXRH^V|G7U-j0jFK0BUs)HBs9%P1#LGz3xn}qZjn3iCdnG zr@<2_*aFuVQ{JCN+NY;N?;?$CJ1t9&4*d~6ir>XWf1^ZK>#<#ZL99xv(aU4d!CIQP zG{|J9`WZ$OaL3;hL zh%3CTL~ifJ2_tb#v{b2|NKA{Aeh=W_<>T(ccdUHCQ2WtM1mcXs8_WSpIr*2a-SWZA zetBmkNTi}HWhycfYC|hLM@}oePWwSUT8Xh68NDH;oop!G3r={$^y%)T1pd8BN9oCm z(9|;>GO{H4jM08-?k6GO@nXK4Ts1g2NIx*0T;;!T+{bQMCkaUuV`|m}qJ19tQYn@Z z&A-r;_p@wHVV-5Jo_e%CF|WLP?a#9iUlRQjL+Mq=7whkMDRl~MreV;(!9@K8ekZOOAjBm#A4upd!zj zOZ}D{tnJ=jiGv)HpT9DKP<~*p2S8oI_jKnw&D^MDW+i%TN>xg=+!q;8ZM3}DdQ8N= zr6C?8DUp>xMQGEuXt3KsUlHy=&_&FzC2JbX$SZXko)Iir?-?OV)E>Qj8MWAkr?NN1 za}-)(8_27hN`|wXoNXP5Xz=+~U3%HP|Fke9xPAq@)MhG+*m8>xCXh`rLvzViZyw1q zCXID#0lqx9tU$D_5!xRI_+LiFL$sNk%cj1go3}1G7GuZSjAKjZZuMI;IR)cLn=<@^ za{pUr+d`lFjo^p4W!73KZS?mCCPtqI6^CZ8X2>+7>;CdnL-V>0Z^jTE(QPt>|7e@& z`_y8;fDP;V&U&6+3-a=mD;$^@=H}z?1y`L}>Xk_yA05TJb=<`63BDf~d_~9{p{6JY zL7suhKX4x^8pszMzLS$$qBM4=X@}`8tqUzn^KRJAt^mqSAy0AX=k_QHA||+Ar(Q1l zT;g1NNAdC)tH-BYV$YV>ozI;#f-m5PX2!7szc1e>?+I5};lxo?r!YPb2=jRtU`9Ic z#=&XuP|BRr}6PvFMb4J$s4naTkmMa4B^1`8NZ z|C2=<97qHn!bBVe(3bE5nbkj!|KexfK@(syej##!=J;_-d=%dyPk@9dVPoOT z=I*7-l=$Zo&=JmpKK+C5hnK!}yv>SRA8{cM)iI)$^;!rSf)ioFfu>}zX8P{5B~+5)trdV;hmLvQmm^gdw~fOX4dpeor=Sp)s2y^&Q&$ z*h=8{W*8d!`aqX>z#rS&s(qPlqf#>&9#$ACP_rMHlQm!y z9s(_zTA}3s)zl3of5qb~!fbSSf*!Bi&}Xpz@6kWmA@_ba!E1be`5RDSrXmWozYMDH zN^WpJ3M3mQG(_XN|DFq4J72MvOra8?o~hj={BqXIr<9$ru}QQ0)HRy9Y*a z>qI8Tnq;A#e?1wN?dT-&d20u)%rFj8DGbL$KMb!b>F+ywEIB`wVKdQ75!pAxu77*}DP|C9E&$pN5?zlPVnC@9+A2yznQSoVlrR6?ok?)TQa7)($H0 zgbj~6TQo!KDdC&cn9F;9&+du{rk;%~M$C!+rv`oFj>9i?wyqj`G5;fMv!qtW!~DXlKiW59xnAeKiHkgeoy+g-eHsR!lMSikgfF8r`E{y$yfr7 zuP*#*kcbDFByh*;FtIBN4rP>qX%ub;?s9H2Kp`u>PUXZ%iGtCH*RTMAxI|VH;!6VR z-q#>uQg>ybW=W7lZMwdaX+lIF9eQg<&#%kOlau7Eaq{U-uhLru!qoF>a5H)@nE@g% z)#n@`ds#h48}7xAoHJ|Qm#-^E3iP23XO}FxnGzGo3!BK z0%f?5Alcguqcg*f5A701w>?IoOOop&uK&yubcNRV+WtCS`C8+>2~FHJ-%w8X;^bX@ z9$fm%(TU3<+!De!V5KR5ov3tk{Mc(DiKU~Bn_wR^R1E0XjT&P4IcijnDZmO)BNXm;=HRJ>LqyE77>4tdWULq;AMTfzdlJy*#I&Qr2YldrY6*Vv;1 ztQ0d-u*?-k{w2;`=rQ-^Wti+tthqBKbt5&(Ob)?gOSf~45xCP@e}#CE$+~D$Uy5px zsq}v^K&D#^fSw8keou_K3)fZ?bi=$WeYb!F{a^gq-FG?EN44gP3;7(J)ke!$l}Ya#j?r!;j{DOr^!d5UPNI9?sxOHQJ4b}+%OoIQEk z(i9(3V+UB=D1gp(B8I=NVlqSfE8e7|TfvEhCSe+ga1j7a1fX+aA(FC(19P9V-H&sh7&<-U#Jca z3Qd_dD1E#nu1@1nTHQwAv$B-?h=33R$To7pM?#vR$V3Ec6#aJH7+ilz0Jp~Z^~4k? zD(GF%;7ERXJiy|WMi%bf`i%##N2tRoDu917k~~5@o!3QuAC;f9`N%`gzbv)qGK?r| zJh_JR{ej@hB_df;SF6vDF8dODa%;6S&pe-t8%10to8k6B_M!#yXd6)nIa*JNM%kku zy4e^O6Szv6Wf}D@vy~n{pHf7NF|S@BYU_il`Zi$vG9AiVCj3+#l<|)%|1=M+-sFjL zu)h|n+Rh54`;QR)cmI}3WuRw&qU%rh(6>t5$G*ZZ00LQm{n-{)9P)umGdkMT^Q#0@iM$7s|rRnR7b(g(i^KzKbhvF0?HC-VPbw73}8@gjR{lFDltN zD6WN%ejVT`#|%O-Av1Tdv2eOzIo-?tO?6Sa+T3AXml<1C05Cb~?_|3ePedt>Osmstd;PY@RKfOy_!Y zLS~$=Yspx@+E7JMXtK5Cz6<>)J_iFezlunSO!t#0kf!$3A-2K?dqLvoRGixa6_#Vo z^KP@j8S;5Mj_*UP+#ZMiW54+6GFZOZXmV1J2c4L#{q;O*H!O7)+!M)^40y4%&&#mq zC3qj!vCS~9x$hG{o2dy2KI8i6o`OPsOfH5!go^m*UMP2j@{Aqw;UbO-FvGDZbxlKJst9ZJ~OLKlA+2bfnd_9CKYZ15R^E`px#xAOExnB*=6m->{5O5Wm zAm)mglhsSZ#p~g)iE{WXoDL(NJkg0Rm`7$>COdr#^7{P+RAEXBzbz6Dj83uP@#Vkx zC6!0SGtVQ(f7k7fJu=2s?aoV+fWJ$MBOa|f4>tw4{P*+J`U1X3?0q*X4TJrOgX1bI zXp5ix$2mC$vd5ShS78rL1AC7YVP%A@%?zLJcSQU27q;L>ajmYDKo4s?8m2MY7(P^n zz4!aEf)61@aeI7dBJ+GCBfSj!7=u`y0I&N? zW$uQLoG8KPCOM-!8{g;5D97I>If`&_EY%=*E}8`A7?`8I&rNU$?1ng%GX@URVgS&c z8)v@yu)j!o4Dk!mC_^u*nM29Ug`s+?i^}*cU?k@~NWH%7rU@7h7VM~G`su8<q*N z2Oqx-LlR~^olHGMtgf=rjm*X8UfmihxKbm}soxtFqaMW3lVaF~F>mVWv@ zhS-3}LMHea|4IB52H!mmD)Jy@pCp+1a6b5p76a)FiUY)#QOm^XdOEDg9x|~L9V)TQ zf0#_u5~yT~Ie_YR{zVJZh95ag#TRiCVdD6_z!QN)Cro7i}6LytKiQjh_ z#Kj7A8bc@;M6!w=ey_(gKF(yq zEZGF-)4s)i#;sWkj|ht6hD?xUfrHE5l-1kINFJZksgn?nG#%}8N4Fj`0L)zID|pxo z)7++EWd1Lx_`)sZqA<+BpmaOH_~p-5Ku*+=`b5R2NG@Y2b1}KCwy@z)qBti-J`%Rt zof?-LiTHSkp zE*+bY2rZZqSZ#7TC`Zx|lJCc7W)(656MIQ&;3`6P1N8$hRX{OpxvH|d`G9D}e+2BV zkS+AU?@^`%sDa$>^)_(gEzIYdUkS!&naM_rz2>pQ&XA3Xt_LR9Q$Z^3x1@M|5zDq^ z>iFv|TF#0rm?&J{ev3r9K>!!M+4WW z&69uL%G-8!3sokcCk^{Q?J^14*ROisypjevqgw(ZtiRTM4-u`5ZW|9>Goa3&K8`vz zGmZ`IJhfJdBAVZ~v#hrpYb8hO_?Rf^W~~>*osn2=Tx9YoB0u+B(t+e5DoWo4&(@kC z?tImM*F%XmS-Qm$Mp{TnY6#w&l$IwC88$9r=aRx33Y{fBfQI-ZJ=?DGuIA38`sdm# zaWzrxPt{_&QtlU0y8!6Y6lflGV|a@no>YxSFe|HY1%T2BIK)NUHU4rea;#XQ1lY{G z1+P~Gyun8{ILfK!uhbNNr(wu8M9J&pUM6ceUZ$JdgkTf?vELe!Bh?dad*~FA_H;N9 zEUTy?Z0A42iu_ASiK={=4i7XBiTYTRad9p*T}l-WHoa9eT2rSxEUGPV>7T*Qb)E(= z?`a_XMXs54yo719A!B<p_?_d12;$Xqk_N*jF}KWu>M_&Z6& z6X@EdiGBJLT$DEXg&fxZ-z%Q$f{Y<(h)90gYBhIHa}@}+v0Mo;d0SODN^x@Z-3}hh z3esB4`+$tULB0hj4K7^qo_xn&Xu>i9<0GutGn}S z)S?GwCi~Unjzl_83Y#eziLs;;0g&kf-7$jNp+~q#LE?#9NvO?Ho()eqidO=Bp#kc>< zV6rtx#*Fll15EB`(-6me$Th>Auf##l7{OLqc-<$74)hAXW}nO{w?6H?6QvK_Htb9u#yeR+VQnn*HUz0VL7W5 zMkBpJivJ1G;8dlNJ%~Y24E5~MVv|{3z%uY_&dcx}w!Ol%KlVJ@j{TXi)?xpW?~NXa zd&~ASBh#3Sks;wgtu4cE!X$lQ%^E)!kS*lv=Z4Ib?_@E*6%GPacVNh2F%hn?$t+vG z<%0n!I4_QmtBb=L#l=Hu78?hAjYw9k2bO;Sh=tn`t1?Digdp~U8I%E6W0rIN1l*&9 z7|%Um9q|}&a8cn%^90Gz0%c!JZ58$h22G(F=QDjybH*64^ZgD?L5@d>CcBo33BEuf z?Jg}WzD$CfmYTmo(%L|gWu$H|=!uxkt>v$SlcPt8UqNoCWxLs3=~!Gzyc=uG+`x`A z3S0O$C9< zEk zwtzzm9fsmu%?0}FIzmsAz|(&ervUzDT|f8yY4PXjpt&TTw<{~8dd3(kEPKC`!8^J; z&ne{+0Ag(80(>(W1FRAjE|y52-t|p&s!NL_a$t31SLcGX^vk61`2-n#gnWP7i%^*< z4Ds2y^nS7KlRQcfb1IytRJsE|W%8s_d0UpbO_Rt7b~83C)YXM^-|0K&Dfe7+PHn9^0gvKC0aT zec>lZT5H1oW)eDvGiYk-s~gcC1Y(U;Yw#ca)h9MoQak;Fm3bl5w6RSkDM)R0&3^1R zXjtQu1FkG?!l&+;Y=uB~{ae(36^>wHi1OcqN~xM6MfiF43FJhXhnROS!_=NKm6f%3 zy`ix-l3d546B(K0%>5EEC&>*|SH(s-ZZkF{~X>Mc3MMP~}GYyr8PB6Jb~GzG2q@JeM^tfHV# z3CeafjkOHwm+qclJ#U82vwKtLU}LCs&qivaxUv|>HdE@a@X~o4wW)}`bg77aH7CHS zooq#l(ibf@H9mvtWpaTD2s$eh@>wZ)#?)ZfKWH)-@3ym!8` zqG6+`Vu_c0c8s5G{ITie>G}L|&dqk8$<{Ecc7B{ts+%CAQc}lvbaru$#J%x390HR> zD3C%5%4D~l#9x=ZGc0NhnF4dI@w{o`Eko0@HKhH$3MTaphqpxPBiLDHqkj8Mk*fi* zI{mKx?xj}3z2x-tSy1=*(U-UR3Z1i~`${P5_(hZkIBe$9rQwnFyw6bPy5?vD(rcMj3)CxPa(oFKZL7o3S z8vEnl&R8^&+pIQ6a|1zFX2G}V_UD;Y_qXSg6Ft2aLhtyq`4{3G?A?G5yUzEqH~UBA z3~|-waFc%>yFrwt?Jx$on%#lEA`UE%o0dAkLHhuLpcS29e#; zi6$n)mi6z(!+6$nRsv9}_s)EI#5B%_Bw`PuA3FxmpYM^JPcxQv^Xb}=?ytSB+go2_ z1zTn&tMHFX2hVTs!cSIP4jOFRPB=C`(se$TT8AJ?ZC3Q$b|xxLHWnR zcaw8r{&)$0x>+YE?Hn-x%i?+HN|bpA5*T)U_)w8zhN}+N0BDC(kJ%p3yMP9r-qxmD zOf_?YraMd6fgxc7W%Y9y20ZkKEW=x8kKw8jFG33kGQSW0ZwuWX{^1<{@X!WhR{UZ9 zS0$K8(JM^u^skTfh4I5swb@o_<1(s}B%cXhR-hVbmfkaXBYe`tOhke3Qe z!xT@iu#@HbZS|sZf5rWq`!{U%TlQWR08;>7SaiDo;v<#!rI+*kvFNK?O?C9!`?_1J zpx>m;+bK%p`+LTr^CfH8ePOG^N6Jd4&kX<5q~aQ9_WN@C>#@_q`w?&B)f<|vjo(JS z;1l}OAJXvcP>q9Nv-jsaskZM09I|AL`^b=@Iml2v91K_s+sI^wA^E~`h1aYBnTQ?Q zl!eMl)ISCmw5!c%!?eEV)kaxkaX4rapxX3L^b`n9ZEBpek`x(9618p5n!hC4(MX0@ z*U|z`5-3KZaIcT5c!niyr(uH6QbS0kd$t`QYvYQd=V^H|e{*7Qt4St=RBmn=rhBrq zT(Xt{`NtV)q0*X4aM*rMFj|V2YkR;eiHm(FV_tm4kAd*e5lMB*wU#suc!rqdb+@<6 zf9Dn;aR>+{({W#W7T#Fvm~s3J@UlI~Yh1hcLaU}js4ShTkIQj7Uw$E|c-iM~T;X+l z@cewfyUfT(YT2Bs!)uG?1!bF=_3Z~El8HeOKWu!`KKc1DMGtQIU!0yF_r-$7c=7bg zl+nw@Y%l9ob_Up2AUI9cEp^+duKa5j%a*21OQvE;{PTa$4_YmJRybEpiExxm$S@a? zDyNqzBh>%+$G);YM!zsX8d}ltVk>Mhw$F4>C2268X~#*3h}%x;H)}W%E<1T9Qqp4y zP>V1);ERoNF6A)unIhu7=<#kAH!Fg?G=(tS0cI4R!+olN?~q`}$b1M!IG~ae%j{D# zOU3h&#}oP`2So=EZ+Ik(?vL)`q9KgZCu{gwSjftEq>}hh#8cr#R&g|e=V|8LN}d3Z zgGJY+0WY~0I4X4-*|!egCsPXgu zDO5Yzs@aSAJ=#+$Zm8R#%J{k9d*T$EOm9=Uf9Sk+V99*HKTyW&9TD~(-gH`Cz+z!?xo=z>2zp_`x9P=o+2yEU zTHPn~ZkB&Q=!3@Y5M7XjTV|#!>0plZV!vzn_okzS{BK--)!qPO&Lk+x*)?w!w;pS! zf74BlAxmS4;A^9(!BdZoB;Y}X2%%v7<*+^Tni?}&h!NEEH(^BwoB~yMHbOVa9Fa9P z78TnPgd1+>X`yT68!0C8#mn3=LAcllMxR3S^IRy(?(A6bm2 zw`R8gbA%vcVyFx@C0*#64ls*$g{%IObhBu&L0r?r zj@Oi}l8&B&Xc*FiyqrRWh@j*NDfZ|3 zUy%a}Bn@*EF9~7%b{ZHsnysL zxg@g^uXJjrg!VJQ8?O{pSXP0t2mF4C{ULW0(Q~>8Vtlm~cuz_&BK*0&rG?CJ&oZ7v zaFP*2o9V8eT87v#!x0qHNQ&oQy5R$avxRXD&|Cy~06WL8YDC%WA-_=m9S93d3R(bJ zJF^daYe;ckoGsuNpq25SbhStk3gf(yrpH&(dnmxSr2p-9nE*Z(Svmo?ag{}(n52^jjv6?zA^{JVm^_;AR3mwD9Pma$m33Lh@e4vZn2PntHsS zmPc`fo6nOBvc{(h&ECi~(~x|+{7)WfA|>!r|2?x5G|1aZp!XnCTMWOXL7#_(Cu)}@ zH9=H>*v}Y6x4n`pLxvkx7)SJ+-QwF_n9uG@xVaFxHykkE{rwf7TpZIE^b7VPrvUg6 z9K`7y*MopZtP_#Q1aAfGfHd9fSf9@ZllO{(7Ay&~Tr(}$KCi;hY>$%11&T;&7E&VC zw1@|btj6PX_jQpV_}!}}IiAQ`U3jUCMhAp>wA$W3e=l@63H!x<}G|fgE z+qP}n+Ss=3WMkVlH`&;>ZDV8GPR_m0`<)+fVP>kkdS<%26695Hc`2vq(;$Hbu!3)u z$i0(PC&?L-cGaR(3jUV;5E2(%f<$eSw|!3#qdc?tI3si;`ZP&M5Z!&Z^OoH0z<`9m zdR$`NUg>4f>LZL3Azr)F$6wN7(nSSg=rZb|d}U7W#?Bw}F7Rr3IA%7kEbPwt5;H9F zr%}EtiH@J)sVvvt6UP8BG_WJ zyT*ZMPCV|!K*S>{VR=Zz{2kepT=2;5?xBZE!j6J@$ufW6kC8{}HutFCb zEi1`L?2|njO%Z4STZ#O}lnV6+xO!R^5N3Zf2E4dpXR9nMLKZ9bF~K|8%xs;hiGM8i z&*Txo>W7Oie28Q-y3O(#pizb$k)l#b#npN!3%tZy49^~1*#nP~VoluvFJvSGv9YqP z#6DnhspK~0`YCT0S`5u;k$M6x*hmX_n?VU;{OwJdkb~K5<-15Fs)Cy4e^`PI$RI+D z-5pqhD)1|JxNIqO{+%T)_R}ssl0dLjuFf%$iMmmYNqoDAa}dHa9TV`-}SB1WBL}u?D(75s0l^6^jyQfDWP`# zn22$PFENuk3{XHR?=(4s2n6!ec5%4VjL_gt6@foy0zxxdWl6LU9}yF6pU?oM!*RC0 zHB^uU3A6cZRz;9cgWGO9r^IXhAyZ%V)xy^;7cjkdM9h@(;%iQ&^=MMcH)+Dw6==VK zYKf#`X5b7}L`JhM%~ud%&m@00-E%vY=&{!Ir1hNeLb)z~Q3y@VV}h`V3s#AE;Tx1eQ`q<=*4y>J!ELMEbMHQbY z$i|y_+qMhKdiNiPlpzOrNNJ^HXz2kEqW}XIsfOR%OB!lo`Q4Pi7@m$CP!1=foM=3T z;om#UrT4H-vTYW(?WhYBZ&%|&|JnBR_E{N&dUuMVg6g6CH zfU5PSWqm&{xX}|Rn3ze&PN$6)Jyej035dw^@diJZ(+Y~8srt{ z+idem;j0$U)rp{aYT_r6Fh=k?T%h9*u&?E1*B{DR(j*Qa)KEn;0XLld=L%RM1LnB( z%(39glM}R%K;}vdO&5aa8f3@kEj-J^S^wi(auLC-`do^MA*Cuzkl!0=LAyqhkyRrT zilv^*{c5CBD7G~J=Qr|~AsrM9rx8abdIh=$No2vYvJZ?+y8rvqzhI9A5iuy=^%#X^ z0uWP*q>&yB4$v+@;k%gvhL0aGOKHem_@#t&SMjxo9da-3|3q??U}RS8Nn(Ep2s{6I zE=-UmV#L^qfpaSv&8y9erDmoVYhiY94fG{|<1zx1bstn%eCvNvv3^<%=ltcZNn(ac z724|pY2l1-NMzSkCxHDViNZmA4Dhd#q#mQlGDrp+FT?_o3G{D%l~Vt+ zDm`Qd4f4tlKZB*dUopwra3tRJ-}ftGfEwF6n=-dt(%QS0p2EEU{)~~YfK%VMX7Eno zy9Ok2RrnLtA_5k8Uf7^T`2XUk|IqZGYt2W8gk^y@B(Y=RUJR5G4<=He0(m1;m`O3~ z2FU8)D@F$Dnd(Hlub*iOuI9G&a7o)q^66?FFWrf7z` z^aI$gq@bo{)uf(Yhlv|D0E;l6CMl2~N89!nO8wJ0wmJBacIqLLhRXJolP$eQuKazZ zrZ|4R_r%|ssAW^i5j9deP>d>gz=F==f)(~1*HYw8{gJ(=qGLI+@TIE)Un2C6FzIBf z$N(I7EIKiPorMT0=Jo#G9*%4J@Vco8m%smAP46<<@z<5c9+%%j=jnL8^t{dPv7Cnw zFlu4=KZtVan~7{-z=zIdHU~-gAN65vW+aR@tQu&)D#lCKByk=?d!>oKV{Ouz~T z917*PPBF;inQNl3kp7IIhl3>#{@;qUk;I#KNri^{v>n6^i|`PL8Kd?wcuTBPcATJ= zrdm84B>m*h6*r@2x*Yi*OB*OcD#&M5>!H4}Ftk|EUaJ>V=srzC)qzM8DWtusf8@8J zE}>hhLCR7iB>k=^#+RARODD3Fl^UgvE{rvww4rMUAbJuG_(~3S8q(q|fQ_R5oDxf~ zha%VNc@9uOz=x4wjG9J)Z+ig!O&VqaUx@EzCge3G>(kfC{Ll5li3^Uvu*+F6qQpF; z2FE2EP)AD!)#YfC z3?j>6Anm7#2!Ffe${0T`>$c)1=ooe-v6-pl7D~_SqBnjtepqa+6wZ@}<&wePLDosp z{>M;r=O|HsJdO>=X3&=AF3IY}iVL?2xDE#hW}|J2KN#lG*#B9#IElgMt3|XL6ZoO9 zX^{E1c;83DtmDatOm4R*VD{s7d%=nWY3ZWcNr1EisPo#B+Fc$}nopvYo!!XSUcOw} zAD5lk(XTBzjBK{4cH6^N8_7H;6uG7FKL?oQOPf2e2;PY~8I)NXTg3c#XOSXK^Rl z&>(}vPjcPL+T*CCqlIx@W!s*sJ%A(?Qd}TLy+p>86B(A9K-?-jKKe2evK9hZYFaSh zGmq}|`AZ`)WIc5}hlj|NLBX;Iq6gbELdRP1BV)))co1CBH)Gec&Bjc*3hfNvb>7U- zHRc5#cm}Mr%U?<(bKM{EnIqx11H~>=EIC+-;`vp=zXQ2qdPBq<9mf5p6%sLFJoql>;PKiJnlYt5FF4z(d z`<{ag7t>sXEDqFg2n=}=693K*KfOo9+9ius7$)s0#ykQ0*{3uKV1nLGqbvGM#?^`EkFq%L8-~P4~?IjW4`jO_3yaif_apM%ID^V~vW)a<@eL zSb6X#fs*?ePOaa2Xb08Hg5OP#6J#G&14FJ7NdXH)C!&}p@xyzbL&0{UK=Du6EH!wg zm}gecKcfT(Zq{CU@4lS*jXUA$1ok_}Z)o2eui~d%WJx73NYeN~@u`)=P+)dmd{*K=_txKTIB!7)6QbO4=*~q)wYIu z@HZM#;1Eq@&St@ED3Z4tjk}#h)2D+ ziHj2DssDCHdmsMw%?tvZmS+xBlvAdtmSPgt&&a>|H16d8M4*YXynBl`w4|N<|63hK zu(KGT5eQ67Fk?WEBOaKuBRk1?U{z*9oF1)22u})F+PvJ;-&7p5Qs)J}s)rS?Yi<0H znD*xbQJRYVTtq8bvvY*SGzrxX*Kh)?)P2zoOYRt)(~hlQ-0a(1u4z?pw8DFlXv0rA zk=d<*P~Qbbz>!a74&Sz+VRQZGj8(cTD8O?FNDJi`#%G$^MUfxFJ-A{PCL<7Hx0Bm| ze>{uuZ`$>`E0I&t^wX!X!=#H6Hh8mNixuL+(M@oghTGriv``yb!_yVYw(-@f&h^#%TOw!BK62K*a( z4A5iC+0BjDoQvk`qnO}fNjECCX=v{SV)}a|X%#e%-Uq3=xeDYW_#g9#xZBK1{=J`! zZpPXC0jwKeMHo^FIoy?Dhq4R zY2MJeZiSzAQ4rE7IUx1LsHtyqd_W?tKreJbP7wH`Dh)a4*A0WJ>kD?D!vb=^r*A;( zwA_PAWc>9X9$8U<&s_ap_`5Qi7|Z{Q$d!j3+UgQfQmu>CP( zpmq02##FDNE5N+cvkZ&0y>rv#?&EPj7_(z7_Zxa}nIn?Qo{axR?14b4AU(a}wtZ}p z3RKlHIiPVeb3c&~Z_bGgj0Yr6L~3T^U7$qf$@ZFC6WF80%8fjh&nY4N0t=)caMARK z;aJp63fC{Q5pVbqd`k!vtI4yMzD(r~G?@Os5eW-&tmi2^s!c{C&3YC-Zm@u_*E7Tj zCYd_Xhm!sX4-bXo$gpGb|4wj>04K2_78X%X7pKsJO+={Jn3Uaihj?18j6zFq%w3p;pYY#F&&@Q<}hEZrwR9}iJB2RY-G=R1A zOejgw5HLA_Au!^A^>aqf+Q$q5f)lmHEKzM~)Y8Qa%_py0ETafQsMZYJ#r{R+ zs#VJAWe4|WUbHY&2aYGaBpegy!79xJ2dlU#5Rn&W-j1J2uedUMLn_ZLg^H4CO$)N# z!`2KU-U{%`(c=DAnGhpYfGek@km2!O-s4{}KgJ;A_&fJ)!5Tt~{xEZKh$Mob!nbw- zhb1xF7~ypNcJuT+J!ri(HXP7YpOQ`7O-GDq)R+Z9%AXA7Rl?FElu~mMgH)g? z#!Z1lIE%thhTb;c@38uGUiF~wiVes;%gb*2a*xyfX4oF5CaYFC>*96z9Kfk=={a8C z$O3F?C(dnI2_JbR7sT}vgruVXGBP%`?J1?wJCaJ19mxx$)F|WcSqs33`+tV4Ksce@ zh8q=qnXtTC{H&G%?pZf0|CE`f)e-;IJ|!}UECxBCMutv-?v zhk=!qv@NEaxXZ;;y38h5Q%gLJ+cTP%n_{Mli^@FYwtSB(@m|xEFGz@IBUfMjfWdF|)9F*d=kQJ6_po}9bI~acVr6S> zYNOicIrN;j^@y9}S;yK~8&+CcYjca-{uI+VZUXD6$09LfT8t&Y%S{}EB)#v=`Is?Tn zu3HOJ?tTJZAcJ`fMa2@J=>%yETr}KIY#hx%KfUMbYLmxVKzEBFpohIfnCH78ndggF z<>!kv773F1ChL{0Pl)HO4g0Q3b`B2Z*V*(zbuo)*qYnc7?;ZT_8;#iG8U4|6(rS=a z-_Lg3>+a|3^J>?vtLbWOZS8>yhgBntM%7bR0lwoSJQu-1Lu3jKHQ9GYZq9`Iqhz7* zLYChzvg6mXV-xP$AS0uj%w}5+moV*+TsuEl>Q>_k@Vc=lVqRa{*ueDgbK0Ut7`6^~ zWlqX4s@=U#Ht&sB{NC0ddtR4qz3H>9d z3QAjdXm!QxUg5~MuFX`6?HmW(8oFBil97n9tc&6z6!gJ6y9hQ-c_wo%n_3i8kW*h` z6HA-YX6)76A>GKu1K^Sk8veYL$`et%TGKW*4=ov+l? zm7j|0CGDTvdN){LDink>`rj7lBeQ%*T0Sgwd|*b{ zr!&-Kus_Hc!RtZU-YmN~Ml%O;2dFLH6=yS>4ua9miOF^KG2cuPXf32u{NOCDT@>Z= zw4RmDb9NXTvWJxPWsGMW(BExhIU~S~J9t$07?imOwia_YhmXd4*OZ<`=+-x@;T(0QKLb^lz>y4raHU1{&x z=YDS1{dGM*rY7S}=ME=MmKxUXxz0+F{YnI!X-%b4q!U3Y(jZBgU{SZpyiG{^G&5nN zg?)FYQ>?FIKcqjyBvr-`6X4`v(DxQaz<``4odz#WJhe}~Q-ms^Rqw0GJzRj{IW`bt zlX>CO9PPPney#%^hQwO0TSn5;@Qj`6zT8U1H5LWgQ}|TsiAoyP6_%oy?4I2^I8@7< zJZ$JFjmpFtnaae93}PN5qW5ZQIU$4d23N!v-6Ff9YN!sL#B5sE#*!PC)#!5yI*w}O zSS~?mFwmF*qo0uXV2)I?rU|`WwJ(l#;u*+$UN$t1S>XCu8#7@u}9 zUi7U?c(@!0XzDXMm)DbcxCnzGuPv=6w@twJN#dE{`xe5z)^EqxYoDT}rRDhR&HhUq z9Mrq1*RUtiEljy57PAmv!1tp2pFh^JPCS_7_#%z3CS#Ze27$bKR3J_MMc; z=G$P~*49>0J^UUoxaY|JrC7C^3Z@N(*DM}ilDrL8FXS+IB|4)EK{?FSn)mIN8y04v zxS9r&cO*s#M=UreSy}9hD$v}es4;GwU%MsX#W0wXam1Q1!&5duQ1d86%p{|qch;`; zl?@zn^&4AX*Vy~T(4HM2EH<6X?^yHoK=Hgc!LWIb;peDcgWs{G&aj2Am$P+l*Q$$q z7E3>~HFx-j=gko>v=p?(?K5|y)%~QIAlH!O>b<%v?q@4U4PwqEYAERmt);}Gak;lb z_qDYHQKQAxT!!lC{fsEidFrd!Y#Dz+Zc=~>dC@#Kc~bRQizj!=>a6~NkFcploKPf@MT zZ->|rN>JQ1Q&Z9FhPU4eW~or=sx>lZw4z+Q0;WVX2&lQ;ou~0qjV74WTk)iV$`H=8 zQ+~Xu+r8&jE!UfF$Ey^7wtNx53(;XESM9;#ZpMncx^!E*`=*+?q9JB1a03POB@9Wv zuime>?7uEo>WNP=-)Xiw+-H35#wa}St^#VKUVXoY(ym}|!$v5szTc1iQk}LvUP3#X z{cPh)kbD|R?`UL*3Fp9sA;T?hq(fOfhzwIK8u$7dslq6c30Rd+>MgO<@1?4Jy7}`O zApy%?&k+ReGSv~7~W*tPl+|cme`^xR^Ebm zDU-$p5|D1VkMR1tlEtBzO|94+KUPH;E_hLa_pom5Ejm^5o98Hr?t2pn?OL|`%vSH< zS)+M0WWtvu&8yu%)^&Nm=W@KiOL)GnXxyD%CYx@oHo!AkVF$)44{9US8RDtfK1_hxswLZ$;4=Dx*6W@F@M{Wh^%flZ=x9 z6a1(sE**<$e&NNU$TiYTXWC%J=y0ny4ngPG5mzrgb_HumE%AC`RF`{^r{UKfJGzoT zpkA>51uQvN;s6B@0TKtM>tBhVzTpnX_yys+7*Gd8ANDpBz}5KcQRvLLUm3MiguWl_Is3JlBAPfdzz8E!PM-2<%ak> z9y|sox9P&>ZIRCuJnZF^Ytm%&k&}7YM(J>mUtTU0wZ%m!sGU2~S2rD6?6#b;G^kwekA8B!j9nHD7+1>mf02I5bY_M|V4`v*ITkK}rnRky^L~AG zT$_?1tCP*eKL8r!w|&3qe^Rc(tdmBQD6IB!MKvSSkGp3FUFt7$71vHBFC(|g9raDmxN8%PbtJs_k z){7aC=*t)Rlk>wWw}+5#j=-m3iwn$WD#bgB`V}0WaG}t)XoVi&prVbyeM*w+o*et2 zzvIjnxxzV4B9}Vuafdx3|8*3L5@5BXMu?G@*ONFr9-6wBIW*>62qY>r>}seb7-M!7#3p5qaQ z;Q%d^l{+749ib1XEh77Vp6nB>gHt>nXd8@bA3dlZR7qhJ(cQFwK#JCP853PP_g^Q}m*+MnoN#Hhi zu~xx*@+RN5)bj4|FgOO^e(Lb?VZaV#g$|KEOfSWwqF~;JpwMW&v^2MDPHA)8nl|IL zG&GQelD#QY&V|-dLr$gV{T1habM5d@1v_RZH}0B{d4{gZ_I}=SFWlModDeaYdcU5q zw)TFENg_IO{r;=_te)o`y`qxaJ|plR^y~Gm@h zTgkbwn%l;)WWV}ieCw3D(JeM^9A%ze#l9QkY^NxGnu1QvbnMo2l1R(rq0I49-MXb8 zp3}T54r64CK|1;X*nD^&Id-R{8Z`wiMLT&@gHs_v;Upg&rP_^uY3hvgEc)J!CQ{Rm zwS7~`YjW{Z;HpYKWpLQuP-Ky zjfqhqHzFI;%7oX(P6fM7Y4FR)$mhJlo)-;@Y(f=%oIEu7!|s?GIFscw7F{(mJ$D5+ zH8JjTjiv7NUVgsj`-0_3!hA<UZzCWXOE$lb zGDX)L(+d$+)Fj5g=_`hc#!1lrrgeDavPI3_9^=hT0uNP2b?KyU(J|RWVaD56;#V7^ z8;%zZo&&cGx7>Yt--G z&W%K#iqhFG3Y-W``UB!y({%pSZ4;Y3a`RWjFDB1|d0-$|3}0{>R@eoRHE$_x(sE1Y zF7tK!LA-O-15qs0AM_dDjJSK{M}k8x#HF)nbwp60KOMPl_d5flluRLRFP*T#Mw5#d z)X~ZK`R$+JN*O`A2G5Go*LmTjRZh&7{lIXSKLuu>b0q>tA%9eVB?uFZymdn+6H6ej+}UZjPTq>>R2#ZzA#)LEDM zu8V>NNIxrxI|}Gcat@c+pZEZMiePed#3Ma{s!JXPw?u4Gn{&088sVx#uZpJbCLuI% z4aPYM&t}-H&{|<9j5X5d6~gW-PqSUWh(hTqu}wDsYN!aE;l9DLgI*45?c5aGt&{PB z9rR&>=rbUE=yJ$^HX>gAi6Y3v4G*DPG#W$=lzie3U1g1nx7(m&Aj~VYLYsx!N@Z^u zTT~!N)xb~A|2%hmwDZJ>)Dp}>eS_vMRQJ{qj{La5ahdK>@sBQ>+=G>p#^f>4aW(*F zkzp1b=;D-fa5xF#d^;08zPOmo*8gxixJ$U#Xq|%L6Cm?hfo#-)~)+ ze|l=(7|fOR9y&N(D7{*1IKC2UOiL6s^F|+bI#tMr$EByI-#p#@lRVPMklW*sR_ipE zKE!FYbyVTr^L}}~i6HQ?LqE-c_&wX@aVuP393Y97sG<`Yel}jes0`hb$4w;oqd(|Q zT$8Zng_`VBPEKC*NU|nP6)oQd&Ir`d*MYl!3yv6(Ev3&tS{}`7%6=oq-cY@SexZSx)1VJI11Xblw~wr$db(~DF$)M3owz*?1Iv$G32)MXh;LGY zH|<2?j6fB2<=Fh#gAC~tPA};w497y&>+vilyJ@*C2@bCEl#9;XGIY2dx)I|^W-)@T zYJ<~6O1J3D8Ylc5;ajHCyE}1dX7MwP7*uD;JJxM#ij@s+0+xXHusI2+_JFxvns@$^ zwNe&WmE@djO5kVW?9srzvE{|-bZ+7aMtwr-4R>6iXwP6PMTD|?-JqD}@N*sM(ILS} zvn24*h_GUY{|!tp?!Bd_Qs**LC4T)Zr}Rr1H|~v@&bmF?!mX+e(Aj~h98^+9c5e~-3d_zkO*O%twc4CgfsGU+xj}$ z6Pt-CTtm?J10puI{>8~6yB*E%(VLT{cUqj%Nq5J})G|^rKcGet)m5|blm;J!6wzE_ zN4j(LeU7vBj$Smz`nd=&!aO82BWgs+s~N*u2UmC28cJiEp&W4uBB~)h4n@Vc?d^Nm3xaaMmwapyLIJ~iOR*UZu zCI-o2Cv<PpAo0;%hi^uh(sz=U&fWq1c!%;_#T?(>X4o z(lY@bUPq~X?(QxydB#l~fff(SKMP!M*>dy~b&Y;5T)|Bc!runJV~fKk+8JTCX|UcoTwibJ zg*A9j1>Gm$XXOr!?ddeh`vx)oAjuG@-u;QSq*%Bv`b}6QiJ)jFihrb}y-est>ke-k zwJe^6d67B)rZa|IX|}v(L8Y9#HXS0~jU@IS^o`7mQ9A1y%VQ+#-E^y@Ms9h?g`et6 z%&jcp5dHG`EYQ1paSUJI3+60-S_7%r%RJ^S<%@15iL5Xt3LOx$fpn)Ie3ei8p+?O4c(=mugcRKap@_!?nAs9*uIZ75raatI`VU8+Hz zCrx0;20c^i9rEMwE?$TfED{u9UUYX)@E+OpMwJ(-Q*x;m@(;&7hFCAbt*PYrt4jbz zVZ_Zj7vx?^u<1vAiz%93MrXYz#}~gr5G-~di)YD?ug!xkcW$4AA9tah$2);5FJUmu z@jROo0)A@9bJC*1S|m6VjOyU}hRCjg_CIWSJ@*{FT+Zb5aNC@-mk{|hP~pV?O6I_m z%)IhRjY8Ha42PV+U=!3vaHumsdf17q^qx$1rF$_F>k3~B{T8K9=X6>>daV3P$}Oob zt4UMD1gJV1NYOtKbKsXkJg%Tc>pfWS%eb6DV!)AA>aY{UG{~A)6=5#=hrlC;BT#g~ zuBcZ;z`TwK^pz0_N}`0X3uT&|)e0gajlQ9C2gAY8%c>^<{h=wR!8Pf6jbr&9+#Tf4 zW9}89z{Ramz^5Aq*&Y;38Sb#vc%Bkj3!heoyKuZjwJF`<&3|^r|>fq z5ads)DI}=VFRjTN_i<9IZ|b_Ctrz^nZ!24NqVOI>n*cBsmiZ{&YswHMv_?YGc&x$b zmwB)2o`BJGYQf#re?lQh^X)&D$lR?Hj2--iW4_)5$^L(iP{mp zt*-9f{CX`e+&e7Y2bG_^1EbD+<6OD15oB+1K&~UnV$Di3dWE9qW6?dNOCuNkB8)u2*V|uO`8rCqzP#%AdsKa1Q&1IHlf)UzB$uxeYd~pbd)3;7 z^Fn<1=(93pMH*&oZ#`vekXJH+zf9-IHjk#(q+?h@{H?%OV4oN$^Bbv6l&JC-PL@v; z5mh;LjN}ERm;hn6pG)$w$xX^j8f|^T+$ano7;P=|?FFhiCg!b!|I5wT68Hm`0DM6W zhYZ<7r1?)oLmHy7enmA-CqscE-+8q_hw-`k)>eAOln1>70^fsoEO^KOSj^Yj$eOYH zNmc1&DAx;w4^k8l;;OuCkA0HQ1x{jBAme%VKfb)?nEYiZn8T~MUH;=1o&8b>pIw{% zt7B4#@RsM33|=wpl*qRg&c)I>Bk_$MZ;f`a&zK$}X|poABCk2t$mGht{&2qSlB)Whl=p4F2Q#;v2-&tW% zI3s}uQ|%D$GwQJS_hW3Xu3{afbhkh<$5cuO`oYx1FrqN)>p2GXN$3@zz>t8uMNfJo zO?z8-?BzYD6({2{p(@7PZMN=CZ$E(~b)M}&gf}YOL7^{v?;`jKQn*CauvSgvCxw#Z zGi&%KM5)=bkp^f`)hs=MM$@vC_~Me*-#OsJz$zt#5u}qsPbm|KJh-$)CV7-X<<_DNzYX(UcR2B+#*M4Chjhw#Kn{we_5{Uv0Z> zxWnrllf$WQ*g=RN#XPb9+iIDK^yuz3>DXM*B?*v~mBmAUsIvb79gHVU($1^HOf--k zKZE!=ps`j9Em>}h&V74=?=01^QiscUV~ltKEUNnl>)FKqYrBE z!LP8pcmiWCZ>sYPh-t<$-T{8ii<(!fhC4sw1$lZ(P#0$UK2QpHQZb!)wFfvj{?Tz9 zTh&uW*a#0%JHl#NDL~wK{d*hxP5X*XxkymC-8=!|( zN_a!`3h%1B{PbI$gF6?c@*3irLN}yi#X$kofoA$kJaN+4jiq?eu9>G9$AUI9VxVd0 zUEFUM2OXViPZ4DAM^{p81Sky@i?--v zT$!`JSD>#}GWZSd5syujn9Do_xV0lo$wH!xSk+`Mu=%-gQDbCvlG{s4yQ%>Q*<^y# zdrCdtzNhu{^yHIp_z(A?iLO!_cimcAHrY`@W2B>x zV|X_yz#19(a(5J4TN?x{ul5$UP)XsDTNv|O{l0TwWB~Q$b7QTW-mg3B-QJ3^!jijt zk>sgF;`M~pY4q}hoz8fth^H~an&5cy{FB=feShWcp{EBcDwCMU#q||Eurv}|-XY%W66elph|RQ~xpPZGcEY@lplc{@;&{=z>$~<>y^a^RPWGq{ z)}F8SvRpM)8<(`4&tIJ4E@Bps$hEy-xDCD^edjiqa4 zK1CG&0gu|k>ASl2^bvNIZ|t2DUe=v}kL_8zEm1o-cemzOil;C&h! zSw@R4PN&W-Fx8UTFbWY7w;n&QBw7=lr||$pUUZUy2G6fw?PmV#nA09+f2b>{3stC` zM>)4|itsyhfyN2BSpQIlVMbJt2`3iZsD#+$5zs!(idJ!w_^WQ~#>3}DYn`=cxHG1P z=lb%h;PV~IyqvMa5*CD-g8Rs5<0wdUZUzx@dZ86L;iD8d!pj%Xq1olDm3a+Qft*mq zaj|%iW&w-SK4h|^+0u~@Z7Ah8S@xcjl_e>lPKghy;2{7hNBfCRm#;-p>{AvWr z-Pw^QJf(jL3JUBmz09VZs|uRyV1&NxC0tb9kCjE|ba+4)zcLj*whT>x8LpVR`mI6n z_(x?m-eeZ5snEXrRlIUlB22=laW9D$J2CxV?)43}e1YX)vB52j{{bD^Bt2?O+Z%Dd zPj=^gWQ4#9obcxhXn+UX`ena@OVgGULr=$L?hadM(i67}BKMDA*8+^troS|p!8dRM z7m15*E6ZApD*LV@S?_k2Rod0AC^h4|P0eoRIN&tnW9|D!q-W%n`r&semSxYVhpPIt z>M_jls4vNpH1Zw}Mq|x0Zr6FTeeuC^QfhtJ*QwIHtKT&P0OOvg@#YLlg5^Kh8z^%? zvs!$7Z_k3Ije)(HsAP8Q7^H#E^5}x9ke;Gr0`ZL`@?o(abDPf9#K+$$V2qLafMz|0 zJ4yuuzRQMqWQXsrp5`KZ_sX@Dori!>+K-M7&-0|At1`0&EX=s*gK5Wjnk3swj5 z-k@n&VT#VkH)a9_K+iAOwthh{`a6Tj7?4#bznz<>VQS5vgGiWxxNp zp#sW-p2ZySUgoI%!;a0DhwP{@6Y#ZADu3AO{2qI*8>NOu#P`g!lO*c9e7)9Se#h1X zT1njIdkOTq)3wq&7A&X+(VOHV0TCl^bs}B3fY2@h9{Y7lc6tb&UEjxk9!A1p8!W{> z1ISxnzM+Y`G{`3Y?n^&HAtC&DaPLRBgZ3?|T~u{<tOJqc+%D!#l5_F~8cjfZ0&jemqw*#Os1VzgG?NR)A91pgR^f7)! z3??X!?E+BJysp(^&(jk0$-0wYWk9>$m+_0i(2w;)NLy6g3II5$+wRtQ)DN~64KQ#0 z9WD}X9S>9}6sds{zsxbR+4*tfK%A{3MTP|N?YbdXtqhp@^h-pDcX$4(Bf^BNYI5e? zf#NpgbV!!AV7sw)@d=S;<_ahITtJ&*IauXG{Kw-~LR^GVz8~c1;i|xvQfE{)v6wMQ zm5d=@B>J9ZfcRf9EXH?pCCl(AGe~gL?0%g}Q_3%U?Hg)_D{SA5ECCRE*)TyI}!Gyv;8{o!&AC{(s%d3W38(x z_srBcfnsELlk~6?JQ(p2_|bO83vD%^02K82LdD&NL|837{`S!=$kor}9O>Z@;kP)8)%RNkM$~K9-EZ%@ew?4tRd1 z-j_YIKA@Gv)GglP6DQUrNJ}P)wfl1ie3YVi?gWwJe#|bTZM*qL1Ke~45fz!qj!;-q z2|7Cy_zOS|vb$Ye+@RMjHioW--iy;%imO_`%a;s1|9B>M0$G`!r35(qn)q*z-}Wa! z<}>+5;Omyf@QePhacW5!BXixH-`i>FzZ=%;*qUsnt;h3~EkL%w;bh6#CS}xvqW~@v za_+7X@BrI@XI?o(Dg50Z?cwLs&s=VPzWaOu;@5^viZoPlXqyuwU_45i=#*~wQ`s<& z_6FZSzYQ74%9fEFvjed;V?WI#>b{RDW2wu(>d?M>s$_nduy(fB6-p% zLZW)3Zl<7McDN1o5)*~4SrncC%fNs%LL8ts4+7d~Yn5~}Qtn`i~D%F7N zRZ#52uaWPU9+MChIH`}j^{!vfgYm&37WIK;B3gwEOq4lmq2*uHlDm90Sb5Z;VUakW zhYU0+krBhif?~dt68FmusTq7>j%+rBF~~(o^~Z|4YcDizc|*$AkG#W@dR?Ci>FS{nS=` zJrV!~gY@}vqur4QY;Trc^6)uDl^gkV32F5M9mf6#C-emfC^Z+B6D=I@H{dAQ); zR_Zvp!;(AA>&NW0;g7Q*!O`Oz?j->PqLmk3u0n2FF#PZQvAv2mL#`hJ()pHJHE z9v+k<_TR_$Tk1EzZui=FhSlp^*LMF2|F&IszstEP^f=y!zTX5PY(WtC?${YKB1B!^YBd#ib^sl)mJ0iuH?OkIyH@@X&oS@wpj7(jtLatUGiE)W!5B2dfG*k{4{% zE$k$T+1<>j#%8(Kbo`~bZhg|VsrPv3)$Q^h?JG3Nx?%&U|m#MN`AFK_9t08EezU;6&-X&QHVEO~s!>-0|*r7+25u~h{A{v#580{vwn zd-zmbB8O7E%#VD$7kLRjfc)NtKeRaBG@GifU~lJFFb3mZ=b%;5e|c?L`rqQP(yY{u z1SHjhd*&}Muc}wJ4-0@6O4==UW4FuN_J)4NuFnk!zDIW3?J+eqm#zCrEYD{*s{jd- z`Qtpl0QEKBeRW8~5+s4`k(D+6uNULz6~E7wtGObHJqe{3ttbkbc|zc>a>Q|X^z=B~ zm)(rm`=R<%AL#E2(=cDL6>RmH|B5O!+`t;ELTrUT8-FSR4?W>9t-t&@yQF`T?jJ9h z#%b9ceuQ&(_(K2d$?yJ|WPF_4<#1K{{{ZGd8NcW5@|zc~hvNtv_#Z((Z9Tl<_TRtj z)*jq&4qs_&L)WaY@3=0GHoo}Ka@c$uW-FHMjaFC^B}OFds{>D^lPi(9LTXS8Ej!1o zeulsjAb^G|6Oj>B(e^$fng!Pgfskjsj{6h;bRyQ_H6qza854mlPsdDd(Ho9{=x!Z+ zQJ15g%Lg>#fnq%?sJcnzcTrR-9eQ3A9pjcu+(`4>@uRFI6A~f2Y1k>&^D!h5EN!4# zas(h7FZVLq-QAVf&G@O+)6-Ki7U^cy+~bI^z|nBTPw>$obo1s-zuE}-Y|2;LHr%6k z-*HEn@a~IMkauQOO0wsoT+Dx25m05dto5s7y|Nuca-S%pWbnW?>R&hG;GvDZ)w(-WkK9Zj z)*XEQyMOc8UEMx(r`u25>E=_{#m4})acsSL!)^cUfm^?K-L?6(wherljjzk$^*INl z6kfnBfCqFaDIBbT1ij^j&{mMryl0C*A}g~k$8uj11hk9KsZLgwviCVj%xi%NBx5;G z1nnCzjodI)zAORz47o3cXV_l2N^2| z67tN3O=A)_#^xSJG$_$9%zFKr~k5pU*V9AJI+1J9mgph zp3axLW|vkZ{{xt_S>d4VMm95pZlPm~l~q9!#uwi@;?F(Y_)!42gH5zMTd*m$-D~Kr zt^S2O=v}(?+t^3x-VGR$_FZcYE09_+9C6Phj%3bH&Rzc}vX!RsR4HoxYp zQ-hF)Mc1o?hSgLM@WU_<2Cn(0N*jCTa^A_s26=ir^b4=&foR=y(Y)(F4~(shatO@N zkd#9Y1+Rmr|2r`9Y++T=gNF}ff){t>GO6;dn|@-N2?lGjQ8)6Xk%{xJeN5zdNZcz< z3X?)b89*V(ER9(rOga#W1OIrc$9bJEQ&SIXu-Uj$cKnIZfB?;`bB=@7rw1zMVs*6c8ikFL_ zYIRB_{xmTACXWj$2_A6NG5(tVcs&(<65NON2p4!R#Ypn%>gDC7JLY}6>$b6x_Kw@Y zFJED!QJN0g1=+PlZ+Rcd44za&zWl&Hy0p{sBVan9-aM|NKQ$iLo5y+774eO6pcs;92;vRmc|%eUZ@Tpz_ia1F9!NbHncA-F zHep2S<1Bd+CKkd|bjVHo6UT~uQWr{7%F}LYg8=xGeoRpt%8ZZ-5EyqXP(hKFMa>aV zLsHGjH1Z4qL!b%-Fht`FGH=`-_78dCRTOV|%m)FRr&ojX{0&J(lcXa5N$WXfexnpb zD1f8lPFe*`7nY@dMQ52HN0Zp1IObmxfhlDuEJgV;4ll#>c0C+{vTd*!e{VbzixG>G zHpCT3y!J*Xmcc(isqp({C{-g&LmJIz&&XNX%HAg_?5YL`c+Lj{%Ya`Z7kCZQ3rjw+ z#d4P)-+Y^mfbqN8{L4~LevaZP!>J4O9Of}9Z5Y?CXOBSH@xtsWu@dTzfbZXfzQ0BU zn_j6AGgg=seGg-WAsDRsIGxNmaR*DP)<>0!o~zB>ax(<#i@?+}9~q3i;fVF52h}4C zM*O2;iH0O@y2#BJJO0d=>X@RGqY)x|luBrk7Kwn!0c3%)rU(7#bg;Qd`mF4FATYHq zsz)`9iWmWH@A|TH958U9yw@`$gx3QJ%wr)47*7@g`@#w(zo+4Oo#uI25Vc-<&W78) zAuwwM%#Z|xRY?q+3}~D(3>hbGnfxq{Az%oMMj+dfj?)eY+CB_D+%H@9%+}Q>IAc7L ztR~_Ojus9oQXVif$PrT;T9WF~Kj-Hi9l`#xU)ys@XF%ouR2p9r}fFWQA z7y^bs{Snadou2DYaXl%V|Eq2F#342&6_LjY1cgl}5@Ebh2*c|zj$Io9hQRC*(00m_ z^g6H2DkWii)oV!yJAr(`4QD=wrrm(113knGIzjS=rx=km0Rp3SDvYK#{+b!kg$5?? zW50Dm0DMw;$daWz7ypQlMRBuf?cNYD1eOZ{ZTrLendPdn)y5Do1Pp=YK!EzY4!T=u z(Eg-J=-P^;in*o2P;s`UvQq)nbE!lY$q-m!1Pa@0*3g4{^@`8Y>u$Qri2nMjQ?OuV zh0$Hks#9kA{ox-}pbj=Yyqx^ETCFYuX!^OXupdEe(*wDXE!5L^vQYRJQn>MaA+XoJ z&|$iJp2Rm)_v>qgJWYU=n*&)Ed* z=d*q_zHc18;!0<%1Rgnn~ZdKqj;%QDe0ZC$2KpMlqRFnOY`GL;uLkjacZ%Fw_#v!rnt4f85n z;T@x%-k5}hO26houSgG9E=xffc3EEp>Y!8Wi%yd%qk{0p;UXS~eY@7w^nfB!pL3-= zp;+Yf1GB7cNPl=e%Q8phUDPHq5n;VR?QUX6Nb=h~=$B){L9q<_38?G`nnc-iPuYhG)aVjKg@Lf7RC^4S8ke`OS-l zd6cbn$tg=^LZfK=l{OD~(HVsJhdkBE;q^eo)$uSxQkA?871E^nQjtZj>VZov{93>q&S4$G>p2uX!y@{whlymb*NYFu zR_YkZLAJgcCnPM-FASf>wbG?!>vaPll)ibEnXN}1Xvol{yd>|)OF8guJ{@E*Tx>~92l`uW{45f~ z4E=Un4Fcphc}@Pe+u%RWc}{f(&qZgl-DF&!lV<=R6}%qj=rx6zqKwQ)p>ql_^Mowi-X1=`L+yr@5g?L5HPJC ztAcN~o@PkOB2wW!l~t^;D1hosw!vR`S|X| zD-aGgCShM4c(N)qr{VVS17Kj9{=6()N(#otEAr|8%VB z?vw@<+uUE+L%=s&WwXi) z&w4E~f@o~h=9UKmrNG|$vcIRMuuG4gyUv8usdTRM$5qW-L__)_ab*s9Zap}s&&(b+5ec67T z`Nl^iAdJKO!!ok>S^8Gt-V8}&aycusOin?H{UgQ0`%b4L2Uo6KTwJ)d)|!J)eu+$n zjw#M3Ki0&)v&wg3f*O`EK!;&4EUavqdGT1syu9=L^3qq~ zw@4bMDVxolD^uE?Xmtu$d3ALqD-*+sg;xg!qtGei4M@4IiD9}HU<@IYu=Ew)?EjmyHGgMN`(SaXQAv0 ziZbsU1lS>zb=iTDbS9D>okkC@G{SIj3Bxc4l@Nro*-AXhfzmQeCWeKLRbWo!Fz+(7 zVs6eIo&L>?68WW1EcX(U1$pF3$L{;3Y}=etqvP{7^B>E z-RoJd78a`r0m_NI%FY#txK_DgcR=2A%%^ic-uL@GWW_!q=@*LfUPga2B$ebU1!*RsRZ;3OuR4^1N3$(X-Yqd$0cUJQva6c{U%$)q#exn0s2uSKonLU3pnJ zJ3Eukg`EvoD@Z)XiQ50L{KNVWUbC&vhYzGNDc{#IOZPnFBB3E&dRVr`(KeZmIsKjH zpUsI+rTo|cg9i*2u6kFZ3$CtOvMNmt43q&XKGG-LqrmtIWV5vUx+4JI#jQ~KYd>%d z`}1BT2j>^(u5+a;)Vy&~;=%AFvM|4L1@oyZ4js^3{o0Gzgb^Rfe zeSC~9#W)D~maJ0d`)Bs!zAtAxp&WRF;>G!e>+zMB9$s4Sc113{anZl}%3S87SI4QL z#Vvz?>SMNf8V=dU$@fd#GmO&(YDUqKLo!^1J|9Ak1?3>1yk?N{>x%s__)I;|2Z^HN z;U_BKrKuuek~#(h^uM8Tx-fvZ{gYMZ=oiA0RUUoW_`5jx2g zjbt{t57b;de81*vmmj0vzKR*CY*DGek$*%{_=gJeys@z%=Pncsue-uqM8TD0rv zs4zJ#&J_p_j3|>c9+%XChH-c!^s;XOY?SQ|I*zTaZFg{RfX)Rg)Z|!`_o;~;+q19Z z7+5lIeT^b2Xdb+XaS$DW4v}SNoyY||S@{{bGV;K-#{s>UO(0V-EyHNwYYqJC!bq^S zx#hNZcHH*yu{0sJee#zx3+}W+#8Ww7BCDCq=m<$I7~Sh z6{m^#EECOOrSyM1$Na(tbvjogY;JD)F+6xLud-^ZHr}Sipef2u7*1XX1e2H0-PGr7 z=Q}&l@o4+oIB#rnj2}&xqj>3x&-X4KFGj_t#xRsy{82}7J~D5Y+m_};L|FDXMPk&B zzi2*=gr5I9FdF#>LLBGIgCg#g27LV+2h_Y|w@{F8@>UwV-k6t0Ha@Pnh?tWuvIaUV+uzao~g-IM=p@A@!N!{l?}#@d)&)PM<+v3Kn*bj+pan4cKy zcUu_Wqn+>V@5{=Ron7eq?JXJOF`lHU0ncOF6RG=w*Vzi@XITB~8b%$=SCdapPTVW#bjrc^KYS0P z;;z@v zi3@e%K7FpC03AFvu4#JpD%Tqnz(@+c$Mj6aa zBN@hFsWgl~AOl8&$EX|*Z1b;Qy_Wsa_A$BS3Wc)Hc;RKdDL6=r=Qah@&5?Wd?3sJ^ z^qJenD#Wk<{IwXA*;c*uXe>K75&`LAlTKFn3S$yqXFSEqQ@*CGD@+D%g2u&yMO%0e{_$3cr4b**g}c89Dw@$SNtn6Z1;X21}vL~ zC6fp5c`#4jQxRu<9;-#f3_4`Cb?%qIfrhfJ!xbqoCbIoW`_J|kLHeQOM;WpV{TmwJ0_TSS zd4ofAHaA*?-qj~ms-wOB;W>Pjx?|=`m-!`MuSIU92}_cxeAenWIkyo-^X#r3y)S4 za6kj}W4vg5N6N|jGdwt?%;*C{d2Js%8quqx*<{Xc&wXyG&73Yu%J}B;BPt+nOV=(m5-+lL;`|OL) z+|3&|Wdm;iRd4^0XjxY}9;H%QP(N{s@qNJlMX-EAsx;>sN7mBk#AdZxRQY z!pngDqj;ZJ8|Gm$k%!ED{K5f+@|~*?`Gk^&1nOEE4!KVjpHk~r9XSXMS0$2%YH(KF ztTkXBs@G+L73m13p+C<>X_$vhWCFe7b(8M{jE3rPP=1id{EExr;gLH!I+E2$*Kb@G zgAxr5jmP*S%3FCof*S za4%oJ6rH_!g=*w?>!@!Xx@ zOkVTgSf5*2$VZcC?2p_c>KKkul#c9~vbzY{vUD`zULO`|-_1E5500faIlsf}YTG!v z-F4}s!@gGQ=lfc`v4GV~d=-}Sf38~QJf6Iug6QLeJt<>SFjvrgns_!tQc14m2~L<) z!l7H(aB0zg_{Kx`-~NyP<{mwIB%AV5K~a_{P%5kxJQ|89VIpX}Vuu9b(zw}smZ`L) z)A&5Hewv=?%#DM9=L318j+SNakM#TB|H1v+zx|sGHm+T}=I-6Q=iUInZ{NNxt5x`^ zSasxw@{Dw!uxmLeIy;t`MKXeC$&PY zWOY?mw0)OMX3;7}fP*yQ0h&IaLU9oJ(@#ISZ~yYG`|+nA-ScP9#d!Sj#~-^7KKMXh zcjN0X)a#)Uhh!-)vpT@*<+RS$YK#hFym9lJBn|0MnN-?%p0rL)qCx9Ue)5_V$(Ju* zxIg^of66P393=jiU;Gz$^X5%?)tOJO`Lt5;%JN6+uKvtZaU2$=`7zEoX&@m&i!UQ7 zYtsBCp}VOxB;zw0b+7Oc@GJMPzxr2q2HpP7JMXwp{y#&Q z21D-Lx#J#T{;xcU`9swZO)InQgK;!|Hvc-`n<1$p?ud{?!ojE2_wL?vfB*M??>_qI zBN04(GR@+2!l4$-SimZxMYCbPdZ?eB%OSwQK~_0$K*7*(aEX;kzk?xxp9Q{t{kk7q ze)5TX1Y-i1KyxXyIw}Qj!ktwZ8gA!$BOpp0il48ta1%YQOgY91!!N)56P`Nk$&-io z-h0pe?ce^bJGgcrPb0WO!M~2e9;2KSISB?e#hTLrR%P+r#A#q(M z8HX5LQV;y>XFqfQ@DKkWD^$2@fh$p|+pVq7iYxQUS9L$zBqtV>g~yM7kk`~7|M;Uj zJv()~*cx!?Y;-(q#biF^C)x82|U-QPtk zy}Thw`iNN(WBJY%0p&T*G$NDtG$PT6xP`s3KKSrM_dfc2et3Z^lhny;r;#CvegCRE z=?9@d>+Zs~PM+)A1?2CipMFYPxVv@h4*33&d-V33?wz;Zl<_@vKI1QHY|pZJ(8))B zI9&<+>W+K8=u<;d3+;MW-X`K(M4x^38QOmv#-juG7Wn=*zxaiF_}~rj|5WAyMRnkV zM;ar!pB{}#B1HHVd7(fBj$;k&Ka`(AaAPjbkTe0SvJ4OJDHOcl+}e~CDtr5T@t{MC zQsu>aSyC4npftS7b4Xj2`7V22dAR9{r2ANbbo2L|_Jv^=83dEbY{L`u)CY7Gw=}u#4 zjS*GMjSU!l4XwwL1hW0};6#EG3a(5zIyw|XA(uS!l{T(GeDLsr3@SLVRK0F(z1c#b zx}SVxyQe{sUu|J~=Zd6j2iGvUxFv1=ok#D8&Sx6sf3s_E)Dr>nQgy(Sr%&9SyLUwY zKYaMmJ$m#A!~bB=7U^z7uK5Tk&s7H4{;B8r;Na%<8}423{=*MHkPX*qWL8Ich;=|_ zvZ!%Z>D(k;sBNA6QR5-^w!LxVhJ0AzjfeN$`|rMkasC_bEgT%*hYJIke%?;xltze* ztkK`x_z1B5l8b9=e0_0U#`m{w-j+8|xDxT+y$3Sadjs=4E+F6-zsON%aNJ0vBp*J9 zF3X=#_QH5gyEa48m>kOrLiV27Q8>2nE;YaIu?QtIW|b`Zmhq<4^LM74@tOno$hmd%7G7z6!_kmrZn+Wo;fEjO$#Msu1%CstxX_R! zs{rOde_U>$Yg#)RjX9pDVd2rEcd$AIh9o>lSi^of=9UwIZ~pR)yludTMsMI@(R<)K z$9Q~jWN!Hp;H&GmZrnl}??U(AgCU8pH$HT4z>rA0VHwp=+W^1%$0KxVGsqf|nrtgD zLsH1$39hrkpjn8pz-YD&9Col6q-sL5r`gRP-li}O2F`UWSq;jQtpBR&O)cwM1 z@Z9(JXYTy$Tvjc}{%IT>Ao6IQl%a_IzmMnh!?kCnTvRVhWoVi_PLt@>eup#*-C(Qe zcC>f$U0+`&8jMSs5J!GRm)>J_f7vH`EEWmK__~k$Jlc+CE5!k(v~{F;NXG=ql-)bzC8Wu$7QcHIMVPq;Mn=VGmqcm zhj4QXMu0r0-iDlFe|d&5d{GTm7c{1Q6jfvj|GMZ0wny%F zLSAq%DPQfwS^IjP*)K4R#zcvadh;x8IR}GA_k}t2Sw=5ygTmYBVUbKGqINHRe>5iO zP(}*&Kol83c%@F%5`L(khB%Y6A>a%P0<3;4*OS+r2($M0lmQx(#i#&T=&$*QM=}ZJ zmdCNaOr{}FAnZgsAl9tbTroL{sXSNCZ@&UVa2h8(wZ1^VR`3`zXQd`=8WtQ!tq zv%lwDkn_AEC+!u1DkBQ$!Rl$~W#DhV+8S5nsyzx-&m@b!ZOIxF?s=co&U2jn=fO7Y^|(qx64PIK|1jTd47*=E0_36RV?;~D--I%95WG~T_sRGq zRP?yqNAbd-DX)EhG%6EMjLFMZzWG*J{g%@qNi zA4;L*V^li%q(?}Q_hT&2<7s#}P1=yAre7}_2hk1Wcg+1PqOnx?0Nk>lkf)*Wp-c?A z>E&ZEPxGl70m>c^_V-?wQx3eNJor^=cp@Fe^YN7mpEkbB7X%HS(b?o|8el!kA`H3O zEE@Q!T*#`GXxzv37hJPA56AMG;uI_D(Rt84tc)xTd2zF2LB`>@p06(s#0MMHPtQ%^ z%Pi@nc=lmbU$mI|^2@gs8f|?Ok7#GoA<4<}@R%j0P08B~Nn>(~0u(BprYVx9(K{x4 zDvz!TgPn?Mm)*TR`GUjA$%$;j$qUfGl-Ncj@VR@t;oi>Gy6B;DD;MV1!j zgYuId3$G~$d*J^)e7SEOUvgRJrutjk;?F$zngfTH{0O`{U*EJmWHHFzYg#+c9|7{h z8sO-UvM9>3x`Fgi zzjK3Kex>uHk3PZ%tPe#7NTalP@}7Se2D$Y#)y|} z>->zf$bhtY7!D9lLsDo=Qf%WqB#T5Is^C|WcapD`8=jMRp|8JYSQWGk=G-iwEDnMh z`RY1?4-qC#H*el_AAS6hd`yLXKljIzxFQCKHJlaA0%b~S1(zU?EXF}lWtZ79hh?0N ztM@$XHPf?i=U15d^(~I|c6WD^F+Le?JkNod80L7_+)MlI76*M1V-F4vg#R=oa55Qw#G(HEu@49|79ZW3v-Zaulr{v{;os;ra&sx7x_ZrX6^G87B zG#VJ~;?wW^VhjDYwl=YMQrF$QbyJA)JS2}NqcJN3%q7onvfP`Osy6x|;wO2*&-n7I zO&@>!v3v&pop;`muekBG78(;|2$~UqEDy8yMV!%ic{peo(}veYd6|DX1oX8GSP`hL zB@ubb6(@Up`|iE>-*?AHNAAY;>!JgQJvV0MIpl+0>p3hv&rieic&%aCGxHf1zo?wh zKfKQ7ze@LtCC^-G#6S5!4)i?tOzB~Nly}~K+x_?d{(s6>8gJjajeS(G3K{)8c`%F* ztAJw}IVuxp8mz|QK^XV{Z|^+2>&THbof1h=mNJy53@KkymCAPY^zP2qp4s`q^J(Xt z-aTigd%D_`FL_h)-cW|}lql`{1TvDise5TJDVl(k%)FTZ68Q!YhzJA#r@g=1>VWD2 zp?5=X@!98}7Xt$W8Z_Q%GT-RHk*D~u=Q^(SZ~G9X%gZoZ?;i_?$&?|{Kc(2VZCmlh zmtWX=SoHnu;>H=7pDMBx8GjO?UdDRT@t)V?&$ZuSNSXpgAbP#QG`ly2tY@~#Yzw_+wT(_Aj1q{Sr%kES-+H~tpT+fuN5JV; zl|-F}37GUA3O+)yfB$}4bdLo%Q7*bR_y%*%iKxz&At9_QIZ zAg2XwcDam4C=rZMu2y@ePC$1Q5B?c{NL6Ioh0NbQ?aU&BDI)+~3D9G?ybp^tMKLfi zP%v7FciKt`mJ$Sv{w*>paVB!@=_eAGIC*@(p6a_N`p&r?4;<^#EFK2a5++1zGr$EM| z%`@YGKHvI)k~d8DU9%bAzhySx`Jvv`>|424Z`Wg$&-lCm7Oc{mJGxm*R&ZX^PaS6TeHP|IY8XdggH!%6Tre ziB_0%A3@TeTgOof5FHwY#xsFYNp^1-(XKu#G_|eMwu5KqrcswyI;AQPdMgG0-HM*} zZW2al3j(e1%<0goPFft1f<-v-IHTQTNMd>eoEGTGhTZFK>nlkZg9di9=hF2*YRI7#Di z4FSipf&OR)&^l|w@bWH6$S9IKckU=&Yv72s-zs>%Jojrqb1$#k`MY^G6M=V+^`5+J zGx7epm}icMUspIld#eD@>aAf%oONpR%QUsQds%mZXKI&r@2%2I;3GY*zb{YX&+>a* z=W$!bsi&DMzrDPEp2>27(|GU6v7{`-uix|g#s-wemz^|sN?V<%HZERxpyH0F5PVa06+jqL_t*Ag;jihxn%mSTehmM zXmD6M9(BNVycE;l)cRa6gX5Fm&#znOH20q@c{hRx6rtS+c%|`kyYr9yW*&ihBZrn8 z+(&s#LMH;pXj$wT+$Rg3Ppi7%&$A>8_R=x%^N0G-u`sWmHIgw23?;3JVpczvXpzY( zZl3WN*Io`kd(`@GzrR?{by`gKyU7ns9aqoa&*bmV{9XQ=I3CZ>#PMrCdpgefyYl<_ zwdbGTt6zKG6Ny_-8^2p4;CMQ|9@FW@eg66Hm-0#&8X77_wB3( za`t!nx!JS)-c+x>4E`Sf?dPfHyAaYjCiQOt8-K>xw)xgJ;0zvg$f5|(x91p~GQLpH zC;v^Jj(I(e-_PUc*TnZYe&)HAA&)qRuJdx{*E3nfiQwUJyiE1ql&}8G?|EE5`+d#? zzwhUCcjo_kdHw9~_un&Lg7@D*88|*<8S-~KChwPY^p3?ZWx3ayVKDsqbbiRoMFN2@+a`-(zPb9y&9w$7KW{5&mk`LXWX6Vxvbhdee&p*`Zncst} zFpnNZlSP)@8>P-55K8%9zu%bG;`rq_erPNv+cu#gX%elIL1AeJ7KKjhVBXQmU|}f3 zWWLYia^|SlL4WRf$GJ5Eb?k`Q3O~Q!sxI)HWz*kjw94~An0TXgGf4AZo6m#{FNeRw zGHCI~Ea`IAGB1Q78`T%(( zsJ4hUZ>>XD-m$dbI(ST1`hqy-`9z4DOZg#H6;dj$_G)uh5?lq%zj-OvUe)hX0 zhttLL@G}tR*Zg)Gcs|@~7KrC@^XK*a@@G@MZkDHg-&8Z4VmdE}zuV7K%x>z*Mw?kf zoAdJJ8Cw|@-`ckxU_e^7tjpFtd5G1uE%Ce7sJqdoe*l z`@6`dRE+4q?t3TW^<+YMmoFx6v-r*Kjak-3{t&!!y87=rEIF=uocum%T&eK%^589A zYs3og1m@0n*oc)B4hbNn^}M_ce)ja^ohKWAy!;mX^9Fi4e{Q1CH^c)pkIQwYI6@x} zo+eF$;V$$~Pe-4P#iojSH=Fjr{9Baqk>F)Q5i$_Z5s!pTN zh(@gOR9PY;gXcMJo6YM|{&HRC@9{@fS^UN%&Yqv2Jum-FR{8ZLvYvNQ`Of>};W`fAq)3kRfoxg*@D3=|k z3TFOIQ_W)`rOWAA|E`?A`7@(~=xuaqWY1P7>Ulc-@-uN-<xbv(@%?vRriF0r z_6-2(1%BIN+IXcPP(oQfhSX`=6Th)6rI6}C-uaB?MGW%uvtRpfdk}x7 zgn(n2pR4v*=9vG^ulI8Y@W$?V?`~eZ5 zx$A)D2#1{UEQ4-ND@vDNd;Q4ImL4KoT=}i3GB~~Sv_1veB9?y|o~w>{zSVuNSj11S z$dkwQ7zk7tdK|}6IP%P~uAhm{pb*9agS?DS-B7}+4`=ah->`@JL!NFp@K-jR{r%h| zEB)i$@0GJ5(bRs-M4nSC$=pe0G>0EURsQ2uBpTwz)>`VUN*g1$uJ<15%(}E zF{K$2TO51d$V<{wMJQ=+?f-}KsXv|5>#7qV1Fg$SojXV?(EKxEMEc3MP)sWxww2SrZn0|=wcRKKH zt~ruYnG^#$nvTwQa%~rTEcrj><#;D80;3^|Y}+^J9-WD=jpX0u`KGh#j08}BmVYz% z8t(JHQuxT@#r5hK<9eK@q5M)Fj|YID19iD_D}TSK8k?M|Dsd+O(D$q!yFX8^j0t)GFEj{9u2{NlE$waBE*kLAs`H)IsbD$VD&;7xgm)5n-s%T z7tCm&fgv*{iM*ucAU^#CaTz%B!2{2avhhA^?>YU-I$-z956IJ$w^BO)(d0apG)=Nu zShsSV`LYsg+7Im*LlC$nx+R|NbZEdc&!@aLj|8=K_yY9C7==eFc~yDXJ9%m1CH(Yf zTw5T&Jpb}`URJ*~=DDoLW5!uz58uOD-w$2=psf;zwwlNF=fKra5A@sP`F)oWQ=eYe z19>O%oVe+}(y`=0Em$2a<9U3K;`#gU`F?iXKIC_RDKw{@Cc3yzmKcNaY{ohUWwqSP~OU0;uO}5#rAWMZjoVb|laddcI?Hk$d`4 zbu?Z|h+KxzIEp8F+o(jTH0lnu#e_~hDLWK0O`VI^DbK6nZ11+Hse@~H7(b?sfbgy8 zlZe00?Nd8`D#*6FE>vb#tonOPt zRBBJQaL)Bl686xHVBgF0GLH4v_JAk)SJJbJmlE-}3dFJcQN>j)(Ykq#EpJ)^Ur>I~ z?v0dAraZI8lD)Tlx6xIR{hgyP&{ZmKbt^6=jsSQzv>C4tC8j*{=Qs;hH1RqC-Jl-y zRT_`$CGh<1IlYG017trU!7Ox-`zem6jPtA`;53C6&__)$$>*gk?zB?Dcy4uJj6y?eEA2nSBoH3X{q5&)v34{q-c+ooy zV=_sYv<@i!5z9zMCDu~09X~XR<-zmy-*KK@1S%#k+Ce90@JlsaF^Pg@d7Q>s@pztu zjAS^l9UUYvI!!Gv@+}QhreGk<=%D_Pmc!$F*3Ituvp7#5fkZRq18q2VKzqnlz*7GGX9&012 zC!ATJyYg7G9Nz!qX(kerz|TnC%5+l5t;2u5RlFX4T?&hxMORl>v10iOJCe}}<}+$&n4MC_ zTgF2GW{)%WT>T3I=qyj-nLw&4@(jqK<}o@bblr z;+5(J`H(LLMC!xJl`HMAX*EbQ5oR9&I(F}@)+PwI;3y4WrOmt(5cX)t^tb(fbBbbV&BhXxTNI&wDDK4V9@`SG5=1IF^rM8Io z=B_i|DW+(+fa%X>7lwG75b!n#O;H}<1H0Z2iVQILJQ5n9myt}*T>J;zDX*~|TQ~FXnnIe^V-=Yq}7Se|EU%wIW7tM*&Em^Ny?Y2|x z*4i!xBDHC2_GLca@6+Zvtj+2fQ=6bEZJ#{o_v^vSQ@(XGS#a+B}W$J5`NzNb3F6lhvBv^IK|b;oYzESPqk z|8DQ6&Z*qOkTj>r5rvs^2$X_?&5aiaLXmv>G@LI?~AhY$Fd&I82{Ver*U9TF^Fym(nWc`{TCJ$+IvLy(X_ z04>+8TVJePwbBFw)xCOn9qcp`Ww@$Bid;?AAh#e)YAi=m+*+a8{DYu2nO`uh5k zAxUZY*Q^durU>mvz=R4x3+@u(O_6x<{6#S&T0aq;Dr2w|3ls!|$hB+NRtI&!gnrS7 ze<&v8=>{VgG9EpCR6Kt4sCfSTdGSmKyaHi_yf$s#RIKe;DD->|{zhS6X2Fe8!_3)(sD{odVs#ofDijmCH@ z_lW0j+O)~iE?>U9;J`p(A){xrGWk6}``3CMso&>0_jvAcJWbOx?_a204YUy!h7s+K z_G-L(#FWX0gM-DxvVW$JcB6o$5nqSC&~MG^HO2P6?ZuWYTarNugK!z%ynbUefAHWz zap(3OYx^js@cRwxHxwIGS9;c||IoqvZJrZ;CcmP@BgS6eH5L ztJg%Q+iG|6EH%SFa-If#%7$kKK*?kn4wrRzidT0R>(^~4)~#P}vOC5kjK>%s;T_PO z{vLgg0Qf)$ztF4tLYv>vyP@dX&}DTg=dZlSW+zmITeuftNLskGjW3%f0(HiW68h}f zv*N~$8^z_zmrd||BI5%B2BXjz4lptyn4(1Xs8gZ?Ge#dm!!)VUzU0vB>60f?CLfzZ z`RL)JV(`JB1dKs55HUKjbH~nN&z`--rX`zf)Cz&Y>jU)Uc&fT!_2K&UR3D^NAf%#H zQXil{#tPyx%DHOgs?qw;zR!uA#zKI0Cp`|K{^3Ij19$EggHkFUh~5a6j4IP!Uk}TZ zNX9|hElL5(#P;pmidCyu7pvE-PHk8M3w6LpxKSjZs2<(Cd9%26>!v9g&&4BX^NdRN z_VyO=2aL<>H>@|~Bt+9&CveVty^aJ9UOdEJkYUBM!sd; zGW6kn($!IHlp)}SjLh4%ZI=?RBuY8ZvAchF zv8HE@6w#GNLk1vTym)T)=&pD@hNnAs?%45KeTuS_5n)}iUG-+$wykE2*tl_HGDL|d zc*yIf-}CcW&pghw&Qv{>b3p}t6S%o?$Yie0WF&+xPllcpSEW>5y>i9cD?Ff*%Ss^d zM!?X&p;z=0AHXPpQCYr)$p9n;^#1)pGa$k5IWR`^PV&Nd2;bPbbBEQdZYiZ05HV6D z4~A6l-lMOxf`vwtIZ(m8PGBT{`t)gW|K5G;r)jeo1BX;Epfxnwv13QEqwl5Bvs;4z z+_xaQz_V%l59u$I?&`HGs!vx<4j?VwXrx&$1H`VEyUgna`41y9;XRt$-I@8bsAUVI z74&*rpsUeGpF4Lx4H|0@36C@mv5G2iZStD>|JAEk75n$?mpssIo<_87>J0{@8`p0b z&EWyae|Rx(6t954_wDF29)X+)-EGjBjCs!@Y1d&$s;X361OlT7+I#e?-w5JtCe-(DR3^k{MP=uz`j@~KhePF{}*X2jy^m21{X49bXvF$v=W9!g(+@r4PJxUM2Bu+BviK1ZjyU03IF_Uw796IU)> zl!E!#gho0b1P_D}jE>i?T`dkCJX9RgK}SQ#>p;|r_E!ZkwRTHKt_~gJ9>U)*KmTF| zC5%dM-%9z@4l8N8!mtd&?BG?H0C@PL!^KC3KPqWAeQN6ITA!sO&#(t-t@wZI~fGI|##GhXl zckkU*TfA0WxqQXiB?bhP37eK8r4jD}1WiVzZ{56A^!E=G2M-<6xxZK{PcrC)2MS8* z*|TShGiOelM=G9d7@8TqgjZa-a<%yFx8I6GO3Q%}nfs)tE}HVG`1ZR^-x}Gxj{x{u z9VpLSCmN^q4)HYbc6|2Cnc~Nvek^|a>8E1XuHD7%-Mg*c;9Z7Mfq=mo`os6nC_V?% znK3Tn?MA=Clqd|yyLRm=KK=AlYwIW&U2D1;+I(KxR&BptKkDC;=dqZt8Tki8crIQ) zHqEG`OTXW0fMD3X382-_qAf-w4m`*?+>n6sM>~d|+eLHeiT45lrIZ1K)2B{b{kU<1 zL4#)&hqkO&tBuR#v|?rP$tNG1r}I`B67f#yP&s^BjV-_}K49L=@P3X6ZAHM^5-eYB z{*4BQ7$~}Y>9Vy|WHAPi7(m28z@U$(4PBeA_yCqD*a2TCJc!0%4`0xl|R6v2es}W@sOK5pt z0>>IHoOe1vY`oxGBud4!okpcS@whoIQ8UKWM|6oVTw2xDmY<(FTJzyISO z;sNmPSMpHUVP}*I5#Q>{O^tG&K7G14cIspy1`3Y#$JOqDg(BJqcH^r*C$QFyP>6`b1M$uZlmPIB~-GHoSY|Cbi3ro6Ped zDTb_#qxFwO_ct;MxbcU#(O2MocS7k-FG&4fUzH*P5%y^)AXjLHWih@ zB@9f^(gp%$NTN=$bO8p1vuDm0fBW0t>^X5TBCV8{Idp%h>C$+%a*gqdI=~q=i7m_=dJ20MoA+ zzk~r83~M0`%BAt_*>lASF%|9|IIv%e;T9XYWW@2&!^aw>xMxBpN(KrmqnZN)!^JjD zk%74ooQbuqz>(495D;Uh6JQ+_MvQPt-XaAbqoLCr_TVwUQXQpzbgiA5SMA zMVXD!s>y-0@M7Z;!hH6DfdQirzgMnWVeZVVje%Fv;NSymzl>l$RGa_y+ix{Gxw_c5 zf1fE0C>#h6xX9y)guxiklMNCczWL@Gt%tPP)v*MUE@&i}u#ryU|7&S^I3?-hGuW#}p@wJQ$WR20=Gyd;0Vl zjW7-ryF@!%d|!&=CDn}|fBezv!R}rC;vHLxy?geW!O5n`%7}DXhGh=CR#$0S9DT*! zy?f1=Kv}96&psrJ=8fKm`v;>~p!8$AqaC9ZU=%d3RC$=ORu)Qs|L%U{;Y@R2vjx0c z-YrSqE*O|FM*Ks@1iVuZ95_()Yx>)6rNNlMnkzTutpZOVf6kq%GoLN_%=(yIr||Mk zwY^U@o#Bxe!~vRb=iCOXYv=)8!NoShkRk`Mbz3ylRO9Y$Tk{P1u2bL7bQGpD!52uI z4%SFoZPS`r_hh-ehw)1I?fh@Wpa1-44IEuHBg7u{As-)QkZHS&lJ9JzjWgmE@C>HA z{h+}m^4nUjvm|D3^^U$@m-14Qk|}-@d|(=tE~h`)P^Wbd!wr2oh9H-}m?Z#D$ME;r zC!d=vW`rP#WPIujgFsAS#t>k#8F?zO7T&q@=gb?8d@wxsORh(@r{8BCHD)GIH}2j| zQ|7+^?t80i$a~0|=CxEWZ^}OYwhMuZr)kP^M`y84O9_1T`KQIEEt||ZjNC?>T*5&` zQMi0Xefjr4SYHi4hL*HxrZ(S@M>3v=Cr%tMuE^K~9e?+`-96BS(&?K73m29_Y7) zb}=9!SpM6;{hJI)r&MS5l+#==UaT=;rBVhKK}Yi;hz`Ey1t_|?Aqn9QVG&Oe1P2yI z^$s5;kdbC~;5&EjycvM@@84&mnz*}@2P2Uf5)neqU`Ud1`LF%`G9>-aVwcXlbqq<^ zB(HD(@)z@5Vbp6t_jhTU97d$AnmU1Ei(-MKVFHfI>Y=I^ek0D4Mxc(N8IokcWu3Bq z<%U3sr)al?K31>6+lUcJ3=04CU;ia#@CW1NwCnr#4%(Ddrlnq%fe4{-`}RHwmR}cN ze)VPXsoFh@st=0y@nCEOvOd$=x|&hv zlC<6peKq%JSr`gf?AkUz=vk+}`jg_5qaWK;l)d}*HW&@+FT{w1VFFq1kAM85c{j0k z7Jd1@{_Fpiq6$%y$I`$5pMST3D7+h>JJV#S9}FxJC{N<|7&AMq9$Epj@34sRXM6;j zu}tojSR$j*PqQF8#(e09X9)vBU#PwQ;lKSs)0y!=lloic#o!MIfi~{}&te9G@MuD| zhfg3g{_{WobFpjpE?XB1{Q$o3(~mzDfBoyX=HEA0%d z@h;-{R63dmst1N#4>$$D*D*j7@F1jL#|U-&|M!po&-gy_!6%=5VjjrIl=S;vC;goZ^&Ezzg-Y4@t|=o>347{g==>iK zX_WfrZH-R6Fr|~J3Um~#gTRypM!;A{1*H^)fssn4uiU(OO&07e#hw?8SgutEl}5=H z3v-z=0cJQM9S0*&(1?zNEkYm3%@sue*H!2*wL_zgBc|{pY^ZzEQPu}3n-~gM$aBN` zUU`}HnNWduf^8ctm+1Aq>x&&)coSpdj=r5%kML$-M-V)cP+A!6HUT3Of@b*B7ftpE z6ed_eJlSh-HAX=spd@lY1H-=*E)WD5v1Uh?d-6JB-2|WhM7=;b;5R#gu!ashxG;)| zClUsv9tk4w3*v3k)Cs0U!7C6($%|=j?BbUKl}feB1RvEbohfQkf66Fvnlb{;!{N2G zW;~AI(KfBna+QKvu2)q;pS+GlJKCj9fzYV73#QQB>jTPZuRIp;G{QL8tuz>*@jAtz z#HeP!>H`J~7GY;0XI$*x%4-F~66q-y!Rjalh|pF9tUW15+GD~P&y-FZ2w=)fT8Q;%M-JN{goBDa!89fY z7LRG^1L_tAX*`@6ut-Kpc_4f6_MR!V#t*VGd(=2j90A&e?ar#{Wef_?_Anx0RKkO3 z%jPXwFY7^Z{MTcW-82nRykU*nKJA}@28@k(En!Gv%`Ez2`uGR(R3BLGNqkx;>0N% zAf%ol8&X$H#*}WjSV9<*77L~0J12~QGoU1ZWQL??G9-0%n{v2!-##sEeZ52&ravjrC2aDehi zy`V0jjF=%w$^z>lP>&EY`UhkzmS75{W<+YTI1xUlnoYBR=JJ8{eKI7m{WOcTqEz6a$XXgGsvX^>AxS)Dyf9YXs6V4jg!=vQ-Z7t_H+-|R zPd{fLMm!9|&qdP<7w{H4V+KS#(lGw7k|Cf^13m{198%ksr^+%so0b-@(NhTNYXTRyd6AHZ~ElP0Pkn8fc1Bf5g3fvy7jTu4?NRhHIT`QSdzct8@Sh` z{QjOekBJxb@@h;>A3`tCgZBoDo7Zm`AHa}w=%a%g4BS<$m$8U;I`sHqaZO(57#lGL zBje%04$ZC2>OBk~_UhU8?SHd6K;ME9dHWsh+NtGC7E=gA(qf`^eCxOfc*jnMWdFs8 z*p=n^vnR$>mP;VO>x9t>IvnD|uux1GZG_PvWH9PAH1tRUskRiAfKdqu2nr>$8@DhK zVMY+36X#$0zr^T>5dk3pn%XF|1W)hq8ELjd>CBiQrGoV`P%u_$s*;U3QXe!`&N~?d z5?ouU4{RaMeHLVV^5m&0s1|QVzAiG&5y%C$&ZX+^Xn!88iA$){Zi@tjMif7$FQGI- zI}Yeey}-cq>ZL|IMMK=+y}e_gK$%1dWfZ$ph6d*8n?XraTG>vP5m0yn1|{BObx`rl zJB8PCIA6%GDOiLFBhai}aWCPWj0?~RVIKv710x~IA3HIzuqx~3AUxt-!t@2Esi1hE z7_x&Ch9pL?@n%>dFDJZD2pEN_Crn?&O`hF>p!d_KPgG}Qgi_iSdbX_eN}2FSMZ^gs z0G;zXfKreLlm-^dz90n?Z$Oks1_7Y+{lR-$TSbfP%Xp+JW9|Kou2B%+2hXIO(#8q& z|InCr?>vTjfiVew0pFlOLw}~j;MKs0HqSl2Wz^!&MB>zwP9;q}kNNbQ?}gSz?~<1r z;dCF`BEw-2#&ApD-rKv;=s`Q@J_aHTexzqx@B30NZ5wzE{%q1FD#O}<;kDW}JHJ6o zWCRq)^_u!((^j~vJ^@*RHjnoy@4*O#;flJF2BwlBo9WCc)GB3pH%=2oAnzyhB!bl> zJJB1X0mdW@`3&~ZUZDjvq~72mO1s88g(WHa`}<9%V+}*5uEEz|zkXZAAuci<9_4r< z!T&KJk{1Vjz~u$rLHs*+Zp$mZ&jy(CVz%R&cM|;EjyxAa9^m2pKh=eV6Ze3OUr*J? zU)MnJO&NV@|16Teb?Y{pWkUP4X^!IC@ClYAfzQLcp*i`}KcLgu?vP6Bx&!#(xyY18 zWIVBqMH9l1v}i~jA39M45+i~Oq+{fb6b+3;Bbv}5CE-y|B^V$`AaugCh|YXy*1$pV z9DXI&=+~t|!dO^hY7;F-#A`nS-q9G1A%`4-7*(Rfz+;8Z!VF0=5)p`xg5d7%(3_oI zh8}6#a2bkNkh6O^QyWqThJZ>v@c6_*kYOQKlvET8@{cfk2tY%E8HZh#_un*e9_wIX z&GWyVxB2eu!r^NunGm6N&%&w*hTHzr$5llW#Sj&3APJ} zjM31a`h!B*xlG;(7%9v0DbZ-4Oq4A`TM?jrqCBuLHoLE#)MEKhpFFbz+TgW-!ho0I z?%n;x0eP1&`g~byA7O+bE&Ku{g0)xhR-&z&psGp)EioJ>g|fqxNrY8bTD!y#s1Ffl z4gqgZsacinOKpkviDJnbM|g>?mceI-7E;H%c!!KhY@YDqFQ*D*Ze(>|E1n?V7etyQWR!smx%Md>2g? z;68a!A4m(oXG)|IoqEYJ6BS?%5i$%(bBGvGlsSq39alM;7T)z~3Un46kjpzH@02h`(7`aph23B}I+8NM zb2=*oN6sw#NuYBN6={SZJ|i=hjzBMGbskRI~9P5EF!=k9L3^KBa8RvkbPVZ9c;+Ugj*fxsxb*E72j zezMO%T{r0p8Bk z^p8IJC@q98MZgsW41^t;;^fLAZ63wK2LWi;tfRz{!f3n2$cSeugH4_uzK;O|K9lN+ zQngSn^7=Ys;4ILL!It&~9~IEnE}<#?I#ZYkv_rf@p+5nyLA(-C`Y|ptEsDj_SyUSu zvVIbILQ9Mb+_OcRmDbvFnGZaGdVx`ygZxe5L>^FFtA{FAs+SOdGz85@v6%3cK&3BF z|3O$7OOCVO;`8j#2rZe4o(6K#8i#lrv3{Ygm!`TvO6tI4t%-B~{CVTs7#yiL^cT6z z#^x+|pHK&Env}nn)txzg6WkUk*b|NU$uH=((@!6QfC%h zKOcsqS**|Ts`-HcOegV()Zyc8!l)LV!D}%J3_~yzB1wegk9A@Q5D1qD96V$sgJ};w zqG5t(rgY8^G!|Yd8#;0$pS%cU5MZvmPfv42hY zA30JSK781WhQ1Jb#}XNkIyBa-{=gIn_2tCJix3Y7bV8I&rZwQrYW+Viq0Q<*@!&aW zp*siZbLE0GmX2h4=7H;~+K=yc@w zn^LJ{_B3U(dg5o@sJ>ye8t^p27zjAN(1igSF1NGqPTH*=$C9idNYdW(GNqDKJ0mAgYdVUM} zcNmfuGIitICXImeRORmQ>9{P^d*xnO(d961fZ7@ zO+u%X%jNPOK|wIVprrGAL@Q~Gp-9wC%AwO)1jaCs=-yazQ!pfe@E#kvq(0@9tTB50 zY9|6E&PHqW00c1o!@!F$$-?QUPP3Kk8S`3TjT3fx`RaFH72Bk6qCg-BlE%D-Bs|FR z!15W(IN-bh+M5z01r?8l6iRLYUr_x~)(YjlGDe)*g8+1}HeDKhp$AF=Q&|xrpK7Y& z6HPyRCWZ1TYujmb`r)GoHXVs6Nt-u4FhhcSm{6*Uua`wM%BhYJs3*MB=w7yWen*&H z1mMrKH-!Dc!TYvVGgDabOj;{L0qq|{0tX(6ckiS{(K|aerJ-}!cHLsVEELhlny!F% zF>Mt7O`ec6)vHpWqiO3N&xnKKi9yPFeqIN>PJ&3Q`#g)#1Ob{-ja7o79m3uSqbRAJ zCy!AKdl;116orGSP8=wg)C0T~PMkO{C38?7Di5_$%5~AL!@LySP(ewO+?S@$iTL&| zibEXoA|Kj6^@4l00fS@$=NCMS&^`npfn#gzSHCd|GdKf%sVB7GUTuoP^d)vwJaAB( z;V3d5ro@3JKmPcmc_iJFk>S301)FlL7w@JHaafyHeV|QS`&WH~zfd2bvmMGa@qBqS zDlHyN=DAdTt_ss8`cr=AAvyo3UbRRsz{TrB0|aVzY^KAMcKY<&S`?c_w|DLAEBgDj z}*pEo%K z#D_{o1k>jj4Xk-W=fGK!Du$Iaas-JaaHa+LFitQk$tVWQC&Ju7Ag39EL=pf-=e?Vd zkVJ(<=TZhB9rVQ0fKJ2QW#yq{RmD0PbuRj$XcoK^qEpH}6ig|tj0$rDlLc9dk`DfD zMtAOso-BTT?bZoDVYC0j%*# z!E-20cVVX`O@ET0c~M)0A3OF;uJ4cJopw#5(<{ttfra&{11JrqP%2YK#G$i!tLYi{ zpG!b}sI)As5B+&gpMiimYDk>SmqgsjAOMXCReRF)6B&vyB3-_G$)+%|yAD$vnCe0p zme(0xiR`rGJe%okC>_LEv-ds}*v zDFTKD-}HcW3|R*cIy24f?YlRs8-wPZ0v(Bqk;o5>Ll_D;;N^HI6OTo?F=D6^SeYo7 zl}*3l3r3FW-kgPZ-W1I7b-9|~-hR?FaeazFr~P3>WZ-}S1Z&?$5ACiik5qQ!V+TLd zvy&T}VqkRW>e^Ipq@n>v859UMtzGn|-dWvH+viN4)F;+Ye5T!Djo1RZ1H3KhAJh}3-jKi5 z8OtU9v6QcI%&o=W%Sp|E%FUM<4=apKv;#ds*XLw^=sWkU_M-lF53 zMx~`qc)!5A;S;RG;f5qzzsJj0p7VCk^?Tn@i$B)SDz8-4$BH_CpZT}d`bksRHQmgN zyuu#EkpCE%@~P&0IBnPr{2Jh6p={Pg!_dGEtHZBlOwiQU;n!)Wt~|aizAS@5wKg7Q z5&2n=n||J80o4KMfZWG4S}TXjqnmc0{31*b0dFVpaTdiVc-^OsvCbJhn}a?Vd5xtD z_)VaVK^N|m2WKS{%@dzsr)J_}P++HK_&0+Fcre5J;Q>qDYBB!YkR%@S;`vKWnbJ;x zssqbax4LA+Oy%NjdV&6zRl&;9?mzZjd`JYto&MGbejX1!)?mU-8ytB0WT;rPYPDp% zv}-5yCqVNhsxQcE$m-A?K2QIFzDGdkb5B=z%`0?1(Y#Z9q)W##WW3VwXbBdtE5+*F)JiQ#YV%PtRIYMwk+T0*cZ>XF~^KyE&=e z(DAS<%yo@&vkMgKEzn{47SIiKp~)-jMTp;%Kma_Und6$tRu3Kw+BBA9$9^ro|NeWU zQGb8G?drn<+gz_-x87dHh@!*`%L{tZ-ZyRBq+_#2wlo#y<#Xc$@B-=v$^-2jLGqRE zJ(0k|8cZ8Dt~aHXx`S|HUX8p#<#Xk7l<(N92NCYc-|8c4(0jfU?O>UC?mTrp>m!H?)KQvq(2vx^LEfltnyMsUL6OBtsI@rywqT z!gl|&#k*IU(a_4nD^siWp^jd~N7F)*)jeZ;1585I7;nA>V>lWi3)E&kHMvcc0Z3-kZ0lWpn6n#EvBeWj@ z+6isk+Y4v<-cIpuFkiQJU9n~JR%_$PVHl6`JWO>Xc?r=*p%()}7$TAPmugo<+No|> zpFy9GL5W3}nFh~R@yL3e(hF>+!N^ie51*lL;9yGYCau4;O2!KEj4<;ESbb3AhQ9V+ z^rKxfu)}fd=B?u5g^QBchpb=TwtZW%O@<`;2J|%g0P?`=e3{lgTCUxgM?_PrJMvzI zuILBmWu|&Y{Na&dt5?^qUn@3k-YlLWUavK>SSQ!YK|vNl2t(2$AaZ=-#1TlHQepw5 zqH|fU4rATA4aM!-cVvCmh=WEpF&v;g;$1@LMPO74L(*^BLVUBB3J1al0fyG`E;xzGH_8kYIv9sR8XOum$wS-pvv|Hp{c&p@h&!CZynX#I!Z|LGoBgBh*7?NP1!d z3f>P0xELc$=vA2{x7f9nt%-tDy*MtWjDRZ}OWaei%n2isd6J2LBOKad+oI1J1VJeR zv|qefFeD*xq8MN(G((aM1=J&Ud08tX5e5TjNg5Q6A&q_#dgO(M5rI0!!oO_Vz&nlp zB#6*{1iVctXOuhICdOY3Ndub3z~ahyqu_;vl7|xEUIut8(LOO4v3}OUg9nTL{(dtk zFwM;jNm5EMB;LDw-=;sUma^!BNhqY$7YvDP$iRJ+&~=(RJJjd90sHz~I@h-!KhXQ&F`kLeV8JmC}$z`-QJF z?TKkI_wH_!vbbJtTJhu!1Aj3uL>VhEA|e}7ujunROhzo*y7Qt%MW=RuY)1Enb_9)u zGwqjtdaW6flF^Ty*&aO9T6Z!eSzQpnCob*PWH-rw{Kh*N+L?Eo^1~pAAqj6LNGho@T@lG(w&Xv;t#eF%LE2Fk0~ zuG#|Yt5?Z@sXm{@+O4A1in>sLh9PO8QZ~M8$_RMpWF3nH|K48h_@JF0?%us)9Sg$d z$&)8dXHAf(pV2quZOba}2KZ1T$Ebb-_BoseMhPYJq?m2}En!9R@pJH=&rG5qzf zf7N#4J1q|cm77|R<@m|dnu|YZLMfwOyLZdeNu%558G|&Nhu{f08q>bcX@}7k^Nklu2k=JY8AivmXU|x@V7(<4VTGr#aBpQqQn~P;34ULZY}yxK`A$1y;c3_n+-6s_{I`)UJ=DrB+~ zvOBX2;ISAK*)fkneE2!CJTe;t2fO=s7pA*uV7FO7#`{S6+xfHSi;I%sjqc(H7?7YX z{W;!EEQx@O&ma-r$$fo0^?ZwT1z8yh&>}0J-CKZv!jQB8i5j0YNd%nnmJJ?eZ0^#^ z1|a|!Wk#OxV&FHz2MhGVpioAzO8@rTZ`L6pKw?NjA!Tdf{{8{$Y|Qn&+5>iy<%{U; zL%?aRv$>>8zETU_jH{kmOzjbQricFY8)vMngI-TWd#asxUPMMUzhJ z+_`h|cKOjd8I(@y35q414T6q!F48AaEWN&&5YWCaUDP>&t10cYX~}VH-+u4jT~qLX zmB9bEzx_QK1V8?y_(aFy!$(YDL;*3uLv;Wz1rKHV^#AaD>ZBQwocw-vD9SSV&p3~PfMZp*@eWN% z!sE{a?RQY^{m$*XCbMA}X1yysgm{J_i2dVct*0kB9?zs+$!^Ou7{L-I=!D09J+8roKNmM{-7s0ujE6gRYC5G1No>+WbzCGg z2t!h{S`_ydH3G(v#Q?mc!urfTlma>;yjM^>FcvVvO{c{OHi`t^CjazL|73y)@on@2 z%XpSw4z4r*{9atoECL9AOmASl0|Y>fe;5aus)A8~=LneW1{>vC zE!Sm)2I&7ti?SkEU^pN@+g@Bk#|_QL$9RD-xn;{H8~wt=0bYWDL77lyP3W6B2o`P5 zPCv&NLn2cS?r2?`=g*#-5{V&@1G;g*)8PwvB{AZRQIIyzwZ+w3hW-2Z7vFsIzoeXM z8~H~=#SIypzWZ*8jewJmzJc~ldp~sOkfo;%B`-uuBd;Vn16@U!IRw1z19Rm8Sc9B6 zRzIZYVKm0G2rnY@SktIAMgZtW|4zI$>IXg&O_{og@^}+32im>b{~JwXW49-~nwTC# z-+$!D;o|70pBmpcz7p-dy#$AzuBhoO)~zr~WatauXPq1|r&Re}BJulHrB4V@F@{_3wXgYut^DoU}FXjvqf^G6Ho50|a#egK}SApN<{Y z?wRtK_a|1mR7fr(OcQ}Rww9g9&wZ)^%07leJdy9*y=Qb{02o=1ewcxwOP4O#mhiOg z?b~(~`^E3^K;t>>m;ofFKw&g`$n-en#r4lW|7>z2^#zZliRK1-U&^+%H1=$MmA$W_@?A}*0qBlu=^?l0vHV8?Z^fMmN9s% zL7ovUQGuZmgE0O74Gj!3$b9F{9rg9!Nw&Wx+OCmD(gpK!W^ie%WW+-U57|Hy#$?-c z1?(3I{$WV6DinVLfrNl{LM0do2rvQ!N?erblwd?mUEn}@M$@t^-u{P6t`rdXm( zva44#Ygf^L!mSQMT#b2!sRZ%GfopjfcoJF0wsz&w7qftM)9MjwBd$+PX<5g0aG7P zET9E~ho6}SgF)b{-+fhl_0?CF$0`|+*fMsd+}}5C*<9>DxL-oZYx7_^efok%yRItz zU(DFV+Gq%%M>HaeVuAr;y{5<_SbA_HhyRXqdl4``A^L+e>md!l()32HYjxqmZ)WIa z5WuFoN$|62i=r)U7K7oTg9nN|;`fIR9kh0fF#@j=+VR?+bvAwJ#~*(*1rlDt=r;9- zz5)T1sgkV8bKt-M6D~1GP!8&sAMO3x$Sp^}`v|bcBN6Ng&KKy9xwiIh9s}ta9;O%% zY)X=NfFc#|MkE9%Iej_&9L0e_2G&1gJ;Wb=_+Fl7Ng2WG36ItN2lf|Vef_)Q)1ya? zU+``#3m1e%qF|(tox#6}tfP4P@9dR$9x+e=pJy5x{W|>t2kn&wkvC~z=*Y*1Z3^2b zM?bM?NqD3Xc4{zSy|#%bF5bl#FJ6+@*{|lc4Bw!xtXG}Ddy)2jR5Zt!gxmm~z0P_6 zk`>LKQMbH)=Fj4~IRdmJFl`nL#}aeeDF&UV8aR0J?1i<}U*tvl?YG|=pNF3G@p!TA z+pFaYgMwQ%m2HLkd<@9&4F(&(|1Pz8=nuajY>`aJbf_=C{4&)a z?@{mkD~a|t{0}y8*O9LDBesa1#9H@PqlFNNkq!NJyPehmCGAf{ii)GooYq z^s`S*@!YP?2M-6Er`rS&&%4Q^xHSd>tptcMlDzi_dNS&aQ3p>G6h9BRGGjnA0Z~E( zBNhmXOlM*~Jc7kCbv_)7LNKL?&WJj}XeXneC>7+5HyT1Ebz-xG6XxHOuYCiZjCauf z@;J8@0dHdnau{Y1c0J07?q9r|sj7bm$`q7<=}bF@kg!7LkC_R)S74GwAO^JlJC(!eans zk~WA^$YE_+h0x#_&3v3SX>+a4}EvZ`_ySqS{6{< zB=5rR72U;i4Ip4V#M6bt`wVvX8yFa{HC0ezQA!(v$`eMU21KU+Bj=~tHT)Z|APhXL zS3|o;nM7toUgMy>(@(RWPX9o^wRz+L+OZi3lplF;Fp$V1>v$v3*OM3Z27?od>9%cK z)8g!+Ki-VF?3dTI`Ue}2qTJMt@j~`}<3%0s`F!R_-oA5O{o3R!eLQWKHEmc6=Zyvu z*7U3{E}UOg4Bo$QyqZ3NewsRf;h$rxXb7$8)2&U*`@E|wZ3Dk|?>^(-Y^Va=>FaqH ze4jp_zUA&!CE>nFqG0( zfjlEj4uOg$S+dFE2+i;y!zG#ZjTo_L2qFs|0r{E{Q8a{>bQBvjPnsP;_znFr9#9v^ zgKI`P5kL?k5mb6N_9kUg-VUs{P`SJ|yfA*W8-cu@Ku74p^aHklMWNu}K5dq`D30z) zhD2{$ys8dBKNjA^h=@U{Ljor8$Paq6gX5!zkL+;e1lqe%0Yd}A1@)yeB(?h38vkh( zE$)wxK%M^ZZWcjjM=cad3`p<+cGjW}U?5}~1G}}L6rgmVOhR+Ec*m=a|G2@k#W-#L zfu=~XR?F4YqC6R{4b6eIRXth=iMx1tckqP0;ABN z)-z+;3(q;AAw~%Jwg=nYOKqR24zzpf5q$~qp)>7#jg-^19NMXkwqFG=2ko3ALVFN! zTx+@ES%AET*C~BH?VdKzK_3mxyq~6>TbqZ^tNmAt zpbdu)BG6VDG@|{QoTj#H`3gP^iqw}UPt|XT-_!0HJYd=saWGskmD$M!*^GSPa+W=xiN8xll6K z955a`U`#qpP%QJa_;x97|amhG}i;tL3^)vRX$}M z;JyhFSsc%=QXtE^Q{Cqx>O}(_?fzkO1Ll%vV-Q3rOj|vd?OOAonCWD+g+?V!JWUcj z6Y=bxxBFIofPX~L){&UAXQQVGuA0!ijJn-WFGN%7PpU&Hjn@z74ew<{H0nashxeeF z)(yus%f#C(x11hkTu__!;P;Jg$Zk396^%S9nvU2y`?Sdm!(}Kf5MQoNC+LDIR*k56KNF-WfKO(e-kE3Nzj>< zKl5|>xK(y>e~Jh=-g)x(I)(gUi|afeXzKy`kzaL>j-`BVwDpKO+k5l+P>*ZXrK~fg z8+}cdOI*$t0#3*3eHp!wE}M}D8hf3n(&ZOT=x_C;3GI1l_&R(%qnnYH_NtG0kLLb?&1mn>JgyYPDo*jRFwiSCXCmE0RJv?6op~AVurKHmPUtXgd>2kVw-{5Why*jjru?|Dh`_(D# zEH(t3@s7a=>P#i|7)^j0BabGrtA6xwiD1Toc~{ncIA6T(qHcZ2$Jt>&eYTu?GV|Ei zI}Qu{E^o|;?0+3^FwrFW=*OBzckEcAE^5^ucF8b`vpaS8r|&$|>vj7d$?uvTfBo_H z$J_UBo)=zs|MY|BRd;^=nEgKcm+jgY=7P7LJ8aROZ*#sZw)&>pZ{N37|6|UjE8P%K z&psY%`)SM9_uO;3BXV}fX+HY?$T@+jXF-x$-#L~`6;~|IC$cQ_IKG0vc*e41(cG>t za@yY2W`6s4zoyRF@pzxMk`GrS+Z)fDdVg+DJ-=k1n$mdp_mW-81CmI1s3`DfhpkEP%G|dH4U0H| zVv$Y?;zy$UY|aKnJ~9Pr-LOHBqi*wtm(ua#9KcFvPWqNp)!S00?+lq17IEY+(C8Wa zIa(Am|6S7al0&u(YA1v`utrHB_;#A;yNXB@ahS`%f}h134OGs?-*P?440kfR>KUOd zz{6Zt7aTv0@D_#|A{_)=Z`NuZCx+Y6e_R!KJU>q_3;cxQP87$biGm!hb?4(I+-jcb zGXYO5-oK@L5<5;;8>|L}V%WpJ>8!Zb)C&Szmvv4F FO#rp~K&$`& literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/visibility_road_map_planner/step2.png b/docs/modules/path_planning/visibility_road_map_planner/step2.png new file mode 100644 index 0000000000000000000000000000000000000000..7aa7b025e078cd959dc2baa0632b5991c41e3ca4 GIT binary patch literal 795677 zcmeFXWmp`+wl<18!2-cu26y+t2X}%73+@DW*CD_l32p&`6I_G46Wk?uaJM_zdmp*q z-RJvr|DJxHo~r4pTGh4Is<)POw3><>CK@ps3=9mWg1oc_3=9GU1_nL?1qu431#j2@ z1_r~?MoLOeK}w2J&DH6njlCrdjC^#8F0x+o{CwxBJP?R0O9{u-Z5(pUNE3!HDe-NC znl?BL#~g_5qN#{qj)&71ts}#tUlH^cU;T&$?T=85z7|t`iHy3|3qO3_&8z?VW!9eH z>GST2TcFj>+D<#nKE_4iw4c_yAUK6Q7EY!(UOLfGnM2sO90Y_g3=+T3cQrhKK$ajb zt`|+?b(kpEw!{3Lhuf!DrU$sZOe`2K%q^DSOcNLv5}3P>9a=glFzPmq*_r_Dtv+m$ z!4DzWx=b!$;#2J{7G6i~ds+rp$_}_7f|P;eT^NZ@^pkSxfHymNoskR5)YytJlSIfa z945VZ66K@*hLT+@bd?bcun&q<5%(~i- z!apLXW4EGuZE|8~07)5#5@LTX{HX0qG>qDGl#J~QU$Kaar!=OA$kE#PHH>_uvo*_$ zU*vjYU@kt8T)M?%zN))ZRL%RuE(5HLpeRU-N}8ekCSk8hs}diY{-&l(gq=}#n>$as zH=5);kr6lLepwGD2J^v&N|m)nce-C-7=vb_}8oXkRmDExS%5J|D$=t;oxqL0EgORP-I&mxPLT2aGd z4NAPhhItjwOFs8S zyuJYv=yrRO4O}>1IwMQmn-sj<`}Ao&M^cWW=hzns!=j*(lao6>Tf`o~Za9mJyxfW{ zl5TwY<_YUunN;-|zto}WLNcfmSLm#e2;S`jCg}%J@}I~EA!^vL^dVlKF{ZmP7A$dA z_P98ZN0AjJh)Q6}x_qip?cs&HjL$>`5WY$<3!nxdz3akvCR+(^Ek+iBf8O9F1Y(DU zO=2UN#pzKtL~(Bg-%)kRBjCo;QXk0ECxyymBXUvPqm@d`QD=N6lP9}?cYP}uohc`j zxI747_|7}JO^Oo|L!A4ugiMJ1T58c6<7=FXoZIB0HEPRSqiCIi`u%`99MNcF>8gU& zeQtLc_;kMhUKY-GqgdM?&h?N|EqVPuB4{v;!f zFW&I;V`;6rp z+ZZoentm#KAAQ11h%-$fp(&&(+$(57_Lx?T`psu~TJt1s#;CWdTZw22mWATO+5?}`OLARl@!PY_6osk{# z3v8JLGgZ`lT1{6*MZhlz(lF7m(J-@vg9Ece;K|UE*-78huO;OA2^;ar0L5R$Lh6FE zHd=_E=ssc9$NOYF#K;ybP62I*>VQiieX^6cCt?nt$8%e!o84jkaoQu+(LjL3x3gL9n22O|pU2FWngFcdBH6jKP}0rMKO9YYf{ z7Sj$RfyjfK^BY<6$f#AN8M)cohYk{Rz6eoSfsgm;5u8TmYlQK6WCXnO1H6O+$CtsE%6}T#FXqA)RDydVh1wekAa20xN~D^>Nj=lG0?G`~#7htZ!*b z$fKiU`J;s&Nyb#ZTz}ynlNxgyV;)P$xYg%i31RIeNFiWgdHFz8yHM_@!+XS2wmv<} zwWML%+*8}*Iyk(>)c1Y%FzA=4T}*w>r-n~OpISe4#)ps5X58~#^K~vIIXv6TG?3U& zEOpfUXjJ_1*k3vHr?fp$biSjvW9_99evGQuv_Yz(hgUAYAjdp=n_z%hr6jpAd9bwq zpqBgac$>vzZEHmk%rPFAX<>NMl)jONP71d-e;b>p+qXJT*dRz($os+RwJ1 z{=upY3#!;E3%r}^pS7{st>x4_IhX~wy?mWLqbyO_3;A|TOForQx_j>9HP8sBwdXvG zjIt^bc+ehWG6ekynjrv(%Y~;!dP?uh6-wL3G*Q^#f5CfCu}HB?#>@Vl^(!_RUOW8* z{e0ZW-ki%L!-I+;$GJNOFFoT&&CwpcV!ikFBed?*y$VP4tMNbLlY4plLcJWHTJC&N zZ%}{W1$oqR*ruJT6FIK_{lk4h$SI{SOF5Nkc#wX(j~ z(o)?Y#_eL3bXU$*TBFRhOvz#Sv4t#74qmgvhf>j*w&E1!R?gJ`pYy9rZl#Yq69Rmi zR`gE4Hd&uL05F%Ni#o2t?(xfAwr5H zg{wc{KUU?evd1Q#q|#g*T>J*Y-)RIYZ06qSpXUOaO1@b;s~l$b^!fB9Z7I5C{btK~ zETpa7Y4yGnd1<@3PrXbV4Xh4o|1bcwFrDkZk(rB4WjlONTJLp=JDk);*9mD!sbqbA zEUT;1PyNbj)OIyBuWmA*HZ@{l$=`|k^l_QX?~B*_0oRFLlC(gUcMy{j=dzOTUY#MG zTiuO+)^!4f+qir!2bglS4RrBz6?NA2@M=Gv>bKX^*-=zv)K%6bX}>qVzkT>}G@Ll{{4gZt%Z2N{s_d%C(>~}`iE&FaY=SjCkG@V|ru7y3t z1?RP=yT6%VboGT8+{sVT4urgUpAIMHo95Y!6I$22X?FW7GG-h-)^S&Se1u~@=-zuNZzx=*i4tC7>V~*8LVd#^7bv91(Qef3N5*WDtQPLkiJ}!ik87;g{J*w@bIkJ@FU(hxwux#%ED>3-$<;N-xVN+lh7K zz(y=ujFmv6GoO9s``q)5wZ;Iai4H~ITMO%P-|5FgEHH(>SifJJupx&C%kGfZcU@Qv zrmtC;KSxAiCZ}OP{PZQU{QkgJf-CJGs7-YyZhGynPA3M#^HcJkc)|vLgHlVlgr{U! z_ijfm$j1l#U3O_(`)mzVX(*;%9!$Ko_c1#)< zcV{7Xc27@FHcxIgCs!+WPC-FIb`CCfE-qGR4^}sCM|V>%R!29Qe-il*I?|SI=B_r* z?lw-2lz-`(nmK)P7p12DJJEk$|9nqNFPs0G$1PHIkE)|Nk}gzcu}zL$%#3U8S5H zpmVy5{g=G{HSd3K{MSGc_P;zypa1a`%4jh(5%&KSniyIJoy9w-97%1YRkffc zRLlNeuszTpz&}f99Z^G!RsnVo21Wu#L0VGF3--7jIhl6o6a8H+m!jR&s`jt%J}p+? ztiH*82nt?9Je4;fo{vKYE-l6soRE3-e!g`B(^?})xa_Pgg0{(B8Yp3bENL)EwpzFD zx9+NT>iQ#ExBlek)b05iI@-FHAKUkDE>N&Mv2IVBW7u;#<#&GEw=I~W5W+SZO9DodfQ;;$hcJz6z2@|#K`$I9 zYae#<%7n?szG++1%Ohl16J!1FP4>JhB8J-;>rE&n_GP8PL!HDBVrKAAXU)zvtzwyj zq`!aajqf$@%2U4-CEKzFFUR{d;J2C{?U!p76V`%EQdlRO%@}O4x>{nxESC1=2CmDxqz0YV;(2v z?ScBsepw025&gTpj`HVAFNbHIb6*dm9F*SOgON$`Tg3^Uua#P);vHG@;&4o=salrA zx4htoYZGQ>Q%(e}0GIpzZCjCR-T;woBYt|gqMh%X*J{iTZikPSW`akhVDrQIoV}M%MRn(G#3xHAMZ|PE4Z)N2o1KtfmGtdtwNzuN}cnr_}O+= zs>Hz|#b5yDI?d?1gV9lx+&>xzJ4!0N(Vh36B6xlJ404h(pvkURd5&I3y$Y$zq^k7 zu1y;IU5H4O3}fNtoDdquZpCWm?QPp(K{oaFxWo9fHmIM<;X*Zy5_m3EAY zUDN$_d=PkbN$&FAP=ZOSf5>7QKYP0geCf?Xpiv5OYkMzmvVL7R{VPI(Z={*>XbEl} zCbM&qTwi}*Ka+cLKEg({Uxx@OfMd;#1?#tC*6UHtj?TALYKcXSwWZF*oW(|>{`1a- zr^*SY@&lfop+^=?Q)LaW>`K8|_LUm$llh|0xum~1-_TM>hwCyrl!~ynC1Rrt_>3MM zzpDIx0j`&UIM~kQ=#W~(r;Nz3>R4q?0C8Uj&C9#Q>ly&c+*wcyCX}b1YDzbxs~)`} z-g#pv)OwNzCrOr;-j$M`i%PO9A{_&nBi`<14F^T&e2ur$U2Sj!kveNk9*rGyh}M`G z7q(RT-U_E9-n&xosXGjx1qJP-&`cv%?H!8s>mF`$AzW)a4N2%1I==&yn6D_yAfvY{ zXzILhOZ?h%w2=G!uJexi`d{}#;60A)J(tdkiZMa4u!Cc3F@))Zx=F^G-uvA8dQ3Ka z9L1%NU#o89%4C@af|O7W$;)qVIvND@<>vw&K2^wlfm+}S^vN#UA_G2^rvm*)Bc?S= zq*o#oqwIe7tfCWdhnF+iEBbcS*vg4V?|Pti^6hxUHL1zNJ=-2>HCv=-v(<8Yzl6lR zzrvG1y3%H(lzWxK>4iO>sqjX+n%6D!D5_8@fPbTM5%Jk^&~MT6++>>{3HU2z8l~va z*|nxla>_HFUQN{*vwxN5OW3Qu1UR@bAtHU79j$4P2jV>LE2+_0^h*spR{w4AMti_% zx~<$q3!==KU0sqwo7{Uhi9C}LZe9~UTri^t4;eAiV93M`PW!W5xew*f$_eX}Ojq4PZ zsyc@ZUn)*_n8PZ@53AOKZTa$=+_YFZ{AWNz-#55#U}nuaCs#rM#`Ury#Txf}r^uqk zO2gKu_{XX4#CV#_cV8>k^esgaM&9L&T8<^n7W)_4+$)s2lxml6s3efNa}NLE z2qo^_ohY%p@1})IW)QL-fM$ft2WM$Yzh4rQLU+>ncJPE8hJH}UE$#oB%(}3Dw>b>- z-uCw3L4{MfxyhfRoo3O;JbCPMv|Ufw((?r%X=;Yaa8>5>EwO!%vQAAU4nIU@el82GvD)F`F?ns;$! z3B$p@PS&MVf24hhmg0CJ5WyWC%`z1>PcA1bs}Sppnc0NhpA|@ zbvRpP00~SrNB*^zNSbTTQleS^Vt{5G)q{r*?)Y-$2HXgD8%lYyyEtWt@;14K`%@67 zc)%I5+>Kr1O~QJe9n^QS_CmO+O+7k3gap69ei7iO%DKB^*y(#`;_fAY_%^%w9$q(H zRi2?Q;Ul4LoLY=xeQ&*Qo&-r$7`YwRK?ToX0qgyNY9RgVf%uc0_fbV-;g13-At7N2 zKz(Sly&F5-Xk>h9Sop|~{mb-bRgwLkEz^|BFZThx(R(%A>puE+rNN?eMlL!)g&}IX zEC4zkgi!XLEB*~jFl>Xw#{+ky!p+p!WQ2R^&~lzN`MtWy?leVzdiCkhP?Sp+R=0SY zfOe{%4a)a|_re#P8%fJc`bM4f(LW#EJ$R7eAc6yMFY?vRM1*#hua-?T1yir9X+k); zOW-()Q7j>2eq;i<3IYfx8P<|$uIbI#80O-_f^(QD)2|plY`@j`i&h%|1(^kgkQLrzM6&jo3MR%QK7Gu)%ODh)-yqN4G4-jvcM)g0$&9_hL=$VgVVG zbxR%s5ggB7xUF`6;9iyM7iUYHv>kWIj)%O_b-n*+h?OLR><)LMOzhkKK^rY?>3| zAn$yTlsooruc?Vf{4MmuMc?Y=glrm7rv<*(v?%nzyTpXCW3>tkA*2I|_3faOx3_kx zj?URH@fVFRpa1+}J2*LVK_4^Zv!=OLw`J}##@PtTr~C4`zW&pDV|@?yR1m%Ar%%oA zMn5PKWHt&9M8n#lkxH7Z+YzxmZ&Lmgqxc*iaxM;^=3%h#j^H<0>Ez7JcE4Z1YJxcJ zXZNk9N`wO2Dx}M^&DpN(7Ec5n9UV+3^nA|i6~)R&i+b}L)KS$sId)SA-^Iho26 zK7M{O?_P@7)YR0C)K%hy+C3k3%9v1|hSV}12(e*(*vV|mR02U^(u+c z@MdY`yG~+Y^WIuiH#E>QkBl_Q%Uf9$yKnVPw;P(Rv+PRTA4+J>NZA2$WJL847JP8i zQSPP%I;#P0&a@DXNs0ZVlf>YzfJT@if=~xjQN2Zxq2gu-MM{W{&YXpfi-L}>ZdNMV zK%_AXVM}XkR@>sK0+Z(Imu)zQ1I|%!zf2I92gNFs6(@BSV|7ZZsy)ihE`iq8YAuwn z9&&)9kg6u&?{O81!02AXQO<%??_!rJ+qES25H+u-{TkmcLNc;Xg&LQ0H`eoU>`7&1 z%qr+Lm`8#)4oT7O?d|QZ#|xbEw=}{ThQ1j?F%h;rjt&XuUpmMkR1PKIF%7>C=Dx@1 zkS(f)4^~;vGJF7PjBO1*;#3;G@~Cy5jZ~aE`K{BGj#9*wAao0qZlimjgu3>>wR zuRkt0uKC{@-7h=6Rv5hcUzeGrum_yS{#gxLif6-|K98!x`ofNNy($y>!U-%5+W=h2 z|9qj`%JH=!%L_C4(Rtf`I+XJ?lrvZ`kg#L&QWnVg`o#azY+zUmE7THsZ`-n8h>eYK z?j(VEKTphj#{1@S+uPYlM8#Qm`|Oid=jC<({)vo0A+vuG`r&&iD#H*;{9o@5c&zc4 z7-PMfcQ$^?$m&|@avVs|eLay`R+@FR^(vRCFhKyQE@|uO8+vr=Y2XDnyv>Zjl`ncr zkC77iJl749O7F|M~!cMYRJ(wtfeD40`XGJ(0id2nFmep(Ko!{uEkFUy)Zrjth<$yp&Jq&7!8}GPh4<2l|&8Fk3 ziPe_)0?!gl5YW`$q32luDvl-7T3W&(&X(oR###$+RQtXqK7`McyFaTG1=s)Ll|yjZ zQ#h01Q#!~ytFIKAztmT#qjSEZ_6*qb+(9?F3t1il0;A9G*7WR07g9ad z!$=q=QHpSDT|=xwV-u*CT+9w2Y7bpl0hH@^{rncDE|LMSuXq0U7ipbstn?&iGvvw| zyp?!QMQ~+(A0_au1Nsus!CkOVps_Si*r_#*GV?}(0Vi%Ovsc%~4a0MNu)gi8=qgxE zpkXs8fVk;wbmX;OK8rbe|BAa9lV!= z6U1$fn`~e)gJB;10R#9?K|I`|+YM6jq$I(7hZ62pREK8aED11{M!(auLv*%w-ahzM z#gS5=@<6su;Vq|^E082429B#)KP%~n5eU^o9*}%iMJBG>E6zzIQXkc%Z3|{xgoW2n z?|$(GI1jyoe5VF-$<)8>V7*L;e;!Dn7}4#xz`tMF6WhBmHQrrHSkvsZe!;}G4%1)_ znMRfOXFnm(+HOXEL|(^2p~JU>k*$nHOsh~tNc`a7RGy4{cXx^7BH>fplX0#!9D zQvA~Gl8YCbxFd^xDNX4$DW5wZ!AGTIV~LRaplX@h*)}?r zqaeL7C4kaI;md(kHjz|jYCL~ywPzS8&gs+LZg^PrH30L|=vmKk8z*+uZ?m^)t~*%r z$;ruJE%NZu$PaSSkwXhzlaqmd?|)D)?G-r3!DCT~xQ{z{hei-P6bt$Sc$%D~e5Hoh zPg{Lda$JjPqD6QGPn3)>K7jWaHWW~tTGA$aDYEhy{!F1J8}M1pEUu+RntohvqiTnK3N^kFZ9Nj>2vGNy;poe zL#RvyS$t>^xSbYvagR~%MZT9c;VC%EO(;;FP+ag&Kzm&BU|dzLQ>MOw0zPb3f;Jc( z9sS~L6JCxfTf`d#rVuA@7qKS3B*BACsWbiGBX0^7_8;!ScxN^jU zXQMlih|bscc*fh?eB(e?e63$UzPNX~-kFf#Qr=vXy=;KaAjQsf(zWh=HEJ2?)ND<#mLM66-)x(u!y?^HL=L8;P8)0-uf+Ynvw;x_!VMQK^Hgv?S#1jo z)o>dN14G`*)9S-o$aWq$x~P8?Da>*`rhMVpAObmEePK@lAlmdgxu}*eOTB*nfb>v^ z*Q@5&F@K&yH-(?w=|iQ{ z_t6D1-uW0njPdvqO|U*O>qL;53K89r8SduZUM*ePNNrE`$bk`vd(#3+&?=zp2MEab zF3Io&dEGDAz*EA!m-Q!)#SG}nD~!O^(!X2`@#qHM%)$Jsr*@PJLRS)68e@_JFh&!m zH8*6PG%slz(QNcPK2g>D4B3(iH6SnbK8|xWf1)5Jha?xPAQ6L_I!`t%S)y)@IF@kz z1HRG}rg@b)pM7NG^R5P`FfT2zyMY&=gOn6;2=Vj3Y)9SpfS1qtQVxAO&Hep6asA8(k>_%jLUC z?36lSDlnG-Sh^rkfIg>jZ{S5njoqPDZ6WXpUB;FHF-+qO^*l-~#2*n?<*w=!AQ|p_ z@(p)w68;Ngpe97gOhk5G-c%^Hi)@p7r6?l2F@4-u1N(5mB}{__DVkY43hQEqBaIAy z2AQvMqN5xdj)0Jhpft2)3284}d_(DdY`^xF`NsLw^ptORgV^K{HhtH0wTUdfq~j8X zTSj=w9j|^;pbH8tzZ|d6nVG-O7ALQnaLaHj%+rcf zfLZiHE{DOGx08VPbP#RgUGVL}5tWX5cj*Jq=DeVXWsFsr29fjdni>3Tf7FZ*9VEZs zq=9S9CHd2;x{0c+uxApO6>+&`ikT zTiC(!w|TwKzd!(&Dbp~GtYK%YzG=jdyu_fFrULeq!_z#JRQDX5$>zLt`xQ}s54Sg{ z8zV%!RmyFoTw7$by+0;2W@@duD5dPMj{_;mW3QcPvt3IXS1l(`gSH z>tz>D)fzwqKN}8c(?SkgeRNvPQ1&HA*9t}j$B+C@QRu8o?3XWo&!v0b zTrT!85%m1fgS24GxH4zwbut4{Pa+*kY=O~1XZQLMEeO`0;aor)&!!W~H&D>rR47<6 zd3~7Af>pguX=D$;QAN?WL#Jn2QWq+bVi^7CZ(QSZQu5;sp$yGCbQZFH_BPR8i=OKS zTfkH*QavOeHe}*5XE7{P)+X%h{+pfO>>U1>bWruwi0*%Ax>iS}t9S?$%(B-^!;fo4A+6dWyFBOp3$W;fd@id;G+Yg2zDl% zr5s*ifMlxw@vY8#YYTA6n&1`dyxQ%zQw~fI-8L072rj77yEBb<{gY;N9%e!b(Km&( z@>l0+S&WdB4Y`DZPa^qr6addt6wm5i0MAlZC#CWU-5gV8XK2t{GD>Kux1d=;o`l*F zdI)E||$z~#_8k^@{W6nl(mDzDIb2Zcc>{D;W zsQf6BmESC9G&Oz=gA*sCQ06mUAuCqqb3QIH!9$Yv7yk%p1?2VeOFywMA!T4^e5=Ck z4`0OwiLt3ap2MF!sbNRmDi-?_f}iyW2!?mE2xy>dbzD*liNK9?7gEMGlAjN>SpVsx(js$VgvCh_hKC%H^TH||86@bF)VAJbDe<%s5Ir6?DDY{(1U`?4^$)X?EI_dQI3Y5K4SV*M zM58WA+HdK7?pIn~NXL1+lRzlAs*@ZWq@-A!^X;m3Jx!A}Ip=*1$LmW#4#m~wceX%Y z_&{Elv!6o)$*!ksqQ_}tLcmh2FkErEWirP=!254^8`@m?t0nIc>N+p`lF^l3nVtGj z=-7DDBc5{|AA#*b1_Qfl&8_bqjjRE`Tz-{X#{`M5J?{C4Uu}osc3$!Eh|q3Rdbc2;7CCQ5kH86PI+9N+ZODb;4&bIqo+0x+|{l%xuCm;A2EcacPJm zLs_aCaX@aDU}<9mBRpIXkIf{egO)9$47^C$Db^?^%0ME!t6xl^$R=8t#&G-m6s0&m zaua$V10*V^^7`KKbDx}ViPA-V)pL!Ks;&Z{Z)6ey$cb5m2AqYJ_cxL*sTwNH(~42s zlJD)?NT!D9MR=Rqn6)*hFT#H8z78I_H^uMJCj6;b{fhfRJGF)zRpmd*Vp>U)X*#gcIMZNX2Tq#Ps{CP(kf zi>aA{wvUwk?z9lc)s|h9BDcNq6naRMCqVI=@bH4oqm8u5V=4|P9?*_vdGo+vZc9-# z>JN-wHauPFps_0}qsrqsp1YkQHW@fxAT-!KklSuBo1v^<<umNI$zxOnGLJ;Rj;FkUxbNoXhix(v;%}r;h zMJXxxx1o~ET6uBjD8Sr>_| zldY5jOoY30=^cTPW$pnOq2b3+EU_q*qGSfumVnBIl2Z$WDd)ME9tpS_J2*cv~+mZM7Bx#}L z2{$HvMUrY!jqnVrqxHTFke8-fOu9bMGg4RiS2N-~Em%4SuS2`5yZo+2wI!4|*LTYo z{VB4FiW*4@OVDsFZN9fC>Nl8s>PGi)Bma2LEpsoZt zZY&5O`cp2Ad?j$dV{0XpB7WGxn+7El8I2eu{`sptfOqo_YTSfZ=3%Nnn@ug2Xh|JJ zia(j+kbndmC7_8+u$I}A>pi}&Y=x;G64tey@;cA?ryAW#VA0kc8M#ZG8WXaa+v>~< zRHxmB>NOm+{)pxEvUh$~TQXb@d&bC7gL8wazya5&9-5=44BOp$217B=ch9kDfZ`!j zY>_~xk*oIW_~3C*B-iCxFovYm!CMR-H*{$U9DI7zI=F8u3V>jx;Vl9MI#C`+_jrT4 z)*Tra%Y}X}sy8vcatOCxV;Czr91H zc&}F`s|Uupr2ylbDaIuq= zMGmNwk=P+Mso+WbXW@xr`9MRoe|pZD$HxJlL?j?KvKK&}^y3ikqM8|!GM^P;USUOk zSk*t+D9|)ZlV=f1URV^{ZWc0At>N-C4i-qD5cSBx8Sl>TTv9u1WOa%$)4X3=k5{v0 zs!6Sg8(xtC2I^wcLBUM&2734g062i9EZ;u)Y7Y2atE>G(-E1*xM9Uo<1u=`h3=MF_ zvrhD(7IENV^LjhSDHzflkxQQ7&aLX&Svo=mKGLLjQdcGCMmpf!w2A`~w1O<7&{Znbw$L&n zwT9dDXm%1(+e5CU0X7WkoqAsql+xL5hP9itNCShT1ZW|5M5eePczF1aQl+HdFauQo zZbD49L8jQM3vhlxXBssm6O+!~e+xK^QiM{|BCbx<>aG5l8$SFi$%S3wxFE=>P=laj zxzq5~EaXQ#hr7K+WJHoJ$+9V*HH0T3yy% zLlrf`Q&)tI4PuOY2PQQ$zMJp@D*@e;6#TR-G>3L2;^_;6X{_E7^c7k9kf%>4(hp7` zHpy`pa0EE(Fa2UKuy&>F4+)-bKHX^+RCX0V1p73o)*7HOk379KTtNp0AIt6{f-G+WtO^|2TS zq)a(V{5{uoZ!4cLPnrZ&z%e{lp=yDwBvp#!e8lqIl?jA_*oRIJFSqd_v9aY#YJEkW zQcu7%&oKZ~O6q{e0f0{hxuDEV*Tp585qv>r|CT9h*ornpkv+raF~0nDE+mN7Fl0$_ z($(xMg2QV!)hsKYkr>LB^6wb?%>Lxq5ob~r;h~ZF@MhsP3b9Pgwow z001)N5Q&J0jj&#<0BTtu^n3ebQJSUJE$jCD+db!b|)Dtfu zb#T=yEe#Mn9I)&T8-zDlhLCQFs>y*VK_AA0z9z*2l?(g~&`B%k5hom}U}b=evA(pB zv!rAN3rP{n)e#5k;ClFmsq-H4sNI+$YBzK;5nW?lsQRU#(53R12xt(9gD)O}pL51h zinbgI-b;NNpRZYm+Jq_YdB%`t8vy>90F#xv$)5B?D0wCh=uN!QD>Ov}=e~3{%U(YT z{V)#hbL1ysQubl74lUBk*=vc+?$pN2A9>QkAphs~Ke6JD+Ep&w9XYB`*+%npa7*j= zAZQ%kC}w|%AjTZdFjI}IU`3VS#(zvyta6~=)EKD^ZG3QCZG#OHh2)MD{)*X2EYJNT zH6vVYSv}9k8 zyl}h5QDzor274G+9rXV0t;yp9=%;pQXMgwAEU=6#&%$7hN#fbU@yM*o@DKDfN0;tZFIW*IG$A7-3^{@( z#7QeL{r-u`EWPb-v!Kl21P&4H_NVfL;Tv`x*eS&~>&{(PDJIUXjfIT+YPi~faA~rr zMWhXFmMaa7U*xbXe^1dYs1c`f=V8*}f&@E0TO?vNQOf~>k2dG(Eh=Ri8mt3tlwD(w zlG2TmQ{(IE8X7_0e<&yQw2#ZkxYEj?U%-9owW_Qb9({^qVPgj}m;P!t?+N9ClVfcT zvH+U$!lxP-8A?UxgkECNK>T<-GTn}gxuH>E9%ZszH)xbinf13rO2Mci9%#VA+H25X z%-EA^0cua3@gB>}&c~}Q=@R|59#x>$<7tE%+B5EjMe22ZHp#u?eMvhQhz%aB>RWx|#bo#XmPknsGpn@K&O~yEjFt zA@bBv1Hlzpcg3S2hP|z#(qZ^`w0u-$;-|-4Zl)0TpE`{%a6{BURQl#b6BT_t1)ETU zsl(wI7FM?5hjyDG!yL%YMZ{IYjUv0DtGm30bCPwq4h{-+06rVOAFGGA%X|7_`rY5i z{JXHne4ji#6s_bEL@uwqy>Ge^5B85y>M|E({gr8qg&*0;muQpY)GlC3{f29DD&OW6 zenijbC2-l>ta=xM{kSZFvY+V$^$JlP5@d=-p(dx@!Wst9#(LpP-Tt2g*XL!FB2hSF zhM|Iv4mn`-FVn{%Ac=RQiFX;E{7n%d6p4b=p-41EO`Teq8Ii<27abgXgQZ_RX+fTH z5o>93X<6zzm#JRBFxh9^>;s9}X2-^nLoKqWKN_SB*e#>b2Z?e_>U(e=>}gh#dQ>@L zPreML$u3{$@S6!Xg*Yn(aRU!FD8=^~T=dwmL8RU13Ft~sk>NDhp!e_JFT!xvF}hvG zI-_$5a8WX-X2Imm9>m1jtU^r=MaGPY?%hJNOFxp8VYum_DE&4c-PH9aB-SE2!JAnZ zq7XZH#$O&DN=X$)!%dv04=Y4*&5q?*1ebE&ek{53O;F@oe+NXp6zhO<2*XVye#)*Oqr;hu(B%Sp z73cs^?SB8&?`%DQ_R{l@{OyOv zt4u;j*E)s@u#b+!Ie0zOVY5FqifnwZ+s=2QBjBn62lk&4Rcly z3iaRc&%rS^CZ6Kd8wCnK+sKmZn0piqHNwSHeLepO^0ib|u|G^_*Z>&i$F}V{_Y}WD zrA0IU-L9Jx7JAlv$0_TK`UkqH>l@34CAI$k#!EQWZ(=Wj2Ou5l29bNjF!^u+JEJdua){R1g+L+K24~S>evMjU*Jq6tJ zS>IC)XM(rMb}PfCm%c)wSLqPigEk`Gi{|i17I0E_2Q^D!iuu~mrkJonjt7Sgt#qc$ zRCm9sHNd{Dfsl7$%b#OAwd`AojG;TXY6NEhrO0f9*DC$S7wQRUcHrCLyCU|X6ycc{ zj0^nuQJfpAZj`PyxNy5yRNRkI5CC1T#@*+WA_2@X!p@=`VnHh_3p zcEWN+bQ4)aKWq(-*|nrqcQ!2LIgyTIzUPgOm9{7FN~m(-0i(50g}uUZ^xg-lgZwx! zd2&sSd2KTvYwV?`#o;-8bKq;z`Xf(Eq8FtIjzDIjZnLxsowfZVbwtXH+H{=Fs5+*Qt7h|RbjYV?>}~dP+56f=sPF_eE9>m+C@|V=ja9nl#qzCdUmci zExXDC*S0yP=Wk$w@0$K3?0G$@02xE8l~-UDLTMsd>bhsBjvDcjs+vp4&E&&F3ky5jPyuqX>-{Rp#mgr@PDe}m-#SRU zgdNmS&q|)_z_+&JDZ8*Sb?VzvVPlnCw$DR)rf{I4N{$%1r>s5~ne&O>Z4yWKRER5m zV>Jxw@Cd$3KH`%6_$2=_2O9L~cw_fAtjR*eEyYu}i-PRbeKoh^-R@u}E;@9-gX0E` zWD3NBIz}sjX2A`kKE96Vg`a4d?w4oO$Sx+aO=Y>OVVw z3r$sI7e4<#JbeXQRBab7-7V6cLnGZSF-UiZAl)t9Dh&fjgD`|hN~eHycQ*slFbL9~ z?f0H@e!*PVUeBsK)-dspP}2cTESjVoS0gyIsGqm98eL9hw3q$v;N{n)wPsNVT`_R~ zM>Qc}+ayXJ_pbL5Ff0XDJ+jgLw=gKz;**4Z)4y_Z%cV#)zA0K!NZE`Uj(ZTJo>h3r!H zJHv*+jboaD->cH|4$kH5lmo#(`#n4!*f}%5ft90Nm8vG4@q56fqjulM-qKJ#k0w=> z=X!K@@_JOpqULuWwB*H2mi;JlR4Q;pHB=PkqtNG#_>`pyIqExQZ+Bo*ca6hfbluP$&vB z`Kr(UXG=1OwP+5E3-z!E^%w#h7gWCj*B9KcQy_IjEh7!;Loc}akYh>Y&q z(2dz4*Gaspf5QY7L-2R6$WFW_6l!YB&|rTQ7uGpIWs|;keWr%|FOqU zo=0<-N+8r(dbnJOJli}UetgK{0RIMsz+%5}Zu3N`@ zL)cKX(_QN&oEu0VL)%~lNwtWO?~H`+KvvYc97(l%U@XN7nuxCFQ4~760Qe%SM zq$*3g>rgTVHEM?1u8;eEB!?WPzmz@j$M%f9-v<%c%K~525rSV{%*K>;NfX?uBxu5? z%Zt76h|?3bJ-ksTet&oitRsla5`P-INtq$3Qxsv8KUlkCEs>#}o$H-zuW$!rwcjdS z70z}DYPF*C>;gc{Sd2FEsFcuzm;aww|C{SA+GFJ$<)t$;xeu;Z4k{#;=ng1RGlx2Z zG9aIrAiU-wS!^~9xsSt^MW99M76DIHyV`lRy~tQD&+8|_yF1E1u=P>iu})DI{=-*? z4r;0fPH5oQOAN7-BPk+BXGf6Pw+?p~qxdi=DJg7kSf_T?o5*D2f+q!u9z_jABsW!v zh0}M{v)v>2gSik2ac^qTlK;xo+8YgEq}mOi?x~P}0bnVX#w^;=5>ThEJ{sCq3SKSR zpV17ydCbX))N(zME7UqmNg*VUVd3k(cxMryvzOhsctg+_>AoQ#=imkx1adY6$k`+c zOHMOeIkxjIc=adS_?Qj(A*V{*m=CK77&yV^4RqS8{AE3swb+O$M3z zG9a$VH^zt+4JQ~-9m1lY)8W3E3n|Pu-&>ItbV~)G78zcaaY zOR^c9ajLYr=+>XI?)eAGp@})ngN<4K)1aAi%9-k#Y zpZP91?f6P4eCcE%$xuJwy*(3v5rSK&6>Ln`d|u9>bhKWH{J#u7btWCBB1(9ggCoCk zR&32tT1jzM)%&>1Vk0Fi%<3lzB+V~HP&!hTM_;3)!WC7Sya+HFvgj~E*tg06h}PfR zB^ls)=v-t#%y%ke4QtwW{a2ggf}pG7Mzc zxkecp(#nej0O>;75_|y_7fMH?gh3>0<9|!(C)XsTU7G+&4fON!+`{P}O%daA0g3Vy?f71`&8a0qyRQHBK7!ui-ar+;yC1M-6PY($5(Anjus zDGaK*J7q|bxnKk4%kdX`E}K$x5c+tPHv7$;r>{q_x%<^j;<^i`|Fq12lGJ=PtpsNz zK${9gR1(+gXMv&`fPtZ~8@iMkuPKH?FHxkVSpWL@ zxm9Z7+94jAsM&^%3!RsdAI4yQUEUhxf;??F{)+0X7JzP8*;SF}n8pnL-z@<7{}1XJ zdJ9E?qqJ$H*|fihCvr8LhVh1B5T(AbR~gnmCpCZ`qQVMWhRwRmcb zgFCr*no&=Hgk9X40mV~8C)X6%vBzgFzo@t5+9T-``>Hf(i!rBD}d!690G~IP~>0P5=8ZfC95vVn_tY%}uJWRfrE|H(E*{7?#OKdC^ZU zH{hGTRx%Nf_mr0nzg#}}wy78ANjSo-sO}twP&)r@5X^qz%rh&qYi`;gwk;ZQwfs7pZ z??`MNV6Wo6+93Na9LE$piQsquxaZz+QR1&tbdt}Kk4H#b~qYqTl zO~u6%P)es$nmho?XQoZxm$akY zA{_VFCiW+b(&jI620&>CM*utn-tUNKRBCC_6O$w8CFPXBM9A%m%G_p>1f>xEe+}&s zm0<@EcVG_fx1Rr*7Ae{jz@5%?faGMe1H)&)9?d+HsU=wvG5w4`>wh~ErMW9B#1y0V zu2VQgz!}8F6Q&$tVq%f1*HTpUmQT!Azpd?k({{@6zHNvUqt}(g-E%WPeEr-8)){Ej z+7y+`cQupN#`EM-IWxZy>EhA}_kSxx(tM8{z*K5e3+rlN21=Gilxk0@wuU1Sh3a=c z$#!O)I1|sq$IlXf9$SL$8$IsQH4;WEE?t9Mh~lgXz)TH>_f2@t1;>_#Tek=XE{`6* zneO9(Oa&1N9iw3pO^|BJxxsNppI<;Tn@J%GY~VKV?7@KUr*+@B+&>oq0RONOG+V2sXEMI4|#-sF@$~UUzXZz zL2UtYnaqEjd_bz=3Gg=VLp+v^qp{zVS&o{}xLy9Mz@OUNjcgGzKymZP%{k{E%O88kI zTfp)A$~BXLn`SO48%4#{S|1mGwS2KaqNbF@(a1q+Pq#LCmV-suHWAMIgAC17)MPc$ zppGiD6%#n$S{DO#g`Sbo2>eFG%Z1|L{G%UZVc2w z)V|@TcMlO^BWA;>Km$WvXd6~o^kTQ;BCEN3E8QJ0DlN?8Cl3%heT+RB&H3E+CBCS$ zN{RfD!ljNZ`@+OXD+p_Ns3i^4(xw*#rUSdE24FFpaBwBxF$6DQW zeI)G73PkwXN<9QVkSk$$obqsJo~&T$%f#&RanSSY)mPKcOUW9+@Gqu8H@RyqY@Sz& z=GEpona$^8qhPUwmiu&J2&VY1_^Q{;rtA!nA3`tIP(=b)3U*|q=i%>H0oPF1yCqf~ z_?VZ<;lNpIwYqbtQ~%13J*KMCCYe}*h!x@Wy3O=tKiH(uR|4`ho{k?^Zvrd;T(shZ>M6)nh znIiWzFzrh)oZ^ME7ES;bGl+gpte@j?eyRE{N*jj(OW4t-rL0$9nndywB`c&{?C$=! zW|Xx1_BCm2fG7QzI6`UKag*S`8?F!cuGT@#$QZZ05OP(QX;z!Q(5u(k zYtb-k>{R%l#@5w(Q_w6i$R#OZbge7OIe6%0Wa!)a*vjf}p`iod&5}yVVQPPL$68== zir=PrrXNquuustN>Cvfe)@0+TahI9;kBOPP6mxRvE~ddj*U>{S6L{~HovpX`n~i5% z^NkSxB=0o%C}onZlzg93?dTj5t&R2<=189ID&+hWyiHG>1EFH-uq($b=NQPi}s|18EtM?fSz|gfuYal#O7^96H{%+OhVT(9V zMw;zSRGYq^NJ81s7uTeh#2gq`{l#^U4;1^rO^4e*l_GYVi&A4=ZFx~MWHu@B3+@z~ zlN*zR_{~@MN@4Y0vB!9T?(Ugczb)!Aq`aPMpWm6ar~ysx5b*3oXdVHRyueICfYPe0 zK#W&nxHyj7M~r$2EhCB-+6Iomkcy!J0P4^v^IXk)M`aMI0+EHL@fubVm;FPeVCZ%8 zX4NTpv^>P6B8Sr#+HYTRq%9RMm!|NKpG>GA%x%tH|&_?n}bRf{iO{2@dz zibx;HmEQ90>9a~C)!;_#oBgeWor1wpEONQGv7w^B&<%|2Ab}3#zK{%lx{PXJI5jkEV2zoBFqrD#-tXv=T(JTO=aBk^m1TTk z6=Y0o0;EyO{*BQIEU&d>MVhQ`m_tmkIvyju7l~uqHD;3JFC+TOKD&i>GV+gKnuf$C z(IT*g1<4(rEPv;d0;GODneVj>m{S^qG-}^4e{$@3_#h*2BX5;d-^k_mfN@4|2mKd0 zAR**QrVypgS9_XXQSIIW$@h)p;1f$O4*;D`B{yzY&Pfl$sEoBW|6ba&;j2SK@=|szpYfy{OY@si-wTzh$hHJ3lsv)Br*` zuSf5Wg-3r^C3(Q1`RktEX1EJ--31>wbq%T@BMZ|ydkZ`(dK6<@`r^7w&p|^o6=3*= zvWHg@xU3Rjo-~`0s!=8t84JqV5cSA%AMxiR^XJi6>I{7q$&3cce%&)kPIZGU5yzBN zax6JEG4Sz=a`Ef%(^)E?#1Eak(RST11p-|&#ItFV(agFCm7eGBtUBeJOH1$R`WEy{ zyE_QpXccg89Y83Gt9AJ1^J#_{4B^3ygFLqvr?Lz?Dd z-b_fQ4vu=I4qwUB0E(xW5^C2MD_~ALITDz{4x%ztt@Za9X2AANvS|<-8>z)ll9n@} z!|-BBX4lBKCcf8lU!(YZzlj|UZMGQK3aY1QLw@nc$0ivQ)L+%a6=Qy4TJZ?ABZ12A zpk5T{h|O1@0n;5FM2LwFGLRRON(gR`XgqsyxHQ?-iw3OS>v7+XkiI(4FGh*3$O6WU zaoICJTc30aa6^#-F7uLRJ(nAnkg9wLNMUtpv3KIp2N)o`~NfeoA znj2)!VCs;dc>u)ueO(i3w!go>_b24s=WZsmD?U>LxM;BcWkTZxEKaEf)%{TEwN|Ah z+kLL%3t=4zJmN+gc64d3iAolTV{m?d=njUxH1{Hp03P;kfmb*=E5ula4;Ke_WT=kt zVPy41=0=YsU8?xKILtL_Car%1w{b(HQr_*ZOgk1tlZJG~zY{FR9Pj@cmwE*oD^bGx z;{}(nNRSckrKjlcE6$y;AM_3~;tI!=43w1t9X4Y_>#MVTg3HX`XCvWT+ofx5!fbzN zc!nZjTt;Co#a>UWdt+0W0cWjIrX7&v?`5ldzx~^(r1LYo-kQuTtAfk)gcfz+`;)b> z(*uUhhjRm%xOD3$;8G|=`-LY_-~x9Z>Z|!Y`3(+FH(!;~OP^MO+y)wXsumO+7AtwG zU)+adYAP0b_(_%qnm%ZZxon%!V#90vd;|L+ZQl)lz5M|jSdShUDq@Be{vlBmiZ*(ry0(>F zEPH|~%=4N%fvb6|ei!n+U*qFZqO|=qgq4|{l?KS(3PFfl2W}dv70!`!HMaf@r=|cP zbrDCANm`0KiTz2v_}2czoTjmbMdo?%c_3lY?}zTcf#R6V&-XoyO$eToAEQwT{r(8E zub!m}YkVa*%Vsa}yqMhqG(g#!-ztYzl18tw0k26sEh|Ksr2;^8-VT;@7O!_U^X0{z zcP}lx#M1u^#wb5&Z2?4HM8<*LlSLU={EgIL(4h=EdcI>#hut#uW<-cF5XTry)h z;dQb^z~PyFx`DdJ5cUDf9u&WMNR?I%>-OEDtA?_jf%=LpL1WYRHLm))4Tf{G7+Ker z?x!=`y9NB}p%W4u+Hg&=S!t%4-1FpJMm8g3wNa`r1iz~uZzNl3ciFewBu+m71v=U7Ct!qiu`VfqinCyK%*}#DE2pP`>>c>bFnSl!n~q6dd|Na~rgYo`oP}Cu%0M`w4WFAg?%aH`XGq}sF#x-qi&SAVU42`YUa$;ZYS zSr>rhe=`-GI|I}N_PEsLhmi!H7An|H-#mWd#kd_k!)aBB?5SNCAq%pCRomtl(Txf; zXmwVbAbRRrpU=r}#OVLH+QPWkOxz@sg}2Wn$A*iSg_eXzMpj6K3VQr+FhQgVNzKE9 z`O?g^A!iM_5Lzhd4e&It|~O6X}Fp$kR6g= zQtG`B;_N@13jSA&yCei8AE~2eWV(O<`J>cr{+Y@N^?qx|>F@P}%i|%%;2&~;f)>#p z53H&`*a1#QvhvsoKOK^pT46jpVEwMvUn0iH|{Edt?NF=vDw>8LkLHIkor>Y~!-DL0l z`R426x?jymUbL*r!Q>}zoRK)jQ}~fr6}+-L1A`Tzz!Fi+M9tv7f+{5!>Nr(RalnclRi zoTy``S|_j1X|AcTmk{}u2Ak^HNA|WaJL+9#Z+nN1VHXNpM6GpbKtYmENF7FFR6jrF zR~=P6=3P&m!c`T}bd2^z_)C_=eWDE1Nx#$NYvd4L0U9K+8-S_yudi(S$^P~_EAap# z3RLxZhUKM8-Ddz$q^AVv_|D;Z3}*c9a*qHj003V!iLbm2NQwfO&4>Tnx{1JS&u_?u zjK}-#+6c61!^bqPHb@q^9hC~R8}nj=r_rN4b>!G$E&S2%(V+!ExM^{2UfvkwtbJne zFAopdtQGdn2KiOsvOq_=VGUGxePIu*I&F6y1Af_p<)pnDUzVB*vrrM{9Lp|aFrP=0Dt9N6{L*Ce$dYn% zJg$$bl5|7b57p@@A59t}V)Eoy4)Kg8^>yhPgGsAb$>Zc`0bJ#1$h4L zBIuRgz|r?L34lq|Vrr3w>E0 z>jqu#9|G4&>DD%m+`~T1=xIsB!S@IYB@T7Dj|L0AdHx9=5R_v})V(sVJXt>AAOtg| z-LmmE5w4@nb_|_pjQ>V{+qgGirB_AwDvt=9%S(M$g0kkh>uz9ry`0n{&!&4-DFfT-v-{e%;52PpKyAtUB6jTYp@ir9KMRPU7r& z8vN_6`n(?6#VlMFXv2?8sZ!PHNn)%~;9sQneBJ#E^7qnUb?<(htJRmEEA;7a^{B;@ zq_dPu%zL@VDW!Tn#Z?_RaTks-g1Fiu&G>MFkuIHt`u3=2jYL{>-C4-pQtaSfs~wuH zy9iq+GS?EF@?MxC30aI0ANgu9QDR74u_35$?xkuUZzf(ZXGWK9b|1z8nT%c3j8$Q% z|Di*Ol z7%90hP&or~HW|l4osl$kSVc$&7Q5f3-xF2b=o=x%w4|~vmLklsDn|b-KqdXdU<2U6 zs0I}~^;_HF#gkqsH;;i~7&Ojb&|UfaAoI8JXq?W_ zbuN$}3I33cEC?pVv?*texw^3sXya0>^xXH?%jEf~yPHe6w9WPvt{mGu$J<-$Rn~l` z%+2S;Q}|>^@yqNt4gn%*8GrAEP2g2-Zo{2fxLHOfey8~HL{0UL!_m*`vt{&58JS%Nkb&_Kr0 zr$mO9HiiE(3ri#VNB*Yur?5iUdjRS!IDuABp-G-V74XNp1*|H9wqO6GzMO|tcgbyr zCjP|4bhYj!3Xe-3PJBIe1e=&0O#fAu~c4I=)I&q-(NIQ9UCovv^GHn~9Y# zwG{Iv7Y|woe@4q{U_RvR3PW>&E@Vg%^sFnB|Jt9L(ZB+oaydX zGc0aUy0@|(u!p3UAEd4LUWP`VfWZjQ%CCh zP5Wa`=qyY3<#Ne4R~s2A+r9I@PKsSur}3tptxUo!2ewwo*GS>a6+)u((sXu8?`3@( zhrZLrh1~DQKkl}F=WA?YI2_CV?RPV@yj!*xebooA&?w!TPbyR&e66T1Bg~PNuHRyL zOpC4I!tLmJsp_}AHwaD_B^zahfL?Yk*u=}%iCQ2ZPaPP_7`!NodfzHEd><_>uwXU+ zP1%+}vlZZ%&`Ma^UuSvI7-RvR+XjhSi+UtaNkBh#_CFFz`^#7Y!9Tu)t)iBETsnz@ zp*KMNLB)d-tVamue*11BZEMTx@ew$5YDT9yel*{guc0Zb#D{@S$q4Zc52a?(3aAIA zyorOT?%ql5Dn-roC2K}V3ILiwgrzN6c0U8$-*^9WI-HtMH3C!xv$ed}t!2!NN1y(d zyzzGD55_D=SkalYs}A2B&Pa2Z2zj!uD!z70f;nA^v5gBGVxS5o{Gum&&0m`1++3yY z)YgxNXQVitnf!DOVr74uix3bLWTR{z(kd?nuM-MV?9xNK*PfXlcCjl|ml0#NSH+&7 z29Yd&6Mdv7&r^4c_`H%z)rFPmhFFvyTS~n4_ldL_wi%(@_S}LV(^yo5B3IE_rS?1= zEp$gs0PemsSpvtB(zIE0r1+d2bO$j>2Ru}-<)f!$oFf}7a8#YH^G$Cu*Yte;6Kn3A z7WgLv*ay(@^>|H46j5~S3p1v(++>&`Q^d2c!8rQ=*2M@CGFk9lLuE@=f4~*Tk znGwZi74C3sM?JV(GJA5wh+3ZjVGSGifs-ZmJwWq1GC+FUUYWIumf}@9y~ZN^Fc2!B z`A;u2_ox;LP&XBKFshoOn`^+xQi9?~7DY6=zv?}_F3@N3g-jpt zOS9oJzZ(;Lg?}B%@z73-q5J)P!uHwd(o6b(HF^a=bjE&=1y$fOr>Z+oK=I66|(^jPsXC&dGWr%{S3)@{|+$nq-zfqM^xw6SdeIvxrtn2T7wuEW8 z(2F6?9^aPj1ys@Lf{aD;+~lMV33{H+Y)GbbE@Xl`)yjWLD0XzIhfKnIWzI=0m@X<+ zN&o~d;(gzVzB!Cr52*huIvZSg7=!YW>SOIpX8PpmC?3p00k!l6lZU%TDL}Z1iF6#p zR8|(76ShC=;KgZvB{jV<#sdImIzS~?e0beO1Rl$cBQ!|{jXfL;lIHh&CjJZFYdadi zU;-4~SG~SN4a#+biRVDpqm;AYe|e-94U?j6F0zT5*@&{hE-KNncJ?38#JT%%7+j$F zDJGCWq|jC7NQMI=F(oY^S+G_8@ivk+%yRX9q}?IloVvxy3((t;w@Rm{52vdeMea{2 zi#ywHJGt;kNODYe^0Kbyu^k>poEBZx7XOx`ZEE+GiDgBtMjz;~`ep)0-HG)=T}|Sk z&&TFaOVzNE0omFxM!I!wa}*6LaF~LhPc+;{grAY3W^}uqFF4$$3cobXvQ9v${+&W; z?%5JguxTEW5J=tM=Z6>5uBUbX-FSd6z&cFxM7fu_?AcO$B2G(52LY8-MO3czJQu0D z-{|@SFL#KKj+B23eNx84I*Eu158ZQVhv$2o74TblU6S93lJq?H~Usb9kZWZ5$t%rz4YS%;5Hx3gLNy`n_@CwHSu zmI@GJ`}^>Bfu-OH>0{XzBZ3p9(USJaNCG7XT^|XoOxh%q_K}IpuT)bsS?A5-W)pko zE!Mi7lmK_Z^N@t+lg*rFC5G@JHsa0r$VVw7sNTQVU63 z?p2;=IL;giAH4tACTHkUkwD^) zqn-cxv8)1ad=Lh-pz5c8u!Z)wTs^7TFVs>M9RJB5Nn?&TM*uBP0X`0pnKX643LUHg3x?Va;4!~N!JDqLdcPWJR)Ff!>me3i zlL52(MzJHyK%nM+n9#vFeqa;A!r^xwp@38epDl13N!naVj&8(V5-}dkXzBRv+c_B+r|0~5ZVSxsW~DpnHxY`wgX?Q*VYm*`K0?ghSLyl$U>8>> zsLHlp*_IhVe zJv|xdy}U#NuI#4t+fq}U@SFFJ)=HJ%le?;zi}8apxo3Qapmr-ZJEk-iRjR6+1dR|& zMl6elF?nQQuJJapSW+`JTNjNc)?JUj3pM3E%WN_GK#`>R=3@RQ+n(WURvP)9Bk%_p zfNk1FIHr&U(1UbE_7v~B;MA{PiqL~m zrQnYt15gE^j#pg5%gO)=?K+qO7st{OzAi`hNdYp6XRJ07xsQGIc;m#e=2y9~_Z?}` z+fHpHOSq2VPjqAqa_%|KE<2Irl~c;u!^5XJMy=O98K&J*T<4pgGn9151HxQvDiq4R zo385W~)E&Z?HKt_}KClEHtmok4E_ovA0IzI4s;sX*jOwfsU5ci+r z(BMZS5xB$|gr!YRRT^28U4lBXBprZOU@|;&$feS_zjb^4-8Y#oufBeXfq$0wT`&hn z=4N=z1k9(^^R&7HmspBf^j3cvxUa4XFd_EH)0P*=m&x z$Evfp>}xpAthhsD@%4T_enkSZ;cNcecZ1d|R|YQ)W? zMQ_ZE1z_J?>7&V7>owS*Dw<=bm0o1&MwdIpE;tb4C*~`!t_($j?GNr%cV(uZhlq2z zb=1+(uC=oImA#V%<)v0-=**mf#fD7Q&1qGvX>>E|$oJ#@jV8CmIFn`ixRluVJ z0r-;@Ha&W>jE@i!wm1qI|%XHN4dab%Y`y`k`R(2RCXi1g8|-mZW_1WCLjl zu1U#7c8xqqddc!RVvMH2G!uAF0-Gg2v)|dDk?TVma_94m%V%}bKu^^PX-QVQ{E^{b z!-VA2w8_)EDxw}8s8J;5Ka`#7PIu#cm~NEmP*=dU*LzDPwIA9H@wv^6^ZE1;J1*Xl zPhvp%ww9`b=vA1BM#Lo1J35Bpa%KC<5TA2{}JccKG;(FMj|E@JN`2*^(kBR{;D2`gQA1No(RE zO`>~=7_UJQZ46$sPLEC~tU5swNVQC||8C}a81eKau^R92mvd$``I013*6)q^_{Wn> z^41_9RhnMkslGckqw#M;j_>ujX-0c7eDtMmR%##9G?GT|yv+D`LCX02E44}xM2A#& zp(t(mZBKB3_unoYT>Rk*{xT@(>Q4sqDAafZu!oF@Jre=g;ee3^Z-)09E(WwaXtdSI zZ*Z>%O*aA#LYR>X<)rU^l4jity?2ho!7H_~uhmr+Ruh`SZhW{d3;7#r9!mw2MpH5>Yi{bU;__2aH*!h zotL|aciSeB^;s^NuFlPrXT~YJk!gG(d|U_IxiZ;=t-s|eP2YFD^!afk_c-n=L83%WmSaTP8*l!V-Z`u_*&tq^HtOG}w&e7;050A;M$L5f8ZTyP0rSy( z@)qk071- zIhtG|kC}Ra-y^^q5o(0dxDa_NRDiAdHF8AfWxS`?tAr8jc|!hIM#tVp%6D%Ha^`E` zT40cEd)9Pm>;?Nryrp-T$}}ndj#NZoEtLT)UNPC?=@102kaE!bqSE~|apBY%4{{=j zMON5jf>rCXBwN}Gm5&NK+K4$awy$|*I$!+2)$MI^4Sy;ex7~7(fx|67P&j&xvG%0- z$2&TzkpDVPf9{f6(nKn32wq857R zgry>AMmTY43~_AY3@;WWsq*{g7AMItaNtnBQTa6vMc{;Lqd<{r&xzA25n{P5$kJX6 zR>IP*^!O++N8JTD1-o1;*g6?aYTvFu$FA56CK@kKv1{vOLQ;Cz$Z1f5C-z5M`R_cB z@k*NSS!~#eP?Ixc$Q=qhlOK^6u=ICSYEds(=`n z3)NGy`aM!0_=aq&&s)>y<0`(pd30MoLYnlHA&e0TPSg#0hia}2$yK3|zQ9UY3TsEb7Y_p6 zUQFrF)tWvFRRBckgijCp?ST!n&wjEa-b27|WmCTK{2A?QkF}ZXl3m7>ab$(-M6F){ zjuI|`5!Eg9{@gRF$S3nuCiYJ1GdJ2O<=QYwi1k5+eUud)UlV@g-Q*=)o?2 zcTe%RM1xv~mruzH#{4Bj*RC!zNcWmOwgV z&cdJXWgb+3fTygZLiQ^{N_Vn~KUQO_>5votLITI|ah#O%KL@}ef|x=b>i87CcDrEE zxcuPDpg=SYuf6%79yE=4Z@+9)z$RpC1<7puC-t~lKYvFAXGEo9gSgtTY>JRkBJ0~M zm_#LiM!dbqiSSm((y#KcfTfcqe09(~JvzTq-3+tfw!rBz^uf3ZXYeeRWJi8WpY=%t z@exDS%t4OgYe&6{SK7T0+2#h8MO33)*li+`beNd?Z@GlHbNbH$f;1^wCow{NV)3Yo zFLiqmK-=`x#)cZDcBGSs#S8SfAo@xykO#V$)D{Xv3cXO5rx^hx8v-t<94>$iHv5e* zJ}AM4S&jET@(9Y$;}Gd6^AIM;t#cw>^VRH;zWlZG&e2-?zO5Gl5&^e3-&2{CDezAC zE$70+DXXFT6;VQPes1W-1q%Od@ER{@m^B?1t*xaGl7Cu4t&zq|Z>7K6^Di*%$WFb< zCpyd@dcm_{0OYVqPD}|jfXq_6_++h9-B@T(Ri~KNTa$gswm)1u&|8A6H(3#kz-5q9zqr1M0Cw(nM81JRS#xg48T@Iz#l|M)Vb;a#Pd9iJ1Q zqyH%q*elINa6PYQmMTlwBUg!3b40dWkO~NDx-+*7n+zsYQ5l42sN6~fj;p~$Aiq8E zo~`k>dta6yxptvIJR`5^6R80WN;Zm!(j;n1+hN1(OPpHvViWa~!jy4P;5MTO-#%42 zq$yD7DAXnGP4>0bToJN5sBil0ysXV?(zKvL{sRi9_-ZeEg#Oj$1I{oL{tqUK@qIZ) z`l3sa3=|Y^hL502kqjSkbg*ATz|6B&Z1x;!>vg6aL|Trv4z6c{kf4LoQ3h-#+m7qK z?7D-l?oNR}5qAEbpjMg={-Wiv-`J5buwdT^g^>1;0|7^xSmc%O{qeU?qVSN-mB~(hbp>(P8>A&d?&R}ydrtZk0^Rj6f>&ecnjgcI zu-fZims%6y_1pNjXaq+iLYy&~$LWth@vmZiHAMWT(J-iR_yrQd!71Gdb-$T(ls|-+ z>R>`o>2MP~1DQ6(*-bcj`nq%qIxed6;JpQBasju@)OWqKu-sdZbe~CV6|qOKJ$P>p zbB2MXOnp81MOpRel!8oYDwGKPax1H_fjAJRiqE>2f=shq_u|ND)rr0crX|fwoVmL0 zQQpnGHv%P=srX>pF3KYOe$dju;Z5)KD+g4roJGNr%o}uAR++?1Tgp*{EE^|0ZqY5= zql9uw-zK>*HIl3_mE2K%!l%~a+B$&Ov+!B_WW?y+61k`bx&HvT$c6K+>@o=<|zd*v=|K$GB$HnLlaPb^#IN*A}bL?g8LzX%`{WwyEN4Dl# z08u3c!yf0g$v=Ni&Yz0<#*qub#eFfeVhS=55*#YkUqW_N0n6)vPyZ6X>_HB=qUMO>MIY^X!5k;NSKY9GmKO2oqgYFeI)N zVL!Aczb%bQZSCQEfdU`;i&*$ObPnXl74PZR@0ISqgkHRujK$(i_Y{Nj^jC1 za8_ovY8I)XB{Kf3;g7&#)F5Zf8bX}>73J1V4LR<6S$p}z>=3I& zVk>Pt-D-Ib0#Tx=NQwQksI2qdV4-IaAyGXH4;fkIu$8fvIW_qzv(IxItX#cGp0SF| zsBLJ-?9)GA@26vWbBYJJhcug-(vb@}QiHt7eBY9t4`0Oo*m zSZa!; zJ*V#K7Q9e>jOS8E$AB z$0=BHu-T|QqeP%U+%4Q>xv|qne}Az-g9=%2Gpq?q1@0RoFt6Y^%k7=o zH)j>elIR`qsbZ<6w+w4(Q40EC7Db7f*|by+1AzYU)K$-=Nyjfz|CNFiW)NN93K%Mc z_EK_8QJjyQVg=6{VRK>`h2$9(f zpY@3I-uPM``NNbbca^gKnnU-pN9lU*Q$#RAC(y{%iyQq}*Z&k-d9Ize1iY}kR%2sh zOTWK=&&I`({@4*T=h86AyinDs+&r(z(r4mjlRx|x3H%!+Z6<7H9Pb1}jBS2?UR%qk zLi{~RW}z3#q*?J=W%%mV!Sr0@iC{kP3mWaM*1!WYo$Ha*xg;A8$glozbM=P^5C_-K zHe2k{kf?@_ISc(sqhh)!vyeR{iOWMEzd-MeoH&BSP zBc^gdKsW?)&tym(jY1TTXM)9od4crab?MT;y0-u4BSNuOmkv(Mj5MJ#wbFJh8rtQV z?8)Q*0X0F&z5{S-ebZe7N-R44uiv~OZ~pqaoWE2qXZo68ABmDggqlXBHUFY)0ig8i zYrEyu@9xqa=;EmuB&(p7=L6V=e#z8X11QC@<4g=Y!QHqqBG=kS<=BTwIrO1dZb70; zP+m#{`B1h3sHd%iQSSQ6Liy&Odgb|-y;4yH2oF+Qz^GvKTO>3o*xfEEUEK-!_@j^< z{dh`x1|!lv5|KPlSjzIkcpk>N*HuevTdC}M2s`NQ3<%a>@PrC28j^#Q#=e-b>`i8 z2cJua&-*4f!b+lmX-lk2Y+Ej%w34`UcX=_qHAj=0kx+61O1Ey_vUho_K|cmS31CuD zaiMlWE}x4Ms}9;Ewf_Tli01(Zky)}g!I<&F7C=VcX>)&-R2VVE-*Efe-6khcv_4X@3$PF9hQ3neHhgy;8P^4r zvIw;XFAdMrMMHa^4N$6YfKl%1D$XSIizVv_ZP~1Om)(~xWRafr3?HHATHLzDwn@nq zJCMe=Q)7_40h(dEWTH$`@lxsPO300lh#Wr_k@w$?$mcgB5=lfQnhHr_YDDs2cWCdH zX4$>7Ssr`5NWSzW45&8%%E02#gPqEfo)F$m>8AjE5Woq5r6l-9i5J^xk#MO{2!NUJ z~$wwbV9w!AY_gF0EYbX!xxhB?LSY*x^)35DGW+p zfS{8lC&ZVa_;U1cT#kMimy6eiN%sbrUJ)ppR z6U`ixOvCFmkL}KefYPm7wNSNm+>wHrmnHX{DdL2ibR%xO)napY(<= z=9nvG6PNeQGcKT%i&ASZjQmbJwE0|s5_fqsDsNVsx9Zhgbt;|aT05E1w_5bmg*D1* zfdY<5_9~c%=Ou%C-=2U__{1-3dr{XFx7Mej;5>Tx$zPLA|5$( zuuBde?37a{OXRbwH8L0hprmeCHUdy;+t4F__Wix`{qOGqWgxw!5?lbMfKsJwAS@T4 z6onuVRrxNQP5^+5%ek|oa`k$z+=AilajBE2ry6g8ng{6nC%XpZiD&y|$M$mAo2r+p ziaZHIWi1c{^oIJLgk;m5TS>Xyft~cuO=35_3AuDNEEjJ_WEg6QrFlitQ0kSo<|%1w zjmq|&RghGw#13#?slzUC0obHsSrdt{#G(_(djx4i(G9ksJOYU@WXzZ{BTqf z4+AuivFKRhEI`Td(28(Zzh(?r6rjX6-orfHRRP?GmqdYd|Bvd*zCWjgQa)7Pu-H`R z@_R{iUXF(hZ*v_P<^oE~!IkBEr>O_&d7C}4J{{ zm6%^8J0m)If*Zy_I_}uc1(XaW+~d8Yfa&`=-m^l^3Md&HO027{TNM;Ayv=oFma%F4@C6tb+mRMj7* zEllvf^s{rl+r9TdC}8+$UN#qR7}vz-k#Su>$xv=>9}VBNlxXwhdm2z0pTM^4AqA8g z8XKg#rg|En#AoKJS8IWC)4EFSR|(E!oDG{~0`xA8EE8}u!4|AzuBZlOfk~9yfq_&= z4aLJj2~BwA_MJ)T=$w=rSMufBwS2j9eMBzY>V>M+q?GuRQdgQMZ7nbey{TL_Z;in) zbX4kUOCS|f48zcPF99OxZb67ik6r*fhDVxn6e!(qvv8Dx$pVzdN5-ZBO4Zdh3s!m4 z`h+AEP@;qsJfSVRRLWAf`{+owe0aE9PMj=~V^?aV-v*RuLuo_snzXL#mmmDM9rA-8 zY)3jV^~^gxrIa8ni^KqtfxxO(MmnS16vIyfm>C}y8R_>xvS>gJb)P&7L*_koG7y5w zriX^T^Q6jmRVs_F%D!C<^5lVSvTJ8KcEuB^t%np57SEI$4&7Y(jV}(<| z+4s*2D7g|!E1a7%vuF4_+mSpcsN|}=&7|F03^Db<%m?fN2w;+tQ1a=zuC%linkeP7 zs=V=e0!p;8dhp;O`Ptw8t@QWz%j>VdE-%0GvgAXeF)ttEY_>B)S$6m;zkXnV(hLUL zgqs#_%~>)e1<}oY9u4!&F%vNp&xB>i;qxX9bI+vBXPoCI4IXpFHQ~;COICR^6CZO# z;wGPbkL&J|0@-!SnVd~?!+R$`8O>aq&c@hKN&rxzx?34Nq?C$FiZcrnNBZgK9bxY2 z@=(C=*t|U#Z%iELk?|G_DDfS+(l_sRk1LM?hUe*=q2F)8zHMx%x?z!3#dfa0e~&zG3g3TNF~6Q=8_@V*6NX`o`E#X z;|)?%;{{I$fWZC_d=%q5+;c&g6g>C<_8K4~m^wW#U9}d}LJp z1OP=!sVx*xGC&nmQlQKWz|3Rihm=UF{U)Cr{-9fqz@I!_B%j`>mcghcp(HXPP5utq z)G!1vX|w#dKW|mrNPuJn>mG>YBV8mOLy`oQ2(hs4`PE=I=!n1=@}G*}4m^!?e|)@4 zJ~=TapPUKEwQfvu{n!=H2Oql*e@*soXpqPDY?UuPUL{X{*$+e8cnQ+9I7fIKnw-aud!bY#_MxkRT_v9sz#nLtlD#{oJ438u zOb@ZH5SQ&=+b+`KIsHKY0O)o@rO#VhTBNbDQEjCeduiEi-Si>Z;kjPvhOHb57`~Yt z%?T*EySy1Pt>~lSscDPmI{Rn}L7vmQfRdre+CG|kVCsiXPSE!o8%jQa#zjSis`5ra zsi2@>+I-JYhtFFZVZ@=neh`4t&oFMx11NE9qO*@P@?zaxmA?-ZP)ai|i&UJ*@#~Z_ z)!cIs+Yp?$G!2c4AKN+an=l@o?_(Sj&rApy#~IG+Y{xXrbIyCtv>9$x-VUNt{ru-Y zm!Y8{dE<>Yn55IsngI8>tQ0UjHJQl89}~xUWIRqZ7PHG6-;pbQ z^KSRJGAUsAuDL^dC*PeCN|Te5IRPanubt;Bvy^k>YL33r>MA)>XPgDiWUj42ECbbW zRJWlHYiP$MX-sQIyrW~js({6@yBXw^q8=F;6luSbl54P&bmB~poH*Bu9o#BpB!aEO zAk`B9;;^wQB73(@%C22r*|w)fTDMdH)E8{;ja03K)qW6!hBd!_sJ;0hKEoZ%eBdd| zkSPz5B;wQA{)WB{dF9{{ELVfoR2-z-1;5dbAnjz+h=pn)Ga5z9bf9tb0) z=O_eo0zjL%(_0MV6gGteSOkD>AS4}kM&-=;5Wb`)<-@Z{8IL6;3NNWCBodNMP~+YV z>AOewm&jMY?w4J=0SpylA2wi59$&)pfUd~5!J(A&^rv9YYFJJj@05!dL(%iNU55e=X+V z%y#6dRa#OGe~d*yDdRMX{#aqep!AVUlr&$RL3)n3|1N^z# zdODpMFL47_Dh0Hyn#_U!rXI|y@^f?mcaJNA0@>}*@Yo!gN$0r}P`cH@UEXMv zy9#|(W|ud2j=v&UdrvZ9c%SaWId;HXfKnIc3y@IC29%&8Psv~N43G3NNGHYOO9zx# zAm+!Udru0uOo==&Kxy9c*$mZ=+U~3k(|L3fTpK?pe)dFQuC$d&jEb385|c4bhD=4^ zb0%$P`V2SBW%yjq#Jg)ii7%P^RdZ#-y*C>LSg+=CIcRQpZg|U%hCU4_VX|IcZW-k+ zRioU~0j2bFbG_HS_dqEygQq#(ZsItPh`UOH4DZ?A$#((?qm)tsm_R^@ z23egFO4)t(+T}gQU|pqW7)fAcZkOG;5=;Vi0dGMF*7F{W%h50-ipG<2^9Cf7-jB=2 z$HLOl(P>#)2}tS0 zy%^uEvD^a;!V5r&5=wOZO({e}2`OGMugDd4J+tm+03`*LV4Qm#zPhGH)^Au3ad;Y& zwj8G-R;qRYlY(cGtWT7}N_k-)3X(Z=1VmCP>@o-GoTEoN<)aU~An8*iA76B;yp6*y zQHQkF4aw_&-X{O!FWMALqGBN5#dq?A<>EUM7?YAX24PGzh{^GPJ?mA<~1+`Kg@moLTS#0j6AzL1iR!C@H~g|3~aPf9$!vaMyk?B2dZ z9(lM@_CE&W-J8Am;_CxYeG#ddWBdcV|BjJWsUfiATrcr#_Epx{l(>Jq| zNZ*)#qC5jFohon5&CQTdvH&F?Ks&m0TQ@ISVEWVF=3Xr~1x%l>{4~78aZW&qnRfZT z+^k#h`wfrH(L89b(}2?Ou-ZxGSYKI*IerB`R-mshF0tnLjL$Wsap^w51h~glL4h>i zbs$BS$x?V@Ly3KSVKF3>Y?Zfy`~n?AmH%85*q()@gi;iuy9<_3;zR5^)?okfzyT%0 zNYa!pyAw|n8N}vP%=)*EWVkkF9$66>j0QfdGw~2X0VNw<)Xqa|5R83&3K`Q4~gT-4ZB(Ixw%xL3h(}=(9`%J_9JFq=H7dA)(~%@-{DZS44z`v~LrK z8RogE0|rp)?d}yCX6Il-Ur|{BRht@1N17k{IoWUwG%KRuZYCB@0p%ls2mCt$rHKgu zN&z3XS6`)BYZK^hU7~Us!^~nq%6Yg2`1^-k8|c`8la?4Arw+j1eVZ{ zZ3(4el~Nj`VQ%d7R$Wso>zg;|B10d+57VNzesClav~KVSx+$OpgW5_9-XtBc4RI<@ zPM#c)Q>Xgn(~tAy@bO}4pP=*u=`}7zo=$158kHY?uMLK|H%kEKhJx?}k?0g8<2m>e zhcpsxCI!(i(Z_MFpb{jIVo}Hep;-9AxQ`r490mJF=XQFbo z1GcVikKkUfghRcuuCyM!Ym;5uie=v;N!hl;E9=0^+8XSbm7j!4B4IM7M?i^?lGTz- zU1GIU`f929!+`W%J9K)C=~wpi=8<$dxlh=p=`(;*SS&z^DsNWb&nMG!Mf0)+rl0$* zZs>ARfGw0Ro1Zt^ZwfsZl?@FIs{WD(aXojJx8>s0(%yy-_7UR{X2PlE~2Gmgol7C!$*^@jImOeTNZ9073v!)t)qVrW# zG0bzk*2+a@BYkz|-S|qEey4qp@hQfZ-BB=JcG^rUou-wtl|16QfRckCE9um(0*lI$ zqwcYjQHP@oC@qSLt2#2)Aq?D`00Ss1Vo|zFv`46YQcA%44C-Km*WTYX0!(U17j5Pcq@mp#OV!Jd9lx-r8~pen0Eu3xPF)$4PfvBo*~r<^^LT22dJRNwu2VTG;?;mEscaPG&hf3+B=~DlwQc z|Cmn#O4L8&JMo(=fbFAv?7%i9*RF@;=)r{i;e(W18H`If8O6N`DfA3TeMv~Z^T)07 z(hIFp)8LV+dM`jt>lGP53F+yMb+9gk`BVTC-UI<96pg#jB;gr15cEoT$|HAfq~t18 z)ZRUGLEb)cLB>LjG8k_}nTz1_rN%!gHO0NMqfO+SUvH5wKiMdiwctmsQU)()+8&7l z6pX`&dLr%todk>T1Z)n)<=n-voVya1?#=<}>=}?e?8H}^UnBJu0x)(|+S)v_@8Jfh zELKZJl}E~J2(Xbdq$IMSe->91Ou{|dRZ2VPCwjc(o1whTGy8cH&q~c)S+O%$ICCWF z3^#rMiUE|e3*yYIdwy>z;GlJTdpjg1+W{n%>qmsrvQh~Kg0NHO=x6Tj+ZUFaBaaJv zV2#F_rTykAt(nVZ-!pC9tV3x-$x?Zs522i4b_QC?ohEfHj)TRMSxJN+AypQT`E}&%b_<;aQoKn$Q+w1Ww7e&u)rr2MC z6(|Bji2^2)_+sUpK;T&uUy(sg4L?ZM072;>Jg0y5(S&RIh_4laAQmQ!8V@rW19UOW zR1))C_A%FehPi-JHl03Gf+97#kmV8tq`6*fNYqF24BU=2K%JmUK$9-Cw|)z zP^zt~bpa(qkhO4hwtcjDC!jPA^*4T7_Q$PY+!KR~RSf0h9;|q=#+x zod8f$9*7_TP$J+%pNt384-Q3Sa5ySGx02G`o`P+kUit9zt8yN@xJ3X^cs&8xQd1`z z>+7-oe5LHzT`60(1R*WslhO(p@eWKvmNvUw0a@8d3&Q{?c_9HrNgC#fY*E;O z`O-NDPZ&yXJI)!1Q!u8s`6NIj3s9ok<0$MY5m0JwX_*cvAql3Y&LnH6YrTPV0H7om zpu~8IL_R>JeCh6rN>@)r4!;|dw|^ItOWk1^PlN#0KpM_7F13Ym`J<;>A} z*|fzAiAd{hPC&^>eEBgK;cjcdm((Y@iyiPR(mWdTZ(nt<5Y9cjfza4$T!O}_Rl?H_sZZX`@F2OcJ`kVgXO0Jt#0j>G=d zFu=jyzNB2b90x#{kn5L5DsYZwfiX8T~qqrBrr?+&6RledeW@p7_N44 z*zdqQjdD{$X(518uJ^fN50(Ptr{U>h-kh!%`mxEA0hEAG5JVz~%z98zn2}KO(T*O* zJTssupcGw#gwi7F?_$cdoN@0PphU1nhj4V#x`i$D4C6rZVzIb_I>9_3{g|8^hMEcy zh9ymU8o}jrbYvjolEHi~?Z6NPl<*Ed&$M_=;3^W0;9Z=+SuOyh*z`tSg`r6TSDXc# znqfuN-`Of>u5gCAfRclFE9o?AlCYqxnTGCs7UwRYv>@uOiAdU)pg*B=0i`v;(uEbm z+4j-qX97x4d8339fJ7TJu+lZpE$l7RVwo{;THph|$ThA_&q5ZUgqztaZ&bOWw-5o6 z2YZrXi+IYO_&Es!pcD&3vL%FV>|xCL+@&EH;Ev0!t0}n&k)#`a-7+{eDn(FVt11Y} z{@twr9X3hZmO^RUUI>HOKByT3I?9hq(l-InCj%&XB_HWKw&zXx0YuOqk_9MPWwDvW zew~N~k50$icAKYx?gZu^1e6FQ89<4AS3n6?z&Xd^zb3PdwHD6*Rwk8p@_) zzl3?O&V4AML}4qKiNYRekoduU^~o5@Vex?RQvj3_VV{f+#pT1J?efvln~*3fmg6^z zWfBryd>UKB0gW1m%_^VlZe1^Xch$+4pYh6O|@w zsgzd$*b%@N^J<(2Qe&3Kdr3aNn_dZS;_-TR$GND^N1ah-dBpVnPC%)pg}b~hlTmI{ zL}%XJ^ZP>q2d#4gN?1cEpfpR}xj&i8O4X6atUF(<%X`2Bw)Ld|N*pg|8@J~lOTSob zdQhcZEZwK^4{eHLPFg}~EzaXb|f5;si`U5;+IF`3SrQbR@?IdO7YzUsT8n6hoVwToD|`le>(L*dbwP#O3N@8 zP|8KE6%dx2jdN$rG<4^)IL`)@_~ptn%3WvyllF7D>d4$LbnmV-3TR)z#U=R8evBaX zObMk*01KANn*!5}j=o@C{yXc{N-OvmJwML24?ax?l*VldrF#b`rR&*p(p~E;tNL6O zGaFFCgj(Zgo}rqR0viN5&}O&^1`SrSj0BWCuxm6vgq_odVR-vkw;YDQ0@bMN9SP|V zMF2icNgNu+ay*MX(JNwBAK&pQIOn5{`7V>x1u!@MecJ z1kx6g+C$3ZkNHr?APvUPv~eEyH41(ZPD9rtX+X&Wl`?=5jB;yqf*hH5Sn2b5O-L^l zP?8X$n-5%|G{7VeB&d3O`=LhLF9+ZE%YVIHBxhlZs5cA=AxJ4Pjlw*iJifhJ9@^c+n_Obtz&;<0ZLRVq#T%43C;1U@@$`UKq_q*cCBCuN(#LN(tx?xV*ryL z`BI*2Z}ZD`NMMzefzJT4`~j*I5U@fyEoKR|+_)Q`2J%MQks8LQ1E-xZ4J#eTa~T#* zi)-5COhAb?lq|`5K9JqdoBEX zDNIuM<_4K?H%?Z+1v~M~B?Hc@w)Uv`ZLYvv`k^Ni>94U0sDQm0M&} z>n5qjc8*n5)p#D206>s&T<~AId`S)I_4oJ7Ff8^P$IgMi83r{sA`ObMG2MVlNg)=P z%Ld*0+j4$=Bi6`QDdpk&6Vb&?&-LPClqnOkz-+20$M}>9ELpB zZ7UYT)I;xzAQG?GMl=kzb|46h30F!c#sFfRrsPT-wvzhgG<@&Cm<(bEJwJ9=t12#+ z4YdWbce_V+Y!ArhEj3WHs!;%?7$Al}0Pun$IFQ^)d7<*=q2vu6L5*w)CCm#5a%6)& z)&q_LW|uTW1_DZ)Lnx>;3e_!m0!kZNTBHOLN=V!)xJi>a(Q*^{VCgLfYf+FEngTsc zela0U6{=T|x(|TTdwzNAw}o=%R@?%VD4~SC?Ko|Ccw+->N7c*oU(1tkJQswz9l<)n zc__Ex9bbpnayCS-S>v1w_M76667wKGN;`l)aY!gdko@rABvd>m<-PYse*ZyAZVyb! zz~s1$LE0$k1z-lyClB+ZhC)auJsg$C9*aOytW>sbFTpN%34lsrND~260`I7zNF(FP zL_k6?t`v^OWw2YMzfAKCIfx>BQE3F&J^z2E6v(lNgcr^D}7W!y3x;Q{7 zyE0{8J74CWFP#F}4SA_4AsquKQR0r1jIy#afJ$YU;9Ca!Ob4-)&TXmLa-X|93Yd1x zR1Duto99v6cNU<;MVt?yczH#+ZX?dG5FBhY4F$RHRi)D;-Jb_Z0n-nYh42dnluVs5 zSvA+$b;{gdQAbY3w7mSW92f4HD;;71;F!D9j~0Z)FxcyXw_@{oEWTmah??i4<8jyu zipjfgCFGrV;&QWZSZ<6A0cjclUeG7CC1tX;al7o>*&tv2I;3)*^hr?(w(c$U>P~QR zNY4-u@k2_<<3oa8Nc>C#l=ARCr#d_(jyX4&CDYT3kiIhf;*lS~xWFK&G&Tl63A?&=_y?c-=C=iM zro#r5VvtfwP67i-$TrMdHnpsWlu*9B{6e0BE!@G4;|;NE?u%xet%;@>4Ch1&D1lD2 zR~~>W8Mnm?!KP6RYKM7wfZ^cZdNV3-z7>^=*9WA%4;v4_-cicmfC9m$QYwUZOv&!* zaoMzCOuqiL2KoAPjZ#q^l|Vj#z(5?*XRuf0g$kb(W5Qhkdr2@X4)2eloH3vD3?$@c zH$cR53HkI`Le5;7l8%uGBca5(-g*K`nD6lew3kM?bJd;ul&u-bX619neK#OOf!X+E z(~#{v8&K-N&VB|^s;sI^8|5a?8J~`Qy&2=pG4oRQY_(9p@QxBk1eFLV-GL_-Pzbw8 zP8&+(J-vymWkhx0+Mhx(hYlT*zx%ttlfj`u`N?1Yr3ENKqLEUK>YVM?)Jt<*Ed-k< zpAQyLa`eJ%kP|?GZ{O~e4oD`QJ9l2rpFgk2Aa^RES{fNj2_;Sn2`W*Cy%AeBH*aWG zNh5ab{9@GCHvmz!PC0w_tQ zVLQ-9t7E_%gn446(u#vg1)WYV^qgOAMbhu^w?OV51g_B>aW&@O%EbD~pRyGC9U}BEW z+?p`cCpaaP2qy6>MFjw*s+ww*baYNMT;4k=xr)y1KA5~$9%B7X(RXecPcVU=A29e~ zB5gwn&tPQW&opQ1&$Pgmdcm%W{gvsmP!GahcWIsC6xGJmUFgSo*NbXVH)Pv zIxuPjO4#LXQ4&fs0VQv;SV5)!p>gRS9Fq_Jkd!yy^vIc;5lcb|c9hhX5z4!DU4yi? zG|U8)kblmVNO^U3(N&6v=U@Vi4M+lXQVAuJ1b`C3BpT87!+JOU$>VW3c_JYvPj7nJ$X=- z%ZDUq5U+(q7CnI}_(|+6H$IudN4}(7zLD3wq`$pw^V zA>IlO&ebMuUbC(1+zr=k+XMsV0+e)UvF8WbV|@1Y3Z{sgHJbv4X9gsq%3D`wxAyJ% z_)x5X5@!ScJ_i$T zt3R;+fE;-AfPzQW)s@=FCnrNN_!v^rV`iG7$Mj5#oxp_)7v!_gj?0-dXK;RA#Zv$1 zkNyZY2cBefbw?rnbo8T-BpQzZtP0AWy?f;O=l@7{?%ZWXFrAK_SGBKXKg+yZ*Y-jK zlag$w_L~4G9X@ zM)P^ock%;#>&3S5cW&L$FV`j5Hd;ZY91=?Nrt3ynF%&QZiZesbFxDduAkzRP0@>(y zD4|pZRowhMd@V;GVFsHy>zk=l=ExW4>JxH>F|PADUeo0Yv+lURi=+VgNN*+$QwF+_-dE zOn`kf;p87BltxBj(-B?)C4fpbwKclq7q^mD9%s==lTq=m%#BGi5Or2Qd^XmL}pYlhX<#C4*A4Ct3Gn^ zWC4B2xMib=Z13qwNq2WrK016u-u?XrY46UHhBgDN7_(*j<og2koexFxBS z6Hr1ySOZy3l7QtRSuze68J1YV)9z1P1}7b@-6&0!k~aZWw-}`zMW-QN$2+$P_i4fv7uxp z>2Zidhe9EA)*bTx2M6W&iIbQZS=-O<*}GTv?%5+0HKY-3OF{|r8BS7Rw406#c`oRU zKKs$5N9FCe-`4aJFz!vT>AB~glgA!^EKTdrKK)GSJ8pGg0@Wq0n_K0N|M*X2-@bjY z2T-hAf73WP)tSs!D4m+1!Vpa2f|88a$(v5#w9c_-(QxLC73;{6BQ~HkBtQM>8<0@? zwk|>xPy#)2RvNprGZibH>HBeF^W=Ucy{u`HhIZM~-yrWrSxve~tGA~Y5_Oh@Qc0-= zC~>l378gcJWm)OqzWlBz;B13DXM5#f!}j0bKOh6}1d|9Xn6DRkL2gfuih_Ukaas>q zZ{~8@_gPn+VRO}86EFLjx!&jATMz}({3jd1O9D!&_69Iv6u<(<2HoWi60p_;gT{`@ zh`AWHpjR(%q+HoI^-N1gg75^rD~=o+2_{iSi7HoUC2AO&_L4?MlQJ-z!Uv+5-06tQ zmCKXz+38XF{Q4+Vp(fRDZETiJ>sw?;TTFIs8-p6VSDH2zL*fsTMm~T@*bR*8b17_l z@AUwDfwzobGgEw@1r}LEV;HX$QoxZ&AI{;~Ea!6MU7F`6q81g(Q{3gvmP{LmohN$Q zZzTV9f@!yT^H}}sDu*v!MtFOL}_jhKpkrOsaIMUNixn=a051y zQiua0@*m{_@CPH^r%(0Bryt*jB$>#i&Pus5NqsY>i+NXK49775fOWE~rA{7yJS9(j zB_b`Y0((*r>koSIv5r6@4RzDw5lAb=;dPf@s1RV|U4XL*>FJu1%jf##^7%12cezA9 zZ!f{_eiJedW8@8maoJd#kS!Y_v9`HJwrnkd9W8*kE!e{kl1lmclu)8H8l<1_Yta*& zXF=#pfL*p}VfH-}MI)Q%G@@0rOkYkLO4qJkQ$UF(76>Y^PS8_Qkz>GvaIEd>vhw;M z-u;Dmhp7-*^reK-&719NE3=7!5;g=1z^GZ8@8-DΝbiKFC+ExOZjK!pRTbGuP(m zECBDrbIr%~DaQd1I;~--ICpg1!ni-Fc6KW&pz;Qj7W7Qd^bO9Wvd?FXC)pA1^YwDS z|2`K_legwv)8Ayuo$KE8n3*f{i~*Fm#-nKyIs!_>8E9{L+IWw8qwlcm1K0iZX_dFZ zLHY4degc&@80Ch^9-8ejU3mJKDxFgP$M z7cX8^n@1;4eJ)$Jw8@sXHU)z?a5EkodLF+16F}mko%W7sNSnl`C)h;kpWprNZTXjf z`4>!#CS?2e?Xr9KZrDoNr{{*=oETiYdKLDSK9!F?`VdCGtL6D`eiJsCC=JyJNrP%k zcu+CmSpfoh(0c^46=Xs_44|a_kUa^-bWih`A`pf0(Pt!-ETi0(%9|yj#0sMePLnAf zO~rDCE%4kl21Z|0Wn>}Nl5^6~SvG`o*^|qqCuxqGGveBhDs7Q2JDXd#Zz-_JI!RAJ zi3VE93r;j$w{|F??F)S8U_;&x4GyVSRa^9B1Qp4D_7`a|5%IOY*mW;gJxdQRIjUy5 zO*`wclcdf%=?v%jY|muJB5B*7upLYdz-p1)3Pp)Ov;lvuZi*9K|9@xe3*#i&tSY z=WIw$pB$Gl+No8PC_U?w1%R|kwdxsxB0g0~^00T(31c69-upx)q z8)Dj=Xa(^G+RY)2`7Qzqyyk*lM`0WdpoCLaZU83=p70cXb1rAfZtgK2J;PZ>J~c5u zseW>D0xJ6Bs^(f(UoVB2i)gyJlAZ=A5zHYt7Di4fafNH-jbM@|QG|H~fEN_`55J4b zfBaimKD{(1*T#n=9)VO4bAUNcYYilI8mr~oFXhRrujXT63u{%j%{CwMN_DT4`QQbW zHV-`h1)J(23DSqQg_u#&j(@m`Jm`KV;3sWd;TxZH-wDgj>r>eEZBqX8y(u}}$q#t2 zjRb?+FcJrk>%3y9DVE4L4|wHIzLk>Qds0$gpTdGGA+baR01^Qo?6wD6O6(`SkW4b@ z7KcZE7z|?euL z>e)PS(#6~}$80{?Jk}k^(E)S(=9-hHN@&)CfKqvRh0gDaON$j)&^ca?^w|Eh$CB*V z-H&V2@0g=`$8zRnIo@r`ZRoI&JeauV*)*U8t*Jh&^Vt5`zY|ETKt13t@%jw;k9+JZ zcunurPErXa07|dF{<;My0k5Eq)fvvzBXgV)VRZ)FUqH#GNfMI`?wF!B5YT8xhDTJ= zy;=r68Zo!}JRScRqGdqAjFqSlqA2M2_NT?9kI+3Gj|L z-~6@w{ons@ZPZ`;+Sjog$z!s)tyL!gob-}sU21IWjvPL8Sl>x->X~Prkpl{0#uJ0r{)H z`YY`6_8R7d0R_KU(PsckORYC{MP%uw4TMWgZ;d`jp5<~gXhvRYO_>>6Io(3psXJEzG0nM&Y zGwRt~1)rl1Wv>>pQfd)u_ zn+JT5WzqJ;3%FcmbCzG@f}h|i$NV@Xow;+%AVB1Sfnl`&xcXYCypjLuFP2v7Gk+DR zuxMrhN+^>8OIAia0F($SS)atIj`gV*VJW*b>q~a;lOx zGL)2~A5X}?|9?Yr=v+u9pvIO+02G4SngUAz_XPg&4I%mRlasRV5wC3DRs@>h<6bZ( zz5wS*P=SLzB};-FnLyf>L==E6FAcY2ZU8`c4ON+_jO-c&-V5%!+2YaXQ0^`j%^i5eg84qhtM5#o6KuiNleEU*)ez!Sy>w`tXZ2CLtl6@~1%@Lo14!SnQ ze9oH&lx{)j0Utgp2`E)4s6b#r=lAT=>CC&#d(5?U_rd()-R$esnSAg9c}dr0>+XI1 zotB3O{BBdQ#pGdHTqeLg+iUY4TSAG~w4vk#lt^kmtF*;4W}M)d5Q|0S;6ckM_W;)Z z1e9KWY$TtLZi=^h-Fd1M3zXih}QsJ{L_l@>bv`RDS%2Z!(_^Nh4?Y>|x{oACt* zs$&s+(L;PXN+cB*l_;3BZTnUjZQQIPXcR+>LWY`?zBk`|Q~u!}{sAark-P#XKJmm8 zYU833Kolqa^faj43sJU@u$$cb@4u&j6xH1xdgvicZg=UfaVm|3i7}CCB9^Q`4AY!w zrPC~>e>9x=zVtr>M7u;H|(=0p{RfoKqb>& zOG_Z3R#~onlnI-++}U;1@t%2~ohw3ix^u;K@6AmCN1LCRn9$7}XhVs%l=vZoHk9h1 z`h!ki*={Bnb0@mG?-Jm#q=qO##D9W3kQPq*WojaXU2!0dblfkej{Be{f?eD?qjINz zRPK!QOBi5G3nYLyG?qgeNn{s%GgO*dT8f}H8i75f2>=lUkVtp}5}dW0nLFvm%FVe0 zK_%?61gRMdP~xs`);%I4Y^P~wx2r`pFGS|Yp$KdtQq_$+yxr`$t-iRZ0AHyK)PB-t zfD7F5Y4$dcgpd_$4#W9_C85Nl^$-%dv4?KeYm?6Z(`41}b85<9l}ieZ+ZSVBaq;2ZKg0dn1teGlcy zm%rSK4}vxL*yq7V7N&3Ss7COSm&}M}0Oj{Um5+4^VX-KT;NA%Uhz!c{(-ZRPnF+Z8 zFtVcy;C(m_crhWBFv`BA!6REX`Q`C1RlrwDMU_`7Yw%IgHcP3hmq?R_z!S*`j*vJI zNPuD2IZoqfrau-~CzH6fk@>xg>vW$97I{ z)}})=%8gB;_#vqZLJXGal_Ho$vBCfBv`j+FbiAK^&oUKhSzfFCEb0Y~a&xCQuKx=m z+(NS!6lf{5wi}(1H`1RU(+DaZJa|z4_HX}IKSa2I(hO4FeSiUln37KR?2ej7uP(xn z_K6cGpm%s!cV}yEUN0LqG-0uBiGZu#JqB$q-YGdmmA9?iwqh5Ut{q)o5{7ZD9pTH!GX;8&(pnp(4{`jc8_uhL5OQhA~_C2yswr$^L zOCxdCF?|?kIhaN)9)q}cM8%%9YzWVGhYue@rTQ7ZY!1p_ywFRjk@js;kYUoLy%!cUJwGj@u}OWe^!^TS@NV1r>JH zsVc;mxgf^YF&Ttt$;XEa<-?B(rMnl4@$tBfM~5Yn=#p|6+1}OGEIYO~!qBn@lE~Z= z-h+u6zY0$Q%%C)mC6UDX&9Rvfhb4(@qXx_a-kE|Pmj^0Xen_yW9UV&Js68MXP_lV3 zYkNjI+0OLuDw%|dA$Rk;edi8#CA%e8uib#e)eUKEsFiitA(p$t?u0b8?jSoK-_aN7 zpMr6qogN9@&~UW{&?J!eB*2wFyd9SR`1eWq6n2HKjEqQ<5=sC^AaW#?#nn<%S}osy zwFrO`Cb{L1-adeLdQhe|ps4}8OAwy9d0S=~M#5)4Dzeus1yBJk}@icY>JQtT+1C!Dn z8If2rEKPX;aVvuI#DQvg{D~Ubu+azO?S3gJL@Jn8d3`aIF^pa2LK20IE`BZcdCK8o z%pFF{=~-sQDM2R`Q9Y%%NFU?ab<s(2tH9oeyQX z96?zz7Ix{#-@*VHLFT?5aAPf)0@HYemWpbv^Lo-8-rDi0OV=KhOr)(<&f^Itx^DR> zVCF`%=D^uz$YbYq_CvgH*Mk)L1KLnhmA9!Wm_?~k;RS*T1=w+1-LyKBo!H8_=9pug zp_K`ndCiz4kcq)7i(n=s``UV9?l{)n)s!ysivRAeZf*CJI_J8MHk3HWr^=fF9a(-l z_7(K1HVLWK!-tRP4)0w1zy4#WyuAV&O0LSAMXY=AtDUo*kWNflzu?(XpF4LBMzTMZ z_aH5F2C8p6c5Ig&0Cm={Zw9c`terQR(bLnd5=?!4yQvi&fdip7~#Waa8 z$OM%B@gM(D7x_Q@;SW`ntqjOw5mb?MvIGQr3}2UN2jj?*!?3yZTa|9wvSo|x+O<>m zL+x!FY%fuCpW@7#Z&VacX!#Y2s(1WSJp^@^PE@$wzJ3fo5P?rvlVB&U&YwH42Er4V zbp81CAIr-xzs#CvRX#LYWCbqM;GNI9=l7NZW}(1Tt;WxH7b#M)BRZ;6acFY-&iNSSb1>})vs1;vuvmM=RL+#02}t- z*hkP8V348O8x8N7I;C|8johe1Q5A}+zKd~8Yg&4En2SeNTTK^vbKU)=0O?Q327W-8 z3Qg%3OY)z6K`jh&^UI}itS_t|YteCHWi6bo9o=Ga?6w-6kT7f|MWZk(JrRUN(jfeh zTs%`FXD`;sSQuN#1Nh1J4q+k&Fs3mkk37@{DV8Rj$7Nk3ZC1pPE`SA391}Ho01k8s zjH|Ku6u^O~Zq-{<2xF+Wi$x*h1EC!+B$a}&aY)-$F-X*)DdKsyGlEMNFJ`o%IogcX zzXyvxK4tyIn@o0l|G$oq%Kk^9pUuAuOnv3uDJ1qc?(lar& zGsJ$SxS$;6tB^<>#;Rj}dH3xJ*iagl6W1oCCk!bb78DXX1U)EuU5!P}_g*TO@4SYO z7=;nk%W?Dx*bOg$ISTt1f;{LJ*w?VnvHCE(PG)sKrmhkkr47nhA_{;C?^7BEWPGSV zx;qNx%0*0)k9ErNi^DRJsFKlCl}Z39(3KjNpbS8Tu}F4rZ^1mO3_xKB<^uqN*)AF{ zk|>Oi`#cfJ^U~z=r2qgx07*naR1=h%ME)khD*!;?A?;v^rwZrQ7+a@gWGEz;PkSKg z7LY49$K~c=j|^a|zye>Plm!c=rM47OZl$oj6_mY@jH;~lN^u!%E`c6-`LsC&!|9V_ z5(51KUKmjJl|n*^8z>NJgL8D79wV9LpbbqMaNfosE~03Jy$?IPMlt`Rjm-+Ez>sFv z*6~Oe^^cOPTu_jwe1`vK{;2P~+aHbvcDi?)l>5Ac0;mhhC%aPcoT^X!SY({p*^?j= z7nd}@LG=~gD9A)|j}MdrreAk7+ZpfIxf3T#hR510^=C$0R095MUEthmY-|*}Irm5; z99DI=GMKc;FUVK^o4A_r%#>D4h?ygrISk83Ia$(7X@jHAQxR^~L%c@!hx=J^5I1}7 zx#rSk8FlRQsNe|!A<~2GobBG&Z>Dsjv+eUEbDS!ZTo2$w)F+=DlYjl!U+TE=>a)$L8$r%gBa)N$N=L&Yjx&m!dLn6zS>YCQ=CpKGsbp`l$||$R*oGzruK}^K;`YR zM<10(4?GHe`Th9X^{5Ws`C#Uy%a`Pxw|^_2pE`xcK7qkJC@;SBlDzQJixR>FpQ4FQ zKDDRicX=AefJ-sStb^Vrd^B{;#pi+!UmoHtW|$0!lRI9fkcQP9F3N z99oyLr4$Z@Rs8w(?M~Q*xFpwa+>k^pf{MgRU&ir0ckpHN^qDhiSLZMO;xFV|-};sU zQk<-^p>x9Gx(7o6)A6w#llJsnB&QP>V(z`Wq5$a5g*g|a1vW$I)U1#`C6E@%b$xGw(8C+yStO?&@xju3o(=M~{943F?zF zFo>NU;dk%at($#3{@CNHQqN62ST{JSbn;0Hk@cf}j7~nW=|_SF$Kz5~QYEFul@f{t zP~L#N``c0Z_kSCZ6St=z)de6)rwJ%108Gh)L|1`V{_Ib%)7vXmQkXY|au4DyQOSpd z4x_Mq1d+H?5zDQ882TXX!yNgs=wZ!4C|OA`JW7x-F$E5Trd~{b6J^-gtx`H~iF|PA zmK^yZrg};>)W8I5nyM+Qoc1d%Ofj-N)t1?GEW20(coKmv9R9 zYap2xge|A1cNNOxj}=J6dcT576;%vh)_7))$TDXs6E;VDP=G_HR2t6yQR7?z*dfKnikCqZBqN_4{{GQwte z`pB>~;2sE|#EMI=B4eoJRC&8_{yY%9Pvo67{`@z-AAx7v+T)U(g8@(4jq)={N_ze2BWfb=MH>T!$fh<9@u7T1IlPs3^p?6l@*L%q`1=$_33Zl zx+7=LpM(9UYr4pYq0?dIV#8I#-B>{00a$hpak$`k{eQeJFTU`i#$^Y^2B}}bn7&J>&U#<8|9y*wO0181H zP@0~Oot%4E*%SaD$$9dQ^~AJEs}@Wjgjo>w1N2-(aKIs;L@6bHvCgh%S|7N;L*HQT z%|?vui3)Rq?AUp;p5nFU3mImvHNTh$nD_9ehB2b+mP`S|3$qZVBpLyw2t5`ToRD!` zp>(1e^yEa1^#^Y>b&1FM9OIjMK_1d6|8V3u!4SqV6GCSk1Y3N!?>jke^1wKzKIr{9 z>IJ2OD4{~zMP4r?f1r+(piLTpJAnWuQkWE_U}QOwEP!A&pgyvaxBMtlJQm`lc?aYYbsLE`yp_5&BF>ljPy!3f660yRojbjJk88 z0YXr{Ndh#X6-ERH}XX0W$jl)Di6Pkfu=kf;87Vznzd@{t^;OccyR+DIchc ziLV^KgqF8q58Eq$@qDp-`^6G~Z2agI#`7V}PeM4-CK2n5-7h%ukd{<(R!UR|&RGfy zu|O^eAP)e>PzMrm%wytMT*Qh%|4MA062M$%6!aLElb^@r$PK=S^&K9Dxdmki1PY`A zo2ax@#pR)0oscvik_t-mK!VFsb4%h2Ev#Mv5c2>uN<@c{{seeWunXakKnoU>pvFZ} z?_x4KR1VVwHPX`?lTN6ZcXo#G0kTZG2MT3)3V>gDLUz{_%H}2jS@ngmm5F0hOxCrG z!md&nb(Om{0q%-Ik`(H1!9Reh4%;6aVj$GIM(;Ff83j7Q1D5!lRQe_x>> za+y_ENna+&BY3N{x9gYTyE!u2-8d`1NI~;`Hz~Q#PNRU`Pk?#pV75`t?`= zG|!HCpI)bVOkf-N!+nOExncSlmJNLo3&4JsZ&ALpyoj$K4D9)2u5?YFta@yZiS`^( z#~(!C{DpMjx|nJ3I5|~)Ljk2y`C*A=C2hE&7L9YW?Q0y= z5z>$JP)!Al4GJt_Ei5q)un5kU2WW_s0w|>`A}T5? zYcD1W7cX5@mAALw{=Hnfcu99d?7-QgXupC0)VZ_gqDeEDnN7!-mnjJl_ zdDLt0ieKm1iLf5<3kT~D(QDQz)=z%1(%oKIS6#OzD3IMYStzz|wpI=_tOLdoP~v2R z_m}J(b#gIj%vOJOLb8~I+_)JEICx=AFsy!^zyT#!)iw)w&5s3CL*iE{P9|7q2tKoa zHU-(%-BT0`Eph=OG2a2VstU{WqD`nH>q-@$8eY8~V2nYa3 ziw9A!Q3oLD7DSNgQ?;{449*!xMuv28QB_r~JGvSG$(_rkNxEiFESrg=I@jaw(<+UQ zK4Y%&-t^%l3i};86SkCoJ-eQ<{eF>LHqA`gO~1}-Ltk^x(9B#fiiIML`o?A`q#hK^}cJA zdm*iEk#Te)g=cuA*NGPfZ#LK~_zHO9_z8LU-FE@NTvF9As)sc^&6pj+$%4?q6V)hf=o{){_JNz(}w@*tFP*$kDwI4BARz|%V(zb{`>C> z0VpmQo_gv@YF zZ9~2D&O7?vzx>HhA)@{&Djg*nxLvNb5a5tt1_sR^U*fv^PXRE1om~d$w7g zBkdK%6O(u^!7&2p+zf+dVciGF18}3WGf&#D1?9q}5lHEF$c>HxsJhv znnKdDJ|tVVu9L0XH%o0pA;6?4wv$Kt*u9m~Jow;;YkUy~Xyu2RnN>=wjrskYsG?z4@c7` zt@l}T9}GGeUpR3knB&E>z*l0KXMX>?u>A7>PRfZZ1JXO$EvYzioVNwI#|Dc;D9)ek z_sO4r!}tHQ_uk)i9of0yz5y3G0|dbYfFzicNJ>~>2nQKBe`Ip=^tWPl)YylK8~*V*?TTp}`v0CWqeTPM`1uy<9R zs_*Q*OSWzf%7*m;s1DK=(Kz@|TaK(R-c=bcRTeUn&dNy;1!ajqoz82yC=YE^0f38B zLJfdR9MV(JP8%GE%gHZC<*O5;(%jxJx4R$8xWFiVPCZadNKnBQgob2iX(S+p-hxGK~+Ex!0kW zjBD*~v3;LOWZg2RfY(*{;hX%Y4HX(_rg3J1NqjfV_$1>xi{fu*+BTW! z_rzt=%&JYgu)on6ef0!CMl(BKOh~>`?TH_ZX_%Ssd$+!X%9~0mapN7wi#gLngr%%6 zIDg|j&ZJ1S9{MstI+S8UMs{t%biL>J(1LN1uDutYX&F{%x}+KVG}{2}lx8HY6$`-o?Avd@m4E!lf7CXV1(fFOB~O0CI=qF-5Okp4zFxTx zwXusAFX@hJl<0Z?{rBbAv12gmxK%wFNH;hz2$APb#JvdM=-<>><}ZKwOZf<%5=fO0 zMW&e9?|%0?MH7Gi^PkHbZ@dA+-kb2X3R^p)VK85+to6fx`sttK|NYm0#mk{ke)z*5 z%8^%(;43QQuF*-30!otFv` zKKke*U4#TMVad7|OaTtII!wEAU}*5pICRtTN;;07`PlZT|B>``^=KQQaYha_YFnYm zO{(=_O(*-a+9*K7t2EZfHeilhiqbeUfyF0w8EtYY>CD=GeeHEAX=USr0zO_?-=Bc( zJxZw3SSLRy5X{)Xj}?$mSx#2K8xdn&am8n&?j93Lox}_g@D$kiYnQFk2fzJ?2`SjbYXE{AsaVrlswpZS4-??L_&>wsMnEd1?Kf&f9 z8{Hg$+556#+0ySA)`1Z~0QElL3o31Z)wF1Q=F>k;$v^+|gq*$HF8BLxKpG23PTpRC zN?SD!e~#`9$gwv?4j&B4OZ#D02|_>4m^lkTiXy!Xa_FfUp!QO7FbJPzd0hEGS*0)4 z&>Z+en~zZE!|jRjfLyy6l;Qy|$3Yu>XbXj4Ts%DNm5ih;MBEZY#RNVc1gIpK zw+R+`3E1kImYcVua_iQBT)Q^_DJs}6#BO<2MR~HWI!7Ana%9i$ux#HImW>Tb*;t<@ z2IRp|!wIdMW=23Mj;+8Gc_;%YM?i@;w45vlcX^|+`4)i6Q&Lx7r=XI?^5SSZ*`L)# z0c$b{sq#wCbw+)Cy?#7mJGKvxtE=MK+K{)L-`Os2)uZS?WrF1 zZvd0$a>NC=KA`r~U;p)AtH4PXP@0QcPkG%si-u_Q{KCsG{X~IjnEOBf^FI|V+P8O~ z8ofMp_>k_p#%=oOXhZ4h<*N!lojrF(cVPJiK$>5C^b08|E`cvriJ*V@hksBhqP?(* zv=26s_V3@1FN)iAB1%J*w_r^B=8cFynsp1v{IF^tNY zGckZkQ_?du3H7%r7>Z8Fn$nQ$*jyvqx7Ns(U4623cdt~f$yYm5VW=iW1rB>p&Lyf^}^pp%x#^6_L;l;sadxnSV*mIeKS5F+-LNE%| zyC}XWUd84aS1w3cPw4xa(ucI4*xA*oe)q2304w(BN3S3K_(za} z*#Olvf-p!I?*`4vWy}lA4Oz2{EVl!cYFU^|L>Y$$$HoVL5ZDL+AGugc$CK zzwk4-ssN=o&yhzv?;;I@<% zb-|WW1561t$btQZ*cGn;Dxv_Da!^JjA4fYNJs|Um+-QGl6nQxn1LlQkJbod4h8^JW z6eN{GP+x;eZ3RTwKLSegculC)6;&?=dX0NA805oDW$bRP253gMTwR9c#vp~5gJ_4V~q zyS^52366R6CArch#Yxt!WD00s)$ZW>M00Zs0Hr1XN>x(dP_L@a?CaX!Gb%dUHI2eH z;&X0H@?Cg>LpP>8!Go*ekp=o2*I={p!f2LBf5&qq3cm6KNB^To@}T8`t|hC$ciK)X z!iQsiJXXmc9n&2l9cwcf{9Vx)*;-xZs@r!}l$D%MigsSV?(TwAVrREjiE3~qzy-LY zE9V31$ZoF-CFPVt=p=u z_VvlHAyQhU1NRSp@Bu{1f1ramOGN3VKYjX{f=;x)k6teye)ysMmk<9ZY?A18$Xn|qT9^KXLBY;weu&W%6dn(|A zmcscR0VVEK!m{#@jZPa6zpTNtF1*H%qln_-@E#_ZL@C**Xmg2x5+$i9N|{4Tkv0gh zQLa{JoelJP%*}G?u{g`{g0=%Ny05oSrR4}H6%@GbB%Og?Y;BFYv5lD1mzwe0E@s0O zLjikPu>VsWmTIe%Xy`>7FjoN}nrgL_P*UEf*>6#@;R>aI^?B;k4-XD2phQrK?+FEz zApNR4@bM+^1nzl{5A&5O832G3r0OpUPE!qt3?U?)h@+|FYg<4%A0*XZx!Nh0u6D?s z=4rXpk&v!&M1UdbVo06r-x!cxTXW>#{u)Tk)JR3mh?Lciz_uY&yI>qS2&2;?1lwKz zV3{~+4^dTWq!Rrqk%S{NX?UAb)^eMykBg_95-zk++qY59z-YGqm0vVW*7KV~OE`OGl5$7*E#`Uq}OU5x1y3?WEDj|9z;W?CM`a`PB> z>LtpjahR6$;scOQf?XyDGO|73BVccy4E5#7x2HSc+vUc+Qn}n!DFooWzif zPv1i=yJaI5Vr$n_%Ab8uAwT+Yh1AwWuv-$^1ExSx%#*l7Ty7W!-$OJ8KB@M)thh=H z5QJ)$w6R6NXKFgAJ^^rv{=(@=NX$*jl^cC>=|@O4 z9#3Ofbl#)xB>TIPDZsv={~RwkzsKO%+S&>UwN{lv-ngkw7nj@-l4Dq=n{_brcO0D4e7~cC8 zIQ*eQlu$aPh#;BF0sY+BvyfEkROZ&Kt&z9ieFr44`QD?%kL~I^D=~u-A0%?0J1r5N+JEmtPy-(;ekhPZ#Cm#E@U0 zIPv6*!x|79p3`&X%f{{S#4elylu!m0dqcgx_~HvE_J*%pPC|)*628hJO{S-5X1r*g zBk8~Uq}|x|SiZX8e(dV3+sIthcK>Ld2j=CK^`f&RrdCo%&(mv(Nt|fBNiGRb}MX@EbR5ke6P1 z2|&$ywVgBsHODhhhdYb;$KE}ARD$}w_uj(?uOC94D{VtbjjLkrV2*$Ufe|gW7SInU zxp>;X6i{N+Bvjt|b9-vlmpv3<-K<*Fm(ms+S1$ZJBAC-ZrHef}N;LI(Nvb+-c`P(!rP$-)>7s!Tn zc~Sra+(2wF&mx!vcYwiAd zrT=|RH$6VG54bVIKn4Ozt*sAKN@e4wjrx&0Oh5_kFw+@-EVTQX=QA3)MOsQYOZQ#M z<10O`@ykMgef-xl>2CLU-G7g~rdJy}1}H%?Z4_$m6%|h9O>HSDpadh#c#ou=OUs{L z`rh+DvV7;N+w(8M%FcmwGun~=en5$Bf`TOuP^!YNz8QcLs_pKtfgCe*4?ss@NNCD5=UD>OoM+%JLjZ zy=;;;US}3)uIricmeaXOE2xAL086$>wk^JB+!u^uZOFk6( z#tRoQPq+wMJWl$EJ2iRK-$3;zB0KaijN z*`L8E_C`-ai2w-~nJfbf#hC%?>p&e>OwyVQ5uUk42qj(kRa~#((LemhL;0tF>XPfX zM`VH$+*1*G7+WXNWR-giF?UqA$iZ!`_?T8BKX|_pfD+6C0F(&;AaoK+4p8Fp49B85 z65&8gG~>3TC2x7<$L?#1X&{R*(vGio@EHH1xu|ahQo2+4ureiIokW?B!%%hyAQ>23 zA4mL0QP`J@L47R@iQRCayt6$fhYv+%-~JLvcvV0}4;xuPO)@73Ds@SypCSDyjAF;2 z7D@6c3B7W%Ww;&LFdtKOJ_2;^Z(=A2b3`~;otn*aV%kNxd>sn2HPFOCAnGlmXih%1;xP^kiH zPqfKOn~9vqlm8aqQa2u1XxCFA+BMtsvvQgFKdW?CLOOHR-G4ok4|b2&{r7mC{N|Xz zd7errd4Q7HP@*{$&h-f<5k#OvGW_Mw3vpHlhW@&}kix9sOjES;_-_(Qen5$4EsAK? zgw9xwS0&?6(1c(TH}A*-N+3_t_O^87dTzgDoO$ikV4zL%XqV>P`EzRDXkcJKJ2eYJ zK#8`LxJ@$+XTSXNVd&=X(*d5ktw@lc&vctVTIauwo#QC&bnDhFT>$9ze_jJ9Eh*I( z!h!t<)DSmc5XBH<%Y|sW4Gt7}q@Uqz{^f<%04nGfsfRM=eI6rl3}B`utOgyKDGD~Qi$uz)f5$sY&gzy8-=03!sHqS!qT z_Nyk>$Yi42$R*pW?#Y41`|{p9weo`xcFBfK0B(X)$Q$W;5=sHh*EfeD-4-?FKwDs8 zSXOL2l7!u$B>2c&M}BRTj|Ip$oo03Y+EW=#^4bL{w+n1ZSs!vfe<0x$+T($1DEtm88UxSWcl zlkVmi90M>H0f0x}**YRkcOS{sOK~}SE>~_gN2P1DTlyvjr7Tn;#n^%F!1gkLS>>{8 zZ%B6S4#4(V26E}R$es7guH6B^G)an{k!|2HK&iA?cX(tQ$b63yOyc}63n-=O``iE}W0qyb z#%`UL*Lcne0=MlY@blmSM3}uBX{iJ%Yl<#XFJJFVA!bWXE+acjY}Y`eEs8I<^jP+*591xmcelQK6-?p8%K%!|%qt@$li(HyEZH+I z)Cctk{ga`0*~V_~7IsUUP)TSm4$q!Bs}jt2@7i^*n^(^Q1gXU?(-fZi3$Xw4wa2>~6RtKRC8te)^N$P{V>`Y=Cxw zm^L;Mp@%dWn9Nk2BV9b&*rmrq#~XJY#{iO&QKZWq*}#7SUo@5-fa+o_hBgCR+Lx}z zJTHKgv@hjvk7Gyhe7V)foT}g#SU=S zA+dCKLhiP9OH0R~43Cz{z+{=!0tj7Go+~@HOv|oald^4ljx=s9l^Ot{p}b)U=J*VP zC!p3q4=^bJmAi)z`=zZ%~Il*H;zccwW<9xxsx5$F|qj}?j|I+vA*iUUR zsxR)?>ha=Au(ETuHuItZC6;3~@bb9;O2#CAQzNl>-8}E{8apzt5fP@Rgc7~`@+$z8 ziu4Ns2lIT`t>JdKnea|Sa5QVLr)Wu;|`HWQ>Gki>Qk#_~M23Fe%D z5_Wkr5qNDQXeZCgExmpC8y?C*$shjn5I|BApb<5$0t5%B6@}>ZljCt2AC1cOYuuqE zE*Gy%V8e<*=^1z=qtQMYi9VFI5cjVsE0ULAStoD3y+L;DE|GP$VSJz=d<2JtrU52R zVWA%ZVwD3Q;=7cpQvBkBg_(YA!Pw~f0)ZyJYuUG~ESi#@;|k(&P5@X0V=kqac#dTB zxlG!iM#u*~1x{H$?y@cr0480#dQCUXIDO`{&I<;xV;^^IqkrqIx8%L|-c^u@63U!A zoIiJ70jT3&92feXJ9a`kYnN{J@spqaL_bVr0!l2qv+V>GLZ5^Zfh5;F(tJ{NH_%B- zkDv2rqw>Y))38m{C)e(@$o+@YG7+o;5o%pU@aV?U+p@jxj{Nxj4f5g7_egy`KV(cQ zogLsqK#3_n37`Z5!)XZ#_QYX734oHSylFXekt%m!gF_b0EpfSVJ1XCP`#?VZ?6Tar zKLG$}uY@C874RVt^k}?YM&Y-vft1j;b@Ix~#d7qW5bRdM9ulOU!jOKV@KX+e&hfD+ z_(_bjuwN9&!Tm5k90p-bn_rGyo&=L<>na>hLiGqA9CfF>92x8oc0cgN(~4M=(2 z8j_~ga=F=8CR1oQQ8cDKWuvmIVGujd<;jtkYXB@^Q;mu-$uFg?DCYu+Vh>P4fxxhS z1(edeyscXgl{XZIfP&x6Hpct!Kkad5n}6E$vd_;?0ghMX>EnP>3Dym>ODOqMO!13d z@p-uPF!DT7U-oIv)!*j2?yr#X#zHTPeV#JSi^=OJROmtx8qiF!pixwy^geWimFgiN+|^>@jdGr z7DERfxeIokcfo>Gy!5%n^Ad2$JpPN@lzbk?2daDb?_)ELb8_+0MY(a~hT2*zfXyU+ z5a2Gb^t8*keaCi4E0rNn7-NQ{Gga^@(L^vwZ73}gP|~up<|--VipJ8CNB;WpM9;nO z;`ykY{9;l00K31DP=Y5Rd`Hl(55$U%9mZ+YhbJ!(ozTFvSmB!jWW0{m4jSpw-e=n#1w%=en4Wro40I| z^&8eHje`KZ((@RW%sgpFg3(#%&YtEs`@VP@>Mi|Q@|K=}QVVReIvYyPD7PO_vXtlK z&$DX+mX!IOC@8#CT;P<3B4v$6Jouh7~v(b7bRE}*x+W}by-_z5R0+fnie~XeyW!&Yh z2nPEgj!#f2^~@|4Otq<5?qx46KMJs|DnAzkD0wP9i>XDn9V~`QFD8zSPkbM7lCkUn zrPP9z^g;U!V&PA3j*>C-7`t#6?17T5qkUaEss$Bv{NJiJy8LZYL(8e6{?2c!Vc=kucsXp=e2Q*MJk z?N|cDA~1ozgrD@S)DgiKZ-7l*oBLp)zGGjS2f0&PUmtd8I|qZ;{~>42odw{~s~?&g zw=~Mu&5d&G{rBLH!LCk?N}KXS6U#|kdFRfZ(;eOjCUHC9#Yrf+a%-)9eB!i1xxs3B zE>#cSLtDFYF)CkwL0ShpyiJDIf`{NIBzI;2NPoxs_Fi)oH^4gXHHMZHy4ZLRu^<2Rpkw8Y}hSL zSawRPVK=n{m1FY8;X!%jNI(v}v{o8-RjCBIlV)RU78x6lLBc$yAX71H9p&Zmc{to; zTZYX~^vekVQ4?t5l#+u1ZO|r$d}!NgWB~kwEwGE<#^u84xZG?RluMn1khmL1@h7Dg zI+_hNHF9uInf&Z$5qaw!@Em}a3X}z*;)fjy$FQ^G$l$0v>L1X}RVXR9rEw!{R$-Sn z*jEa`Ymu})v(&5~L%OB4XZOtfzp1t|f3)n~r=)<9ykdl8tEgTR9aT5fRafl&DD11y1o+V@O>>K+p4w!EcmEy z(bL@vj~%ZFHei)e4t2-sHPvpHw?zU<*>FXa|ufXp(@`$25#7KN?KR z0Q|kXu#t3cQ10Fyg59Jcc{mJJajdA5A%I2&#Zp;OATR9?V$mN!T}xyWZ1ofr!4NVu zp46@l+CHU`bS~x_>$&h&O*btse|Xc2z{vUlFX1>_VzZYPvyYwQ;EFv(jhsx|Df#Ly$gn#cj{&xlz zFMpl_lxRaK4JeWS4pd@Un4t@JHn($hcC_?pZsj*7r_#ZF`~yqE4sDPMdN?61&BJo# z$}}Xoa^&QdFeKcjWipCJ7XY|KuPz}Q@&;u4hECbPH!ertYQPR~wGzpLsw8}X3w7-5 z3p?EsgNi1{*a!ens?KSK$ka)>p=D!-wg7e$#3+n=XtyXUuqKH@5^sDY3A;*3X=@2c z$AbWjhL6h?_>S&j>3lQ@S_h>PW)$jcB646)R1I}++FT_Y;Y&)BQUV+3QIvmtbV^m; zy1F}%GbEH6A)&O9fD)wJu?rls^E~?<>5q4X(#!!$r~$5_r6mJrB&FEzf(YIwx(qa zNdKsN9T&~qM-m{$aGi+*sPXrU%+uGEQLx}=Pr3xrfT8aGU3y03qS+4cW zmTPeoU>hJW2?P^R(w9wFw{9KGova8bRY4q5H&A^I?T%7CXn4+h_mc@MRyoGtpCE)TVm%2ZE_xx01XAL|h1$CD z7PLqv2^FG=(WKnG1&Iy#%U9ds+oY#2CjBFnG)hQeZcM7m^JR10I;gj;k(Xc1frnvb zNQlsLeVky~;Fved;L5{tI7juRAZ**%xpz4oXubHLRltkMI`L2w#sTW-Kqg#gMxN8Y zsBxHt>u=WQI3c7Tc;t48{pOo*<+DHi2|Kl2llBgb+3~0}G}Oxu?ACVl=)3avTkl9& zMVaQ~uMXJ}P&$A9No**&Bv={cshwJgYAN3^o>(?S$49HKM9;r zE^aa!hn=KpxqCMzfBYW_IesE44`7F@6ZR`5gq?WlX}AlCVjn?S6TS;uM$_{1AMTWQ zkJbaIoRET&2?=8i4P&#F2mo7p@|xKv39>3!O5jG5L3&0#ULd7;4?7K_ER*9&nF4q^ zJspv$XpUUI5R=Q7VrU2ba`9G=^ubOO!O-GxRI2iaWL@#5X*VxDDV$V+NF2@Bc)ya7sq z1l}`=JX~`i(8O3$x?2;{)*O>-w}$1~?O|zY9hBzw0U4hRz@T=HROAO_Lv36d>hobs zXgzjuTO(VygpTgGe^tW%{mOHoaKq~11)ZL)w*4u+vJbiUolm8p;=#=iR z!AJq=93VAn(j5ZQjfB)h0qGjj-Q8UR(h`D_f;7@Fy3fAncb)U!{(ARb+w(r}{dt}{ zaGW1aa3a$b5;P^SGgSlXHs@Vac#6yhe^E_+PhdkS#@l@fPC1BKf)*gjU?VySBx0eH-m@(AR-mm?&CP+=A+}niIyb*qf3zdlOV$S!*BZ183 ze*i!Zv=cS9V_`E9vdg^4zz7wNsMji96(Pjc?&jwPL+w(ho!D4WNsQjOacv4uTt`N( zr9NS~nKH@8XA`2{2JBXy53Ch(jAfR9^8t&4qYy+C@ z-vhM8uIE$_ZCji485X8I#D|ApNxgmguu1dZ-6?03WTR~z{*g0TU?$km_*srFbCajR zcK&8k%0Xc{WSTD3WL{}&X_s#K__F(j|w-!J47os=PAb4#7jF}6aK z2Ks%kWvLh{gcld|+ok-|3J29Trs3-oel0i}dOjhH01n;AZOl#Kt8L8PzQk*YVAGc{ zez8OFYWd-hK%;NYSJYtR##l*O$OJBz^Y@y#!30;`Q*k_yG;g`Z$oZB-)Uf&WR&y8t z=*a3GH|3YLdvC@i{XBSh7L^aU)w*Uu0q)2ax*+;--;bk0$BMEA7Hec3N-s;#iyRE8 zDRA32weVl1Zw||*{(ZXgJx7D6^9UE3g0{*1LgG3S8H00pS~HAj>je>}wP)LC|5ZQj zFoi{q`s(CW(crqYQ{@t79kwn`F$Ms5$_KD(_y zl8-2dszoZE7#dncLa`eptt$SaJhAbw=1A-g!2*0Q;U^Bj7LeTkB^gV&H9UjqR|0B7 zz)L`}v@jrAptSY`VSd8Fp96)vb=caj$u`c_xQS!j22N2l3y zZ{k`_#-Uf4(`^@kS=2P}Bte(}Rnr2nzYV{tmN*cq$h=%(uoTr z;jMk{ESPL`h+h{&*^=y@!UwO*$H6o%#7p_f`z|hKOg|EXHc{4@pq}6?xM_-_{6}_@ zS*FP7@eqywWwU_)WvoY8hE=PsO5o1tO{ha54P)`qKWzBVcZpb#^)J zVI+V8^s()$Ay9v_d^!!*g4jpiwG+kdRbi^!-YbE=MLP0P}?y^S=97BO|xIif7(*k&PVoo+}M$ zY*G)LAn6x<7xZ;d9D~(ITO1ItfuJ#(&8;Bq%f2GeAts${uxaph=ikbx z+~Dz);l>oTUdv4kavoTocaf8d?Qg21rbo+u z$GvXz=ITcc?KBvIw+S1>clYXGjlCi$WRK8xF0favJ$K#{5T4M$rz1j|fs}}KL zYfq2&ThsZUJhxH|>O1Gn;XliVIn8*b$FcS%aY0rbVi@pMNlc{WgBm8>P%%Ms8IG{v zKJruTS?N$>-CHAPgKJuJy_}aUv5{(9RJ{cSy>`Ss8Et94-dYiL+8&nu!yIceRz$=e z#p16{8>w@rx*S!j-J?*s@yF@|{;W6lha0-+kIX;O;2R_wLvZ8(V^;_~#()iM7SR}^ zv{*^mIs|`yEoo0~CReVy@+*I7@-sh z9h_8ZbHmdd90^0EG;~jQFv?hTw}pQ5n}Tw@h(_`;)lzrSbhF=DnQG4I2-Yy{xS#0kVYYWzb@u!lac^9N@qQm{Le@LRV zi2beZEwv^}vDYiTRUcW5yzdo>>JUa4F;}&`IrmE(jc>=(kFY--3^VkzGWT~arkKy+ zXv+W+7Z#J> z{b3r_Co2R6%P|~Q!nOfm93Bu{AhbMm?#zmiec!GWC;B^&*#8LU@(0RkGNITzl5O6x z$kBBT`UW?rh%SVFA)UW9?V<6uia8s~G-h6f0VAj{pKEpUJuWY;B)Tlp$LRcQ!kjIN$&AzHO;hF07LREPWxh1o5uz4rlB8Hgm~M~STBEdWRBN? zT7=uGP{7NTc_2Efq|&jyCD%ac=qUh8dE>WaJ@%2K%4st0V&!8rSN>~o7~xF#@D0fAC$<_Tw>O{x~MI+)x2IE+I&Sx^MPrjpWncBS#Q(cb0?#ka{y0LaY065 zjX|@ZdW8JJIR#DLuf?C77v6u$KE2c6s^qNKh@4O7!vjqeVNEr_W;TV=JqBsA!hB|B z(@y<9(6H<;nC(Qr>`Cao&FoFb0m-S0*upb${(TRX&7xhr7|@;!9}h#_67S}fnt^GX zV$qaJyb;_yz!*mwQ}1^4nC^FGj9WeW$}kwxg^b*6J%^G&OgY#7o-`f(nCac+{`7o% zc;>5xvMD_uv2}lr3STgVaWav{QQ{w=7R5{_{Bxik@-H*;gOR+Tl;gt+#uos9fcYI5 zjDt%u;nl5o^|l|h?C3gOUyK|4y^tfZHdY$qvSGs=;7?G8^vg_KjYTy0uPDG&w-HN~ z2et|diDamDkz`AVOpV1=H44<_v=sU$rQEpjGM{(rRq^KqvN#rO2>IKO=xyI-Lx|LR zaphV3u)}jRGcxLQR_Mhqk2r6yE?T+Lg`@;|UR=Itpqx>8*^7wkdKx;IX>+0dRes74 z{(<6mfj2SAQ-#2B3@RT56apsa$AL2IY)@RCco#h7Gyg+@jN0fTv*=0i_Z;yQc)1NU zbN5nY>3aEg-Lyt5J+Z!+=N4%3-+=eM7)FB2*cc=XBeHKGwkN?VKTz;>_t@T*uWC(u ziw72&tr1P#Cxe}H_JI%liiR{`)I`Hawg z`x9s|SKenC3q3txm|}~GgT!SiCY-_#tH{e(T-gZhfMRa+sd2jC9*cq za5gN#U;G~vB>gi9=~_{LrtRHqeN*E)0!bcv-Hc<#Z^=A8`^jvTp{Y_}HHqZ#6w^Xm zzv@%0#dfUJ1meB_=``fO$DjxK7?gE=f4!*+0FDRrNbzclm@<&@uX_Ew>p}r;sCsLH zaqu)zWjeriDtkp2Z?ju$vJ|Auqz14BfTjh5hE&!@#vH}-sBHhCWX4*)sIAg5M zD4gbmq^e4fvF5QQi|rH%J|o`kuOjfEjekM{@D8)RL=E z)cT*=DSv|PE((ELUR4I~z6Y?=2OIhHC-@BPV3rTL#>hdEES=wVT+FrV{5~6NCCa;C zt>}_V;Uh-N?eZo|Yq(=3^K|;1_nh*#Q@y=ZcJtuEU*&b zhD@bW7sF)hQ!DNEqqT|cz2<_DBkYk624O3lQ{xU#)@`ne>-yHSL08*xr2_p*66gTt zq>kV-s{#)VD+r2F4R=cMRbP|Nc*}D69$$`B-**cN(IxhsVZ(-t$jI4>x@<@!88yK` zAxcO8OV88d_u9G?@B+`!B>T+MAIRxm;Z__uh=NlK%!!`U=zaLxJCOZcynFr8e)*Tr zR_}fsy%u9{PIrS4Zr#a@(TH_1?=ro;EJq$XRN_Ei48v5^`y>=ep6O5Di#j_VMWNlM4k@P`-LCA(|SI zooq}Xh6`$LK9CPZHrmdwa1tojbnOnigrv1ceds}NMwIL0{9m_M2X-D0%$v#2YDn$t zILE8Mhqs7)*jdhj4C2vW6+~>If&vlx5xdO}l)J zQ9{@{3Nc<;7M#waGSlB8(0`TI<%Ni0sEzW2xs))&=oPEUJpk)r{xvM&07lQgmaV%Fs3BZYo?!`Y7wCpP_dGelHBE8@{F z!_nYFeTyDant9C3-PyzrZlkF>r60Ec%4VZMAx$d54T?Usm2m0hgY9O6v8|(PmIfCr zJ(f2p53^Sa8E-NQJ9jtnYA28Jp@{QegFm|Z1(E5)X`j>37Namo15K*3*>`f7vb=)ua|!_E;q`p2EIpgHrqxy#2?LQX2wyLhrXQo z5_5>#&w4s3zN4l!>@(ixU9?9Q>|ih|zGPW|u1A+QccE)KRDZt?m0jIS(C=_>H{mng zOPs_SoS9RMtdR2;T4Wtu$1yS?foGdUAxZQHfYsk)8Skyi%_DkHKFpd^Ewe7mb*MXA zJy_>@0C7=4`e2+XwkESRz9?ynzo)I72A?i!5fVWe(jVk;sit_EY?|UjwHi?&R$B6- zEOrAaswi${OeZd@nmu+vxIVk2(f*HMDGLprnlNM!mT}~LGN*tV!}RCYc$)q_QOca$ z0^tp?q&E(>5nJ5dCg^FOwQ1QCaP<6jpyl{nZbT7VYLPjUe?^dyWBST_k3qgYqiuud z5o2oVLKMi9*j3uWo$=ufq>4fri8k~9GTCWCVL!*>bj+?iw-q3~PYH3%n$}Kh%=P4+l`&jnRKyz6y zO%$}}ztFETHTBi=Vl#1qFM&0l_551$NyEI6Wg<8RSdo;i9_{Ncf$F0@w&I%vXnCff`X#~x$o4k#=1<>V- zO9@TV1YEfaSc?`}){LU`%!NF{xI1+vkOYE<0?GI+Yo@mJuKfRL)olW=6< z_=~sn$fqUq_=juRKMAiyhZ%MJlaZtg05X#2VHO3#6BDpIVFTWwo_YaAECKc@wZc*A z(6dj8m;Oyu)){yM`7Ck|5~nP6_EuS!w2dRA#^}14tvE)BVK&e=x@c#&093`*KuNyk zmhG{O3YG<-D5jSxo8`nGfE2-WYkQDE5mn4PD8-sZX- z=ZLZeiamM6V==n!_CM_Jn3ljXx7S&g+E8LPc$#7{vDjE8XY6<&YDImkkzj1)Rau<8tsI};MVYz1TSF~363euEF@OPv#-_Vk%_nezb1olq5I)uCML8LUIIM2 zOxft4T#9Xry_TR2loMkm{bMhKqT=z?hp6Kx8JD&^Wx$-Ggq>7Y`2{YvAEoqVgbjRO z#9SNhi4$4dkhOdW&vMCGXI|(J5b5k9?#TCzw&LR{#~(PF!Qt}Ahu|=`dix~F8kSkt zBE$lPqOK=wI zmqS?BMYX5a3y_gKkI#_b+7e}vF=`|R zZ-cSzY-{nEHrB(1@P`}*=-YKhtQ5gTq?*+bO{D~dEkB(NHOC6z_XnrCRGM#v9;d9k zd9?TOtjE-OBJs>mIw_)$Z-$PK5bxTvsgoHdxQPrVZSg`Su}lVh#kIZvDy-dzIn#>* z@tlB*;O_IenzLl2F+$}Lpm^H?p?R}S(8paeC5P8iC;?idps@@E#)PS7qLis8FXLmG ze@Rz8A`5y^qlM)p=_+IpE0ES4s-=lH$) zSWT9f6Pn?+LvM&V@?E8dQt*9zwVzQ@vkY1GEj(x2FUMiw-gaCEp7yGD0znZ%1zg60F z^tYYzpa4r`t);-?WHC6C=c@-4mITOZT@5ofO5d?C-76MpImP{ViREgZdo5P+;sov9bhT+cJFqS!g{mCr*G&D{ zzEB~7ixz*Zym7_zVO+o6U7BZJavtS^M=_A+2cU!~up<0oL6?PV6Z+AK=OBeQv;JT? zU*7+@y1KzhIqWlDDH|LsMSZH?B9Gi@@|fhn4wl579ED1(t4+htbzW#gg%nMrFj=UU z^#W0N#G%SXx31d9e<`RwoFv~*WP4r*tGh~plCbJ3;n8=xg@5V%Ie8*1Fut@FtF*ZA zhF6z@zAfThaKe=Ab@~92xmb>ytedkoWzAe)`Czk+ix;DV~nj#IJMbGx~;dFZOFOJMmzbf51im_9L=h`!)=z{d=eWWM#l8ESoL7CDyUq~Q7Vl%PH^A`s-SDPMsgX`lqp z{45l%Q`TWQ5XG>($8Z2Uel|z(wAtI=&qE=Dg{f|9OjKPM?IZfJ(g}Ir_J8-BCXLD4 z42>g|@7Bx?oqqf_W{e&SF@aJ2N^};$~hAGJ?7W@q$58dVC3`8Or1JF{JEnV;RV5R1P z5Q?)zXEv*l^5k;Y)zEPet;ib8ufYs?Tv8AZD8a)V{)D(Jc5Ii%9u=sl`$+K7(r^yb zOUM=hWaz{S(OX@xV0%7L#@hOqc~G2(o2Nm&5kQcIp7(lfX#ce;qwldFo_t;ia9xKW zydKB$=V><S}F?T3-^fuGa4v&C8|0-H>~W$fBz z=DTCc7H5&3t()L?_R(s3{!XaKzy9L=!5j*-e+Sc$jw|oGci&W%Nj}+W2ZulM_@fUZ z3>us~9OyAQXIS!@+m)1*u>INDwKt9?`4v_DKi$F)B-~ux3HQaMjop11b}jgtBV+^o zuMA}`&eNOMQDeLeWb<@mR53YdY;A2hQ$#Z@Z8!qPD_`8)iZix-)0#|q_wQ#V; zLx(7E{v>8BHo$sjNt*o{bEudkyp@|dWfn@BF!6q2C(y3vFrZvrM3h2B)n6M|t*&g4 z@n|H?>%DDzm%M|$uZQsCzM6&Uzb~rkCR^t`5&kk`qxAWBDeC=kuD&O$DV@H@`>w8k zbMEv%1O$+S$}4J;(C)9tpU|)@zXbFiF8cyV(5)^d<_pPipA6YhA(P=r$;J&VB|~Ve zD6Ucg;8A6=VjQLy5YR24_$(2-$RDxA#)h=E&#fJe#FGI>hHZQOyx(utOC61?KG=>m z;6|<@KuOt>c{|wPNZQgc6y!#Sw3@A~=t0TE^YS9)lf&e}%#T@C#7H4K=l;m{jF$lC zwZi)ehbHUKryp$?JV#Pe`vN#qYE!dCO3BC+!LMUtsI2B0kjAN}5g2>6OJ6+WIkzNy< zX)l4a?p0=0fsm>k8Y->b&Dg=Sh!`zP=1N4%ho$~NVS&}gURft_WQDM4Cz4E&_9^O# z`K7T>q?NJ=-_XFcQGrmb2`GYJPF2NMOWoBXdK9>z-r-@boAKd8(dC<7d~I9~T-EG- z+P{&$xW&6Pf6K9WgU6;4>|N(ptmvxl`&J}@P`kSX zca#4k8Kg%{;m_04v24zp7l+LbkM`4Wcnrfn(^ZlYVoZrHw{QCXS_o!?34Md`NKn4uiH$5eis^a&t zBjRNa<{c{>1|7;ppi*PpwTOgivA_AV^rsryCRB;iwENrBIga9Y<|+ie6kkyf+w`I8 zh4VIP+CA4Mk0Y^{Xj?MxsNh)wmk-Bf$* z?e8VW1;IVsQbiIODa|}4Ujc`Q*A!)r()_qakbfPQF3banXwle z^oY!h3qqdg@zHu}J*xVQ9*?qO$1sV_$5A0l`6-Nd{#DKEYbaXaa*bF|W%ActAF-QI zA&LOF822S6l@ld*E=gr6X8f7=*9s%#4E0e8xw4S2{_Q{NH}&*{#C)Nu6`p7xF$l=% zpx&awJ<9G%M4!2g&tButs9LFreYPc`aZf8%AuR&B{-sTzg?e-bb242oznzg4z~^^R z=c-%Qb$A24axPDlHgRGqCjDrmt>Wlt71+sy-YG{GA#UKm_QL%A*dEs7M9{8@vt=T!0py&65A+0)@N7 zUznY8Dt08*!gpjZ6Rl3ojJqDnd&q%dlT@Y^2v~CO)<)&b6}}~Ja54MX_4rOc?ps-) z^dW`Il6KkSjIc#>c+s|Bm8<&rZdDfkr45I=!U!RR$){r3~8(`I@;FJB{UhRYS*yp`z$ z`DuTx5m}_ahW=Nil_uC+9t`ro=SaGoDl01W%`Y_u(MAz?jQoFiz|d(Rl`v4tx3x*yy|atlihEuA@ZxI{bOSvr zSy$v(8?LEtRd^AFVEbT~vBk_VXEpga^ z(#s-r=1Kf8(#-HB6S8PyGkh#d4(w>-!=(3TOK9R=XE}d5WjUo25~!$N!f*{_iX;)X zzGyLmZc{1Q%Xq)$U9nZSmtbUMaz~iap4j`AdzoK{*1#np@v(1s!lpcU&WB$8{jJDY z@=t7-bdHdEY9nb?$X#4Yilrv{GfO6!S?9MUi{F$cbA&fGo{t=Ohy zBu9m!x-0NRz)0ABBIUB&4nl?`dEc?@1R0&j+6p4ihdU>4Kwv>kFi{>!7foTf+&+{j zJO-^@P=qWgVnr1u#EM`HaZVvEy|cBi(EqS;;Lf+%q2;BD(&U01Y1-s^Y2uDczIkE|&2CtB5T_nmd?rG;N?;yiB~o;u0h9gy zYJKCs2I=w?{!?y;O2&di)wgciVfgXGwt&ZG3YZJ8kNO{7JpOV%)Btm&6A4)oeWwCI z9Hm^&m=i~D4xRi?Nb6#VO|JyhkB)Yxk4Y!yN5H&aov8P9tP-_$@BO4?w^KCs!o1xt z65A08WfWRpK?M`jcPPbrf3&+~icT0~ue%?0o^fQdqD<=cE@Hhf<@?R(dDzWB8^zz7 z(J)v2?TNDX4h7`O)d~*{0uRq$-&|ZusbNTr5%p@mcsX^84cO#NF)rN#RpJ>I}EC2!Ib7mCQx!)t!3&EH%_*Ae$$}%*LxGnO-*VC~f#| z67=re;z3-7YwMk_zX^{*58+wW&-$9D%^#zC+5n(N1j&Z`qTI+&EAdB~+!Rp}Ed_fR z2_>J<4AShK+*VsVMvrdA`CQ7EX7kLK^QPnjjLjhGw6qxWj z5Rm9QbLfGzgb;Psg2?)Z(CD`E1BuU6*JiY6c}3~qB>SUj%+Fjzw8@+M@Z~8FP2~?2g2BTXFK?s1W<)X%`N{*QUcb zhwFnlQA*Ax-#@bK`hzE4=5Pk;Q|{mxjN z=l>)jgQQV}xPE3Yn@hMu%?BKV?pu!fUAnlrxveVM3rzfnQB;WGZ-Ykh!qYV!`ZF8F zJ7Z4$Q6WE;%JpN>bXoGg$DkO#l-sWE=)weyi}+v18UcW1o#jiJzuz3FWwZqzBD57+ z4#F}&(MoOtY~G&gUgHj+v15EeQ&?$YC3^`os{;6d=#tbZhqn&*5|GQE&dR=ELoyGR z{J_z$L|0>KmNGJR0yVh?vkE+{?e4%KV_dl`WF?5e}>*t*sYh z{VkQBBDfRHt;rvBhZTpF=hB4*?Ye@hltu_6ZOWdd^*utgziwSKH3@LNY8tdfLdC(@ zZwFj+^Oq~Io;F<^U}3^Rs?XOK7U=(N^F`dYyG3`5b8|_dp)Y`wE58=q4`MSLQ6M3= z1|dLP&^nNOJ(|nQzC~cZe~{us`tUdeIVxpxDxxswl$>iHRC# z6*A|xh#ADzfsyU(}%5#MFtorO8X3E9~qB`SK>PdS9LB(K|{NY#j04t8v;gi?#z8f5g{ht zt=eYo5TL-g4$=>*`mH%zZXlS;nh;&p)WNm#<3qKK4BMI=)+_ z@Kv&RUTS2%nKP4SNBk*Y%wU^4;DKeV>h*V%7@Jl_vLl4)Mt|J3O0brt!rt^4I4TF+hd+3vD zJV>Ms#)zEDX%g==W)li36T7h-ZFJ0_`yz55_!)(8bP8|*x>8uSAB89oI-@{DT-bRQ zgfFZs6qe&1Q)xS!Q`1dv;2;0~{Y;!#+TIWSr^?Ewg`qHNX8Qqp5!D0a z;yx-9Hjnjif`>q!W~xndOk~Z~Um*9N(Wr1S&6&od>44pqt5TunB`A#_8?vsSGaoi6 zdjV`R*7l^frhE1@4*jbh=}2R% z#+IdCn<%zcWxJz(!`T6~h%(a9X?MyD3@A93d7$}FRhF0k413k;xJ&f0Y~MQ=aLNI= zOb5hRIR*6pKx>e3%JE0z?~BK`8^!-dYy$DNb;)*cbe+7tbsd(y zdsX?&I@kFEj-Q!f4k#x31faR&~9Q6XNi7kh9@DHgo+efhXE zY|tBA&}UC@o~G~1n4xwwx|^^T>i94#Z)v`uZk*eVWKQv?MR=3R5MJ4vHJl%g@1W-Yxf)zvZV0 zK<#&@scV&(QtEHwVA>{Xc!wW|p^kvOCd~tk33Ug5ewGOrR?j_o)5#nS6{lr5{)>1d zp88IpcFqnA+3{p zAJkHyQPAxd+P~t(Y2A1OdHTn?{_kEP^S`}<1Z`z+-#g?5e~b~v&W~AS!kDuNp&M$W z?5--`AMy*@)SYnW;i? z7{a>#b$7chO@#_9E6_}bcG^^@)XjwH^du*ZN6(r{#;I?ZFCOA5a2L%YvL^`0#-2n` zXWF`-^qZspFQ(}MvX&H6BMU_*&bbyq-}`qOSa?$&Pu z0fz~!=bxBlx~i)CP@17dwy`x=i3vppq}W%G(XI=9HB3_;haaoR8Jk}bg+I~48{Gm& zNF$bG`=ItMVq&z+v}=iF*R5&9rin@$;?y^*jl=bg1grMmveI6qgoODJo$@PTJbaum z*pM%vu5g{8tT!b^KyNN3?q~%qxk{1MWTz@;*qGuoh_JR?h)CY6YpB7~YWgaVI>^Tu z8&v%%1GrARYWIkZoh?h5T-)>QIC>r+)7+}6tkvrsGx)1Tn_PE&{%gvZQ$)qqNTTCn zJ+}ePo7EY?(AR)ureh%inb128$Qvt+8)H|+=?m+TPgQKDMcV2KR|P-az35C5a8LTt z>cYS4kdUYnHD(BiHs4UN@494CIK2~d`_B)-s z>_S2W!8qJtfGWx7*Ghl_e5!x#fEVArm|rJW+L;c?FR12C0FSC?J)bA3V%)SKI%?V( zk{dJ9WGPtIvklGYoyvMxwpcBYzs=RJTb!p-G?vk{&A1c(eEj`YMZF|Hj&v|olnT@P zb^J=1`~phc3{+EoG`R=NY#6tgMc`3Y`^?Tdbp=z*ILbNkFDwizH(5Oow3zwZ=Aq!i zZq^Z~ip)Zc%0B7yvYd4Z*@dc(P~qJbO^1`{ty1A!rpE!GW7&+*C?7e|22!8GsA7qb*sktc z!{9Tk8ajVrWe7K_HnyZOSA7yHTqVX10Ai*tdEHA@N&@+!9?RQIi0K}F$f7bJWC#(` zJ9NZW&As<azz-o*ScwqX9?4m; z@;_2Z@4EcZ?rfNgRnAzETuw)r0|cOHZAB5J3tC)CVM0F@6xDdpD7#U9c@%IB2{D#0 zuR$S!9JFUzlKI*b;;y}LW`5rSEZ&m|JckL1`i^y%ShWYqf_(2@v-D9p%PZOjn1wkn zYct0#M*(2u5Hkfskt)1z$JAA7`OiajOp&k4`qQy8^5^9@;Fu* z^=qfZ3DiWOy++MrYtkv6fy7P5?D^ud``dWzwRNt7*5f5M{e&lVT$~%Gxw@G0UIQ{U zZ`TMKd%0s!%^8t1G!h7RjIS5j{Qoao3>4tPkL>lExYMECy}iBX-0th(IM&e_^xhxn zB*xtGL{Y|04c>YNzVlaKR+`NlvwQPG(q-)@k8AE-T_#+QoqZ>cuUdRv-*r}2sQD!F zI93biWAl=7p4>}q07*vC)5#Q3|GCf1vi^}am7*j*83>rVrKcbS07*bd8!ZvFoSu3d zyZmkUn38+kv$y8x(3$8F4JDboDpj}l80(qEu-Il=+WVWgR4SnEMGwF1W?tG^a@-cF z_I#6Fl)NU?!8wbj*zUGfN-VfkI5l&qs?~l&*!RGhM1>c?vPqVg!SON3@8tZ`mGONW z@0D1HE7|<po2uIdVUf=O)kZo1fnr9|EU$7;7sX+pkk6E|Mq;wS%0D+Wf7^}N)>dEENW#?HZU zHZlKq?Y{(g_q`b)ek^|b^;<39m&M5`se1^(4#kcul3`HTw;~}qpj#FTI@}M}IA(Yzb~yMwkM(1%N{~D_}nqNQA^xntlg2pt$!{KNVs*{+=3v_#w+4{ zhz*Vk9<|U9Y~ObwYa<6G$e!_JF2g*{zaxL|_LrGQ*m5#_<*vVn*C*Cttj#XWcI2s~)(|q6~Q)XN&9BDx3;Ru|MFk zHqx$#+hmm$Hy|f}4q*ZziF=m*irVL0-jir>F~$W5R{BVq*kdH=_1VB#K%2Y3r|9_t zs&@v-oH+!_mclv>D5EN9KsedxlQoH6K2Bg;=ZoHlx_E8p%cg1|H1<5#5V=ZLEvo35 z`UQ}fXMbv&;3E3Z!n;X(DdFIQMUo2vF{m1B ztplIY`;Md5rr(A&qPA4gq`s+~z%!WO1@q&Q6TJLb?d=un&xw)p9{no@mpDwEHr>}M zTlZykp}!Hr&0?8m{N)Yr-(~Y$Mj9{w>q#@aG?R#0@9E&L1QwhxIr8AOZ|}d}6YD;c zkkti!q?KpNzaY6V35#El(4Y0}71wvHKrFm!**Su@;{Wui_Nsm?`TEYc!ncJkQ&Jq3 zbo1=ibIT6(M}|Wj3UT^bkxt5w!=IC00FWSiiO{7g7N>zw3k{BZ**f}-(aQ4E?9*m( zg$F1x+IuhVb}g^@l0(WR zsF=QtZI3P65eSatGNxYALZB2^8tCYrLw?>|uuPhNSwEh}cd1c-Ghs(DQS8xlwpB6E z+2QV|MS157x5U#6a6FJN%L^*f#$|l%7e%SaI)XPA9JS!3%1Tt{nF$|yZ6WzYsWrKx z9fRQU<%^XaM~J=i^6%NEPTM*09Rqf>2fZvM8r-v9nb9sME0!6`iv4)fb00S&_IG1w zg0@Y0VA#rYJo|`#q2oQR3o89Up90qCH(v=i#c-SosstO`j?2AgtKkiVvDu$$z5de) z07Pg=9Xjo$?QcQ=dQ61P2>EzaiN1e!Q(957`+mDJi5`6R6MqlbX^hT& zcTld+zBwOF$EDh?Lh!{)VM<2W&wN7baVN&X)i{4IAu}hW`awy1f>diY{QR@^Aa!3z zkBdM>To_KM6vLJTRn~S^S|8)H*e54nI{_)t=s`A)AP2%n%&#huQmWg75p7N3b(PK3 z0iwQ}*{ttx)(W+qmx<*Z6c-wS#dnP_PD{8-S$A2w0l<>wNLSZ5&m4%Nrjz-(3ivFU zL#HjsZe(#}p)0bq*@Z1goNMm~G7DDE@RjWkwOqc^BJD4?NohGM>wVost~z0tnVYF+ zNAU*y5+<={RIxFs&H3#mq}>yAwXw4c?b4q57!@L3<-i~fQwVwaJUJ;(iJo`!q z&)R2gBNVLpkUhB_Yh|-<%D4#D`&#G5?45#fpkr-1HctDF z)4%>S(LoW>vt5bbn-0Yx@|;KyeFhvraewl}TQ836!T-b5TSi6wf6>B}lpsns0z)^_ zEzKYe(k0yu(jg%&Gebz%kkT#P(j}eJ-JQ?(_rLe9^}L?NTD&-OW`FkC!8H8zW7;2q zF%t8jdp^ZVJooZE#~6rLo5?P(AI%WZlyV*rHKVd>GOj-O2C{1-Qi-(*rqs<`8ZWy* zP-T`VyCShLtGGHw1iRIG@q`r@+hocXXsj@@Z6bq}wR+3EN%{y{Xtn66KcPU}$8;l_?jYqT9@Sdk#`U;|NH+-rVSEUo zZSy5nUH5Yfnxx-;|6UsTKwcv^vM{qrK|*!!PdKrdm{3^WNqA*opfI146OEg6c2u@{ z3iA)jAD8zCbar+*oWcavM1oB`{9g}D$PvqtjGqE?@HHk)hdI;{fxV6=KD;(G#^AF3 z$XG5y+;_`5m6!jqHabNQb(#)#phqkT**7mE5V@;tdlhl5xjvO8=e(xMq_;3QF)pvb zrnTE1(fZpES-?prLqd6(yOVcznNt`ZNS+On4bGl|PB4MVv8k2GmHRA=QF@_6S8$Iy=UQfCn7VJ?}F_p2=TMNWA+-vkIcim`X|9GUkrjcAS?9@Sx# zbjX|?H#?xHq>WD-g^XhJ2#sp26Yk}0*=SDgwjF+hYmiGV$VUAUOBKG0o3_!yQ&msP z81n3C*Irw9r^fusPG<2gz}i>Z$o-n{fejX``#@A5u^G{4P>#-c#`($#sm!1BvG=;e z7?<<`K~;~crensXsVr6vZhocBuEgd2M0Fl+W#LU`hxggZ zI8UeJoRngI-_5!IP^!k^E;f z@pK;RD4liKl2Z^hU05j)wb9=Ro&QgMoD$m?SL)b(ZtmX4*E%ZNys_6IVlmIp%svZ0 ziovvc8J5B#1LQ6p1y$9c?`uxV0S*42=c|4styf)84y7no`+=Kyo*Pxu3;oK60vlC@ zE(9WR-i0e4$OX2h(ZA=H{A~LV1ei7A zlT63T>FpOZ`>W?9%E^c}YZG+d%@)rRkzjbarR#=?HhK4qKW+UCn!KGup%nSL*)g8k z7OUxNYkEzxld+kj;dNo3d}hP11kbE*)B&HuQ2VJqt*>-5rHhkw-Ca;G1&Vx^%eyIB z81zsg)5*Xd5va@~c<|&mp>oJST9$fHNVI`zNcj!w6Y+zLQ`EC5uF{F0)e;AM6pc%uV9Rn3_vc-?LlGY%#lESD|fGya)Ta(89Nr+Z@yMl zG&s<;z$7Zu?QZs8|BWrF;%t)SqtY9ytLh_@U)Dw0fHE~|6X zTQSmhEn68V*e~k6EDZkC1>6~|yt*N80#tjaX66EO znU&nZ-|QA}#$W~n`04~h$8$jM;4l%nJHFzUci(THBjj#zUcM3B3e}`}GU|;y7CWlx zB_6@g;kpT^9+=nnjYG}kD}Jzq$DNhBbU~yzBCJ6!$Ru@E4z8=3u5tj;8O}buNdir2RR_Teqjnu>$fK?dSWP z%q1cNqHF|iwo$%X7n17olKMRD=3WEo{fy>}HavYdPyT3(9yiyyWl}(XEg*XBB$o5OJ< zP02;x_Mv9#%&w@#mF$BC2MIAu9#ChRuHj!8e3k6E4-%p>tx__RS8gJ9nI#lf(ve|F z_w;Y$@w(NcF=r2iN3P2r$5Vy?uwm=-Yvj{2WPGmKE9NDG2mx&8CNOQQ-`{)Lajs`= zXS90z4f$L7FI+IqV7NN4m!;G=R1g?NBR=!}gR$KRy>y?+02ENLYacI%A5z)0L7OLWrqFyD<(j9HcO4<(cRjRw>i(km_KP<}~!t~m`zH-mndcFjkPiMD2A(ZNi)ZaH_ z5TX6)Y1;`K-#VUrUpM+)VU!zC^_MmC^gR8r75&?g1(%i$)Ob~IU*0$KOlp5rDr4;Q zN~n0HVCpy6T3kjBlBPWF5M3}4gb2+H?6P?nerfY8AN@NZG^w-PXcYus9Y^rcfb?bx%uswaJC#7(5 zEC}rj{-*ihO(g7j*wGhj$fLTHQb&+?=4?h2Zd`=0xH&`LeJF5u07;fiS;7osIhBx|xs^oyKlPAOhNi09JcgGMJv!T-D@Z4r|Br=4g zRi2;kZcor+SDM?4I|mt-&nJyRSF%fofu&HVh%nG)fM25lZ*+G-H1-z_ry5gLI_Eky z374?*CP>|drV}x>IrS4Y(VIcjUqg3GGJCGu7{#7U$X0}B200v;4wY<}H!dFtL= z?e)^Mc-1E*bG{$pSS88kVVBtJ6g8GCj+YoiP2%5au_i6>dSCq^MENxNrA3ceWsQLn zN8_G3CLtl_Vzyj#-6p&NgOzQ4`^gq-SZlJ;2ew~Mw|gL;+syKj3I2JfnLo)y$`_R& z(Wux~FXckwg_~qPD>s#G`aRrdhrCmtUqbnwC3zQIx8nB3n%&|g@pHPb;XzsB!pbN1 zw2HeNu4KgQOUu50O4E?#1Ff9)C4w97Aa%zy2M3*$G(v-RLCnUgzkSb0qcd$~cOStC zZ?Lc$%XmoH;7^0U`E$?f?H$`B9<=pm5LA6ezt4r%j92df^vqXwKsS{LzY#YK5Hzws zec)sIAwJ`C_dRFe70lK~Tp>u^(BBY&v2~=AIoC0^u%(Rm^#xU(%NTZ|wiy)y`0lUX ztD9#z(|S6NYqkXcPegp%j*dD_Snz#5F+ODpn>RHV(W9yxeWRa|z}V?{Ogq$M3_vdi zLE2k7n@lXY%LT5Ai?Dbs)u>3%-a$8Unxg3!YMBAD1*7Ph^^O@Ka_@*q1!3m#S&EPS z;hg(qovoq$MNr+O*@>NVZs{Whg38B3@sl(i!)s%@{qP6n`fV~ncPAHijg@%Cjj?JG zpE=AwLs^O}Rn0btc9*t=5{NAFwNUBR=~C@8z$UF8yN8B06C*;>d2HBR6~WNd`qGJZ zyJ?kmir*aj{hT8tbHcR3ahkT`%F1qLdcl5Jpyz0*@FAWch z>HvA+W<#wLq{$q%-f9X3nxeG7Bp=*f;BYPZw7kOE`JH?Z`nH6WXznfy?I=jK0XM|1 zkN-m#d)WF+?pwHs3{8>s=UnFvO+Xitucq5n#S{Atw1`Co>@x=*UYun4nAl(w$h)cm z#Xtk0*_#wrd>iK8pX&2JsYk2vIAU@ncz;zho-tZS!NBB1yRa?y~H1ui;fi91ME5-@}bBWSyRb`f$UaGKs zjq>q0L@@XJm(yoM(xte(hISl^jH6*OmG%x?ELGe_JS!^q1=3Cn?RbV(bM;SpS&)I> z9&YI-`{<*YMjcEg?MAI>eSaj=w-{7E|NisLww^~T`t?Nz$Mfh{N8Hgnq+j;FOe3YQ z4G6!3>ORgesDz2H)*#KSd04^`uW#P+<9L^aw*?KA#}j?Eth4g4%ZeSwiEY9{fKQ8s z^frw32?)nOS>)bozk>b6OiW{IzO{TMXpHyD-j9v7UT4V3E@15pfl}P(u&?^puVIRo zd~rW5t*LCo%!?Jgit=+y2OXRX1_anSy~1-Dc70e8c>M|ZMzC(Jp1QG|sn5jFq%b0aTpi;o zMdnpgbKD^@t}5z!3K6Ux9vG^&AaQUX3^gnvALSilaO4?QxZH({Rv-5%b+ zA<7#|O>T{TcihKIts4kU>I-;&@%s)Z?Kfhchf4~)4Q1BWMGVF&+p9qtOTXPnx39zs z&u2YsJUIPWfQV$Mx(j&QfV5vc(1mC<>-)d+R!5P{gw(_nb&Ygl{6IWX$)KWkA5>v} zYz;$BO$1dMHeOx$`S#x$0hQSL&nsY4_9Hfx9054Va?0_HvXK~$T+JsGDMomHI$!kE zo0tik?*VE&VzKV9lH6K;PnOtdqV2Ph8`|5mNlmp+l_W!+ky%H-FqHh5Di#F-bxQmYj0w#buOUI;Xj5wopbULZX7iqWI7 zYC#^R`+iXzBuv;dnLCUo*A(u#tgb9;^ zLMv9eVP=1!vc^y@}8vLfR#@2{?+~& z9gLVZ)#nORgnQ>|x>@4{g%b?Ol8%~0*)xR|hMyjIJ)H5kFNJ0*Nx1DGl^g(mY!1_jb58K!7g)=W&0u0N zt}t`%JrBd8CcP$@_U+iY;L1oPha^5P=)aqd?CAxU(dHpC0V-IYnjjv4dWP>&#nbD?V!>LzmBpulN`4N0Cfw-w{u%Gx_&yPa?5;Dly3X zPUmU+(eEDbHU(tSXWqP1DJ^$g%OS=tVvNns1%*b=dmH5An}$z{dmI_VF47Q}^ROxlt5>$)A%N9MjWP-ekLHy|;$QHDIXj9|FpLdI}gv4oE^l zB0h)$_%CP5e1k1AdvGn@cvE$vA4xAazA+FHj-zU83vsiea?RT9z^kQ|#`vWw!@F{j z(cj$6;IgSINH;DtzN{_tLw8aQsTKqW{bZ=1;?qQeid^;4aVlzF^;G=*FmHyND7we# z8yEH@BebaTAFqfkVMC$vI`Cw2uKjx`e{6xMBZyQhRu`!+#?w2DHe) z4gUEdW^1Of&+DWCHf_n{?Hs$}W?+oBjn)ElI9&2p_0V~@&+mfNnSTQHlUgf9#`^lk zLpV#!H|m2=oI@E@b~zOXO|fHo&38}rT-q&UzW$7Fbm;g^dBA19C%$KpA#d4gt#+DjGR|jV}NLQ z^z63t(=oZDcxLaeBr5h+opsSK>D6%EOV3f$*>X#t1)SV91qVDj2=l;t0$1Fr{H6Q= z4PACmkk27+(Ik>)<3swk1%{K$Ji5`QdbaBCtva49ui3{cfn+(1rm*>Mf~KB^d%ER# zPakDYIu;weg=P~=1$?hrwUU(A5wXdV2PqM?LT`?i<;b`mDy>c^50{%~du42X=<>O1 z8rOfCfi_22_JazaXMJoktZpq4=#Y?s@&@MXn8w1dzaF<(rfwfg`^fL-` zvE`WV&?E{>eFy|YVZ2h`QsRR#ew5$K=KM(GebtNn6;gY!NizP%%^u`X_%&F-hIDc^ zGM=Yl8-!zJ88k8RmQu8!b~4cv%%i-%y-d0Uta+CZZL>3CzG?c(CbnP-ecP`-#=`YS z*%@`u_zTS-i!GB1`#V_`990NuIs)xM?CdO@vZP({@AdlA;XIk)*NsY6=AG^NVnGt^ zGx!nj|3S{RQD`SxY1=9$u}{$m;6eRAdxnV*ZOkx+?+<&7KY+bDPs9vRHoOp*M!Q`aF)9K2O`rqhZFJVjDjA?mq z7@O3bSo_ZEn_`tc0>7Y;Z$tbN!H-<0nu0)@J6T+D3;b3)>i2>Vj%rD1P5>Jn#%1on z;`@*)Kjd$p%?bGGlUm2;bpFSx6QRH~<#Nu;jy(vr-3YzyIAnRK@r6o}lbPC$WovOva?;K5Xv_Em|N0XD{AtaYolENt2W3l~%r@h) z#SPWeK}Qite6Lc{VV}?1Du8)&AY(SI<*}+3Ena>ATuljNGpA>QWh`v^(BZnj5sx8Y z$Y4k0219!Oaac5w^NX0u0Jv{rb~gG*)8Sz^PvvwXBC8P(*8`jjf?l3|{-b*b9x7{A zT}h60^C&vuqx$+Zg$#atOP8{VrTO5ma-muIi8)FU1@?UViVmjCy0%^>E0R)VHH-ds zj>&11lV1hAVKARwm!lan7SNUvq>j_CX;WJTOH|GMi>Z}P{@uj9{znyykUmjT@J(*w z!~k7Q`jS0$0Z05=*~IkV!0T5l=C`Jq9!qv%UW~Gy1v>>Fi2Z(aIAmU5-%*uA__VpG zR$_|(Sn{0lbYRz|i`FjkQoJ^`r;bHj5X3vZJ}W2{s6HX}JQn{>aY?4fGNDP8%ag4Q zl~_dID>1gKDTPjRAc8Zo;h`Ydee=Z1yey-fbKGW(`CEP5kC{^+6lQS>sze_RoVQAb zHM#em-{+j5-hpVLtik$d1$|HvEyl2uwt=-p@u?p#$0MsII6I@b%RP&Tnb~NTN08<1I#M)mdHTTnTG? znfJU3HyLOKAQ9u6(|gWrdatM&HNzKoU(3*|~iN8ZDRfL8&o z)tJ`Wu`2mZ;r3V8X{>3-ujiVID83CIQw>ucj>OHLKd{*tnzaW!VdEW+(*4cQK=zz; z6sf_^Dm?|>?>W#LO$%4j{zh%D{gSi0{gV64qc(!E+sF34?Fy1IJcX1w9_3r`ty0H>Vl}7$Y!I`Z$ zLl{iL>k9wco-}8WEY|hKF9I1h2~&o^)KhW=-e|6)0M(bD4|&a)Y6mZ*Mk4(R?|$$T z>NO0d`#SEK#w|^Gu+cTk@%E#TTVyEtiqmIy_>Z8ffuhHFaL)149D|7R!&UWPyR_%*R@YbiU%cjgIK`eM0Mf zlg2~6e9HjS;vK9IzuUdky^5cmU(cSF*2@<_u>BuY$BF`=y7mH3=4-}@w|m@H9Qv=5 z=}`GggOPx6n=&4`&r(^>>Wil>S1iAQrLSs6QquO_eYEkPZoLlCEY2i88#&>nIJ3s-Jpv{z~aj z8f7|Mq3lwl+-eI{d2P$6pr)^60b^9m7ES)@`YzfflTb!2oI8X?9piO`#oWR|MN*^! z{7O{&e3K1O@T)y7R4IR`Uv+&*cc$d!xT3wplG6zj+@c5L#e+A*% zKtOt^j021}xfSQvS7v@M8#M@YBV#;zr3KF4`CxGajQoi3JeVpZ$95hwN|jf`sIXaZ zKxD-IO6^(KkuH@eYK&pV0^+EKw?d;E#G zkQ}v^RZ$t319n&cTanJt_D%sg z2})hHa>gAxbWZrQ69=jrz}k#v&`W5t5y3Rtfg2Q&f(pTHKQ z3Xa82ECO)zh7yAFU)R=)i~kp}*Tt`~)Q)8>IEuQtEO;4J$u?cw+&w;MTkD?gDyjoF zQm**_U6F{e8LMy^a-<_Q9=jcABAGi5$ui78#kl}+xLN~CX<)AFE zLGwF+Zj7m_87N@&Y@O^on*^eK9!X-+AuFV>kR`|KUIDb^91V&Y@)X}tPY*eqfc`8L zi(ZK-0dYwlwIKnb@J%4l^KG}=RwGrZgp@9?o?S^5Ji1WnD7_H$hB5K4{N8sxFz75V zQ6}kB;0E14-N4meZSoZoj5!@9^BwY9F$m(rPIzO}r_JO#c2J%?^iUU|NAA61B}|}P zQMcCO8ZG}NX-}pYq~*PBv%CG=`Y`&kS1SImRNOx-a=_&#VR~gHPPF-EeJxl@;QE;B zaK0h=sWA6l@EgJSU@xL$u?I7X8qTy+JR@RJ;x@qOGTHFav9wjhe5Lq2$#dVv$W{pO zP4Eo+A1z?DJzjGKyw7&O_o1E6+D{3-oZQSAgdfs+vv20FU3-c4{X@2SJg+GexK`%h zOQZL|rR}@1cEMBWl!iL_8 z>l?_gKW8W`6>6>#88e(koIp}is5$#_?yVK*23bf|jXuk8%5AZkm>-hM_KlgnB$dt8 z*pa=VD(RcZQ?oy0lG0LoHA}9ArPTx&O0A82H)uOJWF%~2JjB*~RI)4L`CvlU&5^Ml zxYz~_)X36zEeLRY7xFTKL|Q~TxALzmEQ8V42y}?i>Q=+~v^+mM#9XaaGJi+oiLdld z52e56Kj4(#`?WVmo(r=)C{oEQ&BO2abn5xHygb*)8@A%Wq^aquB!e!mvHs4qq@xMY zz9lg?ebW?>P(1o!cJY{bplkxc^7GxEc*Wu!H0j#CY}A~%>V^b8-(YoM3%!oh)<0U1 z{NJOMEoM`(ej=-d^ddPyb#V3I;>5UGtJADP0#U!c7vI#It(Nx$xP3MTMr5(&^ni^> zRMn*%G}sF!?A`W1r1MJ{fX%88Jmx@98BL9nE&-kIhK^Bc-_p==;G;@IBW3!=KApS)1Cd$>PT> z>UctG2KrvS3_@tWd;FzV7tAR3ErK%y={f636t}n)z+vTXwlCF2V*VS0=a}x1$LHQS zcfHm)mm-V9c4c7@2yVT&46g(!CBq-j^IHWVBEcDX*?Btgqo_{o9Rr zuKOP``}ZGKmL?C2n1i~XW*5#YvK)EMqU_B&t&Djlce_u^5Wp}^1+}fCnGuqONsbfEDnx!+YkNf=R~QsMCLb!mP~@tm!5vu^i&Nz#hnw|W63?ubQB)C`ooQ=m69+vc zBKg%Zw7vx9F=i60_-iq*vs3N6t@Xi`PJhWL4H{WrN|6GP9usoGdHQd9 z#RMn?BW8qm5M=WEOYu=TUis8>-2rg7vEo-UNlH$!EIR0q@3-kTBTr@zcX>7tEMH0Q zibccW6cO&!II{ke<(YTCz?bLMZRz)@hEDZFuE~U*H<^L^Q$j#!>^EHwNQ*z@6GRm= zQJ8jP$(1~1bKz)88yi+q#_)5XV|j@0?^F;(&(@I*8QgT@btQLlyCm@6To1_lQiMO7 z&oly(lY3%g{qEk&zW>gg{}C`bD}&xh5;m_E=A>&*0n^1_)Q4N09MO-LX@wF1eD_Xm zA0c%p+X)A@xQ|?qgIiPjz-xk&My{LCZ!}4c%h!7@&MZWX1b7>kqNr)`+n96^7P$#- z!ryV4XqrRln~TPWx0G)}osS0bz@X)x#G%)X4~=LI+kDPrgl<`q`U3)~EPXB}+O#Wz zGrf4jwpAW>C}j?ts=dF?^LUju7Ht&bPW4uz8K_Z+Bcao9vu*OjEw7Lx-#6L$xvqay zD=+pBG(ZgztbWYjv|&LU6LfSO9kCOTj+Csd9VV@Kmzz-vzlWoS+vDbw^yLnh%&V2D zDW$z%6atbDyeI81)HYSI%>HUfYLe4_7&uA)R*K6Vj(7Iz^%pahy`Q*d0>hnNspev5 z^TfKYHhoaRNPI^wPSSl-SnA>}(GelYtDb57%HP`@_el%qE3OWCmfy@bGb+#QnkIY- zHk87YZyIAmBXXCTY5?M>z<-I6T&DdsM_I>botZZEIMM{)BwQS6G8J4}pw@w|-+vk> zR13K{UBVd467he%n$aAput05FawMg=fm&PlIlG`Fv_9UN{AGeztM7{@N35x_3I<)% zp!1qD?KOq1oL3-4uBJF0-yqX~;HVH73=)+$Ne(}Q3vDC7n~?!#W%uAnsu=_%a^l)B zyD$p!eGXFZLxV}O%JKa*6q%Z%a6*8oe3R^7TB)E78eIRq?)Lh^CRV9vx@w)c7oG(V&{nLuRr zYCAIG-n_E#l~pY7>Pgv9)d~Wg2iQ$%<-fDMt5mC4p#7fh za1;BXFo&wQesgzOo&K+y7Q%&89L<#|xXJ$|3y*tqL21rF`w(3B(Txsv$(8XSJ6bXO z(Do-D`*@Y+KVZRz`@*K_04&^EfVSQ`B0vRMt@<`OjEdp2YU=+X-f}D|Ut4ld4zt%+ z-qL(^mXFio$8AD}yCb*u2Z3&$3sVD-DQt7f1a8@q7LFA-A9r!G8?{CH#&2^`p7a?M zEN=`J-JjQFqP#g)GMO!BK3qFnF(e!M8bty}Eoo`@I}m0V$s7J~S-$1t^tKYS%BX)? zLA>wDE8~w1m+x%>0^Mx&miQN+3~AKGgD2Vpg|1!mX2cK$2IWlmzJ?0JX0TS7-8l8D zb6@MP52yd6Mm^PE3Pxa`Z9Vv)=KKn^%BSZMelfbSZsH%H8yWBOWm0G8Axxi!O^=uf8V(+ka?9 z$lgH$?`NKq`9CRpTR6`g7$FdFNWz!Mtc%1G&0qH9P=n-fxWC?-1YiH5cX{gLQ8rHP zybG4ejM0gXf(RWR#h8(G_OPYxR~A>0kUiw>?keTvgsthMsK=WYPq|z+&HlOTQY{ap z40}Z%xqt-o%U2}9ptm5;-n5LfYxCN|T?T&I6R@7Yva8WG>V3dJoz0&y0)Fg&s`*+< z9W_7w{P`$7WcQB@2(4JHtV}_zNDu+k9bFRh(lz5jv_p<(zqJ>Da-3(9Up+Cdi~V5) z<~j7ULg^+mt#!nJY)g;4F4?K3Y;UPjM?!&$POrTw=6tBZoI>``-QyjRpGry!`o3hC*E2+)nBJTtNkL1(HUzZk=q8qq`K}NVe@>~_Sn{PCIx5XT(iYjlPl8=z?IgClqWb#ia*4$*X*A7x_gYg3jPZHDeBeNtcD%xEqY^2+w-S z{=Vu97kkA_@RhzjX4W%{?(YyX*f#pg2JY#-2m79*lx_jE)ndTqP;l7|l-GOqP{dw@ zff^L}*{?dC{W2Lbi0}dB*xs|;w8%sd!#S~SR#&jgTfYGMeP^-RK(~A#~ z3GJ$>nTAY8HZsDa3=I<6?4M4<(HOn4Czm)S6sE1&VzCOjL_XCuh~uo|7>jglrF9b* zm>Z;Kt6LqsspWN&G^<6yhSL#~#+sS~`{9dKHdOfSE0< zJHB5R(`eOpY8uL9%dbmPgO`-nI-eqdhu_@Xv=Z_K418%g5d;zaL00{stUmBhaD^0k z`jY$7^jNO8r0U3)hS8{OZq#p4|vVESo_i_pvE|^21XZk9oZ0C!f z#eZP;MHU1*ys|Ro!ZxD)4<&>JS4Uc!=GcR$hU5Y8fT?Ef(EloEa)Gj)$f33D3Q%%8 z1;mI0x;@}Cjm594OMeqr@}f9k+r%`<)v&>_fIikLo?~04pLE_>(EiWSHn=Qwg!)*& z%X{l(ZKl36%aDNG-+qd^2rXhF>C8YlUd;lMMQR$q(uHbh=QWDs7LH^yfeCtx9C0Px zL=p4beC&@a`bQ1vMrUWkR0q}vnI#!nUJDbDw$VH;oCBd}$|x}M(i25Srovh6lZ-C? z-*B=0@*f%$EJ9*Nm7!LmP>mEuI(~8flMWEcTATYGFl>$A-FC+Q&6K4Tm6YW3e14@; zD-3>lQ*Xa4DYf}@%)_6txvlKJ5vhY&mx(_(FQl=g?=^!G&H*G0x>B`tEms8mX%zPu zOv7QseuFscNO!hTjPiUJjS^?P<453sNe)+LX7b?XXys%G;R)3<=$?s_@st0txqS0b z<>t#&@01vdYb8+FT972{@o8*|iD!~oK&+laUD3X+oP{eMyYL?;s`&Yc=n<*oPqm*xbagDZdZf+z7C0bKO89y$E;G6X1Dvo_QT`^kiY` zsOS8&&A8SF*|?)o9{V$&8b})iVb-kUn9&ri+Xpm9Wt`H$vut?G@@zqR6L5)TN!q;t z!#nd#+$N7>ue1~H=nqteM|S4bJgv#>8;*HX&}x{YiO%ip0sVSxRX;eK!7^=^r^;2^-|?VRt-~D+(K(6kt$>ujF*zJA*)jI2LH#uSz5> z5rtw}QaRrXP9Gnu(+M;Rp3B9!g?mn0(yli!JrEwFKC4zD?8Ez_{1bvsG!;cgg)Ilc zY}gTlOxo>dZ(%Bm=LpYhGr5~fGm$e}Ym@K84 z^k=O@Rm5a~e05t}dF?hLGpaD`*mxqB6LJaPfsV1kwz*QbMi$cC~%)*NB1k5XX97zED&wB_;8N3u!y!l0Q!Zs(Qn?5XYoX5 z5#mN&yPD#Zz4tneUaVJr`^291skuVN#QkqPOvI<}No^{ds|352<1d0Q6`k4WAxmUZ zE|Uq@>(=BVnfVjP?)Vn(dezjygPIrt|1BWV|mK+D&`z=-e{gQU@WwQTn zBeFj|i0`4=X3sQ1kQEEpyOUpQ%_m2r@AR7q2?0}@lbsmnpdsrP<_^I7cDWA(94>?o z0aII_fD)uG7B=$?SZm6jxcm|*=Tb+pm+#*oz=^0gs#_|^RB?^zE7~*36gQSxR@CYC zXch7Wq$q0GJ;8n17^kBM>m;hidv!Z_RtnLrM$-;9W=%DxJjFub2%lMIcN!-S9&ZKekZ z--@2MlyAwWa89rMMa$^hy7lMwyC3zSDvhc+W_(dOv>)~L;LxI%kT>FkjAn_RY{ z8-s#_`!zS>vg_-U)D`5cKkQY0XlwOY^wiYw_@mjPp*i*r5nLRAPmOM(4leoV@%uih z#Mf85kK)54&^5&00g{&uUww@L-oT?4A(dapLWIAZ8=KvpBTdjMF@k-jWoWILqD^=R zyEbXaNb$1WDarPUPHS#%{(Zx#-x$wPCl@1zUt%JnaEo(iKT8Hd$WjQxJC!yGCNX8m zl#<~#i9W9|N>166xyw-)1<9=1Le)c~8$zEkW)C+$g5913!e7oJ`UN~(P&R6&YA+JI zGV2}YCYnYT=^KZ``)#7F-3g}GrN6WB|TsE78%_)1LQC}FMrqVy^d;7OU# zXZvYbY2%+161bw|yzdy3Ox>$)bi`sdwU2ZRumLhwJV{6AI1@7>DeuJHzXJrpp>k!lGBdUI`kdV&?NR!grEEzyj6F9Y2 zYB|(sz_?kI*(0KipRzNIdZvi?Rwo^Ytc7^zk5rCF<16i6PiJZE+E>(!r&{0q=Ociq zSpr-^>QqWQdiEx0;`I+HJMZb1A1LV_p z_-7{$xw+tL^QiCjoCeSH6kJ6~kimc(B$%qtU@c zAINA5we-Nf1Oeulst~J0^S?>oX$h5LQu|ZAhkqWX2r#j_WZX+=?N8FS=y!@*VSWB; zt6Mwbt(E%3xqSuL&lmY}vrz@?! z+^SsMc9U#VFAL<1f0or!3`wSSL($kCSnsD4mME^WL_DEbi1vzi?2f42x$1mCfidQQ zY+%Vqu)jrLwljF2b#o@B&o`3+HP#ht9lwn5n4mec6SE}Cl0Hc`re*2@Ph>O^-tB!F zF??Irb<8& zj+ZtX-=#xO_%l1KZiadiBoT=VzBzdT1*v-;M~j^YL`2>QpeEl}E^#!*3*IYCCir4> zR!XPiYMV`6YTQ1Ty7~dl701}a>t{VE^k1M$6$KMIx>3kang@$3k$EQ(E}Pw)CCoHM z`9zg$5(5(n7o4ArCAFH-ZwkIL4-0m;CahUtw7x-kTXt3PK06x-}Xox=!P5a4}gN#_6n=@i|=KRdi~ zRX(_2IF#xIP#t}jv=e3rkihkAtM$QuB-j6tzyK!u%VNN3u1CfEV_3@f^wAb}2?ZHU z`?Kf01vAf{imxKk8vAP*n#<(+gR1J_Om~PY9GwwE6BBPaa$Mr5%N`vsk9t8-uct{7 zk0)H@TbkF9^VYlILTU0yX{53(m)dE%@nzlMwl@01Io)VvIdG+ec4**{ww+G0a{QFq z#_@)xTMzgWppyaM#WrcY^03s|FnZyn9qTIX3^|362;m zaIvzop7JyhJFd1JJ;pNx_S^(MXZHQD*^D@{b9C(MM1F8t>p%pO%!4Er5erA@6ZsO& zeG3n`h1rX7CzfZDrs2+70#3vRs{yVOk@&8-;8zH6?+_WNhKSbbBhB-MxbnYtiY!_^ zg~S49K|al}33Wvb_&n!y1Ns}*@sOK!86HiJwYfG?O}B-Zcyac;oyV;J7-$y=5|1mE zj7>YR%n|(ZG;4wnekn#}swm$<1RH%o!R>#i|H&n@z~v+WooGzX`QIZ7NYv}#7@0Kx zSk}UZzy5lBbbi|>Mn%Ti=|}y9tXZSDlv-A=>0zgbeKBRviq!I)TM=5TKIue5F$O_w zB4aUIf6pQQQ4vri!jWrbh7;@BU{$;p}TJav^iWB@!S1TW3XZC9}> z`>=Dq3v?x*KZc?+?~%;&yBwFHfBXIDz z@oEr|#<0-9AKUsc#q+~hv3s4jX#0_=bXb0E#I6*9ZiW^Re6H!Yh2pwUX6N^LKWM52 zL4?eos$A;EJv==g=P1o{>IRShlOhAIa3QQG?-H&+Es24d>ac?!dZlfO^`3wNxie{X z=8+5;_E+L4w$wS0HOVvV{8f-Tb%}NQGEs-R^}PL5rF$<6Fu*aA2Mjy~@(lUb-6WKx zeYB)|Fp#97L#r@Nb3r+()^y^EF~QSF=k}lboE~FkmD+L#2bRA&wvWhpOC0=YMrhgQ zyuQpNEBZRjr0YgWEB%|>eph@a`V&LR4>QWZY{Si+ddw;#(2CYQslzUI3Qm`cn{Uq+ z-qLT>>BvtMfE$sn%-3(+=_{SQutY@(V4l{JXg{mj78REiz|}i6i}J;nA|$Qe{j8Wg zISP))XawnUA_4j+*%x0`oY(~|p(Ab!^Z~iIid(}-;NRD+)#l6U5jAQR?*Dk5iqTgX zm<)OD&HrX>djhF#kIs*12F(H34UVg>9Y7Z>(aBO19#!Ba*Yt8+P7^$=?WcdiggFw4 z-iM|V2j(R+#pDtfm;Fmyml^#3%qGPr^?|Ghsp2>-0>@nH-Yf`=Z0zTu9~aJlJG)T6 zEC%|8ygXje4rJEtk zHS=}Idm-xI!g))nN-Hm2R8=!CRwETwaJGZPp;dfjMhniNl@S3lHHc9var~DxmsjOR znZ5k020a5GytoAQ!>V)$#O79_yC3d3iCB6OR1}-Vc_I|0pz>pJv=EYya`Pf$A`1~W zD@WaNM_Y3;#v1w|>LrBApW-*3yM4do85|$&$vlL|+4p}2;(Oe2RC9fFJt==U9=oYu z-t4tZ@`oV9VDnpB#MQFPljrX?=1zWGlNQg0bBb&1Jx<$gpu9(ONm6$xWKZ6B)A?b1 z&C}2ZX>nnF_aJ6tJmC$w&_Zx|xod5$OggxHrsO8hEbYn19qyEY&d+L>H;IV^woMmo zH}*W}TDk;ujyHXMy^?mZ|39>Qp=I{W9Rw-E&inM-+KcutEhnhV@O5Uixb=&@J1vRt7B>Tja(43&GGfbO##fCRmED*pf_7zPhjit-#-8A zD`e~v1i6tVc(6P9+ai*P=OU$JQs6=BDFLoIUkGHu@NlKjMCI66w&_nT!SwE&< zLqOS_qR`HxG_G`U(dY}9ePag{>KGS8Yw$VN_P#9~705+5c}N0z9vew0z9zY_7ThOg zo>-LIZmUU$h#|HmRXsLe4&aW0zk!9;v9Jl**&d_R=EmsV+e580k=NtMKL?09G;4S`CsB&VP1o2 zBVZ?rw86A5t)kv>Zi?CJT_f|oIwY2bwoJv+wA-sIosm>j|3;Vb%drcb?KP<093B=5 z5yk#gfpc*RMKr6>bAmni@`*lvlq5fL>MM5`5vXnt$tI`k)T6a7!oJY#=gK^nm0;RK z1XCP|WlNKWG5%vbAwL0#{Vo*f`;!W`SLAPYs?9p059^XQ1A3Q!xA+#{C-zJMp*xYCe%RMe~aeL(Mdj!DFdHV zne@xHIuCES_dQvM1xpD#?+-dfpAWyD@31vhT69Z{$81ij?Zk_M8XEpz7Qp@<`nGQD z=uAP_jBGRie^f*a_W|c6Lq(qm03Z5qe^Z?K&Fqrl+%d?_3(i4>pt^=abb7WQfoVIDmKVydITi6|8L_{{ zN<}}0e@OVG${evz8<&9JNW(MS!hZC5y)Q)7F)97!x}z2fpJO~c_nryL ztKAG8CddoTCx5Zs-?Ed+O$!3GO%!QI_S za0~9vpaDW~C%C)2ySwwxw|DJRb#9@k;-a6oyH_u{Sana3+v7A{on7q3?seZ@dsqi& ztQgpyo=X!$)5eRL$yEYJtJ<+~`Ae?#WeoFcMD7Zu-9xKkL5z!fiunAb8|M%K1@NcO zA+qmu3jSELz|P2*oWnhuB$7PNaXL6vXM_0@&qsd2be214K#nzDXKYI(JjqgXcAzYq zFyu!9WCkXxjDcPK-CUv~UgOUfjbGU2Vy@Jj*szW7eqa8cZ)7NAjCzC(;_78sV=#jm z0@5#ObYl;3q)U}ss(eyN2pjUwkt8TyE}y@}87Im8cXadha4*7MD4Vz`KqhMpJoLo3 zOq7vFvrT2Lx~H`%7xxLwpq^TMbyUN@oL4?@U#Vhyyf&7rX^qJ0Q{QgSUfA{+ssiSOKpXTqiB1*QXxEd!GesNkmm6 zOX_wWnKWs%88mYc=~$qFsz36Ptzy%mftWOS!;lKbgPou zRH00b*$SS;&(?y1;5^b?I)c5W;_tbBCH@&B?F~&DxH@Wt@1}vO4Ly)J*6`0DEG-(4 zoRMl|gEKvaG%;TisD(Z5BRg3Y;pO2+vO0F(nWbmcp<;_RR8N%?RD-4x zI14cMw{(oM#1GA zsL3gmFn-Ai|1KhkfwK8Tx9%=OR(+ zFO>U>%*&wbbhV)2hTA#APK*@IkyVx$@j8%!xvQLiOChv|%?w=q*L;E*p%q6m0>Z6W zOtW{@Xf$cZ9i4FZwI8T*9xpXw| zw_d$>6%7@!{BuJ+!C37GD>5NzF0|6nAqjHnE;awA7*S+1CB z&yS=Sf>9RE*pFXRBRGh#D0kcGXRT|f<44fEpPiN?8Uv@IL_+}{s`4b^nni#(O@Yc~ z9@Y%nP)X7r__}8A!mwM~;;3dW^_)wQ{7UrLxycCp_uETG` z;5b+}w?m@NIUD6u*$QLPyzJ~qgNlB5Lj3M(ew1tIp9ZM8V9%Kq&@&{L>pS%C7HMFkg2L6om%{RXZ0|^<{#fq1vy*xg*z7)T|Ha)qmvzhmJCvoJq7gdMG^dz`7Mx&EU!F88$4%yM^x;Ro^@YyNW9@EwINc)X#uU8#A(=^*(zL3BZzX3kZ+91!Slv9EWy3 z%{JcZAJy6Lp>1im@ZU8L!qLG)JSwSL&P}x+ZEmzgZ$ry79joIreGq%xXD~WxPRn4a z4r$nj6)ht;uFQgHSHI=O{LeQXt#1UPRL)d^)U@az7YU@8Z9Fdx{vI_{-FdqEL5A+D z*-c)j=UeQ6>DOi_M>29`3ih1iIcm#04qKad2;)mMPOS zbMuPO?GhBmekn)i6}DrKDY7Kd%Ec1`=p|p6Dd+JM%6}3lHi#oMg7K&*0YN~>f-MW4 zK9Rj-&MRu8B6%4c9a-n{y7k2^wq08NCUzbWD)VdR+vpo&lk*-*$H%)*mat!j%tG9x z$iI1(6)Ty@fvJF7O0c1SY|grU`DZNIZI%0x<)Qi3Yf0Z0JDLW# zvl0rNARBR`x-(;~ic2-c3~)LZ3daWNbd|9UIBgRzOWw?=ZV}OR-|4v|>|?g?Bq?M_ zMpH!DKnLJ4B-d&s{PRI1f?R4c7}|SU#0yKyT@ZQdu!H1WTO_r_2I3vBJJy4KH#os0~zW7`cQg6)>?{QmG<`oBo>wt_n7Ny9ABsfcF}P*1w^2d z)+YnoVys`AkNz97*ZYy$?)mM6@YVk8xltYjS3W^pJVL#h4j^DNu4S!l_mkIYU!ku2 zLj5+Zs9chkp^^!6b*J7SBE)K-`ifq}+Pdz|*`!If^bw%%PzlXV_%bi!r6gnUCB`H-sKUf$qa||{KI9ZdA zIu=tI+nl_X{~4U$eVaj-pzyicvVAB)S}`?)_=E3U9t#Q%N6>uIrhO*Sn7sCa&}UH` z*BbujS}IGXWKUW4cYwJ&LZic4fBIJo%dFQnfiXoHuzYf5!C#Uvbh7>}37OS0`;|tA zlCfm(1!2FyqiS!ITGmdxr-!BJipy@x(Mv@rAYqW4(sFO+3E{FV(4rtIl={yi6G(1%Tb>;!g<|HKWxRuAnw+q z?u#|li}qbF@^7wr;B@S|H_WKw;kiP7zCDZ`ivf;_^m&55UF%%9K9QyZ!`jBLWr0GC^1T}0zJ@C)zIaE2lmL~#ydkiB}Dluf9j2qTUQ40yu=T;_1 zqX4AVd#S|@{#(~Me%z*O#*`yAy9M?6&9|NRqBpHMCqYS%GtH5VvTrR&G5HJTY?1NJ z^yyR^!PsxR%%cv$eisl(PuOgJs$Immy}sA2oNsjKwSdtE~inW#8zGpLM9oXvD zv9ozqu0u#hDAbT%B0gfC$oc;PEBXCe>)e@;*+#@fx0J4-*hQk!F6ILw?)idkUqvtS zW*F_Gqnjf`IFhz7Qk^JnK02qyy~)JBbKA$2AUauuk(vWj3%`x_ zGL3v@0Z>sW{Sl!T&q~C~KDeaY3kyiuP*_-*8K_Ep0#vmQ=1#E$@hOOQEi%f{Owl%( zlxI<3wWd(Q4l^4#kc{I`T`sakyHc6Dd1Gv3h~ztn$4@S5kA@#xWbZTNp&+cvf|zPxFmX&B;%wkl zIy;$?^LZ~rd@9kw(GM$<)y3eq72?Z<0OCHwH=AtM(k07^0a$&``>M>4{@!N?303+y zu(p;0*@%s?fe<5ABLRSTyuhm>0A_u80-QlRvdR=l`|Tr^B@U2{s-KQxWS;=@lMYwF4Axz+IX zPgX>?IW&U_Vh$Ex=ZuI!5^gm_IWPz1=Gj)~Vr9`D+a#G{bkx>!x2tiB{%6KjKlnS8 zK91(Z7A#Ka3u#u1)&je&#-W-MJFqPGI^}QEI>GE1xtiugbQn^m5Lu$QZD z@oe@iZM4m!N=CzuDzBIK=K+YY=Gcx*n*H;??|Oj0$#vPTj%p}A?x9YnAjG*he$Wbm zxc*nOgun8-FO_Y}6cllrB^wCeeUwnfam`_mBJcZI16(DRNjCo0zD;(&?k_$-=y-c- z=A>&rGaG)je7|%y>>x9GG2-HUZAgO$-f_}i4JRbtHt#n4BJmIG59<@_snyl!@?*x4 zjJ0V_2MDhzg1H3+3cPnaxV{82w864X*zf;8Tz!^cWW^k^{hnCZqTcn+yV{r5S6&4` zrjFF8Cb-lM3mBBS8rGfHxLR>P>^Ngz>3mnV@e#8pIC?J%%muQq;Xz-J0c>$i3}uZ& zQD%i_=~6(CNu-BEEtoij5~qW4stKMn+(UUFL2- zv6DWa#dJ=*g$&9b=e}F;#JQ3`V=i0X9j)m`T2(vlbX442fPV}~5 zJ6*6@YgX%laRvyp_7;I(X<78o%FBedC{TsqfO-z8Z~l$$a9q(3ERhh8be_ zv_LuN=!}ReL3FfeBIN1M#N4}iez~+QM=?oK1%?1Y5_1jZvS`WiPA~&Aa2awgn)8Aq znG${)EZ~1SliImr9y2%@$GjZLpXjSABxDQ;&fbiH7aDm99c}!Ixn_&7naGyo6PRVF>mWjxMrL;@kBOcUmkv~8$L`hK!kz=*J==-*eYXjpvWgKd`Q*f#?7E|vIOX}y~GYPLH6Fd%BKRF zq*phHACq)Dm>nu9#j@sfm^LdU#WGR->Utd&GL%INpD>`=(pQ#D`T85${@=;;imk!9 zfn2b&0YdVLGyJR(`F8$I_)2aZJwae-u%rx%m}8a9v*=$RsC6=Y1(-x|dr6iA|kE;Mw5LFsnxuN@K&@_XCi8e9- zcmyuJmoCb$EGAsxr_aCD?5ciOL>hAgSeC_2&i|qf4%7~LHXC&E8ve4}EN%tVVp#V% z1_ywl!3ASBR$=w2I(|CTnB~d*)KdmroP=khV5ywn^dekY{}Nlfe#q}My^_vxPl$AV z=H7AgjG~k4xh|eDBPih~K%K!UCe0^U9_a^ZDlq`&CUS4L>8DW(OCzU0`)M;Rmo7Kd zIA<_AGek4b8#fdY>3W3Km^mQD=zSR*TwM^82k? zqU^ods9LYf9IqGf$B1=#YWP0$$a(o24Sdm?WT0vqoSJU(M5SHmFg2SF&|v1x>4%MQ zk%;r>L-eT$#S(Ub?A;>=h|Fl{$;}B5-yv>ioW{=84DNT|pLV~m&jLI^@xLjzZes27%^xB04FzIMt(JU$r)O`q_&e10rhEGBY^gX4A4 zNznm_2F~0)<9LczwiR5xys~WM@L!;0_lXO{^;e9$u%8aXaJ5)h{(n-Q2vrQdmz>h?wDt$x|v{9?T(fg zfwvQh4NKI(4vs~XiKF8$U=!kh84lDBBK+Le+&^PD6Mb(FzmOD)_y<$^NlC#=!7)fn zl-!r+?C(XnsSD+nR+Nv&syDZluQY_#YM4DzK>;Eh_oC4OGdD#kqF8Lu0LD-yv$Bau zDu)jlk@p!N6Ove*{A-PZY$}IJ#k;h)$4k$k9cC$~lHZadLDzq+Pb=95Cj1k+mHkts z@mX-(>out?MO9l(@;1 zI$k&5g>wqY>UoV12^rUl_oQP@$o>2%g7`)H2LD2vs!}qZP859kOueCn_qEJfl7V$$ zicm(zBbc`D1esAy&Rd{4y`>zaMxGZACpCy9uJN~Zn2FRIRegB3)PjM@&*79c<%0Sd zd-JQ5S-IivG>+RS0iSls(SAbJ^ zXiiJh5-mglpuO6fNm-(rlm#?i^%0D#IkHlarnW4%mGW~#RU#`eh6y(Jc~CcEtAvnz zUsSXul-L@Schnuz;zYr|v3}rfg)8$uYao#0hQYe5m_)Dii=e zp4&+aCTX4`gVd6nnJg$mo9G$9KGGv_=@D*nVv_Oxj*Cy-Ko`D2IR5y zTCX5^gs#RBSUAiz465`neMvQAgOU?XsPaLxP({MVp2ZXoco{*%y)wW2BN9Eeq^-cB zn(iLllGYR?us9bk)JlBG;ReVSI5^OJfGW2x%WBM8)(V~lZy$svw{qJh39bqQ^Q#)9 zj(rN7_!WehyhP>L$Vf@gR!xyX+qCif{eY^Z!qSLdr9qp#HEandb>yrBwGomFTV%J< z1H=yn9hV`7xW+2izJrR-GqIXJg~ye=wf;3|(4yPI8ChAqyS+GWwEF#fBdHLxldu>I-=&zKc5CuwW5=nBS*J=QAX) zOMC~JtHN9sV+UpG`*UmYbOmpQPuZB7>bbc6g%R%lwl8+Gj60(Sj6YB0)MVS9gW!`~ zHI|S;R4_YP^waS4M+p*4V=N-jU^HmJ_*3gl)9VyPmBINywk`%cr=--fokKzWo}$7S z;7fCwq>MzMsB<_|IQ|c8!syYy(pBHkl=a@NJt#pL;)*}j^+Z#$Fxa*7(o@!5qgKv` zpezL&ReD|kSaZE|hL=Jfxy=PC7FikrhyN6jS5!Dv_GT@^Wgh@=JkjgdX z7ZGzH_e&Dp?Y2$nM^Z!MBZx;D5L{>6=HCo`4>Wt@F zl&;t#LqqT(DSct8yyB!l1kkbMS6nW0cv?uDq9Ye3#9L(3b}>2Zx=ty^z0Dkc) z0v}4&f$Wt_|LXTzkQPNT_K@DHChEf34a3M7n0YEq68>#|mn!M#?E4!oJ8-C{&8XbovTK zlfQamhGEndJQxv+b2!lk294h)LnCH8SyG+F*>wuB5q;xs`Ru=TC*EB`Ui!?Gm3}=c znA@37y^AyKRCSyX!R;OCyL&uDB?mg1YS-3#_JlL^Rk8_L7|iG74H@4jFR0j)Nz+y^ z;>Q{YB8AQpBrLGZz{mc|hZfuCl=zKY#+-pWvs!|!xf309vB+z{uT^~o?ffW6I$^>z}dWAikl0Adqy01XJ$yYgfj zAXo@Sb1NMiHTxpE--rm8T;)gBKbC2XHX(WCXdJOaF9+U}JH03{sPfC^buYpjPzw1| zODB3x!mvZvh&7N5x%|+Y9RXNRF|0qiF!pR~&W`mGiw+S+DTx>Jz)}RL<&#c4bX8e! z*V&}$e?8lGRuqkB*+pB^oP2+pZ%%sQQ3&eh-OJi~og|oiWz_b12|ap+sja>75|Uc3 z67Fmt zb|7i)$PfvWkjsnfsqEdTLv)$J(NDkH+D44KoC=XSBu8;_(TW2nHSsk)Ro(BLegWBz zM6I=s)L1CktS@U_m^`Px~$ev-fMAbWaQ4VweQ?tYARhSuBLa-c*YdArVj=m?%q zD#~NKDkCecw=W9+YD$J&jqgH2u&DZXQGo>`y@>B4yMfmeZm^xqpz)OSd4+i)o#eCX zti>_n8?l4)w>7)H8%$lHKV!y^`cO$U*Y^SM7jKUfoy1^tV)Dv1FNOv=RJ~iwjF4Q~ z64_uXRZ8d0veq7)w`=djM;;5jt9xBkUa#Mu=wci5vm%?vOie!0gl7ntqLnpEmhJ`A zrrrLzJ=WP&nG*AxHZzF=lH&(RvU~@jC0Hq;<;Tfa#PlWp;_bIh9+ zVfA&!)O;b!uX>g#t$f0)Xp>@fV*LR-dAAB^4`-M2W;t z(aaAva&z0EBGSd)4Yy{`idP()wUUYju$8EVp0WSoI=SGo13)YIEVX=pzD`It&l)h- zrof+!+!H&>Z5kMz7d(;`Fwndo`pLWOxg8Nt$z(11*HbY3h=Gj^r1G#PfXsM6KCq{Y zO=4K*lCDr#)`n-trO5lY8ofHJqJPR{@9?}>^_qJ=dsTK@mP3?)sj5D-r3LjQ*a{WZ zaEi7j7n8)bKOcc)MGYn?tAp{aLkq?7aVq_x9V>75vq{uPIoraCtq!q00qDEf{!>pJ z(F7cQS@%ixy?5qAC7214>i%mTos$@^QRS4d=j_cI)wC!5CMlojm8_DM*Mvq z!<5eX;mq~bqf>7qrG{nYcYw{9wZrzmMl6sj!ZIMDVL5u2M`T%hO4pLE!bZU~az;8K zQ|RbIj;`!0AO-Ba#4H`^Oi=i7*zKqHcu2Nih%4)v$pCSmeU3ypEi_2v*|^>YFVGkC zD;7zrICIu!e>HE&4wYpdlfYh)793l1Z%?z_QDl3QL%o4ZvV@4W_1T}l@q?X4loU>tEO0MCy49wRv z2B9y0JX=yzRgLG#yYwfGAK2RyzQzs~qz)8CYU#Lf#dB9+uN-Bms?AZkKb1{h%S z?);Px7|*gVQ6fJk9*+B@#uH=nwafO$O}n{rw(+g0W)<#- z>2OS6sh)1bxhdb%afUDFID9uRNt6;maF%B`zJqd0bT^iebZC1%hLZ&keJfGUG8KPD3DJSNI^4pqL2%@M~!` zm8T~46>H>(BCD}*N^z4Glv$C!jS+H;SY!{T0?_I0m#kiR@OJ}4!oLQLCWZ8w)q)Dy z5^}d>6k!wpq+Q(({`?Tu5@V%=nZ}a%ois=QO~o}|r>W>N!>f#qCwI=-us}*QygO6v z9G7n)ylzfh$XZ6QpcEGn0cEzh#YwfGE2tA%V=O}UU~#!b_v7)lRtyc(v_(W7u$4|x z%h;3OZ{6lv7fWG=%SSjuPb4q@s}4$2qjS|M=as1HFIR{2UoEfcqgG+B6YdnCx8;`K!YWLZCB`@> zE-T`#N&0uH0Q2@1wfiSx`>KZ|uFTZk6Cq9p5R4^iX9v%(b6itV5rVgB?RZ**f#}`r zRT#XAVvprQ1_LB>rdiC+9Cn1{F6bq5obdCkb5_@((X*(&vM8Vf?D+*~uICj*<$%pR z$n@!?DKo-9D9iFgS<&vCD_RDZKm!G-$Z(CwjxJ5{Xq)}~7DwP4*>4B8f+%VaiCsn2 z9WB8XnpK~EA)_n0`Y(y0!&zf2 z3+xY4i0{ad@lZFYM|7-aJld)MSXmP-^?OE_LS&#!w4RQ<9wM2U(_RIq7}yDIz4_r?U*JL#*fkZ~6^t^I2UKH%0jB2lFK_C_NI`K5y}h&F#;&CQ~)8Y=4LPI>WcxE}%4$rf%zB z0kiPJ$o_?VfM(^J#OL3wIo?Sv)`OMmF+E}Bj*mYv+Ua@|dIP)*u}7J%jHR4LF+syL zr1q-y5>!rPFh61!6qSILCgU~DZfE2k0t-s@RZQmxtuF|~4m_y<(ILg`$^bpBlR2EP z@7Fgb*pQ?RB6EF>l#sB77we-(DU~km6Yd5O&cqWwI{jWn>v!7@`e30jXJFtokz_q& zZ0Z}bZCi45reuHy_Tel)|Id>CuqCZybWkV2dGqqpov*I&`&C}k={EAF+Q**>!+UD> zYPHsC!17`T-v)z^>DNXyy%RU_Zt5Au14tF=lVp$fsFK;`qY9j%es*5^i*}?fv|nL) zL>I0z6v)_CISwE3e*PCz9`4J-{PzP^XB<~75|t-fFpi~sXM$fOHmE>~j$wkE1ggA( zai9f7;rer0#7~B6T6940*Xa^d$#wpfp?n%rAY4*Y{3=dZ0;5!Qbpd)_?{~0i2n4u7 zxhMvjlUCSq&!cg%x-pB&XQ{#@q6A_==SxK%#Y9JM-=D2CU2cVO;`$Fk0TR^`r46U2 zsAZ4^+hTb({81rE7J0b8xdLf4m-azLE(=2jAGF=RjlS60l{^?<7nX9m%>xHE1oL{A z3DoE2BR>K1AS6Gve=1{&U0*vf7d}HKu^%7TBQ*XuKEWl}UuVz0C}s=BEUIk$B!Esv z4rWk+Q9gCuul!tE;{4=+MBgrs4z4ZXN6S-ZMF-SGOr~=?=VdDTI?*i)n|-Tjso&OA zd`*(oja5`lsy;L>4r;fTZpKPyLX&Gu!dNfDsF9-J$OSij%fLfbYx3|RnyOg|SBNtn z^&ybx=y~$L+nifxUw^(LiOpp!y!(qcU4)e?EWdTbRwhx(7BYe{ou-|ENIxG5<@PPa zS_S`i-X71gr^yuTY|l?gv}8C_{#TXTI&LEi8QApP0xg}aLRsx#5}`a#(!Rm(Zd!w? zh}slCjzI{DF)o&tITDHzxG~U^qN2+1vE=tA2auE>^!UOE1EK}E9qaYX=4vx}yl0%2 z1=!*##ynyC)DrZ$tv0|hC7RSvz;v_Fm@wJ$wFTS0kz zGiu`4@ky1G4DIvpT!Mb)J6SW8kbMpqAn6@1@Xz}g`ExV|)}N#YtkIurLoGH!`)MP; zTv)|Spx}i3pk*Y-ncb>d(!KHV_)CtJ-&ly4loel+qRhu{T0YsS`WV0@F-tWlTfWS< zk5{-wZlHy!elbgOpuE_Q0^b}cL9cXj>p28*w`bq5p@II|q-zgnC!VqU|M!5XC;pqg z=xVRrDW7Pe!P|d<2OH?{kl!>)JUG;V@JOLPu9tTVmyTmnULe&S;F}o0XhKmu-bzFaRc#!=u!)T7k(}NE~PdG)+ zV7;G}hhKh(kVF%FTiprV_6UgFdY|N!E-o(1Eg=*rO%qU}FrpQkQl=zG@W58>Vzx#y zdcEwWG7us+!1F3h!$oYLasE2ki2za^o_jW~=cQYSd5auRndep}zD_V_0xVx^Opdxj znH)qmKf~p@-sqr_`&0ByyFk33da3#Z4}>byiXS`~I^;eQ6TiIn8HSdrRYsG9D(-Gq z^zH<4LX1RK1`g3y%#9fYQk!L#$>WMuy5fJn&#oAf? zTYe?O$Q_+A&W5t;(nBwel#`X4bFippWF;mJHVShdb6wzYB#OGm+zb&3%e7n4)G`@` zrV%L-vCZVvu^90kGrWX>cSD8-sBxM-Q^oxZyGc@q_k?}{82qyvt5$NO4X)EqSUY{R zWJoQJhv2yEAvrgN+Y|2jms(<1*7+EFqV4z;JboN4Jxpp|{14!2vwp~Xn9D9CT62%-m4{J1`G zRio5@g};H2SGV3`AL9DovTgA9f4c?*o@Fc^z2}1v6<12w7FMwSr`-J=puhzWF72I} z9-jDHNv38T(~-o*W&@w{mK2#w{*q7Czr=LN~e^%^~eXKuq#_$bvXl* z=xXeEqrU08y&kHkoNi0_!r3`wY(+LdVyn|gl_$AOhz?*xOr_6hD%s!PkAXR7>v)8@ zXn(1y*{7|danigyJ^eR+p8a^F9AMpsn1r zdSwmrum+sX*rUjEqc`hsAfD9AB&0x?Bor6*ffJ~tw8*7O2s+GEU3D=kwbT7+cpC3V8R`yC-vZV^)^2!=3{S< z=6xY|!130SP%KLtZiMl3RN_ti_qtT!^sa+krOn|tem#=%nF83NaAuWgcV!pq;gNFo z=0V>=?O80}veDu{xq){%q-MN+f}(FG!V+6PyNs;?BB28h=Ip$KUV|+Ppal&MQgeJM zkXW|VoY`FI=CZmKQ&yv7g$8Q_`P+a$Ec^8 z@uy>5AGo_{Loiq68J1KI5dbFwHw?Ymr%dtzqbaC{mo65WFgsOafmFMub@Qd$|85oF zJ5~F;|6YPy3l15#dsk(O!osQewE_w7zS+EI4uz?&-4VqW52Pv;Mb69Cb`6H%k%Atx z5;#D;@u_g3Z+^hGFK=2PE_TXg)V^x|tDT-KN?~VSIfDSo{07D%%@!n?LPKmC@_HQ0 zF(4+siO9}`jYyH}9c`Y7>hr?rcIlcl`Z@d^f6(h!f2t;IlSo3baH3QPROpln#9+?_ zr9F(_>Cp(^`yR2zg{{w@$m%JQ3Xj9VPVz`F)&RqNd|UjLaY8X3V(UC*B>THad`F>v z&bsmhC_xHTH+n0OTpum*vrEz9d+D%#7FBs-%n)@Qi&IlwA{qGprFSs>wzQMn}~l_;y-bBqTkr zQh6MB#a~e+Ed|K+$%>Cr3qp@40f}M`4!`uGG7#&F8 zZCOLLk1Ma8*Q(Jq@-iZinHcy9Xx2(Bs0eiRx~s}jT<24F2LF-#JLSyKEzMgo48rMa z+b>RGmoQuJ@e<+7>FQNa*mnHQ|FWQ**ZP+^()!rV#?n>{!m@8E%eACy|J^IMp)2uY z;83f)(v0+QWbkb#UJTl+fl0=QE;XLlAaGUgHfsl=sitm}jRFretz(O48Z1Xv6%oA8 zIsO+e>2LV;cNl*M_#4K7?kw_~TeZY53Ng}`oBrsU4k`K7xhRt*_+^?ACk{qrpLSdL zn>s&*d9Or|xA?sHkx6=h7~>UtT$qs4oOJ==aO?(? ziMlcj^DP?PqI}a(QBQuJh7%mB-ai#~thWI-9VkN!ctBnomYui20X%&STAX!+I6V&4 zfmw`-14vurNiv1+xP6AqN$uM@XY@C6pmI`eG8F{zeV!BieVe80&$+})ysT7jg~R56 zpP&c}bO$Z58z=KuGQTsb2W*>&890f@r~YX8lT_ivw``K2NZXqJ&8xVfyn~w_ z#j0}93(XQ0a&%!s0b!M!9p^b~r~0~~b@a-I$Y7t)FY7oA9L)COu&64kj-E03J|C4d zd7aSSDG2Qr^C?vok)5uzVmP$F;jMe0DB6D~j!uQKr;hA?UD%V%Jvhqoc(0gUi&l$Y z!Acuo!vk%k#tuY4~05&plW3 z+FdoDJFP)r$nTw(8L5(2e{D~kt(5Sd2jcdp7I+jz8Gxk5R;#4LRQ;*GL2_HJI7jMe zil4G^04H6!od&U;&*`}~A-RDuO;2q&7sIL#m@B5?IX$hNiaR_P#aEVTP@i#CC#K7H zvFMCo-QY;U^maB;sl(+KP9~ms$@TOr7U#0nh~_)v=Y4k z&|2v`VR=-;de}pm+O9|d{Q@>tQnoRxn#3)E#f*JJVC;^`o{&hU7shy=?MY7;psl?Gg>qjd_GznCcB221%jc~c(aZBPI9125AKo(AHY#)( zA2Z(4V@PRt8S7^*aXp`VD~=x>($>iSXR+VbY^sW54_RXV>w_poOV@}E4r?cEMBv95 zNBU$a@Wnpp&znup-TZWMqlq}BpUp$!+dM13nhIE_Skw~YZWom7=Io z%;h7_+tX7w#etdk6EO5kPSZr>b#YEvBK7XL{%w!pHii2UoU z7>7Wj)J7%2ooBD*ku?GjnNpB<&5)aVR0aq)<5=91+H=;2H&#N%1Y(jSf#~PO1;0mc zZ+x#|{$j1#z9>OFoKb z(fEm`vcK9JAL|VNd^4M!O<2-K@25UwI_=4@(cyQ(JvL@Iz;&#ck(R|iQPk4noyG5k zMRycOB4pi^IQ+E7B3Tu6fsFXiN61k=>R}i5Mc|^aqX<5uHlVHRNv2&J0dy^OS-8WO6#xj+ z9IxLod%gxnnD9}{ZOe>M$tv3)uhsi(r)e+7EJXf0R64}jiPh$F^y;Ij+1-rbb6tCY z%j*?@qeWJCR!#i2J3Neq*5c)YkgK0ll<>}LzjkBn`3;JJ<@c9`qel`clLO1U8dL#( zkIfPX_05fU?O!O(Z_+aH`?`_*@f<^FuW*O2yVkGQQOq4}S$!;#<7+Kn!-BM(+2VHw z<-KaDD{(FDkiPq}M#ewU_bm>Wj<%rr5bghIm5DrOa(tduf?2K0(@GWd3eTH;48DSW zfFWp;8811ap~e4>B(tL)oK10vGoYH46*3!wds(k)3vnLLrx+fAJ+z-N^6)@e6BwDS zFGOdt6aHzvZ^aN>;F9kgIqLN8%u+ZHsM6-3*o1nb`ZH*?F2dPR*TI1+XBh}YRDj%L zeyRk-#fuCSg%ber2X{7HZQ5&-5gF(V~Dlk*>}7d7ewf5<|GzN?j)g% zygswR$oCKtI&wUe#r3`iiKx3EaNV7%%>UC~K=SnpFGwFv7dZiogp}tVR~pVO^35lk zHIf{}xkDv*H@8MxTcu9j*1Wc}*_`3Lu|;hFKnfda?IJS;X5~WtSo`v~SgO zCRSOwfHIS+Bg?%RdGOi@O<&f+)W45#{Gl(e1DS3QF$E@Vwc51k*U@40bxA?by05PX z0cUC7{fYAGYWV(0$H-4@aKdw=(&NS@JG2;pUvn_vPa%Ap;}OW+WTGTxf==^h{9;%~ zUiIoPjVQ!hZB`o=webpI=k;S#Zv=C8D4t19G;zUEnjNt=f0CGV#&Je`WF`F9zwP}> zG{uz?r?X?hD!tr+L2;a&Rc1{!N;?nz&#eMXR)1T_!q7DeeKa$^t*Vy(F5(5k^JUS; zid$jTdW|!v+0Vn)3GOC#(5A3l*b1fS=C!E8%5{t@{Xq30?Q>or%n#o96x9}iZoRHX z+Nk*ZPk%~y3vFHzK22h7Vm`#ifL~$?e@^lJ2ZnIo$1i@pbK}78_ApV)I?D{P&PXDU zTLPYYbEztt8&J>+!sNPRpAIAW@j5jW)Bev3z~f%+NNWcsgqQ&p&* zDp#6Rc^|cXW(iY;26+ocZ`EMJpscA6uPJ`>CBHK;W5-u442UJ6fCDgxO$*2bY8qZ| z-f0S468T9b#{~w7YFPZXY0JDS%8lXG9g10n1a~~}o7fo1#w)iH<j;di6%R+LYV%=J;8D$+?bW1CMboMY!-U z5r%XzG;pVYi#@WcMP?W3cUR30qSK=zwiuY8rFF-bP9YJNF(f1cI65-{VwvHD?wWFf z2`aQgiybxgyoK&B>2F4#clkW4hVczhURqmL9^Iv~#0-&qI38}=pRTI?=)Wg){?3|T zS%X{|6Elm^=RISCM%XT%@+;*}QA!sH3nfDF7iO0xL=Z-j;TGPuKj^PkMrKke_=O|XLEecKU5D$@vE1Out6d2K~iZ>Noa}EuG+jrN^zl={s0SbKY1gUV3WHLHS=s!df5}>K78= zt~5(T8;e>S96ig-_rCc5=xYY-IR6oL=Agiaui}Bz6HhP`VdvI?34X!Lj#8g)IsWvA z6u9=4^trKg81NgC{|6X8AJ*xsE$| z=oDrJxU9(yCYk#|f@720_YceF!c%v_CqIU3z8W|K_K;}IzVKz_lO=LiZ76`CnR%Qz z>s?(u(UI*#UxPSK?QeGm?a93{lCUYtdOBb=EG>ug@&P^dbN`R2a}18`{knFniS1;< zj+2RP8N<9r&XD6ck8a( zrbLLJ(qN$=)Y`hcGAtTKsSXUxZbpYy&nW`7zhATCpD#LzFXmvfHe}1YIaqQd|B2;^ zu#JoVQeRz~cF|$~Ebb4`{G|+1(sX_LdVJ^L7ICV3NqSp2#Rmcaeg|Ngr)QwD^nSHC zRlKIauUCu?YNW01O7Md*vvmt~|Bgd*$Y~`dAi);jDft+r={4DMOvvh_<+Ku3T#HLq z=%DlBj(Cms(z==3@BBAGrsZ5omboN)>{JrxodwM|cq?a`ct{(r zuz-B#(6G01SW8STd>XV&#wRlSkGjJFiKH__ z!tG49q4JE!wF+ejA{nc$Lv0x;IWPg>GTYSwzmIeO+mLyI0m@5%@vXmreDj;9yMwS` zpws=MlNIK6++Fcu} zG%+h_2;j&ixzZ??07kUa4~JOYZu*2*9uK;;zw;rg%kq2+Z{*cKj3?zYvwkz1%K^^^ z-K?FXv2O%ezk2(_7FO^4H|P${$zc0ITQi5Rk8>{HJt&@bo|(Bd!!bt=$0~%%W9IFm zM~cll3;I*ME@q)oaeAZ6m}AqfTeC=lXQpns{d=Z@mzzCuZ^uTGMvw^-+jCwgcX$d_ zq|4;cjmI|M(Gh&~3@sTPRMsU$>c|%ER1)uL%sr7e9&)^_v{3|sZ>)Yy>D?G@Bwq?a zPtP=qN%rZHxBj|^QT1V|+O9JzER_{@DpTKRpit_p0dQI=?bi?~ECef?V6qmW`Wy_! zc^p*KRVniuX@sHxQ65%@mpj`THO?#}1wRAaoC;pqvW@F06?Tg4e)3j7m)jnko>yhY z(she(gHy~-n@JCX<7v36v{Z=9s0vfk11l2pu){y)VA4xM-%r@c1tj#E!ahqSySb@0 ztp@hR??aJ89#&j@BI8M)Wi(8pio>?Fr?x|x$NXGQ*lIPG?j*f*g5Tutb1*Z}H8H8x zX2KIERYsp5UdV>*z@}Yqb3hV+h zvC37;;J)tVRCyGI@G4_^7c%}TEaEL>s>-?QSBZ25{$4ewDl9^U=Xa+4qhZ(e5Hd}C zZtUt&PWt-iD@zuY=fy9N%6U+L$~c8}%H(XjtCV!D4?b|P+G z6XX1xYQ(lbCUWGylk;yZWVm@(#%(~E@*C(O-wPMoAXK6&M_7lxNfxCV*#lzRn-eiv zc8^{?VOVD=qlXI1ZW(6=p2$4cGHS#2XsKftcZz>~9LU|}XX)>cm$h&VBZ+fV!w!_E za$rv#^NAWbPtZI*knI*N)`==2I1NdU}fv(u)7DX^KnuD-VWt{ zNx|8lAJq9@q^zFcKYUPD;E22q-eggfPr%gDB=`H>dcu$2CS7IznzeOBPlyPtQ( zT;W@x(9Ul3J4gmE7G4PWZL z#c}SosJ6t+*M{We&98Av<56=ul73z_>~eh18)$>aoH}%=@)(gPPut&GM7+`)-?^7P zn0W6%A!jvV`)~!bIQyPBt~BaQ@q|?{TYVFhRC;qXUh43qgQU<+C}i~QI|X*R791qU zYrWi0(G9-7YHTu{C^%QYw^Ksj*KuW?4h}`=%{B$w%s zYs7&++1XHqd?f8UVY0l^$x0jCm)7uv0Jz0*+@x^#iqwHpj3H$=8GFvM4VK*5Lnq0? z(K>j6)I8s&=jcO?R+hzz(v znAdR_!DGrg@*DcZB_!0an=ewx%hi)An$Lt+g2=mD?nt3494_|U^H)|Q2Gg;GQ`z^s z7jy!Fc`Oj?EWu+^ymfY<|5HBHH$XXkW!zL-S!+-93zMelW7LxLeS*K?gr%xM=W*H! zTv+0m=A^}C3TT~Ip=_2pc!O^y@(S4I&5<#v}&iuoN|gA?y*Pm~ae54P3c62r)=3aUqR z@K0M4@>}y7fc9yVQ9Y=(c`qSd*S5I1ege{+(rnfI_yu*^w5`P};*oEBZ578eOMJ4w zi-?Eg8jP;LEH73LMIkwdhy^*NXv45HT8Gjr!^tM2zFQeBnJq>shj0z9zh!dVOu)OC zyk_ug!hoFUfCKrM%!Go-VRN(~^7x>;d^<8rK6WaOCjRi~o8Bt&=GB3L$X5PsS)-Jp ztphF3e@>j#m=5nB_tOr~SGo_I=b}U=GL}~7_R*2e(_PLf8#-aNZr6GZO-(8j!Tvbn zSvmH9jxB8~Ul!+VQ@MEIa6y$)+9Y!6OrJPPb~JGdLT0&&ad&fjv;SJKOEO!-tER$< zsZC4d#PZ%S`sh@UB9AQv76?!c-aM=~ugo3HtiB=*Q{nV{Qi=FPru|!rer=xC7RD7z z`)3UGPu>av8kR$WhS@j=%ZFxHVs)u}*$kEIu+L;|Ye;%kOR`n)fNEtSW;vSfPyG6) zL@MG*w=HoA{x`xZRR69gG;V_GnB59q$TTwMeI#e6OAEGD<2uk~nsGjI{rF{fH5KkA zs}NTUNg)efNlm?=7CE~Uihsd7aR5waZ{rsIOF>22HEXQRZc9O_fi6@w703R)7Ye3i zGy~(TfL;uTp#xf37J3bxDMpMuye`s$wrorKQ^pKg!r{&we^^oV;+z5r1}Hg_EjkVX zjrq=T@3We#11xa43HP0A+_JZO(z|7A-L zwN?(~H}|&s8BD4k+%}t7R;`#{UL06ZCC{cM2sg;E{PQOyb_~5oT2+m~%z5sXXI=sa^1+wS6SKcCjAi5Ee&Rx7+`1?~cxzMdEcs5^!UNk(!K_sw;TOo|(cj&6T>}<8$MGO~uYM`_ z_(_ea+%KAw-E~P$@<4uHVqYYd^cQik^AzWEg^PL@Nc7$F+LGHZ~J zuSXNT_LJ7G<@4X?t;Re0!E+f4yI=DlP!IPPNrf;KXysIBr0I;2x^OU1 zRD1Mv<#oNcHy9;BXy!uN?l6FL12 zr|C5SCYbO)fcWUC+9QJ9WXA$4bgKI3J1dj2XTzW3gK?9fu8F7U5y=B7&)6vul(Zs!LNy-HeZ8+tI_`() z7AVz4Zxsd4KwiITjo@?*>N8f^=rjBGD#LM#JfXoQ#>`wNy~))dEgyqq0-qO*jN5qP z6Z4`x*G07>j?Takis0eQ0P#BhNesR)&Pa?&r;|;re%|Yb{Y$qsrJn>xUJ$*20=B&# z^k%Bpl$~+3%lr`8QzrCfU@JByHHM4fX2 zKHVDzB$ohea}dX|5=_2tC7{=r5ayqXlDv4JLaXYNX5tI?M*-Z`wMXpF@5H3@Tm__& z{$LpyU)s<=&Cuk~0C?tUvw_0NmcF*}A3yb^!{$uOTEwqLQLyI!V<@AX*XAqAyMXoi zu~FNVnAB$TD>a~q0cVe;?f-;a(3e8>yOyKQlO682(k&Lql=p;wj%0t;w>aS9QwJ4V;sSoOA2f#m%mbds^~FWeyaFoHGG@ z6_La-onbh#7!|b3&i6Gq)0t=HK(C;B+|o34qTZY~B`{tsg4xAcslj#ljGWjcj55SZ z8?3UwyG=19kHvxmt72skYY3{w?#ex1bR!$4JMUs<(0O-ysx^Nvf~!F z9si?}9e>b#HKw=k$!}Y#bLT)vXYpp3E5O1jwYg+wabbGU!2n&|!r*YxmGJfZt_9ME z_HO~_lkk0fK51f|ZU}e(X#+Iu0 ziYi80hv2xim5;4eyGu;|7S4-Me=7v8V(WI)gLXDXbp ztRREGWBi>IXMQ!R+Nm&c$*pYP;vDB^}MLllWkPW8Yhf_<41t=hXYf3%D+{5o4 zvm?9gWvj<;+zn~Cuvc4!;hURqgR-z5d@;O147h1lRCmguT4TUP<%h})P>$}DDAdK= zD(;i|gprw3mM2i_gr=!oFi`iQ_s7$Z@u&E2^JdOtwbO8n0oY599)l~yS|Q|?p|=(& z#Bs{g8-$N~;w7~$@qIHQ6~%=MC8Xxml+@1}=Ac_SDJiOio!4s$ zVik-3Jjvt=Y*`r|(Z!1KEdR$C_5Rra@yrz^`KifAII%~({87$4eMT|fhb{m^k4U{zt&~~g)V$v+%*P(Shb@6 zpH=I)k6(w%1Cl72W)2x;>N{{}ayNg=MB+@6JSFbr;*UgZ2qAc9OwP-GKv5w zAD+BV&n*6#JCBaXvS;Rr=B77Pe6rYacYYXYjdM$>g}j$~MzG-FnDjN5N~6<~F5(wV zP->kayFFmv$?vyZXGYJHw`#{1h0g(UvUGV399MwGe z>j7N?1Wi;bGQl8=x_*dtf< zp6nPSP!v)e1+{aQPPha(8wP?>8Js=CPF5VcQY5<4+w?zQ{C^*QiUy46M@}9QU@A!H ztF~Gp*35X^{&QGU%M~x9tw}Gv1f_&Rr^duedn!Mbh{oRF!d-8E)0{5x94*-A_%Ms1 zdPk=`P*ImMv$gm?3;yXF)K;63xfNkbXwAmbYgoSfj2mB_;d>-Zz^Wgu4?nu&LcX%< z3D}az^5Tz7oo33fo6{uM#6RW@ps3P^K}5?{t;zx+@Y(5#u~B-F)@stBdQH4iU;q)8 zx^}4j>#e9=y=^G*P-^$ibeXP97Ixm4+EefW4fx#Bj7BE%odvKe44?I`R^gz~sfSk>E?}J@ zc@gWhjnl!$Ne9=IORMus7EPWnuzuGws{Zsc%P*e?C>OG2-df^q6e-}{qFU! zZCxE~58jqikkg+#3x&{W5Y2`*w9?zXQ`qf(GxGk)C;}mAJn5$qI%VP^8>^36b_ccf z_#2;}kaUc%p?kW_%`j^4Uagp#N`qADcP`U`tr7VBQJ4t+cb4|FUV3gl-_P8V8>a3o ziL|jlkUBwit(Jk(m%&_rN3;>|XX&Is=Zyutn54@Alq?!AdaBm5t3)QG2L_aaBv%={ zgN~JLm}*PM)5`Jg2wrW40$-!YGC#fv+kU@Y|K{t6M1_`L4YHTe#p5mlIAWop0;Th^ z3d|3;C>NHK^Si!_Sw&f7`LRyAFa(E6L|&(S+o&fL<})SmA)eCobZ{E;f+|35xRd>- z=}*>=iIbBtn#f8c&Qf2qs}xDEW@wNP5eEy(5ZPre(VP~e6^oC+UN@%qk23O7W#s|n zv=?TBqCDZy-RI>t4;Nk3vgG$+AX+VHSr43nixY%pFp+e0%gBZIu{{Lq6becKW^*0~ zCz|Ltn1_}f#%DAT5=Op(df*dss_Z>t$e(dEFp^5ALz|cqR5&;8rU6+x;A(eKLcA6; zTj~+yVPp13z+C^9)D1OaEww!!rr(l&7ch^(&a}|cKe-&3A{YaA;0$XO98Fi~QAjYF zS93vw6jPdJ=37Q$~Gj zNp}9f>tgYRP`!b}4+0R;2HGlizqfbyPy1bg$>7%v9pe1BZ(u`_KOVKXr(-l@J$5BG z=$|}LZVO|2r$jEkUSzIunjy+~?OX(-Y#%!CQe-;1Q*`MIrie4Zxa+UeYdDB*3A$_0 zn|;u9ggt0+a1?WKZjEMoPaaV!m39tDNu*+J0E$%=O_LP0(=pV1tz_dn=(P>F}L5DHowp1AE<>O=(JYHbCxL+ z8}F_Dnc9WXpo+Dba-49)kca8G=>VsUVdvets2_;b0Y%%`_qY58+WEbdqBvZ>vGaL9 z#J`m#uGD+Q)$TkUWgf_R?(^w;mjy*;NiVHs5jE?-Bi4M{(5QRc?l*gx!-Dr8!vI>% z&EHKJge(k*F+l{>kPC!N_hrAGfDQ~0`I2#X_fr5u2JPcKY`%q844iwJzo0^S5~tchG2Wt$c+O>S9)4$aSf9Bm@E(+Db=yDw%(dG)~aTeyy!fyyt~I} zC2CaTiqZxg*->4Jlc_5(mqzmx{=m&1+4D4gC!4j5#>ftD?o;Y5YV1+s;JNmf)s5HdM5~Slu?BIAuapEUOXC~-A z9JSStwBnVA#}1`fx8NbRC11!XU0~&F7w-Wyh{)3fVjl%!{;K@@myIw%0wS6%QN;07 zOXgnE6G$~Iblv-y39=|NK@2)5(t>+Oi$e3AR>Da__tIW1!G`=XzP7JGd%o4lDybk5 zZxxfWix0*GTL!|p0NEut<8ZhfbLh=&0&l%#jFC6+NG426acx;X|rhj9K6Fh6r1na@pHTP z$9h@p8v=7PFNzKg5es#D0g?)d%1s26 zHfzCuwa@PVbf`FqhCq z)A2#;_er$Q-S6EcPO1mTN7FcF_1R2g@Cj&5+}o4$d_hGy zr95+ey)%i9iTf@tYxnr*qV~fZhFUSJD11jbGM4ZVhAo`5QqbbV;v=Im_mOi~=Eq+? zC#iPAU*28bCSD|~!aX+_l;il))bHmUICbCS@83!~;2*0SJvWYI{dBWX{uSy{X-CI^-3#DQHsB!zBX< z-UMqnygAbB!;c8vQo}-mm(lUzo22I0eF_%ErOGLCI z21b30pIv;<&p<+;?g67^Z}PZ>_oFyIr(JA3q#0DbEIYk6LT`onjbDD^;1Ng2KM1nmlnJj~vSPsSU zF9erlA#(ADvz8_G`86$3Nbx5)sz&yg85#TTM%LgTTED*~M2$%%n35)rUbDTW%I_HqvveO8?7Jjz#L9WS8r)G7mTObfcyz;EWh<(0cyeKy1XK z^(9B2pB~w&cv(>Zr^CHm1IC^FQREOCIiLL~8;S$CG#8?*-VIz#o4MKLdH(A^=lGn- z_gIKjP=F*!H!KX&7sZ>t6CE5Uk^0Ec z`YHm<<@M8k@)XsUB&d4sQfW*6Zzn-_dh5eA-%$_RL>$F);OSQYwFxl4G9O$e?})yq z?FIt=M5TOxR#98gz02kwM*78=k@sT-H=Vd>S^PKpAmC+@@0a=z5)7x%hgNnmu2k&N zi2OXfNC=M8#}6dmMa7-D()yRPGcv5>MBa!3{EsJjQ}RH`MtDcckeHVK2vvp;Lw!-z zErA6`)k68G+%0XT(78%#DXBxY9YL)9gVW1HlHv{g=cboi%u42vfutk>G7*olGgYVa6Jf?k z?B>G8K|{Jr)BZHDRtr)dzKW!A@iKCHbGhlhwiv753>+xt*6zy}qvMLmH=19hd?^~O zel$E>w(_Ef`R`hAyI1hvn?mo{`d5zQ#r9$U$P1yblS6!_Gu4x-U%XK90pwelJIE)c z!{-ZkN@d|3Q@pe2V+CB+T67X5iaG$%`HEIMTFap3SfQ82ER?7kUa6pjLT{cv<;5DT z9M?r=lIk|>8_LbsU>GiudGCx=R4q_ldf>Y-T6Jv;P7+=|QI;rXy67HuviA1Sv|a*Z zIXRcZpNt-SPPl_UX?`rFAL5y9^3icgvKLj#;oV-_0u4>qq|208@=5PUivRYBzh2(o zPe`i!g$gpw?fEl;Ov;Yl4o8&;qXh^{TXY=Z+sBT}%q+0Yrd@YG)-mPzbrg1}q9f0^ z&>bR2YumsBxdQTfx=0^s66TXUBRU}dJ!rd#9Hi!exFJev6#nBW7h=CCF)b%v_B$TvW32;ljh0GCtA4Fpo4x9A7HGbpQ%l zAKtj|ID!%H7uQHGFV<-8U-I9cliHi0kg+A<>dG7nK|Q%#CjpBb3!jC0x8J}05k3o{ zv~dGaZKKU z3wV<$T1nPJFv5YSiis`0X%SS2l9Fu@Yx38A?oW$wEEG*h2n8*M z)td8C_0Qu7wF8v)Qcfr*iQ6o6$RtdI>#d(k7ioSSWevq za^t|+B!$|gb4!OmeN>dWCmtXkJ{qrzu1=orpl2V3Ran;jIR+Y(slm8AXO^oRHjdaz zVQ6k+GdNqgL72-WoVP2d5_YuoY~Xh6d$BET zGSm(ah?(5oj0?N*Zv*ZWs}M%Yf4`jplR4JsiEW-D8E&m#(Hrr5qZB%w@*dsz%JlvFB2w_bI{p*8FeX-SQ8Ekh`A zD)UI`N18lnH6AWZ-u1Q zlB>@vC3K1!OH7@%IgTWf4ceew4k^+3e~A-B{2Uz->UxmQ@M!mIjvMPttuZ>bg^ zl-$YXThOObYi&VYiaayAT;LldLVUa4;S>7u}V=f67=BXpa~YF)5AYb3<0H|EX#dZlDNDa!)72 z?A0!S?uhb(V)T~U{Eb3=Yj2F(Z!r5OJ*K+%w2CzL0%Zqra9bh!u`r!bRX*n6r68om z9~G4NHdj&Xadcd6;!-Y-qd4wMvaO)#S@&ZCndBRU*R3Lyl1NJ0q0j8qQ;{|i8y;lF( zs1U#a@AkJ2x@)<2s*W;-2Oo7=4Nm(q{;QH!iKgp%HTPOb3$;G8D`SK*T6&;rjF4Rh zrPh_Pe-BQ;JmDhw4XhXLbFz_VzZoa3%e@azszpw^^x>#-BeM0Ae#E zC&$0b_94ppEo*5_lL~0Z&VTu>*{-n;avyUn>9INwLY*<7B z)Ymzaoyx~Gw&5tG#u)KV%pp`VfJ~ysOX7Z*O*rd^Sej#;(zRE3H&-``-&0U0R5e|# zRqk|JS?UOZ9m`=xt4e&zPm`=hvC3Rf7*QcC3TlKH+~0=8q`LHi-ztA}rHvq?POee* z$EQ19F80AfsaMS=I2DxW5+9Xy*#qzcnXJKkGie;j6b#H{iCiC1)p&FjI?cG1!UQ;f z+;KxtOP?XgppB3}qjr)n6$@awM26cbmPaWdbk2itR||(o+RAM(wOWlpGCPatnAg!$ ziQAE37DQyR@)a*M*83lD3Tgxof1jF39O@SB{$yroRmNA5(=_q@emIPM+%YfofPYFoqZL&WcSdV#?E=->}XL# z-v=gSInXJMyB5&aM5-=hOX7%gW&M&HW-0Fe`tl`zqN+`ejYU2ycS0nV!W_b^{7?%? zT=&ErdG7Ss_JR=_?IMo^Bk;Vk<&X3^wzA%?SkhL`)H7hoE8-f@Us%b)@t_-9@pj+* zi%fZFvV2?M-F#>9A58PS5hO1iiStc2l@o& z=CjCc`UUr{`=k-(3eV{yDaw<(W^>E33lzgwn)dTZ0uDA{5f{7Oj%<; zlPf>KDwQX-u$%ITcau4Eb^Z5SR96*wDcya`SmblYZyuD41I$u2^T|)uD~n!jh>eNH zn{9gD_9MCecN-UP(#o8Cda<<`M1CO0BRy55N?+&m+AY8Ak|9 zp!XaVq2_IC`Og2sl0D`61H`wXf2%XexFs!KK|h@(X|)B=9@qm036YEaI^~6oNZPdE zV;_{5<^;OYY&_!%il2w!0cagUDfG1EX#1NW?P6(=@j6IT#_AO5HNTpMoOg7gzguav|>y<5Ap)qLjbE%I2oB1;g|X*N4LeGMIV)F0CEVCLjQN!z173y z=aM9o4H{;hns|-;=vQ-?Di5(L0xGM6#Eo+AhOP_VS_=519D+*sr-@3qLh&3$eWp+I;(Vj`%(p)+` zPZ|)(TQ?`oEF&iC9t0;V9Cmg3x)f;L?M3;w1QdOP+|7@+MkRhC?p=EVG zr=QVL)rD;aUq>AOr?DDR<3d4n&Uo`JaU`Cndv}W$pj}caqC*-A)=BTIzW|U$Oz)I* zn3l^pe93#?A|bxVd2KqotRKSbgqe(iJLty27eB5)_!Tkvx)l{4;*82ym-i7}N)Tt+4(9t{^HFXB89{;^+ z9{#VjT*GHj(YGF0eL(mH3oHY!Yj}7egVJpOAaSbPUfZvM2C)*yEwGu1m`vDhj39vr zJ9x35B%R#`mqic08Hpjj)Ptx0ss7Z_aTfo&or6yZlcqI^GL}A)#6b(jU_7XDdoU_ca!WArR@JX@aAm@pITgz{?_=447awL?6Syq$=;|u$5@tI6 z+QT}$+misN)J_p;hp{3YU9B}4O7>^NPAR&(WacIf4GS%EfB#nK|NfM{zTvzH5?3IJ z%UhO19#iOfef~6Btc=ppi;0n!SYSYf!xb7+&Qf4j;9ZH~`L#Y-Ie1JkX;)Fw3>mcB zj0CVS9zx6m7LI5W{(Dg5ye07!7b^E<(jtHdT>cTe4geGXKHqZVfyp@pzf%HFYcjH$ zgwO8FE+qZZZ@F1f!kd@a4%&N}3#5^6YB)Qw46DwXIOTHOEv-IOmHh;xJR?CzH2^CH zOEGV>cAp7*_kr(t-(vqbLRn6~7RHC<8i*XdQvg#oqpN1TH7BtXdLE1BW<(injzIu`-u&P^soMhv`Df!f0QkMdpy$;{<&l%A9BGnM zQxl9rg?Mh`*p???-F~#VPzIeZwwXH?R%nR8)k zbpuX-XIMza79_#bzQ)ok$H)7!$cb-8DW64t$2nbqprV>TV6N<2DatJfE^MIXmQZdX zde}V3C~&lOByUs;t!?*&(T#y;b5YAHug6E)WH4V@715Q1a5s-&0E%itgOji@)FP{F zFdUw(61v=?)sD|l!y{8+n5YpG58sTS4|60>Z9ic|%kEyyunn2d)}_eX7HpMlbxv}% zR6~0`CCXY><77iMX_YBuPl%XqIu8}|$Xf}vwjr7qr_4vtPbu%Z{S+#a$7&DIOk6SRVe74ttjCE0t z%;^kBvN4cvi~}IR{{JK!rT1o=UtNql0It-~8Nq{$=Pa#Aj>>~jDu33~^m_A)) zSZ4>(f8UrE`zybaH6*19)0XLJ=6c}r3##gQ+JJ^7uC30)H)48@GcUmIUl_8fLs{w< zGbfy63wVANvW>5liX$4Ae#Ykk?Tr)lF?AY6EM+};T{5SO8T2a76xBR9@TKMWT#%E| zqm*jhbp2`7ietfr^T2Sf;*ujkfyd)d4_G?kN$*-S%D$02WOCHW}NrHzyM3)G-* zU*%I$_uD}#IkqGbB2y-;?JC{PjOi2p1GQuSUQ;v6syCyK*7*MkdR^}tFFS0%eqC*h zavPviks&%#NCiSANokT%j@JRSw_Ny_D}GVFcCKx9n^~QYBD9+C#eC8h`6hdw;*BZax!WsV2 zbv@(Dl9_+xAgn0igJ``uh|r>trT-oob~rKjVZl4Y7isD9R5gXalQyNah^Ii8~m&mZ#F)&hD=Xm(I zqXxn2iY`Hdad7Eae2Tsu59WOFEDp-eWUa>nSAskW8QwK!XGA zyq_c%$#!PM`BaZpB+H-aySM#Wg))O;3k4j@I_w0FtUE3%C{j6fp#e~1$(N7tge=G# zR&2)0nsln~9X?s00gq4QR2#=FOAtckP*+>>pdVxhPlCyCeg|Hgf0db^M!hWV>a*t+ z-4&%WeST2=oPgR6g(xU5tiVox3Gn4uv_~IE$Yh{n7{-@LH;SM)WCt{?Radb#bR!vD z@2+=E{uC1|S$JxO2KGJuTKA*8%x#*z`J748%mP2H*2;eWOx-h|$1y-7NmvQyqFH65 zG+gk2&+|5)Fy(Exu5m(`Z4x=Z7!rG+*FnAST&i6#PTkWG$QTuuW_$y;BOuE`G-cG_QjM$^2c$^)4gcl+-aIoJ6jK2Cz1|*rFQC@*wJX6b+xt z{_E#LJFi%Ms=R~Im`esvxJ(NN=^5EU%^y6$;-DzhcaneZL%v^3#~KSwn)0XEVu6up z0TU+sB*M;cnMxDSH~2>+SQz+;#KByjs?AMB|NZo?LGyAH8rY#CyRG zBKik3r2QDbO+>xyLtxbv$l7!s!$~p)LI}i8rN|=yf2-^F#L4{WHN($6j%^XVL(n(Q zF7+Ckw{aWyujAGZtAx*cnCNY5LtfOirH&v4#dnktxPEU)E!}I%+Aln;J+0}zA93Pe zwwe*_M$-%Vp|`n#1@(QG+7eDi_m>`1ObQwRWj=Wf=R3b5fQ@vp+gdcPg-)Ja_u^|? zCW>U)@K~r~02I5)M4^ma&mQOtbd-4)Wvv){lY^5v>B<_+4T|^Yz%^?>Mrsz1b?a^9 z9lZ8NFQ0B^O|8TUs~g4h!u@fN3?7*Aus3uHm9en^L`sg=xcW+)!_b~B*ySX@(XB8I zG&SL!iFOBfDdq;y=#u(wR#!cGtm$X-^Sn%(a0?Mymppt{s&q;E5_LITrbDAFdL^jA zp0P_SDOfDTxx<4uNz=F^L=A14|mbkZeTqgLQ5weE;t1GIQopy-pTy^n}_S8VEP#2 zuwGj^gM3ldK(sFVk{2LAeRszwvR|73k3SFn=X(fO@gQ2|+=kY*dF8Gc`K;zMJLfkw z^i*?58~rg)CP6`*DdJY~()4X4iGUixmPg{ts;4C$CJ@>c)M%vT@VO=NQv%cOFNqbhf{*$K)x>-b5*I!3FF{ZpNZP4e>4XaE*Ysad4PD?fSTl^NUWq4gb6e z6KuHV|Ht1PJ3emqrF;3Yu^U%$Z8vj{nCF}ndQUV-;=}fjOa|rGN+(E;8QtambuymK zy~Pc^Fm(47^%F*^%?aPOi25T^RaWdAL4Z@*iunWz0H6OC?(-IsIarz$Nz zZ`@xf?fMr!0$R+z&|H6VIqu}_|MLRy-b|@m9O%nJdK^R@9&1umV9@+`nzZD01bjTQ zZL;FFu8aKhw+Id`Zp0*0`;CZcm&WV&bo0edmr;|M8@67G=gLGaUS@WV0XfUA^A|8B zxlq3xm6^upv>W>{(4h>ybnJrTTLoR$QvJBg&x=C_n8BaU=+489iDVb7kTL?geuz?q zIPA$Psy>*@d`RE?AskesuJ3n*$RP#M<-_H>3hKVeMj$^?uLzg>3pL)O)&``Y4yV68 zCH-?)@_ib2QdiorWFNF?GLuD9A4hG6xZ(GMXD+l_s){Mxw>FKQ5(vp{`dn{Xf%ICx zC?AfzJS}xZ!z(zp$_rVlGxnj|shd60NLD1lqgC8tOFpflTRQ97wGBqo9sT+CAQkYU zP8({J0I@QstUxM>twXQuPzS}B82rwd4x1KCX4XQ%%P7BM_x1Rv^GOROg^EQTrM9Fr z)5bd=`fyoO!A(U-um@*Rc-3ss+HBGP(h|SHtXtV^THsey8pDo@z)T~U)81bIrGH`% zj%47XKRTJ+w{Q1Lb&W{Bjaa>z!Oap2U|(S#@CYN<4`ao7Uq_=m-_~k6A8%`71Bztog8mpiDeaXnqd5&sY$rahlw{WPgJ zBPp5U%pw%Z#1neQEMWvNX1TmD8szt+8|)J^Wq(;re=k%fFs$05=6D+%Uc;wTEU}#` zWNo)$RQ~P-IBTcLcmWjeii%vsU2WTsT?&AiIEJj-)P}5(|K{xgHc*@mp_%w z>azW{5_x+`9x}Y>z@JCKTney2_`=un{pqogH{%E;gh*wu-szI;JalL^IkmkjSt z8d#J0ukFoATk(||Ydza(o@n0gq=e8Q7fZ?UzCBSTcgGJ#NIpyY*N%654uu1i&%>;w z>*t#bPAOalA&)y;aRaPs7nFDxMEw8b=_}l#?89bv2`Nb_NhOyCkxofjq@`1k?rvC0 zNv;kmB+`OQ5u_YCyc6)nTZ76s)~{Mc)oWe0jxWesod z`hA<4U9U&DrVOCHMqXj=&~S1uM}QJmS;6hE7Q4;QSG&7MyKTHtN}SAc1Xgw8rN%C1 zzG#o1UG`0UwrI^~k90Dnl^n zY72?-qni?EEP!7+ZAfXF)K*cm8oZ`wy?wFq5T0l#uhpMJ1!M*u5HlpOJ0)W<0sh!y zWWW!0Q{5Oi^$}DP@f8XpsdYrY)5f-~TzgO*X?AIm+A)Jo*^pQc9=RTX^wJ+u_o(;) z1VsZ5jKeqGBA`Vuq?;4`KkASn;wBfX9_E zJ2hqCpM6mQ{X5t&H3E;A{^_yoLf@&vqBP|JI2^~ zzb?C$fr>7=E53C{VE+YxmRbyX8ie;wA~?OBaTiK(7c22Hk(wOi4cHnJ`1NYnVmjkq zJ891l8~6Q##cbe(lcu}4ASo-)uEgZ;#RPoRrgY28w;44Yi*~Ao&m`lN>c3AHyWvo~ z7}Y60{=MivUEpQv1pKXCl_6lIY(AO=g3M#`WQN+LuRl%5GT+&oGhnB;j+}PiJ3Q<@ zpUY4D>(-U=`;C_xauvU+FPw!ZW(8&WS)Rw&SMErbcVWe(KlsJniQ5yxnwEQ>{a5Vddg}C;sKks+**U z{^+cgqMZhRl!Dh_vEJIanjO2oNAS>dVz8^p90!Z^Ex}e6##g$G9$sA5aTQv0d4E2& z-43rfwNUmvZUAt*3nIV^n{wkVaX8CS_~v)lgaCD8ovTsiZlS-seEzB2c5Ify$Xnir&El1qF!Y&gTs*y4E! z8lgEEiw$N&Y4hBH6Neu?H#ACx&fQq_6O;^2_n7y7d!>-Ee<12H76~=9aWJJCa4=%} zYC@Y)(?g;dQtl4!H|vGQJI>PJQUCSxdoOUV)aHHlqb-$p-iR{opti7NnK1ms@5h^B zr#+&9`u9vr+kylD*eeLKzaNh}xrE^KRbnb^YK0oWU15sqZw92WTx z4XBQ;G)hRK@nwo?)_CyCQz_@K;hVpr=RSD$`@m zvG8ep!m$Wa0Zoe+aWJSqN>k>`Qr3q6nSo=tyFSBNZH`g`WAEf#iZvBug<&1pyM1_? zEZ~0nXrWgA@aQP;u?|n32|x=YxWE{{rWexbb`eJTFOYk8M6Lob@1VU}ZVAJFy(wC`IauT=18C!#SRe9-;Ri=@yQhspsY0F$=Gr@7tm_mPc>Z z^>!*-v(-{gaCa)khac1=NAceY-AixqtAs^ELoE5N3DseCxcgm8wDwEmtCypDB?=1J+G%31bj?p7}rdgv-Pq8G+k)SF_{MZzhb+MMP;1Zfgm9a zS9q&|_|0A=|J5Jh7(^q-Vv-P1G3TQvB znLe0aCWV8-v@AJ6r@}IIb5D%4@^+=w?>s|iDAuxk*US97d8`Z|qFro3Er!y05Zswb zV`;wv-`yS3d@>p>(vYVdY7~dz_A4gvuz|M&x_ga`6S>^)_zZP4KsEgjAt6}}^W=)M zR{JYix%nl88PR+qD>DpDba`X=gSy9@0S-E@Q%fkbi(ac`=*c~4wU z%W8F-EJ`aGehf#*Fp2i5a8E~4Rgp(f@iUBD^Qnfr&Y_Dk(4=BHlnG6v-OWDgIl!^@)=%}rZ5k~igkc`{B0ffPpT!+{{|XS=Hw6{@@6v1#;dx0X^srs zVKT~-MmP%mFZf8`DOVu~6H7n5C7gxojh`N-HFxf-nH#U+X)|TLt4Kl(wmez=tpa)d z%rHu6!#xgI*VM|cW_5u{>R8(|?+j0=&uQ%gW;Lj_?44Ux!s%QOzhI2sWO z0Ot^WO+oKK7Xrz4_tPPfy=!IhzaLUa`@x`!%jf&HY{K8aVH$-#R$UA41PVIY>+;rW z>|F(bI#j3Urp&kiVC9i?0Q0*HXxRsCV|ljvk^H>;6yNP_^`mW(Rzo5-T_^qaYaLzd zmRehBzSA!3#muhYlEQ}m?ab2h$L!aJ@|`a-y3S-mUWwkwr#pLxhv~ZikKD?q?PEh$ zq@tXq6mNX9B!~b7=$r2bxra7O;x=ejrN7>C-o*IwZNg%hO=HNB6g>>|V`JmDNb$bR z@UUCckGRg)`rte4PHi5Ryj`p2XPa%k*NF4JEw5VJ5pM+x4R zyBR|FV;MqsUsHtw*+89RfErA2zMGq$_62VcCq8+>7Q)?o2elP=_csP)!lbt)|IfzW z`_uTfNKMhUc?7kkogG8&Pl86aZ9Y9K9r{NW)iL7M5`;tq*d6EZL+K3E5OA^^a@)#2 z-d3p+>eQ8s)M9h=c-Q4(N*;i+S;e5=E;D!cm0Abouj6jz+5b3|bZ{ZTwiQ3&$D=$1 zcJhKmqdwpz{1(NyQ1_#fS)g22UC^*B3kw{mHj)LM{lZ|b3lT2PB}-22-{?Z1#2zD> zo^1-z7yE|Anm3Nygf*)yt$ph(!%!7|g|IE9|@|Eyc0%~(@@VE3D5^Uo~3ug4 zsGHJytm9vF<&9XH9Hn7DvsbqqlzHiVXUjBCF5FIT5X$8immu zo<7Qy+Vtew*}E@>%POe<_N2~OTE@f-ce zWqloIR>;xSr}UOo`b!BQSBLNsuWg)L=8zxT0-0915Y|PD>BNue^@b4(Od82GG~1%M`1lBlX2GJBatDpKOI zZw($+nz#u1ds*ja+V-fAglD50~fB_Tk0+e_)gqtLp8w+IT{KVXd0?<+Pw?ZaBmP4d0n zybvVEdt9t5<`~gsQ%=P-Z&i2ldL%Ex*2y#Qr+Q+QAQLBF9v8X-T(-FLI+?FzVR1ynBi_XlMIC$6b$O6e-J# zH6%Hd;C*3_-MSd*+uW}wqJl^))?>7RMIB`2Ckru%l(iUlh#%3`JMtHD{~0B8Ge#kB zCn{{HD}&#O?i4KhJ;*Uu#rt_7<^n@PHum2tHRTS)zV%k3BMf>;7@= z0;X>Z(qS3qFXW#1vXHKC$# zK0$7jZQ*I7d2^wtkg;BFdfSdFqC=I(#JHzNEtCQF>z9{=m(rSUJffZ2+dCv_x^Ft{ z#+~jwCPpfIN(V#rWrMUiLYAg%*V?A1P`MG~uInUAOoChuKc-sokT!A;cEe=Si;_A< zN&^N`RuF`Cwj9)!vJmI)l!!G{4DlGu!7wXoSlq|SX-y?hl@C@JeJ-_OIaKI95RV>S@`Znl=a3=WQ%R? zW{+<%-D}!~$W>e02=U=l63fHcmqDLB04aflJbM6(&9GJL2Z0e9hj$6IzJkR#()+(}IU1_)yVkA$FP66bkj{c$Mhn6<|6m$`DD9)VNovda`xacN)>%=gNA~z_Y|o$JR&d) zQ~qDTn52~1yRa&Tmy>mOK<@hobqXElSTFlwOdu@;6XwzF=SH1@Pbe=*Lq2;u#WwNq zOW^vmiW6UHus`Q*@jW$zy?TCvw$4|FZaZ_J8IEu0y+OYpExHsc_8ARn#&%2$;!Uxy zknL#~E}wA2`^p6^CgUM|qAg7xGUj-buM&p6tSmEX8(w%AVP!yQ+9F2q1a-j8m^kLm zSO8{7l!NSA9QxNZggP1@`tlDfO*$M2ht8#x_Mp-?&?h0uzu`?c2F>=fZs@M8?_!<%Zsl??HJ;ixcEmV*!*qOSxFPuG95%bvtUF2bMuM zOZC;I1mk6767}8Z?}lO!!ZHfI2u1%)zS{zCADmPO$gNWa&J<*>FrwuBVL>l47(oZn z_FZrB){5B;3-vmJ<#oREqs7dy6w#64jO(@wHjW~+uXHlEj}IX{<1b6A$IMJ4-cEe* zK`m3=ViS^m8X0`hn-f_Lk`ISwQb}+OFsQFXWH;DmE9>3 zQF5BTw;(zw{n1bZLzA0(Z{AoeM~C{JUnO_br-tc+aEwxSl{)JvFGGR+m*G0e5p5&Y z*lEKKkjK%FL17nsB|kB}GSJfWtgggI1WVb-fvv(Ip)BGKu!z-PyPn;$?_k~h;Gl8g z!$CLaXyF!i0eH;w<|a1>$2tsp<=puGZ_UC2e_zBJfY!QkK7xO{YUAx#lV2MeEV;}@ zr#3uYulr)M=?0#egvSk>oeZq~T)S|h>(`ni9VKLVEU=K;N|RVLtUWR;tPDNN<^A7cg}y{iXw9G!D$qP6 z<`=(g@Py-I@NvI%@Np(J=FJC)@<$!EjfCh{?);MXBWV(-AT%SpZ5L5--boxB09YLm zP6*(KYqFH;nwy5dr-|EV1halP+I=uTivOS&pPp`f`LBAotKsUA$na({-q7X7ur2kt z)g~N+COXLfn%NJ$#}n<4uEBP_FW%u4t4g3Y&qFa<-FBx}cf6d6aTbk@ig-qULe=g% z&h@?zoQ`M#$O-&a*g^{qnH?V`vSGzd{amXu{*zG0XdX!3O?@Eoy0OJ(!*U8G)9Zh8 ziQUo}+V?kjP_|x@c|v=G;=?44^+do+HiZ+j^KEZwvFjUe*=G;~Wu*-Bn%q#gH6FRs zW=IJitEv--V4F^{O4xLIs@(XJ(9&|*>hZ>Se&reZ&EwD2`A7P&mBxa}^;vtgVqYRd zmxCB&SnLjfu&>nCWJzmaILUI@<*1-W*VDr4kx*ivWcZ+{3V?@OIg;&D6ayv;Yjv*_ zZaLlZ=hH^-y?%N3F9f+K((>*Qm@!rJ9xGSbNek@{ZOfQ3fL0+C)8*}BfaNV5Rd^c%3PMT(;UAdgPyxYp2X1=JzgG1Id8Y%^#@wE#Y=tXUecF+wM9jq zaI1$+u6U?~?t{~S_I9<}N8fU}-q-Onw*iLRTaq!uh=4O`epTTv}H)!!Q~7 zk#vt+c*DbPw4y;mLJHm5Q}M)Yqg(psypM8m-VwCf8(+=9Al`7884!H@H@i=fv1u?# zJ87Ind7E2Hsh#^(UeSX=)LfNAq+V8EKYi^#-a4H^(lWw+)}@F#|G$4EQR0+>&Sure zUBS7DH;`yVTA)T;9L{0laMep|!t+JCz%kLQ$M8cQPXC9JmdxHriY2R3xe%-$k={sS zx31;-mDsFrvtkO~TZXYfXe<5#1O=N+N75cIH9gn-5G*ZAzg&F^WrA+c`2qN;;6SMieAUH|)Tn z)l!ds`wZWv6lm7>4lCpJ1g-Pe!IeiYqCslK9Zz0z=J?*=aF;BF3)t3PFS%n7Z~Jx* z6g6mbm7o2Gf{^eJYznEZR{~>t<0XXHIKW68jel@VfhxCJ z4?Zha9%p*@G1<#9w#OPxlS%xq?gmxxw?BVC8Oq<@s)u6ukqJzW93JG+cr7zToe#P_K1`cvN8J{V@Q3rLOa;2;*H$=$p2gvbQ08p$1BabVbOJ*;s{czU|Yz zlA*OiU0voJ5rCsYrRn;wuaOyKf^4QUZgLr`#Y2n(;W+e>^E+|GY9}~;gOZu9j)m6C zYUpx~V_)KHURDBi|06WbS0d9-YwOFew3Os2%(t|xor9)l5MgyD^Dj4iiw#_z#0>Qh z9wkfrEqU<~dFJFjev%?izEBZj*C}igD!j=K;{(z5X@MfzNZ#1&bEk}{p=|+hdj91}l0~EnkxM7{NIJD)U zEEFZeJ4TrbmMPl>BFBMUZjpW4?K8=5-2#sFo~DmZ1la#k-?B1fU=|h@EJZD`8zWqo zU9wh%q6DDm<5d*R(S@d0+sMFpU`xzIlA-Xj;3VV{asn- zwu>DLNGzml%6pO+m2RTsGjB&n<`>B`@HPqpWu?iY%wRi7NMlAcmhQejW(#RPUcD5& z-%%2NVdY*sfEun-EJ4|)_ndY_DC>vEkY78dD_)~SPThBlMe zzZbPD>vmt@EX)2AqX5LgtaHTr?R5)Rc|}9rL0I)PA42^R&H@eXPdWuNXzbbeP(a%q z1u=Anvh%v+(~{Hw?9OQ_CGw+iE(9gaSiJ)yl=ljRvFtDvt^ej}it^nu>+#3Gc~sh3 zPOnj5i=0D#LS6b69SDE+^gsE>iU3B4v;N{f{FLd*BG{C@7+9BLsutJa6nr?NGt>Xt zW|AsIS=nld+vH*1ujk%0srQmGDYaYiP>*T`MHIS}Jr-qAyL6GyFnzlWM#06kF0Weh zT4QU@Ph_fV{Qbai^>)Ss?^?Kd_&z&^P&D~oLVBqY%ypy1(`_i}FR zeM3IO+KxLoL3p&dy+e?o+42g*2z#xhM?^>oZD%z6By_DQQhSl*Y1E_d^`8u%wE z?t6)2S*aonyDm%L7Kk}crO1YBvt<_lHY70Sd)?8w1Z&G}@a#9$d(wPcF_v6PMg%)s z9c_$EzzYf`&o4pqX{o8s$vFG6{LTmX578q=9*r?V$9v=1c68*m%bqtMvMK}Q zz(E+d9tk>ylY<$M#n^i~RbBOp(Lrgw|DnA(`q)Sn@yv}+$Ug%|cZ85Zk_@tVxV2bpF8TcI~LMaSGRT6Z}n(YZ}sFdMzJs2u3 z7e@H6`oxv8N7MYeVzi*gO_RK~-F-Qt{$%2P-F{p0RoS;qc7G3Z9drLatW6RRY26dD4Afh}N~&Ruv6mlf%{w8Ksyj65>XKHqD8{zlqYT4IA|Bzn5NgdBh?HZ}OJD4pTTd)&F~vUBYxbx zF>^R(D74R@g)du`GAso(ySKE*ulM0Hi>rcWL<+jKk&da{-2aGvK4p)-MhHEqzjnZL zgstkXTD0Zid!5Ip3#F;!iHXj3mXq&Tr!_R#bk;0)*K|?5gYxys|DG?+`xb@p@R>B& zac)f@%DUdV6&Z?NxuNNz%r-yWy6tIN&N?w}I?l1#D}_+=XMfk$)o95&hI?OoGfC4Ge9S!9UZpk9)fH~hZHPBonNNg2%ohJcZ?}@QeG~1Ei7n+3f@61o?ozKZx+?#6{VJfXzN*Fz~ZBGaXXMTLuHZNj>L-3vo;`CK@Abi;c3+u z;(gix#8-)*i@Q0lE6fWkV?0AQ_~>-Fqj-URmz|&3rZ%pAMJd&QsD`fu&gDATJu51P zaIWL`j0ljCMkZsgl2*m*pVTsua{?CjmJ>&+`{x<$vK%Ze!#@22K;?hWk?u;l5xb=N zJ9G~s4SY?<6@d_smn1v`ME4J)xy!*8Kqz2vGlXCT-kRLwEt%jWe{Ur$#R7Ejv(y_K*0O*u{S@rV^)Ri{BZnEt;nq_01FOKh#>`f_l|BMlt zi@G9k#js7oZ|&=yMlLjlp06B1?*6&Y#jw=YhYntEghbVI85d6EOl?QYhx>Wr?+Yb| zWrKUq@MKEBGp`M8H;~+oVO-qL4q%C;7){H2`aN+QU5R^#PTjtR)V+5ZgY#@OT*ZXcFm`dXeTB5 zlbSDttuHW1jw+LfHEGuYu#O>EkCxVy1N9hHJ0W6-~j_8|MIh9dehO&L5F-P0;~Ejx9jx{WhegqpI} z+xT~s*lWKW?cG1K8?K|`{gKQEcMJU0IOUA5#C}SN{8E>$V(4qwA1Jpq+SVcy7>A<;GtUIv2qy+f+1zN&|+Mr}v4 zrRVm!?AF7a#h0!i5XC~t001pea)kPVum`_MVnrE(H+pb5MMeS@;4h=vxhb4XyjpoY zoxeVu9ea)raL&M6Y&(V96FnhpJD%37FVFHF#Za!i!*33ky~6|E)n`{#tHTZO0e1QS z11!Rsu{EhBSM9XWIQ-<$?FMUph4o)g;3y{5=)d0JK_&nR-D=FN zHkD}Iq1}HkH6AOTw;iA1<(qReH!j76lHCVy+7Yn`c!j?U0)-e=;~;NP(gS11U^;{M zjIc$W9LaYOC`7vtJ5O}TCJltZh5wgq1DKJM6FaqNd%bw7w}$|Svl?P-N;>?rYj1|i z#C$RDl)iMcI*rWrE$^vC$2O)Q^#0-XjsxbB4RyS(?L`YcPT?&v`fu<(>VLk<90~bG6LD#W6n}er9pmlc zj$9;&fB1(JI#C7$P;Ry*YbOE+?+FHjBMj>pSb%RwR@i_90@4MAjq4hkTNBfaP(#2p zB`7+B$ZZI*&F?aDKHQ&Z&L0js{ za1bE9zW<)DuVzL=)nXX){^kQ5+@zYlxVA4uKifX1BmBZ^vZgsoBoy^7!B2uAfUr z=9(p6>4ZkYNPRnrK9(+doMHiJXYtOy?KUIYfY-blKkrA%a^wbczefKWncJEpNn8*qbls;41Hz z$s3j46>pZPrk(NW`}khn?`i4HUbwym<>rqzDCkR`yO*ezT>tW>FfZXLf8>HYyc_kk zU5-8O|DPfa@7I3P*@-GzDB@Fyx4buIG`lY@KiJUuQ}D)Cet%}I`1*sI2di$QMS6-x z#jKurT|Mg*B8UN<0WQDpjcvn_O3XMR%0P(n5QT3@kCTk>1oJ#$Uy*{LOH%p%wwD}R zJu=}L5BwB6ko(I?xSJO35|Mr<8oD0keynbp+?Oz%OV4Pyf!GOmup1?c{XVp&HD7s#7rnXH;{?Lp2uJ-i*q zKw4EkVt%|Y$vqf~Vxu@~BZh`=46J%XZ;UlVubm~2hx+Uv_qIw}JT1Ccngp$5WL3Yl zXq;cNhJMvI9AYe#HU9FqmWOCzQh^|&Kwy-Flxk+|tB>6-P4?b00!@sH-W-?XW!)yt zgbt&;yhI=9+uGVUhnWqUPP)G59Oh<@)zyLfLPi2<_h0vo?6obIWcV3d>rc4(-wDA3 z)OOc2YZS6$SD_kqza905G&${buCZCQY;A{F_2n0Ou%NcsPMb|uF8mk|*)=KO9UXR+ zrmWTCRIIk$Y1Q;pPrO(^Wb+0ieUFHuJz_*(RJa;m{6|I`N~l3_Pibzvbkt~qf@LLH zKA~1z^shQg%tPpwOgefYjU%y$etIA2+d;DnfoS0XiA8ci6d(uy7R=^v^k@uwV~UiU zA|`>*qRAD#r6Ml@{7F+!@XX@ut4r^pWuBK?ysM`BD@aHFyf=$=wJB;8ogH>Om`P&Qsr+`CWZiBbDnkoM|5c9hS?vpB*Jq1rKPs z6)pgkSD-|aRfz{<&8G=HT8*Bxc)cI3_qq!FY8suLIjUtW%T|ni+o!#JX@9Z>gmV*2N2H;((VW`(e@UFNb#08r}4% z=N(0r%gyJj|2o#0tvH6$$#a<|^cQN{)PoZ5Zfx0fYj}XrD)c(|C$0VgKflhXF(MN+ zN5aZAbOP08iWmA@tt;B6h<^#K0th4dAhGTNIvN??Zr}`s)*p}wt{?29F_W3A6Tc!eTdAS#kGl*Sj~u&fCq+AR`}S-YQN`D#^%tlksDP z)v0s6TQK^cvU@-?;kscW@G23dfE`X!pieH+D4jCNyXW&cg* zEwb0yfgx)r*AcqN4Abz#${oRiI&>AzH`3y`YnSQ%X*yUxh~`KC6HlDPE1Yca8EUoD_gYTvl4gNQ0z1LZ15%d9w@hxK_tl}H zu#d(jy2~LXqrbCM%<+ZPLcFndI?wroM{suCtG$W+n%HnQLsoiI{H8yZKWAPkBiEkvfv>p_%uu+}0v8oT8f>#C5m^Sh>@o!)uV z-k9-A5mT3qmx=0EEhY8khEp~b#}*5c=;2}b&GUY%+2a~{ZEMjT?8QwTqRbn&vx~5t zxS`lcDk?*(#;5Gq@la%^(EBg}m&hunB`z@!qB`h=-Of?$S{)Ryq5Dwf*~k7u z0SeaE+PQ|iA~VwyEWx=V$_rbBGVg|`@!fn&ciq8Ncq~zK=cjx%8sXQWbH{9mZF!T- z*exx~Cr&C`SMiRB>)(`{`_eqEr_Q4L+&^7Bf7S5%cwj_M82eLc-b$ttxc|$#b+cT3%CAQo@n!cvL zMja44fIi@EjIV_F%R2)5|HOU_ur z&-FiHaY%uGd@>E_DfSeTQu|$II`q7a+Vy-b$40yxf6|wK>{Zn_k1}Yn>YJfj)Jc{U zNvY9qb(_}{n8!w#{DpR{mK?zuhkNefv|HkR+hFdAWBFsT4i1W9Kh+Tj05Dc0#~Y}N zZAkQ)&Fy}-5n#5Z$+x3oGH%Bh({-4T5q1V{hA@by$SA=q$TE6_fE1dtplf}`DyDep z5l}`j(EjKI@&QzM~Lja_X)u;Z%% zxgVPtnQS4d*4lNQ1T}n;1hZa01j!{b+l#X{+N0(9fnOm9{S4ti5W_brSI6oGZoW5= zsepo+MC8Y<~htuI5|kJaV2JsWd) zajPMS8hLztdkR3)#DR?kYOHn|#U9t%X-Kq9h&USiL1apm_BG^C;Actm$2$72IOCFU zzJ5C(e6jC&DaW(H2L*|)2sO<-T@;4LV*~n03XTEltLlx$5%}$`P;Qr7CRd^_^2}bH}>#} zzqwifa6C173rWJ=q~~Qo+TM&!#ZKbEMj$Q0nJ{^iJ}6^rkFZ41?Jsix+d_dXedrdJ zG!D^NrxzhPe$}6MymQgyIQY$5_-z>(fcstkJ|DW}ckX5ix7Fo@57DmaDG5&KibU6i z2>GA8i_~;BH1xJ6XxBsKdsQm4rG z?f^;G)SK&kw1n-Z)TlJp)+6Bp+}7%BLHbyh&(z0;qDYnfrxh3qzqz`O>ZM@3Fq+@n z9*}~5GPiBzG_-9Iu*x49nm=c%u4}2Apx_@fXsXXv$m3YN9@c-_sd|1fYF}P5;dM%~ zRw^M3aTBUA?r%M>l@z!TZ9QI5`jK227aNoOv%1Wl@-v&4{~E5ArP2p=VqbdDdmfuj zFTppZ5+!0NBIpL-3VDY?QJ8g>#`|!CZMkbFl?f^;Em>rjrvTx{wP!ui0Q06PKFfEL zV?by|V-XUQb%X{_aRrgjtYw>T{pLNhNyyd&+BwvId1cf@I3d2WDR-5_i8(Nxwed4q{_sA%Ju%dx9hv8?BSM zIvH|jl&lH#i6c|WTOxs~$Zybch!p9`!IN;}DbRc+e7r8Cg9Tb~GVBQHk7cs=Jhg^Z zM^<7*G@oKYudc=JQrl54vuoUpThZx2zu?M%#7F8C_)Pr1RMG zcd!E{YyoJ4R8~*{=_SW}f4X{T$L#4@>XR{AhZQug2`Y6+nUKVIlaP>P!l_4Ua1^ON ze-xF8n_v4j-0>;>t@sck`!L)2-;dZMnNK0t7S8nK|C(AiJu-q-_pFyoTz zWOV+HknH|OXu4xXA!>!iTB3olKu6f0IYvl5&5c$tg~kw{qrmLGJU}&DnpG0%qhk74 zw>y{VZDKvlr>3skE*+thOgvJzj|K+fkkXfi&jueM#1Y7bW8kZS`jRG+w_z+lBkA|&pH0asaz>7z^69y=aYCpQn^JrEDg0U!KpUYudqd)R*YpM| z@#oR%$!8rBo&7#0k9&6^p`VR~l}|FyyTu#CE@W;xnqp5{`{L)*${&&)Vr$~%{wF@X zV?swo#VAVT21f3F_Vui`zNnMy7k~GBwW;PGGU=Cxs_X0P4*u{e4INgkTM~_@!PBLN zNtcs_{WKO6&WxUC^!8OD+?PA4ojrjRkp~%x*^9=wHinEV9uWiF9)G!XrLE4;Ay=As zn}l=)wvfAdAKk`ume9u?^Hmc|)jhRaxRF*1zv;2UGgD!usAbYJud4CF;=K1RvXYOK zY|P(8-~!CiSKsXr!!3F7F;QOg)StuR;^pAq-n&_MmBI7so%0e$55YG`4< zdhg!Nw_nezbV}Z-qJNx>E^0$#chf3xeBQy#v+())mgM-Hp51;}svZtF5FK5a30*H6 zcU%%DN1}<}qS4Ha$p}*4VZKwHiQFMm=Usk9Skmf$U>~4jml?Rrb<=(prTldD0}g?< z$5Zb6tz9>FfOU#6>r~_m1lz$ zd3bJ*ZR%ki_fATe=c3i>h{Ixa1ST*4fY1FQ(@m#6AoqywYWj0#eXx_k?3|wM&A%_z zDA=a(JDdBuQWhfQzK}$!x-Q{?2&eNJiRmxm`STF0ky8);Aku!p!d+xA%k44o`|jA# z9g5|hz23HV8X)U{5$+!Xz&dtYi%Fa3d6MpNVznQKFgF6XM3#GkC7XC)-HMiW__6Qn zqVeN4C7ZUSb2!&*y_To8@WbD#g!tg&+WNAE?GAU#Qgi1e8sD2*E6<%oD?ox(@jTMc zUs*PxYx}7u%v?Y(V`)c?WS|+WQ%RVN_nq+!$|wx8lA>iGNx2toVbN8CQ;lT$dl`7> z)vMeI|KdA(Bv7b(owk+!9+oN1im3?xbV|D^8Dh4*aP@Y(Z(&}$JaRs{JZe7I(%U7o z2|F!^pRi(4gC|at!+0P@FVC$l7G4*bxh&^mU>ig3PBTd1h2Jw}HzWa%fHfnqzxERi zYu9}Q&SBKtsyb1=)uF^VAbl#L8a&=fVtl?K+4cLHU(Sb%G}ho&28d*h)G!|f%QOiK z76dxTz`AHI=xizrV9M^FM^KQ13WW_tlT+mvw%j^<=?OV5AajfVq9d@|V`s5>CZ~l- z+h#1q!zJ&;k~Nbm=W{t=mtj_)=FK+MOeP`XZ~k@X10U{a+6h|lR~75bB9eD-jhQM~ zhNsp1|K0o(t(5z{1+*B>c(qyZz_mXiPhLYr{q1{ym3x3@X?;+aw-7i@Xj?0nn~WO} zuBj?FG;l~#lGW<>DH})E5~x6eEBR2AGqohZ*l0+e#q0BQe_NAP%vt7e!bcg;%hRiI zExO}ijUE{2cqsU$X0NDa-@^&i;QX<$(bP-3BvqE~iURHj5ckz#%gDKFEr)T85Dx*s zgAq@;KycYQakrM@=nuay`aW#>jaI%-U4u7R`fjy$l<&!}ZSxpdRHz|Z|0eTVbMWzq%r+yqacxT3V_c>vK&AKb+BU;fK~u^;>Z zKuI83$ex{g11OK1r0>&A&+AUl*DCLwrg6W=_jLBh)%9HgDA8{R02DG--d0m-eb?%b z_d=gkTi>j`(`%9{FLRdS$I<^VFfhpG1=HN26QCr~r;Pz9X`{OA{1g|2xGf0V5Q%B9 zkjHCbA43%3YUj9p@L>;t(t^GIVXd9-LwT$wE-lEC;!eVRcZ{#^EarE&mf2r^r^TLl zyxO+5W%D(cuk+ysPII6{RQ!fUn}}fZ$>xFNlyACQPaCDjzw7gr+1`+h2b9E}l-_^! zo_XQL7wp9sUvyltGcz;R+SX!w_wKf%46?^GDL{PIDZ6VqSw+4ygF^FaR zS^<;}MOi!Lp_n)aE{$v~WFcy#C}b@tK`L&%6A_h%40+JR!~c616A+0i3W>+R{cfBDsUy8sxqr>))g?q~(j&9*0=$hI=9q?MP# zDHN3e9!kQQ$E6fnoAqdR04ULDDlWARj?Tg*K={z$fL-h8usCbG?b~-CD%BFuh3Yzv zAU2@Eb9y##0g$AWRBusM)S2c=KHyM_z_k?UtdcdhD7u1@_ThVo`n@|2Xn4+!pE_&f z3tMeE`yukFL&OWQuH=#}#6|$$XRUn`fPHTn{14*IK6nlvY0B?xsgkd4!;*93=^#b03>E zPr5RzjA41`CRCk1&KjF`o1RG6KzGsxt}ocwl`b2<(rwqLimVGiJT+#cQ~l5`&&Cr? zHigx^Xo7h=F>i}})J5PDum@%5ysxsermZkKZ4Kr5*4DVmN(-uNVzeBk??voS;6`1X zvhl@v8$x6|DNW)Oq9(7`cGX?5Ep>|kQv0mFYKv`ZTCh!xi`KNg-5T*ZIfxg=R8K0Y z_E#5h7V;E;cf{2XH#nr`3&oR50ZO9H@?~&S_w`V4R8*a2++9#0B%GV)m44JA z^o&(iRk^)mF?zb>HCH<@IxRc*ocgVs#M5qMPQP>tq{h-Za`x@zkLv=IXn)0bbCu@) za7f=Zprq&TGxvo9O1{DT%%{fCVAVqX0?JJP@Vnn5PH`M<>SfM~!q%-@VK3fl`6w^d z;#-3_wuG#BK_M^nCV(Z08!*5TV>@~Bq@9Gr>HPWgC^-Do0Z20GtcgJR3gqeT?smSl zwbk0%+E8eC&~Z75vtY$!yt;A2YhQkU^zE-}c|W1tltak@O8P>^LTg2aq(mM*9iMLI z_~laIR+Er#8}(WB#oGZ&-de<$TZ4_0o9OvfyIZyQ>azLrs{PjkC@H?54_2r3m0r7* z=gn!a?E&Ak`4gZ7z=NMfm&DX;l6iH=-g&pfJ~%ONA6;m*>*KII@U>qafgH;rXP2opPLsqAZ3uy zGFe@Ges1^N@)NGD(k@e{u5?NtH#Nn^0+H&G;SmQk2yBpeb#HI4oj7rV4d4kjtmVAB z%5DFFefIFf582**d##<#MGYd_K`PW$fKu2$G?#p-E-1vxEZ3lu@9!%k-v3vrIYD&7 ze-=P#{nT1+6gMpbC?(SYB}Crl=c0&3MeWq-I6lERJa4alc)=PfYHioH9d>ws6?$L< z49%e53_$7aLF_a(+H_WvSUntIQ(CZK+pFj8!2>ynNtM~b11Pz!&PLHNn`;WI?Y(;A zYCy?}s;xPg^n{)aI#5sxoiok>M>NX4)4p1uk{bj>R9rXK3DU+awkUu=ddg5d{)ch< z{U67z2WyFAvm;hmmd7CvyN?a!|&NI2CLuS%_32TSut{>;m#QjvVn~vNj9f?*cLO zx5Ro=Ye!jc>}CBJhr_a^waw~Sd-5<|n+gHN)JFBfJ8HNeU2As3xj9O+-Aw3Z@y>JT z1oK~lIZ!qW`nuxQkALIMckFe1ckg!VojYbT5%MG*(Jg_voN{WC`UkinAADfO4nHz& z?K=xtGi&{vM?0!qL<>QTpgr_-;B-qRN_Ro6gF5I=5GOb;$Ky`=V-EO83(#rMkzILR zBC8&8_rpg5nmH;3IT9ecInd2<%IXsXN(3=6hh8hJ#v%GyUWkZY zE~1z5G62USxYHI9wp3)=6ZqxKwm_r2^iC!LrHs7r}q$M1Ti_>3Q)?>cH>gOuX)x3DCy&< zhM@zLf(eXE>0MjkqvEW+@x~h{<^HKteelB{{?NYn{P*0)W~szj;rtl&#}zj>_Qe+p zDEY?HU`-#$(nm2kIOIgte)rqo+D9LKFT*?Bv)T;2{`woPp#?w*hLk9bE-Y+QAEwLI=dNr#sQ9Xz79c_@J%^I?Y5b@E^q)cwCB86a z0Hu(s_tqiRFV`rRYh(JIUNo9SRsc$DAj?Y2tfZ{Oii+v0uAkB$G|^<-niSCFtN*Xe zx#7P4_VHu>=73Tqpg}0|M*F+E-C-VI3N4mbr8mt^V3NM!3rrHEG>&QRq0tx$WBcsQ zH!c92%-PwV9X3AS%mf@qS4rH8k`tDXpO~Fw;XY-%1SoyG)s6{JYLUJPbR)r;l!MZ3 zFqx8|eKk=hn!wd&;+VMN=;iC`PqmLi6wzgI$7FUpu^*cEgOYbtJ zOS$jGIpQlHn*pW1nqS`!II7JZpmgFR`{08Q?A2FawO3zz6)SyvZ10}E_RQ1I*t5?) zYmJSK4ivfjHYKC9KAy~i6Cx$@7AWPOo5=yp%(8Rm<97Z++}?caoW11HT5AVyfZ+@eek7;G-qRi%_ z+cKaeFliZb5XcnjK1wfOs%122W%7JQ@inR)pd?VqJ7GyqyetOR0K*JT;#M zC)|Te#(9BBqAtJ^;E=#2hx-ATBv2qN|MDMSLzMPayKsJsUF<(*eM>bwqUWG1*3B#{ z-zku;WPaM$G-TU%5849{mfAxP*Fuv*z%yC2qb7<@9RC+KfvCU2>Dqh6QSH


z~j zg!)vt?;%PWY`|15jF` z&&*E+$81z7$zQvkwCmRrb_E?vS3d2wQN-h7=uw(mz;fK^AW{p{DC%xO<$a6gGRAW7 zv#>l(0~9U+6h*M82kvOaImK8TEey+|US7x$Dnv&UBAAGDHz&JnclH@;EF4F7QiJ7` zRavA7^s0FVPPxN&^q~i=D4+7e5hWr<#I1yNQz?FTULRs4{^o8j)4-8n1G|iMcluQ`fYRsGJ@kU{3ogAw+yLY#%Q-_sn7}=I)?Rw)CHwHh56y8VZQWu=jvQgp z^PtmJvB;MqiAhKyx5VF+mVl*jF0fzz;+OV|U;M(|YuMaiyLRrfgNU^?H#fVu5>rsx zC-8lJ{Z7Bq6Hh#0-~X%c!@|5B<&=SPZU}%*y(u3-d!H=#o?yI6e*yickuV|O>{vb*^yZHi^ zK)*sMfKq8`X#glO*|=t0tFNRd`X_w8f}UR`9oA^;wTg4Y_~t967kSfoCz&)IN(DE} z2WzGI)rEztOcia#^RJ5c3rSiy} z72zkQhi!a%z;-ki+jD=m)s7vjwH@tIYi$vr#G)S`VFM?tL%}?%f`s46HJ|%(`J=m= zcCl8O6_y_5)>T|1g>?jxzQn4x_^6D$j-vB5zH3qs;R7#$? zyLMgfz-}WgE+sbxy_Gja-Xpqh=WHs160 zufOTC-@iF(g9}w~R3Mh>Ht*Wij#+hd&>r5CZ{Pk_BcNv$imJ0w84v(UVexMmN}3VE zA+@RDz70OXt9T&3YGT{+V6sdL|osd}pV3Jh;1le4sHpm04{y$VcPAb$Z%Dg!i&p-GYx ztjThw?FA|c%y&42%AtJ1V!7h^LZ^l4zISQ2g9lTs=wk%c^H=VDd9w^skvQ?0xD3Kv zQkm(dQ{@i%6iDeE7{j}QZl@0rap(|RV3dgAj4u>o^cfvX0tDd4XPhdHv9UN|Q8-B# zSo2FveZr>4%WZ199Pkfd5g$X3)qFCSG`WUrDTzp1BEmIRN4?7h43d}H4Jqj^O$=B= z@`{y5$58T)I2}?Gi5kjV7qhQ_?T|h5^@Du0mUtn665vsiHi$&HmZd%N3#vpNX^((G zi8}ha>*&up4ah`*qPvSAB#7f9hGD+IE(w1xEiiMsHU&gpHvk>sXclxRjf^@#X%>zX zC-R0`12H2M6&EeXT|2c*=tiaheL?N-0Hq!PCH~R@r4{WT#`SaAJRcus`S2K6dHbp3 za{JNW|Hz*I{`Z~gp1fRu<<-MdL-)qvyOAmA%Kn9ODEW<Yv#CUW&p*x&u#-#N=W;)2qmAWm9wKmvVP zQ90$cz>rhG`fVc(Vll&Ud7UCzRJY^vJ^Ca>DIx*|9@cG#njG@vv#+qQ4z z%Rg~)^kvp`g*&re!~)U54s^ZX?uHm?cI0Zb?>SVPkiXa;IzruzfVBYe)ql- zXKfuKI`rPqbjr+%KPT8;1f~n|yrYV+Sa`{0fTK0hLw*N?NO|UfX<@8p`@r zB8g&dI*oMR#Nk?*nTfzD7_pAdIJ(Rd_S@f`v|qn+(i*Ba+kQB49yqYc9y$o9ftAJI zyf|Qge0$ukP8DMyM2hppxx{!&3|Vfn$BrQu^_}mu*`vp5oWgu@DSb94uqb_19ITsG zjO+B9&7=>6Bd`Oaqjj&O_%WhU+xoD=sGTb=e($y<*>%2O{xEZwT*GFx%JIhA;mMfl!mcaZ3I0vW~jZd(jn6*jL znwC^y=*qyBO7LDBGzW#>`HMZ4%~3ANjYLI`#j!T{7k|0mzWbL4ut3PTiZYI)v@!2K zIyzV;;&cht2#)w1cpa$!XWYFo}Ky4 z>^yh&-Qw7=yJbnXWk^&~^*N_bG1q%OxGsPE zkN+@$64wb>HSQtLd5y+i&C^5wd(QwR)|8T!VKwXMgy2PJPq=*fvTWbJT>&LhAWG=FOic&prDbwCXI-O?_H= z8s={D!W$V%mH2}7)mLAurJtvten!EkapT7-AVA6@1(X}K^uxGxF+^S1>)q%<+9#ckY2pp- zrF7GcPsGIRM$qOdG;G8mzZ6IG1^wd{lK~GJHK253+Y?BlC2w^?A}Cb!YwT#<-KuM# z8>+E=lzozx&$f@+ero&}|B?KJzo*aec*37eY(xLGX>jba%?T2dvXWpD-O@47i~-oq zg@-bhh{*)=&y~U%cQ*ev<)ELia!1Oq%>%>Qc<9D^8;^~5AiwrKuX?OPUuAg+ikNJ& zVf2mmcccXBq-Y#$ymIPvog6%PSL8f@O<1ContdRzb+cq*jw`ZcKQ z_CkQ}WLds+ECBmtnLaHZhpuics5~eWR53ehjwK4FRmx31SVMQ*-%dS*mz`0D#}oc+ zleK<%WxLW+jtW7` zZ!jLamaumDKNN%JRb#@0wsm+p!^;%@o)JazLpOIH3J(`4jL8+-&a_!1KM!-fwmvA| z@f74UQbrcp-FAcO*aAu$H*S=zTepH0YrKBg;yAMV8e2c?#B6`Jan~>1Z5>)aeg%}e z5Es}^vH$3U45ikVSWsQWNNKqrR5*UwvE!tCv-^Z(XH1Y;Gv))d&6Z{J!A|e#k?(fY z$=<_}0Hqp92$af-S&6dk@oBPh)mUh%g2t+GWcxC#Z620^0I17^=hwbc89*MKx=B@| zW179xge4G0aK!ctQwyjEvcbVWWfyVEAs`1FxuU}+GN&d-@9d1I%d4EWfH>8PTrQuZ7?C3Vf6va}FD+q@YF z>y-^#VjvF(7#7d<$Ro8&l08jlBAn_2sAtMTq6{Unyph$dx4TEqo;j;pgE`izF_`Q8 z^5x61X9Qq?IX^8u-B69#f$FrkZBs2jYQ^>^KbWmRkL3)1^bE9d6aWWOP5BA1fu+mq zNk{FaOMPR9)HQUl`8+X0B>zQ7(f7u3!5XR+n)2$8bj-Q?woo%;U zdKbk zUR}fc5Yx48;d!w2%=gyVerChC{kZ*E|M%i*^T3Y?)apyaeLXe$W@cq#ZA?Q|@;WdHt{Fq3P-5WzYT?sEZ$=zYVhsg54kuJt3a}>ITX9jbvWQVu z0fnK_vJpv@qyrp_{+P@x)vhreUx*ejoDX5A(^N}b7Z!on{`H#t>!1IUl`B`uZ-4t+ zXmVR--jTe#e5F!aw0IHZHqBHmO=PVjsKkv9w}D=O zTV8zOQG*49hYM0mQ6^JkV}tV6_rgEjN#SI`FDx?169t8T_0=~DF#QKm$`?WQre#67 z2|6%OwmwV(cmB(;TmPz`}(Y9DCqGOJl>Er(gCj`+}((tTot_ zk-r)&1ppOTr#w886qc4OnFJKVH9-8b>o2tQ?4x8aF#XZ=Q3YBt#<@syY}iSiAuZTp z<^g;O#JHhb6#UbT@z9L}mTok3qa7$-_adMHZtBR%#4j&W{m$O1u7k>foYU;p{_ zVob&uoht}FP~EiYGaP7UEZs?dnZ3d4!4|>hmqS0i&a5B4qdzW+nqOS)d=&KK+*H>k zNJ&*PWGJ=Bk)y?OzNk|gdne&-E&wIe3BCl6OYlf0rrO4)aw)I7Dif3aU^&T>MWCFR zg~RSt9C8w3+c2lMhewb4qZ~YLvYmNW+mU_1l=)uv2iA$TY-`T_obS0wAj|X~01Bs0 zpHkUL+&oN~oCmOMIu7S6Wfd$pp0un>u1l ztQeTV`UBG$?zk9@*VHdRB5_<(cFt+EH)T8S-M1HZUl35*uztNf`skxFcI;TRbvHgD znU6}geOQ<7d5q86_B#0ZWK6gpNEAZbc0olsgxv#d>4QMwriNr`XiSjGYQI$0`eo0~ zld@yq3CQl7AXD=}9XB%v;0gLGIuZb9V|kKll|1LpQ^SV z2WqN`r*b!{gilP2f(#|UeDZm%eDVe4++aW0dZS&x<|Zb_Lq=2v*zY>ag-74QGLiB zAUddwhn_EhIh@mRBYsjCVZ6tIFE`E$iZIC9X@`7IieY%~-S-qs=3F@etZoDm9|3hc zDbprGIZQ7;F4A(IqG5Y--lef)-MR(9%Ewzo!+W4hQfYrQhK7hqBh(HsCv-2lq^AoM7%+b^-Ooqh2D zdJ?1;0e~w(Y!Tj}jo(Adcy#Wv_8kef&_ zft(2BWTEYEH;#n|qpocJ@8wndUxfX-ty_0qY@g&i?enNQy3x>$HoUKMUb>gYJ>Dok zk(T3<1TK`5o0XlZXS{BFY~Y#S=GW$td%_L?kfdUN=iPUen1n*P2b7`2fVPPCY9o8d zuOkX5X}viUpY1qosO}yJv1;p3a$*876m+T^cx>WHsl?4VsgOD$1Bsiq?w&r$$;p8_ z>b0_H;R1Yhg1jQwH(q~3?RsqT{_w{?;tS0JMUyGNf{o6O*^W&Lg{l%vdi(9Sb#t(4 z)hb!Ec(H2Z83#56fFZNgtR8`mqL&YFtjpCkLdR zAnBi8_+u9X6UfHHI3pXBQr|HSbI_0MZ*bS}G;G>~hrBZ%?sV@?nx^hmy)Py|Ru3)v z5f>b$LC`Y+tWNQuR^Y^=3pLt!)I_cU(^t(q+t1i;+=R34Sf_lpZE4%l{X85$k>a&+ zMb2TUE7M}W*zVCh0l={BsV<&}PHsrJ$)KQrzPIDrY`i(vSSE%aTA3o{muU`G54KG7 zH<(`&pNZ2bIxzLla2gK_3po<}%v(_%4_2FaIeV6>tV`r#8RUxiAj89xDN*S6xhe6I z0Wc{Ypi*r^xfEAjk<7Rrs3=dDd9yQR!P4<5XFjMXX3ET2h58Xh zsnjsHbHhQyb%AZlE9=(XJ}fJZ7F+N7f9PiXst?>p>O*WVGcVCEWxNExertHnL*f0- zjxU0-rrjg^`Q^oH#;9p4?mej0kFv5(ojM6&(LaLf_(z#NYnIHOJzLhSUL)LZWM}8- zhcS+O8{W1e`!MUa-`w2ZI@F9u_2#Eac>ps}U=QVV6GfaPT8~j zg6!CTL6Q@x{j5-CP0x{q^KjS!H_h=AEpqZ)yMSv<8gC%&Xb6Ol!T|MEh}VBr7Eet8 z3)oD^r^KOmk{^JWPr9)0>F!1Tv3DVb5_&1}Lcj%ANYUpL$EQAGbHwZhR8t!JIQn&f zr2OoE05@=@ycn*Tlyl>Q&~4L45s(y06s}CRA3x;I_(9R>18Y)qFNB^~$2y7vr0RY+_%tcTF2ew>l z>*#yYPx88v4s>?bS$@;Ql`3jZoxe)u$`3n~6Uaz;OSLc290UFZ}`p0_k z85CXAUdFm*T}DB(SadAwi}i&1gC;Yt2jUkz3E1m)N>@*ZG}NU?ZDpohExG~f&?327 z+yN@k2~yh)Kwmo#>lKmF0t_1;>y^2a0BF3eszm(?fJwZ=H4g3S0YFt> zmxzyniPBtFD@~=fkhhg67ppU*tTjPup-r&|V<0Q4MN++OD%3m{b(+_EQ6~GLJsMgR zeW<%SP&8fhL;IdT9aK?Gpj2wZIRonCAuN6K>hZE+<2V3Htuj8fM&h7du@@QW#d_C^ zzVE{rh{bvki+uO63@9XP%Uyp?HR;8=v(Ccn+3nALZ^F>U&OHp`5 zX_&m2ux!`BTIP|W3n*$Q9h&}P<6@N(sRw6% z`ZN12GlrBx2^hf<5XOA`@y8%|>5~5+Xa5&ogivnun>d7xXqdDuUPKQMpW}!FO14Va z_}Y;$4#_&!390C$NGdNcS47Yp&=Z22bCR7`LjdE2i_kCx0h#Q?kKrp3!62Ok@b#A< z(OYl7C0icdB7gqR|5TPYb^>aFvw#wTE0Qn13*_+acix7&+3`xgylBxPWtAI0ew-m? z1E9oS$u1dHF z|GVGIGtWGu8&6VY5wxOZS?nf+9h1g{XBK$KCPju_NQ@i((2a(EXgS$hH@L#B|DDad z25^2Nxw+rp>3w+o?g4+NaSs;W)W@BVPSXx1o@i&0v2N_QY)3wugD1WYqpz_)8b7uj z?>rxam3Q?0NY{WFe@w-09@zG@Tu|8G2qe<7pRoOD%x1{+1N^Gn{r+KIZJv3ri>F@A z;fIr+zDK#ln~H;0Dg;wT%jJvEFmEb|v-!%qtiyseON(J9@qu{aba#3kVn1r2JLL%Bek z4a(iyG~P~qb1tPZ<2qKADsT-t_`^X3lqf%qYZNII)~;C#cDJQL$|R*ubWU8RemST2 z&&Q0{&LQj*cCN7Q?yJ4G{i(kXnRUYbj3x~BJBDN0rW@LR7aqp?vF|k$e_*Ve$#;MH zHcY4=4H67v{n$A8HazVIH(om?NKHnTMSeUwd-jZ+2B>uG_%VPr#{nMBfGvc)tQE3q zMspnmayD#)X9&#>n}wgLcu2!hbEpYV@{5Cn$} z{m=;*4f2m9aq#a0JCdyz?UQ&P@MCTX1%P0}IYxW2AUzTAFQcAlxg-Vm~Z;-h5w?0m5L5ZuE44rD?e2-l7Rn;mFg0C=MY zz?!#x`*-r;`|n`CcUkvoJXlgI@Qmp*lsawG=FQsfeE^cUCm^K~=P=WcBJ~4;bEqg( z1Z&QNwvLLyev@rZXU-J_=m_cPp3VpAt!&JX0FY{Ww`PjunfeGiV_XualW>^&Z7#@#3 zix~HtL)bFdvyAa!%4U7j4~@NAclXuC&#Sd&Z_r;RxBuI@XS~b<_w1}kbKrN#1@VrG zoCqjzpJzWV@ydO^&EM^$I~r#AHDLPyL)t!OW9k1WW?hCqmipsopXdjN%pTuxCJ<0e zO2S8Dw0{>sBhL5C3;VhmhXAADMxv7wCr+rGO@37T!+-oyxs&vafc}HwezURN+Foz= z@zA;4GeAjehLsA-3a4cBHfYmm26;ILaY|~6k{4PQf##NGu$R<><=~in_uaS3Zn9#< zN(GHnyB7G`Kl~y5GBKaP}sX@o6uC9if z-}6c?`TO7fPUSVJU-~AnlCmAmI=6~czi%pwp-i=A$#$hH5EW)}MG?Z%W3w&?D1S9v0ERt%p z$ag0XBimY|u@71UPFvC+MwGTW*_kMSkNu5?UmoHBGEftx9c$@ho09KkIl)GF$+f#W8qtwcVbg%_ z)BsQ_l9^Ky@!@TztXP&U1rs}EY)&`g?gIrlsf*0?g&h;}WDdwiUpe+Acun>bf=M3A z;t4l+N5F}O@0IEXLXv&3ETAbP`!g3&%q=*Kw=^dLAnAe(&33tbtxhf#)dR`^wGVz* zEf_D4uFIFPnJEH79Vsbkm2dW3m3@~gB`YNf@{1B>HTY$j3EUYM{^DNSp7#WNvS7zT22cRXARw6gN~at<94n_T#mIHA3SI|bM{r-F2=Zh7 zVX){nnUPp8`OrEx1ASv!VJg`3Za`#2E2y);)(2KzANGsA1eDMo(F9&#{R*VvmTixE zU{rScvF%4krxbX54~;8b=7mP{!K~|;bFXE_ht9JE_^_vs!Mq$ziZt(7aGjAG0W5Q% zYC3(a55nMkb3EPGB zn1B-3;!xwRWiv>-1 z54S(}y;=L*WkFuU;^%X?n>!BMuDt4;$aGmI7UV7)v$qGu7}jv^-m_~HwB6dU|M0uh`)e?B(&;Il^~Dxic3f|ElNR6&0D(MR$j zz$Xe%-Lz?=EP%YFskqO|$})fw{3=BXI#KwHnv`i?Adt&4qY145}vh1sjkt5|+^Cp-mz9UqTQoq`M{P)6_DzZZ6&vb)W}2dH)H)#}nn!h_vWEx|3+mw1v_|q0pKIUQzsLWdu2vJt`rt#$kJ7PvSbw~bwG7b z&2MZMPPxp8WoNVUkxb_FB|WGK_G^T@XU3J5_Cl>zRvdHSdZ{(e_H%OPTutA@18$tB-9_bi9Oo~S9h`)lYM zlOdD6;bqbt594S1Q|2<;ns@-kT2KiC`v8eS2s-NcVIOkFA@KoHsUA3RP+oiOHH|}A z-d-Tf8$UX8EskKEJ{RH5L+f;J0VP%w8iEH4YH;I$!jCH(Pe~6^@nnIZrC?O@EuKGr z4#3eD(7bU5ldl)@I1;50#1C!cr%fYJhdy_u~1k(vi|6n>p1yW33$4c|Y(@vWIv_-nhb_6?L{-`;)lxBvbd zHi30Q!Cd^JWsP<~ooLNu*8gler`w-SUe;ldYjARNI=S`EJi7;>bq`)`=7SEd8&gCr z_buaa1$kg@-Q{x1aa(zF$AbvS_EJ$^q5U=$6mk^GOiN8~YVIVh+sfc*ppmSB;P^p5 zAc#nz>=f9mqaNr>DyS;c$E54rMaR}JP5<>N7eZWPSRP3*-> zJ~@68UvYnIksSx>6A$ssgPlk zEl)n3C+jzjgHS`Cq^EI9Z3YJz1u>6ffyIGYkIu$fqYmAJx?bqpd-J1hhx)MV#wVYC zVm1jlSWcfl4J=Q~uzoxRwzo%uU#N5*$9fZ74DL-ADu33+8yC;$FP@U$dM)m){H`qKgQh$@&;^$0B&L* z0~WD2-?}P)|L7`20F9AJW2VUZC28`~GqIAN7bRye`sCz!25QF7B1H6+M!b;FmFpe%ZP)2f|Dz;@}-8 z$By>M;bV<*;KXG)TUjUbrxeQUsfDt1VT>$Y%jPbS zWs3Ze7Sig7;mc=PEOG1kAZ}6e=t=C@%pm+=#*Xs1cXDYM} zPXw6t(n~MNOHi~zEstX|p^yQ4#$g#&A?nD?z4%ph2m4^KTlqbpekS~Ydh-C(2a_7= z4KBVesY8>VIFuyEk3`9#Q&;5RxvOBMng)y?mh-7b+a}Sz2FZ%)mHeDcnVt_#d0YLm z{xKgw{RG%VQ||C4G@dG=>eYFKHC(002M$ zNkl9Q{|VaEpZKu`wnf&ixD#fEjR4B88dt{%!@a?J4~-Lh{_Cp380fW5m&>RZ4; z5HlIVzQasn{+p%{~zk zvh~3H(w+Ie4&sB-(o*G`A+Z6KZIIZ3n%+!5Gk!G-Bb?VeDCWoneSpgAZbw^K+n)A$ zI9H7i<+J-fek9-rLsBPYK(jo7C8g5i;N#eJ>Vo0=K%q`~dVBWlk-zL&j2Mm$*|GcCgw`SkI$Gsf!NdX;Knb16p}_z>B9N*^6j_Z zs_N!mkZ6-cap|%pvUKTEWqJGX!;fUeiWTzetFJ1{n@#`#l`Npth{ojxky_r~h0G<& zPI>_w0&0XC3xV7zpfDi28y9wEbqfcSm{;VF>}t#_js0agOvj?k1H;C~PW9ja_21}J z_3|Ho`V%%FM#~#jjoaDMPQKw+jr=x#-0`qpX>5J-KGNWWqfVfFAIaG8_8KvcNC6*! zNk{W)^MUHHb>dV_q+Hvk33+Ghm32joF7C7+i!F(!5ncN^9beYcp-O#;4{@pr=_PVNwm%nC>!T6?KkdzcfSi4mKXL_ z?XT>s5KO`H;YKazI38k-9PN`mdwb;2kybehHkz77$Yr4cE5NFmS&(6piLZAA)uO;V zUJBVRm!ttg>vJJkY5t5c@-(OnHf|aZSu=f-nQ6Y!awICC1Zhj$EbEtXSAWo3=h=Qe z*EH|JkDceV{ZJnq>r@~6*=L{08*jb=Ao02s6coskB}?R~C!bPE6>d26K#A%LnR5oo zZ*X22#NX)adshRt{n$1Q(BygofYQ+;M`XvYow5s-AEM^YnJX4hnmB2qqOhDJ7-raQ z>Z}v&?%YQZO!9-}%Zw4a;e!}uzx0q=&H_qB^0$w#0r$xOCEz4kzc@`^1fZ0c7bWKa z0H0DosR95@1%?;c-Dm+YP>#}q{1kcYvDvbA?L?V9GY0HiIM`yWW2=QZi*o?_Fi8~g z%!{F-VQ!2eJDk1@9&xR^DF_e6l)*!K48S(9I6OPF8NL9h(7_HHpzNZ)B&jTm0#Mf` z`wq6sHL&Mhu56I0IT?`clpz})Ne5t;1~CNyoxX3D{Xf;p>1!oY3aYV%Q|3Sz_Z$F9 zUhLxlC>?K-kG`#yOBFTHlvXP_shFD<&6O34rpc0(URko-t6)+O*qP8kx~Bw(8|H78 znPoG3G7=~e*RgUj!U3g@_745HNsXSHHg1%Suyg0lQ>8AHu`z7J`B!TewX638l%TjE zK+v8w&blV0Jm*Nx$3AGEi3k%E9Ah5Y#?VirXi_FJ$?ld|t@;@duz) z6O>pP$k+G`uWVS?B9Clr1pu0(HV*2~;8iUGh8eb{1!&No$O-`sQ%wwne>~DgGCGDL zy%@-i$=zfSxl)YT7w`n?AZA08jLudf9xbFGk{1Wj^CXlzuY6ebqSn5YUU6>31=x*-V= zAfGrPOCEh{t!#OAE%pSUWC3>tD~W38Ln>O!%Swd1>pb9;4C(gw3)43Vn3;Cax_5HM zD$w%torYn=8oA?xPv+S@FKM4cSkw1{UI)C>x&>mdRuVbArEdihe*0)T^$s?FRP=VI?HI?A5*W1a%LmB2Cw9Rnp z#rAO<#qSX@T4H!-lg~=O{FodtfWD^XJaXci(;ott(`y=mp}JpcF}u ztX~UF9B<28Z@ndR=gyU9o_D5{<#Ra4dxF{Br0c#yAH?Lj;N(TK1mKo(ziX3x$%Gh?|)%|YEZdO zFTe6KHZTz0?65}I@VwrwNr~~;xNN>`U0Zi|x;AZnhrHipxahdrYoIu83I~Vb_>C0) zuDG%PXeVt{X3&2A`RDTH+i&WZ%gLZ`=|uqL#j+kA1{vpP1r7A53tZks^Fu({(Yg8i$i0dv=NnV1Qxq$RU3H|2u@-7E882`2SWlO5+c%+myv zq9FIi3_(Nx0lWtFz%xD$3h?*sSENvSLn)MM!JkJNoHPWF7DB@twF#5$@zE_?^rMp2 z0qTqm$$A;QFPObBTb;(VeJcQ^7Ja_?2Xk_7jC3}q%JsS!`SEzI96ABYtaDj%xFlP( zh^1mKr%-h;7sIj_1!N2;mDVk&l4UEZ(B=hDLQ{YPQXJ+j1NRf91K`p|?p{b;O!61bjvfIm<_llc%>y3k_s{f0K-8_Ljk8m1a%@qV_H>w6m&(IM3*mJ zmT}|8skV((YgVhaw>RH>Q{H^z4V8mL*%phJEY>f`-1t)* zUGWrB4p)6girm(v4TDw=_DO;XRh89B(PkDIEHnTWNDj-rf`)m(${wkV_rs0#$p44Q z*gg;rD8*o&BACGWgFN;sO9S&5i>E?1oekYRD{uI?46A3B!W&3vu=9v zbXn#u#(f@g7{=^`i$* z)CsARltSrqQYgKN`Mh2xO`N1Ml&HCL0}c=IkgGuUYWwBV&K>r8tE>;?XCU`m#Wniw z4r{>aY-~q<6e4x;Dab-R29~GYpg7*MchBGyN<47ireVJ)dzg+%-eZI)xC+V)64zXB z?32bOpS=BgxxDs4xpYIeQg&jRET5kyPdu3-Q}W}awA?S3uXgtXN^xM_i5-tI3y`9x zS_*RF<&kAmprI~HmamM#M>tRrajaq8BDi3uEP@4^AH34>sQKY|G?puSzs0RS(TxBE zfn#1tT|>Z_dpl5Gf!)mq>Y3(752%x3<;n%W9QvtMj-P3g+NN@;X)c#XSIm};Yv;(k zxk)l>b~F^5TnDRZsqFfxQd+v|k$Sf*oUuR_z)qVQ1sg4gj@QZO-6i6(mQa=(*M?JGF+{c-{9Nz&@`sN#X`^~q| z{zvgavIc^&4ba2==@jfOCr_Fp&prQ~JpcUjy7%P#&v0fh%Z~~G3}8cytxR>~YN)mB zcp-IK8!R-3g&Bp0ASj!f={j$u%8llDDXoSkzp6Gld>~$aIGiAL5Gvi#(+T0xJme&x zS-qgD@quayS~s(=A-~tK@0~4=teu5DbfRQrK!rWnw`gp(^s0LpI08h``oLRlZPuC7 zNAy`;S#u^1d(jAQ<0lx8){47cm_ekWYl4#&*D`*apf{75utMCN0nYEFQ1SyHVzY3K zu7;5Jl2b)ea^;#7S6r2{>S(EGStC`Q3!rfjX9w)%>){{r%Mp;85W8he;Ji$a-6fOa zFGw!5AZ8}TNZj0M5;tcmI3^6&L}CH}C4#c79qnxH{Ft(7zjNMcy{ni0yZ#U?JD=R| zP=4k~-OxVtqOYAa`HB_8N8Zr`4g6@Ib4NvI6Ii|QC+OdC2`PgURnW7&v2off+-HGj<0?J7(1BDVlpecnCs1lP?lGN%s(N$ml{TA`r zx^dOPu=4Z}dmgNfhuWTl#dEi-$fn0}VLm2A=|{vG07~p2+~-rQ1%XA%$>rXF*aek$ zkebbwOJzZK849I;{No>^fYRM=sPOpMaKXmIJxRnUO`i?H2BIPR2w8~iz@}gSJT1}SAGF+EJmc<+3bASD{*Y$v(nVG5bEw*jjhRxC(ZF~yY+P-~< z?AWmb)FpLlNv=%6iiObF!ovVr7VJb}^Jq37&V~RJ1vd&l?Ckj7ppyNY1$HW0i*yrE z`paJ&Kna@XNTI~eM+EdHV<#V6ZQAyFlixucZ0EM#!k?{s$kk4QA&y}WHjmb?y@tDo z1$*EgZGP=_2pQCaBHG;cN%luhHY9sYNlw8c15#L670S(cZQQnwhLFZD%8RX^hoI1Q z9CEQ?`*WVM6iQ^pjfUlXl@5V@1jB>Iw!OPQ1YeH84b!t}+UO&s9V`#$Vh_P2e8*NT zL;MD9sFMgPwRiZWt=%u5ebFQT^LCFMDMMt?iX?piltAeqAp2i8ZwdgV$&x$HBV)&V z0NPi{u6-qPsia9-JGyXqO_ATeGE1I*CNBsmVQY?>?8Ol-0R&MHIBNkVo9FQBV0~q< z_u=sk^33|7Wn0rK%Ny9w!i$>W%>SC1;n_+VFcl!wS)A}2jGT$l(rALH z7j>|X1eChqLVaMNh9Dz$%-GLDD0F)Y`e%{?WWCsvZvUze)cZauDs7c=D2wUv<0D5* zCg!h1X+>Y^_JLy5e-12g=j7SP7Rr-PE|S6-sWNGT7gW{C%+{X^WQEjfmeR*vFRUlh z(-=?*5B!It={d-+^=yk1T7=;}*|=;d#_5h1_vQnz^?)nGgom@Q)j!8JfJJC{qp%jTG&V1grjA}|>IMrO35`ghQ zmyKo{jsurq5@nHa<5pf?u3rQx^ok3!H-@Tvd9dk_)|MMmQd}bE&YjZ(-Rjk=02(cq zf~f_tQ&j-=K9HGJR8%NM5XlqC{x%M>k$SN?WI7ivT#$_-m+;APAis1E z_Zt$?1M)D8Jlb~Wl@kpooFJft!=r*p*u~@VCV_k z`HJ%b+usc+DaktAsQn=mf?4CCSB#|j)2l8rEVpKD*+{C5pk^> zgXJZppTKkYb4d8`_6>P?2M+_)<4C0!DXZamh?I7?pGfiCiJOxqzd&~5V^>{mt!jBY zar`*IqDch3+C>i-f22dgkss)tZdaYLe^)4u8KtY%es^^7;De~xJSyC_~85$@9 zQeD+8-|a4zU583Qos_SIM~#vaP= zu6C_%{P1e4p6}g$@MughEXR)pkI2#kz=DTyM!*3Ldj*2S_w4KgP}45gN*krBwgG#- zI*CuJlgBpBlgBpAliVDDv=H?F!%tQ6x4)m2T_?*W-rFTvkO#DR%_7&L zZ1(?HA)kDE4PZ)#WW>ix!T2;;wG3L|mW-8I^Sm+>R9G0&!7^}`(L!jR1}G1_eEZF} zDo%kEYBjYr(gxXZR1iZ-Bu2)0;t42rp>mhmvuEpGG&w0*KVs6u;D8b{!j**?q2ZNt zF(_fe3@MZVg#bk2!6im|yD3batU3WXao7(b-2o`BX^@LoYN2^7AUCMe9`mag+BB(y zuBWdEb5oJ50XyN+1(X4ogpaYYn3JLOCe{ci_aQ#klgS5u`|toTh3#$B&EuYx$F4%l zHs@StdxY&6wm6LHc8!h8h7XSu&vvf1Ui2Cgj)CaWxqxDbU{W9C!h2)zDFc1Jt)W(0 zsw>b3tEC9{MP*(ozBCu0Y=KlYcS}hdsJ{FFkpdl(0J(wLphlgTQ7Ka<9s_V$CF5{b z$-!YW6|&S)04`6MG(jj=EiMKu-3~=na83`&8}bzXtOXeQ56jmb zyR%W+Yq)8q|l(?FV zq`@S_#^L5d8vuirltYw7bLrA0e2F@&fDspK+IVaX;u2z@>8%fZi4Zb~%{s%8-EG~v zbxMVlmXW3aQCUfuQZ5}nd_)c&I3P`kmxv-slY7DMNJ=R3ztgT=WUD5;Z>%Od@67D4;aNHXcSB3^B$L z^A_v_m?YT#Za|3}dcLQ?#_XJIrF681C;HVs_W+gE_G4C-mdisxsSAUH6cLz^ap;VK zMj_g!MryMIh0^DJ^3V5ua;DxX2!xYLPcf9#)XNjArvgwZfYu|ZAD`rrA0g-D)6a_K z%#{|o(dn1GtQ2|mg{e4nO_Yffdf|_N5(UNrQ1XC6Nm4M?8bAq|K>GatZNB*6L0xW| zW=6O^Z5?U*p$!|r_S8_|7?;ug#_G|4A2z@{EGL$@6Ket`bTLpC13Cc&HoCF1w!16{dU-t@70u40S!YI@l zYYkYI@QY^<1-byG*I%obzr9PUo<2zfmBr#|$+CHCmdu!)EWU0J#%{NK0f6P314S58 zDHz(RxMskPfp*+@$%(fWWxGo03O%${=_K!PTMLN{*;~sJxk9H}w{z9*u z6FHv{RN|Zhi-SB__ZW`$#PL4)0U4i_C@(*|SYCQ=F+LQEbhZcN``zX8{?}Kfs;OHhC#6W? zu-0p&I70lGwHF=BhUl;7pbOvW#$Eeg0AL)!q&^6^kBN(d_26vL z3ZSr2np>OXI=CUqilgM@;Ryhev!tl5TQ0VAp`Pm{4mJ;LPkG}f$c%zsnLW1x+M#bq z62=q9R3iFa0&FU@o2HIQQ~4^WBCVO=oXY%%lp&bWJG*gJK`O6M?Gv^XIE2Wm0x-HWmZ$n$v@8 z@N1{#UdS=}Ue_g;C;Jjt?T8LiY4YDsp+q?he+J9jD`0txs6Ecc!>E}J=7qP;mG{FL zMB(AwVfoJe%(#bYB8GKOo;D&^8LZR&z6Q(8{F>?=QkHC8@~Y*>riv2|WhhlwQHGM= zXnvqj=21XtNOh{7hS3H?k91^w2KxXyjs=uRwL(k7_aT51Pk%5EB%tJUep@D-Fu?8x z77GAN$T2KgUr0F=k3J68z6Kvy-hA@U4}EgU0!n@YN<|QC+aOP_ohq9)6-Zvb2lKH< z4*ggoUw&RLr!O>1MN^MV$Vif3KR*qC(gd(q^x(@a0VRlwg&c~0K#6QUtTU!h71?|? zhAy-r#=Z=3yn7E^FKGG!C1?jlTe|_JDO0AXjK1fedmez&#t=YB0Y!$#ru3G^c^y2A z-O}^Ozts6{usn}&HinXi{=R$nGox*WcHtV%4^g#Xk3V_h#C-ykI2x&mi+~cuToX{b z-U}H@eexCnrGLCvFO2|{a4wc5QvoP#%97c0QV>EwrPL#zd|4!4>@7khV7;M@&IDeZ zgCQ0VDvN+DnI`h`3to9_3$#=wLoITWCEf3@S8hQt>-9U}j$I_wC45Qcev9)7K_$LJ z3}C^6E_MJdC%6!N^idL7WS0K0Vp+S**W&dfExAMwQF*%=o$c-88Tx= zp={W&LAGw)s-XHoGI=K;kj(IFo`9)J}qJuXq!&Fw*+J3+}$c~D~@11bR&JAK%9 zQ&2f&O`+w`2L7H{^h4}>xcA|nn7|UNll5nQIrO*7(P0<+-90WAb)5)#dJy6pjd5#4 zy}R-go;~F3t{C=%aHG^waC9Xf;w3_mkoWdspz!wnVAlcCi8PN#S~IObJ2wxO+-<*S z7hyf3yiDtsfKsF~x!qW2?&sUi)WaFjwwXKkk=oY%KKwpB4)^nL;|h;E{Mp9M>wtig z%22`w8OTuLxsUriH+2%@B%svM(Jz#n8i7ZJa);OUNIY}E!BSR1HyWX_@wyaYaV8>s z<3=04{IofXRX`8yX=&+_4gSTkW5=rSLxM||UtOt!Aj^ga0m?_Js;p80io9oB?0f{1 zva+(&G7eHXk+Otf6#3!p;Mb1DIYn1WlSeH++}MHK9WT67^O-g>p!9zrlp8XXbfXcv zxd~P;Cm^O{eu8Q7eRx{IFhjVxldwaG{%7sQ-QK+CA(Imh!Gx-+DxFveBvB~yD4;Zq zuE4(jkeFZ}z__%466NZU4T{qkzuu;kLJ9K|=aZo932wYOk32|aWriK2^9&AsMrH>O zfCN&|zac1_U{7tW4+rW#1(g2&v0qAYa8nZjP?|o&BZYTD(M_eeOBguxSIR z01Q>Ft`Ypg&vu8gSAB@|LvJHko=8cKx(!kTXcMmCWP2lp(g^@cWO=&R6iUn`KBwWA zEN=vqL>d4n)x*C3dV{?29zJSx_3FWYaUNLSHe}(T3r(XqD0e~j%ln@d$)~%E5gh95 zAxkF+D1ll<02VBR%(MUR*HMsf76l3w$cO-_GD;rkF%krghl9>}FS&+4)dDmb3;IQv5gLMwSh6758I7}>q%+9>LJo(|r zALPfMew5tYTp61?7Qp%@dHSiR^cBiAlkMZ8?G@SOuF(G`G_zZWo156XjaLQC+I6tg@eg0VmP1CPJ z*;&~NFfp7t5Sg^JQ4udy_EF6vRX*|{K%RHXIU!{d`5!6gggoxa$;k>N@qp-_5VTX- ziGlf~;gxQ%w$ss>#&#z2WS%LgnVR6N3?)OMWC0~CG$etJWNaFmP-t4==|l=XklUSv z9VpIUlDqab_BYrNKncJl4;~cAJPIfcvq#u5Hq2o6!@C{xoNp|kR7*e!*2tCc7z(9_ z1yHi{8Y+{rI{eru8<`#4kaJ6p!yjx#RiBi@e))Bu{Ohwmsk+Wa!(qe^)!BVlB{{ZU zwym2c8#hmrX#kXFOplUNCmLn4Vqn z<*oPYq_P8!=%e!{rO4(-vSj|;6iH8}oR~iO_{%bRcV`*GLrOKql|+p}RFI`afC*+6 zv@-twe|f;R83iB#Hie);_-Mm{J8Trvi`$ou)sX&c040zyBCHwj9zSHI`I7J&a_HpGh|eeH_$r{SUoHa!oWXP|<(;tz>$ApZln2lIEk`4}MH5NG67_j;_hQ9voAYVPNQ-G4I= z?)$r)CmZ*j07?|iLkcCX4MPT$v|udU-7eAnjn9KG>mynuHkfW$IMZ6gLCh%~n>Uh+ zQK%J#X!n8K+++qS`+)ir5F#I=YGVVnQF!I^U{CF8Gqr4HI{Bal6w=<+unJ{zzDM$K&^vvqLH6zhpmeNB&R%VoM9jIrdKxTmj{#81>y=4)M&K+D zniTv^;EKnT2L(`K4cPH+4}rr0lyqIPecM&fjCV-Jh8>dUQBNaM18BGV2`KR}Z)6a0 zG!kqz6iVF6)CU2j8hPh^C^Bisp&!&HGsmUM#x($x<|Rv3CdM$ROTPG~T0Y!eBkiQf z@Nv^c8A`fD ze6>~1pRI?ipDsCk%p;e}pqAa&E6Irg`OV8Y@~c;~@bS1j6{3!X`ehi&E zZ@#R3WWB6du|k$CULcbonAx&M=w1_*qjL%?iS=a1y4Kk(GC_aVFRtd%++eF~_9Xxh z7!BD8yD*hsy9$BlKSDDn=Ha7fi{w;AJrJa6uv1M!jKp7xo^VMPPK}p!YYQO@Dht$A z9Wo^!Y;jI1QJxgwE|hae*?JT{OGt_NH|c46Gp?bS!O9sP$57(c_GCcEvtHZ@an+`y zD>BGY3Q)NO4ZKobna@v3KOgpXeyJ=EKp4BouDt;{Qvw-EwO|$OMg8?Q$maQ3^3;=1 z$bf!TPynt6Xdw(R53po$qqV8?YVU)o!@;^~`giNcIWuTrTUm=O@xL($Kvg+Xx+dltL*|CEXu4y9Xbs)NTB{4i``&B|F2BL#hjt?`;E0 zEFAm!&%}%M;?#YV-*;SKfsY0!~{R~pc1f+b}aj|hp0mOyd8okq%4=(PB z$=!JL#C!luvU%k-5*TCM?A4~DSH#23C=Z>xcI}eC{N=CMY*2>MAQVbAFU*6pIM^%W zjhI$Q!UI3tN!Wp7{pGx2J6IbDPztiVf$fc~nA*o|d-iw3UrvP$rKGlghT``=`?2GY za}?X(4Jg^H5m3s>%`rl`A9O&;$+VesL7^laD47E&1+dZffr0_{{FQb&d#PP^@A1he zd;E}f0wCXmlbNR-2ayYspHU-Q9-Sqdw#<^T(DF8Ze3YC$-6#k50#G{IBquJmOH6dU zys%{|v^GtUg6YuuHiH{?%ICo5T>&LM=^=f7LB>HCZWPjunueu|u}+rFWrX{Vd#tm) zZwpY0nDLNOL@vt+mn}jLMxDZIz*)oZ7lo1mlt>|BMnoh)>EpNS<%19FrKA-f-!OEh z<|NDd6uQi`nVm9wx<_7kd6vBRZ-sL1 zR6x$2^n;qDM84dA0lDv$rL(hS<+5yfWFurTEz86qA8Ma5-*7T9+du+Jn9Fo_=`U%d zyM93FBo3I35V)NqFTC)AtXj27&YwFEB{Jvb%-Pd&8g|m8DY9VUVp+3#H53)B2RJhW zDL8*fnENo!C%PZw{9wmA?{8(SKWAS^uj<4fSb|Cl;_(5^M~eJfumWB@?}PlWX4(70 zRr%>mom}@7NROwWKTvNK5U3IeIggVS3-ZApm>m&BkAC?+Brtdh}Sk)$jy zLoLVtVL>IQ1~oIx!!68UWsDT`cH<2R$5oCFE=PhbYE9kw!1C5d`BLa3(EyYx%0#~U z!UK>}u+iyPnw3G(yyu?)BJ4XsA&@>A`AeyAL0!TMPzym-@g>rNLi;}*sc(q4Q zRLSAvmGa}!c-e6#L)tq)P2{0`qZ^VLb3qDns-bp#jy$?;wq%0zKLeBzm(DfHp&x4H z$kApwbgBc|h~i}HvV3T68Y^=bb;-Pioj9yO)lRZBa%XdFr1aQ<3D6QW-9zwY@F@FHW z#{5RO+OWFaKA@C4Hdp@b-(Hpt8`euL6u;2!*tJ8p@7SUHfV?UBvKoNW6HjcDMGF@~ zI5UJagFMQ>45$)RvHPC2HMlYR54S(7j$Wq;{7`cyfjgxj!o1qn5+!vt0SFF={lxm27c=Nr%rlT38q(TQ}X1wX3@zULp;1I@sMn$rS}_ z^2}c|Ut=L;QH+T+R|Q{MPq%T66mNJmgQdg08~#k6w1H6$d^k~eyr=vmpO7jGy&rW~ zTI`WeKlRCXJAG1A18sSr3Y4C507~VuqA*uBubmF9ei<@%u@}PLNu6Ng^C17YC z_1C_$Md4Q5{odvE?%&!(?|#fb&lpi(x-ViIp`k_rrJrXrM=F)w^YNYC_uX?q>1Q@x z?+u{D2D7s&2Cg0z8@yVm4(Ix=kT@W&y!VXTrE? zX6J-51VG8=FC<^~0dW&hBB`^XQ2L7s3csI#60>&8JlnjFUV}B@?niWFo6?Pd68jSY zrAo5A0Z<}U5~-BZAYUOlg#s)QV1RxaOyHM(W9#Q3s0TBbAj6zD9(F(peK@3VA@^=xmKsyZ7KF2zI?Fr!S3>Llt>oL&jl*0<%3WGBM%2Oq*0Kk8hhJTb`T) zL9RH&LUzmL^EkX5s)dG}7Wv_LCxqn2$?6%CW%;}uS-!dr7Hn{dNl>v2IZXulVf3J< zpb`%&#*#vbZ_F=!xy%Un9oyb^{kf+UO179ITt=JB=ruwOa1Fl&pfq>RTnN9OE1NcN zg3O%9L76fsIHrPon+VYk)d?#N1pS&35bb;nGJp~^nmIzbcYN!Y@4oZP)klMg>?koUf9l=^m1U_f}cctD}#9g8bKTYncQlmIBbngGG_ zagv)6CAk2V44}ku$$Odz6iRfpuW`?=Y7fr1<&%cOW(xlRl)%!~(dLzo8(yVgJam|V zQXS;e)JsQSjI5kDTb3`LDy!CdW#uC=m=}1k_sG{@cgY)Xcgm3qty0(4BDo12vT3nL z)~tw;MN7xY!e!&-$iZGY@zyBM!F{w%o1h%)&dl9T zB>k_g!;s5n0}ODr$qw+^R>458nK858^+&|@#`JHV2sqjZ#$gQv$m9tmNO4iLeE4y< ze6zhrN^85Mq?s&lWdM~*Wzp2}vT^xLS-EPAEL!Q6i3I?ZK>Wu3AA`MN4COL8hAD=Q z3o~x|eOR9(bnP$l2qo|{ix%~zeFY7~d3+R5`kA%wAjJva_uVr<$&OQd9VDL*%j^3B zC}AcygE&HE>gLS7Zbk58D_1818<*qA<${I>7sh4%*hT23&7Tc_i*z)M6Mw`DCL`4r zfek4ErN91_fYP0_yhTiF2#z+t_BwDwk%zgCi50R9#T#~KKig#-ut`-vWFU>U9Axt zAy6m9Ou-d0lm-HnlybuXD-<>A2bAoT%~4D1Huhc6%?S6w0bNTYbrl||1BcbMGc|Jg zc)6Uq1kkzUy7WQK`nC=8W#hUTQb<+ov!kW68%kPWzxc9EUVFPm4i&Y7pr%XmKw$OK z)?|5nQ?lgeLnv~7s_fm}1D0HBiz|~KE?kq;*j`ySI~{;h)?EdZPMtcX8hfZ6_~ln# zk*!;|V!n&TycY|$ye~j4_PJ_(ZEbCpsZ*zc6?luX#my+3p#r+~gB0c!?nMfYLR{ zPpVWvsZ;@_h0_5jtttdq2ta9R3}gbD0}6)C+7G5;pj{$w@p&g+}YF%m9eX^%t_ zKdU%VU)&#Q`=Oym0i~Z+>ke9&@O|GXpfqTe-O|JT0hE}f@QKepV`ApuR%6|q$D6`f zcU*&$f}Po&IFt&?9SIufq%d%k^#Ro>#ZEfD%E%N(WF%0ael{pft?BV*C3rgWV7Bw*8s*&kj)XP-y`- z)VRX*bbF+{I9kezz4G<;6Y}Nu<5Jl&Q97d*V85Md=4x-V%+I|nb7$7dR)9&5Jw8*z z^5?`+2<3(#;G@Sn<>VES#;yctlggIaIQ(th+>L`)ms0Zat33$)Ft#YXms+8iKDYW0 zhL$(BImbHNdz3;c*u1}t8?52CqEMO-;mfqt?ziQ!tuk@KMD$!Uq3Js7>^E+=vUqGK z!M2?u*%y6~%SJ^b*BijX1^{XQet;%;*V?FZ0 z`UzpWDPQ)67xgLBlIncs2=fy ze6v1ii!Ss@5vXKp&Xr5u*=x`MSt|!>nBvD2)Tl+rMGXdt5bpre|cxj_RbKg$ox{&c^E1Yh?AR)v{{! zDw#Kbp6&_#pk}6g&uA}M?rvFwTHgL2vj;(=!HILF(y-xbjtqQO5EWO z^~2cl!)#y(gc!Q>{XH>ZY2TAHALc|*U+fQTAdb&bK*yE`osO)$t3K=b=wq5PTDq)_UbOu zaPL{)!8#vq;9szRTlc)WZ9kv{mCXt$`2Z%30!qW~Dt9u@hMm}*1+eYUSRQsjiDj^T zTkoL_N&qIAFW%TULw;^$IaMb^j>H!S<>N07NX?A`>5f^29WxFeILt)F-H6SxhQlz>)UGg%ZJ!n#zJhiP)wmsPgEl!D&o<^28 zb^;!d9y~yag|QS$^*FH8e)`#`^4jaKflA~$*g*=Q$q5JHr=J4V)jFkCh>OFQeiq60 zZLSC5>kA{c#`?3*_BxQeeLs2~*&0Bb-3m~ONTFm|_HnSh)Ae@vfKsDOgjTfG3$vl! zELB#n04vUfDEa84F8T0_E&wvuq@w=X&45x?Kz{dfBG|LyB^UC~ani= zC*=SwIlvw%W{~jyPJ(UR&P)Gy# z$v4}(@HP|I6`DqeW$#h1Y9`~TQ`54X6kEL(h0iJX&!0wAG)kU$aTEZK?<-EGU=?V0ZB z>Gvk|eDC}HGxNQfH$5H3Zf9GzvL!3$fO0@65QWG&6cvAKpIfIW3WNY58>BjL>gID# z4(sl{_7+SaxHMtH1X`@SimOFeapue!oIG_>NgxT}xOnkmT76rMg^LyaQ9bag z6Swcy;pV+MO0LDC!NoqEYF^5D+YuR7hAA)?=m`_h zn*{w{38nX}3N!F0@V3D7vOmaU!M6q`v)?s+!v8MGFFEj^;I71-bz17FTnPY_!f0-y z>~WYOp+rEbS3;?h^{oo?XQmTSB8SovN+>O)gwj-kNY4P2RM`F>?l6r*OJ+b^<$2|X z_N2aBZ3hab&kdo2J~_brQguSgDFi6>$(q;U;6){rr0&@5LdxB(NV)&~=RYZ_*5CjB z_jvbb?<#{m!l&2INjrT7+v-aPl=@}l2>Qr=VT{2OQZa|cp`UqC=Ih%be$jOV?V|1QWsQxkcq~4<4}5TA1l-C z-o=QM3$+@OxjwD+;EOMg;PWpJqqbu=0S)44KMyhpv2P{1UQ4^-00(GZ5* zrSFt(#^2RQe@Q8AcA5%63FC_U)-@MyTyx?^5lz@%y^E%n4w6AfB0DP?Z@n=cYgbQ3 zc#;>kWH0XB_uyW!2Ny`Tee#kM6-}K8_qJl;v@rbd-%iBNZ7FD~q1DM+5+@T(I(WPr z51&3ob!!!-CJ<0s7)y1nWUO2{iB{KA7%!1xVzX7`;KAZ~XD) zwy0>i(WZElgfv@mLJ=S_ARal^CB!ljV2PYc4u=(`WllUQWf@$n#kK3TtQWDk+n5H2 zSoIX=C2;4e=UlT5dHe`4J(Xqia|?FvvQiq$OqDJl@03y(--QO`KfNxb%0a7 z@dqeLrVTn5H3~vNC8^^*aLP|=!zxac^{pjq>GwngBrwy5vh+2@MW6ANX{iJ;PV-+hOVKmG_UEiK5I zHUozbAV+hfRgaziG|jylt2+cL8MPk zo;sxnxkXB8!^RDGlN?F{C@HBPU;i+oau0~rK!B2mbyBIkk!885p;zTi14U z%!O_&)~~Z-#&i?*?ssC(K?jN-JfMnM3E!XrB{3Y)gUl2VP>RG`J0dV4&4dXAlmr-H zN8pc*mvz`HphZAkHsm{u_Nl9Duly1pmG(mwJtd{2_$y7gMB?nr=bgBD^AYaexl1$c zZlt88VHT}stzVT!X`V!wV%ZaXAJn4IXv%Ed91P)fqe6&c7^fRcboF9;}IEn;1$MQUm) zcD=s~+qZ95(zJZqBj?g;Tx2UM7VBcoNrGJgAB%L0hBxhl-%fIx&*`#B5snIv+oQ9lXMR%k~CfQTa)kGW`vZ0gd$xV zjP6cpMvak@N+~Ga4N6GE7+oVqNsH1T-AD-1NJ)41yU+JH-hbfv>ACOwyw18_JBsS# z)3m<-_{4Fsyr;rsmBpn1i2qzD3rRZ_|NN~eHwJ5jicSC@wWNr6%{d)qkyfM}ge;a_ z(YUmh?f%E{7d^u5%K#NXK#q=}?`}j}pBJa-O@_?mBXPin(hrG4%q7<2^S;-fe)>zF zK!`!rK{F;=2u}uym$cHunNa!bjFFq-oB@1$op&5Lmd2aZ`%;sSDN0+yhoV-I|@;c7bW~xW0kY>Ags=k3~pcQU4hL8RxG% z`G{|9LwEoEllc?C!i7v6Xok>$sQE2x0k0U< z9xk|MIkAa-|65{NYOKdS09E&%@WrrJXKkmE@pkQ-Q7&>~|HFKVG(xX~l)rNdm=JR! zuuDvSo6!pZYWaaHD;OpQ0DZHNk9=?J)GNr%i~y%t-**u!-%cze9D^Co0RG$%~ z!oxALBv!lePc9J)L5c%ueqZ94w}b^F{$`b+lq@}Sh;p1i&5_ch1-)Rm;vJWBWlEmq zO-c(_fTm`?#BvMvoxLH2h{G2~ZK2;5vsBCdYJAyFIi1g3Mhr3H#K!2n?o+IDCI7=jSImnk^l{q7wJ_Uqxme z#%(Bv;|c<9ti*%b(DO4<#PH4IP+?aekPUi73Qp&SVC|I*i@2Iz!56mPTzH-+`xw1J zsrvG`Uw;s5G;BeaCAj@j8*%VIX>uEl75L<59;5po3PAmgwRLjKFV_kZ=)20`P&^<2}&D*hizz(;R z`pWRKqM|bMM)Rp*d1I-+;L?gt;X=MlzdtYn4u_t&fRhst&B_4CcLKePr1U7^XhD23 z);HS(G_^&7RWVx2B;f6|ukdZnTABMShsUdM4AiFe?0d76o0oi^xR?+%wSg!>O&NN^ zl0uHkN?23O`SJT6Hj2^s3@q41nbSX7i+_RC(AC#7V(rnf@%jdmJ@PfRPh_cs;f2th z5l$m7`QQmKdc(n_8mSc<0JV1Y>+w!o=qP%%{b9HL@BQVnVQ7pzI`Ftn(BshF(Xc$y zCApH@@bs|e&yAzm6JJR*wCdq~;o{-~kw?Q(qMEs_8=3C;puu@}x`dF8DGbCXLD`s2 zYASHz;daYDC670{fzs_0p0I2y0fJPm zmD5hOxAMoW$`ob+kYrIzh@lktpVWdi|2RQ1j*|oA=MPbGKD$puNvv}v$MP(H5HJC^ zqkpogz|JXVLhADY!wUW1g;HWo1*TN)*E?^{Yn~u-3}nNur0dqt2H0|u-}SK|(KP`P z7?7`T@)SQ!$-8T?7PeiL1sZCLc>Mh}-?m;Sb9kP&I}AukNBd<$VT?!$)xrBGYK?5{ zasyy5vv=k|1}p%mR0akrJalQ!e(&H|$aZ`mX_O_Vkc^6`Xt*yV9{8w!`pzY>S&Z1p zF|Kz(d_~NCCQP9(t3iouFCQN9G}K>w1tB7Yk6iD?E{oXD#~%DgWUet3gGO!T@Rt;r zwyzh|GxeNOE9O#d#Jpxk^=b4yrb?>KQEeQTx6^-s7oN>6TkpM)1+f!R*hyOS9(nm? znCG!1i7C{Y!8XJMFEr#GbEwkAZN)UPzmGWHIhSNS;5#mU=o+cjGKQ)DEH9meHt^9M z?$y1WBH*-V&qI6Y>@Gv>{d@d|GWL&LM}>uZVxALr4zMUq$%69GmqUWSWaD!+dH^{d z7rQ<`QCrD-k}J2PpRfGy#+UIp%ymy2Vqzk%(0j9wr%jwndz4@hG9oH5M7z%^E01YI zaC9oq#NdVvj=;#TTvt7056EX_bS~k)GIEN0@JZQ?cs>}-4XV_`zlXb|dDrkth^)k9<`aTod zT2y4Fnnuq~ez23~BUPugfhO}(N3J(UrEnBx0p(6~ZX6^^=^>`tEKw)srNUXKWm1M- zrGK&Dg<4NAA!IxKX3Gg4L6u#Ex)W-xPEaxnK;Z(4q^o4dfz4?4Gp>j9`#1Mt%^|@s z7S~84o?O{<#<#QvPXx8ZWlO^ln<=bT{Z|(N` zw%22au3L(aw9xbJl1hTTeYA`0nH-Gyshk>6>bhmr%1r2{A!sa5aE%eS@UCZuFOS8}&i)b)3U6ZkMQkFkcB1r$rj-uYM;HNqxC)+tS_=0b>O^Z$X%^}p>*J-r zQSFg%S;c<1>XYRd9|*cm4KkR1)!nHgD>rbN)vl0)EVRUptL9B0DR@3gsQA`Yrfjgw z@I}EBaI0l@Zv)rNTjeDVkJU^wwOLo+e2rQRbK5i%3)*0cTk`Jq zz@K$>5H}U5g5!$eU|p3JmOZuz_HD7fFP`GhF(;M8GOrd2?^+EbaOOz{;Cw;N-$Zws%DfO5vI;+b)z9DP?R>- zb#`7IG+W<{>DONR^Ik<$&*p;?%v6Bj-*Cr7C;Lo8M>x(YcL}SD*Eu<*zU$D@K%0P& z#|a9-lb&P$YQ>*Cg*%e<2*}|CJTh2?>1_)5k}D@oh^}M7&!m3Y$!*_wFl{*M0T&qj zk3wKR>IH*2-hee!8zMO+uc6^(@vp4j4h38t1B39=q+-k77^;~TA3+g^xk9d=1D(IQ zx))@MZz7Qr$SR_ijoTJ%aSEvI0uzVR+qd~AMOXqiOfTvVpNNZa*?W5Uu#ar?6g0~n z>l^=T8IOvt&z&$v64Je0A0Ypb!|`iDRal<|lusRo!*29Vg8Wp~J15&pUO*qH|5$F$ zHeny$oiUzFjgh1J4KgB(Ou<`XIu^|0HMkjTpQRw-`2%;%3f zqsJ|49+-V2w@r$cv;rn#o!Z$RjgqkT>4raO(|jv@{*AR)_q$Lmtr@@3_vvujX)|F@ ze#xhD?0==(7G>;qf?lI)er*S0EnzT8abjU%Q4dOoT($7oGcQW%Lys)%yZ$3J zZ=Sw>$sRNv@(g)qsf0$h;psszK+gcM)@z;RzJRaQ%j=kPRqbwD`^hA_H1f3l8T2O1 z*d4Frcb^*H+1_YO1+iBH`J_z91%2oXkyao6ENQd0TDqrD>XgAu9h-3S*s)ew7vig3 z!2D(dE}}41Cre2}m*}s83!@8Kec$O==^}XgaywNi7eq5N zLu2Bv^$gdZs5H-aJYlzG>jWLX@T?5<)CfmZ@K`Kr?^rp={3t7nN;%Ad;y5$N+};V| zZ6CyBQ5n^G<9qHsld}`1{1Pti{G47X55z^6GrB$InYA9Qr=B}F|Aq`bPqw1l@V(v9 z_!iOpdvT=!Igfr)L!{Pgv&i3c_b63lM$ad)b#Alt3o6?E^ou98*?-l+g$WUQ*LEH| zkd~UNEO_h*0iXZ9$%dG6m%hQkCis|cdVSMYZDL#_wMI(dx{KE~+`02ykd*43LD4F^ z^ClJoPab^q38s#1+1aA!bn;9LwZRvO_3cjT*Z!z;|K ze06%$CasP99OBSSwVSNWV4_U7>T14hQ^gmBg_&d9&UxSZ!WJzMD>OGM&(FOfewRu3 zb6h3@3_~e4mb0!jw!c`BXWeRQG?X%rtE3OLw@iClpPo-EuA@wu33pX6QZV7)z;nM4hU1tj|Q&IeyfYS9uaMD zSqq2xsTVcHJVBtNHVMhusB-z8K;?7t;kG=`*WKLqAvrPUaOCW;-HAjz^6_&WV z1hP7G4S!X(?$qEKM)g0smr)o-@4t7|Qu-QEmPqi_brRz}_wbqeH?kW4V{0x}l|OeN z1b9e38ReOCwUC)5;@bQqsx%|!Rb<8Z;%=OEm z{A%0J&%e2`@AqC*%7Mb!_C3TLgVU(uhr-@91~=SJlKKbzmHtJ*=H8}FTvB6lBWS_! zU@8~6*3vL0w#-J;w;$4eH=ASg^ic z`KZ~8?eAxjiPDo7v1;4n*a;24-4d2Vf6bO>rEwz7iqz&NnI=+vP zfb|XXYxBu&FAw|PS@_4r#d!`F{_a4xnpOwQ6PFj+IZst3xhY1l2RN226OE3$xDG=o z@xYNyNhK}WjN?Vm+&(1Nzr%#o5~M_ZHT(M@=OKP1kxPZf8hsQlZS_e%_)jk43~`9v2`XqRCkPVm8WOkjWXRQrAYd4te1q_us=LMYkrKxNO3X5&n? zod{V;26gTmRwKq!k~aN9V=2TK6eFB#WL9QTgr3X=Zaui5QY47|VgbSDS}WabhAH#9 z@!91n2cU}i6XZ{nRD*w)Cf`65LJUInyxVfE2uP72C&}LPX-kYeV;*0ozWHe15QS|$ z2-R5(?!B;Gw=PUv@CAq`3b1EeD~R}fu;0xpsqk8LVvz03ZTAo5c_&21Ji+G&$2mRS zU$?2vcOFn29$?WyU?Q*=_!d+#K&4o*u|xqtgyKC@vJ|8@YgBQ7Us6I+(q(@~*yecu zKgaXme8m^skL9K{@Iagw2`YA^`hS_#_Utj}Vv-O+P`V?fb1Iqw5!Ki&53=C1Y`|!I zcfT-ItEx;z%Ywqss?Ut(UvVxEM98tfB8_wD;yDDN6Dgl~NM(~YrOnQ=`(sGAtBkl_ zTX!{avksd)Q??>xRn(n=7cjp9EvMW*0Z4H7vdgKhg5~~-dm#$zOOvpxsqdVD4VGI=UI;)D+Xr1E86XmySnFi~l&(GBgs#0m88Mz#B zzhXtEX`b;817BX;@%(heE8*?tEtQuZ&1p80sy4tJM|L0pJ*~ZZOjb=cbF{A^6fOQ9-Sr*k%Ky zMMB%Q`3V5>7&=vfK1V!^yAb$`)K!l+3Z7MrsMp)0(cNPp13u*oJWzX#9#b9$$p{t-GB^g-*G70 z-?4n}DKSA_p{iZ$ng^*AFT)+m&?|p$gvT+kT3Bx-ba7*c5d+&F-zb~+cCMy|mK9F1 z)-2QoJp%lXHz-Yo$e|I08s`=h@`t^L zDR=^3ScjGj2^>f+G`lkOiT#LBHa<_2I4hh(?SJz_V=6JIH`}b;-+Gd$CJ5GD4DN|GmWV4u2Lk?=Z zvBQjPpLMzh*~D~s6$Znw&|`H1;x@JYCK(Mp)wEdSVQ?mo(Tl2ouZMGPdoJx(E?yb1(}e4GhB-xXz)kug7~vOfTOFe2|Zj>58Y-feNKPtw?`3ghD@ zsW!6X!ea``i}sd*zK zPPrG;W*Wh0NX2m8{Vmt`1@eqYe+j}~Ge5<>A4~?pcHIOjTH4x5?OFmwoa$lnhQLMt zpuJnrcaCs{toosui@h|QVjlN90XO8YnUNb>OoX|uV|;7%{l>4_)Ic9qG6*eLpW$HF zRX!Nz)QEoAmRep;DTg5;!f2am0<%EBW?t9`W4d5J$n3{|{0tiH%MWs+ zIWDzER9xsn!yrI2o*HKAOc@a* zHRHE03zN4$G`~)hiwqTV%}#45aY*{2Px3PbJ3m1%^1~ktKrP}era&yhv|3(mp4TZZJS`URptEE#u zU3bs^=h6DrDaoeA+od<(I2iakD|#oTrd8j%cb}O&E|y;~V3LEBHOBIWqL~U#uC^xVY zr=q-P&6V~%On+Aj0j*_}_3ovq1gjpxu==q%=5+HHXXy`g$k7y|#)%Q?)F7wiI55zqWaeBkw;PymIisz0S=NbCaN@tb7ffU5GrcLpmuUZvLi}$o zVKuanfdl}NRbsz$Km5JH>*jwfOYq;_`tUYEX0>=IkZ`FcI$a(oNs~NK>~&l#+d+p~PQg1h@bg7q4Y^W82<(1HB-TM<^u6hla+h-l6YJOPh4KlP9>%A^FY`?(b#f)KrwUhIVqzQ>NvwOmDkm zPx?HwSVVs{PNKjSAG$vmv98-__0=jNMDl@CQOR}iWENGSjn{kT3;EcSbT{8N)m?5Z zOKai(Jm%4lQMgwSe`e8~V1i;brvyA&`qOl5MQbp8QhhhkC8_3PpcJa2v!-M$To3XK z*iBkuzzCO9b40hM3lAhZgN22u3KtGrFX?|cf+AqPO(!rzsk?qgSd{#*g`r{eEeO=0 zm|WlLce%RP=%xxOOfKnGga|nnWbAorWXcec3$QYBz*$SqrC>Y5V_#!O??dWgk=<&f zJ4fliLRS1{H~r|&+6E2uw>$C_h-qaVRMcLRJN_2xv|_@uD>6Kv4ePEhR*mK8SeVti z+pB1-dzSY3i_su`4Mco4SyxO`t$tR_9gi*NXr(kNkC~+^b?qS%A?T`nL_ZYs%NS9Qz*PpPTLh%TXW0)4e?g()ci9f zMVe&QpSIrsGm>6OBygxqE>!sid1vnL$u%V!?v`YI@#Dvb-=Es|P-U5~3!iNz4`LP% z)SjR+Y5&A}{rO|Hri{rc{`xGvm)jK3kY-5CqZnPXda_tgoF%dRWrB^wt^`TU(3TW^ z*}#`2F$-}Dnd+?CaMbDg`@!EL?6-hCx8iTRAidAi7`;7|S43R8WA2$H98j(`6z!U0#1O3#_a8=G&9wd*SdKy{<7$`~xc)nb8Y(%x-q1Rh@(cJB>>lw+dehReaBoq>%w| z?L;k)3TJjm=OthrTKi&Fpz1`j&^*Ji=1f!Ku#EHoA7(;h5+vq!xawyf>O6%22 zSHkxwZ43~>w{(1|@TBT_4R#VN=#C}=!loc#`qziW_$I1b6${b^EKxsEWIX6)El%2M z=V9|zFetu#z&1rx<3I)GQcYjdLI*9gGt#NF$o#r2?H;6bd?rV~l*%03Kg<8Mbt^xQ zHd;K01EN2OkwM@oV`8!|)ZMpSCfwv^(NHLFbN-E2xR0sK+)c*;f!V1SeG?f3N3S62 zspGIbx}>_fnLh;s1+5|C#y$Iq95QfH!GXeWn7+|jE%Ddkg&k0niz9bJgxr3dQ?8(| z*KIa+#IUR1yC(TWOtwE|`9%|2lk*$N#COL*JIAR3z%_$1Vm&XU5>UWaaIiD%?JF&L zlBIc=0->Qpe^y51FuN{$>reZU7XHxm79l0HqdlIE?H5cS?+!30v0MFN{$tDi1=nzz zvfI$CLFoKTN}gWp*G7DVog!ovdIA7A2h_yOkw|30r9@07$3@@n$C)Z=GLvMDX znE(*7@W51J-a0y5aYhHz9i~1P0Kv{KT65je$AqLt{K^yRUY8++!i|4zjo~kATF8~| zRpP`Srnzi+Q?<$Xk}SRohRFa>y2ZZEJ6r%1XT9n|KoaAuHEeeMn@^&lD&{2sGD%i; zv=pawbv+vPMSbtp$4^*^qy~ziD$v#NXTh)MilrE15lfurCto7Y;^;Y^&f@=mruv0Z zNAQ?pp?SY^(F91+ZmK2sm6pfY%k83$#mn}^)c8q>K=K#NGEL1vL`fPReY)z?{f@>{ z#|3ttzKT_WAKyGNM?K5AG`gGuMRC6x+C0-Bi+=l7FT!e8=n?|<>4fuv*vUC5d#(Dk zqA?Mxmh2-G4j2$jhcBUIHj!69#&Hm)K%^TPlnkSX8J2B|5Hr()2&Y&+h6IRt-r*Xz zadoZrq1H`IP-1^lc(}Xao$|&}>Q<~bHv|RM9(i9+SsoHs$=FQrQ%&Mkf#aNC{mZ~M z$K8bXQqKte?@GoLy9o4&X=UUbD-VZs#wBoiJf~@<*xag-J)&X^OuajD2ZdC67Q@}6 zUc)mFm0>9tSNzFK5W7j|Pl0fT4l=c!&rev${d0Js`fFqCNV9s|@)=Iy>l-zDcCN;lPDrr$|lQ46ekI1tHhtKO_Ii6#v>@JFX=H zKor2GArg5y0K}D}zKa-ZtS1gZ%;_`u)!Y(Uns(FEGf(tADuzIBaG(0qD? zWz4$hCKQzN_VS}?ue)UA=2r4aSB?&kDHpZra9t}xgCr6F>WLKCFSsa9V$W2NFmpLg zNm!f{1m-fWI|;0W5LFV%lt0l)1U-`*crW$j0u&owtlY6JQaS(q<9VR-5f%Vq0h2FH zB3yg}bG*)HH_sy0Zs!zR7(1RB0qEP7`?3HKg$pVs@&o;7ma^MEMHQ^pjHhrNKsb1i z>2hQw-gfsOGq<0emQD4lcGtR0Pm_h;&I3Hk%K1m^CcLNr+t$e zkx3?L)E2SXG@DkpMVK0C>-iihG>M4_#=1E~9ljz&P2ZulJN2ohP~q!|<`R(&Uo9EPasaaS{cjh6Rmi!H@vSiv>fRNX>{^yn|j08*5BXUCE;G}ijshJ zk~_l!MGPoeS1anv{c!=i&g36~w<0yS=EfdHYWaswDe>-(P@KjRXwuEjru@BXR! z7DQ{bF_HkaY>3GWOX0vtOCV7Z*3Ml;XN9o`M^{%->J9GO0w@2*zPws8Ezh^p~Azc~%;QCZ8CrU7CW`<$Aidfx=D(+8@5q{t=OTCTK4&b)+EJ<`!K|!CQ7Kp6G z!Z(VOGIw=uQP0#rD~i=Xn!Ms(+?2a;>gyWxud?kOa5xPS<>1s*ZPQGcSVQ_HCi+c| zZqzVao^`O0bq(yk9H`8^Zc;~+4AHt!tBtFzbm%4Tm4?OL1kOUTCojLA?#N+qF2}mU zwdRW2WiQMoR?q@&XWrQtT1c+{MC_sBMn%u(6rMOondEv3%nB;tKlAp^@XH`O7BE^D zlubS01yf*&l!XSI|f0hYy1x_a!*uhIW(kl7`f&Z2rNlu5?sN~yM@Vo! zynioO+S(IctlbLs+4}izd1_@>7aPHKdGLKrxXdmeC0iXpRS6rwLi)PKf#*;>t>aGm5e>KGps?aZ5@ z)3}sGi`!eZ!>gx}{(vr*dgeht67n_sYC9Wxk;*}Z(Wm6Dwi$Tffvi_tGe@2U>?dir zuE>XgQ!-_Pk|`-{&MfQ{-}j_nn+87*A%vQIzvFrh?K(G?5l>D^_p?5emgRjOO(>9% zY^5L{PB$JoF;Or+M;6E1zTL68C&H>XQ+0h!&@po7 zq8@UURU)QtZpSt-rQ(|EZFatnHt@b?HnDgi*w!oDsIrjIOK2f?BaODlvvXm_Bz@*axV1$?n^e=<-_Pw>J>t+Al_`jEY z;U@PBM~`9jMqCdcwQ_cD#lM&*R^xMfV?O&}9So;Xd~?Y^O2~>nN=OVF=!G_hweuSC zS|hoh2@_IguGTYMQ1n~SB8cDq-;(qSjyfnN_CGuhkm zNVXSFQe1|DDMn*|PIHTto7#lMP6w1Du%Gb_>=yz*J6By{pycpTP1DrnS(&j)gtaw} z9>9(g)o$309P5gGTLtU2Yq|ceFWYLZsyCI^p#E)0XArttr}~i|d^gs}k3Js0Rzy%t ziCK}oVZMR@JsDP{o-#h_kn?!I>yWemDAIb6D2vjo-!_}ic92=(a$Uqhby-X z2YE$;MA=2@8d=U@(gqOH+HJWjbc_0x_zRmxj!(gG*S6R?9pTuqKHq-eMCi76S$(XQH4Foi*r)3sjHB)svuYumE0FO!c z`wvu4czfVPTzlYbNU?{_d!$W&dXide z29HM2OZ0jRnM6NGOjl_1&SN78`W@B^yJMZ3B6pHY){ftvzr%n`{E=FgCV@guOUu<% zArhLc5oWB*^Rwe2J8bABPl2j-BZqj^hi|1+7e=nii$W*j_9dZw?HEaH+6G9tb?KSP z!}a=Uf#?+-jHj)3yETywlZ;0^p8!h9tV2rzC>kY}Y^>fBbL~biy){zPT8In}7ZD=k zE5B4cVoxk1=);EXZD^M&AH>)X^JaYtQ!i!|2hsA6?+v6=GLwSD;3h!iOMDyw{IvB` z33Dv~>4I4obj{fHrLeMjNs3(mstC)wfBvD+h3aqP zSf_2UhR-Ow{)-kBrwAgjTKYx$?3MWz=k8{UjJwa%4K$P!xTa4fg9Pm470MS~&5M;IMMSnANXgK-8@e*zKGqh`%OHh3HqBKcn$0HH`ugbxw3318y z@fz=IAw`300`FvJv+G)lGdPiAruf8Q9v0jAdb>Y2HJoS{R%55YvC4jDy=uM0c$W;; z@lEP2#n&mly3QO^w-VWC7Hbd|l=U3Q88sCqzSzS4OoKKad9hb`b#@9w>{3@xo zYfAfvMmy({^?c^3LK;tp381duG<*Rd<;>$3e>=HcQo1%9(DJFtQ%)zlZM%R$(^!(> zmy{KT7c+ii<4bvZ%fwI*tY17N&gK?MYx3GrIe{ zlg{xCnfj7UNSRT9$Ga;FJJ>X){YWm6unHWr6gpo|?YyZ)R7O2g;)x<-gpX#558Se) zMcZ9hq;ZTj8a*oWh@V*U`Q(R{Ij#R&n^`T~(5^~%_`IZ?EJyQ7SpOX+ft)9L$v04q za2WSqt98Rht;(dA=^?$V92@Z$7eOy1rZdm9A0JX}S}?$wB9D*KRCl;)UN)-clKaoy zsb(8*QM`#+MuMhW*XkKnUb+QcKk5a;-pC4f3dNxM&{CnQy22B-WBXyMkWjcD&}aIJ z%8o1N+BA1yU+|E?3~v~)ZQ8xP{{;ht&-iAQIRe(rB--XG_Xl8?yG9Hps0=Dg-Nr$z zcYRHZs{}js0w4mklCMKDd9qku-)HO_nh+Ui6v>-v{9q_CiGzrnc=Ksa9) zt2iY&WASm;UcuAzC5-Kv(HnBMQS8(R7}|`Jkzsl@^eFWAFgr4rwfMgJeK%`wl&8rjnVAWz>IV#NOz+J}=c0I>deJ-n4 z_zP`*xLyZKXbYHNwg0T^C!3*a_gNU4XVn~M!UM_Yig!Ypugmq$b|r1Fcl`u3@TLRM zuO|S)T%&+5l2~8Ll~e<0@I*aH<<-k8LZMO2~YfgiUTM><>76F`)^cn}`r zml4-EB7uBJ4LSgbJ%W#OsDn8e9`@p|Vnt(+fQN=&bqh})7RVxdE&e0w0jEfHv(uw_0olt~gB!7DgLX-nh?XmPb+EA5`)p{#P`3{{SH|H)lX8uLdLDvyAsIaB z4X=9IZ^05Xc4#yLkY>OGK&-xpnme}KZSdZU-N&=$6*fO@4QL#=8<$7_{VXH)RFU1^ zOAHuUX0jbM$#5LaPwW-0R=R&+9<-bL8kI#!j77s`pg6z*iYy%Sp|Q&b+X!`35% z{{Rjq4LcI}woJ_~H+e+P2``%_N&F{=C`?Z6Ghvt7AGBvnS&W%!oDy1AT8(U)_!NLU zbaY(rH9oTxn@+w4O~{Rjb<*fu?bLHm>}!tRd8SR241+np4V!#lf>~< z9#5T^Z-3wK&)h?>;~^5&)mAVu`HZ2WZtUQzyL{B_s}IiDNjwI+uz|3l9<5J{dXYm} zU#2+MZqUDK9xwpz$w76uEnQG`wk$&qorB<`>dDr5v4cG8xR%1^uY^iU zN)5*D$-u>T&gfj~C+_1k5eI6NRI26VKh6GMzam~fo6bk-PaP?l^+bMh+ znea`JPH%xmdJ~we78T!ebw()JCi$^%%@;Rg-WPyUg-oKVV-SP$vS<1}|%S!gmixll$NKDg)L)`C@tqFzIz}U0A*Be>d>`-DL5su7bQ5V;fTLc+G+Wg z{`s<3QhiUH;AW=Fnj;nD>(`Q$iP*Dl$GsVNeD?eazfBYsKD)GOOH}t~F-*u3c=X!t zL6bLdrv75L{S33i`+awNlf&)_5iuAWjI-JQ!F5hSi(YG?f$_=Ncbj5fvn{6`8U!w205O1J7nyWoIpT47}gA!CAK z#%8Btn%=N+t*H`YQy%-SNJ9E7UQmaZ2HC*(q-qxhHj$6pioJ-JKvve;cs#ZN!Nz&x zhWAzFU9GqyVm{rmU7HK<+3;3?$m3|?w$9z%&KAa15*OzfvR_CQKZD;A7(O9Fj998yvO<}z>jVz9kr@Ds+t zZOh8%bYp!NT;m&()CBc-)@C(@TPF4PwJRq~NxpF8AnO_zA^WlCUXn;GNam@^Xz!Xo z(e3;CEp_sbF7@N13N)5n<6nL#zTKR2zFQSF7*1E=L6tZw&T(-(3Ky|e{SJoj$$kar z;DFVBqap{~1T?PTjKv<$^>6P3*F%C+eTcF(aoDJyYM)$pcGjM(l0(4zFXST0AlYb9 zsgov|mOfIHpzC-(sLq-8DFP}`Sa#DQ%I6xu6H44`Onf!Z&zV}cf&Pi7AzK^0eP}p; zn-Dq?z3G7#lI`esLLg5>;}E}q8}#T0lzM?GHIT5BsaHFP#9zcY=*z26M=Rnj*8~SV zsBgg6&~|#~9SI%~;zlFiCS3iOn`MvMmpVGnlbnT$J`35_@I_qp@tNchoTpal|`7Mx-a{PWjkvQ8CDI{xGJZ#8I9%C3kjfPd`NoyX|0du@R09A zf_y=F$?ymRMP*VbEOC|OQU7d1#iw`Fi5+gQ$&9bWo&tl2o41>XeE5^$vJsBcgH88u zy!@`bT(A7~X6IZi4-lyPHXit33upMeJ{lXVWgJ@GF-1ev;N2UW^oQz4BuwI;>YZf( zw#=O$AcC1xDJh}TX>w5uwv|EeAJl*u5pRHOO4$jDHPC=)$P+Jr_xIuYu~*HMTDV}T zuW_PN4P4Qf&;sRMLUZYzC7&VdKK$YNxcGy}t~CE7rR?7m0a-q-RMIzi-l^Ce42<2Y zCT{A27l+Fc_qP`-_ybKQ^K&JGqF7EX$4?^rQduHyb&It4a~QyZWl~RKimHNhT=riV zdw921%pJAXK0jbjgp!pq548Vam89Nna$akql+CLCd%}%7xU)O{dwh@v51Ntx%qk8^ z!e(erX;ALavw*YGKdRLeihumYGF@d1QlkAN>M#MD7}3AfPmG?$=0AP%t_0wE1Ua?y zmL{JKRz>tzrap88kjUK3gg6mP9yPS$9`Ho&FOhhaf* zYPIA+C6D^7!=&CNb!F$gW&UI=Um3=IQS@D3nt!dsyvF;8J`Eh#bpKh}V}1FVv*W2H z#ooj`ms5l1vx)dh4zIUP*YEyMOg_6Yz%|3Qo)AC4Kq2w#3tvqXpjWnviQ}_+cz8SS zdeS}I)HC~!^t{V-6QHC>YGl;x2yM_yy9WK)uVayBk6B<4fjkYJgpk%>v%0&B=s2L# zi}J}4qM0%H7YfF{5`MiQ(Ww~&#d>k8Cmb2Oj(JT^oJ;eK7>8}&o=q0NE)}rEfS7jj znfp(7^;ELKxGjIXn>HD2TUdNLP5oNqYH&?=l$DogWE{Hw55hT$&xuSGduJ=Q_wDe1B;4$BrWZ2?{UGU%bqHKlw2B-C6A63$71_u+=?0GW6<56 zQa5ezHB9B?ohT2qmS04Qv?ft)re-wStlbqIf`%w7_K?4iQxsj+zbuTn`-qxRIBIU> zj7sUtS5?gkeNC?0uTJqfcD^Dl+38rl0~?DRM*Au)K5+~Xcng4#v#ow6k@+ct2`Mct zRn=6}2~Lb?QG-)5=N0NN1I0>JRy{0gy$H}0G%arj`sDvKS-SN%?Sop$ zFVBt*k+E!8+%L@^S_Oy7-08n*asW7yZ}HiN%C2|-DB0$t9#Xa(JmVdtVH`k5pZo>Q z5)<;Q>QRzl_YXmFIw|g;r;B#G20b5amMuIabt5H#Mo^sbJ}bzvTUygOlf@=@;PV7gpq#uK7G#e(w&xRD)!hMzuP|ziV6A29~F|-_8a!!zaYX2#aMzsOT6r> zA&F1-;{%DSXOz+0%gdcIzMr358RgiW?RG%gv47@!mx`nJqsvfd9lSubKiKI29;y)n;sxxPe` zFELF9do-X8U{GY@8`y}hsN&*0RUE+`TKwWs*H}i{#IidfK z2df+qfsKZ4C_T63AO?S5gF;W+AHFY?#$M`^1um*295u-L%*j);N}C@z7b~JlAd!!*b-m zuzx+;|%W4Yd=%macOA z7;sU8yG%I>YGYauN{jz^7d*j$2d+2;Ku!n%2uu)SJtk4+-m;N%z1N<2>pHm3 zDt!~pcGeifc-hP!PS8_u0lWjvc&5#6G3-SUf(JSkdS6Q4T=#ze@6=#=NB;kFKqlxH zgIlrtlM@Tf->!ezmFpRJTvc)L_ldq%+maV<#4m&VuIxy9>xq0#3V7+@KUUfBE+yE3 zwIG2lo7Dj3X9YWY0E*sF(D!}df@K_=krq3qR*MbUqS2<(H4A0e{?C;p4?UaGS0DU@ zO|z%2&Ls(tR;nnWJzW}d1C@G9de8rlrniiX^83EOX&3>OPU#p*8l;D2$e}x=q`SM3 zuA#d_LQzt>TN;t>?vN7x*XMix?&my!*Tp$|pS{<5uk%aWIyCsu5_O88>c`2IZ7Xd& zChZgSS3-bc8O~DIEuht`iVjB`ZUi^p4Ax>lxGbvV=Riyk z7vZzRWj|sFzJJnpz8(@G7jUc7mKauoKnVv>5Z2RLPwDn?!>JxnV!w|zVW%?!zjO8FKHFmLkRsktK!MDY_YTJ63zsb5xd zVHx{*pd0&nqrWzvx;13jRgCWq@!qDRX&O&X)iVF)2=YLBKdhnffXCo1=RgIiOqa9{ z*;G{vN**jlpifd$!&K{lJP@`pxT42sekfqoKn(~&r>ECI7Y#mpj8^y%Qji7WS_4POMM)u`Dt-kh<41ZH}F}(=7u@6LCHEAS6%W! zO4Tp-GxW|FF2IKBJ-^7@eAD6Gp&2wn{uL$c%35GP{6wW#IX7Y)<#+vg?`QOyckhw1 z9sF)czW&8WEIpM`i{pLk7|kVIn(`xTx)Yf5tg_<&^m>pprQ1pulX0Qh9&mcS-x6fg zS#1UU4`UI{D}2uCe6m=DQUYR7(@a2p{r_3_pgZct8Ca(Hnf?rs$!V|$90d9oD&~tB z@<{ZC+l|HMT3*kDzud}DkwGc%n0w<=#WH5QX>3ik*)ps_Ex4{a|}R-dZ>Q)AT8 z6wFGguk9qPY>Qa;0kiI{{T&-O(^m!`Q(7jYAV@WT!V2RKY2&u7zL|(SFcbbt=&#q* z+9q&XfuxdLATeYrwFjx`a|c&3%d;&X_H-A!fAIN67-z5fwMn$QE}#)1upIc5uzGYk zuyfK;oN5)@^rr&{-eypomVc7VTtESbWY9FE<&reVES$_1`0`65t$(Bs=*X5b(_r;U z@So&?|8^-T78a>fs)B^6%d2_T?9ZB`)_@NSYv$8er6nnesA(;S5KWZE5ry`<(~L>jW6*#;3f&d?SRbP%2G4K?HVOT>Fs=sz4mI+Bpe1?pb!$P@)rwWI7My3} zufo*)0l|XDub8K++9M}(mU}#>PICFY%9>Uwh=TGtMR22mGW+msyH(X$iJlqu>8f>i zsRGjnUl!E3*ZgcD^$s8Mr?qLqr4C!v%aT14BFMFnFbTt{-!qXrN2x_-GFp1av>Es^ zaWAGD_nKxoo69MHzA_l-xG3icvjMSdERSx2bS+h*t70!VBKrh0W%AGRdFFoYNTOM( zZfby93Y>f0LgcIR^StCs-hZY`Ri)W64>L>JVz)J+nBI%X!05i#8Z?&CJ(bBAS5MWpiD*su37N?J01|^Bc~`|;v7W$LT)^O;r#r-dz(TWy+I|g4w!@d zfwwVTafH`@7zobdYkR==icJE0NRn%Df4b(I-8jf0e$YyZe$6|3 zm)9cKLy{UrYpdH1NE#jI*~l&qc>-;i44qzTF{RV9o$r3r=Cm5dILt_S9qcIB;kUC@ z=cc?6ZkOnP^U``nIG#ZJD;m^tZxjNB8__Vzvlp1lp}9>hyK$GoPgf6mo+TST_%sso zvT4FUAELr7w=p8s5)$D09fayN5CrLmW~W7NkaI$1}_uiZTRn zy?RGdQ#cavvxyrPaA@ma@LO58K%pb7Ni+`f|96 zqqB(%Y6kAyBFgh>TKYZROZr`pOJ;~fef7ah5~Br$E2MA)iqqAo=z%1hy?+IC7ptOr z^LBG`>aNv^O@T;E{(Bma4i>`GXn>*jPFY`EkUSCtlRN(!CekC}fr8Y|xcHI7>qumv zTxiX&M%NM+{`jE*Wnu!jEG!&C{6sC^U7@kcTrNI^P*}`zHx0!yqr4uPAU}jOR0ZnE zyvU%BC?}PwaN7@ZZqT_oqV}4da@f1u=t>G@AQ!-mh?YS=jgjWzhgOShzcbC+3GF*} zIlf>H~&@t(TokABh zgt=_kqWU78ztBtHujEh3EWa+A35QD>QQq5|Fh@W? zZsrrz&wn_)n148XUI{XswvG&M#wP?}>ptoCo~sCnkJBmqi&uxHe3PkMfd+PXq4WK*z8i*C3DEZ_`#ib=TyeRnrH1tDl zr=};YGe9-`Wz{gs>6U0?70gN{_szxo)g_UPnHGhnHDlJg`LdMD&_0KiVZ7Er^;q$S z;uka&xCh{3u$CB6qM%0vqiAqFFiY;ReWkCs=w0|^9bZ~hM3W=zjY~9P+?86yVs&OU z*w%6n9{M$y+#jyfW)9lJyO1+4i>k_L-kaD8dF)@`>XH-rWK7hs{c|G@J(jjdgoZ?_ zueNADk z3vLhi{jc*HL?Mv+Z>t=4Z%WpH@i6)_hz6%a_5T^KsxYHM0{hRhbNVF;DW3$$hGb3U z_pXbz<%&M42@}f6ObENc;@8^{roGd?{P7;ps$s#RUeC$jZDxetS`jD z9>=~TfVR8@EJ!4uM9=~=S)8f*{S?RXdYv@(j%~HehLq>g@Pe?muEPHc3o0H4I5jWQ+MPZtIuc~ZjFN^4PLcHg?a z|2&wylk&}LkuHP=F8+;_>1wjofFHG1k8IovW>@~8%{F0V*Od~X1?O$rG+xb(T6_M7 zr8s;^!_a~^k3mh(xPMGFHfb(t*a8ZCsK$Bu7Fp%KZ5Ly*oW9MFBqWbe3f@lq!Wfm& zJk$L=%mgwwC;6B?9&+w<%h{WujSXxcD620A6gfZV-7^a|P~Egkc8(sH8yF}Lbjyrh zX$kvWV>CIg4lI8EY%rG6ge9KKqeNH5MxL9==Q;IiG41Vm4P{A0?hbiyfDT0TYUE zS&JT?N6*MIimY+m-5BS;Ocd=_s0H`PX`z3~PtyPvIe@NsINRKKopftIGe`~M4bWto zM-#$6!qEfgI>XH6z){o~YmrzMhO^PiuQYiZK#|Fqz8#0%-P|G-`wkY;CJ3IXEnZi25fC>)RSRL@Fj59iZ+Idk& zluyPl9wlv;`WHqGyvsjYc4$DH*)d^iAJMVW4lQW!rc$zSgdhHh76DI`M`Zb@B0YL$ zM`a5jasdqdymsBlz92^}fD>b-DcMUtJz8ZW>JYOUTy%YEecETD;A@zyC+ln*OvVc> zTIF5I)$nzt&Qp`}UgXqi`H;%&2)N~)Ob*@95$Vwl9MDn8v0l@&ci#Hk?dWMJNvUpL zglb)?!Z#+n<&ossD(oG)AN6<5h`iyJJ2KR?Gci`CUoUlAv`f2nq~w&;J{eC_vFuc} zx3T=b0jPcw2S>nsHbI~>bf6%d%(^l<3(S7`=Sm!@f*4#Xh_RvR2HO`&Lz`9 zv6sed2%11(HQyyz8g{~*1Nr=s!mwtvw5C3)vB|TzxQ1+RLJ$<)?DQBwW`jX0E9++F z{t+eZeVj}{x71j+SkhLBws+>lXGiPHQ%E+f-5BArO5w?42=@_SYqTzO%-A_BZA>t$a-=sabDv57p^pAn^VH5pXX9 zT`-~is5IJjQ^O5cqc>$WnMEl5yE+I!Zb1n5axF}`_*h`h9{<@jA0HohRW{qQ3@pY% z_C0-)lc?+$N8j7y?zn7z4Pzoo$~x8|`;}IL%*>urcqIhfK1uBM{%^JDi|!tMa;QM1 zAF?pZRs<=g_qdXBX@nko9EX?FJxz_bQAJO0y$&2GxN+RL_7tm9p}=iDTwm1_-*ENK zLOqyff1>o-Knj0!UW!hZK9N8Nf%yItJ!eT87J_WiA}07I{>?x$wYL8R`nuecMxyY^ zFYbshrpl0%h9n~d`lp?2#H8`=w$KwrgOb@Pe9U-E{PF+9Z~V89u4Gp$qgFfRG|*wEw)ww7)X)D7qQC^O zWlX?oBrY4yxK+Tu{88pp*OKNQn7cWVOzZVN*W^+#B7M!JjM{19$kNwKPvMp7qpl1T zc;4KPeD~G#i|HLXe%Bp|H=-~4M9TSRQvSY-<4%96XqgBPn7)CFXM2&66r=d~8C3rS zsv42=RV()+z5g@Ku#}WBFL^`2h)B=qZMd2GH!(rtPqbodKdak8uZQ3Lff?>(+7{GI zD6jE{+2di$?|N^F-5uE!_OL2GsD@plw;<3fIb-O&=Sa(0ZZD~8`=7>+@)1E^!y6BG z1^87V0yojQW-I=cL257$=*_JX;w-@&U(4Q_4^uym)X0j)Cu#NExa7dpyWO9W&HD47 zJ><7b7za%L)i3I_(`5TeXfIxvX7AK+n!q(_7ZsOl; zZ`xhoJNwlQKjxq-`SY>Z2G07lQpBK58JwlIu97d@9eDgj!p4hEjfUo%4U~(|Ub(m0 zPp^zFP)!4AxOiA|+wwut^2;S*)lC%Tgqsx=sMPSM2h${D+@V9nNVXH0gv%oMssjWL6nz1=rZ-rQ0{?WY5HT2iwS+Fu*6E!H!Xl71y`@_>QLf zpkn#FZK0Q@@i&7n_mZr94*10c1J+SNFT5@VhHK!%?}aDCqlh9zF#8WcQ}u1y`+n*o z{Y3>8z`6aC`mdYHy?JvAI2PzWh9@F=NNKI!IS}N9agGEf(;a2vC4MZscW*IF4_*cK ziBt9Z26hHRBTFoL0{_uBsK#^b{S}j3j!5jBR>h9m&O~`VF7~dSg`SVZ{y6^_s%_;U zBQj8z>kzR{#`csab2@^GB-09KbW3kWOFL_5%c=J@C0(q%i1|8pztc`GjS0xCMB(Jl z%FJARFR9tG+%Mw#^OHlJw=9*L<@aFZf=$Xe<5WV z=F~LtM!V5kEFm{8l{`EgMpJbEPiKz3gaTddV19Xr)-g1ZHcpp2b%(<6r}=?#bqnh^ z9e1`MekB4P>jPQ)Pn3MDc~K2tK7Bk$2D9qgNpl&djiO2LRZ9F4oVJ4is+PCv=f$E2 zo-4Jj3Fzg;h^18{%>AWQLDOp;5BfvfY|TYR4QIzf?4&TRbx>NU`_T^C@0|maOdpKT zVYIPX((h`t2ofl5sbqCg9dHvX>8Z#mNyL%1NdWF^<7@;lz!>T@NMO-Egl5@yN3kST z95Z^+o&K_LRm9e3n249Pr%yrdTv-kdy!(orsk=E22E9&ZUc#V>x=qO>S3trb@t+H8 zeW0G57joWD*Ymqk5~y0TvLVcl5>PL)`oj}+L$(aeXw5+}t>f`L%%Vbn${+$@G{kcoySVc0NNq3UK^8*_3z_xFXCF@=ZqWsr@ z|8k)Yis~~<6z9Ie{*v<5%=1;*SUkj>t0kERBtB)Zu;rYBwKQSnv~qW2NWm#;lhgr- z!BqwyU%~z;Nu1J&F*N~D!YmtZ=KT+nR0VWL=!m(jJekQ?xaP}DtgL+iOU`-snq--| zEj(fX&1YXfT$4rn=!t?Zm!n4&P^9@ZUCRZMoZiRWhSPypfs0sgA#;C>ff>vlw-d`wt#=P>>J#s3colpe0{v~X;0W}=g+Wwq7njq zi17Aa{iJYm^e07aOXR>9CJw0F0aNgpN=P0{39BGRNlD<}+!-+ie=x*4h$ETrdx|<* z!R+d4%;6uOZDY!=H=TVOkG4G6^j+l-awdlLD;{iEgD-dd9VUzN9b&h|UHO`PtsfpL zMhiM4B&1*XZJe8vacA=H&bVq>27k zrd|^p+)bu575{OY0b-vs_Er5$VQUel@l^X?c64T#(VjH62uEFp)Cx=@u9x;pvo~bRY{1P8oii`%>ZLE%L{*Scl-Q@ zwH?e%dvEV5)cuvBPv)=5(!lWVMr*Emm&*1GL8sXC?DwaB2EPYylIN{- zHN~hn84n43zB-kjiIvI>uFxz^XOvou5MKdhg%`eTfPdpuQ4k>;8xwr#M_B+*i||~# zu?CkWZhh91k4Wc7M$*Vu)r6{P58ScK1{-d7ik4rR2#k!3I9>Fhy8O-^Y`NNV+M6)k zo||68)G$SSSJth zVSb1Df{6FNaBF1=N8@0}F3FqKoF zZHy)Oi)&E(e_>(KfZ?2PHFCoKeT6Hl2N+XMJ<&i_xJbB zemh*iYM^jccp{&l5|`h8HSA=mNj;lUJ$Q&lmXxE}G4v%-k92%n=_rV}$yt&N=pm-zw5&*%}W)b9qUGJxUP88y|vjwu*S?D-~x%R?OeF4?ZTJpP=o{+A~$cZ5HKT ziAfs+yP5~FByz(XN${npuNW?Jnb7SOM+sMKk=_;VjqjbQTU*E$LrSrIB|pGfzv;Jb zL@G0Q=FrHzy;*r?cth+C`dNqH>-#n)oL!qy$RNX4z4zW7|7lUcu`Dku`(_lOv`VMD za;rx;EAY=nyaQvk;1zNQYTaP&Pfv_$!=7N|NcaLjXUuoKn!A;=fO1n0Z z=DJtum72Hk{>C-;QL({OpZGT9>dkNxgH0H@w5yy~RK=&TpZtnLohD@@#w-(i>04T6 zlsRb{uTP_%4bnf|nm$)k_yok157;u-yS7Bg(;<-1cg4Q1@G>nPrg@QneX0GUkVmeV zicy+a6l-0sUzDj}c6SEWs*GKlj{*J%!KUZjV^GCUA@Eg^0c_n**}J+IopK}XN<8r2 zMhr5{mzDLeyue)4^qgZ2H&=I*V%Hy$=7X+TboXo_;?7{_)rBB62~!C`a~5>MXC$3` ztL@qxI|oSCE5Gpm*GRs)=@XqoEbWpWB&NL3_HA*{_s2q%@6=O;rNpL%roV9pNvE3z7qj{n<7 znDg&PZSF2K=aS~6rDjX*Z;y$wZ6zzWgebXF20XM7M<&coB5M$j9M)vyWd@_paNR`+ zBIz4{SHq)z3roh1K6Wadl);*Zy;>GMFPfrIQ5NIbzl9e+llz6D!K;SyOL*Y$Vg0WW z(+<^!-{Vbw%c-Yzjhj2Q7M|g?p@BVsJ$i%ff)$rX`1-grDsvnG%m>~k`U*x`Sx85= zz!3rkG%d8^nP`1@Ul*JGUeDL&MDMWJ(G4^foeLtC9>sm|evkFYE?ZEQokh4^t%@>a zB*_isJF0&-&)}F+E`tXv8qN+a>9xUQGvL0i-(@gXuFISXn<*c0elQn!6@%vVb42p; z6lE+sO|t3l@bCKZc#AQ8MAhYzs0cNFUih&GcM;8Sllpr1vm-i4=BB8+1)I(7vC*ax zS%FaCtCs_L+N7j`9TK#qSb*X;2Dtk_KfZj-F}UrZ`wboK%dH(M1O0DKrv8W%{h5n_ z4%Vz;kj}gUg#!}KY%7;)am@3|2N}6-v(bFcuqnU>iCv2CW63>_h89Hd`z%!K3({R! zH^RF%I=(Xrb#=T~4utDJ&pHM#wg!i3=jyD0WRH~?f5#KrU(1TplkW%!EMhekB@=Xm zZGU$CqNU(G&qNkWXx?}3BnG%~gpD9EZc=C!Lors;K7M3`6G~mtrI{JxbwL8^R$Ne5=~RlB4C`mhBFjGLjrEDNH$k_q4fq`(kuc+@o!TL%%agkL zP*b=)>at~k`F!$*&u&Gc&Y#B&R1A#;LMsAsAj3nt>l}fg?NeAr0q?po=I7&Z9yo&) zi^xyYgWH9mO;=uTO!A(*6Bp^O_HT;Tzi@hUKplbv%h-(cf;V*&W`JX%B4iJF4_dTR4B6TpqW3hjD&M zD7_kEWl8Ut8lEp9%p#2gbJ^_bW+oS!g0RCZ@#iuUq1;Ia2gAR`U4s|aekA?i|L^34 zu?|>JpX$e=XSSg_cA@r??%;U8^oBZUuMCFPQ2=KLW~eDm0d@iV-}7JJx|=;*ALw-0 zF)8^*AkxRY4djsX;o4O$an=^wl44eO@>j_?!!LsX^yr(T00z7cpj|Tl6^!W))MK2>X8beht{bsxC`!nzOajX-G4$;_=3V z9Q1jU-5N(p@CK83JrH}Bc*By$Vr2wBcO&!|{5k1yFZL&;Z!&`;TYRO?Rt<@yE_K&c$` zlFLJfhqq_tHnwmK3JKFo?5}-Eny&YzxbeHXl?ujtTcn06Vq#)0?)Qwrn=fU%GCQaa zSG(iaG>xbV>F-N3FC^%uj%C6m{#uAk>|Y*r)C4Z9o#8c4#gwFY_o*Vw(-h*~VWB)? zCEI#CjC`JX^*1s1*K9cVo{jT`3wu;;vGey#?8BLB&Yy=LJr>Mv;B?jcX`%F^rksJ+ z#O(nOii33YnD_88y&1(zQZ)GXQg5gR{`W2EfDf`FfA@ou(}UF1T`A>9P+_D!2Y44B zjESYWCjxL?XE1YlYTe8!zy1hlBzbxA6*8q(exc zLE@KB={C6_y8n0b-nkBO<&#@}vU}d`B_XgJ{Ck*}2$Em=a{FmX;ZckT0{!d0raD>} zc$}BWd*c-jEJzZxRcLFI`MIhtEQ;32X^<|Yf^bpgr;}fB;U)?0H)hK|Yiru#AI^L$ z_M9aCKs?U@{5CnWUx;O)1?0wEndes={82SVWle{(=+Aau*Hv*5n*nRXWWT4O&_w>l zX0{`(Q)NhP_r2EpkRUZaku&p>DNH-_)3C^I2*mmdlfuL3PNW;%VJ4%^P~+J^c2{cXf(yUIgO zDOWuTxv|M;0~i9?7?NfZ_UHf#)qB0Gb>j*xAT^(oasRnyiT{oQ8?33Vi3h9FTFvOV zyTn9tMuC?p6*CNQxyYXkv^GRUOiKZuX%YS;uY@`(cOLrkr}KNj01DW`l9`R*z>{m? z&}vrT1r79RQhUx2`DeA?Ycx0(yJP!oNC5+ih%&%=pRM#jYTTA%wvo`(r!CqSx9i

o~+JB+bePAFs7AU zP!^rO{i1Z^VDJIcpqV4=yEcpSt}?xgnbJ@({oKULqSxa;rlCCY2*gk5-?$jtBUMwl z0J~;49U}b4{t=hRgflU$RVKlsMvgXe`jOHP;!wO&oo_BZ!nU4RnAF4ScfxLc1&zMGU%`n7lPU@p&#(ZwVAB9aSBiqes@i_Vt`)lVSmivjU=_3vIL+@tc$0X zfYasuG%X5#$$a)mB)YNJc`>oY?C09q2KZ9(h|uv4(C$GXmES7g^jpMj11GgI#rcCP z3vTZ9`7S=YBN82_F*1zH>;wz*`M}fCZdIy&)ru_22ldDHcW%78jL7Ir@ENBnSq$YJ zJ5}r*u9K1ILo~S?-}Md2LXZ*ieg|z(NOz&e4!5@gmNQsni_dFnSmA$1wi671*C3W@Y^T7rUxGzRvGP? z#N&ZJbAcIE=8;9fGwl(1J`Ipq)F ze|m#cxYI#uO73x#u!kqd{NkTq$Y#m_%BlnIUafIwyyHxzMgPOh0aQd~$XWZBz-8Aj zlUkA*3gcGS>S9i0c`0bgNxz1~rjEqdfm|L1lRC|8cSrtTx6WoGH^}^zq%c9x+IO-E zxYg~33H1YlVd~>fSJU?>aEzzg#wxFDQu**%n4s%aJnj7y*r7NR7Z{G*Js{GvH@qTw zaj+E&c=;$+w%t#~L=E!DYQuS0cjqzNF>CSC9Ttg+etbi)S-ur6ACGHF!|BhASSsD3 z)67BQx~Bt@C!vZzE?aqj(Te6UVf8$J(!CQy;rCdB`N`q7xTY?A0>S6vXOr5+MkJG* zA_rbIHS5Q{I2*AEQfe!8{nXO5iK6w(ZJ_ZG;<)t#1 zos>klbmLGc;r*0zxW?x0{`MoPLkn5n^!E4kbTvZh8_}o4utmDjvWR3apBaCnwc^Ki z(Gl-|x|ER-5gc+R{Zf)Z~J0au*CB{;gWWpE~T6rnkq7 zD0)30_#)g-zC*CROV~}|X|PN5Ozb{`Ql>>)r0&HdNoz_z)jNnG>4`2edG?-4yf4p) zNM2!Od(?C(mqLo9oq?c#Xk!BLezt-$p3paT3&m{0Kd)!6sjrk5)e_;#gv>?_jpy!&3!NG!l;pQ2TtHwDJ0 zfddB!%Hp!QQjY$g>GI;wu6L@OIV1$3gPo|L50?c3{iVePBZ0`Oenh^k(@H^^kJ(Dc zRh^V!4<{tstlUV%J=>8PmaJdq!{<*rqG^pY|5>wb0qv``|88}eQs$+ks6~yLCfBrU zkofa1E!~NXKTi^<>(K?)1$cWCa~nM^mIi>GvoV8AdKZt(ve&n+e}nRcDcG?TYR4Re z8}n&bVr>$3$u@D%mLVBM60dOHWZP9MnV*8iQ=p-*ju|EPd`&y9CMv6~4aD2!l_{!v zoGpgCAI&F8@yFKIRgQ~u(?BKJ&Ue@ zE;k2%q1zSpcp?^Xi2n%WyZ4qX3pLKrnx?gC5r%J}f)6NcXG`qneeaXX_@^nG3r`)I zIR8LxR%*wfb!%19&Pu$)=O8efe(Vj4<;N*z7DDbcq6Y59joEMx^49gP6*NX4wAN}poSq)9?&s<`KPe+MShrCbH(>EI`&i6O{9fIZRw$0#nt0ps=#8;=b~{y4 z5wkUc@Vs$?|8#qnGKVH28tfyj6|cEGINHp@rKgZrW)>My(La-rEj>3>SEWiSpUKp9 zy1;cYA>=(Y@vXo!h`|x1^&O7tc2H3SZbPe-?Jl%O4pJE&q{b}z7MmVPo(T!eDZfZ} zSRhW}Pkz#7#fbg-b=AET0u7@`RMf)cWj&YQzj6M%+ib_VGna8-`+PwmGRkIDPYlp4 zKF3AzUT*6YUroy9F8Iq@M>1lI|3wpKR)_Bq5)aor1KDC(7GBEhWZb-?ZOu-9q7;Z8 zU`|cs{0hvI2P2YA{0Zq85R@@R;-2}Pe>yE#8SPYP>gBSyAFg^V33^&Ic2CjkL(!C=HsbNyf+kkWtyS-WePZ-Mrn$x~HR{UyV7QCPUH#LH+?rP_! zT@`9)pcqy*pH5=3xr7AysHFMtAq7!|#Ry)wml;^`oOJS^&OY^qHdU*1K zKNd64W}ky)>x6Y2k9E7$s;H&6#m7K+E%u0Csafug5;Bi5j^|kCQf74Ezb5jrY@*Tu z!Cn&yWO*N_?QG+^k9<`0+Tt%Ion+(1opJXSOWF>z`8ySer4Ow>HnOu@k(7a5p9243 z<>uxB(e36SkJCR<4M+1`13v0m$ZaYR`UY@rMNqQO>`8Z!s7f>_FE2j_kb=fR#|c87d!8R)x|xomtu$v?AH2kN2C}fY}TQBGMiZ z2~=|au9xF=#nlJQy1RWns(;brDUdSB$i97t`S8^iQ^YBW*mvNE1|8irTkG+?wct_F z0MwTS^z`PZT>TlKWfeHpNT(JW4iWfHYkiug7_x)a8j>KP;U`8@1X8<4!p_W)qRX-g z0x&cN9~L4hUwdx&c~d&qP?rb>t##&xtv$b6aUD#_5l9kzj{-N3qXQ(o`BluGTU`l~ zD7O!)2D-9mA8#^7j_MDv9R?dU+HNcfx$3Qi`K=J-H*k_r;4~OgiEA>}jr-HW&%ldq zq3%s~8>pF9Pm-yUX=Enbh-_b@q3xhplwH2Q5;{DB#*9qQ$jfwl^n^PK|Z4;0j znMwjj=I)lxLU*ZkYPnAiK{3$k`24mYqFt}_`2&#CBPkN{@=Fc^dOxB0UTE;n$YD%>;onL2c8q*#*g5u6Q+K2gNAuealLj zZBS~>)h8x=20LuI{ApKlU;_Dd{Ce!wuH%1R)A#Ox2P5wX=}if%>l^gaa#T1SHpt8f zEL`xkl{$f(9B83(`A%z6Fg#n>=jgzmQA{4)lFq~AdF*wyE`coW^g#wEOD2?4sr8cYo(JysAn|U) z!`WHs3W1yGg^kUR+dsE;Pw6G+*!H_gB{K~O)Y7Nn&@o<(vacb>rLw(AE|*BReYwN_LT-8j08-9 z?Uo4gd6AiI2g2?Q;<8L5z2!hW$ZCMm7NDvv^te&~Qkvh!qpk0BtoW{hnYo4Jz1d!) z$x5;&3VhcL)Ll}_QnP>JQd~Y0y0w>ccbbT&eR>Q2WkY<9C{O4Dp3*OFmNe$BA{cEhh?Y zH4i)WeKQ(7qh;_!v!L(I8dj2R#hX;6I57RE*)bj)*`y)w(E;=0)zo;NOLit8BS_6l z3I&lK$&|qc64KR=7xocy(3&90L=chQl>16iUP(#QR#caAzu+-R^zf?qo%FMCv|}U( zN(;PCwdXniFN@15AkST9Y7ITECLhZeqx_;((=(t%#_2kMwbf6zv+jIJ%x1ju?rBh! zeRFsUg&UGL_v;DID>I{lX`FKPeNeLPP>Jw$0}nR%zgd~uGV4%p%cbyjb6BSwL#a%O z&)G*yv|KT}Tp$C0F(pR?OPwLf+z^3&q&%vu<~4)PdLhHbbt{TNHH8#|XRSZXY+=JgW6@!m({#IqZFejk{d% zOwyF#8Cw`u78vbVhDJzQMx30SLX)enmzj@u(TV^;-{1AwIf@^DZ+fI*2TgSr>w(V+ zl^L>-DBn=36n-{Byf-i#N87=YHs~^hy*qEgc<=%H2+;mUv?wvuMxTb}%G-^Y-MBPj`aqC^#adZIe!X89 z3tWTMn@q5cPxE$mVT<8>yRQiy1YY4ppg%+4pZQ2f#U<++Qd~wY08iV!H5m^vs@9>1 zOdXv`%p-xO?-%)tqm@%!63+=-+!LML9Y4Ol9KB8|`AKwTne{Dab(@eqYHLs9vQD7+ z@2RxQKTkq^JVt)CwdE?bjJ(KLK^sQ}$D@bA~D9|7hB+;10S z>FbD*taHl8YG8KfjU{$8=ZqjVds{r_)+`RO83`q3+@v~%o<_CO!y=xf<;wYL zTm(d9D%hnvzkhnNgMOu}h4Lg*+zshHmxzy+h@zFzBHbsxeY*O$wi7#sJ?-Zw(-akU zysdsn(bK-kyv$O`@J35e*#Ig_pNrjU2p93hELzb-AvC0;$q%^)aE}4GaZhe=*Rq{L zgeqDw%!`IhKlh@8x(Bi=m<7iB&%jDrqKe~**0nkDSIls>RXgZy_1L1-w3hx#DA@w3 z(}9avyit62zdZGqzu{C6YY)EjQwO}Ai7+PbS+%0H95-Au)(dL}oNKkNh0nPAD3XIw zTF5@{VO;(0MxWunMGceR*%CVcVUCUMSZ0sJON|J3vi|6;9$-S zg7Y~GNr(=8Z!S0;-WYCvK{QNwxPw8WsMHjB1gthq4+;TXZM%&G9aq72kpI)p9E?lP z;%oXYmp?;}sFp0d5|1tub=|PZYvYRPE7BIZ&7!tu!wso`??F-n4rbmy{DkZ_dkizd zye!jljbxG#=#K{TB*(V6-T0sd1)dNDc_XPrM=;h-s`7HX5acA@@>pypL^;{u_3aIC zml?mL22Js&lFB4YK5_c#_SCRT{kT33!^@VC+KF3YBh@7Qm%1nyiyAj3`yVqMnk9Z8sD(9R~IO|C!S<(5)41ng!X}PnzUh{@8`*qZMFb*G}Uo3R;Z58M1z3qNY zri}YiiaDQEiA4K3gqgWr!)R94g@i^l`B=lsnDyn~n*NL4B2KTmG9orOoHWRXrWA+OBr09QV z&iq4jAh%6CzlRI4w#q>)^|N>elgmgXifE}hi1zr4n@hFz0>!RVPbVG81tUFKio~(w zWy6<;ho_*f?oA9KyVjEuKqS(JX!!|`6Zo55`$vf#hNVIMXBWgw&58r(W&M|mIyQAGQ>V2wp=NI6(>n2 zkA!(6TyyMgZ6z%%=pTF@6Co0(cVS*bqh{>`L`vo$+JOhqgI%GiNGsaY2_+Jo!caHC z8HmF0iIw;HP46Qvm=`qNd+D3AHoHCq<;Ne;Lgs3gn;eV;uJB8SRUH(-PO`gX)H2un z@3|pNv`+2KKW`EnhzgII7Ajb^rhTeue_=;u-Bj`eFZt_^+`U}|<1d6{?A7A}H1|rY zvB|gY*^?^DF=nzy=l}i!@(yKOeQmTguR$|DqJiP-TDNBg?*!)NZv5969jHe6OL4rT zLSM}@bGy_?L7pv$yqE=aw0UhCyg~F9qU(5m>?<<9ZLhCy^e6vp%1G}}bv%9p8B*xI8I7byp-$+0NlO%AR1|l!%irS_$4MfPu!N*q^^8=#! zTHg>stT~ldSG~5d?UtK?{eM(iGR@Ae1UJuVyziB;Zb-1Y@%ks|_yYS4F?)FgS|olV zo$DRs1;NJF*7;&u+MvY+6}9P=2L1_MO(EUsG9?HM?Rf+0Hd>t})iBu*vAFbW*1c+y>E0mZ=q4r%&Cu)dqrOUlw$}`LHSJ^!H}X#DvO5p7(o( zHoN`ABv@wkj%Y4!WOR8^NKv1fHOV1m)Ds(b)6D;Dzf_+jB%tT5Peu&r>K3CmeGTc# z&w85}AKxmhojUWd=qs>Q)YMJwJldfTCSXWK_oQSB%MkN<7gMt82!CsKFQ(l4l_Yea z_GZHHOcE3Ew6q1P^MM=f3xD%h7uw+;z4o&m)b(AQeG0C036Um9G1@+kZ;k!_L>a&K zEU4*3S3)LFmy2&R$7v5`Q|YcsJ^0L+K0b;BwoZBrgA%^l+FxmNxZ+N$!F^Uje047B zlEX?@rpaz9alxs}0Y+K6F_zV1y*;ILt5QmB>X*bdiibG&jOVHZ5QPIcZ!TN`feBh( zRgZbEeP~_u4gm};N^Yic-$S8ix;PqBWV}7uXDrz6kA+SFuhuy~D|5P*Z*2eG>5q)4 z7jhKZc8R@wuaSCWLjf!8?~?xQIk?p}!yF`1a;Ms>@zVusfuYxjB;p~e?GrP$QoMIg z28r&WK`)Fdd42gWPoL-|1Mhk%&*wXuW>+CrIH#C4v4EUUA&>?bx>(@Z1mpiA|M&0T zhyP2hE(%4-c)4VM3Gp1Xy1a$=t2WtQ8&D3?jvGsoPN(5sUwjNwlhO!7f=iIg*Oi&? z2e7H|PXTYLI+?&uO4uPak)z5_P-MdF#?cuw%s~2z;*Apj=H@rM;LwsrE%FlmQ?u|N z(qAWqaFs9{RZhCg8c^VAe_E^+rS%AT;Zor=kT{94)i8d^n#TJD$pq#9N7GqGMg4tU zoRX9-3F(2MyIXqb?hfhh2I*!Px?|{2LP1ixm6nzU73r?$`}?o;yqmW(YtFs*oU`|5 zyQXHk6|uh|KV@-qD}HRl4|}e}KNc@^zxLS@H0C)Adzs_&Y#a1~?i<_ZEuxp$xSJ@t zD8G@D8N0PKdHEfP_gTrUbhWrZ|-6(+IgtS{NcW|;(LpMtN zQF4KVMA@jg_vXg(OpU;0$kXm`+SuVU!V!lupQ07w%j*#^quYO~E)?7IEIH_ItOHn_ zPW`24&aaSYVYBU44iM7ibmD99j2U|z*y7Avhg@W)S7i9xmcPSs;sN9$XT(3$2GiIhVH* zylo%XkZ~N-4PXLe-DRPVR~hn;{;kC8-g_I;>JItu^BwXO*lR#z^KT|)Rr-N}n-VrN z!pe=ENfuS}{q5H3$(eXLLN3U5C{A5v@O-ZhqadB$=?W8C@_i@RCj40hTUcU(X7AjR zCABa)T!7;mS2)I_oJ!th-uO!)Uvwqf4zU&>g;IfQ(W`7`jN``8sNBOd_9`?i zyBn6N7FCK_e3@q7jO1S|cMq?5ou)|{Oa#;2O_vPaOLe{+Q2Sgyff0(%SY+>sRS&yR zV8El%bS9cr{{sT($nAIOa%vRC*v%;~@54v8AYk%Wc>t#oWc`K!tL|W30&lx-MX&w5yJgn5luNo z6et2C0;o}alv#RGjSrk1bZ8C8|Fy5WwMhSjvg7in10_<|yuSy{f)lHu<&BNv=mZp$ zj#Q!I=23JDc~+2YKIx=D$vF!)WOo^ctpBXopVLS0x+H1%@QHt$cKG#r^Dd z)E5~ou&V-*wj!9)uP(IF>omJ2wA(|21+xatu(%UwcoG_%LuJa_hN9J2Mug`dgIyhHEM#2zPWb|TRNmdt z@Uz%+WZSU9v$QZiyQvLq2)?)Y-Rh47_kP+~i{4>Ut})e#J)cE~>B!Ns3nMx($0z); zdr;$TyB>7b<$L%U2Jf=V$~IzX?(oHpsq^0o7FB8+)As7d5@e0BC}$d7uWSD3p~_>& z;cdP6ZutkkP|NF?x`M*NopiRUE%Eb>b+h0{P5vIqmBFti0dIElUZop+Vu>_L;WpqB zM4cHNMlBGB@bZeii#vCrtSTykJ*>2y2?l7py#2_*>mO+lh7vC;v%P(n$cNn}^<$56 z$IvmaBRyXbBN5%^q||ThO5#0&z|*2}l+udPvsih_ZswR%2lk|0tJitw@Aoi6VIvfc zZC*jXuNZUz_7J1^iR_co_ECBEAI$cL>ar9{?cy5}D#`WI@>bXaP5BTvN9}acc%W|@ zl%n62i}ywe(3;U`<~n|usFv9MPgx3CO7GCM5pUw32e8o?tCzWA>HjwH^ca>naakX>enuD-wWPNlSC(n z#&dbG9sA5v*n#)`y^vWrRPBU0QIO*c+V~GymZc0alV2@KzP)0_vM)Y8p|ljJ80V|M z`e3cki_JE3@VqUeNra!+_jy^O6LV1m6AhJ zYu`8h^$oG*!DKXLv0%1?_Vk6SlsPTXCfR!DihHPM9T5n&|nM^WpraUiQ>!%=qZP)+J2k~bt5yG~m*^Y-sr zLHw7^g2baaf-RabRa;$AiI=b8c3yiZfzYvDm@M5kgN+@?a*rHK!1WB;mw%`DqHmk+ z5%IEo6J2iiaVau_iZ{M;_2Y{a;W?Iw#@f$Vp-5Ucm&u{e$wxV2Bgsl$KW|j~Nf*AK zM`xU{=T!#G!)!d|{Jx%6NoH>SvA&9HmZy#M7}5&NGR_b0@N&)(ABa2z2OfA~-tI@x z&%Tq2-<<-wUoC4-sZPg^`GeTe)jh^h%ktx<%mQa(V&ZCWQ{T4_XlHL#HwPcJ;@aPT zFZ!?=Os;KcB8B}!{TNO?XdU%@MMzs>#>U968j>qwL4MA5<*{kP}R zD9T0J2XtNoqdc#&WH>I&YhBL}A$(_-A8G8My@>}KES_LfQ0y!)7FOUKqU+70g!~o! zy-%a{uVB#C*?2~!ksCLQeVid(NWA!d|6PYPGUOXEd<1FzT8lD7jhOxNpktxW-i5}c z^d4{Z$wPIc$T&iVOneSlxt+=(L7sVDs1enXTJqkQh$ z5$?nDWNT=XjaI}}#j4bQz7@bOeSIzvDdVuqGF;vA{zp%fjkU_hSS?Q)CuI&k8?U=b zL^#dz7Qt01f7zZ6hnDB$#1MP4Q+4s4&ur45v^Ei10;cJu(O&=29JY{(y4#*h88%+T z@)5UxkY6(rOyb!XOG0!JQ(2bMlWwP4X?M6M1UW~7_w`nK`lY=c)6y$dW1`%(q$e0>*hAjN$^#DT0Yda(LGaS-6%L)8;=8#c%nYOdi%nQOw%qY0&;; zdf{RQ7Oo@=vT%Z9``gEe@8IuuY>~UA7i65k%(Z4Nn8cP!Ij=m~!@A=o+LVIf8TSwF zv%s$SZ;{Pzo*3m#Vs)eLOTM4VjpW=4C-x`d_Vf!2#yd-zb3;M+6Mw>O6t0py;FeR#Frs7JK7;Q0q zMEiKUgExI3SYFbc5Ui{wtFTWyoStG7xJ4kv+#gKQvGwJXmo~}9hA8e_B||^C-8&^Y zEQ$L^%uo@n*Jx8v%1YVu6&uYD%!x(2_P(E|<6(Th!LPs z===B(w(;#Cwk}=qUzLFZoj`+n|9!()j=Z{Chan>p2g;}e4wIPZbsQIUi7Y$FQA9%N z=gUNB@co$iX)8ITeC&e+lR`Rv_H0h6;hS&R@eR96jQj9lfQUVPf8CD)qssGWYpw?9zZVpkOl@ikkZS*T!;qLwNLN zCk`D0LnfwpTMdtW7nGBDxFieVO*hpi_caPsA;4-sV~ry#K7>Ar#_W~q28UVw$Q@S5 zr4(swz7Glv#kpB)V0sLyU8!p!fAs0?Pp)2)I{o$UG>=AP_W_^Fy{9!W>VvlU%lP zSeRi7ZN`@>XJ!Zgcw8WvE=0c@1K$V2|L3=%+Buwy`P+B0Ri5G*GqX|LsajJO>ke21Eh_Dpqe*}o7z8V*JFEd};_!woCps?2+hzp5 z)8K*=ND4#>(_5#{BW7l|k5yPxT2t;wPot?NxN=k!qGS$Eb!1{)Py3Qe;2^=Wrs9UK zv1@i;DScbJ8yg)>p;43zpZGgBXb}n619E=ju-_pK^ z|FqTfDes~_KA0U-$10#;cMU(It#Mi{Z;g-T#IWp2(^xxkd)sQQ(@z~yMf_3(GTCawR-G*wqf)9o!4o|lvvqUnnCGNW9MA1i=u4_DjZ0{^X`23;T#}ytua$UwHf;LEka_j(_w#j zT6mT0&bpwYKsS8`xtiK}%govsz+4oQnqtTs!yeRnNVLG4>-On<^>Wf{K4Ojwqo)-^ zR@yr94^iOpJyErMFi6LHUuK7k2y(QIwDa>N2wJ5?(jwH+t{6{sjDH9V%L<3?3cOPb z#%>hgtG__ZGq}FN*2upE_dH!2JD#seg~*80b!_}>^&nhqFijm&etn@_Lw)Q6!NA$m z7aLZ>JEkC;nCBOhq*M19+Ii7rZZ41?r$5Q?!qnJCL+0DYX!{2epwTORRmtqRHimbWyT`FtDI%UX~fw}Dt1}zx0jG47wKxh zX{!FV?!H(G>27oj2?nCz^ReQ$_kh_=cc5pvZTLrMo^z4BjDt!WVHXFLZSxk_7VdA) z5ZqKFiUGMsqI}b}l~wn@r)dd-SYI_Y7UMZcr_2<;it>-7u=Bmm6wl8P7LBQY5J8Y2S-ZJU}5JAXsd~A$>kq z5|?=D!r>3T*!Z#0pX|mUP!AbQAg)<^!`-B$xpw$xJ2>%6Z#~AXfaP+}*|3*yhfxbYV_HQc+S-Qj)gwWfW(SC%1jWv5_Ni zJnMtxs+(^%Gdg4WMuSeH?DOBXv>*&Hx4^~6|rr0COxJ~NGG&;(eY!(sCk)V6nI-5AK2zxoQ;d41vhgh zMB)_uNZr4*zcN4RjVaepOjk@}Ov(S-R(GW2dTcV8v-7PYS3E9-AGpk9jx!LUAkk&N z+%IGJDg90yL|jE8#?b@sPf9Dj5O9FpYe$q>QMrwd?j7GJdja_iDW32-D?ydy zARyM^QP3K9Abgg;wY4>klQr|#J=)Li_qevSWMj-@wZ~5uI4wUYR6^!E#&0YPGdC}N ze!me4WyK~ZZL{N;H8}%+%bFOc)LzWKP{i!D-=f>Yvltk@LOE`LOvoS5-o5F=sEb?? zL}H0g8w)5b=2$XFfv|np)!pRmRU%p@ZczvzvYj4lVa#($_)DHwg#=E2h+C;c9oa-+ zNsOp_Uq9OWckrrAV6B$%mm+(YL@IVjg3R{>er>UzT^sR3-Z0=>Q~JF)_MA2j?GyNyX=S6W*bx$r4@D#*3J67=h|8Hx7SsMQYckd zPInw15>Y}Zc}ptv^vdV6ni>@DK;Dj#i{V*_%g*Dnyucg@f7pVQf({YS*SH*cuK&v2OoinKSyQ8h|q z^GI=hK_{`+vqY5&H+#*s0$#ipB)TB;(*yx1TM_dni+K?#JFup027>W8C7VVzd+HTz zWw2O`jJY@k37oQ+EQZE)zCKOUSP;u4Lq`x`kxK_V^HmjVBIDN42q5zvwQw1W&QS@? z&nbZyY&;y&d|?a1n+(69*!1Q03~gW9JR%I#`;WakI&ZqS(8+N~?(!>AWs%sJCd|nmTv8 z|4_0F3XH?Vv4267*#4iDdF7a~km|;LG;GyYzWxD63j^$8lrQ(ghU445zfRUykIrg} zY)lqS4c*wmQ?o(2%U^A8z0Ovqg-6FPXgJ#P$L}ndytYoxh*`iC|uOPO$CiV(F0?`Ja(eV{da7pC`K$uDjmM5luV3gG6EC@*lzqa!jk))8y&bef_ z9>;z`K()hGg%6s?%*`cB*;6KH2dl$B%b*Gy9*R%%C~7ck$i!3S5i#Fz`TJ}lnIv$T zu**jj{c4&|P4Nr@j-N;fAc#0T(}!l?sVF#b-l;|kfT-zWQ|v)km)EoT7P!AL7#8pp zYiR|c{_dI7a{97#J5XoWmcq9Q}-HbH0?cgnNn)3-}d#ozHQ$02&2XC zs$nJ`T7_Bm?hS7adaKN{@O0L|Wv#+^rQujrh3)=!=O$=P-T_3m)PufabRud@%jn8JxUAIIXt!?E&^z1CJ+)k{6C10JL zO{xnZ^;^@Iv?4%IGW!3bU{$x#mCR;DnG?m%R<(y7i?pq-z!ZA@HUmgSk8Ig9S0FnW z;8)q|6J1758XG7YE4?qIa&I_gXV1>g0O#Z+CkT@?&7V{Id=w?R3jAZ2T_{y^WVSC6 z>D8Q{gh4sSspnn2jsE>WT;J#P6G%Jrw<6je_Y#u4C4{Vk5C+$ikL90NqP_GTpaCru zd$t(u`q|+e0uH2zokB30Z=qON`?1!mpYP@!ZJ(;HKT_j>xs?2?CQGtd%Mpaj-ijJ= zVbBel4;_8@vChir21_SEg1iSFuJEzdJ139!Iilp&H&~w9Y=;hCGzMlOMU4J+7-Y>K za@6OqS|C9F@EiuDR;;n0NPIzn(D?-)_RaOMKB4JyKfB@f3jAvRF>=;`D1KAd5pAtB zy6Y1B$FHmk5PBY9gO5H*Q!@q1iQC-)wgzjx`41d(8Mps=hek^o+%((2X-TUy&?zPX z81M?>cJP9OB=`iaa0%-K?TJc6G7$Uleo>*jJ>xSLz@uMUt_#$g=<`B@$?Jg8(Azk! zrbIkXPhDC+W$WpC7B?Vp-j$8B?Ib$)*tVaoUyl`|o*ksdYHaYueg1|xnEsQGQx^fm zN|4d<`b)rFOgq}$kho%eVqem{;@^#beWGrnX#ik*=E3h1m|)UBw1X$ z6kw1ZYO_pjah3<4i~j-lie19yb9)=^gn>Oy>(`>ORIQhYi=t`SVRLNCqgTC1Y5oze zyd8S2XwjqX(d6#rx6I7UnnqOE$=Kt68+uctzVjJoctfGuWZGOl<2D2u>hk2@7`Sbf zA&@dXt;j$_nmlD5x5S!s+2vn?JPopD7Y5{zds-^@*Bd2ut`sx_1HfbfW`H}Mk(ZnI zhEWt_C}NSZ2?_RmX(-W1>|-I1q?A-6+;;54`?<%GvBsaWm>ws)y3{*7eD+THsy(2J zNR>}iX3(ZjP3wK6)H@MppKQ8s#*u|ibEg1@Ie0^nvQlp@(^$N#2fO>jaSm)HeyxDx zZ?FpqzmFZQKsrK8TZRBoP)+4jEyRd_F(T4N03GNH{go2Yra zKIfg+_%sgI*RNC6mclWIg&f>v$&?UXgSG-nNPd;Y^0|u4HIc!Pm<|AIlB)DRjg9_Q z3%oB%H;W9h6?@aG@Bi~T*j-Zs`Z}5bN9JEA{8{T9lVB zBlo}D-q(l@1J+`L1%XD=BY__mna_=gAmOGmw;8712{+dv!5zKIed2A`!cS3^E^rXM z-PoHHNXeAe*Uz5)g-6(?6N%{HK(>3Fr;<`Jmcw0WwpyvK-6eDe?8GxlU%r6>IK#$J zQg>5Rs$1hxNTQuvSt%?tGg&cELTB%Fny_hT7&-187kLRop}z7Bx>WoMep!??Ps>a0 zG2a1l8%#_nu#7zH{t~q#eT9pik&u^1>(dT4+UMRqsn;D(gRm3N9$+F*%CWFzWXVnL zaGnqccqN;c;T?!oF|=#Cao2j5C%+kjPxo!SZ+@N~b9M`bRZ)l|7yeBwG~jAW-8jDg z|mJ)_}J7L@(ook%EuQhpVDWfy}(g_Gt z7L@I@WVn$NNuwW1 z*SH^f$x7IKF?Wb7UH+#*?Ub-0+!b$Uh5}QR*pfV@&JgQU~4g}8i*spCi)6}i&$rE2In$gJ^ZR~aWhY!?o@p++=Lk9MS9*d#?kli!An^UwyFRYpto#DU;j8v|>gu zYTFEa!z|Wu29(ZC9_1#H;0Xr&Jk%YBxHe{M3R5G&Rs;!r z#6y-mRVs7EtUCU-x|G2^%N|@Pp{<-6FD~TAP9T?zKdOvA(t7FcIGQ`NVJ*+zsX~p| z=xa3nr*Bs?ooQ+u1eP>D!<0k$&gSC-S9 zwAkaG`ml$GMUwByGD@k4_d>LeJ4aYRKU>s{(C3WPHNYYM|9+dQI+Pblb zN-)Fxo6lFOD?oDagh~E{m|ATsMU!{ncrH*THu(eyl%qS{t!DoOoq2-l>~S}1zjoj~ zH%WdyEiM+)T$2b_doQ`qko(a?S7@^J%TlgUCtPDioN5sN2Y^g}1QQ?E1Fh4|Z3;R74n@LOiB4-1aac(3Tr8 zZ)~Z=0=`|%waxxcE5%$LS@ccc^q?HX-h1Ss|I+9WwfS~{oOOTyP%ZxB+fZ2NHov2@ z{V%&t#SR0YT}BLzO6ttscf-fWAGcAGim0z=v)#^8<1O{h>jV+VLdxW!;WArWTM#VW z17-z87=UhN9_dCg{Q6^nZ)dcPfm{`T3q?$~n76{bk$PfZ{Eddz%>*@Sy6Y?O%=|po z%{`M8(+dLq&>9~hz1zZRIkCr!ZFiWv7t7x+V zVdbe*ET4AwE2`T3kZ@=wIV9mFse5HLih!m0fI!;Em zLoynLU=UaSzGI7>-2jzR3!Lk0T#hSNOyzWRcw_o}HZglbHf<$I=Alriy|~irrdCr& zKc>JRO`xGDVPQgBiR*1l&D_t*6jv+t^}j)pV(v-6evv)-UCv)xn#F_@T%zs4DHZ}x zCi+Y}x88>b@5goOS$slJIKc=-Bv&ODQ(Kv0qZ*!k8MOu!b7AY*Qs#wc`!>-Y974zF zh8hb6KAdjF{yav8X+a6$!f%p4FL^S@qfAKsx|!KEn?9;GG6jmCHtF-3Fd$ZhWkJ)t zi^T#kUkPHta`SV(9tVWrnuYE7z)eZjrdf`d=vtsDIU{3!nM{df1}XTs4^ig3W3iyk zG{a0-qxEyOP-TS>5iY(X?g3rA3?Kd5GP0VX-_aj91#KqZQquU(IralE$BPNTrM&(j za@(~Po3A{qI^CiS*^pT{N0`6hF-X;*wKe}qxX>qEzJm}4)Hz<%@zF#JonG6NQkWBj zg95AGjM^^aC=k<3mHd}Z?2r3U4N;;P+ti<_U@|oXrFWRw9G7lvTadh=K z2`n~FS?8(f|1b+n3m*DAb@Sss*uwV6t8@noplaOcP~#v%IJ?A){1E@AdmV=V21qs9 zdgUaeq!{2a`s!%p)WEHhRP{Um-r7~4x4+9bevU>m*_>b35xfcuBXGB&1FlZrtS`L; z^F>Jt*kEBav9#Nn7muyfFra5k{5QA$WKifd+|!M3k`&~A^p3Z2&#$yvnBZzXJqPAI z(j_M9>-^dJJC$hjMLYTp=1+P6vFG@k{p0R1jRg>hp@n`oK84?aY+!9NO*sF1FZANa z7NQ)ciTfX_MyS0&(Z0(vhFM_XMBnPkNfuwfM8fU>rbBp|+sRN6qP zgMoa8fAvk(04Y6R@V@CMU7Ozc2txq1Q2D~_ZQG-Cn zrnHUZ%N+RVP~2{BO~+@}7i8G0Twh~jgXg~dY=4tC0b=E)_mOOxv!$LW5C!h#BW&d+ zu5R=ahPOA5@agB1o#a%rRvI+# z-3FL*3Law*(TTM__*YtAv=WoT9G(oIk7YIHz;8`+3MrBUya;PD&eW|~l>f}pLR+W8cLJ*Kp9dG}Ki4i1TR02?22)@yzPDD&gWG5)#K=B^a(By2f zch&2LRZ`fSTqXxrbd^xx{b_>nlLDWq{2PEc52XhCpq#aIh)hi*<7+{;+12F*JxWp2 zIINr6G`Z)B`5c?T;>o_)mz;>hQ7)lZ8rvau6o{Cf;OKPw<#!qM<9@aT8eAJE zEL8ujz?#Z2VvvdpH4hVkR;6Vn9zyt)U}a|o+ESpNzg#og`RrEcmV6x~UXBMP#Ct=o z^0+uuuKk=N`HDY|hY)Nh1n13tMe0Uy-moRE=$l4R^4(ec!=gl)CjY|p*wSmo^`hNa+4i5bV zNuF%xyZy#NcGf%hN(Di8NukGvb~Wd);2PR0>NWkBb0@G$JvrAs)tS&303K4(Q_1H!-ma;U@Yo6e7|@w6#VP(r-&6Z`18MJ=J!zx7pR(+gEecPch75Degom}vp{`qa zhl6e>A(_GzjvQ{K=YQcTMmeL>H#GogQrMbTJXmik{;`(i&g9T<*4h}2A37M^P}idD zK?Y!QK2=tt`dsi($fFs#ICMGcu~~Xhgn)~mHqYi>t?Tou((%9>V%9pKOWz;7 zOT@m!)Q@z^L~&)$c*C2E@At5Vw~GFT$pXQUThB2ficsv2jIIpt*CPydu_0RqIsEX? z+YKRlvO<63K4$o@sv(RDpx~bPVO3A6_D1K?nPn4CQTpYrng|8<#Sg?5fE!$7Z57^< z*chDdPZK%%GFXl8+S}O1X2@49#UVks^GuwxOW){ZbpnJZL2E1ylbYeFaXp)%VfsRH z+moK`6u;2?Mg-7O_$cmrAFI?@oqrRX>`&rYf;R6*XR~3q0J=z^3giNn0l5m(E_|ERE76`Wxmj>(TFnr5Hkcvmh z7@uP@h_KaM78@!CU?;$Vql^NMpMxG2ojcRw9lnWLX5nOICXMM5P5OX32q6V zkq)n^E~4S#-=IXv*1kKp477W7_kCrwijPz|YYHUg3``kX*-@$oGYU{-G5~7GtRI8d zj0VA5km|V0xAlHsN^z}-x%bPd|6b#10M;6%903P{2Sju_aCr?FlwV@cpT&-{ z@i0Z1N1@Pc3bIjDxUQnK%iOk@8CciUeK{@UzB zmiBzd;|T6(cW-Y_FJDYOt#!f&9ZogzT`)a%^{i0MS=_`TNyn)J^2&$z3Q?NfwQ$r zfSUw0GBQ#uSd~k)(;WA9S!q4W5%9@Ff}+S0ARX8LWwU(-+2!=B(pxdy<$^eKvwcbo zY67$e6Q#!&WPsOt@tmg0*kG_40`rxM5ktUJ&i-0o8^TGZO$9DC+A`&X%Er9Xk!?)S z<*@vh-%CttKHDvBc^>6!(cp6|Rn@qm>8ZZYg;Kti$&Ath^A{^+P+BBjRTSTe^e{K{ z^+qugfx;4k2cq&^a&F)2^*2Z=>2@=Ce`HUjkRNLD$!V8!B$$cax?BhTxXsq(`Nd(9 z$)IGkd-(l8rn<8#xcs|+wc_6$&8UBwFvMNeIIRlw(eVnXn#*fR!#${M-!Fa%x()q! z3KH{d)^=MsTK6)^1gR(DM0}IH6MMaMCy&d;IQh|_ni|@q{;TprMF2Q8nXcPKV-!2U;a|H5@RB$2^2LqxeajbmzcSv^qkTnRvN_GU- zAy?lcMWa>c%Q_WOY6DF=2eLUDR9GKg-k*rK*L|I3pJ6U6FQ7+?NW&A3v*>$cZQVx} z>#3&ebJAd3-f6z{_T(wMXXonh!BtmZe|e83oA>hsB3d7+3Ky9y9{7DJrFz;%fm5+h zs}BPrQp7h2tgLGZ(fZQ{H+V}a7~Q95%(Prje8Dq1!rFbiP&a|G zpPBbK*r^tZ#6`?s8Fi}$=L&~DO&QO)uWIzIpOg_mzNogWHAhCRN@9Xlv8KwyXR)C( zJiEt05H0EJe-{+>+u!$n+TfAmYB=CmN776S{>bAcXLCA5`EthgTO?-62II?ruKh0k zSGD`j`x;PT!_Amsxjy!XwK(VJ!)-o7r#;sy`xsA_^OhD|eR2V4YK6yrjZNEUM-l!e zl?@p}5)VI`g&xnd<45zk!~HfJ8A|3Or@ygzqqKOqIj}4?LI%1ifL|Fem5jHeCf=ih zp%vY)r(dL_(*+!_ChZCdSwnD$cstTG^!$xx!NtmfkRBC?8`}Cc!{U82p{7|SOW>a74W{2-FpQerUJ?+1ErJY=zjaDI2L>+ovBL#}T{p-&?J<&n!g)$T(Saz*^ z6LtDn5^HC)$2E`3{`eWK6L||xr@I;IRu{Ht;^3oGk!PzdQgrYp%X+vNO%P4LU_e% zXJO`0lfIaS=vvb@=45PVM*`Ib-<2U%H?^-OVkuGdyO4g}MTNnNr9jAF;^}t~&jd?_ z2}wo=EVG{|P2RA)N&Cgh`^Y4D8HSPyQP^v`Y9dsa@6GnqjVQQV#)q@Ei+vn2q`fM3 zIVf*zA8kf7eO;DJkdWzf+3MS#3w=ZCzB^At9&%xD{qA3gAu3Yu8PM3LFEfol8=dlC zgZ1ePwG^=qGOg~Qbk6JKvFxk%X_8X>Uw+Xbg03%QaTHM8k)*GTk>2PipFfDVE4rnV za$axM6(ZjTFChfR{8WREGER zF=dUWw2ubi(1cwo8OjZ-@0Ocsrd&1NRKlJp=Al=_J@@ylwM>l`Yy%-TnDCHOn%uJ4IKfl!SOx@t$s%GOjtodlj+zA$ z^^7__O4|zioLKiO=ePtB;pQ)%!c>Cc(EA!GwyEUl0zMJ9n(e&oc}b%3E#LC+TeX=> z(dk#&N5Q3)wZoIr@@1I<7h2ld15UvMbM>9sk)t_}fj>IFvQA4?3%Ob*Awa%w|9Rj2%wv0ig zHl#;5q>juicJni4Tk0Xz$tD%6(c;vESZFnBKjeax9j&xJ(cCAK){#8Vzt24c4TYwM)PF|?oUl&AUY0U1 z$um>aQ34as2{g)DKalJ+6Yp43KCRSImWM;(4~5=*PjQcA!qi7!kF8h!Cc0f2qkaVZ z^#*cHE(y&UI+~gh(~W979;)AmMusRlxj~={4J|DdQ68_O#hy4C2<-wNRx(O@5&o}T z`0vzM0#>%D=Ty|p#FzeWKD8W7#wvR69C)OZPEr;J3Z;Y=;?>c?N5!Iwu2y_1ufh1| z7|4)LKipqUCpX*v*bnmWkoIkvw&fxv)FsIk%6F)UCa+8CIOB!|B!QgYzmKg2W^?zN z>tDiWqr3{l8wF9B2M`Gf58tv&NEE$OZg@i_7F#e+TW``4tzlI1Qc z*P_#{MTaD7SSiI1ef*At6XQxM5))5q+q5- z*L+wM5=F%ji@_osQJ%z!_^p(oKx8@byRU%7=8cPxK7Y7T;FFQO%x|oO_giC3P>kP< z+D{y)5;a}iuQ(Aol)yvH5yVrKMNr7+fT^0k0Vn%1YGe&^mzy|V;@qpFs;}^hi|N_h z$IXpgBFyJJUlr>0RBy<(z zi<~Z#F6aa}^^KkD>9pZk-mUE!@Pr8mjvB8gC8NMtRz>g>q#SS%;cbKnkgQJycgolK zY~|_CtqZ%8wqhzIe|N5XXtSR1#W&b6?f>fWJpqUTfJ>Sm0M4dnXug%E!vwFh{eHPU ziuvCat85LF6$L}N?dTsQSk9M?rCqm_M{(1P7jL-Nhuw~Hvo9_dsXK^pz4@gD3Mr*) z%-Pww$x6GVD6QRoDWW(IoPS^mF4fA=v6AC)c4QdiR^h2_GNJs}ej=BC$pN0g-xSh8 zBM3cfJ|yPH5{X_1Snlnij0D|B;1Zjmm}Y;mYlbgj4&wd?g_w`l`p7ZzJip4<%h;7` zu0J#4`ZcLnK%~Vy-`gWwAcDrg(UD{=?KQhg`pEtsAK0WE(liN}v;wg1V>Nx4vwlN9 zd3&h+a#RPA9+)1&P19nRhI=qEU#n!%`A zbSrQH)7gAUlbfZ~hFL^>geyemL&-gKpV6z3LXp=E2j@pVx$cC0ouYi2Q*E85?s2%1 z2*ju!4j-!KQle9Fo%L$}QLL)2&-1w(pdIXtHG~UfFr>qVn#QTz;soD?3@;8lQ|9zK z^}csY7C#rKFP-11?!wT}n%Dnh*rEV}T|ygnVEbzx0IN&0y^42X3;~XU1mPo4X=`5Z ze2@VKao;hNz-6(+`VJ~D%L+BMMv6haD6o5s-@cb99=95ApFiyo;ZRl($)5yYYa>B) z5+QVj&}!6tyh~bP2^^)hl9AV6Ec{C-d7Du^PKNh%SXtmk>1Y?EUgZ+97$9;mbv#qZ zGRXkSD|z_}f(a@mPVW!MW`Q85flts~ZgJ5ozc2mH^HByNl0Z(Pgn7px65 z_2d<>TF`54-nhBtvGzkDmC>%p)T^9p9gao|H+Uq;sspJ+F<}*pOuEWuHl_=9JX{>a z;}`EEg*->q%XdSBJj<|1e>-R={N12nI5`z=JFm+RzVsK20x5fGh^5x19cg`=F97ko z#NwiWYr-&s=X*7!Y6y!%H5H_4io&%BYmM(e)wct|7MPc_G=9|9;<_6gZN3^g-_tdW zjO8)lOM1UPjVR|*UBu)2gNnSuRYn4$Ls<{W5gCzLg!LI8ov6PEDka#r-x1-Zvg8Fs zbTMJT!6n`oN1>g&c&=d$%5Ub%ot6xz#OtX+@;*^;=BKYhmURn`BSr$Dg@g z@?H!wM^BG^|tDg+VKcfs;rAQ&0JtHY4WzVM_ z8WN)@571NrS%+|n<)v3P*WhD^;IE!=Wj_dnUvRjjgBkVZww{1G#3Me@3r!=?{p$7O zzh0Q->LS@G!_`0r4S>dtZ+)f6HB;ddZupnIR9Z#2 zy;u-i36b^gJ!(vh$E}6nSHDo& z?cJT;mQS4ZWohja7K|6~AV3CC5R_~n;F%5VL`oVOI5+Jy{TS4MQgT6^Lh|YI)F2kO zr*5Erl9J8bAgOc7?pIH;85=zIORLT}&8%&gZh+Ul#6z!SQMfKrsL)!Z--c+S_(T58 z{JvZ^Cx)`!ceqP_hktMo5>=IIm5tSOs1i87X&aqD76Ag8vrvBYVnTvsskhC{7!4{c zd|S-Y`}^|~GIhvh`VrG_R$JEb)4qMQkFHOFum%%pjhZyA+Fj}%YjM!myUp{pDTx*C zzQR-~nt`iFUb^S^^ImzZkwlu9T6_G8>dDY%h>bJ7|B8l8(+8&D+vf*qO36PmSGJOl z58!24H$W{bCRFTb@7MMQ4VU6yuEI%-!{k7pUa8^0lQQqu!ig?e32}*zB&vpynBOZB zSYydN%%7s#<@fONurCgJ12}!00(j1LLjXsq*1md>RZ>>i+jww*Oj`&b zjy|~d2nz7F|EOO!k}rjLR#bK$dvDl@2rFZ86O5SuVhi26e))s|(%fU3U;3|AZSJrg zJwk%%6ddI|R?#O@FigF@`MRR@jcNoL!Vc4bj^}U2Wf}jk{zv$)bg`TRq!QKH`C2<* zs&AE)f2OG_p?BB6P+ZXdQ9G%y*p>9&4|Cw_YCa_%=2H+C-GeSG4a# zA1E&DsllmQDDei(G%4ntxs1uBj*EozEB4rN|_?rY*$Hm|v@5g^|oaJAV*S(qTj-5rVrcY?bm zxVKQ;-Cc`21%efKDTPwpp}4!ddt2P;$7V zkE6T{wF2ntG?clY>i3Hy=`V)HgQfb|RHV6#iYuZNb-YXqKq;(hmKvnXEujC zxjV&F$Iw)?K$aj%E>S`0jO&yvbh#1MVeNl$b2Zq7pC6f(#q49L#FppVANH$AkYKVD z*RiU>R_mp&_g%;Jed_WprK6@Nfkvk%Q3on>W^Sf5_!nUHv|Is1_CZOFW?FPMHsl|C ztkvUX98<<#uj6&{SMsn1(I$oq-Gm2H)b$xOo=^wl#_s@6K>-Y0VsS4X#WWC^)}|*a z^`Fk@-42TCk4Dmx%&Aokt{-GMQ^7Ie2?#ec7Hm=zhNU&$bH)yN;i7pX(3|p-CZL$B5zHvG(tK^XgC>NR2Mpg=hZwVszh|B z*VcCWq+VP^CDm)wAO8*r}zR`RD(1Br@C=<&hK=gj@aNDM;BN8?5T zb`KGM{9q&L?_UzI2PVP=CPcatTj?k*Sz#>xw56=A>d7g`p+(uF5_8~W;)5|!lyRqY z@p=+8#nLb&g*mCj0XAPbUa!3ZjnuWbT;NK*w6&z0x@#raF35Cz+cyj@pT>y)8$3N; zWj#7ck)WUYTk^EVzG%IJO5=au1YOr8&Jm1n`@|7r&uQOK^OMdIv3(X(h3zq6ztKTr zRmW=u%tpuCELtFU>4*f3=;~N)OH!1Tl$Y?_-_<)fjM8cF#@fyGp4!{Mo-A$~i5tBW zWGkE5^;9~X{^3EUTN5Yu#{~3tPd&90wsAYGSeU#%&nDW&PK+&)qNer{HItV$k=#0n z5~SM$j+*WsfnzuzH+fs_8KrvXs^>H;g^@VNJ5vKH>xK(`k=#Td`b^{LrL(;N&GciEjxTEkinQvIE zeFpg*)olA}UJNZ^Ec*<&JphA#;;t57%@%k3;UZ1fs~1kNe>1iJ6j(njkbg$zHeX7# z)e)r>otN8LgE8WZ%~3QdQ$t)UWZ9ajt^>Qp2x4e!WVU z4Yd4S@Yiu+KKq3SEzVlZQdAu|DI90 z9=l@9A!K;F^*`LCxOLf>2M^gV`EaO``b%gqnd*PYg|9 zp`OE#VVwh(O*E@I{xoNs>-)AYltcIMbU8$Aid-y8kxr1Yo#+3%w>U{GHtn0PG@gIT zUyX>Nzg?^|%$MKJI_<^yMK6K`L+^I)O^y*_<}wgz<`hMWGrXW3MyqpIGsn*+Y&u2? zE|pd!Osa?{-?^eYt#8=y_d7C9zL$NzW2t5z8)B@o<}gl=Nzuf1LkS@hjG-3kN2`0m z-`2wdOQPDOj+#7XIU%dBE`{(~lWF+3CJpZCX`b3Myn8|o!2i>sy%a;|nZZ1;1d*&< zNLKf=WCoPtrDR-dU_4i)0&K-l3;0yOE~=2^DNGM~R7WcmNtEZqd(~(f!!}=YYFle! z11`_?|EgY#VRz@EnTF)a;4!h0r~*9XO7`0M-<`9MD^D6|q6x!G!!B{Ml>E(}812rd z5A{tM?+0uI)kB0Huds`;Z!EKtn9G10Vque~56u2SB5q=^DIS7{jLBhyx)AO=?xSD) z&54W`RSE3s9g#Rm`*M(gwz}35-G(JW))x3di-#P0vlGtp8;|-=M4PkoLFzYeB(HN@ zSq|UUkW&{miM*%_wWC5CulH^|o$JG3x!x7B4^4R_>a(kxpF=FrWS&KL;rV8j_yr;C z0S`v#o59@?ROPGF^Ba++^(aP;MzJd7)@CcCAE0bMD&stJdNrm=nyX&E%e9rH-@ur# zkQCL~KWErY`B7_M!E*myj3<9Tf0)|PEuPALb`YMKi_e82(yl`!B&Wg<2HzRV1R^Bn z3l91~tDG7=c()Ws;*87@4FcJd2fcWi$(pSu$f}Jx$7`iln86JCqr<1x$y^;=o6 zspkm)?lBDSFbo$8sbvp> zbeknAW#*m#e?rmBx|lF?-OS>o%54|irr%mpt*!N7H1aIw^S3jRx$yGk;rI*@1ekGQV^V84>ag^Llt$jkYN<&lH+Z*;`Hx zzjcn3D}uGRo-ZxACe+1aW+G zbKBw(@~EpTj-kleF26ibVP4hleYJkX?U`;-d+H=R3Fo}WZq!$SJKR-uh&_Xg966+x ztuUh*k4ShPA+t%6ft8)qI9W_w~V-l zxh>A3gx$4`*VpBij?7tfCEMZ5n)%kG>T<_u&}LPS^%f``PuxBpL z=XDSI5q=^TmI?_HTO4tj-vuQh#qwrE2a`?<@rAGZLg2fG#@Q?Y!xysCvy;y6RJXUD zFDhzIqL5n^lT`X3EA>zgP7wBr(8}=G*ic6b-gvg2G!7FstQ}GjqWZq&i{uUovf%sX zI%DC36y@wu3(&hl{fZDR^qRU=OdzUq3QOLoCf_|;$gJ#R>nsMb{8Vcm|0l7-Rv5B_ zjGWPB))cN3?hdcT_gPG$OH@u)jxw=l-2T2{Hzvw}J2;4Y0pUoKUHK-q_k>sFVgH)9 zp>RGCo!H%_kQF&ACLX-PH@XqgZwiUT%`AT8A7>>Q6tfS7dR)$K3tiMqfJ=|6X&8D# zO(kQ1Uru70#NiXy^bs740g#Pl{{m#?U`+x}aP5YD4NMPjVDmhED)> zvs_CvCJI6AXy*++?5#M#)|7BfD!_m!q*BN{^18^-dc|DUZSHFBs?kP3(nId`aKn3x zzpkliQSmh`J$<(qnYyTC_8r@&mT1jDIeDIG=5J3i^uM$zKG(#mN_=yTF$WA6< z(c~aqmUQ-b+KR)zp9kET{7kt`ODP|nCD!uqvILW`c?UI%I0Xcf@gNruIZdx!rQd6{ ztk*P_eh(csvQ~a=9aUWO#8DRxu0&U0Sp!lohIWKAR+naISK3Rw?gyl6@tgc>$19*O zUU%|vSC%+pM_T%@{VDoEWJUxxNj6wD7k;NT|7Ix)h4i2%IRg}{bF{xt=6PB%x;B5} zSKeW|X6zpJpJ-H<9tRHr$#+lx3N_wgj;#g?rL`9%pm+q?Q{Z zQTVhHBd;?n>%IolDQw!WfI$d%9 zJ#I4GJhdI?R-&){&PyT=sw2Awau>K%R-p%PX?(6tg1u#HyE3CPjK|6ioU8C$6%J=) zzfEKTp#8(^voKkLtWCbfpDP5f^G;E71P=1a`b-1N)_Lv6|Mq4DBZ1NSIgs^AlYurn zyf_4$hWqqabv};QcCDTZ8Z!0VP;l8+htD2kam(8UnZKL6l<>6-aJiLRo7!-sM1o4w zYsmnGRh;H!;Q`<{+Z~l#p3lO&m~XtPz_2=s#L962n z;6P>I`P^yYQ_`J8;}!VDh%#`wy*X=hMPGeQ{shZu7&Jcii|FpUeW}#!fQ-{o#J8l> zDrA@>(UM!Ls#D_?7^z7I=q}#nLjx|%Jb1mo0*bZTPH3*Td!ddl_M0vkBDU|w9O702Qm|kdHEG3zzkbtNKrsA|X3u*lgIjbIytrs(lZ!6{bSwE@7yr6@nYS}>z zu6vz`G6H0`%|Cw`4K`;T39hrAH@9DbEZG_x$G1O_v17U`FPOOzpP+v2(5NAm(p)y#Fi4TKCwM zrcF-WYgy%zC$SYl&9XYPv?c2~?N@DZ+8g}5)c*H{lZc!D7IUx?4#FZsKfy!}(|<6N z|16))?0ITQnzuYf<$~hF@s8NgfhT+Nu#@X_wRy+6+L-V7-#lxsLWBf$iVs>f${LZ1 z+gn3b=ZQ-quU?zF@T`|IDZSuE1HP^cnlyBI70nQ;2sC3B@coM5?mkW$_6kc@hoylu zakq;aYBQV??GXgMz2K+=JW!p3JyBoZsQhM52E0}?9uBTqHMn@m*&F)Yo&rE(y@tPf z>k~4Q)1!Y?(|5dR(i#Oc;6IAyKb#B9UI(<~p37zA|JzH0u-gOKX?Nt5R8ijkrpN7}FOJD2-sOXlUXR zU{n+kuhZ_9Kc@>(v;Vy2Euw0(Att&ioB#E&gG{}xR{IY%qtfg>jp@WGzt7bOlWj|Y z`!Yi{67NmdO2Ns#Dz=k;ij$YtX+v^7E&tJrIX$#xB~>CMA2Z!lppC2(F19y0&mYBk z@3_IoGuyQ*KkU*9w^G!}kf2x;7`tKEVatJ`lGAWfR;ziB6B`LWcfIoC9~-9oOXzRS zrw>)hOM_S{V;5t1k2KYTgwniH+`fF3G(mM#?6q7KKeOz<7&08wx*X-LZ>61*HWT)z zx~M?y;iaKk2sa~9S&{KnH!i{S)Yh|EC;bK5YTCAkhlKSa-XP=GnYyz4-ug1xl^Q)T zw##LnPPak-G=QPCtErih!a=7_`gdj$)A2Ci)f3_EC^)BIPvJCq^4!YBVYSVdRBV#H z6wLy|QC1^?S@pkl99_>yfEmMg+lNp~LX;XF1L12y+vmUB-XzFC!tox~+Ky1BJfB~R zqa(OsC)aktk=b>NZsnENE-O0u>VkgzKu2@R-rr*F;M!VD2@b=yc$QfEAGULWEoU|S zW&bL$V-_PfX@x5!Y^#5Il{}}B&emZCZ?hyWF`)e=|dAbur-M}h?XeM8jwb`^(=L2U!zkc>H{nX9=Hn0Y@NIFX1hD*T!?D^bviFV7xA zU>0cz+aqdFUi1kLU>;u5y*~I&F$4tt#S7?rW%~!0*X>LdbUlhzGSf6zsU$@qG#Bv) zOSibA47I++m2EV!RMryJ$j6f^0h@{JguYT9$cnFnmACe08Y!(M@8l&{`@wIsP#>^E zgQn~Qyey#1#jg(6biAhVLjfMBKUvKDdcWE}+$Upzhr;GsJlc`trvl6M$MHDAIyEuH zpf!*^G+c??+}Ja5HOG~Uh2bq&2@3!BrgVW0PRWz0V4mM+LjXv_ZR(d{6>)FiA*;2` zo_BkEXOoj2%T%K%ewj{m0b?hs&Bpw^h3sGwwS-fLnvS-1L1pWRA`7a`EHW|a)Z#D0 zci|w1WfRG^&@A4Bwl$2ZMoV=(1`hgU3!PlxkG7+wJmYA0gju8rgzLvWqo*L@~`e}1s)IE zT;i`jh|e|^Elo-CRwyX1%{mD_CvWoO`kg2d_C&OKEYAJ8u3a6e1u|j_Gi@$UImqSu zdtb;h;!0X5=y8>cDxJlbAR-QqE#+*4-2qNiYu1dSC*Z#&KmJ6}2hAT5GSm&nW;fyB z%&%~VUTJy!337nJu9ax+)Y08iET4f0-nEMF3kZ@9Sa-Q<=atMyCR=D$rKso$7s@b* z)SnKsiC%_+KlRkmVGc)=_m4YZQw5p{QTf`DS`i`I=7^zS14@%|LoubQI3Ft)`NrMs zFkCM-F!O;TMtNVHRcg%tDZ?;CFSBFIU4iWYDWvePji0~7p#FkBn1tSMWH{)Xk5cWD z0~&6%Y13SPcfVcKQWSF(e~~}Sz}5EK{*1gFLYwQ?qXoTuNHJX_pY&gsOe45wRFgcRjgYx=vcDIbYym-R%miOq2K5-JHK4jD9eYY|7=d*PR1-%4S4d!ygUCsG~x!o zbCXDh3N)-bmU|rFD85S1oelYE$?bD8Q0jA2hzI$X;L>5nE{*4vo}_Rh@2B7hOi0-i z5UzL6&oY?j9QM#4hcs&-Y=jntFA+KTH~wP>K+hX+h4saAeqY`beR2Loq#$^ zWqW@it5}93^NF~i#CxJ>bYu?8L65U{A^(Ay>uAAV=v8eQAP-BGm7bLU$xSJu+*dI^ zl6BXDW5A_r5JH(7cs0ORwFz*2s-GV@-X(Xdzd&>>>Z!fv)>fMfUtSfB5A%N&dN8FJb2X-w#lR<77i{eL0AZB^`Ry$Tw>&?*z&I@`_u6; z;&f1|LF0fuo9ciFN?^KCB`PWp+Pg3lq9tD~m~; zhm5$o9sJ`WBNL&jDbQJDm{)E#9Om#8DzG>kBNGZJYl=fjr#j4v_V;uA)pMp9Oin?< zhX;oBPS`lw%TO{T(uQ+kEWh@kLc z5_1EGCEd~Q@MdG7->YTFvWvNDXRozW{lfLj~CK2~s>_kQ>m=jOI?{BvM z>Lq-F+f=5pT~QLtk50-!ZG5}lON2&2PrDGWge#X6`Bp7h&fo~lm^lxwXi7EFWCE>I z0$GuoB%t97tSQV4@{J&fxh28j`_!3CP(2bR0;KM^MKn~4LMxGqwC9NL>K`_|6tB&_ zjhF5_ftteb*)jq)!*oftKq?EImZpUa`XcarCEp7{!_`d5Y>l%%OppHf`A;H%lP-+fl*@0S;)wQVg@j*C>oL zG#vnF3A{4>+_-U>U7{YWqT=urdt@Ga)A!nddLY5231#yXZ*9Je@LTew_84 z>NtCG{jIXMbz(%JY(C?3Rx+QCCM*vqU2Cg!vfKF;(DPO~a##j{{MHZGn<Ahbk{XZwrW=9%W+b;XB|h(!M8nFAj*cE@V*w&w%a0uj zH28qceyVJQuLvB`g=$c`{G|Su@u&a?N!(Yo>1o_^+K*%F2IzQLyq^CmDlJ7~pMW;N zXai~xZS!4k!b+x~#qmXLgA{PMuCzu>)mw3hW}E{skh;fT z+jq?~MgA*t`G7+<7dZ{R(kYx6=E=Wb6RtM&}y>-mCnPA z_|wiTr2WhS(X;kOJHXIo*YbP7y8fwL~VVfDk;NV*=c7?`yvae znB6C>8pCqISX&5{cqxQ`R&AQ40daZj!sk5=1c*K=GhYZ};_Q?0oytdYko|iPV6ZeD zEjI`9zIH`&=}4YH?AbT!-ADK>#D3#?uj)2xFA*?EF;Q)F`h&azS`ZYHX6?-k*#U_@ z4h58@?I3kDmsjB`jvD?61~P^8f!wa=fKO622hxav?3`+ERX+M^5uu|@itb!r6HG87Of)XB~1o#7n&NM z=n2I3{c(beePQT#lACeY9Q}&o&nB^C`KCcK;0Eft6RMTN1tER7lX84A_+^S%#wp zJCkP&`xp0llomCJz>zTneLwwq;Qhr?z?|m$%aG8OVYi}IOPF3-imfJ!D8$@Iv&OR1 zQ=6}e@TJ|X5@kULd+$0a;NdA7kW=e8cydTI4!NZR%_Sj&rh2s0CQH9((+6DYz&!^Y z_dQ0A*_=Abfb~TTBa8>pIn#CqGRD5ZawUgs<6J{e*)+__ijvHqaArppfta);yo%r` zz=JIfzhI6$94lu2?+VyjKu61MAPNnl!QeBio+E*9Hv04O{F-@LItHa)!^}w2Jek`` zVIwNiqOuRqeA)V-o1!P|FP*apB!hi8y?^bY(=2jlO9PqFc<+GQtl+XslavFpx zNrNLtRUT!sJ6%a%GKr-vxHQGnMOl(gN3U2u1c4+ThCVH^i`R;8-#^+a`VTKlo;v(- z>7lP`0UsQWXSr1+LW>*IXef#$i##ComL!$MeCC|CBPk3Y8f(hGSz^*>1!I``BP0vngTR3y{y zP!yJnt?sRguMjs|xfPbxQiCu@gJv#qNt{9Zq8*VX#??dX>pBJhK*$ivlW;&lDFK^x zdme7^ijaJU%muR~vtp$p0Ft6yoJhwI8GuOhYU8XZWgx?I_nS_z;TsyUUD)xB^?RID z`C12X113q*MD}MD?9T$LDH?*=O)Gc|-w|`fSEAL#S;{k-$#Pof!w&OsMg8)Ro5*qv z>5flnkF_@=`^vxCJb%Y*%~P$`{}R3QR*A88a*!Y>cmgp|W+~*+6_7%ilEGg`H;yeZ zw825yO3YiQK&vojS$(7bUz?P>O`u2_nbW`N4}MCp#=-s5uzgq$FL>-fgCE0$j?*$~ z2nKCg4wfYNL|K6=tk_UdMIlt8p6{H-ok0?8%+6K-{d%}Ohk}ij4r1FVEC1+dH?zlH z5ONW>%4atdGzV9zXcSYCo$Yy3QT&9b?|S{~$48u#W&(idO%;DAXOYH0 z*3Wx$R3b;l1EdmxW)IddO^c==JlP{%h;r+9)zEKeoATWU9M!yx%XuFHi!zgmD~ygS zHx4RazBvbYIeUN=RLi7|N4A=0nta9s0KuOzkZlTI3>;*v0tn!9J-Q$RO1nFxP~-1h zI60gO3;(2FMl;_E0Kld(LM~rrK zwrl;O2T%Ac*{!?c-ePW@oM9_rIcCTWRNND%f<*4oOPxNuJDfqvwCe>h5z>S*DQ zjt})6wx||X!8X~tkad*7TxH&wnKce+OPsK|sg+N+h9iydl;ZqcB1krUR~(fRu~KJk zTW^C6+DgbY){d7$1nA9NFP!?10{I4{(WdTj)?>>9@IN!~ppczKUQT2Loj)}ZOXPHg zm}hX99K0x3GmjOWE?`tO5V_FhOLIk6$*%`|^TjNXCH^9Hm8orSS^K?4I6BrHaK5z^ zs^)FQo2jA%vKCE+u(yaX=3xrlu{DGtGVRJQZrb}c++xw9Fl`F#1F+7*8w*XkxfpShrm zEYDle=(t$QQ%C#2Q9mYtoQcROxT*6n?mq!Lf$+aOJID)uyN9!^Lqig53!`Q12OFY? zoUrsz<|H~IQ~u{!c9kgvuF=5EBUny2(}Q3CF(E-^ z$)oC&Q#8L{K0e&$*L8F5w+eS-X(zdtbyo8#uJvALGB!7>fjcH>U__w-}FX1TwXd823 ze?p`Hd27QzzUGH_0EW~kRytkjYGDdHrgDA6j}5+7^!}vk;1E}~1?zwy1>xeCbuO=9 z&r_Rj(?grKkvolL^F!b7uCGC!Ha;j??M_EY_kBjk6Pd9zeBZAd{ zPexTEQgdK47DPlQKBK_hBL@!mg7-`Q$ZBZdkLuRY2rByPu@afBTp{(~FpMIy_#y!r z+!9N~$j!PJ(f|Q(mDt7?g@Cc~4@Mp8R6TWlL6EhE-L*fhBhIbL2Ff?5x;f!`#;gNlwHlVhfsC;%k-9LR z2@KPc_X!B3rYj}r>cKzsW#37Kajjl`@g!qRQsUj>z{nA*()D$@>A8c@= z$^|P&z@H+-M&7TaF9Mqn#VReWEv@BrHp`@^Mb1}X_OA40U-}ZzGr4}%V#KnRB&aT50wFQd7g>aX64_Q z*ftQD`3PZ+L2@*^QNvSOcXPwoMVQa3Y~c!RemfnCGR7!q>%=uQOla{>CMI7RbWP2V zx;?YP^SHvJKN)fg6}dp@Tqn6T)v=XuT)&xH1mh089=#V!gTtEJ<5~IWz|4t|6OIPz zrNvW6a|mR*%`G`O8LPDhbiv)!%UJ!jRBnF; z>e_Hz4134tb2U~P@{Pp3D_n{nH2^U{VeNOyc7I@N2+j8lQ0WT^(?m$>y<^)X@2;bv z22#$km0r32>5=M|?!R=(bvo|nuoo^<$1jCusaPAw4|BPj_D-b>2I7Jmy2hcRex257npM-AA=G`1Gv z6_yyx&WOnF%XVG~$E;k!#_Q5g(5B}jV;U&RB03kbI;YveJ- zGA1UYdtY{C5rCa|@X%1iG(G_!3G5G90OQn3l-&$x_M9!@QKU74P;#hB`K-wYD>_=? zN~7QLJ5pqI9qbLCfnL@YBZkE927Ys_J_-e4h?#XYOdp_>PLgH!;VGy-{wbA!On;<}m$j7y?2+6tI zldAn*r|`rL9Z*`xRUqp?C>8o63R`bG+gWXTNAAB|B?tS&z_;%A1+wH2R|^a9x)2`Z zw7AK%CK>LoZg|Nd@Z$COvP``veyp(0!2G{`G_ysQBR*zxu+4_I56B*?|&I2FbmjtzZfP7t39h&gU@A)JM)OhnlaRW?!`W+6V5*T z3aeMeBxO1%o9dhTlk#C&KnD&#g8A52iM$>6<$_bH^9z=y8B%+6*(GqSK6fkt%(FCj4!&m&dZ)`d+}r)4#e(@;coy9hwG@|>%DYPz zT`{)M-F+pA+YpM#O)gLTUAFWaJfx^xBz%(?lYQAtES_JTOkoBN5=>Vhi!dL-iw=ua z*H1|#Ayco*?=`!6ki!rb5t@7+XpX>h61>*lA4@tI{!>&Na_uwj28?6fqkRtajbYwM zTHXu!2gFHZUz#vdV8oBFK=ZZ1Z7&sm2I#5ni*L`o2!qgok3%-UJ&|tBrx=}Yx}mde!*=J0N>1>&{t9DdRFzC*5cEIe$=L^E|eJy z4OgaTuuzB8AtxY+k-RS`;bN+b6^O$!IWP?KIj(#DVY;Uu8pXUWTCUj^JvjH6lsnO2 zPn^`z(#Ajh6RemTBJ~0nB2;lVin9-6c4P{dPY#wB60f zbr<{h19wqMQ(^dS;pIpKCKNL-%>_P$48B)Ea2;&*2{q>vbtSyUnuPN z+m#}c3uM-&*UA`q=w0uak>Kbe&L2H9Lt0S3zgSZc(cRkHE|ftG`{r{0)c%NTD)xKB zgHwPTqO%o$@Dp4D4(o+r3-_e3?vS(Zd3H#c&66zDoRZT@j`)Dd*)t@;bC%9U-4Kyxtcpr#AN!b6sn2B#5Ch{h;h z%JJ3PHs7z@k8f9iL1bmJfcDF}|3*rlQFa3wcxcHJ3=ZLiiv#w9DGa4C;xFc!J*s>x zVX#YZC8f}6CBBX}dw2Sg_bS1!7iB?!fTAD_!==;l_bz32cw!sdF_3FrjX4wm4?%^# zfcMKd76S??OZ@-7eKyTurygu~#@tKY2%5iZG-;_NOxlv^Ih^5JO;YR&jj$DT9Z%Z& zSBrICV$o;9CCTXmaQL*-XXyQ0=k%%!;UT19kFcYE*D!lWN6^r<^nUXlp|Z%YY53s& zK0+V1&-A`U#h2QSKg`S3^o03KcBqx!g9981oz60TbKBPMvHfQ8*U%45G|l0M#Rc|dp}C^eP>&p)L?*;@DziC zi>eS!VBN5|1oM^=^ELB&y{KhJcXCilg{b=z#zGvn*-?f_0%pbR>?5%Bbg#*A?Z-tg za&msYnmY4Ncs|0xjNL=--AFMPmc@YFr~lj8V(0QqE; zaKq0f#J>Uuaf^W&A{mR1bNx3|`KmrMlDFD)F@&VVSy*-L_?RB$;zAf7k4HwR&rA9x zSwI)i6q3tX@-*bmSGt=Qg6+sqliBBBTlk~GDavWrLlS!{~Z(~Q!40;B06v4@=K;}X`ESL zR85hiqdG<PBmiUs>cqI!GHR9wFWPG z`>6)3V7q}8l0q1mj#&!Y4Ct!}A(gakge$eK^E}f#~ z8%xOg1I7n{#~zSRkk8vV7qq>?9dqd;qc^dIEqcezTlO>!9p?{5PJeg(7RP2dpcvE} z+bQP8HeAE*TYWK446wu~kmahpaAO7RlL9$t3uLkL?^DITuL-V zbmE~d+8f-Tk#CuAk>`e%mm=wN>6uG2#X}o9E9eUvob}M|s9{y%9$3WsU+Y>OXcub@ z!{r!^Ah$l-bkiFvBJoviG^113ANWHO53xMv4*X2$BNj(BzewJ4bIuV!zkSI7*Ct)F z)LB@vEpByVS=y)5F>J;`Tc*hdMF%A4B?DDJs?^TCZ-3hVj^xo`>1d|$^JBZux?kSV z_1u-4tBVfBt+R1nIJi>i81H<8PrXsgOtNDWfdH{M zT+U9_=<26t!iM|g37j_sf;qBn8lkRV;TTrbpRV)Y9NKNw(v})N-c7^fki^?eNJ{tXh4V?;4XJg4 zqCxgvsG;ccUJLT?adgBhPYV@xst0A1V2v`Aig;;g9}H!0A8r7pDDzrJZBkl)P?)KPmTbPD?ZN}3Xn8On$< zuk@N#31b!Wx!6(ec(P+W%osG6|4fX0hqe9h_1^1T5CRfFgrKLGT|RWuE#FO}z=Gr4 zNk$HusTGq0{;P9e&9Z)lPx^A1!b{qQZ)P9@ZR;y^1PIrB(!&pR;oZJB)L((gH+{>q zs60`CGtSqskChMQ!CyaLOzrn5r2(*u&zUf_(8e?(cOn(!TWvexe->IO_BW)xWcHAA z#9&`rW@8H-kX&ycC#jPa`R|+caW!5o6bi<^(~xi*gL+y~x2X6g-IejYI! zr(1gJ`;oqy!Wn&r2)vDO0FFea&*#I;-U!_|0tX^>X5BbHTozuGv(l1M@v~r2Ex^aB zC6ca%z)}V&8pHRLSxBLEh{q&IEs5%(wNLOaKF*>+g0iTEsRu2JF>Q}>aq9XVCh!tu#kQKb(Tqqp zN4=~FIW?F^4ypG(5tyxtie;aF9(E56YNLEK)TZdco_M@KxJttCpt zb1neL&ss*w7?wH*0U43hhDk@4{5AVj3K(~SkYGDa&xkhUFCrS6l?z5L?K|#^BKq|U zr|075Rr;0nzm{vw%0|`s;x=d$;s!>Elp^9h)FA(7Kb2q*9%PLQRv}ZS`5-y#krb zu_Ae5Zv23E#(beg6ereo{oHZ&`_vR~*W&`rAB&0a$PV7p_ZE;uUvI2dZ`R^>0EvM4 zj<=n^NUQ3?F^uqat~ql=Y5The8M^AZ?&5et-i-9zS};FYkbNvM%U+VySoVglMB2@Q zu}Z$Bfr^|o_%^BOEO!FQt9o&!+OP=569Cza|FC+nX<Fov==Vn78}7Vc4fyK4u_uOtI-F?7Lu*@Zf*c8xQ-43^6SQ9Lm?b2MT+C zZ#fK4lGeVuy%Rg!r^!RV4!5ZKTbK_cBy-S>73?!d z^ze;Ga%*F0(I1MC`N*|9>AA$awR5znUOaqPDr#M6sOPvlo3jW>>F9`X1SWgA(vD~~ z*3HIKD1G{<>SwoAr=V4)?zfYnt*0~dh~MRq?@8_HH2OXyYUZ86kQF2dNG0YsUon&; z=1-*Qif{8C2mH~((h?UsJoqaDy%k{CpK#1GNN6RKt4Oz|d7la?85z>~S}2JGIQymgMBuGPN-keLolxQ%6&lZ7*B3#0T}Trt)4HA9RI4^UJo3Jk8Pg0dzK`dYF z!4pr;#`dQQnSU4GjR2GcDsh}peGKb4RkO)Y>G+RG8%hL}UVZgd=KmzUr4e9dRO6Vj zPdSEo{Ysfwez?*zlijoFN2a0Q?rU1F1Ok2|Ve$FrUzjiE=gyzQc^ccgcjG2(x_1*c zY@ki04eJe1Z0Zn7L+M!6Hi@Q)dHyh9YVg(+4nD*jmFg_)Nxw!!)mCY7W z$D7O_mJHG3)hXa^3(Mm=>bmC2YgKu>dQQ09{4c!Y^Kq7gj5x=z6#*p~4fO|m zsE$Ud5D#58Bl=BuW|m_G!A@{&f=a@?+`kn`$z9 zhVcLWM=!oO6QE>C0_J7K<5$nd;pLYJkkBu3eDW}oC_R+y29(?dv*%pEi$)}2hdR^nW1zWBLD9Ov)bI(0TdnDVa4kkd! z@jPegVAGyTf4A@0qsVL1)42&MtEsxUVSG>>+(Gq`RGol_p`k$|z0g4$NwSkvMPt2+ z7cX8!MMVXgsVddo-EDYWcHy$KbBuxQc_k%|eWck02xKp*sK_`X@OT9zk^W<|3^#|J z8^h&Mx$VQDcieT=a}&|a{fzrOoNnZaWe0nVynmJ7ri?6~jNFd{lqfAD&v#P+lqM{* zEnDbl?Y--~aU9?nDyph3s-=Fr=_5c%YD=GfG>A9e7{CwbdePY5jkMT)l$8Wgwmg<< zriJuCISZcnZb~xtnD-qIkOViWzUKf+Dx%8COcbvpd`dv+jo1G|!1V~*oL=5$h5#i> zDBWs6$xS0w#q^Up6|2_#mSs6Uz;H}Yqq_HbCkM6z9C4}&~ALUrwbKzgE-Mju_JFf(i5|dEy6)|fni@gV*0;CR^nN_ z@a&@;;~z#Z?Su94L(Q>cwb*~85>0KC_+^+|n2jeMTaGQ8=OcG!EOKU$X6mmY6;&0_ z1Rm{qWIKkQ7<0HOG#`^g^oP40EWLHq^(dh9^WzW81GgMd5~($&g~m0@gSG{1x$N&d z*;Flad}XtX)xY(SS&jNGd;9 zZd{FP-Vy*LTTofllPaEDg3|e=Si^eCR#H-O5{)S*BY}1R5-64A4Sg664XYF6Vb)eDDs~Dtu)=|`fbw;U!OQ@JsNIr=g0WJhJESLZNQTM4)J5nLLeN>2^F zI-VRx?fEuz)to?QQ$5tXGzOo#TJUXB1ue5-j0qL2nlmI0H1(LQhf&Am<69G!8~h>MwZxB=Yhvh?YZmUI(*SQ0C8`o>^NFB=h#50N`&}~1&2cc)70j6Jrn8gj zwf((bK*{p2%_Yo}_QG@?$wR~R*r+v%R0Rbd3mo#Yjbsn4va$;0XUg&Z2k+y<4?lDa z<`XD>4oqdGP$H|32A+p` z(w>aojh_9;6tMHD`s!2wrJLHfe`K2cT(Y<0wT?d;pd@04ro^8D-J^ig^|qp&G|b|P zU-!5$zoJp@&_aC7A}92&Whlegu1Uu-{8Wo*21i#qQ+@yE`n;vLJzfb=k|AzId3lQh zNyHU2iL#n+R1TF%MvenPzf2!7>dTsA6XL@8ZtVWH4*T}EgpMVlKjFsK!4RoP6 za~RvVkla$S}jb(FNL<=bOb@x!xK{k{|y}W7c7vCrtFv*;;uP6`FN4C_cRm9L4)0p6lhJrf5hjWj@Mi-yL2G}QMSRUUy#?Q}TVQtv@~Q!j?v zYB12%jxO(fw0ld5-*mITP{N1CyE8yFHun8^7IZL}fLdQJYJ>7jO7&E#yY+Z7;g6-4 zMdPXpNcYrYPVxyXUo?ovo?MH~4=h7Qs)wp{1a{f)^-p$c{DUJneWn9neN~UW2U~HH zp5!XKMzC>lG45Jfj4k&kVCw@k=$=lyXsn_$WH?k)8q6?EA`2*e_|5?S@SnXnOjV^p z+H;zj?8o}m!&tL67Hi9Lux3RL;*$H}O?CrHlu#0&G!g=on5_8Lm3%m#YdN_VKuKf8 zm?oYeVK=W%aQntCv3eFzQoj!p2sD5aRd54TTb1fgO?3_4efM1xrOGN#j$5{F!E^Ld zxoXua&GzE8eQ-YJEsRC+0s>0pH-SnjzKO1Sm~!#=P34COazuY# z8wE7q*f~f1f2}HS(YCxc`rhtOh1;KPulBd54s`vd8s!#Y?7(J^w>z<}p?pz5=^BVM z;Ujj!ATx;h>_UE0FK>~6QizH4ZkVwq%;@?qMhCp9)6KL6U$aLo)O4;*W~7(52>~Uw zspSiI_Mx_RUy7dJ-W0GrpzV()nj2AhyJAfv`NhR6=9Krf!Bjb9j#uRxAz!LYTB!1y zvXK-iFYlzQ=sJA2uLUP*f8-JkV6QBmhb0S3@z6tYc=(Zc^bPc)rmh3~z6;=^9UdI0 ziw^@zzxkC1zxr3I!*HXdy^`RXIA$PKml$5)a+zuZ%$FdRY+7*t!fV_Fo9NVVB0wpI zfRaF^A*u`xQT^&;ZW#achkhKc?4>K`9?VJgB8`+8ypd_k@Xv$lq)VU&qA((S|O@G6$sZLJ3nSjz{WtwQLRy&*PuIgz686*ug zWq7EPs4>Y_-S2ZYi~>EH2q4wf))73aG4@ods;f{}UuO()%SdlZa*B~okUR9k!r3UI zDqC@JG0$gF-7VWlDoOe>JuTgoLFFKI41I0C&^33oo-sg{8XWfgsH$aI>xqAdCwYH#@pi%+#=gcZ8v5yGWCm7DPK_%-Y%~RX_ zUTg8OvqZ^3Vjar@uqPWgAKNxJyiyVzqC#nbri1+n=<6OKR|Pqes4Tdx4OFTfMF;)P zRy5-5`38zD4xp1KSq=8HzYeBhn5V<_Q*LK?D2i}$F1dGd5Q$LTcG3_x$u&ssx_}Ix z44D%iLLY&bFZ<`Ob$BDfC^}qY@um8qV>n;tVpEN7syAQ19X><1_VkyDqW#!Zz=L1S1sSK*>O*apH7s)VbpXxg}mE>ZWl^a{^;jdWl@C$bX=JzyQ!~ z+qOaF(HJ0m@2Y#T_3^D(y?Qmu7nV~eTCu%v5%{_C+Vd^R;#WuFb(qm`DoDVL>E{9e zF_(PD^+nI0^q~GQ(P5C?jzcDf`a&4$rDE>gRoJ!b5)K~A#LmiMK1i{7ErMp`4ID*& zVhxrqT#0)YtwgA`lBn%PTxe>?@uqIHN;ZyW44_n=h|>84f;k;2uPTnSuKmT@@tdogpPWV@T+Q$5N!_l5u^Mc~?ou4QgR{dy5k{@yMMxHh2vsfp&c z07_rcPORB547a0Zl^4H>ve??tYlBB=FXGc(wK#RA74@wHSi5)$RxMwG z2iAqLZbO8dV(KnB+sISic-qd8&t6T$kA9}jt!D(`Bys_4+!qqb z5goW86{w`WvMEXxpkuuLUO}QEDs+xb28IZ>E!|#k;^0#%X2MhI=%B-sV@O*Y-#0(;C5eIZ@+f zTU5QP043MVoa zcQZ>$$k~y>wlAQSMs)BAptN-wqx2KSjL=sBN^)s*H2O%Wk6aBDU**Ye!#d$@n5P($ zYp9zXKCRT-(j;)Ep4;4pFqPR4<1!TtpR25)twwtnk16gSVjD<9N+geBPT3fs*jJSL z)QU19D9nx^jSBA5so*|z`6Stx_9G|Sf~gr)KpZW=$Cnr2lY!any`2P=I?+!sX^5bb zaVRnWGa@H3GkZH`O>aZ_qV)tGR%6kEOe|QKNfFpE#|4TJHIJaJeuTPu8u8W#71;M> zGa5U{;mCY!SuqO_t(}P#Ya&=lusE5bwi?4k(^y|MO1K}6Zv;kU|L4#B_?Lh0!`@2j z{~~?oW`(fvfe0RWFpPzBJnMCaJ{T-l`%E+Ws&WrO-07~kQuHIcql7)X6FXiU74EpC8wj`Vg(pJ0Ucfss1?P9WhgExMFAR-m(YN!mR6i-xQy1`L4M)@il^j{awt(* zd?`UCr7kW!WmVXzH32{0?)sWEjW6Ta;slE}d3_5h;QEm2W)e`kg@pZvL=~(5I}Iqg z{_Wgv2)({4o0EXjS5fF{&)o#T2BAjzm4Fgiks#|dI%X;kH(~nQ~B;s@n6?Lak)NE=Ne)>ux zUj6APU?VU|{6B(h1R!zS%Y`?W(+T7n;xpNVk%(D6)xQTQQ872gYwRU^e^lgckQ_E| z{e^(ie^TV_Tn8=>w4)%o7poVBuxe#8by7^_CTA)_NdpK)B=V-hDg)d!hL{$QE*~|z zw%pNWUMvG{a2*XL@0f`nPW@*_TYc%Ly&evwl#~<`dvoJNaNKoc$koR4pnvdMdDXk_ zedW#K6>6wwYyiWgqbb{_n6)@(T3T9Ab*b9y1%gQx7pQ2Pr??4Vk{+c*&OIsAfiz_b zk31)bO({9oN=r-0ku)7sDdv`+pJ)2uq%SGVu!-DwS^9x_$Vy9T>SpEy~enMuj^V?NxEc%&*?qpneKzn-TTg8_X3o9s6#1UKi5x`3C6t=WN3V9X1O?_5B~pQU z7}-3|JePnHTJ~Y6`hDc3^q_RsO!S0G@aE|SWn;^#sd(tV zspK{cZFKo*0w3yJDxjiPj=`EGb9z3Ai&k%avdEYFWel7$TrDk$pqlTTKFMX+PNoy!~M!j+`Gr6+vV0 z! zMl51?G3kC&DB#+F7NuV=pyY43e8LS4i(5+jK7u`*1dV%%Aj9Fqb$H{=lLVA5P|T^B zM<7#_Z2dZHdFTNwT*5E=_au@#sfjw4YIsz94>=0LsO;d;$r%MGpPqvszZ}NPKN<@t zNg=mEHnytgmXI4@YIUKm2sUs&NT5EJgpp+W@t*$@Q$t9AlD^{_62xE>dE=>4Ixbvx z+v^0Be$|aH&s;`FZwoTRy;w}ngL{^w;Ngd+V#9{1NKEcSNLDdRmViJ~0u_WOa8qCj z@pqI%$!_?gjioxCtZxFB<`X}8`_GNS{$}b%0422*jTN>i^~Z15e%u)B?p@a8x@W;_ z7f!CTYJbK-z_zG#1QK--=+KF6m6s}UiT3R2b2xM6tckT;B9~Hk4;2>^9Fl16jA=9M zw6?N2WyYbP6Q0DSlwXi<;%(9cWgGk;y{yi?xlQ?VdC|2quDro=1j%pVT%7T=*TaBc zu-q>GpzG3*Yp*fh!0Xo9bg$%ONj`h-!l+t;t!FfD7h*KL+JlUMI{`|v5+#%shtlja zA5dbOvGf?Z%b(s;9ogLB$78+7+J*YAo{4K>ka}+hsoSanb+z^AYRN)xTQRCHQL!}@ zreEYKh|L|PXznW}P(wXOLp@ZM-Gk(W9_uq1>>mjU`RI$zM_05EZItU7rkKwPDzz_P z5F)2ihzj}HZ<;^GVAUHa$R5VL#mmqgD#sso&%hr}XBXn3O&hRb(?e9u9YQhzrTUr?T)Z&C)7@(D_6Nsso?a6D8# z>^t0n;}@yao}$2u*iNUDv(K4TtEOPZ+9{|%a~{V(JB+FZ>ZGI2!c6L$TTdNIYuC=f z+=T==$)%)x#yFH1#b_+5BR=#!V)f+`ac=Mh`6>sWx*dShM6;&!gT@9&x3CI6n7qCw1solnYnuYn zb`ns!CfUA~4_zD3=28>QZ4r4B<=i-;>#^O~yX7KS-U=pHUtFcIH_-=_`UXY_9t`2Y z!4_Fv zhtkX}{NSY|eE(%~DEKCkWi~)b3oXkRbyAS4!oVVBhW6@!lJp;Wfw=wTMn2h&J(sA~ zd)xZ(hu`riW^yz%x7YJo2TF^%37(gV?`@q$JClVYa1|b48AoW@|0vogeknd+T?k;J zrKnw$*0>au6hn*wl;jsjPlXy|>^%kJpEe$}w+c{FI<5`5G~+iD@z3oYQBE|cwVDr< zL5Dtcw71*w_1Yv>Qt9rwigRXLn_G=jNg{C49imexiwJ&9ojTRT*=Eh0WyhZv^FAj# z8#y^SCf=5mloUHY+@)(($8<#xXO!3Y{JQXR$C$X=G0%cGqtRaxcQ9D++M^47m`31r zwoO43%Cz$By%Bs)ijqq~`%Gm{tyASuIPV?1GDX>5Oaeruv#Pt3;$@xvMq6=$2~e6< zGTS!bF%Bgo7-R6u9Z#!4D%57xF|I*!BoQ3y=%DmbVR8*cs2rOov8738QYyvY^3ZTO9cL(lR?o3u^{fOe zUcjTx$*DA(CnzQl97CvMA5Zxj!OZef>VcVo-@TQO*Y;+hp{t3RqIH0hlya+Yp%OWf z{g_rzhw_qqp4e852RAICU5qgMUxc>0k~*DE4q^A+O1!h<08U+OMQ-LyOe>sD?u{a> zf3OfG4Gc=45h61n`WZv+~c>jS|) z;`}C<>5C9q8=rz*}#=g*RyhK&u@~;r=sEKZ6G!e9*>+;;Ei4C6&wN z+qvV#eW(0H;;#gh6iE5@GiBA{-*|mot*?)^*XE)GibkG18pY?khq3=aGxmRZ5lxNF zm>C&H0Z&A9X4%@gSjv;!>dsyq11P2D7hv_O#aOj!4wftrV-c-ofoUpPXI(tjrTqNJ z?{1*0%iDL|bz`;aWD-#N?zM(k{Z9f)x1{nX0i_!yqnjW&lc-UCoq&>x;1)7&vU2W? z7Vo?Go};02Cjq7JVk_{Pyk!K80QW{Fw@?ab8yC2bz{)i%rpyk`}KwtqX` z>&I(<=7#Y|6KZ)f)xba-b-sj9HY*h`K3|6Kf4_|3$i2aI!b!tOO5t(X%t8WBz!Hd* zKn@CVD@9EUD*g1#l=E^y=s1+P-)F4jhf^JEBPDw)0VO4-b|h;HR;xtSCE*O; z-?g(?SW%7~1j>gqE^lpZt*EZ9K}AIcMI4XN9>a-~Cvfr<_2l@bu&@x*r%k7L&>WPP zmt+3?`7y4fES^Z2MKDRlR#v3odx$!jWD-eNS9Z%EX~C?Rad~vE=j)XtST5&puB(GF zo^dyE@y9(K_tx^JCyYN>y@ERp3L@A_2BEPJc`G0(?DrY*^;rPbfd%HRe8}MgDT5cM z9b2I3Q0f$@G;Ck4_4T@t+zB(u;U$qbYkT&hUZyp|%44kQrULCY0zM55J*cbVse3h@ z=MGhxsA=j$RogI?2oE4DOfIA(a+f7dK{9nD5r;xM?Xm^=Sh}QueL0M@ z^aS+sl(mMYC@L;RvHLV|p3-Z}XO3X`!YImThY1EHA}6ViygL_>GbM_`Ir*q-%f)a0 zD;=-B7eRGL1NyoeMgb)QZJGCIJyH|SU{-!7l@m|H@@3P=$uf;fwkeLvLP{<7#dAYA zabyU)cAvw0AMM8ZnikBSIuG+^mlAj?!UGQ#QV&g-B9@5=M^rZgnPmj}_+Tl0JRZmd zf*u6TIF`NlMj!t4yIvfn$Y0lR9~Msy;U_=N#Z%7_1f>qBY+7+jYAo`IuGrXisk>>6 zjvv!W+H%+3Zs50qc#~duAjvF2gBT|YnPVA$85MXZOqWP<8PGS-u5=Oy|s;F z|6!awd6J^8Q}Ng%kKw`f4`S&(OEGueTyG5IJ2EaF=bGo&@T1&J1W+2ILrHa`yz)m? zqkcUwa@lNBVkY$|WuW##BF>)x4t`OKk3KtwDvFsFaNfxY=ssJ#ZaEgOUxC`QRbv39 zq}&25S+WSrmd?SdwG<~`8?p3a97;;p(Molqp*-f{J@~rm>azD;ch!GnRUeap(s!>l z#Oi+%P`V|RKM5$^C>h-Zp~;H_(j=gCqlCPB-cvowICm0Ix_j#8PUpn60WLReq4D)` zDA~H0V2Rf@wTF=v$Rd%q>e?YxTpYySz3o)A-Hb!02-5T%M^17he)|2*`0-1dkWD}- zD?dcN5$EvQ8%J^I%OO-XO`+1;0?aSUp|aa7JoRi6o_Jn*G}QjN$K)b7V%$NF^4b(q z+>IMUZxhG>BLsJby$zyP?pnC(q&F!Y7NEpf7?vQ7MWJ7wEJual@4r2O{RiuD{QNmI zceY|mW)ezgWZ;J{m*JIHN|}yMcN?Vi4P&7cj&U&o?w3EX?qHS$ds9sxJi;EX8P{fS@1h4Ds>$wr{ zH08VEILgh<#mpHqQBvY5*`76f7N$u@QeM7sBuP(-IFe#Yc$p8SrA){#mVeU4Hp^@W zt{l#FWK~$1*gNilc?NH;an1OhiI3m;o9ow;wF7x5e|`YDvJ$D1@?D9z$Q=#g1r(qp zaV>#L4p8z=UK>T9y!Pt=B`QBBhf)vKtMqgx7*~fBa~I?nQb*Bj@02%HpE{y5{$)oy z>+W)t00}KmLu+g7M^i0zx72r_sihIEZCz;ZDMov5F*(kf$dS~9%RQZF>+MD=Pw$&X zF~uo)6h|d+l%Er!=vSKA1q)MAzBm;bSz+qDp|WnKQAs^UM^6o5=l&rauOGsk`~l3L zF@RM|(`hp>wV)gMneE8Pi6S{K6_qt9_}#A~_@C_wxYW^zf$l~QBouj*9wqCuDoiKI z*GT7mMcRQsgWPn;*?WBuqY_NCGaL9meq^!xW*dz>ZJ$pqd;Wb7#%rsgkAa z8^vbRGZV-u$F{|BMD^kQib%4$lkxg-OY_(kpoK$tN*|*Ro3b zYJk#pCU;Z8$MhSPS^ZIz9wr;B`nJGnoe25)-p{db-#+ZwvxjxI+xq*$1q*FF+pu8+ z?xnuH6zWovJ|&;5v3$9{9`m@Z7p`4+iFja=D)Sn~=0?5eENS3>T##e@anVkWyB%y6 zoU;gOUOG95GY1E#sJsdve|`+LRrQ!2PQjFLGEzB4rb*}A>}e=2osP!3CR{jm0o9iW zQ9DB2X_-a1XMP#Qv}a)5#t7Cu95IO6Mp9-$9KDufWk+?QCLULWJ4@4R(C$0_Nc~6F z<}r@tlOk{5tp*XRf7ZR`a<}f2eIB8d`5#4a3y?;+n4?h0*WBl@$ zzqB^=^Pm45&prQ~cgP9Hk}HhH1{vpici;HmNkHjFtI$mlY!GUEUkNCgZUQD2cu$SV zmRWur%F2ySG|EHp{Tq$PBKeN~I2t-v3o>16lc|MSV`C#~$RQwwxYA7`o6WEO89edF z4K7|K#1YV|nmEtN+q;Ipi{H$Bdc1%yS{RDhha-)ClG*7@?ADDX6EoTw?-`v;Ti_XaMi*?BmIaeaKJk z#>|`^Y1s$P-W7G zGOw7Co{ag^lJM+PiR2QZ2pvyZPfkfd#kmn2Q(xY99-n-+7fn0?Z^67$a=Vn^u}7!l z@kgc;D`FfJTV*fipT-Go?KL*IniJWz!4IRhhWdU8j&Faj4gdXSGfvm{B8@a%S(1vM z|GXH_zL-ydnCbI7vnQeKaI_sHxFNzKrVL2r4Op zI-EKMiwQO@TU3ZmTa&QqdrAI?LV7XlCJL(}C~;O%??owm(vYWd(M@#}rcWFi4 zrfkLPU+Xm5NkHl52t5fX-6;Ju$H{QgP@}wAK*^%=2R4iMI)9W0H~H(;;PrJz^_>ka z8p=3#5>WciHicLl&|>v#2b648%oQqK11LE0nc@9`LxcF}(|+v!yaT&=ba#DAJ+ecW zFsHBsKYU>gUitnSq>xh}na6K$|4@L^mpE{=50~2Wk&;w^`{x&9%`zT?yqPB{Z6=_^ zIModj2`D9!<0xd{5IvZUS6K*Q4-)~G-4X244S};aVQC_W7;miqU#tVy83yRf2=$K8oPI$ zdqo^$A{^&N6*o~6mp}KaT=IIC9n8_lJ&=H>WS{_jp9;e zFDftgQXFlVr|^xCyR8!~4XnHNHUdc9=qIQ+5Gq1Hl~`w`QnW2CjPxWb-A?Mnl-zUz zR?{$RdK#vebYaT0e&#uwfKoQ{iieS3Ji<0dK$psa>*|1GCkFBP{yx0BqZ7N&c9Ju( z3xye7*g_Gt%^Rj+et8OYK82B-!8XQrbK>+ce*c>h{P+63v5{7q zYxJkS$xkvCw^u)^Baxl{?B5~kZaQBvL|tGU%RXwuyW5*kK@q@YR@I7j0+4>>NtoAQ3N!Gw)(yf*4S0_U5+_}^ADV;rg7F|?CJ*8+0wr<^u zO&d3&bPkpF(^|h*1^Gtt#`?JPyiKkLCXJ@;kL*{b76>x>jz$9Zeb&k-prrAYZKb~* z3AEi!&FE=tA;-}$P9ICa(bLU1a^V8%TG}b*nU3s~ER>hdLV4Lt4EOh9c%TP0jqSKV zh1_*LJl$|O2a&WQlv9t|l0{R=wU>mAj}uT5-Dx%Tg{*N~R=j-6pEhRfKIk#pl3kdw zPo3|id#fp+{v&H`oa>EAKE}j#P9SQOw*pYQ z(X5R3-kn+ijF6==UH=l3U25foCiRNqNQ1TZ&Y?$1D5eQ&@ocVOu z0N#3=o4bSUJOY^<5LB|eFtY&*X7^G=V>#_IM7T3cB3HqC1eE^p=OfsEw3~oZCNfeB zuxZsytXo@*wQC|gwT9pbqt?DG#O+|BuSWZgQ>|^G3;}NJiiH?i8&V<=btdz7kMcxg8tOw*UY@07*naR1z zvV|N*5n2yW(pX`OQh(>*+K&U2Y%B?G()F|~|h znF(2FrT(JkrV(z`quj7Zahca`^t)8kPSLW<)R8oVE-K3I>h0u-hE3=j=rZsmOaLX7 ztUjr%r`gk~h z(%Ok*(x29i_jk5pCr?_-CMcDW+J(pOE5Re{W@G;1G?dIIXHgc{DCAl>PVu;3{dx$$ zdA}ch-EH8}a_npQj5N=qiE;j@GS#oy-_@QecDkuNiq$KkShy&}liNZ#xWAK}E^Rn+ zvISKHDsqzt@bH>!th+xK_ph18Q^cmRKBU=7+(csmC5a~zt0M^Ll|y9_Fm{Y(+51@= zKKra0HLX0wj=5NRJ%Ew{+kP?V+^CVRpnE;X z1RmY-O9NGvL5?}fmpCJ3Kl}7E)1`Fq;6Yrtc)@3=jo@4(^#f8QKTx=XhH9@A@j!x9GQT8V#vmLL%`ukR3fZ_XTPhM)m!ShXM=^{8v zV&g0Ucg&g*6|Yf7W%n129r9HNA@pe4_+C7GTTfa-l@G&&bEt2TSnK zgVU*aH)1x*NIgJFOL9*+u?G+_Z30T#9O~XcCUPf1q9)3S-m^bFa}8ekruYy=3__t4 zZj6(;=}tg%T@)XGQj6dG`2@Z=(};q!G?Y%u!cSf)!;fAq^Eb{aEAwqDbH;6iaGi^} zh+mXj7Tj}DjwbHb{9M)o&n@5Dc+q|pptRBerSD_&BR-%+u?W?RYcFoxb@yZPptO}w z{`K_s7>7W2S2twEfpqHBDV#ZT2A3%2rc>P7+S+V^E4?NXtu5f`LgFY8H<))jRolJ6!T^mu> z(+H1ft82K7TH2)KEROp{=p9S}RjW`ZQUcmqLIfVT86l|DLfgp z^TA~txzt5Yjy@ES18VE~RBYUkj^#@W7_NX#h=3B691BiLFl1PuA3-|OdT@xN3qfK# zHI9JN!NWZ`c&G;l_H|A!x>{18xTCWlgSFLn*r)BwJmR!HMi7edwtE7S2we)}) zrxNujX>1cn_Q}Vem_8+eO47l$XwhQU=`!QG+`M@c$B>X&>otr=?ky`*eBHPzbS36^ zKU%NOGd@tfzn+g;31#zhh_xRp1A)|$`dUOAYSD1uI2vhN28+=aDMx*Kg!+@3aiQrl zj%yrd8+&BkT5MXsmh6VDng4DCIO{ePvg5e##sHc z?p6PH3{VnLtmEI!)Vcn=eQkh}D)L&!RkRDI0od8`-gDvg%)O)Q;5#;m%QMbg%|9;K z*jqONuoz13x;c~-oBytxbQI4G9~`FL_;DKV(j^J=11z6dzB5gO< z=`)xHsjF7b`((Za>0kOWONY& zn1bHHYZp3@yB$NfPgh zr;nxU{fs}ydj#CicwA)Cvmz_d$J=~I$x%eagY+c0C~?n0-V+$AAcsQ5`9}0M zlGB4gQd?&TwLKIi>ZOjQ?qu2|T&9|qc8a`p_9dcoAdyP%)mMSkP$y4pBPU+LFi+E( zhLW-Zq>~{ijgn@C1>{C5Bw)xskU^QeBr3e7$}1$28;Mw@aU@A6j>;%7iCHsUP^r`< z)LI|Kx#Pn)@I?pS*-?p|$7_)srp~40UTj%Yj!pM3z(N8_a~361DL0EjF}^buL-_Nb zhVVK8rAmtM4R(wJD47l_Cd7Z^QX-&~L$0Tpx!qV&o`od~v#E<|2p=7w=xhrCV}fu~ z2#!6=&GqJuDOg;dhJ~~S(h1oU?P&!t5!NytR|7*-Ha;A-b{i%L`uXQPq4M(<96rPo zAdgb{F|##9mXGDL((%9lp%5>;oM(WNPPYsKN?zSdr&|C}QWJ1htn2GEp2*v8ap2$q z>P>9mNp(~3!&iQYr=NOyjL6%VXho~Lz*yg8*}c|Iiu>blh@hR6b4wT7i4!NVZ|`1; z7k)%8C7u9C9c(ja&a}e@oFZ9)*s=b7GsL`JnpnM!64RScM(@W)$F}9qR$hfG9Q(2P zjsi;20fLhkt1w(yh594MQS;?-cD!;V&0mL>%SlwuU4;{8>hVQO2hOw8t|zC~{cBeu zJ9Pk==>s@(_7e6VI!7H}-RSHgaG#Wqg(XzVy>KQrQQS>>lx&nI3gm%FECjP+xgIC$ zHU=KCfKrSUxAnr!(`xIJfYNOx^<5cxtp2|)KuJ^?XN0a1GqL_s+~Xux%U*#y&H@(=&$SRGMW_pbZ-_=a(Pnv zE}z$xm$<;UB96EyzxB7S4xBp)D1Gaz{Hg_XZ9wD6*9|E7Bb<$IVxSPGf`&nXC?9_^ zh&SHq$KFFt1eB_%cccTGR%c+{eOb7l`b^fYn2H{5ihHDL74x zpqES$UCjiPK5oQ+{{Ad>pKPSwibTvPPQ?#in1dI;KZo2I2}q|UMq-;%Wx-B$GjKrZ zXy6@d3{c{tV9cW{gV}f;dsEM8Ro7PlO11R{^yrkg-~R5m)SuIgnbT)NfYS5Sp|oks zCMvx303T~Bez9Gq5_~A~^ds>g00BuZZH-mpM$ot~y(u>S`{j$xhyGkO?%eQI zv{HF&vKw_r)6l%E5|3j7&B30I7cLkkc4T$Wq|mh`GicW1MwD zyktis^S~qlN?w_U2e|j zF(3g-i?DIs5-j3rZ}SK!WfH(rJm=020EuBRFz8jD}8%_)*qw<*W?+uYbtH^DpHP zd}3`9Q1TRVdmKtZK#6=c%CTogtJ(QX*mX*|4;HwlHC7llW#pj<>Wbqw*`Q?`;PODRlUV8B*y!hga22|%$ zIk!Y+&D_ayT~Tiub(DeeGNIW=?N9ZtzN2gP68#ELQd^&E6{M}98yab zB6sC_avde&$VV3l9#&&d?PZ+m9>UsXOR;jrG87jjP~0(ub7%Pcixd0+(1oUsRQA6- zESg<{r3{^b;%Qhd6880okJehIdOae-d61Ue?f05N( zHVG)*URvLcvB&Cv5>UD&)pN%IrPzcwPWD~Lw)w#ZWB~I(48J!jGq8=f?DXvT7DxO* z?GMIo(QDEB@7Q%9KDVHbrKjk}jPUlxRezL*rYf5N6fXy)>jsqk{JXN4d({-L?|}`D z*HND9i~ZXh+SP$`#|MtwC$mFJP>%-Z2_~9HZUr@|NZ!x;L zDembXz5-Axo05m0{9q2AdU_^Bsi?b!RwJ9NG*Bcmecd_Z(S-N@B5Z_XjI0acU1>S* zeCSf#O*&~3sQe`%l!U%^ihGeuY3E1v_{DEd;^X7>$Vv`jT0ttFd!igqKUq%hn?w{% zBhLZ%2$rUz^B3vnDnoI!92ZcE59hKae`gqv(ufC?>T2pxTU(1a-+U9l`~B}s{H%0# zDORnz7tcKVG#=jguqo9J^Q1Ptt0G%Gsw5h3KJhpN1_uZ2{Wfmi&sSV95J^CitWJ(> zZ*QmgTQ>%%CrO-43l=OuIqj69A{5bzdtmnLSu*<6OjF5PR_<;JIZm6u&G zxgNRI=6cyQc+~tAMl-c?MGlszchaD4m1l9+2{x5c+Z`5&LMu#F0RzB=!yVHCk~hXd|qi=Zt7B4yuF@L9+zv(jov8 zp$O^arVuWk8^)2t9r$491?(cHMb`k^5*1{B?}4Rwbi*GBKLCI`F7-WtO{8^ z#WQ9+xgBM=qSDm*uSVRj29&G~b6i9#+j;9{bW^!@7j2|)3Q{?qU*gGvdv;zThg==L zsA$32wtlRl2;kCXi!oz*0%pzh0Hx3O5m36&g%$!z5$YV9KZ{Da7f!?0CzJ6wt(V71 zKfhN&m4FaCPfk*Cxl+p+pXWtjsLaZ8AoO zlA?@X6n)DEjj>ewcHXHCSUX@{-Vle9$P!=g*WE6d2Om^YUyhO`Xwc`F=%T{luKq#n z*%ih1?NJ;)(TuYVmB>r$!gE`5@yH`w^p+H0KE-RgdZ-wf_RY7?Q{?Rg4xi0aHH?w#m7{y{TJY6Rmo28XR(j}u=_UWNQ5kQeR%Lq}N5l+OT#ne_gpi<%#Jh^Ex9^bMErE|j+3nF(1 zl>s}jCI%!aFlKJoerhinp)!;dh@L}@%umg z9v$r+JjQ)4R^PiCPd)V{k7QqOA|#2NQyduO+Kh9D$xfzup|i6K)zwwB)i`|kOX{CF z#AD?tenC!w-af(-+$3vm6UUMCBt7`xdfEpGCKaNH+z}E<$)dit6e@8J5oObSs5)Yf z4MY-|;^q)doQW^H^OqY4X5Lo|OMj&+W50p;6-D6I!rai$)zbDO zbE(ULl za?A9ih03*CsXNJ;Zierq9U>Sd{XgQG5yl}-q-?g=EJi>3o;;MS$i=j25pp?%kWDTm z={!oMa{LSeOzAvzQTl)+zBNJ+D@x8NPk}YTLBIgj|$l=3>p_Ed1z|R6PDY0#72e(S@h*5mfTjE_kWX5vtqf>(d|>eV@vl#mtjMpC==@3`?tF{}T(aZznZ)YAWn<0tUmd+(W& z?xV+!qOQIU58VF%?!WIo-2cD>cwpTFc1onZtGe?l(2MKVXL&TnD=JO79*?;4b90UA zUDor{uT#pc>jbv51OjFWJd$yQ^Pp@fEtwcle2; zFO$*Tc?!hppLMTw{vFey6{I}3J< zvW@5##C~iriSrwMdW|cN_*Nb^it7fH6fNI#@5ktJjpQc!$PISRo#=bt^>D5ZoO>-m zNjj9WvOGX3rbEdM4)H4i=l@+N@HeRZY6Gqv7@$N>kcNgvG}1bg$Hj&={MzV8rQC!@ zVXxWmf^8wbow$g{xZZMF%S$a#O)Q5S+RHqZ<}&r{eD+D0Uz$^J_*@4rw%1^KW*=UB zvH)8j<9JE^BV|--+eAgdO+3E*-FGkH&##@qiOS0u;3jcNNj84=<8nOnObL=xc?MgW zHpki|(=t8Tv03zKVrAeam}91x43sb1b5iF_0#A8Mpz9eelck4AqAs4kngMb)^miuW zqn(ZTw_l#ZjxTGG8W~1GZUm1$xCmPwT7>xv!k9;!l+5%9@_1`?0#Lf#b{S=*Ww@7s(zDM#!;SO9tZPqst;>^ZGri;j=<4b+Mca02 z+xhdTsi{VFO^ty_0+O^~)tn(^+aseSGo4I&dsjUPrr_$LK};qid4Rs)RolDEQ`8+I}EN z;L=N+am1&k_9SEe`tdznPq2p$v=rwWD_XY7PB0v@81#Y9&M|eM+BV`xc;C^0M#~(DksMc^&M+F(%Gbh zm}gV)%j|2PEVxN!7l%@a97+iUW(6uq8F*z?6vw{oz)tE=+VjPgfYOrX1eBH}BHIB< zw^1~lNQ1&@e#Oz=GatwcY?HF}4C8DA^iy(6W z=1~Ftnq_%-?ggH_wS|OJhqq2Y9-!nC%Tn`$vJ^LBq(e!kyh&-b)|SOnsFeGaR|p1UoMIQWdMxg$wzYibwqW%Z(-@b9(qJEqKjo<}2A%U9w?+&KDr{`S7T z=iRGSc~-CSfxOw?5-55t0C$)o;E60(Vrm4Z&U9e=2Q~O~cOwp;q7J3zLEJlk4#kXl zdgc{?QXg77vk2zz?D*i2%y;3Q%0S0*~K0In>~ zo!DEGpi7d2H1fN2mBOagT$y z?)4FW1KP}uPIGf3c7B*j&ZAr$ywpzx!Ht-eGl*B7oq{K}=JQDM1a1%#xOs^3nB*u$ zN@}QYi6U3rK!+3huxM@ue)8&KJV`xDiOF1K6Tpd(14gGvg}I6F03~KJZV~I~A{|O5 z^2YH``QoQwj`Li&huj8S%X;Zyl4ycwhWf%7=t;uIJDc%u|9%cT4%bofbRY7vLfE)= z5gxvOAr>x;VDZv0lBt|KO1gWr(}r=BVEz#9qP0g?jCZ5KN5hSCWp(`(fKnT|IcD>t zggBI5kPf9yn_}~aqEyDNk!Vk(tg)E8Zw(wlnf z+LSiCr2Pm1B?3J$VKcS7Rc@y+mvM7Fw6l#zszX$3r`ErT|M8SH0yxgq4`Q^ajb6d6S$NTY7B z6mnFHlSx!j4iZ#2t$hdz>j1>78orQ_#IWQ5l2#aTFuA_u@ehW%#sDr=1ILbbV(0sn z*uC#cKes|xWb_0-(IVKiQeyj{VeWFmSZno&8>c3f^I z?rwW)8-Dd)zcR5faV$s?{>v}Fj3=IW;_84BtIGNV-H8}ChPtr9u`773=Ps=CclYky zpli=a0`+?rUe7g#h?CI(XM)q0DSoSU^1%ZK@jw6bS8|N*wDCmG|MqYH7Jv75e`g@K z#A|O>mr^jl!E5Eq<u0DuL_^+YQ~qR`%u*y#fo{eux#g81Js?C$9D^;Pp^n#$pv_U;%?79 z!w*V~UDjHkE@iK%VvGOXMyp&Dvk^Ndcf%`F+!GL2POx{eC0>Qe`wdzBCMu1Y~ zg^MvjDUW(4rQTwaLusOv{bq$z-CO-@yriAvP`bJLyJLWoWs{>MtIbAEH~FeE?GzIo zZ_3Ssz@amz&yeMOzb(XjdwNZeM0xoFF5)+0&Du4lLqg&K4fPGECrk42Ow6YtcT9oz><{3oW&;nrcsn(jqSRK3q4TG#+_^3qfzV z886foetOM@8Ecc?P0%aqaIkk5cjQIh~@W2 zuyS>T9}Sp>0ZQ5&xh=UDljSOyHC|sa<^`X-42}RI(bcEZ$TYO;!qNx^z3ub zl0#{uH*atusuS6|DAv}{&|n<0;*u4hbm`J1oIQKiPHxl32F(%Di6kpAnknSKC@n2D zeI>IfLZJ^Q;#jf|CMi^~L!){ZkR;{0UYqpFX=9SxsWY6wBw2ZhRt75hizIJq&M6ck;e z(yL^D9;h^8{Ye~81O*5vRaTGS=#fsm|9&k#`@EK?&o!XEs{v1}UxCLquf#peGq7NB z7&+unQvawp?*U4$zfT=X4V~z0?*cQ7gybytVW!S}dF!G8n3NbrX?7G-i8)m?kgMx5 z5wRhHNm1&oBKK8UK|0nhrBY`fP|}87;87CiO@Y&1zf@~dy$x_vKg@Mmh+=OZpu`Y( z&F4@$br$3jNyE&XBCK0F8xO20#C;DXVd+W&T*{iY8LsgX;zZu=20%&WwhUTTUf0hR zV^`p97iTbx^9uwUb7^Z@_J3!zE*7YyaY3B>ef@m|mD=rK0F7}wckHyyv;ef{pL?F5 z`SYg7P5Rrkp^h2Re;gB^AD7plfAHEx;lerBI)Hmz5_u2KhA2AuS{8U=!FQP+q=tK(HqeqV7$d^ZO_{+ogHAxetzWC0VKHWekebqej zCBqy&#))Ab%I3}|htmq&xAtBx<_no8Z`f9zWbMnP1{Yq(8|SC|%GkYvX|kflS(Q`}h@9a>I*ruLv;KLqm=@fCSQLkD#xyXDb?UmdBXy_#hE)Z%@VPc7DOUpq6Jt+d;hv5Jn&!=$8eTeXQk6~JLx5uMze4Q|i)pZ=8RIgLs z2nxONhIh)FxQ?VlY0bTB@boiJ;h~2gvN1tzL%@>&C~?Uipx%{p=g!%?&CSi|?&;=< zVf`kyEz#|J?pZ>659cW=-Y%bysZ*yRCpX7FaEPPG1BzHy#w(_rn8+U|8fyoB9Y~Z& zZ9#dLu~Xy>Q1a$7(L&@9C}9wVZWL5jFB+|Q$z6SMLy72A? zZ%dHzWqBuZra(3l_=>a|kG98la?8 z-rT8l$sACU`B6`G;k70KN)mY!pp-}&2ue~)38q8oE$UD@elm*VH7S_K(+t12z69&n z6=BJ8o*Fk_y2?m9jWdY^lt_y)I+VUWhD=Fcn3Q^+<{Z4PvP|G(*~Ar-n7Z2 z0hX^=VWPM$eHWj({*TLxbH{{@3lq%03n$lITZ0Hj&K9FTRldb<1IU;Fqc`GI@&P4V z+Xp^|NZ;Qu=`qClWRT;e#JVGFpQlc=<2?dOpY3Y#IFu+JK7Ync>K>eld1Z;1Hz!0+ zz!qGrtVPASPMoY5Ku3Qn=FOae#XRuBIFu;zrrK6=)}F6Y^^QIY6f3XGy@$!xUN^X4cUDp;}+x#X|{2 zB8(%J=c@Aj3C{*lEi|}1L z#cX~N_P)dgs!xNpKVijJuDc)eoMo_kzUKfXu?~A8Z>{*pfBZ-M;0Hf2PN^$I-qe_s zp7#?=SGjR%1#))Xm$xF0@e+0A4?eqHX$8}`Q`fG1L05x~0ZQahs;#cI#aU)XCNe4V zmX(vm_Ly#Usj4(%Z99--=O6IWrAs5u`=)QdP4#ip#E6UFdT8##s{VrZNVe$NV6m3qT((4F68gOr`4J0Y% z02DuIdWkY)31#^Vcv;xseT?w2SS$+Fvwch;oz>4(-)>>?#+z?Yk@;^RkvE<4wtV?= zZqy&ey{qrVWr9r7*QZTcW#vUkUy{Hi0ZG#Rr;5(X&NlHi9X&3Nq&aiSXy=${+q7xZ zjUy>JC7B$xL6IIWe@1WS$qXG`xjJC;^V){_dYeOiKnXr4Nm+M%DG2f?67$oKAE_=4 z%Ful5j0XX@J1=5Cyzgmo#{%d=2?`SN@@mmCMsJqayPE&$aw8iHq)f6sd-qD6R&g+L z|IW*q+pSqZDzA=8CQyk_*#|OMOiy{Qs zV7UdpNP34|h>f4L^GT&JgA^r|4Ra%$!~{FqM^IfSK&czs-fO}Kd&yX~C)5zpXsRoxjo`0;J%QK%dK@RtjNnv5Di)A~@2Q7Nv0+^y7E%1Q zWUdb=sSOcSi<0vz2q@{4J+J-wZAo=QpBphZBJ$?O5T)nljccXt#?)XK=NJFJyVrAB zOUrfiU<7{J3KN@$^qlRn!4FYO-e*-Mvp;lhPjv}h65^Kbxh zVv2h*iR)=`{99hsG2@KOW1RO@Z(Vp-CIz&zDYIiLPKnW~-W5pY9%XVd9ETZZm}Acn`;{rv=aGy8l(xqKN+rb=$_&VLW;DB&Gkd7A292L#x?e#*(pJw}CGvJrI+S|&L9T$~W}bcQ$;kB9_y+PbrK`ph$b}0N@VX_J z@p->p>D-dc-o=qPI?A08pu};*h1EE!zNmXK!f3rG^#;HE$@?=^=s$yp~V|FCX9LK8*+2o0VUBv#L|XKuBQt@6P_kVZ}Hwkae)2%58{ghhsc86 zW>#S}fpzmZ<))@)Ta-WY$fH=t(Pt9{EnBwWr$7C%i5WORNol#pq3d7=b=S_duq;#XUVcu8k^rTD{nvjr z9ZLW7Pya;O`|AgkZno_xZ!UkqxLn?y-*{o%v#Ys^BN&g1!?{;`@0;KsESI~M>j0&u z#wIG)ts(392s}V3lkG6m7oTJa-2f3-6Ii)@e-~$v7UTH^pWn!}>f+l_A2(9=tGyGX zbMX3V;e-D1fRb(cNaGv={mx!Fq zBq|D~zM@aao%HDd_8y>E%rWW*=xxEY^d78OLau@rm*BC-=29tl6e+aY{IbDwQ>%?F zZQKIaZ_1WM0ZKaTiP_@jSD78vp~NiHC_Zu$a0BR!<51fFMJrx=?L77zY(!^2bp%m_ zXF*9R%F9Zzks>aeHuBUnDmflDK!tMw({f**y|^@?j}nX3Vg1ylW3Gr7Z(IS~GrCqE zOh=2ws{u*^iDpipX`3ybz_wt)0&XzQQbhYKH|Z6qxNr{QV(Q^SRP9CFNQLCGP&g^s z)`1dbEStpI1VpA$H%T&;x$A%lOH&0H&nUlso*hj+*Y_t~WULH);JH$c&ZcB@tUcz> zRpQrU23AcgOgwq?c+|M3&PU^nyY{lFWA7D8R#(p2c1wWQ2!We`td~CYBxs|mH|Q@n zfo(w>UKxwWfd!0B>A5lznef7}{S6FI^*b@9ix)?5;rs|LRdvu_Mh8J9iI;Wtj-ak( z5cRG7lCKxI^uid89t3 z*(FJ=(`01l3MirBkJ_cRO?enW{Cr8*591bf6A}oV@O`a+Bofw3G5j8i<2xgOD4G3Q zV~fZ7$F|7FF?D1NI3%tof;BoFPF#dtol&07HAD{VZoKh!Bew4u1(Y`Pl(&tWR^VRh zP+Gnu!qWrQuL&qs4C8m?Q2Oik9�v`30P6&GZaDuw4Sg>$`>4~&?PJ{hbis;g|L?`&;%IaKJBBLKo zz^c)Wab96mAkVrq)W)ox1^oT8E3B2DbHy;Nt~m->)7FO>iM+)FN>dAGQa{=Z+(Q8M zo`qDKG0?_MVk7quJ=pstLEO${l=4H;qB;5ec$0!xUgQTQ=0#TdH9(kdj2_CC|I7j? zyPE6eDJw^1az>E^Zp~Zo*vl@^qYB&%$d#I#OC3s?XUBpy=UV-<4Y&`9^4Ea`nf#EX!%`#> zWovw`5&bp3d)G0OOc+oSr2~Ec+eG*~3@C9i#R}2buS(IvN{UgdK6ToxD*GcU%$8#BAN}}8SiEGh9n-Ainyq25g5|nK;yP)(>$L?flx>8My(_T> zrMH8!=>Olp{EL<8|Nh_q$CNpSxLAxSP~~f8{0YOQcf|za2fI_4`78c@A`rYq;2c00ApO;T@ z>KXR+emcdf&vRbV+*HSBwe_|3HA>=ZMFf(Hrxx3(N%MFp#9WHX&7g>cPAE;`*DB3l zwxO6n_AH31MaJmwSAy?nEy>E@dDy9MtPmpw+mly!eqf8_N&%`_uwHIQFKu3tDT%WU0vizqOGo?68h={aywJ$aBUNTB%X>!AZLWgXAgmro`E5B z^|YY7uZ2KKKC;vEkVU;mSsBCJJVf|aI*oOef%3&XeXopMMJ!YT+3@VkqW zrcG1ZWWH5OwRQCa=GEw7nHCj91h>s3Z3WP%Z_!U{pgw|J{UnDMlDtve9>C-p!6P3v7_#&4r=zEH#;B87UZM8X%L4l^bl}Xf;v^rSQhP+x<`0Y z+KoyT>Upc!N-+!VE8`e|td07ZkXOP+?h0&F7=}l3_ zE0yX(SKb{jyoYvi{XY&+I(Xm`}_!#{ZW*if1D_40w&MT8%SEGPW?-U$L8ZVb)ed@S?lHL!-;gXwhTX!!^z;$tsX;c1t_H43UOn{1h5Y@j%f`ID) zCFx~usB5t2;u;sAB*pAvS_uM5vHD;e5Qd?>zc7Yh{Nfk3_y76d|2>|6{&|y>x`IPV z*1gg}pMBPJSEypO!TXQ@_zx2=6Oi=k4`0Q~l`BzHTx6$jsbU5xGw$?TNb#WTJxlN5 zsYXv?>9VDEibYPg$MWtbNjE^a2ID%byT4k64=^n?tQ|Xc7|7MiynBGsE8f>4PU1Gp z#77WlP}a!fpI_@9&>TWzgJ-?Q5?xNSsNNjgEC^q!we0_Foad%YnK4k!v=t&fKl?Z24AL?yPoy zN^YZ12r3=uz-PyMxFIDc!W^E8w4#8bE~8+F$zd=hypjBm?vJUnxsacY?>(M`t=~&#{|W#~6rBrM zd@glv(Crv_?_T?dF@4Vw&INa_@;}Zq*CwpIeC`0Hx88b-x}JWI3l}aRoD{ZxUqDuP zDXP`i{f_ny^l~xL*WZh>(lYx{A+Dr(^9dpmK+4IcqV2343!jmm?s1q!2!>gPU8W}J zD(^DBYjii6D9^+D<+jFv42Ba}V};dLM^Clg8K>~_i-l#78#IE9^z~mLf@}i8q(mMy zA0ju2xJpdqNup)6G2@R_mUk8?fptpt*31z>H)WM|KF}LNe=pktU*oh-jsblvB3B+2 z(VsanjB^!(Jl?&73bs4Y*PDXgo)olGOyzP{JvWk6ik+B7u!bU(Y~K+AGF?L*=o;+6 zw1P}bEy~3FxtZiV%i`K06=|6SVlyM;B1y@z`q$Cc)LkaHqIkOUJLMKLFll&C;TR1_WNvHInj2dCLKzsO}?EN4%3h2PtjvdKLjqtf5)Q^vm~0 zYwafhlm7U`?!(oSs+uvc zhjhAnoRK7mqQ~QelgD45D1#3a9?kRAFM*G8{u=sMFH*3*>?!1wG8>-GWjsG{uodau zIzG%a*?U_#6zEi@O`cF?GuTH2K&h*v&gyHA*nva6wsl{j9qTBw>f%XA^;OspzME^` z`(ExyK#BZQRnW`0i7%=04M*Vl75AA_zbURoH)T8(&hcUjQydclYEU& z{Peyacvlrj@^|w0C99m6DlRiU+Oz#s-gC(c{Q1tvX~=Zq!B(!E0Hq@K zclt=EgHmL_FN{&5yMD_HXVBhXfRZo?eT4YYkAG};-+Pbck%#XOQUgLvlfZl78V6tQ zm(LVX60y_(ex*Z5Mc}}GsSWJI2=^}AwQCnT+Z$bPTPIM+CWVXy$~d7fz$|i9PgeMaK0bzAnak<>goGXFrpKQj-Hp z-~CPmD2Z7|I46U0{rJuYx3Mxvd)G#uNRV1 z5nqWPC7Gm+rH=Tk zwNq{V^*OeDrPPMlf3fHJ&2PKyLDXD!9&WJ{j7!rBYHjV}!?u2Hrroeu$`s0 zFJ>Gl0xVj*c(H%fShV_qI>9ravUVV{m zq;`yLcjN;4Wg(r@Z@c&PT765i)wecbtEk9wF|^%3&`e+9OQXQ6tb8k_t!9?xT2&bm za@k$hkDtsbh*R*37ojQ&5L?B`ZP`fbWm5!6Fo>^Zi%Gt>x1En%?Es2}RtAuqm#a1v zpaPXdBrQlCP!ezyq_Loqh^U(I0Znw1`kg>Am&!u5ZwTIoT67gs<3(BLQIcj#jZ6K~ z2Lf^xpv38nS%72NS=flgfObcN*`YnH_QH#Y?X`D~+X1AGjv(=U8-UUsx35GBvBZ`x ziUB3ad*DC>C_RdV(oq)9%}r-)!-^?((+yJq5t?nwwo`WKG}2uC9O-7Iv<3YP@Z^R$ z*il+G1SmaV?;IYq7WGSbnW{18}!d;_;nG$9#lj8AjBx2Y2JLY4&%2yTCSXoMbuq-IkTxi<%oei_e5N zGG*XA8g;pT49ELJzwth)e#t-mcR=ZZ2ke6nK5#&(y1IH8Py$RUW6T$rBuO#3u*vkX zLm33;dFnklRoEZ-TjJk@$I+upBCSg236+%JtWPxuX$|ThG`uf|7hT{=ww@P%LS2>D zfDl?-HmV)60rLFw&)N&mKWE#we}rAG9X4b7Oio8$j@{A?cJs}f{J@*kSfBPvFJoNb z@Qx5g_i}y}O+qzQuauAK8RB?+Per(=jneD6m%*PU^5Q;5E&ZX(CGtvH<4HQj*Z67ahWRk&?L>J4&nJRD+0P5{i9e6}L$X}qrBT1p zU0TIqK=nsh_B_wh(?s>X^l3ihGEgn271z-I4k)q56TR|S=Lt~qlXp3FSNpy&)_X}K z0{FgPd;iy7duo*oAw_U*c}HfBL6?;)}|1KfxlXmx%#dnp-&{xW#_^yWiSFd}*FFYZgW|ueX(}R{91& zU!TGN??90z1DGjz4fqNd!}RfKR9~YtIr-7JF+-{O2P8EGsPxubZ`%F$-_Ihn&3^h% z|L8`!qs0dcc`>m5DIMPVDO|_kp(y_74~HmMlEFuhHF~JZ;65tF=#j<(n_EYE5j`)Nb;HfC#0f zWf3J=9~r7NB&r(`s8d zyrA%eUAJT}V{N}(cf)ePr-ck)NF(6g#*N;~D`juvyiPnGT+H7QmlN(8&=0cML}qmX zBtb*@0lwxAzp!LPnpYwvA2W4n)a*}=1eHoanoRZo~Z@KjB3;@n~uTSIW;wWsHj05uG&v+n>4A?ziMeA8nzaxF@Se? z5uJ9TZz!-Rr_Hyn3cmpDi9vz*BhHLA?Fym+ebX6@(d0q)k_J&d)t>INkQ&SGB`QqT zj}0e4rHH#c2mb>`Ae;ajLXi(o^d?Ey3?|z?e%Mdg0Q4Cg=&_+bKmep^vN<74;Favo z4IS=#;YvtsJ8Xw0-68_A)zF&0#>v$oV;`z;N-~BW^v*PXAHE$BaPP2(e@lvZxx(kwtU_sTgb_VMHBk1 zc;Wz3&sj(sWm)AU0ZRp_FJtVw03-4$GxmxG;JXGSpBfrlk&@yRTIPO%Ns}ru#Ls3_ zd@0&Sysmb1s?#277rfd>KLrk>JEu+Vpj7vCx*7S)hp{@tjgiIRk*f)k&OuYc97v7i zzn~(0fi}y`vw^N0>ut%lBl|lXPt;DfcAGFSWNUTQ+UTmd_uwgC_>*N zbVYtXaH*Vl`uW`Qv$kMXhi$yEio;K;P!Y|OEYq2gF=fA!tJ;xHGfyiIc3XhDTc`9y6Tjr}lt z>UI80f8r>55FUH)4mWXlJTfSnm&>!}k66gdtKZ>$y2j4OGs^BU6CXwut`}+!)A*zH zqMX8&kLEDdSq8WJkW%^(0PVvMKlCr{ufFn{ucaqdRsf_ z6r?=;-HGS=DZ5S4Gk$xgiRwmSJZ7kx9*Jx*>Ae0PLG|%S5gmLi(;6#w{zwz4`kR8o zBOYkaF@V}?Z~;&{cC6Ljezz8b_0Ur=BWdD=z=h_edCJ#wGogT+~p=mZ=r(}+BDoY&Xw9>e7#eL=! z@ct9O)kkaf54^x(nI>sN>R1Ot2~d*uf!6oZj*$=TH(H^UN9b32hklFKKQkw`kNchP z3lsdOvZVGR3Qs-@X$TABgO@q3kN2U(n4)K1SJJ7TBhu(u$d5iSg4UnMGQ{J*>g3}R zWv{QVx6^2$Xim`jtpu|s`e-b*H60M7pDCc^C?Jg0$%$-|;5o=w-#6ZP-FEHXX|rqQaEi`cjA1UeB}hKCCiq$7_Sc$G_K-nlJyQlIU^>+*eA>)5lDeV zl2DLjl?+O{QAu?aoNqEoFC*ZOJ@yz2++LTOy7!ykWG~2qT_W!ZMvOY!NXGPx(*B6& z;CtLi?$ezQ986>%$Laklb5sru5+lYLr$KtY!*OHU#B~qx!t-!{xn7-zD14|-*krcy znOtgbTAbwO<@h8c)i)Q16g`!O_DJ!NzF?}&2@828X%grk_)X6gCKoNdBFPwqg?r@_ z@=};w2va@^3;Bk49*IArwQ({|`g5gA4@)ib&ArEyY43F5!$=~TaqE$@g7 zKgNwFNCArKZ_R8j^aaZor|>`lKw>ec{Rv>m!U(M|N{AoY<@~Rs!y&mMkf@(Uv3y1! zVOsMFduD%~iF8FK$CuNhm@~;mLLu9l&ScuzhD>|)0$kwjyv}@K~4X{3k&9{zJD}r~} zB;(}*&-u;A`2&!Uk&T2B(jbGqlpjAhhyl}~LOXn<)3&@*Z<{}8u+2N$P&MeavXZGb zwY1uP@ae5n- zI0Hs$G2*<+dz8O6(>?~oeLE^EeV6?B69A(?T)*9l!+evW{x2{v>f7tJO?D}6C@}!PiaG`I(xlokBl7Jg;UW)$4tNszOg%~q!&?KS5lO+A{GYSM}fka5=_?bkj59oIkGU&Zc*Wmf`sF!Oj9Zez?b8d-aID`Q9-*Kw0-SH2NuTw{XgvB$Sq6 z2d2E7`a<&q2M6q-hkNahFLc_GQzuY)J7EhsB7NoJ=}6!nr(f}twVO>xAF zSvG6ppe+DYssq3~g59ci)DW#t0~IZxMnDQNJF~%NmbTfZYf+)YnD*ScS=bL_T+Bf& zz{RqJex6N1`=!78KRtFKJtwejHEU0g@wIT%w|ma@88d}AN?>Fn^Oa>2C5H0S$uF5phPv@@pFU=vPn80pUwOZX`<#Aju2f%$4uLv@eZFp&N|I!f)_3xwIpr7lUDwdI`t5V=Xo)Uy znBFB`m(;6+$J%euM}qTxH+7WraU;Qy>W}J2=jetsrA(-esUR= zA$?CKFj2HP4WJ~IH;r?WI+ui+OC&R1Xv`NDpf;8dPV!%JVjTkh=a4>2eU&eOt+HJdba!f3M(JAg%u2|)M>a?j=J+0dI zaVp!p@4g4Hw2#Gnol7X)dh3@kyuCJM1WQH)TFKLVZuhynetW{MD~~73LFA6)j$5KVg_AVG$HB9!4-&^eh@IM7T6= zBW@HlB9TYZcrpBrv~=;Up3D1Kq(8WjPVWpfh@;1s;c|vJA)hGyxn&ud{_?mBbywXq zaOAQ{(Soy!(+CABYJ;YGEkv~e&E>ah?zNBG*GbABrz!E3SGo(d3-1fh6+Rk$lh5@# zIbkK!B;!TlQNL5TmuHmxqxVHAqjE)Q6dv85TPD>pl>PIVZ=k~`xvGAeY}C41Y_zxY zg+1Pvc;=yGAFNZMkuTty0?7ge8ZR9bRClw@0_PpU5b%I4_tY}7_F zST&xRZ#z+Am}NDyv~iS85*AHr$OJ$U+BaM;T(4vd#tS5i zhEUVVWU(Vqy|2FrC!^=_q2Vq^Q^tQwcYlf>|tZWi5dmP_Px6&+jqY^g^9S& zTH8C=NOJW05XZLz7~~acGr(T9Teg@`35toWYxo^XFc#mYKUX|CrB}a}*GVt>kn#Te z@40Qi#>NKk>-t(XefkVH&OHqqN!8P)Bi&Nv>TME{)?5&kMH~~6Gn6But-nfdOL&EO z?D(o@(PBx82(rZNp*gnEf;Dkf@ z!V=W6iu$m_Gi1}IW?A**EX3FiProMbOg{X0FI1TTkp?75lnclp8%gBb+|+@Db32l9 zNGJgy6cr)@k6kRC&KEWhqWSq9c>*fQWgrdaZ7Z;qe(k&m{YCvqB&5d;qnb3;+{0 z#_yP&Ksu?twa%8!n`PqnTN>@U?G=CrpQtL>g?&3zL=aP&gXVq*_ItsEoh;E-np z2K5jwX-f5(JWe$PwCn0R37@ps%6ZkcwyUiA<+gu3V|kcE&aSFb00L%D;C-W$Ex(?yx^I4+Zr znbf*7&L@7Rv?{;y*E(1J>1Uqi#J8tiQlq`2-6i?I!D(-6*RJ)=m83QVu1Dn##frUk7EVEis8U>wt*X|1ArPoAQ$ZUbGMp3p8Q zx0Ly%!s?h4KiYW;6~9(&C}rB_#19eIiQ8n5Uh1FP%lXN05BE`9J13?myX5!Y51qGo zpI({j>(Q&ibH59HCoV-0^6+wNpb6pLx8m}rr_r+*?NvG|9i_TV%An%M15K!|V+I1s zI@;QOjju6L`#Y`i1uUuk1t!VfoJ-2G-w#earMW~Z(vLjyh|dc@`Y}eiW0g0p3!_0P zq~I!&4U;?Z;PU?YsRByQY%zTzrsjsmlsdu7FTdo{Jf{#Z6Y{rd(I{RjNKdGj2ATCsA4&7VKts@M#;qj3YE6a~;{Sis2ZE0qkjeYE2v^vs`kBr@1> z3c!NW1_V>@on15APk0jurY~+i7$6^OA_;>~l3pQ9j4ki<3k8d>(KGdqkxpqx0#_rS zC-0Q6#JuG~nv2OdEUH6!lX+jRzeN-Iu;7f^ILF1pqpy-|kQiX33MD=ak^rOC_hQ;& zwDch?%4g&vGL$pK30JkJ+AzFZ;bXON;K_782x%0qHdegLE#E+oPjXGtMTZEe{bdk0 zo3@X{StBVKsX+$NSact+8)S3X-H${@A1Yo*jTGee00JSUA?X_crQFO8cnydt2OaLg zA|wbVp!zexcI`WAJNF%7@zVw<(9H>HRd(H)tC2>SU{j|xS;eFl$~wqGcfg)_w#@$U zQn?*J+sOvB*{VxU+J@zau^j`r#Q0Y^vBLQ{j5C3ELOsUfv+>k1^r1X9r1^z9Eo%xV zY|Q}VAHu->8Eoh^*;`vWZO>6jG7VV?>M`H_${f4r-Z=mw-PYWO+EUM124^koy8!~A zJ8DYZsKxY9olv&qRpnCIgAerzLRUu0@di9w09LcpSyTc`~UN7Q$)+2KUAP`3~@ z&>`H1t3V&MmD;Sct)J7=`mK<6mNC}#A-#5%4Znb;3EBBpCiSZ}q{rG&Et_0uJ*bX# zvw_k(U7CbUr8ZZ>I8w-5I#7h9S`lL@phQ3X+1o$Kx(BQIGKj4F%vhuSd$t0wcdipx) zOGrIoyC^TWfb}$h4lc<%9x%$EB%K4FhG=@GHcW403}RdnS{+P2k6O=3LWE7 zd!toWp#C{=maSjaYS*l9MRg!reCIQ^6&1D7Ze1+g0k~ST00?Juy4-ARsqM8_x9_u| z?iPsJWos5x+ue7qwq;Ao;W_M=WuBy6v)yRA`n~$U+CU3^Sj*?9K(|oF^Ia8J>on0m zd@#~Dp+2%__a57_@Z3~-h-O48D0-x|< z=HMZ-H{Z{+UG*I$&&}dDj z_6}>VP^K%_&xQhlU-Y)n=QRe%{%v%X3UkDe;v0=E@?l&^FQs@X@KgAm9_Q1(4}2f4 zpZ5E{2>FLGAxSf}@o0Th?Vp2ofSwCX8VgWT`+tP6iN;OYx%)8!E)FR1aZ&;Y?vhhP z827^Ui$GZF@Tmbxp<@O@s`2zyMa15>Z@<0v`Wqm6A97sjVOJxYH+P=Roj2Dzur}}~ zYfrjSZdpv1WJtb@YR;T#H8nL31PKg!_St70R1(niO;pR4E?vqg9ObV2sP{_eQ6g-o z5n+26!>SKI{IGv*x$DlmY{jY-Hmhb9#{}~gPL76E*<6fIlbCOyBS1-CqO`$~ZmkT6 zA31U)5_wKYC@H=ss-ryHym_-v%s=?S4>)S}tAuONiWVTJlnHBAL*on_U?xV z*_gK@Dbi<)=S;R6H!Q*)(q!!VblapU*nVKc*Uv)uHxK97e>|Sek;tf<04Ob<(rRD5 zwVhMmh5(Z$pbk^&lWE`yT_e7U>JYX0`Rg;*(+Fgv4>6}oVy1tfltuRhfTAHz)M!Pj zqSc;$u7#88P?4e=mGV{hzPo2~YUd1W7zhySM4AP|QA4fJ04b)tEGBs9BPj)`+&FIo zxQm+l@BAsslEeozj}nE)eI)RFxO(LHkAFmt zIUf(xhk}w$xds=daDj5iwqX$@FD_uNH=9#JGOV4P@OspsMy+?O`pm|Y8gP{NF5Rb zz1E0*q=w!yq@z$N;%k2q{h|<~%y~!!6l8N!9)QHq&?!D1^&9PQ|52yGEP?GJe@^Vgg%tPf&>jnO)mQl0QZ~S*e$rN2f`{)XPrg()2fd>_) zJe1PiC~+0;X^Euw4E6%LbyrwxW44_*(rkzJH`vP`?6a44?6Y;tRsj;NMq)AFR<9bs zK2$8BbSRQgdik9URAolkHnyU(SiYmDuY#jZhZ(s_z3H4)mfP zN#D-^P|{eeE-!M8><1AU$NH@k9aKVO>r!KR?Fp?t58L~j-?NuccRh6IAmuN$ z>Z#R8oPWjc!si!6c2&|r+Ogg@TDZ44W%ri%af?`#E8+ofzJPJ=7XVrI`dU|ZMmKKUXxFT{23v7+Tsl)<^VL7nol37f zN0v8gn+mOa2^Fr+SQFw z?m>HJUj}0os-&E7_~pe7cKx~r+Fs*nHWEsi_QGp2+^xy1)G9dT_n*FP_QSu{yoMAg zW89#BSklRsj3#^_QL_$?kWd<4Pem1oO6(*Eb&Tl|Zlf4i{$2_Sh(G1jZ}lPAfgsvW zS_k^AyjrEdNNp;4!AkOFFclwU+9Y1NOjPt#iOOm%QCf#3hT+u9@ zZXqn3+^e?Ly1$S;UMc2w@{m-L7LwMpl28(_1gGCREpzkc_wDz;`@KuJjY~pF8N_`( znf!KvJq~a!O)A7&sb@leU_>?z^ zF6*>78Rec@J=HC^r#Gqt2{4I(95I!gzPj`?Sx5>=$B&BPB*rc0%*k&|Ik;i2U;N@1 zu7Cdb|L_lXFNVam%#;(DBpN7BSIhf^Ge)!!@vP7N!z;t!dG5pEkP&&rX-0$%M~!}s zGvD-Nm)$+>sV^4;@T(S?S@_eZPy6XlYVWG5D(9Ub7JJ_MjfZB$N$11VB5FK*qV#g{ zRs4CyeS8X}=m+i9U)BE`&opB5qrvaBpw>h)0YFAPFkYu-iCRWmLjBSLTUL_T81dUr zbYcUpC((A5iA!bRAA4H+@FVQB?HI6EU)gKVy}1|7rB0iKy3dM5Q*F~NOKkPpX*RPa z!=_AQ+=_YNXTR*RfB97pCqMy;04QykH)wzJUkmJ}o6r$2F9EpGG3^@1##@VviKnlA zY~K9^O2=XxwXHTJSQ^f94DTZ8?U$srF)Mioj$7;_I zYHz4{xtfclL!_eT>R%e4<)gw!b%@4ny={bx$n9gd!b2N}tIs{mQ<|%M;{p8yB(-3p zN(&9CJ8CSLj;fpbzv74aLHQ|NTnycg&qd5YVa^j>6N~u7Gmq*Tcqa-UUfe_(iDqmP z0Zshg)hCB(6wyof%2#Qlmq&MckNA*z3fhY{5gW+{5N(Mc)QN4R3${=QAPbeQfHuKr z(vTeM?mAS($m-igW5wWy{8MiW@edvaKFqC(CNCT41xU(nqE&n?Dc00qLR~HVRZgwSWSm zg7^*+XyWhG1sIvW938TEwhh{cwIoOflscOjLz-;flwwZ75-m8GqBMiGT9>`@M!ju6fHWaM zV+Q@?o*O1`(p-hjTaW_?frJ_YPa4xy`W)6)yHe2rdf8rj@kQEYo1ea{v2NqWjkbRMdZbzx11im>Jv2^UMDZ`OeJ&#Bi;7B9 z)8-V$^?W&K1AAb{PYl3^1NP*L{r2QGMvK^%;T_BBZPWGj7?zivsY2ViJIns~%z*7a z$sCqbZZjv8*+2gv&;I`JIm|+XWQzU7Des+KoBWpnSP9Zh4fB!+g0v+ND@KIDB>b!B(K+)zs%dM>+!)8%47Spwu zlTkD+}4WL;i(1NHeWnyUxCa zG?PH6%Bo7YZQ0sque`F)o_TYhm0;gtRz()JQYPE=H_o@^ zeA%BqBOA#LqaEc@x-mf9`1U{Jm=-@i<2?2Ae_ zT-s0mOZ`ZohAi$xb#yR;jbINdPi+|7-ny;B{?9K?*>7Jt%NU2_G$#H!+505tbpST>Uhw1l;2jZ9Eadx+8> zu%N<93QCZ?;|n2tUs+sl6Ut88gz{V@VoFh)!nk)XDv0oX)%0mL8T(x~>q3T3qlw=ka-*6>`QNMvFA5$vGt3wKeTd{UArDY>AD=$U^Rzj*x|zi_MZ=T+vCr6V3fNa zP`4iS*9yA{@MqeTBBU+~Z2w`ir(Wx`caP9_wfXk8rVq-9I1*#>Yv&f(#{&` zD+3z!+DorC+Z)?ktr?qVefW(_C)joCC-R}M&=xPrXT2r+Wb|hpV4(4gF8$7%yyvYx z+xpQd+q}CDW9p4Iv9!rHTw7`1yhi}}RMhG)%Fj3_x;kwEE;9ixBR&rF}Pb>{8cZT={uh=ucc@${E#{D`5E`V_HiapmzO`?chVrlh5|sGw=6X zV>f({ROTHk&)V&`G_s-OR8J(-w(rQa-#yl6JC4%FQNyj7SZx2}Z}ROYe-GH;dB;N~ zeO{wL^k%MJj;8q!93-h|EF6UR?@ zf0yur*7!w8qREbqj}?p=a*FHz<9tLqr({tr?^ z{km|nfa@A38S+H0?~Z{GVY3`Q>IXy>vN@~i}bsT_r5p&{pApyLTaiw+@?k}}fR zo}8E+XyS`kI66>Yxc>HUf9R)!Xp(ktioqx3mt-D)(RltO7%)T+bPe|xypqQ`X=0|n zU|K~;n;e}6Nm`^mA6K5Ar%2Euh_5;yXrbl2nTg6{1Skn;s;H>&$wmW>CY#Xyfrpa3 z@mW{zavh95YdT%%eNIRCIRHwMbgW11Ri|kvYyyCiHkeY!jTYt6q~JU-YM+WahlUp4 zzlT+4+^M1ki^d^5V}J$5sOdjIE7OYPP#p|C_f&SwMc zLNq%6b4HpJprp!19x6dEsR@{Gg8$`z)!J{KJHzQ((6lhq?zwf6eeJF)n>!~DgV)$i zDU?JEhEx3PG11WB0sbZdrD%aSVt^X04Mcmb{>N~sXIe1Q1`a5-U|WWHN+*2k%Y02u zjY}s;l}k=iw^D0XyZczL@!mIQ(ep80m0C<()bq3~Bj6}mpBN_748SNkqM6Q@U7g~J?Io`5*llV@GO4b%#kOxf z$bl9ou;arxiqFC5ZFXL{$35FFBiks|WflSYJg%CIr*sNN`n{AM4*pAqMR&@Yi0sOs;vYD zK^GJQp%C!_IQ$rLw??jwwerDGI3Kk1QLC9R*ZO*0HF*+7?`QdXB&e|~z0dEE)aeCZ zNC3j=t_=q+`s+XAKgqUGdyL0LY1|+)WgCo*sy9K;T|1Go0GxgL<(>A-yC2!=s}`a5 zw%FFMD`w4;ZPTVBy#-i%?AW0F?%^IzRBN{bwX{dWNxNoovE8t~*cQ#1U<+nd+P(wX z_P`UI9CwhhNA*x2=EOW3MD-L^A&xxh8!K#fO@Wn_V#pmEXml0pXdSXwpY5|(pYOGg_8+rthmTol zZi`K;YzK&%Y+wEQQcM#}wX8eQJq>3EV%?TWC#zRZhYh*m{zZ6X4 zuE4}CTejFAe*Xu)Jimq%%W-RIZLzBtUTs%jz0mHw>n{AAF2SI2TP~y@nd^D(NH*G9 z?3}RkWO1>NoY$4;T!y4D(VO?|+2eMkUVQ0Ad+O<@e7&yq^;!g(_@PWm-L zN8NiaiLi?;^yALDW zcdl)>uY9?KzJnxhMLBzkOncxzyY0h+@F6Ed)J({CK*=SP2-2L!^Z+=m^?vkfz4siK zC`Wj9F*Nh_MM#*qhBiqAUHO?tfppqAziJSnp)_Y}-=+gOI{1JfKuPO-8KIZ=HU21o zlIJ;UL#Ms`%I&8^fzY3nJHL~CDf#<+FLwbCI<3G&9loVLER!bEc9K~ffr`pIIOiLE zjDR1s4v;pK0HuFNLa6~QhH(Q*$}o{{$p3P^es+LT+-cSM)EL^7t0D9?sF#xwf_j*O)K!Eit+BnsEj2BQR%c^N|7M7WnTgrD!4%s)<_ zOq={2+9za}ydP1HI6^Wk`P(~k$mDXl#;etgdm|LKv7>VWKTr{j!!nU zztYJi>2NVsA1z(7ZN`(=XnBk$-4{8|#nLd)!qaJ?LEEd(3s90BwE!9jP?9)o3Q%H# z34rnFlZ1bFOg$Q60*f&Te`N$@#|u%O4YH9NK$1cW{T$RtdN`{4t+#vat#|S79JUue zJZy7O3tO|a$X2bWL_%|_Etpr%(dL|FRU|c(0mi%md*C-c_A{gsPPef!WFz{e<$3mh z{bLD$5}Rwr!60}AE^at1t4BkYYK8P?L{ORJwZKqYcEl1&`f}NLw!y<^&z|ikk%shA%a*amFwQHTc!naSxpM-d z=L%L?lI0mC%u|oZg0ecGlT4^FNM2!z96Ue6OL!EXB1%JjC8>er5%qQ_rtC*;3AX3x3r&ikc>C z1i+*m42P>oDw?DX-^5_LrYLWwO=Gso}J@LduO46yv^Z$%ywdr3Qp22gs`Sj|)fE@f-X#(Vx&p z5${GZV)`dyjr=L%$87~5CO{-_NNz-TzrQU9035inY zWchD>>s$8i?|d8ET~)63rv4s{rE2r@yeRo7F1tp_luP_fgL<^nJA-&aqqww z?-zKcjnz|6J>{k%WSCp^)aiEL``-8L&O7f+mB=^Q^a1g@RAA-8yHb%Z;g2vxT_{U0 zNvi*;KT<@|RuAw4WYmxEL=s7-AMV|Ygwh`e?77$b?Qjc+=ydkl?Q6R1&O17>wOV2m zt0vIDGVDJdY_rY#>3bZK;egU#=W)U`66)$A_$sw@_&ru%7%kk#Z`xnup1g!xBq$)W78L-C5@<>9vtjHL zm?WRIe&$e$UY6y6#J&d`zd6;MEp*1!srSh4($?Gd0P zKxiMv0j0zGjcSIz2kRwb#jW(0Zwr^ z-~f^&mzJUGwvvf)G8;ixuhYUmG-wzLbT1$7u`eZNG^0`n%*GpvrQ?8a8cfE0NHww%K#aTy;$8>rVAsZGAsBin{DypWuYL zZgOWVxqVfh{m*|Wv@hK(^&X8rp}=~-3K5qgSvar3$N9tJn@yk-P4#61FMCn?s4q3K z?b|!;U;d@ee*G*baAhOCfb`ebk!HB#t_im2>O7k_I~${@Y}_4CLc+=&fDIA~E~Vi2 zDu2}P!h524X@BEtd1$C&sB0WG^!orP>7#^H-Xy6a^(TP`HM1q5R2`)tAK6*c#}NTa zT8NC`0mbrnC8skiE| z?N2Wq1W-C;E9cDyP?~Mmu8RPrX)};e%8vl0M;`CCr(W!~y~o?EwxP|gEjn&DRUNmf zHDy*ldzu|OTWl|E$*}k9P+4RQh$Pnpyg`3d;$~D7*quu{?4D~{tUABR+UxmP*OqN( za_3py;1v7l&`I}gEm_uzji+VvD^X#aVvCj*TFrt?n@rml6#^t8arrcoP)|MGW4jI> zwynpG*v#@lTQoPvu3J}Sx7}RBAu1KWq_Q9Y06+jqL_t&-hv#4d)Lw@&8AoX6OaLV; zGT~`EXfjN-;a?-@HqM*j_8-TwRw&)a+Nz2`QTv~K+FcfZTQ0sqwx zcG0HO?dXNqJNx*b;Wx+ZFdV?I5Il96Mj<;y;~}t@{d3MxZVH2 z{jMdT53kFYEw`WixZHVB|}*0${BBM+xe)=Vt1f4(n|6P@xSKI9d{fRf4(HEhIJUZSYPQSfm4C+abt zwom8N6d#dKa@~^1_AmbDIW!9tp)H(d&L#j#O-LvSP(niK96$+v3Bm*+KV8G`kY&Vt zsk=+_Bj%a$@W-Wj;pa3LwbOYBe6jo=;$H|*3a9xddNFf$t+cv+ynWOl2I$$KJC5af{bkj|dWC+qB2M%C| z39x9}_U-oJhab3g^@{QemvGV~r$!dytj&OQzpuakdQOs?XESEabTzs2to4Qm`@li* zz~fQ`X?4(m5&)%FUU|j-?PveyfYLww!$0`xbE7p%VB~WKqd0Q%xer>tppOd^2A8-T zA#UC>Nmp6^4sbxnFnD9Mj0p~M#q@veX2 zqk@4(A-`~czPgVUC**Oyw8>{<<&%u_m-zc)=_nd0jp(V3rhxBy>?i5O$l#KIk`}9) z>^;8vo%&ha*A!pajNc}@a9Wg9biG&4v?0!vA!^S&o71MU?3w5K?CBS=zlQ-~U^04?d4EUsn6t zn0);@)bYMt!ja(xcJ=&xfClCUY$%~D9T$Mjixsh*L<~9QsD+Pr!*xkLO8!XJ$E)do zQZbzNYIoXPiwswJLnXTz!`zM7#gp{WteQyWEhN(1B~WPupv1$7mb$7f<%Y{9Fv$T% zf*jING1%mITmtldw_gLDQjVZ=swfGg;cR(>5(vPPQ_gy*FkZmDB*Zu#jCYBa03QH& zL!1~l$g%H(F`y)SOPT#;mf43PN&!k)lD>r-Ik`;|Ky(E^w!QHTMz+uNTm2c1q;J4Z zQXMB`ox)u9>2~g+S4+D!qjug)f@0Lt@;H4>7*8g4y>c2gz#}X zN!K{88yZ%Z5TJxh0!mVQYdYKP5=ygY&vqM10+ig~yZ|NANCh$zH8d}a+HZvOf)f(L z1HTSOlBC!J9;I=g%6VXMM8deiYHPX41W&cDXGs^+70HsPEG_{1MO?1?8jZTFF5w)4bMtEtSkWeZDe z!`ex9%T3j`cws4E5)w*DKuKUSpb`a2QRd_P2>mmp9Wi%8Tdf;UoH)V9&F!2f{H&WZ zaDWkM_q)Gwx7~C1J$`ENoVjycg2D5Pn=6&qaC3*(jJzhBH#`|FEIj)JS1+G<#s`r& zqfkC>L-}>8vdl$1^2j5u!m)GbPS+w>h^pT|{`4R1JKz2eeL2rTG~Y}isTUcxXWS4# zJ%VRHL4n6eDuDBXfKsTJ`l0^ogAd(HcHGs!C7skySTCS)FMVm>z5)BgLqkaT0VuV0 zIiPeCpy{m}+ilK*GWt&?S`!2IAHM=n+6VBSS7x&Tl>YmD`S#-Ps&j%=#SHu!Z5Nkx2 z)7pZu<6{9zq2Gt=<<<~ml=m|SlvIw;h@nhc80thVN%-jNkF2Z9`0-vujt?C=%%pzY zPk~#1?Rs0We1#QpDv{KTB#JKE21kz^0a%i)r8-{(=rkSyN^+%GXO~~HWQi?Zy3|i; zkr-P}t_*OV$AyLtk+@g6qeXvs7^N4pYVoP^zxqmKlv`i3M+1};H@*Jp%&uJhUA#}v zf=?AV@%r?+hVq98o_X?S`1e?ODMrZed~rffA#S+89Il~W$*X?LUr^;O4Nyw2 zZ)m@eclz@y_n%J+sJ*=HSRIZDC~*Rgz-}$*JU(&tkE9A1u2|d;1Bl>{c{<7#l6UbX z%q0+HD3;T<$XsSjv~hfjQ)Zrgj+15%*4wUQr)>RIg?87i6Om9VvBg)TQZgkM90DK& z+Yq~UpS9h4n(XQ42khZDgaly7mSfkyc1@xEcfP9LyfKncN==h-aWx+6zv}VHoN^i+ zQ0miSo-uz1fYQ(ZzXto&^Ub_aFCDbIR_EGA%C>4{IiM1D3?_(9?c{X{03}r@uBX>6 z@jLX-R6Ej^=LMAFv>N+$q^tlXZK%@6zbN04)J%au8sB3gdpzYy0Kri?6Xo-0A#$9? z6NfNQLpuvl@^s=u@>jUWiGD~D$)%ALM+E`&8_ewHr{+w7E^G`3i`{!VB!5~^WovAp z6?9M_l5TA+NF&uEja1iXwWk}9bZM|NXD4!k+XQRt=Ik_%k#Fy9Mk?tHS#;YZY!FOf z-Y!LSycl0lAp1vvMgT@N(*+#mqDoYN-HKc*L0z*Ldp|{ZY{olo;B}xqC>rHOJWWfD(PqyRdBTyg&krayLxW~F&{j(WU|(@uG<&%u*6cA9MpKowR2* z*V^(KQ*F)ssdmGS1$N`DIW}#UKGb29`_Q2M`ZvAy=(F8+q_GLL#3s9G(plRy`z&^1 zaxAO3(2h6ev1!h=0{}|h3{ahbWE~lRi}+$B#3tqC*ez8%?2b8a+l+#G8$cB|r);tn zU$f3K=Pb03_BPp0{I+d5wqlmCRe6CeT9{#LuJ5%aDgsa4er=WA44||Sa47=`CCkP$HmL1gI`I+!N+U==%8hI$$$sY{ zkTHF*+=?yEUAuR=zy7-G?fMPZ+xqL)bCTYAH`1T#zo8k`KF+vt=4$qI7vd(vM+-|n zzl6UvLWeR++Riu4%s;wHLP;kUZ`;1j$3gM^efQnxc0qNzseGjF8`+P`0^AIFUBV)s zlhuU)B_(iD2YPdL)`6}8P}0bu1Fi)qNlIz|fdPB;;Q=J~`jODXD0_R4-L|^ZzI+=h zZ*xkqm59pQHXBxX%PX)ssNnvy14=RwuSNr|=UrK}xn50A^}nItax?5g8;9%glkxou zbxX$nxOpY>_@e(Fi*8YaeJnsJo#)fv&vFH}U&j%<;kJz5Qdt6jmfRex|*;SICF=K{%i6;Bk-_Zt^kfE-D zDj^>CDswuZ6qs9+u|Tm`Uwy^?^JeiBN}hd8_K-gL>hN3d)ARH=N!o?D>DTl$ z>CZ>IKVQBfzw^Zjd4{;*{&Km7x+Smrt-(h8C;K@9I?qvgI}e}~XrXJ!_i~}fUwS#! zUTU}VN+_iRN^yUU#)$+48Ao`eRVG6Vyx`Z-0VPR0YAn=I=a>~@1I47()6Ws+1NOvI zW=}kmVFyk$*uhh0?1m+!_Vuq;*)?klZT{>`j<%K>LZ-E0=y>agwe|u2l{Yf&nJwDL zBE5tmzHPiI0Vsv>E>Yyv7?=#ZsNam2E}ayC`$`%llzIV_x)BxrXh)a* z@_#qmgD;JtL*9sDLu-K&?9r8GC`)0IvIM>yfazqT1^_aYsP<%^9X`-&4M-(* zv|%R+aPu_B%Acz5wYr8{t36w1ja`%NRR0v32=yvuJlMpXc+v{9I;|Rs;>i=sP!+7O zDbp&fATI;s%o#RoMyAb~on_OjvjCK`kQ^4Eg%e$|%`^lU6r2M-2ssU9QdT7Q9IRAC zfjE8G)9ORKXgInjW4-4#o)nx5-Xu`T-8qC*vB^g^qvAM82_+fi4uI0knKH@^pu`$O zl0pt92}lh8TnZw3P4ri97tklCekh+TsD7sv2wre@Nbv;EW$9bdd?Bk*gntewVM9r$ zynQG@=@fnalr5Qx&70Yiv0YSPo9@cB=`~0w@!A8Z_S}DepZ)%sE<4_K+Pd57?WP*D zjZ20A@}lfdp3bsu80J25R)7+{4xZ=&OzIS%go<5pW{%yM|E6u4@}$k3*vJ=r45io1 zwu#qWV}+O;*t@UY_8e%px8KaS*WS;!CXBQ9u|B$LTCZKdvD;R!&#@&7r*Lv#DMqjB zvFQY8Q+L`9aEj)FDJ8aM$s{C{CflYPC)D& z!1;JXc~nlg&DS-OwA5NBD=XWceDXiwpRAEZuZcZ+`{f;|q7E=B*@rtkY zkT_>FF#Xf0#&`gw^!J9YlLV9mD)liy^ickN2L=E)k^X(D-wvMX#bA7|-LbX{qugCK z6B|ksDkm_XX4)?w?6fThsV~6l+^Ssrr|%)5^uq#Zs5!&sKfQOWnWLtrk3!#Ymnv6i z<8Vzq7{`w&5CaU8tp{0xQQ-CLMhCt;VOb9e_u)hp0hT%l$rkpOl#MG1|m-})-Ag}Ejr*&~qc3P~EtIGTQ|qgEh(C~2b{ z0HKsGdDZWa z11KfwoBaJnq~qtkPN6+RImgo;N+Ykh7X>J3^Ugnir^XC_ss1txX&rg-9>t@kLdo#i_nt zqNq3?DnMd9E<}rpKO#j0D5;k6f-D3MailzeQV*&UAMNb5U;KNAJ%Ewm!9J|?_P5)* zxjlBx%5K|mUA5hK!yHcZ%wa3pN@@X0A|eKst(Y&tsNsxop&%myN54syHSs&u?rKNP zLo&)8tGsEkskv!p%`8qDo$3u3J}_wfcU}=a@k!^r5CX!Z6iGrrh%j6jSBpDG=teE0 zf01(=LLn(vm)t>x&DEzOl1D&<^IjA&=B!AXhIaRg007Crb~}+I>ZZhTi)um3JU`nQ+^FY@yAfv638IfilV ziP$zQx9M~8ZQ7gyq*E}dj;|=sMExlfJ6QlsNF?RvQa6gEEv}!Ur{aamst)p!Py!H( zz%xKF_0xVn6ycrLs(0+Px7P+=)pS*qIFAu+l*r#tX^UwkKuJ>2T37fLP)P=v1t{sb z_wQ^4<;~lL%mgU;I1m*=Tps~Ss*G2_%O1)v`m-I!)7V7uwo`%G{bpzf91~zD zqnn)YE=fZ0AU2_f@;PBGJ2uMQZBM^?%%0nF3}e}x_&9UA-NZ?3x89DL+8j>MMI!9T zkwJUlS3UMHfYJ%ZkM_1kTRFAB*39JuwxUdoqXQHI7VbVeXvg6N;d%Xx0|OYq@5i8d z4&qlilyyV#X4^RJ6}$SXKAXIFu1#Dp*NUglww#I8)_A55;IR*TZyEOds~L8ru8q7< z7sTN9vW5M&dX-M>ondopD(%rnTI|t3w%Fmi!*=lWAwZ`|wsyrF+kg$Fn^1k7KR*{h ziGH6g=|s^_+7l%Z`%ls`SF&`pEg{V~^Tnk3D9Um6cXGvC?k7}%)j~g@L(-}OSR7~+FayXGH(&Iwz-!^ns#3ZeEi66GCAjy#LV45|H1-G8-DnM- zg-wuGky84jeel5td`LS&e=e|%H{WbG+;F2UU%u3qEnD(u0hA(w4ihptZ#h|@pL$f% zodYP*zI}`f1I)F9{N4{p^zd(c?THt9?Oo%qKUKB{@ko$}NoPYcjjUWp`>1Z@5Er$2QYO35^# zJ|S$Zd%Yt)PIzw!5BH;8L%yRu3t{7l6XJdmuYrz%4&gp|)$fZ1ltO-iX6g4K{L1yS zqd;iW@wP>XuM&ta9xD7dVLXV|!sMw(Nw4=PB-(tEhyT-Z6c`1Y7H3YM zu_K4tusKp;kGxo6r#l-sn*EI3wz32xsgrEw>U@kCXRxVZECNt!X~uZ>3w!M47xvoL zJ!Q7}7{_L1me|z%61!u4iQV_ZV%u;7C#6v&jhd1DmgLw*2^>(0XHPHRD1Xu)C$mt# zl2q}UMw@Caw;fPoEY>MmAMNh9|AWNDFR}47)QKIXu0~rtt<6>}Y_pp;&9vKYUx@vR zJQn`VEd0A6As+;^rOhaDP-&DBjV~yzoL)qgG@er&5P&#IKuI=L6h3R#EI_U)F0HC` zA&p*qLH-iG4s=k zA8a7Wm~n7JY{=!6i}DGxW>?3M)t?-&Q>d~vo#i-fJVIoC3fu0zb@t)*qjus{mo;_g zTK5pDO!*jTE?_g2Rbu&Bs6=%gw4v?;@L;}8m^_hdffZwXd16_iO_@B&rITh|4gD7K zfuD_bE@){sbGAzjsTvef^R#&0%f<85T%DqUY9Sy;5>*10xJvD8P^Y&crNmxOdGKI# zM?RjXaGKzhx5E7jjpKXG=PsE9un<6{NtM_sn=unrydnqS^e)*Z;t)o%h!TRiL{d&F zgO`Kyx{97|R5Mw+l7y9vpi^M(1SSEe@sm6_+0j)MvydP}8c3>?N&~zFxQEmiZA;PM zAtWQPbJg6CZ@YFOk+{9fo_p#!5 zAog*d?X;6fb~m>***uO#zG~_OD=*HmA|%I}Tl(z4$sRk^A&J4!-TKmx?53IT*|O^j zZ0?pAyL#%dGSv@(`$cvuE##u4euN~P8)R?hfvz;#bwwangg&@ZGXhR z+hb4n+Tl|l+2Q&fws6*TTfb%*5=vEe!&*-6oeTfwa$27QN>N!pZ9pmX=g5XqWKTsO zB)hwNknXzQz1EtNN z-VJFk(KVWvC=v{>nI`~B(HxcukhBGf``2vq=J&B5^pS(cD^{+yRco%Xn{M0y*ni!h z1yBn8Y?urx{V>rS&fzw|I*OMLC`sK-A2oEK0Zoa$uL1kbui?dKd+acCXBWJ`dTyI- zSlw<{F9z6LR0W`(Jq#$(uG7nN?7pvOV^b;z1I}6QbF!itE^1~CGUEW00#Agi3asi3 zS4knmE*Wn)H2O7Gn)G;osrTu$6Q5{LN4WT2;PI$7lmsa8WhF92pgAJSXsqj{CT|#% zlKF;rC&RA%9v=m~&50VW=L3{vL&;U%i0`c)^N{BLD=Kdz>HYZultLq^b8ArKK6Ds0 zx}(DquVtdnWHIXCQJhBcQgM}7i)b+mUSHs4j8o3zB=YsZ(f%l5(s`D{fq@AXCFJRY zjY}w<3n(d`(u6XGdtF0VdY;MqvEnIwEEn?qxX;H*_eBa%r*WuT2-j8qlK@H=YKQR7 zE7wn#0-;UE+a4jlN~I0xxNImf;wY~EdHQ(B@ZTD%v&^EJ4%d>~x1YprAT?2jg)zvw6_dWTxVpV}nspjbQ(mW=)3^u~u7?Ry> z&po%xcJ3?YNbX|naZj{4sHfa|U73CN`V1fT`G4G5=y}+ zcT7~T$3^@}R#(ZmS6j(@J6 zSSCOKfJ=nX5JzHe+BL;)05C|t6$zB4vyw;xv;<6QZS1$xCpzs+T^CX+J$42j%0en7 zlcVYD&a~R0lMU9`-e+wCIh_85gi-c@6>)OdisnbJXehm|5uhY6MgXj4 zd$*x9B!cmn_KS#?OsK}jyZ95~!{ktgPE7A_js`{j(j}BI#x7Mi0ZLMVl7x~2N~1|A zk*(*UF+lWIG2E-1p>I=G$}lLEJ-|PYq(Tn>CJi7(s1x=8|04cFLP1!}FFhjtK-h4ZII@`8y>$eZKcG(MW9hD{J~(3at({iNMts5a zGP`5bbX&5x(%yWl-Clpc-A*-}v|~-Rwr>6u+jzqQTerHxRxHg1q@kWJp(OAva#-I2 zAduaf^hOLZKG`*l0RohcA3u)dT_+MrlYGtjr$7D4o_gv@J9+Y?oxsaB=Z!aBZ|l~r z&S<8rCY^6n_Zo;`cqcGTN%ziqF- z@rFxiEm*M7mU7zLop*iN?!5Dk*oIP{*Y&fqp` zSYR6gO0u1#ta2D14KYYr_^Ns-JjBs`(uMfR zu<(1VG~xMQ`Zb+)&?~IZ)JLxXN`Dy);%!bB}%M?8`DJmTyZ37ED=_DIgiWYP7}K`jW%`XbLj(eq8y_pBRdU5Dx0LI z(j}C>^{sEEm^PU{FtRT+co6QBaX!iKkZ-ttlDxjCX~&{@2-j8q;{ryJkKiA^VH?|s+@JT5N&r8EjV(9VZE%&+x7ukdX2uL{= zqioHZ8+&Zej(Xd+<*YsZ3Wh^Jz`hd3wI^m3*_~?#?Q8e;+0x|&Rynzn0}G1TXv)S- zmp$?1PW#hSJ8kcweA|1n0E5VrZGPo6+q9wF?)i3stzIkTm8e+Su6iX>@1`D?6i|vX zjsPXz#_Oc!d;s-+Kcez>tp0?xojqx@CU@IabGqz~Tj$s}zPbbzGt@|sP#SUx zB_vTCP(nI`EpCwBNEQ2Hf257~-c|~uS=8ErCweV z@83dj@+wnC{e1BbfRcY4VM7%1^embCbeej~agzZk;1WCn9Z8&-1+AgS zV=_kDk18b+NgQ6-Sl4Y0oY-}`uG#8P^Q%MUyePNW3h^Brt=-h!ZSB0T7ehlsfFAin z00g-MHm_!e&6z#Ju3m5oUk9+6XOkwEq4rj0d0AzalZiA`ENvt@D6I%A&X)?IpO6;M z%c@iKT|X{t=pNzf!2wVT#ETm&5X$3t?)-|tp@_G|eTtjrQhBStXKeniT?;l71lv1);}6&jlOp$Kmon@JMP$J9D zA}ys;0W*eLtrE4essWI ze*J_!@!~<-c^v-fD?s(F%r>p6vW0WYZ1;W+4mj9oO)c?=WqWKRwnc%^an^@L%<1c~^e{P?AZ7Y15{;-K=-sdB@&+ z?_GPF>)Y?VjWO;jTfFFMyZ(k7?2bFW48XM1)9Ni68|1b2jM{RPcaK)i(ZWVaddY$k zWE5|Oavwi_j1!g**z2#qZcqH_38Z)q0`Sdn^}cU^``h--Z-2`T(#j}p7InjqHjN!d`UnQ+_| z&OUB8-Za&2x$P93qNf?FO+&czp7;&E5imJkquhb!;Tq_eejmcGTt7VuB-`?0 z=pWLlWEwjz3Q*E=QvEp|Km4~AGKs~E9%=upCGD^im=uBL8tSw(%|t?>2|#Jb)_U9W zeuF*tYL~sZwHpJvlWbbaB)j$c4ExI0`|YYld2Yj_pa4V4F`)FvCqHsfY5$=jPEac1 zq^-%eaB8(}L_+Cn_vZ0MJpvh`qVd8|U@s6$?f;*>^YF8)IMejkIcIfJY9&wvBoH78 z36YG*7#zm-%rNWSnVsM4{6DtG9?y=~)g71 z`>I=N31Nb|r0P1SPMr#0g;Vw3FSrAGX8opXn!d_>oUvZ|=hGr@K};G@5_u@{^qH7F z`NuHIP$%pJ=6buj+HHAL$gW-)wtEFAJ+#SMR+IoJjZnKVG)alPIgu?Lz=PWR@-8Zz zt-ikB$X5OC0Hx6}XH9enc6fbzq>R>!yy=@Gr#_x_d?_EiOC_|#CFT#JP2dYI^igU_ zrc01s5>UarK|bymc75{{N!dAk@0@5`>cw2%apxC@R7p%69Y>QK_VKdL7Djq#5+%tY z{Mn8W2dOFR?8ahSe*wTr+$M(u;ACKG#Ja2LTef_e1C*Su9Dzg>l?#2`d{ucmv{Ly5ou{TE4ez`Ld_G)VxhWCEq(cIg zo|?q~=};`L@}-lBDU6;fc#_~08lNycts>HS<*8NzNXF^UA*}BmgVXQmi79*U*jan8 ztpl0D#rS5c%^kA({Igb9j(#=t{^aD<*x9}^YacDPfe8AT@R(5xyrUa*r9L$@N}`7Y zfJqkD0Xm8XwusdgRakXVx!tiN$L{-j(yrcsHnVDUE0yFq1;?s)G3o~dDvcmAIWm;6 z1Fv`5b1$8-!$%@^in0^rbls9_Th>rweFKBek4(j^FBG@?x7OLW9$jpkH6Qw8y`5nk zbV$AY^2_$C$A5(mp%1O0zQIaeI6GxV^m~|bTPd(uz=Zwzj1Y z4zwn_>+V%{;$*S?@FxIDAF-$^V*sVU+dXOb-#2MjuR($QRgC~jJVL*l)|sH58ly9H zp}AW7N@g~}_k(}t!^||g_UW?YbwAfTv!%TfYrPiGS?Rl`YtZD1nH5Ey_tX#r4SRCZcf0Cug$M?a13F_ z_?>sV?a-lKd-0Vqd-?5gYi@umWbrb)2wu< zQk5;KthZ~HWBF-Eg+1_a5$3x|o2ug_b0}SauyX-Q+QO;q_V&0vhY9l+U!JfJK5ny< zfJ)~AN~IjkF|+`nq=j5uB)Lv0w?y8u*7OV1C;d3HZ_<&e4ThePt@?ceE{-t(CF#-` z!n9c);PSGTW!BUb=uk?3n^JlB`JEm=s-E)FbBzJzo#vzojvc-#siaEjobndvmTn@S zu_Sd;dS^*$23irkqi>ylL;?2#{Cjp`KRUOb*;p{et%U_A18B7UqnOqWU~LI%Oo_5ia2F(fe`&i~ALAQAnBd@;2tX|57^k0O0+rAwl!)?-Ru&W|tU!9PRHho|)(e%G;%HJ^AjH&E z!n%9o*4c%p@6?A9MS}_2iR(yNb`&rvItJJ@%=5vRbq|G5)<0++Bj_T_uj3qxkN1NG zwOdh67(K$p3f5gUz%vGT?N8jhu0fWd0G z-74}6ZTs2~7Uafk!*%(#1Wu!Bz#%u9X^+;RB778fr5Iv!@4VBCg6FgLHk_63eOzvB z6Qx#PRBTnn&?Gi&d9e{2ByB%y-nVzv+GBs;gt%K7B9rhUmC#Uhg2}R<`qz2H0zsJ^ z4gGu*1uvJ=+?CG+lmsF#s$Yb%al}6PvG7;F`nCP?SHE7{u5oPbhg zN{13>yv*-}`ZROAXI@`U3a9rImow8VI4@66A6^JhTCnmqzrphP14^o=CbOT|v((#n zy3z$7lj%fy<|nbPy;ll9+1+!MA?L%{%9|z5m+i|4GRgW&o&lhga2!fM_`wf8S3t?v z)rVQNUAUct0=}>H*pDNH4p8E7Bo3vvwl>F!=D?%{Kxqz2esQ8R`}AUJmHFPh0j1Ph zq@eVyD~7>^PhOE9)BUhO3%w*Y-;L z+P#IgZc_j#sV>0=czOYJ>uehM@b$ig&;x0yR|TNS2W1)uWkC3s!}jul3480kR{P*s zD}Yis#i6u1;81E2SHny|N&1rnDqXUhZt9FIT)(9%mj;wZ;81da!Vu>OfE74YE(j=P z^s6hteY?0KZ-$9`imEH;bo7u5sNybzd+>@}`qDk+kGex%7*mjsG7_lbV%$5?P>zKs zaxD@?tOM|2cr;W&s7-joO5SKNvb z$;!_SA;N;k>{mfit}U+5wU*{w#HLCyL0@T&07^AgxmHz~gW_$2V~G$hl`_1zbp-0D zRtYLBe~u%Hp-S8IEE`bL`vFyy#w*}f9!ehoO3agtcBgVkJ=3N?rR17X;)tb}i4DBJ zRwy?eueqx`IdL3IkBRkspNIHb9$ZH`0389KlzN}; zi3?DQ0~W>d0iXm-3ltJKME{7xh%ERm3dQF!3rhn!`KiqlFb;Kf=Ga-p+1fgy)_yj^ z`+zj~7%Wdx%pD6MVm3v811yb(0ShC5hM-K52obq}t+~vPXdma>b}9m!lMc2hP`AS6 z08WkEtNwVnj}{?*C!naJ5O6#Zw#mp4^%=7W03%u3M9w0M3ZMd9ECzJiTtCeE(`TEm zE3j*}Hd@Q7N@#+(TPc)x;!o&FW1y?OCyo!>2ZsmktvBQLmp2OSaJLTF0DQ})CYPuTB%_dE9klg7uYm8y`s#VaId}zPc5w{of z11qzx(DocRTiiK`E@Q;>@TbmnKZ8;~pvbbF#QpZayx)HElb_gYuf0Zp6k@Hh5e}ul zwZDZ!sRCu?l~t9lFEn5DzMDfD#GjE1`u)QBi;Q#uRni^~Kq6gC+P(oS#$(}&~r6F6fC~g~C5_ZeZTHAeB6M#~l{qUy(lvr3n%!?T7e|uXP4yBN- zURh(SSJeWh>+9wLC9OS~pi*iakRt6=nc3W2@k*QV`Z=$j@4a&pUx5*`(M~i|JbnRC zx-!Ou-=F*Ne1MXy#7il+bAGIFqqSXYr9^(k#rn!Cuefz`U|_)h@gM)u9(nW;lhw~6 zu`SN#l-E~mzJ4(PrP+v`5$8MIMKS4v4@yRY)TPqRNK5=VAGhoU<#Kc=d0q%m%C4=i zr`u@o(BEgLyOevMrw=bBk1OFF(L9qznSG#Z?`YINwGQVZ?$&HKU$fkHZm+gmZ^wetS^y**@ZcHv??nLxf+vBf2t2NUFC6ewt^k0iAQ3$Cajr`;#!`+%t?=Fr06=uN zCsCjaxGuW41dvu^t5!FnWLzRmY9QDQ^v_4vmGacv-l^THk3`=L zP)X{F`T_L%`>`Ge6Vd1phVejaFdk-O;s${eE)JNJSHNMOx!*rfhB#QEb@q>Ak!>6h zNpPRI^~60i73gh*zEQ?WG^tIiL|9c1Je*-pe!#OK$GB=Pa440)6$gI7{E`TfR*e8iQu$irg1Qh~W~VhkJ`E^wSa4#ljZM@uFbwnZ zzL()f--pubckS>8hpoK49IJIV*v;Fvp>yX}bU&mx#(*@W~@r$dp^&p{6;(K^jY2PQ>OQkM%jT7<~knbYV{0#JH#7C>p& z?pnKjPZK(%^6dvdmdINGC>59G*+1NsV-G)I*0Q{WF;dKU1-Nq78wD(>j#?A67Kx)y zj#x*VRQ>1b>$&2CEL={r{yE=!v%YYJMP?2gT|+Mi`ljZ^l1U>~xoUuQs34?n}+=EBIa}y*-^WvU5Cz&GP@RCNVWCBaoQi^2m8bJ_%BY{Z+?B!&JIPbV>E)rr=_-g+iLWE)Y^@h z6xUhoE{L6p$J;GV^VbkdAh+4I!+Pxpmdpj?}olTaJuyLBN`Qs+9-!( zhw{)9d5kfMG382}C~pcMan{v}3&n+n)gm~5k%Jfk+(q z0gz;^O`LJAVfQAZ~-7BP-q$u z(m2v{jb1tBsCNX&dM6I0KrAW%l=QZbQ%UlAbDFlQq_Yl{YJhYojSOQ64e^(Okr+M- zcSfbHT*)t%B}H&>P^!pDRf2ZHl|`Q>0C*Dgo7)or(ureGB3c+!vyS!%0CCI)2l5a< z%(Zd!B#lj>t7!}lD7fHaak#?JvlQd~k?{%}nkuob$#F}BH2$TaMdGy-nt%%lt{qo> zxP~l;xu9oo(n=gBP^2XS4_jGopOwOGhVE>aW-Q)dBZ(TwMOwu1mgRNXhLSF;t17dq zx_Xoqk6RCb(%@*ng#zOl~MU6W%g zR|mkNEcZx>r%>%Sie$CZap*v`e&$SgRifqNoA~=+^PU(k_U~LN4EE$r} zIX+Ci{Oz0r&2$2g=V^|tX*oPlX+8_UP%>H}dFfUP_=C2WYtzP0zd04pLt5FI9Ah5O>C+s7yd6$jS0ujGGu?p?*Eb>i|VnT+`KjByemL z9Y{k%F+`$9@S`>{2&d5i@hDp!9WS<#F+d8mIgh}lG>U$t@o*7&M&M)#BSwcv1{U** z$*hEpQ&n|=)h#Wws(Qqk;0TfU+Oih7la?1E)|Q8!Bt+rBD~j;>h#=*_jU%7O`{GOx zs3cEIQaj3-c)A3jlKRuXP1-b|#sPwLWH0e zGn}I?F?v&A65yHR;_>xV=<`$E=oi2rN$vz6w@mv7vgySBZ3YXgy>Bc4_ z07_vSk3_M67NdW}iG_g=YBm`w1ayScNSsiLppDK78yrf=&@pKtBe`cqqe2^sMS=KTX|Kp%(PiJ z9}94yNh~i;S_gW!I+Iu1c<$POT{anzTTz*3>z6m!bsNh#cqiT5kXJzpCxpYm3mI zBn~AV$pt8B3~AGk{u_Y47~fk5WHNp|sN}~Pl=@Uo`N(GiN=uh6bz-ji7U=NN*4pO$ z-o1P64^RF9kg&^f?yOz6*1rDruRHO#xUF3df zQ$POo0VS;t(=H&dfM|vlfArLIC9g_Khmj00CI)+4`;WmbH;390#z8If_FIes#t-Q`^QWv9DR@3U#A@sTkPzD$79 zmD+`uv)!)m$?!sel5{4fhfeB3>*a#T+sxkhQUOZyIgI-OGM}_FN%1M}7+~UB(JwUn zvGVq#AN|`oI+U_=_w~$xHZi*n)yOa&t+?eb@H;`>;K zT(PI5_jis~13s5UdLvT&f1Xvqy*QWqs#002M$ zNklOBQdH7TrT2Z%IDBgfY*VXC?{g46H*8eprDwY6&|(_+)GibLJ4y@94c{uxi}!zBw*Eql@%oL zW=%`WY}qw6)(9t^ zlel-}bbiudJP;F{?lf6>bBA>DcQkjo>OiI!ML0p7-ud-2Rhd+@=9+-mxQ+XSgnD0I zX?3WB8_NVjN;C}Tst^FVL4-gg%^&CsqhJWmp((85O@!dkfrCi1RJcxgDI$Lr`Oacq zcX!Nsx)avdi-=)=49idh&WFM^08llgnSwiKh>E3a?VtZwnO%2n zfdiC^064{+l$R^fQu+}95OgUfsCXr^JOg^vGz598bK0i|Qdj@kZw`|ZGM2kh;)-$rj#n{B=E zX1HT-vfFOk>3kV%i*d;<;yxchDU)cd6VyZN6J#gM1e9DA0hE~Ih-5lI3Bwm1XOi~Y z--qpK0Hsg52CZjc$d+Q|?ds)yd}lF!apyX|sTKC~U&idY!vIP$pNXRTJ)4Fwaxo0Y z?-J+B%Jgm0`W4hC;HDLak^m*qNAX(6w6@_gs~yBl|DEfZ8aJ1l>z%pMUup5#w1Zxm z^I!o`y0Qj@>wB7fK0v9OUt**~NkhjCpVS!oRDhD7r#}3Oko`*mD1G5+%>cU)prnDD zx!Lgp`Lk+UW?7$A8DI5$eIJRIGXW)uyaiU?DytEBn+J!IXr+7>`sJ@TYJC6s@M25W zd#=wo5XIs;JoY#r#O2!g0VViP+y*jLs&sw?3UFLR04Rw|Nne!UQ{@4rJbukAfV*IH z5dA6bx%ScFu)X+FuN`=+3o(@A)<1T_?z&~0-FEwS+j@PKZMnA4YU{|KY{Z?^KM-Tn zk3NV$blUHq>4aOQ&xX;5a_^3n_U&(9XIpP*uqDm;aHi-W=C`=1k7cShK_%Va3;#)d zU}xJL`whK9J?EGXxG@eX#C4F5lG}VNkmX~JJ8HlD^#}Irr#`TTnhJg$uCU#=EVn)P zthBXjORc6ZYNh3D$aSb>GcJID(=A~@yL2UeUD6R3cM*)0pik7#^8=KE#<{tz!x_%C zmr!7dix(u}&?M68e}J%XIh|f*i-SkrDKzHH66eq}*pFT$K#L*77)J)-903Fva2DI( zpc$TkJ7yAv(S`je%C?S?88(0QjTr={F*r0xNMJy%SrM#usR@_SRX{Yfn(%=Hx zr060P(>s!g!$f4`KVB5^fKm`c3Z4kC^7q_kWFfjH0Le7A6z`;?d{ROs)xj<&iIp=< z&ii*&k~`w*4+qS#F~FfAz@Y*3Pr;QlgyppU!3pQppE{TpVkxb-pagLlxRX$7J~ASG zNCoIW%3x&NAwe<(F;#X=-70p)D++r0i zE37x1V=uh&zP+AFE&YcO{xf711 zwGFloA4yC?hY1J57UUIJBqhRo^yr8^@rR@K+`dlho>*m*@s)HCZRh`YwiVd-zE^11 zqU^h>2Ji|j4H%5a;@m347Xa1R-C9US64h!c4lqBLN z|Hfb5u;-tD9!qxb*sM{cpZ$n`@UV(>2lknXbZY^_nei`i;wW z<<>e?Cq;V)bkpu&4GiLQnEYou&N}hFH{PJFFFcQk@_Vew>+$Old%GX&cK4%Gteml~ zvCB+jEl2|=8|>`aD*Ml$N9|d->>QwElXm;nZMJ=Do9(z|gYDS0k-eb4NkVkB zsHp43K{ro8X-56s>(hTS$AnKe{dD>&Gu?FT!j-2$Chc^srBZ{0Yt4g81(cM1@O_#N zeUX3EVSDDeUfYMIw@~Cb926()p55E+YhT-Ln>Sb4rVWTJarn}v zXlhd6LkxWnVSDmVz4p7ky;$>Vx5@Didtlcp`|fvc;FskFYi`Vk6J;7u^7YjBQr@}w zY);dOXMe{XQpiVHaaQ4AJ%&ivFsDRW5<^c^xWM{)O68z1R_c?I3VI!%Nl1q^aH?6*ysqR z<>5x*d~cQb!7vJ(qh&xbLLmgTVJ04sB_CSnBzoXtnFK`IU`rRTx0|=-*-baWRRkab z^Nd9qhhYG|xC1v)?TlF8BDmKU)rw{+00d0HEs(?u7|LOwIc^rvvH;V96OfCX z1P8k$^$lK8QatYh+9l!eks|YxXX17S1?FeZBIb2g*3|~AtqWPgv@0X83cwQJt2o?7 z=olJ-_Hk%o36vxO;;{&jTJ_C#&@&H3^0L6@^c{iRB@knicLz{4h&BMki2ETYKWX)_ zA2sm{X(L=i4Jf>BY|KHKevVze0maz0!EBfyd23tJj-SNJ>;d!?p_9yFa56;(Z6|t- z9=xvr(WDBL+t=CTM5#UVOw3-~AGV{dL)MADn3YwBY~AvMc6D8mU0vB|i z7u0E7Vfe{@lM;?SYp?%D7G_wBlefJUPSx?Fbruq+kIV*ZM(4$E0Rm> zmK}=$H-{~P7wD6phu9AsV##=k9X~c^zxdUA_S7?N);hY;#$y{CcvcU1aqkV(_t9M2 zv?Y)B=3_-nV^3^X&?6y0kUnJX6_+AJ3i>je%yZqV-!t7D!_t2@1_uV6i2H0DN*CQ%~wJXDEaLDw@-@crCa2!x8AZ}KmKdmw|}24S-iyg?|$#QCSS#VCS)-@%ycBRW?zKe`n9?l0S3HT}&pwynkA}WB=OJO+o!f@_Itg`SFAnPf+XU|gm z#@}qRuI?)P>Hm$|Gw-ATrR13HT=AjZu<0W#t?sbf@Z~JXvhwB@BL2=BQ1au!H(<6g z;N!B>`gauiG?{S=*V7d6wDY0Hhc+hMYrKCNKuLwTIg|eWPZ#@XuY&JfkW1$Er_J|D zf8Wz`UVxIuNCv?c0Hq9Kq%Ic#rE_U=@iB}tu?q`S+Rw-Khd=yLTI5aEFy#Eebsz7H zd-w1&_~Xm@46?prvdrwWPYWpd{_x=yL&VRqp}zloc(GN{d+INNM00W|c|b{<675Tr z9`7{dcn&3Z=w*YQ0+dMR_In|UJVxmCfv2r9v$Uic_L;XAtv|2OK0ub1D!T8*@IHt zUVCWwYWp95e?2-c8Ue#lI#>>%ltmPMFw-B+?1x!t)3@mth{<|KG<40^Bc2IRilZnv z3CDqSMTuh~8&Il4oODS|joq|)neE)M!Zu!0ZY`@5SddcYYNvoO4(zgk=IEU|ykyoR z^EzG8jEi(Vxk#mT^$h+H7vwEKX>?>9KLQtuMBZ|2sjR$VLfo~@{SYl^A_XexeP1W# z%e@1sXs_DrT{4ac1l~acG)35BWD2pRaR9;Yq!SGq9g#xtNq`Q-EqfCHg$e6|Gieb0 zNmF1uQGk$A#MnwvI6EFIu+eBCB1mCGk|wRH434DQV!XjgH-V1v%rCa1HYEVz|nWh*$AN#rO302txdcC}T_;$8In#MKWemzN7@fcFHQ z_2B0dXM`ftv{xMh5X&cVeVv*+kk+|W;I4IGl!9ufm|L&Y6`?6$2=rKoQJft`40L=v zX1%=;bQnd`3e0oz0Vm)%iX*-fjfCJxfg7W{2nFWoM;gb%8}AGZkHZl-M&1(p(|l2z z3jj+H-b5FbbY2<#h@2rr;UMX}I5pJQ#4*M}cX%#Pgpm6jXjBYWPYJ%ZtQcUo#A*R| zs{#0mO8{DnB36L4s1o!Cl^|1AUQr6LQsMw$fxuu(R=0>g!fbgV3e=_ax}y`|@l@QN zeIaVUf1Lv_R@5v!WIH!T?BV;Q+o;M`u3iE_S!sWKDr$RQ3fadUgVxtDaZR;*~Ts-_le@0+ln{nxYh#}^JGad#^!nReN()g^Y*rV_Z}rtH|+F+1Ho zYNrPQ(P;OE#c(REDM19N$@$8{?|V z<15_&K$_0BEg6M_a?rM7G~mXq_0**ddI2Wo(kAsS^U39-yxbfmF2gBF;FK=g5#tk_ z`!Jn2ShJXC^8l3E+uGr-JZ^8i9&jq1IC%+?%IioHjjn*oC$5PI7SB_(Wu&=kziM##m|NYFKd+s^blUl0<=zQ$4 z$L#MP`+LM37eR0R@TTuyuy*=31Ax-InqL}^lgx)U zyJ<^1mi;!MLu>gGjI#ZIYKV=n#IUj#sE~3DcK+X@P{)1B|m5YHbKe0mAzj8GUG0_ z*ty>GW%zKebPMq_DUjVK{$6yv6hJAP{@M34OJBJAEGXdn(1-Kw1D{@X(#CpD9ZGWo zO6*iPsEbp{?P@uY3Q*E9$8B<1Gu#1OC?JW+=cE87`X>Ercvjid4M`V2ec{?B$_KPh zKhQ7R>N*{a@D5M{R2Usi0ZN>Dmo7t}iUX9?YjS}iV76}SU_0c9o& z;LhQ&FK{H}6debx5#4CII~@8J7UoCbazZhBx(#ZbK$Ph*ltfXwVb)%t-^Dm}+qC!n zk*W*NBr@hKrE#sCMPE0Mr(aSkd@6uAL(GF-M88H+nk`*OJ>4NY{NVs%Nh9b-LQfUo zT|sfR6_!+67?HE7$S@*o`PMU5YrRoK+64Z{O9MK9le3!UxTGjY14JF*Ktz@4D?+^L zA@Im?838m&|B;kw$FPot(tRnH#yFH!!+BIunuj&R#kOkYVq1a&bm=&%U6i!)O40xp z6#-s4Q9@;dXj>5+VA5A5RzK<55+_*+d1&l(_rx5a^oOS-_J3butW5zZA%eGa!-PF@ z-z4Bnjjg(BHNaY}{Q+Gu&pwZ?m`-%XaDb}D!rSuNPC%fgcK4nQcGb#y>Q-c@PIcLj zfBGz9vxfnncO!CotKGS|1WS=6=;lgT2YRE9o*1-4A9h$Pplelei7l-yx7%-Su-!Wv zZ1uWvTfJe-ii$-S9l}Z(F;&*ymVo23)n42;U>~1swj=#bJP%w`VJo_8j=|+rV&8ZK zE0$XuQG^fQU7i5L5KRYMN>;+HR0S=i&q(?Dw}Wm`&oE;6t8%^5c=i3{<7N-F_RG%) zP|^Xkucr?SoCo3jddA*+?>*MEDa1yL(WUft{KK|*$ztd8(f8!5lpepT=I7-6H_m?( z{e8MRkW0@b+BY^j#&_i%`|*!|Y)?M*Bue^Ao&Wy#zi7 zdMYnpR#uXWx}A4FlB=ev*7yqnNxkX5bFtlW%VPH(4n%f?j-5A$(rgr%YiwkU z_ZhFLt!`Zk`fbLuEA-|ZdSuhi(=0XCHJ@8sTOFVz(DZzOk{`=H6p1shFDJ=;JCvut z_GS6-a+ddH%*)edK6UqLedqxtiT8>dQ|p)%anEYyEmgoJ14@2gr$S$cuR=dA07~;2 zeHTi@V&nlODdqmb4}RbPrT_DP{tr4!zMWnGl#K?BA3(EZdpQTy<;-igx_;H-vin8% z@;b0C07_rZ-u8X!L$zW)^I}GNPSdlKbQgJ@QLL%mbVt%HKzaX^HQGft6< z+pPriT?cQ074A^OC3#4}w2OA93=WBi%p{Vd?x2*1-i7|o0z3Xez8yL^VNbnu$_{+o zVQUs8Y}Jy4?bx~6w(nd6P*8~VA#p2+n>iy6ft#qyh^{#R9ne*DctlJNoF4oPQMD&F^p4hRxB@=R=r4e^NYW6awnN zo;w3j`mbNSW54*ryXfPnvAT*H+q`b6ZQarW09J)gm0Wk=R#tA$tg|9Og9mfN3Lz=s${(?+6Nu!!|KgWMgp0oI$kh%*k=< z9SvJIKA(fL#4@JhW!4j^w!vhnQ!QPDqT;I3Nvo`w1OR}8g+pvZZOED$#;l>K$QqjK ztZ{J#ih_-C%IKgy0w@BSXzVfOIOEEyT$CR}VgMCEQ;6q6-n*jwFuH>TD2aPWL}k3W z!K?g8C-9Vd89vYt6%;cY`F)-WeF@4!E{8H5P2H2ABq^MZf$K~H0!^g3j$jf%vu+5^ zqDUC)b;5nn`QsIskB*=?c_7!uCJ+q-P#PGDSZn))bzrqDlFBc)pxp8b5nqc7kejfv zXr2wmDyS3)j^o5)kkNlk%v594pAty}AoAj@ZlI{*ct{~%ipWbDB5Rc>qpB>cv@!sd zqQX%;mh}MeO31zfjzV!8HPJ^+&5InzU=>_Pl~q#w4fqH57+4APrl@?%hYL+g+VlAq zNv~E6Ku4lvMFof*(w?5)Njr^_?Wdm3vEROw128rO0|gvP8$xg>MeODqYi#vZE8u{u zwx|98C&r87FdDMc0G5kN`T?m2&=s@99(ZUi09TC_lJ|*YUG~%e+;4w;_J~!N-T+Vu zSL8Nyo84Mzc_`){M{)UwM+a=*YpwP{I~uoh%V~3kZQEGKysfkAuAi`LZ(|(hZA+~holzCl z8Wkw?m)IrxsgleEeUrs8s4j5BWjf$W3xpqCT)I)Kgco*Nv*f1%rN}u-xqU8^$Quf5 z`QU@Y_R>o)*`Y&kaUeb8){Q&wy3_8u^DZoEuCsOP*8wu26rMg*z5RE>=ks}m?wjQZ z7}UV6*Qv_5HI?xfg&QX{1t5F)u>IuUe_~HQ`DAJhF!Wu0&-oQARyeLDfl6|j`RLl0 zGoNp7s`xpBU{$zqU#j;hno*!VTmsKrPC2Fzh6@-K^hW`Q$KI}_z5H^-UO6yj2M_n# z`zHZ_bI)2$!C8Co?p3sLGm6-2?blDlZST7g)*=?7_=N4eYSeDrJZ8IhFM~^I8G6kG zr~x*mki!cDN`8#a(jNcFSK5cOBz2EcZ4Kz-6JOb(A9ragWYbPG(;y*UV{-veN>l1f zcj5YRp0)OAeK-S9N^vN8KuN%&IF!;ZH7}htO!iFCXq3GOYsV|E*iU})6B`&9uz&o= zf3!y)eZ-v&ii(3ZG5h_@&y(tLIo8H>8K2X|0-$s`2+v|P7og-t-Y!&3=3vUazR-Jf zJ@*r3uICH!(-iRZ&Ze2})vv+EH4jmgZl_a0+$!_Yq2%-RC1v0H_=WJZqk!*IAI?=$ zcHd;C*XBPHP?8d1`Dy`5_4WJ$&j*7Isy435N1l;GQK>JF+tm^mphvC>VrobzoeqpX zEtaa_Q^8ATOp$f9<=c_>a_r56qxS5}C+*mc9vU5YRQVHZ!k-YN@X>ooK>Y zfX`9I9r} z$W@YlkOFXVj?o%%zBn&SZhJ=}1B}mA6ToY9MDwS<5TOmolfy>6g;Ngf%u)!kNMv(O8J+A%+~_JSqbyDl5r> zLl8iz3JxQ*YL|d8<-#o{(5QgoOAuod_mSXUSaIB35g6%asEDaKOaBN!&PCC97)AVj z{eyOceh3WH`0F>H>?StMC zTUs(~jn%_;*Vmftfp4w?q^@*^=05qj&;IKdhwQn%Cu~viYHPsXdTX8SymJv^U5MpU zmk&ScxBuRI#tt4Cg~k<(1zCKnrmSk)wtdRB?U=Mh4UA#LMhXhxU_oT?Z2PF~-Fpmf z?k;=p*h)Lnx6)DA{fQp4yx9A8^O`cd|L)D`VpmAfW<$^D_Y@ z-&G=!2lS_NPF*RV3pmYLXgmmqU^~B7hXE|Jt-QG$C{KEWBA}TkPn@(j-+TlArX4(V z$j+QOgEh^qi0^GhIrq)ZOXp$%@_*t~a-b3e+^r7kW)1c)np2hV67^9#j~qE-|M{Q) zX-_@%l;gq@Czd#{{Jeqjf6f(2Wm(P9CgPQX<|9XXvZ12H(v$-s!V(hBek?(v;xdXbWO0%{pRo8StTb#>k z`Z>?j5epaRP#}|by4Lv6$3R1YIrwD)l+?D%HK)#@)0Z&9uQ&6lx=-uFc>zj({;2@2 z-I-teBmgD(c>_wR_m#(2%`E^*m!n5njJ$lUIF!7|n>ds_pyWTOa~0<|6h53Q-F)Ny zM44~;uX4JJp=l=FbSEQ{fRaO0+N0!9W`odH=;AUK?9+)F@Dr08k3T z>9RsR3%LVR3}wgdr*iDQgGt0GMr{9~6ZU?4r)^tXVOy@l9QcjR&M(5cTX|{B=~Br< zF6L}UuI>GE7zMFdt2xtehdTzWGPmE#^84-KJuUXw_coz-sSXfKfRd`HBMqBqZeriU}UH>m;M3>Xlv#0Isr*)I82vVVYJ`*-UtUB0Flz- za;q*!#HX;zCUdJ%!&724n5V9-N?PO632Ru2!tJHC*0Kz4mxeq54C&&b60Uj*b&w)V z4Z0kOrQ`}YQEV_KT?*(bKuLOm!W<$alCw*>qWmb_HE>J8)g&Mz2fF3xKqlIy0VROd zc(J2{Lz47v3M5LA%F%`F0er+^#F-3SM!KMMKLy8&0Jlh3I*nwd4n^T`2!%ta14k#4 zEU-z3)CfA=LtwAtV^KhpQTzlZ+w+|d#{rY@F+jH%0BeYPk|j>WP#*~_N;&C&a$;;e zbB^{Vrw@ZJN{<}AL_E(5bEm8d1?Qy#kBW=o49m9~bRSifi>nB+Gyo%6UK6lX*HC8l z&6QSHSLhUISCLLSk&1a%s%zeHI%fbz)J|E2696afAX&}}Y|shr66mYG@b#oGU4N<% zXd_5j|3JUB0n|LV7r z>1ZX9H`k*Y+i91Y``I8v#`E-Lnx@k+ZcSt^h(oEZt%GqIJqJ*7-xIpQ|B%?#)rsQ# zkL|6u-$HciMP~`EWqFG&U$z|XmEHJTt+~0GeM7bT)!Kbmv{t2DuzvZwFG!fGp4zCn zc>MSY`|WRkYtKFVtW!ST-P2=t-F26J?XIuc<}I6T1R6=&_QVUVG%8Rrc6FY(XbmE!l&&%vS+Q`k^Nm(dK|2stqlm+!^<79A>pCsOt1zy(%|XGXFeCweWW?3S`jF&tuV4 zeR3f{N#{Jd%=w!+cQdc&D*jU9{an(!nb(>1xRiXqO7CRS+!szJGjLh4PBO7(hw+>K%8!(IzGJ!4ROLv$cD!QzH*_9@kM(<3@)hvE=9A zrASy7ypDgIw6|UZP&zbhZyh~mC;QLZ?QrXCzqtx9X^CycixW4OgRXvMEkvxOy)6f& zyAcj~Av+G3bP}bzb%lM_RMuzr-rZu~{N^TGyS@&t2zUhqD7i11K!VEzD7h9+|51~j z7d^EXlO?WPKqV(q#GX8qYeRjicanojD;ySWhNZS;plL}PItwf!sJ0rx(}dK zyJw&m<*q$84mdJ7T!;u)9FZ(6Wznum4%MY_FXSOsl^X|Gq`VlquW}KU$*W+!X=t$e z#myYfs{ysJ_|=qy1+vV?S}4WR;^gu4)|(pWPOp_Z1459sq{ReG z2wdYe=c3RhLL6j8gapnZ#`z?G+W@rcgg*WK68#&8J`*+(ohu)rI~R1(KTdd%*=yUrf{ zPLr)%jYt{Ae*96V{l`!C+0%de$m%OL+M@tuX+l7+_E>Aa)ZbVZ9=X`P}<+!-Gk`c z2ln(cPupv+y#|+=^pzFZ?YG}%cief0U3Jw}08A~2MO6gf71xPDq5k{htMJzj{kJY4 z=FHNyw~caWl5Uw7_CAkj*nT_u@yGTte*5-q_#OD|wtdHTEb}$E?^)(vDA-2{&Za|nL(%d(81I4q5&l`cT6N~a>Tv4 z04N32UI3KlGwSA%Mkr+r<(=YC`nP}kv6G_|p!Cgee$&0Jfvbr>*W~x{KGaKou+O9T zbCP7{bI!vnDB@!1kWFvhyMEJQgH2?QMBW^Sl0-^s9H1l%E@kD~fCnF@Y|^Uyi>X8Q z`wRD%hXTHDFVq*l&sD1Hd-WgvpDprs4u=vuRG*&xp*!f%@xkW9jUycz70-Y2bAXcD zcIv=QGWIDt?_vnZnTj6;R5|iN!d}}Kw?l6a+mY52=tb$YyKkPsTE?S zD;5TTAkV@gfSJ}D``zy&_NToeI|lbb58O44WxckhzL&$`GP|Em@0zRY;1&=7rHZOj ztW9q7tNRQ$y@$z&ytqqY4z2_@KX^9>{SsIU3%F)rNC@ZJ=wKcu+LN~L#R1Hj57>#b zBX+!R*cMeUvb8Ig+wD7Q?9qpd?7D07;o{&hfESpAQFs6yZ3Y9vI$%dd=-}X*;z}l! z0HtYgM6q%SxQgP5LVPYj6$g6q3=Z-f_#L2>XA`3Vpfmx8(o|@OLn3-_nwBDF*hF7p zB@7SI5ATV&ya>|MNl1~`$5kT5HR zE5I>kpLvsM{A_Gv`~A*#vKo*(bzbk z9eR%XkRWO6MNe5@*hT=9#^5^Yi%ddWGLW)wIM(=s$7!Ot2GcIY)}R0(h>bK?`_6Ug z^d}WT{nFPCN0=V#;&NFEz*CfqIA)$K`As2DYw9%c?r*wfD!+td4sthKApI{W(olycxug4^dtiJ>)EB3fqq zQQCdrm5{yjNx!`b7h^r#Yz^fJ+w-+r`^I;hY!#N=l<(1x&f35K=y`kczYkk|#_>3KItFg0#HMR%~glig_7%yYiKiubZV~KNcO=FQgbbqbg zad$N!RuSTyD6?m-$}?Hre0Ad?wa_@4yFXe`9nk_hxxad#IKLK%hVq%|NaNOP0ZIda zDDBWU0F;_gR+sAmB{&sypzz;|FymtaboAKqV*qeZyM17Pf4|!YiaY7H+jiUL&0B2K zHP;~ih?zb)it=OPLf@s}h0o@%+92oZ;Aodo4v!r79Q#{|{2!D^AO0_|zmCy|*X`PC zu4P@m7SQZ=``VtnZ3))x1hn})l~d4Pf$D%-H#ru@CX3sh&>9R^e_Lq8B4FV_NPC_>{av=e$tJx zgo#1Bx@o|!UO8ZoKD5amdFUFess^OO`dje53D);%K3 z0!n9{e!_EfC}qvFPYoz#<##dl{-UN`0F*A!Gk(C$mMn833!&7;PJogWb7^7vmw)*e zC-Ua=Q2NYwe4ai|p--!4KHjIBE1c_{`My6_zE@g&CLPsw-OCFAxD-Ii)8B_z8a=;k z?e+bi8LIE*1t4~sCy*JFJ zcLG3Z!dBIG*@l*G+qG+n-FfFaTe(W&Cjd%Cs-G`hM_5<0>2A}bPw70MBs9$xCEYXP zPNMxPFA4~OR2g8c0Hp~O^-kEwtzCAsvkO3}4nU~|K&ke^fD-L@I;zx$)Il=%{aG~D zp?tbAx>Afdlcb9!28T=3afl>P&?+UZ0f&e{x+#=$kE4`(VtCLdhx%OBbxoL6uUi}( zE;%3#!)-JKw@oi?=O ziTG53RiksKu5<*^HqaK7Md##~+jUnL+I8y+QAmvL8R^=A1F5Q#`^tPPug*nmisNu$ z6#YA*DGgH7-9-v)Aa8*aIdJaeplI4{h&f5+U@gpvy=i>9^qxAwdY2HO1o$KlB|#fb zkud$2qXRUwipL~&gae^2x5!T zd>e%`Z5$=qp=c2bv5UFRvk}AshXJ3a@Chk7!D^oKITFv4$EnKhj~c6X>VPWrCKc-O z45ywJfIvtes{``@eH!32Q>=U);-B^9c~(=Mu$sCEK4!HX3~Nx3U5FT)n7KwqVpxoe zSu>(ut5?FEvq=3>!aOQKhVcg6f}nm{#3gV+ey(8mV#) zOrmcb?--LN_zo!z>6uV|O>*5wdi_EwGuJ&mA?AIa{prO#fXq&7?e4T&Hsr%SQRc)( z*Iw0ViHHEDh`kD+^!AZ{JJdR0jiq6%Dn@M2-H5#X%~IBfaxw)_`VcE`KY7`neELJU zlU7?@55JLnpWT#KZ?e*940Keg^gzM=PoRLdwrfkKMkll1c zqusKt#nvIN+uWRM{h)`x`psec(=(^6wYS20N6KyU>g9IR#^tO9ack>9A^i|yp_5Zq zQyRDJTMO-`ZN=n+vTwX}7Ddt0E^eU$7C?a%0hk<&en%Cu;iV>UBBwf&6qo zx%(8&GXbUL%a;Kp3s9nWRG!u|x26UCBhW=ZDz>+`qnvx69eDLsJ96|W0L4+bNpD1l z)s41e#}3gv)~-pbJd=jXiMPtTQ9X4&_dWn9i{KUbCKU#rZ^S^v*6FHajE z&PAil=l=Sl0VU>~7X`j(kvBhIefU`t<*%Ig0-$sOg8KpIL!aC&Kz>I@q`;&woB{%r z{{7$o-2qCO97=jG`yC&b8R}YPUF>3!{m#X{uX3++m)*y@cXV9`&PSP$02Ha2(J z4eQarw5^##%^J81YMfO#aVQ0C)lqBa0oT=Ox@x|P7agVnCFmepIIjboBM*8kINM3& zsSkzA`}fCe|I1PP@c0>fzxA{&suG~IVkV%(&&rNN34Iv(0;R;AKB-1cSm}cOK2iwQ)5#$fr8%go?ZZvq*XR7w^BGN z;s7ktH`Lh)h=SSa_S1;-oPqVI z!opz_N~JYD^?FqWdXTE~9oVsSd9E#9iU?bi!G*@GV0?jFz&RDSJ~*hF8}sezRRO4{ z5vCHvH#Bo*%Np4K}Mj7>pzhVt}35SB1w@@ z7;(XV$6reO^hft{f_8COpuoSqY zdIAoUMtkVnD{SRTlycLbM?dPpO#EN$3G^K;s$7D&-(tJ(?iSngKnomN(4Zy>paTu5 z??AWNyRRqgoj0S-O4b3aWEJIO;jM7OZrs>lJ8xcL*I!qK*lHdeX(RT_Uwwr2xYO1- zkY@v9dG@uNuChJ5ufk$lzMVW3x6>VCcBX3pj>Iv$swHmgHssm8cP+Pj?_9=w4dX+U zo$m}H+QDNZ?ipn_Mr5<#Q{?S zYJDD50y?TLe|_h_cj@v2A_i^KcTJAC2}~@?r1r<3d~ApI6$DsrwiwoA@ zQo>^5HO^A>bWi;s&1Fw?A2&-l+p9`8SNtqlEJV$ufX2SO=&v6RJ)k7(jk4|~OTOjh z<%pAiF#x5RwO_c)q<~+?e5hyXH7zqC*FKF8&jpmwT`9}CRd9xTD{p?DrNV4L>E)MS zc4vQY|4^$rtObYQUY$l-eumAe585~Ml zwD`5xE0aiNE}fO z-~XAR>%WTulvH``4W08B+QPEYBp-%TY6D0dhhC?9CY@Ta4!__J#H_O?YHz$ghCZYL zd+W%Ad#{qi+wSdVJ8w(c#tluj5xpcu01HVe^CgdbbatFRowQ&74)ft~D4pmH15QQk zMp*K9Y#rp6@_K$L=P=k@fle2;y6$`xd>tL2(iWz!gyopd=2Zl*rpPh`a&l#Nl4aMaN1WUUO6VxWhKU zP|zA*b4PW5!#s3JT^jX>`eLT%=r2*X)Ececn;MPU#2~;(Kio!r6IjXO5M5RU?onc$ zU4z!uJ&Z53v)x4iD*2cT=fFG}w#f*Gk=PVK6(WfetxHzps~mSsEG=>GK@)h1>!r`sx}?sb2&!eFHJ>%W3O3rbzpr-! zPONbo9Ur%eDSkkS7SJ{TE8bC6#>We2djTR#A?q8Q;1_rz~zj+LMx zcxo1S)fMo_aTpP$c*l|C!575^V@6kjQ<~Is0g7U$LI08S5{;v83i6^>pC7VvXjcqi zSB^5II!w>=qq8k;1T;ebQ~{hO;zpAq?IM(AmsetajsB>FGpVdh?*)q0qkwCJ{UZPj zqv%d5vlT0AIbe9eD}X8lDtV`|HBC^}T}R+-4kh1y|CYa3TK9^7;Iaz7MZtJg*Q)>B z8I-cz#+FVT8j9Jo&nN7e7ZU(_UG`yXHyld2h`f~mC^45L@&=&v(o11`1szK79__cc z5P54Tp0dXBNxKI?>5=cY*veHYK(*V(2uO}6D4aaPjbxnXoLHC{9i6f2-feH5e&u66H5a`249|9}US;H>i; zO5#q^;lsVIlx{&!y+Wi!508Cv%s%??BNU(SbH1#s3;@5(Dd!gOvVQ$~cTg=wp3-wU zeV+S-bQ@@f+pDC=;^HBlSE?e?En3Y`Bdjb`0l&!e*2s6e8<+V zz1r!G(mE;{1>;t<4fek-|4h1ZeX%a+Lsjzp&XuY7Rr#|3h z>htrV%JF4p#`*FW!k!#i2><{<07*naRLf5RPj8>I?&aqLC^>x!9K_@@`^#VZ(C57n ze(@;a`#&>Ozp4K($f3kfo^GrJr@V6-=eU!2=0=Eq9>pa&49j~bz8H=xh_1w}jm_<= zFZbDRo;YKNPEDb(w$YaIYuT<_CT+)UlXf*0o328HMSzk-k@UTi2*}CP3H!xwLiYRT zLw2$^f)1dF?biL>odYA^3(pd;h3O3t1 z~bqbNplI{Ms?W;RM2WDJK?ld4B%*D};xLx&J^g@-5TyvXUobuIIFoqa z0W#S;7~f{BszF2f;Zc-fkI1qbZB>?%U&E=mDS)#nILAiE=o|d$)?qtwvd`K90D6bf z4KqGv;}NX!Vbv`kV6OySR$~dcjgs=BAubnrF$W$&_ypWq((RPLh;C2mkO@-FIWA#ntwrXWA7R=C>1Q*iM zWmsA(02INiqrLcPW@W?)H!kif#IQ!tdo_x$tFOg`{W7OFFBm(3n`Dq`aq4y5sgCNm zpznhFx%)(w$Z>!!X?!vts@ZsrZ2=G-P!gCJtW`ldqoZ+q?s@!6F*}Sn+dK5v&h_5P z8{=y=O1aUY^b#U(`wzfn@iBlBB5(BtlZgFI*}VWt-}t*0tSJV7(vc4b><9n$j{Sb` zNyJZ=T2t*3d-(1~MCck(4v(Vo$|OqQ0pqj=0UA!B*toAVilw<;d+vo^tiC1fIHI5p zrIoh4rq;HsFJ=8I1l-H918)Kz!+CkC{jha(ePG{waI^i*w>Dd~ET+Qx_U^l#_QW4Q zw1b~?(s;PYN{a1)T^sG5J2%?;Yw~QvwGwv|hok6)5_j0(nJ6xptMc)WC2>D^?lbKTKd(K4#*qJZxjKkMco)xjbGkzK(IPNB zgPt=uHGlM@AHlu$W2ak2931!Db1y%he#bU!SZ`&Bf)*BHtbljjc+L1GDt}*ICJ8U* zI_N`H^8C(C8}$vzW&%n9m=vSkes+pWwhIFaCr?h=Gk-n}m)~jD`eDR%hwOpd*Vy+S z15je!I`mrH-hCgDw=;cq7B1AaO+x@mL-zFtr*$X^Pzu&7kx?9?^Wad*p8Mx-+RUeF z;DWm(3TP|}7;peRgJfuM$N{EvaVTjn$Ysw}-Dk&LQiT>?x+DsyALV>F-%Nb^ivg7U zJDGrz&i@`z8XOu#iT^(bfD-Bq3h~ZmE?Iug`f$D#{(`4l0F*A!L4NS~&?nDcJUoYz z2b8pd2mqyTG062+@C%LSQ1b836}mT4lSJ1(ovs($XG4MPKGwaw1C-eCWm|Xeq~6STSryGU%m4t?GK>RMLL_>##lXLd4DtA+9wZ zwmn-D_Q0M53RKH%{n{$@0subnaU;3Dz^VZ5++%SN|LOi_0!qR6REIf#@RKeQz&h}P z3G^tve3>(=@5c z!2}y{#sTLj+sZksN+r$jUAvZ4Dob)`;2fQ!Z7=P-^4fc^x8CplBoHk?NkvH(M|B}H zK6Lt{~T8((klURB)5B2*zmES&^^2%hRjt#~jdOQLdRs#5m%o`JPU|pDtK8^pE!LA<6`!sy{~AC7ex^gdyqx%*;l_ zR2l(%Les0QGj6?u==G4VJ|_Lccve%|&`OjYYEs|~L4XqVDPeKv4qk15C&EC(2!-nm zg6kN%iL$8TeZy&cOcOFP;O-ZLN#z#<1;aQ(KBk>HS+G8^_bfnAIzJCjcez7WkUs>= zC>H>UkQ288K$2X%8RozaDJaTD_b3BK1q>vZNMa#{$XC!ms9TqVpz|oZB3KA$9Oxeg zBp600yxoP8vU01z~j2v#7ShTGW#2OqX!daFHFv(w&8eNbr*M`#rN>I2%#!5|}YnNKzF{Fq94)?X(@|I;}LT-wLCB_Qa!A z_WZAw0K66A!79TJ9c;J%@wpug~@Z7VSGQ zig(I5V*tG``t$OI*>=ks%t!D@c<3lBsxyOVydAQZ?r-fEkFB-mo?Z(>FV~sl9yru! zuf1`|zTVpeBTfvzY+DPEcf*Q0d*DX}2!kV(TTK6_vBooGVhCV~DQG5R!Ub4*V(Lu~ zDEW5r>(om36)%QT*X02vqHx~{0$!My>ep(ShPAe}I*-4fZvE6wo;*P~X*b=p77e=} z*``gK@O*cp)z;R!dzE?slCV}M|A7~me|_hWwo6}GAoy}QV2B5UOng;70cJ0}@Phr} z4}WmK?CXb&d+)u^wmkK;tzNU*O3P$Y4g1P}Kc$z+*V)9o=jsX^)Yawc$&YE`COzGg zddDc`i4g=OYY|(st$obSo*TBe-a2D%yf+CbJ$l!2``Pn1;{c=7_U=sBemuc_=YW#S zU1|`aM$e&>g(fr)m!$^>jgl>@D@-z?#9eLVB)@3sbf z-KW>L_7x@oC3$%}k2_gDtfm8$^x-w#;^Uw0-2Aa0rUrZ)q_?p@u3Y$YscW78E*VM! z1~gICS1!|J7xasHz;+0j7Z)xh?Bp4QbH8Y^*WWy52hR^#UBz-+zPQ$Ybbp8mRR*HL zhzOU2ESm{b1d}R3QCd!%9J3c*9<{%G6t^?5NJbI1edg|LCTmgjOE96T!=o4)GVbbR z|8^hTLIi+U{@x|EJ{6Y-l$2gDuK=`g0D{g^UM>(AGzf-pkjdwvBcn`;&)Q!<2T)?h z>KRH~QUIkfgqK3m5dbATZzb@uHkw5}0u7}MKed_6nY{U$QWNt=fJrc(1HdVy_Rw*e z(t%+Nz}OjpEfv(J*|AdzJ8&dn$BsAK+0(}n;2y@dei^^OFGPeFwiNm`%{`rVp}zyy z^=erdF&P6^9BRXRTc68Q7zRgmP1Nbm+;ZbG+j!G*7&B4BqR*m;qi01lG1g>l7$7JP z0Fndq1I-P&h!GWMaxY*^ppuqR z*fu=_W7bP(Z5p>0G@sfr;cAD4(bm~(t(d6w0zS$^lXR^Hh@%G}KzcL$>cn4ZfB>Sv zvT~Y7^1LPh$pxjrLK!SX;6B`?vCpwA9h>a)<2r|KmGe61t^-Yk$>o40#Uax*w54pk z7qM|fucNT(6cr(d|w>mHp~B^*m>aY_uOh=>UMz?*WuP zxfD=Z$aADn8dDKKN=yRP(Q|0141mlFjfhiU02qF62&U4oHT4c!?Q>`PkS%mfzTTg5xgy=6}D5+CwQ6rG=WE<*8`f^!7 zN$uepg;>;&*mnCgwLqn9+qT=6+rP9OJMoN0Sc3WP##Z^dw!|vPn_SRRW&8$gLkhnO6E~gROcR@Nxps$f($D~aaRQUKZ5Qls?|*AY zn}%#f&2@I&@_KYm!ieXFalg&v8ts<|%(=)ozu<#23 zUp$HUjG=);H+Hw>#Ps zfGi2?hoUop&~bB1o}F(hw&qqegxW4z-@p(WN2Opng#Z?TA#J4H<+yr zJBk!$KNNUi1kj1l-4%s#l+C0USLgkG);Bne=ed{-;w>x$yGZRgtTs`@3B;1OHD|t- z2SAgHNnb9>N0FU|6-Av3M^|tRDzT>|P~w0r)&iISX50aX=AkD5lgj~7w2i!><-@uP z0V<7;#pug}?Dtw;){vW&78e(yab&Kp@-VN;r_KuUvaJv^8!=r}hu{-dR6-pCER~c3 zwo>0n>$pX26rx{yHj?^2%i{Vj`PMMiGfBYWxEoJOGZWLi z4Eqp$q>nxuvAz2*+K%Imwy8dDkKJds>DF>vy|$j~O6;?(alDWTQ0j)E)NQ4a9++O; z_V^=J_VeeLTK(bz2Phqcq4Yoh*FJmw(@8+-nTHqHlTTDyRc#g;O4KcYlB+ZFt!Ggt z{iYXF%04t{K74Q3-p4t>$@2iNogLI?#Hx#>`&ML~0~ywV=H%GOAsC8>?0FbU&%#hz zz9QEaR7(WC10V)--<{pIZ%>XLI1_l<2ljZ(Qfa&{f@o!&O6r3k8DlNO}2jhdVAph2khpXZ?+YyR#;^v2=8=DYF#C_ zr@L&nV=h0goo2c!1yD+s#eqqH(xX60m^Wl$SX zyR8%4-CDF*ahKu_#oda#yGtNNOK}gSNQ=9Bad&qs?hc{&$@ks4ckayjlbIyHlFYo> z`(0~2tM{JLM}hrGpm{9wk5S=tVC0QMaLaqK26z-Tg?TkJrHxn7h$K~qpqJh`aeq<= zldU#DipJ9jw&srqEe(gRrn9}3?xvP=FQ=U6sb(U~g1PzuQ|Xv)u4z)~+4rp5vWNWc zZ#wUye=+hT+1X59PNQ+upPk%5H;SIlJWp~f^lJy4{{*#&Jldv-TsPAz1@7E@9Lr&$ zcb9^+dFI}D{3TtIcj-HwHv%BQ;hQ!;Lq7^YH(wRw=Gnrg``91xcCY|+Z+z&~v-u9@ zEi?DayZo)}1JVR5uG5EmpG7kqlAQ4jU3L9%KK~xyhhP#<#rZ!>+MM}Ri9izP-3OUSaQrwpUH^cmye~+o;Ij++ zur!A-@494l0%YXhcTvV;vn>)=mUsIWp&cLZ3H7^V2_Wd4T*Pw9!Zp)kTH9`SF{^fIE180p2x)fdur!-^yoC2Ae` z=SE;VlMjM=hyXaVG5A4?b}$}11Uc?E2w?|>^MENNtQMU^lbLN8VM;<6Hm-kzQc`6^ z4<*s`mwL=lk&B5DVq;C+vf`B6t3qj1EFs1_1A>v@K9nx3xnMHSu#d3z5r8D7*#`e- zzt$D@W>_%(M?v)*ElZ`IS8(-02T?(?64R#yCFU0H9i}PH%&U5b8Uy0{mC*a!Ri~!3Zi*I)>Vg^3Hy-QNrfzcuI0fG2b{$wD z74}Q-YtPdmTwf$}MY*7oCf7AUx*rZ-Q4!v7 zoOR$=Pf<=1@wEraO+nDG~8tb(xvM6&p5sSOpTr$VE@ddaVPXwzem8(zZZ~r`J zW@kQM`e`)S1|Z-Y9*qs9TyTrmx?oc_x^#+IE^hUoPY9idp!#I4*W$)9Ea}a%5!n6i zNLrmW<{y=?|5m3dw=_4J>R}|A`J`CTkP63OCOoDY6(ma@&lypVq&ld%ozVVR)C*1T zBx`J}tZsmYJKe0vK$m)%fi>uy0ThGffm2Wlr@C3E%@4Wx>3Jjh^Yd(#)w%(*&v&K3 zO=8~tN+h*wi@8Pf#||;k&Q~-0uBM&&!u=f3n>jd%>)FNjc>-P`{pf2)??Xf9nh03K z`1S^zRF%=vrs868#{3L>#a}F=t%1AA<9rqB&K?xJF1`9ujHeO}maYlc?8Jb@o8ZJ5 zr;OB{?7!#P#h94GXB4^;sLF4ik~WgJO|B9LU>k6Erc@eqEI4<#6^LBh_E7|}Z0{fc zsERJ8VpkL~0#hBxHM2Xryo{e#yi{v?0=M1*`0U>)l^goY(s9_Ki-w5*E&3JQ~1u75v!c=Y`EB6o((&b##H+W;J8 z=nEVzJv+w?hwNA`58NF#TH2UrOKtRm*Z?1Kkducncr;DLFC(2sFmrk01lE>p`!cvM zdt1MsCS4rp+GJEVQ1z_%V(D(ih906d=<&0B_g>p*y0bPNSa674!s+KO<2=!q&D#1E z+mVYZyhgX;zN7%)K@&e<8of-?=Cnn(|6X3}4+Lve5^_!(gXLFi3ufBPuem5beB=Cu zim?ojoFJb$qPmcQflh@+&)W+rh;mwp&Gl#hRmE=og4R33Zmw}K_Lt{~BJww-c?fZj zC8lO0+eEjLLT)$@nW`Q;#?KF3xg2A$O7yEiQQaCf7?OA^W4|XPA>lHdd80t35hNCB zp~{wsK1aMP#WA{&u5?%WHCp62cZgo~Bfc|gZrGDQ>^coZGh|Lm_|q9a-HbXMhUrvt zYKvM(Ls##xWIx)gGFqJb?UU3uT_CkI_jC?iF$2?B{mgf2>1s|7$-b6c@ej!-dx@C; z!a7m})8?bO$bR7NMj4U2J!n#B5;uH(eUP!5NyP`_6;Wg09Wi5?Pw;*=@@_P)o@hkZ z`4SSLF^&iBh9eGDO#k-$#m(LzcuUF_KzoHH;JhC%OngKmgD1L;irg8b?ck zDI@5Qr(4Knr!Z~0q4QO$WB9mHrXRbRXT z9itMFKwK$^sKV`A<_jt@^t8n^0GeG>=PTu?%tBX%Qs;m>^yyFhW$er2QRdl$iDNb4 zC=G;dfKwUc&wjQjr?X3^z9}W>{lKtzGOst^mOe8^SGJXpBU@9zc|~o%q8SoV-w-;- z*9g%&2xA?;o@cU%xa#U0pW4YkqU*ssVU4L!xLD3HiOH-slz^FNcU?ga?d15m;*dtn zl?YO!dbo&y0DqFscIZ|lCH2(HFLDv@n12&1Npy-ZrWHk9+xef-%FZo8=t*)D;=|R; z%DuXOgwPx4AexK-W81GG_Vp9&-y*za zf7aKJIidmiRuwH*v)%yUynlJRvwVR(L>I2~?x~LOBi?GSYy%;OBBlNR#?BWEN^oWyzoDzsR zzTV(sU;=l>Y{;6MvcgWF``8g5{NKZxeVeho!9Q;wrz*FJ$N@rlg&&7C4CF62(PL}_ z8IBGW!wQ$f%*J8#9Nk<~S#~c*?*fbOf055v1z;K0hZapN;gm-i=u|WqEL7DaQ^qXC zQ@}B7(P&68enu{C2TiGDoj1Bb2TphHZ%%ilmKQJ~R2~IyjdYfsFP&12)kOHeeiqLr zy20en?fm-GSpZ~OxATbvyOw9qMJ;=dOIhH|o2N+CD5O;j05t}AqJ3wFvDx!GZ91JP7&Mst}}yEgra5V*1?=2W7b)`W=n zG#(k{*}eC_gfNH=mMk?_<#f?L4wG^bur{V{_yf+XGL z7&8@3T<2_u%=sbV!BCU{5@NU{h-kK!VbgPpVpf=3ZB>R>ZC9Ix+}^Xs60MQ7jHa%Y zI)yW18ElF}Pb8Dh(a7Sv=E;0z zTEL~Z#r>f-C=-VVNN=@$Uo^d2Cnfud+>qOkc2r>0RC{=wlE`jd#86{0#^1!AgfYa_pwAy?5!>!kKlCN%`+?(VpPlLF%Ysqhf0 zJ-){|xRD}uT<=k7^YLhM>ZllTZb3BLDi4=WZu&sqpVf$dfAEkfO5*hbrKNY7e3KHP z7(&Cfqiljl#x;2@B8Ng3EOazA;B&P?Bbx*Ro=XJ9DKkj7?J%t&V18X4CaO?T0E>#j zz^S#` zn|=&ohrQJaaB*zsH{?`Nv0Tp@r*ZUbB**7a}oX?0}3n&B--#Y9ZbkE8XLsE zN0mYpu3vAKZE}PF)|;;`Q?E>1c34jIjv>=D14%c4pJ-Z%u~9y$wT~ifq8Io_1^ERY z_!3^SQYQxYyQpCU|3xDB&u;kMU=GNmeFaycT0{K`*qrFox{6 z0>R|>h3O;Hf>RgfDIyS`kyRn+tDWuh^> zTovd%T~sx|`2x;!4cxHL2Xa8P(eiF-tkTs@a9KaE)Du2LQPHJy+KP(fDiIZH&b%u) zl$vqxKAGzuz-?QK@pTlNv;$-k^%av&+uGsLlro~xL@|m7c15V~O<>yWz?ip0Sjkpn z*+@gd#P~GtWcKo$w0>q{x~4?xtFW2k8TXpb%fou&cxBv0FV*oIC^}5=g9M{0M%X*_w zWk>2#R^-K?Yu_AzXY@|m7mN?eNww5_;0RtFFoYLRs(hMUGJpYD!k#yF9OhxTC^4QOWy7bDtD;~9G?Y1K~`p^8XoUZp%T$cU$je=qDxKL z@9Vq{5vSY04!MrpGy?$U>_>g20&6e|Y8D)B0vIZ&UFJT_aA84ELQU28@IhY;@Fg%9 z&*+H<88vj0qaWQ9?uTjc?;oXRE21=~8NU6ZRg+JJ#lw%HvUt8d7|SUNordwzPxM!F zmcp`FMxc_nqTLy%Crd+b81my1Lt(hO)7JbfhxoiQD({Gtje@vHp-kQZzz_@X4c)<1 z#wcJnWdOAob&HDmPAssU%7i+00TnWxjU1*wWBy+AO^}wdyKg#ceEM16`3OU;P1^(+ zI>8$K+F5~W$3<`C!c&gHfo7TQH&AY<5L12Z@P<^)3&EW2i=j;5l<#a@<`ngslGluDj0)RqjFS3*GVZzH`(c-e$vwIe+ z(fit3L>i)DthKp&PwSNu8UgQJ(+JSzuztYFNnIN8K(EQCO=n|c`%HeVC1q0gGr^^3 z^y5RsJl{b0p+rXG&wptIrt6I-Ayf#HE4lq5hd74)h{G~x1RN=q2x@36e9hXcK_aM`^`==N_YHXPeJlIxGNE=?cyWp|N&5v9=QN5dzwpmc|v z&7+Oj%AluR9BwYe{2%o6J9}8nt9Qe zUtBhKIs#qZvvtT?$3^n2VG}dj{o?<)kS|8fAy4n(Z;b|7EE61S%PVr|GxoRZgcaYv zqKezSctxMS2Bd$Hm-u=Iqs7CkaLv3^Q0-B>2IHyf)E3q--Y6nw6yLc1bW@L-lOv?p z?N%8v$$3bTa`q_PIa(aQFwuaobeTn-yT8kV(NK*vWIXo4!Er|N5ibovFQG6rz}Vwm zs--`cAvf&Z!o(J zGFAodoiaB>j|#3AmFq#*Qaj(@DfrVL)^rgc@6LV&y_hqJM>V`2iEJ1B{sBES@t7q6 z41S_#9EY9<9GqR2=r~XwHsV?D`K;F?)urw=K1_UD4@#FVhV4RZ?friJLVn4YT>>aE zbh0#699-7YAf8+`zd%bcp3Z`~5FG2wLU*qnY6|s$30o9qU;^jk0u#6OZ3~t2N9~at zl}H|a$XIxsnzhe~l!&0 z2Buc)4FZme>6R-!_6lQq7F~2ZW{-klIBYDriMY)|bD(%(=ucVQ!$2zP)i|&{GFau~ z_B<$*2F%~f$CHF!tnn4~T`tBQ0dnA|DHlecIbCsf`tE@q2?u??BZt6vKdFJf+tM-T zXoM40};h>!U~y3bkxR@ghVoCh-O0mn-9d62Zc zWhxRnlqeJ@#|m_f<9_7}J>Lw|6-HIVyUYP_^}M$ffdwlhV2y}%w}6)QRyW2KO)G%H zVI5HTOkl-XXtL43yP5KD4W&mTkNDAFnSiVC3g0*((><9{Q)ITfq8wv$Rk60dkt+=t ztqHEEpok8?2}4gl!ma?~GBaPxsmJKf!Frt#Sv27GsQVma zH88RCb~knhEi*B3i9Rs{q{W$c6#B4lUqS#){J)uf1Y!5gfQ60M!}7b>T|FBzoRa!J z9d@0TYsZ`TTE{*6uU&_Nz%c7Dl2NpJ6`Z-?J|cC82N|c|IJZS}jWg;Qe|Uci#Sa_A z@Kt3d{^FUY|E_Go(DLshBEka`(wY@oaGNo!VQ+6A#z<6SHJY|eRG&iO`xiJMSwpBv zf!vG}zQGS?c{@hX%!)L7-|$ZudGerMYe@0(=Y9Chr|zHF)osYh9h)#dDK!4=U;MeH zmv*d$vB<+*G8PNIqLPHzH%kfbIS|?xwtEV1;_=ImzGzB~3kB(kM?B(oWP^nMd?y(U z_Eod0+kVM^!|7CA{IO7`&d(@nh~Jtwzbb6(!m6(XVL=cp9StqhcHzNE69}f7M)0hM zrYiE@?R!9hB0A4g;xHTklh=(6dkOFkgm^bt20KMbcThex{AVq;1>4H+&F7!yfd2R0 z(d21#9saY+um3l({v%z6ym2^Yg#Y3}k`bp2Jz^*7yjb*T^4|BJ0IeEVk_Tp%)mNS+ zQ@)2eGw5KeLR0%exc@M%wY7_Xtyk{qRB z^`e_W;Hf!sC(@2HDQQ&z-7YCK^U76OTcoolq5^>FK7 zs*6~^O{QTyvA;zwO9JRPVg8OWm{aj?YdkU~0WN*BURafWyHSI}$2mvUZJ`_CLvu>= z%(mG-4z|w`v^;UQzsNb5Q!2$V2pm6A%DJ`{#F})hZbPpXzX4$g`gR%!YHnVAE8Adp zvl#4%eo{4BPp60wM`e1xHc^(vp=?jtV2sdU#kLSx?B$TTJS~MP1ac?Ar2bQPXCiHx zX_5}qkX@_Vh3JJVvI^BghOx}$Sj^EeW1*(zOBT^+H=I|DT@EDH`o5USajJZ|8t+z_ z%@*cZBi7+(83xvVHRaSlO%Z*Kox>K-voO`?NV+2VfrNZVsXD8O=^Acd?#Z(Ed8l!_+>kkLAGmMoE(gOo$W=Jom1xg((SE>Y z0~li_WbZ4@SSHzJ{UJiFEMp*RG6z(BilMz^azM~>IPJ;DveprTq#cj`L)_HPM^3(M zv_>07WOW-`LOGOTWnhn>OG7pdQ{%&+QO-bMBFv>snye|c?-~uCBg|Dd3tB?$#(&3I zfW$Qd5-bcVX3Pfv0XWWCvJ{xansJ4^raTs(gkt@hdqLx75iOaURZ!_>cVreVpv4zd zW|=4MCqai_E18VTHQW|C{){Q^&=?{{#f|UL3ENog& zo;{Qf@^g6NKK&`{RZHn0mYt=yUhRlk)@^%#%1xr+K=fn1PJlE*Bg1J$FZRLW1Ne@F zWe9QxgUO!i{ZY2h}5~*_3em;Y%Ii(0j1I&PKvKw|aJ4Oe_8cF9g%)Ho-bB zR;l_Ey#^#H+;DnS>$HPoU4=Xmi!$LTlNl(cpV|E_v(B=hM+X*A)!>PSvq7K_LYSFo z2IqqPv~=c6(Z`ds^iD(j=wliky{~pOU+mz(c(>zQq5u(+2$#-T(~FKx)1u5g?^&6l!;Qq)pmfwSg&>4NV*V=ruP|fRqZAm?zlfvH@nJ zAb{FdC`!38#Pk@a=*nf}pv6pcKRta3>{xG`)&-k9ja)rhO6E?X7;{8k&D^(bzDyuG z5fcJmH*2S}eYa6>Q}`~&#=`ptut{?3J}7Mn=jMCDrdf7N`Pzv}q2*yx^f1rG^03Xf z0X|j95E`_b$~X_vY*chC@u*|(heSJL6IDF5p3{mN8dBDF$2PkR;n;<|9C}T)-WZQ5 zZ*uz@d=4UA7#WHy?4n7yVI@1r9`n6|{l{2&Yz9l9QGpBbu#^+tL4AF3ry?XIJ%}&~)J#1n46&i&a>IVN!sA654d_dpn++_h{~r%b)58V z+&>(g(>{^%;`n<}@(6n>g{)N30{DftJAAZi)~;RtC~wa*;Fs41paVI5PBYLX)Zr5O zf~{J}d9S^fe@1^k1HUwjbQs3x{ zb}kD3N#;N{5+0Q=OvOSzB9mN1#vK=k{MXVxsT)BA=uk|yTUgJ4UUQ~YMlD^}e*|X> z*kM8n9vR2>EE5!rfN(%*I--Zk3f18pwdlXv=FMz&D=t;z&kh8l5vl94eAmZH{B#Kb z<(*cuGR2vyd~MP7B|t(QQHPxDCU58^ZGAW^WO=dRLYGHN=3J7fPIj-cg9$lH^1ZeU zcX_jO=vZ@+cAEgW^}M`Zh|67<^KqUbmu`1VeBf>LbYH%hN`hRSq@JF@F5Ua?TcoqR z)6Zm7-$H1KElo@hP}HLJWc1@wlMbkF%lpLLpRrbW&*nPCPix106V8$*egWq}yfk zYjXspO&J$J=XFt6fywIhE~}~y26p-Avc^Rsk7^YnPissD_01?wG`*p^dF{7w<@m2iarG{3J5Jt*(#3WHRcPNO^O6$iQLbg{QRhpUB0UTD0{5_>-|-}4j7^!QZQ4* zY+TDQOX%}EwopVM*tPM!t3`_F-+^^)IE50>C$E6U+xS@TFyGv;uB;w;>eSWakbmr)^Ri$pH*~AV^ z`PZPA3`Ax~O*evLV8m?2Ow6A*xQ1Ws$MogQX2i#}duP{!-#|pdH(r4nrb2oeE|ygv z0rf6prr0N*3Zy43J1g`WbsWb;6K@wc1S8+U9YvYaEw zlT6IK!uO!bl%(ff(`r4V2Ds)kT$+RGl}Gx@qb;j3hqhn{tK z*c?~Grx3MduQLDd@JM$JUFS#Nmp{uA|H2oyTQmN50x{|`$Os#ADIafWJ1?$YGDkMMPnA@%w1)exS4>#|URAtbRv-;7q4Z?e3v&5OM5yz~MA zSIpx+lsq)PMtDsjP5{eF8BjJHxa>OsOs@m zDLRuy1K6F<*{tBjr*BPu^LM}!Y5mWq=D=;2V-H5tKn~d<4-_?55)YW%C+Dvn=KsO@0>o>I2~vZhh7YIHK8$f+7#lm1E)ZLAr8@bn5dsO&jx_-$ zWYs|^Y9;c$cE^Zcf%RpumN3jzyF6x0N56IKw6~^~)lMhxc$@L|sYd zf7C00Ps$a!HYr`7u~}MdKMjawt79QiuTR8b32ov){*2R)oUQg%5oR_HS~d>kV&;9I zovi|Gl6BEuDLx&KvO672uya-&@9TH0EL0h|V2j))p#NA3^X>eWMF9UzGn;yi*?P|L zqB0j@5xRH~Kpo^Iv5Bb}X~pHAT2h6K(_S>W@%C3F;O*t!ba5N8rVbyoykH{CWwub+ zxvj8p0BGSReP-E8{5vpX?n?Sg`gpBF>ZmdA9vmha?^)kdTFv;)=SfvU#d3Ch13e77 zm8cIYp;t)zh#X7&=2h(vtQcD^Xa9~Ig*HeU3Lw``hV4to#6-EjB3ylZ;z9rVVZT`U z*L!Zbt33f|^g;S6dr$+JY}t|;Tnd5-(hJMb*w`fUp2C~qd0=~;&+zst^-G`9;A~aq zW@kRq+&$qOFHQZVCSvVfNHbdM=GNgW(IWETIz$mnJzHAl zI-5NyCz7lx0gxYMAMumdVHXkKzxyECU<-#tEB;>Tls-7o%jAaa-XT>O#d#akp&KOa zVVmpF_1;Xf{-^Um=9eZfgLu%3Osvyp%hdZPq;i@CvuGfPb4SOL^PgW!l_uI@5gL_7 z!rYF;lfR|rHY4l!l@tUA%iG}9J;K0ka(R3xWptpU_rpzbzM_w8RJ;I%nIyE{Z8Xj; zi)8QYKT_EPzj6IO_s)wLkMPKo44i0T5PbZa9UoS{8h}($;(~L-cRFB>KtGXKUQD>P zQV!_e7Urlh?5nHG@RjqpGK?7TC7I2ymda;5JHTqOWLf2^) z&w9an?O^NmuvgI~l@|y>zicyc#rw6ss8k*lA$jFu9V#Ie&j18$pNzRW;Ubx#U|Kd1Zc{KGd zc0WV>r=c3|jN8!=b&5_y>!f6UF;#bmyMRHJ8H|bhD9ed;=c&&8tepw;Vmx#d>r^Ej zPb~~OpvsSOU|w_nr>>6I0=8C_4^|n6e@b+bybdb&<4N&RZ*m zXnYqiso>uG8ZWyWLT8PfLhpVs>$B|6sA8!yJDICOkJa+vYOmroAT}6sX8FQ^t+Wsc ztC#6_TFh<+HNO0AuRHmzZFy&&#tn|_Lkqa=KB;Ie9D!24YjDBBTy0zjOhsmvqHV){ixLl@J7cd$bs2ENE}<0R>U~`G*u8W zkp5E5+S4EZ3+N57AOgtqO^%5O;X`MlIiGNd_O8yc6fwFr(9A~U^}fA3fYVdG-z2Z0 z6r-rw8|6stJ5_#BG(U2C^kb*8b8+br^>aa}`->~IFl8er6i@+Yy{@eI-D&;q!M7*o zFE1vyc368fv&EcZ7`P>$lw2a<;eeoG%&ozwHqDOm#X}?{@;9I$!T}*=jvY_U1cAw} z_BT{O&Tud;tD0P>qp<=8^(a!!fkDC}=Vx-V{r2D8mSlTdu=9&e)_`Th>60nj9d6+V z_BM3meMfAB*~YlcK;A{8BHZ%ieZfVCqS+=x?9{y zi!7Cei|W|Mzg4p*(yhLXK%s>cm*`O@rV6Nnru;_s6XxF-A6xhOkE_;90O(XX}FMGK*(af&lh5!rOYxHHoH%4cYI9oBn z+AeVDWTqT$g!If4JFtM$t=VbD#~=~6npM}o%gy2(5P+6~s%9qnQ(#rr%1s4t+@1cc zUMFu(J0X1!eSMJNSs;5dn|M}g>VuAnuC-#?oW?7cP{5zriLBH5@-6!47@pF-gQjlE6a~$w} z)OuJY?rmi5wlse2^wS*xfQuzBEur=H%pbF6bn?tOl18mgSDoycogYJHy*dYz}dFM6%m159s{LNT6yFc zC#Ax$FwNi9v?f@Yt2+DjE!FCmM_9m9?RPk46Y-5wNgd7MT~TCL^ys0Vwh8Ix_3<2yN5!<9y@ULkV|w!lLz@~fLx|#mHSeR z*FZHkH;4L9;!z$_G2I_dI|bWTQ7SkBM=A>aaqno^U39S+5K|L=n52)D2OEkM8gUj> z40q@M<2e2PRcW>5V;Vxrm(whfiZt#OvxaGvHV;sS$jk2gG7}xA$Vs}>zfm7nTid%E zgJ;2qfjuK;J0f?stl0}woTZGl9Z(FR=Bm-xewjZIj0YhM?w`Xq9J_+V<9 z2JvZ{QJeSj=9I=tLjbY38-JH$U(idL$!b;b12Z#XJ#+Y7=?T8P_%J-D?(MmIiP1Xc zW)c0iE@*s4TbsV>SAD>}^GMyQ_xTFyi9K?;tP*ThXP4=+>6q!fY3Z;~?oA&IH%JCS zs4n!RpJ{C^Z-w=1WD11(SAiwk?xRE9Nw%|p?ItJ7^}&|R#n}$9$mcpfV4m+-FNcFt#3cxDFpqTm@{1zEwujb=1hKnx3gF` zAK5uj1-npQ6js0!=wId-67;F)4xPpcKoZ^$N{Q)308Z15C$OiH+ei;IogkQ!|qH)ap5U~nV*TI z?)G68oQxE~XX=q@)yr}O@;k>^s$iy)SG$VgwNG%P78U|pu|ZyP=q2roDi@-5HXQ<1 zHtg9Ab;J|;HWwA&WZ;?1G~7CxfSOV2O83{ed2G_R^*A1R!h@fWr49v|v5KWhCRmy} z)W{{vAWaN(Oz(b%y0;qL%PD1xV)fy0t8`r^+Hm?wpj*6BT{v?oDM8{xw#z9=; z=p!6IO~b-O)gfd60pW7OT^UoHqrht4YC3G!QVt>F7pe&hS^B2qmcAS*z-kQ#3*CI4 zy){7>q927gnDaK5Lp2mMhwaJ{=FjPIg|`xttxx2jdxyUYc|L|`gWMAo8QaF!huY$-mK z*i@!4EkMmx41LXgbhDW6SN`)Off=-1ugoIB0u(18!?4$mq9gt)uS67Og!(VEk32;> z5s6b}po~?Qf{mC)`W_2&dnL#f=OVBIpulR|qXl4K{WW2l_{V9{<^wR14J)=VP8vJiJ0o3vG(`ns<2+05=O=B$k z^@{pw&qYVyNIS}l7oGt$>%`vaKesXHSy}msRGiUXtat6KXp*%qgbS>{TDqXI5ScDuIxdwz63eN_~nMf@1()P$?4m2Xqs#(OU@Mg0@YUIquJ9md1&KSTJd^y zA;yj5?f9YQu|XxP{MOiXSe8IiHM=*@Y9!bk(+SL;QLiYGxL(U-&tDa_a(riIP$#34RY#KcUxFuQut zdG9=JpOy~`{>i~bVUc~ZMaG7i`_ZKb#lD6UG-fVtp8jcHf9nF(?;t$_3xg%6k`o_m zmGX)6{riJMYeYSe?t~?n;&zj&x#6EQ#N|P{llq&o{xRWzXY;tM+lf^;7~na@^^dxq zb(uX32ytv!|Eq_il4JDsh9A16`w{p>vApqjU-sJr*VBWT>9tNFr9vN-&I;pc6Jr5> zZaxl+gkOD@##?fH!LD{)dFB3!{_lr-Uj>jpY+`MQy?p`FiOJeHC*V03?~>^=Ek6_asnOnBp03fpan9Fmp5JVwtZ<9NAepnVNH;p}X8QF?6QhQCYj@ zyJ7WgIEamI^oH>e2?1Fmyc+1L-!N_&gWhJP~a7)HPi4Txt z!f#_e0IT29pAS6 zv_%2#De+Gahk{blBcVi?#e9T}QfEVfsi>VKvIxlMQy*~#*{Wy3=Rip(&ykt!Uo`GCQ#L~oB$ict|p1}$V zk9N15M#HG9<9)>E&G zvY`4+xHLN@;){0lN>1Fx_3?ef0v-$zf3C=rV%bP{Y|Qn3QPmFltf<4rkfjpzN1l-I z*Q>HfmarQhcMbc`w3%~}HqJ5!SLy}Qs|4@Gb)V&RpH0kUo*agw`)5rPPm9sLv$nS# zSoAxh)Vg&mG078<7Q0%LH+XuO2>T8PDJ@E0`1=-iAao`+O&hJK+$WT)Sw5Rb0RC8u z^&N38{)wt~rPAbOE?-`7lDJzt`d!RWzS9%VUeHZNukVhO)R9sKxeMDKa*T$7y0(2& z`LIl+5|t%!VeZrE%ULq)S9ymo_R`O_WaZy6B9tTh)m_j?291g!VR-uycaipKwmuzM zcj9?*Q|N~9#>N`v?+jXRi>&c$04JT_?+jGgd_KMqJRK~imS2Y^KGwgiP`=&QXIC0q zGj(<@{O72YVSjuaHwgUBW#2v-4AHf@vEIu-z0O<;#zChPs^BYeH8^Sv-=Aa!S4^z$d5lN5Y3jD5= zX@UP*Du4Y$g(EPWVsE}Jsi2JiU4h%wj-2UqF^t4KPEoh&%+k1OO26($+?n8Pnv^(= zUPvV_PnnOm55*`D4bY``;lRhDAO)zsuUmB~j$GGrx!-tK6EIEB2IUm$MW* zu!|PfX=x9K4`+u{obRszUB(Dm#THFi=ZQ&%OS!ZdFmivWG?~3qrCd`QkeA|YRZ#N- zW-+jWH3%-u1t9L-PRH+Rjp-xTeP@mUS^{krk-VmS)6UE&%oU_nb|Su^?-A8d!=t~! ztLo%&cmfhe+(#>Dn_@nNS^>89ReGpy_<)wZ`RsKaROpuCh}}5G3wbrUCCZj zKR`s9iJL^-MPLLWtyDw^fvj+wG~6;uMcVIV^)EVK%Pu58s<2*Z=f`jupwCQ&g*oDK zaUjc^PT=Ro0E|NO0Cmj^W4t8yvg@#RUAx;V z8mIexeVxT>*z_+G^6?p7*|a$nbSFsNpOIRCB{}nnf`X*d%hd zLkP{>EFa{lT@(C)8Ic4iuz+q+02OdyOl}eE+}r2LG<{JeexQN^jPWj1SqLok(T2@7s?u zxgR7IORvmnSPG;jZqH^_n|iJV0H2MdI=|Se3SWhx@A+bMNa0}KZ<=pVhMX>7m<5*%QCb9%a@5v|{~6{f?r!rW~> zIaeDQPZsAM7whZG5g@x~h1N5|b@&trL zdDYc858)3(Gr%g z`$;9|q^G6OdyL`IeD(*PG|Y9`zZWpa}@bWjwPCm-1yGrdVxv!>=XL5p56AV|mjr36?*9gyFNnYMXTBTqOgj+IHcWe>^jVOXI@xwOxut&u-^T#zoKPb{b;0HEh0Qj z)mx{*<;ed^T4qr6F#nk6vp@2n-X^GOn2m3uLXh%m&oo=1Y-09$oWoLh6e(JyR5+xt z&L@(oXf+Sf_~dP7p-i@*O`mGsgJwCCS~gTqA;SZlne?mRVEGpLBBLG=83DuOImoG+ zAb(dJQRnr*a(8#vPl2FbSatdgAtb=_2Q*x7UJ)Ix&}2>W$5h!PMzq%@7_IwPY%{&PGJtJO0)6fS8DO&*K3hi;z!h* zF!^ds_(glp1Dw%R8e@|QFZ(*FLwfpIzGFw?c=z{FY~Ry?%PnWoHPDLH^X|d&h0AcI zp%0gudodF0hA-8Hg|qW<|GEWOy|w~NS9vjiu@^xf`?ufcWWl~sUl+!i^TXJ?Zvfj4O9)YO>wOE4?QQl|Tk^1K7amfyS^Z`MsSp0~BNp}n;o zAAR%@e*3%Ma*fo6it-99U%moA{NWF<`SH!j4rL=03Xv9~gHs8$!|jX-Ro|gUMnPP3 zNpaw?>oFkbJjY=_^l;rquhI9KZfH5dq%_GWRZkED11WsIwE^3Ve$ag|^4}STpWB72}B^2ay4ZwBaPhYFWn?J6_%o#zxACm0vO3`i9tDJe4 zGdRnYW%4xr$Og2oqTNbc-%40_k*2THI=ke8q5 zypPiTH*+1CdH;2j){ar7>%P{#&D*;2`#zdXx=cm`8`ip-(=|6-yLt^*X?=YE=j3Fg zps;}Js}kho<~U=LW6j3VoGu%S#i0HF&Ye5)i(mW#-96p-$DjQSFTe5%f?Pw&8si?{ z^04F9x=yIO`qwiJC{5mew)0rmhSuP958!D)$x`O-bu-&o_p+L3ZWT}x6>R^o?%hk7 zyT9bNZKu>0ocK-K+re(m_$4Te^Lp7S=l&wsvlcFyN2ES z2q;|`K+8Y^&u^;56OS#xs+9q(UKuo-Dn>Mm`WWkG7xyY!l8fpD7yMrC#AQ`ZZOYB& z%Ph7<6lW>Vr`#k8ju>WHhG^p^z6Szba^Ot`xcK5iUEoO~NRTIp*iaNBLnDY0yoh^) zIDer7U+y@M^V|@o67!LaS0Wy1p>0Lya4Fg%1nRh9&nI}6BG@vJEW%KVz^%q4b514& z$V3S$c@XlGmfQ@)n66o}dq!CPI5(g`KpP0I?!7)g$_UVuCcnUgvI;LMD!l}+VE`lU-;L3xEIS)q_>cw!k+NAQCdV|{qUvYH@H$O13m^$h zasx^pwwH%}2&D6fML#n(%yW6LodphQ->1!)_V5-gQW)OLF@6lL z=b2%2uS6BbF}hIN=7E!+XeIj4$~A^@#sDR@;m{Dlq%QOjWhp5s!>p<~97{RuYf}Z3 zRMIh{T(0*Sd*;5nEkNl+9LH(5?P$WsdmE9J>_t`H05+_yz;n+p$GinqXlQl-rM0-)PPuY z1l6-^Fk{9H112dAQ$^Ed(tXF(aHcQ0?zQOq7MnF#=2jN_S@`7@fzaP<$KKy3>Ht6o@v3Ak%=-O^9SWoONw* zGXZH;LZfE_lp@@XOmiq%3f+BfW*h5X_I3d!QNZ0#?mmiqH%jboSGC7Y4TG4rzfC|% z>DzqFS}&cYhkeN`9+f`Bh^I%3+(;xr5F>%#zt@YmX|J|N&_5i-f=VC1v}a@e+B~dW zQ-}pi_?3h}imZpofi}I7VL!nOKTez&z_!m@vG-6rE;Mpu7LMUZPc6cW&o9EFg#lx; z2s+3JNOA*8^3!rRsq&dC-8p5{!av9jl(?4kTtUQf;Cx{gm^4WL80(SXA~{F^r-081 zaxq{co=gT5Tnl$%%*Y=m4&vE&Froe|8+^P`-b#o|Ig3Jb`!LvST4D}kKs z6c_eheoZEgMQ2*>iOphPpo{ho1%*BXDi!AIc>>{h5-rzKXlYJ4+(+a<8X?Ke(GJ+#5v%it-D{c~o9N za3~*H1gd=AII{RKHpD5Emou)nbk@ z_XJ$XI6=#HAs3dH>3W1l7$a9eiUm`2Z(7^9y7mxA@+7lKp){bxAnC5aFn7SH8`5SD zMO$LW-|1_n*y-@5B%^`S<#MVsI<7`Lt~-u0GZj)CMqmbJd^)J1lMtU@H%}N2CBmgc zeFO#j2`=;+TUu65ZWVGU@rz~RCV-LyQ)v6E!Z=0DEUuIJ_`kObC`HJjbduajr%uN4 z#jX~7y1xa3;dX>l9oV$046nbo8cUW{qp2l{EA?T1QLV#{{q>_9N-sW1KC{0(pb1UM%Nyd54&;>@Wyc5WNNSBD00s=gIGoJC1b?Xc=z$iSg2?rPMzBr=T7P-0iqI7+Zx^{zGLW>k+?#m`UTkDu3ZzRp8IZZ6(5sPnD7njQ)3UDn+1GXL z9;5DSo4(E4y4L^u=cTJ20Q$O8vj?u+xCjO(<$RoONw*4O}~T^=ukY zvXr@d-OM)Dz3eEUL^k!Nrm2a%St{5*VqNP$?S69Me+Bzv-6~S9CEya&sTY{SE0A^SF2}r0M z%$I#SPWC8?yk#13DG3PCBUx>rLX_|Faj}(P9L4o zZpe@3s8Am*_$j`|ybJlsHn6I`-(VaUFC=l{LW-=<-0(Fe zFfhbT>j=T5aEc(E2ZIETvbYiUCHm1D=I%q598rXt*d9>?JW&H6`3ZgnNw*w=czL-2 zR8tdM;u!6kujm@+I!>4A15u{84e|iPRg~$aP=sv?42+K#S90LO`G|c ztoUPwi;5>d<7oqZJ??1wZa_&%Gc!9^I2=lZONY8?d(hoEfG*nd@^XR`1eEf#*^k7L zqYdKtB5xY;vZA%6wyloiJ9&L>6;R?gEu1--z**Xz`#Q1xKqp%Ju96$35f9#5iogHK zI;>b(gXXp*>KY>iGU~8xUmb^6A1y`R9(MqxSu@MfNl{J#O7DGe8lN8?1C-wU5doz) z7a*4)Zj@tCeKM2=l#)jDm457Nf@ncbj1+BzV<$Y6z*h(Q@$P#a*nN=Ta&J4i3y1N4 z{ljwn?Ekozc_k>eo50ayy*PBd6IXhM%{Z?hu=>KoWq9nN5-eQi$D$=X zHvI7tbP)HY`o6>@4Tn-w1EK_sXOTmxa>h)~hmQCjE0*q`V|~W9=4c->9ZhLDAd=$} zaAU{!lWVfQy`AE2d$4ccUK~DrnDz*2=FG;NxwG-)6HnrW7hb}=dGk3xv43gor}MP= zd|j?BuTAf|ccdW>pSU}&0;c_=L@~AY-M42SKHd5$jvYUahQ@k|h~;9-mMwVnu}2NJ z(t?Ex4A34Y*e)vTL&bIZ*vzNks?A3WFi!YUK#7Gm%$jUZ11K@9<`Xk!2`CAC7Z(HF7BB_2XB+Jcai@ujjm-W9$#N z%*RUvl@`p)#td?k(wjycNdl8JPiX#ih&UxcNzpCMbv>DxYPiYL_?|qoeckpw-OHM} zgkx-~97>twGV#;nJ@eVuac|45wA|P3wC{8o+CPaqQxPX*+2%-LMHczIS=0}Td`K$P%l|)qpDv3k_ zlq8~O0VNMX6fe0nB(fJFc+}tRMQ3Xe-5msH`q~I~^`XC~j9g0Gpfk6q1Nrh#*%f#coQo_~kwql{0eJqUW)JqGNBpz5&Zu%taf=Km$1gEufU7SX?~Oi`Sl7 zi2wZeYf(Lmj5PJN$PK^xd6%_hB^KQdIk6l z<4+&-Vb75cwDw*_(A$sy^Y8A#fBDbLNMmr$0Cs=TgROt=z{zX<=!sFJm3#U7IS;N` zo`=UCD>c^Z=NuS_a(qyC6A_`lZXd2Sq;Td;6kqP^!M@`?E(+{wRQsMW&(lBVUBYnAGaH!T^xy#M>gvhWbIx!oZT<99);EYOaw|UZ_!H!K zq3GK^_ZVG`*^+Iw`MDG4^|k_~LO> z*C#0M_V6Q*P@mFr_Pga27gpF9%S%8_AX&y(xxS2+PV%)GIw35eq!1#%l5vL^1(Y~| z%(TfcW(MRt*S_<-M*r9KfRc29MahY}|0{AQ(eB!phfhzELrI*Q1eCU{2;j|E{K(Ji z!>@mN0`G6Tg6!OU6z1mPrKjfM`Df>2VQn^M@%=+Qjm8-ZnpYe^$>CI*GN7a+tZ|dW z`dN3fXEw~VJ1zz6*i;7+$T$6c7Xj&o zgDb52WvFX?rMVrY+%`$2VXgI>cE4E)*vZA_s(V=jC~@=GCJvn5L7WY!vN3>CfsilD^s+17ge<+C~r#QfCp zlZUlSOYrQIWmGO(z)c=O66(?shmw~ZK^9OFm{ea+WxPkYf!x)OBWF9%OnomD2pI*G z=8!|_IzWlbTLD9|+!K!OpW+ilAA)RaU=#oz{=#E zB(OyhC@E(J0WE4pcPv38A5owM6$Ru1E5Onv0o-%17sbU6%_JI_#m$p+JY^Ln5h_ff zh&qu9X>+LH$>IERqbE+Cq;G|-LaTRzHn^Hw)KHp7M0Mv~q0rnTnUK16j5hL$t4)lI z?v3At!@5dz5UCZ%T+;j-%J*c#-&-GFN+PmxO z;Z#i|rE%taT`7zXU+AIiS8s1GhQri}MO!MR+%sl7I+TnK7HwMD9%=~n(d#Oulw_2+ zwZ>ygKeq!YojaePUa~m$?uu|j97S{YS@aGb#rh>h+zfBx_^2g!P!dh8V}Md5)=RFP z9=yI~5&rQX*OHr&fKr>p=elm>P@=fon{Sari6W*EawV#|Hv&pd^#~hq9`X}Rq6jJV z9es6h1Rs7pjNQk((cD|dvC)Npd}}HG;UAW8O!$o5`aw7T{g-X{>OwDCIUdEKID=e8 zi>g9+>y3GM^Ue841^SQ-^i%9Di}Oc5lCdD7!(MU}rtrny5$rw?!G&{e6n|^OqS8vt znOTX)9?8bD&j%>FMn&OfC~-W9lh031MJc%tNgti&42}!6B~34tt6sa>L?FZhN;Ay7 zsHtGosNbrey1MFk{nqWL>mf(4PdY+GA9e)HSkKst!j-=x%4fYKXpyn%J=)^YBy zHhPFM^BFAzFRts;?gvx2R=TpzxO3`$(`f1LZ1f^=oSZ#-28RwEB4^KDii>@T0V*SU zThf*3)dYXXJ8$Xa9 zuU`E6*T?Yj_Dcxm7E+wK5YIm`56?b54~rM(U^d^?)ZH8Zf;EYA~40a&dp6;GWbtq|_FOxamZfWe?P>P#-n6aM@=Dv2vywhcH z=k;y7wluNsRLf_>PXkI*rP$=*rU9kN=`*^hwH?m}cTXs~p5{=pl(~D|%r@4&tO1m` z2)fxRZxeASx%d085iUkfmedYE|bIC?S`ek`2h zttWO9cil7HWJb%pzac`}BQyKaa86FPYMFELXt3M776AAr<)+A&=xi0)n<8D;7PgQ|&|2$vb9X#INwG$0!m>IiRMC@tjJl&?0VTts zw67nnU6;{6cpmpHE+(L~fg*2n(M`QW*V@DQVh2Uu_SPG)HyY`|kDg8gO5{*#Z=nvQ zlLVALJdJHfTq17*lzy59lq9~yYFUw33J)22*iIpCAD#Hv-bw)LY8;0NC~eyjCg|OV z&cSA6kwfY4UY&>6e=?syo!889r;moQf5#vW9_hm23+-s?8$v}e3p0yzuyI`#Hf*TE zyrm8R7ooSrp9|C`g{6Z0w+$#aDa8+b!>pZHRlI{w-2q$#nVsbW65Hk zib%jWCy(vy<6PvUh$sOizcl!hOHXsM0WdiCUk51h)HTDQ#QKudqkTmE-?WFT-;cJB z8p~y@zg&%H0UP49?CI^n#~*!+Pd@&b?}1Cku3ELqh`nvtumLMqu4JF9He|JFxRN!O z_pWV-xzE>Z|HT$!NKw8jl63Fy^0O47CAdBXy5b{C)|kVhZ^y>!Z3 zgdcd0pXkGhlYRL73oqV3$bO;z#Zx|?rpTK(lnM%N+lQ@tCrIlaqwZ^Wp6=^AQHF1O znxk!b3k9{b{F?wu-@$P^4Jh5D^Vtq(T^n43*A8Gko7SOZDRcL_nQg3l*-=1giaL~R zzp#|Zytn?-?zfZzTwIv8*TR!V?SCsGZ)$JnqpA{OeAAC&+^kSkO{-geoi&^$+`L2x zYMi?e!lOIA7mR4ulSFdct_)rF-zotINg(lvpGc%`A5fu$2CCOD|*M-0;M> z*%8x47WI7y6cLk5czA?mZNkO#O}KQb0+&u#5)_m2U5*uss3k}Gi5U$stfQw$+*bW@ z){~2N*+8n70&QK~2vQuzSB_#T4qBAkk2(4M$S>)ovfo}DYYX96M>b~9or~2g7P6`Z zxJpIBbxk?}kH?F55?RVBB4+`0O0l#OI0}-~vN}6Qs-;8JYm`HfDnK1i5h~%0#t14A zNE#;BlhJ*{`bAh~?yVg{@SZzUikpp~AjplTIFWoI1_?$I>dI#q7I~-Y$*XJt&a31eY{Z5|rTFoy>#%B74f=QhKuaeN5c#4GpYN)tjwo_q4UYjz zQp(-l>~JXk>0<&)M_qu@kJB7V5_uD##8QMfKZxtZ8A|eDxzw*ELPqYk`UdKCIv>N) zBO}KJy}=Yeog@A0x2cK~cT>`V>C-OB^3;j}w6IM)z zryj1L_*)JZE%q@#(vM)0tS`XwbDRsTl{J_$=YEO2HCqlPwt3}DawsucdgwY$%6rom zYL2vV+Q#19=<2z#q>_hp(Rxl`R7Kuwd`rE|d+Yyo zxwhO&&tBU+t^0N5b+@Kt=`xk_+pyOCMgb)|Uem5E!*`(_rvas#^gi3z*0sUa__EgD zioAXC#TWSb&wp+vrhoqDekE$rXZwFA~qQn`?X;8_$H29;%r4&qSkt>u&fDpgl4^vd**ohcVX^Ua|7iX|_ z*BPEfHUsnLEXKzBO7YZF4xr=@@VI+@D5cHPuEuO@d^ks)DTlv`Q!pfSUU=n?TCfC5zp#I%Ww&<(N@l!iTU%ZDQ;AN zvlj!nz>VpZ)&VN?CcBb9ms~&QGcfaF);ty(vLcPKJV6a%YGR5|?-5H!Kc0t2K#P{a z#5tr>??Sm$*3D$Hsc%W#LxqKLeu1X04{k0J2`SblP{atu#XO;{suVM;@=#slF(*!m zdrQj7x!2%^l;50LmjK&_UNjDEbtPl;Pq7@r9jHEpPo1_O8*th=1634pf0$&FxNgo(N zrSggjDow62fRaE{z8(lBkvbaF6B;FK?N}gpcH@!qW`L6AcrbGc*A>#ocIje*isj?@ za!&`g@9RKIdlN-F8?bJ1Dc*Q_Jyx!oi$N--ZX=+yZCf2a-AN9m;a&pUEB@+hJv-C`U993xWNpB5=HJz4#hV6*|02zp|<}DUqpi=K029!)sAOWM% z2*ngH-~#Pdp8B?R>t8rm^OU-oRXpi!BVK&zMXXt~#?)W_#<0VTu1}bTT|YVxZ|zs< zxXo138qHhpJKC1!7Btj1;7f|Tz4zXG(1~?(=hP4gTa0I(c@EEPd6x4(+bTqkQ}!91 zawjvDyxe6oamE=-?l1zBh#}FiUb+xiB*%D(aLhLiC`qi&z)cJ=GQu~+kQZ0@o@uC0 z;KM&h@gF-0D8(6>K-d%a`UxlnP*fy9=?wm~y@BtH5D!(zc8R>X0VQV~IAh;kLKRNd z8qKb0Kex9junjYbJJoQLB=LQEq`qtW-Dp477-B!ZTL2|nezlwX`uo(5nRU&a$1G?{w)C|l}qLLF0|t`pycjl<6PSgXWfY!eHu_2hj@3Hmu+KPY~9OF14@=6-yheu zy=tuXp9+VP37cM+XpQH#IzC>aUIsYOidt6$l!hq6wRc|(`@V`{|NgVsedG-F>^OkZ zLz~L*{Bv1Yv4UUC)eo6sz(+0@S_>$hqRyiId%0Po$lI~Aov3T;VW@r-<;L;+mRdab zOfA25d${=`fI`s2$yu9UT}kv#sd7n8#6?Ux2B+fV0qR8R>x)whPZ~;2~S??Dx&gh+WD39cpBSW zESej{qFRckRr#pkIKU&#hY@b5M}Ko8u9B1BTBMr*PYtrNYpACtkD^5(G`HkY*?0lY zTnjKvlscIR%vlZAEV3~ygZYvyG{r2i?P6YH2Q>7{^F~nQk5J5xr>k)jtW)4-&83K3 zHBW>q@lfQ3wjzb%GU`zxx5F?uw=!Zl3J@&{X7QxCJiif{5qE@h+LVs~lCv0yH9$ju>sotX-tl%y^gv0X@4QH-LS^;hDkBY^V-0i_+g+i|t6 zo(kqKW7VQEyh@R`m8<3vC{CfXD@vVhb@=la^#qT532Kb#P^zvZpws}IAfWW_)-%{~ zs=)wC)uq{^fKq+|0W6L~^`!vEl9wo{9dX*AtKWJ#zsZVg>hRGRPk9@{{sVnD-x?)1 zA(hzkbi-GkPvXT_lPDtxplqDttWu!g*fc^;kqC|-iyGZa2O2r9$aScL0A5%RY~JkQ zyjXmma(qe&pb%~*!PQEoqX2U z*GpYp{dnh{xAFGdZyU}y1zo>>J#{I)Za9^Sii;_3OZ{=_eqz#KA5x+R<7#TPv|+9LjRHz4 zqQ>lZaNJGO)n;y%>I#i zZvsvKe5)y7+g^pdB|u4wR&6X8&us-JaSLXA1q`IP!qq8ny*x?m^Ur&+ZF?_HooU6P zi>;_Gt-#_1wRmVFm2y8D;^}45?ZMQzK=tv9s#jlCxhNMbag^e2dvg_5INm{S zg%OnG7x46(Y^o(0Kq@$Z>Y1}KtEvVwXHXx?44+X>Ev}#xPkQUCuSZu?6B_$_QO^^# z3UaEsNu14ka+69Ru9do)&Ri+S`Mx~#QxUM)?RjI=LlmQ)Byk>rdYX7rT!I2`tdk-9 zIBWAIhcK%+h*{+nshdM(*{taxGP}B z7}G@Vibir*>?D}<<(_ux4ZDK2?n_u9KQGu}lyX-QP-?DA5zOhqpFTT_od!_KMs=A0rCOtuJHL?UJEj389k;Hd?HvtDs)z%G z>f}Ib8N=z*cUc`2oE0!Y~1)FiOkI3Fek_Xj7kAB+l|B z(ZbUf&r%=Kwyiw9?dUK%2z(*hi?s^~w5$U4^HgBN{Z$0{f}}^7^G*^$o{*ME_;KQB z3a5?&yAL+u%fpQbNBN9mw)f5{#v_}mcyeYj7B2IldcJ^P3n)3DuW$faiM+LNUed{A z7EscuVH(M%VbnOhS6et<0uh{R>+0QauT7xzkM$F}$d}ml=^Uch|KF@TWkv7rDP-r{b z$<@1*j3gZTG6{*)?+0tw*oEIRM>sY%x^>dfkp`E*4H->RP zHC4*+aNRn^b9qc(-jo9A<}m$u8c@0^x$cGlQ=LCl7aP{Pe-l8-6y$E8?9|IR4Jb`O zE8EemJ3%n>GS|z%awzTCv13}~Z6adbMgD4cYi|`$a#vG*!&xl2eW$O#?G&(WuX0WX zD3wrAvqUl2S+tJjZi6coZ6bI%wq(|NmI_WNex-Gc0G*`tCs9PJgPZ~%{HYEfzJCSv z&3;_&L}sqPlMgV+#|LlOubK?0|V%y zh+QgG#CjGR5GPJ$*#nV$v_)s5D@lLRS)5)za$)hLrx15{JfH~!(L5^aF68sHNQh{~ zXMVPYMBdaGdH!C^&FaCbCAnC)rUbQ%L#U`Bm_*Jb9UtzaSfTVFWiwH2FeuTK7WwNV z7soJlAdL`Eq7IFcQsfhT%Hl>UDET!SZE}qG1UI!~n*+1;blQz!)Phd?E4&lO#N~}? zTUG5kLl3d3xQ#x&JE7gacjh`H>pPRl-#Ar6`0>kN03|9+)+uiSlQID%aXN@ZUXFPK zDzROh7N+M7={j?QavHy_^~9M%l&A@lnMOu?=+vkr0VR10P)fwSXl_iPxha9&1e3np z*N!WVS8%Q467F4CMv=D%uy$Q7l0-#%`gP)33jw263=Z=&#-SDhN(&62R7udRp*~45 z+8%sDKxyx(Msg^P0ZKo9tCsqUe4~JpPRG)MT%~u!@Kh$Lw5RgnRDcSO`^kmbNpUxF z3>^*Nd=EF}oI`4g2`D``NRhVz6ccPHA^0ExB!RdQ0zhF(wqChN!2QD*zT6$gmF`xw z_qGsl_n?+Kmmb0(B#Gmr*+0yoR6uP`=gIOqJryFxNz|T=j~E#+_2GzzHQh@rRvL9n7$@1 zANM;-Il0#v?(4}*F_!maaWeB#n({MiBewkj=kC6qJ{&rD2p@g?5e^?d%yH8PKLPh2 z{_uzR!4H0bs##S8#AZ3*qW~q=TO3ZA#-U55@7Vp=EIQ_Q{gpE=O$L0BesdbvPM_kU zlkPf=O6fIBO5{z4OYq$kW4Wkuk0-fB@jrhPK_lOfGMg6p@z$$Blok!)owqOHqutHa z)ty6|i$^!iAm}#(EAP$5ilqU=#cE42_C7GlI6t)BMyRKrart?x^i zG`UT`z70UhO(r{Ttm}UEbzQs1g!@`~-pPEwuJV5q>6o^(<7$c-T3Sv6N>e1*O@d7W zN)r&sb~Niw5X=l_4d`h=X(9^Uz5e=gsP>-*lNttu_rE>OuhM7G z*t^$|t5bsS(=f=>j1 za`SvxwxANV^NJBHr5FmWln2Xpccpk*VhXJ-Nm?mACilgRNYchBwh{{w ztYV%NpNo47cuaT=Pk}2j08$Rc?Fw>wk)PK~g{$QJBJ$JSpNGo>#SAY%$!Uiyf@it3 z-A4X_97x`FR0Z0wW@#?&-%yGLOL8!SM?4pnQCTdxrTke0lc=CKo9)XKjOpv8Qs0ht zb8LJ(5k-LDVR88^6ckk;z|D}XHQJQw)-3YaVisIbm#{{cu3K|G`rKyf4s5Tjn;FLX z-{86ex-(Qb*CQudW`Oa+I3d4tzvEQh)^TD$i8_=Bj!N&C#-v@0UboSmBwdsK4Q*g^ zrE8yMreXclLCM=fK#9u!dG8~@oQUy6wQCebZBAl0Ih1zoX~V_FIyAIgbO5DS9-s(S zEx}Wsm^c)}A3tcvJ6qd14_rlfunDg{Rg3@nv$ZHExO4eRf`C#t^$?xKfzuLs%O!_W z4&HoYK7RbuT5{=$yHPrnB=RN>C5;1d)X6%4lA}OAi=0kf*tNHrfKnU>j^*Goft?vt zTsF5X3ok!6gy(-Sgrbrn>O(3rqDirY4locID1O9wY0tI<_U#Je=*31HZfK-}Zt7j5 z{2-j8EQ#9rwOG4$EuMSsIm4->caN<59c8n!n@j6j|H)ii z28Ed@-gtS*&#sMh%CVG-pEz+6pMCZjm8u^=UELMx=NiHfUitxb`MreswevBLTvqBY zmP5(b+m>&%aa>1pn<<5nL3Y#Q68u`tart0w^VT`KR~m@!7sM_E#$2^W@;cRb{yU{&Ie(2$6d( zNagWL*~#CbsqHMbKrYulvaTMD6+Inr66aRJPLj;`>QS23roT-CO5cg5pUT{kSy9E2 zvG4F}SFe#9|C-^V%%M`vg2Dox>|25yinyCG$>27Q=4RO#Iasy-m$>gQe(?)(_IKkS zfA%xH{K_i?o2iGB)|kxk{T&>)(}0rG)HnRvPGemK(2K!+Z~f#>i@b>n-z}rbLhWrA zO>I*Yd9zfoi!07?n8wYH(Xt&RGF`~+txwlxl*WZIhZgoHjU zpybpx%*88}R`ac-jaGtyQkWbCE$t)t&A(m1fBfzu!XsH2B#^RvUL_Z$)wqvGUGvms z%$>&<7e&8P?2le<8ja;K#va=J2NU>gdz^q$7zZy5p_hQnhWS3MxHo_`Yjd!QwvbAu z3-Wo&7z?E@uuWHD(DB??>j~a)F*U*sSYm+N!2xdIx+!ATORl9zkbqZ+`HDE)r17th z08f|;@fpD!lm^LRFe8XLRY7j9B~C|O6Ui9$v&4DoTLL50J266CEhE%j5+mnNf|%LEB}`Em&IP%nzWrTA3@<4vffxK34N zh@wj&p4!HG%+JBhxp@Saa#2JbNyW5!*Q@<{y4u<1%`Eo-X~B9@#G$Obnr&Z6W;Aj( z(ORQRwZE9ujETFA5e01C`shaY>FAyawv^%bjM56racvRiuL2jNdrpK14FLI zxEEb*A)JfPhl$IzUMqXaPwAxHS8TlQKjy zX5;wrP6A3T*tb7|y~l#&6w2nQjs;l4@%HR932b>Wfuh1}>er#dW^(u?Q%r+2pvE{1 z_Igowp31dPMesQlh=01Tfg*dHk!bIkJp*f&&B1;5=VQae9?V@#U_fyRxF>EAsK!8#Yt`fkCM`Ng& zJLk3lCCvx!HKTbyxcY#e$r@mV6UW61j&km8+qdE4Pd?$?(@u`hJlu27J$U`~*Qwn4 z8FQbzxy@e;eJ&k+ry~o(BVAi;Rl1#JPeKPf2peTv{OiAj@&5@>;=55u=lVHb{E!Z@pBn%GKmbWZK~yIUmX?L_mrq;p z<-sm~^xy{?zRMq3R>o6V%dla6Ha2VsvQH@yo4+#6F!qsL``Ee)YM*CB8~65B!j7B3 z_s}ylA9kEt_j}li*Hzil#kzVp9&Oyu?e#YbDB1C9-Ro*`ci&6{N)xo7 z?P%7u9n;>sqv@IDP?|pF%}trR`}zhzskIeN)TtnyF+~)4DJri+wGa+qk&b0$*R_r8DFPK#B1LKJhJPzzA)t#tgZ9 z2q-zM_SAPG4yC9M&8>0#+yB0TU;d_!Tm~j8mM@}?kJWRrmSP#JSI01Gwgc8AD2El` zM#&$`f`__7yyTYIcPNRipA%3z6eXY(LGMTko8}XgS{B5Lm0m1g>7z(q64_ZPp2j8} zNhzE=#$&2K?V+;VAy7JmW#zVyEdM#Q1F2kNqsb6r=NF-zToN<*<+r@TgHnpTlvI+#tFfEP z!Mkww40XPo^P#Rk&PBes!L&Opg(pyma(*EyB)!7J4ct68vR)AbR#g`Tv9vZ9OO_U5 z$;vY7R4GOkPlK9KPTKkzowlo+TxqRM7#>pDc_LhPE_JrdCN~8$r*XC-&J~MFS`kp9 zm98q4U4F*s+2~E$FVnGMGyNyKzkbSLNR>#QH$0dm6_(S0Nw-sgNs|3KA7vKpR;o8y zIVMV%{u2R8b142KKuOODD7*; zUg}WVd6XxD4TP|yl$@Az3-RPLemwE49|h!UEXd<&ZC(eI()cBBqY;q}6X0&U7QqJ} zHR1hF8qv!7HIl1xR(?5ZD`sIM0i~y3^kc;u@_tg9S09AE(%;0n>ng?nnrL@z=REmY z635$O=#EEGo=;`qn*w|>6w!#u^>7FDAjYmpbj+wN;7%t+O2RX zx%-1%H(Ecr_8lYFZfLr@y3pO(jZX+B{f^4H&z?O??#N-xojVsl{pn8)w@(F68my?S zFdJd5QIwWD-OTQEvwK@McQ~7#^~(&Cd9U}L;?%Lfi92a80j1r$cbU`P9)09dJp9nZ zSbyJoW2JXU3j1Y78@KJl*MLI2q+OW zaz3CqssAqmO8>6`lo){T>$S5ycy&ywv_K)ulRleIbagS|#t(T2Xc@u|{tX~{Tv;ve$%P8_jaK%xY%@>%~k(>|2-9miE ztQECROi|>Gf*8EgM$1R8AS&b@^r8N04FC4)EBM!UF7tSL9#PK?jS=N|bRJf&3{e+S zgd8!1bGSj%`q!Vxf{!9$l)WNYl0}g>awu)1$Qza39z55F&S(PbY6^Ig8jrWv>29=r zT~vJCE!{-ixKQq`uM4<#1?Zr1+~HV)inKY8aWU=TG2cla6=@UPiSRni3TR`M!%BH5 z77(W*?4*xi5V@pMTws^wrcheIO;~_Blz4iYMB1d_dvJ)f>ItKT%DofRuLM~w+)0~4 zaw`=O;0p1iI+Hp<8;P3b@*%U#`3etv<6XGdrxjdnb z`jE33CWqI9eZv^)597okipA_9SXMuPhMrFJP!9`yX_+v@=(jwS+1 z)M-zf!nQBkC<@z(^Ou`&=~@F8%_+r;&#%XQ>*tcgj{td$3ZUO>#D5T^=^g4oY^alf z(gFi0l@yoYya1&mUD&?sG!9>=$LwOxCuRBL07{&SI2Zbeh7(d|sWeY<>~St2>dpR7 zkv9QK6nWdbKkNWXgA@yzQHoUyi|{xBrN?N+H5H=nGAT>&iuJKTbr}&}CLKyFrG~O& zZJW@w?+fd?*8X{$HHO|XvSA*I5GH{1A^Ekc*q?ap*U$L_MhlMPlWI0 z$OzUgsKR~AXX2p;bMVL`Ja}T3=KFEXSh1Xk_TKg<8^!wD`^j8}740(HY_cfR&m0Pj z_G>je`*1fE@i#Oy@B`AY5p^mqDK`C8T!I>Fnd8mU@lMm;JvQ9e?tIh!k^It?hPU7a_|brZ7nv#xC*)64QoR7B z%lP;AE|W>ei{cy~o_cT=UV45$#nyOAPURr-^Tlx^!$mtehr9{uZ6N65@n+#5ft2mr zN3j2^UK}{rfi@~;T0W}`bE=C7$Pkoa(2Hl=aF%+Js2&JK`F`YNK9VKMIq}J=H{@MAR6%=6#96o8-cEDinjT)66D&U{v&cCjff>lR@_I4 zK2}nv*tv`luq2-)xg*TVC6JVhndC&MEac`8}0g9OP2D5lqE z#2p1F6_r%5$*C5Z8|MJQw4g6y%Hi-QNskl7cSt=4S|p9k>2oYC%lcQ%1&n{4VbYTu z_Di#JnJnNmpk&9syKMw088AtJ60MYT-!`ChEA3{RDl?86+CJmu7@$N^SamE;ErUG- zS$lzPJ6nuBbD^1HZ_SujU54kLTE)%%98{ERJjL+NA1~u~A6+J}O{McgeR%olg$7V6 zBA|5kOah0GcH@iP=W*;})0k3j>QK6#LrH*=K$!Fx)!a!yDJ8A;zMz?-#G$m?1t_%- zW#i%5rMQnAfsbtQT;N9?Ss%>PIMLHYXhpg-F zOV*E}jnOmtnKcFz5XY8UC`beVSy;Nc^E^d|o?RVbB&Rx5B^4T&h zU9uFZ?3He=)7|Vxe7{jo)biRItXn<@k3F1=&6|0O zXtmx<8D_j{T0iwA8S7eq$9K|S(=O@owp}KT@I8KL`>>^x?llGthaDFZI<4?-0+ifM zsXEzux&6Nn*S1})JJmYd@P89PNrmLNwPpA&wB7d}P_m7wwskkC^|!8`XBs`TgZNGY zO3K$=w#;%&-~aU#aJRFi^{oI(0+Yt$P*TZkANlJ`Ii13tq=4-Ma;;T ztx_3{3lm1*qA;Zm16>dGO7Jr~pGlO1*FrxCU<`7TbhVirH5Vgz=XaO!`%f;TxFCgD zWhrcas0Pn(S%k&&dHis8FTdP}k>XKiDFQvIL=G1~6u04NYdUf52mz&?U&e6cL_f~d zb)tDNg3A0{>H(tSY>Ij1XJ?_geF$}3LuSL46C^hf!KiHHazhfJh#UbTf}s`)(y2TJ zK_7;>QHYR>!KsvwM{XyPSo=l0%DDR$Y~gs@Zuwp)MZ_7Z#9XAxQTX+8$39kYzHD z$IIZhN_tmD(wMh%zbf#xawuhzcCzMhKXb=(`?GxZls5rO8V3Sj!sMoi^n0*%S8F^twO z9yWk3R2H}LG)ylZe{vZ%Zki8Dq*HOe#F)h08O4Ru9vnaDW1WU@=wv%CxAbuS941F- z3Xg1r~g$`w>qRbkP>MO60sva!-dq!UKn zGm5+ay7RHu?y}ghZa*8&KGVIPPZUOLBw6VZ6ZdOBf!F5d7J^_$@b0_sVi(I_Q&WRE zHFL0K%N7GFl~L(?kX)ylFU=Z@?@o7qwhR-wPJPt?w{Fx_%#Ji;KO=a_ily67?c{JM zc?l?~JO8i$9;FVYC{Fk5Ve*p&9B1RWmS0W zkz71UK&e`QQf3jAd8V;`ra!qJT7Q?86RxB zg4q>u)Xs@x^8<77%;QTjZw5~wig$9OF^nWdwi3Bn)V-9)jaD8a{9+&G2J83{iFze) z`s^U;Te{Ffkc8)+5zO*aadsZLjq=b(MM-T`ILbA#S@>s@TPBy>NaC95;`DD`0X%*j z5;x%qH-3uV#RVquxNNd!saCYSP7Tvae2phw$P(a^Eu~Y;jaim-moV8Jo|slbE~JtI zf>SoD#NYhhBk*HZJcoRZ)hgh$4!Zkh*XL@Hm>b?ZHmJH0&a#$UvYRj zqGetbaC4Wh8ku=pO2DI3@?CeihalTE963CIgD1$r)ttqX*vLh}3?8U0#JZJ*+=OY< zn?!rZ04`nWLQ{JmH@O6sDAJZ>s&U$dGiPDmY;NEd2eITHia8WJeWIYii-mJTsGcRo z-6|86jVGn!iei7Pyx$unsB|NsL>>f|RUAvE+We)-eDmtzt(wd<#*3esZe|?bo8Fu0 zKVDkjAwT!nx7D(9fSw6Z>LJI4#NPTTCMA2vIh0&&FSn7&bqxhFLnEUcN<9=!jdElB@?&%HU;ooR zD50*T3k?L6PWE8i_VYM;uJHyArJ^E^Q!43~@le^Ahdb~T`?ogbI{i+ZL&QkT7(V<} zCjp>V9vm=)181poh8&hpuB^aAI)(B9o<_Nelg4NtbpWL}<44kXwgBp&xJD>;M44Oc z*)@XQJ4aZzUYxqnLvhp&^Z5jE)RS``b>op+GDIM|zfXWt<0zn1DUmnM5Ue?i z%SlC(mc~qa+}OTjT|=BneiY6EN&=I_;iEN#Y=3{h;fUK#E~Q`o>X$}@EIT_JRn+73 z)=%HUPu}{8(cvgPjsj+smh;9@u||n`UGACXvf<=!;=AIxpDB^dxHe(yZ#g^$1_q3- z!4t<%;7@=2qXCr4%E}-sKuLDSj2Xz~M-M;yjmDUzpUqRQP1ok*cAa{TUq^Si@vhZW zBrj>jekPPCow=xITUPHOKl|Iy|Jw-u`!7duihB8CcdkNdCR1ciJu-nHjm6Ow{xFa&dJiaQ)QSe&u`PS+o8LS^KAo^Y`MNo^qops zrU4}vmF(b^mu*n%x`K^f>X{wH(}2<_S?>A^+YfF4ly32qH%kbcp1q%TzdaOiw~Za^ za;;TKrvxZzBcMec7lmeBp#=)ByW88))!vHaFaZZHJhSo&kjIV5P_lp^P>c#|hk24x z9kw5+!?N-?R@B6?mSQRQZCXqv)gy>DU*e*B06~hZ_$taMW>&ycWeU*J+=td{eW4;82kQl~?Nrz^$Cy_4t9CU;N>1KenK(#ExZ)@qtSl0Pki<$O<2!L>Og zXhiW9W2v|nap`>Gt)FReft~FgA$L=pU-h%deH7v$YTN|TmKA$3vy@y(1djwp39u<3 zU?e?A1-#CuUopS#mX>)b?f@#X=LV6WlVNTWo$R8X9LR}n&&f0)Dq8AhM`*w$L@Fc}BsF$Rjz}}jf`TUYhE~v5) zipZ^``VLTJp_@QKOJ^_bAjJ@~ag`!DrBn`HSU^R@l?i@fk5Z474~2QTm{k?Ry*xp0 z;R4n(NCoAz(ytZghC`c7FF_@rhax;wDD0tDaZ@+3|LE&CK_&GGr%ud1(@gjvGhoKO z2r{W*0C(Esgg1S69REp^y~`iE$G)wKodfjjYXy{)!A;u0mO&j{<(RB|3Tpr*0>Ked*+BI`|vLQub3&^4L?q&Su{VV7h944SN zOh9QK0j1?sI$VtN1e6X_N6d~d$f0!pMh+zlC>b4LJekn|N@;( zw75^3vH#E@j$S6*P2Eb*ZLGqh4^-e@D$-s?%i5Sfry?BXtP<6`kq$|U>c(gVlM}3^ zJ$E{3?7@RQRQS ziH)hjtTB@wH@5Fs*VbhsSK%fClt!qxNo&dj2M*w!-@k+1d-hNqr`z<2=bn2G&p!98 z;Z|C>Xc6b2AVDYraeC)CcDy{@<#P8e`O8{A>naT!$GYRCD?bA$G4FxF0d%wzY&m@z zpM3l=6?5-)qL5TCyzl~EeBnjvxT-N9VpML8F#%|{+~eh)nWyS`{b0%rG4Z{cO0Pfz zD4B7?8}qN3nk`FkPVXgwO27OcG5pJ~M{v4_CzF!PxPtluH!h-ur2ncx|@ z`;ydowQSxDtX?()n+YgAwV8ktKc0v~Sw)pIYE%HXvG+ERb*;ZU>_pcpKihBGj86e~ zpHc{SU)Qz0zgXWhxdj!&h#-}iRvY~y_6fRgEm>WmKERSw&B z=Fwd`p1=1ZZ%%XG_-i|wb!`aS=x%@c-3dU+<~i;DZ7A?{0!p^u{B3G7o$FL7pmFWC ziZ>-d$;3g3NJK6j9UJbUQfx0Vo!K=W>OS(Kgj@>&vK0jhN(IU3 z6bR6g7UB>JQUoqQaLGr}Igi&7jWc2rDuMtPhLaxO6oD@(0C(g{>|$J-O>LS98kq|4 zwai+5qv$8`x-HG~?Y6=Mm z74a)_0OghB^6(7vG%TKob-5px&zIm_a|!yGT8tbZeor6uN_AsaX%-e#&%m<9MOb&g zk0kNO3j8;td|t_@%!+8er=&s~p3 zFEiqd0uG}AZoHUQ%I(m^zSlK=zji?BMzW9ZlhJHJdgCia14F1 zom@dXIw_jdf@9~dvac55fwlKy&FWcLvYfzf$q3&5{T2Mjdv(;I)XzC)055M|KtO2~ ziY4-Pg-W?kbQ6@K4yAEK-fjSt2%e_WbBe}+F&q~v+U`B=`1mi)`08jM&Nf5|NQdx) z$LCNqXeJge1y5Pi_$9Dlti$P)Gyp8;1D-1B^$gNR*!8JDj<%=6hu#h^_U!4wXPJRHrgtiHDI*pNr!&c6TM$Fv;> zl#I%oB)pgz|LxpER^Glkd>E%ro+KIhRhGZm5L|ECv z*BJFZNnBY8C7o~cw#BvAu=_UrRsbc#)g=(l8MlT0MD#MzxGmu#zEghl--7sWzoj%% zZxAEF0H}?Pt;) zeq;T`?6|idO5{G_3ES>Go{)6@@WU-&`?l$Svyf0q?5m0U4`1c4-<$4PaOeD8m%)9l zAKSLQkFzb8ZPyC(DOSFC{5D?ZAY`AO=cfjcf8`}0VUf)b0@TuI!!JNDfc&! zP*UHpeP-^o%-pSso@=*PO=kos#U`d&56EdQsjv69uGivb?R5;b_F}wq2)Wq>Sh!+2 z38O1;`cfv<3g{Q7IOrUq*X6QYI!B8MDn=o z$~D%T>h3m?=O~MPljPG>aq~o}UdQVO2qpzQl;ANFT7ESSjbJ!DLMu>2Y_!N@+GL-k zjwq!=6+H2rcnqO-0I39!Aq4^w4u*J)ToxHwAi(kdGkk%R_*3%xvwR5SscF{{trFLAp-9||RKc$JN3R9GcWmVZ& zx;&i=+7vFX3AmAPxubm)H!kO(_C_{3$cyoS(q0n*l8py?C~4)zqQV@iB&K2Q8ej#j zLse4Zsj@U1DU`NKA4tzd7DjJPIcd>IA1`a z11JfMah#VxjQo+qB-B3KLz4PdT&QhEc1AXKY+8*?8_KbI9l_s10ZR4wmp|T*lXAcN zTn+x;|7#<8!$`_~Pk>S%NxAEAnU>-f=lij!BpDxmP=gPDUV}V>$A*NTebqxSMwTn1 zR7W%9^NM3}LSs}=r7G&NlU?}uU@O6`e$+LOA~z!yAG}tDS6`~YqAHFZ)xyBUktR=- zU=A#fim2*DsY#Idm{u}9Q9fXiWQ54!78>{C%H<(~LjAaKc^DUOkD+74N1mHvtf(Y- zwl{zs`va6T%A|B*CN*=(=fpzw^+nLwOs=(S0URe6)0s;XJTHiL>euaE0)jQb<_#Ix zyfKH|b&^q(H$E8&od3PGK&qj^Mv5Mnkl(jT2{Y&SVP3$O}kfXELF=T^#$Q zuBjIau~G95`pth2;=li6kRKx`$x1*ems;Liss$){s4h)Qro9tr>TRc$(RQq^s=&sT z6-Gko#TQagUMXoO=bkHYwkFGAF0Wm85g$q9O8>Y`cOH*RH-GGr7I61#%{gYO^5*WV z$~1BRkqdnb5s!N&zOOQT3)T3}vat7ZHW#pMIu9t#rq!lTI}a#L(>AuF*)Vayu$@=& z^7DYwG!6L_M}Jd5DY364?mxv%GUtnKpKBYc!cPR0$cZE;H4m*1bgsT)%QxM*LtjVB zH(h9I?m-d>X3MGfH9lU7Q?*NRu3-V%hq}-{+Ko*~9ax##iPEABE?x>SM$+x(t_gHg z^DLB_i7-uMCnx6-xX8r-8EOY8Za+@5+T)QFjPMKm5HBwEwx~#K&9`*TjJX}^r0-w> z#e+nNA*!q`%FaYFt(s+JWz!lQ8L$mdL*i`$C+Q@f&dm*TVHqabZ3JcfB3qE_LrPv6 zQnFJBniw34l0B3u;3PPe6K#GZH&RG4xlK%o6KKtjCAmWghyYTOkHprvJEN4{ov<%?BSpmc#8SZY;3J)WLyrvM-8v-(HFL-dRQK zi+qMXBBNJZ3Cx}Zlr-e%z!<@sQTh|7yYczq4qT*Fth)9g6jDm?@7`L9H(sqEPy;NW zkCG?Nc&fBTX)?eWztm^~kjb4!NhM?Pjk}bCWKI3(Yz?BZVFKsQ1@PHdAzW*uIxSUv z^V7Xpv$BnnSnb%fxe^;TE#&w_5@;?M1HmXcm%^yOA0oMTfPmBl?lq0zdgm~fWe$+X zt{=O1mEif8s!&)Q#NfyS^1=mBR=$w@S>jNlnydKpOg1GWb4bknKHjIVsI1_4 zokP&fn5R>A#<}Mm?rnSAhVDLZ;}S!gM)ArkzRx1Z^X7J#A1#99-fL=ZX8${3RP`=j zzC`fv5?+1fRr=SkapOj;UbBj2&YcoaiszkJh}gbq%ZD2O(S){zA34G@np4G}q-WiD z#tBR}?@fl3uJv#XPXv^**)2Db8>xU~?>!{y?jB(O>+Zy0e>awumtft}61?ziI<4@f zP-<7;pySwFkCxURw4p6m?40mq&Es)t=8sL;0_tn>>cigzP_pML^Z0Wx<(0mh z$i!#mhbY5$Q?uFUn%EYP%fY6#;SUBV&9P^99#ER5*V&F{!^8(w@$zOM;$SonC{5Fl zPjU1kfKq$AF^Q`MaxTrth!8W2i}DOw)H2c)l)jKl>??`;PjQpX`J&tB+J>rd98hZO zKu23Ug?eaO+V3|LVnfPJRVq2%e#0Na4UxBUNs7LfR`fQv;(k*%Za4N~te4V8?Z3^XbWXRFo4!NyY@SDUsykCt5ETgK}yg2^tw*CKJOSUej4jIuS|} zWTGG!8A-kgs>4yegbOEe3^~`+ufF&@0F%I^D6JlO3@3}y$f-h_ZF3RF#WJ&G$QU~T zXQ)l*emV6vye_&I1lvY9@xO4fo2rFfBrpdTwQR>gh|5vdt00+DN?BO8G6U=Bt142- zO%vM(MfDMQdwI038E8=ooEfd-oy58$vEgd)HG1am~_dEFmXN^)e6DIFf1o zjgnuPKGv1xqUv6l_eT9fU{VsnIu+k87Hkz1^^ns6Ig{AgG?k2P#<%Tp8zvsN`wDHI z?l`-hc)sGNinHnGaHxJHr!m_CN&=M(utZ6v?-fu=yl0QxlSx1+%yO%r`6yl?h07DC zf?UiKFgbSzCof(@MoJo<*|3(TrJ|N0jPP#PKTha{AK^?y1NO1JMz zLP>y9JucsGK}{(Q1}qHWowrsKR3aEaK*>8Tprpka0o_)Pe{ErsV0Yut@ph`t_2FLE zFiOc^_V@4B;O*C_Mn>tzl5%!8skt6MKfRf6q zBFo3`pGG++&gotj?ocAf*?FY9|LI7O#t}wIn116%E&lnR{|TRb@-fC~!L-AI1i!fTMWRqa}FCSFZZ_gtxLS7jdzEMY3#l#7SGq#m(}X%=)|eh zXX(#SUGF$fojQ*F`<}(K`=7n6jar2DD7lt(-t_l2j}c3RV3Y>EVIe5Yk6 z+t*3OeSw|w=4H)&n?zw)?-=H*4+8YR{r@PT^gpTc))l}IIjz$9n%_iY3 zfRb&E?LFw~>%kK88?Ibbh?k#Fr_@*q7A{s^v2LI?atbi{>%OjHmB5|I9-lm8`mNcd zoj#YJntb5=!=5HQr47@3-C1DuZ=DR2l5`f5_0?4o@nFO>4vN9Z<5j%!W@Y z@KbVp9#ER*M%j*LLz~P#u!@)0zWh9(WLs$NgtG#aIFVC&+dph8*#2Sn=ffX&3)tt{ zhAOQCC`G6e)q&2A4yqRLD>c2ou*w8-N=!mY?*_fw&AEo_hmtasaG4k!BSujcw5{lLU=eSO{0WSG0C!X_@zFZMA=!%l&qomIcO6Wa51^MDnK~v80IBp?p|K!tJ4vC<$hxxL+5d+F}s(jU5D-?xT}dzxo1c809^w$jl{CYc6UQ zN3nDXDDjj?PzMkIuZ=@Smecb}9`JmK8lP#>1lxc!3zN>6NR2T+O-Yzgr>9Zj&=R& z1ex#DhjIDZ01lsMz?J*0SX>ar;?gKS_}OxN_~CL&D6wOSb4_iPpz>z>dh6XVT1diu z`g{j1&Nbsk!vLCyj928P#p`lOu`pj`S8#*8QO810E4r zLeHU>b>uihu$G!gB;b$Wz-I)A&eO^x0j##+ag=8?p*XJzJGWP3=gw+WEoGevh#BjW z9Onl5eYjH>p*nI9$B%X6$k`qen)e|%-ivk1%ka$3rC7Q&N)V|H#S20xtEeQHD3v#= z6q=`26{ojOMO5EWabqslmCT-beoY$fny1@@<{*FE^9JQ(=MDOJ6$}RP;K2hNq{`dT zqeoF!cbjTtcd&c+9_-z-2U`iyY}vXQg$0F1oml5vE+uz=c3;C@SD`zNJKnvWn8xm_ z4dVIQ_Fz4GdU|l>>Qy6I^~J#hICStJc5L5a{LWoFv2)ih6c-nBjHX1XI&N%?Q@N#r z9nargh}gFC_OTb6BEb~xt2Wn%1{r*aildMJ9`W@tjQy~0>4OD7ZV+@-AO6SR1o7*C zqRLzQ1p3Cu`A!5jmialh`}mQBEQ1q#m$dd!N~sssg#}nbV)s{GNT+HaC4l)J(KSr= zYNNzr>VTXLA4%XGp3$$(V@8SR6S-SJ{Y>6GZ?gcDY#z4n+t9{;pP_wLe#kO>pY@&Y zTJ~N}cYLaN+jjGS(p0T8`?z^PX__{(9nFR|nSE$&=heRaJfLJ-Xzqlw0hGiGW383A zTfp`g8@i9pZ~ypOz&_VDR0;L6QD4wk*G_s#2g$sBZeE@PC{aR*a}t*mup+YDAW3q$ z1feK>UpLTAsh8{5T4;UjI!#{FTzywQI>rl7no&ry=mPk{B$g!+_6W@z4Fw5Ca1of1 zlEVdCI?dX9Y1W?L4As{{^y!q4N++n)AI(5VgbOh7mr%M#;`+-dB~w+-i7!R-1#ILI zSSqAv3ggO(MoA*tL!O5KJbC0`%Ff_~msZKNh$9F?%`wh^2~crj&%uq8US|Om_* zx-+E+zg1;-y(OI$q*o}XvjSQWsa!E9!tNA`?+CP#V~)&E2Aj30aGZ#_4GLo;Vq>gH zZ4eq2kJoTb!UZTrq_V&`-5-TgH&a=3E#5*LKgh-7mqA>;K`TV}sRBox{w^*ZNl%`?AZun5ICiQDU!J+4C(pdaeO?n}^Uz38KXX zS@^qmtMSHba{zS22c{i5UM5)3=@M}Q{$0J6iv`-0L|khj2kCfK-6C2t(Jd)5Jcubg>$77PtA9}b2 z)bDKHn~lnw&BZ7Uhs!3!}nR=sjg+)z=l($nJUhvp9hqtYMt4~%>zo) zw3+Q_Hnhp?L+g%L+&rLUTWIctvjLRsWH+()>KnGtBp#dJ|M9heo@=*P3H7oGbI~RV zC3#5z`1pxDH!l|jg@q(Spka1urbQ&4-Q9bX>0hOfWwM|)ox zy2+)Kk(@^0C>^OJf0Z94m^3iqAtdEDMNC;_P0LWt*NrH}G!HdQ>b$$^qa-i;K2Nd_iD zbeLa^$uZ&~&yXiWq}}3zVC|@G=8>uzy^&DTELqcJg{nNg)NVpt)GCzIc_A)_f->J0 zbAHamQ<$f~8abJ7X6w>(!q2ifr^fP(oug}*XGqr)*d!;CBKepTp{f=G%8{8FCooC* z$-F+l0Y5Kf$HMQu|jstd+YRW^?I-(5j#T`L??ZgLyx zku)4iaX^Wq1A%8P&Td^H`Sn#wD4lD;@pJXKPyVE#Kom8!zy9-gs_{BGl#GPZ;{YY~ zMdK$srTCN_)Z2;cAw69ET@P;G2;$O}0bIL9OJf58v{R&WSs5iqsEV|8>jZZ09!6yq zjS5h*(C16T7^M(&N*s`qis^`}tPHx0|HLL}!N!TR-ntXxr!#Wa@S zp}MPw(w0)xbp{%RdT>~07AH3Jai4Co$WD^@aWkUE6R5A*erL{${g^RNshFv(r!_uk zG}hDp@W(&kkAM0j$`+JiLD>RGjqKG|Uq#Kb8mil7A|-{S<|+uilZP{Y+WeHgdpq&k z?qji{#LGA3F^x^8BiPiSA&DV0)Hj&&e){RBkYBK10Tz@lz@9yO@Y2gKp}M-7(zK~m zA@>{5Oy!kylE%M>UE;`R2daltJ-o;I$CGJW(&IAeAV7)b<$J^dlz5D>N*fjFJEhmu zcMYKQPZRj<|C*pAF(q1ApQL0jmX~CrtSHqGbNhT@T)o+YTB@>F5QMER&ByB&P^#9u z$ms$JO=IHYeM6U*i$}yKkZYKHBKoa^Ud>9ia5?z`vio6t(WT!_Ae?tNJOZsU& zsh8?p4+v`9?Bu6*sl$1*320>E|NbbA+#0DU%JUOc5&$IliIZkdJOx}tDG3nv44Tkf z!2Q!h9+O^LRH7v&PXQ&LQXSP34^4u5qiI|;F8&Ad&%;#3lViOOrj*u$uMD>(W{TOafI>lZ$dOz^S1*JUPc! zDG0d96ReTM*ljKXzP{9k6KA~m;(P%bddapbX$#*d_OBSmj;%x3@=OV~(Wj;-vHau& zY3s$kn@xB?65yWBauTL23yqDdA96U4WXUnUr#%<*B7f zTsV7CTFym=(`+mg`v=t*CB>!%jijrhAxdY2NqR1|CAN{$YLcr8nfDFD?`$klx!i8D z0o}24e%rp+)y_{dpmgbcI{~G3N+?aRkCR&{L<0JfB5YWhjpz3zVcD`U)x_%Y*%$RB z{_jImUmsrCUV~qLxQV3C`KYTW$@Q%foZ)zNtEC&uOZ!k$)rU7S#LH#2drC4*dN=_tx1P`qt~pi3WCu1ZEh zNimHP&KyoIafe{na?DxVlE{q_rC36s%fQT+om$CT3JY3 zoggsltvWk0p8^g9fDlO2*u*2YT-ZZVE)gFcSQ zJ}fTEM@4A{7V<+uR(cqxF7jP+rw1hjl$I^X#~UwELg~Gjgc5UBDO}CMy_mDbGYMjG z?rPfOHvQwm*`$43K0m=@>euq>*RuhX5}$*_{hwe{{@_)%W0VaacTa2@8`^hPOLGgF z>3syY)6>(80R&0xYK$@uGoLkkj@F0rQc2eO|Jbo(`1P-Ujo!Xq{KKz)WsD{ybFCn6 z+*Hr^9D8=>0i|gk1KVkAXp`Aa>W)|3JfLJ-XzqmbfYRK#mou%2o@=+)c~1hAB%u^r zA#nDnGqhl!)gn$*!{G_ObjURl;$)SJx*J!!@Y#V{s-p~`qpJ*^Lq!Cg!UQEER0Yc* zS5YQLXx_d%=wn<6NzpOn_#!CDOh$Q;9~;*Aux=f#zjZ{=A{Dxu9XNZt31b2BC1owZ zh9!A;`^{uL|2!p>2s{;$??JLoTpmxBQB!Io9b*9*l~;e9T#MzK5>Fm}r3YWA9t&(} z!9m%LAa z8-X{c-mxmg+E_LEPMp0R?##dIYr3!XBiXj^b+x?~ASxykoN8_BB0$`Uzx*K^ zzxym3_lI~+XcWbnL)g5uA6wTaVgK%GN-LGYPXh%>nFQR;2qrLH(w+3YzEeP_y!?&t znr;2C9?tmYjE^QFesKB?^+nA^CME*t>gvKD{`e>S=}&*68eA9mJNZ6Xi+y|ckxOYS z)~;V`RLKNDss9>qnq!Ha8Bb!Dac|o`A3J0M_i;tI)3}et<8^!N7|m^whKon3si_HI z)~(+F06+jqL_t&szxV=QkpHQlr1t%Mj`r-{jkn)^o04DaQA(+$?Cfk)R?!AXUD*Iq!B|7a3{1d3e0he{t2M3iugb@mN4f*K-$HecIMY+xD0Zb=aiQ z#thtS(#{~epHdR_UwQT2c|hsuzVmi0vSEBYnxa}ZjSc4kr70Te8$`_mO4Br&?PxZ% z$!sT8yu2BRI2g?XO16dOPB;%J&7FHW)0)`l+J-vsaez_*$v9KV)~WPz91%D{)V4qp z@+gHxI;t<;{7Ml{#myU?_~NTu1eE&F(v*+3o-A@B(L8mC;8SuTwblwS5#geWzyiWF zV-)Tqs1qbdLoSvs%EFtkCE>N#lgLjIp(l69sR#J##2w;5$*8GZf^{p4v3H*jTc07A zlt*#Ij3@N0ngtwNN7Ax5p5ouuA#}uSpmE9+QV+<#a8T&4OEsQ)+vL_GjYk6;-~(bCtK$9khfbV-v}Iqx83K zL~!&gs^pNs`0Cv;-0B@cUUCO=Gdi)NY7v%KFGOWUKPt*vkexePvHhu{gpcHrNPVzH#lehKBXDDBr-iA7Bw%2^}m7a|6Z-UJ)y<4Fczp9CfE?t_`&i@T}zRf#RKgqDm zv0-^W-gzY%8`ehfmrtnjMk%F438l2;e0+U5gv$h!t~7L^v9}8gGkZ~)--Dljv<^T2 z+w~;n*7!sOmDd-R;s8n_K#7nnYff;=IA^rd6>RquaAwG=sXiB^wJmX^rPJ!7z@ve|UbHli;E#XE#D9F2 ziO%6}42*SSMbRKOtsKOTo%z^DYj(?46f-}L8C0JO51bdL;`yj{*~!rVC~*F*MX7auR# z0E1M$I(+yT4j(y&%U@rl>huLvl$Vp6XgzlA-h~%ld;!asFGqmylrVX<`~;`PtL1j_ z{9=)|&(AiEJH56|zPd^D0<#Za~3l#WqyR^<3^S`kcFz;PHl&0Tt9O>=tH3ayhBcp~(PJL5qq?wdxbkkZS_R+-s z`3C;}TfmNEHhkPYv1x2L4=8;*_iG+dnx-9XN3)?#W;?0k<+U$A4=C9dnmgfN11Q;k zqSkP4&z;tpn>De|wGCCv839T$z8+0w^(TvF;%qP$Y$#SgG3tYOl_MJX#*hJFsEO||y9dOIeJRQCy0veJkFwU0Rfq+aD zNxnUjIMDQ46J2`KkKL1AMjI^;bAoo9E7<9?aQy+vuD3+ul20j2F%gxtJ`EWgHGPap1(TV z#L19?h9&|+jIhH_X4oYyS@Wn&EPSUc6oUL)#>Px?Ib(-+YAq3{Qo-Z>oan= zZxeznt4o)Th6dya2bZlT+H`kXhOL%a#;KgzOKxYAb|Y1Vch+jQgExwt!!c{R0UK8f zZ((-lD%{EzpW9g2$04hGv9|LFn=;LGMBq|uf6+`cOW;%C&C2icT75KFCKwf*STr4n z2A;mgO(w%0NyQ-^+Io+_u7?Nz9b-QnRS#QJrkpt3>StA^n8|KCI( z`7xFlqRN8@I%@Roo5*>;^)dV&v+Xt*Y)i?8oEo2!?0ce59SB(5f2UpBc}#VZa`Mp zq=XtHt|yAMC{#Uh`s4JDgzbtHR=HngUF`f>SvqJ=yqr-pH1_Sn!r#{|Pz+Rczq=1{g10$Rj=@dUmHT0UD?#Fuv`ji*uNj{*|WY_yv# zb-w+ITSw{<>;6l|xRw7&n$5uFCAUGho)TfV9>voZ93TJ-M_H+GXd<-9ycOS}>k?T2 z_EVBizB=P49IN5wYpuugdbP>mk5WVTPkU4>?g<%6oTyzKpw8B31gMBpBS=r1bm2}r z2PP@c8JAGYJ0NWze<{{SYmSyhnL9F z0;iv~ykO3HRZtZlawT7Ym@o&#?nVmlN41@$Vw63MdLv(k3=s`!}ZTArI{_UHI4JsPt!el`vw}cozoD<9TB4 zKZRp@EW`!=iBE}Aetdy{;W>wqeVa%KivVqCS7B2fgn(a1qVksgUHIZb{scu|X>teG z36X@$n8xzaDF9=?YMZ{2q9vw2M9T@?lKUZHIww=m=2^CNFxhRD1=Xomg*}3fv_{GS z#AiBV%xg>$b8*yZrgSL_1PcC%>Z-a**~*%F7*ByRFRrE-W==QYH=##A$07iM_t6c=p40r44`h7E0IV zn~4W9q^F#qDE>apU772$BPlTt$gW(zkr1*r&k}aXye~ga+A#*$$ zV}BoqB&51)hABO_V8mKj1g3GuphMJ|LmN`!leVh-%CQnr6PXHJx{}b9VrJpt)t3xo4UaIZ9)4)`1Z)N(}t%YSqI7{-Q;KHxfsDYaEFZ@x4Q(2Z9puY_1EwI zkQCt=%XHomIFQEeHX0i*fcBPKdKrRPhRt`{bx|2Q)1c`yQhI9JpI%VIK{zrwz@=ZfWgfLFKK zn}4+9w=Sy1iRRnY7-x<}|B!8f;t%)J216v*Vf}QktHS8|vtb|FQNB2~U@}6LRqUVy zF*!WY3m3j9CNlWRGuV3fv~6xy#$SpP)PO#kkQ$W%D2IHx+@cqTaIEDZfc5%c#{J9< zP0uq&5stclPmCM8up(LjV8Wob`ONLYW67Jp zp47c*$pp+#C6>oGlj7ss@!xs!uAb5^V_>hil<#gx5N4-Z&`@)Df!V1PM61R4Nu8co zvcz^A`%{vWM9=BcHfEH%gU#qF5?;sGP(%-BB$Kzq9W}N<+sl4+U7(C4^EEkGv!%j0Ntfhxp zDwU4bu-ieD*gn}xiJpm2d~^>Lwf$VE)Alf8wRrRPV5mD8cbqBYcCwU31^#EpuJ+Pm zQ$CK({1h35bl%mF?ZRRPpwEZmL)|PCKlI@*`FRN9TA$(C^)m%8nfDXg+cz`5tWbjr z`rV?EybKNO->JcatNv`|`8SHixdyaU9Pa_?^gM=F772gU*BqzIjw&)DYq{pjo+_TQ z;X!A6IX$00r?qcq^&H%|0Ga$?m5rqS=PEAuA$U#cTi zra8C51OuU{Mg^vH?nrFOvY+9Su=xY7PZXMM(X~(?Xl)VEw673o%_-L)amZJ>;i%^eu?f7-I%81M-1K3wj5lQpx>kpR#Ix zOBH^Prj{+BW55ow3PJ-0Gi;uzP#>?$=VZe8%XeUz3gRK*CEb><%mTK$fv-L@_1{>5 z7fIy;3X=2tKS`=Zs6>}T)FjTokVk8Li=9egB%DLE$H`=PxI z872IpbNzMVp`}G2Iy!a=t`EKIZp=ph*3N2NLrX{J%CO&GnoxT8nqF$u=sKaltf-z_ ze`E!E)^vG&`nt(qEJFX`@Z}MMzFHgvET+@#u@$~Mg@#j#x?hMlBSn?n?eU>PL(OW& zs=Brw+d2DB)8Rqxd9JE0fr-3#_*#jGHEXpcMi6B4^lro?F>j|#;>-~kt7J={JumpB zPb2Gd^jM-;RT+@ZGF7(W(cSFU&|$& z)Cstc=;()#;TiPa$UeYVGe8ry3XGyaL#o5zBhwwrG2peSl@)qRmCCTb1HDWCnS}-i zZ5vC{kKXI#*`8jC`Tzw2WByrX9VK2bdmBOvV|R1a6ShEtQ;PYp#%jMg{n6Elvk{G9 z>~ywhksk$3`_Y9-#7)3#GxtfLX#4#^O7~Ww0)v?rc5##!`$bz_TAsDuKR9hv=zswt zwz`Z-S_MybncaC&!xs@Rt2SMxKR=g;(iht#2u1In>--zB{nx%o5>J{Hek7qJ=h2JA z-4mSssBv5JHF#2erHcBe9f+M@;0btglfLPKjYuTaKX@_u4+W_ zQ87gJcdSN7Aiu!9-u+T}P{z39Z|hGbOXCXm>|I&gm+OOml#YUN&uuXtBSXBP#X2ke zg8k{593SDBCHrI;{sQI=E*OIxw4eR|Q-Z9xN5%iblwr+R3=C$yTA^`L+5zQ-VxTdo?vu|;{wR$d_S8*M0<*6xz?hqxL@V8D7*?lE9YCx6tSW=5 zqRZd~*QKUe;8fdGI8Jkv9ERJQDREGoz?CABW1$3Lbs-|Q#gD|Tq6<#8qTtp@nel;$qdYV2Gp%0wX zi;F_9Bv_OpvH>`P_G^QyJ{~bcd_jDo9w&SnARFMk9X**DHL~rSz}L-amwPYrRFY-B zxTw}gk=s4q!TY$P(i+2V>lgS$m*1ZtpS~QYRLjdbocDA?o(zVc_g!5D;mo)3Y9CeL z0Oc`C8L?{b|2=3FHYEuD3FDuH#9kVkRrG<^lvXt>uiQ_~G3@!oH&CcRGv9U+vLvv{ z=XW(4SYqTU|0_@@A8Pl~)xm4Lx}$+F2J9T0c?W@vDwe%mU)x{@!Y!4{cMgkQIZw-7 zV^C~g-nX&eYJ&1A$<;9T<9|`F&6SS>TA_ZCuy|Lom3<0KA5`{jXEs`UFG~^q-$!Iu z%(4Ec;H|Iqg?{FEpq8U}v z^d|W8Zg<|@#HoJi5~9rBlv(NNL=^NM6L#C}k2ZeROqAbHBF(SR6ai>Dx8vmRkgJS_ z2OHg>^porr{8eNn?ZGNQlOYhYTKKw@c_Qr!JC@t`5=8kQ^r6%7E-_Jjl`j>NoYJnioshBm|P$10Xopb^CLacQ2{RrNqx}HbY^itEA@7`hyY!=*JQd5AP zTYK&H!_TDOg9|!Rh&oN~uwlri1g-$Te2i2Mw=F*5=-3?0LNm7Ps7>Fh%85Y~hs34; z7lK^slfivs_bq9tc!kBj5CN4J{I8Zy(m43`?ZPyBolECdK^F*Rgw*O8?ysB88Bc`{fq=))aT6OdpK|o zm#BFCVhGnIx<EDTatRzM}uk&%|xQlIQN%Bql1^*zJB?>=X^h3oqAgfoRAM;_BM2^sFk~ zE~sW%bY_dEhOuUkerfro61lN!H?Y|4Ktld06;@G)v?F2GJ%=o&=H^}{0OPoKf1|?n z&;*SJ+QWo{)>pQi;rRvmK^fk89(`fD?g4>Bkt(fq4x=tb?NtmRm%aC@xe|6yCu4-H z%x=v{oIMY;Ee`AUv*t-(%V!K0Mj0jiMLV&R0hhXLqaUqovt&HPU2FUtto1Q&;6^$+ zIz(3T|Lx4EU0yQg;&4p{wIw0?cE4Qx{tv*ut^%o|!zs6z0BNawBD#*{@mMs(yKfN* zTT5=4Uf%D81B4+Yf889XtC3+fuk`u#b_gelz?a1IQ&4)^+nLGG;b-#`@_<`fc1}zM zlGkEOd3=|5x{zxd`3UC_Trn+>sdzi27YGPXe6oW5gA_IFy<>^>aU#9 zD}6}sfVrlvawHR6BVOHFSR7i?OO7k=9(*5GTLXRAyr<`2I)e4dyyx8XO0c>2WAxGLsQrzO^j^dsFwRlmz?(sjfk=V_J-Zy^lXYWhw-Y3Gf!p)$sptRrQ z`~E$ICb=-+T6xaV`hRZ^sD)?@%*!C^$YiwECG>ce_5b_~vv@55f3kJbJ7Jn+hhNKS zkCA{0$MP}^cB^`ZK46!0!WgGovsuBVv)1+_qFOE+882@Tcm&JIWr5e_*Q?#5<5wCx zb01}Arg$`dps>$blF{T1j@GIfw{&;ki2wTYi{{V;jTmQ?gd(R8ReLX3D~Nm_(e3*N z@`u_XjCJsq)s~Ec2~Qyl&pX{_OE{&)(qf-?f;TR^_S2mo@ z5l>&HcuVp34A+%Ewlc`dV9B;K@b!>Ybe9NZU3gaanTb-mPvXW=mJyK7ItoS=s3oPr zRz$7*v||PkPJXd^H|zuKsjh`4L}(!*^KuJ7f@y-a#QmgRPnphUSd3jPrXFH@oSLvT zsuNyWLi)h)Kl>tS^L&F+Q{o!H?M(Rmh^Z-mOQ(5K&eS0oqc|9cCJNW3Pr$Cq&^SA~ zPlaun(}b^6C3e$?)63g;MTgT%+b;A?lU>Vm2%tn&vNX(a4O8fNi=C~$T5_DY`IRdi zAYnOtkx>ZoFHd^mm5z@e;zCUVMS~JN{kOV zQHD2%zQ{8|67KFX87@5%#QlFmjC@rjn(iXF_0}nd=ErcW^aO%abBuqa!lYOb(5r5JtA zfJI<#I*=e0h)ng^7e>Ha!&lAMV2?PjB+cKBbi-7R&sk6~pkX(X@Vx#f?3E!ZwCO;D`z& zB^K5;$LmYhx;PC^pw_wKRw^-j-!Jlh{=BLmk8N;G__})=Lh@)hyc|@dqC^-3)w^E{ zT(+{=PG44snfVt;YZ_Tx$}N)7n9+!5qXZ5Qj}YmjkuRgG5LP5Q^8$~HUVtyl7Djd~Qlo)D4%0Kn zimoM{hEtn+3;bmt9&M_-v{6oErgGy8`6HZM^KA#se#O`O#Z74np_Mok#D*DPW?cnf zn{ijB^kMSXVULZzdes#NJBGa3=vSMH%QYo(v@eN}PKob&&Vhzj2XYnx)IrwHOoY)J zbP3M?PVo>xM$RiO521%EPTmN$t=o#Y-TMr6hmp%|XS zF!6mPMo>?ccS@yD&MveKzu{*4MLB}v@M$~bJ|(Y=kCd4-kz_});Bq=T9ZfLSEO;1+ zH)qHQ2f3(qD0=QEBz^QjR&*%$=+j6t%D>Lej=yuOG4FEyV%J~a?vdMoC9)Ml5jg>G zUMEY9;T26$(H_gnh1tADgCp;a2JXD>cS}Shv_JK;qD<@#Cw zh`ZG`o&pwKBxC#TfB7wGTQAPXI?!=5aX93QG3@iPp0$ z4qk>(i~9J1XiY|=Epn2BieTfB2P?R-8Kgon&}m-J@F-p*M4rq)zB^=sZ#{%t-Ja2}ZG zXKp7ngYfUy%zt{q$_MCQTOn;8%Eou2|49xQ;;T-LNRXH4W>mN_4jWG_= z-F=d$5I~eWvxk=F8w++BE~R?%IrI=q9}z4j?&@?+OD8k)?>oCRCKbM4(~|zGgR@$w zQ-6(ueZq;>Gd|^gbF8N^y3BS-D@n$`*tW%6Sx&ZC`%&8&-tCg*I55i&!NTEcLFX1Y!Z_)9 zHSg*r{`iMl1^u~a!P5=^d3t`v3`p!Nre@6BQIt3+znP{jqW^GYFB*6dQ3wHxh$x$S z;(k)7YnhGf{l|sfd0({IM+0J_goU@=Yiov~oVFiy)78#uaioj6XC)4#7o<2Vu2I0+ z@@U2PshS`wfV3*SC?bSuY4g1|q8L70F()b$<%3XQRCB9S{TmCq^K_lZv$yTKjx-h- zrw$(YO7olYnj#VIdmd{GvPoSGtRa}&A4m4N#>lj@HpV&j@Y5k83lJ$D4n64I=bH-R z(FcBsN#pyi*<$lqer)F|6?q*HnbD$7w4Z2HeQ@40dPO!U)YDZ=+4Pl*gDNgQ$~r!! zi_EF98*|oMj;cQJ6iRTFa}=(q0lRH2K*8Yerexyoj(C+cCU_gr@SUjqIN2q!xc zfeR4JyllLj9$6fB(H*a3>0+mNY@lD_C*`T;k}%Ba^KZEFij)rh0N}Wtbwnc-X)R@a zLUNXg6eXydGwcpo)a7qFGAF6hYYwgKeNBV$+{FXV_HP;8F;v{_po@+rc3);-c4l6? z`jJwYI#FUp4I2k(X@7=~rBh%xN<968!}VOuystOA)n$IR8YM(^@47K_-*nQU{8KKc zcNNt}0(#MIgFQ`0$L&2uN;2i~*58=RxzPY6$y6;;BsQDhzIqZ2eB6=0x>9o25P5`< zIlat&Ht3pCo4K+9uWP~r)=dOEsciw`#KN~stP`b?%d{Mb4OaEz;SD_48JPu^ZNxMt zwuly-;g@;5fgHigY?KQe27NzBQUkxI^Sk7SACSBvrt)tysbbIw@1CLyoj}cTP4xc{y=;9WcsUeb1z)12%a>5^HKJBO0|;qM8HeQVmq252Di4hY$}MW|lt5z*n$f zkz&PERVi1v6g8@W6>>3lCG>)iPb2br1tZ~~^qW71ZSU%>3M~)wPT@mFT}QNw_`XQH zztgGV7|DoXtv9!$nXjRZ@L2llr;ReFwab6(80J*^&RM|qF3VVdt~{1GG#1J?L8`fL z7PsWs@p5uW?RDT^YhwacILvy3M*(NxGPhP6n?jc!(!aN0mW~Zj@jmLJ0rtISlbCC$ zumKX1&K}Sv@F|M-7^Od$kBE@p^3Q8NYYZf# zXAc_yspQZ^4uumlGEZ|8d$_Ib#YW1YmtZF492(G%qIgNBWf7e5Wn_qF1uKx^I_MGSedYY5e>`+c zEEnb=~nL|;8VS>>%z<76cxRB&Cn ze=ON3`n@+(KEV)SFwoc-Q`5~1)xxSB)dWGrC~{aANK>uTR>mEO@w=~>aM}-&bBXfs zO&qD+ij-+Arl1W{L5>kP)?lE;mWRZYQJ<=&MiYnH+s9apqg=p}y?0acFC!H9crc>X zymJCE2cwi39>Bm|p2ggl%_y4RSf)W0$MHVvdJEsK^LG>WJ4KN^A+KGQTDi<_Ji+ae zX1f_npXsH6Lb3 zDVt1cc0;2I8LW+;8y^~cKkj@YqwPxz0dbgCSbnoV#FMN|3Qp7jZPE5BMQu90#aQ(MCyC2{P>nR>2 z73HgV$e14k+X$V6ITQhw=}g@Jd2_BQ~wi>NW> zyH=lJ)$kh@yH&YfVO5Wu8Di9jt$dl&)@!;uNECvO~5R3 zn1@>3I{K8LpqxkJpMdrB@U7)tc~5Xk zoF+9O0>>Ml)vZ%O&LK^}k6H|*baghin!bW74N!0V%=a#aU5HMi8pwn^9$(S;tZT>l zYU;*mwi4;9GRxRbZhvJ2M!!*1=8RDBRMzJ{oKzokC3KNUw=ET|69o+Jp=G+Rmh#LG zd52k78C_$p*Ek_S5$je#owJ;RBM#bo9IZHzz2py9zUf) zZL@A89$M{$hXv(+DBWjpgP6max_f5#)st)ZSR-C2{nV2mLuIJs&}Y2 z)#Fkb3tL(~gj1Kk`}rXBHFG{|$39{7)bro|>wd)8;BL0--PvNJt|)_2bhAQk>{Kkg zbtN@Y-c6dh3!LO7Bbt_TS2&Ak+zGrN!k71PYEp7V3-#pP|w00#}R+5{`|P zgMGy;46#06mot3kuPRd>$#ke1SrbPTO~E6nR^%aC3g)=P#b8S37|Fs!`psumqR8~|e>7YB{n5tkRmi=7v~)7D?Ae;3#?73Bu%03S-T!hLRoG7+ zEVFfWlV$M!YRSR+;G_P`ho@y`=|w&e^ALPi54TkF3=71ZW7tKM*7LNPTjH5{=LZYD zWs*EvEm~~utPlTo!hS;xc0$U{*dxGFS0O-hDz0rPt`hVE$e93 zxHIJ4M@ZEHqoXIuzX!_1NKLIXc0zrHg@!>$~=$b&olG(&c ztJ!xZV9p6N*WK=;g0!XbpTD;T4Z1u^l z>~qU3WPG9!kCV7IU@OR>q4ub)k`F1*_0)#C#_($EPbhMhP{2Fvj*lmoFF(NGAH*Jn z^--0V8xd4^HyzV*O}SOQ0L4ahfJcn*SR}w zs9JNazldhCpiht8{GcECKfBPDm9fe0(~0$2n$2`~>fB@KO!IH8+ZHRkhi(MWomWg~ z%lmaV>Wm7?p40!49Eh3)m%=nxZ7CZs|L=f+J!RA`$DfhqS|>X&-TsX$W%LENSX5mN z*WN)savK?!H0S+*Aw3Yg%DPqY<~YwcR~}7*lK=-KOj0o1^NOqFQ90Ry5a^1sVuVJR z^7&KPIias|WIQ;Vhbfc@(H6K(SXrEt^^QwLwM{OPMaJ0zKL5L($Z?w= z{xKVj29(Wed2CYZIm7gxTD6eE&dQa&I)MK00~jW4N)>a1(qf|VPRh^w=U6e@3`K+Y zo@kwuck*l;2`K5zbO(prytwOpfmG~Lgr<*UuCw5Zsvme?5;gEih-m9IeiW^ZLiDaQ zpMD?bTWj!zd_M+~px&2ksTCSY z9{`!F{$T%Or^oPD=5_Ot^_s}@i9q!Eusb+YDpoH6;d4*ZQkR@1rvLIn^cM5oMP-*bQV)2*6UfsI?NEv4|J#ZEmUCe?pvQ z-QE{?6j8HAiZbQT;--Sf>H`ytXpnT!e_a*fkX+(_kHLvX+n$LFw_@=BUg3i2IpsoZ zQ`vCw=5t)<;Q**0eyY#oiG}zh!D|V@|kZ1K8bXc&Too)>CND$8pc#ooY^RguLDXMd?>-B>3W2XcUun zvYb_`KgFIx*vknU8}lF9pFU*%Z|Yhu#o?WSs2^jd>l zb&Z3ZmsH|x@oU9nwJt{6vrSiA!=%JGOzD)jebDS$a_{ogSY16lxxdDBM+#XjrJUGTy8yO5Kzr`1IU>Mqt57$aIUuB0Pms% ze*)B85&hME_$=}x7jVW*EAZD}mXOe*m+X1277Xo1qM&F&f?n!pmD zNBT#V;@b)oA)j-2ZA6!H)wJ;4Z(h2F+2Jwd({*m2@aDcW1er==XE+_8f!t;^wP;hiRf;e3y$O@ZE zGdZ3V1C;e7^s- z$$G^|iN`GH_4CZ#-Be!%V6@g6i6<%yQKikBCE4)WCZQnhZzy13tF(3(f|T7cNHLFb z#}>&W>hsOx{4(v02Jcqarc#*rnfSgq3BJ92#y%6A;gSwu6tVd0>5Wm4WBf%h!s-2YkM^=#C$(u`k$3lHl~z(9vCtN}hj6l}6B%8_)$!bE>Bswv zn=5x)M&#|n;q+mZT6F4Td@CK!hpD}h<=yhd9^u?Xfp7GGCqLxzp&PRl%a{Q!XhPJo zhxbYH2HCf@vKLE6;9MX)W}$QynH8hnl~}6c+3ezRmqOXUDaSPt@m9OMFv6LOU7u!| zE36H-pNk3gTW$IM?{ik^P1o(DC=6#O>`YSyUsorb>?|7u1^cY@Gw*=;6ARsS3sa^l zZ)3@oT1!2V0}5E%Q~8{_uGj)q>w$LA7L&=f?nUJ*$Is>0jL&A<@6Rnxo&Z>bYW_dtMVK$B@N}bS%GZRhY>K<~>JG9to=ymrI2LGLU3m3)2a>0Z z#5YVA;b_uX-bG|DX-*0nL3vROkAl^QW+_G44 zz7@b77nx<5%_7ll^~6yPZ4SOLz+?7eXFe{pMYi7mSdXpBD42Y~%DG3NKlF>ZgoIn} z!Y>(b9nvvNn$o7JI0DJuqI=JBWNB?w1e#ZaoA|kq;t!YXN-*+1<}Np(Ar#blA57s30*cMi)BqgCZ3%FZ*7LBF*ecz?c{BIRPQEZMI$nl(JZ2|n z*P$)bWdPTz!QiXA<8p|ToD3drDa#0{S}J1y~*-7duaLF$*pqf(gRSyuDglDfV^z}vdN zK3bXP7Zi!pZ%&+2R&cS!($MyjVWX8+Dyi~5`_{n|^Jj_-6<&d``JIj{9sPwVbBEsg zp*1fXTri$4Gp98cSVl<$&Wc*>qn{rF#QU@x+qFu6KBAX^bYSAJ_6R=%IO~#jN>7jAdmtUG2}MPdcx7)M$H2vo9$tW1VRS1K1rQ7W zekdVz`qXlW9^1cEO)|TVoZZg-Q8japXjjkebB=gR^-9iiNQ*ilPt46{)t_S9CIB;= ze7}pcK)(y>ckad2&Frk4# zUl+6)y-aD(`o;WIr9ax}>V0NWK+yUt&5~F2Y{*vAJW%ZVw&JBc77GoUlx$TB1Yu%g z&V$##aQ0p`VC*{fjIx$D1>UG8DJMbC`x_H;e><#mK6tIGSTXstaWYu{K3oN#bUy6x8&L&w7n0My+9{T4}_ZoY);Tvoz%IH}u#U?qgHmC0#M}Kn~ z25xsVfeiwucPpKwioHbLn@C5{K2=lB>{yodk8#=gy1JlE;G%N{WwmIwmTMkm&gCB^jpOi`ablrEoYAzIbRRs$F>ky0zr<@2TYSJbQX_8zi%5 zU21J(ZM=>QPOR&h6$to%_NIGv`Ht`(d5rp)*;QIe$ESmngF$>3#`6Nc-=m}ERN5QA zmRwd+wN{%vbB7s2KkqG~Z`D1I1iUDaQ;;?Nd+mMu&cgt`LMIspLE4dJKUh7Xi z=oyg&CjGxGfP;Vj=Ybl|0Fbxjo@#v7!p^$Vt`8~L`{23X@Le>hP~_8;R3UI-0SS@_ z*fi3@z>nBr{oNbz2k*kIR;=Pp6CRL`Pe4d0tjVV`CH>8kHL{Z2^Y6v21Xf;=+;@hT z`pLN|zdqgASB{c5tY*qP zHfGzYi8tc%R>+^_4#eD27%S_aZ1b`!>%x0oMcExc(JG^$(_BxqOh9RD93q8r3aWhu z{o1jB~_eLS%<;boRKN=(MY4bsHbZlm_ew#6wtRJWw#e-a^EQYx4Mm z;7G41hlimod*Jnx*jGn=xR@5L@t6LTP&r7FAtM1 z8yuL$qs(51 zK$r};or!R0xk~WM$fsq4$m6w^3|TvSG*eCRamC{T+PlwhzpnNXm;_9oG^IZ+LvfZ`ihh10D5Nc%W#Q|CQvitmQub@NziWeV2QF z|5@o@oywo+N7i5X||OAEqwEUiPU{1F|9iqXKXl@abw6xtv;WIt-A7(z=HPT zL=3EBeVeq=q|f?zOQ*A841J?n)W>yff-p*Xhn9 zzxC68PA>wm@fRa-Tk0e5Q60DGhnrhENr9yu#qYx)DaN4SUm<(DprR{lmps{vnOE%u z!} z*LDv^*U3BgCK^~o{znqMhpln70!Py&&iWbp)y2g_J#Z&a7lqjAYPY&XR2mDl#t!FQ z*RkCfTNo3CDZd6N^IWlO7=gRLGZ7QI*a;aAJL1mnyBd)gNGUv|kJ0jnh+0|G(sG5S zZ52N3+Mh-)$x@8-ANg!o(C(z!Sk#O!Y7g(@?3VqWXlT7F9vC33SIL|L{@$NK)ePCd z#1AB@xjaM*z|7l;+PglBO7=dPV0BJ+`m&efP_Y#33-hCCOBs(`hJ5a?>qVYxf{t9;Q{Nz$QrJ% z|LdF4BT*ioxcF&L&&z=1ONdYVzt(?u0gDd)*W>|FF0#&!V1wp0yUhBj(|?ajkSKdXjoDrKljBlP@HyYGsnYqlqD1Bti00=^yjbD|Gb%SpT?K076%+hIpJ&+G z5a#A4TnOf`;(MXblGS45sNW!Zv!?mrIMzE6%y?*JjLBprT?0#EZ~^sjrcL9?ZVeeJ16u`v&7Djun|^GWw%PkH)h?C-J)SXN=B$BM+p@Ia}@wVc6l0W@o5omg0~Nf<1PA$%>cPG?gPRznsXN z3%>vSkFQG%0nQ;5P0YO+Y*=w+XW@2V{|{Gh!4zlPgxd~oK>{xjT!Op1ySux) zTW|;jf)ikHPjJ`4-Q9I?4Q^p@IP=vxr)t;!3sXf&w%;=a}3wb@x$?XuanUaKCR^xL0 zIIFF2+D<|6IfxYz3@pPGv;R-bevs7I*!m^k30`fyWjT$n!~viX)M%&vyHJY;y;#Tg z7NU|oW;h$7z3m{ohL@`>%jvLez=r;ImydWMDgt}(B~$FhW!#4?`1MlP8v@Wp|7C z%n2PlLbg?x_~Egz9*I_EjjATngIwza=sWujI!Ov1?r5zxHjLGU>V>}Of?fMD?@tgW z4_SJ@r%&-kGd}(Hcn*lT*wQzfIiIP^?f7yCzc;_K@7trPW~)Iq`?v@Dgp9|*00>Q9 z_<~y?#r!+>KxqqG+ARpG3lT_K{p;vZBfgC){zC-iuP{882Rhr;41~XTYNxj#JGMJ4 za-Ola^VBzHxyCT|$wNd1_Na~=h=@M3A5`MiWa^+8Ovd7Ed>lx2{bHt6_zv`Yf4KkG zXTEd>D1H!q1k8A~80DRvonCzFdCBd1e?GJG#A_!P8$%Ecr7FI{R>YQ68ycfEa_QcX z3e=oEWR=zx2_m5jTSHfxs5MOlkNs)680}+Rh8@{-b3!0DZmTYr_AKODVF69*d6M1d zBsp`ha`u3DEnGh+ow8dZ=bQjq{rjbrPNZK(#a%^n702T~P9FSy9p1gBT}8Gu+|vY( zuMD?X704+hS7dr%3Jy>%f+V`DU-qv8YL7o={T{m~UX4X&5*_>aUZ=Q#T%x~@&RP(G z!C^u70V`_HEJOnjNoj;RJUtIHN*ANBDQPg&thqlu^9@GE!sBTSwzVY3F#iRAxG5YS zr#o(AyuLHS6mtNIKZ!^>z)q^|(!7V#ZXHZ1LKD1F)lX|3AIm?+h)gd^Jt-WgTe5Dk zE6rhWrmgkUaKd_uCK60shq#=PDZ%=H;y@u3XV3+hD06kM?L=)6Bj3Im4xk{N$qBNF z5Z^F%sO|0^=js2$$w@lQHBr^*hq{m;-{I>$KW!S`Xpf~TjkCbC?ZL#_1?!vzyASm< zxleqT;=#X?Vt^wfVB7CMci^!36Bv}4mtRjju9f?fU)vq=h+$2~IM?~!@vBY?3(3+4 zSEURiZTjm^IYpO71QvR`Jz`3`-96akB%^^)<=bE!pAx-2BJ;xZRk>*TZ`j9C2jj34 z%KhA*;m_x$$JV$1al=pty**?*po~sTZ8k?ONJt;9M4JVg!UJWldwB(TcEn05aM1w@ z+C2Qk&Cy9^B%;KPmOngsFIP{}Y_b!k^@3Frs>|s>w4jhtU9CS1Caz+pPu< z7z?)AD9H_$?rN^UxSu%{>0(^#*iULtuu-9UQMMki=s!%NI=~jo^IVqcHHqM6aLO{6 zq)(F^&2w?chQhOUl(Z&OA>5rT*UEQpE; zVnYqrzOT5n1MYT|1pU9%(D%1FQV6cX=HN~@F?3>8)#TMp5e0n8BJ&N_0Y~0*^K2kJ zV)VZ7lMfurW}lB&D|KvW59;auh(mQo`tj=8oo1sd8t$W@Li{s#ws^tSBCgy&5xGd` zXVOtg)UdWvE`BR1)(PXszmVI%VS=ddt!J>QuO$hxZb32mo&c!@PCHgm)2;bkD2b34 zvfD`oTn6NF%`xBsn^f0#gMoqJ7Xqewk4`fDlzTU-+Pr1Z$E>R`@BM22ib-})4Tyfv zEn-IGZE`E%O1Q)K=J!419+pW*KWU*FAXcyJUjxy)76&y8hwZNIAatUMibzW4@T?K9&-FFU_? zAHMyD$L7%5L~hmU(0JRJnE>m;D2RiN0tdq%4_{K|Av1R`NH?AN{#iBeLEA;|_{v+4 zMPtO5?=-G_sbaaWM46pWBBu|c6cns*3J>K<+uz@|WWT}vGQo(R%I=K*&s|?~O!07c zy>!|A)~xXpov@Mj)5^he3tZ2N)ILi}ixoOGjKbDI{7=Mv*c7wLO{wtuRxK@#Bon~sTBgW@hKOw?5AG5YlP+gk~GQRfc9HMktfh_sl zj#lLgAr^SG4~eub#}O&i)9OVP{CsO1y~NxBkqn>vl|?r zFbB)-RS&^#t$76gC}QfP<3)#Bgh-3?2MV!dX(mi^NHRA1O8tc#f&;pb`lI&NTi7kI zLbHc9hpV7?ebC7qQClWLJ@q>czGTs|8s*^9Z-qc*cJgYr zl!s4E)X{Ae^;-B3 zQ{w4i-dH4nt_|ev07)&aN_%?gGs;7|u30T;_($jc(p+*Zs^G)y#m`yJU+r3zr+ga9 zTpK);*mSgO>d_r1oJUe@41FT1P#cHFJ>*f z4?D&aAKi$LF!(Q}WhaLUItQ4w!!FnrisMhArdE=;B?aQ8@IcR z?Nu-7t(Z;*?sR%KFY|WRe+W0AUb!Z&h|lMv75vwDgb~#?M1Uw)Uw96xE_dXxr+vG{ zPc(y+FDJv(sb5hvx!IHq_|l!XIP%`uJbhkQ2N+29$Br#)AZrI;KVQ$rW$L!^R1-6IKkF{`$= zce6^94SWBT!1WxP!EZ9ichz;c1NORFk@osdk>r}X?Lw#d^G8{-FRGpPE}A_BiS$fP z|7p^cz)CM#8vzEDrR8%@fG&#d&G^g(IKEnf!RLGh^WsX+80*j8XU?1L-jEH?nKj1R z?wAupVRAjdEFTM7-n}xQ_#ilE!xs2);3xnw`pObyf|wutT>kdb^UCAnMq={JN01D%O@~&=s8&eM>rfiq4yeXcZB?bpE$z03%6mu23LZ0}30X)2}xbHca z(BH10u-usQnRv{~1Gn&i=)x7*foDjCeaG_$cEMuOj@q+8=zO4rr2WyEC*A-1mhG~@ zDbS~uBc^SL2O&WM$b|V5rkS%l{l%&aAOp(;)2br3U|MJ~$3@{evt4;@P zRt{Et)FRN`gw0YKr@U*S7q?|9^@cJDdU}j*y-22z2=beS|M}cWY`u0l#SOAFj2Dlv z^1I$5=3leF3ZAzLvV6lDQt2H@v90ZHSn@g7b8Oj}YxAZ)8Z8iQ^PS+)l6JnT;R1Id zdBzG?&dQa0g=z@Irpb3kD#s5|5DYE_fr~cVxy@E;8bh7NdX;@sy{GX6dTA4d(k+tI zqmUZrU$Izz751tf&{4qRWwK%NrG(?wg_G5gHxapI}|N2Zl3Y}a=1r%3g`H!wv zj&;x!+JqaspIz|?2GqdeFSN`-Z*VAnyLINsvc31?U)D>u%;vEHM^5p#W~q3RhN8yM zGBJh#z2zq7=a`ZsHJnIU^_j-QBXVzX017I9B#g8qFpmoM5MxiTVhwqFH54_0Lmy0? z+$qaz+~(h&WvU$Qq7aydf%?~;xH9Db zj^XWNE&B@?pl}(qi~6!NL6^CWsU`p@xEm2IEc8N8X%Pod3#A7UsAbiI!#P34HIsR3 z@rW{1;4JVBk6ecfDVLJDt&`@7vY~d!#AlBWY_}I^YO$~ED?((_%GKdtjDMLa^0Ko} z|MFHypWPR0F5@35+}J!D{5F9afbH24qaoKuKvq=T@?SyG4W(4TVo482`J%YE% zp2+f^JP`0$p!V;fH zujO@7JWj^!%om2s6D5(Of3=73yM3wC3BaA0!2~j=N@T+&^X)1e?p+7ai;ay@w9>XF zJ;T0sdhe$hcLx%vU44C-FctCGkn;1(*ty(xb?tnj*`JdE2#e5(2{FcNeHS6Ex_OdU zSegpgc=_3LIrH-JYLdCao%v%@`k1NzXMz{9L!u<%`$)Oq zw^gN1b;GcBJcdvVV6~%uNc+p7tR9;E%TLFvh_pZ!1T}-GhU@T7>Z}C8;%^XWRW%Su z_xQNu*AX8%|9Gx2F;&*!&3#Qeeo)Qq!21FN1mHM6)%_das_UXgFJ`vyBwF|-Sbhc* zUEp)UqwRB>#+Ms-n%5JwvB;&7c$L|Ei@*xgthy4MRKEVvf&dKk-+p+{3)*{`9+i9) z5_Pe!C!U5~GSGCHdp-vvYQzfC6Obi3pmwYqdHU*Eqz8G)NC=a*d#qMry%0y7G1|DJI= z>#{Q2DeMHqgPR$Hd`^{U8D4FE&ftQd#4}SjyPRzcTU@NOs(<5l%Y zz=q%WviKPmr-kicF{#O^$*Y0yxEW=z@b`}G^jHs{vQprGpTk&J1aO$xQoDIziugUqOl|=w5G66 zsaK1YZ-gx@F5VSqQ`%Q>npc~n%pHXRkoSpDg=(Cx*4{j4L;nly1IhNg1_MmRP8RqB zt`gnoVCb4ZJs6TuU6>*QEqt=;?KG8>E&`guB0|!*y+^9he-&Ahe=6W|%vN;OvwXXk z7DGvCd3yXEnf&!oro+WwLTW|W=OnPUE5vLuIOG#2XF(>c5cwt8B+f^(O}HCh31F9C7ct5(}_LZ+}t~lkYH2SVYb7aK# zI+hdkxRqnv9xZ?K_~p&Kf0-Ay*O@(Fm!R`V*x1ruKlC^g76{b6aoM@Yxn?H)Igk*{ zWVYUxQCe&7S&MbSUyEIj)~^wojODyp@{8{GY5|3hg} z+Jv4=R^XH1I~N)5zV1i!B@K-HHjRkSA=ZW~G+J!ypm=H7ml^P?35xCB(<8(q6kEzJ$)i7{ya|Ww`tF z3N|}6*f<=XnEQU>+N@R+E1P@KwU6GlTt=B;Kk!d?7?Yp)O>QqnCS*roHH8b<;F0th z2O%jqDK)OpeHtV)r{KJo*;{QISJ59rLHw`pKSu`!9+jYR)7HudWx>Duu1*AEg>C4h z1NQFigLc_A9i~{y^%{NR8^*Tyn_rJ=*JUCZRY8&MGpLM+eePFV6qyS{v8?e#M4P-4>_H9V!|4C(~c9otgt}ZKnChP_G5mbxGt=^Om zy1Z!R^F|XpoaWULo~HO9_USU7KAY;mW}5vZ@wfYb4TN~A(q+tt2mb*`t+0?-dF`0I z@B4;+=&$tZMS3Uhrp86+e|pktw5zC=A}S%gtGK0kS>MkJ*iDt$Z9K)y4YeEHsA~d~hTW%6Qp=2FAGt5xx z#C@T488G-XV1Smv6Agp&zSETEP>g~7(bNI(|TS?5NFA_Nb9%Hg%s?)d{D+d>b zm3cx122TJRg7r#LZxNQ5wp-71*>{}}MkdqvEZg zE5h&RZb;7Xpox|%$ptn(NW<(!yF4h`HK(~fR)?*hu zz816ZZM}-{~wTVSW`3V zV#6b23zjS)hAl3hy_z~aTOtI1jr=QW0}cj`k89qb63+Cw4vXaO1Z|o7q5|HNI9@-+ zCAD#A_vLL(an&f);e+HFCAo;^8OG2*@vFY)3B(8N@BEn08OyHK(#3dSdf*ebaKAgo zpV@dxPt4XjX7P}adG1m}dQdsE^&4ujWX+G@iBKYwL8mrdf%5kg3U84S5NENLr)`(+ z5xq|6Bv8`4L<)0i<^*T&HjM#hTRbQnT2Mjvsz)#h)oy3>w?ZDE07Rz2h=9(l*`M?& zUg|>#|NY6!{^47qD(ttV&nalS57C9{_pD;&9hG2&@(ad5BC(VCT|vn1hmhm3$^%%= zKXvF%zf4HSTJ^lVDU6}XuVNqagr5s>wPQDKTSAGpPsBa6TK}3&*0|)@0$@9t2pUz9 z7-inOq;A;oBc^eC?vzZ@{ciUJ;Nq;)>c2l&1H9&rx=TKlR zG;?Q|{p%toU&1IRIEek-m2LOfB`uO8{w^CeM~|spQ{m zfsCNDq;T0jr=%!v)`{hhbotfws#6q+mx#4(7z)IE+Ob8I?@;W;7?x1?b-X60W5I9oOoMw?0_ym)Cqod3sJ%**rHmLq6vdlQf-sUS#Hv( z^w{cl+4a8p4HDa;vonNxXVf{giB4y36+685PfEa2AssEBl(6MPhvdW zcgrC)hfqZ%R(OwBbGZBad1nDnFr;HUo{s$#3?SxSaqY&C=PeD_emEv{r+XUlC3XZr8C$9a`V4Du`A@gFV^gx~*)I0x5G zo&|S#E~Xcu&}iI(TU_AUO&cs_6Z>wwd!gP3fEj7MvtdiWX7kVM3~S36S`8yviyEnv z@e)aA5!XKT@$FhzV4zlcUp>N87jFS@ywJ)XS4Y>RcO*^7@f1b>%#Q6nbuQ8*)b%Wt zR}zH2QxBpsU#2Ix-4>?BN}BmD*rPWVTZ;RUm#zAhJApK%jMWtB{V~t}O^Kyw{Ogk* z$9(;8=+CJG<)!0^Th8+FtEPNF@*^KKe3}+dP68gmRQu8% zyO!;bZQAq26PN6Xin{ZD25@5~hN=r=wS)GkP8G&ld1E+aZbaDUUE*gmsCjNn0_3vf zgXeYD2hTP~Zq&Ktc)T6}1LQczuRX4p8*N#tWTU1}fBI68G9IdD96Kl_ZxYdDKP@T< zH?Sb}Ne#vAFU?jC;HQAWoSpqo{GtxB^nXEa(shq8#P&>#{hsRFXqZu6FrBD#95GXU zNZi@h(D#`M@u<4easARuMSuG`1Kpg4V{FClzet!k4}c;^bs2oEJZ|Oz^TH{6so@g9 z+@3m1(XA}1iHoQa@TfHR40{Q~eiu7n=3a$R_^1Z|+gH^prfVq&}y{Iwq zQUp*zF8~E9YBu?TWKQYAEn0nGG%(-?Tiluaj%juuJ`_aPXP4^Le?ONHso`jt->g>K zlD)UQj>5;mk3jMApBcr54uh=yXQ^|n{@U?I@3Y2TpYgiX=0N*W7fL;L8IE7Hbm}>f zb1o5ImmLE`kJMqL)Dr&!b?8Q6f2!V}whA?8c=TUg$@4c|pxRE~+HBGdzj&nW|I{>G zG`1-)DSrl6c~ld%*|UmQ;tIf8_5Pp>3QS}1JRqmhC!1V5i3P-wT!b#Dzkpi^XR#T6 zew31>{1I`ylHGT6TIbpQVzzDByl7st*-B!;)LXgpU#N!DI!OD|`suTH?-|46j|%1< zwV7-hcw&QjkUl){(rg`Uollxq2VG>fw$@p%Xb=c+`1ZZ)KK9o|=p8e!pv79I+W~+} z?oGuETY27|a_Co=5c)F|R%Ryt+j8deI%jtD{*rON$-V9<*IUH}gl&Tl#f~Rr7T~2} zl&9|Veh8+mCJ-{5j++6up@sYW^R3P0Cu;Uw;jG5dJbZq2ax9x{dQ%;7`tW2Q?kAo! z@!a7=Tf?&4$!vs!%+Xe3d1J2js;!pTaykX|oDzM?H`%OU>4)Bh#& z=NVnK6ujYlTS8eORdH-qyA2PcfJVX;l?vtCUm5BzbNdCipYHHc(#hk5%}fK|39>{p zeg7JncYM17>6!!&kp}%!pRiWK_T4{byKM6(&vu;&zEauRPjpQWzPi+P(Ku4ilHBZc zpGY7PMD1BH&52f5Rz}~SVE})eH-bVw8Yin!bAD2PcJEL=q$Ek5aW&1Pwep{F-c81q z9KO_h@)CB~<*6<7Iy!e23_eZXbV4*EHjbY2Y12MDoQLX&zX@3hFHiyM(j^UMT;ta7 zSf|!~#0Kvx@5u8<;Q9U*KwC)*W8Yy3zreg#k@B3_B%Gd0+>vNm=5bl%y^!LZZs4Qp zm6S(-)(I76h)T~}{qT2dv6E8W4^wT*ZCvz?Kio~3oM9T795LFY z1xPG?tiS@XQYvkk`{&BsL$SqFqOfxNs$aY!NnSgL-fzefc1X(LRPCj8H1raD<`BVc z0lC!yKji-|b3Mk`oDY_xbo+l>cjq$lN3yN1_fM&&bM;D*R#vE$Bn}90o6lSQW$xOO zgkAu&cho6{TOVyS0F2S$XH5ujQYj@h$t|>*?Xo4}x3wxOHINfVnx5=c8FvVU|17}} z;_}uzo~<(P8k+KD9Up61pJ(E7oLsJvZ}hI5FwW>Zw~QPzbDYT8>|Ly==5)vnQa>Zf zs1xTBj2t9I?_;gmW@7!i?SXvehTlzEoumEZ`I&89!7bSgTUQ6K!HLVVp@EwOg9h?N z@t2`JZJS2j3LXrU6LNvnWz40~h8K&R?ac<%bQOkhdC=O~8Q)6IY6=UiP^)LC ztndOPa8>;y-a$HsaR^SUy}_~_vG_bWTXJ!J!qVYp^Tn-hP^B5z+cGGTC9Pq6PbVY; z_Y2Z+yaE*Hcm|ib{yiC(koFLyGO`e872bDrdAVqOCeylJS;~0j`EP_@EDO1$h=W$xgUuo2 z{jQ2cbio#1Z}ixF`uS|-)Op78(C26{G*>Xg8LXnh*wS2H?5 z1(r_wxYYSLMjTw{&}$MZ1a$i&(7g-^Ybs;UXz0Jg<9#owle#qUx6fo9QGmaX7eh07c8tKv%IVW z5GN8iETTX8TD|tV-(`h}8I?vZPVXsR_SBH}AyLL%c=c&8!~4H23{l8?uK1f$O_aXb zlob2=O>IO)OUZ>4Gc$l$+7r zm3XrMvW)rCYGmXJ1}z0YK?JdiMD3RtE8IEMj<}*>+is1tWh^|e`a1-C+{B;m-lT0e zI#}(mE+tPd1Am)6Z-N)jZlTe*==({c&*3<(?VgT_iOc^E+nCI6?F6Zv-cl`iwD9wv zsJfN)C<+JcZa^EwG4`Y%jLD)hH4m^r7L!(I+Zm$o+A&TTkZHT^*SmpibS4^S_{7mI< zs@$C22BU)=^aUE-mMc@PaK>oj~Y@^UnKeQQr5%=i~AEP+bo0NKk?q8%+w3tI?9W6n@$E~xf8^GV$7+;mp1ZuCL(1iA2K)40p#BT(FB z#n?NR#e)B2>#TnLA>^xe8}l_|W#^=dj8mW=u+IPOQc2%alNGQ~7eB(`jC^J7$sS5A z7ckMVr(?=t+Z-zA&5f1046s|Y7Q;Z7cV*ApMIG=J$;Rx=x2|JLD9Aln<}vsW5$y{z ze3PCETBDrRZf_y@mGwJgUkT%T#WY=fQ3STF9@+-3Bs7Mq6PW!`mIn;bs@aE0gZ^OS z@CAeY6Q6b9D94AO43qr4s%1R|a~*_+uhKJ~=!~b+ z@iL)dkH|KIW9d$IR>>sO42t>z-VmA@fUd9)zPxtQcag{P&W@%&G}?`YvcXB$X1vrN z@1!=C({;cuX|vmAIWYX$nXFz%LhzuW+AjZ->V6w$0UiF`RLpCjqu80n*|QS3l?RT6 zWpYnPjjYv&m8z(;lJxpC5|pgdMiJVC6u#Y@ zV%{n?ES0z$h9>g?;i+O|Pl9P&x4%U$&8ty*y%|;O*{Hx2NPWOmsq+OQi=8BL`e=n} zcnXTCEN%t2ZTVaivcDHJz@bA699@w91!PP zztri%08Ik)LzDfpmDJ$G~4^u{=BSa^@8d_95rn8S(i z7ShBno-|hN&}oNN1HE~|?_w^lFxshbOGxbpml+bP>M9d~B2wbI7Jf5#DHu+3>hsI>047YTND~pSi=Lru zHa8E?`dMw)<>Z#skImUxtc_~f>$*jRiU2a2=SWH#)0O4}%Mb7ab-Jx}N>eIpQh4mE z-qzOtAT2AO@z39E3vccq;GR0u*FEPPMXmkZ21E-Nzl2ZYf9E}66|I(ze@?`t{3;1Z zm}Y8jYkc0n#U4bSrZ+Ff0yI`Y*}u5#78tZzE^u+I?&B&psIu#R8K*e0pg$9hTvS#l zLVr#4cGvD|Tpj%I7%B{+UGTXm13kA(tSm38+ut_v=cQ>yb_6pDvT%xbUp}pj$g7OV znw;kJfI2^t;R8E#vV*?BP^Y`zc6SB|qA)FrzIhO+J^OGdbvqKMDWnZ!_q-|2T?GLb z6QFt5{|7CokUDjv6dcfMnP8WXyuU&pD!T839r~Jz56#(374O|?k=QBx4=%RW4LgU* zILdgao(pz#%GL$!v*sUfAN*+coSgyy${~a{$mCtN^LA`DyT0O2I)01r>-;8f*^Aj@ zOUTs+kJ(7pQ59w7;O*S?+=|+=AOPl-La5$+J^1F7%EmL(4l^3rFy;Z46rP%zM+`9~ zQo{mtIzDW{z#_;LFk;XZY+hX^uE@^Y2IOi<+o`HqLUd zR8JuuPDC>T$cDtmhr={{P>=-6%7 zxoOU}FSb0nB>IvJ@UuchCMDbg?OKHby>(3E|oA^=u zf~9$O=<%P907TMO`wmq5M_h@S-d1!mN}({cHg>TxIl_|YCw|axz7Za%YUv#Iyi&C> z645tre5Z?n!kQ}$o>)GCbkcJzd654~X}gS;R?ldS(>(2YMkEV*P|V!N*s2w6ydM3eSWN7)guX6 zj43GGs0XX2pqjYuII}#UtLc(H4NGVIw*^C})0^|CiisH{tCKp{;$cT*euleZ(0|}; zdqKXh$WTDVCT~^}7Al$#MJmE`%%)bU@LKnyv z?N?EN#cUMc8Gy8TdR|EDGCAKQ?UKpiX-<+(_hQai-30(ZyWD@W$Em+!#q+;0^E@&$ zQ@50}B1mXs?};t6vJ>TwSTWm-U?i^fye5jg5G&UdmW%h^$RoGhTxx6Bv0l|Sq??w7 z;j_TqwQzC4-uzx!w>+L!HXqhD%g>)_8nf$BmPI-ra@Gc2MKgfwnbDl3l!{LjJr7hr zB;u_7L2}oUotUpj0Fcz2(alEwP-jIY6W+#l>Z&5fsN8;06L2sb@^qXJK1S-UXUqX-)x6b(g>!^NMC|E5{wT)^zdt=?g#7LI1a3+R zw>ypte*D{Dbyjhaw+%mU!|D5pb|BNEE9&5gsO7*R)~b`EXJmVhv9`9Hx-6<`qfel( z17F4kH}(vFgTSYe3mF_|pOpFO^swbbY`p`3naQgmsSK(lcBmc8p0T_=IoKAdNi4Mt z5q{dxxOr_md=sYL0Rz{QPmjQMbkr>a0V024OdbpKKLD|i-V~Fv52@|fEpA}i=>TTu zBIYFwwB!o1szfZEx(b3`Awh8U{^mfScAM>~5!NI&{mM^-brumPE zgA2zyp9}2ELHD1V8$4FdU2w~S>&}v#Uv+@S7SgRn0aiiv&RY_z84*YV?o{Ryskks1 zuzYR*W%S)An~<3U7Ak`!W*&cetA46m4J*QpFP50x)d3#rYiom+3Y)3K$_eK$6-GN4 z$MviFdVp}fVb-`c=h~!VU!w{+^}aZ|JGD~bhf)IK4Lqp-?Zn{y?5ohE_QXaDrh2bv zho#^2ey)MTq>GORX0o24g=$DkUo&mNz@|vp`-{-uk|~M_Z6|#So9@?QPC#5eL}Typ zF`rJzwQK%bYFHKWBSMag#Iv8W5-!J}rDhf+8hPd;XUwR;Sxwws-r6(@WbrQMZZ?%I z6Gmk-dmEvdE|ymq4_ovbpAf^gV@*P0jscQ2bJ~~1i%$#l2)OF9VzCUXU6D!?xs0x} zPeH%Mzk^09RN#|cC9pnJYQq4>si5?28NkF{puQYBjBvSk_*pTFVqCY5{FuVYMZ6+9 z6C-6E$WbFi+r<)o)?}UQdAt^YPMfN^Tf^)-Xk1D<_&o&4ZW8KDyt}0_Ls2fiMfI&a zJ=>j{K4;*IAh(E^ar4D^M zRnn63fM)+h-zmHEPR^c&IM3+=NHX(fZF;)+}f#khGicb zzT_WCgGhT=&A*J4O)INKh`S@EWAn`ajK9u(9!Z9CmW?0$uG%hpj9l~XHRT3AN{{(%#R$`d=kZ$B67zyJqUVu$Nd0;<>B z=VAC9calx2%!J=de|hsI4~6_ZM{?R1Cv5F1B7#+y3Tf+8B z&jvx4!(Rr-wx~r-3kU+xlvmUP&Zc;C*T7jzj!xX-8!FT1$|p&s2Z2;Gm1*$6v`OP} z`Ql7IYW;HeA>S26a8vb~QS0W$cLM(u<8Bw9TOV9<$MQp)0_W_c?+})KKKD}kbP-=6 zZ9x~+OHvt0dLm8;Eu=kk-UG&kMe>d5ieRrA>W_667vM2jSzvIR-{`&4kWag zJP!y!wdNHn7Qf`L@);tYO zga6MdPIsNp#vtS6<|vCXgd|q7W@j&~yXLJ{@208MsS^7BR^u*y2i~i=q;&mkN((r% z8Pw23^h!lQ>bRa=Y#Gm_1rDqEHL|q4qwjyrm|}77F5`;``d$xIRy`@p3%t&jp*ATC zO#kND7bZdrh~A6BaiX(052ha#$jx91XhO8|_Xs3|v zsSwDsqB@#S`1r^|6)q3b-~V3LqSM9q7jp^ha-lHjY8lYye7#ko_Aq9aAg-h2cOV%t zIjIm2<>r4l7=WW75?4GMtoIT0>m*V2Bk-ML*g^Y-0Wgl#P90Efb{}7MNhn0oaB{qX zr(O7hAl%;~TTIx*jz?RQJAQ7rZ10aO71|VIY0q#%is#0G8RHSR_M6l1K^$}V zy8ybm%+hOEU=|W`3U`&wzwd}Lp zA+z}TC83uZsi{}428zM*OfkI^l0_(4Ue~o_X1C!fECm`3b#}R0|6P!)<;d zghk-`{X3s`kH%a(7tlH^;I6@_vpW@h_fp~XRzl2Z^0{HdV!elmp39Y-3`Sz|F8r0w zHug~EK;yXAM&SH$I?A2#NBh_OjgQ#6)A9QtSE#d8^*Y*vtZFcuRV4{Y_NF&$DCf?1`** zI@3OMnAL$c{$bJY3Kz_j|p&z)oT`4 z*Wxpohgb0LOX&PG6vfINfU%F8!PrSLBlgGwvZogo?bkk^?6-TANEw|PDF6=#q){Gy zsv$+~PduUX77p7Vtm#)$WN+{J@7JR4h41A7OCKBs|5lbxI10STo}SXnwqO31llc9g zmDdKQTC$^2P=sRc-$%=y5Z~fE&hfURfUHLvnru^iHHFDkd$_FwXVfVy9nK8qsc`Q} z)fvf+b^DK%kAN|ieq)VH(@(C-nO(OIf4cq|z>#jx8)ft=Il!Z*p_TrItmU(l2_~jt z+E{i0G{VssP<+|?hh7(m5YKa0{MBk_T86nDa}Xl{)CgX=qzaQv33in2tJZih}&agivT8wiz+Onz|jF{oSG8hYeO*qopSk{qf?`X$! z`8)}wNULEQyCPFFRJBX?mqldE`q87!6ZJ8p1}nr*%y&_@EG9K7<>#Q67*I}Thw@q zXf7x<66*P)IeCg2TUCGlIPABdw79&-cwjoP0mI`rHHx9)l$=Q(TJIeo2?g}t= zYz`0nUC)1GgMYr4_u^zrj8Pl;A$Q~F*;;^f~cwvph*Qi?`M1ceylWQv)~Ln zRf2PDbAIro&lQk$@n>NQR9Qc7670_{wG#nCK<~u$4l_Ja3^lBOGE$23$c4z5xkyW+ z!ArjI~AX<+t!ulA4+ZYh^8=p~n-@hvY zkvYA3fI?vVu(QXr+v(e-c9DFsH4I5@iL<}t*QtuWEp7!p80Wy}jKG7ypG`j?yglCJ zD$dHxmMT*cG3}~-uHCMW`-@$%m6Y@|?anvLLuDc}MjhUjV;H0YVWoY4uIWi&t{wXB zHYNaRth;{L=+s`GgZE5iB_p8zow zbn198{D@#FXhKo~%_cqi)5*V;&A^RCjhd!)AH0sxxi*N_t|* z4{WpklBZTY`gQyGyvf4<#Q)Hc-2K=~rYtQ_&W!d;21pMbnlLvVx$9TgZqBP{WDuhi zCgIrL29CTRKBS*-9EvbbGKcb(!B0oY^fSa3e8&DRXq$kr^oe}JdvX{f2zval-gZZ!7BR>=E{F zYlKC$d}zi~QrvA3S2l4POAI|TXp}y;yBBUazlF1(_2n?9vyKi$tm#D4s51vr-ZM7N zHP9mj(lsSBJpMwiKdCcxLZ9f23^2%+y+Ev)G&Cr6vZEwQ$@V(C%&$wBlb8Dq#{vF* z&cryT*}nFx>1YR?Wnf%!;TiznszumnCK^si zFGiC7*;%XRk$G*a`2Pb7LG-?SqO!TUKY|G+n3UfEN+M>S#2q-U$T1(Qt1q>x>SE#u zuA+WPN6&TW3HJtTIey5*g9X00m82=9c>R4-*55mcN4*FO)GWJpebR2W^;-YrxD{rH zF@c0!y%E{1Dz!&<;1LV=(*+_b&yeO%lxmqGkZxRyVYEbeu3HDG?l`kB-Y8F$Oyv=% zi{(!yDhEDlw{+vHXiz*pV zk_MvyrNCTPH)^cMyMPP2Icx*{^of=kJd)A(`$w#^ea23oD7V8m%B=wYoIE@vZeBBH zkM16{t&e7)^;H2UUcPnRiQ|+2Q{^K!k;QGhGni>jqgl2At;VgZt8DM?JbUW7Fq%q$ z#emEa5u~MTYU|1EJ@~D{EN)AkTf7>Sh(ft`Auc5a@fCgW{s(sI^eMY}^QHr8_CK@V z_C2-FwmrHH?{C|jiJ8pI?&_~e3Hv^hbjtm7@yVjgm(Qx-r$*+uwY3e?$TN2A*m3f8 z5OcxnIG5PP$B|vOea8;lv3&>cvl7dOtXn2>nqw`wB|l>!O0x8pyvwzfWXCI4RPp5*JxzweTO>R&-^SM~o* z0HxIak$QaBgTAAKh-^TwGWcrY|^TSY_*u@ z$>c3bLkTd+X(%PW+Nx;&1Fq&Gnxi^S9M&~jq)I`+0i^uUv|QRRQLwDRftVw9K6ggs zvpseh;_h=zbGV>q<%t$UI6ZE)IT5R`L=$1X%xbD^? zG)!6omhyN~E(FSWV55TEV|a$@6U-}^XeKfwc?(FI9-nq02hFbRJn|jZf;tn=bZAga zLehOF#zGU#IPoj-y8{!&roI7dk!l&z%;Q<*+0;QX<*&)L4V%+!BVo(NG~2u$SxSol znaxbkz@;N@r;ugjz{v#Hh-BmlyE&V>x%S7&V6QeO5KxUEu>r_Bb2_d(=&{tl1N599 z98f|a>Z^Wp@<}?e6rdyxB>_sAw24gW>)44o`{0vVJ9?tuX(&yiarDH7dRtRpWu0iK zb@t7paY&yV9k8q%Gz=?BF_+7+Nw|m)2DCOx@N^ad2o@dn1Z{YRwj5|E zsca51)Wn{)^4+hImI9Onva1gSV>cB1lx8APF0-M53F~Ydw9(;dlLxZt$sBv{UyJRZ zKf(4kvDFuKSbf7SK#&}J?wNIHX;#_{nq5PK07@rr*pcHm?83EtJJFgCxC&nycDv8) z$h5!tb=daojaYVWHsgWvk-7!FA?OvlrhcKyPig>?y$2=~J$XwUFKA99SAiL)PM)&Q zKKm3?$YYM6TfA@^H*Q2Da;v@Y!VC8N^Uu5dhzy(L-C|phOzn5RpWOAx#LGl2LjM=G zhX<5qdD#h6YHArK4B6oDEWChl;9btJFOKHg<$mmZ;k?QrS)u z^rQ{XPTAwtWA@apF?$TIteub5!aG;!#$K793s@KboP@JbZ_139kKgNDQdx9(*Onab zt_vI_H;>e7%g0}mfa>43sc!-(rM9os<1anvJ3QgrtbeB8e}|9w*(9}4|I2{VcT(p+ zD4^skQzZ#H$x@>sgD)>C-)a0lx%57rAPtvV(&hW#zYsZjpiX4Pr|I`TZgQSpnCBAZT4tWWV~=YQie0ZZIGr$Ys2Mg3k7NJAE>0 zCr*yq;ZvP<^wt1*0!RQ%NYBs1ds3dg^!TK`{?afUH<@r?RFNhN7tAQaGP`3EtG^-m zlfp5fRVr9wr?D;(7$Kdei`E0W?267>QNW0cLiuB8s!YMDGKMK$2Ruq09bv{zBYhc^~p&V;WL&4w?utKwKcA+u#MYuY}1ZxE5)3zyinRUXde}_bOYSD(>`wf z{g9eYp%F2b!586iYj2&fF8F;q2y)#$1fLW-HF!kJw>%a(#qcbZVD474!d$3ATdA@< zY-JVFS_&frIGoU?$;#2fLmFMGhoBy#b7`1y$+HylO#n)Prh+E+FJfIEnlqfs=z zVvqsjb}c>K5gEDs>rYUvi|PK$PsSLW!{|MSyu+&l?5||_bCbl0CP;wsLAmkqT0ld6<(ASGW`()EU z*TfK^_L8J(IW|8-+na{lE5nhiA3Z*29|}-{L+RYrRvU#AY0v6<`ewCt_nCDuq;!w= zTi;l}l`tOF0Vt)10u7~Mv=h5$=|gD6J=r*H+a4LQ{m)d}v-_(p4^7HAAf-Ur2z4Bt zO|v1)V>{a9<*dm*`lQL)(Z*{+&FPs(>g^XVZ$e|E)YiboRVIza_%wM1_(tOrCN5V9 z5p%mXk_srPp$6TPA8aaYP~f}ICtV8#1Gvs4Hnc=!7ORB#Ps`+df^Upp()3~$$9a`k zanQCJ7-c-_Mw4#_FNbA-y~TFq(=0pkd8XZLAF(UlBUX?xYL&$!_QoG3W-OxI+trxb+uNBieJ$7lZ%5a__w%8 z06zG$#JCrrl!)TyFdB!{_Xy2R&35JT6|{nm*{1+YO-)VCtgHsloo~Jo5Mt{?NpUeB zCK#*SoJjIg$4%MXwZyrF>qK+;_R;-5)+#cT{Kq<%e?pXoYSU_73Jd^qlQBFd>-h5tE z244v>+1Rk1C)G4YA-V5pp$%gL{w*yX@OpD+JfW75!I*T({T36NiqpK zTd+8AX>jXTc0eWVv%x;d*W%tMotlqjK*>wy;obYX_9gIbOD`I=ou04h<;~yk+nL|{ z^UM1mxda#kw5GT}pp-CqL*qo+NLm$1BT0)DmfoBbe-WoyAK$nfhC3&Ww;lL%&R@Yz zGA3_$imIt8ws!!N-v0G!4CG=qB@bqN#mvSGqNfWk4$R(8pB>>#cZ;34+=G`j7^$PV zkYShDnw6#Y>=SrxdU4Vk8#DNdUJQY0HVa7%j|hRHJvum;dMS95EVp{m+PLGE|}HfVeST@xni_ohZy< zx;2NYkk0dA*)4{(sFWZA$Vr7{(@yUl&QFa`09lejpOR_=tugX2FU>DN61A1iwsH8BdL3x^@i90$TDdPR*M%*` zQ`T66xzV0{+xtujUXL=Yv4O=yzcyftH;V^cO9 zLyH5xs(LD-IxoW-YDx&jwrW$z8Zl|AU1^Z1g7!`bb{0mjWz^C=m91Dic2dmK0({gL7q8w z^mr@*DD?s;wb;nitnFxMpg-1F-(U!nRZP1k`mJ}OkGjmYdd3x)+#H9}Fko&US{LE? zq&>ZU%y#S?XQ5mPxpt-HU@|$6Sx|)jAnl##Y{dGyAa=hwVITbIvc3P|6}(}g^)?f? z=e9Dwy|@{#S7p|KN3`NaB8{&-hf$tg z#)JGTmrHJ>DX)oLon3bE;zj%5gAXtfJnTNq&Z0&4cYpVH_V<7P_bxAvLkYD@r!|Wl zmdeXg=azhK%E{z8pW2?X?m3h?$y+B{R1*_Zp{nv|9AvpMQY1Gku&}hHJ=I_@&NHi%@(!H+ZX+Y-OlAAy6 z2Wpo^_a}IIu^r1Q#w4cQ+yLOcrY#gA}(*tp28wpzOqW;2#G5h>LyB!61=$XJgX&O+Ys?yfiSK2d=&)bX7OQ|K8%9Z6-1HV!Y97uJISysPRoJi?bhWT1}GbqX*mD?9^_#jF*wuq}XSx{kCP z>N2gaE}g{?+E4%*1w~QIFOFGWeii|qD;AjQy9k2-z(Tpj+oEy@WmLH&7zf3;{RBkZ zBO{YG2B;*r)@f*u)znr3EChg($cUYbb`sNq&$Sqm*8(}vxM1(<0)R0@Aigt&16c_} z@I5j#Yn`oQcKOPbeRg=x4xfu!FI-InV`xPHx>e#yZOf)Y+p)XUHf_$bb!+07fv5(= zQ556Zn8LA0kx7VLuv6PSJ7|L{pQ<(vxTv-mluBhxfLn0b%mXULmtDTxjR z-rGIDXP;Z$7mY?@ri22j&$%bmsoE9yQ#(`@ z06SN%h6f#Fu-+r6QltW>{6zWGx4l`ag+&#@6$KGccl5rV`fNh#_^OM2G(FX;+U>h0;rAoC@+r?YU;BF3v4>!gew7Zdiow=UX?Z(nc;uffS2TUbc`rEEIW44PrICbH&HMO6!!n}Sw#Ki&IOYE+@*V~4T z%jhR*NLQ)=%3IXdy)({~Tba_2a3SScWj!_Mk$JAEYyw8c$H(o!frIw)%P#}syvG=O z9?)dio_YEid;057+uF5jZQc5HmYXXOpOE@V{Y=u$@6Gu$(?9wC%z5$|r!D7{(65Y) zj6h=y!yi9xFTVI9s(A0v$LMcFfk{93^B>?jv=OP+Vh3Yx2~e7o=PT$D?vahuvUq-> zaXgMxEN#2Bt<~DvTWr!j9U60YzWwsWQrmM$fPbX&CP1k;kGUFKd!1v$wxxR1Hg6oo zSbKpz{9uhOUtUBzm*ILgGLYoUyjeg=6bkutYDIaC@)#~8kKyNa>gCEOe?NZBZC|%s zD%HQ%c%mEUTH}9QKuO>J#QC|20$kNzKd0~BMAp8NkBFX%w*n}spn69_EQ+$XCJ=n* z&Ykuz|MD-a+k5PXKl%|H#m`#~>i*fpE5;vBAW5z{eLQ*fD|`6d0VVGcbY7oS)S**H z&H0GSGYbBE^8QRC2#d?)GhS(P(+Kx;U6J2c49ZG8gt_nPI@iMY^fPtPNIky|D2X~( z2CwTYFMaO6QtRkOAD^4wQ12RSW&ov2c*+r=gp1{C0ZMbfIrsOC@^SnA7f%7LG3fZw zkU{<56rjXTq_7I-UR)|f=TTWs9Rg7LAl>%u>$W`~HNlAVSbZt>corAT07{80RK_w# zncQS+C3Bh#25cC$H(u$m9q;v6D~3(RP{C+G!eG_n27Bn9DSP~pF#sjJIu#ZH zZef!{Oq#a41G_0ODF8}Qb{ypJ@iH1&eO&ZgVZ2N}H!~z^9Axrz9?h9HAdPWgG}&2c zkD(eeVQ0@x+VL|JcB-k{&NLmji=CGMdupsGuf{5i^R241z?Lk-!_m4jydvcRl;AN9 z`$w$bQKeG)NDILE$p#5L4~u!!>n_Gz^{?f!*`<~#yV%ONy0N=7K8z%kBrz~0#h*Hi zcQ2?Yw7N>X%T;7y_;(7U(L+Q)j)mm_9Odw1f?K4v6-g?k0mx)##9)e5N=eZuqP|Gf zd?N{^fx(y?;})PaHqwiV*))LCf*A>=2vCwVlmMkooqTCx+I%*F9O1h@c zO~EuK0Au19GmcFFptZ%ZcQa{w_Kn(y2QK1G=pq7H#n`1PwpG>Go>@|En>Xj#z4v3x zcQtB**o?|Ut#2CXk?H9%%8>&QAiF1$DiCx8U_+?{*Gy5)$R<%#xuQaJhwIus2Y`xW ztXxLRBX~!TlSUi~EkJ=Wq)eL6;++p^xpNrqzCd0tQ8%p^U~UBj%;7^>6s)eO-zv-c zY!T8LjSCmp%GHIoZUa(jNTg+92;6xozNc@dgLn#vQ$vhEJfGn`XQGd!NUjWXe_wg` z)BdF~JJ?WiwYM)o<;{t4oq|Copuwok>0G}OiGJ#G0K?ia;TgrKTTR zao&28fKp>^o%IY(Th9RMr32&EJ2Gyi`B}EIn(>2*8X5&q8bJba6kAyFVY{cX-L|Z0 zw{1_Xu*aWRN&Cb0kRXh`sgtQB;^x0HrOC! zfORqYp;UWikB&x=3`$d_QcFy>WAC@RO&id2QS;@5A2aXiJ|Wpm{J?v9Kz%*}jFe{7 z&ip;yS6_vZR7cglC^?Rt^!3URcPq?7%o-Z%a0pOoqk~f(-`siGUMHS7lduyl$aG~C z*(w|&+=1%ba_sP65}H;%1o3W6)fa#_KKd-8#fF}N{q8M15{oH@sp=cni|Awc*-XS6(heOCGL_fzw5<=4YnCmdCbnV|Po4rr|? zCQP8xsgtMd*T4R?z5e>^c+uffm?z3pGkWr;rUJ?`uQDB zJsbMtc?i$XUk>$q*_>Mb%XFy|189tqxypPA8kmbgpf|k zrO);B@C&E%K(W1-K4`o9?orBEET8;uolz~=xc{p2Sl1S((J+XFqtdwz zC|yZS(d^3*QtRkO`I(#NQ17XL(q#ap#BD(7Mx^}8-}mOLeoskM|JMhU1VYF@29h60 zcW}ZEChv(aNOpr`AEnveow(Hgu*dcuK5w0fe=ID^02Iob0hFe*Mr=A;>O@k*%C=!K zb^T_iPEW$5;W=sdfSto$QBUuX)x!|3UR-An+?{5RJ~U~Imtq_g&?YZ02k9mlc#Ux| zQevhACJAI9VPX`*@R!;@lx@GR$7UamUhrZ;kK{w)Jpm+xcx~%LlBE@Cr3;c$ILEH@ z$rDH}U9kSXLKxEm7T+*kFj%z<@NCyuZfjN-vzuRFiiq zhetRJfp>KvCDT5Q_axNpE>7Bo%aZ_Yc&F+bwQ-o*aWIN37WldB8W*u+TvCvMYx^mr zp@yvyNq{9wt57|tw*1^l<`C3$P$x_yKUsi7xw0pO$2_rXd=-XE_OK!kN3svoKNz>} zz8DfpgLtv(0Z^Js0!o$11t!v9fOi6vl!U5VBqAYCQK|ZMnB-|_ArZArcI*Y3u zsp-i;Er1u_5Y0V82em0($pB1pjF0n~kedCOi`O|(LN^go$NbQy^_tGVa6rj3a_vHh zB&mRsB$TEAlM)zi&lI490sjy8O#>Xn0hBuJ!{g_y7ld%jk|nmNuFksYx4i^P!fOMw7stm51}U6 z6t`2yhwbgRj@tHjjv=8$znui|-m=`DdwL@_lqzirYN=&4sJv+*P68S9v2=;AB|{{^ zrc$XdB>^SQb>=}pqXwOu3_kvOuZ#erD93uAm^}D^qbo^pQ~g)B`uYHrF1Mr32cT46 z!@tREigvV8}-vHLS_A0SoOH=1eHfcdKz<=Nv;W!wFaod1f&O-Cj;4R)^iuTzCpd?T!3p;g17*pS~C&&Kz z|1;Z#EkqazpKmIV)RTnLz!1i}NBeAb#i*@aIgWiSfW;>p0RM|gOKSspdDD0;K#A5o zAD}dsrn4EHduO&8r`!qa)s#!Wx2K^!hU3i^GRrpB05;C`v-< zpa1!vX8@(|JpUb+@|+h?QesLgB|T67EB@zm1C+cYCnpl=&&v~x3|+Rgwz#*4_Vx~T zx;tRp*fAx_8-hII$Zcp{UA@Ozn5e3%YTwb4?!GER>9)1CF$rD7py*{!s|PXKiAlD& z>1>M-RbI#>xn%KTTe4&^3|B4-*~r!NHR~=^veNgDMBhn$er_igpd?Y^x8Hu-gi=a$ z@^Aj;|8$-7@LtsUnM_g!fsoGJV|eG|9-ZDF_vKIVy)QB!sdT=XBBkavoa=ZcpmfoOUhh3q5Y}8cQn#L--_wGzoP^N7efKpj$HWMEn=wOU8JPk1<8pK$1XaTFjC@>C( z5Xvp)Q03K_$?MTGDbMNoS=w_u+W*;5H zyI5j~IEZoWJn~p%i|eqjv>KIwWyMyrD9vgXrr82iVQPqyT**XgARc2En{>yKSQ_Kl zhjc)D2jB(LG0kVO?b8&qUL<7tU}pR9#MC>0tqT}|bX5L|bCD#fN&vh`MXl268Y)PC z#A<7XStRCKNogTWg6PGj1=2IgqQH1X0E#vpq|P${pw!zJcR*hq+ zmSQt%<>C<}yV9^nQ-;b+k>wZ1EWZe2!;*fQkwi+?J0Fhz31~`T+Ko*aqS}RWp-opz zC;5>JY68@OfHJ;~6qVkcpl;FVi0YWS=m1nYb3Bf%tC*c=nzUmVCv13pz=kIK@#a@( zCArWXb;Ct%0UOdtOO9b*Y{YhNAF?-I8?>|Sqc%A; zX|<@XJ%n`1efJgGhBcLVK&)`Ey{~uL_Uv!AcXpq$Q)i`0T1!^SZE00Ln+m!1*w?e{ zv8VC+hFvm6ZBEErpSp(t9kcHb@Y17snx3(uS+})eSW6CZkUl|F8EgXroW;h%tIgD zBS*erC_t$d-lV0i#fplHt$IPN?fD?n{^1|T?e(Joo&xZxmrCp>l_A*|0Hu`}XkWc@ z!0x}l#GZU&Irgz=GXP3bdz&@N4gcY7el`<r@s38bnb15 z0)^v^%9cu(aISZCt{4C%S9xo`fYXo>s{}w6m@prp6uujdH~Ri(dH>6hhtINnpJm!} z>;GDSlE5Ve@3F}tQ0siXpQ`e9%Yc#+y}2P(Pk!mc=K?5+=pHl}(usqptGqm%I&})y z(P!QGo!p4}z{+C6b?I5l78fy?SJwaxHQE|TUSPoF-GVZWo+ z+}v!P9i49TU;^(Xe2QJ%I>4wp7PRQ9Z&+^?l?)Jgk&uDBYlcw497Ep2F}yRk69)+; zxj(%PC`DA7OS3?`&-18ynp;=b`hIGDbw2Z3?G{c)ZA$}=ODL5{O*2b2cWk;+NK&2z%`eHgQY7{ESz8P%e4RLAN|?7q9R z?cs+pNWC0eHWe924zTd29L|(`?!~lGvgD4a%9Z5RytHAc3zM3_ByX#Me^XXMNIsnU zj+lPYRH_sTqM?ALc1aVRi`nj7efHkFebzbH;c*aeP{VQ5-wN>fgdLZqi%PJmG;NEQ z8)H1iY!@M6gg3a-(#RW|KChISy4fU{0^mvDZ7pFJPGe)~44%>kV2S}^+VL27`SKvY zN39QZCI&-RlAX@(aVB&r!PZp?Dkj6kA?A}p7K>$UPUItXkcIjx(n{IX7ZOX#zsfHy z7*jiXLW-FFt*n{_BuLV%4ejx_18+jL- zQt8~6arkL$BSo?+%9D(LYgb&LQj{t7-e?~MJVzm^w>ZpRoMVEhGHC8i$L>-(jJ+6n zpf#RTLBvo}VnvD#e3GChg#{32W~ju~xj{4ac)=ayrk7(?_i$y8{EzQ+DT; zMqHCGz#uz7A2E+z{XFVM(qb}@F2m;PXOc|gl&=syyZliTPPQ*DCj(DJ#ZeKGFNAwK zMmHm1V)nY84P)`#G{bcr6~C&06178t^C&~E?f=kh$M$La055O*j-v90QSOaPG0KhM zS zcFpWf`PaGb$?K_XyTf2|Y4yJ4nz+l^!7542XH`yIqt8B^YOaLXRxJH1I z8*F!VTu+8J5VbpB|8a?$pw+1jrw&NTijQ8o#lL!2Jx@VtsvSjR7$4^+Qi|M8&?h1Z zr8XFbNkC*IlmL_@HKjZcp$<4SoUr%a9<aznUyR5ml0|}II+q$a6Hg71m`|heE z)+3dNA3NgyBbNZ$n(W|#bUWG9fIYl2tInA=v~lg3Z)Dgr&jGd}#aB)p2q2Cj3Z?$& zHqs=;u3XHYPat^_Z|Dr zcfNxZ=^D3TBrr!{h@=WXP7s(R;7ISQkIxNlt*wBNJ8ajkckM$Otm4BDJ#3FW{0I`6 zcLPM;$#`28b!o~tx8Kf9FZFlm)4G;=p8AZRC$puoIFYoWB!k>7EiG17QEv5(3vKV7 zO#8dP8?sjp$*F$#5vgTsqACo$|`><*DcpXmO(g2HJ#Ucs~4AyHvaq zP^wG;l$bAR$BH3@Z|fM+3HLtFW5~zn`OV*#Z>ioCL;VYbP@k97Y(CB=1SU)EaXvsP zycv@uq((;${_YDN?_n0c;ErMbL&>rCTfWbq8$Ww5e^+X>@G(K z28MXI(ADI8-eLz#s&K=kyKdb&K&7>a;jcghf2q4Cy=Lu&3g&o4{!?BE*F$IiG6G5= zk15&ygF6lN^Kl9u5NOd+|GK)mTmnwNO9d#g&=R1e_Bwa63EvCf565u*_VJ6MfY&AU z7s5=vXlzO@=5)^=@p|VvgUO9l-e8dcRj`!+z@WB}mdQ?ghB#ps;V@kv3Q+nT#{<^` zl%(<&0ZIY@Mo@X{8OX4v^Jeewp0YgvN=KVU?P5D>aTtPcEX}h=@5-{Lwq@FCcK)l8 z{wT)lnX8e&_@p!bMJgX+1Ym@e9Y7E<>XHW0(pBptQA6N~3{FQR;2Ci;dO%S@&w11Y z9I<5S0v@<8dlPYXboGokX~DIylynsr$ih0Q`jRbU4aUtSMVMS#(RNtHAd_VKM7HMkJ~7)eES zcTQSI%Oq-d084HC*4{IQ=N(*sPo(382eoMo2iFwEt&&($Bo$}?riJ-1O*yu>G1HK4 z2gCw;!82J7QcGTZ$~QDP24e|Gg3;CSu@Qi$bX!nY%fVpgk3{qRtQM>Q@n!uzC=r6`tw3UiSjK-mV;u#%G zlX{*@Jn0?oU|%VLoh1RCVhpAB(+`Nyi zq?OW;NUNuAE39te7@!h1zZR83_fp)GXCYROie^?sApMoJm-0YX$u|e`cZK&>ffx>C zh+_U2f9HniP5_itpQ5?qOrM|gO1Q40VgQsRog``M&)q1u@+SgZBSbY5^~LBBY$&1f zCbhSW^gNFTP_^B;!vK_eY~R5Pc=#ZG6um@Hlp|q+0NZ-b0y>b-iKv8-_>!iZo?WwLR~mjQrnG+oct}?`MQQe z%22eVgI@XF@36DA-8Xknojzp`K7b9S2On}U=dQc%vKkyfNNP0AJEf<7<3Hh>qNT?0 zB%l-|t(1?@-@3cIZ2$iKNYm{@ZDg12+_j6bZLJ#zfB2Dy?TN=9cWEiL6TLHc4!>Sz z!Z+qVGw*dZ1^x+ai^Z@J2V<#N##rBg+T8~LO8*al(i;vaWibwBS{-vmSrG>5*~sWd znr}_zpl#iVgwnl*_UMC+cpfc<&I0*mH%{-!K3_C0^C|ycl(%FBanPB!anUfGN2fD1 zOa6?W3qStAj`P;x4QSwWO?f7?C9Ux^uL)4PIHU4b$gw8APS_`zuJH>34!XWPnp{he^-jP1OZCkL&La6e*Im>QE60Zyx4)1=Z}B?qk-k+r7mtPH|^R%kytMM*dAwMdHCUn zZRN_99*-P3Y=?;l4<2-{723&JxoV9|B;{sjF^R=U|Ac>I>C&a9xb?2B7|gpD)ry*H z6H}F(tY|fw`9kV-HNH;^P|~+P>EIOd7LN1f{}1KbtIt!+-a z($b_+?i&C~dRXa&H2+ZO{$(s@sNZl5dGxx`LQaFwOutVq>QsMBG}i}|l3w0eG`dl4 zae5gr1njnpB~skC3qa{*cBuiBjy0dRK}jf;XQINC$4&-rwej*M8%k3c=GM$524Vmz_L`1kM>2;DZ?coyy_qY19Tr+2xJlsjb`= z)|8=Ag9Of_83yJP$Vc6f4IPLXY#g=qNo08qLYM}5q5>aJtlS=x|qPkk-ZzV@^vx{$Ogfnmu6luR3dNP1R` zs8WjRS~abhFrhwsG&2nq~^kq1kl?s$dg0juTPPicS#a4 zB)Ym|A70>kk#sqG0yQ||>E;1DeW@24SJ?Z4(TV{u7Uz_s8d7NWHA7Z|q}Yaa)x;Vk zta6x(Gm#nw$e`evsJeR|XrCcWlRpQPd@dG^xW^8^OSkAWJb1-X&rt^IJb+5_BBms+ zH6DjCI@}L7lmsLN!`ySdys5v4Ne=H`k%dqCW0nN-rlfuwq8?yr%i^}5_AVPrdC)Nr zSLYeFdpCg6o?hFFvG?;x+f^1dT4_No{ejlOH~LUb>qIpTTlQ7~gPcVJNF-2mqzU!% zXF6@d?qAi14W(WOljE0idgTNK|t-8P8NZS^Vj;k zgu2O#o+5uDH9`QT?q0ie{(_AmrL}8o`>is5r_4U1W z_#`%$rmL~#R$~utS%SB(#kPepddr=7=VYAfMKy5W2UGU)Z>Mbc2^>5>R@7PnP}P07}~rfwUr_BsIWV z`b#B%_(l3v@5rRBMy2|`%}DaylaK0SJpf@5dBu|^<7j#&s>V1^&}i)AGPLq?KnKAT z$^TxznoGGjZ#hGGZiNOnDEe3OcA&$pWPUEq^jk3iN;1lQ@q%n9Azh0R{<1P@w4f0q zPtH8&?UoOQZ>OdguH8z0Za@3QQXsYd)dr-6(m_;T%x0}8W9(%~KuP`41NS^6`={0k z0+pnl^pF4ePcC?HLqI8{6^_Xyzv_q298j7eP^bisanQU8>LM3O8zdh`go)o*)6uV23owY3d)=bc-LciJ0oykW1u@tW@*O7FcE)wXr0wKX&} z_#!2SB-Fu!hgeh{VuFZV`#t#3gZ8awzvZI5sg1%170uMipdmjD7U3A~g=6YFQsa{f zo*LDysJtnyFc5`fNdJ=@ua)OdlI9=EyP+Pm_;NZXn}q-)^+$h*O#4#Axw3g-Xca zV1{*c=3ulGhH&=~ssQ75vMmQN2F6}YKSoTR+?23yJrzTGAlnu#MwP1~ms@~Iv|0CR zrbUpLFwKyf02wFYv7MRJC11Dlj3kt<*nrmidVv2SC@D{aKYCBkYseIXr#_)wSRe+X zqzod4e{2Lvhv7`??qLVFYXom_Q`X#!lv1-9HoL7ANu2TcIDiH_^@tdkGWKs=H)tES z4BGOQ*jiemMO~gt21%`K8pKXJ>j^|;;xT9iW8%QZL=N_ra+wQIiR+Q{>jcI%QH#5T zjlIq(Ya#Xk40H^^aHj!eWfa=Nf*e~?nQ09*IY=Mi=6*q*EnbYlYhulUX{)XgV1?rd z)P%-hx+h?+#aLBUv1?UQU~#}CMQpZuoQAL>k?0ml28lTS{|Y+#HExNg((?+Dq)-H$ z$aa&Ybb7iX380S-4%qu20z@8**_jKpi80hHva?~>@g}u7##|V)RVzzuCA;CprBm2E znQ-+zuN=ODvLI1vaLONy>NMWtra|kFP>R;bF(9LHXbaQhbtlhMC*wQ+O#8T%NG#r6Z8wbq5=14KBB2@)M z>Hr{b(c&~)x-8G_X;oKa<521A1IfVG$*al%xS{qXslO@gmXV)8zwm50x?~=0MZiQz zD*}|1c1q%UK|hJnRh2C|3xJXsUfEB&LP9Ay<|_lKfKnJULOwqBG0MVqUl*iOu>$~O&)yy+952`zq{q^87hx=PffWJX6=h+k4QD3Z)K3YU zaOFtbW~1IDL+lgOtpKGo0Hp`k^xD?Vy|}rr^O%QyONJ=EgH#`2^f1zh#}CD^nKo#z zyuH_6+P&8nR;;vzRjZKHslt$V8TMpyt*k2D@`_}$OVU)-D`S)Q70MC;va^7aND$RV zG^U0cib{K}nh&(Ni6f0awZ7CB^xN@DnpiI$5iVbBv+ejvQ@AvgU++grV+pxRt*=QfzB5Ouq!lrU&ksM7n;$D)FFKP*MosonhNwk5eCG zcDfC(QW$hzUV=x;nn8Qwk)`(dwxvkqP#0BG09fj=NlGxcxJ@(B%CB8rM!&Ad6?9A` zlgg)mGv$^P=^z`r=j;Rq`mm!{}5kt=>UE2Ti^Va{pp|n33*uO z*Tf^t=HHY0SbtK-fSEie>87z**_Q*B7GfFVt3g8P{{>Kb?GW}^83(naQeS{dH7eR2 zeWTWfgwnc-0o$|=NxplFY}><2(TFHv+#6fBeUP*uVe#ztic<+(y#o&6{lV9h=<{w>tSK1N=V3Xg}QdAvTtd zczp87C+!D+@dG#Xr)+6((ctY9UUIP3yNZ5~`{6l1ndgt54Mw>?4xpqYl}75(e|&;J zse|SxNahdv)j-2A*z|PwIH(|_^71@bP*~tNq%L5?^{d+HeD9`QQ+cQ4#@_R$MKgc|c3e;* zqi;l#LVaD>Y{47c;lpvf)=k=hhjSQS-4B^EJE78f2iASsKj8X=4)KM7EhcV#YdJ&b5a|t_wx3CCMik?xQR)RB$&c4c}B%do{ z5cy5rXiRsb+(|&`3ZvWrO1iIS1tjkwmwWA1d(34sm%YM=@Ew8}i z2_(k$eTa19-Yx))W;@=3f&9z{s=fwQt1MfP;-RV#hPR}!jGfsCIGAKUb3h6ET#q1~ zboU)ScE=rcNZi!BJs26xm;EpqwjUlez@#`fn+9zAuJ`Qq58k&GwfETahI;^%it!GY zX-iii7gvh26?ke^fV3Z}TO!Fwf0T(JfteEVl!THKRzLX{@I(w6;@Bh5(SN zTcjbK*x!%(?4>Rn$G%i$Ikq&)iYyn&tepJWb|)|_o%VPEsl2`WTLAC+?Vb0aMKg(H zVjPM1{KkHJ;?aKFh|1rZjj~;pZSU=hVdQzx_8)Aw{g*oF`yf-q=eMn~?|o}6CK?KC z$#Nw3B&F#<^=v-9jfPC89KDaKE%Q(RuLvrtKnmTWZ96E>8eAK#W2p2=&Ew}k|GEAA zzkiO3FCNQate<)MY5TK3{WIUZm2{SN>#rG#OnLB%xs-1!=$i7Oxm6pn+Ne3p z&WY?f{pwf0vhfMpDVxgQ{qA?|umAe5ZS$thzS*qJ9KD;GX3D2N!D*DHs4V^?o$p*i zQsp8lfwH00(AdaWmVphWL3{b2R1pc}y$)Mq)i}fG?H{tvp&?sQ){8oF4@TKbG0MFL zX|FOHndrld=BPWPD9A@VF93rnl{B}n&o>`OAC2ly=bt_e!WX_8$E(&S*U9#^Xyt2r zA9#3~rYQ-f%a<;rvOkK{Z)DbDKBL^>Q@4_b@Xn`w{4(U>(=OBJk)GOwum`O!yw9`l z3V@Qxy)e zzja+{ekx%;vVSTG|NbX3Gx;Rz!t08~gN(>ar(Qs4VPR52sk9jMI$|#71C&Dh2*(-f zeOmQAli=->o1(yt`bDT0o(t{ZMu1W-jG3e-6r`#qMqQvvbS*mWeka{tc_G6N9qz`C z&{-Rw9AKg|>I^F_ zpSGgXgyrWBd*mY?(vdon-54#_#i&k<e>tOUZ)U%Ucg#D2Mq#>vq)bP@?1Ss{BZYrQuV(9{u1kCVx zsk%*PNR1mSQo|3KPsjIpvzp3|mFSP{GqseD@PV;~CK=hLOfUCRp zBcUW)j!1Jzz%9fcT-nV^FGfDDvRnWv?EqjT!{cBU{dbn z(YFkcM}Shd14<`b>CXa`GHWm>jI>=|hV`-W)(KNzl$nECB0v;tu?fJWQS6oVGS}s# zefYO#;yJJf&-rnk1Hwo0kei$IHjH^phXD*<$8Zc>9>noS0+Kc zzAZ(v>yADErE1%_aWP-k^n?wL#ck{ArFP$zrEY`g{`+!l zK|OF9-xS~`+RU^s&$j3hB4?aBopdrcB#Rl=+iE!~x_-w2m3pup^U_PdvzM@^bpBiu zefF$_I8Q$QBw+77wqer-m;6_Dnikka1uS-Hn4gpmEY9GQaRD8v- zW>%XJejvvJkqxD;o0CwwM*sd)%Ju~%@|j8~h00RdG!bgD^9~SdBotbN<(ls6zk*Br zuyeBe-QD(||M{QR)YQa6W{b&<=(1(YJPJ(uw}1OLb_4FSKl`&kb3myS5yfDUU4T?? zPp`+{{`R-_o8SJ%^}`?E_Ba#!Mr&Ns=mW+i6PiE*t!LcJ47(GVGS;C6M*~VNhw|@{ z1-}^05TtW0wKt)Z|M(C82oun4fBUz8n*@}iG@^xPwD=4IK{$HRqggK``N@vIhmG}< z5#;9HR$VLTsQOK*4p#m!SzuVYDZasNr=bC6BB?R8Q7I5!0Eu0?LXXO2Tu=M z#{^(`T!50ov@I@cwYyiJx4ZAjwfi4ghHLg3%Vqq^Ml}mmfNW{E-$yp`6-|cGn-rGf zfhBlh5fng5C3;c{CUTrG$_{Zq%ydr=2BBf7)yBmDR#jmer4mUKCRxP{RA)pZsZ33| zy@&{y(09Us9#5dwHZ|^QX%nM`>^{rr?-czhVSC@5LW*<($*mSU)qWYlAr^4hIV#I7 zv~qUE8)|cLq>ydPRwCuFGR+n*nTEL=w$fsZlg|Xr9xA673;N@!DvnxOJdX&;FqYnf z5%1nM427TVu_Grt?ev)mYeJHs1zS}rS0#u;GALvZ_hIjbW><$mVy2 z)i)HQR!u&Z^N#4H#VC?JlAcjn9YFJZhyzSA!t;#l-oBLCWKc^JyXZ}he5e#+a1jDx zcN;_G7+|@Ky5Px!(=e@r_RijBJJ58A2Lu!i*{a%lTZ#1UgZEY0w#O<_A%l6rdtG)O zKwcVZez=kkA$>}KQVHLZQDA}?=n#_+c}r3I@Un!Ck!<7sj2Qn(qJT7=3k=I4*SWsv z5~DhbjjKLDyN>oTyWG@m&8PeA(1A4j2xhx;V#Ed}$-AV)GIFgvzX+RRWwyGp$nM*k z3veM7PK+5hiq2#tBch3a+D}#2$`>>b+4GwzfBd!{R=E11t8MY9{-QMXMuNWM#<-IP zxzz`>S+%H9fD$&S08|t-rbl3i|NM0ST%GNi^qma+(NQ%+i{WnsC>ix2Pj7f&r@bJh zlmwJcwNBVX7SfPeHCBfdTV+0~m7`PEHijBE<3>5EY${gYWZVW=6M2IKFntmmN_TDQ zgRx(L$G!z@qQGn`a1jV#orvUH(qbD(_OiCsh@sOR&Prx z>g?&qikK7fS+8cI_Qu$R2TB3I+C+##L?KaWHi$mDK1;FLd(oMzXQ*CzPAVOuCn@8_ za@gK}XQ#chV;7D9_R(hcvf)uuP;pL6T8F{jZr41 z@XAacXd4LzTY*XrC;=+9VctMCGbN!Sub%G-Q2Oz>y>nFa8+m5V3ld7fhSK7aPTR7g z75hm=4k)cyQ31d{#0JtBs#7_{Y-%irSCIk~M|zDAwaxi&UW=~&&it?3zM7;!pwZm5 zedrf5zan5$(s62U0+r-+Cpg{-fKsS~aQq?({DtIUZquC|Mz1&ge34|j`rG6=v@riqwg^d%B||V2s3IV@Um6f`LDJ z^r$~`@4ff2YqH5ZcOLdOH1Yh`fBly|^2j6h!yo?8!6qSz**TF&veMPA;?Urbi_-q$ zm%qTf44yZbASKPTYSk*=anufp14_yt{{$wZj|l|jD+Oi4BGtvBEFcYpYoKeXqbd(IoJ7BkxQkjSp`rRM`}oF;QSsHgDB{-`Vp znp3q{()Xe|h<=CEbzdPo6aBiizc)%Zq^9RWxpgh|+q2Ki=H-h^7lM(w==;%8%yoBH z7xg#Au53OLkAxWLl&-(;UN8vh`KVk;qIwx;&y!UWit2s9e}qA1_Rj6I&x!&`TBp{P zFKX3Cl8akE_;0F+8AN?n3*LV0YDgVP{WzaVrl`2ke^0XzRlAlcSyk$+ganIE7=d@+ zF?;z1>;@sN5gYH~{y6F%7+0<@v8SJ`wXYK=rn@|*WyqF|Bs}r~l*;Vj;VC z`(WP}k^aIN%GBmxv^Djou`QQrcihv6v}OfrE7Mkxi#iEoOoA~<-g(402vCYxPqoKn z6puxm0>qF4Qx;>Cyga#`I{@;I&JK2~n~?BnbB~#l99>Xb=bkpT;EERcg-o~@0mcQq zT+NH=k_{;LdIy6hCQYuB1(L-lQ5BmM@Br`zL(`A6(y>FiNMWVfx#kvYy3k_%W5w1r zQAEBoEe{nl%o|w)s!&L9FVccyi$@7}PjcEX@z;Nl^%uIn@NG&D9 zFihV_ZyMg_hU{!}KY(2tp5cmE0A$)QJCegJB1e(L8kro2Q7$5F^ydp=7+oE+ijo{+ zId=LAY~>p4EG>Hy_VlY=omsMb2WFZn@YnPg>T$XMN>vBAnf}zSYSSHeN>6wvB^|Z86z8^^ngnsO~ z@;;cPYRa&ydm(6E)H^DtgA5wyx#@jG=jtoT`?BLG@3T^YkfffBu`j^GtRy9-0Q#IB z-oHdT=;i=!^d+UCbd?()8#KWtLu#JGwX2TT$p013k))^3MYWOys07*;~^BT}@E^*KK8~9RlP`Gj`09fwLq*HPZT> zIWM0;Sm6p^e_$rP<6}0R$c-SDS`B8OaM7C zCx;EC+;YaoY-{a^BasJSx;NVn9W|sNyRD_a8?dwuK&sVNudW4DT4}3S;mK{WY*3BZ z2k)Lo^{vegpUSiSEvmCZ40;#Zwk>(g38+M`%A?J}&`Pic)z!2#Dl6Hp(hyq`?Hm}E z8WkZOuuH7YwSqH0tY1jNCGkT$6a#(g^jSdmv$hMjfV+0SLmR>~CYuM6Q2N%h-((YZ z(^bia_r0x)?y8mKF+3ce3BSWJ>J#LJikC+v^|2RT_^tiV|Ga=S=|yWs-E1rNQlI|% zQ?$FyZue9Se)OJKVo2&5$1C#^@|BvOkd_~#(J*QnkWllzVh;R7A(9IF_vhKa{WQnk zJwu~cfaLZ0IB6(FJq{a6J;P%-m}s|^wJmo4U8VMor`BWJuH1%3x=@$y2TVc|mN=C_ zZ4aqf2b8W+47G3lzg9>sLwH7I2w}ea;hv7E&!%4geLoN7o&l6ZX6UAQQT<=GleEqk zPbeT!lBjB%+1fOuO@#MFC($^xsc=2~R^^522z4?0jCYW$(o&k&dgglR>b(&3oW84c zLjFQN^h}ga^vvu#nhR6gPIM>blE0_lSEQ@QbnSW#HGJgDdQ2AE+XKXrmp=)iC}btq z_$3Gqs0|2E5+9(T8q}+ziLPm_Eo~~{5ksiH-U^_k^a5RV{#6d2380kPI8)EPV|jy* zm>o653@S~MJ;wlzjvhT`M~@uEz~K?^*m_qCyDaT5U%t#9e&`XGERuL`Z*PzN`q#g9 zed}%8w%Lz<^drBQix-Y87M==1lU2F$)bop9{K8`$hP&^+`)=F3d9&}hET~=J%##{~ zCN=>?0+U<>&U+^=aoL%aZsnOXXY9TA-m?P-4>)r*GBUz~dln?pAT%&I;6}N$==}co zzmFdJGu~LV*v!h#W|GbVpknu*$y1O!cUX3TTcQGfsk-~ZTl>|%&3>XqU1*jtxq0UpiAcx(|IwVVK zZD8~)u?cT$s99l~p|hh5+ds9aI8DKzoWyfh8?zk7eX@xPw4w6M^R}q;ge_h?1&C0~ z5#!Po6Bv!2^!y48m%(lAMpFv@X+k7V0r=8Y3LxXkQn|`y;>;C5%C#w&J%x6#qYyhjNCTikmk#(=iNSJgbK?!J z(5lOGZPmJ%tymvtp`Qt;C#kR@#`|6th7rh+Mf&-u806(e_FyQcO^ncoN7G>v;?~_C zLrtg1CPx+^g_1+P^bq^46YQl8^_>X-u?fJOEC7>SY!#Jc11MqtqPil-8kQ!kVR5?E zv1?risFs%7Z|OMzHb^$8TW7%3Wu;4c0h>~cb*b$lv^jrJnM!GA(J7k~*uO!k4}N6? z!5n}Sz(q0K6R~0&9;-n;B@^2o?HD%iMr~%=PFw_n(s)EeTMY2BykQ!qwba&ZsI&UT z%sF}O2my6br`p6|?3&8+DAh3mAP#~8!0G$b0DodSC*l}6$Bt5NHim(-X*U7`V@S~H zeZIwi&%A)sES||E1~7FDBjzK+<2-`_W(*k9tgIi@qOS+T=sk_(e-Y9L-BIkAwhI7y zL%6BWf;lb(m@3V|eg%?M4dsPaTUuyKR;AhE)hKZR-e%;K(Cfu87Ic0ek9}UQUR3+d^zh8jRBhPRli~G)9+Y3vTvpD zsm?^J(3ip-r+ZGr4G(PA$2(2 zK<1E8DoTUC>DDtiZI@9|RHbGMm*7-=bW);90$9@H_81aM_ukoW8#dO!+*i}52W+sn zjj~T!aZxd9tOfSLu6)$$Chg?8x9r6E?Y6vei!EEc85N*9+pww%?|ze(SK4Nog@b%b z9|8=)d*C$DJ^VQ)5=nJxgD-{zV*<&-xgm_PUT@@C!LO+WQm^V;L9#s1IlQBzDnth_ zs1C{Ci~;>2YTuE%s_;R%htJKEif=Y+w-Jv5lw$OWqJk2n8LO!GTsHe@S21oC#*xtM2e2Qpy?gR(*U?-Xp^pl< z-MA>*?%K>ahoSw3dW-|3{+XV3iM(|Z)qXXmN1n#w)7U$kLLyC@mW&zcj62r~vm0Nk z?f{%>?8i9*8UbVD6ZZOR^0fAwfm5V zh@MeBg=;#hpQ_EOFUjb)=>PWHZy_nQowaro@vJRg+z5cV$(`}6UAvx*j5^Q5+`3Cm zclLbtn_lle!p+{*S=2Wp08af_ZAW0ZG!A6PX<`CTd(cVq{Lv$&_TsCx_WmX8AQ8lb z)+fEZwe${H7kZyrY3){%cNtG_<@W7owxE7oYJu}PoAi&(HMTej35eRP`xK|MV^EKIxY*T4C-{rXqG#+c{h z_SgT%U)x3|JRym$uEuv&$&yYA5=t`oHv=d!NlJvb7T`y~P69?J3^JN1bgs!oc@`km z-G%p#bLX%{fNR(zhuz?}m@5r5DuWu8(vg(arAwE5=U#x)H=g;1r=fI|F9Axj?KH-_ z%Ac+~T~g@uX`V*utNm**xbfgMx6W=hFE<_(BU&my`bPN9l>=vZ=H~OO`~@0*I_aj4 zh*6IZHnqms#nW!J>Mg4Gs6I8=D1cAp1b) z&PQXOK>iCCnq5LKNG8?SHIV;$q=p(jR@YR)Y!_p&9vAaSNhFXMO2cq+8uo6)uy~~J z2wchpc*?={3MFNHt+v6T5*z5jJv;GSQx4w2a;>v}()y4J86F$5#5i_<@a&ce@R1MQ zmoG`TB`ebzzmdeLD@65l6lR|VeHI`TLDEwBEcT@?5<+4U$*ak9n5HPk0BELT)p()H zre1n6rZ{BXoiNy4X*Nh-9{@b=85jp(8iQ78R)Vxs8D*=iLb3y!PBo}3E-0_E+~Qu# zDd}TJ6Qje0IaZVpAef6+AEY=EVw#8`GGv2=E2=b-KI1P@;|6sRGU!JDI8>DsGcZ7{ zsOPn~HPmaStQ_Vf8#)bHSNo`)Je+1HkD0aij#itT8;KPmC{u{tMX!M3u4|01w+%ovj$3??4)^ z7y9#Dj5eZBi^^jq_GTIzr>t=qKvNa=>PpM8t2Ak4sFoBI3;`~Q;b%_ac~RA+@_3&! zu0#MIPmr+?qy8vms?g>&-^0cT{&@0Uc$fmH3<{#5Linw7Pe&(&E5|6xo_s+J`b2Elqf}9g zVA5M#%JC{zVJAN?Q=JQt@< z3sBW8E-HmgIW~-n=g<(~Xs>J}W!dQyU3TVFC$wm`Gwsb*QCeh+8W!04wdEMPEy{1s6J-vMYp4C;mOn^H9;C$OUWjm)>R+ud7qvB_pvp2 z1Xb_DRt;#sa@BIy{afswyYI6lOP2aOo_~^x>OD2h`Ol;0X7d}K()GYNNBNg}v^GBC zzG*C}L>cJLVop4MwA5aCwc2(A7*48Rkcm2+MU)p~%oj%5=Z?nCNxX*KtEc<%T0sPcv~tF9H* z=ES>+Uiz(b2{`DeO$Dvv#Ivbigm(jd0*y7~s150U#0N3AU-7M|pM`c7y%)7zU5nlk zUo_jEbxq;Qcl1nZ8RmQD^G|m!T>^c+GDpa$HM(f7@opGfp8Bl~gxp+dp-6HR$wJzM zVyLI6+*t6n67WCXdX>6};Ywr$&N>(;w?UzIxT2K?li;>oW)iM^u#iyf3r z{+x6lwJKA(Qd3hD_$2QUjd*K#;Qpk_+v-(TQ&Z!MmsI;VGXn(;Oy~0IrQI9ZQ)q2% z^?b&#X`uyWv=G(8C<2tEp7$C%JerVx@E1S89r$yer{KX(l27`U7Aq=)(*HEVy!0mF zki0rU2)dT~J6!*y$D2v_<2>_m-kGl~bJLmoTkq&v2!TdE;8Slh*r#@?MW<|NxNbFr z&5WT)Ut}nalte;ew~t?13e49IqLDsYXp5N_^C|s$iNJ^PL0)f)N=xY9>QGuC!mK+; z0GErpkOMYiPEgx;o1_?fhPn0JIPY+-H87B5S;J0DtTcRaWdwW|)qq*2@X?jdIgt!M)xPV2?TdCZ+^wW8@}Te&C;$;*Z8=9aUoosQvP z?X+s511N_D@N?;qOWyeljI^QBo`*_;^jVT#S2k4QmG^C7*8NYQ&n8Ru6+T_ zYAwuat*yX2+p^U$D=8CHBgTeu1Foc}M-oeFeACp4Y%3*DH;5<1%t>u2p9N$FlBE*> zTS%i|f@Wek%{m8T);SPEYPQEdJkV|({Szp3r6aAB1z?8zZ(J z6%t-~s6wWr)|3X|CYAC@q=_Vmf@m3O!%!+O{KO715-M6`OWKa_3!HIKOmh|wqyz^v z04rz9frJD$W;~^I8PR1i&U`0uV9ISb6}#lmIMP3302w0)8l61eWADCq-j1Cfvi|X6 z8%Pvc8FsXaF@#CE)i#vV-ZE+9699=wj{zEHV+$xiNHL^;)rQ=|q9irQ ztPJ4F0Q5A{7EIW9xZ^;kwFHUN=mnx=0*GZ$fJoAdYm%U00vLv&lq9l@1`m%6TLmgN zwWxgN<>n)O$2vq~zU(`xUvch{uY2Gi!|dGQglC~qYS3CJ1m2`CsP_4nysY_0*Q5Dl z_F26X=KE>JCcULVYokqJ>x`I_jVg9dE&yo(hJ_1I#UHhOd)n;?cG#Nwa!~8cvueDS zEvhcM3Q+RI7%nshc;ld-etmtPJ#bGSjD0m`2WkL+Xdie#bA||J>oTC=o3CLzX!n>k zwH(H)-(hIm)ioHhysL?1Z# zk!t|#-o4xHrrjzPuru};vuS)fb3wk!nR@6^)GkRa?M32rs z6Yk-SlucySe>PxOG5!A7(L(#}uX1ho5p0HGV{DXl`~v1_Z4UJf0VoXv1ZK5cT}i9m ze}9=h_xuK15BNGZHcZ3o^4g*sE70*@!hON#1A0+iGSN?7MgQ!1*jXw1;NTE_;y zU((6%z4yM`dzMDiZ9wT$tm%l@$q{c(y6TAGzK-FyY$jUlwpa0B$_OqYa6Hf|I`dbz*n^{DGCTrW079milx4YMkWXUME zK&2JSSJ-2ZJ%%*XCJdJ@b%R@)9HX7r2(_NcGHGa{RM0|E>4p4h9qD|LKf_ebprmwU znCoBv^)o60`P53n*}D2%d-%a6cJDpajDuNtNRtg5+9d5V9i!21Kv~9S8G|GlGYz1EAr)-tP!x?v zv~MxR8tyc?O4USw()s2KxVHYt_U+$`+vN8U`#Nv{xkO8qZ~8PilRVj)**y#U`NVB;S{o9cAwtKyqdP1K9gIZTGGgq_eQ2gW=+d z7_^%LOd!8;B(IR6MRjNtBjqEu6q`jWmtwSeA>Nr5AWKw1sgN|wh2h9VTFGP1q-Ewx zatT{Qqyv;e{g6W{L7-j*ummb;<2lyeoMx@()9vkddu{vf9#on} z>>|>ySpYeW1(mkCzR(_e$ZYG~8RRLC4HVQ83!nhDbK(F>697uicnVNL(l!eQKZ7|s z#u%p^6bAVICk-5nvJ?4L2gCwgPFf%4`_@EPy(` zPZXduiP}y8lzib&J?rMQHkyc;mVRrVQ4i6jz^rhIE72P1 ziidTToBlLok&dFK`qy;Y0O<_EpyPcEqV)A3>DZZVM-GnIySuvVqeDY>3J+s_V;NQh zle~CA8MH=1X~-$&K#^)4LA3}>5@rCP^o>nD_Q(T0(0u{+Cu=Pa70_vD7YB5lgt1m% zef5=?y}fG`K&i=EI?mZscbD7Kk5;rE2pvDuqE4w7t78fh1+zdf2e3f!`>@j#59Ucn{KLjo46X ztZuajA1twNKfm5KY+eA*5UG0SV7xw?=OwYJHN}+;c1~fg_cIhddGxVB6`Bll%NeeR zV<>O<{fBrA?M`cUwLLXx^;>NiO2b6jC$iV24Kqo5x|gr;ECjn2jjwh650S=Sr80{* zS8Q!*Wdo+gv#znQ1Zm6)%o+$-N)75mYC94x5SSz_tDQS{&hY*>1t`sS+0>-J(&wMA zgwi~uQU}yTAc-9THeytC^h!c5RMJU%_w02eeKL|&z;3~cl`A|-g-wRG1rYt{M}Ori zZ+QSWZbOO6QaVBM>4g_wz~J8tr~$0Ar=Nb>pRI3bz}84H&qcc}5+j!Q?Mz^hiI#}b zgr`N2@+S$SFd-}dn#0wwbnl&acGy4t(?7Z4ZrOGE?svcI=(YeQpM`nWC%w>^^!t;B zkk&lu%s0u-^Vsc6*Pws~jxgACbl~NU1%?KaQY2I4#O<(+2VYq$RDRu8rggZ%9JP0VSBNX>13Dz8(OjrsjlYr{mVW z1a*d$Ber^7+&11-V;k;f;Ta#Wacq-F>QN%rovqo3+2`7xy+iie_G7l^WUJNItg`yL z)!0dqY7vH-hmhRqzhEn?a_ynJaW@U1bl2V4xR1xMv$shV04W_w>WJ&{@kbI=aNm+p z(j}EugP8ua&eeiiZJB27Allicv)EBOU~g~VPF_Bku^*R*IIut^O}0`?mM5Irx>{Sl zY?;@vKt} zpC~WIXhu@1B>||6O}#!` ztq-JGHya@B*x4utj3~wKRT=7T6~#z?l%on!JqGZQY0FksB866lBn<#uA#zE1n5`xP zX)uqFCkML7mP=*;N+L}*H^}plRHkI?I};>?>fv2LKib#WV4jT=<*xigB-xH0kJ+K~ zNLS&4JR2HU<-wFT4C7@gZg<|b(6$mwE7Pr{N+77}17=eHw4kE$B?aYRiWW><4?)dF zO~ixRi+<||e`XmPy-Q6}mPk^9d}1s(0u7VT`#bug!xm0^gATpj<94yR&zb>T&!5Y- z=H_%ef3eTbw_u1qPJ00S$wGW82X)Z;nk<03TwA$ZYk?A5wj6JOl&PFDX%1GTCi$Ss zrd-Ni5~XGS)|WE@EEHpazDir|9igqHs+;m3l|%EqfF$iWUIi#2q3Qx#>SOwZ6C*n4 z8~T@~8-axCWC}V2;-z9FelL0^%ppo+hRC{qMTioiHE=arLwSv*4N;d8*#~4pt+BT! z3qUDz9zZD*bvKMd*Ops5fYPPmDU)iEY!k)dO-JW=~9TlF1*t1#4 zn1_lLVA&*6Ib)LvfbxXB@ha<|cgL-%wZ&SxTkPqrdG^dUBy#Sovb7s(tQ6zYsv5{j z?Q0DcwPm$ywJnW3v-C+`Q|Y)tjc^u%=$b;j)LY>Z9YvxL!ZYC*?&%n==}7eUOufpq z!UX_z+0m(ATw~R>72H!>qAjN9cnn~UBru~kEgIq}F9vfW$x7Pq8*jwywYMhia%Z3Q z4)>sHm}48(*4Q1JtL%aMN>B?dv@UFkbrQF~bIRV@and?_CR{al0p2t>u3ru?QH9e5 zv(*Tv3i#DJHHV|3XyZieB&)j)vt$kJVW157tlP) zuj)3+uhJ1y)=Jxv;~QxcXnj8km?uf#M<0FE{`}8>00?)#r=mLYZ-+FKM^9IE8h-1! zWSIF@xWLiVNjWOfuz{$$Z$5tkHQQ2Ku&}{SoyfD_{vu(!_asnnOIRE8LnT0bDIifF zQb;|3fJ^e)Y;o-+JmZzvbKe9|0)UmOtW+c=p(IdA8&bfid^K72U)1M=g?df(Qs~#=_!XtweA)iO0Hshl zVNCVRL0}DdsTC1&b_oCgKmbWZK~${H{n7pd><%3F-6GjTy7#_&JpSreks6yO8QCk6 z4W(iLA~87{a0N;Uaa4TirI+l*mtMqe>mByocfNxG?+q|OG9-)cHo%i6)J*BhW-;KW z232}8Uw&Bw5&t}&nn=|UiP1tfj#0t4?SKF8zlRa)u)q4Nzq0Rs4?qdgb9n-rDQhy# znctdFbnUYUpH;e_MP9#TY0gZ(s&iJ_0w*tDy6kl=bsyOhC@M}$D6s$ybvVcq{@VfUZrH@nh>fbYfQYJ3fGfT1Kf`mjlhKErj;t7XDB0veC0M!Qvl#=Pr z0!qLbxS6g(s$%WBAsDSmTfeE29sEj*;o3bmJ;;IP-|UG-^K{fY*I zG?;t=DFRw%14Q6<1fFs=NfV8?YWI>9)sFEFCe5zyP6y2M<>?SmNwgApFO>=Dn=f0o z)Si0k>-I3a%5r+3=mul~$z-!9h6JiO*9;condr`F_gs-w_zNH~@&B{;9^Q4F*V*sJ zLGPUfAV`3{Q-$iJ3Mo-kx1}VGotvBfWv%=_U%uRRSMEyeIMs2HWl2`2Xp*AXdnW;+ z_udbH`+N4B7dQX`TK19@%Epi{=A4;1Gwc7Sjj^r6mc=@41tjgy z?cHp9_ie_~fe`LBQf_!@y*JO7;u&>ddTZs4zd=@cER&g;8Kx)#ga0F za_^Na`TX3^60XvMTU1Vxx$@zFQtANr9pH%Mnhu}@FztZSfF1g@)lRsDQi^qtq}i%c zf}K>9SaTm1Mgo+`mjg-yliWf{c}19MllJYM4fgz=2HUc^2B5eG3qbl0wo$AY`?1!z zPP_QE~`#O3FO(5 zi2xf}cIq6D7s%vwC#fz9e2!2&zwC?unJY_WAbHbyl9wKciy{x-x>*aLG(?+$R2)EQ z9LvBsuCkd_vMiFKIZgpmNA+24NcoLi;D!cI zsv_IB2MeS}O94$%=oe!4vo|lX@OjCu--=r!WtW**YO7fI+_tU6o_Q|K9(tVmN}s8I zGn=_;b^=g}pwj4tye?3d>K_C~3rOWMenaK}2q#GbI|boSQOD&Op#EEK9g1G7KsHJr ze)ysN1j~K}%uyhmisj4gd*Az>z5L26aP%#KM~={&QDJ%+MdidZf?Sj3o%~tnmBKOY z`7Ur<&lQ0CgCG3BliZJ_xIOjsQ}%a%_jkT{99cuD4)D9A&1=-0V>&%Ok4sz|`l94> z$=7&59vZ@}o3}g_6c^d@l~s2AYL312-&m3zjT6;v(&|BAi*cjP2UO}B8M1*f>Pc?1 z)l}6JXrsWswSTK^-?9|GCESW>P#IYOfC7{vJ4p6H0JA?TU%t)rE_Xei_}Sv_3rIks zC;7q|$gApv=02jesJmU~L7_@Z%NEI>)#Nz(gW_m6%V{SECp?32%Z z!$1Fz07@#XhzCgx6AAJs3=*M$Rk&)LH*VapBZrRIIikO{uyP@HxaXdG7B{zN?ce_G z-%0<<3guecyJs&Gm;2q{T7#XoQI?snU%SqV%XL;-KJo!lAyBo-vTfTocbyaXq)H)| zH(!~+6jjgl3g&kSoetMf0bJoyrunSA`fvEIdx&gyUOm3+4Ns16;dvK9iVixb{q>OESri_9ZcE;zxGz5CT-bXZgJdI zCPc2A)sBzYG+!bRez=zr{9ZqTp878x%g_eu9jyUIPj?* zI&_$z2^Z`VOwh%cgDYvZT=EitKRhz*E}-kzuEzy#y$3#!Rp?SUNEG=}pp%}VNxR6+ zy+1|6mbHvOll>%CBU2>5kZaL*oRg%ddl>(AqOmph;R={<7cLPQuC>craBG$uK{jq6 zrG;r&am4@_GI0IN!vZYFN{iDV3kRgjgbX|rrH|EmS!79ZjgQGnh!uZ;D}g)`iTD3V zgO4aT6L4q6t)*?4mGc1ym*PV?HZqur6$T{hokP~zn1XvEz!yZ+Jqo3ct4a}3&q@dp zy=)nz*voTKzzi7}${{4vRYVFaO@$8yD1}A-R0zsrX(-kZ>bfU!jx(dIrD`mT1|4co`9p`jP^^InLJQ|;Q-n6>v{;Xw#)@djmQLJkZe zatUR-6qlh50Ez22iPjHS@^ zY6-HIp*~_=;w~xt$N?q5q&`5^9-gf2hbLydZsxTwaH&`MiA3utM^x)^ zJuH-_0i|K9TD6RboMp60xf07Vi2fCXMixrcE|U5$CFM1;%5$rGthbIIf#ZyH@=UWG zyFg$Ac)2oZkE@mx*scev>=E4A)@@3)^`uj0+wIhucHErdL_6NgwbbL>d|R_B*Phvv z%|dDp{RxpSN$FJL$mLC~j(kMb!G)`~6pdlg+o-;~&V<|qCMl`A)4WxHlKO7Vg_Xn^ zs_%!7dL2jBmJegFI4rw?dw?lMJY{)@l(3w!$Mrx|zUMh&2wct?LjUO40- z>ccoKAMY07~jBg-ggn=^y{`A0xV({{`I*-br$s6EHR1HwRIu{r(QN;jau( zlH8IDEHpG7iwZ(3tPwISP$rcn6uF$u-L71|0!Z_bojHBR3rZ#P`s?4eZ)0Wj&;R_- z_D>{*t=+h3lkI%)L3`|p$9;ud_Yp7CSt3Q8JA2NK9691?H-r-3{qA>d>(;HT2<5S2 zpw*;kPz=vj#nPY>HqS3B>&klsAkCc9d+FFc2PpjxR@P7+U-dq@-ukl=os9q``PWVe zP@>K`pj4PYy?PNkh)~zR>U=KV|0|M!CK{TI`hO;>^apC+!9poKwE!!%Vpg%Tb67Qw z!EFN}(XR!RZVjWx5+$rSW*fJW?n{Tbb18rlk&{w;Y$67S5-Z%PmXG;=8ZJyz_8H2> zyYFAN&jFO4+P>Z%-njuQA9Owdr3=?u?C|9}8-ZwgRq+bjxv|vVcsU)8j&$6;Qc3Dl z)ptqh37rBj=m3HC(I%BTdDPSUd%vioynkDJ2OLVr?dWHp;|lSKr)2_(mM-@`R6Hnh z3u`!uFtp@^Bl=~I&b=@0#M>V$>-f@KfdSt0DLbW ze=ugBd@PHhPP=id3zq||R}jjWG*-6N#X0ue?h1S2i88CHiFwMxQ&CBg)+SK|@vtEJ zSOhGI*f|66!N(#!i+e~Sz5Q@ypfGFId}yG9;m!M1*TWdSPBswSU?B{Vi4T#gw z-et`L?bgR?|71!QQb+cHLL#bKSDa!s07?&R#&u=u5?h5eO=UH%XQhxzLoA&J0EIf` zNy@2|)N!n7;zU=IOAy!_hZUI({wAy>CSBW(IFHidB$9=PNTqMxh}*?8aXWgf(LOnP z$u8dPw6S;*cf+C*5GFUf*#6{|Z2RLs&W7L`i!v;xQZwLDG87_!Fx3N8&BWVlA8k15 zaULsM&Pg`ODRD`3OeYrHRMx78GJgr1Kpe>_@k0k3C?75x#bjm-E4*KQ9JgP66t~+g z&5)zt2DpP7d331_jOSP%?np6Y{J@$b+rGI7H&U$AHm2H&m2d=A05axsU;a-(nm;zt zgFGSUN^EJVdB`l^|NO6;cBT28r4Y%jEjv5Q=i!=< zpE`ZkK0SEYjvPJ=z;)RAu+URKem@b{UVuw!{|o!4=gumd1?N4<8Biv)Nl@Xq_WB-< z@%{V%{C!Va3~p<0v#r~<+IPS6T?dpZSEwwO__OsJ$wx_jw}U|vgzlBJMPp2KAo;V7 z%>6zepd<^W+Uq&?-cKiqL^p2N+D5SIV*nvYLk4MVya$(v9xKc5vQ4Yt8+)u|8c>Qu zLO)3zPsge(UB0#IUjVOX1fX2pWt;OZ;Y!ap=N6QExNvd5padjC)g8@olx71;xa$|g zp#+#90CO&&q?-oW&)qNhz{L~ygaksH5BpI5EzK<~l(tfZtAQqBqp?{=}m`h>e+$PGi$m$VwRYSl_29X({# zH8uWd2b9i6fRa9oXid>7_V3?sHLGhJJ)8~)sRB+ExH<<_FyA}(p zAf{uBfKrgiH-8@*cz6@93si?`3ndhdX$z%!044oyZaoS2THN335>O+LI(fH1P+8I! z$Wmk)P)b-Rih_16 z#Z&E#0mg_yTtr6f>g`d8Z&~4vk60nRMr*6Gd1kI{S`E+uk5N@kimj{$I1>LivQue^ z4@LYs5``WqGV~0Rp03nCI1WHI>Ml>cJ?#<bRA+jw5bm0tgT(+4_xs$TghP#vAd6G7JsNkLi5k8lBdKx{?nfhM%Ob zt-Y@Do`mSR*O~$C8sW@rYRt11q5<|$$A-s-t)wsuOSEiTu{6`FmStLXbvoQtScm~C zi5xwzkQK+w5r8|8*yst=Gw~-$vD5pgeW2*k?gYkoR#`Y0qCO2lrrgm*1lrD4CYNQ9 z1Xo3*+ySH2>qW1qTeF3?h`vRCqhrZOe(mQw?mPPzUI)0Xa_;SC9zdzDC(U{~((Ei2 zN(Vk_w9ik@SSSTRsWri&q`OBJN<4UsB=Pmg< z!Lq5j84wfhu8%)qmG(FsSY1Oz?;EuJ_mA7ld&UwLN)=dyN0z)Q+Xz(B0-b;WS$`u; z>czB$lKKE1?RC$I&B=@Y>%eaz%Gr{e|C{K(K7Nxe(CE| z0gO|zQdNGU`mSGu-$u2``&|IEF02=o4ijbXg9G(;?s~u7#I(q^ZxwAt<6cKZ5Z+qOCf4y!_YV)rWMz^iakgO@E=uCkJy zT9>T+1pLZEDtbqxMLl=X`2i8*JD|it0Vk?AW20E_F@M%vShNp%Cjm~ib+;kNzDD$- zLs%-ki!5$gWo4xYwt4C0m+YmNUUC;_(MD(SqyM%G7cbbYTeq06ueR4-eGTiVCv7bpsw)9_G)76}arX|OOn4u;R;v#CmXJa8 zC3>Dd>$!8c5HLj;qiVHKna3;-k5SDQ#0zlcRt_0^_VyiPK2eh_j%vp}~o{HDC!0+PQNl$`?E$ z3@WEjogtk9a5`nDPM!3@?STjGcLhdoG7Tu5JMZona>00T=YuA*A-cTLPgR_1xsL{6hJdUKOX$5`Lj6GJRGupfr`>P%6NssR-VS9IRVJjlcq= zUoS;kQQl0E-qgJ^-+$}PPOK@3RMs?%E6$Wv5tZ!$c$2nmD+2UD`K`wFib?0BCZ8y} zsenqiYo~~=Hijb7NffUub`B1XeUEIgC!g4WyA*spxbz%9Id1PB7_+PGpc~@@wy7+| z{;$`{namd3l8Ts>SCAJJvglnR)m?QtMc|j}b=Z_=f8XeUCRrLR#bcyNu)ugly}5Sv zDj}s6R{9qXG^KL>K`cXMiBtfeSbKXr?s2vB$EUDbxPs!yeMquqT8hutV~;#$Pe1*% zZ6F$)R++^?rcLD}4vk6re<}HH!KCqmB$Zk2SiB&gNLZxA$FKkz%e1;%xF6h{z;bHD zJ~=#WHvx18M|*5|0xlWI$n&r|+F3)0?lr6I!H3D~qp7Smp$iL;!@?ppi$df77+f$s z8f&u{?mV(Bh!nBmp-~n;aAhOrMLTJgRV%F=_dQp*ku7+UgC9-xal3V$)oVC_ zE@G8XTMyq-|Cn_Q3|s#QmP?~;RFWLtEr)Q^aa&$6N|dKU2wbbMuq^?kG8R<~umS)C zOR87~R&PXwo4|4@J|TBF)v=(AkU;APmJ+O@=<-?tK%ad_Ygfl(k9A7|{H;Dx4Q!=4TWks*Dp=l`IESNULS>!zMGKUxTH}%x+se!gs>|mZK%$&O`9{RXGDX;YH8(4 ztiiAnQ=1WRp!zl?vU+68)BV~0ZXUS{utfO;3>b4ODM)zR8i_vF2sl;Z^NZYUTp%cS z-ADa{R~Wy`e1D|uhZmgh`~t@$3#A3NF9IkH_oZPiltu{q0ekO*Hal{nk0@^dk0Ytm z7D}BE-!}t{;zjGCkB_TCkSJRR1?iW*v$GxdwRU7$VVkyA(nbK?c<*imf4ebm7tW1g zNj_=^>96Vr;x>jm(Ec5R07`=ZN~Lb0p^c(cgX@IY^hZq2>^KE%K zsq;*9pb3jRxk8M`X}_ZcNFbd&)rrMVvmHM*#NvQiGeHMvOjreF+P5DmwS7+!l@YhM zO$1apacs=qd3)H7p02m^br*5|gT>=U zI|XExe3ct8ztEh#D#Z|f3Q6E|i~&n6cM@WCMFWlA98vRQfnj}WSKU3hIseN3<3Ikx z`*eXva$SD))mQD+S6=l#T>bd;!Yt49-asQdM* z1Sr)vcC6~$w&H-*?`iRM|hXZ z+m`_-g?!z661#hjQvN3ZrNO~LU;Vj_uj<)zXPx6H9S#tg5lfIt!7ov!xJoiTl;W~| z`*wH|%6%Yf!2L)h$!E`;!O#2nbf`!717|Ro8CpNqPqKj0?{;k8VXN1ywwjun856do z4q26IRv*tfFW97O<`#75K<-sQNyR@m&v&m9zn^ErAdoDt>0_E4kvz(q0429jDsY#c zf+D%RMgG;(9nSBk2=AGjkmJY%60qP*qjXA|iy3kxMC zviK52fRe<3(keg+g?rMiET-%iKW~F%w9#rC0F-c%TfHjRo_u<#J^W~im6oJneaUl( zV3mSpja(`x#wVGyPTIjklXm#?9y@XNhTUvywHF?)vZtS{B8piyq|@1U?AVmO{rKIrA3+JRwW2Na&DTQz@@e=jPGIX7zIdl%fOb z7Zs^S7Nr9J-+S+U`{4ce9Xygdg81lmGtsZEuJ(R)kpA{8mZ29fUh=3tjm=H&9wMb< zEqr&|wr)#sD{c1QC|Y73NQwX~kD#e+kuO;&xB-c)Mgo+?y`zNU$?Cq5x;t6@Ctb!u z;@sI$0Hz_7{{eWFuomhawk}rRYXE&$lor^Q4H>p+V+P7$CV&upOXaLUA@?lYq7tv_ z7E0*=O&SUmK7NF7dP74azPQoR27eFFUa@io941Rp%qTM@6j8aQiN~nDb&}{#kceZk z)YKHmEpFVJ+eWPkHLuTba$^v^r?S|Q313SV z?vxW&T!!)o$cToIGK<>;0GUXoT?Q1-t=ozo3tC8a}b1QRshbeteCQuD^jgyRVHmA z-BzyQcvY$sN@rz32v7KTC9OtEsffiy5}(cc&j3mz!^|TH0pHf%YONiuSf>@+%BmF} zZFY*bEhXcQd4uOT`H#v=Tl6>i%w0cAB#~I=y-c#xEoWOO4bo-+mtBBFu^Y*-QTV>j zoF1@u-)XT!#{e3MRM;_;mH?DWtgUa#ZUZRkUUYTzS^OEJ+!Ey22B7rEk9OM2`*7#k zund>NWeGqDE1oVmlj?@J|1f|RR!XPhHiT>D2!db@NXZl9m1w*$w|+hzJ)fyrg?H9qtB8hdir8r!@z z)wXOC4;sAz7G9Iodt!;P7sr}pN!umAa>r)1f}CL?Lsl7;ynj;%tDFlMS2NS~{`T5a zuQl)19QyOmKlg}hM~@zbGi%7_>3jF=b>7mAn>PZ0ZGtBxqK?q*TsiYTLf;nHcyIue zROpgp0D_c@qn{nc66iChsW^P(urC%r{LrKJ*kg~`uH8?-m%79AtE%IiPXOU*3~C=Fs^8AW+ZxV(J=(=C-miY4j6$2A4^Wa-vUI$tbL5>8?auoztd!Kp ztFQcxER-Y~^+`$nQm8k6ihB7?+`bZ*w^@Q<;83CY#7h$bI_eQZEf2s;P+wnf$B!R_ zaQmFQRLHF&GFxS+PWW?2Zf?t26oQNTVnuoDwk@vsC_0xS6KT~w6rfis%1?QlHG$(;I2S73tasy!?xA!q14?uA zy!id@5(s7O^}}aeD(GZD3HKs6lnRL`sHlQr^&)f*p zkt1L!+JXWRzR&C6o@eZ#haR$;n$@^6SJHgc;mUfmES z*&Kr-DFqXtOvbuA>QE`bb=oaDMVu0|pj2L!=VOXV^# z9ss2%LTN+{KZ*Qs8;5_Wvu(<*pPRC47pNoWiI{rvw)GFCVlf3Ncy^I3DJ-=I@6Weq zU&^u_JJYQ&58f?Y0^Pp-gI4(f2314`jqeP>atf}=(de(m)M3iO9AC%ZNZobaC;3NvtuU)?5%eQN^%aDE$UTSRuTQs zlBXr8^uNBbqbK&cmdfU<*d#A^t@XS` zq};W&w|$;jSru_8xqBP+TO4ue0OT4QJfEJS1ppR2@T+?Jf`uTbL?0gfhyxI??M^OkE>;x^ zpY=~=B&A7<1B#M-=+Gg%ReQ@h@*djxkoWbwpWJOqitefQs?9BYLb>@7{^(SqDE$zh zWd)_h6Xji2shT%wQ9*O*%U7=0QC9qtaNW$8*`LDPAnb#3833ga<*ltX*Nz>Y#6qdhK094!7wS9AGFDJ1 zl?W3vN>W~03l^Xa_R#ix0JqI{|AWh|Y{?Yv=VVBASk>iA1e9jK$>O(#BoN9roDXyK zP{%`=2M#3xN+od2IfoKlyZM+8-_1fP+)wvU{v4jSxWD%#5bA{Xq5Qunprp5nER^7R zOc=fVMjT4ILFl8xUdO)S+t&stO$(1sRX~qcJ_P<;zH-@>k1kva)R;9W2<(xSQEm>z zkysXGWR$aZy zR#jI!<9et_q2c>?6)Ji2PTxOhoa11ku)}ZWmbdPqv5yA}Pj#yYIeAR%t8k_^}lG#ap9x zRNN>H9ViN;wrgvF?Sz}@{%v`7-}YRTKdf-zd6IRDTi-~hOKc0tB^*~Ds!6`OK~2_2 z0awlvAVEPAKK|rm511fxU;+JdNq*sl7u>yA1l=7S?H--;{JHZeBDJoJbai#QLQ)AA z-b3)+-GASGSUhZUZY6>JMMRC$q?;}k#YBLTKFbw`vLF{KD*c@x{5X0C3X_11bby8w z8wbp3hd=1njY%Sd$zo~DE?&W6shjbkw++QAoifU>b(Mv-Wn(d5O%|L=G03UY02nfP zc7~HUi?~~Wl9Jwch_R}-rw?$Z)9XZK)pEC1@Cl|AGPlf8{J8R2 zbvLH04lbakran(SJy?9<8q_@$xAtMII;dX-Xy}C*X|`fHTtMP~s?M}EHCR)XrZetA za*ms0Zs9l_D{%*x(naJAw~+xF#87TMY91lU$u)V9f|+W={V{8;PqF%&aa?U~lj;Gv zvh7A&Ha1UEFmr9ksx*6M&y?+a1lP-|JgZp7f(uqDv2+BCg@aNGmSHK}djbF`J^|nY zWRspMa&;^p^y*kS#KgIzveG{^Rw=Er;Bvr;OSB0j41kh`SAj`#n{%1*6qUUq@cGZs zkkvMHBmJW|fEZ9Z$(9J|hq0=WRah%lVV3}uEW43l9ZbOwUP*nm7mf;eLi>Tx%s}li=nVGUu!j+GIYV-ZQgM>04gg*&DiL?|T zv8H+@peQa7SSWE>w5iyqw{S2V(A|EEP4}F2U)>|zNdN#R`I>B@6pM}UE+fcQbwk%G zid_y?-2J%SHrjzh07|zp?e7OrDuoXUK&c)+ALywNF4xPDMddLEQ2O4J-S)~$07|P9 zfKnC>lj~dB`|Zm0Hb~(6>}S82up<{^L|QDf>e5nsZdVM@IL7=-d|?1hxRN>mqcZ0) zWRN|D>1|sF5}O*ozguD-b{voTS5Es4!VkWzJ^7*jdcMe;IFuYvV$m`pf=(vo#u^5z zz{qt;^;er30y(4|3owmmOqd&=tRpH3Yi8so8kJ9f6o&eXM892p2E{?_AF zwtw$RWR{7=Aa0$to%Zerb@tiucB^k0#Z3-ZSr)UFU>W_|i{{pm(3X?lY-{uDZ6{Wr&pf>mchBWS<--CQ4t0%V-YG5uN};NK zZTm2vnfpK;R|B4JgqmDMFjdy@at$QU26V z`IgwvSSUr_P>X<)x;Moi{+hPXsGU~>MMa>J6pw!Rl16bY5D|A6j07rafRd$>fF%J; zD&P!O548fKqypAGWvL{N4^NonjQ2aIdlkc|_A0N0h((&I@;vVWOqQg3o zbj}|V9h&cNH0Uk@O7qF)n|dtNQy&}>)j@S*5m5T(m1ro-g>tS*_pFU_j@D|UiH6S2 z1(c?U4rOWbtIx8cLO=)rn+z0Ek#f5m5KaZo9mB+NsEbu;tY?1t%MSa`pEO%T>#!B% zVkxm9*IxVfQWW`8RW15GQaTfRtcW5orW14jDf{oA<=DqW26XD4w;Z>rn3a?(!VC%m-KHk) zK`vne6u#?ylRpPQNyjx=*Z13ywbtLR_f_kk|NQ5;75DohzytR`;L$e~;#q)eW@g4T z2zTM)MXX3Kz~yrp>!HieEus}bag%J^fN}z-(w5CzY}2MK4$$W3=K@wlN`@3Q@1HgC z^B2$&I73jJG!fL8F@?pF(&%uCM}cc?nXs$pu?#vt$}`*S;`MfGXN+kCAS%erwsMrR zO2W-ouSfwzfgHD{5Ks))xEdmaRm-YNfRcFlMog=fDw8e%1<9@gm!~Dmh%!Welsxpg zlm%DqrN|2;kp)#MJWuH6fFA>WlUU87Og4;SQ8VJeS0_MIBLGMpAX95M&w&UTzH!Tf zI650+!>50WWVpmpCJ;x)D3_?OlAl)Mp&aY)PQ}%x88EN~%d!GHd9}d0;%V^aq*ztnux+UBAsoCBDRsGR-&W?Xfce~i zT-H072E|fvf5Xzj%Yyfl#YI|bKF1*H_AylTO72Ta$V7+`TlAL?-pu$Wpowh4>DJol+i7J4S zzgzTvlC2-&nE&4E%@>m3Z+H>1^>$2_$eUc=Zr4J}&3v+A1t2nun_*M5uGxT+@~n(0 zuc{1?{nJ+p2={X0h-#H;elL+BTk6ct1Mtg0!p9Ju-DWq78dMe2FV zQw08|QAd?DKFPW;YJk)nl>x%lm9saFImi=>qTSuPfi>(g`{~bqV!y&tsS=CQ3Kn@q z&i%^EuK;Q-cjZg-bAPyQ#!bWcGJS7lEa_oB)_4}8gWjid199;wz4i0AuK3(KqY+^80>CkdQS2-_j}Sg&ja7XK7b3!7D@t?2KsaD z3Q<>29`CmIKE7;+FW@_xv7U}&1M(apjaqhkyR9u~0Z_`dJx{F#P+CI2onoa+Bn21 z0F;#T4Cb%-@Z`!1LHL0-Z?TDX_oV8HD1CFwa-p27-w1t7xMnt>r2YxTmAUBehz;n|iM6Jzp$;9Iu>bl=j(u>2JjVOz_xkPiU2)sDcbxFe)wsQ_vU8_m_Tjs@ zGXW@_uj{m~fgW3tJ!CcIllIgztL@1>H6H0|*$Vh^&?CHRC+fG}SADMp;Bw$Gq3-Lb zHg~Jy-6bOd{Mr;OLGH;v`{_^Zr=(h}kJ>xiQM5M_iRWAP)KgF4p1j6a^#$%L2}qI~ zgUGs196#=>&wYKo6AC~T{3O*iHRf&<4?b*5mo0_(b*Z~iWMa)FU`fRkZDd4w##&|y zZjeOwIUnS%^HVn1MgA3h>x3Y8d?L#Vk;jUH30t`gtEHN9 zTerH{)^5d;Wors9P3e}4(mXMNYueb514`{3U1S3QX4MK-odJ|QQ_7fB`Y5r+j?7Rd zamAxlU5QiK>IL+#wRHlZW5POHu&zNLsjI_f=o*S^!;rQ2zz0RNzJYkR^%8=*h&q;+ z25I}!0sy6atUNMVEyFEtX$-5~RFpW}(;$Uck|mdeA#!($_46dGiCj;|dM=g+@RDIS zE_d6FD_!uDvUKR;@)@Lm`&MLo5XX z+LV6k3o_T(OlbGi7=*MbfU9g#J<NsM5-0%u;g=|C4nSf zm|P@z@jtR)&}1Lk0@zB1JQ?|tCREolco%U;)OeBtTvok@mzjCcsi)Qa9oH znp;}nP-(&Sz6w{16e3tj@i0p#Q=6CwtsiJ z?RzF2POwzV$)o=PEKfnMo^8*!UW7~vRGQv&o|Jeu9S&br_Wp(6>b<}GjTRaJC2lSY zrP~RYxA_4j>R>2*_A=hpW z5XG$o@OXK?J@`<%Jq#dMwgfJwktqVxjM&fK?Xq`|c3RI+H%NE4J&q;nQx6x|0}m~+ z`*tq1vZY8U)<=S<+l8hDfE=Eg>*G@fmU`kqQ{SXE6cKbUEKI$JfRAAoZ2Nkn%Gwo$#lmPK$4VjhRW$W_V?I8fAXZNha zqN>aTW5}&qeWUt@ML;P@_+QhXi2YbFTDO7&KHg_Nl$F+|J>X{?qyMC{M z?cw*URV|K7oezx~_4wKx9Y4Y#t=;5WUg5`~I1GY^?Q{iS>e_y1CE_WN~{PLhb&uMZ~()d9p{Y9`?0z~mi zJKx7gV>Z;2X?-RFGgA5tLo>LQmRLo3kyWoB zvFZ(^6#zLa01XSV7=pK`4=b#CI5Wg+QnPwFmQ|SVOn2gmEb!gINL3qv3muibBs*QJ z!^5~h%2jKG{Rq@fEx57Vg4DRao@j7*P_z@ttfRlfIsrh22g^|A%5bAl)HmF0QOXN( zZ7DC!u&U*NAe9hluZ&p*iFpq|B{eP^*Dbh~Qe1h|V>Rx?t}HhpTKHBKy9c1b0;(ZiY9BKn76P*xExRGD5ZUxvqB<;#|ns;jCJY zwbJskEC7;x+q|g&P|2`78-!DfHky~~7Iyu8xV(`XaH(%-tOq1rfl|8}{yYFBEPyob ztIP%TsMR}|AZscCO3J%70bqJZy-Ya9hXghhU829q2mHIAn)63e(dJL(p8D^#j$`Bn zFiD`2FdFew#o+IWVNDh+ls=iyV={qIkoj?qz=FMOI8vN=(b5Viw2| z&AlSg=r2jx(LS;BPpTW*{9N?$%l%6|RedF6>i1-!RGY9+5-InRrO6gb$s9_Fd`)L2 z`X0>M-v%CW^mAOBj}H<7E@lUA(N9x1OR{ij-k1hokN{5w zR!Fh_!3lf&mxK1=A#cNgsS+?AyHUFPveEzBdrT9c1V~Nq0y6w%kF4}uX8f`d+ zg;FX>U=d(pc3Q8k&hE0uwrAT5`znblU2H|Td*+u)5?m7iB`rE7$y)Ed;I>eGU+DOP zH~RfOp*p24?2{$obyIbfB(BFg+I-+pk`=WmEf!tgk|p-L^Ev4K0Z?phA@~OKe9eW^ z!4L!}DYC2P1JlEEqTNM0zeu@%3zxUhcEkR6M5JE{pfq2jmAoRty$E=T1O9kJW{FV) zjS6Q9<-<9YIHuL`>D31P7{Lor3XR__lysa;_X@;(hp>eJ06+jqL_t)1GJWNu#0rWu zv}n`4v>NV{kwhWtxw@a89V(WtzT3d3b91*S{}GwsM*vEHzX&MJ711~9d#Jx&)}grB z-vKB=%3P=jRSY<;j3?ErZ`2F_4rex$W!V2Fuj;>{y=$-$pwz}d(=I?Mtq^^y2qhjD zq(T&K$bH43l$LPIk>ZSlho@UN#<7$bx1&c|?307_@W#Opm%hw4vC{vCf0S*{?oR@m zrK7Qe-`d^<7fc%w-UjWz-yF9iH&n4=wglz=)x9y>_dHertFfrTJ)*WY#ZH}$WA)QV zM4%44THlTP@Br2~6ZV~#*V-H32AHXWCkVF_xzx$SSt^bQlzFXaQmZ~~MyI$#L_u~D z*pFKkmn%mHKmF7W9ykEk)8_`^r=EPmc0RC!{v6&SOruaKyss6< z-K|@{!6l_~Hj5lO5TKxupez9-0x0i3+K>yPRP z|H7tE0zb6rv|s1nbR7Ld$0!H&89fkpH(|ln+zhbOh{aG#+?t7;*Mv-38p;7f%B&9# zm%(vJZcui!abGF{3|UczWzDiQTeCq4t0i0-WeJjxwNefwz2eJa$a4@5{AZT#auvRz zD@2eweRk50pECzq+Oa^;#Apfb!Wt!Os}1})n`3e`^9DP7sH)CmTB9oitWD5B>=QBTfKgW zD1Nx8K)O_b%i;L=FmsC$yM4RfZr9h_vgJ#$Y+A=T`hcJ~^Gt732qH#u_dExcqLQED z9c76XxvC)oy@)IH`Veh$AM@k0YD+jf|6bD7<-Yez_=3AzN(?{1#0EnYS7qYrh=tP6 z8|=WZy6s{;mPLKyP@*0$DYHgga+`6~Y zNKP&dbuQY%o{#g*x%`?h{SWm=<)Au5`wSdPvd~$PAmt8^lyy!z{o38~7FjCMH^FHp zH?;U9b%~_KhV+yo0xx9R^&60M(;nad<+%OyD2fS{YMf`^4|cU+Cw9BV#w zBNkZoZb^WWUdH<&&6%+*^sz3yp{gVQ662rx{+8Ajf-xMj!-oz7gdHXN+p#EmGHz&3 zKKZ2W*}Dh##ud?TR5z10$y4{zedgQ37~}mS*M{xwx8Ei@>JRL6BCx~KrAzG(|KJbZ zGO7ai(@I>XrB`VFE}g&^Jv6Y*+#3xxvb278K8L=BUf=sA z)d9`%BS0y_B1GL#T2^{Tls8F1eU3bn76GN1I`NeON}&PIJSytAHQ{q^1Ru0H%OK;O zDw9b4MgvYX@Mth&@Zt3Iy+Q{%rxVtBzb6G8fFXB_^TA8^O-yEV?|FJ~{bu?Zo~39Y zP0ss5pOsf_!AeRNO8@8Y{|^JT`emjbwT#SCeTs7beaqaZ=IrmwBp(BKMmXe_eaK%i* ztP>Zt zw!yR0PUN*)al3Ur4%zImU9ZFPsC^Wk9m3MH7*U$lZ3THgXa)YF8>Uo*x%DpYkvrmd>XL}moAAQhJ3 zhKcf02Eeq8R8$1?lPPycJvrLM-PD0Bu3v-9`syU$+K64aJYcn*BjgwB97w9St&0Qf z#Q_M*-~lOPVm)Qqd5VO_!U->>8kB~WQVf?WAHrvD&qESl^zw}J5`rdc{NXcSI5e{% zCBIzfIjZEp<74>l2f}F`)Rurz_!|8L%MZ5#k$i~EH;|6oV662D z;Ud;*SZRr~su!i9b9m6obFlO($)>z>Y|A<#!m%&rdvRF?RwX&Zan`i7j@gAP>f3tlt#>=^C?xnhYL?r!^~>yq=Q3^o z^YoJdO1ih#lK=uI@+a^wy!W&;Bq!fgH~4&aF(j`2GIl)3AE&+_fESmyI=Q?7=*mKA zHiuHg=NUb9{tN~{Ng($W?obm`BP2Q+K)%$J0)XyJ`a5{ksGA?W4XE_NxU~?a@D@=D z%QE_GXaETHuHB0RA&CBfR$17;3L=W9G zfjchMfO;wDS{A7oRRSo%yEJW~B$u}c@|Km-luYfYuO4kwpi?N5L@~GvH?DHMy#sdb z>NPum{(`;p?mGmUc-MK9DhRM3KQH9aoB4~# ze;CHMun*uuExRjxBFg&R|1OmGg^u6- zZoijjL)nJ?9YUaZR6jeJf7E?JKxw+3akKC_?C-e$;(>co0s$`wZGIY1qEnGkOFqT| zZlNR&rO@8ks~+jMN{fKfOwoRAfYRKC92(x-3Ar#P?Bo!8l=ODM0gDyi_Xmq zCgHx}J~P)w*Mw*2_(Io&-+Yn16wbI@-ah%n{vQEKSTZaEN?$~B_ue(3?sy$dOsX`| z41m%kGqeI+9txQ_EHxI=%tg7=mp>E%MZ}$6_qfnN=>6?e&X$;X|GYe2k+^n#q z2(ry`NV%m<4wHf+7XYOUBKfotiLK4fo}94LX9O7Fn#AJ&=5;yt#&?(6o)_dg6>WH@ zxJyV21jDtp6L#QWyZ!r{So7Q-f<$^b+$1IT^1dMer6J2D+GQSOfy0FV?gON{e72v} z<943WWw%-(k%k-R#Yd{`*(a-Q+txIQmQyV&9~enICV(H2Iy<9^M##)ezpEUDJ~GI{ z0VP1Cu+`OS!d>gpf8+*n^X5(Gy^w0;VJY6_h2tduKabMpy$~JU78J$L-XGA-mktMI< ziB8Ka1jH(;@o0IE@5;dK1fT|&v(h4fnk8ufEUB#gGnpVCiV!BE++Y)}(#OdM8PCWn zyp*~V={tIVaZ9Ogd1Nsx9w-^!3zxznY#K=Cu%DpTr1UTD%M?PONm%VRG~FBG26B=6?tJ1mzRq5*i2p=<3Vt$XLYv;Uw&-N zKKOXZKEF0(&5DdRK48U}LspSHgq2CPJ^xa*Rj-D~ocB)4z*P@mP%_U-PlcOh=Dy(_ zdBeoJa720**UIuv?-~`@%#|)89p}H=nl?WAraOnvi9?B9RDbm)>T8+YAq!ZPD3dW1 z=uuQ@cw?{vk-MLO(@tDX&z_pF3ukFtxWd)q5_cUJwsUQ_(eY%_Gvxrw!!;{yT~(q-H+0oLOsp_V8jvxU`-ZVVVlBYLN5HtZxmT4 z&Ag4iC$+xt(^-4vTURZ#`R_SBb069SbYJC9{|?C~0ZLf_N`Hy9(d)0KTjf$n>6c-NksVo(H^T*X?&7$8_IZ!J z^Fgg0yV7a*uUlz5wp8Kr2B7q878bm+K#$(T>%oi|c-oAd!eL#h8l;BedmV^=?z#I) z|L|CW8~WGPDL_f2+#?=5pd4$iu%$yjosmwt>w0xWTt9aUfD(-nOlVvtIRc70lm)U*m%k0sIa_xy{uvmm>KH8v`r?HC*EFF$N1&){m7@AO&MhBFT zE_sgtC0tqMMy$w=03*req5uO^@eKMaTuS@o`de>5{NWGnU;p)AokvN0N&=K#dg&$G zfwfWv;G0(V)xT*W!L7OI-`s)-t2Pzww7B$HUnN8RSAIz9D|G$wW5+#`=;ud2$4co8 z;NF-$u=63?`Ow4mCFM39KuOkVa(m3ll{I$s4qlh|ya*`WS*Bkbprl8KMtx^C z=06f$uK^}H?~R^@A5{WPL}nkqb2OR%nR6TceEFJtO?cKqds!%r<9er1+KYhFLQ?u> z91r!u>p+;GuwMj}z8U2=H3=&nRHM2aGAsu>RN!3Pz8;Unn>xB+;Wl!Opb*u$iXMtN&T-PpNX7XlYWIv zJ$LRLJR3KiGw#`EpS7nU=iUq;w0ZL;l$gjoSirxmM`fWSMXk5D55A}tS5nTLIfYBw zDQj+OhNGj|SGna7H6uFL`n9&YrrHPj5PM6M_Cu_%IBOVbpVH7NU76t%bF!qqhH77C3-*6Qr7FSfY@Wbm+ zpJu8VrII)n>KRu=BGJ3+Tw>#P{#(D^Pt8Ck(IwFZUURv~Z;SPZT#H0{9LM4!HYJx+ z_?=LoX{=br0U`o^v?51YXmzztx;5XWYu(n^)@dzW9atIW*^~(`n8pm%F-5Xfz9KFu)kpu9ctc(< z2~g56rZ-&{z9%L=3(ZAbDw1)M@FGBovJjvpu#Uud@=6NUXleeQ zD~hmk9Kq!h06M}EbVCaFE`U-cfMrG|b(Xf*NHo23=de&Z+GW2y&}JuY4%j0bR|3SY zw7pMd+OyAOQs1DXroHPug5~(k8wc=0@1dhA&q!9$r-a;QelRVnuj+&Hp??l2)%|)v zN%;tUWR#~UvjI?2eNaOX#~ZUmE>S-q5R&@CbH+x@t^saeBbw)d!_D^b=Pg)}^;p+P zpVgEV+2aqawMTa@14K!K6n@G+I?!Yvf7*m~VWyp^g;Ncy%~i`F^4^|hPwh%40%)og z)7KYJev9d`Wad$V>SK6?WtlU!E$}M^iMbDhX(lb7e`yAkF z7u-_syc1a{H8wTUk2cZIZ?Y$zcpToRhq07;z+K-2nk!PGR{E9H_bbiXyuNcp*+_s% z+N(cQzb?+bGq}4QI&{cB{OBXxS6glUhK;su+YWpArTu_d`}twwCh7}FUVXwtqF3MX3rs*p!1K_1eqYBjAKKxt|bP?{_LujP9v+pxdmp;Q~y%`XZl>G#R~a`+tf zcieyRz&$Ae)d!`}<^!OlV+&a*c^y)7XN+C6P?}w=Un`)bM|)w+&ciqUn>rCqn8q1A z7XhVjd~r_K(dofK^A*w}p!Cfz+b{YCnjcR0RZK2reW<}k97=IQ1jm^emcX;JeECu= z6C+1gbV_Wa(M?R`!p%t~0E07hi8LVM$K zpMAo!Wx~)c|SW#SPuf3jWul+In8f8*0rB>+WBJhI@Yi7jr6NlyzkmR7` zgDwq0V2G?l{X4%sbLK2AZ%6F2&yF~slK2N6e&`|RQhNOH$4yE6by95QN+NJcnb_Yc^W%a@1*cgaqiIO#493LD)IVYDLol$VuTO?5RZ;P=7Xu?-iHwVo7-BLgB^ zZQ|h5CPgkvycb)@f5hRZd;>xO1Po)D(bFl?^a-9l0pK@k7cY0%`5T=?T1&M7h^&h< zMy;%H#Fj7315~QC8Y01Mf+%+#yhY{6Q)wy%cPm#Eqt$)6h{*at3S-!0l^~!I$$Jur z5aljhAr~oGFF>k1#c$z&8Xu$Hp?~)F7}i{7%>ZEa0FAdB1|gYlvxb&FtgXtey>E$i z#XD^<-o+CJtq@C{3i#b>Dp$CB-m+EQ@IY~Fc{zYs8ARveT#^h_mQ&WqJALAa!rGJppo(qF}=* zIExHLc#5_q;{mm2{ERq58yp0B8pciZ)ELU@I2<;$b_vC`wFhgzlxiD{mFdw$*_*Jf zH3PO`b3eRQ<+vCw!CDT&!dUqz^oJgIc=zy|T5fJC^r$3Y!HA&r%C&?;GlAAX6 zb7bd-zrsJ>Uy!#5P?F2r@LepFW@H~_De5b|bkqpQzur>!q(n&it4;4mol)7+)JExx zlz#M+Tcn$Ir4cK-ej@Z`6xs${eIMFZ1Rq|e?b?+Fi9baCwWIdVTch@)j{)TYP4lxe zZRgr_d-m}(d-%aL+=Wx&eG-3DWVsigfKQ1e093(h^lX~0GM0$;M!xv09LCbHoFq|s zJ*SEaH-V)m=B@tQQ5FJ@ekKm3&+X9RL!OpmsVh)v*RI|6!u}VXxIRvqYphVeuR1ty zJr3fFgyIUC@}Yh~fRdsv-M)R>4t#RJ{_{uwNic`YR>=axdaPBy_r34hcfa=?Z-cUc z^ZTnmL8jAN;=T!?PajVHpyz1|`>6j)A!6h$Pa^)VB7$9JRz7th0+hc0Lja}s>LBIb zYC~z;sK%7F_c@)GHql}augI`HPgdAtk1}51GF`Jqo)wFLQnK8?&d;H2!#?@hIu^=& zkwYn2GQazuRrbl{KMg1W7HRC9k3-4p5M9P1pmb;bSOk>rl*w;=L<86&p!6Gy?VkRD zcQRpOqWKAF8c;%UEi8Z#6Qxbj9~NES?&+fZtum)MrVkwYHFL#e3#IXiVF#5&+&cp( z5w2ZIt<3Lza*J%shJ1Vd4>IhTeJE~Hm`HA+ z1jk5yW8ALZ9LMUX#eVt=I4c^6ZnM0`Hm+G=`<_j;=k^iJhsb1^a5v@Pc9hLzy}ot` zFsTcdu^~HoBGt||#4Hbsr!3sPzV~{bedkZ|vGh^YE^;THjOYc)FV9xu`HnHoBduvU zB+dnwV-2_pc5war4LDlP0VsWDpTK$1+}vm@t5!1UUyn7_^R{o_KHLJcP%N{3@~@~t zdVKQ4U&==dymPG(zh1m}2^XDRg(rL0F=+9tXBk5psdIeXqa&6@KLk!jWtly1eP3xLBHH@ z?T{+9!?QCmGGxQ!gKjNVf{S4V7E0^aOu53grl#1|Ru@}t;iTmip%@ccji)XV|0a%3bgQzgE*(~5rqTgIs&8sL{RMA1r7_eLFl1+dn4Da4mh7$+Imp7 zhOD8s!0H@v0F)}Rs9Q!oSWeWx++6Ah zz>o;bd$3fhLrFb)ve!9cE1!&cidY^j-fR+gP>k8F+^9wsP_*;Z3sfTa>{8@R{F zO-9y9k%f|8M2a16jEwaj#GD5Zm;u%#0F{L{e|=XR^@He`pVU35j8iHoZYC)z&9_O) z{#&oSvJ6r=>lpwOBn*~FI-oM=YHlgx9RWf0wR-1C+GU&Fyxw5-O@MZtW!BOIZ&e?> zTEur>UC@uK5!_(8rB<3#ilU4K$b(YW({OvspzlwkZeWil>%v3^Q;>=3g1$Q#LOv!v z>Ysql=qjo1o+(|E{B8~|Mfr6!&A}9jA>2Ljki^dGmu{tvO9a3nEG$Zpg#$|1PSHlM zUGB9HKWHX$WRD%aoC2VPIe%U`?viEJH5Rv4+LyZ{x~z1A1pp-?MpjnvAj%Dj9Nb*{ z?9{Oq`khYu)rldy2m$(&+g91553a-|DFaX`leRhT0K9~simQ)!x1u_r+(&?tUO`Yx z1SYB8MDHu9{*M4kWUxzoDs{5~rBKRpc~hFdToOu(msz58c|pBj^iQ8uKd|iMUy6vb ziBdR0JN%evph~B(SUSUa(K()BMRfLCR%X~MFQmguhoui8FJnCW?Vpa?&jFQg_l{UQ za zzoXo>c%Wy_D=&Wr&tVHnn)+wA7{TqZrKQEAC;!V2|HXqjl$Dmdwd$Y$`JdUJ{n?-S z@4|d-`uAW}o<)ybI%7*avW7E})bpKnW|Y3s@-q;9pMIPkvcvLjX#nsawc6 zeVhYI-IhApW{<2$w>`U-*`tpY*=7MsYv}_f76GMXxqqFXL)q$?$)Ce_2QaClzlnvC zejDoB+`Y~%Zuhrd)T z76GN-T738H55vIYg9UT!S%8u_loEiF{A(9ElQ z+!-`!mMcRctIvgY@L&_JYq%#6VeI-9Kn%h~mlT!Q){Xi0%Bv_`a9&6`(=((9f=Ai4 zTSOzn4e8*aW_$1bD|WqY#5Po|wJqycLVTKP`(B9LYZ&h=iwS-%A$;1fYPxWF*iIfF zw?m(#*pVy5_LD`gr0xZ2@dVnO)%C|BQ>O5a&ZQ*z% z7Zf6H5EO;bE)?zUz4zY3%IGrw=Ww(@uKoHOuiLj@|284*BNBVvbOMVASt$vaQa%Js zxr{N#k&8q#tI}GTzI5r5yV2=>H*VapuI?@em5T8<+O};Q?nql5RN6vRxN=tU6-HX1 zl4A?Hv9u&#W#`?bKw(8R2|2EZvgh37I7-$~2EbApa)J~a*OQw!My>Y77>XpyWPO)i zuf=kze#p9T36dgKf{R;q`8cHAsrJD3wRZp3HMWA)=Ze*^CTS7hg(`4JbwNTF6e1T$ z@uoz;ijGR!+I;VSI12h9U@1DscSQz+3n~IhsDmi*V1i|ZAr;)n* z#z^CUOTBihp$l-S57`coXZYT72_BG-wOVE08o&l z%PvAMA#R~q3}BVLZ+ayMbM!4z%~kHRd37WQSsUpdL3Wbh7ufXE#4~hv@3;A`VweOd zQBvKId!V8O4g=DS3{Mex5t8nfA<7(HC1iQ^THMZG>$MB;Rb>)6Ff)~?i9`U*gBX9^ zsu}eU$pDil$A^TnJDCh^(aU z$7#Pq@Gf1w+KaUcfYR|UJ9z;@X^5le0!lf#W850R-Rly*gn*3N)FK5a(JT7*=;{6f zem1&>cM{mXpp^WlU+SNzk6Q>(0vO?+EUnVSd*+DCe2>@L%r03SQTG4#e}ppO+X zsB-^p0Hx_V%*~TOhi5JB?@bA)4tSy=Ip9tC2SAAv-oNLwC|AtFaqb*aZoQEJC0SrD z0!lOGy9g-F$l|y96gm(M*khzmKK|JL;UE6NU1JtWxqmB>-ZMX%9(0(TXs`*2vnD(; zgLVrg5bQ-j>7FUF-!3Cz@~K}ZCT}x?O;q;DfYJofT15O?T3TdFvG~Z&kt>rdlmsGZ zF3U=AN-=+n98CK3V540YpmbFn6aY$vCAMW_p1t-h0Hr-BC9<55I}Xnl+41G8aXWq{ zZikLE+D8X3S_9THTUNsxu^ED7tdsUVpUxZ|g^_DBu*k_G4fNx>MC7iEkPd(F)}(!M ze9UhD|Lnc@msQu5?>j5!9Dt&rs>m6MECdKe%d%uymTb4&-M6n_yWL~lH{Sc@{V_ed z+dZD!udmyo6>KX9TLBP4fXJDGf-0b>oZ~s?eZF&_bvP6tBssLewP4kbXXUl_p5Hy^ zcaC*gocOKnW%k`?%53T40^Hr_xv8AKREM?83$2&iq&7rq+(#Eue?yz7k)nO}D1%Jg z`uqFcwewqVy@~16r%t%7IrG$0Pui1DK8bthdZKtJBtTJigxBcnkc1ZTAjt$P`YJ6i zaD$k@ojZ5VPM$i6SDj-39q=T?T1(16m{X^huQ! z7nPtjBB52lmw*Y0u7pg09@&?0PQXok5-z84X-iFz^uM%(R^F65N@aCIksRqoHPJ5#dx&J%NO{Bi4Ve< z3(<^(bQwoQktPPv23svIIzymcRAzRft(zVJrRWygQUDpP=3v|yK*$h%-U`RkrHcvc z!#iAmALeiuhcJm5u=dVAyqNXc;4tLhaR0;-Xe$-+wXLw!s__0+H3Ls@Re*k#IX0`# zZ1&tqv~3cY7-sYAGTZ%epM8YquJ#_%?1z6TV+f*d%)jQ9*v9p9ZN(~F&NpT7Tc9$U zS}`jV04sBV;;IfbH=YnhWSfasL{(8{UvYsen1@7FmVimMH2yi^)%RWiU~rF#>J!F< z(o%x{tK=`EoBgc+A#L@aYueF#x=U$>bTtfOm~#pE&%#_wd{ZF|AJ4Jp zp3Swo8ECfwT8xbWSogEuKv2B%!;7|eUzZ(ihKmWWdfQhw*!>&kLL{AQTkgl@eUW&4 zB0wpT;NuG*N~(Wo2YIAa&|HY-OR_Dzk99Tzar~w~!=JFub)g+|;X=frBrk8$hE!=( z9%*J~1LS{JUra5k`jrZL-v>a+wfGnxlbE;0h}~!*_VmYX&(1M>@0~F_dX{w%o;t&n zby>rhEn951c}uFGU1ZXxc_}c7qa=|x_XI$R=SwD@$+TW+lEx9De2pF)vR7Yu z#a2XrUWkw=fYNN zt)iYk=bO*@yIy^LWb!tKR_oCd*EE!RZ8!7GtMj)_@GtL%(6^!HQ;&UI(&y8FQfQ&Of2%PN#zC0#DL{$p z-$2T(CefTr&bvPdP@0mK4)2EWCj*pj);OW_Zg%afc|a%;0i~~EuYSHVUDx+|@!?@J4JduSw!0hd()(^|4DjBU4k!tv5Fk-eSz=D}#^d~M<%%*ma4OLp!u(8TI%qDW-bv9)kf@ZZb6O{+pG)5th^{CeBn4>{ zz5DLFZu)lW)G2>C+X|<~mMvRcqex$`i;GJTXd;4E{U*G~rPfjkByJu>5q68yK*Gui zxHFC&JBBITQ78U(b2~sNfmHQ?RWh%W37p(k&zm>TwWIXFm&Yv$^(wcUQ6OAvUx1bb zZa%gX&=bIPFcZN^K#k%hOukx)Eob4rIyGsh0hms-LYCVzK)cKBH>O{uwKlt=))p`T8&f<0B*En8i)d<^UsjBfENa!Y*SPcd2dEE}R>+wsu^XBgo@C z95c7b?R!O80p#X|kd03QjP}D569<^9p!~&l;p_zNlPB!J;W68HY}`5rx@~Bz(`J<9 z+k7++mZP1sZhej|hp4-}Jj1|9X_G!SN3K4-O0&xV#QOKJBO6hYiHD8i- z2%B30N@q{^;x+P;?f9tIb{zmCrYo+6nCqeNpo;j+r}j#`{^07``bNnDQw}CcOG)bwgTZ^1a;T%c(*!_pO+Vn&pChQ96$L11?HL;z zMH6ifrnR-n@&OG3CJ9u!RX==IIrZ$27G9*OqAO+i@p273A=!IPiYd(##zCpH4V0Y-7LFj zT{d3Pa%`OSbb=^ADMz3ZCYb_^)UI*3mEx>vTB+RBlvHGpr~gj6&m0XS&R|W<5U8Xvts#HA zaI3Q4>iq4}`wP4t`c_p>-w(&3&!;(*{;~###)4w#|JwpeY93y9^&4NSSg*d6hLR7w zWLw`w^Z3sSD0v&w5qDCUy7+{$U-v-dqz2Xa__*78|I5Gp%QT=A8tM+*-q7cIw?YWf zV$*uD)fWw-E>r^XmeL5 zrk+AR=iDW-2SgIlq3g*BkDB+eyWi!`6; z71xA{c#L=taDiW5!I0e%^u;fNFs%!8d=J1(cQ2+Lt(dx^1$5$cmwkHt0v_}r!X7BX zLJL7uFZp{DlR!WFY{{0$i)lH3S??&G598i^hPopDZy%TMv3w^+z56Gc)8O zPDJHuQNelqQ(-)CQoBTNe~m|($~XbIAP2PK1fT#WCeZj%KTP6*X=oU2wc#A=?1J3= zG8#AM07VY<0yGX#}U_yj+{xC{CGSkC_OpdOp&Hu8||c zY6lDWiXV#?(!{EF6kMjF*;Q4IWB$_j@|s6K+z=%43Q!_7+C#vSexVSjEu1%redVhQ z8d|9kj&&{!`s78Q>jG4iC1sGHepzkT61RhgCNKd648Fu1CibHRGDbUB=2uul^<0~a z%l0|*@Z!{%W%JPnna{SYJO}ejK*u~16t5P*iGs@IfRe^Gf@K^{$M7O6O%<6GQ7bQ= z#zZD{x@Phgtw%cVQ|7wLdGg6RlL>2qOx|2WiTh;oCa$BMyV`BX?mpY`37-AhxQ{wy z18#fORYdq7(;e20XU7EI3?JLH7;kQitrqRT+L@V*(KejHG^5!%Xstc8 zVpg%O#DT+#r8Dfo2l8#(_I%7R0g=$G%tG@o8=y0baVc|HIVmJ84k`r#tHFqxpM>V6;OYYj|d{l{^0%h?d^Bp#)Nd#ni`wj)7ul@c*04#bI~YL z3_)#{YB%rfaE0_)e_fl2a%pZ%@R3&DKtI{@iJR8#*tx^kel^)M&pcz_`qnen*wjF5 zLPHRsT7#K1J$$xOc0v-|GC0 zDg4Es34I&3=?$WDq0grQrSz7$`}fuN>HYtC040A%W$sM_N;i&=KM9~THJkKFoW8Hc zH2rw$@BTZF)5~_VGWvrcSwQUzOqvFi{yTf@kC*oi{jC=iUTz#vY6Vb2E&FDGlD`P0 zzbyUniZq?lmu!I>`tl2;qu=VCO?{uPp%jbby$0~83X4>1pjf|rrL7a7^iZBX^l+|?;Oct>ULT2L;%do(-={D)%PzGf?B!pM z*&A<-*vXDgyV%=>>*;>9Df;aJxNjbLa1r23IovmZ9gup5pfWp&aq4l>F3o()JOCBkd6tBL*-NpOA(WeU8?bNV|vna3OuZ&kh~CY^To-Tl>{g zYws$su3pTc28OK`t*e@f601e?tF|`J8ZjSRFn@@4HmhqWvzl222>1OSk@Y3-lNW#z zkdy$WC`h0VJWF1CPOCAzls>Ky;V7##cXVC=ipC`%4S*CIl~zBi%!=4AD$VBiaR9xT zokLse*kw!`(d5Auq0P)s*z)=zTfAV>)~>6@^H~)n)st2N*HSJ3hP+p03K+_O9LCMN zRA+%_#T37Ub5Wq#8UInQ(AC_dKg=OOsT+fOC>g1{n}z9iqWV_tp{q<+zl|cKg7($V zQQL*n{7`MGG2mJwi~$5|k+l!ecD=oE_^GJ-S-b$AZL?EnFX3Hp%vu0aMgRcHa`UXb zFyE@m^Q^ie-|A|LY*sbgN=tKW;WD&&5cVsoAm(pd>T97PxtK;{kH#?g4x6;~_hC z0j;4VpfoAZZW>nbhj09+txf5%FWZ}nXC&oAjR zWl&4#M$Jt>lRU4Bf4UIX9RW%*dlI13*w~1v-z+lKxNg8U>Qqlz?iF!J^heQYa@Hp6=4R}6?xz|qb#+WL)X zfZd~PcP zJ~*2medJMltpTNO`;Y%PY%jfa z(Ryq#Q)Q8Np=ZuIpA+l0duQZf_BjKSw{p7|P0odQ29)dHb!!#4ds9}o0{`eGVTN^hCFe_!vg3SrLQ5>P_(G6Ww(%*pWn z`v++#-D+-!%i3wuO=~E9)q3-b zm1k;S>kUN{7#!y)?tr7)M(E=y#i9# zDl06_ngS?ALYwLx2@Tg8>UM4D4`bFq@m+LW?ZD&P5f?6g|K9JN^QZ?+slWZ3zqP;n zAAjeZ8nt+3lgGD|HjYaG3I2%l01XSxV29u6^gla>-A#T!~08X54Eh@>}aZ@uWKWCA-BgYfCM`yYV| z697tzC`)*BASVf~&>Wa?nRRyvSVHTDv2~d-cI@DU9Xo;US1Q?kKw-Us%xwKO*Yu|;-2|EH;)8#=D#mrF}S5?`a)>t`g+qTWIE!*mC7DV55 zbMQQfrd%Ec$^=Y`C;BM6h`I^x0kMpI0jp|$%`J_6^|4opKb(uujd0>7TY)YTcok_& zno7S4U<*ll-$r?|>xoAKyZ<1SqN6DMR$3z32h_tgdIa(T`ap5ifu>SBbw7Th-Q&rV zak!N-X@?0LnH*wn!kdI}Sdd+S=2kfzRTZ{=4W70(<=DJMIo8;iV`XTnsn5Y&DU1YW zG!aL~(B>FJgAM+!e3=A_XGx$^)DYe_sulOk>_}CR29`9jyn3p5Dri5tM_`iL`FcRf z-~x&P@Q&L@fJyJ}>bAp>&09WeQ~@B6042p#lB5B!=9%KjZ%$?0o_i?Ep28u(oY|T1 zuw_AzPnu}%ee}^Kd*!v`w&!TK4a6$I8msIn$e(uCQI2L} z2Bt~$xF2h5r)5kJs26l+2+@5y6ZZT{s;uF@Ki<~YK-NJ4O3ls94k$?jvaYVq=ccYl zT90aL@=f+dG|sM-{JIjQl~;3_5kPY@k348>$|N>X z+_&wemtJCxJmH*rwKz%m+T&ld2e)s>40(|)1YmLj%=2a(@VtxK%WIqZ6W0Fl%<=rl zNa_CWcfZ3+;ST%sz^8D>wb~|#zc+5!WcP2~Vq1vCBF;_IP`WPt^!BH&3gLRlD{O;s zc{4z1f@i^T_{jd_KaSW-Z?{=@d;uWpf+$}l8|wuR@3Pf307`3S0Vq}2y3IMZbfo}0 z`dsYm;!jF)D1|b3fo}CDt?bv`a;x*#-86lm76^SCw&|^+bD__t0j2boxx4q(?;-kn zl$7z>k@L8~Gdl;02Dm3HEB&KnXbm4j%)J081!a;CKKQ`??ce^*oyYv>AO8`DG|#$b zW=cCV{m~HSZrFyz@9^z^8=&-6Z?~|}`{1FlVH?UFuIpI)(|}TFnLB?wwXgLCr3cRK z0B8uw002M$Nklx&^&!6uA*1Y-i*q>)JYG*>M zJJZeNWU?X)%(X0|->Py)ZRwl}xTDJPDwSm$wq#mO74CKcO0qIXG4brBEO>uIYe^=D(oRYM zC}pF)l;u20BD5EHApuie!F+RYC%rw?MpV#SB^s*{0dDd){35Eb+DuV@eJ48hgw=uq z=9Ip!sVybYOOTI#r_%}=f3dhg5IB{30dITr@Vs@^P7yod9_no`va6k#6n3NaMf+VD z7_v?PqLQ3akBjQy(wYnKGPe+-_+oge0GH-ro-{)ykmzZFS&4g0!h4pqM2M=N03(JV z{TcOkWIE_ZrXkSP(R>1t?7tHMP|25uh{y+4`t`u&dwpwT$3w zjjygbLoa97S ziIrnQ_weR9wslKAoNYO_nwXylfFkV-71OA^zzPbcxqmA_Nq0u~N3$T+r@BD64o{0t z{n7sVdPW~e`%xN75*V7Anw+mKTvOQvDtSRtg;6QP*h_9zs?e^?_TEI^4574b2^^;`fYK0ZY4uZF!%xK-J2b^bQV{Uu%weH*svZJ=|Z&%Z37r1Zjg z3)}QOruV;kEuel6aVnss^VzIBB{*HG@SEHvZs)52pd8 zL`<#orw`r<>W@E9c7Je%!lDq$8@3_ga9zjRp9Yjd%iQ_fseSD)QoLYH14?&R->M&P z=*!Pj1qtjtF??ZkKnVd5Les15(opKW37~{_0sJ@-prj1Y&KL(!nkcj1zI@1De)%Bg zGC6jxyTVEfYHUTrEKEVl?4ifAZ2cAlK)u-Wf9M%n>IAUNs&hcP{J&0lqiDVdwN9@p{PTL3f58|&CWL&kc zJBxzzx|T zLR?{@+bXl#t*m&$s%opy+`-$=rdhUO(@Y0js`0WW(q{FYK!b=+CDKrkra}lnJHQ8+ zM>wbyY2^rBa6n1zA`F2vk{E+`Uxr~)0k|1ml(2%v6KTXCLe_XugkRhGd+=z}iO@_u z07ue0zaOy!m-t-_l_mfncG!{u<*Y0ch*V;uXxt5>IU%kW7u?_kL2pdbDVj_<_Jb$z z1onKkHO|S#lc4~m5gQ-v<5swp;OmlUR~$eoj@eso_PFI`$(=mfeKAb`0QOuym&V-< zfRaEb)g^h2`I!-;3_8cUtW5@5qZw)weyx8YxJ=0(0aY?bm7uCI#|cs+e}> z!VC~M?ed5$s9@C(p(4Y}RiF&$U=py=SjlF*uiy+k~s+po5rtQ+&?8fr{VQ0K8S$om}C21(h z0YJE>9DIFLC#o>1{tV+Ubs{SCb>(F&dIiEsz!T=JH2Ff%oK0X7J2W_IeO)*NI68sJ zSE;?dJKuV7w$L@)W2@`NY{B9&Tfe^2?z?X$yjJTOgp{-iA(!TM;Q})EypCmb+QKYFStJ+aN4$qjd z4ec9*HJRjz{9Ju;`t)hr^YI@0^>2RdF z*hWX!{q?fw7L|z*z=Z%PN$XX8UjQk040G7ir+e&|FCMa2-@RZL2NqfX#3KKl|G5>Q zv;qyKQM^Tt3|j`Kd6`6SUzO2Y_F57*?A@yDw>p1A0@Ei#--c~^i|AbF^FIVoQkoja zVJxTTF}?rQYXS9ph&KRAyie#^T3k}>yq_sRiE4y*QhngmIwfaZ`sncChtq)4pG`wa z!|7&|`Hwx!{#1EPO*ehf(7pzgzSg|=-g|EHCUxm)FK>VB-u?5WH?^<*WpNr%`tvmY zA2FBEk74`ylGY2Jf*v+(c=6ZE#x+3cW*SNXP|_FXNI1H=kx4R4=(Ks zYiviAj`6?>z44fw+X=^ zmoL7#cmm=fV)!zS@FV*8$(CoQv58l^k&pf@# z?!gRV=4?1%DkM~^lEkTi63sxVxE6)bhG84dYpZk7dD7u0-Ppq%J#y4}FW&#)eYB9yyMJH~=AfVMyQ;1#x@T$M z;E6oFU?e;nW_NeSt1ef)rmYLTiJD2Kt8aA~ugW9I1umb?Y16_4$M-N@_Q3KzMtAHI z@l30VnmZ+IENJC3PRZV8Dt|~r_1ciWeKBT_f7I)yihvL zF~)s62Xdc^*yK*&Ou~5zLyFuSVVJF;^5U0FOMMKaIpFltiB7VFKYzs$llxTl2SD?? z*19YM;Uul}oOfE-Om>bd_34RYC^lW{yDAKg(^|mi_xigjjo*~aiJz!%nJ|k7Zwd*M zq#-X?J=r0rre8iiD5GneZc#F(rbOU@_f# zWZ%Z)lHiDBo6HjLg>o`$F9i4ygz4i!SdM?shzMBt-1Qq%0(?g9bHJv8T5Iy`Xw6$( z>!3}c_2h583vdnHufAzEtc!@Z|4nh%L}RA71!a5Cpvl z7%2~pWvT>P%&G+%t9o&m7;1;SQk|2m6>_ybuUycIrrfCD(a5dx;bFybsCa1zGLVC3 zq)wWd-#gM(2JbL-URzy2Hb;y;cTHLbE{*y5L=2NW_qSZ#W?Qd^^Ng7Y`&!bqIJDw6 z>Z}S`CCZV#nFAs;pBzce-BQ*V*Ec(Tz(N7@no?oWsDcG

1CT;dD*=qsLJry7x&1;w5dwSCmqacvxVLc9H!;)eWTbGi*&OI&h1^yj z+^H=g`rM?=?10EOX6|=&tCEt8E=xQZ3Z8q7xo!5Dh zF0$e5=gT%sn?rWhAofF>+uX@a|2I|y^ke(dWf;SbXFjT|kf+5h(7JInYPx9-I&U^%T4|ZlWAwGlL$Es-NZ-(4zoBo`;s{La z-hw1L<#+ah|8~MjK^Oi1xa03wjOt(+n?Q!*{~VM$zcK1T9u1OK|AwIuGK*x4FF&gaGyLSV7GvjU z9Y!C4MV8&}<>2KP)2enYC=0bll%xct1Auk+$H66~PaB0<+vFL$HH>P5N8#uuqhKGNK zx4m>AkIwETI>&P3_WnMBN<`Rj{(GF0+dFi?TG`#&l>R3(=9f-(I(g^J2?lPn1{*~Y z5~1<)t(Jwueqs%^l)%yqkorftBEHzRQGX!O+;>sEpS(jRf$EU2_#WZW>pLpk5S>1&xRBC?W7un#`}(* z&b?N^ACy4gD)$v@&w~|QlI~e^w*=CaEtfg4!OmPEOQ61K2;@*v7mDO;d*#cWbPcmG z3!}eaV&|@%~U-nEXWG!j`8w86)qz=EV znx>3*H{KL9uLOKm6A_c9ueopruhHJ)bw~0_vHd0?kW2erY#j8o79#_mg_Dh-aNJ`khbo;Y+|UARG5MN0_<14=mu704qgCquc&IXhI#OoI z9(Jz$#JoNn7uYpHo*Zx>K?=0i=|E288j`?NSLcAV%1BM8T~?~-!H9Hp*K95OrWJNR z&PCa0Q=!>C_kCcV+l|!!N++ zt)pb7`mh)9QulWMXG>ehDoqLw63+C4dySNheC$bBXlq~UkzJcdHGB9xDl{fXZY!2G z#gPNe4#A1@xSZ&`$Qg(oKVC7u1O$M#3_bTU-KdlMi@GyO*&H&VQSPQk-P=p3hJi&W zyUI|?x=`V&L3c2BOawPnM6zmQ>EG5Y9J(eP1o;Nr@2&r>*DBPMPK647)Ca2KX&Gl^ zzu&%VHNY-hko&6$%OKrx2wTl<$!!hKAH)T`nrz~?pM?v(=GAz4J$YR&$&B+egm`6a zgt2&WMQ61mDyyc1PRX2h30Znrd+%sx!6bamygD zAgm*LUS3EJzmE5IyF0%G?7+gm;eo7Ur_XX~N9NP`9a?x!UNU^VD#WETcMLawRF9J9 z#n%+D9^)~=DAU#Bs>B3bg^De$X@2(;Ytn?uW%o!16eSdfVKU`+u%F6Z7A@f!8B>Ej z96VMW41dNGPGzg`4=rf!uO*|*LH-sfdDZBz%tM|#ng*E*8A0W-Uskg4df9L{2$^2X z2Ms-sgPQK{_2@%ZD+ms+6X?H}uW>qrE}P|b*vtIN%P*%-h;CL;b=;n~>vfoq;X+Ht zh4P^ynFnU>Aw(WmLLAPM)l_Sw*8r}9KR#lUk4yyOu za#9Rb{q>9pHp)*+!Q>4K56{BVFMNVD%)5V%o=@$|;#-dPxv3zjs3=$4kc~?DCb>O` zwDAgS$vpW@Oz=Leu_t_>G5r;XS1-k0JlA~=l(eK>sUWgZFO7UiS@W0Fc9jN6u!K5X+}E) zgeaG!!4eV`5A5C|4hhPC(6A{Osk{ zI57qlH%>9Ix0l*7(s+TX%aua*-sxyQr#q#n4M*@D92gA#JGeAwWY=lp3UBTgi)xC5 z{LNKIJF#eEO4s;aM~}UEE}1FQhF&XWU3SR2zr)tkm3ebKPaprwKS@5xH8lG%>KXCu z?o=*Ox!3M7CcIGSxKWn$ZvvRi!Q@bbUl?$Q08et&4@PtuG-a1jmV}f(Z>^4nmCQ_X zfZP#ed#G!D3>i5w(;v1$DFYw%d~*S*3*e3mt=b6G{$J78>rY`?YUaFKj-P(9Q^l@JavC$u3 zP|%(4S5$n?YNlodJxC@*0AlC7zD_RUP!e`_UQnWSpjo%D?}m(2w%+!KAOG|gnf-)_ z!UZAAd86bYG2ZP@N099P`T!vz8;{X!u>DvI>?XSJ#abYvsr39B`n*0T$88bEspUv~< zAO(Xbc*i{(Rayp>2786c-)+VJsY1;C*trWOW4tZDo**SW$Qaa1Vd zb9y&^Z`9rOy`;vymyONxjsq6tG>O@hO0}#Q$(}UOgb9?LQ=Zf76sF3SAIWUtzaXf~ z`8aEN+dUd4x16j;f?nk;$)8G|uxo@nuc5%Y+^^Zx0IxIqn(k;bmf5G5sthbLF1C<+AEAFgkouRrV?33Q z)OT`Y){5#Rk%qTPS%r7WPqLlgg!3&IQqnn=y^Ue>`Jc5A^SL9F@Bbp^@m{HkiH*sp z)HFRXI{^6(I`bz92=i?OBW&BY7+cSH_kB$Xab{hpc)xTMy8HKY+;k=E6Z7Bv9BYd| zIuh70RZ!E9bJ++?@w?2`hj4IIPHaNPQahBq?!G-!xn}M=&ZOH$Ja3`6-$InqS|-z2 zA^_|%dRWG>K|^Cd;QiO>y+``fY7hfAgQ5Oz&|2oZMEzvl9RXnNR z7nCq|jm*Xj*mb0c5YHA!h(}M8A_%=TsE&!H{G~7PVhxXyNpH93{xp|LENFc{YWyh1 z_^__QzNyU8gY~(gcLP7Wd%yqZs9dVCVZHNXnKkpnnxjLRz*Q9{e>OIhtZBho1_OmsUVSKnSj#6uz;aPzWn)MuFmBM2ek3D($cA%We$9sH`o?L! zdwFJtna`i-dtK`~FGl0fvu`<08j%rZ5-cuGl5vaECm;zqoRwWOq{?dYE%OP^iJ^aP zHJ_VQ2C>wdROl^zLw@ItSqdtfj~+EzP~Aw~NUudDMk6tx5I8_UblIEtG3(VgP@Z^L zBn7-Jk_kh>*Dhcz&}yQlQCcm;bqac0Y~ayEDQozlXS1RB{iM~!qM`GC$ezy~wWrdy zYqHFyu|~+yB+kEp;HH^~JsE&(rDo-6EqKsUB4IWBJM^$)i0VL1S-}CBm+*({Vw_+F zse}A}v4y?1RD#EGM?RoPc#HwHs4P&mQBf7$h+7QjB&+e-nya(Y>SdNO;Ld1LaY0hK z#@PE*-`*ZEEh54?)~#>d?J8(>O2CdpsTptrd_O$;p*!Sa)<1^nb9)7q!86PZB&jVJ zZnyjRSpY)2*<)=S9*c;xPczwi9nxRw!VHv0W&^V9;dfRdI1WSFlnf(>Baca!zQW=2 zh!Hn_v(fi9vh-CIuhFfqYJ8_F@4WY|9~Rtvs{^lfj;Bv&H@%P@Xl^v7f!`kVR7CQS zZ1dh^k~(DO=c(6C)7KzKRZ@Bwx-5RLzV{oUfOAFCeGT=igFKn8 z6_VNr-9DuNllodT){bAuYmUKM&9Dm)=V=XEjuvC{ODmBeAUWwrb}YUJZ@6k|g>IsF zFEfO`%YG!pm0Nf?v(brkbitnMno*bCb@|Bs9Y81V#|&|+ZhrGv%u(OE=~#v?>FgAM zO461#)iTlz(;}63M~u1+8fcMbM4w0dQ!~XZeYbPOpjwaSSI}DBZ2oK*s0tUjyI7%B z&^mpL2q-#9mjx6N!2l7)q}>pGvlOF6%6XHKQe7wf6>Y-@++AVfFen!}1J1wcwU%#y z1XGP|IImS{$!}4A* zmMHDIKW{v__*dFI=Nrc1_dnmA9!F^`aR+2iTG{rP!ZcuP42&&S?5_MnCli4nLquBy z0(ppH)M831BFjY$sUF+nR<${c6;@M&1`COY#wFl9$6MLbmVCV@6m#sF4{!WZgOl>= zRL$QC{x0#YLC@Y%^to>&Gfp*gpf@rZ=p&Y3GFn$ep>K+dBUyRaBfpcwIGsq0E3?VC ztx2X!pPa%g?;=0YlwWN${t|%Aa>_GUPNc?+H$_s$vURt-U(naRBW_aS}E=>L$}w;4RcA5PumOuCacu71`YEh@MkTC`5!)|I+K55U8-g;WrYO-Fo&NF*%S( z|4vdCtu7{X)oT&fBwiLuOueVy4-LNjD>RlE?IFWMj+b^lhiRO-HWsj zyY%y8Z@TF}0eQLl(f5XG+4HDlT9%)pEjb~Z_I7ZN^m+jD zHVIP_YmB}|PQUMXUFfCe;I`rEMO@uI$#BD#6Jh!`ce2B}=0yE4Y5A~>Na&;ye8jW- zSbEHmF(*~${$AllY97_20PLlzwa%6Q55nAunRjb3zsb16;?3XH%!f*Skp7|0tHTV? z$NU>-z^3m<{N+EBxV3^f0dtK%8kXKaaHa}z;ES#fNi`DCNR-r|Q*&J*dv~UwHvIk* z2SLq6$4#{Xj6tGK1G^#V$J$=y9zC)8+%VL|x~bkvmoqtvl2YOq{5}riu(#S|L+GS2 z$1f~!JF1(s4LceqO-8TF#y)qGQA-=GGiy>f*EW*@KcJe#0Y$9`l>s+SL$x^b_fjr) zZ<2z%kilnt_>qkM%xRkKU->rke>0)o(N)iaogYj_ZMIsB#=A-*p)aL{$lF;SeGo%` zp}hSy|I9HT2Sk}~K5nhO46$nw;1}+{f@Gj{ch6UgpY0is@!I`z8{R=eAIvvOS?{=-&&B@%t zU|Ngo*OD0wzgK8oNqDJkXjbl;eTs>V?jSOZC-)2!J8oK@T4OTg{*lraZtJcCEJj>( z-!gAZAYrmG105kVt>Twn z9OA5gJ-q?LeZ<>jG?Uk1CM+KG%CZuiif5th8QBn9xXlHhBZ;K+)t#f6R#<QG zTYqVnPx=Q~dWvk>Q|c=_Z#oRldC`>P0l%ii<|%<>JoYZ9k+wHfLxU$gskWwMj%K74S>tqs$!!^|f(pJLM_HGkt$Y{;TE( zJ1Pv7)i_IpWUb9S~rAwiazUt)tT z;4=u%tb78$zBrQ6##&nV6aQ!9nl*E-)Wy$HNNnVsQUGY>NZ_{g_etzPs9cOVH0UK` zXUWYv1YtOSh2D%Qfk2G8!+z-G-gc}s7)iJ56UtLOj!zn`I?BO+=>WEt)kwQS}1o?tv%s z=xW%yE`xjtEf>ueNeBr5vAEGtpY~T1BvK`&=v=2ge|zx%jQYKr@!(mG3gxhvLJ)pS zbwmsgK)w__;?^a_bT1-~M*{qtSK12{M%b7(!KsMNB4hQR1fX}kCAECQQ4vN1Z^Hb1 zgfNYl-|u}ozV{z#%JOfqT1mw!?Fw&qbY9*2^Q|wLA)T79@4_~Ke}QER3??}WWu%Y`q3wIV{2D6=X_f>rhq!bq@r+UxRNhvmb z^)2r1?f{ym$K|68pzJ$ek;3h_1Q!OK44Wgjy@hK9p8I-7#zwg>!Tvz?xpWe#45f6( z>v%5SWGmdYFmPWH#(FcGan6~nHj>HNMo;|Y1Zneur2r#zp!CE`MjlfeohF4GB`LAp2e)#RO_bAPzyn<#z^^{0Bq~7A-?IVU1 z^1c*$`{qdW{5lShmHm2avU0NF`gqbD_`g`GoZV#%W|QQIepM2Wk&4F7^ozP3J6gmJ z55_FNF9HfBCElSc-4&mY1%Yy#!bj*JwQWCGmwOI3&PtfJapG@-!dh)^w)|V)SSTb=D?3+HM zBXB70^wl~^U>GnXMrZM4aU9|pGKZp5Sm_(IwAhEnLf2!YIC~w0Ie9IaQRX$(@(HWT z!WktTrLu?Rx;^fdSe^?sHQAyft;n0lgvMy5A z`FzG%WX76Adwxl29jt7<0p@1FJy;#u5wwj83{NQ;Elsb=xCKkcf>yay`7>GS@$%2L9b!9fc=*}=ECF&6)Kg@{_a5DIwz^*FV7i}y|=OjBz z&RN4d?th!b|I&NYdhS%uObTwlVd48l|AOYxcXTr)((c%_p3F5>hb?z%JHBMSUSCCE zS4^~q#K0PstV#X0eEUnfBC(YxwGe4`tzQu5z%l6Mem1wDEOLhmBAIfY| zZJ0Q}UE);mYEW{)1peW4_vW~sG#$InW7Sj%?%>O}H}S{3oOXBew|FZV<9~YjLqBX2 zny}Cnp&7$)RE&f+>?iu)0KqRF1K^$r#dW{DESB}~#4%s%n9MJbB1Kw>{LDnprtl z)itIHahx~L1i_e<>l}Ps_jy=prJ|Uh*nNhWTVVVWc zy&UTJGGJ>km{C z+U4v8k5Z=QTWi(qH%thY_JKAlaHPux6pb=2 zU3}9MY92cm6FWXtI$V9zD}j=IhTr+jZY_KF1QutsHE4`o;UAi$zGrf*ZtGTt5LUglhJ$qAKV>A!r_gwx-LX#@Iflk zgt#YBc9A$K8(Tvxg8O; zp5#3FuF&i_o0mx>8!FmV5oZ@p^WADiH)CVU7Gph0$cn9@FBii|y~X8Pqm>*Ll@Gq< zI@yGZRCfOCcvZ8)?H5IBYoJg82h*7mAK~9TUu=DU1yG%?lJEp~;ZRNIJ>7n14R?vk zO{>c}*y41l3O&T(zGe(kK~3pncuxsSUuc0Io9Gqd#p70SeVi$!Bz!F16GigMs?~wW z6#1ALODZJG52PNJ!Bush#iXYhIjVR^?(ke}qumsE*f>2%da?0KORlACe;zxLT`rHD z?RA<+82~1R4n;f%ZdgJCWhETX_P=}=Sr!cBl;+F+_iK`268_$z3U=rHb?{sJ9LM)8 zXswwAyyhXDKbI%!I(B#RaSzqBwLZ%@+{Tb|j!4~;HRK1`oE3_*9rJHbi=Ob$P<9u8 z_x*}NNlVefsBetcn*JkBmeg5$@HEB3cc|fs(>x|ZEfTg z=e?ixOL_|J`FwsPXYpvjSuBS%8SinxAIYGuVYdbf!%D!SD_N{oo{&^jf$NIfbZts2 zdMB8N57{Y|>EqawuK{tH77?$np)ua(6r*DW`D8Oc+7ekJ!c>XalbkX%ZEJF&jd{yX zsE2>3(|%;!hx5)^lx^El??B#-Oi$QPHW6TH?sENpmVG(7aJ!Qc9=(Yji^7u8ggU?~ zaO!as83~U`+RcUYG7rx|X3 z;FSvm1@bOpb4paZX!%&B3zS-4`ts#4MuJCth~z*c%F+%#FhQ2|E<=%SF79=4)UpB^ z3T~8b*6DhqDR@6Sp+(~oW}cDiqI2~*kAq@2=re{7ZhADX-zFCaM=Ne!ZC7ED0B5mQQss+0 z+p#PhXAG%YQJ?VcGUL9%U!UO^b$^NGD`BG4 z`_J!G%oY8gNY5HLcjrRss_2b6|6;U=BOL?RreLzI8K`QU$Nq2Lx_4v#C1R5UhU(a0 z2g!+swv0KTpOfK<&&}h%9dkMqhzr_rXZUiAH2UA&e)!+r&fmHMuZ-zk6)IjHKTjm< z@!hCI2+Ll>7soST^dN4@Tfnj!ItgHSThxF>QiZ7gaDb!kA-gA*E(Ya;tVZm&|8Wpt zSZDOQi&(5k+_B=Z7Bqyo-euNWrNh=wKsao-M8xf!Kp;y!-J>Dq`vS)Cfe3F)QRYft z(}^Cw=U)z}p@7_8zR`;b(^JZB3ZEZjsf$mU{+rWvMTI4XiG>OJD2+jmTVwj@)_++= z^3@3)hSl!T+!=ez1Bbo*lb0uPuJmUVCCwC=G7?Wv$(2<3N)gxZ?O_7_d^7W*9DV5m zc4XvtrPMxKxyrMF2S4q9{(zz&|Ni&cZ7RU&<1J%03F757t-fObV$Hn$NPAqX++&yENW)XiZt_dBr+%a7 zZ%Fe2Z$z{HU);+dXOH-`XXpJt^0T^u)wy~u%QeyZBo6W6;CTi)K9sU0D*@68N|_D}DA4J6X4 zqP1j-DkkRI#cqluO6g#e_dW$Te)Kd6Ua;31!2mBKJM{6R9{L?lF zmtQ`RolDImgfHJqq}5G#RNFu< zfPG4`9qNm_gOLcOh@5m#xvqj;;r$nZ*q;l(;;$e21zZ{JCnv6;FY$>1@yBNai6j91 zY54uWCd57dEb_2Om3hT@#@!p5HT19{Q%yrWmT-AR>dKVI2$UOrg(6VE4Kw*Sh z1r_nP)x7rwsSO2#PK@UH8YAfyn^d_bsQYWqi3|247;Y*;xa}Ft#%A^;04dJG;mXHT zr|(O6_o$q;VDD#G@&{@-YTKh>+_N`>@JixKAF%UM)8dUC9|;9^15g;-4_;*sUO8W4 zLBJIIp!knkd~s}kVp}rF+>z_aYm$%j?$QplRBqd%JP}UH8eOgQ2FT zu||M<_pvpQ?BapI1gT~<#=NU0~{A^Jrr%OT?iyeB1C#+-Gv3g96X$r_AB{ z>%uTqD|{C^+?WZK^}6;+!RHpjxQIWXlGY%jM5>U#$ANPKD1SisiOtlr%4^;bI*E5Q zs4Vy~9f?kU#rng&H=sv>%Y6~-|Agx!@V{vp68Fsqs^hhS=$!O^1VT-wBi>3Ctk@d_pp=brfhu+kOExTvVX!GbO6|8r~@-)Ymp;aiwr{f|CChS z*UK6q)3*zYeLoWHD`2Q*(qIvzgRXW#JL^uM#v$GtI*^2bW%s^UIzlv(pI0?1R$;`Iah{juP1$x>ZmGy6&2jct z%+h!DXAwPXTrg=fclQb+QlzbfST#dvr5A1SkMZP53Zstsyiv6fgrsi^Fceg*pRVTE zeNc)wvtfg*Unor(hmv6U2AVfLlLBc3YZ)OdT=KS&?Sp^v!#Ag^ICmz4gV60(mq z)}=MHaMFmmIy-Give05WT73ek@IjZl9?A!SCL7p1@rh=8#7|3UeDHcqR}j^QU%yOj zN&=>zZ8a4b4SNTa)T42mE;I~x3fSmw1(C~!I4A?}|L_9V&hwDA7a+dExcil@a?zA3wM7Yk&lq+1j3 zRQ1BUqNjrBe0Npd?3R&O4DR8b?&FJIXcMmQQ-i4nK{PM?B*1A7rF;Q)+Z4V}m1uv8 zoCr8@;{qDY2kgv=?SQ{D!nsC^-8JI%pTG~tB-yDH~dVl99_8(z#5leo)lt^ zu}43X0SI6rgi+`9|7Ong+IQA`(YyR9%{wS%XB{YeW8(t;@D`l*zx6=RqYm!{!moMk zu-HFra;|q?;8~%qg=x6h^{;uagNimtR#b;lBO5n^%+s1bb>r3+7SB4VTW?(@@|Jjq zbgK}asJb>AJ?94$zq5~#wMtT;NvnC$YyxOza}{m?N!!07m;TsvtEh;s_T7U93xKyw z3oLC$d(XNeO@z*~I!?+l0Gb$R3XA#NRe-Embb$zSp@2`#$_pRk%1@IwcPP{@40#eQ zCQTBEiL~HeuWu7L~`7m9R>Dp=%9_N8g-y0O_e>ggz%rx7rF5>tD8NGVjh+}+Z zni_}n;pZIAoc=CQ-r#Na-|%Erqzz4>r%|Od>W}x&NAl&>q@{^~C1sysudtLhl8TD0qY7IVD4w`V1K&wABfX!rxoC^N`z*9@BTs0Kul3 zrUc76$Vhy5mJIG*evYz*i1Lsqd?-W_Cs??@VfiE47}s_Ag}HTxLqhD>`T}5-CT07S z;4F_q0Cc9S1UVzW*fz=&DUUTP-79Vr!{x6VRNYUVn}_{Pts2@l+iR2cx!v(zZ_EqB zRYEvS9lh#tVf_x5lzKMmCJs}bSdhl3ec0oc|2Q5%3h^3UsPHX8ij{v0pIrOc-31xW zO*Tl8>i-~I=E_&^M{>t3ojV2Llu``DS60U+jW)rawiVQF>bIYD-?R=i(QD1jwavw* z_1WChchTkWyUl5Y;xg)6{;xN%)gmXDsd&PKwf~fB^j6IK*oFNpoP)>K%~0k3GQFE* zZj4&VAvib~9(D5mjH}rDhV60p|FZzZF*;=9^+B#_J|TLcQZ1oT zIQbmx)Ea_b@=^USdnYWf*uVNu;r(DQ^L~m)LwAh?&%scPe2yoNGx@|J7;iT@84T|Y zzCYeEq*f60HG_%|Ya}aX93^Q;^C|#2-SNZR9)N7ku(NwutE?p#YIFdIb>e6ko3ZKu z)7cbfI8JpOZd+t1t1%Y_X-^5F+k8sGpuP^Dr2{4yt?u^stlD) z(=E^3p00bxpOabPB^(_t*w_f#x!$)~V>NBjHohw7L~A^X8}rLDyBkZ3SdG2tA8*Df}2CBn(A<1{8jf#;j+*T{aR6DP(uLe{}wF z-;!)RInS}v15FHtMDhcL)j3I(tO@UMQF>_|s2#}Ou0V0IeZHv6w>}p+j=OB2o#y4g zHK;OZDk(1;$PcH^BS*!7s`Ga8n+e@Y(}znhw@C!OQsS;DhbG=pkBc*sws(}i$lv7x z6FmR2if9!Dlv?zZ?PXc&8G_;j2|!zZw(j-x!{yhP#Swdf!=T=hfz;N(hnbr|g%{Mg z)pjW<;*H7?`bG{Ep8JJ)^L0`)`!+bCD&l3hsw}}F_Njyv)~4$6c)Efm)YvBXM`Cpe z8yo7w!6Qg1>ZOFw?^3jCZzUXu&3PpuI~%eY9Fb;E_)c2s>G@d*mGNcGT2WEe!-`0T z?}m=Vmv8Ah3IDO2N7W|taw_7K7nJ%%&>p_Yr!pcpXQxP zCL#^?OmSjr%!8{5$h&$lw#VRZ=;8$IA$3xalr#u20F7*F8QCQsL}PXgZp|R5)HyiK z-yYxokM^Nf^S}EzVGi*P2XuU_bP;f;OBNkmi}Lp0hV~YZ9k~gtxw%fRRMgfB8qIjz zeTT5~7Zr-`6kjHqb6QpI(G)QLV|?6rJi7mPEyIQVcP-zSAr1fUR-W2a1Y6W7To?T} zi=QVKuAD5I$NuVhBN%g`WGZ%9Jdd04<`#B!8j2yXeV&_LQAu)}UO^9I4o2{~3f278 zs#o=yN&9LgzDifsOi7>>9&=XLu+T(Px7UHWKOw4um~V%I{CsuYz8$qmhdi*abKKds zzm3)B-_O9MJYfLqn2!9iDZ6T`mOR8OFDB%KNaYB45pPuTV~exu-82mdEdn6IDBpif6#oa>jl+ja% zs!@!c%*a8*#UObpCp%#rh>pe!YK}wg=%m;zV>0{5c^45oTC^9>Bj#16c&u~RFP&4o z##~Np7MJlc5?>YfFgUgO{mJ7&Slpjr*PPo>ktnA&s>+kEo!1^Z-pZqw2|EsGN<$U) zO^D_DL3C?=pK1lebc5HO38#bN#EAv2&$s^kLa6MT1l7jmUtX}$b^zrPQK!Z*Q}zpW z3vAW;R#ZHX6QQ)OCr?rE*K#i!mWL48_P0*85w&>3}a6+2!UB;b zbW+s4epsn7PTow33GtiJ${XvxHKxHcM9~13@zN}AAyeG-7dy|~aY;!y+bYc)b^k9wvlN5K3!MH+l zD>YlaurGk}=Yl}*IYYT4Wkf0m(GzX7L-oV8j~k&IaKKw>k4UW(5$f3{wD#jWjJbmr zSek8{>#fD_O1eKm7dLWvX|4Ev7*3CaWF2|IoDRzW{q3N(9 z;#Uge{YopFmfgiWg3m=i5g+7kkfc74U^dQ3KFHe{(+!Ex&~)$0;{V*>H+CoHfhx^hF7&@XzL@5=qU0gF@aykdlTkTP=5t10ypB%XTsf zcvJ9si{WA>?FcmAgw0f~1cj4&k8s+qSXO9OHLhCv70;mq3S}`wKSHWbfr#oq{wB-( z?f!V_UWbs~=NI6D;hKdYq2`8>bBi5Xyu^L)*z5*3T&r2k}8FB8AlDVurrWd_ZpHqgmy-jX$j!yX?6G zM88hw7hPMbVdro|n71JkNveO`lwT2m(tE*Zyx51+b@^j@(?@98&A_V*sYhZe;ui&w z8BQe{GdM^>CdpJrGk4?sJWY`e?EX+u#w8%s`G70msm`JC)~~*9XOp=m0)ZW97CPrr zs80Mqg@+N@&+PB?%()QsfDT75IIxep71$r*c^K$iMzyH9&^c}ITG36UqQd8bqVcPP zqpE)QNCdc@YTyaXD{$_;Q3=+#xsiTK!s0noMWxgi(GPQ@UXa8p6UnDT*-g02*kWI+ zF|r+)EZX{!Cqwc&JJ)l79()l9vudEC@*(N@XqGQqi- z90IEX`rBDGx3p>aqZXz=1t~Dl2dZv3ZJ;NBLJrTFB#Pc-J|tB$fjYA#|G^(>YcyMC zy&=a^SZaOy^te91(Xidls?G0>u)?XNqTv_|OKv1?z7{0g|6}YAi#h^bj;k3Lb@xWg z?!z$*h{KRhhUatmOcEyI`_H!*aPY%svy#wXIheMum-Es2>Xp5)j==(#Jy zU#?ohVIN#{BDS>FcdocQs!aTC?_b^=s{ZKvxiA3@fWu*3{z^PHMJB_JlV8Dqkv@hu z1<;i|`XxAaH>eA9|3y6;c>F#1Wu{fBj|dM^S8|ov;PG4-4k$D9#DUaGVtw^qb&bUG zJBbcZD>$Y(Y9xeTNc=M2;xur^%@{XaN5<`3IFCwtQD2>h(LU0^abLLCRac35pe+8k z`CzqN;>Pw^v~M+eK$_+q;>SX785C2oz5NEMDT|<_Rp)3Al5p$C8LfIdzf8A~^>L-V zxkKkYXUu6ea{QiIKW2b5+IITM5n}(3%;I5@Bs>E_hkpX=EB$VY`SF`9n;eL{ASL)F z33d05*!Er<=!<5J1Lq zVx?jp)w!On1SaYGIBSyW@3BsYiZr$Qv3io14KK%xZ7x^Cm$(a;m=I4k?6 z&>oCONEaT*Q_?%9ppL;>xN>KKaz2qJNLM=^`&}3@#0ey4nQ8jZ**c+v#k^i|Yr)hB>p`8mzR{XV2Pr1#q+p5xI zsU!M!cBJBifm9Uc?jPpP{OX)0p_cfUgb!8D|VLGa!W zNuBjJWB0_T^?SI}(1y|Lv6Dz==T+F+*AjqUHR3Ha9pU@^pT68LRS>JmSi@<7eV__4 z4EFw5pE>3dw+NO*1P4t{Ma>N9*6^Ft$9fiP^V^U^p3B=4uhKG&pNjD4*8G9-dBYu9 zcFjErJ1Y45P6sn>SA8i3KxWAc%3;5(=%3%Y{`-imlF5m%L-(C%WWfFiyXh<>OlcwR zetObGk{?;ks8C0_NDG3001diHxaV<<#zNg@4^iH+=ekjmVxAjmjqp)zwRTqh?ePgd zD#e#tk*4H{7$;}QKG3A9Ll)i zwGOfmu6(waDkqNSfD&nyeK1dJMSE$K&L(Im>Tvtauw^MA(ZpiBG?D(9`4%<$G z{|^8xPFei9iFF_WFEcMo zzYfbs`+S{$5kN`z)br*(GyJT?_LoZnzCHN*_kfbdJP#;ci9<lg3MkFwL1TM- z@%#Mmn`NBZ?RUdrcG7ekT0gR+byJ&1=&gptNOk z5no<&n6C~KJ#NI3v1m%httBamB(5H2SAXUNE-D|k+pZ6r z?E+z(Gn0mG`NAxF=9v|?Kp2M+5zXo$WY<|Q$%08?z!j0rl?02H$#g8q0D4eFA`noI zjV4*^d9&t5!n>auK=B{2hSo8cdIsSQ85y_y%yC3yE~*sN0~;>jGU9n&(_{j;@`p5%`_4j+vmY zWn}`k0;mCD_W+<$%OtK{eQ<=0*umr3_CaGdC&T-sM7a8tNIv}ui!A{dL>J5AD}Oew zUL};LFh3pspqN#bPm{3BB7#*}1$;}8co)GXl$9;60|7d0#LUQVaRMen2VL)g34y?OQ-j09pxDazb%!E7)|z-vX1IZ=S47BpY!m zMFKzxP-%)WV}gi)t?fkas*l1EGhtm#L)Hez)`{j;`>drEixQk*acNx!r_!>;Wwxj` z&lW<~J-<4G$a9%iUPc>09$ARjTLvmW5dfwjP+9<%M(mU@*?KiIhD4p!J(>)h0KW)q&VvM?b zYmsf*kPSaujPi4%L3*k_%Q;3eshte(IRp z2-f_)T))0#pY9u8{4HD^#eZ;I*C>5aKuM398F%JB+a1)O;2gK%&f!n!+&}`dmLoZU zG60lZx#IHCJ4yUv;xHQ>9s zL)mr}M@iUr<7pfa(*CjWF(R^k1_}KU`{4ceuuy#${ z%ybHx2c^7>f;JL7#{)`TMBsbD}GKvhH zrJm2{Y?a5`pR0wLZLeI;07|&MR8?15UQRA9rm0x9GbbcAB!QWB$+mAp zejS#O_W3&hB7l;Ao?lfjmN8OrDUQBqcjHRa z)e2zsMvMLQr3O27u@B3oDO*yWYfnDD*dExifC+w*Ra9{gp-{L=I3+?~UH$A;a&bb@ zM2&5ha66yrGaQ>$`t)@@aPiV{DMt$X+)eZ(MST1D&!4jc2M(ZAr#V0Mr|~(L%R+fY zIjI7x27U1jo)!M4I(r0`DKSCR7IzMR5)Y-sjJNIa|jI^lD z%UxuZCDlAP$=0k(CdyF(U*!uRYbFw1PTU<#AI{Yl0@DWfT-BX>evk>5pUeGm))Mh^ zeSOb853y0M*+s;`qJd`>G!@)0W2B)W`U2oseLZI3?ec5wO1 z09Yc)LQED~(bzc3^O$R^sQ_vza_NfEU#4ZL71X&vN+*r@N?M)M39rjSNq`df1W=;c zxbjMA6`1IjkYLmwyvrkJy2Eq}2NWm|vSf4BLB1vcmPSUVX@4<0e-6U#Gb51yHeq#g zo~Vzh)`hF2K%xvH;Z+pEI|Ye(-NJlZ3fX^MT^@iN7E7d5_|PK45gEHwCTBgx@A}4= z{p7hZd*O`r6Vlcx;F)tGUnx1F1^K$LK{dK1O!#6W+n0$?NMeU8ZV)p#2 zQTw!EfasAOmX|SP4`G>f_qKGblghC`DMS9$hOBGi&lfCY0Aeyg^6gNv31mV(eRW8? zb^-}R8H{A19f1gggV*ynbg4T%e!cJe{uUZHlztz8lE3G5uj6I+=esuJ+G()I^)=2> zJ5npxz&H)?=OPRuV{zwow59+=r^3lKX1hN*Z~Kq7*ueOp4UP>!z`fFLTe8y1N;7dE zHEZv{wffMAooVZ*j@m7k`g`QwI@@tyEj(@XEvy35;4G6o1SYBdxHZoWvdS^qZMdFX zPLZu2clF*B58e6m7p$4cY_GrmI_XuXaOtc5?N|~$_2kn8o7iR*l@+)UmrxFkAF~xa zw~hoTX|CN%RLR{Re?pYbJy>QPB)a4Q0vD{b`|i7s_vM{{RJXeT3OZl+Q$U6kEak$B z&!^w#e|zQ914`m(lEqUVksZ_ch!Z2YLOiEx`42 zeeQJwN|Nh!E&jw=F@zFR3QttSxJ1B^%JKq09n=lG6FF@(pXP^C@0HrUVbbhxSB><&s z$SvIH!l!D`2oD?yKq)Mpn}6HayDJHUhh8`dKn#GHG!L$r4eQG6p`B}O&DI5$ z1z?nxYc|3c4y9lIDrV39ny}(6BIX^mmBmSR_ogh!xHE0T#!Oqbf}rA9Z$z;kh`@WI zq;TW`pcG7&rFfuU0FVS=5?QyAUX(zr3U1aN7*_5ISX-9i3@$6~)d_nga} zt8;=R1ud|qNCFh_U!6{!JjECGLw5McVHdIJ{Q2{4@*r2aQWPMi+g9IZt5>ao+o;AC z)>Omak#CvVsVHQ)>cq?KIF_8tQ;-WMTM>8jZ(0BfRxYt|$lb@~QW3@CKzup?0Hm{L zhwR+h0YI5{YwNiHurz9EDNJ%u_LtSgZ1K{l)e*|RZebOcJLyCQ!~IF&U~xtUy@D_xO#Owba)5f481F5Z>T^@msnz5=7mU0>^$=Z783Fo}Zk=oeQgo z_Kui+^ue_4{tzpyCPIIsWDZW{lfMegh;l6-66t)vxJ-c|xZ;dJ^gJ@rXMJNsa9s^q zE?icXOz;+BrBu5x6ZgXmTZpw*b#)pthg2AgrL^=Zh`T2NQm{@U$-+X`PdM*@?J4S> z+O@%iB2CfD=SU?Cj{Z&h}oSG8Q^g?%Z4=K5L~vPx6nJ#f1}4V{ z9Y2j*Y^s$OWY~hLT;z~zH4Bgn)=K#R)dht_?ZSF19SkiUPL~Xn+@|K3{p=TG_M2T} zc8v9lu=-d%Jc0X|1!h={%ol$#zR}^qM zYI~Z8ZFsED3NisC?wEp*8}675RknU(C4dr;Dhj=ms{jdZodocqcIfu;I~ZZvp=0r# zbK9o+NLZ%s{p~h7HE0j4UH|~Hz}DZHVjDKo52Zu#aJh`8(l0SGqYi_@m)CfP zDUYmE^%0?usBdq)z6(HUmy4!({=#{yt%Yd*tB=|}ci#gi*mA3>sd3L!Vf9=sbJx0` z_?g7XcjU8UcI4mIoK+0!sM+OQ~>*$(?+#pLcxIw0-9XQTxto`e?wS`kNv^LbTg%B+8qsc8crP z?nc-6<4+7kbd8e}ha~}D-+mpIiuUMwpV z>BNnJ=u68=CLp?8nkjI18fJ@#q*R5GpiG|HP+x|crk$wPhl12cP6lDx$IhGaNS2B>C z^e6Zqyia+S$XT5t$3lzY1 zSse@$Mts<^GjPMp9LTklwHPVcioQi*TyipC%gMv_0k#G1 zaoG2ZU>>2<1-#%MiiO-H{6}(ui^b9avyzFHHH@_!oHxgb=yg2V+PbH#YjDbX0E7C8 z9;wJ~nOKwL0%9(jKhLG=>SU{4fb|wp@`?ba^8uIg;90terQ&nXkJ(EAO0rJrgn!3U zkber6VshKjav4DBzd1lD!}_sMQhN2(Df`K0j`{BdLGC3^%N1@4>L3Sb=7kJ_nPmKO1)0oc>F9C(M7 zV{8IY3Bd2ju^|ALVcYk~uJWuss2RUN)aa#R@wj&^DcF}L$lRgZnq>mEy4Gq>n6uIBN z^jrJwZ+`>7T8XV%vD$Im?RaPh@5^QG!+-!ny-PCWny!I>#jj`YKfC3@1rI3Y7sOrO z=<}(7-qFbvERJzNYe=~yd>PbQ!g9#dq7DRY8@S&GiMeS7TUbBSwKnC zU)@Skkm`xpb?#Wyc7J-_KHPWS24o{YF=%%ZsqN4IVvTLNs~SrR#*h?oaGeq%sKz7Z7`@p| zzV!`R7E0oDQn>F!hkNbgk2+E02jSQtx)}=o{Nj1G48qo@cBa`A&!ho*0059I2G|k9 zY60GvV63BHx*7V6R2nBT$w`W`erP;o6&GCm1pSVmqhp-oEtV8jO;$>BC)>AgpVgnM z=ZkWkOOHPGsN+)7*C7$l%GDx*yMh3v@Zu%{9J|&M9;fG?>-)Hq9rZ0GMtO8D5-4F) z)PvkJE;L^-5q6(Fd)8W8FG4omf(utY3QdEXkVp=zRRiL1wRB^#(%WwRWBsH)TUcCY3rgzjwiVg9djKpfNp+SxC8ZI|%E7fVL%;{EgSH_T zJC`I3CqK2DnOfCewl?UeLz4h4NtKqB zHqYu%_Nq&>iB1)>+C?!dtK_<>RGU`}nRFrUe?){+vq`3(B|$o$45*g^h!g?U5WqK` zB4tpeRBs8a^29+V&~tKP(g8{n3V{wU!YrUv={UZeg%Z~}t1SM)I75;ggES)-ZK$8H zOsfy+aVX4cGft5KY+(no3jn1FERZDB^o%sxjJTGt${?LRnM5*pmZq&0x3lxjL$twe zYk^#OaB|cs|22hWR#jY%m68CZ6q^sIR0X(LiA=;j)!mas)X52Z`7Hn?EUvn+9&un& z3h1K;lmM)4N)}33z+@KMl6iUdU;j!LO6k@InAO`gWiP)xWk34mr0s7*epnIC%bBnz zwv5>Jd!}q9ZoMmSFS`^_qTDJaxY-v6lmbz5x9eQ=;P4W^UVY#9e;p3Sxj&4Bk^>pT zd892s-A^-6kJ4YYDVZC}oiFl(r$5EzHPdQqY8{~T_}9MXBFG8IQa(hm zt2DRHr=+o$ zqPTvcN}bzGFUeH+hd+m8pn{;vioxwfNz z>fhn<{&yun>FJ$MJ07NVK9YTI@qO2?KX<~-xg!B6U8COo0OZ&HbU*p{uJ;ibrfuhaP@?mPo9<) z1|XB0_3|t}kV_U)Z8WFVZk5?B>Lc1b3x6gqTP%6ReG$L!Ovr41f7UnB-)8!B==$)cj_WJ9wH!la5s8Xw~oo`E*)!NdfOKef?GF!Ny z4qyBnmjZJxo~VdpxTypJL}kS7O_AoNqJS6^SjCVcmgCX{mIq|RdOD{eX@*6qaoo

Gku6j|lmK>6QB|9-7?)$?a zLrLbvIDv($9ph}Zg~~}ITIg|Kq)zYKPbM@2T_TKLzI|!WUY{dBtG3mcxIXo-ufH}> z;V~#P8^;VYOt}bgl8Fik24o$4h4Cd69eKiXn7%F$0I>EWXG}fJPNF(aav<#7fN|Hs zRp$~zd56KQwa)7H8hoI$u^Mo&zmRQQ1=&~ zf{N!-X3XM$AW2hnr&QjZ%>+hB?k8b~(swUPpT(blnm+%WzANz4w!I!Bb9JqRI*V&L zRq6Fl03@oci{6$PSQ=jzpm^({V7v+P(6|C4StgaFyu2{E2V3nMlt)|MFAY;$U|=6`9;TyNXAdDPitUK|aqFUDvZ1 zFo1M1iQTjgonsbSu{pv3*Ga{loh?FGLkFQf$@sgEaHgMR+Jt1E#aOGor{T!YawgY%@Nd_zo}k&j$!_luA!yi#lW6khJS#wQ*GSssT?6N4588@ zO`-+2W#~FjMo#IO2pY#t4s>~jKXMlZBs&E2bLd9``~{rofom!k)ZfGi;I}n4%4N;B zBUz-@+CE5pb!B510a<3tMQ>M@dXdAikrs*fyuOum-Oh&QIyf~cnJj(jD>^dSBL|+g z?6*KG3;VqsqnD*2@7s@9_TebZ1!$2lY|%R9yvXk8p9f=--klH!=wf$z#%sPYN~$vg zw-@qL!y|i3j+}`(Zq^!#&%GX&Lj&Au2RUxx{9V}XxVl2~=J2OwTzV86?1=-|K4-3I zk;K9+&gjo(gqyrqJUN$^j!MZk3(tl@eLge)c%?z&*r(&M8Xf$ILKOT-BW8gQq((}h zh+Eoh>!=<8(S~pk7s*6qH{zGCoh={h4wL)ZpNEPuHEx0~I4yyn%Ri|T^`0zXEPu>| zT7O>&_k5SVh0|!SuY^$d)kHRLpD3H-bNqS~LbEcrDG4vhQ6WJFc_OOKsMYc6s5*iK z^ALwg)atDCImrpwtE_Zl%8QOZ2au9tMAVooNnQs+TT$A=TtWY5d6!Im*+Tu#Bi_1% zP~R#b1iT_O`cTed&P6n1GYWs5?9ALCIMuiL-o5&lDs}r<$WzHJrcGf(=&}e{>|40D zMTT(f4V*q_t0#HdZd{7BQd)`n$O2_zKTXcezXemCKKKXeLp=r2gc71QQd7Jy1OP>f zy|@L#Tk)ng((rg*zhBw>>8R>ipFXU^0!7XeTwN>~#oZb(V?&g4ODP%VI)g>Y5OKel zI=UsP=7{$6NN3UA?!UM{H*c<|NamDGg9Zk=WrT+~xm?M%OZQTbm=BzCC z;Oj~}zbg?0&oBA`LK#d5B;~zM{Yc)?Yvai6v7m?ky$5_orVmf+mF|`-p3#4VT1Mua;mDOLaEA4lCdcOx(u=T(xl|yra)7~W2J2sE zEOj*B!KHh>dlYuqsAD+4zMtoW2OS%~ZJsUtgb_lzpY40^;d}1R#hJ!lf34d8H`Jc4 z|EJzIF~$Aw<|pVU+L>!&_XRK)>Rt{>3gqn!@^5n3&u6;l;eFY8{<`|c3oON0M%Cy0 z$gtvRJi_sJ*zI1vjqW_t0`xjQ&wm&6Vm2NL(Sh`Rg}B&Es8YzIJpZW=Xg&=MX#N)p zL+&-nV(#B9(-DTgua(+jfD6m3UnO~(>OHg&nScjpAX^}V9%FX;x7{Z5w`Wb%&i
@_omM*z^H@2nF;iWNLeIo?mBaaTsUwT%$kV zk=$-|`fC7Mp0~0KJvu);{%F7anY}Kr{reUALCtU=X9>D_#Q%ss2+ep zo)X<$Oz!W?I|ZU5{{&1S zuy!UYNMRP_X*W66hgyfu*WIXjf}~9(l1LQYl;~)L<>6x51ker4YzCh?wOk{}5kQpn z0v_L2Yu}-*3P-iwMtb6#I9sxeFcy*4^P9US9#~Z^Y8SL>f1B|^onRU4WUb_>&hdPg zxO|1K3CMta>4T6#a?2%Pv^oTe}nSD(m?i4dMuxQ(t?2 zf`sRd`y`zJ4kVguIUT^{`0sJN3+BjNhbJ*Gk0wI|{aUtC(_X$xMXY_XEQpLMYV_{& zJv)ifgi1Q}EZQv97Lj^0ApXH1vO%sc4YuG2u1bleJrj-Z)_20>sy|p#>ws3|nweW) z^HAcmiY9;fuGHrA&ifs=H3A#dMyT)K9fc_wNF-KOk2UADd}9@8~^wlS_R6 zePIJ?zp~}gX79LefX~|w;!T1W)cftq2C(BE$4sw&?6>uthpIg` zQ4;T>60DGQ$d7G0e15*&7jn0HS|`L_D!jg%lIMTL>_;Z?y_w)#dbs{X+G&W4^Qj9y z6@iVr)d!OS8Kk3!r%XpJf%>`VqDQ-!L=hG;W&DGv?7Zh^mlUfZ&h6*so(0}YbE;a} zTORWi0{oJ}-FvHgq?LN@fBRb<}NoE!AD-ojfWEq2dZ1QL)bHRbt=o z?xFU1zwf!TQ4^DUzF?7vBJ#v0c4t4$KCP;04|eE(q=gB+o!jem{}TCe+AtGB9v(E- zf;b8W=P%XkRtPap(91`_)7@TDZr=2KDW<-SV{fhhl3Pp0uN}WeC~#+D;TxRK1mms+ zZ8x8bx(*ZR5Us%tGE)V7$rHU+4zqeEgDHV3&4*dckJs-K)`Ek@6#c?I*M<9=Ws-dN z?K>}McygHF)c{+AqRxly8>^O?Acvr6J(220{ccG}M1DEtj?21}aw>1kyVL8l0AbVr6piUDhh%&Mk6kqm(5+x(lBcf1!?RH(zPEEZ_;Xv_>*Va3o(=#2sw->lJ0zcTZ#j97y|s zf;T(=?VsEdM(BPpp)D&z`xvvgYPKET0YP;ql}A7phaC74dERT=e1QXcznr>hIVa{4py~-PT=3uUL3ymSCpSqRo|5{X}HNk}Qug_r9&t zxq0aq1>D>`(&~gEiE+kmS#jH-%yo{@E`f5SpweNhVtak!6^~1B)kMp_5_*(=I(!H%Vk|F&k+wEf2WdOIk?9VVE-fc=pDuwN zp&-RxCEXHwNY@-E=2XUE9~rJU&`0Czq=Bg@9p!1beB$c!d_jlncV~p_w}0<{%*?Cm^EQ(p)F5@xe zJNC$~47YmcxC`B^38(n>$pu5r)Axs&qED~qfKr%R5$%R-^LAqks!yUmp}VfnD~yICb8?~iZk-2eR>~SUq93R@AY!+KSsdK&cP&W1UEBS z+%ygYqs^v;PCjnAF7VaC@89cv4aGTw?56-l$lSczt|4>c`G;Z4<%VL9p!>2^P6;07F;uW_XDHy4?JD7$}e4*Am*JenDz z`kb9-*UD0kXM20Rw+7}z;O{kYoc(TiOa@F*D!Dfz7;_W*LWs43qUVyMvQlJhjH19J z+WrdvYxfoADeNS-XVrY^w4k1qYmj}Z!j{s)8|_>j-SR)%QSZLFrXwYk5TL<>!jdq8 zNadPfHn)a=GMb;CL!9ycshZ{Y89RPb=Wq^*dy^EK&j<0ZCobB2}aM2VVO`C?P6m8 zi5(btuX1hulI2ZTkm7%dDy5E`xUD@5FwZUuGHKE(SKE1VMUz~chqw?|6XTS&)-6T3 zr_VVL9T>uC+5IjGlUcVP9BRZX!vQN+`--j|VRjg5c%fTh*um?ARcG`>nkzP}dy&tn z7_|L8K7@fH+C2CNq=IXhhBx=CxX3xYS2Gt)S6v8*Te*#dIkyg$2$vgWk3&h+q|F7# z6zI?H_% z4RBGTjN=wyI#bq4&+T3h%TudUirr^`RyTx4dJI7=+y!d6NlD`8wBZuSsAw@)|Cm#6 z6VPZo6%wXs)5O)df&y6ggJY5?Qhoy%8f+pThP_Yx+*ZEf0;eL;h$Rm{hCg|*Wxq=9 zk^G`gmzbdr-}NNXNw>IeRyH5CDQZpmdZ*diG9W>>or4*IDa)MwDL~1+sRoGC(UCOj zJ9J!sJ6B!Ejq%Kiu^f$0C9HEyYRgtSP8kWM)B7lD=#7ngXjpbuBW?l}-0E;#ig2j* z(}W~J>6b-^m^KS z)P9t2tnSzRuHsH{$}+<9c_4Rgqa7Jf$q;$0evN882|185^Qv(+EpxHU?x)na?tszO zkZBjgHkUHBcJHPl&g<=-&*aR6ah2z*5rmETU%3=Tu;I6{X2L~h2+>g)8_IyXQ*$2r zjzUmR2k2?MPz9$HzMBs+3)_s zqTAV%=4m%x)Cp~@-f|x;odB$J`(aGt_!P#fo(Kr~a*KVG)qOc!_%zNt{b5&AG?7ec zRy?Nnfe?kWwG*I@)?1PdEd2l|Wr4MO@TLrB8fDcguMUm3{pfOCeTy77T7&gmvOw_2 zv;}@S`xq48Jv`a@0q$2PvuDz1RfdMYZ}nn&hNH5mN3A}1xVH@}T^xSKlTX$AY36ONYXNHS8lP_jk(Bo@{Ke*5q~nlMpp@jx#)P^ z)t-NKvCvPlR8S^iCEKzew{i=cuP%cet;Rd=9vj)~R2ovFwayA799-!P5at4I_9Q11)lE4744$d|@^fucjAA3=vI|rBDL9KZDMp9h6Tcyj4#(E1XT@&#y2^ zfg$d!XX&rF9X-A z&FU97z70nC`S*ESv&Z2s-lul4hVx;#&qv8v&wDc1Qk(dT0thq^sG9Gm^@H@%mHsgd zBdLFejYVT8#0lj*>)YlfB~djJ+Po%xnDW92R`kbDZC34p(_*)*xa?)^WidJZT58$WKv9rFWt&)58qY*H4{XrvC!s^YFGfaeOg?RB_kVfk;S1X zvvl?4_Thwp!@k&>LTe1e4{(Lqb!^#wEexCiLxc5!ry&jrdO#5?b0hHi?p?H*adZA_ z{Mq zC#AG>7vJMQqm-Dt8FDB^5=F9z5)673NA%YqG7b1Hh~fmV9*5fUKJSDOG04Uy-{f+* z%f&vXgVcK>g90-7t&swu2i;Lrn4RTOm4M?d8jD{;TluOr1~i4~8vtK3hDU z0s)=59q&!!xNVW!M2mF3Opvg-V~(q6j-6m_1o*NKcg@>2Bb`CotHf@!|5#Qx*VNWW zhH7FAX~F`_9tHr$#HpaQTCi6tI)V}wZVkJxZ&lip2twq79cm6(TJXE%0C*}O9|>SB z+%P3bnY5@xNkxUj66UeZFTe{tzG5(H^~$X=XS8!oRCrmk#yEn0T2_r zJP)>s)=j(uk6}Y3B}bMY5PvRc@hfDm`0nT=1H6%9fA9Rg5p2ZzbLYJ^T>Y*p)~69+ z63!=o`EeV;Ey~=T{Bs)EVl3SLvRdxfHJ6TxY6v# z*ETmbgw??In(E0GXHndib8HnO!n5Epw-{Se_du#WvW_CPw;$e(caWsGThBaD@@ii| zU;FNo=0c5h1a3ZKzz@H2Se0wLD&21P^F@<9wGRO}C-uXGjR?(DzE=6)!?q0)6^g2> znX-QOPl{AnuD!va|et;%!b6qKIRRHoLy%0ebOq@gyy5tFH44QAmu#o>aY?V<+|OjwoxW%T5u0g6si*jJgnFbHJ&0N4w~b-{DhW9-d`f z>BzfCG<^(xcgf{1%S<=13Qw|n_bHwpgJ;7GR6E&Hk)hrO_|*-Y!JumHrfvq_$5xy!X4{#Ks0PZgwgNB;B7 zHan$OEEZ6jGT!m6Bna?sGQ}g5y&$0xi>JUt2ZBh8Y%jh%U21p8jx@SN#VyNT7}-pz zE}LzV*Dr}3muCp2kxxnHWIrQRzyBrq&xIhC$9T*9Xs;}G#p~uC3TAH^Vx8IDc}oLI zd>5iMk3-_8=TevuS#n?A9}XLCw`vQk#^=)k%=U#KpT!Dp)(1p-EG;aw(I*_WALdCD ze&;LoYEO3c zQ<7k2;22YRLj>^;+;sZJnj<*pHHmk7PSs)%t!Y;T!*Rudf^-)nMWMc{7h5E*u==AK zofH;Sb+~%>YT?4|tcuSabhkm-3>A$cB6kAi4>oJ(BV}ex>1NNyK_x0ZECqX)BmYw& z{2Y4kkz0DodSStes+M0A1vf&shax#<&jb9f^lDW9UxsXwU-|w2Qe@D413c0Czvk(- zL8K)g{%(FN^nh7@_`h<@VT!obk8|Wx+1MA}SvrQ=nF#+*VD+hDRTPT}QvfiK4=gJ)lp3Kq@nmR9-leK_ zW5&?_qp!>rLyY*DqMl{IMU-3nZPD1;O7Xz;xB>kRx7%;- z)Y<{Wgncv>wGGxv=__*#N_J+nef(4MM?%z$_`P_&UvKn_xNaF43EpvqJD>qjoo^n6 z@_!0K;t&F?6VzNy!iX>i`bnvGB?DaGfG4OT4?pQURFl1qSNTPjd~=~PdMGpnG<4+Q zm={L-T&YCFD@9?Cx_bFLN%{g|vX+=_N)~+X0UjB9QbZ&JaA1N4RKUk`xv$#$Ngc6b z*K}9Xn*iS0Rv3UeZn@SZ8G33(f+Q&H^1I!sT}I0R^u3AUwls3u2B)2EgXN?QYrqVD4e2kY8s+#K=Jq-r#>M%j6%54VfJRN56UuGu5^+3ur!ecq|{*7GxNFTLb zBI1S%)At%O*W|;I)5>9!k+}Kt1RXydA;Rlu#B6MhS@sAcnQCL^L4;{@ae%R&r;UWJ zmsOf;wa_DnO5;^cT3vhfcP?ZZcHg;DG#wEEQ*iofOsXa_%P(Jly@TtvSAc>$d)BFf ze!yA^6DkjRzq()iKV1M{(h<~Qm1V*#-4Y~sp+~$6SOKA{eWGaCy5!^^hkof^Xy{-*S)k3jW+tVBtrBlWm&!ku<%P~q3b#+W_qa)#3A=;>;I>2Z)!Te10dNza# zK5imFm74*YNExaqf(s;Ak}8EWPK(J^pc;fV8_ zzZ?cuYbduObjUiM@Hp+)5&L@u*_a6*S8?_zh*nMd4?78KxJb6e_>a@Lj8up%ILwb$ z4y(CfPzX)Y#j;HHy;#!14RBKGHAdohIy=YzRur)43G~C;Mj_(pReX1rC)K;CtZ#*D z{9(k^;hf^Q>F09fMo-0p02?RtHro;!=rD10B$DU>zUx@r~4vL1jz;xJelYIY~>JXp)Gu64MQ2b0D zfiZy`4mJ&#R*l^;@uy%nzRTuwo3zk7FYxqyweq``|1Phe(gnFwur7NnMzFkAhqNp@ zzvMm0auLdXS$iIh^SSH4Cx@jdHjYtN(bE~vTRE}U^4}Djiwil(sgIjg#(BY~0i;kL zCDIEcozSU8&*#xT66`!nL6Ei&RspQV*yl#+&-SJGF?yyKFY-~Lar_Z)GzMB%@S>so zc>U<-+_2xuPRR1EBiW5+Z!DjYadoKrN5P|c^-Rz>I1gFyekF@hgP|dgrJ;ElH}RNC zAL+$KjQ88feiFvio^DUq3RluA<2|xhCp6(%+02>RF%C5-E{xF#kiEIi7KpZ6u0{(PI|mT9SxBAfO@W=a3RJqJU=B zJO^G|k|Mb}>R;Jyk_aRSUWHPI`_C|rZ>Kwh4+PIbdiF%9-i83&(oL_y>se_hIyXZ< zVlthj9buiN;aLN+`dZU<2MZ0)_}CfMoSY{!^&GXmQQ9g*br$)DA7lrbm>2$;Lb!gr z=gfYu0XOR%Bj!kbAfPc9twP5N?CG&oYKVnac&p#%T~!_0%1>TcJMb|JL=)wHT^Ue{ z2Pm~Sg67P8>BA}I|JuM{aRZqo;%wGB9{wdy<~R{-X&pw7pxWV4JDoLk-)A@`amYH& zVS3Uqz%;$~>olO*3b%*3-oNPEzRkg`pr+$*%k?cX&6;kp$uSn%H0)${Iwi>A``19c zdaVftH@J$FBtVMxzrD%Ztb)Tq_XFKPSe)z$kYZS8f(2{jA%_xB?+PL)3f5kBT+SMod8ML28QPLB)jPFnm z!&O0Dtq94$ypSYg0m|p(pEP?1;RXSFUXw>6Crfh?PTsT5cY#4$H~+ift!mj}sVmlI z`US1QHoGpyToFsqcSAlMo)O#486^?X>$COt`M`$(>JCt{I4oLm_IN3FNpf}kh1lQz zFHEo%_v{sPhYh?Nq4R_PErPd@OX{l@n4#tW4%*hXhoc@|0~l1enx2Qcw8;O-Fcfx~ zteuwiiMPDg07_rzHJn7#?wc{!e#h6XXxvz;=0+`lSK`9o6T_i8sIdir`1uaDH6ahT zkFI`?#9epK_s_Vz``|wd6<{+CL;pbmM^MXc+a^J}C63y?#$VfS<{0I$=3@Y8WAEx9 zi{Y_W=D^b?r4QeXCT;>&wX9JdnL@zE!xkxQEmJVyrn`E}QPfo@f8P5Y7b6@vt`O4E zlZm|h>^g3wB^z3==!z*LRXA;xWllM5%pJHoZSc73+}MTJ<9dLZuU|#^u2&Y1|8_`V@qi>z`IodTgyE>!5Ibd-s}|RIUI8W?TbZ!PdRKk`%(9g^l zI^(EnrcrrnsD|wAGM}U}gknUp1buDb6}hhn2h<5+>Gr3JW$DUX)FK7u7GtD@c7mql z^4irzt3#Y++3KuFn~-^~KUeeBSn2cpRpvX@z~L~&WcUPaT^{iMwI$5NqdcdVGfz1I zB0Yes(I$4=NOWb>()U&9C<9RC6X#QVb-tBd|6vW}v=Tl#6dsmmTJS+!jf(|1Cd$cK zCLXP%i;I8?=2=NciSj2jl^*q-Dazp$1D~{bvyA8Yw7W4pJV zHvotb36d0jMf9=&blCG5<4)OwmdsUPA}|)dmb7#r?B5G3Nh`Z^V3zbDD9M|BpN^wM zKI(k$XhJEw$e&=dTM%lcKCOr{WEvT#3AT>=rE_R>{^C*P6dHiIotjTsT>TzEd%|%q z7Hh!(RB)@XRQq7(@Hsp8BH4G8KEV6ylrXt^WkrR{d8yS#5{MY)w0cWCZSb5gDPujJ zP>2?PZ@0Ad>ALK6csj$QCL{Vi=q|CBc3+96s`+v6f`o!oPm^JTpD#itbFX|xHrdt- z16*POSSd!PwM8sj?!&Kv-cMkjzO%Go5*^`KdOr@n>kV0>;MKYQVxyN%Dddl_Q5PcP>xb=nagVa;k`MmjOgDRY z(F(?PY`SXXd9vfWfTKZOa&8C*yc6HQN;?HIT*>5T?b%p@_{aA#U7rOvyB#M(xbiS0 zn1}Vh#Tf_)YsS}6?aOLlxL&a^O-!B*@Ipuwzo99-?p_c96eUSbB*jnT#o4}_h{KS6 zmq)9A6-MilPi3B8KK!+Y8H&fZMqq8|FYasJ&X^Bx+ZVVoRU$|!pd>%4eFK<%ILmHJ zNW!j+!>N7$zX=z@_y2#?Wh7Ji{~mQ$*IGoe9eoRQ*S7G~Sy*UFJfo~}P2^k@r*ADp zZZyyf@QQkfHP4O+?WS?&M0tY8jWPr7pFMTe2wD}Kq->_*U{z9!7Cn#kf{Cdkdd2w& zu&)I(J(YDlhl~3gfk!utf4!!G>J~(%u9))`^MJud=DA!o6Y;~^lz)i~-C6J>Urh@U zRf2R|wKD#b$lKyR%0#S*v)U??{FCDr0|{FLaIJwOrVZreb6R+jj6o-ta9xCt1#ye=Mpw2(H-Tj^d&_R{RT#mHmAWKTMXL{-`!C$2@5^#hT z=9Wo#sBDPawDfe^MH?hvrz*T^qTi`>A^WJC^?jkeeK)bb^!%^sep5}?#3$`i@Ve}N z6F&3HWmqVEsDxB$5_4*0$Ex=9&4i5dpv;fR`{^HFE+c$I@p=D#?hr2O{9LJ{g9oQD z`W5iIOG(~vE@^Ya?>b;n%-al$I3WS;J3=n9SDt(P#@kuf)Kjf9MqOlEk~k?mgtG72 zFuw)6P=_9$ds!|F#hQ4Jc0h(vq@CRI(U8WwT2tAUU!N$ouFx8<_i zj7@&)ZE(yCNwhseX8Jb2blcx5Xo^ zLq#2wl`BW}F3EfTOOp0STrZLtIGnB3~#N^RBo=M zUG#LH;4qPkdAZ^%u=?JzIf3jlIIz2nayY){Hf5i=y_B9lTYj+m%@g;>n(Uu1>A?wt z0K?fI=>0J|9AlHPe*u)}SGdTnq~BLDsH~$vtFC?yEo$VMIl2+I@e89Tb5M7C;=ej(;AK-2{icFl{}NQ zHNCa$-4qyVr&Uv960hKG&An=CxjC2q9%5+DHvt+G4CzQO{D9!1v8JkYvjW#2KOijZ zdqWcNW^)lDHJ?-pZFc?Mb(I`&x47nPFh9qrhrIve_gvVx*V6>)T2D|9{?R667Z_&J z>9w-i(_ugI%sT_IqvYcKAY zO<@)RTgGjD)v1`S=0FSyyQ#b&q`F8Ep>XN1K2PkZc>~$>C<~pP935_7W~j}EyIrU} zHv8W`VYS_3_q+)E&@@c zXU@w>n;la~I7V_Co?NwEu`-7>7Q6^*ohr#2PQU5q%dbLDH6WX>oUVFBYV@v;>N~y9al7*Wm72+*ZDS?RD+LoWIw| zc;>w47zjyRO3LbVx`O!imF-EjpHZUxe-?~A(n{GqUHL$3Dt=d%)dS?d{5{uv9~GOf z6-z_ctZFW8kF@W1*~7e9T{%7-ryGim6dLE>bE+&FN8{}zPnkzgeH~nyB&yrwj3|^g zahfX;Y745I=9tiiH8szuF4tPb66OMb=thwsa0&y>V=l90#AGQdLTNIkcV_n}sIv(C z41ycL;bz-nPd)oSP&wwsH%CX(oK)RShN zW$jx-Y7jU~Txsblr-+#$cKNY>SN`j6I98{#?`(uDVz42lv`(r=fv$CF2`7~bSjJ1f z1&nIz|FU(I(}}%Bh>$NSX7yb=?+^7Yel;y?y$DhgZNTwiF_%0Ed#Hq5aRd6fW7Xg0 zW?I7l1?_bJ+(A&)G{6{%7HK7&A@ZpFVMVCX4)BtowS2Q82#ww$$j9+aUSc@Fs zyv@yNCqHz5b)#FS3AsKQEH)DGu?~aSxSyH#($IGpYuZZ!ShR3kJM*KVlRHV6iqX)$ z5GS3spWP6VIZ(zVnvFG6uEBU!nk`Tkc>TjLPCPh@5IUhIZoI$v(}#dKNP#xM4!G(6 zyiMUqeksk!%Ghvqg$8S=iM`%{n6GLxGBdlG(=Al!d+fL0t+m{)z23!*j=*}Ifgk@7 z2HzzDwTXDy9TI<#AA<6q*y7N^8tZ9fo|Vuw-wx<9(v_WMMcjBm zGm|Ji4+7n386pT49zYq*v0yg(8zElTV3RQ}awzESex_UPq|1W!!zbit@72olq4=*& z*v5OyYs(?w`v~Wa&V|gH%3&8iDxYrR-hKWjP#wHJ=LfBP;X^;BfHlKDUX%l=morMS zqhyGPWj%&Hfy&KbqPx|r|Kv;Nh_^d^04{6CW$)6U@NYd*6gp^n+o0l3A%G(77xt0a zCQT=)GG~&xp|?ngs*DycMt%)Ic}vbjX}`|**{Ff+p><$c+fb+OW_#C+&?vv{UNxZY zm51$vq2TC5!P2hW%&oy2l=*4wllesWE>R1^Nqy!Prp1@#kCDkJgk9~OFO3M^oH(&V zj-a?vd_1tQztJ$il{Pr()N;kkf;f+BbwoKO7M`vT#~=m){$a0F<*R(|ZQrK7z(t># z%~^|Gsi8@^ef&U%wfET)Lo0K>)|c)^5)|MzTgpcYA)iyEAF7a$+WCR5b8HHi>&kep z`^@$a|8$@X$f)9St~`NzlC(KZXf*~Rju)V7V{R_N-kqB9*S*TO{xzR%g*(FL3UZGz z`)Rx+3^SgUY9;-o5)Rw5DB>vOzgjOqB(y_ zBB?jx_e^1ZEQH@YyWS53KeYUulY&AXv|79Dx)E#%AEo5dyo^+g*xeY}va*kU7Y6tG zrY|rDFb^#kdK7d@Rbvq#@9EXb+X3C0`Aw2G!kdWTqa;m=?YjAYR%$;1IOlq6>|qZL zotFLpfl>`g+ryeLweQFyfYd$q&nlA(eup)@wRlH)i%cpCszySRlznxdxCTXixe`)? z2tPqKPB1i##piv5%xPo#Pa0QpKI8b7heE=Uv{_Eg?wVL-{@nLqWd=`XQI-Ng4 zn~9?pE~7+a2#c+d8cZqI~AU~h^5zNiHknJP-h+XGu$W&!Y5%8o`q2%z9^NSj--EXD%CO}E!VnUr@Kacw0t0|r<28bP zx8%x~STua*Oq5~k)O-QMh?BT7JE*{a-^hNDw`hj3i?8m4%2$Qp zgQizjnD#Ovo0OtQ@HCjhH5p5FTg-e5&p+OXsEQ8dzr$p#*9?#y4tHIYIjVihsksKJ zRw;FYJC{h3bWG}!N#rsa#qm29$Mqud3~T*_Z7KZN4IBC=Yllm!DC;_$YfS$#_*SsL zho#yNwV9bwH+cFpRr@~8!>ej&+PQ^X&lf`IaFh(=aHkJxXBC6ua>@=gDSbpId37jm zVLUrz{kcbE(ZTQf{eXIcVyb8k&zk2d#CG-Q>nx{X6@m-(MSU36c#ZTNxWXgtyKlUmj046i~+!rQsr zSJNQyPc5flrJq1>NI99t`kdLwq@I>N>)BAl!rFMS)*r0gPMoh9b#ISvH_HwpCey?6 zOhmQW25q`l4$oz9?@;#Hafe5wZFT}cackCSvZAt-E4Cl2GZSd!j6_krOe;Q6uS_Y| z@EUCFMTSLy{&KY}MFEa}(FGQe-M(57oeYnCDh16cYv`MKXH-@bWmH1?cdb}VO--aW zMHv*b&{5&q&SKQ8ZF|@ig?QYQPe%fEI8fDP5v~qPzrc-nvbIFuQ6!7{xE`1kqRvh` z!~bR-(0>^!h3xmimf2(0fIoBct>;P2hx&dO`wPp7KJWfG8;%g~ktQj6irFaWn$oEJ zx((@M?xVfY%X(UIKoy~FB@@2;pW|Av6G^^(IQExQc8+7Mk?83`5%N&=fKCxMMy8p#NdDOGvmAMB}%)NG&VG-h?%*OB*KE z+f9Ld)%BaCO(>R^*Y*=2$evh^2U>VyEtjeX+#&5fs&&BFpzD|{8Idc?=0*-Uz{ton z8PRwL&qQcQ9>GUMDq^qN-^(P7J;*6Co`PE9og%L`Ng*Malv~ypW~llNX9gLa_WeP0 zPe}Hf0h}`bszo77*9K{q*~5?K@_|_gHHmz?WkD02Op=CzT>#;iN9VB{kmBWoRsJCJ zwNp48=Oz*<>M-ZGCXtHztKl(<;&C`b7>`^8<`+Qeax4{9jjYCJ6sP0Cm%Z*bp@l3-f6hYEBbpeVlZU%kR+tL34i1X+&F~8AmL= zp_-n~#Ikc}M$-({&Ez4TS&z>y@@Ps^+@csxxtL%Jqk@cQ-p@3rMYSB9uji zU-kqi%VPd4!^9wsMyWYS(GZO59MkgelBenZI!=ImQ|f^Itm00P(epiTI@R>K@xEv@ z&i#1AE=bHys z2EIksl)|Pyd(R`l6RwZ}~Do(1)A0 zX%JWfshR=X&v8=tc>`Y4R>;%t#61Qf!~a!_7Sd)1{a!U+Vt9Ph-D+Dc@(kpjp?Eu3 zL}(s}Y%!?I?0A8|5B7D(|897s^ey|gzj?>w1%E;?i3m%0V?VNAcbxqddyBn@e0~SL zIs0Hk)*+Jh&nGaOfQ=RyZ;8;H$q8Rj+4%j>;&XFf;$^z{V{52pww;IjT3(=s=35Zd-plRJQ*;42DRvDe?K*cfTILom8*;^I0Bx zerAwhyVI!DSe)?JM`flU8l@i0Gry+34*;pMu}=nnWG7Y11NqUT(jm6Enrlj+ekM`< zg~EDlIE9dzJnth6=2HloDQ^)nXAYzG_c|#!eIxE4t_NP_k6|a0?#0)?$ASo5hmt4nHKl`TipMB2{KEFb}(V5;V}+R6Ldqu%x67W zoXS05AVaQ8b=@izm{eY_HbK^w6-XPv^kQ&XC|FrvpGa(>d?*4^=TE?t=`^$0WOIAy z`5vFA`%a^I<@_rdHh^C;ieFrRczfz#ut=}jm85obge_s5AEHWuQSfI9*R{09aZJxX zIyxHSHlj{rnmSb$C*Am^LO1B?8l(NzMb5(@q4Fua{>Ys2Jjk>77cfy-=8t9dp_3>) zC|@VN*7M=08cg()J(QEC1VmLk!)8-ZM#X6FCYcN=%N~R{SalLqE~{7k*=NnB5DdB{ zjgH-}`A~udHnLy|l2PkC`A(ML!K(=e$aJEW8a0ja9Ltg6a(Z6{=RTV_;IMRw-$?Jk zQWx2PvpqHn>64G)VIiwlfIiu6yCbylsA>1)=$>&ZW<=Z&F|pG?r;;8KM48yJ?-QHZ zXx*|RrkQhocT%6ac=Zi+eG%Svb^EO(JW)5W>6*048!3zc{)PQD&4cp>c9{!s+y3nI z9#OM-F7&3c{;m(ly^M3)9MxQD_%X$|b(%8l~cYP@L4d9;ki ztZ@shf`p&2IRLhw)ser;lb>=>vK4AdIWC8X^V!~rDc7x#ys4VC^+(adV?yLt5ZvwXbY{BsJeIT?qwMRInh^q5g=ImOJb{U9DYsJz{+u zhS;s|3F8bhX~&SyQbas3AlWiV6azxyG`|}wp#o?axIG2z;p?iEgo&$Sv2URXF&|n4 z1F^K?AqbwN=5(<8)B)bSsnRx!PBwz7c&Sv!gu^q+#y3`je)>MoH!#sH1M;)LWMxlN zj_=O}MkY(TUoLw?>$f*zW|c8d*w*FCTqHIQsdXNH>%)mNEUi;t%Xigh=V!kxNAycUYZ)i>eZP!EToTNMdK7>y z`cM6zT`EsS0z%?kWv`r1)?Zo|Uymvy%G+t+=fCssG0n{8vm;eCc1b-+(l|_mRI+#| z*;=Nf`hO{lCk6ka<={WI7nLb+#Ya#ec)nS(l{1i9D1hP^q(2#Qr}3|vgbKHG@A!58 z484}|_|sNb+~vLr=XE{94h`IISb?KS=~X%Fu+#SvdrmTY7-AQQi!?qAT0b-sLk(}75UdiZ4$Wt%0OH5qYaW9=U zRW3j0&MM0m@cdyfo|tv$n8O-+>~%4-?%edzFeY1SJ^ zjdM-VhH9^Zbk6y`0(F{QiyqjAh-piWFy|@Cnr$D7~OvtO>YwU#wY1#0Ydo}zt6zFAQ4x|*f8Pwsy{Xq`@iEfmW-d#+a<|{Q80Kezi z&eE{IVx#{RPCh@^V0W2z-z81DODl;eGBT7+8c})qx6Op$FQV2jzt{|D%8GWdvIuTK zc=!_-K-uss_i*`VT=y-aL|XoVJ_Sa*;|@jDi^z%EUWY{A4-2E}T7&#ToM=S^Z2Nma z`Mm-oH+i$=Mb8w>p0mT#&=FVMV~MG7;bJD z28#H*TE7+dHk4Y^gLOhq zQik{%Xg?479)&9!M-y>Kv_g{+i~SmFx_XIfnJlork&&JRDa=o7bRa7Q2sN;W_6QzI z;rg;HYrvb#N3Q9JnGRmngiNiKG)T@xmQ~XmM>CqJBWoIbPmbi4r8(iiaJ@t+q`D^l zDHM<;)`C;T#ubd>Db2&L#t!P~Q>O;=7#IK64TF>rdB{9(dQi6AG2ZRCt?x^1J)GgP z7_VPcT|9WCA04MIng^VzIwql;(nu@MeP2o!=Cd&H;kPhIKdG)wbkIBol+BgxCKZ3t zB!96Z_wDK&rK7wwVZ+=NV_$&4OP#GoH;5+L_fhjDwTGvN;G-Xj^1IPq{6qnuCMD5` z4&6Xo>&^E72{dUQ!+Y;}PJ*yS>abzWUn)E{UKGdMT}lQo^e@viw`QA!PSdv?4eO{b zJPll*b^YOIYWGjU&_`sCM*_q@PO&`g7-EA| zEA>uCYZ*-dbt-M>xaWyjtM$KKb`5C=`9J1-cGX2PxB4Io?Pos>{l zAH96;=ii6rw`iVzN&=Am;|-wxCz3n~q)X4J@_#gm_4R!BPSQTyY@ZPN_E7ra>F$jN zS)-rC=hT8SrJ}Ms%o+aK)VKuvi4B#N6K&`lO(AdgS4(H9iVsV&^fQerez+cmo$x>Z42Q^|y0PanwLD?S5E+Z9G%N z0Sv}BbX$`D;AiCU_PnniSrJzkPjyhval3o`Im?^+?ou$}2@FT~z*SI@ux6^P;D{)F zn$&g5(>e8#aidH;?@Z=Edu@gdnv#^1i;+7YRiS#Ez#F)9>i#^c7Mz{ys63o} z4>X*zXOKg;>x;0}q|<^Jx%F~yT$VOsys7|i;C0HiXu>&chdWzTL+a%4-tz8t1Bp4f z@Io_j`jQWc&41L62hGq@j6(-9i613CyJPODoBBS?3OfFyIvX@i$ zyjIzZLlu?5Cpi3|5`Cuqjo+3nU^Yb=Z&uyX#VPr=N->e|uQc^pv#N+HX~;64H}&i( z-ezZ#%vtPNoF-1yH%d^eQ<9hqz#LpvWgpw!9SDTLpyswau}n94g5_RY!xFTYuohf; zB8xK_zxJXh2mEeiLCDI!za&#av6c5M<`6@5MbpJW)yIl63NW zVq_*%g=LW$KWQrbA|{8cvZmP3GQWv@XSAn{4?x?z!r)k!UZ?&-hwCm>g#jKi`&^wz zP`dsSRMvBNiH*@GZ6{5Ev9e62;f)K96wb6s7_Yzr7`ommemJg?pfIR$;h{NIUv`d^ zdZ)v^tV38ehg3v##r-WG!M9gpqlVA>C4pX)tcRc#;Z~FUybVlHG>@r?R_s~Kh6^yL0}yYO%?9U(~)3{zx7y@ zM&`c&X<9DO+E}iDvQ}8JRnFRur2z2-b_?S_k?F127$0J?{iyS6g$ z`AzTYcmGnXW8XJB`88KYk91Nom$ZY7snt|0G}%AP|bbEeiuny@9fDU;+f1u?=5Y+oO#fkm@S z15$3rqMC>t>nD*{j+xh5qcLhxY7 zV4xmGCm$>nWnA|MK0n1?3^cC=kSz8}Aa%C>gwcB0Jm z_UctWv7z3=OBn1$%IXXxMFV3kKE zGzQpFnaW+=uBc+VEa9o-cbSZh@yufgJ}tDY9Nv+LXSWADXvVpe$a|Jk!W6s+LyDUP zq0PeUNAD~&2@S=_=V@_!{V9`ySp;2Fa)zavgjRqLQt9b;AiO^~fV}Ws0`bird4dl9 zsD>WaT=&gKP`Vw=#BczEY=%oNA8YL%D51^OlkS3?=En{4JynCcTM+zPsIz1N0Zc2#L%sP+F+p&N4=B;Ao>Ia68dH`8A#SdA%R0~a#E<8k8RQ>o5 zG;9Euk0$}Pa;L3!nz+&*g?i@g2D6`Qzv|Z5f|AQxy+#ecTxP%_{MJvc*#8SsBRTYn zXY90O+>tk$KO@4Rv(go>K**`P<#x4w6n7q z?d~iq0YD`V8op$|igRzB_e?9v9yb^|&l~mH+7?4{>rD|K)mm%qzuR*d5x7X7 zr}ST`KwC^YGnR2fchzl1)Z=yZ#~XLeB85sZKIIJ!Nhtdxwjp?>ZXQ*Sfq*|3pIdsTk=4=$iIEshovjUOb*jSDs7;sEbGHoio*!Zb!;w zBze{$C&jUrlhjy16rpE&ZjfU>V%ZWCgn$8#YF$7)-O;(1O#1@Pjq=(rf$y6F_$TxA*^M=R$lJiYKrqpU=1; z$#KiDjxQ$JI84S&<4=W(zhQh_^@}#am#e{IL;5=eg|P`a@wpi#19sb<(G*W4~WtIQki0xC0fyJhil!0Nf3rJXt z&u4dHGFWF15YQhQY;(?JAJH?ROv$z3L5l#tv-3k#AepJ9;gf;({%Y^H1*=TrcW7O{ zdnWQM55vpRUZcOz!7vht{po@el>bgs22%~>}eVq|U9uB`kK+eu4);~%0{ z!&Gh1kaK6}q;HTnvj0PJ&HamCx-)N>`TfVKcXWBq5jp>&2*iKNDhb32+XJ$Z56E@>v48it_|b_D6<%lX-ovl=@M|^T-zmPFQXF!X z&`m-?ZYiBs(=?p;?0?78giSOm_3~HXt6h?bhwC3<{RoqDTKE7@Ms@y~9>Y$WDkKLT zgldmK4&_yJnvxVIqz;5A6i=Y85gb3Njy+mP(;0=BI5^=0ou5u7hBg=4TjW3(Uwfdb%7r=q(y6-DRrlUcEuNVnwW=>Hm(`vD67r~Q!a=uxl{5`z#?I@ z_Y>Gp^$mf8E**Rv(M_$RFUEC-~MKrFgh(G%Wib8dF zJN|J|5dNOmVxM(5|EaMa6CN%iu-^ooEs|lN)l-J7a~mSQsOAOvDT%}{TxB;qA=?lt zNMK{1hkqx_#IjD9xRVq2oxDbU^OZPp)-qqc%zNv^dPdJX z;S3N@ouB7|B==r{$np7=pwWiY8c z$J%$;xAvWjfdeQ?RyKSFwCu$FO`oS1Y(Q7Jp@%wF=1acoD$p zB(H}op*AzT)h>SMi!s>^dI%mxI@bLvww zPLxtRY_9&ZhgTfqq^XGyY=ZAa`U(qs^6uJ_%w`1!7b z$t%-gc8MoGvC`4+RB1tuOVIHDYSQcRY|T7C;(wZSpLp6+(5XOh-;*>I9r~sE7BoG& zLS^m{5Ta_QP|oRvKRC0@4Kp_>xVK| z1`y~WM69&fve!i|_XTQT3cHtAgBZyKTSd^U9^i{5PwX5wn@gO@nH&4klBKjF;1hRD z_`Y}~sCz$Cr7MgD!Tv)>l!LZ5Ec^RDqeRA|0 zU-RFuRj&RlZV7i~`xq~s$r|e;!yBl1%&uEt(4fYs!RKhQKJs*upmDpIUO8%I)A*YD zRMHmu9h*@NUaRQUOVPdFGEU9~_#Lw!17G5+wx>EA{9c=hj&#n+}| z$WLK$9Y0U3Z7TFy)a-c%jGi|t+SzRS^>u~p1-QquX@8uGzbkN0w!HrKgE)hNei{t0 z8XOo!v6TP{!^M9P2v`*qF*HTA)9P3q3U{7j?YKA3g2lOM3kx8|6-VcF-OD7({88OJ z%jLA%tn=Ofn=X;U85=vc)Z%|q8 zYI5rzZujp5f&$Y#XwWGXt=&2P6C>Y|85j4Zg$dIuf^2lQDlgFi=%?Gnz(I$mKN*Px;M2>`JN4KZL7jc zFYR;mn?*J*02U&igLtYVL3CmH)U4Dy)&e!)Jg+Pw#hjNkNWeI0v}3x?%IL+qg3 z-pAz)_hA=NdQCok0UOiW{4kUzA*+Mtr6HXy`L^vUVg>|mN*i@mGu2*(3TAzM>Brao zgaON3?BY)=G$7FB=O(YN4iEEvJal_H0Ux`cIp?RJXki7)dr!xGv14U9Y#@72V|%{F zPc+R@bdC_$Lxy+mrm^o^j>Y1;VPN35p1nfuIYIjj@-KXF<84~rfAk-A1uCQMkAgeW z%dpSf@?J}!UcYBszQ2g6IN_c*ppCF*oy%&$2#S(Y%YpF%~hoDwPP>i*7L1-JRbvTeq*OECd=_s$A8B^qFU z2fXs*7m%tj{&evY$nJMKp&L`^PUnn*dUtwAK|Gqrtrgt+XRKR#%oOxy5p0Bbsc$T= zOZaj>N$s=uBkz|f_ta*`a~@m)3xft3B$6lGMBLw4GLH97ere=*&d@`sBN>u|yOiPB z@H=xQgZvdHcS)Db3ZeKhR$E5d2}-{VXt58G?zCpr^}KiC0tlR){BMTU09D}IO=*fH z4NC^p!NHM{`i}cZgQZH8n%+&NMEs#+) z5@)TW9C-j@4}!X_s2WB9S8i@&9>tdypXvpc^z-`h44>fg5nL3Wmcbn_SM%ZdzoW|$ zNVVw#B`3)iC2S3H4a<_fB-|ta%7`WYVJ)ptU|SiV()9uy5Uz^GBQ7_HWviazSz)lv z<_Rhf{OKLD!J+yVSx|p6?So&y3zNz;MnEKw+VhU`aR>1(h-9aeI!VKdz4g14gBE##0AgM_L1$G(P5%+&2w-3a1O3z2 ziy7Ub^3eJ^lnhkE3=>8?r9-~HFeQWu$HS`luOSg(Uu4$MMV%*9muxnhhA9#Se!T0G z_R4#tD~KqqO)IgN?&zaCYWW3Ga7Y{KqIwht1Ad47X~_MBXj1(CrIJK6Uvf8L_76uX zono!?(O2K?x;buzrK?@9s*{MOg+`N|u`RtSBNa0F7Bu5t_#&h6yx+)DMXb1s*2aNN zl9$TD0j~7zVtMs@AZYejZ^-&4i+tK~1BH1ytg}?{rlDiM6W(3$Kp2}>uLZtS+N-Pk z`a_shv$V9ukjLn1#n|#@53Ycp^&0MFd#w&3Fwo zJB-?1wh}vB3+y<|@H8);Jp3HapGO4Fny+e{3$y>#X1xm&ds{-%Ko@~FrncTy}pB$z4F2JIBmvt>S0Z(^Y zQh$<@gl;U)@OriyqwG6*eqZQ6roEIa`A}6Q_yem^IFR#&-{;S5ajZJbLUr?9n>wtk z5m|m`c%%5B{Ih%c;=du4UB3o@$8F*9?jG_RKLj@FO7nVNC^jqa3gS6zU2SN)6Q*$* z3>miAGWYDgr8uf%jk#TVIF@%!B3@AIRxSz3{^t&P88a}~0aj?)fBb)00BfP@MMk$D-yNfQUy3-1J({ySUSW9wzuT+U_$0|IagZ|;Q*R7W z0r|%5(-s?-jMn=Tic8rqLGJhWC}&XIE~(tR({yvzw^`enM`xY3nqgVln(%63lE<1d z$r*scbf4VhzmJ|ftJO1J9;|mluOOnz<&wbT$f1bpDfa#F^X><9nre06a}OIP!RxKV z+x+X;`s;gyG>wn_IucDl+oG%lYL8q}mK=sV3N&R^tl)KekNv^im)+|VKM#e|C({h> zbD(&&EMBDL8r)wlKq4&O$6{jnkh74Tk8do`d3LH(PENMmNd{crv-4FRRIbyYX{MGh zQzrly0p64!4-9xtZ$8M(g41ZrV;R!L$hIf^Gi++lVn2iLR0y43;K4Rzb0};NlngB_ zW)XC$pXoPdldhS>9+v*vOh-HOcm5OQi*A7(GyufaJ?a+82?R@_GyuWBU&jcusO*@l zKLNOk%4MGrQl{~0&MaXK)NtZ05Vgf?0S4Qf z5R_(d`9Pyx`LV6n4}TTKfDD#NJH^r}ei6)h!e28=^DwCZf%cLK07L3Ow8D&aslS&I z>XfK++^P_~Lbl$ExP6^Khjsea3M!2mOr&K*EN!wj>+=4rSrl$V%7r`kdner?g^@4s z2lj7nD!5h|?rah_!ArwJ;i7mC%0?^+xv!s5kJ!;tGXkp-%;&NaHZX`QxREwXSRGiK zEk8!1aB6gGivt9ry?ZB3QfR}NX{6K;=0gLMbf)E;KdMrm`4PHmHD?rE_N1~r@|XJH z@D{og-e{I<+x4UX znx57Di*BLx4{Ft&IBy&1b$43{e|$eT(?49c z4vytH^2W=`i@S4+WZibqvp4XVp?yj^|NP9KrhPi&Eotqtt~uQUs6OXr=u7{|>F(E?C{C;UtFk$G1D$OIy7HN_(^b@#JsLZM2Af zj_-s;Y0r_WpH=)TYZi90J1W;J^YNtsc;yQL z3|0s8iEH!u!2BOs zP3ZvY_APTZPfP$clAwLu!RL}NM$0W?#oh>ZbBbfR%U_U+hztA~CWjxCOey97`|$ z=`8s(tnBsc$yJ%})oY&b!){}0l}B{+qFgGc-JLznp$>!X^&=@wl#dx<`npvPoxYFS z-bm?;`4os5cg)e2?=VAh;GAzj`X-}RO+6)yp*NkmB{(NlM;pgl$S~9As<^%m(pY6N z5ee~_AO}UCLY(k7kUB#aNmJ6Ash=_2i&rv#h|;G;d)&Bf!rMNz&e{8C%){wW{itlU zcd(HLw2|3WjU*-LemYMjbCGF=Lu~v~_AxUR)>|SWqfO1IQDGXm20Bv|8YNrldV0nd zff9yGhysa=mer8Skn$htw z3EV$=qZ}PM9b{#GEIJ>vZvN0(TSJxsh&my(DqgRoboMjQkpYf*xTg|6K5pNsB8OaG)ju@$WeHL&eeje`9v2nxbsCXw z2tHL`&lnd{-+THvNAk3FE&OzH&)o7w&HhD2Q?|sw`g-b9lAxWfl9rxWeR)x3jX}Gb zrNc{2=aoxqou*ya}Idc0A|*TBbTP5{)diWXKH`O|0t zy$Z>LKbq=BpyTaDpep|L*Xt1t)4(TaofY`yw9?=*2ejfS4>H~sV7kWVI)$cd#t?nZ4UY{*pKI+o?Jb1XdcUhknl*+iQ zeTqE5mK_;M8%jMd@C|&W0`sg_KGk;|nzZW!;@h(UJqav6)(ly7S=j{R>9i)$#5Sam zBS+X{kv3QNT=v%*-X_m4eor_Pj5}$@gf>9FPGf-vSyH6JWuM1_L^5g zc{gkBDJ~4Q`YJuJD@JdgNfBn!&t{j{Y_F}et^jT4p2+ZJn8;XDHxp=>)5g??P%h1k zN_$J(-!#+rF*#k( zEzS{*ET1qq;dbk+4dSqFGrzbP%*QbrkFk}~=x?3sj|ZeSGvY`Of0lnC8#muAjzRyb z>X|En=p|9D$b4FrePU(w}XocU{ z^@V1uwJL7;yObPH%G$i&q zSgtqWAN=rd3Md=!8o#_A^bVFt+-{iiZ!>_gk-x*5C?#=m>WtbnFiC7!H{erzxlNsX zD&Yj(uHp)(kufv_-{yq zps(RK7PxqVICM8A;P2+)f|n9kzsthM`t`S5tr_m=0(#u~azostoxo1YBLxgcXXB_l zoe2yI8{CyAel|u7T3!-`~zX1`zqh7CE7FiNzycU+vUcgL#nnYzqJ7Pr_;`- z^QDLD{Yxaz)#UBhmX4=8SdBS3vQJ`s#IJWu|7DODBZw9QSsehf#s@O+n4Dw8W+Irs z%O+9fYOc*!gdYb_D6nCzw2CWK9CkJl$VP?=i%RYqP)1gD7;hvT$jD33S=5Yz#UCh}9*jbvM+N?fnUB}c%rWP&szj%S4pOD##7l+E z!P~r?7s%KD>nu-Nc4A`tf4ezow8{VU#q_&swuk@yOQo0(Wg~x<30ypY@eGDN^eC60 z5X*9S*)%0)|63maay!#zL(;hS=|`$PGi>xeey)A$0?1cy#aoRT<|G6|38QcKlw3~6 z7MznzZ8#*Uh^u5ZzS4a1BTkP>gMOZ*aeFWq4aXHE`lT=vZ>S)?|E!$u_D*R~>NuG7 z*)q;`Eov!|0v}6hIlOety`sEto>k2C!{&Cn!0{;`%|YbfozHaSE|gmwYSVeT8Cy&- zh2&$nLRonOR;c^lRkTe{84|B4lU|z&*zO1Und5oNH1xYqnOMOX0f^}(-q#ilBeZ%X z;C?;}iY=^|5@}`TYdTQaZJo75+W6l+2U?a|04$`v3=mW>khB&9=fhEKW0kr80G21F zopgXX9S&3-E4c4zP9wnqwI$iZ>Rjqw+H_RpzaT~Ifl^o(^qOJQxy}=v7>cB{wYr=F zoB=Fy6w7SB>guXyH*V3~Ldm}%#BjYt7MFBMMzpM-NMl%3-Y}SoYP^UwuOYthAjXVd z^@^_(#lY|UEgQJ|lB{#)*6w_wxU9Lra8GGWFk0x3)qMyyfH!z}Bfu4PPlrR4X1Dr_k zJr~(nu!iw>qdQ57?#p>=idN!f7wW629X!rR7nI-}N8|2htN>{xm7dp!Vs%d#O!;!0 zmc|NN=bcw3m0}p*|TQ!2A%&{~!_ktQpa5sp_KCDe zGwoPn$KW93?c3P%0Sxia=vKky4FUXhep6+q-r0ltYkH=L3GDJ~MGKywA3AOqMWWv< ztdBEazt|Yyio0#wjO+7$#k%)MH3;RDd?H88+F4)qBlGL;zKvx?J}W`5qn`_K=u^&t zpKQDq@bdZ&^@W3;XJRVDIypP~6Mv4r-Kt&rE!>;L{yfb*U3h&hcG8?wzT&&Sulzoe z!qawa+a8|1BM>&*e0je=h@S?BIsOb#7{YM-*G_&Q`T3eW+bUt#^2#^Dc3qgh5H{cU5I(JTmC7J~-Q`?bF^<2^ho`Y86*IP zh+?=hvAjcLf0vbKN=+I;L;jfAY`GxR(y_PuJ{}+ZAw5?|RUhsi5io3P^!9WPeR^8= z$m$;)wDSh?Oo_ZbK$F_-5WiVEg0a@!eUqP_d@@0*)*^o%1-=-xPpl8QuJ3>HAp8Dm zeS7@+JFFCV^4oWbx9(eeWO1{{ad?^}a-UuiDLPTecjx+(piTg;*f+R_2$00g?bH+38p(xFFYBW$xktgJvF4>Die8 zIJgF*?&5_xyLx@hn(?G~v->un!I%w9Oj&M5zGY`1yu1itX(>Y5JF@XGm4WE8fE`)^ zPxxy_S=9&^_VwJ z&BFSLS!YX{-E5w)xstZ$q>abxFs7pMa1M`vly8epWv*ptl^pnAF?F)|SOs4IL z>s4oFv4tGFjktSX%r0GwBDx;63zw$t?Dc8uotd<;D9k1L$YS!YCNJ9>>tQG@E4LSR zM{scuf0O!=n@=B^F+=h|s5noH1C(H0;UkD=tB)q_JW$DZn~6B+-0-5^DoYn%{YhDL zOb6XM<=7AZlYG6Oh7#`!XYxi?#7T2HiJk>ix^!*ME+f+Y@kenxa2PRtJn^}N0!SCb z4$THUzK!ttTx{Hy7k2QT?65a~vf6(3+8Uf*C`9XthSgCvz#Bl;oc+Te z=L~Wr3&1Dw-clN~jZ4h-qM^9wg)Gaji~=YDOaUlq37B1CwdtMv5GCwSA?*vx!{vZ~ zhxv8*D(y?wAwGz-GiH!JU>TzAaxNhcrE=oo87bjweR-v>!{;n)|M+qswH~Pa)ww>j zhLXB4#tPpFQ1b0IvG#HCb?C>JTMr+jKO3N=DC*_l2LQ=8r3y+7Jk+uJ4EMVGb}4 zpfo?{JjF3h+ zy5Ggo)yG5$Q7$?seBSKbtaDP)-QDdN16QwJg)MZ|ZZzL;9++<3!aEp(==o@miK(=4 z(?-~0Yw;Gi3N}F<{i;}c@_H07888&1{tEmIDuKS_r>AMsj)1cwsyN6L4^tZv1mkEAXd>)~+S- zTkBx^ju$cZ0(1cPaU{q)wXAOjlzfN7nE+$i07{c{m?q8iTTMA2TwS%jzAqE6iFk8s zgdK*d+Bnur!~Gf7k9W1^8<@bg3}AMeZN0tOHgJ0e<_{pvOMi&S@#2~s zTU3*6b#+-Vzp|LX#S!<9qCJ&iRke9|H;GO0@zOYIw_3UmE18s>&S9%PBOtI@{yc(T;HUwHd;!wf0a?`X{Y_Y{o{X@v;eE zP*YHB4HfyeWy7p(-a3bQl(fMLiRZjk01jm5Ci0g)6OI+}0_=1#;dwla*bocFEqH#A z75FBYZ3r9$on)z)&(r}^~bG$VBQWL zjM@hu&e`=|n1hIDiw&0vxSNYs*C?J-4G^z1(rQK7t@hL1>+BUi#;jUh0D~~Y@-YL~ z(^R4m7+namgM1@PRj!jL=nKp~gJXdA-#=i-jvdAGYP(HNP1?`i_?f-=#+!)jPx4-v zu%pM0*`bd=0>I9-=XO4a(|~8~>1TGJt+t+fQHBIDEnAyg`QT9En3aV^n1M$GC`piA z8eYT+jlekl&@BL^UizH<4p5r4jzN_(6^{QK3ukOYebn~u$+JB#=UY)l%nGZ3qMRtV z7)k(12~qB3{rI|)PE;YXVqtm690>Oj;cZ>6-wS}!LuTX?blP3@fHtK%5C)WTa&j1p zAj*9|4JF#%qXLwYbx3=esl2?x>T2s9prnax>y1(S-9O!c_TFk;Xv!%3>eVf1BW;C^k%tJa*|8HH_V@q& zjD2+S7G@oM`N}D=Eo&PY$Tr&U=d;lF0Z_sMOD1pXUYsB|&%d+y&Qa@NlA^&pH8gPw zYX-XEfvE@rI@@0%ASnQpWOAT;=xTlO*CajorFFQU9U6$+g)@jApC022@FhF))g?>M z=Bp~&IM41_Y(Lq%j5HKj{h~Q5Dg|&uV@jTuGSiDmLrL(3o`IWtfD#rw$UQCfk9&6N zPDTD97L}PZf72w6?UB(DG_4L&CI?}MUBblWk}Y1c*tQ_b{oHfU*^4i}=s=BNBC5$r zB4Uan1B^!rC?)Tmk`BM$uTu{HAU~B?$@=~^Pjqoq-uQgdxs*-#T5U`FMl3PqUw?mp zU!icX4r%u^C7s%p+}VB!(%|tley#wNodecJADiwf6Pe_5L2}CQK!~ zlNBkhnN|;@Xa-<%20*C|K&h>{*=lOaVKFozoS#b_pF#8) zhE9K;-Rg?iv9J1Q-?!{)TZx_Q!;~_TZHv(8TC*gArjnsKly0k*N9YS+A;IEH&kow2 zi?-UZw2Ra*Tov?f*!@T(GIgaCE8PKfp`+>v6#PO-@b9|j9J+?6rM{OLj~cn_>a$DhfL#nunQFw%tabX=H5HdT*v%-^~aNvDL4X-XCdqzUjF-B!&|G$AZb*oeJ~k2b97kq-}MQ zDII0F@hj>-RHIFOuAc4pxe7=n^veREPxWUrjZ> z=F25<(?D4sjqbe3eCMbExCZn(mY9epQV?b+XxBW~>na}@dUKT~=wf~79$I8VB!S#u z;jY|QQ#QBZT(sY~hS>4Nar@%4i}u;!3pO6hu~ELP?%KQv$gUH`~%6)&S%_{Fye(8wpO5f+p!(Y0| z#qqC>JHcoT6l!a0oj|m-HMVZq>P)S&0m%H~2bhlvPA%C|y11q;y*q zCOAtmeJUu*1TY0yp2JJnB;F8*bL_&!VF1fvJA1CkPF^mw5lnk#U^3Pg#%<+NgM}5b zts7uNt;w=t=Fvq=Dg|&*O^LhyC}>feR6^9Q{XRDDSyapYxyl)x%>-MQ`Z91}M!@aR z+L5m#qG_vrqE4;jYt&c(KJd=qn)P#DgmxX@d!6^%k1{8G;6;(YOU=Ok>(##=S zQ9eOBs%-D8l~#?8SXCYMF>{Wx)_YhI^N9Y+BdRZ;aMmW$m0Uf{Imwe3Hk1RY@3-)8 zZTt8AcM;_dzqiBN3pxMe&jFQvxctRXQV^gdhLXHKes6%1tC&CjJo+{<{BZ$Fi41lH z9E=`aTJ$@-{1A=SKhv+n&)2r%5RS(Jpp=?JkN@vv*=wxC2xb9Ldi=}uo)q}OS;_%d z_H;X%u6RI6nmhx9saf2SNtL)WRR^e7X)0&|7XEX89S8e_< zzSNiBU{a~5%2Sj(kYM1rV;pyrlSDTeoD)uv0Hq+I!6~BIYm(_FqdKOU7Nhm#qAP;4 z)z4uiV7=W@Yq>FD2R}G(2R^!BgX0<2Gnr|-G1q&2?<&|OC3r$gw@L=gF+4K~){*&# z+-fV@K@506awB+H%Foop!AXgZeZeY$OQ>R>zplH zwm5B#=bn9zvZ-)dO1{ne0p|AwDEW7XUni53niLtVC@uYAPOU5 zF4JZKlqSdX(Cosrt8doMoQT-zlX!XTo@oFX@BmfxHE;Z3q>k&IE+$K46*P?dp+i-Be>B~4ki1tgP(|yE_(Uz9Lv@R2% zb)I(7X*aHR+PfcA*>8?iAuJ@%WaOVtO_ZYmrF`Nu6um_m_1YQ)&DShrV!S(MKY4Wu z?^gk!Br`NKnf@{{W-!hliy?v?ol3_H2>@vn@$25Gb+ymq{SPz5?g50c$JkeHT_ff6 z5jY^APs#;^$je4!1{1Qvf;7y8@hVqaV2z7%Z7ocob+Ej$a)W$RG-DbY5?l{QoL#%6 zzY_CE!7l=mTu}AU*v%i%+GP!Kou$_$jE>F&bk5slJi&c=6j15Hq_uaCTF31%01()h zfB@yW=&R&aSVP$y-rxYhmS@@8btRN(KHe_VVJr#E#8{IL4Uz0Q8~_T4060*+WbI-= zJQVjJ0xn{SQo0klyW)9g_jljoagXAj_XU(x3Ni(Qog`0tG1xiM63f8+Phkj9cMwmE zpB+Kh?vpEa>1u{`j4b8DL}id3wc{A>(c&XkoLg)adBwIDeY4kI&9;>?7X^2M%mxrc zo&qpufG$N4Pgl-4oG_8F{=Po?m1bx9_Tfh#*(m_*+UgpBq+0a4R`8x(4)A*cM-89i zL|_m{4F$G#{W|-rU;o;E^3zuxpp*?m={o(BoC{P`R@t%@D-ex`EeD8qcQLrH+rd+$%%|NO(Wbqx_2KyR^`Dl!JG5n=9q&sW*LT~)Sd`8)v=OzMRPl+xw{ zhElR-rWTT`qlseo$HM!*dyV*4ab@`37T#9k_1nMizYCzGd-(UFUu)mO^5f3|m3_GU zd%AlV=k~gYXW>XfrtM|utjU>6>f$xEzB5BfH+;g{@Q)TyQeOMUnc4yP{W|CSTKqHp zI`uhJ^sIwWv{UT1AeEWB!&``(FK#Y$G?1C3jE+KB{{C_-C&;slzogz zu{4wh1_l6>n4l6WDoS8hR5EGJMmr>iu8|;lYH`=1b zn7ow=P-?dS`~Usi4t;f#FCZmWTTy9$@$+>E+^)6i%7|50$&Ec=nUA6`Z$D&5)#BerenV%zuJa(m|KGTXF0!|EG(UgB{YAP4_~)aZ7pi%z{e zcByCZ`ypSvDmUM5)n>&kQ<)9+529^#kZ{16Uv>9%quH~<-g@gT+x^0B1jUyD4lZ(S zTkTt5lqM?zK}IlLls1QgypYw`*W(Jl%H3P%roIdA6Z^Z~6*_+3YrZiP?sw-$wC^GF z_Zy$)(~xpMN(JC2?sQJXSQ5y0jd1be1?R%M9c?R>(;PN46=fAJkDuT5Jl+GJgH2YA zX=x4GVwk9*l$`;4KyH0iFP%;f$iY0!k@+-)qtzA!C^>VvpzWx3Ibaq~O3^t$(9Squ z1`L#w-FE&|m$i0|TRVtSAD-i-eH2ZT8CH$eqn+@=j#=CJ+$@vVEXqF1YU^Xx*fa|} z6#xXVML^2z6b!}bT$mZsMU1wyoP? zE74X;OJUv+s8)0{$~2j$A%ZO+2*$$K0ZIas0&jQ$fU2?y044Pa+>0P!IuJDv&XKuT zES3czZm=r)7(CyyfBIi#_MZ=y0VpZIC_qIcQI1)(p?sKMQ}KSAi4WMeCFQneWjW@# zG26R$8t_Db60wa-ARVnV;HL<}Z}O6cLYzyJK))Cu17tMB{dsQJG)&(i>$pk2x0IrD zQ(}`dGd4LpgLxq)1OR}OF+ixfNkjMAR-#q30@JrGThndhcEB2R+e*q1bIyt2QBwUS zMne$+45XiJvA*<7nZ@}<-D3bYvA(mL!zmS27qClRf6Mil9rUA?o@QC_6!2bmK=o zN6%MKy;Zo+qQhG5ig&Q<+y2!pTs8Z)7p9z_d=Dk}2k#FTMHgRc9!wtP6t#hTpngC= znx|}K_Wi+UH|)fzOuKM>iM5VX_c)IiDS?v!Y#i$r5bDKc^R^H0a>K?9SW3B8Q3ZPl z>ufBoDR;^rQ0cCmBLbr%qX3n?un{lYp+kopQ%R<93hUNxuyyM;T1Q7a<$9WrguTxD zZ?kb^YBBXH zEzPrrTyhE)*^7b77t1ht1M?C!q-oWiwe)gFg*}>^)H^g2J)_73?|Fe&}96R zfKuXRNk_&1)X56_Lfxv&;@sl)X(9@%fr+H{YH}`*Hq)>g1_oyA2|6u z-IgQNyJJ0 z;U4F4oqZqdE_w%uLKG4JL9lnRh$@zC6{}dbWy?;KIF8f&Uf;j-y>G6#C2yQB)pCiO zY!$1L6gx$+SAgifckJ%>yXV;f79c2*6e)=c9$@zA(`TNUd(OGfC{ihR8c_1z4Zru% zzo~T3K75A{7R%4u3Bnh0l7FgAZZ%I*3$!D-UMw=nYN9N^UA=nMPMtbs$BrFy=jv;< zI#^Lz;ee&BTemrNmFnthXJsvqL0$&xi30Z&j3k9(DUwjaCF1O)nA~(eG2KKmB*cU* zHba@hnKKF~a0Lr+jTeUO!sRYIf3@ANUNgv;3$14gNgFtG@{ok6Th?in%R8+aP^$_u z>V|blGi=I4^(_@ZH~>!K05tN~NyUHzceTafREpZMlRdWoScjdyGGSLbLx3b1R-Rj6 zHKlp>z|K_aoGhHtUU2E6FmoV~fFD305)vcM0a14%Q44kglR`*<1fWuIGfao3R_7W5 zy8uiI04hBZWAZvpT*m>3I{}nB+q><>Ulsr;p?Wrfl#x{4k}D#9(EDMDs|U5TUfWh% zY#RZT_U?(>LysV(SuVb`83!n(SRT&;C^;}zv5+(eC>v=JxHB~ow(()|AK-3y7;^NX zY3pf8v!3=eKs|`hTakpqTHGKKLOml$F^vxaWD!O>96H&lR$2^*k090Rnvm7usw#6J z^Uk+IRL!7Zg7X59Aq{W|P)U8Bb4oOu>)yCTg!G@-g2{wGo3|&tn>T;2thnh3cxEx7+7r!K9$>bJSH`zyDwPkLEEQ4qQ0 z_mdvrzW9NZJ5XP6 z0icuupd=|fwM(@R0pN=OO37K9eC)G1sa%t9FCAZ>1Aa{4_sLJ_+D8GDlE350$H`$V z9e+A=KxLm?{vSJ_q-^;Nwc{l~=?3-OcRYUYJBs9Ue@$L20ZKQ>$b0y*FKfQ`?t>!< zC8=vjDj^Tu+9eL9d$@2DQFr6kdC8D0k9zpIUOt6Y{TWFpNz#Rh@C>{_as~P6NK;^; z1{1*-&OuoH-VmmUS@}HG!fJb;jZXL5Up~9tzWucwmH~#4}lv zP(sq>PoH0B-}=@%E6NX9Aui0SW*jmKfj}wnili`L^--D!D7knG7}5xHZj>1SN~p{P zvr-1O_~QYiMc;83ofqyMk}gh~Sc)cu`cwE3$CWZX1oz6pHYBauNlVE7csgvw8M(Hh zw9xkM&a^LnIc%G@M^IadSZ1mQ%5yPGgfegEVoi8H_OmyyyD)nvIG8J*xf}kS#66`& ze@eRsjQbB9w0-*z+JXK1aPJUi+}1R#L9J@1J^j?v&V;?dBsuXZrDvos0ZMbZdviw% z%0Mrv9MorOFUc?Q6DW^oaQ*%Lu3a5FcHCZh#dv#UVcFy=| zahL{?G_n_@CrthF+tfG|;<#fcdu`vl?RNP1gdGEXZSEIG3dl!VmOY9J&;2{YcHh=? zyKh@MlVre<4CPNyUtQCM14?Gt1D~~+2g z$pR*?lQU@m-jWu=A{~Iz&;C2#e*AJiMCL&|4_c#7j{*f?4fj|I0=@RZLCbOt*8sGU0n#kPy*;Ebz%WGVaHvR zo=*6HN??Mn-76|VBzy)cZJJ1YFeuX79fyb=bxopBff}0tt9Ra-v3K5?K_aCei4^KC zYQG(mnE)aoB)MW%ggRbTHK0;$nr#AD+O!&LbpT5x081HJ^rRWYOI%J!p{lI41%0ek zwGPo|Q5>e2Z7J%MAang<-Im$x9Yj7LB=B#>d*|Nm}+#^FH4p6#$^|Dj9 zec?}DuxGFYw;XP)a=`4%2@a)YsJ7Q4!J3E4TbQ~Y7oa57K9!iHqyVGJ)?l3(8G~L;21ZAbyg1T<>$ErCO}Ag4L_L7KSe2V@yIDnk;>&5QB&Pzl zMJx{@U6+R%u({RsU{>OOeS8%)#qXnTi+JMOa1gekzJQt)?zPumwcq{jxAf87ZZ%qx zN#A__oA%h_k0JSz;eezt69uh+-wg>RB~@`+_zk%;8F8B#nN%LP>BFM0`7#Kmd#VmW zKmwDdr(vU+Lh=KNg7)@y%I1QdJ$Dvz>-QI*4Nt)U{GyUs3WebTV?h2^;W;C z4jz}E(k|qs6u#9Nyh?}R3DkN2e)h#o}5u8w|#v>*4+nb^i_Cs zPG>n%=9Uf?515elW5#U^^5}~EBC9~6t)V{C)?6j(~jeD(&JQLHQ|I|2+%?kS=AeGH2Ma$tHAlNm9)Sq?K%P&mJ|fPx+AHl86>I% zD0Mgqr7rvFFAD7+UM_^aJdpsyx6g-Q1=+q8(%Cf=?0R3#Mtbk*wCJ)ufOh6@KffF!a zfD}tQJWT17O-fklm(!+ns-}orDgfGam7I4@$K0@iff(_aK|L^T%TY(p#h>PDal6(e z6Y-|We~kl_BGhSGA?-+^ zDHL%8qVkS9yxf2PCSw2ivrN0%L*c3oA*GiV>a>-)BlhH;N_+gls(FA?3_vL$YG0C2 zBD3z==D$0BpB#{`-4386KNfz+uluGa2efqjsmlQ^bZPVD|FHu~LHGWt%a_}Y&}SA< z@*T(RHgNyG-!IJIh5mX8r8nMqV+l}Nm|6GO`E_NkaoiH1bdQzdO-A>+0eUbnW#r4G zC+O`(rYZ>~_pw38I*_uE)uBREFiNerE6q+FpF!1az}`K6)sA1d23N!Y5*CBAfYKBz z^DU5)9y)f}{_w_rJB6jG?3{8e1y$Jp^H&Y_y}xN-f;GXaJyJme8{mcr2BaF4G9gNU zL)Q)Db=}?b>D4TRLA)FT`C#(o@AO{A_xv#?t08H>$ao@v0|LJG4Z0DXd#|2f4`d(ZgY^|`nfJ)_? zOx7E5O^#Syp>YOlUDjitdsJB41|mF_kI2Be9N+wKi(?7{oi z*tT7nwsm(1P9h{(;D}0<+N+J=m~bXkhNdySJ{1LQA}KohFi@G47QY)NAEzRvn zi44K96}GdDkb6@H2BNR=pl^!-C)QS0iTv1!cMl>rVF0_sYdtwl0zIiOMwe0o{gQkfJuC~21fQhigZ002M$NklNPMaOQ7NXbfytb=Rb?6W#hq*Ifjt$r?fz6-vq|cpszc(=ijs%4 zH!@9aPcV-RK}=0dx&Hp@m8n9^2B4ZUV0GCO_SD`odje8!FQJs0kWg9zloDBW7k9JYqQsakIVj!pfWi_fcXG~r zwvScr-UX7*^hqBVhmyKSZGIn|-SfYnX+Y_^0sAc!*9Ub#@@ApmOMucXWbUW&HC*mQFskIiQJ#>*W(48%0z=$Oi#ReLVn5C#SI{Ghq9VUWH?$ z*}~Bg_&A5{g)eWl7oOW{L*waou{mmoPc+$^`;XZr)J^hp%B-%s-2V1EHTKtkRpY=U zfl7g@n*b#Zsx?vd(grt>P!c$#XuH`52eW{ZF6e#j-A(q|nAj}_DDkSi(T{+uIQ|3@ z5P|{%zb08(z6|fongqvKSy($Ow+29rx>X@tSrbBS1_S7lFp|m@xWqK?Oiacg?2p;C zOJ?WJ4B87!?Ibr4UT76RdID||++9YfX*bNcXb zh7FBoKy+?4HjQOCxQR;h)2tvbVi`y;<>jJMRFz^ixDqVHmE!Ut^3KhTAOMT-j*T%5$h4r#w7^J4h`EHC^T|p`wT$F8ffz_`pvKq*xE9(FcDB)MBEYqOqC+Qr#1`0d(Ip&kH`E3(!}NV+9SC>6kHFRtBIpeb5kSzuc> z<=Z1)%(b2OXIoY#pd2p5cPa$P<3o&57v-j=P^W}Tsk5Wge*e3doa=@!sk^(A*ih2+ z6EjFj4v!35K|z7tfB*fqd-wgedFM{Z-|s^mw%K~xT98Zvs4TC5pcg=i>JbKfcHcF^ z5CEBigi=p;H~w}n3MhrbgI1R}fy!G6QdXt5dac?H@Fg5dvl2?O@`g&NvPxzAft$ar z1TSqjl>`2}DosHl;oc;H@{B~W9j(QmjfzyUmtw=F9Av)t(;O~GwR|$d)s1- zdbaW;I&6RLQ=j~fzvuV<8NW|{R@XjNfD$F@1_7VRlJzCZI%7~6x8k33Vzr4wwe{Pd?52e|ASPeS* zek+s8Ggy`CXA)Fu_0?tem)~A)-}%mRR$Eyymsw&akWNC$acXE{r^#V3id;-WNkpgG z+^+`uvw)J%7)?S2EcuP$G=t&98}6c$7?{^zFaed?ob%7mTE%@M>rhju^Gw?x--y~P z??ml#3#uu-t+pBNkgq(m!anyOsJ#8oS^qhQYSr}AwBy#;fsOdbpLpD!(>q7MAKeEG7;9X@>6xehEc z4GbW~fS)rrl!tnaXIju3!{I^IOMk z2u~3{7RHcF=^LCx-D%qPy%w{5Z^o?;0_pA%IG-j*taob2aed2Qe$wmM3GpM>;-nyklK*i8yJU612kn!rUfCXeFID= zk2R!ITcgd*0ZM{Fln(-wGEg%NTOU#ta{u;Ux%U0v=0H|1ltm!6%Ov)^BMBuWrBcG3 zR+`pfPd!{`UwQ37-L^Icf!E2J+jwC(}OyN9PSelQAnGmP{W zv;(9$6|t!Gm2qoWX|}Se6r$`>tgfZvP?JNFOcvrK9Yi25e5n@39PlQqdI>;@7!LLi zBDL0rde*cfZ7xC*ZVC`|T2hz9*>#PQxWTotSn&RdX$b$P?0r-l&oquxU%CJ*x+n|! zbX5OV<}J6{Wq@(@`L+R`xz$K3RWAovB2F1uVap^=${l6DEa%NgdQRc!Pua(xD^`xR zpWSqi2lQSdd*^Q9g@4rN{p`(KI0$(8=3a2^$HjK;+6|A0nEt#9+zeo{7HFjYCO)n9 z)=B&0Ywh;d+kJN8a)F)d0+~g^$N@@}OM#7AW@sEC6o2p&iQdV+3@vy9++D&P4zv)Nmt_ zL8~p8urC5AJ@UXZTe~)54QphjFd;oi9Z!iN=|tUgW#tP@kxSZC#%@dOTzRU(ENwT; z0iS2S?)!c63%ce3h1-=-^8N+imY{$Z3(G&ZwEuMEfG;Co{+|S(G#dxszR4PY?bDG< zHy?}77NC^e5ii!!a$g^|!-x9XUFM8?eJi8zJ_Ea63MR z-Ij6t#+NrbK^U}0f8vKKIbDzkkj}k<3I%eCB>J54C9EBl?B$b1oi@N7r z*pgUEOw?&xQjP2E>~v1$b^6R{XAQ2gsnMyis9Z#xE_Fqf+nP1&aBJa5DaS2m@|WYd z3&W_6O3=mu7XmM+)5_wYJ`%7{fy5Sf^%5x{n$Fn73_x+zP9KTe>0^*H!-aIUWyD%~ zr>q5VX@ZGxerh(>$0D|}e9EdTqqeddlkwF^=dB7`?Wzc*yFs|pUQI)aW^icCPQBk| zC*SM0Lq`hiom2VNKR$|T&Zw;_g2WlFo%QRoQ02?CItZQ1%K<=8;fkQH6-f{{tM5@Z zF;8X-Cb#0?5uhY_i4cjEs+8N@btH%&1{PSO=LJZKLuqyV~e^<7( zbs|j$=-1gZW<3KV){jKf;3OPX5GR-AM64t))r#S{E5ubHF}boj1n*Y5l~uvLR6_i7 z46uM44afN>N6sLG@ty6hgpYsaRaUsHBmgP^l_YsZRfZo201HrX5J8%2 zO)+b_I%AhEW3le)IC1N+X3W-@@-Q8##HbxV-fu^b4%yr9hV2ih z$XL}wIr2AGeFmzD<9t(Bc zB^8@GOC~GoSLyE@6A4lrXbPY@Hfb;aanjy<|FWGpf5wV(GHlnj4Yq50rQN?HVp}!@ zDkzy)Hwq^18enU3pux6$#&1Q}jgWcfPHo;RMLn^pEPcC_wZ68tHmo(hV=un=qO&X( zVb))YwApw5@;gY2eFq7KEYxGNk(OYRIxvWujZ|%hnLtFGDSJKZ_<)!kE&LYvFq8L- zJ>%o!>Y1`g`QYQ8{PM?foRn90GC1Fcd=Up_O$e^&gFto7*9G_OR@>wIt#7K-;AGZY z?)K8;jkvXI*E&}Q&?|1Gj0_0$l_0>8m?Q0; zaZM{oqv~Ta@G2f4_?!S;rU4BmQCI72LoKH@g*x72Cr-kXb1iI*?HSfLj!F{~{umNG zsi?GMrB7OAX@zrpQC-{n03_Q;pA@2MC2M1nY#EyIIO>&*~-L5E%L z>Ohq)V%5~Q`W1P$eq(`c+LCQswnmuX!o$M^79plYT#-~#{NCJ^bu58@RSwLyb^3sQ`GIz*c z_*%LB>9@))e_5)&g_4tJlPv@U#VWKM|HskK5}R z9^gmnwn~%wKLKbH<08lg005ks8V_4jV-y1Q8N1p9*?HTvwRHn3^>^C9&;aF^?Hol( zB;vNB7&W-%VOvp?4FP(ARo7(Ecc<9$GO0cRjNwx01JX#tOajaq9K?!SXDiYy(^zV& zw!)&)>j0$);F(C&qf;pW7jZ0@AvFcJQfK>=oxj{}=Pz{-&jQN1&<2pc8lE155o;Jr zW&^gokUp}m#x|_3w1&+gTfK=zilUGe6Ib=&QpbuB7iFES{Y_6(eyBXA15Tz%t&%*K z(|uPXf~*a)Ojq^KHQm3n8=>6Rs^^9BEP+$EDJZ%GfC7*@BeP`Ag$S zjt<$+UK_F@RI6Aju6gky?4gUoS z>Rbi@I$GNyp>K1RBwv2{WjL_fZ3s|FylvuV6VRQT1MrB{}K&G%^b)_4f2Rp!=7g@9#FVlK*@j0 z4Wq0Uc2kd*~ObGxCAKO0QNu$ zziTCU3-O)nVl*;$o66tU0S_pNi=l%RXGt)4K&i5_4D#4Cd;L``IUO9t^mwyfZtJk3 z$P}y5Q}(r|8tkiIZLrf9BKEu2r|kGeR;{})F+m!!2Baz0H$c?+c#%Evr6LBbQB)t0 zF!1AWP0WylNCuP?!FlQjitjuLA1>SxKnZ`{q(OUy3Yet5>p$Hkd;N_`d;QHxq_QsB zk&~ww$TKNgQES^aRM?{r=iA<0IhMzSI*9pycbAiz4y9nQzmAHF>N~ux;83;den8(qK9TBp6d5AXc7g!tB6V01bgkLA^-;N}5vZzWOkv zhvp=du(ZX@duk??{zsEx)a{7RkN@|S{lh;_*-5~V8v#ninL}31r1%A-DPMSDx#a?e zXuhvtRJ0CI!oLXq&BaAA44N|Ch9Z>cQ}q^4x$@>G(SNzR!l|yiV*wBR1;CQt54QLW zzT!F{@4nU&#q>K|M(|X%ca8zpb+hm@Xk9&-);W-AL+}{&p?X}D7PnGV%F0SIkp{}Q z3Z#@)R7J56XVj5Q)Tc60qlCa4)w2-NU@<_lk>LUB?QD0zad}xKrxMh_j@rMu);SggV}});?UnT|S?0mo5|_Q6+w*LF*aov+?O3tYgNkp#&bi zN>qf`rZ`uPw9<+dxfpCf`ibvBD)CN58c9Q00i4r-`RRa3=^02yAx#w#TFEAva=3A zsn*tSiP*+1$$*mT&ytllGV88w{yXIN$pPt_zE5%=6;Mi^6DEhTbo}Yd0hPP255D}D z0Hu#sPM;W{#oI@fL{`#;N z>jeBgzh4-hf5-2a0HuXFbnlo4WY%dEL6)!ujw38h2BcIINIU1{%yZzOKZm_R=BM3p`DY?Zxt zF2#QJ$7wrpQG7#93`!?#!>TIVyrIk7Nu!8I*aWR%P-(^RgDk_^5k%pUZ-4t+$EkGb@+G7j`t6~I97-EzUZvh3@ZxqPloV6{y;vA)azDs}>k_{3$-8iV2lMtuv2*GEu(T!OG28DZ zJX2Z8jRNQmQ4Y=5ngMvuL*{$VsV@px(xgyU<5VtXOwt?HG}!v}sKKqR=eWj7%S*^# z%{W!}H2YSLd$aLA19T6SC+euKMB%VONCgQsW3t$51Gt%~EQ?JSBH;`B!DXgHJ_diB%j*N-aXuE z2M)E`rKU7H*OP}TRgTp%fnBvc9VsQanYO?Ogp|^Hc$Gq_02yhtBpRwfZ8{31C8S=K z4B|*a$)`uD6riL@yrd`dDAW1fneyhQ&tY#&Y zMy))v*H#qt0=8D$^MAU6v>>6B2u9e2Q&D4lC4ee;Inhrf&h(7Sa~HQD|8*shV^Wwp z(?+>?=@+g!&@Ulb7To8Z7$(_?{{+bz9Tn#lwBrb2^SI{FimsO-oW6v4Dk;$=49K`3KOOw>erb`j$E?t_o3zsIWwQJBi zhx%+}YS_{N3A5qKsw$3KMM)g~td&Tm)mUY1s^h3C1T4uxGDcR+#>PkBz8dEnA*m`P z!a_ODNmWyILV2imro480I_e-R1*FehYZzmgXgH-4xa3={%I`cg-S^Xh2q-pnB~M8ZFxp73l{Zu|L%I*ygk*n zz)2+)Q*lq}FNOS4JEyDX8b=(&=tJIm<86EMjkoMHl8zV7pT(+Ruj@C|zbIeyP5+DU zeAoWsFTO)NnE*HfC+c(Y=d0g-jg_~5{#mBI z*QSLa@?6F_qD@wj-iOK?fYRPt+q5lWn{nxx)FGs{+=9^(pmY8n6`V_R6 z6t_UpbhXia>x+ttkr*s;>eIP-xlU?UTz|=%Z#xV3$zz43DG&>H!xjd4aXNu{fD*GI{rSyz z2L4=o`Io$RCkuZ3d)hAnN((aQGjQtbfU3$8p!69i(8ZGAI-0o~iDpmx=UU=KU5_RU zomfN?sHjP)R#uCO@~xz_2tX-fZwgR4Jc^n_k2SGEUWV14Ww9N9|{? zjN1t;0kscy!lx0lZEGuS`<62M{DW!sg$Gd=Nt?ECIs?|kva%+?p|~s$1*_0=v7CQ2 zTTk6(%_?pKP$I3&ljb(ndF2h8q>=(q$#vNdP+}fx$4*Sy35aM99B8t)4_vUTUHwia zWKDU#{rPjO9zVItnN%;snh|Td7IlD;l%s*22THreO^dV^26I07-m3a$Z8Is;cUi0VPE|`FoL^5MO@&e)7G~ z%JICkC6{e-0)tQP?6+69+zVmmc70wifCHCP_lc zZw`3oM6qyD(HpLlQAguOXY7;1OO%6NnB7!9ns`Iho!C<1@H9zc#ce(o#1es)jtM3q-aBor{aDaDwTjuQPc^eQ@KdRC;`OEJ56K8lLon6-2$PN+#i+C4PUZ}~_eVeHLT)z;bS)wNa+fVgTs zKvPwkl@?{AeoK68kT8&vMCC1lzY)tJJ~_leGBe6;N{)OVncrDsiZC3Ub)j zcfFyqnU~?g#Si@@-@V5-c=mb;rQo|HkT7rnOeVE2)lErYrJ%~10S8q&>Y&%`%{QB@ zsXx;OX8`izn0W(;HH=nRv<+UR0ooU;f-K5B`e=rI@$n4HD@Kx8ed9&W{U_i26L<~3g^^Wq75=}H67jOF zpzlzfqdmn0C;`qU0Hp}z@dJQKl4SkeOA-6mpJ&>^R=(Nr4H|XGrkkuJ(raIogwg|b zwgq+YZ97wuMxLbJ&^GA@mL!y16}W3Z{u}G}3j|`dNM4^q<_o=Z^gcFL=g1tMvNuM$!jR?|A33gpZtmn_CLN-PeFePB-p;|rB>CmuPyG0}_`NRc+2nJ7O?v@K(#KxnP*QH(``f&7RyE{f^I;N7;{EXT>fXufH~JhX9l=U+zVI zldu*&3n;z&-kANzZwKt?)ged3o0lH8-5bhn=k{f+TBb431W>|6xXgqz({z2KrVJ?p zlw^4+5y!>)t9f-*9o%gKO0ylOOSDUR@I%i@|TWNsjRFFv-D;5e+AmB1xIe1Io(1t8!!0cXoJa*m{vJXu}FuQ`0qor4zXK z9FIwFPp{)n(&VtJy29$2ps!wCZ>t+t11tfC6hMxQQ!QqyIXfmG5bCG^B}wuyA4CjD zQfX4D8`Ojmm!DTeo3Elj$hMw7fPzj`u3BaQvnFT{Jpjt6Tn$C7eI#my8JSj|pJR1Z zQCrtAZ1wftK@32-&%d({{NXHLZy$RJ6>N18h97 zJMXxd5=ud%3^9vWd}LWq zd%yX9!o^BIFY~pQlDY(ywQ$pvolDVo$Ln4 znNH&gfsX?4hDpbyRb=N|d0v4%{iR%c^4WlRU8(xo<>y_b=BN#Ec`7;Dz%z=a6O} zD5=~(j?I5d{60BMUDFs(^TQ=TDLH38`^Or;X;b;jEvdYHv@-u>043t=RyXME#h2g* z=2AsaKYd+@&^oV5;Z+JNiVqKly=FlCLa!DeUz7CGyUu53D}A z@>3t(1>Z*b=Qn@s!}RC=zV^E3C6wNH;|=@KkACDPE8qLx_w4K6__`b1rf0Ca;x~Ek zgP8x#^-p~Cz4!m4`}9A~hwI9iGEzNR0+jyeR0VYbz8Px;?VB z%kA-d0`fR%VT@$70&C&{D~R6AtK+f4uxeTDCfd};W22IoZlHUK5PJKrDg z`>e0@+4R>qP4yI&wl*v;;f^2e$1HQVox0F(=R1e3Bqz*BM653GZ&iJr?b@^5wr<~y z#V<_|E09{w1R#LBL~&DDGUkvItTBUnl>DEX9I(lW0qg4MgJ`+mic2sR$u8F_Kap)jD zA?X=$`S?welbU$L1Y}`1p=Z+SKqY}VfMxV0(I^~B>>ViO0HrY`lmL{F#BzypfRdyl zmDx<-dA~XnV&TGed;S{$N`G1hFB+|ojUuDIML>~LgQINPyQ9|8 z6|-ifmabjHS|9yyQ%gUf|CEi4Wmz9U4m8X7DYEM*s!21p8bE1n16KSBB-zzVe#fvT zR*w24B=2b$8lcQ(NC$E%fJtMhK%&-!>YAj6!ju<1KksD|D^V{9qU1XDN=b|(Xw}md zw=0*CqPjF}7tgiWrHegw4a;>`2Xbs6isTcnBBS5xihAJFDzx=$*IC2bGOI;msdAOb z!%?#e%Tga|o>N!`CCt<`Nt~&CwWvjEC|7}nF01FNhr8#-yop>4c8hhkD%o4y7QV8; zTa~u{f`ZcG1a%XMEA6!j_?eo?0I18b!|(LiA-NMXw(o3;4UCcq7Ij?xbd`zx1V|Hr z_a_hK+0)PFL&l$Obt|ymmj{p(!ru_zQdJ690#cbHf9b;q=r3M>{g3vmU;o-ppFV9p zy#RWs(`pkj_amQs#6I`A&$)g>eMcn{snsh0lrTCGM=~wOw+szAC!r)jDU2xEAkv9L zNGQGbN}B!Rzq9SwH9$=a3fMGae^br0(?NS`Yn?r^dzIY>n6z^*5=uEp-Z=>+#WIUN zhbLO*sta5jb9>`+>OMucx zEAzV!D7nU}PSSUR#8<$PK86BewECx2Kv`TE!lFWOj>&Df2DDmGP*8x?i(+@2&POvX zO)C{_@-NY$`byze5(fv}O7h^~kmFo%&+=1JT7u|m3HtFO=*)B~aJuI{IEtR)h=1}c zd0Tj%e9s^2-6cTD=f-DaKd;rN#$)mpcJ-iS7P?s z?~zbC1aWXP6VKjZ%cGCU$ISOz_}m2#2QJpq~my-^4^G#>7r5^6Ky8K6E4Yw+SeHkk?vWmV}Yi2sGK#-{4Tp zh6dwEX7!?;&|$~lAGXuirYtKp!@l-NHQZ3;ShR^)18EE1*UUz_D;ba=Ij;XDeNr=W zo7!69UT}e5Um&v=?!bZOcdQ`GirA$~m+Tk6_yvTmuOQhFSQOi{XAh>S_o523-l zMEwxo6b(E)hmvA3ub)^XS_>x#3(psMJBK$G9|`K@c3tZN)Gj;>R4 z>lLI>t^y`q!5Z9UK;9P2%(ppJMP+Cn92j-=wYF+itu-L2B#EU`R9Q+(mjmczFd+xD zWkMdK-AS-u3IgP*NyaFENpjs?y#U3%R#H}EE9%+z|n8ZGP-S9ArePrD=}Ta9BHK#TeUg`((Zh#t;x5M!4yb> zW4t?PZ@trLCr;Cs^rczPRJyGz$h6wBEZcftDu7a|Rj)+q4FEJL!~t7|VT95`RM0Y~;iww764d)PuBo!s^<`F60!cc&aJjj0%gKj0TUNiq*dP;U z57J1gLt*kRBuOQg_sXLw;sv-to&y8g_-GhuH^S{94()@0kt25DLMjq&5$o(5w$A<` zz=}RgP3g75oJ^}&R*8gCq1CO8+sf6HeMtc>AMk@Xc{N{F-v3K0T$@=;El zSg26?&3#7_60pHF#ZqM+^y^6wpmLt;b0z2fxY6D{>5I*k?ffTI`YQ2Y6QJZJlmsZL zo+5oXBkrkmyK-p^Nup6ZdL(N54#n+!>#+5W^w2P=D-l%S!UYL$QtaV|7z;Bo+p#^z zwr?wdFO70Y9VSm$ph0X*Wf214OG(M5E{r2}Hs+*JfB(|&?bz{ScIE07w*V{;v$C>m z`_}FFv)xwKtaQZwwX5o^ZdJXLR*JJuWJ?_tJxy0Hh#!EGw%Pv9=cO+CY;zCj zhb{S9aOIBu`hHd(&c^2s_@3;q_wG*m@BLhC@5A={dC!p7`nKPSgp!Z9-^;(`<9Yu7 z4>Qn?+bp0|oNnc%5xaINYOnnkK%z5q~a?4hsdu_{zXzWU4>d+f1Vt3$n_cBMET0zgU9 znSr{SR@<2nFyM3(0rhhqx{-pr0w}TC?j~*149)|UlNb}z7}5X-4tCogUTd?1N5&u> zCxY=TdmQPjhj$g*4pw4!U`E|ANJ8^f$99 zoP~oOe?Hs4Bs{v&^_vOjUU|l+anblLEcE1a%3t{<=jse-g^Do9L%3_0m}zo${#>J- zKidc}bH?5~{yr*=jSeJ~nw-WIT2$J)bt@7lTO3fhcI{fOV-g(jH;iPOrqx($XVM>K z@(G{>chbZ-#Lh@DNRpv+d7jm*Dr5YRX>c|(4^MagN@7Wbz~Wsxw13(T9+(DT?Y9%> zdaSXx13y}Mb{bOdN-N7H4(s9o$#L7er^4>X<>jFA${6Irxj|HM+HC)UF?;WPww>zD zv@EU{AZ@a1eTHq_l@5V)*l{bBm(2hwOdtH7>`ago+Tea(T&2YsS_VciOt@E_>$La{KaE$}KxL)y?e%;Am5y zl}7$0b0`T+BI?(-W%q`DRGtDe6n76lX`(Kd@K~jNorIDIl=Ys{C*CXgZ&1sN#m525 zkRBmYu{bT}4vpnykek$<)%@Vm$*bL`N!Y z_|Ge8NVZqx=GpqH8f#dAWE((Wm0VTGs*z;M%LA&wI-I8(0DZiycIgV|o5^em!RIpYE{p?H5sL1bj+g13A?Sd{Vucw%UR|TU*s{4?k33UwpIzAPCql zeF&fpKoCi;2!Ky0C5!ZBxilzVhYlXH*Is=UOP>dvafarWW*0Nf3s$dMZS{4lkw|Nx ztu-L|1h3w@b*QN3Q)Yw-pcG1B&*DnV(up}B82K)V$bIjaz4V8W9XUN_r@Hzq3L(73 zMv-ib+G9Ic+Jg_Suw6USY}b7NN?GI3ECD(R+@;M*z1?rFpG?kASGD-zn(O~`?}G}& zdvqK7h2JH4;rnfW&!2yg_Y0r(=Zn4L{qxWG^TnS1DA&CIe((KKc$x#=ETH7$=l99} z_~ZXc`^EC}Zlr%- zWSAmZJqbx?OLMFHxaqz`g0+gN!DK!I$5r*K_&}_2;;a&f&tP>@o5J({xeJLOUHj0A zO1cCn>4S1p97^*0E`1D=<9^-oClTg#k+^p*(A5OxqYePb7(hk3$#%h0-ZCRersy^HnUqTY= zX(r1NAToHRP$r_EMGA{trpv`K8H#J-iWHN(5G3)sWX=}K2dDm~?~<*46PfB+EQY;z z;ywHQAAWCtzzH;3UcTIR@7`?>f9_$-i&r`o>}(`cB<)&QSV-ELQ1}_O_iVvlNeWUF z+z8HtV?HhOHh)jo-M47o-Ot8}Pot|t^9os&!Cjq8XwrSvoZ0?3@r2F=^hyOK1<)gf zNnUpk3sl{ZV>dP<<Mn}2q(sd+`?Bsi(kcM1y)sqR1@_eIwe^>xKNNrOiM={hPt4#Yi^7Z zeiU+H0Io|Ts5T8i#5`baed9I?04pxCn&OyMU}0?YT3LETHMAn#N@NWYb*Db0nyy}* zvi*m`cI16#fhUqs3QHOU2_3)b=sG}YL7jKNkdyXMVH0<8B}s)(d$*AWNlNM7>?Udi zflk_#@&qVCJ#h31q)l)&rdars^pq-=K(&ao1~&w#Gyp+&FREv~sKa%3$E=-w)3tuP z(hOG?{r4DBZ$p#NU{l6nz_qHpGWf6x>8qy!C1)rvu2p1Fk0MrD5u!gpq6y9`@mr;1 zg)No7PIW;p8Xuz98+QGAI7Lz@EM`J19*af*F9lpit+feYy9s`!mQibM9)+RZDMweYeD`grv%Ih=nv|Q@)=b!++3b3k9qk+Hur>oOliOF`ME3dPhke2l7Jy% zLYYoU&6GTuoJ0|hPtC>iVLNpqg7JqA)ZfkkDgpLIHW0-+UJ25X9ci=`*^RbmCk8Ga zS!L@t=1@M4;IJDMVA#(^7sA3)fnyUY*XJN`w^Nbn%i`y%&nH@ecWbZX~0y+aI zu}K2*OWP{!p}iG0C!qwOgvy`tISlye0j1gbhR;iRFqd_z@;A5ncNRXc>kF^RNB_J# zoI6q9d)?+Q%{_MABa2;defWYKi~7IdnLBmr!cW9G`5UV|zZF19@$u#4_dbpb&;9k! z`reoA-7Zg8Zod8{GWB-DoUH@+r}AF{ls;N5z3YIIqNhUhl|Y520eo|Fvt7P;nbm=l z4hYK5$zr7^3l#)Do~R*61#S@aHSrjTL#evD+P?6GFWCL}-|v8-g2IAe0LLJ%wXM|w zQ^#0Ye(SBb5Fu`51*wWv}-%ZczL#478pd_;29ss48XaNI!RB^?jlmsZfdjQpi z7J%}>5nH{y*y^$Jv}Z>cj-;@?d9cy`^;c)@*yS!8MOvc1GT;98FSpoNpKD;Hl1T^? zk&M*1bK)d%gL@{Q%s%OJ5{+5)P=|@r#gjmVy~BV~kY`NRFh3rU{AvQnUz7nliL2C~4=k_wFKa^MzC^*n{F|Slv!IWhpEm**uP=CA(sT1OQFT(_ zffkDdDn%kp%5a+KX_DOEH|W&VnwpyJ;>C-0=FAx;r6=tC`SY$lt4(_;wDs$eMq|=g zTUU!ZS|wz>c{ai1aDuVO_{gwxg9C%`qzqWWGJs+LD5=hCTp}PvAW9%rNL(qu8BCx{ z^Qf%@lkup4o<2Thhxbp}`xl0-aj4UV$B{f?QlElbiwfMT%9XZmO{T5e5JoL8WGj(; z8Jl2Y`o}4N+A%wQ;hJ55c)TP(&nk=ath%Dmsw)eTw92vv9*zJi34m5Esq#qTLzdYB z5JqY=A*s^P&eXmT%vw+e+blBhjsNK$?g5?CAP!F<5F>z$C4M6F>icVX*y3?L~ zq6(0>8i_90-WZ!H!7`X9zZOaoxfmqcbKnubilVFI!4(I>IZ!rHzD{k72a<~0)r;f{ z>N^&;k7PdyKvFl<4i|{LiaQlFfHDCr0{*}vW&p&d051A^Vo1ryQJ0*ubLXb54K=h* zq)VE+CIQ)`J_ooGLGlafqJq$<6{n6_HTsK{WvHRmr&|5GkgZr5va01FTLy`GCK5|& zfI9-4`D`G7B0e82lInXxIUtE5OMBw8QXSyHrXcQ~g1EbfxQI;r;+1JTi`vv_cDU8w3dUQ}lk}H1<)C-&!fpP@HyO(}vM~@zL^9_-67h^77i`Y_o+rDGFZP);) zgz9rKCgdYzq>3R*T-E<51pNxqm8HGIM`HH+8&NxWw9k&6Z$`BdF-8E%aC(kCy}1;r z-I62@B><&3^@8_8NYnub25Gv{uZkdfTX^p8DPtGg^nCKYU`ld{#>^fwsk#^U+VGne=FO<_h)h07*naRIa$=qT)hU6bgbtdK7LB0HuDcCbYD)*cG0UDC(n+KI*_A ztteJjRXVUK3c;<2^^P1l!YcDw_pHL&ym>P#c&k|Dz#0cj9r8nANmZe?w#GJX+GIQK z+u`)2U1vrEP~}SQV0=D#;&AnA`X;O9Y3~jb4+#XD091P8jYUYgmjET7mG{)%cQz_$ z)m;Hfs*fUk7Z91p0N<%$0)!^3OMWUk_5?ZEzFJJ;N8?Qkb-t0}RK4W&#JLrh%5_Rir(`>)@gvy<0) z5b2+=bu04h@BU`9J@<_URxeZFhQmR!E9XoeML!gL8ld;>qeljgc`2uBN8O>KQAn0yNZ^VL6~uHvM}#63j6cqN2DS{OP5BaA09yhXHG7Zqy#R|sDhhR~D^a^}5_fUTE+N5q6_fG31Muez zPs7)fZH4f*tf)w}S_teLR%hATHFO-6fDVIWsJ~_BSP53@ zHmpkrtWIIVi>0!XOwxmDPbzA&5pmO~0%@8nZXHRR2vE`(2N^-fp(M#0CbFo~{rLOc z_WghCwzF77(}EsMG5{APqys=n6%ke3y(@c=r0TXWd;v4i{K1NiJytfp!?kY7$AbIdHe*Fd?mkv}t}37W}X_Mil{^B%jkKEs~Mo#v}A7`9BR|JJmMm>y=J; zj^fcUs+RPfxDM3tT8Ya=h`Z08#~NkR2$D)jRdFu_Kw(JR)Rqj}it=HAEF^MRz^JUu zwaV&D7D`j;pHf`dDU>f*qE9jJ5r0V5-8aHzj`BhUFjp`FUIZ%fP~xicPvz_Lm&19- zI=`7swNiibSAOZ(|LQ=1(x`JGfHo1%4-REme{YtZd|y0$=ixjWx2s)s)-zef3#wtb zsq?sVw!X5|Hm+Z7yLT4YLk}2>#;7c2&^J*1rJfzdid;l$hqzI+35L;>IF6Lk%W&r% zJa`bgj7Iv4PDjiw!1%uVcG^zdmaSWmRN7=E%pIiCshkinD^N-G(8=jhhT;J{dNgit zyct9NyVs7Ky#_!r6tp7%rKdKQ*hBY~*e)%`Gr$1kKU;evV;vWe1i-t4*k?YUA zU&-;|DL2le{AK|q7M7$%Q$$}cmy?UNKREdGy-EJwyKj<9ZX(hP<9>Y%?)a74%7;51 zi+k5YS9hroOMudyDZ`H!P)amf5##kEr6frusj6vJprmA(<2O(N>rV|@B&dfEAGTj( zjX{I`M;>{^9(eEpH@IKBZY@BOz@jNfu=mnSFFDC1smVz?>EVYTwr$(CxxuCeoNvGV zwv%2GNG0$`ABpFld(O6P-xlN~l}eq32fk!sPW_nTqd}ru3B@1j;>(hW`VP0^lPCv? zyUO1;-+c4Kt-Rftvio3P7Ic~){P1V^?!tVyg-+jhHtrkg0i|XDCF;QvpmcB48CQl$ zQC)bRbnCi9J*z>3J~qjKQY@6u8IEEl|mCOtv(UoO@8dYgnB8qJMa9?}y|z5V@wr2*BHKz2%(9TE(SQfqK-&jqBY4 z#pX?0Q8Nj6_#~y|>Qb`bw;r=a-UvLrPgsu=F02$oEiXmxolgBM#xhyHrDesD22|Y^@GJFHwQ~pUxIB#$ zpD3zU$yVO}?+*v<$NxA8pfqg56H>teOb90cCAD+NjX&4WZ#%d4*@F*N!c|j+L}kbU zO0qC_D}a)3GqZimLO@C7CxUCTG?=jYN`K!l(km=*4vtwjfvsH0_AX;G?`EsHq9^m5eTYAC;&THu*noHPhk48(t$1%-+65hU3pITKha z3n6(Fau(twu?biQk@&<2s(47bUAa7AmylSxcmXxa#wqxf`mAxV&vH<2%f>BZL8}C* zx|*s2Te}XoHXASnekH<>qys6YL&VNxSo~foSUw9uG@g?DeIQ4Yx1c|kw9H)I3oHrh zl7G^dg+KrBy+Uz$KkKi~wIzOO%hLdM(*Sl6>Rc*7<^ zy)Gwbf94nITv5(Ga1#eXfz5w#u1d^ZPY%o9PrjCXJonb(NB(`?^~a07@9!o1vekMBPg zK*@E!WW3vGd@2C(4T*P1s%Vk`Dqux0SoLKf$jYyXyLErxJNxXP|M{QYKv0%<)WL7r z2B{{*nqz=YYWT0d@`}Cqv!6MYGw~uw`e^5_ovhq#m~HU;_wBcR`}R3$CW*c4xj+B* zpWEKOdyx=GbynXzpd_|`0ZOVcavGRQ^-k#kMRI;JqM0pvwdWZ?Cp{xT=?6dffg>9K z-uJ#|U;p~o=PH%z?8nvl%tdcDp8sPHlJi1^b(5R#Y}|)~a+d|DmTLi^BqG;5>TI%v zlIqIGR=zixhNZ{o_>&=+YFk#6k1GHW>PJ#y00|`kCHR)IbF-cL zi&S8o+8goJctz6CQKW3drLTLbQZ=I;&rFAqR!TwABnm&$jGaG;^vjuP%*D4@V^52X zX?%en6_EMYBO$eJ6)J68LP$-80Xo9~Ut!ySaKPR<(vKCe8Tfs$Tubw-TW$bJ8L0Ub z*_O?DShxyX3945qOvXci2Od}n@>0MuChy@si@|*+)AF*)_D??;wIBQw>bl)SHZlq4 zi&W%h0VNtYll#xF8L&O~4cY^HD{b!sl?wo+K-!513C5u&E;t<}#_2)u6pCvz?0tI) z##q5^_nQC&1qudT74^V@Mcn0r-V6Llj3SXk{7pcH%-l`~`n>GqqGYLmq1Y<|uMC4=Xr4yUs5 zZ@J=eC-XkHb4B7FO?o`>>f9BT>kMOmNgYPQvamPJxg_DzkQkeUKpm3%*@CT zSt>tLN3L$5B9{U%n~inRtc+aSQ9o^ueZJ3j?TSNMz8oU`A|w_^m>-N-Iv`Yfi19wC zYa}z!>H#2c2o9w{ zD$E5RWc|D{Ny^B?Ba7{3zbkXu>e8a3TDZ+VyYPn2{ri6JpGo-R+poWTonOiCB_I12 zZnRI1XVP(U+rH7O?z+NCdT;g`2d>{p?0x+GHJyJLprrYs`YXTbdH0?QerfyIazJ(M zw(G-O@!<<6{+uFIdCmir=#QoTUR(mVA`**k^Urglv7_q4Z2?O1OnxQ#r%U(xcJ~1# z3d#{@0?N1!IQeVCaa4uEK2;V%Z~~I1uvQ^ZN9Phn{mDQ7#F6MpjcqHEMcZ8mzk`(| z2o(GJ?f1X`z5Uluf9imnC!To15vf*HVNIp1jE^WE06w;tSc$lF>9SjWe)ZK?;Yz5m z7hZV5snCfJBReNM=x|iPs$6suuEJ;qO>yR$uYfvtE1-P*^qfAo0q7KUDsSKa{`cLA zr~{O~@pY%JCzU-9RNd>9=AMcFVvTjNYd1)c%302RIOuFTJ31Zrmp&|>9B}P6DGCeElWr|~=$@w-1vaQJkh+^(N{UuTA^FcwMNL-{N>TeGDsTJu57-&F zPP&Ks?8&_~_Shpej+~Y65(K*epme#PrDrV9Y_89@zxwMcd-l09%RqG|ojyu~e69HV zugp9^Y0(&RQPnKDs%av&n1qr5CF*2QFF8(H(Z5k$ou6N{1+8kk_$iL`=YU?o8^iFN_(-RB`9H2y?VG2q2rPeC<;)^fZPhb40BXWi&$5{yd+(VyZlCs-L z$kx=>FqjBdshx@<->X~NNN4apxrGktmIAm(A66Yz1-P9$pgd)ArwJZK>GIcorvYmu z$t+86qobqF`fGPLYGkO$|Nrd0hkISudFK0}cYp*4uz@5%u@^~{s9q>plI_?|ToT)p z#ECPRu{_VD%)Nihy_w7;PBL@nnaqrxxXV?NWvh#ns76w3C?t9(dO0}f{@!n$b#QP1 zu!*EqxX6XQ&)#dV@~!@^uben>+|7o!wzc`funKE!b%?fX+PnqeunF-qtUcki$(Gf# z)#y-a*wA3*ScOx)7t%P20D}c8#m#Wiq#FgRV+m@QE|U*OL_uK%+!sYy8ABHvVsL%u z@f}G!@_M@+K6=hN2WPEkN?<~ztt($+8*3}j!IrY7CIEp(IAAtb+d065b1eW-m{dR3 z&S4sOYz;<5Hr1Ef9ec|Fl*(-H{sK7a3b1m8N@~P?B;J(70-E|70}pg5;@}GlV*pC7 zcZ$6K{ePXZ|MwrK?CbzKD`y2L0Vc>admbBM%-tI%&mY+Z*X6;{WdJ3u-2l~S|6wH* z`hluXcVJcvPE9?hxqF|?ex^;dZ={v?^b0oJ;;e$)JX0KD%@`vNn+v6uotS>=`}8wz z)h68W$cH~Y(*ym%s|%~IgJ;kdj6*?`tDl=kNjhT{*6*ZVfh8yFPP4P^2|I)D9Y9oe z7{E#T)BuA@;WDi&nzvfOqek>xZQ6)sK|sE>YxA8`b^ZDR^z$SECg;(0q=Y3hN!heH zRoYmpOVV~=pJ9MP*U}sS;2h$Uqv-wVNm*~Vl!s4Q+xaOwc6`R(Iz#$1V>XTMp)!=o zHzf7$o&1XLlmSaL0k$I9OQ6 zcO|}8(OyPvSJ0&X6%;@bhKS?uVnOb;JbUrgA$#t%b9TOm{*(rk4sCC+yQN3zP>~(_ zL;#dznNomKUNR`B}vNN~v&Z{;yq7{NzA}9Kf$IsYaF0+oVnkX?HMR1vEWw(b+`_}ha?IG5G1eCOf z5GEl&X${g-;!=xUL!ZjU_8>q>{)#x16hSOYyz1G9+}$uhNn&HFBn`ycpcTR1tJ5(b zWSH0l$S91sd{jBAU@5(n$lE{v&woY-!WkDkkh$O6@3_Nmho7~dg?~R>BR@gh?c3k} zwzIAO$)EfQ;%*P2;Jbnen^OojY66wS@-8b)0-yfnJOAQUFLzp}sm&wtBFR-b+INjQ}L;1B$iTWqu{ zx5`9t|Hjk1%ucZ=Z&&l7#8pX`TwwlxDw$ttC<4&wXJvU=kck0+f8y zr;T68`1J#nwE0ppj9gm5uHZz2MNS(u-=t|#B~DVr2E;{09EJ3cci)9W>8I27>sPQC zb+!%NBi)$WF0pOR#rD}xZn4jOY76ute38a?aVN2v(Pm135>}7oGD&(m{^;8M$tjL6 z2&h*%%@LYpVf9S$hI^PO)q@3deAs+Y~+I=fe=)py+KoUhHz%|2&IkCK!I>#*QT zoVPFL!(6BGhbmFMu>A2nhm7aeRd)Skzsvr{XPT@kUg;a3@4WN=!&o{Th8lUE8))@G>0F*wZ_ue~U?;d*>9WC#;xP#J><<~XHnyp*A z4$ic_)c0;crgiSuH*Tbu)hr@BDHH;)vEBRXEWx|E z$wGVY)}Irtc_(r0!}LG4WopvvyUN<@&e$b zb>oFni|ko|lG7CKDF>AJAngPuWdJ2;ConAbS<%u-t;P}SF!NoELDx_zv0C&y2qmf~ zsrAT*2xbsP90NgZIm=x8i+OwD#Tjes?z1xkeT3nFhxwS6h{qCMS*Pva{I=b3+nhag z=sv{N_Ok9Cqn(N?EV$xg_6Kk?O;64GoG$%p-~ayi?U`quaWx!L#c})Xce2m86Yjr* zb}teSjg1@OGArYd2m=!O=WSSb07~jIfJzK0=yNrD;iVya=H>HP>l2^^$6s-oJ-h>P zy!~tKkONAER$h&Ch673h4=d;!=n~8(S=JmF`c}++)-{{H5Hd~qtN@~5I?!c=^$!;+ zWKlfXKfJDEd@&1k++oqB_fLLK9YG!+#mG^x%9k@I=U*7q|;GdX6pDd(#nJ-(MA2k zn}YxGwV&31-Cf=8HHNvBdGzEi0+f`8becB-rKPoa{Q)J?3=4Nn5}`JH;`ZYp4q~!^ zB(bN9n@C

ay}C4y7M_{|6{3>~U_Qdr^?ObLUP@9d@E@vjY>WoemQHDV!leDK2m9=?3a) zWZ%a`FXt-KUc`BME)nJ;pMT_D#d`FDU4-VD!HY0Lug{%3=ZnwUS^-L{9JwwBxLicv zi^TVlBjg9UK<~4?XV<;PDFM>*d4;Q4h*SUQP^zm1P?8QM0Hs%7Md9wbQz*~vg&SuV z!1gYz)Fc_ZQg-}QpB+8jVZ&@DE6Z2e?YmalpZsaHedhNnT{I>rwH3(n!2y((R&6Ax zu7SU3o{gRWC2=C0K7+{bZ)ULcHe&A_Z?iLu&8sVBt)_C$zVds!?JHl{gZM!q-2aU8 zMOlCnN`UhLlw$0PJ5Jh5^YA{NEF|EOsLyI{QgWInw3?5ggEkgV|MF=&ie8O(*lZ}w zrp8USdGls#YHD(kHz_clgPS&tC5+@((C_1%sBeN5E0Q2T@`_K3TZQp)B~2NhFEn@H zLf8dBDuP;i?qy1UBSI=JeH-Fi{7uNa;)`i1c9rG&<{>w~kq#k0S4KY1}#+bMnBzfFCrSJAV#Ppv}h6eI{4P?y$716f^LZen_>pp#hyV!F2d8 zz@?pgF(D36pfr@~5;(eI{W9Xt9J^(XW05MJR=UUqM|&jEvvGcGU{$srPpEonuOJ_9R*lQ+SaYB zZA)V%9B&Eg3NbIj!(;<3W&!Lpwg_mVbkx`UOc`yagv~C1B#b%I@zmBbPy3mITWZqU zJ7%q&JoR#jA;MN-=;6SYJlnI)$bXg9*P*l<VW*}`|ZccGtVo_Zze+2W69q5H&4 zf;HH@9Y30~V{c8{o5x%1%@b$s!t53sO>H3x=~T+IHP#Nudc>NxOtWXWmo@%=?&n$O zXN`T7P+;9Wmi}e{0oz*Jd>`=~2f}C0o~0k2wdUqqY-{sYd*qQv?9-q6r0ZBK6QG0` zbZ9(+lGL_CKhV&8;sjiWM-uiTT)I!c+zse8LRjW>6pcNy8*$Ow8_`2nL|-aGY!*N% zPaIaz7+_djx(norM9ol!cj0ZMSo|GB#OLvM_Vu#E#=6V?c)5GBk{zd~eTi>Z43iVr zlH}4v$xd%cn9F>yXzWma({bynv0Q-Cc@B*Ohtg^o4}uOQai};@szFPiX`smdHuJ+@ zf9(Fmws$S+=wif+=_t&#NGrC7Sf4WBAzVRmmvFEoUAfDOyixZuD4{i#4ydkJhms1Q zrgVuuqhKE|$(qX5c3^k4{ox;#+owN^g3wG~l}-&f z0@AZg9-FU>4yBc-o7;Xl)pUic5_^*)Zdb_7CXN?jtWks4?{vdo)F1q#%ljiKIxW!! zC}~4^zCCG&(WCVG(F^v*Tdj8NYzJfds3qsd?CW2;-TwH?2N<_u^C|b%UIb*(?wj=uh$#ME-S-nU5Sk!b$jx_WTRad)=2}ty3aV_4V}*CQDzA z^z&Seb1oWzSvVaysN4?t@JzoWpd=t9I@MEd*!WK2^)AL6=cDkA03`ub5>w3DRHf%4 zwGq9G-zd)Oorm1~#x$?CEk-)5bXEDZ=+oR?28%{nX_+qsweA>3hG}4Mz(wM+zgHfk zg5JCDPAllW>n=Nh$h}T2)w$GM1wZ*koS6XM=o6)a?vhHM}5D}m} z>*&j~6WwNAQ_2O2!}a&zhJM?(bHMJucRl(c*TDq?fQx9AK#F|E20{TKNJvNd20X+6 zkN+=a|LuRJ>_iubZYa}tOgkSFWd-PUDJZq=6~*@0LrHt+lPLhU0&4(>C@mvSiPh0` z#hs-7AGu3>-c>4#DronN3sMYwzbW5n47 zdQZF_IkBwZNFb!L!h6pFaa_X1w&(RoScyY*cJ`uzAp!Wa&gvWLpc!=tw^stL(>eTL zf6BW1Qh-WuE48CE`|K2;!l0e%9I{a?mdz#Lipj5|EOqGkLA3(hscXuyfVrw4tA6u# z=WT1TOvYMb^)zB|Gp?(nq7w0ne5{=rU<8H`oVL&*AF-%>xH%&^hG{b+_){m7=zdEe z0*4sfsc}0!IBDauMhAD<>asjrTLGw5v)XFe9Piv(WP5f=H&-DRj+wvK&_46g>j!vA zqIe0nAr6^RgFy_K3d&R3X#nODBwYMDT`!sX%l)m;OX@BSRQWqzrrj)!Wt#oL7`mdxSzvyDmC1v5DI_4_^ z@fu&{-=i+xI0~Tj$_N}veWrQe#YQ3LqkA{o{RcMNefJljhYX!s4k)1@9qOW83lAW6 zHEszFuRM}W9bM_C%hl;5|B)8oJS=Y~7V||K}jj)meH>gL}cZcIJG^wcn!Zk^nb5ApyZt}-TAx%w3zWl2Fok1euBqULDZqA zv6LcR2U47Qxt>Ns7ggZ;I|&Yn4IzeFkb4}bVWKSB7b zzxpc&l*Hwf4JZw{8R#K<_L*lrtaKVZ!pXzIgLhg}bF-~S(WZl1EFOHZ%j6J2si~PQ7p4gu+SWH1oGZJK!-bsEJEbE-o5yrN)<%Jzo9VmizY8whFN{m{ zSiXxcw*B}%`|9I2VKvqk!wuTqRb+1;E4H`ZnXtFsJ!2w%C}h)`pU;Z>Mmvfb%Bu3l@z8IB;$}FL4zsy<<&{^hf1say z7Eyy$rxce2C8Byz(pJP-L_{+s3BEu^Eg7l0ZD?-NnCIoQLJY#{c8m*x*X{*;yu_;2-sYqN9 zXn2|(vf23y%w5D(Qh=_oO8cKbsIpUiV>UC1+?{YRaVQnAhz5z;jF{9TcTd4tF$qA0 zI2Ar0&Wa>)NMx!Aaej&Wq~-xn&;caQ59ey3TSa&v^f3B5Xd^HY zaYRH2YfC3>-Kr#3{VJ?+Ly1+^j#_2i7|Ogi*amzx;!tH(7a+kjbA#F`nIb)bae0Ww z<>N=kN|=vI(5*z;o%7b&h0^zq0_*IXvjGlIhsfA0VskUH3W(028WclsT$3cdS=+e2 z)HZIcg)?7D+=p#dJp}>el+Q~}0A5XS=0KXN2+_{xpp|L2l%yIrG_EWi&qCi1U&Ju+ zd%dHw{5yS{aXe0jpcxd%fL>=;*K&Jt3(*H$7Zbi>P(}mQ--9r0c_^rD| z^b4<+{Eg%ALY*uWF61M8vV2@2KYADA$xXmxQ~58~d07_%=ay~Z&DGt-a%gOq#l8@~ znz+Vr#7cdyH|z&RWpJtb_|F_5ZWRyfgOt)vmt9bKx?W=3SC_M!U;Q>I5b7`$*7#WT z6zHsZ&Fi0bpuR1a-6wp0XTndwWFk;W%rD>l?spxp_{NjpaOos{SE6royFeV;;`O&# z_-mNsesU_>YVCj*G9NF?n?gq4`m zO?~^aALrc!XM?KY!kiy?e}_efC!_h9_`An@fq+snMux zIsui{I>pn}++<(-qp!g#`)NNF6<8Gpp)fH7g^1UuH3hndbYl7ARq2YR>KHEO!3#Z; z({DZ3dp*-{4YG(Avwz1;TZnG~Tu?qV8-_j*uF8*oD}If80#!=^SNjJlF^j&+j=wi!@18hmCtKTX zWCn{;Yyv)g&n@=3Pi(Udn})4=O*`|!xJ^$oW+WsQ60B@y=jTS;N4i16O!;EEEiH&W zaCq=0W_#Yi@=rhFQ8(Skg92*X0uKc`X`LW1?q_*%GjHF%%@4TLFY;mYDU_rQI#k3I zg2i(eF_TCq>r9je(^u%eQj#r@cNT6Uakj)hR9sfTW<`pJ8(1f70KkwU=w54Y9Y^dY zj}2;`p?laSrum%xCKwb-{L%kXSjEPx$nK7Iy0O&u5_L61vSq5beD8|*tzZ?JQNBr?qg7?5`XP|CBq zvZOtF8zA{z^xc{@R<)|0vJKkwghT@pC^s%=tP)t(Po75LSV9BTG61pYDo{t3(Gt@Y zfNkh;DnYcbbV1z8IqU$(Lf@pk{*A_)i;sZ0u#gTf2dc zP4N_92MXm`Tc-4Vat50Yhy~&&CM(e^RAuuhb5Bl-d#3_}5Ov1#**X#1>A(_P`%tO% zPoSSpdVKKpg_D3wV^&{N0SC?|Yua34dv6=Etvgi*YXFhf(2zSR6Ns4fXI-Te{VsQn zm|bt`7g~45^<+%Gun2C!GS*v#m9(1;l)W6QcZcol$;0;cyL;`Gw!Jn5K$(XU`IPdV zV!cgyYs%_vb9K4hbD#qd=RBgSW$sgO3?^nLNh@K+aPZO008>qPIO4?IMyjgxf zK=SQam6jnE84S{#C#QVtUh6_}s*AI%f4Bxk+^gWy9k*XR*KV!nr9%m>vZ4w*u(84R zH`imOy2oxk*h9ZTzZv;-qZZ7O(p{$ZE+1&3xjm%g{et;6n^uuFah{LA6(;)lY^7^V zFVbDVqg!cB5Z^0}+&Yf$;x)t<$`qfibPZ*T>zNQLw`?nYdpXauX`(%wEV#yYrnQ## zdrD7hJk@L5|AhS@db1dp^nRgERDQr-o<%xbPCjmi`QT9?)T`<LJSCg~h>?QKcL8p?y1HCni7c*25%-QA+gTLVJ9m;cFk&N%97+;- z`@s(uMBW~M{P6%N0SZMI^`8XsxbHb@@n=5s8BQPWb@91+03}(1k(IeHxG*{Sb_tIN$zfJsA_UC{8=l1!}f1U-D1|bHW ztbyJKrP!)Oko3E70+QA8co*sEjXCQT5&AoS&Lq6ZDZWJy!jCwpGQ`vH<1<~uDT5wn z!f@|#r}IXwE&4_&=)HXAo18EosCZ*JxaPV@<9Jm;rS~eIiN?)B(-y|Z#{m(sgu{tp zVS1oYTh!!q(|zzM5ZkJ9nrW}O?RUv=8xCKpDD5^0;fL0Kj}HqKmFI?w5O-jaehc~uJ(5?CGVcIdVp_V9f>(Csp7J9ZCSWp&_CO1kN1^&c&! zl_BNoIy;r!#{j25NLQsL1HO=;aNwIr>NUQ5SOA51Qsv|# z4*gqZh*?yqh4e*Y6&Gt!=aQSklKr^tx1nj z0XlP}YsU-`vt*4cfF2kaN9W@VIwbR4S5JG}IF^SdtZQh_+D0U9Uu0$ZfH780oU0L| zEw>>yHUa>u@<(lL;h3#1ue4R==*-!C!8UF0XJd>txOI(IyPCdM)CD*-2*`!<@8VJp z*edP&KdG|QT{9RIfKx?%65w0bC{?gV^f3MY6La>vpPRK3bODvJd7eiUFEJx<1P%{Q za`PDzQt0AgG$T&}j#Q@T=nu5603T8(Pg)O#c=T1S%cF1S0V;`< z`c7-SaSjf}MOIzYz?fA7aE>*#GC+S4kocm9rOu^`M;nakDY%A)8|(tW!WfF3$Cxt) zhpHG)s;&RRxDAX9P_HxS>&j!yhs5Ny0PeNo;%O@?o3@74>#U)6E!=1`aN&=lYboCv z)>Xg}N1Y=kTv7rxir`Qxl!zd3o(6hxF2VUWGgS(}RBabV&;>Iv%=&rE+B*xay}J;g zWY+qI;hF=G(mYcRM@?15YLvbg+tynqta?|L@smz$-8&&wrUhJYYs@L4El=s zRbXY3epgxw$Xixn9X;iCrmf6gJ91$$po9|eyEix3fgSaT!jIcM4~)}~rl>!xFp{n~ z4yA-$v?2FgpqtNy>Q_ojK8!`W%85=2AD@$v%zX^w0Wb0=>~TEBbk7KJ6S3E^#yB4f z>5ob-{0Vtcrb624Yg!l3CenFW2&<12XQBY^=E`~phjasbVMB9 zg|t2D^gDm9eNZ|N@e`$)9iQ^8L#!f19i6d(@S4lTu{1qBMVq?d;BbknUtzDwIH~=n z@8f(gmoC5Zo1ua3Gbt|Iys!L*x?L1;c6{VJ+r>S#*L`+ovcJ*utj{h@vyVp}RR5xd zl(9>HmfDPP0PXE$*-`60CtVg@HQomw0HvcxkJ=A^@FQm|xhxK)ta`|<#}D)Ubpw>t zs8vDo0$U^+5Idg+9#xPkQO{gI3EV@{QS$7so`nnOSs% zY6$lb$g&0mDbkY;rJw%nrzWM`&COfwKmDh_wkIBc!sVjHT@;<0gC>oi{NyM0?f>(C zU@5M4xoGK8+Ss@e`S^Mk1v*s>N;{*j3UxkBAUc_t09d-f0$~hRV%MpZ3Ck&!mvJ8X z>m#s`|BG`e{fGbfAMMLu{)6-aOB1fd;l1Ew62 zq=b(1E)3>O+UZvzz(xL&jt7q6JwyB<4R`UkkHqPCF7=IqT`J6PIbMc*7O~JjdxFXo zk2>(l!ZYdZ*16o6bfj=qR(u8#o9yZ7b|sEtan^#PlEt-7uy48#J_X`bz>`>%=`@W(e^7cp}VhMAcUL)q=BSVU|Hie(C z0ybWGi7Ggrf(0~DSVMuDFHMqm$-Nft{DXfE(HKN+Sme&JnPW@E(wog58-Y1CQi7-Q z*kFb6L*osRsmp62NO(RY-Z&r-zy7fSHB&zpiK&!S8WdF(F+rS zs_Wg7RvJ^G4kqB4U+~UpIy-G09UUmXZS}sdg9QP|n=vWBVf_Z5V+5vYlOgWZ*mfXD z7z)EsvTSj*8KD;Zo#-FF5zr8xE&I_&=%LCi(81RPS#;3G|3lw_i%8{3 z^(jtc9U{m}R8H+?1KiA8x9xEKdFq4ePpbD=f8MF+ebQsbe%fZ)ud2T)NIoEwHn9SX z=jhYwFX2;_nt29}7jZaEp;svZQX(LG8qSj=M|#*a_uAn%r|gCIra-BbTLDqER#mcz zcvst?HW%c(jJ{fjcTk#uo7VK%mgX+ov9r?l?cQe1&8y%L9I=X8DFdzmys5OOzLzrA z!FIfL)=m$>rKCMJd0}CJ&$Dfa%RTwEV*9uMUZQQ{5|KVGMjZ`Cq^WxJa!79*X$SZx zyB$-{KqmsJ3m9Ya@EN^sA`Wq6oJ`n5Bdu*r3b3KW3_-AEKpKJ8#f&%T3AZ`E(>qZg z%z*2>O#^UqEXW#>zD%HbjV*9-WdQR`LQ8K_tSOUlrHQjlI+7-JfHX4b^}f2c!B(M9 zqX_Pv;!?mCA14HE=tNswCZW9Z2}H~gU7Ve+~e zPWX6Li2k4?9A60lt(mC;+E9Xxal%+0TT5HY-g#>nG2|f|n4Gh5XbOx+TSSKvG}_#d zu%=CBx8K%)N{M=ucBc^U0(S)L6m92e`w5hUtDFhs|Fp@^gH{A!ZsMM*nr9rJ2N_EJ4P(^5BoWrHU+>(B73fi!W6iJqjE`H;MTaWlRF>5^`Id8qcI-sHz4YqP z5=(-UfU45wk;|pv_iHG6tX!-2o-U4Y9l!okSYl;$emeq0dBcM~{8()*$3` zO0QqlC$GTy_~l%Atc_{Iir*c5&DTcscdeP@+Q|1N^t(l2`9KG+dbczz*-Q8FOn%e( z%dEwfmcAuv@At86JXg937hTu`QDzG5-)D^-ieGtN@{Ps~-l<(Few9&RlJ=kyH;!e~ zI)4nQ6B&S#=$kmsDk`H5-mouO;` zqnmjMgjk6Vnpe~ogej=s>o8Gt)idc%T2-^kMIJT&NxCXJ2baMNqF&`!UwOs;*FXPn zA2TkhLn$_!^fk7lu#Skae>kr<5Kz(}tbvII2%TFUTJ)5O=FySSptFKgfwuN`_s(j% zf1iuFH8(e7rJ~-a8R|a6eI%<}-QC^x)1Uqn5a&BqPnbXcqd&sB(jlu|Q|l+mv0B>N zh!+6rSI_Wve zX+foX4LGip`=9>Fxf%ZAFaOfM^3|_+TvFWW@ep73IHdWLCrl=Ko(7aO(WaeGAka;N z;lkpTpM2t*621%1)A>z*Cpz79ITXmESUz_Cz$rl8#|?>c8tXbfi@)_weP6$&D3)sXjY*14U{_ZM<4p%WBV8n`s_C-=j z6x*Hm7O?3=T!OJf%5B}V04~g*W^cwK4Y3&5gv0;6AG-Z6yeer%$j+ zloOcb8#8Sh@k#VOrL_4Y1&v|ioS27O;tU(6fB8*<@ceyk;JU%$n6ZfUYl zJR(KpMVu1Lny1nR`~pmpZW#xZ7P1hta?P)c#?&++11)uG&4!r;_FQ_QFbHRo<{24v z(B?uXR?W@LDCunsn``E>dFoFmRS?U^31wI`4u5pB)CGFczVwR3_0Pxi_>o7j^t%u8 zlQ?!>P98IWlDC`1bnx$QL_5%U?>!~tSpC2^Bs`Y|KUsg$A(H$Ur`F;)S%*%Qt=qO+ zH3k_pHfU~$|I`l^Bin19(eLQ28bj1)Weri!is8m71e_M2lmJlTq4#5E8E-qnQ4&}Y zQ-9QkKEXPp<;)1mo&f~joWbhgv~^+1zIS-WCg;j%tM&B38boQ~_(2S-l<%}Hodcwv z1q4`MHel=Ox^3ImGTXnW$#(9pv8El~H>@K1d|VL$rOoELEGF)XzW4fgXrR@qR{EX%I>Md-PcC#=Q^fkyM_ zN`UWxfFr2Ufl&tp> zZkD)a0Zz*EC#|w@!Zxiffjhs>wr;IP46YFCY=|z_mf0$N&8iu=<^VH_;1H$$HBV?9 zou6a8C;wB3aCLWKi4Na-dfZx0k6|<-VI94si$1?WMEaySel4PpYvEkGWlNPcH&?sD z?ycL3D04nWC-M-@f?`Ef0?3i-gC@-e9pp$70Q?{dpF5H|Y*71vdy35PJk()|F)~T` ze17Lqr!+bTmAv7nt07)O|50VcDk7}tNGHDuDPAnhi&Wn!*<_8ciRIG-D6uemD}32nm6aD=V=EnbwDV6 znA180VP7I6EWLfbE)}t5%Vw8q@G*|;c@F8MNpz)YZBQs6u&~t5w&r2s)a-?q2kaNm zwqog2B5$k@ORDS;+)4M`T5k^@Dzt|mEkKMC{a8sXLTcWny;u_9(;X$|ASVDy@sS#= z+AtJS1&AsTTWkO5d|uOF6WzkA_#~b2g`fU?x?_2~8hGURHpU<0)%d8ole=hG>c_)o z$9s|dF3Cd-%lC1QCaNx)bDaWXN7axVN_a<^iBbLp!#ohJQ~{Ca(ds1={qY@r=wehiAF%*ZVV%1s=%@OziFMb@~dUsDdl8wyqWxJLO*YUjJ#j zYTYMrS%8w(i!Wlp<-h;8|K@sj1t@(HgIv*cxwN+OJd zE$Pmv0YVL5m8D7;85%~bdKa>X&$#UJs?}IeT3u@gP`-WNeRpH3xe-o~awbg{Ob}g8 zfRy}&kqcgVKl|Cw?Azb@HVvZ4KJnEU2L*^eR&3l<#xxa=COiGsX{G;GBk+-zcXWDzOwT>{oc-gBT_q$zx9Kk8RsQVmwV|uMMO|O&{vtT9>L;xG7)~vZ&Zg%oamK) zoc%sbOkV5$egNcJqL|t|>cpbDs@laMsxT*f(|v#`5UV_1v$C4$cUjMLtDsu@Y7Zju ziFtG`^mLyGP&$ut+eRxbhHV~jp^P=)iT6hBCqL`6SHy{g0*hG`Y=807d+qa|*=Nr^ z3)kgy{njyBXuT{Nchr{KgLjnKJ@=HLoU_Pw?t{&mQ_pGIR51Wc3EtWJS&+Nfne;07 zqBvyGi;!K8^zKYe*xBUCdDzx!Y$6W-mEO?tOaIe<($_ft=y|rw9zW6viWo5iq$@GN zlr|1*;Ix^BQslMR&b3e3kA8CAo_@B=-aCV`)6NO2t6F0l@xSv}wSDO;m9}F~nVV)W z#+-77TY(rf7B1_u%e-uWOFYc_J`^GAfznKm!z#7LgR<4iNefckk=$K>TQ}ZDnmy1-A;#M6HGX>aE7t1@s8= z8vrHWX>%{pq&aaR@T#OR!RDXCDYy~l=K%q<0mnN%=sybMn<%aVe>DJ2Pt38&okL;p z9Ndrzd-I(Ud;OhZth^;{d=_8|PNPb!hn1joISClVaAFr&Z%yK>@`ll?ghjD+#kP9~ zI$Un8w%hMZ+3x*-FmS>YgStHR!&!7t&e*Y&6NtTy+Moa>!BT(}EVQh?y3qa_K3GWKXA47mYPdU;P?!#(C@o4_kFO3bnQ&>HYF8f~36hMHr#x37uF}jF$ z4t9t5MD1u*Pot00i2G{oy*x#2$UQ+-QlO&@0Hnxwir*T_G7gYLNvRGLk?sXnUErXz zr>B?se$LjfTgRa$ir4|XH14@Lyf$_Kck?=66sL*|DtHu#!{$i=y2FHkJcI*Co5t+@ zz_Tz932O@PL~D7k4(KWx$uD)9yHukBdXz*+OTTpQ%(9A8EObJ#;F6VS z>EJ*S2RTLd(km^@wa4xF3Fe@oT{fIp7m`R#T3O;%tI2=WKKajkX)qHcU@({Bh^B|hWXDiT7btxY)h3?L7-{XlOIy@9MP=`g=3_g$*VQdfa z@bNdl`Hg++@4v-(G+-A6l$00cD<^O1EPkjj*A-9_Wz_fuD8-7?B0;|sob2e-_w>nA z=p}m3^$xv-0@U4mQNWGgyJxrU+q(+|daJ#$tMdz#QN>3zQ7q}=aC+w1XYBjm|Gtf~ z@ZY>;3v9wW5tF;qcJ12bTtyOPJ96Z8JN()apCH6#vK^gFU--fo?BJaTU5r7E#|MXW zo@1>l-;18p`LYKP;28&{EY)jfAJT8VPE|!fKnO&Qv*^X^s5?^#-i}K z$8jV6#IoFov_7zDT!Q94iBUfegbGz~hq+qkP!gat?@Aao*sSK%Ql=%Z*s1<+x*JD< zG`-cIvt91*_)eiBprn(+1R8e*CJ9ukC~ma!Qe*7#crs{jygdl#04A6@ z_56d+?zS)f-fsKl&tZLkddNCh)c11me*5}zxR+KT#vo9oz&35o=TsWDd)ibH3)Nyg z(hMw6wH;x6&`Laez=;{;nmso8V{g}Ly~@43+OE7}3QKfu+=X!~t0QFH#xQ=(CRh4C zLo;>=3;&c3ks!L!(>-IqhBNDh7yIGb8n+{Ga1|An*y^GZ`@$z`?T^2{25VU?-Yd{Q z#wI3OrOTx2WnRc{x>%Xl@g|fr{<_39yBx~}RU%n5h$76BXha@Ire3?VA#JDSRi+u+L%3dEBw-%XVm6EDE95QnI5+6!C6)O+bCVm7 zUg#O|DN1osC$vUUzr@esyV}oL*SU6d+SH?S<`xH(^qKmpHuEZn4w?d>6#JckC5h;W zV@RTO0&(CPWIRd2O)`&nFiEG*o`H~w(5{u4@Z5VZuX;O^D0@y~mVT5?>xi|s%vx7( zz74Wxoh8pR058*ta+^qEF;0C*g<&&YkQ%ebihMw&O4dfDcF%od< zWY&K1%Ncv?*pMA-?KhZ|C>V2^>rui&7=Y6M{inqaD5<>4rN*gJ0ZPg_<@21UMX_}6 zze5JR+{%iVN2EzR(PK&VGo}PUBGAx>YXLz%CWt0_9ya{x0(xQ#V}VkZ(-Yznumk}E zXdS_%uz~ir=TQ<;>oS!MuXZdy!g{j1tIx%pHf&f6$4(uisbVDu673>hSqhwI4oJZb zW^k)0y#lOO7NFxwaFUPWIuO9CENWXxM9!qZeQYEJH$)Pv!SiKEdB6cx` z{-z0ZdR{=M%iuKn^+>Q84*bpQ)>tE)L>rr`t*Mc*sIkyiuYzl-vIs7U0yaK*h-i}) zk`yHp(*TUV2?i8;?1fj_?Ty#-?alW# zSlbvnltc)?zWnJo+&_F^zddlzemi(q1qLw+*f0XNjZ2S_x#|LODHWo;UHY+F+FAgJ z&eHy?vG}&$B_4_qc`gv^n;e-;0)D0dwm1gze=X4W7{KofFZJ5bpE+%Bw_pM=zm5)5 zhn2TgcK5zjh{ES1_D0&PD4pw86XjG!0aejab`e31O>WWEDHon+|Mkb|fGY&?;4!Z3 zZ!hOQes{6BFBMOWL*Z76Cx%(+eRdi#Z1%I<`*b{NJxkK$d!M)TinbX5r8XCHUW5K# zSro4XOp=cPLX1AN=kQ&8rg{n^MCQrOn;S`i%V`f;`H5q_xVW@W7jsKzN2iAnCQ!rP zZcTl?*MHV$ejD3^0Hs;xfM5UmIs4Y%{k`w~|NS?x^7f@Kfh}O=4INBNT+C;@E(!4A zd~n?XrAU_8Y1N@6pQ=;eGpEnkGfzJa*U)RQj4~i|`YU}&2eG`?KqXewi6z&llMYR& zZcT^*Ju2l^oLa=a{L;(z^Pm4bqbz$3h~l9`kJudt4qy&=!c79d^y16*(u*(o;GvTU zS#9{#r#^)RxxJo64K@x~`2-YmeUYn=P5hDLBArS))s_{x|MFk{OBSGn$eWjq1tp6K zU%2oIS$D@6cHNv0c+14T((`44eykqFiNM<`^`o|>`tresb|FAXgN@|qB~LGQ$jbth zK4OE$hptiN(BJEqLd0usdDK6`*rGS8e>Q|^K&h+yyj1}vRh2dZV9%oXRN}f9?4{Q( z*hv=Y(`*9D(Yf@6&uv2?|1I{^Q{(pIpO0Gyq7K88BX&n~xqbfk8twjvS7Qty&lPnL^W3u+?58LwHFTS>?X^GrL_McBo9s3?B`PrAj4Cqn3)1GwQA4b5J{j@3 z0H*OQW;I@O@)W+h{J$&JyT?EpVcQbuCooB(F9MWg)l<4tHf`R7^4hgd;+5iBcJaDg z7D*;jakRDSfZ*7K~0S+boV<9Tt8(KT~d_l${=s?e=1ZMTL6>5RN}w~r>j~+_`r3VajPYX{0w4K5}g_z1O(`xv6iz57xg)DYSc~xc%AMW zw3&iU1jb7zkG#i4J^(r@(D$~zF5m9Dt=JA8D7IVC<96G=LVNKAHoz~=+2Ny|_UiFA z8=NGu0=PS**qHX74Jb(@RNP5LEWYI(P)g_C2dq$p^pnt*yiI{TP!#XeqJ!@B#A)dF z@egl=P^ldXuJC}06z|XY27t-+yQM#IifLo-;~o$BCel!!$txZGRdgPuex>Q|>oQf6 z5R!mC5lBWD#?YJB@AbbFPzu1H#2OQDvw1rreQ}lf*qsFuiZe?3=ajH=K|^r^YA`lo z@WpH#(X=5rh~zuY_t|-@{B?GtzpaPgy@=rSbsKuTt+ITFRhDi-i~_Eu@}xDc$+L|O z`L?;S!nOb~HEt@g#?4se<2eldE;3m_+VUwtEQza4z!}BT8>QWIHh}2l*)s`y>1cty zcA9rnjB#*BRhO`~0a&Rn2lOb41%cMLa$M5q0a!%LM#2IASrFg(r^`RLqHNUvVQ|H z0q9EHx3x{$iPNJi?fJAWPA@suBOP{1&t3S84w^}QpQZ4(1%^TLy=WDD0v@Rb&NjX-9MnDOnL&{WO z?SO+P;5K{Zm2Ugx(%Y|)dOKXNGmjhupNd+Li2*T-S{?9kAVGacw4Nq~~p z_rZc6`T*iU9lz$X_HT;P$B!6SIt|5j(|tH7;PVporE6sRxNJa)YL1duGUO$li@*NO zuk9bc^$!k8e&fj}?Mr{~`&I&eAz&)IFFSQ&Gl|y^2gxp(%Nq(P#f|v|7U$hv-I!xO zYX6D?>*t?;o=Iwxo9Mjtwp-n*TPeViIDT|WC=sI~Dn)2KVPYthTJ(+=Em0I`#Mtf{Gq z@F-OzErC{=NaW%m6DgQGP{hTE-s@fsO8S+ad+s^=yTAK8Z&ZKr7yr?|@|CYRP^Ob@ z4MCo!~a7nYxjEXys|26KXV+S#AvESAF0g@{}P zg79M#oV<4?;69zPpZ@rQ{oq-N(G0O8994P59?JgaYV(S9w+YO1CvV6EGy} zO^GB*h*97(hd4|(x*8?!T+cyQb5oOx$AtW_`P2p!@1knjWD;fQf%>ZrayCIojI>z7 zat%BeN?XuMaL`ZTl@D)Ugd(Umk3 zlbFJa@*yw8!avq%5l{k9)S+h=fRX^C4FC!P6ZMrsN{3uNUSJ7JRMMgi@U6ywJ(rIz z1(+mDUe3*?Zxx9|__%s<+|JR?W@nQCN(1iO&nK+ye9GE7M&MvV7hQkKMrXELf3guU z3VAvC?iq_fhlK5_ByU+Il#bR;>y^U`;u;00D-A3uP8HXW?3!Kpd{6 zC27w*pR||W0ALy%#v*y|_YZcR4v%?4{?zT3X81P1Tfea!ak}cT z;q>^_B)HK%gcDsdPLD-12c5{D7d-Pe>xO{wUDoGW0Y28ZnQ;Ir=srr%#Q9!QGw0jS zyJc_fH*48%N-?wia)45Hd?IY_xbv|l_J^SGs(-mShhG+;lCk zXt0!Os{_l6GfCmKd7pyqS2}BUV<~9oj-9aMHX(Mf#W(e3Z0v`b1f@9j#Cs?0bwH}N zwl0pv&uI=bQ5Lc3PEJ^XV5NI_FDKc{pYwm|DJkjGZ}$S!Wj4YY;&=^pH+L*V`|CHET~jKWm)>9X37IVh`=Eus{3b zU3TaZI56v`t)fOi3a6rYEsRqr>eaZXQ*IxMuBxr@QTF8Jab!PG1HbZm$k2>$GoR~* zsFhbu&C)$GgASI7ag@P!&)bi_H;GB|3Cub7*x+c7-MgpUKKsc!yZg@7w(}OuRMzve>gX+q!LSU z750DqX{r5(ZfE^`+%=O}qMJfj7ipbC#D8{%1KkpdU=_iMCJ$x_Gg;dTn@r@S>{Ryp%YbN*?}X)mK_CpWZ2q=ElIKqy{4=kvQqA z!lEgKQV&XU2$Pz}x*mAx6lFSbY|ei3%#0m*{eqo_v#@P&hMC9THyltBDLz7d^o9aTvC|HqwCe1cGjJ%qf$aV-UF5B*vI-OI zl@1^YL=s1cKqcLe!KW*IHFq7n8!@&!(2cYkT>!h-$fJz1y3#jbs+5+NHhTq5C2>9- zKlTphp3iz5if8w3zQOO^v&R7?aViOn(z}Q}XAc1JJ`P6l8oNS#AFo0vCCVobrEh)f zTMj6>Qf}u^VxrQ5lSwESP>SE@#vjwU(yQW&amMSF#__QW&m`>hrwwJ-Lp;661(aMV zH_98;CRf2JCr+h{y4(RH_xD9VzWMT+QXswHiuJu*-0C-BK^&HL(u*NW4zm8xgDaM(jD7b9?mbX$_uq|j(z`a;wr!PGP>Myn z;>e+-O(qI$Q!LzB-h13Jp=)?uD9d6(#4$4$P!fldxRqpDT7Xi++J>+Y;PV)lvKPO< zhFQI?Q7P{+|M7aY31-K2wQ*eRJJI%<(pOc#xcWVLaVR;M{PX+h6|)97=x%*9r*M{5Wz`aHiy8 zks!Z>gFm>K^4UzQzq+mojScX@gVk#c6x> z6|4!4j9c%_m`%+Q_xyx&+HbAfWVayhd*If5yZu0(ZCGDq8`lFYtuC<2RiwlGr+O7_ zs9H}$Ws0=oZMv0H{`gccRT0qK+X?e6*~2TWYE+fOJ@0|uxD}uzTc!a3ng{%xrvYf* z6sJ@NWq9+*oW1sHpZ)sPqjvZdhBV4=r;XocV>4Klo}0GY8piCl{TI-oS_+rmIu4pw zStcN+yLtpa0(TM7;(3KrJ$yPy4Jo^xMc7<=lQyi|z=`&HMBi#*Q?27fBq+Rc&L`s4iBbo84!Yr1 z>hJG$6OcMNP-77Xlp4kw7n=);))c2soE=c2QOV_Y&WknD?6AuLO5#xZ%2yG2W5IbN zMBZY4a<5*nn}04zfjGD*V7!lm&4S2VCnuIzdAkWHU6P(3#sG`P_Vk#*N^TLLR9?P@ z#c4fyOyIof08n~!(tiCSx)V4>E@eSogBj*K_N_rbNu9m=*1Y`&t2!g2?Up}v+8({N z0+Fx1cIe@?R$4u2B^BC4X!*?8$Oa)Vg=g$jALjq{bBhXkdC6qP!t}RJ9^L!c9ySmO z9_mp6lk?bxl>P7rGxj|IrBmlx?7hwwYve?G4<^hXy0^hT^T{o?4<)7fC7d=FNiT*J zts?S}0#w6m5iPfn)rC7x)Zga*$qtkI?(%;}KuI7{!0# z*qiZE;1SaWTo96H@{GwO;znHW(&1_{nbO4k*3;stTvz>2#=wAYmk`m3~ zWj?@!^!Q8wI*g9a1At6hPv;EW+TDn;bptGw+nK&Kb^&W}bS)g4^8&zH6i3&TAq!j_Zw`?>F>*-ha0-B6;a>#JlzWvyr53G%^G&n*z4v{tnL&_y`kHVD zbvgAry>d%2;i7)-&|`ux76D9-Nm+Je}Szg?jQ!K8h6NQ;fl^MNB$xW zc;iJ^nW+cA@GNke#nvwhslsp`gqq2Z97=jlzk@p|B?b42m-1W~LUa&t?A^Ee?U`S_ zWiK5*XCsN-)|J}jF%{FcHkS3-y7~^geQ%i^y1yB4iM_!(L1wY0WzNR7xF z>|ae=B=QEJln?hT2S92!%CmsSw>bkSJ@Ht|KKaQMVwAEX zRRZS}bWvjtB=D;PXKL(v?(eutgpd;Z9HX1%T<-H2=W<~`O#r2jSpU3kfKsd|UE|_h z_Zb%n83(}hZ(Zbl;EaLwgNFh50dN9zO0ud79XcS(-XJva=DKve{+QRY_$CF~8l;N= zlf13-4TtT_B#*6(l09UyjN-@6od(9pw<9)oo-?%?6-^aSv zHQTFgEej}BWpOAi)ATZQ%WYe^zcT@E-u$*HpsMk`3^#s)st2rkvpJM1%dq-TT5r9* zSjs`v_JKn96$~^Qj6xx2wI`7_IXK$aLwTu~k4&N zq*#m$KmO6Q{phI~JAU?*y>srAt%4D2b6uG|df$5c>Q`>DyWv#ID`qS&M07x+3@Gkq zyW@b8L`6K!bRBra@sC$h{E@z9b|*Q{ui|H%v!V_qiMvfqO!xuBhK(D1k>Oxc4jnV~ zb`@#f=uhGpr*xOp?NwwZJHD&<{F0xDw%3%ts=J)}Qzldnx8CJ|65?Nr0Hp?NZrX~- zTb1`)Eje-lC5gePH49=AU?dm&MF5b(Z*?7s*aSc+z$y#b(dJR#hVK=JT>PbQ0+MDW z+AlT}y(2Tla0+Q%^ZMZqJA9py(V`d>R{$xRzA|IYnZ-Mk6TomvN# z@?i6kNZa%TJ$W)|#UxdXD3r!eZ(jnIoMQo^$WQvE zHt))rIE#{asZYowj~i$FrV-)X6C+Jlo9Rdg-V6m&O)3I@vp67Ghl|l*L85!o# zv!fHPr36Z^n*fy7JD4P~!)zCS#k$FUmwm7IN-F?L0-*GGfj#~^qy@OQsw!}eg>g+pQ`G7& zfN`!byv;NxDzHFF+~w%Xq!q41d7GT~|OUQ+BNl za!0^4AyuLBj`XuIQn)xK`ZfN@JSA3r!zDyXcugewP7iny8;PgSqfCt4s}X1rkrM}$ zCN~eiLd7nM%fAYLVtVoY@_^Ef<52RlFO$ElM>lUTL4jD8x@P;EfYK!h_Yr!nVPG+! z#1l@s=TOQmkr#14R+X*g6nGsRmgDFy>9;rDnzG-#mbCYJ@~slC$(r&~tiqssWMh@R z*9M>j=Tg!1Ijf#OZI58C_)q_Izuo`fS~gqL=)4u6r13~6>lG}rCC0!hY1)M`F8;bk z*A>RP%ZWYq5f4kY9Z=E_jji(OdvPdDu|a*|`57!o&9bRIX|KL>k^m_@ ze|U@Ce}6ron%4QsRNzoDKgou@L6P!*!DapMiduN%ch?C}atDCVW{2k|QvGlrivy5G%wjQpt z#*KCSuCiM6Y1No3Xwww4)+KEE90mCE&bLam86CS_n>6%`fZX z3M!Dt`x?zk+x9eirI*gbo%@cx{FX%C0*BH@l-qAzS8Sho%_TpvDA)4~zE{ATJcyq#kn15dFT$4+;_X8-2 zeqL{?kelweN`b3w4`I$`ND&smm=s0c^!&PVD8(@?UVp39yLO4^B@-GFudQ3uX=7iD z*O(f=y%CVSScqk!R~Fr5dNi=i#t&lNcsCZSroDY^UC~THvV1?P`X+jO1W{zG;*)mdCUFgQonQKx*or?^LIVszgBTZ zTE+b8n(eO#pcK=(R%N&u&o!ce#w9Hf7()Vwl5TWLj82K}F1PYlUAEDxOE=p2o-sSw z(r0fRodi%aJIR8+zO2etmsi;8)x{|MFS4^(Vmj8Bw6eK&TbDd-hwiPiul>9IcHhJ6 z0JNv^=)Xui=gfgSM|=&W>dWk_!bswH7$eqI5ndygX}hfLwV{emOa)1ewOqBWokcO=otNkm9HaDa--J zB;fw>eK+3^^k5C{e9BIpxnOU-*K6;cK~GX=ot?e_7mKo_{1R0$;Lq$VZ5S~te^G>< zrIMtrK`d@FV!5AfJYk>Sa>B+2du)85$0}~yXSIhOv{lVbi0xFu=~7CcQBmQv5(g2A z!;Lso@@g0A(`@8ZsRaN`rOq#!g|kBnmIW*j0lvUzS84*{Sqr9(-8wo_N- ziZ={Uc|J(#;pI8cFL@hAGl@;e#p*w59s!BSnc}uz7zJELVNY~oN4fy~-LAO#d96r@m0bo))(DtB9 z3c=q+r27O4yW#pd-G;JqfXNmx83BZ9Z1pJQ-dIs!+Zrn|o>ObP_f*=py?NHOP2zPN zlc2+C7RdnVBU8LCo<@U_B5SF)SmM(3A*lC*%zKUT`I0aYjFT3T20#VQA&3a+vGYv< zBA`Y zi$~Ksl=3-*fIYXVq1ZnE*u4GjrxUhrJtBmpRU$oPu^kYnN^mJaNuicFiqDse9!I@P ziynSNeyE>bsmq-|t_7fUrFpm+{`yehYT85mCKpgr4rQI~y6I4gO_yuTLw4JY&#n)p zu3xM-3{cWQr$ti6Y4FoRg9%H3k`@~}jfr4V3>n9aFafiu;Ko5Bf1pV@h9qWH4sm(B zj_?QMF)sEqY3JUgD>XZ=SfTNn`$=|Ky%V4`Jw0u*@+PI+vKA1mynWR-CTg&rw{-sW zO>P`YEBBegUCgcYO>R87zb_W&wS2b{{jOyi?Z@GQ>4|mwXd)IKHIpdotAGjF2BA_Hh#^)RUWQ}fDM#$_BJ+dqN{9>VFKMCXQ zLP&80B;jmOrVH34%yWp`g&E~eEZ_X_N5|~DKSo>z{T6d`rFL-JTKmH1w%P*^adN(; z$kuLH*on>SaDmN}7TE=|B&7(2R&fnQ(Qodu%cYG*EOYkrh3sASoyzBW`Pf{^x|_yw z7kQHorKpr!7N3}}1S%v?vh>y5ywzkxB$PL_6&5buCjFV_57Emvi9FY< zbOs_><8N`_up~&o4**r6);Jo6crLLg0SWSjh!6oIunCtUY>5u3CZ(J>AghXV9&xdG zz!&wJ0^%MXFzfF@_fF@ewRer!NdTock5$@{bEP(h1v@$#J7M~ke1bmc+(E<#7l;)C z6rjX;Q^~YFzUm!2wB~Je2TFe+e%DSbzx56)MNxHeS*ewj72(C*LB0hZ2{+IlACN`m z2LhR|0VttEX(d2Oh=R(ixc-0k-uuat7Gr({L19r}2*R86oG$&2v`PMN4zrD^eqishojz061Oi6Vi zsjt^%TY8;}b_yB?0v5GL&SDodi>U_HSy`;0-nF<`vumui=g;A_?Q+$oCMq^Dh3%u+ zqD{^h-6LSBEVajFD^(Y*zoXd>?H#gx!|gWISF=GRiMqMgjZGh^t?fUc_ZRCp{kObS z$7YkfcCHea0NIKzwRHXxp6Fz_d}*F>r}4%ImG)LUFx+NG4j1hH2V3meea+074EBns zbFLa9<06ZyVup1yBVY%Lc;ERN&Ulup91Zii&JB8xwyLGNmJq~`-c!l-a9<}r_c)eU z*KKa5Xk(*m_QEgQFw$MHQvgh_qsF*WXa44J%!3MC4{dy42t(PQE7~VNwGPnJjr35r zjZI*Wb^I!7X>B&rFVC)R07|I4xtR?04Zt&{sc)p>Eh(ji<*H53SM0gx#_b3H{fzzU z#U&eE9ile<)(bGTueZ(q_;Y1@`pae8gEzkR&Q7GE0-&UE5rgOKKqyxjGv0n^pnv+m zW4O`vgk(EDa}Qs9C-0l>?~h$T=^h>c+p7Lf#zTB&M?i_W-ih?(@5Cr~oRi5>^=KTM zv0mGn_?|!gov6HRZ?!M*@jal$Q41eYL~8_Dl*Df-4PiS`HweycUt0At_P4SUhp1=b zBB9@I5L+)_&v-K(zrr;gle+0=46*EZjAb{T$7^~fN+>k~N|I3e&Ue1!8x1iWv8}NT z9b+Cb-^P3I=C|^Vd0&@LAn$dTZ~KKE=z81BxQ!XcKG3l-{w@He+gR=0tZpL(d>PUF z;D@%d3ot#b3N?|My?LYNL3g5}UzG7cClaMF|Hwm;aG&aN>S&E-~%C_ zB!SXP?MQhF)R2+;GLju-fS(L=BF!<+MmLW{P#AM!x08oG&rnzu2_eP#*}Bb42ZP-u z?CM;)QnP>mS=xT~n%NapqUvQNBsF&Br7apw_6dak88;XP-lL6xC1{K1r(QW(}xo_<$JpX&6KzA#)v- zDBq?5O4PBlLxlq3B4UN*(fdXDy7ZOk#yx4y>6*N=Dac!!fSq7VN%two*M)78N~)W{ zZ#@qfk_dTu9+El{P#_?A9Pr^SRo+yrqUxzbatvo%|LT_J3|;F{X?_2Cqi4uhSu1EP zxVZ+7;dvfP?rRKzYx6;~4){~U!!Y2|l`85Rc>Wt-x2we2sU?r&OW4y|X+qK|$NMR3 zJ*YMIH+lj6M8B1~oWrD+xalC`e^h#_DRt78Wb^I?g6uM{4Qp z`D;iljoKIny+?~p&@G4IZq$N1TkOFj-FE-cPP^|2l1qm(s74x6yLGqOl*i+o#<@UG zZ--tN=-Q>yr4ZFIA`p^B-bo38H9u1u*F+g+n@dTl*8;VI5qg=NC@dLbV?egrhVrct1SQUba8{@T`5}qeYk6I)48U(ngaQDxbi1Qo9ZI z;FT4GP3o<@+ajom{E|KWm1VqzwpkYrhU6SbpO73+Q=7dd5SvoGMag6m@CH%*UqTKg-5SEGDKccdwfOB`74*MSP?__y}iAR*&ZCQw0gV||F%8PnD_4S z&QaiI$3v`<`Yetg9q%@v6zg@bAMXsHluUkgqEEhtMNbo2t7h!n#>pA4?L_35m%or> zf+Qb37sRXe^)M{-TNdEB$i{la^Oz6ESav+ddNrQMYkKT00VQ6X8n8PpNP1S~i(z;G z06+jqL_t*f#C&!BZbPKa4fBcZzF~sfbYlm)-lm*?C)vb4(6KS9@3dK%oSfwAT!WXl zU8CH;lYY3HnQkzDj9q8c7z^70rA}1dI$KBV^0ir1NUqqgUs^-ut<}!V@nyEJ(+04) zAj$r9+#0ouDgVU=e zUzam*cFdZ<3-ZWc{^gtY7k~ApU53$FTFKi$XD`ggh<)gZUiF#=@nP8b(LsI_A6aq;8&%(lsV%cOROj=6VUGo5=e1CV8h#Oh^?fldN|-@lFU=x4)O-`WWtp_g4HJ?!8rIHVgDAwI%76 z6VFo2n)jb>Z9clur7oZl3r~)MR&FJ1&%@_C8Aw8@=2CL&wu%wrRRA3UN{R#6&N_5h zfKnSkgkT2(<0RN(vpQs|mB2_ciBF>+GDQ_>F z%i2TH@hjyew%b_D_A-t9c}K&W@#t4-MF{hjAz{IB4~r0ZX;D z;H5F;AVE)e8sprOB3Bzl7D=I?QAhR?>=4-FQk?g&&8s3nhG4kAET zE|9~ao+!KIlesX;3rv)V^0=ouCc$BLkhV?|sN1dtXIMRp$5`644(2~cuS ziA(A^K@-6!H(uUQd8$C7o7ULDg}p=6ydgUBku_Ak)MGfYPE}xR$fCW34u}khaCus+F+Na*1j<@RA8Kp#t#C)W!>(PHCpDyRFODOv zG-0RD*X`70Y&b3Bl@3GkZLHh-x(hZkSg<2|^LA)olkM9F7{51Xy+|u{^<+?k1F#}L zjdx*0btK|a=_Np$Wl@QL5J!L1dIW4XCtI*88nuFTFHlKlMoQuA$`qBpzQ_a}_ipqW|{d|BX+m*`2Aj&P!hMiB|tdstdpQG#Z_1_t*;SKa$0i# z@Az8#cmLzOox|(hwTT>zW;?E@q1VHm_9x$NvClo#%*GtHPenL$Ak_zcYSSjh!Z{9o z$0g{G?&)_7+L61#VlMF0lX%^>q>8DpJI1*mZ$v;zUf$$BTq< z5O^KmYLg!`y&cEx%~3<&N!XH4+?Xdvjrn&FHjF3l_^jS{%AdZWU-Vlf+vyo!dzFW} zU0@C4BKCQ3DXy;8xX|;Vu3{ZM&5mX7d{NIUZUi4g3_uvf+A5$X08R-op#+!{0j0sg zemjg;t9ERkh>`TV0=m?NemXEgHDLTSo0Ylp*D#C}NCSxZgi}4ltZMS%Q49#nT2e*p07w$Jk_KSwwk7MbMeD+K zdRJGMwfDDM8>&rh*otdMlBH92cK{qZFybw2N)cPb*zHMd@*oI;Eq=qZy&LLoLZT^; z-JL)gfCN>6=#7AOVO)qN0+NFFN2dpCP;D(k-v|v-yNS&Ej7vu9Ln3{_TH)%lpjq6oT{NJ=%5pARhuKAG~q_M0hA8xzYb7Jdd%}|{Nv4NxS;d6 z9}B;sDRlAf_X`b)8-KHs^| z#JC`hXr#9LJ0qkB5=uzlc~3G{pvTNq4oSV7{pcre+Q0q#8+PIHkeypP&K&FVzUWCU zTX*)d?d_YhZ$5paaGz;lfO7QMWcuxYi7B;aeW z&e^~Jc+{SIe#Kt9)NT_?9RO$;_eOp0>8C38rLR@&;679YyPE)%)OfX6gCPl8E447F z!Oo9$!lEhSRe{9Io6N_H&ld!S&i$+Pf5q)CX#{2p$K&eXqX^*dXvl2=%pLmSr z?;h_S1!5n^qiXVY{iC#syMWT|>9;!qD5EgM+jBZd^d_EqxCsQ6VAEk+a(ocW-Q~UEj|8rlMWJBpszVjz+uGrwP zSUCft#jl~gF^}!}-^%$;dF*uUR`UFPOdI=J$Hu6>+m%pyACHK*cF@GQ3Tc{dcm-m^ zDx=)dhEf-Rl0c ze5p=n@Wc~1Z8Cr!5l~XG3R=g*ukcrC{X$H@<+$r_Om~Cdaqh?4jeyd^{6YYfR^;U^ zV@>80(%U}0nUeMc_ydA0%`jY&G z*N{%<&J*)+cqV3|`=ryUx}8Je1#^`eGGH9MsR`9t!|x7-s?P*fw&8 zi~P$l@FhddF5L=P+zN1%L2@N+UELfzGDvX%4m8yb2bY#-j^ub}<`ENWCib8T*Wa79 z0>D!aCzdUwZRHu+ne#rN69ho<81o*Wg`=OtXKNjhv`IY`ykTmbRsfSKtJy$9PcMc5 z0+CYSfuwX~do4|@%0M``)ICz&^06YZFaD=F_ih7(lIz`CO@7}x`|ZRhb?1@+ZqXReb7C%S%8v`J^;5rz-13ABnDMkfRctN87c-4N%RR( zC8g_97ZgC@P2`@>Y+J>)&nmW-E?&gz-{~3#r)$_nLM;y4NLMGYk2F`Y9e&+J*Dj zY?|UD3ZCGu&ac?j6~I8%38|vThT81D!)EiSP%G@Q2X-n2Dif2$c!pXsJ0 zyaO)zJkT5vkP;zwoJRPS$BTXzVn5HfJz4})jVnSCM1-)3f9}x>o%0~=m6>+ zpv6nHl{%zAC3*kU9&r_bq6h%}=9`Q5v!71e^UoLUH>Xq;C)G1=Q5w~wvHG4-|&zqb?kyNW8tqiTC2 z`ouJi_w{=hPE}zW@F2JD~JufA(kg?LYapzi1+$ zr1xH9o-yB@>ToO9-f25;rHuD`+So5THpX2*>HXgGTids>=h6nAe<{9xHv&phcaz%N z)vGgX&MyNf)$QMY-Dl^QI~`Ek2cUEnW4IS!=w?@DtX7(~<3mmM!H3)IV;^a^PkpMx zjvdnmGy+OtGpS8-*eGvG;%wg!ZmsE^JcAPA;KKsu^CPS|)IF}{+;ue!j=n*L5p`QG zt9ZIQxxyxU*?#rQMSJ#_cu$&Nbq4Y=jJN)8|H~fx+8<%lLhCyJa(I`@H49Km+9yCs zk_W*UN^)`AL3L}`k8j-F=**2PH}xX|N}FEZmQfqRh7ycJkWlJ(22bRO;htTC0V163 zg!%Hs$_!B}$V7u7`dM&xj#bo}P{V=sy3%GAZcD zu<^0x-WGMA3+}B*zZLbEvh(u%kFI!(>$Xn)3J-*S(V1qmAN1FQuEyZ1Zm3{Mjim~T zqqqihD1+Dnlw?C`aA?2|AC<~m!BwFIex(=_DRhBUC$Cph7tdGKTLfM^YAk#%ev z3A=$0MWs$Qk^~xYk8@p<1dZ;O%Ya!(nXK{**cR%SHCtN1Kr)7gM<w& zYt5pXJ-b{6{8+QmB_7D&WP%RqZbgNyZP9wW>vmwE52M>%cIa5f4jtta2>sOx7*u9x zEiGUG9z)=xV|Z6XQt9+*JPKaIJL=-RO#^6lAeGkNma$Jg;&??{A3kC zsT-BIF8k_dQ})HLr0}$tG6WuxP-1i>x}agLO4>j>yh+~gv|VW+goaG`qaVM&VPmbo z0SPu}$$g(Y92>9cv0arnQQ`d&-fld^RyK}-_{=V#6shy>j&}u6(qb4p)hD{%3H}BQ zjoEUKOFNy%Ywxc4H-0+SCmv&Yjpy;2a)~ySo_XdO2bA=6>wDk(o_*`v-`W6_{N2aq zMxikuzwj>pG}hx?Wb=FfXzUXm8{;mZ^!qn7!iGF-$F~DY9nB+bj`8w#dC^Xu9J3dG zi=o@!w%hrYf_)eXrMXF%@yA`vRwG_u6F^nh#PegN9!02TUdKS4Yjhd{okm+n7Q>L%&ep; zX6k&ouG>$3GG#ybM_f6NW5pE)_mRCVNGKh#r=Q;E9-?wErcJFik7*e~Q2O&tRC)7<-rb+=fYKtISP`S#^71w!l{Yv6NeqM?|7KZtel1RDv{{9B@C)V(5JAjp zR6%ozBK7wU%vzKjbK5hL9ul{#A)w^qv|`}e2Gbm`alheJ@6RcXgGVZh6Lqur!x#ik zijC5x82z5sY43wT1KrcQEiYoqQ+*Mlp66b8D3tF7ge!iTKQb0A?{4mK7D=88su1gd zN{X_dH!(3qzxTPyTcJ>ZnN(WJabyDN0kU(FaTFcY&PWdxC(vjGNs%IRq72YeE@4C& zsiS37*|3id00htkpi~1ql4&EfEx9jX3D8OBFzixybLo%SdGdkhuNE+15BPyZNnMBm z5=0)=sMtm|J_d>80QOi~Hkd+auDxNs_Bz1HA}Ug4fFYzt5H;$?7kUp!L^F)|h5Cc` zdinuW*sw{-{Zg$6h$X-AYP6&(30yPmG{GW=Ys~L7*M^Zq9Kd*Ye>-^sB(-+{3AER( z2~0~Wae1Vfdbr-r^)`V`#GXNbhmkCx5_Ba;^=Aly$dXiZ*YnhcD}YFnEE32Q{>Ide z$C!o22*om&S*;jrl}Z4VGUOpZNdvkDouvLUdigT<*X`h;04NF9azIICso*4R zBWYAtSQW!4_O?h>PY=Zy)8FtI_9T=}iWs*gc2I);6`-Ufl+B3d2az#CqZq41P&@&f zD~s|5SF5bn8OoN#(MiQ0I=BX!tui8^BC=Z8Of#B%l0NTe0B5^^GPV`I_rF&^|lP#p`lKD z=)oqt|Gp-BV1M3@U}LFcux{;xY8U0wh;$ZjpIO<{6R|aqC831PA%LYwhwyIDJ2dHq z%H=SM%f zXdn5+g6$dZ08HxxIx6HA zXK4A-^OK9s`HvR7{-4I66rb~Bm2CfA1?YjX#K|kNLp*ojICS*WUb|{`56P2M(PCgH z=EBk6OS?Hz?Z`2bM2R~`MS@w2XHTd=GVk1bwA(Y@GY-a;ba-zgmGnjN7|#<}(pI!O zz13#{nRj23!}q5Em^rnxP8b+P!v3zA@6PshH66A1Sa&UKtRcYnf#FF(R1ekSmH0Ml z#UtJ`7pB3*-7yAA7IQAYbr}_^sKvs*9Wx&bW{)~p=sZ39EUjnB)YCSsuo~%q@^{z_ zc;O@&OV@XFELkEav)glUNH+Se-@w(hx}&$d;M8Focx9UIzyBfRVHbnyCXhR%IHa4n zzUJTt%pU!82U?21EBn4~~#qLRahtna0=Ph>29bnj` zcEV8agbqk+=RBrWiV06XKf?Iq`Fm9|+SlG(T_-o^d_|Pjl9iUTJ|-gk{Qk@)^Bobs zQm#f0TiU8yzoypA#@ZRaBF@UO0{3cWF-j!0TVaB-8|GK?@7H)sn0^f2xEwtbcpbe6 zI|BA%%B~f8A&jA3h|fVYMnTJC zcT1WvU|b(gxI(wKXJTDOFj06?-x(&~9zC`EjDuvFw8gnwmuWIqAO6Y~FWe`!vl>`i zqt#gJ+}5t%EU=DW%$MLiF@8(XYW_JsceV&6!lr>69htK|an@{{0g+~Bdp?xdh@6pD zoEB0lx*R6*vT@zG_{m3{zVftnh)gG(yc!x}cwMW_@dqMhYAK+30S69wx*+6s2K9jQ zRd4A+rt?!Yi|kLPzAvzc+2;Ugl2(5YHo`{1u>3tA3ZJK}4Bo`i-LudvvHj&-9Z|5# zUiw5bQCm>zyxSW8+l#fB(GV5G`6>I)Z?;0O5Y#>4d*b0!4xD@Mn~l>FA8H9HOI6<# zrbfUVQ~2}>Q8qIKx;*~`c=tYIWWk(;3IE;$DdR7;m$6~uMI$TKu?8CG)YNqVR#)Nr z)f=3Ds|FG@keGsOq<1C_#XwamIOghI)Kk8N<<_l z4pP4>7B0kAoyO2T^#77K<@Q()fiF1)%2$=jXEImymHx=WUA z?@t)6#wVZ&i#wY$epOD3&we@P`EglZS6-M4!%lp4As+WF5_N$5XP2S!)8+HiOQX=8@3k2J+ zwwJW%4x9JV{IeT5Or6zCJ$E#%T(l*AQQ{YNpeHr(?IoW+q<9{z4D#_8bWIs ziw(ugk;KbYvhUfz3+Ka}f4Lei)3T&u(HD&s0(VcF85tvW`Hc|cd2;xFKMnrH+3VEO zwTQfKd>`ZaK7;V>+EkMN+D7TLd^Mj4o z-L8L4Q`<)b!dw~BPt8#Xy8oKG7sL1~`69VC&PSUi_SzFLh1(iAfAc;3PuybXVkqcug0i9Fr<%lUq~&x#2cYG zBv|RBVd0*gIUMWjI(iT_1z}StS7$Zr4|K-U;(-uVrNaYFaVl~qXyRE5vepL3iqNuzg=*l-bcq<$vjWOytc7C=thpQOFovcH z-@>C@q|sR8`2;>QR@JjIJeXzM!MT|Ah(HKU4U?RiOgH4PDfm$ERHHb@jp09o!l({# zZ|Sv$$b=hm5rk>90hsUzwfS#6ef7ibI%VGro zLKb`DTyt0p70qEtA3F=qaNFQwU1nK2DtAtX=Hd;Ko_$CXk+zVVjQea^)J{W|?M8d+ z;A31te%v$1fVwJ2snm4vG$P~!L@t`Xq2+E=Z-$NFeDaQ(LXmx4%O*}j=u+&tey(K& z{qCYA#5W5lJ72v+M9N}$b|f)snciR3-1BcEy60xTGe=aTA^C9pa-B$s>zdf39-zl* z1c-utAly4y9iSrFj9**`N)dTe9TgRKEE3z-l&vw2$Q76D=2JjNsJ!qY=vZmXa+Lk) z95kOGKX2i>X@^kz?b^bbyC7}(Qx2<1p??_@L|)@zFR;(H&g3IC3*V={yY*mO2|bm# z>eV8Qj~n#w`D3ED6=o!BCZDA)66S*B2HL7IQ@UWlQPI_lQW{Qw7Q*~Ts(T_UH|mUa zn<&II8q;Sb_^1kpT|_!8O&)I=MNm}T|E*Gvo@E2sdB)%&%t<8)wC{`AXaL(ND| zj%Qh82b=6B$`O2k5*+&Fb3XbkCv@ZzS()|3<_R+{paI%~1(>Km!?gMCG>@?P{c5Y{ zVU_0GOK!5C5?)*mTV5@AnD2>ovd+kCl_(nMtpdkXSoa*nfyGrh-QD_Rt|^I`plQ*z z#ZaJWDDxb=x|lTb_GvlyN$uy`%MRm;>KUG+isowbCG_k{)({`qJZ({n%ougx z&R57h)GRjIAC&#B9v`Mw~)@!Y#RNg z$3W7eev5OU(x22V{PbAtxHMHlm|%W=m~(tc1wu2rVFbckj_a$<%fX}?+FPLcexfZ7 zQ)Mv-AIQy;6@=XzbRI(z?JPn&jv)u(CEO%jpW+o?9@r=V<&B*N6Hq`vuPa%?J~J>hWI zK4lb>uwOWZJIVG>Xb?INq2Y)hGo>~&uYo#m=y^8!=W-ZfPZNicIQJCCcJDC3@C*a5 zAo=JE0ZC3I~LdB%&g-y>FY8S8glglpiIz2NnI!2NrKf@C<0ifW*}k8SNB7{Qvtjk zEg{rzLF$nODu4r_*dCk$O_S;qw&S|*E%GYLaF+Oq5M-Td(Nw10a^T zE=FL4+d_5*vH8(<6|u!sc}broUbK~{XcI@~m!#ab&OcX6Iis>2pV9XtM5;{qH|pp^ zAnwh^o9uDhm>1t4T4dUhdhIGi?lNujPl_g^zwBCZh1_}NovDL_9v z*`MQHYtr!LXi!k$^0Cx@#w$_nA25C1wyZ&Xrpi}5$Dy?&fJ_tTC&9|c)OnwgC@U?U zrRrFp*@$&n(i^j^4Qqy_2yf7P$4S=*Jws&kR{JxT6)XsJ7sn65MR9#xgerwb7$ zSAv%>)quW334N*$NFT-R96vhLbvIbgzWPkRJ<-$pVr9#V>getDJ`6|uU*9r6JX#n% z^h*KcbChbe8RZlx_C&$v?_M~%d5d%|lvd#u?M*{FUP7n^WZ2zetUSGSJGIgr=N{|l zF!C<49lnPF(7CIo;gX^`g7QM1Ve8}4w&0d8jH=Hm({@gm>*rAm!${)UJ)Wh{P{ zqIpz_G_>K7$TJFY1x(B+8ln6^j2TH6>l%Ze3K7qD5rt}cc)o?gX8VFthUdUOp-xPp zQEDG$8iTsCvj^Kb?pYUF{~Z8mfeI+=)v0Pv%thPDqe9B1j5f2ch2iTYfK3IRv%8X& zhP6gh*}rE^i1FtwbpaJS&_q4pql-8%haW^v;LN{$l0>oXOcCkm`V8krwW8nm=`A}s zTyO^^ANR0V=ermmEQ8!1JxKUyL~r4{vZR!+@H@+%1VkMR;DVz%&*#Sxf5H;hFOCw4 ziPP~F$?kDJ?`~tJqSc7j*Jktk&oz(B8s&RppL4!k91{9`BWw+3JnM$Py|MJ?a!QrmDyE$zG)wT4fwqo7{G{J6X0M+m3?L*+DC z8>8YY_5p0`aNIc4YW&4sk{EH$tm3TI1K+wqER=hmX@w47o;RA?09k5nDN8toXW_uP zs`!Jk7@GlQ#>tTT2o)qVF^(A9mnmdTr6;{&7Tc&xcXHKFV2^w~%`}GD*;4+s!UGe} zEx}D4@0He^Ycvq!-hHhBRzTBnp%u}9#UFQRN3${Uq}?5#{%mjwxr<-WjOeVpWa?|{ zVehNQ5$s=sv0gK{0zoGj^Ar&L5p%NC#!jP7)s}BM1%Kyb zVhL=3Wk>usiD!tDa?J{E>T|az?%swYnB4vw3ouA({k=*gzoe-k@;T0TBzzZ2T;$nV zJ~fOx4m3lnqicB*g18iB#feouY4{+cr0$8G5~(B70bWI?#eVCv$&qhhW;3Z{0B=h8 z^-XDmObT~&Oq&fL*|O9ycRbWHVizQrZwYaoGhBSe?pb*vUSfWiu@7G{i-$@j)v zf`juvYca3Zn#RI703106?+?%ruGiaU77J}@7lWlvXk0%BB&2x1Q$6Q?Vnil9z z*+j1i2Re7H%(AUl;T&x-Qry@AYmWQle!jjSTp>m5URd01_%jN*ft+L?Y>vf#;>^0j zOxR|H%SK<*zR03u`d&t{!eln*hQ57CRXk9}F-~Xq%K9fb>!M-&2N_b=KHF1wr5}$k*kIqU*_(u zBYCV{?&-e{y~g=uJ*M*W?{Tnx`j5zwuR?)HeBAfw%bCIdY{A_y+fj%r&AxuiZ&iGe9PQowBGyQAX}ni0nP z@YzzbM`X@Cf;X7~5gw87bi=U?&HFmCqryL7E4KQmz_;NlFyr)kuW?4itJK4Nne177 zZ|7Je;r>i(zA$3`A2uIXfz^MQV|zbzK`Q0qk5fE{d;*ocC~YtdjQ-!>-#%u4NNqXZ zcS4q9CfeWD^!9ZD$eY)i9&|6AWUmqgA)Hk8>+-PE+vg*0ZFC1VL9nNaqLHb{Ur|d} z5FPhMMu$OP&{f^xP;V7Adq;all@plCf9@o)COF)q{=nf<#qdEc=#?j{3#~+2#VP9h z>BIjnsK_AM)Y5(^<5@bd+9`VoSm6#srX$W-hNw!&fyE>74BZq^zSq7${I| zGfr6G*;Q~Ru}*;^hXi2M;_u(VUEz& z0Vh$>ZY3-?hfMkNVSL}bLYdbI`}g^eDl`>WR0TF8rjrJ8gUMDA^WhkL{(zgvL^gw2 zsz_V2?ZM2~aS+3#qn}yo>30Qf8culrB}qi$IxR9MUtoe3bp$Zw)C|qc?bl|$=j@X8 z+V^>t;>A09ACNdn2D6X&LWR{TWS8}9{+(mwFRI_jd@%789HpO#$9oiskxPDH|1#&K zt$`TTqa&s$=Nh*i2KLyCJ+8p1${VYi_*I*mJUK3r%f7zu$_gevPDwg|CdM^S#bx&7 z9P%N(AnqID*uK5joiU5Om*?|!iUsGgEvVSiBc;ppVobC*mH3os1PV^tcCN zZIl0JXR(#R#ddz^pv6b|N5oCwp&>5T6*@&l2wr<=ruLM^!$0hpV`iL`TUKwt{aE2| z=$JdaK6~oyc}6kOH(}aPsH+Ar5E)Mi0#dThaepmj*RoO-%TM^r+!Uv|odjgix>pYO}keqg=WA zCK$qS4buqgJ=0&cQ;yxk|m6T&WZ17fJL% z?Le_#OPC462nKgZ1iV$}hg7Gg08_ag(3_N85oS5;44M zH7NaG@2Em~9oKvmcTg^NMl*W8>WFb#2(vk%e~g@~JkRn@aaHn1cUAv?8UKu6V-h(Y zv9YC?0obN^yh2fe#G?`43>WT6U$f~0IkI2`)BY&?H(GP4Kj~HflJTFmR`bpt8QNij zKs2qZdm&hk0J<|$cso2fdE1zDvy^P7nz%BVGx7;`7oijJbNIy?eL;Y)kJ|Jg>l}OS z0;1ZKq*EzNUgO9Gw4<73HKo61X2C~Qy0r#7 zyQbX>31M~jb*hZbM5-IdF%f}ESt-bRNQhnxXs-e-wH{`)s)SeDAggJgZ@W3O$>uCJ zQ_lCR^<*x;&zz{&8D%9OSm)Ok%M=HTg&K=jV{)Ytmg(Ug{BK%=cE9O^$O@6yw7&O* z7BZs73s|G&U}95vb~`e;^huvwBr;XnDTc}w?sw!9dhad+X~~L6{|-B0F(y`6b(UEi zGT|hjJk4O}B_|_WTEvc6>YzyD*24+q3Oz|EqpcUxQ)I^pk4YWqy*5d?o0Qm$(zjnx zgXZ40tjNryCvY0!NCX6J3Nw`xAE+)i^j(a>4jDmxU9x; zFAUJIwAz>?$6LEg6V3WneF74DKPQ@fbJMCnOf~y%Il&il;*7ty=av=k$wZtcA)g$r zo#9y+J?d82TB3m==?OE4^N?9+@?D2&WcnZ4X{J5t-b2~APHI_of=5#fe;GFd6W}>X zJ1f_K)?CA35@3|b+o|19RfJcZhM&Nn(;|1KT!U;BR2Aa%EJcXnv*(ti> z=UlO|r844CQ6Kvg9``Xy&yUMEAC4>pe1E->La^N}&LZE4$Lvy>dE|9U?(ChP7REgt zJFa~_uy>aD7S1wS6Fs2nPq~Mx<}sZVn=zHih$5`gaV~9*4)6nh4nM-RLVQ?O=4}pVCK05dbl*zoni#=QNB!XnjF^2$ zCp4CRo~%(msfl%1#{#t;V-#`1hO97MZZo(SH@spK`5LWRo@pTi8QY2^g#HwqkqkY2 zY2ArHzs}3R36ftgubSy(^~R~Ib2(`7UO_N828o2MV>~g>C|f%Hvq$g3D|+Ay{L9oz zOIO|1LB?3(?ECyR;%rKVY>?ey9pP_-*&)r>jO5^?K{3t^;v^q?jM_MLlQ5fBx~{dR z$1@M8c1k|_l1E(5U(GWC0e`cEU@=k7#`$<7?ydb< zO&Z*3QS|XOsTkmX9k&g}l?gVv<@QOSVE-PB7F--oc&6$BNV$@v)uLvVLy?%5CwAbx zi5dEI)_ui2qRC;(l769ecDcx*X%rHLi~MUJ_Ud0m)BGE0~%C$@SG2*r%*UgQ>hV zrOc5@%)E~-M;o)N@uG_H%}Er&2C`i9kxqm#GDZlv9c75t#9cB-JKisUj2wvBkBKif z*p&L~*;X8hkYll}Cc8G7%C$0EKafgX$2J~T7ga=aE0d`hobz(8y7;QGtG(ve$|FCUkNej{8gvrN0;bpl`gi~(#0W_a5C{IK z+aptUnK_Zj?YU0se$rPS0uY0Dq<1$T&ep z_|Lt&z$!GX6eZ1?u6DjKcQdt1L2+aUl>DiqtW8>&hUHfh7@ zR*l9-MknE8@PEX|u6j`%@<5}-gGTVG33v0WR!t^v?as6B)%JC{Cas4u-Yym&x93@S zBR~CS=WQ2#)Lj>Srv=af3X~7@5G!5uP+tyJjp8Me)E-MM@=TrYd^IHHAlTfctR_Cx zRw{wHe&n;zwomSY8@eO)*K*?UEy%2p90QMsmO7Yb2W#rpUwG8>e!5wt)TuZp;1W7f zN%i>BC_yP=MNO_+H}q385taU{(flit=K%#T34)OUqIg#-d*S$%l#%~XOmbT)-D2lt zl@O|e@GZx2k=1I6y6tJv_Jes5?^wv~XN`<$F69*Y9Ma?QrucK)%WB5hyTzO>@5j1h z#{@a4ZA(G!N9RbJv){qR$g3IJ>8jpRlE|rT5tdTWUpOBKm-87#VG*AX+A18W^!bsD zxA$#+chcws3CTJDeB|PVQz_HQXuV^GW^~mWX{C;2=Q_>ez;LBu4$?{I)E>mVI~54?OU@IbXx1TkY7JAO>DWy7 z88Zmwe^31*0?W`N?LSmAMWq0^-!hu6hY>=#p+k&v=~O#uvKz2Co8M&y3;r?JlYT3hvO zDw>-bN?w{kPE0n^^5j=Ppdsm37TT%Tp&QI|CazpXc93!huK!pl$;Hj6;n0bqYJr#`v_52KZNrZ+ib{(&W|tsA!z zB1*XQUR-6C-yLovawUGGjCEI6m|No8Ee5y!8JUMaCdp#jH^3}4fCW}uLd;gDP_%@4 zbnaTQ^lMOf(=d@-kz8ezYhy3MYH{SJ6{rp@$%iSQJl*1|Ly)uD&oHnnTd4YjUE{%l z_Tqtle%@lG{PwKK>*lGnd!jo@{LNk0vuK!t-I+RCfjm+NTmVX_z4U%9ysw0QJZZ$; zPnLSQqK`z5z4#pM1v;y;(V|)D0a1M@f*O%ypGyset1?X5zZ>F?2#<^|O@B37>6U+% zWE5t6qK|*f%E3K!lXDi(9bcyo+2?r%lYdy!fk}@BG+XT9b$P%uZeP1+=feH#(r)3> z`7y)QnyyM=VCIZB{}miF4P4&`YJVWSwmvgY=HYUM;t=(z~*e% z5yQ_A1y0S$AUBAdd%t0TlXdM*s7x=7;nVBCjmO>qA(Ub0^{=h!=HdUt4h;}ebQP%y zJ7zv8{(FaN7aVrp-~M|4{jnbSv>?{v;&+?fjq!!NM_DwJ#GZhl*vqlqz3%P5HT&Gx z|91;-<;o0E{~Hi>_ydBk{Rtx`7rE1Iyci9mCR zH{us^ap@JbuIn>yOP}>vck3|yOGPdQX)E|SLe$mG{cRGF`kGMrZPEtuylY3q6k~gK z#g(wvdJ)w4936WeF`XY9U|K&knzHbBZicS?P zyI|9s#@pRYl1ZZ?;|_C6NU<&qwf@y@3PFg9eb!g+r-U^;ZdsOu(rgeA9-pSl;fg<*BUP7gWNeDu-ePiI+vibA@_$0bQY|ejg0Cpm zo~$is)oOx8RCN_vba;g=U!;m%+y+Jl5%7)R14u>)L16^~M<dZURm>;`Ddlp| z#ImN*3bN?MlHHA;j9A$9u!tNXl|M+UtCJcb`xJsq7%&LF+lCICydY6<2`Dq0wd z<-n`r=fh?yj345Wi1Q0Y&z5aQFT%qP@k3h>~@;VuLJOq6I%8m79%EbfD95E$A< z8{qnzLva^`A)BE7Om}#`jmh;J=F#f!86La@f^Kx5lvI ziWdA8c%P}_ZQA|t4fqGKII93)fQ%Cvx)(R!65ty<(suU91_f_WctYy{jvgX5^D}sE zJ*G@xxkj>TU7_nSy@+h`!#2zu>~YC=P)17II^lXa0Wdh0Fq_GJI}_=H2JPskM;mC zh8?<1Q^O6%R=Fchq&`*OZZgL8JqWKn0!>Ea$j=&zB79UOrq-@yZ+=K?$^ma1=X7{e z|Kw<7;k#9{D(CHb^Y#cpR=Ll&vQM@}22Hb6iD%IR=Eb3Fl z+nO#rK`8ZDJ{!3WHQE6Tc0TZ+Ui3uV_om(y>_<#k;06Y3wO^(SP>%e%l5|iA; zEbKu7@-(%JMv?1XR#blseLi(=ZzTV_ z^J?bmxfrQxh<7Qu`2RD-Vd&7ck!)uc{VjPONtNl={W{Yo*EQu!K)`nI-=530w%%8k zclknK6<_8dfyuTd@$G8v`^8gEnfU)PFS{MS{Ekaot@qw$(D}O5mTMNr3nTB4N^WT4 zx$)Gb;c*kI@NhuF=zG423Bfi|PRA!}vkdAgi) z@Tr^WXX22n=4io%8TZAbWpOC&J&GjDH5M*Cmoq~|v!g^r4<2Kes|D964x%Polmlb2 z$2hoSo@aimqqKCv$Z9%_HgIt@L52~WDARP*ep0{VgCbFs9G3OQ^@J)NbGEz}?JJkp z!t6<~$)cUWQgYOlWo>KEF9wWaAH=B;vKq|_xjM3{Y$rUXWmM_QlL=`G_@2=G$w*-U z@;^OK%aaAp5bXqruJJlc z&N8DEHl-Pz+lUeo0dohb+!a2oqG9SW*ly3sxPXrDBPE9{?>hFVrS zfGT4dh)IT>!p4ov7Q@h!`OQ9a`4FB{oM@t@szP%2o%;q@3}M&zg)lHiVpN0KqAAtW z5?;l=3NolOvDfmA*#q9aQ+vCN4B`_)cyV#bu==y8#^aA@+!!G9Vkn!6Hw%;Vwqv&{ zu}xrcd6#WxX9DSg*fbdw10e)vr5}E+W^;dmzbrPnD%ksT4D>a_#p2dk32j}27g`o@ zj^Ea4nhgvX7QMcfXq#HXsBcH0tY%mm6GrDN9`!*qP z#?MWA1r4*mx!O<})Z7KEDsFz-`kxzt8G2?9j-W&_grg>?6cdVKJgju`Ul${d77nj$$TYA=T7&gbcS5?ub8Vyh@MuuVW@>jqi7P&+LN}D=vh56^39z zyQ)xibDg2K*w|FNNB=Hk@s0nmYGa;ZLV4o%{pn>?R4N*+H+AwlP!UA(7xzKQ*cZBD zdw)b2?HD`XRGqPRejN zDh*h_yv+#)2Vrey&v40cznR7gUfU$PBdi=F-=O;ZqFEbj`8!h{qk zSVWiS0zcNsX(4|;X7c!A4TOWkhn~Q+Fn&oc|yGdpG~v8$A^wvcy_I7h+br_R&E;GZR*D!&^`C=nIqPtGG1}5 zgX-g9+KX5E`q9=Nu#U6}9aDGs5+t@1u^G#i2Ch(0=SJ1%H3t?*)rnj*&+ka^gxr0$ zp<7?*3+!L?DPsYe8|DJVjU;2F%u(;6tQvGecaK6KdM`dYYBocx^V?V?>kDCbA5Ju3 z%Ny0SP0ALJVVanvhNmI;M3Xvmg8NB^5L!J@ovF)frzfU(7J!64TAViU(=8~I8S=>i z98itT1@P2ErKnI6^#FP721S4me|Ue{?+h6&SUgcJsN%Xf0RY`!N9!Ad#j1o2C*`b| zZ4J%4Nsto>L928GXT;H>`;3CLbq;a{7J{)1u@&qjcj>M(`a!LQHC&`=KpxzI3BY?n zyak6PU4Be`J!LpWOZ9CPVQOwul|>UTkC^QD)CmS_@N&tvsx_$PWK259jx)0MI?W8g zcu>!iI(FpKBzz7e#WDas&CRSM^+4i9j8@GgrS0DXx<7r{3~_yM2H7`8GFsg?sGVyn zc1rj02)kWiJx`Jtq0s!>j@U*$`9rDx5vBhJt)#orEe^6U=r8WRUflOjyz#w#*JFbj zkime1z`Leh?oDv6lDb_D5~k9Z0StK@pHH`Kp+E1XkNjM5rB(pdF1^W^kuv#zc>6dL~xq_Av$FoB(jf78Q z-25_Aw_f_660qXK+=cwf#g9j#Uw=_3JbYW>p@(&9RbZGvPl0VA@n;mQlr*jY&x@Nm zS5Vnc#hJa_tNw|TyWIcg>VhB7w~_Y0YIx0y2Vs|1)~;h`3i#jrkz;LB0uPz<%-gQw zj5AYSeqAU#G=HHBED|?O(v0hNkxT?j(v(j6-^#Aa} zwSe}b5~m%=$RNofqpzzsOlEHGKo=V7Z{ZWCVJ`Z*dI?dh!yhIo|^e<&w0&5Y8lGIxl5awV)KMi{Gk~&C%cy&VOT%@@pP~kY>fDx^IPZ1RxQDt zJJDG9&SQC@CzGgg-&?M(Xa*aAwk2v=5=>|qvu~WRy8umB{V=Q2bZp#+)1Dw2dYYHG z9q{tNCwOkKbKG3Znn7*FBsI%kHc$Iy6#N6rBnM|Z3=ZTvQxIf#^DV&PP@cZ+-!GGT z61D`2t$g94^fuEJ1LJK@UYH>cxA-wPhc}Kssv% z1Q8ZW@MfdD>Wh19V3KmMxG`%ivOOynE|T3~m#jLyImS?5!q;(T7$m{u;(kGOdQM{_ zc-#b^Y-p|m_UO^nFp*}PrKSF;k2l%PKKev6iboVcu<{-sRgteCD-;)7@!;+(T4}br zJvz(GMAqJ{2~5fYT-Vg1=nvAG3*&@ur6HS-PKi8gtNvmfq*hzBO(%!FB>0UbKdzM4 z5s_uLR+z9S4Gyfs*Xn3`WfY894@w_8z<7GhH#c?PJFX%TVkPr3at!IX1b~x5qZ~Cp zEGBF~jZoGNU=ext#&VVWU#|9Ea9vD4mb}-FGxepY?cjNYH7h5p0MlLr#8c}(_~+5f zPZg=7TRzG$i6hH_rc(zeWZvWKmj#g}EP z{}-t;`zGe^V@>A~)|k}Y#*lSS${_8XuIwvQWh_iQob%0YMgZ#1+drPw^~ITV^(M3! z7C0Kx@gto6ky@X1dMsnuSgnqSgw<7GY(5obvHUW3?hVza{;lS4XA#vo`5_CGnf23- zc}}jeg2q>#0~e41XFh4IN-?kKUk-k_tELV@&`cdO#)*v5{Jl9Yw5J7-|FEa3mZX&Q zISD6%F2?ULL2@d|1R;TiTP9Zi=nuDP4K7yBmqNbq;Y2u;AnkI8b{44zPTRW7JleXC zNRAnoSu2HBunmhY<#6_-PH?YxGrQ%Yut$0 zX*XuvF4zAwUI@)muw2lDnT7xK6I;<}wEK9sPCqRE?+m8m_P<8N|7NiD2eb^76@(eS z{bwRV7CEXPGc)U(A5EIZHXbXtoLzc7CXD@$mAc$gm0YjOrx(MkaYloCs#rA3uK2l~ zh6r_u&ZNRlxs)DcO=j2qWt-R$%CG9}mUD&Arq;kO2%_x*aYFaHEnb>Snr$1{t(HDt z1uBnnqT^TU`sl-k$tMQgFF<_GCA?h$GrmMrD(PoMEny9R5e||F<5{MU19<`cRn<{R4Z2}eNozhV# z`%ZzhAXHM-lQQ%e^uo)Fk%S|GS34wP8DqR!mma+3j2y=Ggn_iYNjVE?S@;J3q&I9D zdUW0xx~(WG_Up!o1xn5Vy#!sPieXW~$fm@)6Q*#wX1R_uvxn%<26!1Kqm*`qM2@A3 zG?Z?~=F_a0^ko8wj*LMcm*kt+^}Se{oSC&YoQNUTF}ivKzvR8s=pxyXhnQP1h%|#a z!t1j~+D{TUXAx0&cM*DNzu9oa+3^orlkY5i`&<5&b-oh!VMlyjGo&}KP=;MB(9-!&(}51ZQx9j&H?{KL&X5b z@K9y8$8pa`_l&NJc-xPb)^Bi!(f31LE0j_~KkSI;ypiXCrcNQwcN(=Lapzk$W9S!6 z7@{dH80L_-UvHEx)b2!b<46osdsIKrq%@wsqh5g|dM@l^Me#vlrCRbyHedo^XmK&q z9%>_mBvIXh#as6rHWC}Dh$(9GMxRcI3)x%5EWh~%?VS_kk#FCGO*Nar#*@^EXRD_; zpysZbU;a01b@er}n(UJk z8q7y#!e?V?_^${{?RJnELO6yRs#MN6%jq?)7@N_yV8zFnqDgLfL;cJll3yRO-3j>- z9q+8mB>X{W9z~E_;MBdYSih?5LU2o4;lb)WY~B8)RS(%Z zRS(a4;-yhlgc~+kREQWXz8v7zm4~)NC$@PbBZxhWPs^lSG`KQ0-I~k88(whHYm9+Y z7NKGK4&cyV6rUw>SHIS<$0+2*u-cqtRK@6k`2CCk`O}AB zP|BO#R=^vA+fPf2*bO38^)5a-9Ky2$(yQJ-X`PEZY%{)aoJM~=o2rItra#sx_^_F* zuI4#?bmUvfI{&u}g`=--zIA0jWqVYjZBTPyF8TIGy zaE;63lFnLoK3{^`nk;j^w8FZY`cpfbiM+`UP=ac*L5opuOcXXj*p%2S0m4K$|Bz?b zQ1_}f)0Zo+CBr(^VuiXPgU1vuv#~!N3!-1|atYrMac;Hj)%y_}Q1O^kiCJe7=wc&2 zVXFLVC_%jf>H;;c?|XA0IKK?!u=8iviQf6Ap6>se?RA-Gk0q?zn;FaBst}xljaugM z>c>&HM=gwSuLgCW%757gPsUDOTkP@K`A3j{Mb7rv(!nxsrpa$^Z%2jg2*#C2^FiC7 zyjUMekrAIDO3ctHc92pFkPGZ~e2sE#I)fG>3mOr;a5vWbGl#xLXkt8QesImJmm(!U&@-w!VAs>D_PY& z2TJ&v*tU{XgMsPX@!h`g&vwo*E~=LwAEy6=Das`6Q_0tEp5i&u+Bpu8Y6Hxz35&SO zk7A8;8y(W=69eoHI+RD@YiBr~h2zL_t5ze3@D zi@Jztw!JkAIm@T^0kmC2vN5jx!9DE#N#!Tv*fg=tk&`u2=^rn~xmHhq@~6aB5)MAj z5k~Gw>EII5H&ZFyxuQ9Nl(a_>6xoYwr~bgB@t71gM_*cvi}pv5gbaU;v6wH}@)AES zEQ}vlwFUp?nOjxWRHdHQs<9KM2ZdCJe8LvPj$-O7-!yMPM>zcym8ybG99V@K6eowt zPv;}|s$r^b8^KieMBT|aiVDXrr-ZenBwoZbDjaOZs&@DgQyvLgfMbePsb25kVqU$F zRIi>3&I0WbP+FMjVLO=lrF*x>=y28(#R)k2QaQ=yN>|vJGuu`~_E3t)KXJPC!}}9s zHfQ?qT4@_DG37bPd_h2_eb#OD%OYa)?uL_}ucdcYitqW#$Ga7-GZ4ICGgtvTMmKW{ zU{U{h1{}9#ONjfrhB0}qH6)?AzUN?3jOWi_*UZGUiRXx8Cz5zx^Z&4QR#9<<+m8uS0xoZm!s zBM$=N(<9&@+bbMy;au|?v9Y(7%c05@!AYLaXa|fwp(>p`GDHP2=(fOUX{f1~>Q!@9 z<0@hL*mc9#yT57ttup4f#3eFrFNdUOTPzT(<+$~j1*)t1%dQQcURR?#gT@j)%0 z#6o!b=cH+GvT3=+D_frn#>KUe@8gOc>STc(nET7Uu`nJ+a*R-9T5CrKb1{^0&RD@^3FnsLH8`6n+))LPTqQ+-SyfP;yoYI zA|_&U`nr_3^?J>9HtSp>o#c7>>w^^GIL)@-<=1_U<4w0C-ZJm@fv52$o0|TQ1lutV zVMgaA+4+N6H|(Z5m}k&ZfRneHtJ>ZBpYJ38Hw1L%Z?Xo#3V5<7R>Sm(aRu6bhuSxX zT9s!fv>yM+1=#w%?&70b31v+_JJgCQ*;RZnjg7h{;_n;dP|sVQ(NE#j7{PNUldHc& z+Bxu?e^2RUS^S+8$=9PWvPJYdE@}D_75=B~O-tLeQlbTVQru-`f($At=^Pvnk*tkg&Dxy9YR)Y?{I<_ydrg0mpk?&O3Thceh-jkD@1K zs?+_mGSES?I@0?KlrqOmo;fLwe{D?6#X&On8a9x6LszM7p8O|V@yr3r$0uPe+n3JqwVOSw(MRdUFbxMP zx6yLd25;Zl*Ax1-#-4rhMzS-m8*5+VF)>LiW~@bp$&AScs!qS^uKLBHUQR#i|HVG67PJVLHkb z{N^zX>hm=Z=6BMxU>^wjIxeR_Qh$e>@UwgX3zlAcE0w9eE7?xTWAsU=3$nG9NFoZh zj!3xQ%BewPsBA{Nv%sz(+j$L;n_7Rp-kSn>PyZ3y>Sa^hz^U zrRe&@CBNxnMS?r$(dL7@h?_={CF0a3OTZWtM^SYvOGorMH8@|2F(fci?X_kW;q4z4 zR|n+Y0+O~Nt~03%>f%n;O^>)Sk*0s*NAtM0PZmb~8}@7fV(fuV%kPuuc|ZXc2{fe1 z6x2z+RXU;`dkMcn$=J}N7~iEY>AQ)$#9@amN+pOEh_7{z?w84d!dQAegQ(Y;KCM1OQA7aL>Q6i@`7H)QYzJC->{5UN0F6mG z4y0)mQ$Nsm!5P~<548l&GfgX-a)OUQF&~Y$6@8-nyGy(eA62n)gzyf$z?nJxqphbA3;<}x=9r@XHMhwl8Qc! zWJu;Y0>#PQn|RQ4mk|#^eq2B`%JsO^{thfWc-%gjQbLC`RPk#c)>6ghV>~X zHBezKy#3!hgZoyLL!6LGdmNy9|Q0L7=E@C|ue} z53?Yh*vl5+J|+6x@nK&*{O)%F{=P_FoR;xDMXtdJf!?Rr<9SC2%H8U8;8o6k>@*b?spJ(D=O%qmg4yRQKkUJuH=9Hr}1&OMqyhJEY=zAtg> zmVJ`QgCA~u%A44261dcDZq@jPjq`|x<`4O1dh=H$ei*#GI=!>QheprgopRqSMtB|f zc=}%+>i>Gfx|Zm?sx0$LpNd95u1Z>RzRa)VOy@AH+9q(}d**~5or00+MPI6KKV4Jv($#AeqzQ4ljVd0*&;09LKU&nlwsYti`O^J8 zK-)uFDZG%gER1uX*^d}$=VAYZ>F!{YtgY|yb8OD_-)=eo<5~3QT{^+j5VDu|WxsPe z`Q($S>ym2b8UuR)ebXQU05v=;A}j7sXn^hb-g+kF)y4jy$kg7`+RM6a+nd@MDH#AY z5oFGe%tai3Y+KXiZe?YqQ_?+s@8kVd$J4{>_7jzF;syj4la!P-*U$Uuc?cW3-8#2l zuW{bT6bF!M*aElx5fW#l#W`WwqUHt4mc+EPM?w0%J&lqk{AytlJYQhpG56#AKLV=j z@Tt+|oHY~$sp1kxJYf}5#|$*IaqC4OFZf1}})T!4^#$;dP4SOK1DFnOe3G*d-Za+!T_s zjmM~<&v6s%UiIU_nYxL!!DQ4Y{2DMt{vB-O0zdL2`d|wE(3h^@49793I=BRR5%E)- zFuSS8a%Xb`c3Q33j)5@W7B=M+ zCplODv^5uGl9&r}_Hi0%gJ9b`h7YI4Bo=E;2(~kRe9w~8oL5^P2fvuZ?@X4r{9AA( z2y(>D64Wl<0nLcl?!!s!0#uM6(T?l3db9a;T8%V|%9)ivD!>2Sk#75+lk=LXSr_}y;ze99<3qGOl0I6FzF6;Y1jN>86#r6o7E&tWUVq(_Fy z*Oi7T6oZs=O%oX>SXOs7x^9N_7bDUOtV?C7S!;C9N!r>K*kDC#p-AtLH)zAa?%sM3 z32uB|VRX^s?X$$N{$6WyFg;yBs5AU<#T?#ThGmMHCFaB>YeCJAOt|BrmJedYQj#Vp zVqI{=^}4TOvTq&i)+bjmb=K5S7w%%V9M%D#@HNBDd0#c`_5O-MrmVLkF==Yb02&uomPlX;J(IS1#nGoQ1<-bI;!NG zw{PMx34FM0pa2US6hjXErSQkRf@&~QgoA4DNhBBD*y7KCKIXAT)@8=pczXKEAhn_yGgK48OBQ(GJefptW zOt?A15&gTCl$g7TIh4DwGF5PsYEJX$axfaDZTra6<6DP^-`+yy>z;|#>0hsclvQ~< zaGjV=)8><1&StBb-*$y7b*hx^6S~i->?YAHT;M z(fnpfXi>oOHvV~Y#TZ#0<{_)-`BTfu2g`V0dKc4xba-Zc;*{B*MQo9S`Wzf_cZIh( z>s@TvQsm_{bWB=oL8jI@VDmQ$FTu6GtIi@b`fydP6NZ8;f0w^i&~sQc{|11z9btRC z81O57YX_r=gtzP|`b*oR&uOt~>hr{}${YcM0sMPPSJH(@M?lFW*A~6?X$PIkN}c~@ zYQSX&=0^+0HNIQ;?*dWnQPRb>9SE&Z$U-kNospQJh?nTyc&KxC%|@ug%FsP*iCln0 zY&br~6MA_vW<4|&ox|=a0?%{b+d0qkI2jIP2$a39m(@0m!2_9%$h>PY5whvKbyfjv zp*H?b7leyVD1rg-`?IL>M3}OcOAg{70OnSlLT$1y1kFF0M^Z1YKqi#`WJHf@iC-zu z4oT#WTN)HKhmWCTPp#-Du^men8}F7JB|kR>0DPI^>6J^r9JQe-ejp2dy}Ag@SAWY-@eKU;QV>GFni zvGG8vQ&hyCfp2Hh9fgsmuqDV6vtRgvs(@jDyYB=8(_vp;RFhvz>%m{A^0vI*m5jLV zWXKXC@0! zS8Pf1bhFn(9jYl3@CFZ%-VD(3E}4U228gaAgx@Hm08+0g75~bw8BIYlHU0RUc}Gpf zXHGDw< z&O z+mrHCqgXpb{eh;ZVDQ@7;tr68hC9j_Le*V%QXGoalHUGO9jZs_RhYU};aUoi& z_DAGQC&@fT+;{$94D3|NNtZ6r=hAAcTU+1Rk(o^~*&NF~7hUDHck!K04g5pX*W4Q> zRabZvv*6WM63on4tSI+jW`a06is|qi8z(oGATaF51v`>CImNNL?*N_tW5@4q1|hbe zY={?|u|Ok@2-^M13lmktO>!228`X~U6I3dSeS0!A#Q*h%xUlSN&3@%!RbR5Z1kJ(^ z8r5yXckYDzhW>8aASY}g`$i7h6{yg<8Vvmg;ZQ;rc#tCQb9x)-?#kXr$j=OI)q#&A z5`CSkD@qQD0?r0Z-*iLmxUWAs;~dH-9`tjtDOIN>*r+*bf=0;o!(Ali4$k%MG*uN# zAM*SHzaX*5LjAL{+LdQ0r{L22at#@X1*#}-s%1-uK)kZ#01*Ty&XRn-R;~1mh^*+22K2gtv4SCNsmO+ z+sg6)u-QM?87I}9s|l43MKKuu)qVS$JvKLbp!?%x9mD_Y^v?GHI+9qQE+5{Uh>nr- z9tVA_^z?MdSP9dM=ud)l+tUnXidVtiS;yJO1PU$H#d_~Gd7>vDQGMh=jtyIu-eFbm z9{x8nl>B1&W06sS9NINq47z>5oM10)2XlozXe~zyvv2>PMeK-|Ff9uc zXISM$T2?=2n70UK*ukm&sdvW&Ry6kx(Q5Lha<*De8+RipTlf-Ev(U7uK*ko( zOz93Q{0clYgnY!l4cbjgF7CjH%GhoC`g+$M>vsQUC?}CIYeY zL(>RX5JKR0&eq7n&y41!PI*nqnRzj_u?Wg_@Y2`D#JM^i_HAuCqAca$Fr4fGveJW! zths!C*EPc7f7Q(-C~HDC&Jrqh7XEk0wC9{FY3tD&r3cB zZIwkB)e;rv`Dw1gRduDLT_^?#fW$_)5oqmz>IYN z=X#7xK`U1ede`hbqSn<1JyaG;A$em=ZkQFmQ7HG12$X`>F~vOAR1sbKLu4)<5RO!C zOG*}j;*a{dturD+fiA?a&Dwr5ny&CmmxHPj;Y5>Dkl5FG4holi?L;*YA(0N!EG@To z3S}km3HDOxNAHwnu*<|W%W4=#EeyOiWU!*g^WuUv7nA(g0dB?RhFKt@M?EoP{t;}s z*5iv-J5IV>b;qg4Raxw=1`<*~T0a%6EqR+!*q+5q?d2k~36K$QJPzpZF9Kj%7DclW&504R$$`fuwJpEFiB~hEVI}u()`7 zTmSSr41E^sUDjlQ7C~OmCE%f*=nSD>1*`8SgL`8qwKy8FS~qU-Q!@c~yZk@U;jy`jqWhI(M()E>x&CsbCeRe{%g1u=;SQ;QQSi27Mu41b2E_d$)1KD1gjln zB}{kL7NYqKsgUKo>#(---1a6tk1nsHph=ZYW{^eY9oGP$TzfuJdd>lon&c>ZZ#`Gu zUJzKG%bMoZCD-fJTSp~k@6bO(6!QWj6J*LDNgtct8!8PhmgVK^w$s}s-j9FXcdYjv zT|*g-z?p4XH4b1X3x#H{Ff0=$>1A+DPh&Ut~_V=~YFdsWE$+DcnT(``P59 zUg^UVY({H3`nL4pfjc$WeB-sJC;M9{iPn?PF?i2SYVic~{S-#Qi=h7uX(gamHoM|d zTNGyoA@xjR1YuW)*n*^MCjdral?7|HM1r?OaDvuB~Aux(?2Y&qz4jq zxf$IK==z|}r6*s43n;45iLm8$YyhnsO@1SYvedL$sXI@6?g!pwi}1+btm@&;}2bw`SCXUuaab1`E2NXMbd>PW{YG5 zC2^ZkZ5PWI{n*ObO~H3Mq zy|>mxFX_B65iO_86{8#(UjfpeFW$D?_naQsU2@l8S^cf{_GY`7zcg7U;(In8urOnC zSwJfJa7zHECfGZf;)44UENYmN7s{~774-VEdotgcJ0|WYgRmPM5bbNW-S13dfSZ4~ zSmsaGSIOs|zzv1CW(nbN73ZGgH4G-rb|PPbjPVRfuT)t#x@^~}ZtVJUM(VJl15ol> zvTF`C;xp3Tr7m5lnhgJv$t?Su=y4_%Tn^oGN`$%Ci$={68kFI3CSl%s=1Rx$O+(JU zskX-3Vu;|;vJ}EOH_Np_{YxXk8M+I(z(LI zZ%ZgjEB19<)B&~$vuXROwNEcBhL#)p8AV1xVSr-M-uYz(sC-HR1ZD|B4S#>I92I5? zRK0EgJhxFagQJDq4(dLXJS?RZQFlUCxxIpd%gPR`gCFGAWJl5iW~~4DUz?W(iwW1_ zOuHZ^v?q!eW|($ljQw*~BQ3Uy6giXTpC#VEcn+kEdJuZczC9K4R^2_WFtH;A4TbC@ zz`+y?xJV12T$dMYj9dw+TfbJh7`KftU3orso^~5GF}W>O&kK*tA(X3eX;|4Z^Qg=- zZ`&IZf!#GH8cg@XPYa?rOW8s86z1v7cIqeYQsm#2A0B?9fOUT&YD*ny(a6uN0 zNWH7?2R+@dk0!jQ=bL(MCs%U1#>L3Ocb8c=hqFa@7o$aYX$P{W_M0OxV`(2I>8y{) zLDpRxKtaqq#iK;wHEaCtWiI9J#3Tz=ZEX2~6#F9{Q_Q1hA(wYsdkg;>4%=dPJ7tYO z%-&>SeCta@%(wA2L9#>o`dtw3N3r)yeNghT7C}Syv#q4qxvb=m=U*6ve0xg|_BHSI zK^ibTtAyqoS^k&LN2-A<2&wv4pVu(Fii2o#B!q`zdt&6t)S^>;ToPPkcV<5m4Fw7T zZSm9MXB%cAJ>9px>OD&stWlzVEK95oiZjzFFtnwVtZ@!nG#w3$UHJCi0gpa&8{S1x zh%Z)t2d`W~N>}_InUi}?fu)O#7N2(x{1g2L-fj%0!S6R^)8J8TnDVX#v&xo#+ORJ! z(*nM{wxQ>UZQQiWpS((53->{euV1ph z5HqM{5}qookrnGKcF3up`dPor(XzASZgXEKl-SWA5oA!svAo9i|ICn)CI~KB{?1BU zqf*@u%=P6OSwgz0WX`1i<?il`BS zscc5z35)v+D*k~pL`TCX`6eDn`ZbSISu@pc0zbU|x;%@g$zrAg=!==?gq9e8hIxM) z{!ftq2MIZ#gn;1fFFAXqeX?k@nVg0U`!7x#mO6D#sFXAoD%TYGPh8YaYi3>i=LPfY z5-6qMh1J6-YWI9Ri*e#V@QNq~G&P*(bNq$s7UhT>chPaj?7Y8a0mZb1RW8J-#dBdhceC*qTaKEG^y@p zK3w=%+G!slGDy+8Cb;g`5Yf^DyOaiBBq%b)RLfb-3(hW@RDN-T*{cWrn#nS1`lNj8 zzLmI3QzAZpv83D1(8knDpvUTn0WNKx=&(?c?yvRB+s~K{Izh+o*Qs?4%6!8U&A^&0E3_!Iexo8g-Dd4=zUWEFsK&}Jr1*=ojz?vEvf5ZQ+CbI*6e$@0O04E_L zB|uV|d#pvC`djx}od`HY+c z6oCm`FigKFH79JAynlV&;|sz~c)C?V$aI5xr6L({b;C|m25f)`!`svex;;>Me#fwM zxey2%cA=NM!z6mwP2%1ctT1Q`cAu*o;;J#06I5wEt-N8*@K6{vzjjzX37STrpSBha zheHMjw1vJGLg@)d&x7dQd(D^XOj`aS3AaNwW4xAvUk}d-??BT!50iq<>CWr<PK}=@>oAtd{9`tsjQsue_3Q69t5!Ds13yAz3cqWsrwy>9Di6fOEc)K;n*a(v zfRe4G#^1tr?E9Efc7{G3eeJFZ^qmg|^%UQ>B5C|Y=fZ?TdS&&kO=t!*rFHpyg#TEAga zAlh#BzSo!2@(y_>>u<+^=|)>l&s(!Hc^@iJj&vEhqQNpX=`7nIg_@(ZA*drqEO~?92ka zSE}0(TX)n;Vj%fV!8|=1n|DMZH@-NBkvZ}!{FfOSH#8O{PL2qdoVc7K4{Ge_LG9Y5 z#Y*-B8fvUXj;H8Q10NV3KGZ4ba5-G~^IbW`f;){-7xe3Y$ME+9y`?%#7?_ z{z0;wHtc*h10Cu%g?{)uL%z2_ye^qR3Lv>W-YD>n9QB`Zw={{+&qf0Lp`V60P!lDb z`BrkQ#rav=^jJXb6z_j2mR}rM3Ff$t>7$MOqv#TNfsMh(Fobr>h(;f z)yWRHc--#!q*iK}z1X7_c#sh`SSqug6VW6Ls?uz_^}ZbLwt_9a&EBM#X2JJm+Tu+ zNzs^MVeVo}VK8XGM+qsadBVAM>kiIn@W7(hyN1&|b4tWJ_{}|6^X+Ww^-Kl4|I+%c zZM2C;o(1=!z>B-t?$q$0&Zu;%|j5^3Q zpB9E;WexyArT`0Ro8KPf=8%65Eo{3_;k4}!94H`kGn6b0HVI?=khZF1+L2_ zH-XH#8oc@X5Zm)`eewdE?_}M?4DD}7OxU#fxE=JmalU{0FiL9?EVXbO{+iG?vb^~w za=Z>u+WWxBOixl4G@}4*0cm_eLW@{G zX~}52eQK3yFBwT^Oa%5AO4aju(f3 zL3p)(2P)?t{&(LKdTwuo$*Q7;b5{*m)98j+_*y$$_zuC7h(^-B@PPbK+WwYt?dQ$+ z>Fc|^_f0qdDN>mevk_7u!O3vH#omjFNRfNPjd)V1i$ogd{$iOXIjPUg@YE610T%4! z4ERiZL#T)UK$5XJ4oB?~{KZ+V;l>h(YQe4^NIbpAFyytAa7_$b&=rNmwS%-}v@fq1 z`RK7py(?Y)O6G~W$*hrZAHmY!C9tN)b^wW(7?uo?3`s5UPqR;-6Gbxzs#dnI;FY$K zJ^m@987QO3$vEsUC_r=CI8vLl{-mI?SuHJv0b7QTzP!ZRc8WEz85RTn-QmB$y3=6q z)MM)A-3$W>vm^pI`($jmu$-OL;5iu;fY9WL z-^DZl&a0q8p2f*82VQG7CP}TK>#3i^it<}THvgD97qU6;uP+~JkISdW$fQ(AxDB13 zGMV1z^Z7ZpAY)`V*drW2>L})!tHhaD#q!#JJ+?}s6~67r*U1%7?)IBKQ%pZ*VP(qy z1gGp?Nqr_x$GJr{f7;WhD-T4ht@7%qIX$hl0*#K(nu`(y`bRZ?>iAS+(I)-_rw2u?h$Vzd1DUJ1p zsjr4XH|rvm{|z8s&vrJmm&4pbv?cXNGBqUybb+LTF?mGSmN)<4dnesivwn`M<`AeE zu0eAMEx0cc%vwbvbfa#;^<^cZ4tYUO=9!fmr}t{G8(jB?!1`Cu|H7GBMC=&EZt3gLb;2rN?-Rd2C9VmEide!+E9U3TkmNBvn}!upM~&ulki1zAew6(@{2lWW;;??P~huu1##CIYzFV zg=KP8H*eX|fmY6K zlwMHD{O(V@PV6RD$DKXSFF&N+I{m{@-{;|n@A{S2I6Qayb*%t}a-^8P=P*AXO&B4? z_gC(F&Ac`Y`gM!QZR(GLupTe75AB!4iE-B87wb`r-)Fprtrm?k=(*mv+5@?|pA!{8 zuBVz4^UUa7Mzsbg95zS+kM{C-ARo`^#3PaC8;Hh$CD;%^ug&4mUCm~ECE9e!83Y<% z{lK8lli`u1AyLc4PWN%xq~qVkaL~M5_+wp1c;4u&`jHS-d}uR$;X6;HkuU=gZi+9G z``=boTMkD))&w9_W_D%JBHIHe5ZL!)KYn>_n&sE7=f8l9J*Zg2nT zWhKIsmosB0B%$Gj+lAUnB9vpCg?w`v6>&?dh5u_^ZnD!a$q{7%F4cW3tZPS(Xz7kM zqUN3|T`4d_J^+HDQ3{fekEZbSPktBfiNOySmwh zFZj(x?J?+Rji{K)^m&_y8qse4%kP;nLXJ4=E_aj)s(orm#GwV*g8d>!PwfC$+mS|$ZEoitDeiAa<<;_s{5V+mKK31*d-{apw4 zlYq$xEEUMCZau-6m6V`?WP9uZUSJiylstf(VYGeH;yQQ^TD6Qf#5Y~e5vG8;=3tZ|)^=`_q6mI_Y z%&qm`V113ExKp+ovfNY6jaokYjzg27DeBxB$UiZ1k^a-qRdDDUGN$Xc_7zPQO*^9o zN+()5N460HU8$U`BJBIZf9HYT9J9>>TfLW1sYn_*9fsH3^o^3b_`dcD7xZV7{a{tq z_Vr4q!uw5Jmw?=hYPUNj)9VC~d4hi`Ly^TJactaw3%J3p=x#ul=ZvyVxDif70;Os9 zmvaIl7Rx>6y_me+nJ<&1f*!{h`vp#xknj0;b&{g>r9IFW92et}u_Pu-KNXr~LHm=y zX?ewQ$}=<$;YCtqV^DPP!`Aa`$@F|Fqy7~N#ap9z^}-*kfB4BY^!6(%K!LGoM~+wC zmtjj5zyPMwm@v0A;ZTx_qrM>j1=|?ff!IE@tuGmOzSx2nK4}odL$i3IJs(WudHHRq zcD;NBwB60ZT(kP}MA5B78k{jfQ}C{@3p@2JW$pg}G>aSO&HmCn_xu%dSnx&5E2jJm z4-!RJdO6ccc0^OrQ~DqR-n|dpF#g_R!}jhE{{HP0sE?|FcUiOKUiCBHk|(+zoS8w5$YJlk|2xPy;$4N0 zhh+}*9Xw&_|B_vAY-VJ^GFbgLXlL>kr#}yI|nE3$1j`dzu zaoq`RPOKI=fOyESsu%UTt!|}bw+DlM?Bd+9vlpipM_zt{#sWqG0uGJKq|uK@6KjAa zx%IvA?pQ%dK~d7Z$80bvI1Sd6U9?T$$t3q_9)~Q$0n;<&p+?crYr zAxkiOf!Vf6o)IMeS_ok!5z_*sK0Z>q=oqU9WVHFT&l6!p847FK5AX2J2Kfje%!!uQ z_GiS$a8cEa+Yh-Vn_!;nEAc}{_KzQujQMch3(3C5ST1_I$=sA-`^McxMWww7x}2ZW z@V-O8D(U{~-9TGM3a*R+b|7ma4*Rvns^1&58wKvQWcIv#on)5^0yg_CtbE`Ec$jMg{P(h`UEtYsfJB#H+BGP*pfyy z3Y;mMx>;d>@LZWIN#gMOI_tFZeLaVhH8C?^8}l zOvdL3+dgBEqTb}ce|e%g4?ouOLq9BV41OXxYMz8Rreu5>#aH|$&tgF)p$Nyx|Df>q z1WKQkG;ZwvJbU;*8$_n$V57joEVRdc*kL zV#m0zNjNrWTBT!udAj#|-fQQ})1fjq%beRzw@Wnd#4ouC#KAZ%h^4dRnyWlOg{mee zZr%2L;8V(2x?`!@kmiZ;^Q$vy(=e&DzFGLP1h&%_&-KKw&e!z!GQ0O%>0VT7ig8~* z=%B;p;YK+DD~`py)+OVL)f4AbNX`d;IfTjjw8}*ILr2|408(X6uT@P`&_`K&uFbN| z(Lm(ENq41DlPmJ9EyWwxZ zpciSkc>HHDHRKoZffRAmg}nT|X3yd5_lI82GHTsbD!IurZumW9e|O$@3-`PecwbE- z7Cp9FjhY8fRh-7RG@0%d{z+|W1e8E{!#UJL5O;_J zd5zN+ZhWg%Hd6Acr(qlw5jMWMI1Tv1bg0-U3IY1L&-ob4$-pH#???Q%a4_qWhF`2P)yE1 zJJ`>9>hd9hi6O`#%;9{TJrJ{l;sItRp0&%q?eEk`@aHt#5`fTy1u}lt9}1bwtU1Nl z$mzQ(-a$#Oraum-$5P}hBK_uf8nyQt;$ex@D@7XNxB`nT`Pk~VAr(VDgldTai)noQhkAeClTrj^50Z z#_4SqTo(Vt0WJugc0!x_Bb?qvHDA1iMp6QaErdfS3IZ(=B6#1fbI}{-G?V?QGp_*k zmS=DVzQw|R=C%i_$CRAwBDuawImfeme-PKp#ATuT+Do}ww*E+v()EL zJN?*}SU-2M6hx+P7K=A3#J`{R_$=ACDBYktqGAIbwVAZZ@8$r?R^5GjPa5T!66dHg z^PK(wH(Z9R(C?MY)orN@{X>RDQI)P}8S(e1;tGp=L0{(MnW{~oGb^i2vIaTJ9XmR0 znZ~~WuFbR#;Qe1$fyv(ph@2I>Q=!|q+Zg3gSa+oI!&UHEisI&FUp4-c4Bmms0Zpjh zO~i%JpNmsyhl05PKH>9!eokV5`KQonaW6CZ1u8Ine#pTsf3VVXy%JlnN5`@Qnex4= zouRFHNaN*GOh8|3m{vd%1X&8#t^9po)2Al$p@l5?l7>1}42L{7yXQ^9q&n<4V#JP{ zS$|9U6tb~W*}O-Kd^ZK<`r9Okyj+y$`150s@3Y~7jFg{`#JErYrXPF4-Tt{Q=j2LK zLsD9nEFTpOD+aOl7ixo?Cv{Kb+NQy)K?)|XFOqjH2XORgt6bB7cBKAN-q$|O$er@% zu|<-uyr^?~uNCV{;j`Ht*Rp`qz161=iw48}(bVSyapAM(mj6ts;+x)3kV*x3bO|9< zuo-;EtkUis`^)!p=`&oamN7FGsm1c^4xQu={-H}SLaOL5*9S{`E2=u9U%Xe{MZHND zW%`>k5=Rruik@#T1hJv$jTIt}L=_^f+j)dmMSBOlX}$w*538!HZSN0m?Q}zLgYMXp zL)-mUA@DNIJcDnVCh}q>1=b;}JrxiqSEZ!}zO|_>IO!C4UoD=*Txnpim&u<@@_Rf*M6)1Sjv4w^3#9W3Bf4qmhARSrP0t zm%IBAE!nbjSU?wxh-eJ{G`$0TBWr9#MlmNNDUlWGlKHS4G#N#tttq$V16~RRjYFJa zp6sy=DNL(>g~^^iBX-O+U%f}OgQDI%>mS2b5KJl>{~Z1Agw*PvD`=8ZmQ$utIfyXT zZi!h?YB`tCTdMH=C>0qKfB+y`u_?_~iM9fgNgIM`DQ#&fyT6E2QBBx7@;2xXFrpSP9K4&FuN9~Zw^!}re2sHF{TV#+@+fXVZi~kb(m4|Z6^;PE7M!T z&5exRII~itMNPnIJhUjCAad@F>6>(xEJp;<$&gOkLdGzAG`a3BR(e^vhPnKkd;1;r zt*)cw6QYbJaR$CGhYRvI`QA})M|1ylvldQXbG$@Y1E9j`T9=#WexB=IKu548K74Bu zIn&Z*e}r=J2eT1}uBrV2-hn8^@iPH}4sNKt&Ev&Kb~{cSVo}~iEFioC-(odrSn1Co zA84h{HBo)dDk%v~>Qd7Z*+YBim4fum&25sllw+pLc?F8*mS!wWgVdj?VTv+hVP%cN@YYLccH8|TZwEb{CP~hR-kf`g zZ1P)e*I%UJ%kbci%Xz6sq;+xK019N?fum3**kvlKzXu`)j7VqQ7c{+43N1Km&VM>0 z+;a!w)7*Q~d(?c&=B;&;4+;HN!S+!C0*n zxt&s|lz+uHH6n)1AcS?f@=&8T`(ZzGfELtRC9SLTSY2MXvjK8|+N?1}rGjuM07s@V`(vW1qKn+^=_ z#;VYsj|@Bv#0j;`pw*7(9oL5idr?fQgF-^`dhU9A-q3?UDF6i%|B>Dc<{*&Ud|2ww zYd|J*l8mv!L4v{p5tahR@^;qT=t7#A;4FV}DlL;@F#^+#4!b=-nD{2bp0 zq5SSTFH}=)ydH+oOjyrS>$oJaMurFEXh#Yml)4avZ zIAAF5DX!gz&xQReph-$_O`T`0GW81dgT3V`!9q}rSx*;CR>@*FCkm2HX4R7jb0OHD z*GBlP5KFQ}3Ig!e)hyqRGX?p91C~ctIvqw$VTF~6hl1L-nJHzvBK_{*OPvw-HO=t% zoj3ob5-sHB{GOVhpx>hQEP?IhFm|dZ+39xr1TGok7LS~O`{CO5Gse^2c44Sqz2#tw z8)On0*WnJoR!#KLj63MZBL8VI;pf;*=52(1-*NGv0hA@?zqF7i{E-XQvR&OT#Qx~KNtl{L_gS~mD%xx0pT z5d~p(Uk+jDyb#y#Z?(F0Dvr$#4fvl*-e*bn)DBBkvyh7`11Q3UJIfBVB)w@tz?LCl zvtCaHU9_BhI!Uqx>#eq_n%!!ag61Egpd(Gsigl3HlA$-2 zqN6vIj_F`;(9+RzqVva%>ZE+9qu0Pm;<(10PqMOiBwg5rTTHjtg&JkG@D8YmEHX~CAdcq=iHU2JAWL>gi6-RgiNv# zF5Bl8hhBPul0hYc!lLn+C$+y4*20sIPja$^AOmF#CjZ&^*$g6mPT=T*@AHF}LMr)e z?EU+{rq)mHe|w+T&sV(O4uxJ?^EW6@{Quntj3>x=5j32>U8WQOiFdp|tgU$y{QiwC zjnW%5{Fvng7-o!@pt6N3}VggIDhm z`tCDcf0K#EccNj@7omMGhQ`JQ(45k>)c>1nQGc;~{(k>I0LMT$zuKLD-6l)2tZloY z)uwmLrq+?1z@CaBU**g8*|#?B!auLrjn`kc>#x6JFBf;)Pbx_K zn6igYA?*XWQovC4@++^{(#x;HlmOnqFibpp+GalgIUCr$%Ozjdkvh7zfV2_PE%Pus zbJ#jsTr7Ir#PGF@O*c?CtOEqqaVafH9hJ3N=fi-Q95qo~UmZ!ce(K3WSGHcM=;UciH=PMf)?qwLLSv5H4{OB42*^YNiZ$~gF4eil;1*K<{vCnBDLW8ghV)irg;s+q5?>Y zPiah*FGjx+Z&G^aH;Y7`^BVm=zkj-j55#9YQF)a>jOj6JQeXqztuABafOhgeCG|Bi ztny4HX^6`gt9JI%4g28gO}se)Ho4#J&!5z*iD|8rlZC~yuOC3 zw>)hnBKYUt-<{UsX$`m3+_IWS#7-LlP27z-?abEMk4Q>VUiKhNnCKh>XsD7RprmtM zg^~A*ZU2NGihUPF0t}_|0D34*A*Ad6?LleX>B=kVE2V{!0_c@UcRBzh;8yFY#zFa1 zi|#AG`XZY{vDDB4E|Z|P3PjU!dq8Oc38ix%1RF}nv7scDH+?ATIEGB3 zArxgX1G7g(j;L2ck#`b}UIIBNOCY`C{9@fMU8!OayNnI0B|PO7dB3ssgiX3eeUdnZ zA#ogBAicD~I^5ucfSecHkOgtn>(JpPQa6pu={?1PgB%m&QyWNl%1#vR=Dp7&i8zfU z>eLwC*8s|g0P6Q3(RAPd9_Nq@ngocK9j3b8N7my3sR|PZkfbaSZz64V@lwOCUvJpL zT-|P9i|xwwj9pnk(T(;L)s{#{UN%W+h7Sm9fK^SK7@IHw(@&nx+T*CU{o_l^_QESm zb`9@x)dqUBtWfGhmbxbZx^nwyQsX!!E!1 z&-TK_Y5VJ2Gdwtq7oj0LfhVpQp@ml zUy>tj%JGOl7whGke?fwTwMfn7RvM0hqMeZx^B{&I)y+ldac4X^`frpHl0drO(qIt; zR=C%(q+XS~b+EWj@^(L`XO&O+bz4!)uG%k9MR}WQux_Z#BzV4rAzedVrbt{~sS)wU zv;t#?TH8DtCO5C=?D{Q3C1uXeFVDkB@g$&67G`shI1F+(3{yBUlxHlEW|%2p*JKTb zvWVOANf?1i7|XmJK7h>?Bm}$(YL42*vBCHYJj|dPn8~0X=xnwcNe2L{ls}cCp+xmd zc9E8@l!$9Kf>grvVbm8#VSJU7rZuD*N4_)+pTH`gUSb5d1eJP!LBNq{O7$M&)1rG& zT?^@=cW+1|I+2n1L=xP#5|Vf#fP+bGKuLMjSVb!H=p)7XHU*QqeSij@U(bY@8^9V} z$8th?G9o?2#JWSWX1>}Ijv*}o9vwg_l+QSkD}hHi)3sU>pYJXqloLw}<#qDLyRo$k zbBh?Pz6j1ywWG&RV3hj+NNK$3rv>09yxWjB{4UaNcf0tisD-B)HbMg5_1S zYrMO2^LULzqOZ7ucSIx)D@cpB09u;FbsRCQ$u1fyt5sBy*Fcx%$+xgtK|K>`MI;|< zR8*(D1`aM-sI@j5x>s`*<|crb3~CPzjN2q}2-|Q4NrO%{ksPW6ET?T8khws5T`Iw- z#f^?*uW7t#yI3oB@ea!y-s)=BimL!fs5jrbX?FgD6u;+yVn|nAS>K>%K~hW9mAN=q zXRfV43g%dT6vO<(_NC)yPdsFH_5zM1F0I?m)gjdU#vukj1|k;gmLWlD@_s1<4)EgW z=z=}8XVIQ}cGiC7`NMYdB;NC;k)j-e{&?eTkte0E6N;M0>?xWo22Cy4$y`u#^yX@o zw*!e0a8jD`Xn6dn^Uqk&`_TJN+^dW6U5dwlEua+3xmUgY`yV|8KFoZG^XIOB((b;O zx1Ek&A5gjnrQ(E($CzCUNnA{HZ>K76{`(sX=^sB;6zCpfoh#}GM~hA0%iE`Fs6N8R zFz(v`O4{63N+m$0lKtp~to`uCtewMq%=H_WaS;!4V25qprroO-E_dwc#Cvvp-~0Ak zzx%NL&hI>8yJrX7wQ?5QDr}X>FF;9h76V~PNOpaJs5v#jh9=@ovp)WT^Fwi`RY7}3?g$VKm z-MRhPSZ&Eu0tU1-C#dm~Oc7_KpzD-uYgGNq_HGcO-D8qCGTVay)hrT6Gcy20v}wo@ zC5mT!#m8si3SFv5d;uPehG@GYf&$_XLN!v^@~Q$DBcrk@8FQv${mlZ(WO+a;RCS`7 zlLZhEfFwpqm`%u|J4xWd*ga3BK5!0aQawH1B)jYf$xyEDt4^;VDQ3%|{Y?8LxlKFO zHrB~1Q8s$S0|@|e-YFqtEQ>6-V3&;~n9eJVH}U4p65tU=&sQ=23xip#Hizv9|1&?o>$Nxv9+V@&k=XOJ{YLE}0i88sNZH6-cQ0KA4_Rwt2!DB#UW@)II< zllzhk6Nr;SDoFiQh{r%!5xHxeJjb2?h;Q`V{82fbvPk!vppAKRo1r@9&T5A*j9H`h*Z$3JL92Qfywh9qW!qQrnM*zJ$`1=q=~A z&SR$V&V;`zQD>p9t`c=433|Hw*{)n9>(1iBf?c{G38ktXIeOIg?%z*|z3qr16ay8$KD7>f(E(4-FKh#CTun#9mD zfu|}z)YYM92gr+Mc{{ieSlXU*ev>~GA&-cXV5-(~woxkp3T2T#!e*1CkXUB>!^7?mL>4=z*_HpkvKq(~iHwivw@#4Wg#{GIc zsyFR5ucvD91+BbgVl+8|ILx+uS1}0Tsf)xZNrQD7Wb#Se{VzOV99=j@! z)yCu9>Q$bYFS0(m7A4w&1f>Z~N+*Dl?n#mW*%NH&WbD$_Ch8JR`|p2Nvj6-8HtraF z1|2{mNosC2G|57V`cNwyMp+pFsg@df8s%$YRE&0MMwX<0elWB~>?wfAlv9F1gQVXwOfJN{Y8rvp}i&QMszI^igP=#BR z<&!*&yV9yKC$ihxfZ=dcJ+xPfCC)@rhhtn^i%HBPEu$!=s7ASJP8LQ=(^K`-XdV*CPT==!q)t2{ZtfGD}s zDHuI}709b6G<0GtH}C{iCSJXQkzC^Sxsu&j!aflUqr9paMy@S`(UI(!tNiVkipoH+ zp@IWHn?WKBUduIO#yLN#LQt=MWE81 zf&>qIxM^_~NwW-+4FZ&8%y@l0gDowoI->3}Sx1FN)CxqEM1eY(5|WtK9NQYgUO{gL zW27#2ksBRU& zb-SG8dfPnlx$ua;6Dr4>9@A7<_^(@ALI>PXa%k_C44zB_y6Wk^zomaMPrKnfmei}G zOV_9<&h;vIHvTLwF1h+k4Slb}#}3-w0~q{QTgaouEz(2RdPZ~H$1rIKmu*@lNq%Ve zjfY}gD#P2%G|@ED``=kXwL<8wemDGy?&6ZXl0xder|a%=^t4u^AfY5lB!%#M6n>LD zVcS2nn&KKD8u7hWD`Rj#NedgGQ6`7cZwy&ySo4B}WyqyqXgP!bVd9C~a1XNHHzD?ZQ<&I~Ms_z_BL45_Z;B%SfJ9XcIl4`RP`f z--tCppcEf=hH0-p7N|{le9YF6Y^>S7S&ZuM22|RMw?;gJj!z7r8i!OA4jV3GwENm6 zyh-BSbB;DuH}imF1BSLVA15@p{J!Y7EBXBnlK^xaDb^_%&fODZwphvXEQ6>oPy+7w z-Qou-JS#FlvPX9n?V)39_9V6epL%q^9cBHR9x2kkA|5$c0h9pJXLb>1!L0^ahfvLi zc3SgQs@4+$N$xR}^i-U5l-&y`bw)^)6Er10BO&hB<5As;JXvoSW1jB&I`0EYy_9-z zuj3fUqk7Uk-rMy|c@=L1l*k-xD2?HTaTY)c<83h{?@%95iUjE#`+!o17Tcc1$r+C^ zlO}5SWR*egof_rV)}S9geH7>&<36DD=^LYuzD4}Nh-rp9(0tHuhpW7?Xt*U z$)=tq!Fl!M$Lgc+=e=v_ZAxSYw|i1~wW|5b#-F&yRk}y$r?fN@Kxuuo757CDGgm_j z2Mq%|bGB(8oNL)%eSgLN>x+CcZU749@QfxlPVT5tZS!YXdmH+4D|;JKpNkuIovSiO zWuU91kFakP7yvyRnEIrZT&uML1(be=ph5A-eNdlKB#=gOHPkGs7+T!~?AQb-;%k;9 zizrUuk4lv*YbAhf&_@_4u2oYL5V0YtG!YXLU^3YTkb)A+*wR;Tm@rre7zUU=B(&s3 zOkbrH)eLW`%H&#xpR+JI$O7;*e*q^YaRaPEO=MEgb4d&doxeH2p8|foGoq#2Oi>Gy z{D4i}AXGEGPIK3&S7mpC%FfU*nd_-yWWLrKhQX5|Xj+goK{l?0_0s@$C znniM`1}G(aFEt2X7xDQ|?m&OqC~1Z}1*w?H29l(#5H@hhGQF-E8?;?%Gty{iNsfxdzZi(7!80!T2!c1sdoJmYCe z$zpz`7Alp)1_V>PBxxrLP6AT5A(=lJa;j+2dYix;@HyIZTbFWIuc#NsRVJx4rI&`F zYk@ZM7^(U-PlRO(&lQs%a-qJ3&9$pnZZMZ?b_}=i`;SaJBQN9T5hqanT4F@sIv}P% zQ+1I49^x^%>^jhP>UTS7)Tws(m{7Tzozlc=m!cLacBgd}m89PeC@Ig@X96SXT&Ml2)XgpfHpKU;sHpS8%Or!6zHI!lj!PKlmsFFU#qlTWr6wtk7o!{AvxXXAQnjA91=g)~ zEh>6ReX?pSyn75<-NsQLbugW>mua`04ERf~_6UGN%2HCxF&v*P*+cu*?TLqH?WrdY z+5X8*8*5y&f$9xQt*+2qep?=W*ajbY2*(t72*qw6zkWz%>0^}UDblY@m^PrKR9|f4 zJc%`F1U|dL_h<1(W}9wy^Jj5y-<_sMy7%}374FxDQg3bX6+^G>PU4x+bcDo<|^#IASFy_q^3`c%dgrUfolmM{Z|H>JR8PJ- z#JJqHxfLZ;PEwYb5!q`}+Z|rgeKA2BTw&KoHk}+~+{DvRmH7m!p{RCjTej*%B@BtU z8X%P$f~Bu1o)u6PgJ@08+d=`xZ!kRo=%9KAp)IsXf{e*_3)?hXMM_?w9LB+ENY$JP zC_@|3hR9!RjN5!`0$?lB9`dN&ih(<1D9~xC5i^JzrHQJu{T|Ryy?cOGIhepfAcq0& zjSeAQFkZ9W*sR(sK#At6cLJ&8oliKUY-WyfA3-$-lp55j5f_Ek8o_koibFdnErtNR z;J^=2cbGOnDoHfuVcaBLR>amz5y`3oK++g0cLK9^8Uz^0wYjEd733m-Lg9G{*~uG~ zz#ci|;}zKwv`G`*B#Gujkh}r{s1!vK<@U1lC%IMwJdJj{ z#tnI0s1V*5CvqM&-N9BJ40GI;XFU(hbQ%>;VZ9*)FewjcA|OYSc3NL^pi(&&6upAN z9>RVowx+vxN{h31>z+%`%5}WIUa>lk0xp6?Am9h!mZGH3Tn$OZLGLv4b$~WWYDN-m ziY~E7niGX=tIOELxwc4q>vrtXNu=P$0hCaGr{boh-=K%LpE;rVRwGT4ti3^1ZWmPd z0Iu%ylANR7HkcKg5RcnEOqy!axGHFFDfC`%N%I{1@w@_ucsO|=KHr%TF|(JzAI3o0 zA-1pZ&_QFS>NPqlvO98_Xv`740VMZ8r?nyH8s zQxRKD%SbXU5zBx}Wo+chc(}@$$FTN=ODS7G>PhO++%dG+Y!2Y6Tqe_|7Kxk0t2_YM zBOo7}OqLyCK4FusFltkSBg}~b#xrlX$iIoFIwk^*(^{$D3$@Q&y>5o_U&pxkDle!* zK3c={o1g|cpoAEfK&2$?A6d84QyAtxwaXrR?6B<_TDC&*4J(w+TON;d1H7*zU;2WL zeEAuG^kJkThuld-nIB8hKFY@TqBn32Y-jk8)|RoF5Pqq zrFC2lr?Q8vk{X3!gjvSe@9#d7x34{)v&SCC-Tf1Y){kak3}HrKs9-;6DaVA7);`+z z)f}`J{ZxgpZ}uknroX#!+}qk*^-b(WNQIL8(-s@BguS(xW^H;?FzEs!6xUz|KDbb~ z56)KY?f2I0o%h%6{P|6L>lz#Y5(TnJGXr2U-CRZW4eKA-acktpVZ_F4V0a9#Y3@oGN(+NYA6Z*aXgK zVKlwUSLSM?3=fKw3=C{OD<(A$Z<^+7_9|b;;cTc>Y*ud&I8dP-lEBKsuoP4eC958B zwZJ9(m4s25=Vkg8yBUB=X~3^E9I$F#gImv2c7gerW&kAZgM|&Aayc)U@-_NW;_Ey1 zJ|v-}&5=VXp*`&}aKMXdT}mSvBcE*K(>!#L3&u);bXx7TganerNJB5V9&Z6yX;fQc z!swH{q#;LTn{M1(V3`;$h(%gkO~e^1eXXZHHO=Rh{v>Rs+8|`Y11J%ciuVc`#y-1> zR6*12Xo>OmnMLs~l*UmWoCNkrGDwgSvQ55>NrK5+J}e<%sd+7SD$A!E`^16g zeNIwdZ_pCt&yYj;6x3u%C*@JMlKNzxe#o9#4Dw3o{p;ylysx8!r>t9|tw2c)ucUoA zIN+&qhCaI~ZADYuXJ`9Ru@vPM;By9u$3LEAOFplzRyuV+h1P26u$LotN zZy(hNm(<}o%5CcPCP`7Wck4|_W_@U=B9$bdRees(;E^}UprW+y@$OV<^CnA!1cs#Q zrgy<55&`otb>;V#7O~NG4V5_TXSZmu)L=1*WXl*rS}HYgqCrLeF@WD{*4Z3ukLF)Z z^A7@zFvo^LQa9*)8Q^nMNA!-u&Ux5B;h$EHkHUDjgP$HJrd6%k9u6aUX zc3{O$jIP?Dy%RVO*o!Ll6&tJk*k&@9?a=IQ+q-X{6&^Whg-1_XerV8gM7oXo9qooD zdDotBh|HS>-PI?#fcJpj{F0RJ{6g~`~)LY(8+S1SS(NG|c z@lH!u{utx9y50B7o8la`rcXO6RblbYtNX_8x!*vIl@E zu-79mFnEso_OH&`Z~vPaJB?f6haW<12irShvVwGuHip`pvdd;`Ek?lis!G$zrzLdl zO}$AyZPTTg#7=O3I9x(34`QJ7RTbl`H5fw}45?8tq+CTlQVsC%2 zXm4SZdlNepWo#u!oK$or9uIhMI)6BrBH7&u^!p?%mcnzBjU`j%lNWKTm3O9sgZ z5wd~dR_*2MNH54`bc4EuXKX-d8RrJ30WMk&fWhDt4C|1Wv&mQR!4_YOxz}t>GA@%= zsjbr%^5R);7^#(ljJOuKml`Gc=)aT`^ z?mGqQaZpb5><&s-(A%dFuXU<+tB-(s0HaQOwN+rD?$J;E1)AhO5oQ{5zd(1orXIj0 z0h@seT=&c+9=%IYJ5(l-Hu+y@F1u3Q?CzZk7|vj0jwmpx0YEC)CM~*itfxv$-Ocb0 zWf_koNJUIGvBXqw2_$4#Z1tNhm*5Rv8Ubr*uA_H60a|!}NA-?%fyP#elC+a_h`^+Z zOOnaxGg4`gaAqQlt9Y%~TZ4wPQKbR=&kWGh-r*v<18UGxAfU^bsD0EcU^LHbC-?RR zKqb`^gH$f@Gq6QUFy4#D3a^&by#yvn4OHMt1<*um-ylGhjO1^yHddGlYI%k>TCTXK2EPIOU_nyL(LtF3n`S4&HVv5r!c0wHDA1Oc9QDAP}=!!0f1scjw*37brH zXe8mH73iY4gw)a;(y)-t?Gg<#U&leP1gfp`JGCa2Y}z9LO(0|Van`#)1JvB8@~a=5 zfVO%4YR?RPT4Noo=wSzxC`a#^Q(q$x!f1BEjtwr@B#j>(!8N_TYtywqvm;a2?F*m( zl0Ek1)0RDe4JBf#Q1B=~smfdw&yhz>S%7H_-mG}hd*r##YH07zcF@6?x0`3vW8HiF z`vH_#1x2QywhrwU*pfJ=f4#i|309!Q|fJ>uMa3~PnULT_ayB;*Fw_0 znDhaqHpw2?lkV|VC%S)Z`hd~{JFNHFaDHI48x~uo{h&WBKq+M_D;45~{oM~Y?T0_C z+J&pDc5`VNad#Aq(&KC-^Dr0e(sK>_(_i0ZzyG_lcKmpjh-wkcfo#nPP>Q9J!g)uw z#W#kZrVU`&?>hzjPfy$QLmYTcZumWc3fTUE%aSCEz@+dM6{Z6E33sSB0N=1nvAT?B zpBrU6d#-Ljdp%>Xzmvki`I=o_D%o^n)y9eWfg#HdP1ydyH9I|U!KTtn*sIF1(I2#t z1N({lEXDoQ;Dlx12C-f0n|?8QVhU?WEY+ZQkS3sheQ{?Wo`PvjBX#7ohuM~Vjijga zzNaO*1OSo(WP&ZTQl)CENGa4&WgN(Cx{Au+=#=FPBY6F*SY;h)COA2PM*;>FwAB~0 zq-z0KHTs@I@+gbPx;mt$fBb<{X;py3$IZdHrj3BW3DjK=rTdsxJ(W)TwfMH(1foZt3 zF_`R;0zlnR6{cAXkpLZFj0V5~_EA#QCk!erjxmu)fokM&c8((fbvp-{RQ`t!8hEu` z?_3g```5Jw4_03i4^*LdT~a$uXBYtxY464+5=z*9lJrszIz?b27In9y=AY)5|GrQG zGm$Z8O`&|3vf!R$L7F%kW}i#SrG(B)D3a^G#z*s8!RJ~yC0!C)lBGl90)R|%N0L`- z0xC&DMz+56*gExANEruE8Y1@^^%t2ZS>iyFXOnp%Nw^r)PR-{#2TexNk`^%+RDTY= zw;aG(ow6!CthP#;Bg1)(xmVK!MG`~+v!w8H#1_P=Yb_!Z@gbc|R22@&aIJMjM3b#4s&jlq(nOL@Vrm2|M93H8r=P@TV%JFXOn9i4i#rA$b5Kcx zLK!Vdk0wEDqv~X~df(g&9PO+j;pXk5Y~9sA*=wRGZ@e!N{@V<_LAd0_vEcZytZ@OT zGl-H>T4!mO&9e$fVN1U^L`mG$SWorwLDEXHAI?L}G1SYLMB2+&X^%cS)aj=i3gbKk z5r?SXZU>Y&>RJ?yM`cu!2*;T6qrl|h+Sg-^8!;hB+7|3UYQgs7WnkYf_6UCnJC4E*-d-v;i z>sQR%&9fMpZCa>-Q|1n^^q8E8c~3 z6?^^FdHeYroA&ydF?;0(-~<4J^cNm!owp;Y^ENWQ&j$BCY=t=+_h zG^!|tlgDg;IJ)l$k@IoX$3|duU|t-!f~mp@Gc93Il6L3d7WL)7A?X8*K?j>OVpw3P zV2;FeHrTZ5zP!4LsasiT`q%CXV1l()P*1_T+w_!;j*hv_6gMIZ$RkyZ$bX2vkqsA- zPsU)SY9~fO97l_?B@81**aclk77fKzi5U_zGeA4VC~c6h0_T$h#2DmSJj$jUtZjFR zGD*}pND@Gj5=mbLVmQXbbqdJ?F@TapkWHWszSK*yK|q)ukPVk1XqQLIK?aq@($3G( z?}esay|ipsFXQcManRl`O~9Pf5OoCx%>XZ)@p7ZHfIyN&!qZX;(Td#z!?u5H&<;%J z@T`=vsomHfLdYpR3}6FeCvQ(u!O2p;3pRPdDqQbL(h*hVV;K6W5Q3}-eO6H5!SeoPpC(na51Bjm;+u9b*N_~5yI?KLW6NbagTD+fJt?L$_5ga zNM<1YAbVFGYG@RaKp}3pT6Nwb2;kg=aGv#u82p;g_<>P@>x-8b%X zE^0VRkWAZ19g+p6N~#ZFE6jTax9j%SLX*0C$4iKVZ1@PEb;&ZmI_O&OlU`W2sm8OO zhodCV9FR>)cj>>byh5~mh>~(eH%c5p|svYji<^ddR~D=Np1{u>w}W!ufN~| zryNY8Jnbta>Q!H`LE=MG z9ck9PjN~63cQBRW+aQUmitSKyM05s-4FF{&)Wx-Zl}qXl zADcd)6shuAKMGJvI6v>Ic4z@mT3D_FDAnyJe_ga6{mrUfy0u}qN}DEQnF{j4Qh^)H zVaw$|esjP5@ptxNBOyn`S`K?#K~wsY9YbKTw51Kf_k*9N&0qKCG&ZuUeF8%KA3w;! z*?<_M4VcyqY+_VlLiviE8}g|2QE~2O-mYCAvNP|O?9Df?+k3K^G&f|IOV|$LA6A6y zsln^^(8P7ycWjUCIeF6d&9rR)z%?7LT(#n*E4F@X4lB?wp%_k`Iem(F+6JcBfMfVP zjowHL?!3hYL2j1oT?if6ma9#;6ben1)JTvV2@Jh9=zfoM2bkaiR#&RFuvkTHqzuzr z@^PF(-EM3gTTV=qCO}RsCvM!GNzsO%e^L+8cla0t^dO!RI2iFP360%066NVjwA4>z zAXo;Rr4AzdCNk=*QY3*OnR`TN*OzY7bF+u(ECBZ98A)vG2dqaqbBlIY#dc>VkBpi z;|1G0GhhdH=WNex*2ZR#1Q>%dNq=R(1;GvnlBCMw%+c-L>U49vx!Ae;;m^A26kXLO z_do^xGkhQZN%r2k<|yiYyt)3j63iUN3=0`Nq060`yYKuPpw z%zca*AI4nwHRb}1^stx1QDa3`2m3VNRA%q*6}NrN#iz&MOmgzPm~5#;O2tjU(f|zd z|Igl=KUsEM_nrA(?R#}sRqyBx3kd=wK#{UYYB7WMSh8Zqo}oOBu;!PEaD)~9qx>gK zc*c@V%aSaU3TvUn4aAN{1HE^nyKCQ<_vZ6CdGozj4_%FF5F}CH%c^|$-n_Y<%$qmQ z_nvcdfZA-4;U-4YcPS)_t;)78nQ5gywt;#bdMVs!6$}t|fUsDr<&)s6c;_(E_Zk)d8sRe#B66QfVV4KEn=_(tsf$Smk24kU8Lo z#-m9XH*y-~%jh(v{_rucSv`E!RMJ{UYDOK!DvFEnxLZQK9V_+80rSdlqnT4)E*P810`7 zFPIcxI;fJQi|=fu>kn4a2kXmeUCA2UCJ4jEHY!u-QvBP0aUMYF!U2F%UcJjS zWcDMH#}fBbwE!#&(_Fm|{km2aP?Gu0(k?I**pF(!9Byo)+NDjR;i)u=0qw=b#qe*u zF_eDt<8gqbmGt)28|l`)MYfKwBe4MJ&_9;O`$yBuXI9e}FRY~(UOJvW|CQ5ehDCN5 z57uVUmABH$yYHs;Tk~o2&U`xk@)y$CuY4g5p*qkveGHQ~NIZ;TJXc`JPtO1`EhoqW zGb0lv4-?E(v?12z@e}vB?_yoQy1bSa7gn(AgjyMB!vM(6vDstnC^i-8V+9XGp)q2~ zRY;bvGJRU*dyzQ~jpFr8tKauMEnkMj~%7>}GU3?T(Y`>Xu! zKWwC{@9(BNcaR)eX16x{J;LtJ1EegnT{qiv-$qjF#tKAptZQ2-Pzxoy`qHyA6Y2b! z2>_%7cvM4z3y)ONiP=6>I{MPgu|A}F*v$&NE`>nW%{ml1KdMb13M<6@(2b7~&`GN* zd9G8NHcE}Hv#Znw{vozk&~Bw|^>p?e>QA&qX)~StWE07o;$Q)znZgA$F@rIHQUWrz zS!P_YN>C{;Xfu=Va5YCTj64pwkOvja3E-2vaUY;VfTdH?BFgq=@ex2?MAGg}fQtf| zfIAr&u*@uxltCx!qX$$XZzbMzf{{*B0T`S2few0b&m03FiBbR?>0rZ4UEAYW>Tm~U zTZkzrB@+%Y%>#icKu=Y+vLvB(vc|?Gx5^vVc8{xG4avniZHYd%ZDyh4GyqotTj(6^ zt}@d2^IBz-NE>*=fTnF{J*c;RN*x7_(Wr`!R7K9=5CEcp6lL#aB%qx<&ZGbpp}Zz) z(+zwb!}B$~V?*!lP1k}bTm)+KoLSpYU&b9J|p`=h(WlTU51O?M7V`VrtBv|G{ z&J=kg%@ew_mR|L*4`#I179(*=eM9<4z{ohAuA?nE_!0Lb$cP=0L+Z#r^dZrU<}z?% zELR0E7>@BA6m|EJy=!d#a4kJ|;dFZ8h0moge|ac<_1Blv`DaKMTRMVX(k6Y4w7#=q z4yRa$QMAS?R8=f|NHn*jcHaI}ttTpSd{T$*_4?!TEpZF2jO)2;eC@0WDD(iO$5HUp zf3NiMlhic7e|vz^lhEvOaeIK$E#|_fX$*Bh@eFPzo!0qn7{#bxg*E%Gc-Ld{S z0%Z6VuVNce%H3v%@tb1V$WPD&TSfu&I zd@F6U)v}Tujone0ps{r0#+`Kix)Mo4>9yCU($(u5>DK+*X=!~CwHUtI^7;S7)QL2E zjIER}uBR8CUQf?{VJbcS;)yiI7uy}a&Tp+?v*_lvw08YkT7KjGwDjitY39P&bo}C( zGg#JrB%w95Ngr*ZS9kl4yX@_zn>SH?THeKO z(jL1Zu}cy_%H}4joY*2+g<)O7$Zj9fN#lc?X=-pcO~Mq;jH=Q(kT^PL7wSpfThV=7^Dw_y6{^eC4$68UdTy(>l+QMXi^bOqGi^pYJ1g>M*Ue`MP@P% z+L>LR`>jn@Cka*`BRVUnw5|fEEiCP%`Q`02H#>|PD_eQf?f{7FC!}t&6hW?7)f>?Q zRd#~66x4zC0Su7D89>m$Mn~((N3|P+sxAdg;vV54L6WBo6J&cT4v`>3R)e#|5y?>}lU2qm)&UK!WC9N6;TpMbMUk8&2%?F7P9Jyd#25JlSk zEG~pZ4g{2-2JH+fKb{lYZJjnYcos0YBj_@PO6>%acRJhQ{qV*YG~zwxhQfIsXlv8i#E@z{g_;A@TeE4zGvpv`HA%?ywl z-P#%BgTy#>MyiXsB+7+O9+lzp{WL)3HNw7XM}+iI_h=+?JWvwY!KTLrQSxd2C0$4x z@$QZz#M9yEP@IRcZ|7~yEWMS^K6Nf#dghDi zg|AGdU;C}ybpCTxP%${9`kDe{jY*176^AgKH4aamO6@z3+8v`6Ef@C)C~;ahJ|idH z>-EPqtHkZ(**xz7N{^%3(Yjaq_(^JQ8vQR^Ldi<{uy#JMPg3zuY1|&5^bs9X25C8# z=&@jrg>Vk(0ZN53NB7v>$4?9>9n|#C*rah#Gd~;Q8BpRi18Zf+`9&Awxh!BGK3oP+ zT1o%)k4MrU|JRXp_u*Dr+g!sI2wz!|)L3=lynYu|kG1sgzI`eE;lH_<&YbK|r%v~W zeU!Z1lMBp?)n6*0beL6U_qc^=^{?&7#5s^4*WG@N-s3ZWGti~1E_DBHot@n3>6KUB zNw56$O1gb>7@I`1=>fpS!_|4>uB4OWTj>-kQO{j^COvcM>GbrO#q{*K#dQ44RGK<{ z0)yLFdx0_DLoB1Yv6gn07SqC;SJL8}?ZB92qWXN5rEPRTRTruhE8gzoZ^=3F7ul(8S)uQ zDM*@7Pa=}q7KY`#v(!K-IWmfz%#Be8_pfg`xj>lGma+JV>s+yIrIYyC*?y$R2GTT=NR!ij7%r!+ zFvSCSOqWm}@(KFD^7Ua%8LzsN-mTpGkSu5~^exl2`p?E%ygS3gT$>p#mTFZ+Bi|g{z9%Upbrhc4ySlp0oWBT=yoY4kbeh75a(QNh^yX`P zFK|&5WrP$KN4w6c(6XHqq8$K|JxqC&a5+_WP#c3p}Vqih#y(7@wLV7ms^-(2Rz!@=|f7AO&jhZC5YN7`vrt? z?Tz)_w1ok~4Zx;#;_U3A`bYdd#=Cj$Li{y|vq7E4m?uY>OBSfI?~)HW8!xJ-DrK<= z7aiMfV>Bu{h)E4;+EhoK4k@YFt&&dG*!ab%M!GoHNK>d^4-8IXgub4}n)7LRXDRJ6 zm+Syar`1>3W8f!g?D+XKdHUt_+{>raSH1~Q{Y5^4Op^Dgs-5g+*qmVOKumr0l$Dwb zG?y8q{Q&yRmKaqE=+F-NP^*u0K=*q6ag8Z)+wYkiyK{}-lTdmb1wZ}wN*_N-O=CXw zSz z&xZXNr8a!0WERZ@YF?xsEkH@eQhHeTvT)69iI*~`?&P+I@p4rwHu<{0ilobxw^65h zr;&aFnDol4@1~U%n1vm;{$?jC446)iZKn$-H`4iY07}n3m!5s@*>w6is%$g!7}-Yk zfo+wW?2hIad!1WtTfov)B$VE}mNxG$r!D-{#hEnsr85~&nwY_UExWgAKsAi0=CuBH zzSHxPJTKO%Id=sCyw+#8vb2&GA1<-u*$QeUt9(4}Pje^E0-nqTbC*-VFp*Yy8;ujo zFli4*#!?$O+F;R`bJRW90OF9nzOz2T?ZH`wT^2st5nFw4Ei7*qVEJy^*e8-AmWrYrvqbU>|BRJ(%A}_m`n5 z44j6NcLA^_2l~?35PgK<;XXi?GslraIysr1I*VPT3#hW4sWY}wYeNN$ZVEqyTHEj# zAWg+A%9JYg;!ax{I}ao6{hQE%9o}H{GN2@LSpX%eVcY08IqXn#k-?Nvl^&n8v!Aus zL;a|a=A!#ixd}iCq;d~wi=~B4B-FO(|9Q4HUr4jZPat)85kLu$6SPp+xhzIS4*1V? zCp>yLkOZEWiW?Wg3c#Tn2N}jOZZ*JLM@N?VJ1)Cje(oYF&s#Xfo3z#AH6T-9NQ4Q7 z%ajTj(G}q`Q)NX>>pfglJWl*+In$V|_|}c;#I$){Gr&@eTNPwbD3wa^uBhRM*~x9#_XZX9`D7}LjS_rPG!(7~S$$w4-b-}=r5Ybam@30xIN40k zJO!XM%Fc?r!$>3TrNNyCX<&O1yb3@K@T>9QhiUKO53vn(JZ%pn#r*84^zt{R(}gch zrT){Cseg{z_VbQpM?>c)w&~>-ERAv&3yZPgUg3 zHGU6JdK?8m{r5^AKS@pVJjAoq1C*YGYzM~e0ZIpwCf_K7v>Z!xC#Etvc~69L6Peua ze)qe9Qff2g-~ao6pZ?YV`LB4v@*1i>$&?p$Nn7&k9e?>0=Im4Frsxrjt&cToe%EtzjI>*>2HMU~)+0lWenynxx zBA5}}3M*_FS~>CHE5>8-brQhGR_?#<5w zfNZh@+IBiMGnSrx`eeF%el$G=pmgpuyQjgl9Y1w4jSa5wk(MvNpl}T&W14IQCZCjn z8s<_K`kN2t)7HaMBD=t-G6-n`Nk=f;|#k zPP8jC+7S#81E92kohKwzHnvvCmi|0>4vB>mFhPJK_&&eDBZU)y8vS2`HvIxhAP2#~ zQF*s{&RacGrtc2k8JQWd4iN;CB}b)%7al;V1t1YzlL=H+40Q_Ckd&qo0I8uyqL;yz z#gM^T<}3cghbcY4sP+f%3|rNwSAMHR;mVFNjDAu9dQ?0jSoIINU=TWe;hTy3d_E zYVkZZh-16GuUche4~UmA!43N%3hylRG3U~$p^7u}%Z=+d073x0FP%%L&mjE>%^V-w zSjXSOMqFPXfCIWzkeYV{k}>pitPLeAl6d;so;qxJpL_bA!+|cw5OLzU*jH)Vz`Ld; zv1SgUKu7^aWF_S6XUA~#0|&=Mj8VYSR+-XPdV0_2kh%jnDp?soWTc1Y+%C>jAFEQG zNJ_u>T$gMO%j2u62G^?Cy8Gn@c9J$W_pn2TVSDB!cT)6KDF7wNw8b@or?LB_J#Mow zSr^`+V)w1B(jTN>UdfvZpskzM$#YeYWYj!TWP9u!n2-`yT67pN+IFtfU)FMrIcFSI z^sSvuc4gfRRkTr2E}FeX#oYmPZmP~^0t4wdcKD{p#{!VjVE7bjyV`{tMjcHFK<5mM zUC~g+As>-;@q?sSt^MTWZaO!`9Jhi*SM|0IBtMaFYpI^+rJ(2M%>p}=9sL+2PMX`UERq6rOvY1jWd z>~Qk2C6qp6&u0%%`iQYzCaiKS(K{y-@AUwsLYbp`?C#^vm(8I8C7WMXS%nmzu}Pye z>$7=$G@!J-*+_3)xtHF4_ip;`pN^)#_}&=mL792jWD&d2(10jhMgJ5F(~0zd|I5Dg zum5#_I(aO6b}VKA!u{6Ra4AS&Fm;)d-ulP|U@LtG^*@R66@_=@xi4QC4;g#fAj869 zdV6m<{0_|34r}?{&7rijK9TOAKK1>-zn6aS!-e$5mA>@%w^1dE);7{y-(s2_eaP-M z)9D-E_K0lkj z`20*_11?k!*}-kPnT{W8VvHPvy5mUP4du4v`d7{1V3P{nl@JK~O&oQWBv2y|P#hHF zG+&2w7;$Sz2vAePOV4p1y3`y9O5pI2#LiiEmDkc&unp!ut_7Wp!?nk7#L4%dwBdT0 zf2DcsZ;BES+y%I^4fd)1vG8y$yyHMnarPwR^#V*EOs92My;DH7$>Ork*s$NVQ>9nU zXMpw!_U#C8@Z2cv5Gp~rR;}MchkP^*c}f@OjE{0v6NA82+&#vSDtj5!iYCEuds7ud zCC@T2A~<3>wzfPA`AF2r7kWI_nbJBM8G7=U^J~}JGW5FcdlA_2(*Tri?D8BFvrq7p z{%h=LM@QOXp9fH2cZ;3lw)#02%n^KqYP&G_mSUU$oqRR`L+MA=F000P@{vw^d3%h5 z`yV_=?;#1f!{qkNa~IS33uh=nx?#@;F`11Gp8bJcjLkzon!B?h(B*R>ut;r?#;Xmm zd)*GZ*zug^aOhdh0o@gmf-!F}hE$)DVp2c4f#*VySx~9vR8zwsxN5Fpd&fcnne#lu zsfm%YbC)=skD+#bYDj!~;pPeUN6oPSXm7hR$QaREKMM3{&nc^?DQQS5!u&YuqoWJS zGQ*;>6w65gl;&3eW|3CCgM`uTI{-LHA1U#x-KR}dao3fcTteCin{5P#I-OET?mQ{A zhnTZ`F4s2dNGJJxaSa*Pp@)7;<4}5Jh0!@@Y^O9?AAlr-%p$av_Kgp%r;$-Uer&B# z?ix1xn9Go;G1YD*VEfqZlpi|&UE@O-#wO=cZOK(4uoXV(jK2!`ILGBP~`II z;q<@$)9v)ne{Tn%WP;tUCIBLwCs=W}R(J;hN}mXs8N01=@-oxkmV0Eot(go$M?4b{ zH|NDk07}p&7|8r}#^)opS%=rTbEBT#`e|Q!G|hJ)AL`LOBXP3JUOb!yJKWUpGUwV5QdLa3jZo!*F<0`SPmqQ> zMpb0~E7u^r5nP;MmG?8haZ3o#b0>dpczoUW*m4otBG>Bb8WKNzZT5>ZYH!X1=Kx(! z%+A3)QpW%i$X5VDTEXZ9d1KMf@?Idr8dxxk|GeOr@#}DM2)Lj#%#Ae7k}sJKeiiQ% zIPp{cAYbB%xwBbAC8VD2-|Gv%umte2jLjG9Ro%ZgfNF?4lWnJmOPgtNX+16R$-hB4 zP3Sa2C9#Z@W~YY%NXF6>K+(t;jL>8g8$lBoo*sv}8cpZUVo!+uz5DnwKQywNhDUbN zAkrAxN9vPntF|$3j~T}_!O&d(C+NXX%%wKa_J_AurL$g|*k0ok$`RSOh?nnI8JTm= zybAWhwTbi*Wrg%9rHccHI$ku~`ayquNLVRB6=@|CRCkqtDA20+Ql! zr}C20F~)sb6urf1b_ROKe25yxo1Vk>9jLcI&+`h|FQ9S1YS?cDJ zrCH}Oh!JcI^xuDgp?+)ttzt`V9f=za`|EWUwY9~3#0M6E9-Z{#I|C9ysHS1JZ3B-9 zGVG8scL5ghQJ?ol_FJfhttl-DO{rEu$*Rb1JGYX1pOQd~pDlo-E&8;U0Mk(eqZQ%n zHGn&IR+}CjM7nY`9h(?T(_{VY#7JA1uWjGRC~9oXVcYf_etfKnlqKLe-!GIV9UiWy z$%+0jygoWQiuC13T3W?^-pU&D;Rvd}lWBZ}iO=>`ZM5|cyFH&z{xzb%apzWAzy4lY zxOyeszw%DnURX^t(@5UVo=LM`dO96{>6z4zI94D2&W&s7y?5VDn;+awLx9y2(Ejv= zb7|({g;aat`BeMD^QZ?8Qa?dfKu&B0+SMTm>UR^zj%Bx89#^f)&+thZo8@@erncWz zIYkdpIxOWr-SNseD90zMt!a9I(vwi^;J7_N>0sK#oiaenu|)5jm^@cPX@f<3Pvxyp z=;$3wAD3fh?DAyO1C)+Hf5sxZtDc?fEpK(l>Ao+!-VG@6opc8o`*+^HlCHe-Zu&3( zMq|F^r{S{Ud3O7t#h>BP%)b!s$VFD66O6{zuE{H^06N19~Ezz=E-h)+}{V z3Y2woRVX8romK0u-iHE8@{;I7N0|>Jbw;#on2b)>dE3~XOsT6@9f!z^xbY>s0+cX8 z&NW;CyYJK*NXWqWXv61~AMK{^{J%TtZ~tyJ-9#nr*3wd1P%Hw*-~@J!o}QdZ-}uT% z`kikLrq92C{hiY+;*U``7*UH1l`q%{89`N6thH-qj8Whz(_=VW!zcH40lgWb*XTUOF?{ zfJvT8&wgn(oxeDePOwAUENUHNFj{DHrIB$!CQNw9d^-1~+7>ym>r$nTrg~Uy57k2Y zUs~&}yKRV}Cf)hB9sX7=imUu%@3zNe&{Cq&KOvn#+Lo(GYkuKdH=gjM%13M?*K2?J zxGn9uuhfS_WqtwaiiMrDzWN~i+}u=p>fFgR3MYziNHET}q_euYpGfRKOz?*aGymvM z=!N8mZ4Vk!rq7`mK+wbLMO^OF1q!Fgs5_<{+vclOT4&q$Hc}N2NI6J~ZX;!NWG7bougSBuD_1s`{%2x2;%aR23kGiK@;7 z<5RHb{N?jeo{N|hh*-I7Qwa$x8z~?LDBv@%FHXRzPCkwW=QZo&98lCHBc2$Q<3MLp z+i%;epa_<3=D|F&%Yb#<^rM~?fDh6^0!@w?AMpV|6(tX?hGWVsJ->&F>|0lMk#t;5 z_aA@ry& zRMIV_VcIpqu9O>qGMlL2O&(8a<|L|Y6LstzanIe=!ckWq06v$bdjN{}kW!mD#xsBR z6o8UDmQrc!u9M#6nV{z`joKyO>pyxmUHR+pr`zwmkrqC9A3&&?p8ebl>GHFmOUKX8 zg|ClI(uB#h%zQn6W{9@>;4b+)rnaRGOPRooc`HJE@KzLh5!H15JW(TWbP} zd{Y?CeJG&X1C+`jiXQpMAD_ui*8`L~sd04A%lfq(58ILwzXvECmST^O*8`LuPoG%e z8Kn%o61{U`^1LUZR48+FkDYz&x!xB}PeSPk^=apNp?j^-d9T$ZB6Y;eYF$|hC&L0P zO0l7|#e(teH?F0(-n^Fn;?Iw#@BGhW*lifWi0=^glNcwvFc*l?|JqZ7=}VvQPrviE zjr7~!V0(48m!Cd1&Ei*<%muQAQKOgObzDwV)-$k>M)NS{3T%G`Sru+Ht=oqe{eRnh9;I{bHm@WZ-@mfRa1CbpuLs z8BmHj1BNgdIci76`K6w6f*j4;mNfxnnt)=NIT9=r5Ce<}uG_+m70LO{&YcDI0!I%q zM*HBwHpXc;*zpJ>+iYdOyr^OA!F2b*V0wUB-uT4(Qv!{?yIs+&=JHR-FF#}8*9B70eKvP67eFD6&&$aJVwJS4v)<1)K zw$m2NfJ%%^Q`?l=#U1bFhQ)7gbNmy>>MulrBGgnSMXZed!B0gR1Ku9wa>`9{Z@yvt#{~mQq4WXI)A^Mu1`d zDWPOxq%+TK@68!3yE-+W+F?h>25k^fGQFcFMo!hAl10C~R8Mzr_c8zMAgQ^S7Lig~THC`b zK@>?78pzmU1MCL%be?G7w*iWFctG~pg;IbGVMmNzXTVrsjBhMa_5hMO{X;|8VPiMc zz715zHqz9@FrN1-^OsVog91XR-VTZ)p$1mdJ{IYnCT-y*pEAw z&Lf>R&Muenda}aDxBvQwY4P4|BxX0$`1EKx&qfnxE?rDx z$0pP0GzPZ^nK$uUyjRvAETqME-%Af({b|~~bq9&(!8DBRq^aNfjWqR}zd=2R!tbK~ zw~0!ikJu2vUq3+BuQH${?epAMb%X(jaNTpm&k87Y=XZ!I^rHNnDDZK{gH#z1l?B-2T`V6v zqPTn)xDZs*yXGGXyAN-?dMmy8`t9^r-SwX<-zpj z7YEWm{>EPV9lXYSM^KMZQYN$9Ie!a$6rf~y+p!pq8k9GWjWOhLjp|O*&aHiBU2nGFKzs6VIscpU*FSAH?cd&^x#2)hkALi>RpyVpO+f^ig9H1oND8M2Um;0$? zVnKeAFAO3v`!<8Y$T6sY8pp$207#b7TfJPJxb3xeNZ!4&mtF;|d*h82q~sRT^&2Z` zc^RYHs+}|^(<*)gdsa<6Kj4}$O!Z-Q9hyvMrpD42Ul>ZCe{nFK!xqR{{LE|(X(Wbg zrOq}8aHJiWJ{aPf(gOCcZL(rWP-w3x)Svc=_Q2lq=|694omu1=pWH9`=W)SNI>$A`!t)L%XwX2cVqtL!KnXAjHJ_EWO^kA*@>T&#p^D@) z(~<6pPEFWdu4B>1%vw%mYQK=z{Qz}i#B0o|H%!EW7phf}b;<=>|;|NAC&hIgA;NQZI5mH6>myk7FUr)`= zMI<0Wplvewt|Ps(k%g{Wb@gO>a}Y_*(X_tRm)42Dh9uEqh|4)wR4yJS38&;LsFmJb zPqp7v!w?(uoDytf_z9$e#+ZAC0Y!%R2;=*4diFF@L&vb=HjlK?JnFWyJZH10s=4iU zElnUvGk`$Fo9Hv&>fY`lirS|31fe;OihchpoX*JmlKlX|2&{@Gph zmnzh;L!aRQpu6``rR zr1yXFR(k8Nf6VTh>uK`LG!jWC(#dDer`hwT>8~NmrC+Pb)m<+gM~m;?NO!;g)AZoV z^|S^ux63XEPkrs>^wig1PQ$3*jUWxVD-gJv=jCBk`38pUcN>ClIl@$v{1tKC>-EPq zyTmO#TZ!Ab#urprSilhfwHxt#%*@QBGTLZl;hEPYw3-TAWV z0ZN4`N9@RA@$oK}m>p4A6tiN?V3G@F7ij=Tth?WO{d#)qjT`AN|NC_MZ+|nL?qfq~ zkI$c*ETWrxD`^U&#$SDII(_*|6G$gD({Fx5QG32H4iCqdMHi`U?^(6t?I?Z!X|;HX zboovW@z;iRH?CaE!snR#^Q*2{Jm(yU?>|17lQd#FujHef0sHGQQtReP4l|Bb;`i3@uS{6~I z0`wRj;j1ys28L7l&WyJ_zj_xy!g^$9jdP1UBOJ*cG!xrSQp(IZFB=*l6lvmU08V~K z^_j}q?gIfO<51v-03{feb7$vJshEx$S*uJDFC#Z9@fX1tM<-BRj@o z2)iLLW|Ko0&YnQ>2q69oY-wxP#v!42FIM)yEY;rMWp6-ScPD7>u40 zN-`NyU(%Li5QB>-CpWuwueyxLt@VR}CdNz0e8K_rAjX$r@k|=Al|!5sW4*;@RHm~d z>hLa#j6q74JTE^Rpp?hM!KHW9zls#)cO|et;=w4K;Rq;I00ToD1Ki|g^8w-nD4crq zR+TD0#?c-Sa(&AworJOdEew4JaJUFf*;as0J7E+4r zZigyt4X?)65FIlBEeDu`1~gKRVf5j_9d_#Eh|RUSI%jxH93c_Z1n^NR2=zLy`vHT7 zM~BkH^h_F`oFM%QKsT!5%&#Z#BST0p(dVP18B`h~4R*#ua#KLbE?|lYDJ0d(Rp%2( z%0LlxjXuvEQRd^^uH5ONo~%kR5%-XM+GCeT+itQ9DBS>nuK*<`&G?An_%nG7(mbe| zqFjyb^x*oPbob0B3j$?Oeb}EgZI-bU6rm2%sRaCZem9D4dI}cFF zW7jCus^?f=`iZl_x}Z$%b^Y+XCWj<>UObF7!f+u2rg`N!Vnt-K4$k({kZ z_tj) z>E$n+O)tH4B7Obqwe+>G^A(n_jYD|to@8E-vhshdTHEYsXMMWQ+x27F%T4R%(y}al zOMD4Xh|o?`?zWDW?}8W?l2c@(5$rI~YCVH_wVM91PL7x?V!5}2TEqMA?_jKUH~szJ zEQZHiQd-{V$MEw)dbs|6IySnOzW$}pr>}nbV*1jHed&w%vB?2E;7NTA=7+76*~Zx& z)B5UsxlSz96W~ge({7oUr8RPs{zV+?&jPzCpi&%l_Dg*$0SUVo+#1Zyjj3`q4gir& zexxJ&Za~R0o;nA!b5cYmm!Da=il9|S*0r-Tuw0Y_H&iWR8asRq-|5Fbiqc#dzD0fH z?%f7E)=dQ0E}hN95`!81v46pYi-d^E_nq zdC0v<=2nU}xh3$zLzumX^8iY#fPJfB6HRG_F(ePO%3J#hjyA>fV|v;dj3@WWxU3s2 z+j0t!8F2(9C@;pV^r0>>(nAc-*m09%0Vxf`N&EmvISTrPv_f?+$2iolpp?erO&Opk z&q)E54wXSfvQHfd`h#4VQ9AEOsht7s^Hx)WvgFTE`a+=m%(bH)c;+)72JMMaq&b3S zWL_jZTICSOqI87ae}E08_uorfJR?s(QvfAv!7L1tA!v}V__bcuL?U?PXt(?97RO20 zx{8b+^+SRvw_OqED(%QE%s11G8>*`{*lCj8(C~{ZjkLsZef1t7G#(wcHRi&d3bpD3 zAQ{AdS`F!`m5o_;Bb`I42*3!x1yHrMHac83%I$tqeysG#Z9TJv2} z1AwZ#3m=(|paM3iP8zDs&Du7`vWM`zU&)*QEOA7-u!$FQXbgikrc;q$X(TI~H^4wL zlyFC#@6G(~ERD0FK;X204=EvS05$;lQ**e2(o?#1>lV!A&2$_|m5@-Pfn;Zfcyjf~ zhYiW-L+v{|~d%Dd4;6d&OBVNAe!q-R0@<-3lc?)MuZRHL1LDd)3#?4HLT*Ul2R%)`d@+%>)*4g?c= zfYReA`02k_`uMOljdyW8$IL@j|NlY&B`cVxsl!(F$i(XbN{{KP&H>ta-Z?3i#DO8_mem!NwgQ^7v5@hU1vubZ799*+Iy(H0Vw_1vGgDR z`dC_F0Xm9N?*8UHBKTKOFWN@6>$&uge&b?#>C1iT<(FaLc~R+E3gfE^R&`?S_z2fs z;m%0jlVJx0Xyqr0Qt~eOyC`LG$(@$#xX|dWk}2la@6J9XZ?G!Xc(c1d=}qr_86l0r zZu3Qa9gV65)F*!W>QZ|3wPmD}R?};5uthSGT6GMi4i0Q!x8g2fMlF5)tIq-`ollpa zuBA(tC;;ZIiD$nb*2bz?xTQHYk1w`<{lUO<<#Op#tI&eB1hZx%2=gB@G-H>yDvtLH z8O(>vyx^`f^&k(?N%V;0Pe+_mWEHfgs+0DUuy@anb2$J2KmbWZK~%ATQSMq_167Pk z0411@mNSv;L3ON{LB$mWqV=`d{&_I$nQW|A%;93fHq#Cg0~_q1v;zZMOLsAV``&xY zfObo19foiN;xDaJ{`wO2#5Tyti8MLFmv6rGk0IoA9D}mQ@Mi#%&YqY`=PviBbI;VU zQB}uQQeTif5K!8|mWuYB`UW>xRLOJ|bwdFq!JvvbFrcxM);{`~ z4gQIk<*tjI z+@;O}GoUn&%FsiY`4s@Al>n43T)c=1#CQM&s=Zma@TBu7y(147t1;%JQNCA=km!p5 zZb>hw6bS`9TJ<1JK_tjfm^DjSba4D~%LPzkT($rc>rnD3l{2iku6u$>b^ABQMO6p# zEz(aV+2fD4&j(O{uq*V=F{BHVi@sH-T;cZfUK-%hNV+^n=W|014?=S!9_@*`I98>P z^8}Mzjk(VI2-y&aG>rGGJ4^gBh)o|pVU+tJfYSBY6-+?k^yyQ88_t*7%-loDXD@(` zVE_?77`Xp{s$+JiAksEQuhD{H_cJ7l0EacEuY_j+Ow7T%Jl}#+dei6~FRdfzi%ZRP z>vkh{ZCqvESSBAOmX>3ewfm^%;CY7EXwxojLP!UXq!5MF86R7y)o$W}Dmbc649J1) zHswHfC``4lV@L^&Bi+~!jRt5NcA&$%;hSI%O^$fltsdoP9B^a;Fll0HJOH0TCh`%c z!?BQjW3fAX4Di zk8=8=oix8NpZ?t+{Zab%AN&DpVpVos1L0Z^FX!d4Eysv(^nZGQ(gA%~24^`Q5Un*a z^#G-VD0FnfyZgEaC>@=?i<)*$*rn=+nXvbzD}a)460aJWE$moqB0=(#A6`#C`O%H^ z-~VbT{qYYms+p$J%n+Yo_wJ>QwI8K(GaKpmfA`nYH^23Kdght_bQ#~zN>DFDD1%*= zgr&%G%+|V3LHuP7oG?1LxO#kqsYv~8CydTC|m)BrG z`bX2m@OV0Z8e2Ut45sJ5Fp@sU4q{JVo=B5ZFe_|JpT9f{)NyX+)-5V$y))=QXysf; zyRa^`FrwEw!|=2(duB-znt)%%S z5H;+aoI5uGpwtGya=~U~N*G0UI@;c#egKg}!>BAEI$dL%^Mt>LVO%AVZeC|cplglv z{>|ld?e+)h-otemL+o*F^}{S~r-hB3G&!)1y%D$5-bzcGTWMl+k{#yGrE_O65__u7 zu0|N!p3Q!gui&F_f|IDVO|Wy`C_s`s8^v12s&%&$CauhG8a%Jn*#aHLJ_AaElu9Z| zb3KUzP~s?)u8RZ2sxIT0xt^dwj?_-y!5VSDoh--O|68&yp{0m&{j(mO=NRFTRG$hRKUcb=(3J`Vl*(xA+g~-lk1G)J<15cm3swHirbcJ9Ma~>8G0CJ z`%8a6I=~1tG`} zU{qU1%wO)zRRh(it1smoY?#PTpVE1Zc@Yh~Kzb%*F7M&|V!C$yHoNz3r;{g7V|Q#8 zyJWyI059{X{VuT6;wb7z$0h|n*oA8w)iWhl$Qq0%JzT&THa3jrAFx~C{R}GcC<8`i zm9}>&t&~gYX z>BbQ98AM`nuQmeZhSCU1&>t6Qk_j3NlbnD!vQ4Dz!b-7 zEIJlqJaCNNFr&%Pk7HcNGnENp5__jg%Gp7#BAkO9m*2Oh^4d3A$;o*6qfvlZ+-hRz zJ0vurQH?&n{@(lP+I!ca%}nx{p9DlxS}5KPRWUJ_m~C-_UlftUX$$chU5 zElF}~O7{MBFmRhYZ!0ZIqc{a5x*nW)O~afEPi z_5h{FQRryg>+b8qaEV;^RNjt2ALcb!yP}7Cw^XaOlB@tq057fv0cYx{0d26W%@6+W zR{970_x`S){^S*Q->FZhlOuD01vgPe_@C+g+*ZHD{P*{4+X0i+3L zM=)ss-)4~V0=cu2o_Ai`pyI8cj1$IG@x`f*he8vV0yEqvd8688h;@Emh+2@|o21@D z$7&nq$IBtMBv$2M4+dk8x?-_{g)bI3U{rTuR8}zl{P4k6x^`_Rz50_zdgZ4Z>6JIH zrXOE@k1sDnX%ZVqXQn1F_&k|jc>Y-W%5NM`&%ZdHPO%L=>u}T>SjcOeC#1e$97Fv{ zHMce$+HKCu>&%$S7+T-5^e*wswM>yTt)hACa%Iuj6}rG$m^#DUIfk}YVF>XzZ||gAci0W+ z{RBAf4v>7BcG(g#Q(!KD#j4vaoQC++Ep?R5GWM$9SGe5a2ifpq>9@y;w-#Xmmk$GRJ8W>Ix1(ba}3$1u_h1234g#O`^^%S!<& z&7C+A%w>^KGOxl6f2_*15=mT{O6x=G`OkKB2xm}AkEm%dFr0Z|5`Z7?W&^!Bk}PRR zM{qx)`zYls^Auo~f=x(>1d}fqQ8;^|8Yw>qUKD46dTUZ@<8^Ts;2c!$S8*aE;&2%` zRL7i(@dl6?pptckmQ;!`z#t_TJr95=$5w(;5Fmp`N^0ivdFraL0w|Flb+Nkk$(ZN# zh~UM}T7vD`;Aw)|)Bu!fNGa73#i^+S8f8^uovRN%SV>pjy`Pqrw^7|fA_qGfLjVec zwDbN#BRyE$LsbhEFs1@O7i?<(2C&LLL3;_1m|Yk(g8c#Na~}XAAyp)xw88wa#&Kj89-07 zkFDvMn(gfaWNd_fkFiXT7PhQwh8baD=_T<Ogb~ej*!RM36gnx3d8-Q?0|+% zZ031pZH@v);7_Q_@}^-=wP?HFtP6bZiwGaMg3&LN)XkT~}`hsBNf$zv#A z=O;9ee`lh|s~z=2XZb!2ZRK848K(DIZ>hcm9X(um$w_`LxKA73zw%ys@7=2bC|$gG z5qm0AtOFV2(!Hv597vpx7yuibnZXNc(CtFe2*VT; zeDoxg_S2(vRVJ!(^hW1o)E(Xflv<=avL~H=Y9o4p(vj`Tk6-ah<;`uGRZnn!^LPqgDV)TP$DU9zqHy z?`Rf_PeNou$`ZR>;c_>Z?Q+ss`B%niBYcV92`EJv$s3h4NgGg-adUC&0@{}#V9}O~ zVwe$)o(d=dSnSf^{!lXj3_-dqgD~;r?d6{|3p>UF% zSU=mBnZhakEFhs| z_~|oq7;3~oNabW+YrB1@kI67L(kf~xXvx8F?xcJ7R@1$^8|j0aFqgNme}Zx6`IR-) zr-ooA$5Ca2G2L9lkoiuU;>-Ue%%HmojiXZa^toobbfFo*+%!@H6O-5#nHa@DnhR#jq zrrcSX#KrbesIL|3l35wg2FcLcry4GH4k8mm+e|V6@!#%qJ5;t?FI%klnf2OxII|G= z5Qrr&pWkekjW{LyeM2BW^YQF=sJw-g5MYw&1)nV|OAb-f0F+EenH|h@9>3N_MFk`+0T)8^J*KC|-csE$+cX!aGN(QrSn_M@NU*Neu9b z`Fxx-gMw1nL{jP~)ZUm=@~&ve*g{_Cn1*%+L&a5!=Z^I^gGm(95ynNhJTBVzT60Up zt@<^_mT}rHzc)&b)iDaAymqu)qV;Qqde?~fn3Sq(=f>!4a^@(GSzX!yh1FC&Y%H7%e7P${6KGhIH!W&AjJ;s(cm-TAWVNhlqm zj{KRb3aG(CS!t6741$sh_PsVULP7~Z=`a7bFa60+SR~etr4vXf_3d6wYb*Z^DV^o? ze|-CQ(?9#YuUCMQj1|U?0f92`Gs==N@9O2^@zH=%yYgkh?J_gR6>wpD;+D#rOHw|O zBcUV%ri+C!Oi@{k#)8!CsAEfN+65EXK=rDzMLJZn`caEgszqi<)d`odE`OIpRfFy7 zf4Z2y_qX@b4}P+ouH3GrJ1g9EL5+Wruh^H*rSw~0IhMZpjagLu06S2@8sdw6QzkK_ zl3=((J;nMV?G;RuQdKf=)pFdpGAPy!@3-9Co`aUthFeR0an{`Mjx>3FULxdU_aeOG zI->LAF>>K&6F_NoJxi!8uzkGD>WNcl*-rRG%-l#+vhFTQgLvxdXp>{jz?|)%UPwV z*no>H+ZSzYojFEIAZL$aU`P=88PSSG0uvq1*(FbypK&LD3Hqu}J{a$+a8urBo z9`HP1*KD~TH8npluQFFm-XZ9UNv}cB^^GYZU~TXm_YR0@OJI>WnW{p5xgUIchn< zX8T*Ob99z@J%_Y^Ex@_HGkw0B=XJ+UaZzeqNU=OFRJS($qg~|6k4O8L|CTc>#zZTm z0kfrlvAbj0h-Ix-AU z$#I(R_&i(V;32GFBr?qUdZZo^x8y|JDosQ>=qG2peO>z37mkxn4^TQn9r-g=6-G^PgGHfz?|ffpKj=-q zbpHq&NJygEX(^$bs z^hJ!5o|>LaUw*NkUc&JBvzJHG(-+6m@map6v-w#c2BWQ?9u|$GjEHU1%Oq01+-Fpm zp8%9>TTWwZGpt4Qa3yVhZj{QNvBF!w`cWqRroQbMN#E>lHidkGn|#d^AVa~)&aNF>egq!k$0#noN5oX6ny z!WK4HnhAUfm$&qu>fcMp0E4C{hST({TV#)>3ukKS>}ga^jw5k!40>Y6WafAcRg3Hg zut_2#Y+pqysB+lYQG$SXkbI6eGaWgFJ~Ad@s5O`v%g2!}C>6|%0Xff{sn^^$uZR?v z`IZHDyL~}j3B1I&is?@Kxa)oSJ}%TTF#|KI79CB|8P59V?sz)V_zk^=*V-@0n!DV|w^NFGeF_2c>F zX4E?dtLH(a{9IS9%Zd1ndmh6@O-XAWW~yY7l01Oi%NV7`c2P;MYNs}P+^7(H=>SHQ zN;1I!aHsIAq*=kRwSIXK`A(io@HzT+m(2v$u|tIPC;)qNM}V6m`3WWyaA|(Amag6H zPxskXtzKguXAa##jdhzH8U^5$INEC{nZ&#rAc9Syc2rCoP=e#$j|x#QZ7+>zv#t-- zVs};q&>0(@NF&2;XfO~vf=-M#($vHr^9#1;*ez{rygzn48v<~qh2gbzCs;Qy*iRk< zNEcx%X?&RY{iFp<8UY}~(6(x7spc?SFVHjTwA_vt(?JK&Y`3${gv||fbi;8 z+>feu2AEgJbpe)Rt(Q~8uXCyN5=_!7p>+9jmQd=4s4YOLO0&O;T;+;!*C){Dp`%bM z9}jE}Yt0+wg#p(8oPM>FD<9lh?cglq&EhmV-@p=h|puKj^*i zfBF~0=|BDrTWmFsr)dGDovVDY{9raKsp{vUtdNPqI3W_s<$R=U5nfm9P;#~X|3IE>Jj&YeonUpke3`NPB8!jfwYV}p&jh1+6BW{Rk;F`4o>63x-cm@R*_O@r75H=Yj76m`8oDR zan?(kWtZ(bp*|8}IsamxMbJyH?X0zx?R5YCL$;8w8$xAp;)8VNsS$Q%dn#Rib|yXl zbYFV<0%|81)*fSrHaZROJEq+LBthH0KaL%ptr7st5*2*Y2N=w1F$CJDMl>#o1rAIQ z!5kyM4u&y@OE2PA&N!v45?1ELa{b7o%u;bx6}s~&w|`m3&USR3ch<*nL5C&OJN1tO zl(I@!dkxT;{-e&bdYc62N#|M69*Q=Tbb>|kCzIL1XgXe<0R(Ka^iHO=xnve!7*r`h z#t!w@@U(r}l8`W+Y2dq06*Yl}<`(4HL~V>76FkCR(fDXT#`4#w=L4jRcGEE=9jA^ROT*YJ z8sU|4>QoH_;Mku-`g4X|(k3VB#M8L7BO<%}CTRD){o`Nmr`&DuInjLqusM}*&2T7D z0x;5;c1S2m5c;k)b|@+LOD@ku`8kORDdLtpA3jcb!bw;i5mH zdd?4Bksk>tbtLw*D@oVgU-`?@U*&jMf^?6EpA}HD-0nONTbEwEPmTg*9F*f>b1w0_ z0VO}&^&^capmY+uiSBCIa@Dih1C&}6X`S={r4}jnpOk@Cj^%EdJPg-+t?vO!g+fR7 zSo*pgdw|l>?aPl}^9oQ3rhat{j3--*U>G{cY5tXdV_z~=F^aChqd!nf6 zM8;-L`H%E1;K4X>JAg|2+hk_mD|vWbaT1()UgqMs4937Y8JggOav}9m(wkO#Sx(8< zl+v5Lf(epV)CIqT)WQzCwXML6E6b#y2THaV@2PV{DRtAw! z8w7OPOLrb_rxom~WCom^0gnbSwmmzBDjT~&ot(kW$?PCsy*H6QT2IGj_zE^RjoQjc znuET_rW$E*bPqcws!U*0B@|ZLKtQ2pX~7=MwthdLMDaQz+p?gc33NdYX_qfcSiH|V zf*haSal9R5_GI5p0}gOehw5Ib!vRr$5y53{FJ*OKx5Kl9(jrE=^(!kYvCG>D3>crk zcrk2TH4t@?sV!@OlGdZoddcy`)#aeQQ{s(jZP?0>F! zigg|%}szN)UKM_075muq<+?5JjK#b;En3BnI-e~E_v;wRd%CXSyQ^m`Uo~*>kJ9B zH6ry&&zH?v{DpfNz9 z@o@}ePYw+P)`OeQko`9Ejn*82dlD1|ApElG*{Ti_W0b|ZhpfX zmdCBv-Y|c`$g2Mx14h!tSSsTor*BUL+%NGWvOlB^SH+DytGuc^k2c9)w9`dZx!BEw@2sN3zY(8 z-Y&<(Ql)#W^Z=#9Qts0ouZ)9oJZx=C{BA(W@ScRyVX4@T*8`N=wAgo623k3mn`J`k z3^%L?C>07F-DBy~a_j+0N4GCOe$6`orQn8KU}8WSb)_GC{}%pc+lEqe60TwznCN~Q z*n1^iKD(9vx8MIt`qn@B9DvdefKpa5lM$>phwGtAKy0<-%mSDVUjn#B72DKK@)q>ixjn}rfRBR|^>7a5yAG-mi9NPY^%A|cEIU+Em zN{(tn6&(bMO1-S7QXZJ3<%r%4eNyUYigiSc^z-){>4V$NboJ_Ddi9Mv>H3ZBw7oiq z9Tj?g`DVJebc-#y$I}X^7wJ`X*SD%C-981qUHGqNb!Soye+;gAn zkDb|$qs}%mCjIC^X$NzxPkk8Q?cabop2Sa3HPr-V_wWpc!gt6d3MMJR(FT;b?~M*u z-dP<%A37~_Ub#`!m%NVh?6ZCSR$YFGnJhVU9ivYB>lHB!dPHzn>Yv+Xce_hLGUU4e zMhmDqE-XAm4Rkd?rIV-fE^ndob^xFhPi_~jO1|Ak$>$T&WY?`G(tloOa8t4s&d(}P1e?@E#HB{je;7$`2tfn^B;u&z1fow2G)UdIp%UxWajtJWS zQ~J*#(s5@SHQ_CQp$7JdvQ0XQqZmP*bqrQ-GR*VfDs{vZnKq8_^Vo2^dl$(fB#c&( zPFg0P2b|wu0AyNQOe?E+c3)gVJZaNS2Hfc~#wZe@NCxSmE*P(_v71?dS<$Xi7HzA! zJsUtjQw!Q+7_bK1sgLvAB4y-s17OtzOb0gtD4N115zn|F5`GkWM56#n0{}^EriM}M z8oPlZUBvE|X93+$ozmDfaYmr$03(7aCgw;U^enML81rOE!vGBBekTs)Dplls5JH3i zij4r<9S2IgZpFBC9`9575u@D=#E(?Hu!s8D&8`m>?fjOoFWWBY5vUSlgtFWBI(yAf z$BqQZ&UsQ`o0j5p+?e8hren-h5nG3nbIG?{w<7#d-wl58H-MQ@kFabU<&EPAEsgpuS^StzFIradhquGx?Tdg|) zB^K>290O27ts;za{~boT+2!p&zv7~jPs#mLX|gt-#_O-Ar!Q`&-~Z=dO5gm}v+2yq zopk1O{-W$xWhIpAfDU{Iuc`-Z#Hzd-P;!}{L-T6U@4`CSL_@rCx!=Avg;&|Bs^P9f zO?C>Z!)ye@VOUFzgSgsIYK&m0whrUAneN1C=ryu;Vmabo0O;>NOM2>!;nH;UB zV|;bLaCRWQ^lM}3g_lOsWz@1RT@+DA1R9Aw7WCN zHs2W0g%90C5&{jsboV|xvpv{AYO9tW-0MT#W;0#Cy$DmglXkX7i9e9mwvk%dSw#{- z@n|e+VGm_y6eEsEC(O)jrEv`7_79IDfiRp-o#=`$lI{qM|~dYXU%Rh319z&hLQ zPElbW1)Eo?rWC_ycxfSP7%kz)qr99x7|Z?15V4l7q=}WxW+1S z0Z2;L-nS-ktl~WG&{d~>QA?it0)M_2rLE=IU7AmoHk1|@1eE3hl$20fNlGYPxOkDi z!-i4|P!a*?AO!6({o`D@YqB`kZd;vg?Bhaa-dUgkN)qT1L{j2M?~GtNy?}vUL_+W) zW{aF(ekR-b1fWEE0bSMY$}^gu*+IrvA2i^p)RUz?>;^F{()93FD`Z!q-np7Se!GA| zE7%QNSwc1vFlc)VXpCJDcQ|gWL)YaUc0m*9F15eOXpkKy2l{rPt8|hM0?u22F3iLO zsG1E-rYXJ)up@k$7#?B117HH+70uB$#wOdd2`A03_Q@lNZgM-ZDtmjV5{@iUSSzh+}{JQvjtBZXDN{?KP^*f@&TWO90omy^SOioY}z8K)e)HkB}LRZNlMi_V}W|u~9=s zYcsw1*2DDLYs=~H{$V72_tjBsi|isHu$!J5-Ard^H`C?wL+RN|$J2AqPNZi(-=8i% zt&vz-gO}lD4?yAYD=^YL#^keQrcM#Q>dY=mjYH3q+jD?U~kW&jarz}C$mQJ!oReYid zB#9dYmQZC9`I#54WE&TyJL2L=emWEG%kfDv`P9WN^Sj4#{-{bSp|rTLSgE|B-nhJs zfzCFdlx--HGU)HPJiIG?*`lg|L8!c$hr62jC!nOH;r_ASDg}_QwkLSNm=;X53P`Kf z92;IENu#upJ1gc9p(<#0xmmt<^@GGz`YB| zwbKCP1@ztk{02`VoQRTvxIDa^J70KB*%Us-^EApcrlD)4CPO+1kY{A5iESe48QtTv z4=UAI0C;IIkIexLPSdBgkQkgf&JJla%oET~z)T6nrA3}~(q6dOpU$4@2cOP1(L$0) zDw!`{Kvz&144?WaF$g)Td)7C=?x=94u&Qdg530cK12>}=$hbxYa{VO$(n!*SK9ly@ z06W3aZQO^Bo@V7W=V(E@3Uq6gAu;vR&^L!4IqX3}Mbmq&x~*|6(;Uk@$|)|4{YQAd zKGMH74;OQRP3F1@IJE*v1M#DN^))epwVK^L9BNwjP~KyXUU)-Tqxb zLBFuDkZxSN!Lz>}#@LS^KaOPLXm|m~ZqU(kJM%njJ$mszSqhYKP>zSqy~KYMpwzE~ z5`fYPjdJ&FC>@HVJwWLIGL?Z=j*p7wJtq@=4^Vm(g^pHOXJ32X1C)+d{~flrt{D$@ zF0x?&@JjXQ>M#)-Fc&}g{x$sd^p}4eSBV7@HhKcFkT>LsNOhRQ{i`f&}IR8(iIZ`?6T z%h}RQ^L9FKny0aiZ0l`j2{SxXiIeQ)dtC6zZOMU>wg#9~gUgdK)}G5YHdc1ckO4>6?uaGu@Rpv?lRHSgb9PFL|u>w{@&N5i~BX^btU##MJ2*h%Bq zH5o@rWnydsBf5*}>M^#kbW4!aBybc99Phd>bvt+LzSaw zqxU(Jd6YA)oYeHbAtffSn&7GJ&(`~=ouo=pa%dmr!w+(n@@aFAsqQ1IdQcl4oe!b@ zLzGOHN5@i)NCrbtNib<;r2tA7*nMk^KBPbGh|)WDPV|6b=J}|6OBhEU)>e{8M{1A* zcL>Xuju*#$3~r8HPC%&|Lm{YS@kAAmj9th$DuvhBQzB7tA^+vEWBW;99;Mo5PqmyQ zHkm8dus^i4#LkY(+i4Zay)}U)z@$wyuQoOTny^jOWO4z+5xWZK{G&vYz|-QgAT9YI zWrTKG?69_lgwp!fZki{;0z2bKI-dt6hQgq=&j9DDZVh2|yN={hx3etqvQbc*QPk7M z(Z(7dVMjEy-iEPNHiFj{(bzaDrA*TZ9+7u`no@Ivb}x~B54%Ux08bMb#;&F586*s+ zIU-@?yzKnBytIwYrggfak)FOhn$DeLS4^%1gC6A^OL^Tun_^&PNG5~bonW4Mm{WH? z?Q8GlwPj{>^Sn^?ALR(JW$fAdQX2^pKr|KSMh28Dzeu^28s|KsqhmZcc}QacBf%s= zB~^~ScDACRI4d(yTv9~TFkc+?U+HJx<)5HC4bLiXU4YU6fKtC`VbA^2DUj#yJU$Ow z8J{U#IsUAGQpxAA<@e(K{3!5o#)D~ej|G%Y_I7zYY_IhIr2{Bc23k3GMspG=gV%F? z4^Zl)(9t~a?Ca9MzHppu{3_+P;kRzyf+5{S1QKQv>zRr{k8>XDuJUfn@2oZvN_ab@ zclPt5Kqu`VL3eqm;=Ema39HHERbP~q0x^dDzqz@ce)NNP(vN@ecKY+bI+^~zADx10 z!*~W@(-^z!QaE-WfBu$QjB zvzK1`>2CV}*?aHp$dV(?(?TE+&>BdcKuNNSrHh(Pj_9*}X11r#^vs^!eS)2*>Sx&f zYj;nxNe;o! z6E(J|p`^YY{=$Dp+gw6JkigqaFo*g}<_^Ol(W_ zQi1V0Sf~CHVJ^cxE1|i(jdsK~+6JreUSX`?aI>!GGP}@tGfr zai1k0m|CMUEs_tV)s^6sTV`*wXegbVKgTm)J0t?AxV8-aFtNL+t?UXA;l5A|Gt{Bp z1yza%zYmQe?I!-(J-Qj@fG5Ucve!^6(hvqeQ?YIk%QJAow`^ z6n`|!8h}g-xibj!N6?=eEnoGy?IL>*b zUN4&-pcJ`r4ASl|-1se=knX3HiP=hHjHAm)qH^C!68b{P9R4zNe}DAB1^eR%7ws4S zc*_3IKb}Hz5-5Q1GFY|u&TZP;Z)EIyKc2I<-@rq53Nqa|t5)M=yP#WhWy#KyF zW8dmcVp$M817+c}UO5s30-z+oCQznd0ZIr+5|lhw0zyAA>{cX}NMk_eCf9G2?b4N! zeg0|FKK?jopMQm4p!IubBCOa{f5YYm8}{PDIeY2FbN2R|{r28_S%fHrI|Q@>!kbGn zNzXLPQ4~%BH9?Mk#?w{?~PlR+6m%B#nn`qJwg- z>D3X8qS)hwRL1>6^&{*e-oiwg^=Y%UD%uq5XdbPz``SIW9KQ#MRH`%(a2s~}j@cJq zWbOJL1n1H{0HigvC7>5a-V*2qB2S?9JdVUUJ3eA3XQ%A++_0U*2a>k-9z_dc6k+z{ zS)B2nVW%e?Z09kzkzg0V3J76ba=2_6q;Vti&hUT(Z*(X))O=~Ih<|`g!TcnQ+Xv4T zamD3f(iqfC(o)RwRQ%EfPx*;uV%jO($?@5Ubvgx}`B8lS?goiC^zQ@Nhm;Qa;iBHf zNik=!P7=YeUEAyMlZ@5pNK-^v0SxNDy(VF}K%dnW0HtMsMx1gxpo9;l`FUw54Y2wF zjD@bK4K>S}X$c5ozCC)!kt&_gzTY#!%tGx;Ax#Po0+U)zIl>0y08o-Z-*Ui5>mqqB zs1N#bzgeW5I_;f-3&`O*x5+l9T3c&PG^+rJFy|D2qHeQ!Dsfqg(H{jH*(-x=n}NWV&~W8Dbtrma* zEJCZaDZTVxM6<3B;U8=elhILtoDm+QLj$9jpN*hV1VGO{HN?FoKV$tkwpK_l2?vzG zUIze+1~4HVB&v>sNN5B~JIV8?D<4M!iu}8cM&kFIH_DIb(T`F^X-nxy|5lfm?Anzp zXf{^t{KCAQJUvIQp6POq9fK+)G{&qX)f{$!8D;vNOsac6eNFY_HI)lNJJ0PG98l8Y z?F!B#s&sh8C>*HQ^CbkWKN%Nle4$TmOb~n~#kq~t#5((>TJK@h`&~VrdCn7!OAO?H z8&JaR=^XdGo4jeKKi#ms@Z34jeqZ24nCAd(KMe4N&~ThR#R6^g_w4{LDNiN}0+oXQ3keC`fYRdCCgyETb}74SAANEIP{{yMrtJFm z0D@%&=&5W!I=^FYeye2jubi@lS59Kyk+ZWWnh16Jt3AE)5#2F`pgZSdnqm>12t`p1 zhs*x07Y9WV$ZKmT`H=ME(uvyAvy`y`z)9#4djgAs=}!ciyc|MM7Hy6gWXe`Y;B_A_ zxJi)^y^2u0ved9UcQ*l#Hti0MweQ?6<0ondt%)5sXItGG$Mgm#+m0^a_Xr_$3hf5@ zi7Mide0;cWlOt7|og73vWeT%DfF*WungLM4+Qu~{hDKU8gahurK4~&)*ChmZ)HIa( z?rScvvlcRFDftXbv<5uD3^L3Yv+2A-OU1WqPsW`>k(?L&1b&23i(~hNeKRSwr(#@B zp>_vQN*B`H9n{!;y?RD`H+ElrP&@59KK`)ELt~*8Za+erF3Lo*Vj7D2Z~GcmRJYwe zSKIIGqz_k1p zIl#oZ{3n6`CXr+DCgHE@$n0&;QcBtj>wuHwdU$+ELuttt7cXN1SY^k~1wiCe@JL#x zFsL0OI26{A`s)PckB%m@TfkNy4zEmz3_ZE@UZm|sY=gTtkVOOB6q%C+5?mh;GY(n zLQG?^xESL?)VX30P>LKnzG?Sdr(ZTblegnLuaR=y(J8E>{Y~fso(fT57eJ|{t&F(; z4`@&a9n0Lppz&=10?M1m+BNCbFR#dPBK$O4y!KVG}XZV78aoWzj zjEe723*oS8c?4sH04A~Pn9Q_7Mo81Y;-8+I$w2%O8VBW>6h>$Z0#Gy^JZ&7J}_I+9ZS4%%4Isoy8vuyFDQUzdXYZb|)~!!K7^zpDGjM+r)L7 zoWNjlVw@d6hV8_uyiHQhot-mC2M=;+oA3|a4A=aqRs*0UA69waHA?+DhfO+e`AaD^z>UlczPK#pr3f zOuB_sV-Gou@5flI`r#Y$GUR$wjGGeV(6;Yeg{!!`- zRc!#iKu^+$MlACyFVo3W8S$tN__B@@p!IcpD1lIJ;zQ}g+zDHF0YGVR5Un48Po5W| zQBxIzgFI+8YODHPOfh#+dx^{3am%DD&(j#G7{@LDXElL8XcTTMVro_eAO!;g=#h32 z;1K@YO04$=G-joJBg~3XNV{lz4L!JZ9AOhTi0e4SUIkRz#Dud1y=Bz)s&$-UH+FD* zO&h2)RRD%sGSPEYLK+c4YBVBM8XdmkavAOybw$8Ukxe024;71O2MwcPgw|1U8-S?B zZikaLJ~ZL?kM5(W&>?fTDjHI1e;BY&&k{q`J3?V?eaUXz3V_n-Q!m); z%xU-(!R=5+0KYVjbnhR4SA~MfoW~O=^}}$_(P8@fK{UqvblK2gQlD0RQHcpL#sVP? zxoSYqAf1TaS`gcJHH1gi7UrDq~}y4Nxy7*fYR}tTmR;ZAB+qkeh0=> zK9kzg9GTkjLs3;U=h}u@S~DefCi?9!E_wXu^AY=}%OkekkcJGJJac*b_untr4}Vy+ zcitVgS6|ik(q+IHX()wHc*G~HN=E#{olNL($`S!UIf1sAs@5K2b6{))Xj#27Hu5_3{K6>06juw1y) zC*@KA06+jqL_t(jM)I!kDCyk;8l_pT!)*rFE4L zJafT$Jqv(@-zWUNDBioVV|T7?W1dsD4J^ynw{ZNsRz;c*Fg>OwWZa z#It$%VS(aA0u!tt@ys1=qiG_IE%#&Pk|to1Oy7JA8i&kGWR|GPj7)r!iBlrYIxlod zbyGpJ9@?Ne=c6v}Efctus^k-r&JFwyB~(|mitQjJEr+3fs^9Zx5aj_?iDG=hUkV<{H4vs%xp8KX(QYWe5!+IqnbZHa%2P zBhxA0MGzoJW|!LGUJj{IbVMrzce{1{>3=HqEH)&{7S=q}KA zAL~n67e&^;+LG>L4o#nad=p7CQOXzvX#%18lLvg(aumqRtpg9_m_CoG8Ggesi5=jX zF*MM!iP1qoSnjj7|Dtf`YEJdM(n9gw*cf=hBj*4|@?RAE83ipP0a4kU<{rlQbBMYM zx<>@kIl%&SloyiJ?Gdu$((uI))=yG0ERfWyRgrkAYHMrDXeeD}zG`;%%skp@(ohl@ z3r&nAj7s;sXh>EXZK#?1LZq*Kfeg<}l};VDi=_|Z^`!64+768;T&9N3!x~Rl*Rig| z(&3sGkW8qhY1Iko<4$hp=o<+rX?S9e22cDF|4E9{Q0f6nV$RVDhk8dPB*(IycV@Vd z{>FbCK&iXEqs5{Be^C?X_^_i^`4~0#inngwazD9hqi6DVSWb4z^#G*~FZLY8#TnD? z2S?0TC0*+QN_*IMEKkyNssW^5Ha$S;_)V#QJn!>m96ze{0iG4up})+NDOt0@xuS%X z0)L4VsG)VSiD3EnKfho<|N9Ge@rx<@u~IzlS~pDWUo zn8atxD=+5k)t3O1&_Ei&tW9876Cg=iDz|Un!2}53SgJdL78)*)in3Zu=7Pdbrsg=C zkx3iUxCec>Xp9KP?SKI14!D!K_4P+NO@0iL_4WWt0xz^)I%_5XQgMC6is>}@XiC)) zuY=zv?||l%5(FwG6C2lPxUm1PFXIj=_ZNaJr>spLh23A4coBl{lm?RG-Qplw>8_ic ziV*^Ai8{TsOWldKw<-(?{+^Vq7 zFx|?tHFzKQDZBWIEfxF;3DjA_*Vqz{+oz|;?cA9YfG9rkamwkt6Xd5z_t7@H2yS9- zwkZuEwB|N(48H|Xq!|60^$XAew3aKPx*WoDZBsj{p`9enqza(Y<_5lyXk#0jx6N9^ z?v3^c!ZWBPcE8Z!!_$eIWf{(9ND!ZW}fnOG=_QF5cf|%;7}1DY7!uJ zayos_hBX-IObF96Ew$b}x4lld#52evFb4Kqb9`6|R9^G1r>Eq*9-wqs&K+E?2PhrD zo47b*+Wp{&`KqpKJwWLIMjoT=^qh+9^vk9PC>^7TOi1R{D%)iQ&CLtlgbM%q#0+(dtb`b=G9L|BV z+h{ld^#EvP5E!#L90a2+)u?4`W5w*+<)&S^)UZ!3lzQ$;&_ zx?uC?^Y+3*zr8R&!ZEv;&EPKx03|s5rT0t~p%cvu1u(0tsLz4h3fu9#TJQsl1!t6`VwX663ls_^HVt|-IX(fP zgoY6s6yxk%H#&tUBZT691ZO$;eeQ^wGy^^*Z33y@Dacs@j(+P;Z8BEi10prYKa2ZTp)K;KH^lGhzbG55uU00H%IuAsIe7`24luVUTF-L_ug&h2H$+Odj z&o^3jp)pFRE<6>`D1gm-ZUahU0QZZuZ_rQ)%~OIl!+2u5A|`-Ij@jv+QA1j9J~sd* zwC{Z-b0KHNuAu~Q88nonm6)?WoTcaGn~SdXELgeIVr>yu?sy!+so3P~NldW@oos0p z$>B9hjjZty<^M?Lrt)31w%Wq%3@~W3X&c)O{B~7{HLimPp{0~(P|{Ko-sn4{QMW>V zRc&yO*NJ6zB`nKt5+A=I;#6LMn7Ge43-G6(@fR_>9A_uS5x^d4{>YzD&UxAgE7T7k z&hR7)a3}C+SY~Qy7)?zK+Vs?*n`X*PP>!$%0axARjCQ1@lv7*Y9_RF#=TU}FZA^eD zk0z7)lVxX~bO7H;MNHPXS%}OLhgx3zXX-dlrp@mG=<>Tp7gHh5mCv)*i#wN23aBx^ zmFUpdO;_bqJDo%CozswZzUR_)17Qhy_+VSX_uO@y``6ql^U0GZsqas25~V7cZa4I% zIZ3w~a=mK%@R1Kv4W1fYzc&{Fg##pv<--mkXZ~PvhbU0of)lzYe4@;lQ$EdmQ0ZNDE+`;8~ zfYJfHiHkF)-4CL;5S6dk1C$P6MKZ}% zY*i8D`3raw0gZ5w_eQKxwA4H!5oH&$V1fUxc(X}4FKgRM5>gAAQ>r${VFfQiRz0QYjMkDaQT|2|VGtMc?x=3_^lc0%h~DimYqP;=S@;RO3=B-NRg8ELpycf2N1|WgccR13S9JgkJluSGEYvEt5ykEi|bp3Sk11H6zLVPRU=nmtAyE3S%H?)K2jG! zLn)#{YDa+!n4#^;^zA-rmV8>3W>N+duM9vW6J;4dLZKiTG~Lv;FICy1dHpaJ@wUCI zoUSENW3F+3UFUuhK)ZhL7V#zs3K~q~C!u4=8i`riHX23pZzTL#AdYqyR9r(#aA^fl z2@RvIZTvBnDrgsN+H$oNXz_9BM^q4;P5vXI$VlczS;>8-Vwt`Xn}&`7oMFo`d;y-w zyU}o=X{T`*e~RaioXQVsmowee9>igRp8!p&0|+$4Js@92QxjP<_Rz>A4+~RF)i7U^ zLu^tlXJ67v)lNE1uEjE8>9Zb0HrM2j&XF_G0NTVa%K;h~OK6jOLDxb>wVn!oH-&Rm z49xNK^gR%`L?0K(z~c<^7bg)yT5D?P`aNdo)Z_R z()}J9aUtrOVh>O{fRV>2JI;9|IsLNf0ZNf8$0zmAX+8|Qz7xauBKNg~wB6kb5kM&^ z)M#V@l=Rn%J_IVXeh@HM*BZ8Xvt+;g<>&TGG?eZx&)Ut^SzDEyj;g_%3&Zwb{?n}e z3_$6{`MjNBTY14r0Z@`4mk5T*2fVrpA#|$mR|TC#K*_&o$?!EPT0N-M4P;(SxaxhF z$>12gQnY$`z?K1Dt}mADt4mG$4z^e=TUIe!Y+-6?X41k(x!t+4k!T}$)CpT>?{Bl^MOg9`$-a@#Q0t4 z0Ihd$ao;xt|+^(h9#Xiv3DGXcJ980>WZs)8THikzm}>*RV@?K;8SF08C@ zCH|_0q8g3DWy}j@B)lrhM^77w374oDsPZPLrg`Wr5EW8pdr|p$FjdoyldLWQCmscN zKm+rsBL#0=KjD-N4z#^}8c_0U$_xGMRuGf{lxp~+!rc(shG@LuE2)NGF%-?LtliP% zLx^kAD9Qs;wdlXaeclid1UST|Uff$UOAC(OZ{BR!*4h$|u9s{V5GOY<#yzMu@l{ku zdx(x|Y+ojAwOpQ+&G4jww2ejDCMIh#W7}b!Z`JBnLgUTt+hnRmEI@-CT=!$Hn#X}q z5wvFrV5d)NKyo52z$FRd7)4p@LpC}%ir*rhQIze+Ja4EEKxtst=6LqZoI<;j^$i}* z+EnE>1AV=)R9%y(-!+Ud_e6Vd2n)VE0G!H$>*CW0_`5Hu*C9cTc?iC~;swh2p?(A~ zCOyJr2bDAi8uqL3UQmVyGJO5|8V*^Zq0o+UbiKXKViCVd!W|Z~;uzJkVr-%NTvx(9 zsuBquv5~HJ1E6#baIkJ|Kq>Xi3)Nyz-l}Kq8BT2biKco^bkW{DmUe&X`>&mu@HEoi z$=~lNj4a_>EYRJ3%s-B)*q{){l&~cYDD`%E3oJTHzxUq*2U8czhWBNsT>2Zor=is0 z%W*u4bNnc@tBzt1P_9?hb_*y5cPmk>;Xy#F!C5>ch7nHWzz$cj?qLW zr0P=|IkEdYF$f#_ASbqPw!DjZR|Y``gacs^C%u3*8KkZPj+=2=0+7+PtJk;fS3d_( z`iIYLtvq8ZiU_WCgvz%UM(lt6&vW*(pN`r5*_@p`kp`3`AWIAk0(458N~jFtQu>>= zQzpFZI-(OGOl!kqJ~M*p$%rlA%-OB0{5AE(oe`^sIjrDgmgDWcJ_u_Q1FVSJNgeAxKz zYTw25jmg1rJB4%cGiSyySu0}Fh6WNlv<*+2jbX}nYOY`> zr`hf~ar~P@SmzH?d_-V2#5U&{IsFZ*!s&NlBpKokS|wYXJGMdJ8~9PubKuOGGj8@K zFi9qG(#jF26yF6twx|UYSw+jb-sWm#nU*2{V1*0fN@Ivvi`R-(lT=OVF#dXT-d3pX z#k@dVL!E|0J(W|fn6EXepmT4{&wTzcuM%L>F_lYbcFMI{X;Eq^B!28Q<4?LR9mlBa zRM4(=+@vydY--)Geq@f7BRZY>=`_)O;^*Nqzwo>XUeh3M;e%+M9nwkwI@MAJ$J(s1 z6>S9%$cYA`?&|`Wj=&RH-058YisbjG>^rOB7#m+?E7-NJvU}i8Wz$O4P5MLY5TK_) zTF3WNjaWq!uR+YoVZMwlVWDWM1-uesn!dQibjajfSHrrheMz`131Z_ z811*2F*N5e8_USz78+x4esD4fU^)tLI>_^>h?(Y~0McQZx*59@vO^*3KMPPMz$|p= zopRh+qteFHb=~^{n1pXRcBM{a4yYXo(`IIBDi!pk&|C#@NZMoy!6%O%5l*X5jQ^04 zP|s-_P*RncuVW7?*KUDhCy2h1`k@fNNxP}@@I(n$)PkZ$-Wk1G3+;t=btN74w)x0_ z5>0ngnQr~b9`B`fuhvw$Cx5!6Gg8Ngqc-wv&%M33`&669@GxP6fB!Kqe@>GZcX^Y~ zymRyCZG2q*)p(EShUtap&Vlal^#>6Y%Z7JwD5+z8wicJmV`(VKY%Kf>;*EqbdZllDkBb)lMBzty3XXLtrT(t_ zn+YP33rv`G?c$fHQtCrcF4(0DS^M)JGjC5XYb`w*uQhAh}+=kI)=tFCv&%XCo z#@>HFiFEM(coKW${0Q zGvlhQfee&!LR`$(@pn{56A9l)19h9jC(Zk(a-$LfsNCtQBzKSt`fQhC~a>6D50e!(>DP}4k)3aq~}A}!7jW5 zR7Y)l-Lw{sx{aNSO$zPF<}l%vfQXo{%U(o3qD9Rn{C6`UWhp-iUfwIjoOqo~+7Du7 zC=jb@eMND*1EQsf;Hm>kDhH2r>}W~5&rmkh4FvkSabi1k+;=2^B?gW&@|nfW+TggA zfJ(apV&o@GT0^W&H$_ELq=9oGIr3J}YDK?{REwFh!E^l1JD{|VXZDr#Dkh6)4@pyK z9k6mKm`h44PCNGHaSoJ6BS_6P@p&Y0v$VrbY5+;nXsQ4_ZCCMoMENSFtyRFI0&9Li zJC2byxHrWUo)~~hO|*sAmX}m77uuxCwrYfS2iaXsC#WToKdDj7n0L zOV8j`ycaDBG2QPh`aSu>>IPZ>2i8#lPLa*juLElsYm3k&`kHWqC%k}`J`+4Fy zadE~p{UA~SU55Wfny()s}845*FqFqfN;l7nS z>Iv}!8Lfid76K|lf;17zn7~9p>E}QH)PDXCpR!BStZmdVdBa~z1Cy7%fKny_lpGF9 zge&zZ;gYryng!f=*T_x&BIAl{2lz*=o-IU`k%!?d2#kYDL0F3_SBsZRb`6m0!+*`& zKmWdHS8!6jS=vMht{}pqy?|7E7BjE2XGiRZKgin;ew4$95SkAFE!qxT!T;*7Lyg@# z4NQ>Wz$49R<2NZlg1M2Oa;PA)H3^+6;ZXvmz!;_8fEV+N+Rj|NSgoUlv~m~UG>bcS z>Ds#8y3=4Mts%643bwesW!KiWFnuetJ$l78JZii6zkz3Yr2cWVsZLK0+R2%s&79oz zI6KvEvp5=`nkm@SY(GE}W0x5a+DP~wc1ObQR9Ng6k^IQ4$9>BP^bwd8I1vkkl(KrR zm#|yf!ft6(W^Y>oP&$43w9U-Sz_J8TQo~+eRRiz#jNh|0e@*~t5}fb!?z|^Wq+icg zQD4BU1F=;sbx?w7&~ci-6!kj#xi2K0c!{WG6bk8z#A5}40D-#hMzjvega5lYpbtH% zhUX^dzG5H>RJ~PHn{C)8n&7T2?k>gMtw3>?;#LUm!6CRi1&X_CaVb!sxVyV+aW6aH zKYP~99P%z!a**eFZ@G+a6uEJ>WTAcFbpHMzloSn!ek7?sg38Zi?ojel(}?^&{b@yf z6_l*Ivh;K2neG%RB@(hoC7zA_YH8Z=oqM&Xv+6fXLzfzi>dH?}jJo|1D@4^}GSPw5 zX>Z$~h5DpgC5o(P;Df$kNC|gb*(X4yH9UZ|@naiiq9BNTFRb%-SCvv-b5s>apa^^p z_G2@zul_1QM-F4$)|B4E5AN;Hx;dCy=a3TjbV@CMu@&hzSTEwfaBO~@Ep_s^D(l?W z-$CH?BEMYMSniJ?^+^(o@kIo2dLT5H0#ds6Pu()hkbO=Y}PF1Z^#@kAtY+j~$2 zsTs?3PMy}L>m`Z4W9qNLC*xNdDAuB@vzrcA*chO`T!ji8q4;CiOzcqPSUCYL)Hce( zSw&%aql}TU(4>{HzdQW314-?aIJ(G z7G7_$)1B|;nFE*Ik9JTYl&lZat}kiWi0;B6uNLK7?B=YhJjVe6*?@rPr(-7a!h{ef zm3VN{8tE(Y!yN|9Nwq$D2b$*%X7^)A_68sYd|>yB)5`YoC2@JyhYe%p{k}!xel|C5 zFtDX1Myist7fRbIPqR8PgFGY~FnD1epbnNLuRQ^a+dw2nD>kOb<7 z&BMQxSkXCucr~kXv0|0G)*$AaQXlYK1>&1NARKS9E13HEBR_R~2lP;^Gk9LCGjKNU z;ga654Z`Ol!bI|`Q33=98GJ6yBV;8w@j7sm$Q{ylv&r7s6FvaN%=Drx6MD8(k}mv} z(gF%s{=g(OC&*!{)Ule`{nR&DY zu3^y0y?y4c1`NvlP2}d&Zp5EdHqqucqo4R@7so%$zpv>@pcGHpm;gufq^vzP&hF<6 z^S9AFZJ?Awe1J!WoByY8#H&r`xfNh=Cm2>9KzNazpY+^Al@kGv#-C=Hbjl4I4|JeFjx*;k89}Kv$jtWeaz;uyvqBT*+5QSbouwJ98I=N3MQ!VU!;3;R{GIzZbbI ztSSc+=UyADJ=LfA*4(e*MScJo&bH)TyFW0e+S7rQBMl+GpG`M>TeHFy$HfgwFBsO@ zY*RI5%P%egMCD!F5oSU_hlG1IPr+fk>YEsKR3^e!%9@Y`!Gsh(+LEJ^ORQr^(pVV$ zrza7tp{skcyHfOseqNGl?>TL<+RpY{pGdj1u$epCMIi{zgI^}D-UkeB^}fqL_ZsY3 zqDBwKm8m!A?JKV@de!bsgFGK+XpE!(665WN6ie40p87-7f#|e;sQ0}$hvGh67!vZI zPA|tbpKkg5G5?=?Y5rf-?;_d%LSk~ENDNW*A4GM72tgg_D48fV$akJ|`oDmfV6Rx1 zFOn7gWx)ViKg`oU{f#)7yrK~#_%D~+mv_$7e_^@}1lPP1%gw-8$?ZAzhcreXE zLg0BqKa0^?r9*SQf(iwdA`&kjrYI7}v|7HiXLkS%cT#GkJ~K$QdI9@rKdoZ&qB`wt zOk4luz4J$+UGalv8}cN=4VQglI1JAb>40!ze3I9OznfZefgz?D!j!FT3^+&v}o*_{X_7H7{ogYnCB zdNP@hwM@=zcCf0c9`cR#!`|?!@>x!NerG4-vwWIi;AwU{7+ozjcP4CNoabbUYO(4~ zY!W?8^w{MwP_9z!D1B53I^y{oOO{51IZ=suFbMM_fMb0Q!?jiKBd$gPSSmTbG2hgN z9Umqd0T7N5S@BtqL@i_MAb1=8 zqJ2{mV0zK(YYWMs9k1N7Ep{%ruL)J<%V@Bk^Og)PP0>?B@`zjr%E7e}n9oRs^n5jz z99}6wH71wS>0<4}S$ActxCASZ*!(KJ)M5=gHPZQpOhPZa{Yv;+Atu75ou+dp*wHy} z!=taOTbEo4O!57tCfR=pO!@3a&?vT;ylW-y(1Ci$<_0g?($IY$sGT~1*NEH=c9m@o zynV<$m;x5FbvKrmGiK)Iw$xv71n>#w-B#i6C+@G@P=6XRiIR~p zk%OU6YR_hOdQ2Ck3}BD1pLg>Qx}jU#JIm7ly4LPTmq_bR3%>| zei<7U-aM{Z11E;!6H-eQi+}bbF?hMckm*`sqop95>0aqQ)!ToMvDII6S30C1@UL>U z#zV(}9|~z=tY)>wlRN!1y5gQwA?Gev0I?g7Z_Oil#mEP0N)`cIbk?yHx-wszNL4bTI7SqQ|~=*Pfy^$IW!+(;k_aM>r*c@&=X6LRUZ>@EI@0_D?cVSHg2e$|<9y4&0O zTh~FQ0|l}VzUe;MBBNUm`JStPI%*YyWeTNFju-9EkQU=%EMH4hVC7L!Z!S{w{TF{q z2ITGs3HJ*77#00-yh|rbjk`Eh@?Dfc|K8NZqu<#a5qTR28|gA6I)s-V_0M6hfepF7 zI(^{P==n?lYf(axTt*^`>$}daSmX7^1yCMycP+RUs%e0I#KpH%d|)oI)k}wJ6s*NC zNNYQ94Nm!G0+uOyHaa{e9X47c0qdW)2XmQ_fyPyx5|=?D+YQf zcE~jFWxHkk-;MF&8KPK9+bWtQBaHL43i&o`szeN&Q|kBkyG-RHm;^*|`7LFHcP`Tx z7Z5_8+MI)Cl)~u8m)qHoFE>{D;JZ-{l92e-*gK#5`2~?omb0bu@`_)AVwRVk;EArg zlaOq${BQJ=P3)r*Q=|obhH_&kuzI?KIVc?1J)wCu1aO+-_;Wl#@?w&eV@U+zne#nF z$dxdrMH2Jk4b~q&Au-b!^=7W&pYm7Nzi}~Z z=$=K{oq%@F!1#Rh>zVSBY@w!TM(h<$ToAR=*~(vn1D|Br^oH1_zwAO6`69g~x}dNv za~X{2d}Du$5ABX@*_W~TAw4vUs@JD`ZQvwJL?cg)5d|h@)aQcXOt9DLnt{jP%P~U5 zjlcPyT}5-1!$uHYK#;ma&q+BK4)AAcq>>tG=z*;4;vIsmTKzMowpo{f422<8wtjoQMcj#R)GXjH;wk;j&UOX#`0;vLPi^5F!9Ms z$yVc*p&G_>o4B&ABiM2o!!j1WF%jkQT9O#uo<_i^7V?lHz;I8ZJPC(G-rt50Z^` zgcweSMZjK5d`{stk$Nra92MsuwqwBPEF_qWJs@2+FS6W ziuaRB{c`a_Z1*tGuz@{1(@5^)|CW|O*`ALaRcuegLjR-w?x`j+qi?UPG^CczfB4Qn zB}^DkNyuqDkv9F*b?_~%Ggyb(&neO~HMvM4u( z+=DHyDVftlw$2zhq0C6?=@9=(K3nGH7FoUwaMq@Iqx?)xrx@yynFbT`>v{t~d+^mC0f zTnn=UmDs>0pBWvnhkWicrOF8~{GxaiSoXp8^Fhwm7XFv8Gzk;srR_Z3P{X>4e&%SU z4wqlnxxT)mqOW~Cuax%7f<&Z3AdxFsKR$crRg$e9lCdQeY)XT?iOFJjOSI?izhsgX{~tN0OOx0?TWHIX2XonRC9r6s?ZRYXP0rT+_`j>ktN^pXIK7ZcJ zr5D<7FVywGL6tZipPXcsn&ra{_1B5$kp3G_Hg^E6;xInmlq%8ga&(wFRMzv!$H6+Q z5?V+T_*?3Ip%1e7H>?d1IYiDtW>3)eRyR(h)!;wUf|zsuAGdC^_669K``xjtv1r%z zZ0M4AS0K07=~nigq4$Vd%>OlCGYLy$M z1d(x{@N?72b6I@%$FE&H8^IU4r-jUfvT2`Jo~EPChuL*-fLxKfW|RHyvmLF@4M`lj zU)854vdQX?%SD;db`3nS-l6ye)KnPOOH+*0l-}1MQUW<*e=JCqfS!H&{S$^+$-UEh>7dl6ZJ=>bjA`O00e*`0hZ2J25ZbZ^M=oUV@n^mvQN_r!MwmxSbhQ zcsX{7WH5-Faw{GUAGi^A^_|;SI751FbeQjgv0_HXlHKJ8GoN|8bEOC*;y;8dyxqZQH!GZXdkje!2ht6?|A%HWC>lVOJ+*UcChH<555P0\t`5pQq9BZZ^Ab! z#FG^zr9{dOwki~WdNEo;zk{_tt#uxdLZYEZ<>|?$HJ9p@h==cMrT};R-^5TtBiQik znr*rU0nj9;mtVhG7obc7(4TmWWZP7WV4^!P_9@(J7Yk6ZU_+jGiWLPze#2mFWv!fDOKouNpsAwKmWJGAgsU-w#ZpCJV0DjV8UD_ygmMAzkeY#z)zeF%);-y835R@7Qm-224iBxwZ_3zrx~xz13-;lk|k|KKN!k3o^v z55d%|M*Gb7-2a>H_di$BoI8?H{jL)n6QXIBC3;O;>hW1jw6|$hgD-C{17^F+NS1lG z7vKG5Z&vALKj3}I|7lfh#qy0?kHG5e^|A367(C+tS}5^S**&r9vC(UQ#!Z2Egcb8g zFi-N4V3Ca~1?k3rzYwW>v%Jr(Y$YC9ZMtT&_vwDV#P4>x`E69JdI>+RWovWDd2hT}nq-c*vv({N|?ZUe|mTByLZ1|F;RXTM(iLZfXuMQS?Rk7{?s zKr^LOQ^SrzAky~}PW)i+0zeUIb;k;?|4-g2lFBwCWltG(@qaOT6uM;ApLtzy>Ud14 zrrt=Ai;i0;caSP1`j*V%FymH_04u&yw8TVT8*XmkecprsjgSJAj9p>#ky+_rVuVpK zK4#_}S$Pvxa`D0}%Li8@ll3wMV|uxhXj1o&L~V+plw#=S~eHzZEYOd zR3nWut|sMo6{u+F+55Znn$ljh^Kj^Jf@lqv;ha*4uyArzO3)uAO*$X!)j=nY>^^#P zI0?&;%@4<8it*@&qDeYu5w1fzK?cP$#Y~9fym3j$+XzaEe`R>9jN9RYPuYwGc{|6xP$UsPOSZfV@PoVQR472|*OLzV{eUtCTO)n56=k35O6G+bl2r&T4N2RC& z1Lbfql3%=GmGaqGxz8F@pq`K|xyx(;4{i2~mVfiPZEMFBmxtO z`|#Fm=ptf=iK($!Z%xUXEG*V&D3~FlOyLKUHaXc-*Z1^2m74*LHo1OAe~fV;7+q0C z-_^x~%^a#68j{_8USbJ-ZpI0Hw)g#o-X+OyNFjL0KhczhCK=n=@E+=^$ps{Y7<)KO z%iQF9kkHu6dl$}D5^cj9;jrq_5*j}nv@Ke+6o##LKy!)8R%469>@_)?Kz$>S z#(Fcvs{Hc#U{a?t20C)zk%~3dZwkt=tYma} z==~=vxnyCsk_7hy225Yi_)B9by(j%~M%;VYr4VP4X`v%yHU zK;6%NUx-q8Dk(Qn6nr37f}o`ye3!3k{jbS25mh z|3GdbC&ommBr)5R)9;)qjS2cBJpe53_1qz?klcy!7df-0VDw3klRBq=W+n;_Q(xM* z_cwwhai`48U7mBsNV_Hw&2CVs9HV8lKf1Ahk5>*F_y`@{ac_^%N$ZIctvF)$tp9xw zB9f29q&+kDp>s@Bm=rtDX$fYKPeXmMEVcO024bg`y!h~m-CXTSmwv=^vY*kzw|ek{ znY8S~itrdgoZb&;tJxFNABs17F&y`Q3sv|_*R6e*hQeoJ{}4aIA&aI!c|cq_YqGC7 z^EZNbV;kYRHS&V8AdG=$9l$QulV&*vdVy@9#u!r@dxq9t8FKQ2L#wU-<#;KW%Z^z zl=`q{lmpjq=C%(AV6~`pcBPL9=b>#uzn+O2e`Ph?K!5ESgdxb9NW|nb)yfxXVbTZu zy}tzKI0MwPROfRC4{1|~YBE$AZkQ+*)Ah#AF>D5lZN^SU8bhIOfxsw19W1w!CntoE zPyWAH8ONLB=e7TSqnT~;r{YzUW7v&t*POY(5AhT_pE<2( z<7{{uBTrxo04aOy9lddWS_fq?OPUg{C2KwOAD@Ii4I$_m>!nEpGGNp?+IiR&stTm% zKr@6L&-rOm9~y(6Xt5Qzv&zg%bnVRa7CtkVA(e3<@b|A_)WTL>nph%Zg;0Cfe^#^A zTKkUtwVonCm4tqx-<2Ym&@Aw7N_I?+IO5+65Ii1lz z*(;7lMH4G6gE6l&rBp}b=^7eG^p7mx6zdXa-V318&pa{$Wr1yRwd$~s`FA)AXs@Qd z6;+ou=CckgH7nJp%)H}(!^vFpG(PTfz$Ry8F12It;?E4UM&~(X?AI&*6eUAMLLuq) zcwgB@@Y6-*ORgA;_%ZhIQf@1_#*;MIbMxc9Me!*3yN`V7i5j2@P+X}KG`!l2dILVW zWi-b1j@u+pcg3svC(?~|bZsnRcVB$tTxPBbqmp~NL>7L5xOn_;BD&a*?1uuh5@~3_ zq#SSzL${fUva*!(uYUxDKZ&fn{5Q0HI*jvgll_XRhgjbURb4WQ;)=^v`6k65Qgib_ zbtaJE2+WHAXaZ(k6{jotK-ynNPn+u-K#SX-xs-@Au0-+QpC@#Y*gY;cnur&tRd?8) z3aMwBRa3%}{^_CTN1?25rf`TEoWF@;AZC@u4}3W$bXz(VB zwiA&maX5ppa2S%nNpPECuj3HxswyoJR-=iPo&Bu0f0%q{e76lKDC}I^p#zirdZK+$ zIFQ{${r84ntqIp-TTV`LGs38Hu;j>ud!{brkf3Jmw1q@KAcd}Lp7Wzgl2i$8j8b2) z2hN;UPHx@kcP6Co$l~e{g?=9|>KU;sb8;3eE$WaO&0K~X9)eU;kNOxANgvr5f=!9y za};P0=P_!7s9sj~kAC{ObX$aSbVS~CZzoF+nVRgUMpU9yGmPsYi8k)26M%;j3S&i8 z)xJRk68o3My_Yh$Xa)X`jg^VVHpRJ%wbkZKkG;`wl(E{eX(p}4NI-nXQbkjdAsi(G zuQU3)^w@XumnGmld*7H;kvVxIdnDryL653(hRm`kYx9xhz+bNc#I$)t3 z$mAT_rUfh*!yz=LKN4LOsm$}e$PckP`SPIJ#OkU6fEqt$MvqntW;NjtsAu&Xrl@7f4mHX<_6;AaXBZrdZL3_xYDRpnN zapB0j^G!M5_b2iuz=wr}1@=qhz4g(!96)4p^2)U9RN;HQB)L|IQ?17gJ#U$jRQ!10 z;8#qT4_cSb0NUX|mZz6JSd}Zj?x)zd_02a@e;J+g_eaO~@qeQMZ?!ewS;p-!k3IB# zxd(6SW&IkNpc@y&F8Gix~ zSbcDQ?xDQg_LP+^6mKaDG%xlys{!%{OJL2kLa=_E{0(zsFJ}rLk;F@)P%1-Uo9giR zTj^@LSYuqd1MJ?jPuLcH3Go6Kk_V<-Wi8@S%>MmsN^K-KXP9_`F8c zJen+^QyyBG&Pr7w>0I4;wV?0#mUug47`NkkIxI`WcGU9^&e@810|<4k{L|n<|NMAr zb-l(G2EgdY6Kk52LEMeYxB{W*A|M$KrXGz__Fv%?zfB&G=A~;jb(68oE{J%rhX)Wt z=UVl40R|*xu-x`%*z!*4xf)OdWSqj{jhsKXJHdF`a363VLg0Vm_tYerP3JG<*wEg1ge3Y*)=rHA`wC%E**NW|CDW6{~JKJ?<0 zL(K3ZkF(xRan{{z!&L<;2{~tisIM}%aHnubX9o%#ze4jOiUZw1uParW8eJ3JUM%j_eskL=gPGOgaj|rF8XYGeAFuR?I1m9VA1t9A;i3NE@oh}(-zP5z>VyRq zJqjTbN*GR>wy-?wrCAihuhzv#nlrLAu4gKJn)x5Wyf2UO=r07~$9w_L_9?cb?UBp4FIq-PLr{G6pvJ=an^_P;H}pH>#MHBbIZ1>pT6 z1r4;iolmPQ9HPV}EqXGv3I4=A?fDgPY{^8n*@Y0d%!NI)Vqy8aeZ6&Vz{<~BR-N;W zk<@j=<@#07fXOsM^<&#_G!&116303Pee7-}dOJ(IsS^5;*ZCUL(nGqly-#`?{Hr-4 z->=RW5oI|Xi7e(|`4I<6Dtv}z#pN0(ImjGt6!NxeR57lEWxBh|Q4KxA-P7?V>q(I%Mui+EBLR0YNHpLjARs+V*(IVlo)NRTCo zGT$Fo{3r~~v4oLkX7>uR^ldMcvq``ZL*rjdaN42lY_U)OZ;=B`d8iqbsvM+niu3KE zj2u{2ghI3ZR+Xx8N(oN+aP!m0pS!CrRZ@gukxGNioz`w>uU@^T6$;*x$ND!iu*kahb8Cmu z^NOo5IGGPIrGmFR&v1h(Z;n#FNa#t{4UJU3dm!@KwW+nb{! z4*_V-o_;*`{(LYHP+V2C&yeMvPr*=;3Lbtw>O&B!`40TxjeRSn!s2>RQjWX3nEN^Bty??q)8Ds*&EON~D{`i_hn7(e;$fbD zl4(t3hR`c5NXMbgCu`U-5+bD$68G)JGQ4Z`o`n4vbcXcit8uSeT*#yxs2lOx%1ybl zkCl3E{-Do(`n8KlaxzzoY9hy}bjWW?dsqCjvQ(2S!{Vs0c$@2fHqK0i|!61K(W>50qSoFlgAySU7<)JsZ&86 z%c%0GhV&-5F1U`VdX3WVDUPH>;&hd;TyV_3EqCjl?jI*dSY67S*WYL24@_=>Q$4Br zUZ>|fOp@#@!uw;h=PqAB`$+jtsfK_j#k-?ZBB8%v3-f1U`;>vI6)>pwGKDSnmQ z;Ebzy|0~fa`dSxdy(0258wy=+k2b4y*@^kQe0<65ex($RRbE1^J+Ql`InY?P7cXY| zg;5w8Jayb6gpoR}o2Wg*>mS`b4Q}%-Hw}2N6zoc>Xzo*1U$s-&v`Yn2joc5kS^HcH zS)FA+K-IY97UySP{brDYPayFr7)dEPaU@8X5JCyx(`k8v&hNu%jE-LW>I_4~#`Y-3 zBGla4rQApl__(bis}^8FVm=H+qS^W?CfV6aT%lPewX?&?=1^D8O*U}eW$jf15 zVk~|s`jF#PC~_b^$CTZLPydd6t8bH%OTB z-jH``klZSUD@;0lx4P{q2)xaw@GoWr;^M(BX3+V|Y_w8~JAs`CmK}$Yvx@omE&3}y zvScD7+&=f*vHFD zaXUH4AhIWsuV`}9$+mNrF<*MO=`hHu0}q&!2^VGF_j-;UbUV*)bsT`byq0SU@-^XA z^`Oko*;193Lj!Y%+ENDu;h4?!ee#D_x$5}A^Y`?{=uMAx>#W72lny9o<0jG{@Raca zEg=8|zhE}&3v*wnx81+wjI!oMU<%FqgD=CCvadFs<5fN>`9l0pWpl&Y!b^6)7!gU; zx4~l_L+CA8S+}=qL1b`uJ$TI7aVTBdC3~JZjhTzqp;B@j++;d(c9M zpYQ{Oa)!z9{TvFRujKxVflTYdc7AOj@4Wl@Hs9^HxZ&-yVB|?_n@sQ2oV5z0Uq;ar zUjXDp=?P4>X#A$Ftp`R7UyNRq2k+0c8@`&YigqnEPA+LF(OJTCYbYyUu8_nvci*hk z{kj<_%MPgDESW|kBEvNlzEkCJW(SCy_>rPh@9_2vVyy5G11On6q%3SacIV3T+L!b8 zUP4w65zM2fAR7B6gbaS3#>8g;mL&jdAj}16;1PzHw5j222pq-F8+4D|VIP}c&B<#t zn1xO*Yz_-*-177hwx#Y%Z@3cPM~qD)!VaO`wgF&6seS+CsY`^usP&O{mV{UXrEE0l zw9w7)h7Fv;z#Nr%(xH*<#T_r#cWzQi7(o_zFI+IoPmEH(Y&iCv&{yb#z+AYdNL;sTU{|D#YDmzzr)pLor*0?v8^D|LM7Tk%Xd|wxWS(nS~qPwqZ#D1^)G=mXB z0^OcKdQo3d*-G5yx@wSdtP=gdWRiaPFTZ%<&tbn)7EPM3)6^2Hq7cc?K62pZai39? zaWzTlf*MZwn&#f3ZU$bycx-4f=E!91JQbFNAN6Lww!aB88OpW_dn8PrkBmeawzwb%wEhMuu}MMd47`VUDWoUnd9q}V5IGS=18vNbu0G+2XxY) z=bD{_Q;kY)-b636Me%VMd&Exh-RtLc9x`gKRP4kXg)Rr4{QUY+Fy+kO(l2xj{O$n7 zZ~U&pHy4?<3wlrmUzh7sDiOB^dIlEZCJp5t8gE6q4hPl>AO?KxpG$py; zF+bj-B*^K(BT8#!k&KXQVyGe)v#i1}FbD4p87E$h`a?d9&(T4q@i@YW7AvNjV4WKO zIO*(L_+n#Wc2%{S+gUU2I~Qa(;A~9^qB{txOZO?M(p-V?bN(d!nfAv^8CX;~qmPSl zMX!s`9<QEv5z(T+@G)wdjGMn|&zgqqTBj4&Jp;Q__RlC#bA}OrKkUo? ze&LXxv?=alhz_Tan-Oekuv!~q-o`hgZ%&#Rju>c6#XbsZsG8Zw=@YN~GX<{S{X!A| zZs$Y*SJSk{CH26r93qY$9emjkccG7R2GvAdNCBg386bgPQtldzu?{|gl?CSIbR}pi`(7>AxU8$ z7e}#4&El(I`SaT1|A)s=Bs=DR07*K!Ayy@Kx!PrucJpoZNfkxe9R$7poeeG8kl?${ z;bkBj{WG^Jx~F2tT=Jr&(eWQOcY|NeFuW>Do_bETB8Sgr(1b&WwfZ{$?Bkf#(*3$zdA}f(+zi=0E5|MC z*-7aLl{(ih{37%QK4ev{z50DKpT^SR#u02eQ}Xt7Z3uQ=9T-#s+9v~FCVI2{UjBUb zxm)$)e~{5Yb}|Jcn3Cttd~CEfI7JwPeeXH@5VriWL}#(4#yqaxVf2(IOU&H6=||Ie ztmtZgl>_YHWI=rbIou^d<1`TMFMHZa>2I^ z=tzQa_kCnDB)6|n{~k9vG^h~s%Xsu zt4+rq0KpNo;9};{Tx>m^`E0bVm?7%t);3mhX_qL&S`CMeo%-d9YYAPc2INh(GbbHe zi}i4|CFfYfML@AUh~&G4V0Zw-k1W&uP_DC7Az6HhPPl2N3P24K2`XjZS|eZ&q3u#_ zZ|0gkL%acr{4+p;8Y0!#$0>me`S8kw{`>GZCDriV0gNazb=-)mRp>>9ua%Dck*g!u(K3(`}84`pa-5XF*ta63p`eJ>gyxJvXO9 zqKDuA=S7UELaMs*U^*^q+iJ>K~vbblD_ao#(~@^ZGDW!R?Q{AVUZYuOO`UXIBALE4b}&vW444m}t6 z!eHWH5@ye2gC_S2=PA>oUbD3Riin*%ywyguWecA5L$q{dc$|UpeD1Z@86^>NEH$ zpaoO!VV3XL$jxEpFr{;0M3)7)DO+q;%~a~YkIzxuD7vQi{QFe0K`GqC;vN@#DBsw~ zo5k6~Q0fp9WO5qU_T2O{j8M)!EL<*r{F~+Zdc|FGetnMCl&Tr;b=5h0;wmHv$9N94 zapw$q0nj#MrG+Iy!x{|Bb(5Zlfnq!Ll8TrN3!|biBvZaj_lg^FJr=^!I6Ho;*#kbB zkeU6_wB<9CnS;YaKb=hyHhGcCx8KhntWSB~-1xB$1t;n!p!<~B?K?F`Em!j08@QDA z#XYsd)!-wa3W&OeCLhqBi=N!WDD0Bc55wmR>0ssto7%=ZryP@&?mw(8YNbuYs20rJy-FiOf z>116TY6{G9h+-ZpoeGm)y-dPBgljce{nyZ5Or83^AW2(qKpq+2L8v#7$6bk-8Bk1G zjymbq0H7TJ7{O#%44pXFD#q zTrDf;1Mr2jxNVXW94+vfVsv-4#|5T zx1>8&!Lct{;wUubinWQ5A}@QjOgwRJ7Wlo{_S_$-JCc-y(176Px+SyKS8Z*#PrkEN zGX`_KP1;vgU)e5|l2m8F&BJ(HH!B$fUWP=1>B*HJLF65 zayZlxzWbC)PP=g~f7p|-b6$wi#G>XM{RP!eX6Xx|d*PNrlKfG}&%R%PmY&qS(Z_O` zB<@CjzQ~>5nYyy zTJ7^d+ddAtNVi>KP5G}mS3#PBLH}mG=H9@ChWQcJ9GzACSjv;|c_}W3Ic=u@20uV% zHfmgq5BKejlVRzAOdp|t+aS)hEOI(J2Zw72&c!(n2RQ-3l;D&2(dj8O zZKXSK(UNJOPRucx<8J+_V;_>lRYBF@65Y{C!D>~c)vDc_gMs=hNmIkkaRJ|`8T42# zQIwz*9a>jhD9w9i&m129dszEq|LGa`s&x(gP^I+h4Wz{@H^?!n?ld3T@#qlPa!)>} z3`_!vU`Vnq%8$&g>jIR%vlyQF{#3Z~v!916 z&psP&t{w>2nhu87zI-_Ri#Hw)552rQ96lkyLc%XIN^4|Xr^0=2B>eFEBjMbo7sJ_0 zX9S3JNm%AU*xx@KP8>QE?ms;k9(uSn-1m|eZI5b`KAkp6AW3<*6iIW+*ogE4UAQDb z>V?s8<@&h5of!cs3(}|58x~}yb-%1_cb(GLw7-4UPW&3^?+S+xwTJtDr8S&>K(Ji|9w2c**LMPX%z!!xR zIRPDPL+jKwv}SE96R@<>C0imt+R7Gm@?At@^o(>A#Mpki3E2~&twX%;?lC3Sy?xq3 zC=jPj<1tjSMGbhROKPM#1@;U|YG|KKySA$#l{F}Z)<*=q9S{)6dZ9;Kxwzv=*H=%-Z5o>(*222Zu)G}ANFGV z-#E8+Zw%|}B0q0?z19SjD0Y=`arbiM-lLqlF94-`uihy!b?>GUpwy}ZQ~;EQhYw1% z!PWvwd!+`p98k(K$_Hu|xvI(d6;+FMI`op{^UdhZ1-nHnbHq#e;%r}?wMs|S)Wl6` z4E)g`G{M_fT|F=A3pfivY`)ME3Y4*3%2PX}n1XxaI~_)wf|WgI2_^;Q!R59+h6*4KEWs|0v z57)1*gdhE|E&TN9g>d<~pN6ad^ph~&awv?q9+o2OL*X}Ge>mL#Kv&qW?N7}ei{Zw| zbhvzVD*Wh2li`O?PlnO)>rx7RO+ZIi=fso9;U0&E7Iiw@ zLfAJXP(-J*?K{vKjvQ|ZhmW*{{X+x#x;iKv!vPB$HBDj#2^E@kB9J72NB6>Skiy}9 zYH~pevFA0eNm@q0gm%?Q$B{rK;XBL8SiK0KBs0lYG%3TLnbsD!*=0#4sZ3LnG@6zk zB(||>%iiM3tN@Ud5)tYUfYu>*PEteZHM+E$ z6{uG`;MlgdPp71HcgsjocALPKwnU3HK+K##yV->~ZO2=XBJc&H<=}x%#gQmda;fHZ z2bbd&XAIplx9~utBQcdNUMdgnU`FOe`4TU)ERyAg2f&afpcud+B)8GBeBwNa19gnW zyqLt{Sy#+UZUU1c&CwmgZ5}G4A^KSw<;f(Gk~rzp-ng;yCj8*O0F?Gdy>6rw)H`Mk zpmg+D>{Cg9DAsNp;cDZBwZ1O0^0wD&0Vp+IoozNn)cu_TO3*@E@%FOWv=!-XEeEK3 zH#GsJLjshxSVC!QOS*ljZz-TeF?_JLBBcv8efic~%96H0%u9Lf{M@`=JoNQi$1~5) z&ge_>{aWx#!7KoijDOK(AYdUqr}Lv{6mM)yN@{Q3))(;!ea+Wf zktY6u!GSP1FsK)Y17-lH;)**mdA-4)jQ$wKezWeRQ7@om@kAGPelW_WnaOI+?Rqq? ziEtMVPUl@DvHPR)q9wB#I+O~2R%s6KID6$@VmAv=lE8>{e@k9JNQpEdrG$gb%A8Iv zo6&eOH5n$RMs#}GO8Cjo4uqfoqBC4N`*Uq$`*~Ps8`NoTk}!JUXn6G_$HR$ZJ)w^i z*`&+omoHohFT8jyym-DT{PK#VWrP}_)u*q!O$wOX!|CJu!b2}T6pkK3myaZYw0-N$ z#R)UFM+F|q%r3Tud4VoVOVSIpBt_Z+ISy!R)}TzAG(@*`w}#;XoeU;DJ||CwaO!~& z_U&i8mHY%WxgMtlZLgc37YL(5uSzL)9QRf&Ooya)kgS;(5Hv49XjUNBoOBjV>lrgX zHWem>YyqT*C8on@Mmmt#&Nr*EdPYXVSXzt$LMa_>k6T2yog}B0q~v^dx!ufybUUrA z3c-;WShI8l@u8qufK8|LGj-{{jV)>d`rD-6i4)wAp6Zac>Q0rV0|nJ>#G(61>?aZN zVF(`@S{8`5tgUCQ0+RsG+T^A*JMtSl8gI}#Q){DCt{_D|s zxAd)-zL#Mm`H&{23{bi+kx-JmcdU)1>2wr!<8Z*+PTuxey$Gp-k^+hJs6L|==$^`fvZ965RtPDnod*F(Y`XHqhltegyhn`ef!MZ|G@o{B)DI?EqX1T7QNKeGYCL?r7P=B zIsi&6KA(8viSVgUeag!9r+@mV;Sb*P2YOMFbQNz!tVK+6D)NMM>!G1i{&yO$Qd+g# zteh;cORq7tg6~Z~-o0eX0424n!NEZjh3x5-cmvJEn+oBxSK{t%X1nSxOF~26=lKP( z&Pyj;Ai>&KWcRFWTbl(SNG@(o*ux!UHz9tbKDi=bXGK8B!pLNpzd0JlHKyDey%H`7 zQ2P0cr^7#8+#jx9KNGIqJR^n1($&+}8BQEM8cyGLQj#%xmUPne%y@YI#q;6pg&X0< zSZ}yA(;E(S^o0G=-GjcKZb{7!54VR?$9n{ncL=a**7ms7@WO@3@a&Z-0XH)9lPV`7 zGy>2ijdY+@Mqv8Uq4scKzkrr~lBAJD&0#5nJ|bN{$0Ut({IpJI>jSW8(iSvt*{~JTHJ-_RFO6sEe5dxoeKkO-r$-vt zb@`ZX4>f+AM{d^$nx^5&e|dv>g8F)#|C;Q*?c({15^$K&R`~t;Xf>p*@ZCDSRZ`Si zC;I!FGsfGB+wNZ2jn4u4yPGwDlE{xbl=`*SJSae^w^X2{-&fM1#JfKqB0lgRJ{aEp z?sq3Ur1ViYyOts)A3NMGrM|20wiQrJp9Nb;SIm>hVYV?yu_4=qAQ85a4kBzW^!UuTQjD@bH8{l{N$OR zgv*yNYvHdK0PV|Q+Z@~8XcQeC?cvq0esy^Duf94QJ9bPjb;Ek8=@dDoTK36=+O)wz zUglP%!t>!5v?l~m2|(!+pZG*gKq(v7^UJ$cYgO5SD|??QO0}q^MqE8aZJ!dmYKPlv zzDc>WfYQ)V2~c9PVSr$=DXWuu_;9cCv>x7+g%N`{$}8);rAR!w@uZtf(Tu*n;pS`v`#YZ$T_E4aMExjS}!4(J38v0!Lbr@@ZX` zq?9DGv>&fal2pxn0MJ;CL=cO%4$-RNSQE7L8A-CJM-o?TKWmku@&QR;4fIONN}v#u zR*EW#BEc|86?)x)!}M^f8s!&HHN=~aB=jelE+eaD041G%#|d@94AEs|O1j0T=4Pak zI3-k|57JYBKgxsjy@41GDVpbIC80DW38l%gFgAJH%5e0^G1bK|p~X}C<&Gqhi@VZO zbYz>EySty;9xt(tkmSBn5cijz&Kq{GIQY3gNhHsNv#}`)8sX2SJPg~yjs;pvehgXq z&E`>ZT|Ztn>~`Ge>4cwow+tP|&x8-$R|1qyo;+!%ym_>=4&;#X&poTywZg5JUe>=# z^5(o=9<}^yrR#psQ7sLpu~rz;sTSY!sAYQ|wZh<6E00R_;fA>zK&f8Z?uPdD;_g=e z&Ej1><R!FPy)i zwcd=RkPk>0VSni9?UE?~rH$})H-x3XyQv#c%Cx&IpoE&8C!c)M-u(fT-v5CQgvZ|f zn5o(Ue^_&QI&QBCusa>L9Z+JhUe?wKwz*xqb}jt)$Ipc4o_kJT)JODXeIz{l>@Um= z^bdsN$B&2K{EgoXzx#W?CqU>`wj7UJ6(p%7X(e9pG2j3G_rp_9Jr!=;xM9*jhDHoW{5FW0F`59wt_pZb%^^ob;`LKdCL!qfZ|&L@@kVSB^+VcgXmHQOKl5m}PLJCO8TnxGIVp>mw{oC$Tw^i4xGC=} zmZ!f?5IT3{cWbD|MLG$9j3Vf4ww$_YzAHNXJ{o}LY`ip16m;j|~BTeD?$%n)Fxd&pu6*@7bW8H^V z)!#b~gsF}r;kKkCuTNbS2s0Z7B|g+EF`~t#gHq;vAPi{x)_}m3B>^Kk$SjP`jE2i& z7sINyQiUeAy~(r=$sP*FI#$BT9w9hw0(2BsxRR7aOA1He(U7*(4M~agzTu^?e^_CX zYkG1uOpQsxXeOStHYL49qoYj%>sQ0I(aCU5fVcWziWRba{2%D>EF|;?$gkC8DhaRMe4oN@LuuPZA*e2A6tz#105|AW1ksQ(~ zXw3qLgpI`{^eb%1Kq91y4jcwpihiw%kD}|rJ^@UWUEySDSaYC8lfUX;JuFQt`dgs# z;m_(Bz)ag0DW8g`-F9IKP)Vj)U=qMrvj}UF@^4XYiIBdAVoOWG5nKy%lA@iNnhH}> zZ*t`R%rnXcjNRG^+V|+&q1_W9}4C%BEY3{(AkY(O+-;-4t%K zc~`6K`Mk2v@O%xRB=s4s`oQD64Qi!b_-!!iaHWGI zfb*B9<#yhGmp*SBpk(|>7HUfw2_**Y%a<z#SPnq__4q7>8GC#Pyg^o;g`Ssr5*3t+uIvn@rqYyo7_>$ZbAB)UU>1W{LTs~ zl#UMR>3G8%em%VTx8H1F)tWj>=t~C~O)B>1ZyAcf;@lgdPe6DtX!{+25-4TambX9n z1Dk+MnYbEHK5m|dm}a(>i2^c6F2B#)=3NSwJW`+}Vv=|Aw8kP|Pc!eCx_eq405bD# zSwFwuX*)+_t+E=aTw+WHkb(B?cW@TWCQOS)-R%KmL$nD zC&`~Hp{M(5TB1cAWhR}`cG}vK#-@2m8BNa(g~^4!Fe)j~MYL%H7LgZa2c%Luhr1>P z3@u83k))^Ev?Wao<@Qz`TA-9MEqcbFB%7XijTxqXp$t9w$9mB zH6*Jje+!aT+Mt$fu~VpY=;1y-L94>bXcMFCrD(%QJ+A5$xfL1Hk0j}*rY7m*3lM;a zmoBmc_}_l2X!w63JtC!MWYnpqm^36l-)X}cTo^KR~UFWBqy&&R52%*c&j*>Nk+SDrDR z=h?Go4OC+56ZPM(kKFd+>2;DzyBZ0F`_^$FUx(}E|1LcE;Dc)h1m8!?DMriM z27-|Q9^0K8r5I@)nA!jDAS+4ai`I~U6fHIcOiT-7x-cyb*MK-u^uw051%M~OqvRzd$yjuNvO{EJ zMM)5W^5|4IfVS3_c5Qu5M4rl02TV%9H>>>kC9y1s6o)qnphG!!69ocLl8F#n5>i>E zmxx1>b`~imiNIqR$M@?6gMPoGm(%HXLJWMgF~y6Y^S5ADN4m4HVgr>R$t$yybjm8r z(@1O|v)uM5yT#6q3F$pNfFJzm!kzLtpmgQRm4HE)O#&-=k>iv%PI#N1 zn%1IyPP#OD>?F6Ze&ws-D_{AF=^$Fx%NPr7yLY8YG5%3*EQB^$+1&-+C&%{&lZ6(COiaAC@xR zLCe#NY@Gu763_^DA82g5fSzf9hE%fj%uH4hsf>*Z9ZDeGAN(MSxgHa^#WoIJcuJF) zH)L}x`zcS?=1fg)*~>ex+gZQty|@L-(yMBoOtSi`mR>dYG~r!#10U8c6Lp*69rtW` z!6;Z-?b8BjL<< zzaO4`;;ArkR13E$?m0eeB+YDDYsK3( zKBz1PD4joN^?yn_bdDT3Vx&RCdVF2azg8KoDdqa$otC?1J`L=-ZhOe_r)E(~T{8x& z(oW&A)on5uvU}o;w!Q->J@CK-5l~97BmswCP017u`kMoHiPoBbXMp%0NbWo_g}B@Uf45%<_Ey z`~M{T{_p?3Ue2Vn77eq0Wg4YBxt(2@x*P31wt9D2`C7#eo8kHoei$x(=UZX^%Ei#WJR7dgpAKK0|JUIg zEpH{X!V^b;hXA65m4z@Tv#hOQs~x>zQNYd0f>0F0jMU!+FxjPXA*@VjKpK%7K#?xM zCbqjFp|m1>N-I)=)Z%)K6ozNSgIXnV#FjXl@Rq{iw%gLnbXyV<($yppp`igu91S)L z;E?o?wxMxanp93JxK2(Jz|$s$*U}3v@JG|Wz$LE!o&`xK%}76h0405S>Ch>1ot(gi zf+L$<0cLbZaPm#={h4IA_h)b#9vIVkwH9*_H&PkIVU6h+E(@kx!`68)H*>W+b5L}} zP*~F9N&@n1x3+vy2+PTwV(J#S{6~C;B-`fb$ymH>>ZSCE?9_Nd3rHyGkcS0ed3oc;EpW&35)xqASCTO5TNAb@MHR4{B$asWW- z!nq5!{?N>!V+FSLWtJ@b}crm>2{0jysaVStfivRKx#NOh-y;GW8U3 zw}1P$W{w>@9$x?Y*9m<3RRgPRUwl$nXi48=GP5X z5Jp%euYUHEpM}T2^tgT1`r|+TGrkIDSb(o7EXoFFa1$?yya~vshz9S zp*>7X5J}shmS&`ETfk3SuLNp3ZOhiOwyLdYdsQ&~M@h6*0ZJ>QdRR!t3~et{yf%$_ zol?Tx*)ABUc~GD^l0^bkB%#E3*xcH!v9Vn(PSQa-rLDhPfKvB}wwvt_{rjZ!yT2_A zXbT#EQkQnMp@#@Or%5Oe_>hD-r6VaCmmccsoK-qwlFpph>2o^ZK*p46E5D_s)u1im z0?;{SEdnpgi!hH9+&E#g#8e4zX$+K?@{qufT?k`=_DKD;j3iOTgO%0jNg2SF5_~B} z(699``Ek*QxHFSxr5lSRTM}M2PBZ4p#8dj<7h%YU`2iy%k&F3+ zFsn$8$=#AMpZJ56D-ufR<3p^O4;p;}@_Gcsp&Ki5h_ETKcI!{p?DXRyaVH*^``H8J z+fDp|Mk`a|=HmxE$8l;`74yU{kjCXBLn zr9wEbVFwFEK&9J~IA-qOC+W1qM~`UxC#U`ZE<2ai?6c1>r{on`lVMotHn}S~tc~Z4 zO@n%1xAPgr2qoI0f8|h~_}$r&lH`|8lwR5UN)(9OiF3;LG;aA#+TxNV)91o#n*9I( zKmbWZK~%IQR!U#&^bC>;sT@jqxIl35`%NcyAYd6;CZ{AFH&Gg%Lx6ZB(lU8ATpg&r@d)v#ko9!vKXRh2V|Lw_@ zT+*S`vdj&bIWl&|*p(E))}R{G*;&Lq&pSQuc3lFJc+czLt87wc=Yf?^@!37Fq_yEc z{^LJ}zxkWL5#}&aobr}y3tRf=otK3_l14o9f`=5(dVmr=XjCXN$2+gibpf*GXo4N2xy$pA_SSiATU!o&gMHdY)vIUeGio`gb|nSZ@<)61 zirO8Dq}lN%r9zTSx+!x@;SYwvp zx#gPt1ab+yLX5|xjuc~VW?5kUlD4slH{GquTbs}1hTSDSN$pa=?bqU5Q&^NRmEmbp zC=NKYya-?;(oGMP#`i_>W{EhAZ|W;0mc(SBO^*Eeyx>9N*q9K{7D2+85_N$;=uyJ( zj1idB#IyB7wh%Io>sjs=hcJ4^&A=mzL)wIq&9nGxlw^psabEp?PQVh|pPJQn1_b8y zN5rtyfITplM$+Fi}|F)PoH7%0+JE!`xchPS+o*v3z5JK}W0ICzdO zMdo#YMGR|;K>-VG>SzE>%==u#v2E|_sLnI1v!o7U{lc;2iY$x|sz3Abc9-PuLCb6l ztMC>!lU{ix#`d7~Rh9-L#px+abQ2zu@<3PY=T4j3o<}(WQQ|Z5yjHP^O_9@fyajxK zS6=tzhca$HTvEr~NO5WlL@ZxYCZi!Cj0n1{CZSV*q{ZKQS2m7^wRnnJPkfJa&)8{0 zF-C8w*zh`SL)n-~oyj{L3nnHe?1OZ>_LAGjL)orVm8g~KEt_O<-)J1*qrc`=k;S1- ztl#-4K>s$Q@e-YhY4xiINRLLdGFT8Z8_yF&m1Zd@FsR-URI=R zm5!@UyB?qf|8L*CWfDxFfqyOY`q#fc{E@&LB$W1{m0y!T7wJw(M-z?Y^Pl@%_&XW4 zDx5xjU-;EueYLj9y+M1U@3%oFHV{Qp1}1gHr~TwY!inupXV0DuKY8XS;h+BLm!?x= zPKt6FY%s1v>4qd&&YU@8Vsg;*=v&_^^m5S_rDcl|OFK?((Vc-I-|9q8z6Xmw>jZ8) zk%?`7Ik)^{G8E>W*F4vg)|yDW-GK&{Tvjg{32ZwifRd!tre~(qu2$2D#sEbPJT`z@ z+)M&Wr>w3RfIRWS-Vg_@XH@7PWr^hYOFNH!N_;oQ18fKg)Iy=RN1&3%`OeXa&@na< zMqWG@Zohaw%w0Mc7OtERO;e+xO}dgUE}aOUS$Qmcq2*tuSq-#Y5529|bnqDZk~A4D z2`JF^wpN|))+qp^O$f`pbR*44Vu=&f+H_h(bBn-;)>%zXE1|brU`>}4Vz&!W(#dIk z`+5W_>4l|bf9Po5FZz_0B$fbyI2}$Z-2}|2ElDJ(qf00DVg+@rK_3NHp@6Hc1J!D0Kl$m@G)|bYK%F{+H-Af29$}Mf?R) znZj*_G2n-^l_`Lco>xKJ0IL9t$Q;orY=KZH;9f;X6>h4RCIBSL%rosN0jdC#Ouv

^!=3G>*4OvDDz;kSS$G(#XIe51iVi_&A9Y@loKQK&2J~?@DzMeF;Td z#g>aAP#0`mx1;>eljNJNQOk@l#YvIccZH%Xe_;)PAzl6iN^cl7eMomt<7N8Lpf|BRu|3eo`Or+CXUxZsI&Ig<@SRc= zN?YKvIEoTMCC#yFH@x3-%KJ0VJQKdCL&9h~ANb%0!()H&?$9Az15hd3W@1A2yM}Lx z>#nu77f?zXeXPhh*#g9{_yJ6+M?#5aj941x)Bp9;;nSb~boljO|Ml>1{`J4H)7^%2 zTAUx_&Ok9WiG-2>r7wKm(8ErNs-HM{$|RKD_{QG|FA<<*UmEq&Wm`<_#YB^P22i4r zksqggv9J2V#f!F>WWmAYLStkCTGHSI==6ghd|xkK9l^G|z2hBe<3O4PQA^5Ccsi$l z&0|2QG$^FJD)nT=jl82H!#lt1xkBf5e{4F*+Q~K>qI6$RdZo~N=MJ93MpFQ+LB@_5 zmk7ty)TC{9TudgLb^!%lU0oS*$Yj8wUP!>N%ITe3Gk7o zAv=AoM}SUOo3=1bj>}Ah+vl!@k#kqW!t>9D#ee!q2xGS-X|xi~FCPtmxANxj)$sbX zgq`g#s?J{wee)e*a7Ma}Btg`rqwYHe7IXJYNiBwZ^(3VeG94}@+>w6sW}byM@Q z;;n}6eueK5DA^%UsZ(@xNtcm~Hd9H8sn5n9@DfP(mP9wFuQxSM$$v`YW&FZM+ibxo zJW90fokZY83fOC0GYLsede*L$Y)k8^7F4nY_yAfdv_Pu}>@P|85r(mdArNkAsIsw& zXTtjhO`JrhAx$RMkCIV(iJRzJ)~RhPG9+lA5`|jlvN2C%oQ+jVgKL#CS=B-ebVSKO z+jazj7AzqS!nkZe#X}KrGvY-DPO2-rlx}hp-Fa{)-OkL+hpB1l%hG~@F`EVEz<^GD z(e?-U4*yG6<~~W@(~6JsPsVWznF&rBMwbGzW`$gMYV|3efs3d6(0_Hv2D66+Vg{KG@680wKZp1wpqBAu7zqhcj_5%Vz)fT2dvy><;gIdGFv}XxU}99 zFu&Axa*5odkBqe#YaeRUT*g1udH%|_FY}{rl0Oe?Yk{P%c$LMv^AOYt?NX`9koTBQ ze#P)Y2#}0aI^Y6zmA$O}W*v(AhU9?HU9^{0EtWVfc5!Jz>m9zxG ztnXRp8z`VKu}_l%<5&50ue5^_A1OaffiKa{a>U%S4h?uuKc@hIN%U=`5+^2f%CL<+ zeE99sdT+pN!dWr3K;s>JMQRe3W%#hPIKLQv@WUU5&;0NIZEfiNANW9c?6Jo*X0+?0 zv2T~lFhK0G%k7NUZob_%K#4Bsm)+C;R4EQ9wFpq6LcjF*mki~*eQU(F7;wtl+u#1y zs6$C_L3G-&kugp5W8qVO^+`LX4+*7zEoq?Fyymsx;GtoCy_Yf(CItaJlM_?gvNk1U z-(OU^U(gZR-QoDj)7l>Q%J9#TP`dxL0YQLIanUEx$ABMA8q7SRlWh+GQ|L~*cKy0Z zNBNO~zEA|Q4g3=$uK3 zO{ZjW=^1{!-2)*IXy zI+SkSumJ>dSq7UvwKcw8`gJez%*);=HrS8=n6t*5S2FCWQ7axtyHa>|A=&>u~79HZREu<1!i3iWq zaglVHoJoWKgg#<=`q{LiyYeO-!a5K1Or2WYDv#}|J`IiggK!cS{HxwaLWOK(abvJ^Dm0a>O z@Jz!x?=6w{u~uvvNB}VRTLrN5umYgs+@g3&E(Q6-AL8;pg&wUGoP$um3}C|#Q<_uU z+im&UpFi(an>I{EauO}lY4&od@qb7sz8pJx%od59{>F<37j1{F@ANHWpVcG0g7NfA z0MMke%}pY|qvF*b*Ur>r`S8_nD%IM~#*cO>Zfk_4^$(8YWW_reseP_KiAU&z9?>i)& zhJt1vqkMe8z89~2e=~k0>$Ba&4=V?2BmK4NJrBVUl(KWuA7cQ*9{|bw5mM34CN7)b zY&|9HLSPc067vHpZNBrJ?}q>PzyEhrkyD)VwpA@b19yBmQMIKDi#XWxyrh>H7C(rS zven}&U-^mwG7RK%TFj$x`>k(#)bt~vBnw4qlM|Ctv^^C*^{Gz?Q2K;PCZR*=wXc1R z6lNYZM3Lg~f;1r=DS%2}{_>Z?m%jYCq?h`_efQlT9(m;>;dQV3XW`VTlL>uHV4_im zg`u75rfCQo5sPHt;fv(72AsJ$jv8knpL{{F#a}GnKmOx)!e9UO|6_{4KlGsw**;1; z zT2Ka^>euuOZJc{9^a}vmw|qd-NgBJF7BnI0#j#ak2KI$PNlgyE{?|j7wz72(_Go+~ zPrY;+h@^0m5CQ;VCs$Lm^sY4VVk&?~;FN&{xW}PE?&*z6fkY=#5wx;W-}kYl)VJlU zK>`D)w8R!K3oaToQF3Bti!w^{NWxmGwsInil!(={dAi68#B^D52qFyFdX`lSkIiQ?a6Z7(xK{SVYPiL&f;= zlLKz~XN#63?&+DEq9;jsb{U)6CqVTO=3OI&Ok%tGmVQLLLOKcQv>W=6gxP;!zt#+= zv~|AQJ|M9M;37OPBnFP)5E*G{c-t@a%}OkeeKi}ldNstbmaEsX<(Yu6RI~`NenG>q z{{&DX+!kNfiXdKj$1>NZmog{p+8|}M)3t)%5g%f@C}%x??!1BVr%#^_N3^!gUa+>- zwYL6h(`$8KE5UonkG6}6Z73Ez^3z(%8cry5nOnB6;SqUTUSZYh&-1=?DW2>Is4#r! zQ0UXU10P{{@hq<0$pLRC26k(7GVoCABO4>tAUMPc5Sh6i5OHu2>6C6$&RiO!ydUpQ z9&85H&PPwn`f7O>bgzcCtsJ78d7Clfy5@Kc;|Ee{^nE@e`8%G6XDs3#keeM&fJ*=H z)IZp%^MFzXptM!ht}#4*HI3rm=>m+eQmPaOlu%rS`RZ4{VxZE^>$glH;zJL;EIev} z(ktz&AmGf5z8FvISVsV*PkiEII<4*D@XmL>GrUHC(n$eC`z4;t0KtpYxb&l7zVekX zo7uN-C_MP!L*d~^9u`RTNH~7txRsm^0dPd)VCx`oI5^HOfExvp+Ls;SNx36^n~>w}%4^G?y-3vUb8i!%1%gns9piq7wM+p`yrT zJr2adJ_)5hOh>jJ%GRqz-IaE!2++|Bp%haukKYQ*+U7R?&2NU=U-&|plLCIO$T$(#{f<4??g?R|S$Rhg|%~i?s`w~f;o;-PSw->3PzZM6)A18hI?3uIS%!|^8s*@d$ z9Y3y*hXZ=a)K;kiP^!hn-Q`D}W2kc(z<`VAFWMGoBvbb3;}Kv29}w)ywUOvp{O%PF zT+ykHmo?V|Fd>nMz`&5!dTIUV3##@2&H!%kO}#sOi`wKxPXY+V)*#SKQ8kz z`(pT}H@(RKrI!hSI-+BJ`C3Rt-@I`v+>(jueleUreLB414ZjgyDG4PO3Ft%MftFwR_|O08Kil#007~zD-+S$gh5=NT6Pd*u z;$*Ma6l;$SK!rT+z2n*7;wtW7)g_sX*VQjTmz*3JSlmr$D zQfgfp32mz~N~lff&!Qxhrt~z2QfQ4Et%Li*k>C04aO5p-4y^(nF`z_9K*kf%)GDM% zn+;}QTq%hOO=@aMn{y(uD>b4uF)czqWDJG$f>P0snb?km4LR+54CFzRprXxp& z!-0ePXrT+JGQFHQxw13OIH?=kO=biu03ITkSSa-_l}xvK%%m2RB?#9VkLbKy7B$Ka6eF?oNs`Vq?Fi+fL>ne zn{~eT^I}|2__hZuYa418fJv7xT`>$`4WQ(0C22q29@zHIw#g@+cp`l4V;|Et*;@sm zw3Thb7@vSA+@r5!NjiqGxu{GBls^B3&q;aq--XfJV*+zV@}IN9pwG)3!AMMYA*zP{%Jw>Hzb~SH4m@nFLV1>Q&+B@uQ|> z(}+--08oHRfL0i%8=K4Rc#p(YTv#AJX=PG=-w>emU;gsHgj?D|^XGs5XW@PCd!I== zA@yWeLVGr?n4Si!B%c_t{@;`@6`~lwvIA%~Oe|K`CEiyHzc%FFbnyWr*#ZeTiKzuB z(Qa(AslXAdg9`42(-w1p_Pvs6%o=X2j^eOWmigq2jtiaDaiLFqGqip2bD{bCxibHX z59l&lnGKWb|JSALds320TXf$@ zNh~cf7FO$n6*Ig$N0F&cMYZ5hjX{fr zmCfa~=x+Gq#xwD_&xX-s>b8+|iN{6y+M#GV6(%PqB?>C z5~jH-0vR!8K$U%u&>hG0>9I+mC2j_4s!fu93Mf$sr31d?Wx!?IE@d1^uwTnIUvJw+ z%MNFh&gmNO;R?sbV{Y7tqVNX*luk!L2~w#qo43U}>}qqk^V97eE@qK^4GwrcqILm5 z34JOLJn%p`apFW-{d!$`o%^%fHL@tY8h`^{Z&{l@9}i<`HZbYM7hg0L8pnzfSPKG8C6Cm<1iNGP4x$3y@nBvaV-#tsB_B$&W~-tkyF zc^`M%3CKUY`)1nSUNNmuSfGt(Z!{_0a?f7T z-M>`Dy|_!t4+*8e{Lg=x07`!z-uJHrC`oEzjf4^dS!PDE^pY%`hHQS-?mev2n+=z` z`QVxL^!xH+Mb}#4J>ETF!&};f4>pLv+m<&CBBnnnv*oP-lp3%!on=^5-}m+j=@L{x zT5>=dq)S3!=q@Rd?rs>Qk!EOy5Qgqt3Jx zGyNnDvzhn05h~y;p)#f4$u5sFBNLBj^-(YNse3haW{9LtQE{*ojrGPdz_pMu+6(?6 zeNIQSWn8`vKvT@H6z30xC&!RlSaKe|ki3W-2244GcI49KdaM$TNZO@){$Q@0#gFDk zNyZHTFeJan8=Ms;?r#0j(7LmHJ|@lENS_e;DcWXYUa_Sla$UqfG`|K`jt-`IgG!mI zXO?sm+C80U&)1203r6VT&Z6ZcBM9*NW2obQ9QcpCBfBwMvjXBqaM~kH&bNz}tZXak zt9xo_1aiO=LnxZS63#Y~@)J%E{?Yz~AcJpx$oI?_E>tQ)0=}G?B5V?J_Zpc79ril0 zZgAf=!#~{t{epj%PKbbIs_`m96?V$sZtr9u_hh(@zhfXgtv#c&3^$}=WQg)}xtuJg z*Ao)mDh%{-P*1y7%s3%3REa%60{Y!c{PU(p>gr}xow_U$abRd9FFxA7t4i8lIjn=k zKF4UM1gl8~!&lWZkW{|M%yZ^wq<`US)e%lMOjL?kSp0rh@=?7vb+g1yf75byVPWAd z>-}H~R7x&%YPx{o)9G3eL1<(9Q8}Y-Z#9IXt3OLi`gOqR6Ls)Oz{|tB&+3!m?aECD z2|l$L#mZTXM{vNk&C4)-tjaaz)I&)`ejshf-G~GJ31aK(dAeD3&{v`%*sh~V_~tPw z7;gFixT>-GPgHW|cEItx!J&r5z*t=KamWq*Q%3F}Q}LDM*=QWpM==xoks~k9vuF@` zljDk>ihB(Sz_rE+I{k~XDFiM-1{zY^Ymbzj&b#8DZrB$^7iMCB_sH!~Uj49-Wdov^ zeOS8fLkxFtJjPb}9{ub~J?0!=q`-&o-6AuaWqnI0cq8wUm2OMcUxEakbySC~n?uEm zTPuYxDJZZF9B%8!pAI^S@$sk$!tkly=&a6;rCKeT8|87oK21UoKBU2`WkqHiBq4m&!OY)7=8!!+^IYW#B4(r>rdF|UMF0Y>VUwePMIgOOR{z>?4pC+` z>78tl8BXe&%S>qAapj^367Y_e#u+ZX1U*DIWC?)mHrrEj2{Yo;VUK|m! zIci^c&^nZ$V_NzRhpZPnQ>o|&CmzE~YR@%)c$0uFcKyHWkX<9rYBN^`6T_R9xscWS z@>T4xS7IODqp=|Y-Pkkvu4-~*Zxgf@N%`k zWi(^V@)3#>zaTI%+c4kTBl0X4wL)z)m%RB`$84RM2KkU|ptyXLTU<#u?BNlNg}nSL zA@lHc(=_|p{A^0Q^iCk>I6v$5QJCb{QdbVygaP^wQ?FbT)1-+e)o1|k@okH8$W2*7 zx<*>Ppq#xdsO+p2fcpxk2(30}xZqni$VGwPw)FSfQh_m?unq{Pk(;jtu%_*(34I1c-^BpRrms9F)* zc5Me=2ut?nl6i&sq51jLW9Cfm5B-&VFgZLQL8qZcHD?2iKmZO6C-Z}yZ8BEA zAVIC~rkxRB?clROm*}tSRa6*d$BFLxNWcRpo871O$^yR+1b||WGRq0$ljEI2lCU2N zdap@EE7_V#Yx#TjFO$aWL`*lo)=CuYT)fHMp8TOh0l}6xowE9zL2wh2ycuNTreiu_ z{8eXSAZ{d4KG*6qoQew9#8W~dNZ}#}8EA0sFrky!@DX#sKulpLbBKzcf{`D6z70As z)n^L*78q6Y_}C@!I-p4^qb+LJgEXM^w{GqD*d>@AjFiZ!ZjEs-pn?v7_k@#0BEK$~ z&v%khVTR7!arkHs_y0gEtZ8LuILO%O2}NS4yupT!#K^&$ zG(LP=pBA9V8RbL*A|^Sm-ctf?y<9q3>kTWtgvkq<97OOvSBGI}In$nQ^;U21D0Umz zWWhpX-0p)gG{|`YgeMbo6e}Pa8z89M_H=*Y4r_H=a_KN}_?RP&=G6*29$egbY#>(o zd28FRc&r#$Z@89P6>vVxv%V|-(EQfK0GouvP@y44POyP^A4v@N_{i=^EpEmRdooT( zvU@Mu!8dO|812#8bA5Q>v^HDZ1~e(dJk{=ZkSzCcVmub1_T9-1qvCFt%NfOeZKqad zp-*h7z32B`apI=o5AQ*DcrQf-~)$En&Z_bVHww6RJMH{B7 z8OtsL{@?mf3K0^Vyj7u%_07=ZSnYlp6{sqx+(EbVNmE8*a70RERar)HEGygJQ;tZg z;~m@6F^25CdxaYjHS<1NCZ(|Fd?u}mllwify|Ub-rKUwYR+ZQ!wVo1Q$WD;Khf8^8 zBASuj?>dk-oX{iZRA>@A&k@^Xe{eqSW>g==(~y!vLDN<2aDQ(O*%CSK-L1o7x7PSB?hSQodn< zeSJbOSV}G&<{th#K`z)rEz&09RecCXP=W4)8T665JUbi?>P;3W7wdcn3oy7jwDCRM z_G>eL(5NrjDN!vQh^V*BPRWbNW9DKO6*!82^5<0L9cC&IKR**;4~#J>n4KX?oAVcM zspXY3x@QM&UKF|Uz-L;hq_xnbF1C7qpBvFwaDF1A+w{e^s8UVt_4qH6b0ceO#u|HU zXlt$@&31{%x2YerUhtkv!T0k0t0jQ(CpDuoyZIq}tA8g!_wcqR*ReU` z&)F44Qgd{1$-NvB)M+ZOx4{-aL_%`lKkWwy$Yt9-p0CudnDFLip}~qs??*NJ`-4y& zj*$B&%H!>eE84|~ z8^l_RvGm|c#C^TRK1mL@QNLlOJ^vRuY?j$g#CcHrAODPM*S)$^x!67>)IK9_;e*TF z217A_>L+CMmG{VrEk2iloTvb^2k&eDR)IvjN?4Lby|4T4#~I6oB4OWN1X}Hjptj&+ z3=;4Qa57#s(+(mvrd8dhvJh~1rnO$S#7&uvOdUj52){KmflkrZcGNl&CvS1eiP`I~ z$e}F6tlu1;H0*9ai@3z<@EX-1fyK__V_(JKx4n^I&W_#H9%6i96*V)VBOl6)47(RF zcKdumM1UhvES7a74RCl^@mONd`+M(?vbPs4COLuK#rcyL1@-59=4Ild{EHRMqi`O% zd+CR*WD@O}LZ;!%PnE&`$iSnZ$t2et4qlJn;c|;aLky-* zP6MpO98W=ZXj}&b|EJ=P3*J-a&jMcCK zR^R?rOx7G(wKi`bxieYKA9FjH`;UqrqNprVj2;W*fc=U$#E!~V)^)3(qGH79oKU5$ zywBY1Riyt;Lmi=2=dvQT(adi|+OGtt*sqElrF0O5a|MOUcaGy_6rhq+2J|K@;9whpG&>2 z{%kt2>&G1OC|Q$Yp9c6!hoE_Z!QN~A74K`fz(UZ2q>py%AKJc()FNb6##s6RhJ-33 zXdd}f!JVYkWi8TezW;>TFaPM6daKG@GrKs^lY|D!5@rkllnB@#8?r8p1m+uVvkkEo zI7g?`*@PKqiV}+$-H156RarD;ZDxwxygEJrWFg!X_O7BplgtoW-+UJFnhT%n4(s4< z(|*CVtK)_@8c4v=2vN%ikzMzSaKvF92k7%df(8a6qb4F?YV7mwE!jS;%T_|ptV^F_ zPdT=8XT8gA8n(gw0$Vo1jUIS&)^A!iL2ACgN))%qR`rrp%yMKuaw4Xm7#n#EnI#f$ zE=Dul`tjiTh_dYzaa_{*UglAM+O|i_0dMcIwh1A-W zTOh=L_LY^VwQr#$C_NBojB*z= z*9ucoK?VpiUFVE!gbf|tf}dleqeDKXRLr+hz?N%3M87`GLyXqgJ>pC?`_dl5}N+&#GnC|XYmCYvv)Xi-bjSjp%v6lAu~*FKwk+5Mh?EF z^SX6$K8WpI8%!82*dvj!HS+JUR zBfjCp_u;wV1$VIgcYUhb%|WH98aA|*ErrYgd&KMC;cP+z_x9JR{^jrD9&Is7%cDAn zcrqa~Sh{#GDZ$IR9SffSDr(~EEMI)dZZm!hQq$BrDhg}#Iw`eZ#Zv8c+jLZNv8k0~ zU2gK{S!#0{!pF2E%$eqpuv&e7LI+HY43BG_zZYiNa^J}AZxF$YJ?>g|zlmPFb7gy8 zW^7TVb(g!XJ5q^lW^>q6Wsw6QfST;ZlhKK3)1r1JbRe}wcfKrB!aQVwKO#TR&cr|F z2GhDXw9S;5W``|RylX&?^chQttIYNl{g1?HMP}G&xC`Hil2Hx$NC5Z%eU&;L4k9wU zaBeopl?_ox!}n};MAR)ToN)ZiV=D@AgwBRipX~ z3#!Gw(UQhCXhxW0WdP?3GC~ig&99jeBo8Dlh z*E7rxfbE^z)Ae-|;dQ(L>59jujDQv4rDhDE^pRoJe1}dRYO(C!r6d_Zlq+FStB$_|p0jU)t1C3Q> znRUBG%GwhS)nb7rYGcESVupRC-^FxaHvCN~PK5$@5kC`)8LCAOR?5T-!>2C61VHVq zO`C~x$s zK42T}*5c7Udg01sIj@p6uqcL>>>Q8qFzSypxb$Rt>fW@~k(4_MH^7rE=3r;vrymbF z-AYsrjSYC*T)#eotv?}rnmy-CPq?2-8iGEIeKoRZf!wS@5oF#vrN3T5F0i17jUbCh z7S#XUNO#--Prj7GS5BMEcgYf<9F2&t(TPRm7If?$LW3Tz;kv5yb?_kQ&V8pfzOBZs z8GfT+@sA($-$=!qS8Dzs=S}X9mMOLF=!bc=j z4n3fRa6SnuC=$5l3ULVP+G{l3pzk(d40vn+g}{g_)n`crB_%%yx?m_RQnB#7kszRl z80pgMwZ9yks+qWj5sEG2*HNa~sZovlGJ({fU7`o>Om1y*GBrPP%qpi;9PUbHaL!Ih zRelb=BmM}dtxH%n*K#bc^Ytv2K{c_yn*(-Ib?WijYOg3+bY$u-Zl$1sk&@z6gbh%TcCXi8l$O1JBSEc<}thwLeb15TkvwfBx~?R0{#;j$i$Eo9;^lx zV!wYnwx_xiD#uaz{ZCBWR{gBj)%>K9`5|)QFu9>Kbo8+;TZ9~8_wAheE{B(w_iYK} zTr2)P>~PP{SaG2tEkP+ne+h@qiGZW4za`&K4O z2AFOM3h-s$@0w_GY4T7t?+7oEX}NF>EtdRM(s^AkF4^wfP~x`sriwO%s4yetAR%}X zT2)s^;qBuiWfYLDDA4ZL4j(dua_=lpx|UkBL&e5xQ>^AK7g)|rH49tH_YP3qVuL?e z&4N`1uPrLuf5d-}^?E7G4(lHc8@ji0ylx2PZS%?g zKK2vp6FRH=jcdw*t|of#-?#cJz$L`tL&U+d@?VIeP6SRVl?7V*+pnk`9WpyG=4x={ zByT^?M7K!wrBgutUizCct10MIAJ`fv7q@5aU#V{hEhUL=~B& zEEpQ2ZjzT~rRI`XEg9_UFkb(^TGRwMuj)5K%*iY?0 z)phend>x$|5DNIGXbGtp#!`~A-cB7wWyP?FYJ|sQo{2^%0V)#q*BC}@@AXxsbIz{; zXH9|>InRO%gq#u0Pxn^`=I5Y<*!S~RtE&`5ks9tG)M*onhZ9^Cmc>8#8jF-a;7@$y zGt0OtYQh38I|`m>e@S}&tQiaB29ctpqf7eu=vy^*;YU9xStMUWS{yE~@hfY1%}>$} z>5?+Pa#Lkl&|HcFCct606+L_lubuH9kL%P2}dYIan952~idu zI#)2ci#^p;A+&|A8kipZa4lJTDa0#ZRFM>ZE3l2wry)b-QNW}k-rn9)0RaJ|)A>`K zpCyWs2UwZT%!Hd&41;v;-tyrUCR%TO5 z84>UpJ_#(EfgX~aNv%3CM3yHlZYI`i-Pq6ri$UVQoCBjl{OW3-4kan;RUzdTY*tCd zXv=Gt;`Ba`ol6&sVgGSFR|@)^HPE-&3^`-5Cr?F%&qK!d#=In~RH*TkGowIi8Tm>2 z=`J>RcIYE}v>*^3So*Wu6 zA~9j}YX7p2nqcSkrsU~=wb;g+?5e;2!o)6fPqS{?nCjrA=mm#B;@>;T?Ho87B8T)C zzJDC8LiG6^LJ(rabVLfT-Dt?--Sej-@DCz8O^hzAO*CuPzNnZDxJX2p%vb4VII^J- zC)Yn6?a$b(FV@@SmY1{D4Ncb$MV$Lr_W2@b{IB_;88i0o?l$nUMo#j#kXC6 zCg*Qc<(RAY9Q{~^hK8Kb zv@HioPgp3Pj$uOGZ==)cyL|+<#YZ6S$mh}v4-F14Z?s>==66`ZeYiPkJmT>4^FwaO zS-5XF6Hn`}J#Gy{MT4RfmEc?9-~&FyA0qq(R+MVo4sYg@9&twbs4&{H&iSbENMFXX zg-J#sq81$BeyCK0*eWYLUx1IE(hnnY`|?;~)~4pteN~pX{DT_4mr#4mg~=SEbF@(3 zbd8T;+4$HTJo!nC%&6J?sk63}XC@Igv+yqY3jfd7-U7yG0_L2$@AiZ$-YmY4o74o2 z4y*W|R-a6=38?K)2$K=DE9E;~o2nlhCWPH7!wc|*(-8-M9yGAn>3`@$Dj!x?SNBwI z@v%WNu2RimVgoLCxqJZI0&B%w%P}KKC4ROqDZP$DLt|q`@cYD(5pw>#42cl?qf*Lo z?b56)Dt&1!8>X41#zg)Z%W$^_(RXv0ywg1{dr@_L&poed>gq_@<#bn}@+kIBNQR?|Kw z@ZFx;wIA_ZqN0?2{lC?YCngBn6?oy`M)iW6l0P;Cti`Y*OX3K^yDt0P{)y; zkdTm|fVxks8rt9vGXCDse=|6*JEp!es}P9ri<%y=mms=ERd?uMl?fAL6qAa1}(Xf(&_8#Lsesmx|1z% z93($@te~>mOwA){Cd?_rNY^CshTnQaui7Va-|fs;wJ(4cw54r0Ptp zPEBhzy?RK}k-c`^Xkm06yq%y}T8wrA9g!{E8QAr&JXrDH_fWRCD2rZ!+aE|kYHTqi z{`G7wVRUTlZ2Mh3Ty@N?X z`PLDj$HZmC+8Y5q-;oeFwUVuMh2W6$!eS_}udgJH*m)c0x1W65m)b^} z72CWwD^lFspX*?QM<{yEOzN{4mImvHJ~h;7xId*Op+Z>2jZ9#HU|AQi{YA)X>pC16 zn^jslI|jjcNhGe1t3vzYU}CQO|5*Sv0%k%0gy1(Y|A89q9|8~%VkCfTZ-~aL8)M7K&aTt_D75^6E{FHEz&egZAVH`w9-!RL!)8vF zYk0Knmp}lV3Fhaua_%`VX{udOGNQrMdwL@> z&>c1Bk^lw#pQyjQQy2@yuX^3RU7FvsNm3GS|1sR3PF+qCE)~E+2@E);^5H^$+M3iz z0ufltS&!>G>6QR}Y}6_hoG8Qr%g1e*7Aj*nv?Mer=$vtOO6uzBCJIJuDVLK7$rCvO zW|@Gu0ULCptFFiv7%vGmsxGY17y#qEkj zHr!GVHw#=FvNSdGG^1ZUtwgG=*T0%)?9*-s#S(5oI-`gM)o$6E5R1+C^Su#`MCS4j zJ?jZ$93?g~(m9I)3k7C=WA4mIm{F*m6QN9wj6S!yEplljy$1+&c3NXW45RAFN}4+2 z{_<}E$*?_q{Fj|{PQrfHz0m|Mm_VjFZBe!g6-=VL!iGWWLF&%P*!OA0h@ZJvDvSV@ zVttbrGgrFq-Mz$CF7w#B2^#So5J{a)u}`%b%@(E}%@%jK^1r{df<14zQSBDA4*78W zG@A(Sfu-C>Fih|Rv;r1S!zjL^qX-0QsnN~X7V212_C#XTF z7<4mUQpppr?*$_IH}<*_8OK^1N{cB=HbX~h zD;^1&nL`0a8(d3qmSc%A(AaKxEQih~Sf?Ea zBV1a#clgg1YDOP-bN|sN;$%*N8Xc&IR=BDCod6e2^V>N_Cy-x5sbm2OF>zT|F$w)B zr|qxLyyx~6t>oAzjJvenBz zf~!^46?COE%0tFLC!^lI-kjAYiqA?^ES~#XC`K)Uu3J59vKU{c^SwK_GmvaAQB3nv`Z`4Q6+W0UeZJaTbY{vA10?J425piVUAQP zXrSlmz-Rgb7^%_Vm zVBO>Mzu{hmY)Ra7v@mUQAq}K=TPRc>xge7p_Et>F_|BBHVC;~;<3vrll} z8BYuch{w$S&nEwg6B1}@XZa^!0Z~}_*mTNYZAu?XPm0Dfeo=krQz4}%>5oTrGhMqu zzxwc(2rI+z#Vl{PFZHGr7NZ_?7m^s)2ZkzthW?9)J`FshqKuR+zH1=awGeezC5e}B z4J6nH&1T0-Tn)Ke0>6jwZBpakd0Jw7iK>{K2;p<`&kN*uU;Xm7v$Lu{%k(D*AO1_x zn!)~2U#(+V`bKHo+Q#nc!Im;Zx}~9&>!t<@;p@_?{Oii7Sui&zdh)@ zJ2<_ZQr7PwBPFd1VdTjE7F>wj7cul1%dUKUD6&)Gb+SeG!jA%rM_SBxMgk&~-M5l_ zp%HNUA9`7T$CjNy2-B!nJj_^V4IQV$@(jNeI&@qJPPi6^7QY~Dd9n$zFW9L(Qc5)%#_kG}YR0jtn zK(mYufd9xA{iRHtr^_s}KW?PpYkN%;7aDtT{rm4@?k|BRQ|(_;0zSEN8>bZg1p*jv zd2Okv+r$*s3qbkIb^#l`;`xc!@O*v{!+w^~#l3Te_kdwFn+&rSYRudIO46`1x(1x{ z?el93P{Iz?`5EGYE?gX56j@I?F5R2E+MlJir0v9R<4>#E<77=U==`FDsQ0J=oAnnB z=?2p>Tf_EisD9yz-wZskkAl_x1mgmo>ea&>UFnHF4&T6`o|ii0e|a{Y_XA>A=5bu} zk|ElBs0W)%IBDerVJJKIT*V*LlA>LSLa#(w*nJ;rNo<$~Qw{P2D7`WoTHn-d!{_nF zo+tk8+OM2(&hC13Ci*Ygr_E}uoNe5*8dV6)RlLg22=_VP8aQ=$IqJkad0bwtznh;m zv$ob^TG`@0!M?k6zi>fZE2{e}{MF;LOhce@X`L0maAbLL`Q8Yx;_Z%R;{Z;~a=vHX zy)5{gU~oj*o^*mK(CGW$J15hl{HEC{Yuz!JTW&ACX&$4#@H;-fxqGggYbrfR{}YV$ z_AMF%=Fcs9xu5wTFs>f_A;%YKSy^LS?^Dy1`KPA~OG`^i$BKpA_NN64X}>To{>?|F z<&=C@6e79mlJ{P@Y~TIBuFqIP2ie&k$Ts*CC=ra|xT%ekKmDDS&vu?vtKu7T*ZRVE zsWykOP+LF%M_1V|->g5J%tch&+B8h8 zbyzx9D+=t6W!Hva;IyZ2EI$C>r%%>N%&_X=)S3&7k6UPCo1e!~IGxOJ)nE`%;(pzZ zqy9YE8}X*+biHQ;7r&M?mC%%oNX7A6!Gol9%Fv`Oht>?w`Al8MA~=_Fg{j@HxBjW1 zU>g0!{dB;A7@YZ7>oiqR<+RzyX}eeDxQu{Kh&xYW$UYE-?{cUM1WNZuDkW!eM^aA^W% z`)Xf`^vI|OqHZ!UXBKjR9uTgXVTPhUA*y*_V8s;_e|m-tR$>u z-YXxuu=MS9PnsD}`e2B!r?cGF+C3#0$x$k&Hy!5bz5ddA(osA9dpjxj7a#t^CHze! z`nxc8gO&v{f?St-=S&^eU`LjvI;*MfTc^z^b_w}C7P-v)ehjn3v8fYFmYXz*Vr+%L zJ>QhVLQ_%|k-xRAfpJ|PCB;1?RO}O%HFx`!@?=-uMe?E{I>d}06!T%><8?`|O(r&E zOpceDg|6Tlq(ZKiq+H*nNqNi_0Ld!I)OwahcW6$WF8_u&;hy9*P1mnEH!9?i6knyv z635~Yv*O~Au#XS;Lk?X#t2g_CnbiwYYqi{&NKfF9$`U=}C;F}>jU;iOm8#bud&%qx zv0jTl1O>4B{-l#YzrnWtO@NTw;g3;bho*J(DV@*1x|AP)JXmd{6Pc&!HP($MfZ{XcB8sXJ)R#}HU4szjNB~-0)y>~0=4_X3@ zfg4htet;#BUGqFVc9j~zjY&Q(AAQu%f1H$}INvKy&#iijwq4)bY+QT^h1s`@;!<+= zQn=(5Z>6N=^`S8AJWF=wgeaPPqwg0I@UTIBh3(LBXFku+HTmfcV_5ZOf7r%nRLO}y z$bG9l7zr=VXV+~Rf6NL}swD=du-ji|4j&A1TtoWYz6v{T_7I5UUWlhwo&`W(Nr~D< z^E+*T$15EI)aj94-Wk|R(1H)k5{(I2)`wvaY5fB=VoDSq{@KG*)BYAHP!`Uee~kL) z9x^w(`Ne;@rUZ7JyW%@(7m5{T*gMMxYv-7i8tavk-l?qnI=bLNLx=!v&-VvAsb14X zswS6v6DGs+TqdV$U5oOkUXf^Ur2ti6|ud_ybhA@6TRRkvqp&KxfxxaAMcPqZ%{v^09_^<}FH$ z%i!H@!1EpA<_2M9$*7o_kLpeppFH^wWa=I~;y*#{%u53ku~n-Z?-y!v{jf3k?qg4B zWe1u2(c-&;u_iHvc=HVq@>7ol+U-OBPo!;*E3+pJKlXMn8E^L)3X~|Ls(Ik7bkxDk ziXTT?DM$vGE!N>YkZ)oJE9=OF_RhbQI|M7|HI5e)}aj(N;1qSc3Y@e}ii~v9rCy z*Xp^fxc7h2cPDW*Ut4%03Q=;B`8BDu1=n4={BSxEMjaB+e$G++CmRo8@qx3MKN&7z z^>6%x;>%_YN6}l9Tjl#LQ!KF9=bY)TVBi}@B}_yB6102Yl+@W?SHUHX3wgnOwo9*P zEAH5RTfL*x#KoR_5&cqOdxsY4r200!*T%?Q)n~8V%U3-&qd6@`Gf#&D#NK>~rqV1I zs!>oRK`~;#;}&^Xs$D3E}j9!Q_5i8+$J7o0y zom@6mq%lDpa%i3PTBpU;>bC#a3uhn^lWWj}zq8$VqtWWlUDtwkQs5t$%PRiGinqRL z8+6_GGIe5ou~@w)=Qk}@;QV9xy(Aw9hvMe|s@l)~y0w2Nq80ae(fnT-RZ39!*#*u8 z(nO8O#>!1K3U?Vk+N`ar>T^Kf3X}O+$$6s&n73=52rGAn3)IDJ-2tsW`d)U0ttX`z zap6I$P5aX&u-KAJdctI0Nk8-c5xu^gX-`KbEFNvt;?*iqzjoe2etEP&H`ztD@WFg5 z{=8>8rDlTh9dVwU>_qd7WD^%kX@mAYC*hMkh-|xi-HK6}gXkar0JHujYrG=X3LJ_j*rQPr&1y zcsF7$rjq&dFEljAV)lgHNTP!Pih~h^EWWQthLZEZ!fRYjCSl6Y8232m2{Z8-fow|` zfBPyjb8)F!{p*xO_-)YsT7D!6%+!SSSe`H@i8Oc8e>%XZL@C2MyO6nlZkKXVK_cgJ z1BWBsOE?3A$9xzQ6$1|(ItY?=QFZNNKh<1NDHFX-|2AOBI(|5W6_-9G<~VjA=ykQ_A1u?4 zg77C56lluJT@B=x=SzYOFPKp&A!voLr~bCd692*WL!?A8*(%=V97VXSTi4QFpNtt^ z<2un1r(?;G+}+5%@iPXaM&#iU%yM^Qk@KM-W7v?4TCb>w)>9fu_xPuY>US|;eZ8!R zf^U?%l0A|%pP9M@o0e+4fO^0Sx#FY)~! z&t4AV9lVF@z%TR(-@Q?WlZL1c;TSLVxK zdT7HA4vvz5%S$)fY7Z7A0zWz_fZ}{CvrR z2Q}ULkYp#9=F0R*F-MGY3yQ{_*Ti@7GB|h9bE|Q1z0&bYqfSoy$9Yb_`#P0x-}3Ja zGy1y4yUl04-Wl*2UXAzH?OyoALhNtb`?ETk`~KVc$^<7xM^i+fSpBjq5n+_4m{Maf zk@-7!CYUjWUJ3NBH&osCGE{9m3;+NzAIoBqgs+0!swd zDwcBJ-)NBl;rU{Ok0~vHaneu}r&6qua|uzp)3?}(=?vf|0?e2XYhP9kp5hJMUrAYZ_zWUDH-^e1H5z3aj5npWt>{HSt#X^t7IO zs(SJVPLfQjBuK#b2uT2<#*av23N{NncU$}d&j;CA555}B63hn{a<|9Y`!;`h)^Tw{ z+<&V= z-hP5u!~t%_Bai>~WYZYe*u(`mQvR+_^6(s~zfla|J&gnIs?ii55(jCN5xvR=<{9yK z?$?YoDnfqu8k~vzSYU)9*A|`$5hIc809|f^+-nv;I~N+7B!6Q%KOIQ51Qm)OsbW%M zp;CG%kzWpk!ntuy&OyCE0hfQpu^oc$^xQ_Avd^JiBB2|o#w?vjI}ITP zm;|uQ8mN|^+gltHb(cJNz$B7Hxwj{ZZy-II5e^zpT0N90Qx$MBXS8ITAd`h*zW zKqU|%6@6e>6o^#1ymVlOUgS^nSNMqyz5?Q(+(!p;v{7-jQDw+tf}h7;E&^!r7+wL- z)8^~twch~JP6tM^_ZykFtxHcjG>*}(QrArX?OBS>>Z@udbuli7`g+k(8Tn@Hcz4&B z4RyNKevQ;EyaINn zcT31KmN}V_@WG?idh2HI&QqP&*mRuR(&!nZPn$5UI8_Y2ji6*wj92SSq)sW zlpw~5K46kg(ZK83*#8={#wU*6xS{+>P|WBq7|A%&nfEzq zXIgUH#N%6ef5R?a!Tw0GyE6CK(XyRk(=mjH(T{QZi5jS9ydfR|x|`a~4yZU2`y_G; zTm4trM`Hyw3@6SxW0WN07&wu8R@yBc5WS*@=_c0buAE=anI!bY?uoX}uDRbuzFQyR zU%^ETbmJgK$WmisI%jynuSIS}vOg9^vfLXO-Igec4)EPJdJWg^Pp{u)*kpzVE$6+@ zzazg*WzMq{KgN4Tz*W<2P$_D94iH85fRY2P5&F<1Rl=dib8GJU<_WW%%!1LtP2t6T zI}Uhh%kF5ge&cMF;Nkj+=Kz&2#%WNo>N%c>mT^_}`e?zxGz_UJD0vFwHDj*8pDy8B zIT@*HpPS=`z6`);=K#n#2}0O%`Ps$ajpM{7OWe;$vqjti+X)ep$jRq~vA$NHip~?v z+TR{25P;>+M(*h0NIz@jmseT2+`7*+aytl-c>fzNRz6wD&Bjz5%My(Se0D6N zGf&9Rqe)0XW+q%;<@oqIThOO3lV>wWux6%%7B`vf(h_nVOy*1P%WLZV zkXb|kz7E;zxRft#;TTDKY5~8_i6ye_SCeF*I6q$PT;y_`0H2-0seE@?;2h2BbuBE`&*OG1L74plS+~gQFqV3I65#3x5XW< z%NE=*QSZ74Ze=%m1AM+M&u;a&nVEeYGMZ@p2&_C54LM~E>z{9J=}MMibO8~kS(dUI zH1J-YtcojSa?16G-*6q#f1}X|4U+^JnE92|SX^OcEN;*&i0#wN-)f8hX?q_K(a#`F z#c3?D2WxcLTP(NPo2-}5BLpzO2t*PcWyMRCJ+-y8Yw(h`OUEqW4hXM}erL_uK-mbKbF6l<;qG5A92XyK{!AgwBs8dCX8mhC%lIqfy~VidK&` zhun3jtwl%RMBIrDCg_ge^H36HwOzpVRAs)^!=cIZ`KLmbkY!^@9%Fh%uKKQ0^FZH_ zw}Nn>l$cH&Q(EPRj$*EvGy?Q!sGppOjAT!BO9Rovemgv$~R$IQZzJYAQv#ax6kg`8L@MBS%@DL_jm{V!7kn6 z>DWOS1f!bLl!mcP_lTTA>G1a4!vDmH+rjVo`bM?z#eUCY*5ZNuH~ShAF6N`V9>KF* z&sMykKjJetxyf2~?p8^z!oI0`3mN$>%|WS|U}=XK z3`|O?Usy~#Ty{s@ON@lA@*0!q+|QdOx?n~re4dn_q7&^3%NjpG45z#g5>{aw#Q9m_X7B(g|+&S#a zK3B*=q6Hlg@r!u8+nTSHo3EnQBa!4E4Da_Mk*mGaN7Do91<{jgEb--fjrewp4Or#x zVDF~LII?Y>(^@t#wuVypbt{@5cOEXf)|`EfWH^~1XrV>}zMQE{%2~Kf%9*_8ZwlV@ zFBSbk1QXCRidW-NxZPIhx+Rgz3o{x`Y@p%O%<8+Ysk1H*O*DsllnxEYj%clo1s98u zLIgRN#bxxUsbEM$Q=2Ge1wHmcRKDO{_euJnN}*HP*_2Qhv#|s>;pYiSsUqpM;QyoP zEQ8wYx-N_a2(HE5OL2F1Z)t(zF2#$xTd_ir;0|r^;tqjADK5n!SaAsi*Dud}^Zwvp zW=JNv&)#S4Ypp$u;BuWTm*hoLV5e7=+cu^n&;p+9%tzC;YnD-)-l~|e0Vzy#_0(kD z{#h*rrDaEz6k37e88jFA;_qSlKh5>gt%^pEw4Svq{JSM}o+o^Dj7)jfPtMd@nC?1j z&m2DeqoKW9c5z3}5H9d0NI+D|@3WPtR9G%Xt(Y{;j!||*{#DqB1LAD$nRBhcX8p@W z*{EPL`Oe%NPdH5 zyb2EGm%8hOe975})GT^Gsp^Tc?IC4Q_`w&G{wwXVHm_Rjxz|u6TD18!4o7-hSHYM2 z2pJs`#}*kHbXxOT{2H9yc6-}taz0$X+7V*DJTgyW97oXurt6+9s0wBA&o|k7p9d;` z`Uq#(&^ll}3F^7I zl#icn`*!53N5|{k7Vt!?*DC|}y_52nEF9iBhtdX$ZS8cX9gINDLixF#R*q`5*S(gG zd#r$nDML@e?76b|%Ofqam6}@oo%#`dk_{slAALwlhj zLD+wK!-WaB?Wxkve8A~$j*egc#n#P6XT$xo#XO6&HO?8R;HSM_5fO>0olz4r3=fSbSgNe-N4bMFZ0nA z^sWGLBQ6k0aKb6VZD~^__66mK`E==GrF=h*`?j9 zGkoxPu(uTa+Kif14P3sNdqyF+Hp|ru8#0BJ41S4NZ=YaN z$Q0TkWu~HZ@Z2Tt(e67O{omLA_j}{(-S0S=Bldj}fjR=~+H}s2B{$SVkgn${VY0DM z^@uD1QC4?jyjl-B{#!YpOWNAccbv@^GV2q6JcSA>o9~8}o227AZSI23*xa~jx(;Sk zTNXXG8(1oynLReH{6bP*LmF+&>R7XfXFpLrJk0)kT06Lm>DgOJgBrYjpzNUG6E9s* z92gH_TiJD~7v@*KN~s2Z4V@R=OSg+;I!OG8Ca6DBrqWR&tv4;ApYF<1id7wQn!BBW znNEpRbtmqQ+QnM+vw&g4&$DEM?|_p%>0B^80-(+x$v`tsLdNPBQYxmLaH(Rz-CeM< zGWWyt)@;Hjkm_QSIg50hLfDu5RE+!m?cNTC5BDR#77LenMALgCcA7?!Iw<@-DO?(V zr?fh2vbp>xV(W`7J<>6?>mc5!4QuGBV*y*ftM%eTIKTCE%n-`1&Lt`=pY~xc!!@#( zjUp@1;PLC_mjaei`(7ttIC)CU5tv(|plHpu_Ptr?ZkyJ+3Z4|xJ>L4a(W6FRf4g7F z1}UJ)r&bvalF<--Vw8;jslvAz17NUM#N?5``Kz0(LZ!Xp8|ht7+igCLVA{`DqED(Y zlyy?K*uAU!$DWFYg*}g+o7={m`85)FWiRxMW}*+WiEP%c`6m31rX>mKnM8fh|DQ() z52?IzuKIMBp51X(-h$hiesD;gk(2kG$lMPY3+MZVvubTU8dBQI(XthbJFC1!0T`9J zBz(hh&@6Vi?CwDo4yA?XNpIXCs5np^ch*8-Z6xAzmc!?7xW*h-F_F@I}?h>r|jW)tMOfXR^3nZ?*lMgiw+w< zQ2|l3-Ma$NWi(L}Fnm{)X#wg(nuCCNC033Zu`Y!TE3ChHm~jK&J3R2D|8nV0-uZ?8 z#0|kuzJ$8xtvC4Kvg8_CX@j~n`KJpV_|){erAKqYQE7#nPYeO}R-_4|Y;e0?Cp_d> z9u`oW_Ck8lt}Ulex?gn!FS!F}eH&~i&R>z9kdK;H!c0oLcLAEg(_LbJ(6tndOOFH* zBn@^}_Uf#z$X?Lb*I-~gUDx^i&t+p6rvgj7K&qu<%Qv8V&~Y`OyIpd|3-}Z;h{V1u%;SUvg)|q z0K_xVE#Qjb-&GqldGU9edbaPoDSDt^+pSrAAKHC>lmrS3)r%SDkeVZ{JIMz%e_d)R zg|A32x*VFkZJ>VsRKDk$Z>t}ct3RjAU?wkk1z5N1T(`!!>b*9*=zSfLflBt6j;=1s zIoq(H{JbN;qeE%rR30qnU?+eqlLKk(rw?)Y8FZ2VoV+}!A6gKx-Xod9t(F#g#Nz+) zkOiH%zku(ovH>%=qXe0}d7P-E!HueKy8FXF8SAe8J=3|}Vi!usCl&tfm0^Ev(Cbq@ zeU$nYh>DHX%Ui6!q*~<8_owPnljGPhK!%}{ zOA;JrRWaZz*v(-zN!Kk90y)aNi3k1s7DB%vS}7c|*NH<03EyOme^9imQfaeY9ca2m zfjsEG7m~0@t-#tYtimaPuNqf~O64yU+IoyLShS&6-eZg>!^p5Pn&iIH=CZ2VS*nJN znYiGn+&!J#&Udh{3S4{4eVIh-B-()-@&%Nz-F4;~7zke@+QABE+$B>Yl!(f!aPop= z9SuEcxOhDF$t?%j;>Y4zQeot z_l()@&K?Y0EXK}BAj%~1I|F>~Qn*aTQi^%P;~o5D?x z1+9S{oUYVG=$>Vx=SEt+5u@2@T#7FCnMTP5eh^71e1QMyD9WnhOj!W^`Wqn| za2!Ba#A}_^gB(IJu=6TsJE2_`S-^gi_fSMK)y4A-fFA?NeGSL_KFA zlHZ!~6h9dr=c7?-*ya;z_{b`%O?^W@dBiXI%Ytz{GR6KhSXxYh>*<$J@Gv zGyj>J0<#Z!&gT4ep~n0*79kR+(W+3G=kw|YP7=BSifXd`LN^O@ILUT`I6@DLnj++{ zq4tcx@?S%T+pu^@bp6>+3R!sE)-0NP^vDagBKgRnS8lC=oOEH@F^j!devp2_hD}LPX-BUF-s6*;rV&P4%6ZbXO znp^EAgg}a;W??FRPLAyE^GSXBOv_+vdz^59glGIxijf>Wrl&DZ1YR+FZ0N8@i4Way zy7vhH&%DhcK^2pzNe@$MkKD0|oJq#09OZT0ANPq8y|X6V=x=WpAGmZJ4bB;Dx4oW! z>NIvr5~yxTOm3T`ZR(5u`+1%qD|$$-9v=|P!%Ch|$EOD=w%P?`dY){hxJ{@;MwY< zo1)0r!*r8D$9qLY3)bEdPFHAEU)om--&PHYA&Z|k?gK81Gu)WpDf%;QMjpo9{a%%* zhVc7lKnKriB=y2&UX6jeD6J{v2r|*c%p`{r6#hJ*`<2i!dz@G&3u^d&p6sf{sy2Wn z{@IeYy1L*U%34TG<}&Ac_IsF7@^sOZVUG$_2$O!#=gvy5FS$0X9b`_3gKPgs!@THB zmy?M3-B)P>zR2fv65q3?6%LHEaqfH^tvs`*1M{CcuKjU|C3~MsF0yLaVvCF2jxSFIhs&=L~x- zjGP>5N0^0$y-N#PT$YVYlb!zD{(I^>le+E-Dg4zO8#b^aM8JckvnQloyh)9Z^W>vE zJuKk2?cnDS)}}c9qAF`4k1~xV;LAXI`nIZ4dwtuw;OEKmk%NB*{3iBI)QumXm0u-Q zx=-{Y-Tr0KkDxmZGMi6$>lr}^jHe~^OE&(5qqe=-jZ!5hw$iY%x+s#Xv4h-~7D^*c zvi@F3cB6eYj(2eqaLr+*A}I>9godxj6NP0t9a7#Jt+I0yn4+d*K4L$gwT1KQX(Hq1 zIbFlSP6l8Mb2NC&4TO0i;17pYr{vgYDjecFWZYY)*ZmBh!a;ePk`08abe6|@3l!rw zdmqT^P)}==-XO#-@K*}C#;6o+ohhr0&jMnT*71+=xp|#+hbmfdgAe8cL9S0okDpBL zgOcpTg4$<;Lj(*Wdxf{ImK|1G=GttJBP2RyO>x`~i=~Go!=aMGvxb{_4LUSqbnOX0 zJtQQ@?`cOk%(LEzt%I(molgoG?dWqI}VC8AS-}8C4ZO?AnY?CC( zN6*)+L03C3kl~!@?>>H&uh&d7 zwNU&wWBJ|AEh07S^$zBuoHV6_-PfuS|vq(Rh`>waYP*;d{Pxuc+oS@^-J_2Q5 z!t>5DoLm(|q6+7Os@P^@BudA%R~FK@kz_eOjpVg_3YzWtaxaT3BQ#2@&^N44M1MDP z+z!KZHIePh3)!z!n6CI56=B-pg=yO9jqS41EHsPm!0%@>CNM#9hJZz|Fz{)c0(dJA zICG$-D)?_!T3l9SVQ3m@6$Xo}LYz-y4{?=&$53#JnIFX@DB)^+{Nl?ns9zcS`$hrI zXJGl({}Q(8E?7{QUFxEVb+fZaCr<}k_-+v zrXE~PJEL6>-{f~XJnPoqem>dD$QGoBHu_fWArxv9@Kpu zdvSmFxQ5umW)t*qZq2f}^Boi;0rPEkU#MC6o6{(f;CAE;59|vOpWYzb*k^QhbRH5sKk*|gtcpmDZ(oXDUmgxg4@q6$x7{=y&i^fgvpD43iOjZH zhpcxywZfX94zf+iNQIT-g?<}K(iehz31?1g73B`zxl_#=tyASr2HR_!(Ch^Y_!Qp0 zBwXqUqqgd=IXQf-HhD<;>9@xQtjW6&N}`*GnT`cqTB_8?M{(S;z#h`8gsgW54ou`r zXnpgN2azP;_>?oq{`&RHa;iwK1$ODRXq2f0DLWaouvV z?#ArOg5jkQY^qjHJj3^wCo61T`-^;D$8*y@{NGa=CQwK$NiLCwY@t2Do5OTBOHYoN z)rPV&=CwWdhf|@lp~T!?C-Z-!(u1@=Xewt*zl}ZP*(pg5G=E=TYEq&EXnQ#yrqeka8&RO^E`BzSDKSv ze9G-sYX4d%Hsq&&4&Nx4=e3w+uH?qI(3j`pUg4JjCxI|r%ci;GFXs`Yhi`YWGgg`( zV(Xn2xCdBlr?s7!w03HV6mh5pr~EK(Wuit}!bzNJ%6fUFl4mEYI&Pki_^$5UQmTHG zew4gvC=WhqO;MrY_*|#^r7+Y^tR6p5TX=^Myow1lWZS zWLmYs3V)ZjPeyOZ^TLL0-~c{ZYFzQ*^?9maVNDnyVr6(Q|2u4GW=9PK(GpoB(c-ou z0Xs9Y3fd`tm}J$`&lPrQkUo#RABra){$(*_r<>EJn@huQ69?JgwHo}*`z{OQeu*LG3sou4Xi`BbTI=+UrSo~V$VCB07`_L$e-Q*t z35RXkWOWphk}E0wvK;)K`Xzx`HxVX(XS#fcU|01P+dLv2zm+TvX*WM;$2So@#H4a) zSa?7n1IwS$Ud6{JX>omew*46Y2O+Slgq%GwK=?46R6P~9VPycw*uPw1SDZHnH8_ag z4+|9o@26Jr2#77#akfHHDt~xnRNi&(8gal87K%&y*{!@dFf6&Q-!kg2h1vY#=fo zWqjg7xkfJ*6sr{o0>W$o_ejbzwQ@M^8;1F!bKjfVh@qPP|;R=(8CFHF)z9J53GREa|U@dkhMz8dO4 zt+p9sSe6x?$xjx028KAO`kk2@Qsctn$LR!AUOguWso>K}E}}?MK^S&FaYs#TgsydX zZ$5ZKH4HtbqHusX(~7%R17F4g`%f^!0j3_g2qj-{-M_49AKnef{8w7G4gz)D=J`Yo z+;L}u14D7lgUk7N3h>7Tg~P|1^6x}?iuPbg&Uh#SyHCb$-CCRav%E?Q8Co$yPV-SU z#;rL76v)Jakw~Y6IL5t%Ddq?SH6o$EG~ssaABVZ+>J}x$mcX)?S7K(G|q`N z`)y~Ud^XY~@NcMO4Q6=PTcKBmKNnGN08MHwpT-90PZt|zqki+I^MW{;jhh`<=rCu* zB|Mj5^X;BxE&-7+;kOW58OB=#8jg+VT`-Rp>hO<5szs8T3#0;;@r0It07=;skSuq{ zvPq}Rip<-VIK!+SiGNmwFnpy}m^;211PBCw<)IEyaODgC*!ZxfwcRc4s0do?gO|YQBHN; z^9VZ<7v^@(zoW6I1r0Py0Kql0F|^?5Z79C`!k5{1&E6~Xb_MT0KiVvI zIeLO+Ub^dV;lEhP!=8Q5rll_T*9QR7(6d4Tv4rZI*(6Pa@5&g-Q z-pXY0)r}i0QJBH{0RauvYXPF39ViO3>M^0Q8>lCOWb8@g#SJ{g1W%DkEcbssFpGHe zOYl(I5ImCuPmL#RA_gs|R^N=$6(ne{nJ36c30HRdlQR9Mr(Aq8C^7KZ79oqQS8tQ= z<@NmbQz+esPxb;wo6Qt}=_CNLAk7uc+z24JUqF74?FAN#2sY{^J3WtHnFstX48G1j z$Au+MkqgHao$vC?2Lycz@_-^?_2ZHWJoqG@ju ztv{>ootyU0i5^IQjM(&3H&=K=H35qZC%}|ck(i`{IAey<1|FaDn#o6V|BSbni)+-s z$3S^a`Yl1olFRHdnmj?D-|5hnSPd~?cac-4eP1>GMV9KYWyMvmZSDP5!{65YQNINK z1-3NPQdzc=dwKr=>c$P@=Fb^uqy)$6t!Go*Gm^7zLC4h6L4!kQ+L+WOl3dM2T~eza zdo&d&S~=OBznzn5s_J^p?Cv_%n2?FHX(3Y5pv6}*jI6eZe@bL_TyM%rT8V&FdG*NW z4qf)%HATA!kyG1$p799oFP%E{c+8bmgGrf{D1{G6RA{M`n+|P3V-2w}eF$!uEace% z>r=83j$PXm5-cPgW(g|U-yM+e4k`Kwmxkf$GX`f~4*cNX}l#Z-Jx6bmLDRk28>8;Q2!C|^aRK)Yb zn51c0DK|DoA9~@z)*S_x!5_SZ+xOzzXEqq>BT!K&H>VCgA^mDea4zGP7zDz^&iS&N zs|uHup5c8fw?8a-3^9$u&L3O|cM}d@9i?OMM9T(evUoZS=`YpgV z$G8^od@>6lj!)DIQ=scp#1+STX%4tLgeAGBAh}oHiV3O;k=KAH@nLYVaH;8UbfhNA za3VOe{0@TWSTw;8HD@lM>nZf7GqL_I3l;T4M3oAk)9w#(wXR!v0wXGcHwVfKxUc`K zNz4Dqj6gohZ&Rp`Hdb351{L2O(gn<^#$#NEo$B*tj&a^()z#nS@NZlc$I@Z-KAk9V z+>`>oJ~Uaj=^LF?G1GT2l8}*M%zv(3YBR5Z-_D4aH8bp{>s4wCnR)#F%8-fi++T}A zU56M@5GWg8Cw-7df>_~v`OLpm#NX+1Bs^>NvB~ePVUt5DVJ3w@1rk`;4(@-}8>eAtDZ8b%^K&r5#I(;@6IPLL8z z;#$neFA2vsJmeG?W4R(cT~F65n+1WVm^bTzDJLNfNFGp*>k;Wq<~v-SPDNfv*Sd2) z9FXI-q2IL!&TQO?1P%aC&}ED4_#;lp^-|@ghGV|VI<;fH)YY6`I1*F1c_I^$c!Px^ zZa{-i)yKGX#!Wtyop7aZl4K(|hi!ka{-v?}=K*33>iRJDuX+iwdR+!WnzMMvG)ScM zo6DgO`I4cO@M@N-1|L}02e0-a(ov5j8JgMP93l#8nJz(=Vjx%EN7n9GiVpdgVSt11 z9G|$kc!YiD*t}XWZ=Gs&lW{E6L_94??ny&Z5rYFn{AXzu%MxcjRO=sj1q@Dnbh=%C zM8(f)Z5*@piX}_c7V=Dd8c7N?=f$csIW~H!R$|5W*ZfF+#3?v!)?Z0_2^FNA!(hC3 z_XZ0G=QOGBMHLWHT1msZn`X@XPVeg7`%xUZwFOU<1m7Vn99Guk;moX_XI=2*=@6f; zk6n!EU5LC5HM*t^u2Sz3cE0}*5|QOB?uT{2oE%@x3DyP zQ}fe<2#`c2GvB0qo)Rtly#%{hCP#^<3lG%S@{TSF zU*>kIi3ZllZ$F{6MMo=SuDOFumn;%x%EjVUKf34t62snn(Q8(5VKRQ>h*po%voR_Z zH>P+J*o4_D5Gt+^i;JuCczR>m;lP)RS`!s(*kX|@>kRN{Sc)29Mq#0L=ef0!yFDDO zbC$MXI@fn0Vd90D6NNNRd3|K7Q4+4+pyP`UMQnG4l%`03vU7(8%zcDrrFf)tKVNoN zirk2bUDMQ!xY;cZ&PK4*8Fvbgg@%UE@5<*QEY4?mzU#qReqnWxJ@X)n7UyMhpVLLk z7SIS^BlZTKN7*?jp= znP@!ZxU>^SY=UF227-^>_Yz$63midI^VQGu05u2hL<#|ARyQfFlMFSSipwOCb)Z|% zdBxHUsngBpi}cr)%igz^`_@024ICJ(6)UEYgDHCH7>d7F{kcI)2+$5+sxTd^A)*d} zk1xzf-Yv7ns?Y^%iqg7NX!4TXN)^den=qJD@q-K}Yco(pdmaip$FkY*Oh4As*UNts zbUR(yJn?rMt(+Hy*MxhoA`XH#!i~`oa2PeW>`0k14FwS*^sY3+OLq>m0L%UNi@R zlM9^I=ym4ODIB=t0D!tPbI{}TFn_QSMRv#4K6f52meMb!nRkD~scMWIBlkFnnSb7j z6lOuNE8dc^CPmVoIsNLKWT4NQz6O-n>qj{FP+X9^YzG+*k{D8u?FJUwYjNRM@M`kY+KRJ}~-IRp; z$w|^f*0d=fq@SmmPzbiR0A@E@fW$HYMw?3kmB1w#)6ytFY} zjP;a`n+fV+sEPjG6cezU5L|!hzS)iSg$7Ov$8YQzVyu?pS_*0fqY}C7MP5{14IQ~H zvl54hoXzbbS0vwlfH=<#`5`ASAaFEbDc8dg2Llq}h0<___-nv$uttx`k9y6{$(2_= zs@lu(DPLPaP;w3yHg(N)mHe3dbss?YsuPztJSt?X#I-bDmKP4V;&mA^85cdsD)0 zhrARZ;vwrdAoIYJ$6zzq^a^9;<#A7j>k$!rfCbPFf{X}H!hR{5_t&9FQ#gyf>zoGv zs;^3#YAe70gY{kS1+f7zZOWsYuko9FX}MSFic_a(Cmz7W(*;y` zoftcnd0mP}Vh#-9di1iqeSp5W-ab8@6$;9Tr^+M~vpUObT%q$7^ggVejXBDkg$eT( z5Q>I!xBxY`i|~PbZe8a?uw3Y~vVZKNe41ETzSp1d8~(PNAsdex`i)!kipLl{>(dxJ zB5Wm6BCw47HZ=4sSfUwQMun4=SBE99*IhrS%05XO8oba=^nBBV8zDqQ(sgk$Y9|fH zxLc;D4|8V#oDGbjhhI|OEy*XGvt_@NdA{A=d^?RnTJ6)3)suKW`GMluX@(~adUCal zopWBeDuRdtrYz_&DQfZ_)hE6v@lV7jiTYwU{|%LF5g?1&Ua0L&BOO$hf4ulZh;`Z^ z#&gC*`c3g1;@P1p2)_O}s~Who89QD{Y3C6lDQPqj=%a-9viY7Qs#aiVOA8LNRS<%oJd|P%`bTk5>nchzNo^) zJJ54bi~RY|6#P)?z>l?T$n={aK0#4W~;V2f4i(7*tOLFt0Hwa4+^ zT>mWp`)|8Dkr*~f^Z~G4W4D}`LtK#wL9Q)?Ezl9<;Ouu-$dm9AxD=J_KxNqzk{h&z z81aZxHd02)y!=_c(D1tsEx>(&-@G&=l^@l1PBdlmdBzNpyP1b=3n7$@I)suDg9L#1 z2q|GEB4;3N3JAE|OH!xlP(zM$?V@Apf)~rCwEGN;>i1%i0Z7jDe%3=eb~+2-pzGO6&oDCmTvk`J7@L#NtE2w-GPLjc&pGX zYw@6AA$3rS?cO70HyjiH-yT+y&=AZ&$yVD{-1{Q^D*V+OgTAZShtp0T%>^}cncpht zA^f6X%XSELKGGdVwmcq%q#-s4e%;Y>vSMWF@NL64nqTI3%7Er{8uW2j#O`oW8*fSM z12-|dSj?f!b%Qqboi@iS_LJ52*`Q+QwAZM+t^{_1zj$6TlbG<$ z%_h!?1IF?C557OmwlBa$3}c#-Jcl|`HtGK9Sr6PNRrLQJu>$u>axwsRiGcLHRblhD zTWL_`talc_voim@+nw)SB6c!b9~Ei_pV`&^i^y~eTWR|hbyY2hO+awA*rT`XP?#G- zL?xf-IY!y(ePky|>#evOkE#hv5&ncv)AHF2L&#)m@p)Lr42$RWl+H7|%Lh%9eiljO zZE{N#F8~AjGAHLd6^+tOZAadc)G@WfjVA*ayD7sz%N|=`+MdpP=E+DD z4fO%_8|NA7X=U16f6u+1SL*>sTmn*%Ng7cM`@Z|cRobFv0RDW1)(XN$QASTE_PGG6 z@!UA2h$7U+1h3uGk9hyQH(vI@`tIWZ2`K}Ba>Sv2dt+%> z(oj9K3U|J%Yj{NbqMW5rbAiBxa)#Bn#m0+f)SsiR5mj_hK-TC zwTz<*6PV2pA?JQM@&3%TtPEn+`I*EZOiO;YL4=JubPk`Cp)1IGEf~_~zK?gxS7n1b z{r~r_kw7z2GC=?VtI~gVt9Xl|!{nzY2wGu|TRPDlLJgkB-3*7Wx`A|?c*82&A*A5r zh~U?ON2ou$S&I%nBl;UE54pb-C3e`uD9rpx<<|dLsrcx3%~dp+60q|ce|9P&x%ECg zoh33vQ8-uXnS#HGoo}!C?lAp3xp8jIrrD!d&}m&ucwRm!c?mOz@y#_;SaTB@XP=x0cm&xtyQR5UxgDzumaLOp?PcqaYEwW-!im=jyYbiTi>kONmCkq zLfBX1f2Ei@=6vnpaS6DtLIH;D?fkROZ%B~ETuz<>Vk|>L>#U0wLV1Ye^+=r?{CCs& z;=%kIN5}U^_E89vvs&c2@vPNq8=tt>e=?6SZiW?K?nd4XZvkIm$x9HIUP2O;$Pyze z1HUIyXRc|7HyW_~CJ1<#Pr(f{GZ_joGl<-YC(E9$q25D^yqA&eT%pJhRm zkRk+_o5Bd%-;7O~UFQvi|0=)IpnKsX|6xQ>@gVwZ2BDLA{2k}N;B%!4Ct5CI__TX4 zBN}Z!a7oRufi5;-ho@W=MT&(CYAY>4(_B7j@>8rrqEow75^S`=WH$?Zf^I@zo?DwV z>|=W+pUB_?QDI2p__QM`-BAl>f#VmSy&hd!*X^j@&Bga|e4?Yuxcr6ahgK#Wp6J$- zFhvW*rDA&MWb}#DNzDAt(F61i~x}eKx3u3o*gkCNk^fZo@-Bm-7Z}$DJ&BaeW!b)@5 zd8`VbZ{0lj>aV+ZYgG~{y{-N6W)cwBKFUiz4%?cPp5XAT)P}f`2!v2D|R_f`VCIi%n{dIJ&VQc z)#f7%VogbQI;`U``7meuFG4y?-a5Z<{}jwg0Kg_eGjd=17{7wLfoCJGl(8Ma^a4a7 zb`aqwWuGQ^U%uBPW+0IYZ(^G6r@m~U@;Gu4$Ni>bzS3Rf3I^+0naHFzO6Q5cOP1}v zUFm0VKv-RT=k$$=x7R#$?1s2dkV#36TU~_41%i0OWJsxR)Q1v{@{)&C>6sCR z?I7d#TXP_g*=f(7tC(lk8{Zt@KLU1-E>X%)4#KJi^3RmwIXan$aE`S+xmL%@S@X-u zl}L;4I85N_IQ8?7(+aVbGLvgg=izFD6xn=@ktdX|hf@l_wqIb1+5NTBLtz;bV&wvh zYJz-bEKXdRn70;THO5T#CwUu@BgCCq+`6B*Kq7+1jPRw5T^0NMdnBCQeBU+O3jEs- z8-m4}MLUa*;6+4S$N_2un&ynyN&GK{gHoF>{GaC7J<})U;oUdu4O2g(cMskeXX~9B z?*x(6pljn8F%<)P8VHD<&R%FR(@W-^R(~2!-`a+MnWP<(T>it!f8HELSBuQw07cRH%_TA$NjIxE#IiwHWl8cj@2xFjcbN(BG*(C$aRix{6S;RVEEp*hh~x4 z zO=i;nj1<(z22m1XEeM$U=*8M zXP<4Q^OpCVgmtoox_K=>x;f^@vU0R30^^~~yY4|u9=}njVjYC6xA2nuo^bIF{j@w^ zCX1_f37Zz(mnYEEdRGp#N&$wbf*c4G2uZh*BbOEsG-ID;v8BQe`|jKzV|x4j#HLuA z>Tb|)3bDbMMAMG<6>s%u??+cnHe#Gl@ZP)eNGqdQjj*su>ipCGAVVK*=YX(JTU--b z;#-(YE{lj+Gur#Iw;y9YEczV|Pt?NGd<4eNJE+eaJjc&}3Y7f{3l_o|MEgF{7$)Z# z{~RV8-)F^&C_`J?AghUfF-^uS0rN!Tv5zfoE42D`A6>So&4GEld`dqK^L7O-X8>IE zMk9c&JTcR!+im=Do_E+>k{%GVR9VazG`MP%?(Mv#0aX$PX%@BGnl|e@2dQFtF4Eb& zNYAL?VtxkPzY<0NHdY)u$<;TKkO=qMZ#!S75-)7Cur=RGzAm1@?0+HSOQ;!tyLY_g z$?Qc=lbL||i%nlFJZ)}ysi7dymV{X;{5V5d}o0WjS)&7V2pPstV|w&=dr zC-#q#SFt|3%O~+daj(w|E?O&vvKB3OpueRUjCjoidupOJM<}epb31A68=#UZq7tGu^RR6uRnbf0P(9lejdWdd)elBv6NR`PtpYjXnmNI z^Mh-N?f*sbbU(M)CZ4vV;G_(vr^rM2Lt>1y_103~eG%9BE}Goo_iGY+BYvCOPky0& zVB+&dnsw`(ID48-t;@IW@4qIh7Ex)5_=pwAb5 zi|43+$OiyF|Lr|nj$zxLfRN`8&kHTFt`k8JY1gIH#SYrO<_(^~!vcxtL@^DAz{6DOo&Z=jmoy8JPE&slc+JM?38y#5ONgRb7| zBdkYs-e>$1Wr3XFT`=yGG69kv=4@Oq6F`Q_3x_iyrL*kq=RHK2TxGXy#mw+BWXtAc z`3#~`NUwWu)+Mj8@>lT#WigS2!R@XGE{k@We9@rC-!AM|cgE#Q5k4Bm-#=O_tC?H2 zCWOQdf$~u@9NgBzzy3wi8!p+l$4rYmK)p3s>T$`{_FJOWR<}NgqW)Ys69HrHIZLL) zMyzTjbgjbzrXy0v?4Kff8vNm`@G6f+&Gmvbd=}D#jm&6Gs%am=BHmb&n^+CxNhP~J36|8YEK<9Ug(G4c-4%Q8pUKIcuW0E3S= zZeD)bvIkiSkoKTlRRv52sYzaIxdZ|^ey^-B_gJJ8+sB`Tar8jXUkEO0fEeRDPP)0G zw#%bza*MqN7`7+#@(~iBI$x(*L^27j4VUz-CC$Q`^N1YFpVF15%GNV=5l}cOHbL|h z#%_Q*z`mG~qlu_E8?IJkBoUtFkLwu?o*bCppPkpcWW>~rIE-|jLY0^NwH`CQR=?DV znb*B$ojqq#=83Fn!e`QWvcN-2dAYmbW@J(fXZo<&Z@9hWbmz|xXXrtd-rXIQL0(rg zo4B)o@hft(1)f0Cj)LElQCNBw9(sq%Jj%~X=ODL7PmFiXthzJQVFIU2u_-Y+0Ki-D44}N`GF+D0Ow5x2>$Svbh=4V6f~*yUHPw(!zcde*Bso! zTPK=tP*?<#4DXx8tZj<}BEkC9Klzb8O2|6dc@;>psOFNkkA6iCIM7PE^Sa~g_u7bz zkC-^n6c^i|usE_W9nk+ts7Srjor&7P#;5l4G+~$KcRzJPDHpDBhCuv9?~;NK$3Nk!u47CdDPeM z2qu^q1pOnNW@Jfh7kT>(Xx4PeI<63u$J$w^mzEH+w6aKnZX4H`v-u8nG$l zmI+$)G1vd?BI5F+xgE7wSI+&eH#|{cnM1-Z#T7pD3!A@mYAfQGvqnCivdmILa4cr} z)TbitF}i)8TOGzGo6R?mo?@p`yKCOvUA6p8b+sA76&J6?PoYjZjC_xhN#tO8>tbY> z*I1_mF@fI%^%!_)E*Phpda0Ba;(txs!BAM3QkH&wmL4GTXwFHBE3 zyq$pgb4mr_rV=Iys1*67?6u&ipl-!)d_0vwf#;18FnkkLl<<_eofXO8c5nyi7ZrbN zP?D@fBrM=IIb(NGznR+0a!(Y2c29aDCqRhHg6DHETUmJ9|4gK+vk+hz15iIn*Eu0M zh2ma9IS0+-AT995u~^ zGqmVXnA;x7dYWf&^(*mF6wAeWOUp;01@Mr#-RK6jWz+eK(d>9q4dvWbS;o96$`23A zmemp*IzG*ws6&heEnMI1n0I;uhV$#_;bAuEzd&Jnb39X9nb(WHhCcOkmbn=%Z8Zpa| zv?f#XY(gwaZaw|y8S?BhzL06jyN!Xn-J+YvrG(EdOC!{mGO!KQ)G6Hr5^^n{x^HBa zt5i*@2ORceKET9H7hN`pw~e^i;AOogtbXfZhX~N8dmokAgeNf!qPx-t)I#TDrnu|}+Uw#>~ z=6>xr`Ki|C*Y?k!S@XH`c_-p_KV7N%oG;I*!wUpDV2%A`G*&~Y%$)U|KvX&MJnw5G zIojS6FaeD=Jgqv7M_AK;R!7+44YPf?1oP%r4QA%iH=lm`;6=7~!gK8V>aC|2&1_G9 zUBmeo-AKEN=?&oN7~nX*A{eZpg*2T_1)9o7hr-x$K{159x2Je+iS}HyFeEy0o{3_VCi_P_L!V7QKi9W#^Fjlmw&sdPrknan?zW!UIjcqP}-ctV?|P({1Jx|+?WV^C=lgii8t z1XIn~hRJZvJlZSp>Cj85ZaMGx>tsRNPscsJPTN@?sa~1Gq-qcR05AK&)tCP>@)tN! z9?Z-Me}6DvKTMMGsX${&KN>|awqd!-Tyf@EnOS@8DEwJoSnt}0f?h&0U+w_0mv_g{ zx}|XB_l|K)W~NwY!AA_Tu#bs_Me?!+Ih!GyhD!zIUQ$8RU1t^FEH~0pU(7 z8GueNO3U}?^|=oOZKw_M+;5~EVWN6jMkUFCYP%7Iwj$M>x*2CP#t+EH6U2^lH*-uT9plP zFs^*>6&Y4IBGauvWkVq~oE#c15^@9}rXsepebl!0B__Gc1;!hc$DUI&w$Y`AYjy{C znES{UasYtCMnyIp)0~3d|X9J0J=6Ji1i_%Kp*T7bfuR+zsSo}TdNHdn-s5Xw% zSJ}L3JY;W=t(^?nA4%fi5Tjr(`>(#-oYXNAD60jSBWbyW3eKS_pBC!D#qAQuJ;Yl9 zt6xe*Dg9uuu!k@Jx%MNNTQC>De!%7dc4c8B-9E;aWO zGaMb{m$h?elZ%#vL51W(lof&anIt?w-t8}Cj?b^Waltb{DIji)5NVbG>>PJjRJ~s^SdThk+yeYh<0K}FuYi9H zMDQS{6#<%>t0}4Xml|wpzcUSU2(KSX-@e?ql;c99*Lcd&xsdU|SJO1Cgb`gB9N^Qu zd5flPuzB_|3(uFU^9O-K9J##=jv9%xLTbt^J;P|vzV#xV$ z@33ZBRvEW6a(r*&MM4000A-SOQ<_Zf><*Gkc&p+MyzDh@xX*BjWS|~ugLOU87Ihx? zoJ?wtG^TFMH-gR$Ec=wJlg4f`1!RO3*!B=!Ir~ga^bTG8WwS$iTFs+)5&pfCR7Laa zlah&DEV$qk;82~wD}7?q$5x|28gWOMN94!WOo0d9e_ar^Qp5>Kn4vX81$mov$&F$_ zlZJj6PibCB>ap2dT%%f!Xu=9WRBJ9+2h269AAfv`mkg?i;njzmOohhm)Tk^8*(a)DZztfo3#30*!5~K4)&G#-Z-jCwqMEc(j~zbZ zcdGL&h!=C$_sicPhl)WaE{FqXr7sPYZ2Py6FQQ1@KM*WVrFJHAS5>hi5gZ|Z(in1O zyP+7TmA(1G=Hh*w>4JtYUHXn#*y;J0p<$DXRr#2-_tzO2=8})7(P3e^;jgn zy=gXlh-Clf+L_n6`@)`bsbiCXHqTV)frqYK#Y7cHHR9Q75g7Bvj`nO60|bOHhO_O> zC-CYU zM*KmVs2*ouuN5AFat2LRpmcf!(q?Ny5z+JtnRrK4BoTztw&t-uX|A;N9L#kNi?+n$ z`QJyCdE32s#`Iy)SOFrRn-uZpD0r!`^K4?@e&?a)K~)j{{Pl3Qwa>jo@@j*)o81a~ zB{edr!v?_tQ{~CKC&>E4GaO1#pcu!ifc^?t?!F?@b+lE2@^a$t!->`Fw;-m(YRY24 zZCisuePMy&;r9wOeJw0=@{$$(0i`6~^Mf{9AN9{n$N1d$8+g=$&sQTyf1hO2T>^b)UfK^EsCC2*IYDDni(0S_Tzx% z?aob=;5kY$Z^)OP{yZn$KEih?3!}xm6!9V^o^-dj^q$Bout~{%)0H12&oZQUxj$=; zBkP_=%^i*W~^Lmmq6n+_diz-ZhW?oc27Z_;!fKzjC~l6~Fo?mq2k} z43&UppN>b}Q>~*Rna3>OW+y8NOkCc<0xE^6UHj3Wtseq}%{s@P%&SmAGPRUUX!UmU zVRK)v5K`s_{>R{Su-L5T2yS|Rv^Cf$5AHuDV*Z2w)`G8Am*u;uX0&?neW#5xKcZo& zSL`77aHF?nSP?Hgl^JPYw(i$xB?B+Wh2mo6=>)DtZD$Z0Gl*E5CWBP3Kb7%zg>GQjqxSH1I68p@x-Q$1M6V*Nv+s2+X| z(L-MmK^J{ZvPg^NasKdu_DHLgEx-3N^?CH{YLy~Q_501(EHR2WgfJ_Q_(%@0=yM@| zHR~}!1s?LXS-D}ftQw%Mt*e2zXc5BJ%(Tc(H0-j(p)Aq) zU_uwxKNT(Xn#FNYLK6Muj)>=%e{>82OiqHXEEF@|y!AzNd|G0zCJn_xY6TLizC`L7 ze}1BHN@8})EPyK#6hE$$(m!Z_o-V))MImKSjNvmS=whlN=m1$tvZ#}%Pi%+5bX`7|T9Mw-eWxejsBH0IC#sBsB7qM%!|+q#kbB*DT8m%PKC5`*D+XusfJ&DuoYPT8H7j>)=ahy=?% zAs~TCO_kj&Ek)$M160;%^t%n)5z9v7DgdLt-KNrMP?(}(kbH^eJ@p&9efFeA&3eo1 zLIe<7RpUzXiC|hDK(q^`V#iXO>jjeZpKP)-La%=wL4l(YV%o~xh!56%vG%5YLkIcm zSqF@Y&|yc9z#}Xz`7NwoQA+ettf2urSptBuCUqC4+J7Kc_hP(Nj>2)#l6rm^j`@dc zM2+8Q_-L{6-Kpf}GU6`J)OhxD6V)9GXOBx4dHbl`8X8OxOhC2HfQu9Q7x#Z@TL4KE zQc0_jNmRPJ%jaMb{KgC;>&F0zgIL<6rAA)w%~T~`PYI683Fu%tdvth%@-#Ix;zh12 z;J>yHZH54qSlgkQUu|X15Tu3CbFCQKt9-Pgq<{<|2f_AdltK>BJ_iCSC^><8N1(Ix zCkR|3mv7jHc3)Rs?6GBrh839ghPAmA4Lk(%B#9_k)*yL`RL>$Lf8@soK4+MaV zs!~Pq$VGd|RB9;gR#S6@YOjXAs(dFv0SI=99S=(qKEEn(@sjK9=WW+>7OlZZ@G``g ztXkOOuylP9^F;Bw&#Ti`8J745@@b@y>4 zIvTurk$xOH^sTS#ugiHr^fFjGlBCfpBvg=ip0qBx{8m8%QP+2PZk0|i6=-gTd_MGU z?vB1WcqsZ^=BKJ!!05Q1LA-nbW`g39mHw751u}N~H^U;2DQwt{IEjnf>f)jPw*t-` z;$6OLRl1)LCM5VnQpPPap;|{+slTL!^nonF0#jzODs&>sU)$|v(g^fi-}!%}I-TO4 zG#s<3Ue>{xIiFPga{jG1t$&52dpH19HiF?+bUi`xC<|GGNU5kn6}X5t$`SSI+7WNC zj_rGb?n^QEvs+Ovww}CC_pymWT`Q{)Il&|;jx1m$hQHm@p<3u#ih35lQ z?hjY`bAO$ou3siSh-bVQbM9)VMlJ$8Z{31M>bWY*0V{r+;^7Z8ioav-G#C`a;tLcN zSZ*Q}<=zeU$HQw$_W%t+>?fzQ9v}JWu-0%)PgbIdCT6fw>jCmLL*!F?5++Crtx6jT zpduhT8T}nlUu2QYW(wFI$S6#f=}3zhOQPuD&L%U3>YA)+lfQyP6K>7;%y`XW@|n@x z$y1@%O5G+2WawyNnHQn3XLHF5)`@sB=-1uA9><hgP_ zzHR4_$m5j}JqxOejvQp;q}UZ30i$(t;EgKe;*AX}uM@07iyKx`m$y-J_<2G&fMr1A z{0Pr;oRrRx=)1{6-u0zEf1C0A?QEm;X7~27^QrQbB8{J>Dc4qT$#s7rs6O-0Bl{J+ zY+V2M9iG4y%x^v3KaT|;`;wTXJk{A1)Ud3m5a zLlE5lU<_vN+nb&Z}RB(;P@Fx@MbXno8u49?X*?ZiUyfm6d9(PtUAQ9Rg2VFPGh!* z7O9J*ze|zQ3(L$wN$t)-sC}S-__~YSzqzVjeIm9D8kE|EOZA2H`P2ZTaZ%^2 zDh0UTU*-XY8=iQ}ss(i~!TQ8+)jt3p6BvNbg}J0Yu;T_S)~-)zsIU}8aenGjliWkS zEVdZ?!NuB1`Yb+NlhLqa;YoP%y-dL8Gh4Pt28A@E!qi2__y@gu*H~#xmAMvGHiHEu zfCAnvc~!v-n-P_30zO)(>1}-PwbMcpYA>*L_pR!S2hY|n10ZWvKN~)51t-Rj_+`de8OzTk{@` z4zC!oLxedJ!``Cm^kwuJ(KN`W_G}K@@s{{>bHC^&n_fb27`Obk_cE0^Imawbj=EDM zF@6pamb}aIr&;Bo7`PuaN5f?%aLoJ-+U#h(Y&Mi|qM=<(jg+IV;EwQ-VE3@R%coM> zK|aq3hd8DGjEf{DbmXmC@4&dnS> z3ytpDMie9roZ+k{eMj#cd-d}sV)MYFK#Fa!is|%Fe#2AEeEvxL*pj z@H!+m=m_priZ3y(L5;P&B}Q%*z?xnzhp+tuFl`L|bMEc&e_zG5kC&c%Y|j;AW^Yw( z+uK$Jlm=vsI(Z%=zn$fzZ5JT6d?d)`TJh!Kd{mkfD{GU125|rMKjSXiIjM@@@4JN6 z}g!*R6Q)S zTWJ4k7jzFK8$ypl?pLD+q4AbLs5wOG}IjtYt*1g1Ie@8aGSg>X--kx>40=^6-LUcjg4THWr zpuQ!R7Tq*q02!V`HaD=AErhJ*b3>}OVIZqH$_3DTzlvq?sPr{#r>*yxEtv^(`(=Hs zf2_X8j&UgEWLQLfjjj_u4#891sL%>BH2yK|(8swG=D_Nh+}U3E>7MbY(qAi>v*LgZj0YYey+pMd-3+umP<(u}; zZNe#cL|w&$gk;&*U(smcZQlo7IUWM4b!f4~wLvOP<@rML=V(UMUWr4F^6T_F2Py)k^%_3IqSI?q?P3*6 zua<0%aw&**Xz2#!mypCSdm2yG5DBkN=f_>nWNrGFcW=*~4i8nPlT|JSJu`>qA0J+| zwJd89-hTZRpnn4)J=@3@2D?TzL)&xIjKS<|N(|#Du@J2CvEsqfd4u(mlcW(Q5Cm1W= zJ3t7o#KzrN##?czi%+dC$$uSpv=&&tUlCRd$SY=X0zQO8#x$4rL#}W7T@fLDf5mt) zg0`?hG?-V{{+7e(?BaXBn}Kb=pEO@7%iqQ@!UBoCjS>*_@R5(!$$y=q77u+r9^EnIs;p=H1pET57MI0ZWmf&u#@$%er;#=njHclRy+tH;3Ie>FHN z(*h7{F09n*j}`>ThxsaV3KSHSP}BQ2>%rzFV3{jgSRe`rj0Pe2pMoeDuW%?O{U4YA zv~vM=oN9u9srg^GV2T}i695AL-|Zdp9eJ*%Br^ZIaR|WZvh3Y>p|LG?wC}J#35Av^`|E-hDu%fetafJS_kp%o1A#`MQtDE=_yCYzK zlN$CPgZ%$|@K?D^l2A}U`pR4XTxE0Xn literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/visibility_road_map_planner/step3.png b/docs/modules/path_planning/visibility_road_map_planner/step3.png new file mode 100644 index 0000000000000000000000000000000000000000..73ffc586c11b2d03bfbc4ee4afd82e35e98366f2 GIT binary patch literal 791560 zcmeFXWmH^EvnY%t!DVol0fM_bgb8kg2iM^44#5T|NFX=^gaLxP2e%O1A-FpPm)v>Y z_uO;N`tH3yzW-;h)w_FlcXjWsuBtBSXmwRNEOat-1Ox;u1$mGL0>UdO0s^uR>Kk~? z`9~=g1O!YcTNxR31sNF{bvNgawhmSZ2=dWsx+r=n^YdM2^6%c^$vl9D<}!z{brI$Il=h_Wlr&fQyI(fl+GrVn@U4 z-8;4r9-bFX<23|`Tl*n&`{DNKFUtc`K{gHo57s7IXtoK0D>=g5$4)IBR0ObXQ?4eH z_GUjW`H<-+TwNB|1hO;jO*Vcf?R$DgH=0hQ5TdlflpO@AE{v1!z##1Hg083q6(Ft> z!UQRbE0;+hzSQ@hfrirEYz&o=3y2R&w2}7+UEjxr++Vu$_(#UKcH+!EjaVkpiARg? z+gtvQ&poYaBvp|_o1vt!B)?~5If@c*PZMO7jV{H#RjA$EOzVjBQD;-Xr9?;tYJf^$ z&tT2YY~)9j4BR#}pABx@talX5!-=u83w5>qpA8`!PSUac5i6FEcpBrksdDtT0ga;{ z8SKmp;um?a4J;%FQ%W~kELL^5i>vvcIN!gkjHE71ha^wae3Np}q*sj(%fPNF7vp4> z-Qq0(^+l6kd}hW=yI+>dW=aJ`l-}1s9X?n>2fEs&Bs4f1jp%m=Y|jhcf!*p`B^PWZ z)Y2rszitDjR%^=ogkLh(&^4fjZvYOLYD(TIC?-c*tLu||ff>hY7Tu$f1+OS(P#4!5 zNFOtBDo%ax*TmS^)w)Vx$dB<8sYPmKa()Iy zveX)gh%+RGjf+GaZ)N#D(@qvCPa*%+6WV9oA-Va8(vK1Os7sP@`m<`pNfnvw8Wlsx ziL@LD+%(idIxrmt*}~#aYX$G0s`kZT0U6E`T02j{O^JGv9~LI?%4?Wpfwdm8V$py; z7jr)Ddx(&Jb*#!#mr>e7Sv zb9)^>PH0L5sUlINy@uj=UGdjH`F9IBh`o}%iPTAW>ujZ~XX5g=@Y8rFRy_4$d|dKi zlFTr+NoA4fWQW{`)Q*>S$wR|B*~c-`oO>RLy}DD3b&{)M#zsuhxSW1f^Sv6K?`YN4 z_fVl1= zDfV(Ju}HE0^_w@MOJ#CZ5@D%h^QCl17oNy@5h=2}DHesPIMol7SD(~z5#N6DNy41! z#$2!htnBe{q5MQqk|Kp6lz018qd6dpb{n6I3%$yeViiIQdPCez=t8*?+E#)hhWxzF zPx1~oJbVK8jd`3NO(TSNGxUzOTmBVZEIsf*{%vxYJnm~A>U;E3sX1U)5~V!lC9)fV zaCEku$miuD4n~#FY&|G5qiQp5wqr4dKgc+RpzUD)Hg(oo0!=V zZ9ga};!D;80t7m7O+uY}Za3raY@b+O5Y7fA@oZjce&VGK`N5z}yN$bxJA$emz8X#! z&U?;wjcbe_4SGA7yN@w$F2bEIl-T^KIl?DoLH3wl0*IX?Pj8XT%M2k<+x(2KU{w@f z^jw5r#G!#>tFB})`fgN)RfAPV394PDUEH8{)U1;}hhITk%dz-{LMnj~W5|8De5h@R zeS379>Js;TqPZFxlwQ+~S&3;j_00(Bh|vhEqoX6MWAMrFlKDyh((DpS!?>;FM3B;K zi3nJD##ZaKCxa(WL%d(sLyTCNmmJ0~^a_Tv7<<%bD*bMwY9%rFc+>OLD;CQhGm+Gbm-`!K%IHt)N^>gn-=>}976OstvO*v4Ga|W-EPj*3^P}_Qk)@GS zaRKH$-pyZw%2WFQ-^&}_g+!WAcfT(eLcBiyF5VC;RL&xSZ8MlBjK;%zAHR`K zG`%D5S?njfGLaYkF&1M;UC1<1LWEpIdXzV4U#H4kbTl8G9x! zC4R@-hqv=_qkD6%kBkqhhFljOnEY>G1aGV^maAAE8bV3AMFOM4nHVUIXj!H<>TcR=(g`Z+B$_qfj8xbp+gm0$v7>5v7h$+=c(MX6cP3Y zj%yWtpQWYxQ|7G_whTA!ReGcB-`Ub5@?#4*++6(ThYzLV)9oc`Ds9}WL4Fs1u6UI{ zZjTEIXj;E@-rZ1s_fdbh^XF~5k1@M5O>9y93p4gHOj zMK$+NZgV?-V%~wYp%UD3?FvsoK@o3*)2#Npc5&a{d)s>y^m=q2j0D9$48FySTI<*jnYem?m^cX@ER`wsa|BUoW0|4#oRpQ#!4&BjIbFuS+kuRnQH z$vtP6Bk!?@zIMCK_fG7k{pSA5Rr=51>W~i8!FQHsb3Hfj=VHHb9Dbl^@HxX9Np5H8 zN^MQ6WPg4vudmYolF4q={%3L?Y%-rdIcjMo*oF4=ahWIJtIvl)xA7hF^k6pPR1=s> zIjqd5>r>ZePt)m|POxY@kH6I*OP;oYF21gk&YB*6?Z-3yjs^yM>WZxT%9>>D561Vm z4_}YQb$zuRm!%f-7bc7-4OZJHKW-hyp9w|_7*(N_3s*0CTwRViH=;IrIAX0XRgXCs z^f!7h_b)r2K$a%;>~#$qQkv^*_O^^l+kOS@-5RYrrK}RRNgjVbKKPy0eCv_pY_uvd z9aw%i>GwYH?8Wx6DuDVW&^=74Hv#!4G9gO0bbq&G(9qMyKtYDgNz^m8;FHbc)-GKf z-A=sx*2=)kTd=0LyPx~sWVGC}0g^$&)Aqx3uFmLOrbXnS4rK|2iC@4SXgE4lz}8@G zI6EbA$+~e(n15%cVLC<4J3Cs~{d8|APc6qPPu!Jb-|*-@9-@WD{`L>v@ z%jd6KQEy4%MeW(nF6)b~z6hfS)fxJMh%f)s;rM*>Jcn^&+izdGoq>w1X(z8WycIt` z(Z4sbCb2=3t#x-C8&3D)tNz-zDrfUAyLZc>PI;#mI6c&cei?txf6=`ZT6c{G2d~xr z;XZMl#gAq5R1?o_ypg>zzPC7}79TGfk9-(;nR#@-a*x`Rd?9?8FMeTu7U#6&j5MkA zv3jx_Uo#GF!lB1p2{t6y!YKspNlaY4gi}>hTaKfm&Z;AfR2;kV}kh zXV|Aq7ZH;sGY9L(s5rvJ6r$-5e{!p`2M!n>C@@%?_FU5JIuOhtfx!1e`krju7I~dU zOBBWj8_~VnRuA#>ODL1wUd*Mk<6vn=1H6ffGWm)qWrw&P=HTOFGkSg=WyH0(j8H$O zvnHMPF5Elv#8`2rpUoJv6ZiW0PaRnoMJNyQ>}7D=Uql3j&%8FK*eh@YB*scl;iHNQ z0t>v1itq}N4B<7rga}U(h~)oSmPKSjK>k-f5&}Y$EyAn+=%WhH|9O(&=^vPX=g7&C z2q^F`Jb3cSNBZBrUqSPc|92VL2i}Gtttq3R0M9io+^npe+-;ma+{9e);T32u@*mt0 z5QrH5Nr(y>^yl#L=WVt0JoHqQMJ${hIm|4b&8;|m99{ky2SLn71YUHs@-UHa;){~iZq z*8VS>_qd=xMt?go*v>r;6D@n=kxFXwDPh2ubG_O|6^J31#B|pcv;rOaE`E_&1*aRSQS71iBdKe{Pxt`tgWUF?=5> zY(Z*T@ElHM|2&B8@E6m+b9ni+%q9LY%LD>~6oLXsTFVFVxZ^&Za?taw&zi<#Ct?I8 zja0}h=@_Vdg;(3j4XO7dMU%nNS7CA9m+l$8djFTK8g@#hOP*S5)vCeOx$GODX6p8w zYBUfLPZV7g9Tr&SHyU7K`8(jE_OipTVY5S5FcdZv7YB*Eb8@)vAQ#l^52#`CB0-7_ zp*2PQe`IZOQX>$Uk?caP;44f-nIE`Z|F_Hql>}gg)%|~O{1=3&8ZH;mPR+D2>i;p( zzkdQ?<@o=Y;(tc@AMF00Wcok!@_%Qi|G~@uAH0OV0p;tlz5ODRrpOR!kpC|-yABBf zfUjv@vxfbjRELxW%EtrrJH*8;(Pt2?!Wr`h6Oj(;g=?q!N&&f36<6W*&qdnQVc^vf z24WhslD0zS+v$hoMb)%{^k-RL9XoRJ;=0G{SgDFj!NvJ1Oz&FDw571&U`B9ItFLx) z&6g3&3VFT~wfp(DxDT>jIS)J6<5`;TbXa9fopC25J_g$DoeKc%qN-;GhL1O~w9fi_ zuP6N^nJWgkyMl1fcZ!Q+Ms>FOdigu=<6}cc8o!WbJlRW^)@)`xkt-Rueb9HrI6SJW zUn{TL*cGHga$VFZ3mtC7o3|fPnIAs%4D0_$oB@J+xZiB zKCm;69(%{s0}uVMu{G&ePYG0m!F7pd5AO=3W(5muzBc6rGfR%N3CMg_?pk$A%eA*| ziTJU7^oGyn>@3TZ@q5P1VTzHa5V zw=VwnwE1kfqvD~}$>RJsw_rXS6&9y`lV;a4`K)-*h-Yk9xM5zzmNNA~Fh(lpXg^iU zmU;eerx`rUM@5L{VWg|lID6{&=ljR@syo|NGBoP0UA?=p(+b#5QSHr=3AQ9=J!<_JMw&JQYKm7xNC@G2Y7Mimqq_mJ^Q6tu7w;Wp$~;d|icSX^p`nd{DYv99;Yt&EaYbrLgdiT$hF+p?&hy&v zipjpeHrl}J7m|LdTgKM%t@@IM=@n8O+t%8PYJaRyT=P@*O z3HP9FfCwhj9Jzb?IlL!WKy1)wN)DOhoEUS(oeV6r*FjUd_O5VnVVDSjdKYqHQHBiq z%?|ox(v=pzDL#^k40s+B)4Z~x+t9O=3!_CS06RP>-GgtW?dgVxT2q&d73Q#X1_MnD zPqISCU!ylrGpm&VUYk628nmxd^_CL$hgp209E(B-mUok6a$T|Z|M5z-B_-+7L{{Zx zjP_9~L4@elkr4TGmP}(1yGM?yZ@H{iq<+HwJm&NZMcx{JV#(y&dS(5{W@@(giuRxH zo}Ya>Xg}gsA*li`QKSCw`rA8G#$|I&M9sl8h2t!WH;OWWz6ZVjZ;#ycGEYVt zVi%gJ*@YH`dVC8O4?C!jQiR?hpdM|Ft&-IzqO7*ucrFmRNV zOCz-AwUoJxX1a}KZgf#rQ5k;rzs>1-!*3!W@#3bqshB7wicTJIV#cB$~R9om?HtZ z!a$Ion7uuUE9iI$*M{m9w6iOsfudn^d1^KWjlkoYA{J~H^HElL+ zB2r$7Af4sMO04QsPeP8IRMUw1M`7I1Kf>}!Y(QR>W8blkAM`msD!w0i5jDr`N91t^ zE+~8H=o)B9c!$z`xz*B%#vw~e8E92uV#>QQ_JxmpddH~p39r5Q7?7Mq`5UeJA9>%a zE>0gT{NV0elF<|hlOJfsgy|@~?Dq+GCk)7j1m-To-MSk=@^rWIGm?T$Q zD8VqxE-(APcPecHuP{R+f6)`wH!wmzsArLUxlr4d{5$xU{;d5f!K1!O$zM(s z0u$gWt~j-dysxfF*>~}M`z7q_V|auF8&%^ZKkr(!(1qCCo`IS@AHUd8E9);s5c6=6 zC81RTh@h9r)kb@&TO0DZ`|8Ph>v_PM%p~zj|c|)mGB8BOoyF1EP=S#}~ zU)OJ3)8%hZ*-wAJF0!YX9=Ad|uf9dpcTz zs(zw4fU}E2S(Swx`>ca8l97ONA~Iq6JTg+t#>puP<<4@HCP(f3BIo<~oI6i}VgecwURn*Atp@5!OU-Y!{x1C9uy%-oF7(?yo;dE20XQ<} zrX5l-ZP5K>Xe@6$}~3Fm_hGtcGh<45P+RI2v-s`%T#2EesN#Y~F0O=LVW zLIs!=n||k2&e>4j%fbB4RI!rV%l(zx!yj8^^QTtqXxKU{1zQZZ*M)iM#&mx7o3emA z@dW1VE$BSI!=EILY*V)xSt`s7eRck_lflLNfcu{h2lAaE5QF>_1Yx?=Mts*rf;Vj7qrY1oY`xc$>pFAIsTFGJKc z@;a`Dy5<@UR$;z(2Q%Hdt%0w0_lPac&5<~Xg-OZCk~=#)Pps{PX9$rDzto&v4$4=a z=;-KB9Q09t{b+5yvAaT+Si9%PNs|%A*Z8HJ6+EX!^6RK|z#6IYnOTkj@JA#A`BU?Q zs*cH-5Wlv!8t}FK_IggNo`6P|ssDPx&TisZ%L>`9TM#5%)N(-TGQo;E^MJjVIGt+ zQY73wx2chqsD*FLP*H07eJT-ou~878++7W~u(xO&ny#!!dtSD4|MLCCMQl3xJW*qq z#iXpBNb|Z$`wd7dse5x1`g4421IR#0NjVittZ}Om6WE=Kyi<-m^Np%C`trj}$NP{9 z#t5`<&MeJoULG_#APYu()bCuU1L}Qu3|%{w1)b%Nv@s`%F~=$-0Ka4xQyp(zZFTi} zy}6LYAJc-#+1Z`#u^=^`OuI!2VjI>ZGcP_4q|};660~oKcD)sq--ovb6E_A{n<7CyBRfKeM?*??S3bZhd_Mp)(iZ(Nhv8kEw!%Zyn^TB zIP) z_}04TVQgMv69;W6N+ybBACCPcd(w{b-W(DKwOl{PpZU`l-Xr6u$&o~PZniZH?1@tC z`2@~y`BN{C`JZ(#2H!RX@6839JWQo;yXQS-`wQj^6f1>!h;1Ip?2gI=dQTPw$3d2g zOc(W_ksCM?FD>aMbkOso`z+^9=HN@lU?2{aL{ji$*NegZSnze06L=)@$OgDuegI9; zkizZjLM+}kvH$*KUg&4yUbm-P_Il;OhW(W4-ckI?&U+t4-3Jzu8F%~$7qm}WT6IO! z`LAtyf36p&hM^NP=1}HzTfUxkY$SH%1-C8sS+LtZ1EqYYocfM`W1g57!iF&iDRJuG8FVK@t^lOfTk{t4wDCxz=hve>ll@RbV zw1`BQ3y6%2jAca48esM6j%T>SNBH~gLRINK--S=l^&{2Ki(Xm)A={hJIFDijL84@+ zp)Q6u^LtLK1CydNb_{@;`sU*xtz8^tN3IIIxNVYEM|m}Z#$L@D+oGV21{9+%%|%mJ zvq^yb$^l-$2DYXjQ$R)euj_W5%M%pIyU?c{lb7P@{J)#TT}*k;$JVRANb$gNgSP`k z+=Xmspztil2?$JOWQw0eVCHVWkdos|9v;}ah6!B^Y+u;5#i%LvYZ0=Bp0 zF4I&h8vK=UL8OTO~q-Vk7a_6*Z^ zHCi=FfGl(k@tKV+-W!z=Zz%2S-?5SoGev4%XS#8c(`VwoDc3l!RYY|sQVd|jjxl{c_;izbhMm<6SMYOI-B@|kcZq*V&qS} zMV#999x1y%4dQ_BO*+&9FqZ&n>M!SiA7p&*&I{UK9*!;#)Pk3GdfUqys5?r6%wJUS zY(O)rs2YqM*BxTI1wG^9yUu~4G*EfH_KP<&R}z1H<;>5q-e&aT;rZY59oiOpLPvJ4 zxAAjDaDuQ?<$Fu%{hn)5T)ev5@9G1Nhru9oyO>ivmj}Ce9lP3KP z$;{3UM+QWj2*}G`7N<7S>6@y(+v!T*sk1(zLP`}zle3e)Ag*P2(vStlU?dlqEyNz2 zm2^3gAJ%Q#RWDpWM=Q*);UrLba27wXmYK*<@;-5iI%B?qwvhA} zQ{4AX7s@44kcy*!#pzKcz)7hID=7GTSNrjO{kYr)3CihO+gbKXgOHiceCBX z!L(bO;e+Sr)zfh{VFjBy0f5QH$WXtkyejhMvKdKcr$5Im2gh@#bosS(Uw^Rc(?h8? z<|kc+N?LJ}KXoOgq}ufAa{K04rc#cDhSULGhoxOrllPd&6Pq^sxT3KvS6>VIk=&Tm zc%NKdkjXis#NvyRp&(NFD@a{tyKN^bc|4g#yNd*e2nB3cKQ{2GO7M1$bh_F(GHAc@ zkkAoURZ|;%e!Qh1_1zu<3%jgK{h2DT{pqay3hw+l;E%f!pTBDwbQ)c#;I@w3Snm#7 zNM7CIqqP+r`iv*g{&>#c*K*@XS#qu4u(G&!_PZlCF_o>gCU@CYL3RSX+d5!j;A=Oi z8Stl7M9_zN!Ye=U<@c(8(qHlKSG5T~Zvn&9SuKyW5^G03fQ2BAp{A~9$NNIb2fC8) z`5=O(TVY@fPa&N#?Z*d){y(LS%utA z6yMRr$$@?233n?e&j{EDs1WG^u-JISd1pZci5}W4w8L4H24Nb>veXJ-oAfGtnNu=jzQsd?E0TjQ zBZ($G#X2jm>I>d7GFl>Ry#N@X@_c?4qFZMfKYN8s95|xIIh#uWp#-BnN+P-Ti|tIP zSlAtd)4!gyGI%*UG5F((li;ATu-S7zh)t zI-ic(atNQfY6X)h87^X+^^#m*-X1+rXwAKn5ztRf-8^u1c9xz{neYP>Wl)9^pEdp~ z7V2mM;fI>V8q8a+!s_u9NUQg4XC2@@mVD>d_06p!3Tm+mJ~;2bzJ5z7D?rWzC9i-a zqO(!vw_2vAVe8um3($-}L@Cx=J2tc4S%;KpCjDQ!K$g2Se#I)Ztf8u?R)#b)qYPEx z%a44w34gzn`+C6T`U~>+WlbMiQkSk&X28xH5^RndF94R9v4qzW0;<#(aNZy=!lWMt z1H7JHHt+m{*IL=ZFXdSQ*+F$NQ4hB#eqhNDt*Du3VkJ&fEW?QV*8hj0#*aM4rl)oa1GY zXg!*;4|E~y+YtXdVGSF9ybua{dMm-GlS-F^2Y$-F-RNZiDwdzQU~zgG-aO!5d1E1( z1O>=@Peb~1Tp6yg!bnndj`qfoZ zAO!*yNTq}RDR0h1!6>%aNg%B5=Dn=34KK6t4HVwYj(J00c-P;adrDREdU2W9=G_A* zm7EnfuX7sGgOhy32bBkb=@g@x`rqeKJ}eOxUdV0n7dV4vuu;?g*#U4aCJ8bOn&f{( z%C-Xu0}s#54k9MqmJ(b+1mz@Wyz$_ZXI;f$imP7@dDHXvxsoC^<5x;8pJlc109Kcr z4Rkou8m2jUwqF}?qF(%f=w#r))dY17;0QHiwYiJQSmDPfooFWD&XQ?BZlybFlZF@_ zwDFUE1D`|l62w)%3Zyk-TQ*y)a9UG&ba*suW5i#+YCtSp5AdWGfO0{Ef#_YSu4mO2 z?ZVZQ{Yw#}vM3$lV(c(gK*&!P0C+{R5=1}@x58&jF`K|_Mj3NZz)qs*15eqDK#Zxv zEkfvBz(!>+cXpS@Wkk58Ry9A40Mu><60_Ils?D{Y#0RD)cy-@tjHtCzi+cTZ9J|_3Cw;Vi zdh{}0L%qASQ1JY@yD-ktKnu`bo2{E-pv6sy_KW4&6RNuEpo8WEG#mNH8KD`!sV(>m zJ1+Bf>rxI$dU=@@jUsJZ2*)SZ@Bk4vy#iXifcH{&0qinHNcEx-JV3h=SF7Gx**Hx+ zuwnI--o0+ugSPd;Od$W6dtNN?8+Z4l>Wnd^$fUs0Rq|m&<*(ehx&A6IXCq5j+5JLyw3nc5kzC2?N5J$Al~jK*=`j1t`Eyi&Z6XC zdZ-PfJWg8G1Lk~<%vQ!42`UUzJIECn(^$~VUq##q6`GeL1IL5KS&I{;972kI1_DP& zS-X(Q!3DAe^Y;%se1gq(4<*7v5@Xi7-BVrKw|gvdL|PZ&CP1jZ>GyWVYCu{w|2RXh z*jP>2NtA%40_gdI`mgJ-o^Nr5uk!bC-8{3$b$Ap#_TAhtbMA_Y@luGZyOmWx0PGNF z^7mn026%|I009CB>jje4`5;Z?QL5iA+F2t8xA=QK&5guK8RlFIAB~}|0VDSuZ%dIH z&0Nofq9LcbPPe|}Hl`Pw={cu$h$Y`ovHSqnfgT^$^n8JU_g;8^@s~}*;5HI5`Bsk( zgo(Ni_IwxW_2L0IA9ySaB)ot*saaen#D$+E**YvQC;-d$?WJ6wT=dm8NH#}4pkvJ8 z8gCS$MVWcnhTq*PaoO8&)8}bOplQbtSr*O*{E-l?7q4EMQc+eOT3E=KhKRUshSNbw zi*2O*P02wV756?ylTH$N2gRRR0LUFcy9mD6CPqBVJ)d(Y~sf` z3lgh;p5P?7Odfp=n$hjNw88}^_6PEhLztq{{tm*I8?Tam)blQ|3-RGdV(D|f2qQnV z^QNIn_z}su9e@i~Rw~IuUG3Ylk14adq+^V@zx93ysLIoIzxO0GW|wAnO?sK^m2=zs zMcJOeO$nIA0LJ9~IXOJksN}w9zL4e={t__9Xjgfz-0oZs`v1-Tv9A~Ja&zDE0T*27&ciFpTIV9uD>DHRX)ma`#2Q3M zQh$I+QBC-`5e@dfuVf`|$R}ZikQ1Z@Kc}{Tdz)HC8bRZos&Vcn17wjWDC!exG{H$g z^x#tuKAK~{rP~@#VKl3La#_6VEQq^h4Z+fPrhLSYhJ~T5>L+p*$%6RvLwad>lU;>6 zFIwZ^dcE5=Z-c1cfMJd;j94ghg)O0M;9%j z^-AJAh?_!BgTy?VZ@^E8B9qC>rSA5{7FjgRhcv@Bg<2Nm2>v1BQd$*@bIosH2hs*Y zSKi^pJ2gR=zR(&|ebMcmnXf%%?fQaNs84}Sv=Jx=lGc_?G#L>Vnsm+I1Zm$m;iC9Z zV+*;WlAY*3wgJHLZ(B~%ba#G9z>mh8>hH@lFFt2^bw5OO=nSJ_EnkJd=47P_3k7Ab zSL1;pd7Qyx2VJF$-h zH5RbgzURhHfMs{@bUuu7ha`Yz#20WRDa{cBfnmaZPG(}{A?=Y3Y_We zK&}AgyzkJc#0mbL@L%<=wrrbY5;Z zUX(c=Gp(2{90JJI`G!nM-`mGG%?M($6q=g5(k;BJmG!Qo>k zU#(Na)H}EaZF3P7Nd$99q@wc7)9h?soA2_X)_mc1qZoeJBr>86joI+qKxp3hyHNQ+9<09tW+@FvjX;@RCD@%B-S7Adz<_hAe%m?g1U|CI;h@hDXTs~;zn^mF; zn|SJ7e5^X@#v5H%TU`3hlOMzQ_}e$puqp=!I>j1|E@`giXmfbz<~>0}cUje9A2Ina z*%>#}?_#$0RJu$D9Vc}hoXGbq{>nBn>zar3fR4+qKrf32EiQpuNh|drs z6kT2L8lS^4+qesm{)NmC4{Ng26oB4r z+?j!9h#qqU^sZBC%`CLyVP^q*qG$rpYWcp9^kGX1(*C>IOC`U7kG*%8REN$2fzy5S z@68*~wf{w^79cHt+^nPA8?{>&Ymk;ZT9cw9oFp@t0R5Z?Nf7-HhM|GDc@QMukdqG- z7T!m61llonO^q=jlD{AKeyR-ygg=62j#rf7N9iI&BpC+RKj-cIr~LgoD)(ui8uZYf z6F&-XEqptp6)u{EvcYt74b_><&6^ILy`kh#iNTJHj|4|@j!YHS8R=)XA7*dQPNLjL zAio%)s=1gBpqe~Sm=c&R0xM!%p=eJ*A@nv9bMUY z<1TZI%8q@oAh4{oPrreO#hn=KSv(qUUKlFSp-Xa+0JI6GTRRRC?_XMUP4ghoK&DnZ zGO*PZ`&Hi)*iN$0w|Mk^oiJ_lCc6qx8L4@#SQ zZN&pDd*wexY9*_y3d%{6iNY4`S!66U^dl_kGL|1%=s6^VlgYbWipN1y*l!4|m1waM zL+&d)UhGIh&VhV#G?_idP2pq@(n6Hf-&u(ofeW4A1n^gaT7TP;>8x6eo--)bi{mcS%+>Zd4OxqZ ztSmt_5V!a|+A=M4F0J@C@WgVKz1INc0%Spa5i@SHkKPcddhYdKQ zq`Gdd?2jXE_+~>gqdK_kK>hJ)&KY@h&>?jM!E{0XjHlrUA9&oL232Nzq84L-@=MwU zH2gHq;Cvs3LudnXeKe8^SN|Jb<4cJPrY{(Y{}Q_hK@v&BX#}*o0T09FKxvJ8Er!|3 zu5Tt-8>>bV>qI?2Az1BU4^2a0B7hMN;;?^KpDtb5d)!bZ=k6`k@1#Q)bI_y&0^~mP zIFkSx`hVqP={&LuE_tv4E+Wy5fMvaHqA$^|HdYvY^wwnTBT7r;8)Lcq0p!cB9@j>n0H3ZS! zUw&jR^u@ni!v^dOV6kZ!iC&f`(g;>09i#s0X+s3`r$hN|RxWkkVo);Oy5i$0c-W(U zV`tjUUsCPXz49n~cQXkHr#1RKFnYhGMKWp&y5}yWpHv8!A*c;jU3j}606g3th7*oa z?|TyFRF?2(WNpn^J~E66D<*^G%z3R%mG78VP9QBHp9&=`u)_g!Q0S!|0{ix6xjY*H zrXtA_o_$juG~;6N)j=6##*8MD-U?Y{>e9Q(>in+tOT~I-AMGC|p!zoxz%dYENW1i9 zetDj8RorM}`F%vx-MtpXy!$#L&E>S#CR!n+Ww39l1Gr2vyRuDC#u31?na<6+sIV7V`OV0Ka)156E|_&-@962V@w{a z?+FzfIgesiCKnNu!bey0xNwJL$%*`?_w8%RKH<*UASMG);VHIiCk7oz-4}*^l`(){ z7DoN7{|{>5O#QlIH@eUwG~pSpHYPf-&W6KDq6|-DjGXG)^F^;Oj0%ne?0BO`xYvlN z;2%UVe1gZ(*pb?oho3xsi>rD zMiuL;`Yv*SwyybNTaSx!NGv}1u4yuAEQ zgASD~fTF5_ozC%urlzOgT?%x;>MH>t3}E1_7VH;`hiKHy9J(Kul!HLR=1JT6fAM;M zI_6dpZnnmixWiq*p3J#M%mi>!n5mR9nExspxJup2O$nEaZRWgii|)=YOj}Yvpzm@y z15#Vz%RO|nJLNA4yZfQ&`V_&i39Gq83aU9hqYgjf1(pF}@qse`(rnoW+0%0^kPPtv zJ8@|i_Edw2ygHp$;YXshmT-NHhz#srHv{?9t9un0DFvbwrcZ!e+N%rbCKbukoqShT zRThbFU0nQ-M9xe~B}OlUOgA;Vj6NTElH-#^2hEU{cDsAPR)F32zy6w$k+j%CimT4t zT#t!;GqSGEDbHN3F*FJQGvk4qv2lU~6T^u=d=80&inBP|Q#I{es7p5M-!@H&SR3`d z#av%dgCFJi=uL`g9>3r;fG)4%70Xkl42m~xr%XLPJ++xf-t(t=^bK%`e2aVSNe8{r z%7$A404K-lLtV0vG5}b5DFhNj&RUhaMifiVuv`&Ph{89b(0p2{zoO_mV$2~1j4`;% z$J*h8KKOHk;f$aiKz{!1#+wdGrtTvOwoE{CfqQ>nWng8XSdO1~tbCExyUkd4k$72`G_llN@b*6YE#Bh0^)|?=gB6Eb+{INbM~sd!At(8Bm<*4b zsXWh0WgZfEdp94-#?Cp6iTYhGk!tw*XnyDA*?($skt4^&I!}~#FISTJ#PKAVWdc>W zzHo}&hnd9|M5ypiI63;YTZFV&IBhVVnb@bC!0r|d`MbKjc^rzz1Guxu&X~4GzJPw) zi;oRSWDjmPR0CH$x|y#mfp*}?C}|KDwlH248^@R=*rv&cs;?9-<+h5L_m8JY09e8)K8Wi2nvxc3gUrME zuXy48sLAKSMC#F_sxFSam!BoY9UYX*2L<;Ol0E!km6V%JS=aEJr0j}1FTt%A}we)dEviPU9_rk#;AR=0~O{{_3-zUL5bK0bOzwVYJV64jyZN$F<94 zHyW6{&%|E2ddfJhHe)%$P*Ahdc&*ij>s47*-_mqK-jst*+6=w z2O!gEC#Iw?-X{_M4wI~Ue=(wVR*h!$Y4~KcjJj2|8!w$?)Glr zobE?Y4>T^0;)jnUeGW}QYqpBi(}F1(nBko4j_vRW&Vr=`|EN4GOQwQ~aA_!uDqj4! zvD9`r4Y#C-k0DpMoJ4Rpj?hh8Q`0;jwCvN;f?&hiRdFhY=F8^A{$z7p@1&_G#&La8 z90dtQ(wvSBUw#D_mdX0fm6D-_(kiR?;42|IsF-r*MZLo@BU+jaJFam!w5KQ|bFTci)?gVX%~27%)#g)IEzu z0;omkpmR;JAF(Hc%s^VaN-gb9OY^I(SVv+EP$FV+AUeI)xhpzmG5q>9@GurXhVTf^Jf8knx(7-ymst zk@;)(*VK&y30!d0IfgGvqX!M%E^7MgUsu95pzdM=j0p%!h=)F0Y0}v~T@}52K_T85 z7$d*jzM!wq-YrHkF*rFn`AjD#YwB(XA|g)D=jO*^FB`08zgGW31h+|wsFyT)-ClY~ z_a0hhi@N+@*+T@xcroCA(soWH1*)j7cbS14B9Rg(e#noLXq{g6$iwdqJywON80tFiFfmGvNvYzdz z%(%(H4T9KoP`kl0wr_BI)id8eauMg|%4RC`PTfX5i-_3dO9+b-}kSzY1xY8;!vxZp4v=n!asPKS&h0fJqN37XUA$Gc|>}- zR@d0)B3sP+rJh3E3&9Cg+b=Pp7C7`}`HY7Ksv`{=>y6SOkgq3La@6-@Fxu~yz;84o zP>yE$4#wRa>GN>~Dh`So3BpX|l9%eBxEOGPyurL|^--Tev2n-xt02G9BT$i>YYe}% z(@&i2zZ!*9%l>3%Wkj%uUPJkcW{XF76D}1`5SD~&3p+bifH7C}-bxuYmrIt;AT39s zir8W-oxtGG0j`cp6rkd0kK*0l5lcfJlF;HmCe9Y80Pdgz$nlls)yn(}Txq@=pz!)&do`T9v-)tUEGjo z6qFF!ME_ix3QFfN6?H~j-kp$GCnDOj^xH*i{4Ji!O1<(qYyNa(i!o8!Lu^3zN`Jjp zgUOuRU}yuwZ^CmV`IzFfuH+5W(C2_+sLZLE!&c$;hi90}rkChaAT$uhFN9|;{Z(_} zOS)864DX_N|$tlNS7c(=g=L}DGXAQg1|^O(nv^4cY}0FOV`jjwAB9m-@SMD*?kK< zyqNPn^@%eBnHC)#ef(#1lBql?FE#oRcsN(K;u?? zHa^9aJA@q-p$L!cclhgYB9r&t7$}s?tiJ%xD{>sV_Sype^0#9+#lkAE3}L&@8et{* zFw%uzb;;sO(__mjNBjV3zxf#jiu;8($WpEF3dBErjE4IuoBb#hkm*qN zAj$X(-bpD`whZn@C$13g1$YE|wT|AiuG%1B3+*3F)>}jH7Ueqj>?@!pj#@h~{EY}!3Zu08>Zfg+%=Ur!Xq~q1=1Vi9K*$)k4WcHu;<^)p$^TwKLFnzs?P@ zFg!jKm)CDLeNWn#L05lfzL=fNkFQ~m3lBWOTXF$wg)-la! zsn}+Pj;=fSz!s#0Vv_(ooZ0B)K>; z#4M#2}uPqBNT6-N83bAUhc{({wE}euFFyojNX`)tXuB5nlCmIHC&T6*KDu2#&GPd z4|ptFm}^|ZM|CXA8&5Xj4Uc1Vx#zt1PUKbsY^Xt66q`+5{uoM&6>=B-Wdl!~AG1KB zwwQ9x8l2c8x`+RtY>l6=TdA}?^n75p>KjUzpN<1|{I8qL=%a&!3Qb2K$h6nLecv{U z;^)z;Pios+ST^A4!|ugf*I*4glEg|L5~#TS%J&fQt#3y_1tWx2Lj&Uxn*p;Ly?x(m%`-*q)=wmq3v7Xjoc$dfcBT{rh(-++i`HhUWySd*;@ZV6CkC7@uEIyfhUD zJF=G780qQ>(9Kz@rpvXGB|jmiO`;ep=qC~1XnBmpR1rfVQw%95PO`mjVln3)rG{Ds zADb94x2+5}60XRh2=1t6r>-XLNd8LPq>%6D&;8fJ2bi~eMiRZ=*FOrEMtn-PAH@_? ze8nGQZk`%^ffb;n&$LuV_+s3%^j6CoTxUp$u?w`iaJAaLNkndj2!_`1>hTOS%I}-; zW7PNa?P9AXxYvZc1d0Rkssj2wY}ba8A=VO3-i2e!Td4KjnE=(0Y&pf1DmC@Lw!2 z-?n}2VuX`O^N`62b*z*&sM0)GbBgMHa_{9{2B7E`O zOKW&sX1|J0Cqr5JjEXXkNfa8v)pbkL<+&z7pL!dWN0*u|HAtX2wlRZ+Ban7g+l&}9LD#89t~6s;uja+T-ul{ zGzYv#l@;HThJ9d3M9JNRU{oqUJk$tS7bd5V$ zEAHw#HOW>Uk}zo^^u3^HmqeqqI<1*;c<;6F`~ygM;ux z^&V1R&hkemk%mEw4Yvb^`O$X78FzDm|AfA1ZQd;-xC|OvNYG~}3l=T|z}9(=bVTUb zt)e0+XvX)w4p~dpL}}L05{v~ukx4@P_Q0s{Kpen=b$9>aYNi0L#%$Ho*9!1c-Z!_m zI|{cS1e8Tn{-&#}YMl+6@UcyEu;LMKSz&C5`JSpfFY2BTnc25+Y&kiYynNp9iQQbxV@TBM7J@%0x+J5I>70yyw)Xs5NlLZd1aF;{ z{#hLMM9@}p>z^jO)a>B$qFZkQNDuVp6tZ`S1WF>&4~asg7NZL@meNgSSEQKFMkOV=1Oriw92{$jgYT!Uk3E_|0hC9=gd^}p zcUHufeL$kkM1qB7|o77T3%^Cu+{gt$af>j0_O^r+QF2ZRRLS%b)iJ}T*6WnEl8f>pCk5(93BD+a@| z10XAH^V}!?6WpH1%Slx&o>tDR?B@=d)dpWKp_Jvt{Cm#&iS@}ZS@RblMIQ5+2Fbkz zjKXjD*ho|};&n~-6Jq>$*~i6WD)!t9^C=duq4Fte73MzFwH52~JOwz@Fh!*}fqY4D z!C;Os>cJ9Z#KCv8VZ`JmNIh(d9Ix+3Y=)`yeKpG&n2k5;MMuSYJB`}rYUz5$gXx@- z$dxW#?lg5q-`t`5^RHnCfSaEJISCMyTyho~D3Y8+e9GKH@39pcdoPA(U9cEnef+eFwbssx*B%5xl0SeKyr+-H8R!)Gb33)xNHo5cY*!RpG05xJ-yP%vA*Kh% z%3UCf_Vs=e`iVyMC-f0CIvn+(Bea{U$#$m%+@0TDI~ ze6E4DT@_((dld;pcMbIYMgINGk-+WX_#%7~{@VLw!70_mF2xsHAaBxX^0VpoqQ>w| zmj#N|w=f+oeE;&3xR9BQE%P__jd`ZgS5X5s{ga4pHyr3y#=x6GjIEn9>b+eqc^`b` zLeWXA3rZeW1}X>QBKh^mA2X=A(Qi)+i$T3Uzd`x5=;^|?@%C=4-AfN(Hm;|xN58j5 z;|Y_yZRCDeen&lGg@$Tis&}Rsc43cW(wlcNr{`xqN3D;boWrHhSACBbiie;~K4Sr|T8D+UBfa&ew^al-gbIwp*MY)1h36$}45G+C50tL_YdN=U4% z;XwYf^Cw%&7v#T<2^c4RXZ{KlGni?$%c;>pCAY~mdX zLdY3kny2zCxugFBUCsmGY5AM<+c{AgKGtrE0}6Th#ZYoyuLaBQW|J+Uw@)r!y(&j< zyR}sHLmcJlo7uZGqLbn&K61GV)F7q-3e)akk}7_DL&VyTb!%&q{Dx9ByysMjy|*5% zMZ{YVN=k@e8j0ivZq=a?sOk?%Vk=8>%idbw-9z)+-BO#aB{!=1cMS{}_+Ou2c=X77 z7v8U7$lP|tgwy8rZMCF02TvS=?8rh666vXK2(vhb^8U0`xAJ{1_n^(KZewAnt<*4{ zOtlM6)-HYCpgb%;=OpY$$4&FJW#))D)t94^(euIqW&Qhy3A4I3HGr(l8fF{2t z-LCZ&dNoqTb2brC#J*JaAkUC{!}Fx>dSgzJ*?(?!U%plI+pYVK67?Si`|B%_Dp52b zfP!1RBPUiKZiuidsoEuWqQC@OyiM7SEeAmsk!r@`OB@q?L&-qeHYkhm4O>wbik{ce zCs+V$;`(zw>^uYnF?5^<*5erRpV>6zr$dNvz)w2-A78=3TssqB#gPQ>RoEVAUqe{7w-_i~n#rtN&({mWoE z*q(UZo|e+Zz2Qr?cM?{G00H9$0ZMsQ>~A6ECX2Ead3u08CI38Q+v&dSLW(aRp0}4d z{%rq37MN&g2x6p(nPM`!TaB`JPDgKvXkK<5-8NaJW*aB>$Jkii4@TxolGf#iS#2oD z{xmiH!day6y)&6;FL~cf9*+jWHtK~Jyoa85 z;|2=>x|!OKBuoX|0h)NYWdlkyBCojHedV*nQ{vog-pngbhL?XT=P?@F{T%v2aJ^}P zb*g{AX5aTLlsK7MOtWwx={R|7C+u~3%j`1LP387R^}=5Oz03oa>2W10V6TVq1%8LrC5<(#@IBN;z+}+&>w--({(3 z@0=SG{5s$X_x66LBQQnB9^7Ti65u{<`ujd|f^_-47Y2nD5Lg@F4dC&li)-Qe8)VEW zgPpFti38?96aGf!rnZ#CeQ#|#qKF{(t)HIO0-wh`2c{;o z?DY`0EMD(yUH!^X=1>`2K)m3~%Xyt73}gG4;~He%UEel#FTFR$(T%QMNGUXd*8*Yn zzJ=Fj_*tt1Q-9*vN|~kI`yr5u?Q~$T-MimA_$D{wK7SD^mO@9YX^o>ST#@T%4$qRP zA~lb4W~ZYm&oGX(+F2-FzXOB39K#Gx>h64nUl*(>6toD*_%4 z%Ea3wryxvnb{Z6{88qIKVO)RfGNU*L$A7Vw=)8S41}j=l0&oSa8~gt|%7n#V(3PW# z7)c5J&PN65>Gts-*RJP)DAk3?Ij(PI5#iv_IUjw{Fs@J53@*f8U(w?HPj~@{jrGL= zTlLkZ{lmM>8;Q;SuPpKE)8YFxyBHvTI;SHi=LnpsrW*xIH{2uk> z*Iv44_x<^Vr#y&kkhz_ooar_CIsNU?Gs7b`A_zOICa95bMTHJ~@eDd45Y%<*C=g-9 zJBByC^bx|<@g&b>{E4B#xo$91v<-TBSnv$;$duk?k$&d%LboC2MUH@zezT%<;ie zZknXIQ>(V$(nphm@o}>rkrrUI%9m9iDhT`^u%x14Q0o}d&vVDwxv(29j@t!B%##Ce z##O7Bk?wx2a2-Q0F(P7U7#^TC22z@F8iwr%PL-X;LpHYgv-=P5&BU_C2+ymw(h-|; z&#?zXwi)s$LGI_oe7VFy72CMD@9&SJCFCvt*<14Pswb{;jyhEoziD12!WO!OOYvyS zi!lMnw=+Kq@i}BeJ$elUB_W`cjo&jIB55{Krl1sa_))u`6j3? zIYXNoNMV2*!tuH!le_zQHJ7hpPq}L2d!=vsuNpI4q|qx|jRV3>XTx(3ou7bmONe6% zEs@BCX-QkXJz(riL+k99Fc_&yf)&d9&&=R|a4x%1dqdBN7$ zXzNm_&rYTf!maTRf09>X<`vO-DK8cwTarQCW)CNH!?v*X(>ly|tAHN5t2fm2^O#S5 zKN7eBv#p7)7B;-eXzSWUn^Li%G@5Js4$&`urra7{RRlfeufyXhU$+7Ds0j z>>V4&0edLtZ5Yj_l4=NjkrdSz=>lU!siVcJ=P;z*zs2cw((lsHDI!8MO>fmE?+&h`GLf4Rq^wD)XN zS3Jf>qeOMavTkXMRC0$10yv2y9l_;qbbeY%k$wBQK&d%=&N((ECE4%aARDHvLchN^ zVBU~bg0Oo0q?$dJs`A;o2n1;f@%Mw5B4YaNqt{)0-huaw3jF<~YDx=U)3G6&I7NP9 zw@)NTGTkhyXt-|_s{nj^kLTI_v#n({tecaG9_Y{Xt6m@Xpce}rH&;ab8WkHz3HuS& z5e-NM6M(A$yK{sIo7R#mi;W8b5B?O~pZm`I`UL6NqP5OVN)MY@0AO(k-fB!2p1vzD zS!{uYI>d^v!Fn=491o%FHh<{p-A<(V(lr(zfs8LFMZ8A5OjaR9(Y5|&IYeOabGpGd zBJb;+Qs`MG|Lq^{;~}-xHhQ8dv{XZ zl+e>OjvYRdO6w`^8m&u5I8@ihr%(t+KsS>IR-cwJ5Z9}JCHo|u%i(gB2hQ?bl%%ov zZ&w+gHs;0aC9;BcT9&)ekfWaBw@^C$$T{O zN_rbv_)~)~g@jtqAu9>tx_+h{w6CS2ai9Vu?!i|;W5?!qE0m_BM=X}j8T6EQYCvOq zwvU2Lbq6f1IIf3^ueAF1&tHiZj_d*2keBlZT$)J%d^&E=!+_fEDFaBGQQ8+sFLkC_ z_>tQCAf_K)|LoflCxr0n96Nx2%L2nSU}~Fr>ss&whvl-z#(w3m*m(m?(zh!uF)GY& z(kUsO5Q27}yR<4u>&E~{eU_=A4d}fnt6RyiHBH=$J7@k|TQMMgxzv^E_lv__#;Jc+ z+hi9m2~NV;CflExsFv21inIHoirKyazX*fhOpF{5V!=%wKw;lY$3hMUd2~)o)p*ci zzt~GD{~bxOlYhtg>TMsA-Lt47ttypdk~fuT+JNdp_;&r8z+nYy%{W@zz#D|U( zwlejHjy|{+d4`F*ZHaA%yLNCrj!XDsj?zNa%L=NioQxyJNE%-q2$c4_&g!tH75wumhl-&?DOAoQ=d*%Vf;|yPQash3($ev2m1${#*wFK*IM*Lf;x|V6oBvcM81dv7yKp4_?+eZ z56k-f4ntBQN0hN+WFQwId+!C0ZmTx>r*bIZ9g!gmywvySFE6a<_k;8tQQ>1GvltiH z7~Ew2JBCnfG#x|o4t{(W39P}C#oKK}*fWdKJP+Ha&lAP!4Oe{TqSf{_rEqZu? zS8RoU{k3RfM2Ign`4z8o%~UYM3kBv(q|=vTwqjWI%V>WkV<|Q;_9WlE$^gW%v2k|3 zMaPpeq(or?({Fu!G#>vtkz(V=pmI(G?GFqN_88N8hQhle{1E$cHPGXbvaMNc7a2P{ zKuE$#PmPRK7wP0ZJW*>9pH#=6ntqh5-}rQq{b8u%iCYlfmmr}(X0d3j)R1wgFx)?G z0}r?}71^45lqof8s$xs2s2DVTYGAw_4*2r9IEjFa0K!VDP2)5?^ak}N+=it7Ui@34 z1JV7Yi3=sw*zmB;IU+9QZp(s3m|;AdD)#gD$cu}@@8dF5oH@ux+yYh^&A~?!sB#?( z>#OjlW<@(AU$GuFUDo5N=R2g5053C@*uC=B5I*JsDD|dShRqtXi_TmA`cjW;Zv&j* zB4JU?z4qhp7D*xRBfz9fZtAyIrCY#5SAsHmKyJyAwW4eKp@l@NH6O9o#t>DM_Larh zspmSI$eqxy2)H6>mZx3u{sdme3p>Tf0JPX*vE;jnhD#f)gsvrXal?C9UZ-8d1wt9!Al_oF&ZZ`;wG%J^?j0&3V+?-#Y3&Moz`IJlaw zFqp6nj}73;reT!({V5ld6Q|v8jw88;l8R;aKIq4x`jsL^s;GsZ4ncC@OyQIy&GG#2 zb&Qk0(JW6{MK^NfDl-ZC7N`=EX?dbBS38teqUPF1?(dE%1s{00OPht^LO{T^mSL7^ z*tt+$jc!fi!JyxYlyb{EoDAX2~a8?dsx&& zk_!Kx#g{JmWxFQ9a_{%5ol7~t79ro+n^68jZ_`PY>y^s}x_cBgI*6ZdtKJTv^Iz#K zDmaR5PaNQPd^!p%AOFVi!Xj4edtQ|*b%9n+bk$EIx5f2Y#8N#*-uj*i!GJOBp!)Czv;M;pARf$Fk_Bm>m z!3*Afv<;=|a%gRZsp|9V0k^_QC?3O9Ou!@fvEPS?w_S+ap-E=%U^kfvBYFs@FltsJRt$`?Z zez0amk5>gc1MJm4e1YL0Ot>eyPg)WVh-x+mol6;ijNHQi!=@O@R98(xj>U4T(xe5J z06t|lsW+)i_z95b%QV^3n?s+(>^m`cgpZ_qoxn3-a8qQeuv$>?_}MuyLN^3Tayq=j z_mPl-Qx4Mp3-toZqkAkEK9~#URbff#JNN60ffe1o0-^bQxVHq5Q!H8mm)N0YZDhZ8 zz>-Z4StQ_fiNbC8Iu}V4qx-331>VP-m2kyEv#ao~z)X zSabv{XG9I_e6Rta86bu)%(S+8vZChNs5pyd#EG8QK+EVSSVS-%6JBl>B%5#;-#l^l7_7c zNm*lxljN^}+fK>>hfNz%tjUQuX`g?U{ou%sSsGNfVYPQe1JAtM8>b$?4{$YfR{0#r zensaWQ(NmkIM}Z0eRNBFdm2#=xIQzMLR(xvNO6f9bf#QZPfq=2XAWK1>aKBs9&^+- zXYD1~s9t|oXCGp5%)#hL0?GNuaO21kowRcGC(lICNR`ks6-X7^e(Q5@TI=g;vI{TV zbfe5!d;#js6-ixOINFnUx>Jkl3*b|aegNvUpYnk?20;20eM*@eOHsS~1Z>0#fLnq9 zQbsjQlw`G2YA7iD&*%oR4W8NhbY!C5W7FXw_v6(KjAB6sg}C=}Q+643zV;cRU)U`(E@oO{R?nd$A92uNcOEc=ClDk4yWoMTwX%uBZ>!QXU#6 z%$bO>R`~Dcw_Yg9N?gQ6e*9R1r+L#!pdi+ExMoa^94&R`RbG7k1vdHav`eg(r)#GE z5&Ap_a1RuVH}3XI4Oa(S&Fi3XoFx;$`uwlVFQfps=Q9gw#@rD==fx6tByV0W3pA=(Y%G3O3HU``)G@a}ED&_tV^-%a{BARb#>QkdbvrD|KpUMAF| zo&y|wNuL%C;F2E{O@swsac5=6{){gB=xGh#Dn=GQU*dW0-|$|JQsDS3;_EG*!pl>B z(QA~5$y|b;4{NE8O1&={P_`w(a7$s`&iYoAL+!dwEBN^1MYHb_xAOo$DZ42frObQA zTwX-Ly>q%RIarH)Qw@DQH3)rrOG~x==|L0`^T8y^lZzN0%#6X%fnClbLFrL!A{NQL zC7uvJCD*bwQpMHeM@WrE0AOm-XGcZSh^iRR0lBv`cv0Nb zRTTAkoqkq^kUp~%^MSKi>s+@PoSvlugk@ZX64?-4d|1}z4;tdF%8-sT<(mmAk&F@G zgM7tD!Ay~P?fy@1RZcjW4qfgyS{|L_otKVuQzN$W?VaOY1@eDsneWHTt*zW&a}p8B zGzQ(D-mxRz`eXL2To=MY?R-KN9aZ1JG zEfBMQ-SZ-l3o|!1R7u=k{nkz7ks^y0S4N?DKi6QHuaRp_8oteFCHRL6`%t zK=jb(>7cZvi#jfOwY#AEp)mYm?zT_h1rgqA?BJt@lP$A5dzqDvHoAsw;)2R*x}%%s z)mKYTH(_ToZ84YTr6v&>B6y3Co}8XfZt_Z4r)Ir3bzKu<1vu;v>&B~Rcvd4kPcCzf zApGmi#&fSP`RJNT8SZ3r#5rz~jDWZ6PR8wPGGlQ@o%rPY8Dta@pa5!PbkFC}sRMC5 z0?oT$d@HIrxI^l90hH$+y7K=gknXQ@*JZ)1gzno1Kn_;D$B{SfS#d;Rz$cYw}LB3WlCLED>GCph?;P$RPz}sYU{a06#Hf2W_gnQaGFYeo%-DgjLnsriAW!T0&dLf1XuT_6`(2ty?B-<@dn5>zKUj2!em{BXD{qNRuC9g+J@{neyrP%H zu1h^U;}8Sy@=`rEZ!r{@d1YKK4z+E>Wl+``3ykzW3-OTKsD0mWjI(rjA)We}g8Voo zuRmH|*ONI*%3}Q#d%h=>`#=T*`-dA4uBF*l{$FEK^w?LqlH^vrPCOYaOaYIV2Y|rE z-K(0!^)lZJqKS@uwxMY+h;t9u>>|nB)-wArFCJ&* zT}=YCvBePY!hN`Da~b;hhs*o8b)X4H33_7*^2lq>uWRc8`GmZyqHG=eUGZBJloMnrtGSrj0)UIcc@do8?r`reHM`$x8gc!EW)7ZYZZT z`8X=8g*K7)`r9TtAi5G|Uji=CN-qG)F#2YpH8v6Sm)Ys-qVM_JowPC;qCSD8s{Ltm)#+|piNgIBjI17?N0-qwt3rg z7rPgjHwRb}@p|d?zm()cg?47aADq6Zdp1r>Y4a5^WqZ@>--7U6Qd8vq>?b9Vu>mGg z9gyS5$DcHLfP{(v$9=tq{lAPYr=6R(`zND+u|w22>O4x1&4(O2z5{?$-xUDkJF2__ zq_&G``J4n0N-@6D!Z1HWbI^!;AEB4z&9Lec3mj0xYVE@`WS+wAwHAv~%61CG(FE8V zq}j4A^Xv*)u&ZH~^Jqk0xOK0^o6E`9f&xEzBMe|HOnFm|Mj|K8n9^If8-(?;?}rT~ za8ml-@l;~XEF_1btH~x4^H%dDB(+?JLmv#N$<>9M{M}WYSAfk$je2-=uOC`eLmTXe zChQ4_l1`UE-dD;Els!7F(mXTMbNHeP;&i3LzCIstL%XxZ5{vusEnQqB@n{NUwRDSp zmr(TJw7A-xSFK|8c)5dSzFpr?>Y1WAKLp(FoD2&-Zus4<9p{MYiH8`Oc~NpqvCCB> z{yt?T1)T4d)xf7ei~O#Cft%Tax)%ACW8h^hgvKZ>;hJkXfgNBOt&c0k^d-J<`r6HB zC=ScTs0_2ybfr9HeTcJBrA&0zvZwsD)FW34-CPi=BulAk5r@KE8=eDu&w4wau&brE z>RVCP{%qEP-8geH@g?p&3|{D|BssJzf})_OK871fr00w_3+0Gqz8cD*r3W_N!bsub zR7)*+X5v*74&V|mT@Gh~YiZ~I?k1w!E!%*B#MZukzi@^k3s`qpxCH*04qc0ec>#^h zf5}?=G=G_j0eTpEE#^5&GXasC*-a|8bNRk?S}SlOhDLDa&jh;=#G9h%SjU# zIt28WP8t*c-BpVYky{I+4b(@X=kiUxM$65-=OqnB)ud6euab2Z@+)U&uC>K1M)!cnN^ zuJ{y4>j%omZ+F9}W`sL3Si#rZS`cf;#$=S_iFy4o3i$OkGQQ!&r0@v5UgT@Zw}4a3 z&EF;a0@neRZlB^r$n*B8=N&?z9EpX{L94`-`qecZ)(KxBHNTQaUP8P5|7O$&2lpi>X7(>p--N2Kz}Lc6Yr zn_Sw_+&cy2??)@%_2cv{Q-N?64N{+DO6HHg!x?`25pU+T_Q}gzlpIn!Gc=$)V|VJE zM$_du0lIIhkh-65@_-el!~t}qxSreo&kwz3$oengUe!o73e4x*HVmT`lHf`M z;+C#v3AVB!v3TzDz&CVkK}GATvxBwoa7ooRCxK}iMSYZ-^6D1wF3{Fn<96u@n|A-! z3lhl1Nwe-RNdCL`je8dA z$FdPCSl4y>&!icl6@R>)EW5v8?m_fKNb}ZIb7+$NBcnj1#?R^`>J2S`d%ko`xUS7_Kk;yhEFrVy zy@sJKUEO7Gi;EQK#!i&m> zb`0>c0$W8{?VuYzZ~;cFiK1z6)?L)ug85m8SQN{}$!@wh1w?Qs1NgfPS#Jxy&vkMX z3d}`1FwibCB$=1}(5nW*RU`W5HczA8!zEob>gIVaXbCmbzhEA59zyZ_AyonU4UB{xm!Jz~V72XT{9XtfiK zjwE$Cp{FQC^gMV)PkAzq1%V@~K7hfWkA4@rwUC5$J1)q!wYpjwJGlETvQHMW4Pr&$ zD=GOEA1*XYQ7;&?`_NnuUo9g=$5N!}oisiVV5JYkza9*uS&qe7wrh$jLf6ycQjuY- z{>jUNe?*yV>=SA!8d!ETpoZl^QY(<_=#53ndcfCtiAwk9d;H87C^0FU?sA5^c#`;K zU=asvYl5ge^5O{)5Gn=)wvxf3&Bf-H@WbgT&mopc6076Ax~66+dFB1Cx&b<_UhRj! zXINGPW4Jnc-mQlm(I|hKokf{E-kmC;<+5PZ;=_?45qT{bV9sb&xA*%0o`BT<_XN`4 z#8tMAc?hV|!|lN3Jiym+h`M>D?dVhV`%Qm}Mh>^3XT$H(F^`3dV=z*F8^ZvTMX>-+ zt_0IEkZp^v!8`t2lOIiE)qZITzO$Tlar3BfaFzo>-W4 zMK*YasN?pw_#_jG_!0~AtNOSN1^G)qgh3FTr;Oh$zQAx;&7Q%Y$-PZZKNElU{Ri`V z-q2;ZY`-ke>*B6>ek6#O{HmJppe`+QB*HR~Wi1&S>?-$m|iKZgXCGR3*h zsnQZ+jBz@MZ^MrnB#LPm+BCKAiWf?JxmU2^$`KJ^PL^SctrY%IgHK$T@nIQ)1TnuI zZ@|v?tTb(wyQ^&FVKX;1vPahApPL!1FNY)G6<-hUG$c#dBMM4#^+GW!OV=dHmF_~} z2|W+ctM{@ZpN8{oswMBeOkW=wI@wVt&nANc)m5tfb`0!{O<6`&q$avtK6}e*y_h7X z+)3ui2c1~7=1aa9PeNz%WkOpT*i4*Kt!_Oc_Za=Ns3wS7*@Dd=x3GF&&N57dif#fD+zyD8i zXTO2fwO$1ly&PL)wEO_1wwS~Jq_)riA}cuFS5gZGm@X$^D70~Be7VUSSkH2y6ia_b zPY&7Jk$g6~dgeXJl@M!hQjtF9+j3+q(%CSGa6$TKS@)C^VM4B*? zL%xFsmY}ZB7Y)93}KJejA?_1rl5gE)f0_}20r@rA82Af1URJo z-lZE-(d!2l1S!n-D;D_@f03?q!m~IUc$$|tSn;M1-FtWyRq$yJ?zqGM)gr82JqM|s zKp-RBQrbek{VZ~TNDTvtW5#UIG|H?;>M}*7GHO^_{ z8#Na}VE+yYgq3?1Pcnhw<< z`eR3W&qSJpsVJuN9Epu(O4F5$Tydak{2qD%GZm?b8cO;J;V@5s_QYgPQw%nkD@%$x zP%7{{sI7HU9a`9i-e6;yhqbAHH{JM}_=`?29>emhIdUN6nIi8*XSfP81G&P$fPBYa zHXN`pIpomf2I8(GXc3;Xl`G~dOjifYLvl!=D;$w`tM>Fjb=HU~a-v0#O1jIRc*|s1 zGT!5_-63|Dd4xF3K9=;pfoIjy@{jni`uN)(uj|qwZADWl4D85B#aQTW4O9*Dijl?d zeQW~r%6Ktxlo$BlPD-=>X&Gn6ckJhFak`wqJTIo9R2{m^Vo2UA*y?V2-dXm|s9A(d z_ivxMpuJJ_3DW2cO&I60!pc4uIq521E0(Y7>u32SpkeSgHnL<7nUw==%dH%e&`*HY?#=QMV4A{!7|d;QiZHYsKe8 z-213*u2#zDaz+;pPw6PEr?fQ$Q=v&@Z%Xb9;Qc_fZQzgz(6lZ88u;Fl-cLSimk+!Y zmD;-lUm&?HSNmLP>au*4&JpSk?&!eF;L5;4JzzK zDGx1duzNmGfYgRnJyewi`TCfHVBsjy442V&|ReaNtyqRLdQl|sVPdJj(PZ}2R zOCFtew1!d;Gm^#Hgan&7bGpIbtv@@S18(CVJ1DIP^754!yh%(Y4ycMzPXVPr&)TToZ+W1(?%7};s9rB`38i!#q1 z_b$+Ao$j4i;Bt=2cJOD9Am?ONblYm*x)-#xaujChS#Pw=Nwcdjcy%#dD1UxEZZaM# zkl1hU_~KTNd;ugeA*>!dccFe2HCG4uja#^x_pn)(AyRi6UyR>p3^1I)ImyJpyAqnS zjQf}1UsZVi-&MhH$z*XbtgRlnCU~+6bcAF*_VsU~lA|fi(VoU*2)>3mL?8=E+;Pp6 zu-Irqz<-+eF*3xvs7@r9<3yMz6(3ej4zb7YC!4lj44+X*Uesl)?>|i*!!{`L$N$W- z!oU-d*f1*V94YJUCl)U}DOw&lGYl8xQ%S{^&1 zD@=FmW-y1cO^<66M5=pD(q)opTJrF^m|b=7*lDKPM>pwkVJ8KH2CH-BMR9g0x}GeP zoZsYPdK?akCiKeJD4LQc0l)I_H?s^^&}Wr~v_w$q(SUG#NYRXGknl zU0UxXs(b>XOIDyW=eNjI^}bsCr1g{b&u$lYef_2~{TkUJ_Mw8x9D?eozuq{Ay5=H} zfW$t;EOn{_;+y0Paj7B>0{1#1(K1y9C#P~PZQTRB;sPsM$}YEYz1xSblXUpxkd(*L z_H%48+I{Q9mbyD&YEb^G{~5k{d|rkmy0@ZA8-6mV5|H}mntGTjXItY-CeGv1su5>) zjhG8LD?V(9apl3)>2`3*+B=Q;Kp^XG;N}^Fm<8M$vwkRuW3^7N=sW^Bw_RQ79J&bj zU;0jslI!!?<0yoP`ex@k2^P?Mcs$tNgbE$R=meL3vjHvJ zS1Mn^dHs{2BuLZrYbKh2*kn|i8#p=NfSw78IC5e+=J4)px87~q{`=dj?7whB?wf)V z^p;&IrRVd+k>4Z0KXSYU(vpv}5`8bs!FYaroNdyt_sF6YK6A6ZM1zRo=fNEu3d-Az zJj7vCSPfy%+yuRhmx}lpOmPR~Cn80u;xS%OYy2;sz9~8mu5Ei_+n(6AZBEeGN#iuO z-PpF<*iK{Hwyh^=8vXMgeE;zr%v!Vd-22`agFJc>_Z{HPb40NQbYd@YdA9yUilsgy zT;UP(ubA<{07V=3ksr7GB_Z@P##C3B!N=(bxK1TjZ)c;#zt2{xBe>E|yNWVwh0 z3LOUhcWJXu4iG#9QoH^nd_!$?Xjvp@#fhT8p_6Ruv?F~?nV$Sm-hgohj~1k4tIwSO zEt4ZtIN6&WT(>b4sp;vSPh+s($s_M;j%$u>Zdy>elEAkav(#9cZ^FCVD*fc?7O{SB zS3>M11gIlb&wn-jbUm3rCF#{;x~jHjA71KDqPmQAmDO_BR_jt6%9OU(DZxTUpkBch zv{8ZSHu#>1bXty>h-JjLG|o`blB3aO+1{q_SRhClBpW^2ZZm&)UCta*cm8Qbp`J^S z2DzrS(bFOA;rJs-mW(lpRTyIMAudRa?bj2;p28bNb^xp%AHka9L@7Y7te5!Iy)FlOJX-_qGz{rkAz?$0_iA1(~eK+vPw&S>gNN^=7}9S&c>y z2f2ypL3MNr9ZR?LznIv@s67R#l4MlJS7oOB-rjODqvjkK%9R*T(a8+!O9l+8A_S?j zq$vIHKKL?orc!x4C6!y@e)Q;R5NK400i*qBYGGk1W@=C=LZj>!9?A!@6nNs?qzc^& zL39?N*XR=Z4CW-yZezMa_cSbtRy^?H@~7Sb^xFL4+e$RpaG;~3$S$&|QB-)92wl#>0m zj3*OdMRFnZnvW#qyeibiHM{icx2M39w(QSQ;lTaWB!&cmiIib6i0$W;0%Jm|`wiR8xal2LEdylWVpt9&cR`y0qH-r`4bq;q*@LaLF~)iGKFz=b(>&+H~gh z3v=(T@B5A#aPu>?;1LoOu9F=p|63qo_ay=}=~Z>?06uR*KwAQ-o&>T6m&81zdX&i9 z&Ut1-LqIVkbg{w>B6z1xaURz-ZtxWEYX8410I?v_ir<~GQaUWBx*g4w1K~i8xa)GU&Ot{j9)PO5%-cJv1u@iq`?SzP1Zb;_MRPe9)o47XDHE0H zH@}rjfo100oRf+Rjhs8;s$!tX1mK)Y4d$l#+kSu`Vm)TE%eN#ISLl;$oC^Ds6e?`^$HQLC|m&IEYJO=F9ZEx!Qf=efCz%O z#z&`1k$~@Yxlqg^G5aPZP8>@aXX%)t^N*LGr#6U6eEb*yS_)ebQbQWkP5-Xc1Xq7l zBP;S=ua6q|jUiHHRX%WuN#k)ms+v`Z(&5tgXjIfs?UT`u27ORr0Kd7|1PKv<4nZ%l zpp$VDZ1RnAqNvl&cvf!o7xA;F4VicJh z;G~i;^Sk`9>m5Wl{iBU`%DkbAtK;aR%T8~Q5OsD=1UaUlif@p3c3PG6_{U~o);jt; zJt3l8xQZ1N98sn2U$I9J+B&&zTXF2eX^$X4*7kIM9VxJkiM)r#j@{J&jR5l4E%qPl zT_@|P)1*Jr32r|R==;D|T}I?d`l>FeV4UVRN`|cT=m`a__3BEdRZGGq8ZIy6=k@TN z>+LQ^?E3d+R{bd6Si8f=v3BCj|6#N{7s7hIb_k$TD+mx)3T9S(WrUo$M#<93@(g70 z-zf=~7Q#xNs$WYUT16rD^Th4cz9`Xq#H~N!iLL!yCrc0CC5WQ+)VR!)*`gU|lN%s^ zD#0Fa{3qYB!cDEsf;~~D81AzFP?_7Y5=m{Up^mGhDCr&C+%};0Jfg7PObrpb?rc-Z z8j7nzkNo|x2Rgle1X)4D=Lu@5UT7hg5^3EdXPupHj0tFK=H`csuBETvc2?%ipem;w zOc$iKG{ND7w3EX=2`MVHMoHGaODP+lJ~oPXVbKRsY)xtF|2Mh0h9r^fBLfa>kKBlG z6C?9F$;;OR=?F&+0cwK#I^W~mWI8$wfGCL$W>OYzeQ?U<;@l=mL7avQDLac1R=HWNer$l=~pGW;R_=o~D+Hz&r0q8ZZ%Nrd1g^YBFc% z5A;^AeTkizvyiICMC&sVTjA9j?>tekt|)6z;$UX332($5IY2T63a1gvt{;MvfI7J} zXDq$H+vHmYC+q=@WsAsX)$~F@&(`=uLeqRHU0HU*hvt(`&`k7rF)LAeBZA$s-*92J z9KMu;=~O9gE!lrybTqu@-OA--#Xh8;Fo$GT0i)BP1WDOG;`AvQ3LiTk9$c#Ze&u@F zkQUIQ55M+*e!v~!1-`X$u(1K_x*wvu?+%dE;rBWV6FtyfbI%uCAho~1IBM|;+fLDI z_1)Gybf)F)qjmTQ>9&2-y}gbj@lKn~n(vL()+rAP>Em$A{*CXXQMMJF;&arHgUBoC z>^23Ai{(UKuB7XvFRv)Uw9%%_#72|?MASiJH=>WVbXxj;Ozqob=VScULwvU zej^W?q)q2rth7iiDRiON`B%<7Y$ixH!MH?|_%PZiR11spaE1-SlAZL{1L#o)H@5h5 z!wsR^I&!dYoO7M$DWPO9ih;&8PpFWkS#olo7V5tt7MfF0CRcb0gkG_me~{Xxb_$4k zN$f#C$L$^Jr1PL09=jDm{?SDo8HW`zp3VJEvf*eZg(yaMV)if#aWZt4`A;5@l#-IN zCU4^`mU@kri3!o!OcsrlgV*2zXDi3C* z{(9e0?yGW7a`FO_^E5P6qvXYm3aVtAf!+Z3dLo=eiogCfi;Zu=HtR1sWkUa?gsQe zu0xg|tDP~icew#hCg^Tm#Tz$ZNyWm_Qfcd6wQ&1Zr{iYg*4?Y|)wV7IcD-Mdw=R0r zgU57}h2FgEq=r7;wfoIHZirCDOAwu6(z1WEi^;L1Ah7vkMMe`~;wmrSz%osVuBEBT zW!G)>Yw&a$mRz2xX%`K6fp^C12r0GRJI+5d9;57sL#hppo@VKT8q5!n;xv)Le$J1P zPX~3E*;s47^Ue70M%w$QZk&ux1O}WL5 zqCjWo=1#+la(UeF@8wYJ5Ua(tW>nS~&-WQ2kh413a5Iy_j5RlSzOonkSVM^Se@8Z& z6;w+2;0PiN(2A|FaHE4lp-WOcO?Ekwsw3uKjwHGNZNU{$vsNgLJ+RP$!p*+kKG-VpNsDzz~@+l`s#in1`7xS7}m;g4x+?+$3_qO^U~?d4BP%Y6-&99 z_M(EGwuyUlm9AyiA-LSQ|o(VKIoGouU%kagx<%Vgl-B7CkC)mh) zyC7sM#Vp-xzp-;)3j(&0>XB|zavq3yLV;EVI_yZ}(pC#=ve&t1i4J$UpSSPvba$*a zojibduu&HyUJ!(!4l(TX2aUxwkwHp-$PKlhM-RbtxaqGA=R5ZUyMuUJuE2|OOHXKV zBCm?1wt<0?9MFb!eUlR`I#OB9l%*yz(*pjGGn+k3)a-im_BrPkBFrG33(pQS6v%IU zpiYmDXs73uPOL+3?6|1oxZ}76)hS5@H);U*r*Q$FkyYFLxGA{u$`z?+waZhRo-MM% zd&dzxxsQ(3gXt2!yrX;zpmleeW>RjUfg_bTQ0O6I*eJ`L+{G@NSId*WPyPH&z5`H5 z{I-x;mY#EK!LZ0~X@F966>y14t#i>eYqg~GB4(D{_%b6s|6fOSk%1Ynyq*si_d;W{ zEKKW-R5?lK2Ci@EV}pVr4{>#G7N<8s*xF%b^-NUzPI^7lsvIyig;YC1Ps$`RqyTW& zUUd8)86w7CtAt5Fq-M9NZ33V|KOH`EK~P;yRf_xNs<^|SC85!^)U+!c6&)H}W#O|C z%g6v7v`89sl50szjm@R(j85Mku9%znDaY)RyryycGr}X{izp!psAmqlg z+^RJz*m+qdgiOYezMvK?)J#n`>&FT7C5=eetubc9OA!;7csKRBLwCxj!i4xa{IRfG zkXW@^e)QfEM$C_ycxc73z|TbyYOaHIcA3FpTww2DNGsST4D==YogPUR4ti7$@H0gP z>^<0JCAwlqESU5uz-QymEG!!&RXUE&z0d44jJ`LZXXlh+B|VjbParch^IQ~%75tqUmR%T9fzmZeog-&}S6R7S(fAL^2CPyiqKCbR%M;Yzl=S?S2|B{A-MHXjCnz5&LNI=4ndCyCj9O7cDah{wiufc7dy zXTwJs?4B8sgoY_5=F%V{NfV+877fzm$vfs^@;gZnqQeau)+wZmJ?OAh18_KLWJKPy z_Rm{o!M-D-rzJ5EGDgazT2;T7FBxKB;A;GFApV|t`VE!|>@r`Z<Pg(n#o|dxQq4zUj}{XU zk3I&=79citfXJAciI~P2%}cT4ssVGTp~pE?VJQC%+(8$dc`b2-?#Ww=&eLe(Ut{`X zo+8SKAJSt)&R|4q!QWZ68y^jRAiSQ1((}7K7ZZ1SA?(>A<=epM$U)shtQ+JcN0P-( z+(i1ZeHx+eRq8}fB;SFHN5rzpnvuqq++<{AIoFhVU_u}6Xb)T(uv)uo6Ap~Xyf$g= zCRgR`%)74E^cZ}f%PlXV0(3WZ82)o-dpF1&SpXZX&3&MYb@TYV-{`vSBZARkR9}MOo)p+HV@(Zn)5VSItiOhuY-P? z{f;J8&L)z{UjgQpIA{7AsyRy|8D%R3k8lCAd+98q@8a|9o`Ot}_=ns$tx6Q($~;;*~J-&GDedFrqjLiGP$WO4na& zMv+{XgM+Q2h&Kw7MY}VSkR;`QmLInB(hv8F>uTU8-F`Ud2z}Y-EOGxU{f+_@?wSxq zk|Gzj7E5{-kFAivr>lUM+RyHKE#23BR$F78w<*|aPfm&fyzhuO$?OPu$&64cbEMis znkwuem9g+qyO;Sth;@NWkLMYTy^H04UrPVJh~vRkOjCM;W~7JkfT&meCq~;}Dh!jO zAkXj4!%)E@RaRlA*69OR1`s4l$6FcCW`Kwiq`AHpS$|ZcO#il`pcSXea56`1W({=io;+g(%W6tx9hnvVuy+xa^GubWNwrjRE5Ik31Ic{cZJOlLU z_ln(RW#PEE1OZ}N7o(96(Jly)1NDO^wpNaplXzK~j0rJ*X6`aM6`v=JU_09JPSc@~ zAX-@*T@%-=wbZ?N$$V5cid4tqI4`Z+?#s+ADopwyTpH36tv{|TlGMDDzjIOph89ds zyRI1a4F(ukJ!}Mv3G|2)Zt2m7i}3T-PZEunD=BW-7GEE#0a(z%mF9^0r$;=*JiQc2 zty6LYzgpvw|-Ed<-$LWW8^MjJ2P9e9xg|>8~ zf*{KvTGd!s&r0U3@HzgQ6a$VvEQ|#+Y0=tr4rw~D+8T_$FPh^!{`JPq^h`v&&;YSv zYOLh62kOAVfAk{Ki7*7&f%3A8v$+Zz+Q!s>-B4s(H%J%p@dGyGBHp)wtsnn#-; zRoJM5hbi{87z*^|g$)6ssK#UN1OfSMw`n44GDIKH*nbG?tsa{kWhpJ$Ub4^yjp7K0~2_FGqxu;uF7{nW@MscUO~ zb71LQjMIw%OYo9qB0-Qlpf&0Q+C+yTjyh)Exd7R1^eC=vW+JfHU&iriX<~R@j|!}C z8dn;qT|%)L9PybIY0~Qb(79;HDBP33vF2n~4zwwh9+H0ZsecPAFYt-&d z9e!{h3Y65bZvmc%C%ssJUOvn5v~GtO@4#u37`DK-5LM^`dN}D}PC^jG27*+9RTnW# z@xkO=lwQa?OPLZQ|BWGBG5mv**I3}TLgt8EFfk3LJWS{S%-_Z!@g5v#MmdlUep!XH ziHNN12qz0n=&U6P{x30XV<>Vny>6O4oY0v-$P1U1a1*B79hNFnuk0Ya11stYneS2Y z5e5)5HoZ;}V5Y-BuO=!nw|}_!!GZ|>rHKzr!b^jGXh|)!LSG}~!AaF1rnA(d-*hGj zh~h;J{O`p95#(l$-!y~wQvSxYVh@bASg`zYwzoXiX2gl?>4jy;o6#eFi{NiVm@P0O zqsbM~i>aWFHNFZMZ^;$Q$A7zbDR=g47uLrS|ap!4|ct?Os>_Q zF?k~!KocI6gLs&XsszcD4N?3Ks0GYV&2fd61>He2$irgou8Gt{1{1K zEq+;vFCy$|i5CmG)-XA~XFB1w11SSyuR zRJd1JlGZRr6lv)7vqEPMdtz;=7b2k~*~&Y!g}Z*9-@%?AyS|3ynSw>U33`k`CQ%~1 znM?=Z*6e{0UerMbhk14P8X$Yd_0_^+AJ4~An-Hd%c@G)a&q`3n$+uQUlN*50#H9-1 zAS0{qr19BxY+Hu&9+OYzxeZtF9SVdMFOv!<)sS(d&Oo}Y;;Xg?y-^1>CJ)kr1HntZ znzY%talxq3QWy9y&_;@$XKn~<{P4_`1Ud-+>Z!gU-*6a9i0kPIAp+pPK_beMmC~`8l)y-ZU5hYC?*}ZL05si zbYHLEf98hOl=aeaB^Tlhb44RTKCHFsc{|DG3EfM{<@<3^l~I=pI+hq7umsuvKt_kD zp~a3ziu5w>r?bz=fJPtALujdF`<)gnqlXuRI5fJ-QR|!Nw@(5&R94F@34qmD-!#`=Giwe!QY>!Q98^h>ZJ2i*gXgN7z~m!1 zT42fW@kBS<>axA&@rDTuPqW>=&uEy?yS4c>$v&4o@j?~z)sn+=BSnR{DEF3mv-bX_ zXwE=dnq}xo(+96huI|QLT0mP|`g!Z`Z0$wl%3WLudERWqODcJ>)Lu)@EgAv>g5czW zsP60Bfd*v#ld|W8-zBy-MT!j4nrC9gj|>{UZew1fN=pxnA4d84X98kC@78) z67*{G5{X?%$r7SO*yZa?N4b_pbR-FJ@fn=&jFmhjFG(*~oY2LU<1K+-0soWNS$KKr z82SIF1&-&twIK-Mx=LJ}pFW@J4GK9gKPBP+W0=RYkOfg(Z%29sONXwd8_#{TQ|s*+ z=IKd3pR@eqyLd3&>ViNl_r&lM+fw8o!SX!KzTDnO8*{KYxT; z;N)ZZV1vGiB)`peVOq4MOWeM;Z1hKpwGdTHpf+_6xs|;LB`;x?R4$4oQ+)JWdMcvC zPp-lUcZTRsGDsW~+G8+rly{y)pgzKi+0&V^6s#3wW$Dek2ZSuA%cl8S< z;D-_lOO{OgG%IXlmf3%ZjxSJAKD2Z{-dlCRbS5D%nh>N@IA%I1NknM5na=%CQ-?Rk zTYzA$3k;%-7uInkX#z43Kpp)oA@`Xk95t9zQ2c&ChXprBhu>FB#Z_!37hqwHs0b=Q z%JY;C_%f2IMN^sFTMCPn?4rMhn}e;d1RR!(m|05-V`s>c#mNiCX8hRx7GVgb0VpZf zxq)Lt6h!&w-#n@X5M!dkz)y%CN#R(cBthtKAQa_>C(lI>KT+i$glJcV6}$R}$* zEPU{zbbc&4kzETTNev&~mw{D35}Cf&0a>2CeuzgrfJtS9a~<#@3Lwta)YJsT{_Y#< z!{=y5nRFo>KK?%G3kLK}F4;92{LJx567>E+Fm*UcIX~b5GL3Y#er29<3tZ1R z?Yh3u!`KTd;SR9kMm2JnD>~G$BA)OuBwEbi}8l_3D4^K^O+m##F|3Q6h`xRwCKoU_@B)*3Xwwr9RI$YXWqHzWG z{!5ebwl~g8)tV>O6vLdWl^kz)MM+G|^-9bF@SDdEWi#Ce2vgjhbAa3|*K{Kp`-h zrN^=l1Auj_G$Ec!lQSC#>+Jysz4!mgypC`xt7{RBV#-^?MKHUzTXRb`WZ^%@ zx@R;~8e7+Ali};@>ldYYCU{Ki(>3ud?%c1?CrVoJqPN70VUPH}J6%^axM=tM`45kk zJv`Ts<^G)Y+tcgcqq)TYz>CbqkjhWosNc1}W(XN+X9)`89eS=0ukT}|*OozglY+K< z&Q~hH3s|9sAhWe_m(3`O+j9qlGQd!N<>8DkyYSp25eLaEOiUr za>r#&nxd}($x*ir{WnDJjBC_IzGT3k_ z&?W6Me-QMo+NytmrfEFj-zAoJMd8yrS@^vlO8wsNM;ErY;|$|2!dGr;hz3`cHoUE^ z?GsUm^erz}YSvmT;aV*nI8YErSf;STK`=Ai1l$7(CKE%Z+24Y^XHGToi*Te(OTk}M zSJ(T`6`W7o8z}^<%)b>f2Dg2KM3Z<^ygUCGZrz)TN13;?W7H9F-O0jzyxQ;@L`S2T zb+Ulta^!R<2 zAZZ>6gccU{y9y0>Fhb=fI39N}uAQ^uef^@e=fIDiTVo=thi)av5ClT4>gi`pOA~V5OMP$+g40ka) z<7&qx^K8wpAPhn#Z328SG;;3u^dEHdUPZme?vN%d8Qh}Fr#)hT`b^$s5>lSz0vVbd zriqrmWZac~@OGs#g+mS&eo45+;6L@X_<@CpV(i!~qII*MTVkmiE@AxPqw~3&g3odU z9HEjJYWkf0?nkJ(~62)oVC+{J}9-f>KwgV^LOn5VJpXq9ZF_o&vVY6DdOwo`{*EOCk)m^>-G6g(>J>P@%LY3Y9NWKd(?r#yqn8=RaEgpwAG+3Qvq^VX z^MfSlK9>4h}6ms2Um=_ye(((OfY~I5s}z!y|`N zS)32+R*}cx&~iS}nv15uC)q&g97I(MdN=ruZ;>MJY6tRHqZ-)hhFzZHZN2}=Hu}Gz zVvX{AQ!!c&NPXmbbga!oK!oM&P`TECi1PXRcmbOy-pe3CqF=AG$6dQ0EU>=NQ+#p} zId7G)jQ;kdTtjaiIEd}X_9EH4T>iYGeQmwHA|1}x5drk9gU{QDGRN~#oi?3DVK|Zy zn;0FON2n#l4To7UQWyZ)F3Gq`LM8$hroL70W{lPpJ++-`rFBZ<+&bkkypi^sQ!nKV z)~T)gfDAc^hol`;p7M(Fq6R_of8G8l!zMkDX1|J#9a9RRoxyIw~-4+ zMS4=qI=`dm-U-P`?wv}m!;yJGV z0GbgoA=9^#hp16G(ouqT^dR!v(C<3Bg#c3l8+*2->z*Eh^K<#h$Xny2w!lEJjSi9O zWS7CbSMO>MZt`KRUv=SQ>^8{HZq>*8q5*fkg_j!bDl1tJp8(Aap#Tgs^gU~03ev+u zf&OL=Vam}4Q>W;3;yu7wLN?ApO;;*fjUF$C=D8f*1sM?5B<0I-W2c+&Vw2&J*~X5? zGix-u$|hZH8Ny9_`rY-v3@x~v>{!d_0u^B9ak+fC+^jm}(g|b)^6BYelvc%tBLTE! z776+vR+@q`$(qAFDQmRp%QHplV6YRZT?X}}T|IgAhzBLbjkY}1Z}zsV>9s4v zyFKN$)y?zIU^@S%aJ3dlhGR?h^aVD`g%HY)asu@xMQt-)io*Ix@Ob;>d2*jpmc5W;6L7oHqwjIM zL9O|-)ETUj33o<^YXi5k$O3}If(+{d&*sRz!GYl1J=n4NSfxHESyo5$qomUhXHBZ2 zSpR11^6V$&95GJ9(9EwN@hSoR7AUag_tI{Fc;VnT5uOGcyi0zlaSzY6G`G!w4WaJ5; zkT@MA=Chr=c;@C%4s5VP?nItO#p$%_jsL`NL3{G`mV1|itQX6jxM6kRWMCskHx+u> zLI(=<$7kLN6|Iu{xJEL|c&Ja;2>e4N8C1c~Env8LTL_#>_q9DI>hEe2yr zp1S#)QF@w8PZEDbPpk)&m6YIxuQigt1lZg!y8W4aryxNm$IxnEH6#|KZ5g~&+L#6O zb8`9O!;C)r>q}tF1ZYkDBA0aVEL{wHA~-=OXJu)k{6x?Dd|d*Zo0C=MZ4n8+^vI@= zM&y=AUm%bVqNV;*Kq~2oKpz@JSqqu~qDGAcrXmHA$7Ya;t}qq^xRGSrQJi-EJ|4hc z9cDL-?NUGFi-+Q~Pb8^9c~~goibKOa((LC6uZRg6;3#VZV4){g32 z1jWTdT$Go#`RdIS5GFoWj2SgdpuYk4omb?~tH1I(q052i@My z(;J#$mj^FiTQV zz-T_GYx&uWTXNoisIsJdw-vK2(?o>H1)o<|I@xgM$85|}j}om2v%TvRrLGnt>B+bD z0x#?1!Z5{uE!k0S51~;>_%Z~MQBcRhf4$}M#d-6B$&=~p#*Q9CaVn3$v7@lXfDKsa ze7^MxVOm0b+Ql;jb#YtsS6dxet%c8L9miO3*cmKFVIP&M z$Af61LHCb(uPbeTP;xYudTm3#OESYMpwoFFs#F4?NZ@~lXpBX|6gPjkz}CIrjR}2+ zH!1Ra0>kwqIvrqyh^v^+S^(6Nbuf=uDrlc{+KS2kFF7nTTt|6ES<-VIedb(UB!gtD z!*S;4rO@wY=}!C7TEjo(L3EbM`CuW-YBC;ip^xK#YGRjoe`i#pyGck1ztt&*%%@|- zQhlu(S%}LGX?r_cuomQ63YG~KXVok^@_VE#F{j)(<y-SkBVSo%#_ODDB8<7mWCXPrPH#c4}W!atZ8rbqIaqX zf>%*=w^s1D4f{47%G~%EjP3_Z_?>{B4z?Q|_U}>XM+GvMGnXoHVfa1l1`I{qD+?q> zHw}7W4_iD~`9og-wO3q-q&m-Y>e_nsOnNxanQM8Zk%FahQBh7~s$e3KamZ7xOF4`m zW8L|hoDbeYpcVRLlQe9-_6fZy;g1#5Obj6UVE4Ak0`M{d-!dxwd>jo}l#vxVV40~- z0Oq-^0@kqH%M+djtce*$3`1c$^^^79&H!(iYG_?IkyO+3JT%g;5M{(9=yUVwi4>3b zLFFUy7jFnrn?a;q*s@a@&03@U5f&ef2eMnG$$OT7zoFN(_!Of+IMP*^G949Nn%$k# z4AEB=8IPNZv21Pvr6u)bxnY112Hn6-csnxqOqQyPrtk6B{}X&RvZ zxy?{TgE>M*9?HKM%&<1d$PItLyU4(iZ z9RTz{r7%QskoH`}6|vRv80o2$P9DVnE^+Iuk-ad%Ij0OkQHHm(u}a(YTp?%m;L1bV zcu5@J$g8yuC=-naY@FnC{MMpD)}eUK=KnNfNRU@d0CL>?9?L;yZ7;cfg3#>GjcK z60-CiVM@pVqeE%+CQn-k&YThz$ioaUqYnIu&tJ&aSOXt<1EC5X)IKljJ`uZ4dSV+a zJGv%va0nG&BVRr+0Tqa#u#5#IWb;qP)+L6G#9&>? z^wm2%(0o^8N&sF3hS{>y_)OD>qu2p-zu>??{p8xGh6sKwOCT1dk~#M;d&Yi0<#(F8C($M)1Yy8ZYn1pW<3%&{pc*3;;0TZ)=PaVjzm`l z3k|c~L8G~LsD0#*P5dz7N-kKxk+}{C2eUJMgbf|Ix!{%7dy(E0neh(A{Q2mHFv<@S z(mQt8!ObpC+U|33SP?hNUxfU|SyhRqY{7kG2tQI{V(|~v-*ux4LJy*E;Y;OdzM4UU zb4>a)Fr`ZIe&AQA48f@e@Z#%(fuSImAjQ>Ovc3j}n>xfE(7&p^s))4n_JN0V+{HTR zC{1lIWIENa4INBl^9zSA#DlQ8&usx?Z+*AR%Tp@eu2uc;9gEZmOvgIDRh{`5V?BDKkg9TU2y>c7TJ0c0_e?}D&= z!NhC*Nj#|#KDJW2K-&^qDenG!91rra=dOV2AwJL{XB@wcoeS?5dmZv(`W6St->^$0;lyx1d2nm}} z27U4Ka*Hi-(<$zS%5w)-GQd#6%boqrR~E?g&+t#^;qknkVcnT-Rmq!%1CPyWrkpO% zC(m!BHxFG7{prb(y3SdE$E&GnUy?XFqeYoiFtGCLwR!<}b}b;pUxET7YyyZj_7Y1y#ypEP%-bp!a6LsWpkEvp>&}PL;b;#mG;T?W5B%)te%XQW;}<5c zA=0xPjKKAC9>8qF?*$61m%(b<$Y+J9>9;uqBYx3nrImCV5O?knGxdJ{yL>?Vxks`??<`(A7xlo4ThpGavuw?QR)&bhtX+Rz!Z=y5bTl7U3#=vEeCx$TT zf1rVxe+46JsEmPonXSzRo2ymut^t92k5zDmV*n%Xc8=)&aApEzt$-*$|F0Z_IT>sR z>3b-62PtlopO}RHmR%&7QyE*f@U(0e9{!=3Hn(i=K=(XQ_Ulx zbY?;f?>i4%%uSRWV^QU>fhvq#@vFRA5^wSraDGVXMlG%BCf;_)&&A~c6MP5qr*4s>IJBs-vfvrZdg@VW*$U$lWcW^0WuYy7N{^{{^di?A<8gpa+##~&~Co7Jac)W zs2F{x)h%}|=>SRBPttr+_b3Oi%WjSzPZleKop3@PB0W6Dp5Dt2y&-Rq{qpq*_KS|Q z^CN|J{DeaR9VInd2h&l- zu;UHL;ra;k(Go6(CCQX}2<6MHH%Q%DEA99RQ;-GXCe8Fmxha{#b&JtY(WWYd!Q=Uv zo8t8~FoIR}(R1b_`( zH~P2K&&N!?7BF;m1$#!OY_@Nu@Ed8Nv16V#2SP{Wxs2hj?XTbWitZ#LG6LUu-G9<8 zlmNQYZg@yv`KG(LR#`TO zX%;IN=QpvHcl9!^I=fAcSWhv>f3ShDNdB~yT8^MsPkad@*{@61KMl2W8(kiBTs2)< zrO?n*(dN2nO2{~RqWccef;xsXrznR$(a%kQ?XX$rx}CpQX%&8{lzTa9*_e@F0hcZd zo;rUTBbVW4?-o)hHLUl#tL(@H282=K|BnQG-Td>R{}Hqg0dkcqgLr|CYBa%gEew^a z2(DnSZ(?H$I2yyKuJSYX?6R}brM+C`HBbJbxx8Ep5b#y`_v_bCnYVtcV-mA|tDGQL z=2^!ujc{;f;J=DMb?ynWk2BeaW7a@|Jee#==%L+A*bGQiROE44a5S*zjyIg?uPcsT zVc(ar6$gEiYg$e==N2u2C{x0p7Lc~b>{_!cjpWw`FQ0F4z}P>18B64^RoZbf*vswb z>=*3jja!l3mx3}7f{9Hit@~9uU7U5T&W+@#zVuyB(42LqAAH_*V%XP``-%uHmnT9w z%0q&>^VoodaluWDeK#IfdMI=}mM&_1@seSCBzUz9vk$)hF-U9G@5fWiG*b$mKc&XX zN0DuCW2byvTBRg*B-|cMFclk@)czZ4--t#ud#>UsCcLmxpGnKg5`6i{dfuc9XUC2^ zwzRp4iYR;Te6GSbh8#T8AGL)4%|zB?%tYp=!zAoaK#(gpA>}7!_RH}Xll*x6Gp@IZ zA{MgRTjA?f24N7r)?EP8vLaGTU@R>5agIM{5k|@DRUyh0)J|5v4<}iAG)xgY7;-~y z30&Gqf|BCz&TJE*%rmgs^jr=b2ukjvH2UKV)zxj75|dFYHh3A$#l14Achx?*?a?Ob ztM7T#L$EuKdsYzQRhUQ0-YYi4T%RJbvk0*Ly!)>Cd2L*Aq_L*l$tJ*H0~YaU21lo8 zW~?X}de^+)m0^MvTg2J}xL91RYG(8RHp1d^{vDX9;n*hh+ITpxF6de4gHwm8u+{{-kRH#H2 z?*b%uS_6Y)!m%BTO;gc7D11vtkS% z%_nneo0FjedVVM?L*}m#p{K39qCO_lqH>Aqw2V^z?sf4h{ZrDVuu^8-_`}zt4cC`= zNDq6iAE;aI5kelury@gd@x&GY74Xf-GM$qj@tQ864SgHoej~nQ zsAjEFdt= z`|brhJOKI%-7ob3axK;+sx;644<13`zV`O0##DcQAB3Vp8tNP5NdQexe)&nYH8q7V z)&!#d@gM(D!GRzD_{X~Bt^!DA36@OhAPb21IKF1n&d0%n@583lZ&jOW^XAR6W5;%R z7|Zjv!nPEb7*Oq6J0l1f2g3a7#U+CLGCquDIb9IczWxDpT2R$bnZdK0(x*?IR>SEj z4Ay@7%1`Bm7ha&m8lgpHM^@lw8VdKb-udmNfSq74Rnutj>nPeA4m@)lIbs`@oLkO> z2x`0FKkY`)@#`3Y2-*svoZ6+ExzBpnE0_Xcy5$>X!jBmWJ74`u#yZP-ihnynJajqt)m*ATtwgE_s3-pd@y$jZaDxwxHs17~7rtsAy0L>Kag61E_01hBdQ$qGW*bc3kW}GKwZ4+&BB#5W2bhy?|`q28pL-nEzv{owgZ`QFR; z_)#2#Tuz`(NJ&8mV-&V81c%Tpu&rU6W7;rBCUcq}E2{)mX=5{yiUZif`;>+unHVmT zp3Y*qa2A8>kGtgX*%6sc)yP<;Mm3HUAj^zkf#e{TT9(MpZLJtbRRCa&z{~-_Gsne~ zB@%~G_JA)Y1wn#YQ^?;Gcm?1HJfxj3@zvnG7Jciqj1EWS{Ba*N>q2tj>V#Y!>Xkuk zy;u||mWpt(wAPnHtF9cj#lo^1npoBKekrYhO)1c$ppZ7TU{HQ)Tq2-f$PdHPfpTa> zabpQWba1xW1U(E%7(j0VXo7*`Hs0gpi^l2uu~Tjw<3HLEt-?|r(kz5AA?pM`mQque z6A|*1&+y-lACb(hJN5-my0@N~mqL~TV7v0k5elAji55RHS!Z`jCHTZiDb0j%nT>9s zWFvXUyGjAuuCtEL=XC7E!II^%R!jYv`v~~XW}5ux*lK)y47+3ZN-P@HWqB1ay-`?H zsQhO{#?^%9rnF*0>=@CGVVGy?<&tJf8hTjN)NasU{Ka3$ zcfRu-1+qBEWdp&1j_2+U1#E-K`cK-^b8@LWA0mwRO~1lnEsPMkJ_=Lj$pI~=1JoN%{K0@L*5z5Pl`nR3e+ zwJWIEp@yvOL}($xxH=@2TaFMAra&2G_0l=UhXC%60c0$?UVARboSMu3YZDVxM zip@|`QBXB06=gM2URo`YL#$=kmjlYjk}K{;}L8d_ukpmdmkf&%!I0%(vG`Q^|4 z1Uu)wSR=&+(7aCvRZ3U13i+Cb=Z=0v|I)Iis6-l}Incf#B>Ns7 z!gy*7`2kP^xrrw$BpR?&?sbS0<@Zh=eP-R@UCFt8VM9M0MwdNf9Y(YoIG3x zWA_ts;d-ZZ4FmK{R7x}h`#jKu3&U2`mv%|M z4*81!&=nysf%Vq7)-L3?^bXXB))eY7com8^!IgXle^tMe7p{@{&;&{(<_l5#? z{BG-7zFe4g9hKU}<9X|l6G!_9B*qUBT%Jd>FQujU*bHTcA^=f^g;@3Aj0^L<(}ua* zTjpcdc)+$n*|vdWI?W~?ciM~GIJicXS+bfhUB;o~`|TK!V;ItlDO0}b*k&;4+b;CK`(y#D>) z{~cq+sQkE+J?%(rFmygp9X^XiM;jJ z@8vYkzxB;;$}`V=6RPi6eh2k;PVm^_cj0T~@z0OR34EbE32h@Hmd`!+oILy7vpVo% zx&)&B{_p=@t=n^H-cwIMrMnt&M=LWS#OBEWqNV^^9XPOGe)F5xF^G)I_U#YgD;@@z zyLQ3$R69^jBT%fI%qsL%1h_I zO-~1hIdSYWZcZ~LciikfE7uFi1+|c<5kuQdem^vguxu(tn>zr7LLm&mFqq1~_;e~= z1a06kx!BQ(-9urxe<&n_!(6gFu09c~f+A0qG}Sc8hUT@hc70OTGpSis;g1QmH`A#flVjX+~*0$?EG(Owe) zvIu~wSi~5NSGqcNTFZ}gNmJ6r(welhPWyKNCj8LEww)i5E?hV-=g-4mxF8)J9j4CX zqt&)8+b}lSrXbW)Pklw|u#+9-f?q>fS#90pQTgcbmhYlW>A;rD(}Dn}0|594lK4nd zEKh^>*jvAylwbV{8c{cM=(B# z;7FTGY!#e#!Ig)sW|UhfK^%@*ii$C@E(#$J0MsA@sU*fRNlZ!-C7^#bHkAostTP6B zOvusC6LRnh-$Qwahrx0|8A72Vslw(mtu;w`a7Pz3+lQr!+C$J7Gt2SP_#zCeUI5a3 z0Gm?rVWd9^-V-E4I5ghEMP-nHb2*qo5Htz)no6@{#F_bb3;acHh$nI8GUuie&}x(3?fjcINx zh~=IEj`bJ?bRn52JB&w7$Whn?WP4ww;B$qMRnix6$amXbSoz95GTN;;lV7BOcX{qM zQb6kq(sR{Q)=`e*ty2wXv;he{gU>Ka`YU zY)3mmREQ`-|6_T<`13iCNo|(UL`84}t#KArHGYns?>5|~~0|T{S z`9X?hC2hFT7>$;*?rR*#27)^rjuS|B zEC&u8kT>3V1C2^r9(r)Mf>2wa4b{@ps)NcDz^EYJO*K3U8}l%Q+P5G|)nQ9k*FOn1+rta@%$P$0K% zvQVtwtgY;zCU?gS%(0Rki;fFV&V*@{5prUY6uSmK^8hlWd~TRYL#~*zxXV8BS;j1`5I#{=9BkWSPwW~>huYcofFcDC% zT5|07Eq%?P-e@D)K|G&l9yqXP_fk}Xa>C{j!82-e*=K(D##1VTHtBE zx~aU*zRf$ipDAE$LXPQJkGpxR_B+~)h5CEj{<7R`cj#=G)jHv|yT4$Z#r6T&cAXD> z0bDN4Y>{od&TC6wd(YNQd%c)r7-M+ymvx@zH+Uof!4Dus(1_vchnuGB8b8>!WWMzVF=Np`tsOB%)X3jZz%_Gxc_|4`m*>T@J%!8df-R`p8>2%pQbM+JFbR6GvoKMHT z+0OHLv~tF|AnPILfs{`jA7YG1ji_J$`qw(&_l%Y2uXXnnh+?BbuLCx8`mE>|@YV6i z;Un_)+iwH7Ij2k5xQwl(r3E|cwCDt%MHw3%gUWx8YDE3!jo%2D@xA!Mi)sjrs?zji z{x5#<3vDo7dg&z{EE3G(S4;bDZoSR4-hKC7A#lZs#*o1oJ>aqkwW*7C|v?>uZ509oVs-g-;l`gLXa?tGcNH{4bVh;`&WZA5Vby=>=_$)%)0S>*u5 z%4$}AA*-HSCIwu)Fat@yZj`|#c^sHdPt(SYU;7n)Xs`njQk;Vnw(mD<&vWB4r@4Ir z(_%cP$H6bp-EnZK*9^BVH?DmiF%g%s+_CLb=16-?$XoL4Kj; zKt2%%a01&=e9qE{r7{#WG@Oqov;#r_?b4-7s-aEI?9*q?sAd%VcWzE%2bo*ix5(zr zTjc4dpO$Za>lxU(YErkO<}blZONHr{4_7rj34SUhBgWN7`DNMpFxDSx#S9u6TX4mJG1*pgUfMSF!G_aT+4ayCXuw6Kx*{TBOz48)5|AJPENUF@ zfYukrS{xIFpdA-3oUye@qv(N9J+!8R0P3PL)Ss5CmnnOGxpZ|zE_9Bd9md8H6KTj? ziBy+V%Gw4PFW(TC4V!$jVIu&lbzw{#N2RcMrmg03NV{tx*S++vUqw^aML{5PkH~M{@l5aVWdos+NSO z8R#DXYj!)rUIyUw@2W)fm%sd_d<;vDr%JF)lO682zx}PEmp}X2&*bRQqfmIh5nsn} z#5NiY)1_!#AM9tJ{Yn1cfBQE~Dn;^xAN)X$ym#OUD^hyw2}jq>W(OOi*bEf9v+(x$9 z@~S7|CB_gI`cU`==F4EB0K-`UKBC~uAMC}maXIyQ3?G7qF6Jn2`s?4VcNK= zO4j3}&%xI^Wd9o-00mabhV>gHANn<>Ao_%9Q$h@j42AQdV+V@H$zy1nEtfZfNdRk@ z1I={G<@`~jch4%PI$K}UA{xJ?!+2GayOx~9a^Ol-pSOx|_1*r7_W)Qst z9H&|1JD>e=QvT&%#^wCg$MUe}7P!BF0Ojum7`0Wy@aNdhfE<5ENu0!5^XScj_Y&VqB2LafT(~STl^T>4+03m>P zu^8$GALv3MC|wT^C9?;34Pi?W6bt`Y5MY#G-6q%^#-WRBN^akc$ela=a^pcixVE65 zF$9pHIA7LQ=Scmg9NDuwEZcX5WkY>JHq@oc4gNEfa2z>6nP><^#c(8hJRf;L%@K&A zzvk1Cl$>(S&CLo%^8;z^+FDl*4amS*^UBqLH5s@R&86i&qpq$_KRU4;+Xu^6uI%6O z0+F^{-`S~oq&rVXB>+h~r$L)Zjr|-$I2X`ZqjF=+v@l51zn7fXJDK9OF=;9Dpe41k zawvUHWqS$ny7@^Ut<|NLbRe?jAk)6R`&1d|p~Hvt6gwW5NJAY_*RNhz(CYk!b9$o9 zF97cR;^SXPX-O$;iE<$Q<3IkRaxLwJ&Zm9Q`Luuketf~)rVCgq@Vo;hA;j_V)Bj2e|Vnj+0-Q zuV2cjFNT8^8^g46e@AG&>}mH586-Wmzk-$opGp57SThx%eHFfv6NpmUuhjN!1oPe0#Bot`JWp!Cdc5JSZ z?OSVP%dQ^Ty1QGdRu`xqtuREWA~ERJ0EbNgA94spg?RD|EDfsI*;Gd0!(8j&=`J+{ z{b%yl*#Rf(hiva?SG#-HZh#zn^kdl%fAm9e-K>WQ9l;yKi@8CQatYIesUd0Rk@fA{>Z-Ad~~5n06Y+Mlw5ILK zo+;@ardVdKR2G%UnyLcXx+yGM8p6`BD=6D`LyQ)u>OqngO56#urhupfb#MXfN+fat zh*DPyl1+dc5NW!4fJh?RLvv%3idxjw0f+)u6ai6!(P~&-sVa4T+20jg1KL-$JGeg4 z)YJ?hsu4g`mDJVOsYo{adZsZvlb==u+lbGwr#`E3W6HC}vO?dVqrY)J&O{5Vv-J9R zG)JVMD?g0%J$WLJnjh(2vI=ykZn$E6aOOv6+KmVU_bg?`2<@D*(s`sh2wN*Kp`1Oh$R!5E;!95h7!hZ4j z3HjnrC#2<3GZe0N=_z?11I#*f_%NP_b@9m-#&scqD4zVng)9HqShdmdOCBuCLO*_t zMGzN;&#*8hD$2%4ol*p%$hk$9&m3ydw84Xo`BgR6Nl`yfnG9Y}g;|Ck+73YIp6(vy z&La?2Sm=)Rbc%~{#5l^vHeyC6L!-BOX5AH212)O9|C4Q(;U_ieMB!C@2sGZd-E6&diaMx!^BrT$rsXCISGSg3LSe zNL3UF45lYtz@w?->s~pTXW>K z{WajwsgYGR!%|*54Bd?oL4(rhAe3>75TplCi$s_wF7`tdDJ9^A`vCk2P$kDtay)T< z#1A>3bkbx^rlir#pp0Jn%quyL z{6Lh7MDQJ!1W|A*J7y(=8wz@-95~7LfRBgW`7+p( zFW;VRgMBQw9+b(|j#?Rp9;rfb6XnDQWo+sJO4%tJuz_2%x>A1fy;btVAFYzwnp~Vd zh4z3YPz38Fp17A6h9dkBm84IoJ~HOR8Ri{g5)cQa4lx2nlT$&paez{^m(EUrLvKQ^ z-RhBR4?1NKZL%<@TFMH_WOZp+*4BVC>a~#UITVum`k>U+A%74Ljf3M)8@wjO_QkZc zmB0ag5`_|kLVi$Gn;W_4o0}Q|L`^_t#76yiNpVnZM~uUJRin%Ptmqoh(TV+l;|16E z7#v$#TEG$4qFm1#Hg3{QDNoqs7?y4_j_YZ`FiN>Llm7BT?!9j7M$?77_=<#04O`O+ zzc#ih`bi2WUPHCf#| zdTNY}>ZKYhBQi5BKmM}4)C{e_#FA}>BR=TQb-n>n?Eh3$P9UnX3P2RZbEnlU>RqLz zFjkmo9{2vAeDaA(Uu8L>GB=1N2ckF_=s1i)oC`c|=E(v{olQJFk0KB}+3wIGazq_c z1d@$|6TyY^=fN4(u8pE*O^v+w!TUHF?|og+a#EmPrZZ>Gs1k87T)Wxp<}Lk90CW zwnK_m5`<{OsfhfdP9RFzHa(6ghPCikCTl--PdAgF|9SR$dDK9Xp6IKbptxY^A`k^@ zhCtM6h-fJgg~7n+?{7N{o29wc*z$LchSujt09vSiL4Z(C0a0iZY!_zcOXu0b&GyXl zwvhBv?{NOrr87VV%wYhcIDsW%4)CFvSQOWj<08X@ak+J4Lha34t#bWNt8@=WrFVjh z^+KsCDU&+rf7-t@D0_G2g7df>98u+xSA-MsiYL%t$XNxh7k~*th*|+r0SLhUp-TV& zPe>ZR^y5?*Bq9bs0!kW2=SlBgL*Sto*6N4xGc2u(HPz1;hUIo;hl>!@IYou@JPEC> zwOv0beE!9st*mrcDPCsZ7wn$V7^RT~FjGdYqkQ?NIoBkcC=ez|ZdPflMek;lV1Qiuqmu@UK? zYz4*yj?uhQDbFvJpS?%*2Su`ZbD^wXn=ge>Ob(<6>nws$P+A{^4ls!55u9QcQ#FWS zK&?VSi06?j3LJHDlq-yRnCqyAw_|euR!pv5>y!&u9!YB(^f`@IK@7A=3UDf6X<-7V z9Ogn#S+4BalLy-6N_i!8nH57PRSpWP39bv;&ZUFQ((PW-I4x&Ac}2*3@HwX zs=_JBX+RW;?tn?C>%qE$_SC6U3Pe$bM;3_6+%}dRh+?*k=v)x-nmRXlVjk_S+qYD7 zF2BH?Qb6{7HUw_^hk;J>D9zmfj|eU`K;*7rTZ4W~-DAzR89QHT>y67R_9=={?G%OM5JA zoZf@Dist?1H@{K#JnD#2(L9ucV3g%0Gl^a;U!!$;sb=y|54W7|jXOd)q5yQVO|orq zf^uI>O0+$5@G@hQgx%B4W9Kf zZ3LkP2M2VqlH`ceFQnK+WA2!*nJw&W&*mF{=5TJKjf`>-!nPYg6o4FWB7;MqHH5Fg z0elgRVJ?l}^tb_tu=h(l^f|WobtxA>K2E9ISi4Gg?WmQVyUJz9j<9Uq0`90{>Qca| zGT?9_$Pfx+E`>sFDn6$rhYtIa>rVt_u-W4rN=_zRD~FSJ&$(6ic{-;WFy%^R^}}K? z9Dcpxy85^0`UC;=h2ID)$=R+)>>uuWf6= zN4OgK{znY}qM*J2U`_zQqT`5iKoqa18D`B@5iT@G(;mCJ7#(<=1x$(G?xxWjr(#SRJVxxewj zAjC!ka`$#G)HZZL(L8|DdnMA+5C7Nz$~q?X6@}o;D#VA)GJKRQlg$v<+psAB&IUY2 zLWuy%n7}dJ5Z7b5`4=QdR16$Z;KJg`fW6Qc)6&!kP;yeHiRJ-7WLu-PIl^C|nf(0E z7kce)*9(0&8-9K@U^Juaz=@cGPz0k^K|G5(XQ>mC>v)bQ7T#hv8kuYUNf+&!ZTfkc z^z@%syelD|nab|>Pp5-Dqrd+d{Yh_*30&tXN0bLdnT{x`ZQ)vFokxG;i1GtbRKHP7^(!<+a!i#BLk1OsP(0Km3q-jpn(cQd5Ann^p&*t*Sg zt>Ic29T1R)PF@(K$l>+tU;kQ91|$&m7k}|f58(2ED3tq^H&$n91x>HJw8u++Yx%Q5 zK6wwCaiW?Dh+_NHL5b~g7NhOnHMUtoWgjhv8X)ayZLFFLh~h_e3(x#p+u^mfCthdG z@~#1+TMCGRjwla^8W`+X4qFFAtx<523)AP-ujdm_GJo?PN6?NHAjjB*cUUfhQ2b+D zWJa2R7}zj2_g!6aX?i#*ckhkMne#nz>S{L>k`IHEXjs;l=F6s<5`Zz)5NBU2yY^Jb zrn<1Ksl^Fvh@WEV7zANsn71K{j=9@$4j^6rYg!y15r!W81rSB!MD1q2=jzYqXzNQ> z4;q2SF@0X;bLCz}0Xa4g;IvDM;N8XA;LMq`0NKv!x?u#$$m=%N33Wh`i~8-OZ>w@* zt|h3$^3%^gmCye4nQY&_4Zzzr`QG=wFF*b1&s2nur|dEvmeYyaxw0v+=K)cgKmB;c zXVz8_p6_7eW9HL8_RD|$uiXGt2t-A28X@#^O{|uQc!gD$Y_EDC2O1vAhws3##_e%@bQ_i)aI+6-@sU^%oLaCuEBa;Ah9~mc!3wOoY5`gnNX_a5 z7WFtmF+K^AJi3L@8wEfO^+-KpF0*d4NQN;d%IP?eI0i=n=;Z?Vqit^)md5)}Y_%xmTXa|o8C63JzT_%rMZY#v#-pf28>?j>RKLS zhU17L5LKZ-6c47M$_@jf7~aMsbD5m~dRp@H>W9JoaHK-9BWj+>D5mp>SbRjD@SO6bSt&fd*g&`rdX%VLoPMAhPQ<60b|?Njo& zbr^aS2jyXVx7>ypY7w}b3cz5qduyeUxm)L61!1^gGhmk`^zx{>o`^xr=ib6Nm$5j5{>cl^+s1Bv2EXy~apk<`rtG@70|02EQM4K87{78oD&L%q;NxMpT)v9a#d^k}I&7T;!mA|@ zoAq4SfYsvgVVtOU6C6_a$K`%Yr!=<>$k0f+^iPyaEdbQj z6?w8_%arWeH6h!!=SaiWGN}Q88pk9Fy;tsG02gO#1K zwV9;`qL`2G0xe%E5M{*mH&IqH{mt?j{Wt*7j|em^IihIYmu3MFRjgkmI0+O$FHc^6 zUMgA+$Tlcrz$ZX3F+PD)R)!VKqUfJfBpQ%1=<+EqD_3-z;1&TWreS$yKJ?2b7wUdv z@tf;^#%l(LWn8pbjwsYeT3uNko6Bljj>ZN8%ctF|i?u!V1F4QEv@>$*sc0U7DC3Bt zyvZ!a;+rK%_R%t`0k#9ujAO%GK$I>}GLYZelD}BlcHpm#<#}xj(;0y%oSJ8>`r1Zx zbNXy$S$wwD z#JQ9rUHnpn4V`|Z!Pw~f0s$({wd`A#7mZ2p;e&8o697)Zm`iRc-Xj`)FTIXXBBTSG z1hp(3=dBwHfKWHC-_V0Z&YnA~z*Ij@K;$WSwC}$Au6+362MR8cBbpz=E<&dyfvXcI zPpI9wV<))5cIhD~KmO^D^@CPA5XHPZ-Bl2E^l?NHfO5?vMJE-@Lp^Ek@pJKfL{5G& z1>H+Ma^qgJJnWs4@!%#@Lai$ZUfoc3SGI4uCqMdVz5M)Vd!(+8A3!Fwo*hs`Ac`?A z28coh!)Oi(62+h&3P6;K=4n3j5Gzl#gFzBa%`v%kHzMDD`$#_f{Hok~I1b=wuY_~A zDo{iK>B-n*8G+rp8eB=+*2){Nm&mdAL(t0!eNW)B3WM8<%vL!7NXJGeVJ9%oLO&CL zAacX!7X+bXoL{P4ngpS!%PSmCKtu{3D)r>S92w{%m>QD@_ebT%EpV0H8I;DB3c1}= zE|X|D5j3Vf4=gOl;deUg`#r;8IVP?9EXK<0oF0b4oc zHOI!rRP@i%p&l1nDl(^~QgWtY`C(oxKN%ZDT3X3Gc$1ATwr2#QoW3hA;4;RYjO-P; z$WT{S&*rX#lKR^OX-6RHaqD9}C84m$iHw?#C+!Ey7b85{QdeGqA%lI!=w()c(oy~E?sPc$agB@j(08-+MkrEJ~0 zO13tX$(C(p0HN}wqC6}`1u5|_70tug$J6k_-aN{=n*fZ8dXXzC2}E(8b@Zp}Kqu#6 z{(K4&B*UfdEu0sDi{|NHJSM007(Q%0c=!;9lw6R@S1!w~Tenn~WFd4y@k0Vn)upB0 z$?ZF~gFC7mX+lXgIIF2Dz(G&4K1w?HE5G4jgks}J?|C(-!Hk`NAx~$Cb%XN^OyBI*P ziCmIy-uueyrYvKc3yL{kj`w2XkeYzn%juym7&DRM%A+paK#b)N$+ zxul@Nd5VCBpo@$)i2MMm!a+Ad0j?^tqMWjFKM-XR&q$x=*90sn z=enjg-S0boM|#niJ5zNSt;}Wk=LJMroHM1J^;n)VW9gt+OU0q#CAgUPp#mEU&&QtS> zp~w(o0|cXz?_?-ovQ1@pmi1bGHNdv2^qdb6<%u56rxe+CFrQjlnlLs#aX#YWWZ3~x z$&D`S2kkQmz<|~aIdNz)cHt@JB`A}g09O)#s2ptSbMkRS@nb07Z;Q)?b8Yg?sV2GC zGAW%S1=0b%M57S^64+cH+ypL?9SM2u@EUmy93<7%xmb(^q!8~H@M8|@CViMEp9pQr zFb4=lKm&aVKdDE_D}pxO0Gsri`C_iVV_&uhc=B9N4^F(h07c;cDd#Sn2T;+iAE+9( zG|1M?4RZXW4`Gi(Z%~bLxAFrO^GRKR7cN}T6Y~f{@mS{haYVU%YpH#7;<7@i!D4zQ zSq?r!Tf25SB42;yfT&A107UhGI|wJ{O@!8fhM*@ng{A>ff97#SDG-%XR_=5}`99Xo zt7@kMQI<#2%jgyW2b%()-oq(0xe2tX#)m_4?p(K=J3B7lTrQD29gx*j(L9LT;q*CS z-pLt<)9DUWj>^%)1MY6M<7ndK%7bEY)J+uWPY=A}9h!0o z*0pj+L*|<0qf4`}_Uzu7{WsZGW)GHq`iwPT^~^R;OAzWQAPOJCO-B?-ZtrAF+SlJR zK3}Y-HMPaQ|BAk6bepYsMlW;u&hr4GEWX*&&OTdyH9-2)WPzxcLz^WBqF78Ly1&z! zALj3Q89)OwhQstRB21JpIi(gWbVB0KdXNrEs`DG}d(b?RU zP$sqmZ3}F2unI&yavV`qUPvISth`KtDC3BlsqM_0#c0sw@B5QvN|ad4STLCN%!frRwK zKDZAZP!9&={@p?7g&LIJA&9gCyh?-sHWijg<*GtCxIYN6Ab_%#%0}oSDlCSAXh>$M z-X64lazAMnePcaE=~N<5^UEJT^p(e3^y!Pqaxn;D8X8|&)x&#NpRp?Jx#t1LXlDJC zoKUp)@7>o^bT41NEEg|bl*f--A?B3>y;h}i@ZceNZU1YsbN4PNu->VMn2_T-1Wq1i zqz3@j;y9u#Uj|0FduCg6PS=W%bUDXJ3W&PUBNwkX%LANDHxb?l9Or3{s2_f`PX0Uz zL{Udn3Wy^89T>&5nV@rcH?wi|?CR31a|6+O1=F6VrlF#TkFJ94WUM5qUpVy1oKntz`t84ZH zT5?1+H8oA=i1L7_IqB!8^@4LU#|!gpJ9EVH%00HZV6K80of*z(&A!Ps9d!#oYHoqv zVk#?NrPh>{8wX5!{QmgTpJnftcMVvZSrQ=XJJ^qx1rU{~Nm@hTGrLwm$s>}#liRhq z{`fMzYkmx8@6fet|8tAWp4t6uF5lPi7{ulRqQYS)z~tma%d%M`c&a^!A-?2lK1vr3|I?1&z~b$8nl;9~mCe6Iglh#n8~; z3jv}OhT=S+7Gnt79R?F-z*)@1ovE!_6=ZqDes1 zX?!Fhx9@;M1orCn$FQx^)dTUPVRAObr6?~dRTTxYdDB{Of2@|*-^_u9!f9}%&@#HX zCj!W{nFp62=EE6^Sp}iH$L>Avl%wV1i&g+HB+JB0jTjf)&?`6ve8%NZ+b4dGIlicZtfl=Nq^G?$7CypD!FB6d%^gvC? z{rge*#bk&S=Q7Ib@O|iNnv$RWV5fX=tPTL@xD=L- zOBiEl7>Cg00_deBt(km+B8>|65b)7x5TDf^Jy_FxhLanSmx-~2OagSBn#z^QNRC{+ z6qT!2qG$(wa`{e|JQvdJ+kMjtgqde@=Gzuuwi%5 zeC4ouHrMxP*<2d^EswnCGSK zJ_ST!F=O;+;?|a)OGdJhypS3&8kuYTUK2xqPXbW`g9<_o0*oTvpNS*N8%{J09Vaoy zs2_ez{7Jz8Y_9bIHa*^Rf&k1TU3$6AEkK9>K_~}A1>%@z;`#8yh8eGpk0zwEB`&Q^ zQMqwvNN(I6lIE5HX?ol*V-o==8qbkc1p!%K8XPrk;$&=wu#zO2dx; zlarHb@7}#D_wL>U7t|$);y9=S>ID)wn95{!-4fPuI1MR^HYP*$_k$NMOV>}~6 zlmwzKUAzR5vvWyh({Nv>2Ww!4*Ay)7KSh|4wQj^PZ@YI zE!L0AxdzpcNg(Px(gsJ=9dJZVh3WuAkqgJgWTJTlqJI8oyQOYZ86HLOkabQmH4xmh zn!XYaUKz6DVod)_SolAE}m%swjEh(MSu%uGbU4nE;cXu}e0{?w}@5Ot+ zm-GGXoHKJ~&^_3~&F=_BLHHNx8mA%rfPX%3amYS5m&i*EK7^lD(0L+>Q&SbV)J8_p zL_2N2WN7fcWSgR*?DCrNW8?Ql`^cqAI>aPn`6(mt6^(B}~a)=xy}$1R7E& zD7@jSIh0bGIT^=X)AEyBWI%t6nt4aS`tKbsmo6|BTp zeq}Te?~A>23Uy7n!8}mgH`i!~=k53B&p~2ey;1(LiTOPpW&~pm@spG6Wzhh_z*_ zM%j_$74f}k8G5!+GXMYtD1xN4_ieqN)@Qgsa+mgK5uUlDD=-d|B4R%C*q+nbu~83(|BE9K*KZM44@p%3eXTMNuv8|@zn}~NxKJYR@nT~ zZM48dSN(_>>{Qm^5j!+wMeU2#0)W$;uloMwn~nbG3!Kq`wgRVBK%(Fih`N~|Dl0iI z`=t0YCs0aNFs*6li}dsu>hLDKoiGv=npj;`vL$&9xHI*$`!3i-x8UnUqpeK!<*P4=WQK+Fd4hzxTO`j#{j$)!E@=>R@4eN~Q4?f8Yk4_2sTx~~x9MZcN3kL8K->8?aaVok*Tzj0^>LsBHreNy`?HY{3$`uU9r+)qH#BUvhV&vaFMD7d9XzZl(T5BARq@$HPq+s{eV z8^)6}eYO`FrO1oA_KMuoL4vd~#ze+rW3ydx`>zN4&HN>!r49m#YLSd_Es}_9I{cG6 zQRL+0zMubyeS#s`Jcn@}ROF0#REV?{k=M|qxz&_iVN*s)xnl6|Dud!q*dI-dNBY6k zpHKdyhNuLliHLf^^Y`z(Ob1=)LnWhN`}6ZuKXuU(RQp{^5@RD%mJ{8KO{)%Lm?Q)< zRql;OJV6ZVs}VQRX#ou{9<(umqWzAqk732)GM`vdT;EH!jlIN1TsTtB$h0mre!~0C>Px#aFP4b2{ymN6#XOSVi8X`1+4i| z7vfJ^ZqZB_QCi&QomN@Fmh5GAknTTm(LcjtuCXTlwK+9pchv|nj zcZ|5dXAp9~LGKxmY5*hj7WX+5^TGU*m?OE_eZogI%IE7eY4dshN94n4=*QTjlfBWt zaNjrZ6VFzL$@HTLo+G9rsihvCQk{NyQG!S8P-X3wagyL7sfuv6vmOg;*}Q;+7fF^A z%>J85j1Pp|WWoWMA1Q5Y{A?`h&gz z)@=*NL}fdlLyw($Mnet>Zurk8g4&0whNXLRf!dB$6%WPfiIW?c0}OYx_?sM-+B!W6 z2MPVM94g}2AmEEPY#QY0z4h?R4$bnu;PBjUi4(qC(4b_;#>Q=vat-*RO~*e-eK<&l zg@yk6sla(S_?81y(xD22ohzMx3WABuH+(34EQjzcPHa$J$g@XP|wR) z;n1h=aiA1Px6ek5A{fCNx2;F|+9M@fO<_hCa6=mK=(Oxk5`Gbmnek~zs0ZPAyZc2vAqkPPvoj~K{N;M0{bEQW7~Ck(_^W2s;j#+> zo#U7G2rNha8&_8IGa0N!IH@me9tVgC{~0l#l5=<*xl;)T0iY=D3%_-nCHZUU>V$A17U~nKGU}vWljLf4Q6KqD!P~kX^As6H?d$_aG!6zYE&YTAtD1)SBDD|& zVq(Ln|BsdO98ZzQO~(G=Byey6p8h?W;jdn7fMrvs4%Kzd8S!1877A9PCSascbI4$X zam9N?xdvud!btBlvBI(dGE;UyKve=5}$JBhNfikf5atgZ}4rz*&C> zRvA*q@_j?xH`;#3yoO&hzG``5tU=GsK_951;6J!%8i+9TAeLVB-VIv1*{>rASR&8Upw z)ajWr%!?s@Pp9-ih`X1XrX@f0bN~Rk5nyq^N4s_uI8x(s{z8;eUK5&-rtF73K;O{( zfj^5-;b__5@ZK+?^1uoR`A+)&+?ky5=6n=nGz*wv5V}wszC2_ji%+G;>PLV1u)^+V zeY0#DtU&~e={d0q2&g55%OB>fbN*1q;@G^O%*>u*(KTNDYkKf}tWiU~^_9gRM-ih0 zg?_3^+(bJ)FdPx(nwIdR5KMvD?e>H0ue`rLTXIPwaIo`MI6gVH=5EP14cfu-c|Kg3 z{^?B7-^GI?6C1m2)bzVZ0}xUYpHaTvni+JJc#z!64siA+frjdic?ihT1Rrh?hfKGYCo)9>*{vM z7|BixNGQeHjiwPIiLN@q5wrSZ(Gu3$`WA1pVr)_U*zM%?eI^KRud#N0)rw3?!c<5= z@OvEu0Xj0Gl%`DIF$?wKhVpeey7`)DACLl0iiH+@N-O;Z<5_fd>Z-i&(gWX2Dkkd&vs;ijXuY1;nuAVVuK%J#*5 zD|2v5N`!fFni@JlD6HLf)b?2=C)Wjqd%vD8oIGlI0`=^pkw$W$KCf$~?~YsROEO_~ z6Yc#1<_!m?FdGsH8VD~Ex;0?jT#FdvVX2<6s_|V_!gEhprVHa!TVYP-DmV$>>H4d+ zISU;EgWF+m^yu7Iv{p|q{d4i-q={EWC;w4KZhelqcXZ#mFh+YjQy`m-ir*`^0p+^z zYhrZ6tihl1jH_e6QDiVMUk?(s8#QWm44L>=c<+Wj3if@#P?p3fAD{iphe{=2jaHtP$CV2wz#j9d*K)9zN&A8u{d zi8<_~*<{>RcV|{|ogL#ypqE6b5ANevc`0UYYNUorCk2`J4n#e-VpBqS{n4d*0JN)xmE>Fu3#15@{Q(PAFRRwXK3!*w#L18u)Wq%|?%|E} zHW68r(ByZsOt9|f6HbABko#rp1fcxjL&{zjNnBaH4h2RI@m$O48D1u{9MsW+vR{xI zXXC60xhb_j)zWq~QmzkhLwEq$@M(ITUYo~tKdkFNS5wdkJyVqNMh@4N>=A=*Y;U6omjQ19AXOoU+~ZFs{~{pGL@$ z5NmS|l3;7;7>pfFuxLmM;~-sI7RptxsL$D^AuAUO&PSwPl?GLPriuG;@+SY{g{GLB z!b7-Q7X&Cg+7zaFYQC;1Z>fl&*S8O6Tgn{<$G2u6@RFDP*j{6L${BW?3oMhHnb~H1 zq#CX!CHemAR+Q2O&d~#VJ4Dy!{N=^F8ed=E{XYW)L3pdX^*xbq9ukyTQRTnKo&Pl? zasd%KFgQpQ_0-<|+|Ge(P1G1_@+nloiz`AzgB5q~NneN-R+@O()DR2QE(|PbMsr>+ zwL;2x(}4v=m<4sKa_5I%wPUJ3aT7*mapvB7)IW@tA;;dY8YG`{!>9^Z5+d{`-ClYs zB@^O1N)p0+NRfI5d;08sx(|QJSV|ufp9p+X(K+gAYA`D*dOO`d5^aGOK6!DWosTLt z=mH(X`lL;4se{gJ-Jh95K0cfd0?%6{7W{sTWd!|2R0`gB)e6jwLzv zk==UoUexC#4&rmsXS~!D2F+H$dGig;W-1@%m3Tb5va0Xsn~Wk#EOOPhGklA33gcNJPQL*W zs;UE4m}QFC_ZDgwvBM=5xezqpqGg)2p`v*FBMOQ{<`ff6eCiB=5~-!u5|G3{a{^$u zp+To0$DE@{fEGYGZ;TH<|eiY#1N|&MK!2j}p&pl$|Jt-^h&B zP#<);G#P#zr|g_DJNtjmmevbB6-jrxzF4#D0ftdtR*LE&f6Y25c!)>EA z{~>p#Zll|qHf9R-t)=kuwqa8t)6`B6b#;~-(wDGtj)*Wk=;i>~piNr|FJskD9HS@m zd|)agBaYz>9X3%!IavCKdsv+#LQl+-@nI{Pa)3$vtTWbdDRRy?6ehfMUQ_@ZkeA){ z825{k#w==(T7Q&%icHLa;Mi@^RiE0rmaN69)~n%A>g1|kn@DqUhe9eb1H%Z~-0CdH zg3D^~-z}Y1$X<+?x2xIjB4yY9`)v93&=xw-6*+lvb(h+pJ-h*30o?2vv>+Xae|nWC zr7Knf19xxxhW_S*E_WWPjTjGlj7(vMpOo(h_mUm3L_bFRZui@3dQQ9eeX3pF7%B*E zQ_7HI9yY;`#b)1#IkcUAce&Q&)&!<5AZv8#(_@-59e&H5l5;Uj7|wO%eSDJ6@W;*t z9&s9{u&XOfePZ&1!D3 znq^i!(V;m$n$bHe6oNV<@yx5p0;L{bkeI$ z0nqY(8bGSNAG`(}0Gya2E4)9qvAFi(b)zIt*#rCbDOS>q{bhN;*S$*2&@}d|0quyx zE|EuPZDxZRChlGh-bw!cQ@(YLnJE?vr_^LP>B;kd`w`>=>U$E+SRw*J3=n6s_PoY; zqusxh_xUht;0dx0VW}udJ4>!^fa&`LP@k%*MMSyUUN|8_!lksdjPY^?whz3VI8V$+ z-@4#bN2&Y%{53f{a0h^W9ygnMkmXlKDD8{iWpC{ISoW%aUh-zm4532Nv?y*{@L}G1rEInq0uRA>Za4ZWCFH~P}f$c z?<}d7E{MB#LI|2TNz8`FEyI!36s5;K?w@Ah?*cod9m;S$AON zV4MBR#KfFxDIi4hQ4criAq<=a#~nC2_8tLDj8~s4NZoReWD4y;72cF<_=IM9>vf>y zWt8XdUaI_hCi!V3Gus^j?9v6MyP%m&ilEx8mLk)SwS`47JeKvAd%!MVS(>mL)Pvcy z5o8PaF*mtY!1sf=B3~p*C)FEAy5Ft}jXw=1)#_70Bc=Ilh?!_C9g(sYXnS&M4_hcV zM6l!Q(EysVbpfLe-wm)n?EpjuOWlQ#hz_sl{|x;D5<=wzIq>Fva-d&E+zyqJgCTdq zw+8R%ha9n;fv=Y|TGx@1DvC2jYDcHeX|IJW!bM8fVy29;h5iP5nzS@Q#73maGbr#=xQeMzlB$K`i)4jf*6SB6oB`7F3C4?f(~F zj5EO9OgfqS9ohoPl5L0JR;#GQe{#Ka*gNHZ3Q>jUZ~%B#T_I(i#5@1I*~tvSO)8{`D3J$qv_SdUeJ72sRysN!L1%{##|<3853QBKL2*3 zL*X9_#SDzVOjs1`y#|^b?GMOSD-(eDq5(9=G^ycXPkJ9?Bm*A-<~Cv5-aE7CeOlH4 z9wEGZ3-E9M%Sp@=(2U$Pq0hmp@AJKLE94PfxUhOSE?cO$vxq8KUPBU*Qq+SKy#r^5 zvDL%@1H&!LoHUqvJ8r8Fu80X$*7}CLS%}y>T!n~~dXgaO*W-7XKD$#)&T4J)-n;!10R1Ywl`){7${93>@}_HxBO<=B%P( zR+rnGFZyU7vCfiShW?{!UE~{sO9$Gei*l{giXps-E?#ikPI9*VPqYH#U;qJs6>|;? z%MFRuzY)A}ivA)_iX*-Rm4yvLGKn=6N68}`vtOMhF6YV$*CmV=mS%0)h|sKp%8pt^ z9iB>~X6!QNbo5@Qc)C+lgZfa%U@Dx51~XLLJ&Dy8ub1vqiWgCKadZ?s?|W&$23R0*3Xt2ToRP2tSmvLRYTFrI)TRb@WG;=E0Lc*D_O4%06bP` zu}@3wiS!R7NCQGYur(7;bJi-8c3Z7q&L1mw`E(E6(!p9qBzIJ9?ooys)s0bo_#(K3ndIznWz1b2fej;+!BIL9DxEU>0W>Xzg@cs?cL77fZJdIDN?O-G$9HuSG}G; z*}LwoH4dg1{*A@VBu%ac!JsA7MGZ!B4p{|@27-<5jqM`$IEzjW`_iR{26_b%!K*|@ zF>VUrFKVqPEaW6%`c$Xm6rGS)V-&(#l)V%7Ifxe^$APd>MjSEJ!hm3`_n9kB{}wK| z?*!rzRQs=nh9=SSqB7+dTd?>Z>IInwexqE&_%WfU0wC(~a+zO)c{W6RkRjO8X%=09 z*X8d_kg&FB4e>U_&6Q1H?Ia_6p*`u~TaH);x1JxWoz#_&x%6>?p7YCba7RG7QhXPf z^F$D(#38^qMj3n|GUbTWBn{zunrYfEu>xxUxXl-)Ldrrcj*NVE^5ve?HgQz>e#M_!IA84`%rERL0q@ z#Hk<9CPYT~dSneT1-Q)vR)UAx`;#i#k->M6k( zKjy8e7S(NSQYnP0eO`dtXvECM1*sVs%(6F57TYc)qiqEnNn?*kA{5RXIU93eGpTvo}{>*6%=+oRF;B?Vu#LnLF4lOHJh3ALEMc`p7+?Myj?L*MRB?LYI zYp-`ucNaGnN>@zICbdy%xw2olG$U0452z%P0IG!_&hRI-nW2cda|f?0loW zrfes`Z{O(X{CvK(`A3@)_UQ)qGY(~N==DpT%Lbe)$CtTd@+4#Kzn1B!AQ38Xyz)rh zH%gpJ^vg{jcTnroo#w14+@(}J3k|M-U=GH4p}z=LJggTZg937#j1#q8;m>`oan^JU zS*rESr3|Ro47`2$xYUZU{S5&1#x)@YYGZSN)k48aE)DPW)Fjk;ZE`i+-IQ*zD}?O(<ML&r#)zY5K@A7T~T)ko%m^O@5WCj zV=CZ;JXpu`iK6PdEY4#pzUnddop#T|hyWvoOF&mq6#`0OgX6};_&E5}(8#gUAzVax zBL$P@jL7-p>+Ejok9|6M!c2`iO7Q!IK;o#Z)=xG8AF<}(mpX$WrDnPYt#eZ&UU35) z(P~^d4dyUFyP?I45B~ZBLw2=D<`OV1H!ODZSMolaUE3kC#}=jU3a56#U&PWJ35USS)%~A!slu?~S2OKd+M7Rxm_Eh(gc_u-K#= zPaS~5Tt$_BJU91KhcptcCvj$gmF3~V>+P=LW8yqZH@Wa6Jm}p{W_qxf%<>KXCP)-l zKp^ky49?A7MNRwe+us8U$hJQ@?(YYti|-~Fon}}kj=P=B6??WpUF7D*wT!{L8bU%I zj>-UfD-{?^M=$j(bXFZbEaKf6vzsQlt;W;WDmYn2hm)yMvFrXT82hXk#VZryMOokg zMaB8bNDL>Q)GZg)mHQ^Q3*WC;vwD`~nA@kBqs1BiGc3w3*8NbM!l`JMcyA={&J$v% z-bne(!x*`Nu1u%)lbxe*o*#eAT5QRN(7dsZjv6N0=h&VSzti%M`NYTHSF1IRAQ-B3 zS2|EMeanN5w6D>I{rk#!N_~D_fMvY%_q3=nBN2dcp7B6?Y53+-jT5a6Z8_Q~K zFzj;R-qAY-Mep1{QQLQu(z10*7H@F79d)G)8%gG=Z*f+(&L4bO`A~wud_A2X{5})w zZ*K)DO5q_jP7-_7QeelUH9n2@-#@XyS;>EWk}ytSfSQN|wfUa2L~S6`$n$w}z%C5u zr4E?-A7Eej=ciq#Lf+xd{TLZxK$l1h)iDYw{|ErvAqesqwCg_#Tpg!wvS!(^WWn}T z%aip$?TBSxfzH_b(+e0ooF=G;4Zakc8oh9`>Sa4(p&vq-S6c?Q7h9x_S-*^*ATr+l z>`IbzwOtLE;%=sm@w!n0Qa8z!xcH;e&X!mHIx?}|{IytLB6sgp1*fOMC0r=2sr41h z%>vaospa9F0+31@JLcoDXhAE6R|dAG_g4;z8Got#laje+1Z0+K(#UTHAUS#YG>l_v z;lhbL5eD0dyrhs2xXf4;#j`AdIl1B*J_p&WDHEFE-F>}cmICW$DW(s~{oeun-D<_iut-9*BzqO^Ygymy# z#YU`m2<@xJmvWXi`GTmX9XCRH-;^mb0j>Z9hUq`==@wjwhmM$H#-I`w4>fWdj;O<* z0h%jr_||LbKWCvAIyxykNiW#O_NlRqucKnH1m1RS{fXI5%)d7wiFs}Uj$TJ0YeT(d z96@Y^^y+KHb27)hzpD3Vnn;LurX!mK^Ujw``C&u7c$}#|cE_vqGVGBf(H-R$_y`jZ z6lZ^BIRzZEC<-EijPw_~PyLLMINWE3a+C z21D=I9bZ|EfHsERL(aFC6n9y*^ZBtN5&B;H_4P>;}*XY$sibV z8*8tX&2Oy~_n}yQhTd)eVRv@K1@VR>5MpKf@E}{PWN*K20!xEtK37*#mL9#Q9PPLoJNR%hY9&5#8F42Q zQU9~jh3%D+oILrw`jbci%m@+i?e< z|I|hy09 zK#YjQWzkoZBJO-FWs``-F7V9op#-(WKo?H6f>nJCTn8<#TUb%cg@(fCQ*1@*e$*Ra zmbW>6098*;Y4kd(iS~~%F}UB4=_tm+`jd5Itti}oW8*Lmrz*+&Luhd9ru`yR{US|Y z_2IuFmfD;OshEe8Q+Q3Atfbn6loKf}K3ZkJpvWE2#G;6rnZNpkB1jq<8d^DdU`F~? zCdcRyp-Yp>kMUQNUId&_>^t-?wM#4#1?S4!O@hLy;2*G#-OO3`kOZEL<)AYR2 z$oO=EBIb(&C=LvyMa)7&FyBO_pqcZ6-Q=r;5X`Yl;i|z?>B8kI@C7d9^m=YF9C%Vb8FcbNAofhw1sqnVs!-$u!l8jj*&p zIJ0By&UEHT(@7Lsg52$~ z83s_${xyKMS8~G5T=ViUQ@5XlrgO6$!s5E#k1&fT5VK2ZJDx)cE|$fQGGy>PX&QZY z(HkD@9)iO~LORt7=8ak-#ognUq|i^^*PXI2$-jvh|9rj=#3ec-rF7ms$B2O2?7=4` zJk*I%4X3*%PTwDJd)%>2*c+|+dE{7=YJ{Mp87xLjYn*6Km{`h6Xd^627al^l^ljr^ z_Cowf{>zfhc`TERzde!kxJ~84HokK?v5o^d5NM#~7M)Ccv!rBE@N;K*dgpyJNNkr2qGa=;` zvRhR|kAk!FWkkp4r?4Bhtx9MEAX?!9MCn_)jdYAJ{LTkeS{w_Mw8CzUFNTE6q@%qW z))(_z7vE8w2k|6~3p2RPqm2_eHmi1{MO$~bCJua5?W_cQz+xCr{_&mN;Y`082t)sN z-C?;OWP~`CADH|HOp2QSfEg$SOcnY$(T{g`(EZolKWb<+FYACofjH_~XF!^(s`i@d zO#p@Jt*0KBR%z#Ip7d3iIJw4Ykwgzc&bB0u^KcVJ)Ua^U7FgwHe?V9{d(RV?0)8L( z*LRN=Aea8}NdL!^6JGMag~7O{Wz9T8QRk;~;DbS0n&o?CK(x%46;w$4CKj=vaP=A% zs<#ps;u>>bc(bD=0NO#tm=Itqrd8yYlSiE7hl5;L;HPm8#6Q7~PjNY+PMmn9&WzG* zecyjRqFj(|Bd(@q#L)ivU?{%Rg0=U%$!}|6_1KY|VcuVl(FVOVAuQuG*QHA{eiFIA zd1%k*RqLn&E|{MQ_;!u~XtWe#?4BH$*w`aQ@(H`!;a?$-*Ve6Z=q>IK*gd71;%FC} zAq%^lr`OFcD_mk~opp7ZkQ>OI!X0TaN2mb@_vo?Gg)(J^A+sUg%*)-x4}|ltyHOtv z)exO9N#R3Sm@o_c;GjNpL;?VtrePHM_W+pdNb5?Bld$OXRsE@oZEeJv@A>}bzyxV< z4vP~DqB$<{C0h>-3l9o_p;r3v1%0!BP^uN;qdk$2HLTa{YDjfkB#X-=q)qFiVajFK zh*%UFO~R@dabo6i+ed*JW#`L+>C$JCF{eXq$|ZZE1&f&mQCl4!aVkSKqsH{5Q@W3EVlX zQ=EzLPY&ai08@=D3!+=-fLBn9SZ;S%xd!k|?FRyT&?A!pBuMbV}0$y)2!g9I0dhW;>6>|SmO)YYn41&D7; zKeee{15n^8<5!Toy$ASP_NPy`L>t|Ht1|TkH++q+B17g3G`Wg z(*Lv`99T?X#^@=1hjS~#`iRXEwod1Q@J00g+^^1Uhl!Pi1rVtef3Hr+Z_h6=TN9+F zs{Vm&G04KLC*Ti|kd+8079sx&KF=g>R18pl_Iphs!!b>bj67jl+6Cg)F$bz{hqi8@ zo-Q2jl4iS(gnv6e)Tb2^MF|F5QDOzt5@LV8A%myl$RV0~u!GB(|Ge)TzBS}Vh_Fb2 zJgABKLQ75)wq6eIAWzTH$W)0xQ1p}6rWT7DDtp^#`FB72_RkN#Bgy(P80TD{;5z3TxTq=b<@A-d0~B zMk>q7TQSzi`Vt5IV?nhL#~QhN>hh#G*g1(kLkkgx2D1gk6|N;_j}~Y1RoZuiRd)H2 zuY^#G=lHvE+t_!Z_n6-@4fZj3h{L;I+Ly|2KOv$odP!2m$TBCvj(X=mF(PGj zQoxWsz!?zofdpnuSiWWl3(C*fi7I>AZQSbKbj%0FBPqdl6D8B8h4S-i9_}b@ljC@M z^Q5Rh5x(QC-2b9o>n)7lx#PbwJ&2!ZG#a4i|m-4 zD{Zk)q%wuL9=LcOmzdXSyy6$NK@&}SvyG760BRs%uRz6YnQUPmGW25#06Or!vcu%{ z{H<*}HEom{*Hf7-TUb?%iAKp_n9X(FDHUhEGSMv1n6`#yLW&BIO2-7pj%b~XxGNf- zr`x0Lfze8jMs{Kxv4sjsI$`qA>fZ99g(AzI6;?oQ{&sSNY+FDhz{GE~~#l~v`50y;#H(@uJkdnsNuHB3cMA~@<@ z^neLCu&!EzUubvM(HJn59VZAZ&p{ewek7wz`=hay%y*Q@S}UM)w%R1J1Hmdx*i`xC zCx4%5D`m>f!A?tlYHuMp*v1l9J|_|StK4Zxn>G7{-TI-L-j$1Z)R2wWjA}~jjxY+j zhf-$MEeAJ~Vj@HA(Eoi3t-{v>{^dvk7hO3q8C4`y>7)(3;Iy#9OrKkyr*RAXCu}q8 zeszj_x*)SFGf666>!(Fwi|VvrapN$h_jo7Gqtixxd8JJp161Xt^!&_QV@pxbQQ10) z4pLQ7DJO@62L}WMT5br}DgP03b(XXiwwn2Na&G$gzjqwpNJd}*YQgXzbPKc4 z2-IJj6g5sS%-g%#B0z;RmkMBOVD@f7(>Q#Uq9aV%I+*wCSwzqW_I*Ss`Tg#QyI)O& zShQ)-Dpm9$K=Bcwj6bpm3U=v7jH9J{-8j&b7z&WZsJ*Q;iV4t%vo8jB2j)nHLz(vE zEc1;I5Br*^L_eE*X;&q$WxHywhR`ns@zY|phiV$&B~Q~Q{i%g(6!C!@4*68>TCO2< zwR(xtOWx;xJ%-CT)NuZXE`F~u*n^Bm{IUT+mUkmQsV`pIexKtx`kN*#xmo;E%2yKZ zk%Rmou8bPv2*}|lG75^62u`dzPxmm&w?mo59nJbuxw|W*OH(U0`1l`R0^P=Xj|69~ zv(jBg`zm+p(y-3m;h-IHfpr}-g8#^Z%UJ>Z1c*@TQRcS;*~b|JfJgL84^fi=p?RDi z;tG6Xk+yC|brKGC#^~EWx5AD`CgOIa0?FmzP<%!6&{ZL|15I*IEw_mqhtj5$SJA%T zydGn9IW8s#9rtfwkK z=1jQDc9Lk5xa(p;I6uN?#ji%(5<3_7ZodtO6;}`(4U?ii(DqXyZugLq^~9ACi4w4|U;yskqC33*hZw7AGw@pdv0M?IM4&RtUuc5R(FQ z7`{dI76AZC9jj0`s|@$~6=^6*(8Z0T**o;v8;9Zf@Qc1PQg$QP^MsWE4n3KyD8U@* zVoNRJv~!K{YIJrb!*L^o{SowwEGT`!Id)+_o1&~euw4n5x*3J9*WZdyw7<6FH4-!D z2ni$gDDxtqLf$ki@k}%`%Cq2A zW3VfxYA?22K_w0P7>@H;l6ZUH^?VY<=iv<9pqq=vSdP$-;edc+IWjL#q5ms#G@nUh z2XfSxO2(I#*qM?XlBjQV+|N(b!qE9Ej{(#?jSV6I?V+!Oi>kto%wlPvy@NvrN}LSj z!9wHwE@~IKXv&8u=`34!xQVl(*usc6xSrlsFWmZN8F1Ss%D-)o&-P8k}3MuiW?+`3ndq4W#_5 ziBceQH$;!Md|8gavk0Q-FI9Jb44K#l>FHv5W92tYLO@j<)8nZ|CxiRTi)pMKFx;xq zqKk%On5;;8$csrd- zqF+nWJk35~kyfP%Hfe^zZtqOFsPb$bU_3*npLpQHK@xV5`hIq?;=sA#0NZ&BNZ1_4 z0~f3zHMEMp-VkBd zu)g8gp|W7CT)3noDJp8nGPy zupTt|_!QyG&o3xEj5|r&I&!0ZGrfnr(v|6WBGyL&2dY{?d{CpKWW{Au!LjVY#iJq}tZf-`q_{Ke|Cil{=>A}wy? z#5Wf!QQ_}&5(SeCBSzox>PcM?}=ez zs_uNA#N{%}>RWP&xq691l_No}{mJv?x=v|UPxqs`p1}P@b??=Vwvc$PI*@I9*5jR& z4ZzcaKYw6Zzy^M9R{vEmn-OWR$N7vk)?>oAB2W`Oc3=|evwNtwr-@i_hB5iLLS0Cs zAZ8$SGY(xn(k^54#c%CbjThVz_OxuH-+j)>-ky12u?wF@`Qt_1!Oyx-oDD9Pb2oVr7JMZzWmyH{9|*$o%{Xu{|)4T)jfJztPyeRu+tg-px4;lh z&W1AAg9$37khR~f?gy85LS~kBc2Pd%5Phw$eUUgjLv&A;@@}__cuGM;AB@1Eb58zZ z?IP5up<*miY3hiKk3>0>Wb%-wK!w z$vCAAq~5LXb^OiFAH3Rc=Z{!32_4W4!PP`cW6UcrsWX$nwbqhn6qr;#K+LuKgldx% z8CyA%FaC_Xk>?XUs;Aikc^^UdSs-uI-Vf1A>rpjIzJe96MB$!>fMuLw@HvwF>gJ)H zRX|U6#R7gu_>HwP`2fhGsk0eP4m?=i-Dju?h-PujQP$EmWochah>hKmnzS6W^0=^* zaWtZuDb2Ku@cHTu%?DUki^Bs`w7w#0maz~ueyKRXU|GxPuaXyUSzqa+D+khR#>Z#* zdNlECv?ZN9+2uG-F!UJ4W-XJJw4&1NrSPpHXljq9c<4!~utgv);4jN83g-4JUU)@& z-k45j#JDjZq6O2F?giV+*}5Z38`vdl5I;>KE>uEIhsa0g^Yln<{SIOGzM7rvX%-XW%u8RwIZa#isKyH$y-didL3_3&ty*tuEj7}`m`h^IJ<}D6jp^0j9 zW03M}K#YTMZ%2+|v`7l8X7iiq$pbpi2A*Zj>l!lEXN`L2*_ydDIg@NI5IzuKvYGZ1}Iz z`pG$3Vj=OO-zHk_R;ot-E}_g6XPidh?Jk04?}W&Z%y#whgQwlID11NP9kvePz=aGZf!tz`&o!B|Jif1Y9`J5A`Jd?4aS|_`s>qvuf8_8azf4y z68>VNfWC7kf7=cck{3~D=vc^F5KGowO<_)HS$Kc=y4~r>tlsU&93a95>$6*E*WN_W z%#bhu4VR1Uf3S8Dd1})iD{iH@&kdezJ%~`_ z12NzXRSXcINoYE0pO4-q@S~^~^d|bknflJTLe4&Ck59%@DIXowin6w|HK|)1+$~~% zDnskQj=i}oxFTwroh&|Z&E6o;4G$_={ob*cwpU(NVS)vE{B6IkAZ>Kd_70B-9=vo! z8H*KCPAeejN|jUDI~YpS69fBhXg!SQc9gj}pLBrQvLbBk|Hsr@cD31X!NSG8 zxNFhi?p{1-(Bc$#clYA7xJz&-?heI@I~2DDcQ5+pe$IQ=IzJ#;`LM5@xn^e1Fm0fy zK;TQ(x!)cPpW3UHBOMl>c+Ij(ywVtmIy|5*0NwIt(IWfP=1oy5+qC-}dQL&Xq4^E^ ze>z-1hJO+%8Wk>fc?^Gl$auULuhA#~%J}3)>GH5zn!YDq6%q|c(lK%>V%Z|LUa;=o z7ttxPsQX5g#cJU(%ow%C)o4R+^0S^raPkB;~{t--H{VU zP>V)S&vi?VeMJw(Fz73zQcb&3CSYNYz}agLFCqyEN`z85e-%O+%;*rG@2l6^0-pJ% zazw+Rl@2DRuD=2XdHI{Sqi74Ett~%_#U7S_yPh}tZdUxQ|Doa#DO&I1dZH1p z<5rDfWXFGR7hv|d2M0Pk<1qWbSpdZfd90zV*rbxFQD~asN6sK0cv_!1Ec8*y{~En*mAxotzX=_E+CHo~UN*Sj9q?d{^_E zuqchQ>cR{L1?|PXzdJboFY|zed=`lSGwez`0C6emtIy8j8A+euuVeUx<200-_VdV< zXovt65FN1unlGZH{>uhSQM3C`b0f-`!y*|s3@Ev{*6UFsrqcOZ8i`oWKTb+W45-x| zLYMRJjbbYAqW|@qOxwIp6yqw4KKND>zmZ>uMMH}{vUSUm_E0ajW#7MvZ$P^iw$|x0B}@ z3=aC^SVWkY{v&LiYT+W`Mht)#_Dq?ZmsPRBspqQPozYI94H*g*S6k3AZL4z2Q<}Hlx_U0bfll9X`w2|KYXSIYwfW3gbtR z%9Y0}`QE}FtaWJ>2Hs{Pzlm# zPM2KYfFD=x{3DrK8L8QF=o`izDAMuq3460eMo3^!&sGi5s=Sr5T(6`A71rs-$x?+e zITR9^N4Zhh&>Eh>H)~i-3f0{?OrJJ)Moi3S#2Ml1V5T;M<)*7eJ;QH%&!o<`YP<<^ zi0eNFnlQDJq`$f(ZQtNXI#q5$g|nzkTIN_Nn$h(`$f@W)jtr++;VSDnI6QGArkl~W z*lcT5u7%f5xS@+(it0EOb2f4LL(p5NmjFLJ|46%Tc-j7| zH|=}9Vv9$PqG;MObkGr{kMvc_u27>YlWmP=WK)bo9`a@=SD?6@FpF6giqU};asGTD z*46Vfi2VaS_T7qAJ_Pz9yC_HDp6z&TecmQc<-|lIy<1qYFF95-IO{*eE!|$LUpums z(Gy7HWcJilU;iJJaSJRM#C1Wx$4ttkaECg)<0@(@_7yAhZ1G-j`H5jf53XZ{kvGyx zf=T6E>R!aTm8on^WB5!&qRRmz-QCrb#M9bhJ`D8(y>VA#3Vu<<%Idk6fm!PK185?! zfiPSC$$hN{I7CD{6kJn+(l(I|)Fdp91u%Q$)qh$$N&G%a`*0b-^Lk)w@~d@6R`ORw zS-}kxQxiT(JC9GY^#<5QvjE1DB|u_6osG}U)83pl25)U@wPi}skX87+`*|6-gA}%D z{f8g)CJEpZjd>04mrG8E&l~;uZ!cCa|B}UpQFbGS5Zt{y_xj$#1U!yuHvALLPmX{{1pj8-?!bedwQ3w+ zoV5;PDqh`y6};?~pek3)tsezL$8(b^p&5@x`0)C(0z;Y8nPA>yS`5|~(|4P*I85pK zLGf*ra+au}a&^K1NrlHdJ zz$+OZEtZ`>d2~4y$~* zWYH!hFI@ifm*Dr6khkhA0yRx_7f z%SLK1EzkWqIZa*aMJ86%Y6p$Oi9kBV7b7%>$rI9`f}p;DWr)T#h!6bVV-d5T#sK{* zD4NeQ-~**%bxpl&uR{+C#;$ttxyE(pgE@9fG^hloDh=2H0Zxb^fKQOsVt8p3RxirX zHzY5CQuct~d3s-+Me_Oh(%6ZZdWXf~!Fj-4on)fFwJ*&NzevChM|2pxVtgv4t|Z)z zH!2;?-PObx7|rH`7T8KKmQol|oxSk%>NOQzLR%}-yCI*rLyG!XuH!YC=6lfWZ|yqfV; zX|-~9vJK@FXaovg@Mko*p3OZbPbF7xr=I?lyi7~i$N5?+#4!9tm)UpRJT@0p`#eNyG-lfq!8Err%aRG*305cMVtWvS;u-|gi$`iLnK_mOeXC}t)f=j+O(Zr~*Ap9mwI%vIGB^Nx{2x0W}?~cf_rca72 zt(6?2B7nK-JX*vG7Wp31OAe1!8C!EP*bgPKk%5M#mgW$WtCyE-N=1|Pb`YRgHU3sL=pm)tx=$(? z>SFg~`!91e&&}ty4*&br_iD^)jQUXp7}s0dvOaib`KDy}op@6IOK9b{`o^(7(lxp` z@o-_-H|Gq7z3%5tzsExc$}7!2&%sAR`Dvm?oz~+YUJ@x8)-pGnS8H$GvHl5^I(biy zkgKO5IFN1Ia-a@I2vLX{WA4vGT5DQKIeiKEA~r*c;fr?&LC-%=7_Vo~y({|>;Dvd) zfk{f-kFvD-M*o;OcNzg7rWoTFf6Pt)sxT#dNz_u1Q@jA?4g(B`r=0bO_@K-3XG;5~ z*8U%>O)HbmhIPT>OC;dJ>C&x|rUn1Ax@e^j`-`y@m7ro7-BPdhk;*%bucYtZ# z(bX;$D8-f6WECM+BzNVha39S z%MLV2b6_u6@d=qze@^u+s#0aJRM(pJ;WhB6(x^iEQ*o!j6cga?wmvE4$@lF_vtobl zWPrLw()xy%o2Qfq9^BGT^=w$jsWNRAlnHqA2?1yoy3SiTQ8qYa=KXop%di_@?XCXz z))RPpci&#m!ouQ?q<(~HSz^KSCw-^uVeqDEUzhZaWFHEVER?_oP7X<5tfwthvf@90 zo{*g(oD(b~W0(UviZG;35%+}upl=w>W(_N=ypfJ%0hTv5c2n1tY<~362T1W>`pdd4 zg}no0+N6hPb9kg(@Yl6DjcwMP8ke@1vws^4G6EBn)d=&fYq>_owW?RPth$=TzXvd3j6>$R(o} zT&$aNh*Fq^p*PYdBgvN7A4-O!qwj0FN-a;4hKL1O3>2~0hf8j(w8ZdD5vm^wC@(Y* z0Y7$TCmKn_wYaM-@J7u*HAs_6gC*88I8hV7nGK*FO-w7jN< zx|Rinq8Gov0}kWH_dO2Lfqv!KPZ8-n0?=}b z7&E9*2_6K%hd?xQx>V8(fCB)ov0OQEE|zWjXy){T%c13g$Ma)&m~5gn+z1iL26P!Z z9#hpB2N$1&d+;!)&_no!;*Odb>AlzTURYw1cY04xOR#&S+(ybxcod9QJR%w8g`9^DkgG_{DXx=N}23Ih`re52p6shF-K;Usj2^u zGTEuU^9>7F^}aj1l=}|h@Mq|kVJIHP)`wAfS?R!iypirULn5%D?fy_rp3+s5Mp8h# zqe-~PPKON{PGw4%@(~Wx;eWPFP}igw8_pB7VZ764iUs!@x4J!xDtsp<(I9~Zt$7DN z&KsLi!h-aJa=4eBYeX9k>?eCsshE~q9KZQPA4TjqB-+;!ey!r3_q0`A#ahtVy@JqkC@xu0}j$m4e zi?P9Wj~IVqbTmp_LW1*}idsZXNSWK>ckDaWsU)m1bqZpo)v$IPhR25R#)Exl4`B{R+1Pigc&2H3!^slZJ+<^}pUXQOAL8^K=5yb_T zR#vl%D-lx(DlgaRy@OjXlUoJ#6|)K{V;t?IaCTiW*UMFvjaMkcjBgQwP;p2HMj9m? z$TH}BwvQ+F?Y4G zJSN)Boir*T#%xbMhH%)+B-ip72j&`4JySs#p2^M(trC%!mjRA_?np`o)t!Jvcp0Zf4-5`O~_fdN%JuujlW z$=kVCOE1J|CP@HNS^KOrnbJ9dT|+rfUtzH8cfM{fRpXt>#_z06*Y53NCbp|KZKGuU zkc+PE+U4q+=l#}-sl0tVN)7C4E-30u*={PXhYycdZ)hwD_=<3egIwb2V}h5xoin#6 zb*Chec~78963?GE&exLG5-+u;@gJWEyR^uz0s^Vb8mUFTs2V{<8(2<)J*P`W zhyo7cYK|A#QrvxGu4H=rYH)01>1gnp2Y)bPx6g$W4+132 zrP+Bg90WrqTSgeI&r9FYJyPW6nGWZKEDU=)s;KaM`-bAxt_ZHQsIfc(P=nrn5*mZ3kLNagZ&frq-5oy$hWs+ov^jUrTC$`iUHUp< zRpr6{5IU0Qyx~;E

U>en__F5VQTxoV82@x6zandu7X=Dr-Sdhy<=fvyAoj`xXUd z9}*?H`mQ74t7A{q4Wok0jACWY$1YB+5jYGS@q$sLuSNTn3y^yNN7+Fskx z%{1Z2N-o%pf8`C+oo*Qp&tqlRdx@X@K9etKS8j5xR!YABsk`H1(Rql%D9eKGl%At= zcHLQPAA>dKm|BGb?lvmp^zVo7vnFOT=Ah%+AoYA2`HZV)){9LA^l21)$o>Zt_y;|fKnj~l%;<|jns(END?69#H|Ll_4UnNE5pP8BM=4ONIA7@gc?$vJe;aH zZq}I1F#gWza5ky>DQTGp?zxN`-o^b9W8b%-8$Emgh8eco7L2)47XSPvqUU>>@zvZN z8BVI3r$bZ$KbsDZFukDK1L@c^H0&<1i?`EH%3idLha^hxD)hhHXiU!@iokJCAGId zH?tXYjjR%G(_Opyu%+|qv}6ApR3oy3qSuLi0=spS%iBEKb-VjDg$qHSWk7xM|4L3-lL zEfl2B4kg^|Xg*Q(O9%-CLj@AQzi{pfVz@fukK$uumu~&6fHQ}u0j<^X8nPRfMtDc^ z46@jplv4PfC+Z0HUYK*tyS-UtRUs4B#aUSQCG9JTF#0_BFA<4BM#1w=Xy(^P$xvg} zYSr~Nw^ms*Efw%XrZ0_?3dS`F#A_L+Av|#J6%RCFb7!%y`D=c?k=b{3o?V1hAV{n2 zjQ#)6D|f%XZKvW}o7q37_n!G)aMlPuI} ze!%^T)#JuR-~nIL7Bt)X@wxXM^Srp^MTrWCuo8ZYHu-by7V(msYJx9G21)n~^y8d^=r`1>?;bl4a&prCnad9)h4g|*1juaoxZ%g2ZCv0e zwkYK;1~^G5+4?aFV_kxrQ7{>-pdu{KVwiW5P5_?Vz2^-7{G~HI(nE3pD|PmlUx}Ok zBoqla{?wFYqh;_2Qd3;o%-Vl4WI5AJnW{@_R;FL~eD?{D>S&E>EBeb6>KZ0^i#(Ew zd17B>F83$1+kE!u*$mqH=C^uAwr8kz&41bX;B1a+FgWiHq5!?fz@PS|UhK?%+&n!R zbKC!1%Q^o2b9v54I)iNsx$hGCE^4%Mt|Ojf3>%juBst|Z>K&r7l_b58FLpMxe6a80 zgO4@j^Sv14;Q&IMWC~0ixuoNi)~`&Rb;H}Z>O7JRoyiil5yuT9=zh;>bq*)>`SOocW;4( zlz`!u(~HxPFGtxjd3BZDHbcx5R^3R3isXcN6D2gg7(xI*X`3nTbh!E^?*Oo`M2cLI z|2aAKq}|q$rb2EFV>5+e8PA))X7IwUh-6c=2+)6&LK`Q&=3)CAsVGr)%w_nby5_uu zA1S8vN@o!~G%RWeg~Y_EhF#JufDepArxi(a5cuGpzJYLKHGQRSwme~+P?ED7_CGcf^1HzyP&>X?JP5x`^moq< zADr~c^XM-JsXEprZ2q)2y{YD-mV1XuwD9ASbm^0ESn$G> z_9S-*fW+Dma!Tj0Q#p9K?@`bPy}rBK|9vu3*1N0)#;FYOp~_#jwE3@kb`NNkVo=0U*YQ)d}88#-TsCq-qK)+Edg6=&|pq|21d@aPP>X}aFx{YL)g%|fFaerku-qL?Fi4~oIxN9mUi#kC;mg9Sv zL>;cW=}HW}qg2NSZrt%U@1De-{QE}m3|g#rC0KU zp`~={N^_Y1>inD2&SgI;*&p1U7n^=m*w*mvIVTZ4H?3o$!NU#A%%Nk4z$yJPKhTj*#%Y$$neHdeY zFfdl0&|UpYZ@pYe=bycyip-m3T1{t`M0k%{F~aWeF=VVHmUVuT7u^)lOWZxSz*}bV z**jH~9HqzSXQ-uECRLFCAx5midZj<$E*S~?XW~AEfpLGxmj@K24Z!ynC|a*}xAW77 zDyufg(heoF>n8fIqd)7n(6Lh6r>!=f>Uh826H377kF?`i_^>wd=5u2W0ePHmM-ZN+ z)(MUML$==TTbt;FVvOIPmLC^;-&5flQ7d*^hY|RyAB1 zlxu_&*ky-CTnOPa)v+AIm15Pl?uiZtR9{j%5ry*TW*LwDR_N37z)`yC`MfP9y{vju zhzeI2Wr>eD)~AaPR6ypL`-#U#mdrU6ksU@o9(0iA_RWF1%aH)UA-kv0tU zlC^iuDp4L;9g?+9JFj}blnn+{Bk80Q*@zvk^cFIyizEn=T>Ct37v2Q@J7s@7WzYZW zZ#of>17%b9E(>V{TwZ85{hyV|#C*eF6RGn*L>rL6|F+NZnE2c~DQ;`xVA7@=U4GYt z5qfrieF>LV>7xLp97^cZZGPq;jyrAU43`<-@94vV4xARZ`>pA?zZ+$VXkw(kGE74R zD>}^_0t7rnqVwNP|3?+xDkt?YmI2SjY8csQggVc4DPM6K5Km@B^!;UhGIhBww2bMo zN}{1J1G}RA00z1W9{gX~B@yuFTf`$_oqLae#|7RVF)(2>zEUslT;C`@_8Uih2FlCa zO2^nGpoR~H+9kO&npxOjn01Ac~p z(1Qck`P?5f{`p~MSPz~5LK7;fM7IwS4+2D&zodRkD<#?#SxC_MwmQ?p5K_~Pf|u^B z42oy}jG`!AUYTC@s>nL?C;hTDkqU^hvHNVz*7R{7D?hF21nB3LA<~;<5h(R5|QwhGya5 zjX$Q(l+_hwn@A!MZ*c(!u7hIs4Z(kvhE9*!ZCrr3^<1mbOjH7Nr9Xb=3+M>dI=rNA zPR^4x`lRNO2uIPjTqelDVvh_V3?6`=HR{7@prM&gbiyZUTPyEH#Fm zkyXnzNt|q-rKCjTlPLTBE&_w0r=j4A5(JMs4>75#z^mS+w9YSOXM!y*xn=wW4!2+b z#}N+GdN-_Y2+ud+FC;ouWO04&woS=gcOdiF#|`j}c6Act>TzDeIFf3uRKa!CUri?{gh?`}?pdGTOs!x(bz zh#7?=-;5Y#3PYg*77f3({BiC#i{Gst*iozA8;`|9jg@L1&*-UVq8Ssp^z18VJ?Ia= zT=RDiXEDI(L1}wd0#mlkhsmUgNCpA_&+JS@O(~oIqa=mcBV+j!i6pel%8mHPA2Low z1!)Dk#O)M&SqQ%1lgs!HZ?|26s=oRcrvBnOaqW)uS+^DNwWsEt#Eo?cL)R#g+^{_{ zp?`1HEJ>9~&i|xPi%9o9j5~(LVMDv+o*P%KNw*VWHM{))D#k8<1-v@m97T`+c?LdV zrJ~*O2a1PhAs4Tf=pkf0`2x-$bdMo3fxtRMr|y+u+#RMmD^)y{^&+@O9zCpyOX+FRzg{cn1CbF&+*M<8kkt=hg4%#wb`aq;d)*%oj(Q11lGiF8k}S zJz~a@cCRAZoM#L2J_;!^AiUhZggH48T?Z7(S1_(q&sOMC2W-;;!v_=gd_19xH_vP?65ykCoH3FC?$Rcc<7Q7%^gIRHNv{C5Y>Zn_O!aWaJ z*VFojECHE4`3_3}c`E0ntJ1o0yD`weX$#;Etx7j-3p_z_6m5$@>Qs0cvvOetvnSLYB$@Ml?Vq>7;5Ji!Zz*#40)+y-I;) z!AXHkr-5Tc|C*(GaAjlppwEcjv$g2>+@jOf^}p#&mGua7fZpGey7^IJ7eFONjJYe` zF~<|3bb8(Y*73JWpLR8;8=ucqwqZ?;D7J;&KSPHAle_sS(g^XXNNDwT0R_Lmoi`Uk zyL!6$q^{ISOzlL8A|)1Xe!Tev1J-a}on%MQ5%%zUk2kl(5!?^egZ>c?G$+YP#EgJ( z33i*!WggRmTsxq`mWoFBv9gP8EA3(Jmi+Durnx^m=FV8NusQMpN6SLU3f`i-rah9yJD0F$rnMVb5}Dso}E|0*;X zavjRag}p#Rl_BQT*~;vCha=U@`J~z_y8Qr1fbLY()TI_I2$OQimNem-l@m6)!EKXStidU+9| z5Xqz~*NBTrB5~($!cDR1Tfc=>?J(%ucBeR>h7=Z=qZ&?{3HTPnJ9TYDhJCZOxfG7c zvR(D1CZNerzo-s~b~wtnm)^L5E|@v4j!virJw$okIET}F%Ia>UoBdCnW+;BO)@tX;8oevFyux1TH$K8x_)+ZBX14_$ipz5GMs)BcsSGaj^(VdvLB1cShw z0um=W;5D;zn+LX^7puv`6zb_|jnrBKQI-&Hd5vOWaHTJTkl<`Sw-5ry4v`~YrpE8& zF3q!5B&f==Y7nO!e>H5^6}UmxU|v#()?b5=Wb~}aZ)9H*agR~!=kq_4Rx{<;B>zl) zm*WJKI=^xEkI!qm%TY{bsf}paH%7&>xDY{ev$^COg?bQ4$>gEic6EF#rrvvl`K$t3 zm`8j)`Q@LllaumT@2_Z^TYvHasM1I-2N|(Tu0Aq3B(j7>m`;kqaRc9-TtB1VCoa!b zYcyP?WZTrYNY%@&ayhI)RWnZ6gdb@8Url{k1{vm(J#O=N6g=LH-%EUHu$YqMq>>gg z-IB!3m&kA@<_>H;{2locxUHZF@IMDB`S9e3C{cbMoGEL{rHzEvPb`ZF&X+Sk&X-*) zgg?!~`JU#~0A_~6&%$bz+5YiWhIgac^9q*Om3wUuKoYu3U#kEQrN7+!Njg2L9ehgZ z7KCG9+X;kP)+x;9k2%Y5=i;gy*_p$K$!F@p&eIi{Bc?f(?^PWo&D8m9^rVK>?<;e+r@mLf@f8;_lzwl$uj?EH6}zQ?b7cOu%mpP-(fKEzd*}I z(=3gzqfKz>z=K^;rH*enbc(Z)>D=ZN@h)eIU~BR+l`F|sPu<$EBJ(xI0-P=Z+@W=I zJhNmGl<%Hk$Mu{MhIg(6CpIP1kmm(hq&BXgj}|gFf7T2W2as0lF4P!3DZt^H3=ajn zL_k!J53sQ%UJ}CjZk~tos^4e@qg6tknsn)cjhyR{^T6=~P;vOa z&0z~Y!prFCrV~_*OJFzpu}@$xs!G9UM6^csWdfd_t5 zZ-Fl9Z24q!YeF^sq;DNeu&Ntce`Nf)kv{GV8*3@d_p#K}2~1bK{5^P{pkM1Eh@#d| zrW&jF?vYOMt$joJ?h+hvl5w~0A$*d!y!BHd0W_r-itUg)!m=86DWT>#6{5za6nJ;6 zWzge~0BzqL-01XD)6@HWRBM`t^@#YY|EJrEAEW8Qxoq#qT*T`$MZ7SxW-s2@ijZ4C zGpezcwY2G@h=k_-zF$PA@vA^IDJ%%SXo4<)%GLxcB`|ug^CJCfI-g~4f)y6@S>~3k zKOP6TI-wvEb%PJ9LmKaZtgO3KTa#z`<`(sZuDA;S z0LQy?v+E0cU`aSxO#=+bv862E!!6T;(cMUS*WG0k>6y?n7=eVT*WZF{3lx9VN%`b* zeoRwY!wUY{ls=*A{1~Q}&dO3V0AhW!_0vc;^M3hWwvQcke0m-lcM)5z-meb>mKL~=9i9}829%C| zZ)fn7_SHb;K<*L50&YOuU<2GMwnRt@RY{2%40=+K@~nb=vZ}H(Rlk~0B`_22yPVBI z1v|=LlSpAApxU_m`Z17>c0%bYs=FuT>vV|B={jkD!ab9FQ<|IMoTeZhH#rt0N|D28 zcxMy2I zEru4(v%a)f5+s;EU1S4w>SZ%k6`mC0db)s1#xHcFbW~$*O;}Qh-8oA5iGc@?lk*u9 zdwH}JcWSW5ySSC|7<<~r*fpw}by21%>Ki3=E#dnepSS|%AGf;+y51eRnJTFP2lbb* zjRZC$vL7^UqOF2tw`5G8pyL2--PY^~!Yje?n;J2C8;NnrzW-6|=Uc&uagVwC5`p&k zcRHxFV;2GaBZjG`CyC#~dEr)kqSy-&Wxy>b2`MSaNTuVtyREKoe&=@^p&IoU*(r>S zIpjY=8a+DaKT*()MX*YyeDT|Al41#wQ^#PXF%s48P9@24K+|qqE(YpdQl@ocnw}bz1NEjPyJ$f#a`)5zQ&@1 z?^oYq+r0gP%Sq!q3AJ~e{rEqg9+tw>Xq}cO9p+~Y_WcC_(QfK{yFWgY5Z2Y+QhTOt z%HqeL=%nFMcRXNS-;;rD^@%ZZ4m6lt$zBsFg*+CfYS?(Ni(QAuY|4Xpv4;4bKcpr{ z;jpfVtwg&9r+9u?4Rdv)62g&$v0k1ig$~yj(Rh6J@T4 zY(_YW?UQ3}8npz!3N!e~OTatj+4t8EV3Zery2gW%@Ml-*eKC; zy�Dj(-8-eHAncht0FqEf~Ok36S@jHHO2oc>eJpdLBAzFwCtMKI0{YW|OidkNaCi zYz5SMg8!^Gb1W}?3DmzStiLv3Y;FIKW|r(&fp6xxafxlk0Hj2X70)d7LWzoM@kr96 zkpED}51i;&d^qdiJT~*VM@}*LPfZm4&wc&0vEo>`F>e ziAJa#_KEb5MW%q5ne&9eR6ehFWfe9DTXX(lCSlisqkHJpBU55?piC|Bhrsj_L?6t%SzUZxnf7 zbO#9dG<+yinGxX4tb)&^C+^?G!h#@L=6-d?^~r6rpOu~0vN`Q+r6#f?X1V2tjxa_w z0g~|ZXr6E8l1?7npW&$A7!T~*6JBPIW#SmS6R8YDnR)w1VJJ}VG}=aWXB#3-jvqEq zadL0?55-;Az2#(~uUO(-SoUC|g*SH|Li zG$(OGX^zUu;6MhQD#xlPdd~~TV%(l3CxPknKK7HHub&Ir@l-s!=;+x)n}To_z!i00-H4r%3mSEmCn{9blXoJb8MorK~N z(&7wdH8gI@R`0c7sHm9yS^r%OiZ0n#y)XluiNgYPj|4ATC47cC9%%UNo6o!MOc#vCt8O zaop+Fmr1EkluuN)k?ArqYx)l-vxOX=PN1QRWF#SV=j;J2;QGtV`NqujItq6t_9`(M zCGFF8C~TrG0T!LA1G!cH(9>bF%-{_&pmd6ulaLo3T3OO@$MO)z>AkcEY!$5CFYf?9Iq zd~=8Py_$W}`i$cHaa#7$Jb~)h=X^M@?byN9)F_Sjb9}dV{{7gd-?A{BgAX+7gCupl zt8rMIm8S!796hCb^R0kIvX&GE#0Zpz%tmU2`(3Z!ij;52lnD0T(AVL+8npf84qd zv{GdNG{1!ehc#{}e#G2qF841V&td`tQ2(W{KTN%(iZ%KL4>ylE6;-!3Q=o4=O(8^4!xbhvu3_@&J)}+MM`WVjTZqcKX;ExO z8S5rmT@@D&9thlzLb$1{AcCAaNmN+dwBEqrl((mRXY`*Le~`~wkiEx>ppRfgR(5nS zU(40yEH#@EanX-MoAq|%sFQBayo}ax2*iR1kF~JgHS=COW>(qK<2?kGOguNS8%ea8 z04aX9MG@$!vo2S?{~?57QEHT#0b7PzUg8&S5>@|gz6-_Ci!tHIL$pvaphv@?jslcH zch*JSwPtW#MrqKFWdY#{N=})`%FjPI@=2Cp#sKJb_sfIZ|REMc~kQD$*7#9YpnJ(4YlsX=Z> zDE9JwxJ~@;3&cMWm&1jMYDBYec+!J=jm!n*P2OBF2o#nAy7zq!v(U)6hqY;HvQcF$ z!QCf7!I@^?kyNG7k}-q7D0MkH##r~gB&rW(f@NA1=qf@%^5QqMXNsX95e(w#h#Jx0 zZtCYrI6kB*DWZ3IQNulx<=m>bB@@w$AG?Od!->iyqukqcrc_)lys zW0tbbGMMX!yWX02DLqZRP8w^*_al*9Yw^&L?SL^vflM$>T3;Vwb!`l!{V5v+JEfqw zL}vn|O8HPB0OO{hAhXiye?Mtg)r#rUU2o*AjL9dSYx-l!0&Sky=rtn#Tf`D|C;xx; z>Nu`7j@yHZ;TNd0T7RCvQOdUa-mszB?rRN3%L^0_lVFt~+B*4TJd7CFv}XPfR8&Gi z#SBI3Bt21W8&(t-szd%v1|vCKZM?0uGjew#rSRytu^1*VO&=c%K_KJtg|z3Z^3eY8 z`@%tERn?{%2M6YbFSalF65|;wjrIj};Q16Fwcnp5IZr@_ zn}qCTSbN>=w8F!-Mp@J5;5@A<9;_0(E$%Na%;ZMVetFDVIPP7E8d)}fN27$vFD5d% zAMYnx+k8&w&o?_yK9nrA5ReHtf1nJ!{IqzzDQy@a8jw2@=SFTl39ogj+4YonWK{6@R7gslo>+D}rzTe=!EKf7mAnEm$fnMoh zX_cEf(V;Gt{J$^8RDd>bjOG$F0S{+!)zG!*{Fh=Z$^bIAx`;*{=?-Bt2)GxDrAKP- z-feD9Y;3B8vY#g#?~$}@)D!i%&&33Xc=^vPQ#9>I^6|C{Km4t7dpthre0-auQJPTt zYVV19K_L{`nm}37e`P8{th_6^MO*WLVd88Vcl$+}oU`XarFk!xf6e((4LgCXm#3)DJ)FI`6{9&S&(;v#!t>WQ1$IbCcw=vX<6Xax3k(V zrFmklie>ES>jUb_`SR?_Q`5}q|GUcngCU4fz*@6>p3H}}@20gL>Go&Pdjhln?g`RA zN>>!t9*Jc#WAG=jL-mu-tdkhssc?mzJBbbgX*J$M5l}Q^{TvS6?g7JG%X!v@YpdGj z&E(JnWOXNp9(1wOii>rg0b+oxn#QH*nWTIY=4Fj`!?ic##H=DyOadky?gUNg&Xd#}@r!1+i-%a1L7?>ZM|otQ$ZxDMUoc4Kkzu)KP>XTya|fG6?E zm&=-ygtzoHqsB25wpvDIDB_fXc+uxc5Qr}y8>2)OkHi2?obW*JIDj8KT+?wI_2HWd zQ32k!i;VAy?p#&cJ$6!Yvh2Bq%NkC)DSTEywfD3nXm#2cK3nrDuk`+SP+lt_#CKd= zoRvl5^7#7`SIdY?7S#guYzBnIED^U^p`zdrjq}yiQuJBCXwN`2q@}87c}&-h$PwC} zd_Q{sJylE(A?6eBT&2%uIfIX>Zqki~P39KP4LlgR@@3?mC;a_PgJMTshO0ORkf{^8 z?+eQ`|L-t+yBHg***&@P3z|TC5Ty$F$*^jmp1dkmj31$eyFjyca5>K?+}?M`d|r0_ ztmVJ%ON2f@0)oESgxA0)TRU;2E2-c_Wx1ZPj?HfnSfX-@eg3ddp-L>WoQQVt%<*{m zF_L0)xFSH#+4mj0=9M~5we<3F6#o3~p~%S+kz0r}+3xkvxgMF2TI`-2(-E_pPPXdk zr#x+bXwYCf9~fEM!xNh7U*TiRLAv+bQuqI60W=~;fl17hqFVdJLuO%3MXkc`F6^;F zXS6^vwPr&|5de zRTt+%;q_UG{m`G{|BtV?jES@B!i9^wyHngL?p6kOE5+U2og&3$aEilV0~9F5-QC^Y zio4r4&wKLyJ2}55lMD&DbFaPDzSbq$Z4iwC#Qa1Bg7&RivACT@Rod+@*6VG;VtkDP z>ofjJ1XB1{{8G9SCek@w_|DNvfC$l3V)BgQ$^jv4WlGJIav|XXQA6?k zq6Ad!&&3Eq%VoIdB8oc;?fg}SSzY_1Fij8E*t>HEHNFy#j(0gm3FZD0Y$A*E_~S0}UzJpp%)Gq`jRLRmIzR?sKaq!Q8cj7U z+8$e5h=?7k?QLRJb5JPcJ|3ML`xiEmX4+h5b^z%|4!A?G^x9z4P__3*tm$h>c?LUl z8p?{xLQy2)D?RT==lJIT0y*JoNbOb@!gH zRX>Ah;L{r93B6ft=`AAJf`kQv-Bgb)x25&w%#N_*vvhuWMhu_$5mSI-RnuC9=XbpN zMdg#PJ6+UtGg0hh+z!%_Fs4nvY#lj|rd9<=ET9~vRN2eq@SMus{W{Ch2Ng&zX5JL5 zyds%gb1l3KRS(Y{>!CgP`;0)T56QRi9TT-fNXFB@xBW*GJFvCOU(`=MrrkY z`6cdt9`PCTt_8T~RyV2l&2cRcA#%pQrrv(rt&Yk6R)E3Sjz66WvVnmY?Sv$-S*(s1 zFYAdylwJvEhRxpIN|-P>XKl+=D3 z6$|`YHylDDA{W-PV_SNSm462j&)C4(4tf0~Ohy3NJ%EuVL^Wx^H9Kol>`p2uHj8>J zOJBunjHjao6fD8?>amfDWydJr-3>9MU z$+T_)rS{j2#%v!N#84)amp{V5ff2%#64@dg@d3Hrhy_wXkjwE@9_##+jpUlZL?5n6dF`a6K}G-Aord%6e!T#PXg|T*K_aStb1m-laXZf>!fuN z#=Wrn$WOv@;=a<2WRd9%14XCeB9Xh>4#em0uPPIKxDWse)WW)W2kH2)LNMCd3>Ux7OkAQ1jEGfG3^UbhBGJkD=A zX+$^MGC_%~p;P&4>rEN5%69{HZ2LKya@`i_2HkGv=FQJD`c{cu+@HF%s1+HCV0IhE zFMb5RZ-CBy98SK8)@(eyE?gV@r=3>)iD4e^6X+KY>$DAqW8#;lhqB=YzGjZS!2iR+ zON3fimM@7Y3+K5;wRHH3`>k1$OK4$H`j-Py-uhltEbXfE-GAYMIs z#tDYbI1UCCOSjMH5So&P4&)3cWSi#kb72-wAyga|K2oa=vVu`d!c73A*h|%*mkF|_ zCk*dBeHV_hccsJ7?#Sz#M@eqFG0r^}K>0_KRpdU*fIQ3rp?&wAPvGZGmfdwTg1{2m5H34Iaq_8D1#*Xh0FH(7)zz9XWL)_&0cV{e`$_C2dej= zks}tzp9FNvhNwn*)1OAQyS=%Ol`h)dnS^1@`N~`CUYq@a@|*IwUjc-m{P_Zs4R7r} zud$q)=>A>$>*a>RouY@{T?*t*NV&V7i*uHgLY}#I-RUP5zoBOq`Qv@^`}90nvd`k1u+No%+arrYf zAp3CrAKEupL6n!SULnT5{_DjPjTWv^jdEng)@|s#_i|sOYr&0;NAG`h4{=SlxmEvM z2oOzqX8+%*J^lYWwIM$fPQB|UFqZc3uu$?D2xKgZ#d;#)&@l}bwh&g}`!!&;723~o zNffLm*dA{-m|VCMQ)~`Fho>54@v@|{pG;w`I*7Y>6May}*wq~@$oms@>gH3n9)sKY zJ&PclW9azy)Cg>16~+=H-Ru(XIeywuYc~tmOeSTum1vt{vJ7AOY8ph+1T4h_IkN!u z#bIV=7I0}tucs`7{A&>g-{n`4e0s!sXaI+ql{Be%Aj&(WYXPl?SS=fT{Tkt@?E8 zM5kVI4e%F4kawsHuIB8V&e$IP1mZW5r6Fo1C=w?k$o)n~J(sPVoemAMylVZ3;sw3S zQjSauU_gV8nQbr4t3F8z3t$L8p^XC7zPJ7Kx^LKxGaG*-k^twu|DKWqu;Oq(O$RZ= zrSi?GQ1BF1?2q^lK&gScqERfdFlmMC$y3{e>%<4}X#QBiZQzm7)9-3h8vs7y=!ZV8 zF&G|qFdXA;r3S7o5&2bI-{g_wcsI%fUuX=YuDlsbtYK_3I~vU~$Wx~l7Dx~-M}g@1 z9RkrukC-4@VUMbI7&J{uk1ei2`pijuRjLtIJ>Dg|yspmz4NA5i&%Evr%wmoKzZeq3 zn1_#;&zy9navx+_Tf8?4<#TJJWU|!Q2p-}zV;5<^e;+y|h0r#EIFARDqmRcZ;AGR4RAuQ@Ur1d1A zjm&0RQ7_znLmPEJ?qc?AkkPSz`E`CbNmke86$oJ+?F2t_R6HD(kU(7jo;eubW=0wy zT#&G|#jtFYh69Kt6v45>|K^Yc&kDNokKgTo-0hB9zCotzDD2fyo7nxkbnK_gxwbQ& zj%8mnvnp=Bds8}BC=kux$_tnM(vJ$)g>`$y@EH~Z?$pVl!yW$+A31mcqxxwa#zvE> z%Lwf-yLlm{CuaOm$X?pJ4~cJ(ofLOm`FOviu5iS7CX|xG|}yNB-Q5i{>Q)mk9Yd=Q1!8@ zgd`C(ym@ee??!Tl|LyDs5k7rXD>@co>~37nIKNL5dFP`xgxZqM`E5c=A_XwZwwaf_ z(9g45lqgGoEx711%9A&ej7fe)NDry^)Z$&cfh1us!F zunf}oR>!A+8|eE1UNLEJzhFL?IXb5}TbYE~obL5Uj(A zmNEN~fD4EalFp)Gx;-l|yEl7i(u{h9At}&G4?x)Ajtsk4Tb0L4*WG3du6)W4X87@u z{3it6TLzRZRE5IW z;mm*aTch*(VhF*^EpS&v3kJS#@RmUid{MKkO8WnHJqry3A36ggVPQ?ppx4_UJZ!ZU z8SLMR5w00B6qwG|+IMC+S}ubaV(#9l*mo6@;?;lCV7PzX$Zn;(?R&v4NfWp$p(RGA zAXnTOX~ty>P>}=2JY3D!znEVhg73Liv`X;j(oVa!4WzsudIhri$@(X%;OpwY{n=m6j@E7oy)Vn!yp1G39~%$;qlS2zX&WoV)LVP5n*bGC3u zazHEOK1S)1V_7hh=6C$-ZsQ~(DNq17>-341%#j6H zY(rF2Q|AdY;> zi&8+0m1z(THuuU<$lc=l77^CX{jnlJ;23&|y!b{8x&OW*qh8-zrssHOS%%Y3J@h)D zzB;4f5OfaE1TZeT5Vg|~g*s;Rt0ez)BWK%BqT5AL7A!BRBVtVzQeD;$rCQNs+Ej}P zUvE`gT@RC0;s8PH%B~Ry*wl~hgS!g4oSGRHoj)%ESge`jt~QvvUvgDN+7j``zmz7x1_mWx^X(b8NJ35Z3^seR`82+08F~>E9 zE!!WsF$x=$DO0?2Q8`GYqL|%T^m>;IW%!zNdj(0Q$5OKjdM}mqXBPM1q~9t_B*R-p z=lYTkqD`Rojo+tEBi)8}ZvOof_mU`FS!Op(5GMx4+PL%fql*rRHJhzpY(=FNO5Q!0 zqtEZdh651@j&ufzQ`y0ASEI0!yI*XTo$v#yOO7aJYC7)du;05%l#6A|{&3<|M0R$o z3s&1++(A|@A3>A58hJ3wT}FW!f&ky$WZz_ZdRyn#dQ)Ji%(_um7zNwbPI1h?laoSU zA3>@%OgW$$!DV9fyD?rYeI`WQx)PV zIv9~u1YI3dk$iD3^x<@0Zk%BQ_?|i3Pq6UGH@oaVl-}!gOC_Y6K+Jz4ZCPZP5{B5l zPFT`@(HyxC1s`HxnGmm2e9Z{z+#ycU(klE@08OiD#!MZcaB`Bk`3)Gd;G2>p!B}A` z(9c0*syU4_HD(I?wvUq^J%f<5D0Pyo-u9X%(>~XAX%|}XU?0S?(bQb}YqYd|F8y}6jkh|3bzeY|-wurmUeU^-$HvK4co`hDjhl7#FWRQuzU}s$ ziHkLY?y3MaO)V)^T`D|4{3i)70s1qkDE9j901_8vq)p4>BTt_=E$X-MV~K;SIbdkJ zde5j=_k&-<%9)>&0p&>7gZRVWRGfkK0o=>df>kHjJzJ+e06IjtH(+)jTVhdlqP3|; zG^uMC)4-FL3`prbhirMl>3$H%v3Yi6|33p1NJ5C-)wLtcE*(C!nsmV#PB<^9VeYaJl$?-ASR!RyKbsFO;Kl?OtdG}{EOzejtl@PpL7udp12O$ga$_{Gb@Lc{@a%>EC!I^D`+zH?! z>y+3aBTyEqdHnj2{!NS5N!C{HfB6m_gNb`qAx;AMs$n4y;jsVOtw=m;*T37iSES~y zE@M1+bYvHO9G-JeuBRK=cvJ+qGuue77iQ!hS$fryWo>+N|AcgbB3{te{1Es16Sh=I3Ba1|v?A`uZ0)>BNRk!9N*mj$J54uFOA;4~@CtzPZ3juHc1MSM=1I*HnZv;tiH zyvzF$!87TO3xxsetmOpE7Q~48{tRxdg)7((!;~=R($qex^E3h)jD+B9Uriu`?)|5b zFC=$Eu&(i2egPx!3mi$dL0*GG60P%TtM%!=8e0Ql?@kX0sxW17dRp4KB-pTt21|-W z?Jt6v=8ri)IbLh762Zqymg)`Wsx-tc4MIx!3kphmf4X^4_UvSORthx@65( zg`Mr*2yW%~Pey@H#Wi+c1bJ--iW1MuF(^bssAFY-92TfyUo|aIGtU3{+>ttB9w&B` zpU{M^@Ju?LufhIc8P4cHrDRf>Zwslxvap0Nqg`fT4+cXAgN4sL)OapFNV`5>pn|cD zc+3dTG{@~6%4N6@dbflRb;83NZ`9R_jg>86TaPO)YxB%6lk+U5rGP+#GZRfhXDv7N zo3SYSrM22);J7RMh!&jpb&*}M#iF0%Dr?$e8{>qoc6=9ujH}|JdGfd<55yV}tj`p7 z`W7)1;6^rW_rSr;A38kk1MU2Gdv9>-D>MdvvTS%GwNWR9Lhd&Jj)}STY$5Lp=4W{c ziOlYmtOKlA)e(dmw{L~O~6&0GGp;v7YeV~r?zFk>GEG!t++hKxVx$U18R2Ws< zw;DJ%vF*~GH)V{Jx9_Z*VW6ax zg9uo_xEB2^ixPiP+8a(ye!4=`!{)na=Xg)8FWIkV`kq<3_X)NTPPX<96rI~*{pV5Z z&BeF)UC6&jRFz|srsZZIew4z&RA9M_>^NG+5|*w0L0-5-}hSt!njD00QW zxA7bB?0KGtOzhfWr)4;;zRcjpf^tNvh`{+fJf!3_g(Mtw1|{-hXJxBKZO5qi+%6>A4#==>_phZQmMz&K^TOM$&2k(+awbj26$)B>rcGvG zcswm$OCFmkGAc@VfXFE@xwn|zwTbUfHnr!ub(dWo+}&|S z;QI)LxQ7E=h?dXFW&xC$*vTQAe5DVVd_OSh>y^t+(oO0xhCX8-%% z9D7;0tbsYbB)AI@c zQG*60ljND1o!z(BhwJb)Anre836e4f$@PqHt}LvC@q0Ke=I%S;_c^8!6cn18IGk%w zy4O7lKarh$l8ta+=hd;Lh&h75O6I@y2ab8N;f1%>xR^?$D34d_8Q$|cA#N=1{PV*- zu%zXXrx*4UqZb8^Sk{7!6SfF$|Ef^vUw2+R$sjPW;irK}+|vB&Px)q94I+5EH9rgV zO#4G%Kwwt=fN*Vk+U#A54x7HPx2=#q9(=w*SzD7jKLQ-sCeFrSnjAY%EJvPt^#{Sz zq-d!U*v?)0OKi=R0IcL{b4O!go-)caI1@j=Nad}Hx(*3%;8Hak-r~^vgV14MeA-8X zHO-ZWe{~MX*KkLz;IX!x!4mSjGiPJBeE9%7D@~_ZwlDOU82ZP!gXX-Qq*M|9hBI0@ z@iC@NrHq!){6m9B*W!x#LTp+DYNlOL7=~Py>V45nEOb#*o3(cI8?|!@xCSdK_K6=_ z4%sp)3N7=_@-He3k9Lgtj7Ye0Q4SOc_G`^Ms#&JRE9`)UxQOy6w?JMMK?~tbSvx%@`BNH(*o5@%t+2x z{OS8+cwcDC)Rp)=YL?hVVxJF$ak<8$IJ5r{XE!#p^VYx4l%yGzYwa&99pMBsXgv1c z*XqBZ6p6c#+qOa8YLucIh2JYxhj-jIqbqY&Pn?+b99oLvKl2truH_curbT0V260v?MY6Xp!xbiv|{TVxL#J`^Rb~Vk{ig ztXAn@_B{1U;@qS6_ZU?u;>jJwD-x99T`HW&1NaJ?T!@-H`+E zn9Ygn}qebLCN9qZa1ik_#z!0PBD?^~fi+ z9P1LO(Kbj%8Gwk9$uS9u4ZOI*AmqWx(Jh)2KqnfZM^*kv&KNNHtK1$>p0y_0=XZaA z$5Tsy*lX)-KBy4H{)>n#@Sg}TVb*Dz#)K1ANkjfy(OMZD)>Ink{p6 z7toXKEBFd(O^F0%Ajp75SazUHI?a6{o7St$DLxc*@39+ za`no=zq|inTfHi#-N>Y`?^0rpn14xDKR_|0<}*(+f%3 z;K>$iv6|iVmm$K%IJ*mZF_z`ptW>L6tB}i{DrIjQAJpVF&_Lk4t%JvlWve@FnMCL_`f!B0z*Qjfkfdk1fbSs%n8~^iDL&V3Db_?Z4LHJN#hXyq}Zm zHhijbi%k$V3#T;b?x2v z5n11#S@)3?rNE$L3&YbTwXhta3RS&4DF?GO62=A#Vw^ftJrBX-AXepED3G;^O<-Uy zBxs1Q^kzWZOU92c7z`Qo;}?b3&5lj*CM=gl>(srRb1Hs|@GzcW%62tv7$26lwq5r% z;@+C%6d*{H;VCOC?j);-c9-S_N*DG&I0HFIOQ7tD9mTvaDGh&|d4#w}Oi90Jk8_TU zji;S<|H5E91acYo56Evu^q)e!iw1UDKLO+*1Jbh?{N?5kE_o6WQQz?!_4X9=$jqFJoN%YFV~Y9Y9IPQ5F=|IwTD$D=!O-n|q@-eG3)p1C>xi=HJ?4>lpP>pOeD z8V5%lCDcE}i?XZYsed`r$zJd_M#PLp;ah5iTET+l`%;L?VOU@w<(xdsVP#4JNYezZ zu(T3x;~rnI7KN}Q*({GsGiUV6ICd;{BMNflPG&8TwQXR@dncJhvZckC8bj&3o3Lh9 zyYk8@Ba$=PSytPc`TFX3un%!iJ-j z;s#AeNNd<~Uin|oaQeUWjBH5Hs4q7#+_a!PUM{oeRbh5of#xGO&$6s75h#Xu#5}1gVNQt))WQLTwuPI(W*$4d#^}vtipTzK|~%Fo%2r-#}zs3 z->DPnMKhxh2A7n4D=$Kf93fg|`+M=XplfHs@V9r~1~qIyOa5J53#tQv7w%g@bGh+h z^>V%jt->1xIr%_)>%(OPP_#!Tma~Jr5b7{T$a4qc=E(1JO=BqVhU|I1BIi*;NlUiy z=xlmdf|h7mIBDy9PxfIJ0X(XOR`cz-o0bOX>ru(yZ)v=`-PxjczCxDDZwNTBLY#nAR9FsXBAdHr%&kqC(>Uw&kh?lxr$hzV8XoF}$8)iGwiz2d{O`h+6 zLtNwfV<-S|p=2nt#8xdwof%hjG6%p|BpN6(XgB!q#P?@nT2R$a_xLDbn^>&SlUdWQ zfb^G$@Ie$Jce0J(94Aug!z#kty9p9W3P0e`W35XXtR6#$Ib?8R$@YB1Fp{wJ{ zZyvgP->XdQegKu#siDuS0xT~9*)W~_GVN|EAxQ~qWiV+6{|9E?k1I?`*wXVcUxCgd zkbcx#99EleQ~Z`C4=p`&S&zbG<}Fy;z=>oxVK_e(G`>T)U%R)Rd9dR!!VW<{Tn?ya zFCdD%#Ypv5MpgxY%UFXg!-Phh7vxPQ4z*vr^vxakKW!i_(v%u<{DoX}6 zCQo7Ok97I|W!@wObcm-^dR6j{`mh6`Ausp-^mFS}lEKOO+;2!>)pH7a78a16Ip<=N z*E~>BMrWl!^HEQb|D^w0VGiOoRW~vz`Wdp`wP)QXP@ht`o`zdYhR-mKGq}|b4Ycw1 z@`evB4|uYnmM`}ihlR}UuSCHNXG^E>aX<%NOZW`8{aT?>5+Slx z$D1HM{&$a}JXF;|Q6XNdCdQJc^gu$LA_wMRRRVUyo_&RM=iLD`{Z1bkw7a`C`$dvZ z$73W;#vdI4|4vT<0g~-dD|>hsiTMpNXIXaVK9{oFRzuEWu8C#<6vx-Y_tooJZ# zo?`a<_vJLQ3-BPC^_1fB*-A+A;^>dK89Q>VK`=SK0vo8g1&_795*GCO3k1-NB?;i7 z)BOstEN7^{(STNSY9s0|!+{0~VuAoEHAH<>mhleil=5x{8UUbecZ_>;jcn{-6z1Ar|FxqO1U0M0@;6l8(DqSO>l2dXL|5=e zRa+cQK8qVy1--w!_!5)#j+1=WKSMF$&g3RXp!P4>cqTqQEiZ7_gqRR&?{0BWpp&|N z^7l;iPrX@YCJ9uwDiY06aXYuL;Lgp@L^Z(zUlZO5zlckT+s?y?9Q3`#0vZ2q*gw3i z2LQ(#vt~Fk_e&-Y#0(Gad~qvD;A=$@EmtqvbXL;+#bwCz%sUsCvu#P# za1(ZnC}yP@vgdV@BLAv!znZ$M(``9062#QXR<1ZW@D=Qk8%=?jd7x+Kz|j83X{KlCJxuW_53r6su#FYiQ@Ck9ntmz~+!?Yu z9(7$O!6BZ)gmZ3ABRL~HOBYT;Ak}P{9&^7#$I|g@@KiHC37tc~O*oiY+p0_#{x&X? z*vAQKox5mtcDH}SfTu2QHd>?=5`?-Kv!Hx_y_C{2Qc1WQ4Zwv3?3V@7y)c%r3*%yU z0f~ZD$sOU%Vl>B-0k{%m%Q4q38Vl3Q%25og}B8*^RKGPKoV#<+% zxT$6fEztW3s^+D(!nhaV@TcXGvc+cSDpVZWaO+Ght69KOr1`R)KKBWzp z$(dmsUl#PjvTXFNUUY<>pF3)*uA3`;8W9a4vnxIqT|Swlu6Gaywk+sG=$!cH?km9p z^TaUwCkW@}J)<$?Ddmk*x)b>0Ghrvz(npA#FAUK?9#w2!pBrHf=qJi)UWq!y-d>IS9ox8nh(N1VYfv5EMxnz1wB)FmR1$)^g?H&-K-_~o($7}b z{bpi$-Gjek=`oFB&90=y@F#NUG3O)p%yDboy7+SWE>kbiU^UFZia^kVx5)k59~{5< zdbR87)Z6lbbfcoH`9&oCqMCDdMs zFpO3&xcvO8cuH+Rs)|xLt@vpCR*S_-TAFoc zb?WAqbOIM?OYnzzbApU&>2%df39J)}W2U~Y@B|&;-bJH@?fX!hTNTt~w&w!MkTiK{ zHL^Q?#e|PDif6^&#+!KUuo4m;QoWP&Y{hr3WuK6VM2)%>w2VXu*dr%by4Q3>D+r3w;OKjd&PSO2)4w0S+iKw2Zp92lD8{+ej%K5Oig^r=TN znyI{Q-|Y7KC+DB&OmTEE;f5eCD*|oJo3F5@VXsWT8bOB50IPu45)zS6=AMA+I~}JVG;(ba3VtH;s-SlY&CR)-v-A zm1?VuW=S&+c_jfkj5?(%-{odN8rM2zd~+sJRT8$lME8-Q|LDxog9e+?!{!mk=5rK- z*kVH$AD6i~_@MQt`)M(XOc!29WK8_*i^8TYNvMj7 zTFU!1hzY>RET%V2Se_>^E^>``Z$u&zckH_5@Af=O`mm=&@=kZOYGCb&Znz>i{38(5nZ9N7j+LbZB2v}_nIU3-pya0G$x z?md`Om|-C93R3?;v%an4ji_K$NXb~=M(1<8qQr)y2p%j*gEK%vfBsIw$!*-veQn_1V%-d7$4N}ZkuCjapt%& zQDyso={@hahJp=Ag><3{tFeE9U^O9`C*AVP&s!xi$5gy~Ha9fs)#m9F_yTIq!yiA7P zJuKgMWKCHndzkKa#{qkfe;=^n9g{Q7G(uz@ep0(aSYI8%Lnq zaOe%6&02OtL4powv6cAL=|sAzoV-_UrC4tSRE#M_BL+NphUZpyI9%80%Iioj;9lXU zbKD$o-&7h~Z~FP<_tsz|FEw9~IemilCZ`+HEwB=aJU5r$QVYi;k^}ZR`xB*pRPh^? znEJp*?wgC~w`U}7xvv`Zu-ZtL34XegI18wSjwsig&;P|7`zDC$72 zIhxBpBdER~ZgmCw1@fRpX6l1LXx&?3`9Tax>Qure5nyY8Mw2JXne6bO`192m#~S0r7bweK+W&0#z<#3Dp{Fc^nSdAf_BGY z=sNm0ZN@K6a36tA!6`jrXKNR0a!p^p*SyNwV32vYHj#65xmLcaDwWoyXvBso^-GpA zn8*Yg2^Nip@zMDU(C9-j3`0yF|Wd57G+~?+_u zEz3hSOZybwh2t}Fqv5eQ_^aTpcCSlhY+Ckd$jZoUd&59f2U@{L>|MkI{^HP3hF|uD zt^3P{pk8R+`=IWrkgDV=dp#H=@vcb~uIpCM3UOD*^ih*hIJh-N%5tyfVQjJk9FT+rvB7t=TPkCwN86M;h19Y%>ELT= zo~9_+wpg8b?Qj1uo>atby`Xb!%dtQJtKI@~Zqn1wRo}yC%q;9!zpfIiN~Cst5~1^j z=9X8XWFEA3=pm|AC@MRZ8~)zX%LP!403Sr&l!-7l{t&~h)#nB{lYK$o6W^r z2K}2}@Q^;AtZU93TBDF-tzDyQ|0MMv34^h_Z}(E1?bT#qm1}TYBMAb!hZ@zq%rKaA zW%UhgmDii?b@`VS=I>vJD{lD~?66%E7pkU%&>VPXogI5S*yLgLsu<>n-zi4Tr=&G^ z`!VMaFAx>M|C&TF1D{93l8cMruLlO7=;gswS`hCUF3)swKClF8Zt+^JqQd@8b|tA z;vCWDMvY}(u!0Ajn%CLXD6PgjG-h{rBQMo7)P3-Zr})~P_*{vwH~vvWPKmESZ}j=^ z{%!>e(wtPtfMMQTLMPI1GtXcvwn$^g#o%>Ssrijv+pSYIx)+)7JgI3Hlw~-hGH&;S zQAo+BJi^&;7{?(24q59;kTz8l;{$blavN%wZ!>oHHC>X>U)Vxx+Mlv1OsDErWY050~;G_aV$gk#%AKT-!Erml-0&Y8z*%;K7GXJ_8c!+E6$!=L3* zuXjTup@VUJ0WU{aEE|Db5!!GNTJ$G1U8GFWkbLe^5oylB#0i~H8au0+42wX^LsOgK z`hn^?`=jP_9S@2_53ES_2ATr(y56*cTVTeEE!VI>)-~m{7ebAK_7}HZPP&&WN*<1% zg5}{@>fJw#mVlix7m|JfB)Wt@9t)LUmp@kGL|$OOs$ECy<`fs)*k@u(h>DUzB^$jV zKOX)loIdw+kNhGa6DUdibTUm?H8AbyyJ3I3b$tfw2uW$0)eg3WZYynI-Cjx*$QJ$< zJR6bur!r&X(prP9pI=BUYWW`xcKUf1A#mVdGn?BbL8=*H~uBsBb5QZ|fb2dtAul8OWpv}m-> z8s^`4X#r$GxwRpOYoW8!xMu=bXsO7iw8a&iM7pPDif)0!azDkV?X(f44Wf3l>~J2# z%RxTAXqxuGy2AP@H2V0xqXKS;7dMI1wT+(#15EP9v~i{CXc^F{4@=sd*5s-1cT(%K zoO8I_EMIQMhdt64v`BJZ=dF};kJa7Db#FGG4$U)|`=3*HVS7=$t@(-}dvbNln^I5v z^u;JTw9solDl7|{=WIRgH?8(jkLnh6Q6D1QKf90;ZLk?#omx0-WA(A5FGW{){;S{Mf7!#hRr1yd1v(Y>*(PJ-yBx!H2G%o8``DDb zq?`p=B}Ot;Zfd?$y$i>eHmx$T?sixL4TOixMUKeRJj5AlEsU>r#^DvQSaTQ}H+n#t zsZgNDn6@GiDI?mID$|gf1zXm=nPrLiq_@xQy6lv)Tu5%OrSsVat~GmhR+a9GeVMcd zSurl6AQ}I!zV}`v_lCuS&>E(%VI54Fe)w5DugMLiu_Cx~#zeHj4UBko$R!h@HbQ&$ z6FybvD6s1E;}#D39dMZY+}-jN1al=^jdkoeai|hX6xmrZxIAwz+ExdQ?DFNGbCk0f z3itS&*81ivv|YkH3+SvXq%VqET70wl14##oFvvvhiwepg6^#BcJ+4C+07~`|0!hbn zf4pB4*TY&qze2nknp;19!o#K|b?y<}{iEYtg;x784FdB&Qz#mH`$MPBlP!H)4IV+3 z@0uc?6Q=crKSY|EV*3RJ^5=N{XANa##J+W>y?RA#ruC~~A^In+xyidgxq7BE3F2w? z`X9XX$wIzroYGLNlkl5JKbFO^*Gd$bg@Ur15B zp0TpXr9P9>c1dnUqa(h%RFQnJO3Mv5u-RXn4hUU%?5e!Ck+cgjz%gj?&4}hHU1lJn zCbD8`K*R!p<$s@%4kpy0-JmgsfcUO;N4SW)U!Y3vpFh!o1Y*Yzm+9H#`u%DO9kE2# z-S~a~U{_XE>cRd?noTQ1R1B85d?qe-rmswXjc%;LbR%&e26 zM>aAk0kP$`Stbi!)EzY@lnt51FaRMTl!`u$*FnsBT8`> zWRX$qwjbvCSO3YaFbINnYnna%7N2uFS&9LJQ!py$r5TNwnq^3&BYch?JkLDq3bx?W zJFA#w7R`UIF>BwAb~i&N>hH>(18zojfZ+HOKG!A}>KNwq!X|f~=)@=ff#%`(sqndm z7Ua`^sBVQCz_%CbrG>0w?Kae&ZOVCZ1~n-pn44X(RTkA9@vPTRA_7lK4R-^F{sC3? zUG*H>X@NeWph2AtYR2?`s`ghznm4kgslI6xZF}M*04qlktjL*&)UwIX9XVO$EHaE( zWoS%+x6?AQ6uT2StKQ-s!g7N3^>t<+!EcY<7@NH(R)&&fXDf)muGNrxt?VaK+>cyJ ziT|c!8GaM86N$-L{U5q*xN#x-=A7yb`d5QD&a{&!BN(V1{{MRc1cAFvP=Rrj-)rLr zMjAiMvRecrukb}%aeR@95?khGk_WVVA@biuBRJ(Ab&Gl}*<-$U6q#IN)kjM*8ogzfQ)x#&8Hx!#k!U(ZvY_E^Ahe#39 z5-ou$uPUFi3RYEzi@Z{jOW@6I%A%xA*Sd)JO{H?%OCh>E!i+QjVz?1HwlGSp3j)Jo zKyB@3-!+u&H43_`?&@&oH)VK?^d3z#)WW#q09Gw6aNMJs9!}SgJ2^}piPn)Gz=1z{ zT?CKcqmC#7(01e}M*M-ou0G+vZf-+TRyAMvLv4JH3e6MwMC6p38G^sW zGfET_Lj!nHbcxHrgE_`1(Bn$~&dOyZwaHv7c`oa&o7z_aMsOm>9MRUMKFH+IF8C0y zz42@&Y^|u%o8bW*dPNTGqS6u9U}H^QNgK|A5X5nt9a`X}0@;+T%#}>Y5$XJG61RD7 z*M(SScc)>dL?lzV3FzbVkB}`rR6iu~_IF#1_&n<(YFPG`Mz=sA1M{%cU{eljY5V}_ z%)k|97Q<`=UMq{Lf8P$R!c1xDK2vB>pP;5itjuj#PC__Y#Y6bYF|$%;?=0e)jCt%L zn>{Hn6QY?0ohL{6taci$2a9Nc8Z2rosVozV`L;XNHAYC4EvPVS%qXj7rEwDfw!`cX$x6GOZZJrCo12~K5WNd`4d!7~h5RYaXxez)$#_oY z-CHcS+NRCd=0Khw_F@WR=L+YEn#uMt)~m)1vq_FSbO}O4*V6mf7-!sgO;;{+GIdv& zn0@1DP+-My@kwF6cQb)l;j!%%CEo$FHa9Q)#R#iJ)0cN~T2Jn07wd@skEe5BkF)=x zbz|GMZF^!)?4+@6r-<#wnK*5e#+taXZQC|_=KY`RobT}L>)F4(?zI*M!h= zLrZ9wc=2+z3K%BJUfb-$3keXk(DQ3n@kkPQ;doisKiAX6yHVGpLJnXg+aUqK-ap1r zw0Ukm*!I|in>Cw|4gREv&D?}r>eP6YrpyHYFZ;^nPKW39UYc-Fl(>ONU zw@^@*qpXNWuY8Y*gPk(wbZoGd1H)ruTIgxO=6Y+5;OKSyvX)bE(yz!yxcw)+deQkW zFQ~4Z-@OR2I)a^{0tw{H<9t&w0vk>Mc?M^8B1)xvdIH3zznQNoqu-G(baziD%da9g z(Sg!2LWmeCi}7cO#j@^0ggYVKVL6EeBP{f<3YC z2x5pjKq5AUDMuzGiu2~=AC&5=S|}I?T;7i8v3)#NiC*A8yx;fkNK@)PVZC->eRl|z zBi%T3U?fTlnwm9rYWTj0IxG6;kW4Ra3@?3`436SbQJlgYHvpc;7bay&rcHxcXE>F! zM{o-S8;6ujMLf)ir1a8u5z(R`#j&L`D3*|{KX=le09btz*Pxx{Jsrgqhk!5ScjQ*r z*A$?J%6?mY70VE&c)#qXR&IAMe(l|>PM@ly`Ry$#3>~TtUJEshGVg}*L-px}bnrth z#arLB)i2J7m;Beiuh7^abBrgO9U8PFpx6IS*NmFA<%Nc-Zsj z&z}^PH%2hPs_D8v@(!EXME{*`b{!yVtTIvj4IUcIuJXPACt%ZWG#~Hrozi!cdJUo5 zXk13f#!EYy0f8S1Ai!J>Md>6c`*EEP(?8P@2dpcRho*GxIF7$1_G0_>Oq8kW7nJ8w zRUo9FYut6Beu!|FKBbC+S4qtp`$mNb`N6_HpP2&VrsYW%UXQ)>+T05X2FHDD@Zji6 zFg{w5VZ&VG)>J-bsP&_#C5|LZ2M-?~0%pa?^b&^@r8DtRXnagT2+Lu_@G;Fc!-HN9 zIh?bZ6Xyu4jn?kk&+{K>!X6V(ng8G0T3>6Nf zw`(rn(%vC$|A^5n)9OEsP-huUW3oBPirkTiagfQcYY?ic*osI#Kl$qKHct*BN%W-DBLbQHM3%IWEJOpbHfuZ636JdQ^%+9r1QaKf2 zwjL>Ho}k}YTkiQ;hJX%1-FKkYR}b2j3GIGi89fAmz=&7cnpT!6SoO_aTxa?Km^33M z9)p3jRNI5<>K=FAR=b#+z*ZnO8(x_`j+evfEl7#$c{ddY|IJX!28q1}!uciPqBO&Y z=fL@4h6>V%=ZIdv39rokix4ZGPkD(U`eY1)9i$NNziiawF zE4pn(h(IGiJs=(Gj9xIl;P!WobfTtHwz=ee$w8s1ddpre{C#B|Dj&= zttf`UOa22?%^+gBM!x=mDzKcwj6=o~_l6WU`z?9$l1{_b&o<*^r1jGwyi|}JR3`b# zN*$O_9chu(GC_iLZ-y5^{dm69NOA2T5niAM;Qn>yCl0LaAtH2)oOiC-IUC+mJBRY_ z6*;NUQdBX5-6?YmtgChIc^%=uBQeRAgt>A$Kln%R)Q=CM5GI?U*n~(ev7D#2YJ;Z? z@9XtGma_c#x7y2qb<0GENG!+LqBx3Q9y0)jC|-(#e@a$;-ZQKu9_BLi9Ksocwc-;K zQVBGAGbEM(hycFi8a;Uk(`|{=8jb>)SD3$=z(?Bo)@9D4LP9SS;B(9-J|rh&`6azN z{jl?+#d5WL(1hc#=0A?ZA=qn$x%4c+v)qR5x;VrU8u(M= zcdZ)>rR~iZpQqC%l&F~jD)r!GRIxQ{1r7;O0YZ*|fs*^~-20^6ffl1bFB zPLDJfgP!NVR27|_R1A!kD(&WRZvR39QBWElv13IfwKL&Bh?wp?%#=zbEO0!&PVGN` z@-Jqt?(wZc?nsTj+?cYMBYvwER2=84Lt!u7V*Z1tgRSZl+o|djT$De;>dsf2EdO=F z{I3*6^cDW$d{sX4B)y`-i$9P!lke+!?{4*J8H0&Y{fugweL=x7q@Pw7XU?e-ZR&K& z$)!3hN1*;Lgm4g{t2K5rziSj@$JDF&(Za|vsS*K4%RR`$AAXmIJD==e&**N0>tftI7gg{6$niebsJ0C-l>i8n&EKk;YuU&8fd|d!He`J}9fhLzW<>R{y~O znY(HPE5A&8zT(OqNcklA^>ZPCYtenaq{%JraD_N;GG)Y)%34ju3YEO z&HjdF0$}wlQ+1;F%4A#4*w)!Gjo;xJR<0;fQJa2PN}O@H!xwNL3yH^`89y#6rKX}V zRuKJE;71TNL`e4!3gY|fe?!*^i;3J^%(gb5ip(|vbg;|Nj4n>|(k#gNd6Zrw7A0Ud zxqJ6hd-Alh(7`Z_{Lv$h`14^7S7w=tX6^>6K`Do7@n%{J>FXQxKxa!>r8KG*rJK52 ztwRiDmy;6EdopJdGp&mLUlFdhHRcC$747APoYf=$w}3WGkZPs544J>>6hK1D3=ggR z7D;t)fVqz`_H$h#-8`Vc3>%o1g^id_GoJUE^I;I&Ht;-zu$x0Irp^G0tLD|FQp)Jbf5{kcMG&xv0)oL)fLV#M<_Nh=+KaKcTK-3FHog6JqlXNc%Ek0?DQl62uKP3v&L} zgBIK>W_SON#^9pj+Y|RgAT5&;Gzs^G3lZ!!jd^XXh92~Kw~Zw zt-jvlO>l?V_RULICx=rZNqPMLo+G6usZ43T!B*UgpIozY_HLg}e%4HFZYFlF23P#7 zlyP<@OPHd3KGsvy3OJ+mIbZp{u%PQAh?EAzJB{wKckoVbywS~E61Mfh<_w11dslGd z`8q{2wA1JyEO@oCY42-SYy4)2PmZGnLx6~H(NDUlYJQG^vWzRP@QPY$Ogj5CGM#$6 z-v#}vwrxyUjc8)+c54OXn{Tl2JF$viko_TcZ^Q^jA^<>cW7p}Aa}Mc;L96CjIa|dX zzR#i9{?b~n(t2|SG!X8gQc`2E8mV%nY@aW&NzluQ@$NYDigRMEGdw!nsD)%Rfh0XN zfoc;<345Goz|Ym5{L$X;;#>;>0xlxBpJ>A}sOe7OHD^TzP>NIk=|`(Z$(j~c23qha z26_txJq1EC0RoVkFXFd)v~ly5pe54RD=G_}OOOLG;WYQPH9p`B3 z=HYS^!3{8SQi5~S33J#w#~Gqh+H zt^s3-BJb{N=jvMz>#Qyqdt9Q)y{z%I42XZ=SZ1OCcAmj{BoAlyeMOcAq~dCc;f>@g zf;5HJ-GPfwjATyj&^(gmx=l$)XvJM(ay=>SO*RX^)yK zFPOOncn%Ed`U6dwF|FI}wS3E)p4|UKbU&>sI%@^C zzf0Do>L12Tq5|+3ik%0`944ErS3`{37Q{|F9^Jh&ZX1&`oY4;Z0C5gq@?#?+pTdVY znhfi&Q=@`lw@;F=F83dkk*rr-CzdT2lSStBPx|fx8L)IR9(WFk! zI58(!kXkX49F>%up%QHw#`!+MVY6xZh%gp{!K>p|apU&(Z?(PrR^SF(oC;}2Sww`U zaf`=%q7}ZKgKIyWl{V=+!U6o2@|l%X2DU-=)LWKLo1C^%Q$qVlP+BDFlLPCx%>dnV zt>(r?IVpqS{jXfasO;k8ZCPSAGe~F(799zYow5q?ZmHGM-bO3ObrtAPvpi?2Wgxrn zcyX*xenXqiC&XnB-tG9;^ZK-xsvfsu?iGR_=yTb>vHp4mnbR#)x}tzUd*!GT5uFvd z8iuqG-1PjK@`Q2YfeFX5No2tBwesMNJFR;L0m<%?hZ`guihAkv6Htiwf&cpJ4>xF-B@^WMyA9=_kV4n3(UOo|)+>zV9(#qAFg1)#CiTB<`WuVUQ^{(1y>E z%xyeXT$2swi00D&`(`NY+XqGz#ztw(s?1s(MK?qEKeXoHLB`)Wr3e#3qWW3g=1$O; zxhv|!oJxq;QNsQ)lG-$1Ey|wPf<{w-eNs@7CB9GK4xdh^R<&z64-1YS1ou0O75nC#L$Nf$;s3aWn4 zy_LrlCKRNG5t0;f+*BwX=%wTg%qsNrM47aPFCCg$K0ILB3@`zeKI-#Kv2rSv1f?1~ zqQ6<5s+PnB;^>$B{#g|P-{5s2r*+9bcd`0?XyW{8ezAA*XxH!6ZZ98ZLa3_!F3#!4 zt*S?93~kM~PRuJUyrhSL+*XxNHP_<0{lC3nI#oV#e2^-WMv6l=`8}@d!~Rh%kMjMN zY+S;Gg+)dX&kvb6L`U0T8bc%E>y1@$@GT5Swox#w3{$-PFk`K1xH|GlW&$2u%8MYz zo|jZrnvV$^46vWe!vzm>pHzrXY<1JRa}?dqG|d?xMnWdgZ_c0Mq&=A7dbC95M3j^9pX_P6_TOkyI-mas6*r$|e>M;L8bU%j()4+@ab-mz z|9n>Nf+;gN?LX`bnC-L=d48=`zDquDKmpeR?0EFwHU#=yHg4ax79*r;CGYWFu<|_0 zSeudFtk>7dPuHwUE31;#_PE5=nh%SG*2)%3bAlCJ^ji#q1ZDY%SDLS9ONH0NTwSaB zn=*t+g;Vx84w;n5bwH(T-!#5qi>>+kGoqEoBmO*yZkkHz^jP7_A)IZPmB4ckV{~z9 zsC9z^9)##@$1vBJ-`t65fm;+-HQ=LC;w$`eb9h&xn1SOw5e2bT{$(j>Z%q61J{Lcj zmk>Cq@Z#1DyqGSAhkLrkzf&C5D_&dIlZ|rHbY_o$Rwi!_S&bowh~LK z^6F35fkFNP!y$=FDJ0-1sOz_t%Qj7XGxV%03_vJ7?V~Zh{bqbAWnfIR1dP0hLl7qf zb7%}D;Bp|eaV;NKLALtk=$sCduk+hxZo$BoU=L0rKBB-?7Ub-TEFoS`A`xVZfli8K z`4}S6gQ?UprQf=M;{3|vq56mKux7=3Wx;IUpDz7x=xC3RmyqQyLY1^mc7tF0;AiGB zFAr<|)giiT<9{ml)lkds(G1v8o@nfEFTt$b`1EoR8GqO1VM!~zLJtv;2SIfdRt<&t zK?me;pp>(G)UH@$FE4?M(uN|6=GV*$_*cyL=5qJL&pa37jhMeHCE3WBcs1%6q$TNO zWi~D66i4@Qj;akMeU*{R)tWi^i+v*}0S>dk3I%L2?N`b_^kYEV7-Dh7K$}_Evsu_R zxq;*W&Tp_#d4f=XrFkQ=ud%cf5^=(e3wcTBp<=0Wl(D9i2-7>AtW)(Hycg&inhp)vj|BF`ahk?hP5wcd2$2tg zwT=SuotI?{z5FYwAhh3ZOHhFRQ^euy5FyVbHYKuD?7W>zWTiQd+2GXOJuwVQrOiNO z=%Nux?c^3CKBftVj@|rzxwIVC>}F(sZ!;E(E>Q@7%-Sixuv+!L5l|_aCaf3K_`A8l zsMPqspP$12{3)x>omq)H5#bd(0A32C7s}-=Xy)_8*EMcHPFqcS;-Y#ugs=%QbpD>= zgVqMI|2}_y35EsTon^2QF+sbCd$C{Y=!&U{z)X)uuapZ?SlgryDkd9)Xk|nb9rZj~ zCZ6a@QN%mABg6Y)1uPm`rPGu7t9~~uzS>!}5(Pf;@6I`f*HM2fjT6^rLYNk~54lyT|3SsgU9^02+rAN#cR72^soo;NWr;g32>$s+l{ zx^`bc&NW#>V{>r^$uzP{nyN-{zpcMT^V)e`p#e<4=BB}I1Rz^Z#be|$R*=IG#dl0T19Y+2(o_8ubC1-6iYc?&y!2A zWy+EUu<80{(*9J5Jit2;tp)YtuDbH?`{scNVBTADSuqQbBXs0~eN%)6D*7=s z?iV>T?wa>9FyNpsF)>w%9uiaWc$k|!(%?^0wJ}mUkT2G#ZOzQ{cD5NNIu@tR700t! z9WbRM+|7lB`IDJS%zg_-_-Qvg@l|d@mFE5LVdfk}W240VT99%?9D15Q_et9(qHQp~ z#B-b~@KSCj-Is8a)u|q0@BJ2#^T)~kCChy?44`dlv4L883CPPlaF(ueT4B$*#CzB% zI}OG(+Ngfcbf8hnd&>xN?3jEuVbc5WA&32+a(L&H<4QEOA~|Qad-(79a6o*pE*|~$ zV-D5|@=`2Kd%wtq(3_VN`rx?yCBAdWLvF)C61QswZPVbCO&^e-3m9|QhZzO)tYZVg zRic*dvLYhz?}luO6{sc^42aTb8|=IG5Xa_*Xlr#Ni5*t)x}amAk&21`%dsNYz)`!pCOW zYJ`rHPksik3@vSm=6U|B64fyS+esA?K%Tum&L^T@Ju^~%XKN!rUT&6WRzVWfyq3c> zAORA*DQZ~6=0g5Au)FRn=F5XE1blZl*r+oaT&1KcCRGmm$<929WfNDw_efrZu)A1( z7(ETmL>)t7Zvnz6ar5VqJ#4GGBq>KkD|lSbaO*2Ql*1YQ zeUy2Slcw4hJu=8x)Y)Sh=QZ&L8PWKzA!%K0hR{^5bP@06*Q)(yI|-MV9c{A7Acu{k z8CbeBUF}?8&I3i;B)(cUi`!eKk@U`H{ z{wG_!A9K8eM0^i|%$|z)Uq<(gA}>uHwF&$T4Kuy?mk3U=kO;SfMoj-4ir?CmzmTnk z@a#%*&DAmcjo_R|8`({@;0VjsXT+E?&OD+MRmO5ATKr^FUX!hjWY_!o!1VliY$kPJLy`$q6)( z52%k8jmiTi#j*(46yd5bDRa!#G<`?0gJV1dxe~%gNKH5CxjORJ(G@y-ODhc7qNpzm zuT9v%s=*)zVHH66{#6Ro)`!ie!t6sQgmRa_9wM)ZOBdiz?>KP&R;JEu1P{swgGW4iVn zEg5nsyso~LK9hDZ?_WJ1rhR!~jud%}n0nlz!f!D!7>PX6iOy-zAPj8ld+J%H6mZn; zJH0C|T}QYWtgr!%M-p3DiNMF~42H+OD@l*EN+ZEEmD^2~Q499h^L?$4X7b6Wi)maP z_vAv-udZ@ zHiR9G+mx|K0xs)sb&uP=%zjS?l^(L_H60|=;mi`i16mnv2lw3}?&t3cE{_Cm=gi?1 zp{IQ{5~fg~hs%oI9x=$_i0f^1aQ29Tsmi{U78K&~LK$+mAVn%@`rRZltPFo;zi2MD z8%>0+A>{tGGc$#)!Thh~Z*JTAF7{|fWu8~#QcpQZ%)yxThdTia9B2mDT?JUjFxpsM zSVNC21{7wDCxZSHGuwd0*Pmsy2d9oU0L|bo_QZo4@JO8>N1c(~=VkGQd<~Mif*0;N zElpn;Cz-Nsvty@*!El^@wXx1fN9B2RQ7z9%*yFk}x$`x2(!z-~rf68`X2@ZtAv_1) zzs^z&HY*CXD2YlC(AY$a7ThI|RM@;x(YM`q=b*qh{6Y^6go2iXt6HPCI}%lex%t%| z<8IIN*@CXaIHHP4`foKYHf%7WhE57Ul$^mnj+NZ#79*-EWk4vl7EEeXygH4DMC{rO zDU>+0j@Kx`s4h)@4L`HX&hGr(Cmor};Q{C0b{o@i3bth6MkznSj-se&@~XQ4`>nOO zybU-m*g_BdTCkM^1!ctm#PwK1y_~`^AEz1{t*q5IA~g)pao>;u$%5ffrxoN ze&|E#GZ?yd1(N&0AQ_TmM%%SH8Qb7=HF10&1S4>kt$*!)mo*8{#lpFEcW2J6(;L=L zr0_1l8Db&mTXQ9HJnp}FMkx;)0QUS}+s$T+F16A#lyGs>RG*WjC5e>0LscuA!Y}4y6FsN z^Tk4lNEj#vIc4&{xjy$O)2R%jXukW={$j3&22|$8qn}DVWh8ZSg`1r7#*Uf?)`}|E;%f&)W$08jKRr0tR^6JUPzKhIAo%`@_`lmu;o9O+Bf;e`}2MwKmSogk*-oMri!DFVubg_)(gZ-!D<#Jep`v z(&I;r$Z|tYUrsdD6105g*G2uOCDW20QlM=3FBQ1lDU_KiN@$BN){EJG2l8eGVVQ-# z^9>9P3bNbJEiP{Vjn)zjITJ*u5Q^)IME7)J)&NRX!X>01)MzI6mP{0jJ=X|tp_d+B zI2v8+!_;)&C87YLugEn{vA=%xciF*tD*xw?@^AAJ((@7AkroBQ9iCc(4!IvDbV=0U zOEjGmT*8$lE$ctVdfU3A0{cE-CgdaTZUH$=G(6v5n5-54_KPzAi?Z%;qpVWUqU-PI zWqxS*&!JE7DS2nGg9fc1Z`9K)B}ImJL2O}h&=2L7poZpUoNsRzT2Y$tfpjpvd(v&P z9Ygt;uwx0UTNRBanREa{oua$lbz1-V*nw2SR0>a4o=-jKFYJsIWg5-duHQJ04s8w( z7gqoIs^u?+STd2esi~fP|5->nlS9)oxqN`W*fjXN9@zaGpnyG#QKUT@FW^riY5?D0E?iq;cE3=f_o7DCPu<-l(NyGixe1^hmEWn>*> z0NP5Fl`U|dU)jgXACKi>CNbM;TFW$5(lLdR^l(OHFk2RWdBjHgrY`kJr=@cnT;+XU zDD9)btDLaoC4?xwL8wquMe;;VD)W{s|Z@|2L&r|5+{`d`6wto<{;% zF|Fx9xdm%a5%qjr`?S3GOAUUC_pPVC>$Q-YaQPgF^yN_`&j=xK$f<@iCa2o!9n~ur zl0vA0tKu1*ot`$+d_zBlGBDXltSxWvcOP1H#WM&(({Lw{6<5h;Kga_jKS?DhIHUDq zxoGOE=^8aemr~+VtQIZrNRw-&eQ667h=?_d*GzZ9hM`ehBUT4-V}kyE68PKzH!pJ> z_l`g<_@ad4bN*AxlPrE=;U)f^!7L0sd6s0rb?j0CI+HK{oTV1nuZt#PLe-4yK(b>~ zH;SPTKKNr^Uh2xETVG&LM1u*DjZ9~?cUDHgW@`8J37Ex~3E+~*lyp4NrevJ>v zKlm&!Px5fN>FOli;qju=R_wYn@O#+b=3#k4Vm2cGb4QODo|pRZbHM5HuYK0vS&;jb zl2`NFu42g_&n+Ot?Ltp6Z`k^oViX54dbjJnkL|6m#)U0#e05gqyI6;KT-@aLVu5H0 z&<_7W!0if2uJn?7qtB>3acjL^KCZb1hXLBI%ppJdPTzplCaMb$^S%UOj!${kLP(_4 z$sxuKEh_;x9CkT!gix~E;FTO&D2hG_6tK7@K)~sC4V?mmLl0TRXbr`NDEjp_B>Ge@ zrB>vWs4`-K4oMaAC*mOwD^PDw>t6+Z>WCu~;5C#*RO_(rX(^Q+>RSJ$*##LyVhB4<6CocVkgFXZs^%V+-zcpdLiRXUwif z+*ff^7tOKNQk9vI#e+cJ8H`4PY&Y~g2YUhs9m9OhrqPU}U2NZ#CY?isf`xGZTpH(8 zH|rR6;zrGEa7a=zOG6GjdK{2CO!MA8bUabpKP$ zs7tK*+=W($>>_~Q!?pDc`9Ea2zGj^TT|&jtFPW}ea!)0pXxSz6JmG3EQOUF7h=JGyQr z>w)1^*w_jiKOg*LqZh0{wc5tHv_T5KE?5qkCGrd16qGf=NmLECRmo1 zPbAk{PyI4(1$|*1DeRg^7V>_t)jQM4S)rzm9cIA~0!pUkS*8e%5+PxVa~_&9{{Y$c zhz!tdWSWIUb96m@;df{$Dml-Dh<{a&q&pGkgisNBZVD+Hu!t-~=eO)%(MmCFD6ZTq zbK;n_0zO(^o0K|B31%TSv9(KMke7d`psRA2M1aI}Vb0!r8e9|($ zAp;mkR5Lw)Ju`Xoe7rhzJu9Amcoz)fRq5Ma)7RLUA!K1lXR(?u%gCkWM6^P$p);blQd$v02{{W-ZxHU&p!Q_aq1Cn z@v8HA?WrN5=s!uQRQolukI7<3!gaAL3HNc{h*M?Sg_ZE(3V3f+N|eAI7Ue&z>SO@L zBqUZX0dLk2XZZL%Jw04x?VrWJa5M0cg9>o3mJbbr0>ooOhz%(S+v431%5T_smFJ^& zR~_8U)wA-^ZX5jd3azy9ETh2jUemj$(WL<+FF`?EN0FE?Gtum#1lrbpBgx}j&8=$2 zkxhSoMCAUXF0I5hp&TPLeC25mECy~GZxP24^kt!y4@oj(4| zfCLM@6T6E2Hd%aF`sEsu=3*1g*k^i%&`hMczhuYlHv%2!!_p?%i2g48l;o55^7_gp ze>yyq?&{)P^m^VA7dVE{{s2WoBh+>}v3(Gaq$IUo445MvW#Hu4ZQW3;N>(W<-$iZm z1&7lh&*aEr*0|<#-3vk5)pxoc@+@X7cC*dgS0aD>$mef@pU8XtR>kT|bV-T3 zQx?}XqKJKxK3k)KcZt~KyqVy$5->fX=#^|(;2zcUl0Vm!?>@eT>ASCa{5+EW+uw=- zYW5HcAQrD+=wfrgg;&W25sGTi0DO&S2gED!?_yM>OWT7>f2qSOAXUkl<2Z!F?XwtB z2clk3Kt91>O>Cg(j%xz7{MP*Ex64sd%rLVq{ z9X*AWL5dog!N=iZy=4s`=LpaK zTc_+zJ1jTsH)LLZ@~RrCsDUw*An|^4PqAL-c*JH-=V}>QEwLN4amKlMt(2HB1G-lZ z&Y0c5R6Lp*)LjF{;P{yJfdxHN_+@*6s}D)2ua8Gk_Xm{hW~T^>u_B%(u+YRynV*^# zpRQJlXw}FSE&lbulZwuD#}^hj#AYLciVu*_t&(k^;`73bziBev$nIq)IgX3q>my~m z&`I4UnH=68i9w>@&AY>Znv=&zM}=hKgIM3ReN?2@Ye+^u-vSE-A*rXE@KH1G55bPJ zB`w13#pn$pG4t96oR0d`~T&}K1`xPO|#{GK^ypPH0aOUD;07SrZ!DW@; zWY|oWD6@ULs&g6uUQhiP-%j@W=I0=QAIqf#7$24!ab96)3!6^HqRC&Ino_{aglt<4 zSUbV*zNsxfY*M=oGXDje$PLPmrv`QiRrLZYzhL)oY*1wTT}iT`lU;*~6boL~#FKnS z#C#-FadAX=U<`>jOp1?>$E5O3Sz?rx+G2!AMkMdt6b*=3 z5tLcEZli^Z{JrJ5*a5wiIq2xsFCJlx{8p>Hw^9SW zbP}LYahkOq1ppmsbVX?EFkd|cp$_vYjPxn+dF2xN(Tz|rxicXc&ge3g%fc1i1$7y`Z$x{5=a}vMfmyHs z%e19rh2UX>_8l(x7UgP_NV4gY|E22#x|zuGnG80_hjRRNCh9Y1BaWH%X1~~Grv=4q z8Y?lt_6q9bE|2W#7{kYWa)a3m>ka)o5}?+l9=-J`-jHY&Yo1I}EtpF^;kc3rngN4x z97o`U2(1oJdbcq~Q^r((Y+*cAAFc1jwb zF$tm{a*z7vo&rA_`ozw-d?aI{h3S1CLcFKOMKA0AfrF{Q;ZrzH=l_cZUIy!9SZhxq zNFyv8$fHfZ44PZ2khKM);#Vj$K!KzoO}t2Zk@CqD#QkTSblQ;?X*V(0BiUtGeun)8 zrL^fI8fco}5=mE}|4Ky_sJuf1rQnAoRw01K-_=QVgClTzv@zv;^#tY0DmecGPRD%{=k2SH3E0Qyiyda4FFyMZp zEuxm|QjTi~w@GCR9fodx_=vN1JM7mwpiG%3$vCZ0ISch}B7nKS*4xAflN*ZuJ}QYj z+~O_czBc|y{v7`7vg^Acr*nHI07ASUyWIG#yr21E^|0#D5x;Vyvq&{_e;Sl%D zCsg_M_1xh#WWxj=)ET<#ve=lvRxKaSqn;l1f(`>bFj$kZ@0_`ZH}*%V{sbJOPgJr^ z@dBy|tUX@r_AX{Vjb6c6g4YJ)2NO&X?0NPvK`7!?7ta-P{E;LA$LzrlxUrQ~CERyn zla!4ydD=89%O>AD0?kUfRu+#s!Pz;&F12<_vZTO^J(d=OR7d~m<)v>Hoz|&U@;R_Q z>T51|#Vzy#hV;y4IoRv<9*ZNX$89*d+z(^+eQVpyzf|Wuwyx#EEA|8Z&HeuzB!9^> zvN63j@D@`o-iw7TiinIr-D2p2SQ*!?z~5IC(BiEZW;mZAor4ENyL2@_f5xWRtIE-- z!^gu}4R?bh?^0EN*rKx&X9+7!7PRiDdK8oSmW4V|D)I10Ihi|vBJIDFJP)C=hMZg3K4W*4<^ujhu%MZS%YGkSRD$Bv`=h zaRF_t2myGfxig@gAekd`Z1P0?%1<8fD42IWRT#Pj)%KG@lemgN;&~YTZl*iXF$be3 zsoSh^6coVeqp>E7Z9f4MlX+CI_z4K(ix5Z9o-v`u3*>8xf&VKL$D0?)n#Z%&k=_@t zEM(j+o_HEO%S&3&<5rdYNrmlnA;5}e0~TW!b{#1Rk9%p6y0QQ^Vb*AE+LCOky$eYP zK8l*q^2>|lr1yYGE`&b*#2i&2I))RKI!-SZlP_;+EzaYgGJX}!_)&4!kQw=-&NPZR|?p~%1LgzsKqn26IC`kYbFViNu*CzvNk z(pfW7_a==M<%1ngIxyTi@mG|`)IYU+6*<&Y2YxIQ(wE~u zZ4~MajZzt3P8NmQA@fWd%)!?;l&2SQeYl)$w#Q#)kNhj>c)UtEZJC7YQcLxmK}pP&skchjrtOAJ8FEkJ!b-ip zQ&CqhfA4H-4hSIT>HbtGX}-j#W%9W2+o<_OZ(BF`kzfkkqZ}I`iHA2%fLF`@s|)Pm z{ZT?`;x(g1+U#Xzsf(zE!zD6{flBs+1tkw_+$h}Uly1a1@K!AZm2xDduk-ZWpFZdY z_s{9CM)Bq9!L$!k%9vXUiHm5Iy4(OklnN5QbuoPTv@#AM5@FlZ4*?i}m=(^dnseV> z^ni~=|7gt!R-+uHL*t>SRc-3<>}U=+Nl2duj$3jrTd~mvd&T`X^6^rfE4xyGH>HC= zjQwpXUh^xyRbhObKa&Se5n4Pf%ie3irRLfNvdhL1i2BCe1L~WG>AVV8Iz1|o)Y?u^ z5-Z{}v~I_mA1Y0k7q$=_ZaI~Lro!#+t8jL$uO|<`#xJMY1-6EZjJ{y>F3D@6kc(`q zewJ9tU`b*7r{y3z*8a3~xH-9=ZNsT#ShG94HFrb3Hb><$&#E0$CHS^{S6{kxc zBrSEnw+cz^m$#ptRtGrgYH(?mAG5Qwgv5k@(^>Sc+98b<6a`O&buG-mq4D#aIhBfPHupElZA%YAnIei61Orf+_R0v_@!+H0p zw(du7IJIck<}?-^X&;oA7KvVx@(Q7Xz2!Ju1aBMNKELM>3KNjYS15A$^`doW?>O!h zmog@`_X`y0?|HG`L8$MiXv;y&k0+eFyGKw?*m+hB-fky4Vzt`*NKw(7ZEMq>H=94&v1FtcGdYgaIfz8N%5ffm5}0j_*D0=!NhW zIiMJ4)R3oWv|IX#>wg*SWmv`QqeG0ibWh1tfc?u<6PT<^3O-70ub^z<(g?0VUqteS z#bR_ue-Uw>u|!rLSOgrQR>rDIStK-i?IvAN-EZV%5IieBA9b@R0$kl#mio%HFwGC^ zVYq=n)uOx^f3&c_tb7DBj}H)ZFsG2N*C1DPF_uRF0X37rU_nD`BP_!q9JstBhrYs= z6TAfGk`%MYmBJUxEDQOfF;hx+!FcM`0M5&-Ugmv_cvyFB`Lawf3t@70EMkysZrA0e zMjQG&{H-kVv5;HHAh~1kQ2}zq=O6vrM%DAn4g4z5Ko}W9QqsMKJh$))=@7x+W1oPI zbZ0O#)?pP0n2hgr=Y{-p_jCQB0dE9ofJ)KIePuDV8l!_CXIxBGG?P}w=^ZOSyCpYv zyCOXm>wLqkC~uxF%1ISt8~2n2^@WELm8$aZ&`sky!(` zN*S3#GpYd!?73ZGCM5Vxk zJ7FF_vrt)!oB;oKFwbF83urN|hn>RBq-4L@W0lq2L<2Eo`TCv~L)+sDK0v9l+q&9# zjX()pw(jYh713Ga7Sg`P56pRYM!XeL=Gl3>*N`Ec2SE z5LfxeyZTs=8|mzvfq-g~53?;pnWryR%aKgd$a{NVyx<{Qjb#D3b;B`HUFQeku!Rigijk<9?Uxdq zczP;-^R82o__s!Wmu6$N8o8Yc51Nx;LUrUnRKs|j4gg`y?vgY2qwmW93xJb&_Gj=w zG1SnRig9*+Zh)4*{)6a!wpL=@(dmDu5|4vfrr;EmAs&@Sviiq0ki}HUIIOtF3X9NY zG8068LXdLL70!XKm&kuw6?8JB;ZMpiC8Ia~N$C>j;7g9%ciO5@2#gk!9vUlgS_rvjUto@?Qw#D_@4<|`Zcv!TCH9HqV=V$V(=VGe`*%p7YQ zL6zG;J&vd8i0klk?~+*{NxO(kD$B303os%YN-RzW{(CuGG6T8*yrg(hpv+Y22uMgn zJ_H(Qc|R7e=V@B9K1E-FMSA|8=A8UNYG1$KK2 zQDaHXJi_9ucuec?_qJt~@@Wmy-cgP&NX(s2lE_G`meQ<-WL&f^(aNAe{$t(;C$(fR>?i@!$1RgT!M7cQ^h~bN(-e|P7pA9LCEtK z|KOD#>!bi+^#%XEY#F~^3vmL?EnYcT)4rOrE1?bMG+8}1?3wJDv6`twflFdSN2j;B zmZ)>UFr(Lg_gMk;HYn3i%yaJ>S_(~uXI698d2YOsZ-wot65%CSB*rXAVWJbUbr5tH z4m+~slC#Qe$JCG>v%yjus)sM(!a5#|1hT%)@=|H-7+3Dl*>DP|Q)`__Q7I~7MA~sT z3yY{e`4W*3cPNNOXdPaW0^;VK5f9hyqCmg zQ%~9ep6jf(o_qJRxad%x1kPc}#>$->4J%oxm=jKIiL zruSxs186;?Vx}vl-v>GkYB*H5H{eq$anQwErkb`lGn}8%7(@iF-zen$;0xr=MlcOw z$~@#=cY}3oF%B)*o&f$5E#nP*E6vleQ1wxwE#x6%j)~6?@Qwjx(TsGUB?IZ58 zEM{qEzd&pmDop49q3N3c>iolgwQSoh+qRZF)fSg+*Ga3EwN)o;opkcDZQEM5t?fDA z=XpIp-G9OLxvu-ob!f3#%nE)8r0N3U?WrW^>DW+rd!%T;YTfV5j+wz$8ewXE*ayH? z@#>7+#3VqLjidR8Z$08f`OLPg-=X?o$KhLUc<~pf7hr~{Evhs3XOIRFGW~KN$!&2T z@1Pr|^t$t@Wt&#sZ_iz|*6d6$B^7~pwSQyHIKBvYI8@d|*4()4gBTiQ!rm+ycwbSmz3z^zXH9uy z?DFS^ghzM1x=|Mv0PyOpK7~;q822TbguhOe=(U{Y0m?GPq<-HgM79pbEy z#9lU-c>z43+9i?9Usir(;nU0g#iVu-wMz65wpO}7LViPQ(o7ZrX5hzUo&F(;Ad!z(j)rv*PB7GStx1bT&wS)Qrf#(4!ZP3&*V(R2heMfY7x zxbp*t`S)GB>?O9zsqWp>8Hfj7BJ3J?#e_ASOM&o=2i&5{&P&m5PmB?XrvFeAv%GS_ z{@eO+c|F|j=>Q}4He_la{L$NCdU=ZAc_-c82}5rcad%StVd)fEw{xTZVKsuHT5nE* z1pmOD7%LQUShlc0VjGh#QQ{H_=)EiXNvf|T1G6xU;i7=>n#P><3t^O84XRC|RFR%fK~kOQV%zuTXQeBX$eTyJqt zaU>jSP;~Ci>>&m?wD*fDToO zyTwy1j6QVDzF2d~yWNheR-xeRC!$^muED4{!DGs z9dtE%`1kh>d!eh&QjpYCgrk8)1$cAjByq6^Uh5}Pv`uF7&K2qU=pyh==0~)j zt_rZ?ogulMlyrZ!O$;^AfKEbwcaZCpc{NRdd=2I7C```y>~!q=%=qOb-M9zk>(Jtw zH7Lk=cgexlZsaN&2EakFd-j%qd9qIqK!XP}g)30Agyp?GvHabybeR9E(IKn9hiu0( zhY9zE6 zk15n6rE}-_7hYMP(OgJESYUyQa+)!WzKDSvtd~u6&sfr4xTcsdeE8$mQBWokP+Sal z3TeQb!z1qS!~4)BmN0@fN&VwilP0;73W#w@-x=z5f*8}!Oq)I2Q&k%{(A@As#RqU#wHbgYD4QK5*NeC{X3V&ujN?EpJe z-tSA;owO&otwo!{1+O*g1?kn5Vg6aW7D3t_~A2S zdS~+|(kO3OI3o#9AI0f80%+Sn$J5@N@q-hbjI>))4dq{RJ`lXCaw4)Muomfy(KbJK*2kE+RU#jaJSdY? zP1PH&HRC#phsKVxB?zLRsj*TWu(d|I(EL^*L1%9L@STg*!{1ryhWE+q0lat%W{C%2 z+8N|3qfVKv=-b075_QOSqM2NVh8qB<(Ro9eetzxuw|_yIoLe?RgYFO)`9I0WvEyTR ziZi|JCO08J{7p}tZj~gPu21>##rKINxT#~Ncnm_u>kuf1?K6XEPoN3P{4@y=uArA> z^|!rBb)+a%9a9Z$gb)a7jDxj>J3~lFqOeh?cw7j#yWI2W@tEe|M399sjEN{|chg@H zso0cyV#OLTn|pyK9)E`vNe>6~e0`JKy-?r)y#Q+=4#dm#-r;?R^rs`91CDjtCA4eu7c5$n9{=2GQ@)Fm zkg#8{P$;FMNlGYXt|=-_&~rPyV?)T@7th$QGzUxo_r}zy0Ey7Bqz&DL{~dM4t?1@agGsXR zbM^~LHQnVcODA{VgK)uxb#$VWzsMawZKBArm2L(RPc-J4m%>RZu zxbgcc7sWE5y?ukY0#(kc;z0c4eqQb#^a4M&i)94hiY{u)@^&s!VDFEA-HDq;Tk@@| zU9=t-#=1T29EUi_(k<|4<4-lKUhUBmIOIvFxYc?P0X~0@$Q;#jzt!wQ7Gz5*+G=!S z6=;n0{{_eIwU5usTwIdj5);|a#DM!}>BQ0f6GD1vUp~z*1?mh!9Ml$mL1k--P53p! z$+z;_BB8d6-`nD8zBKy=v@PY{xS8v|8({(tS;mKVk1&9Gy`|~p?p9sWQyn*=DCN)O zRXioBhC|Sl+}*9$UH_+Ds?EOmEWzoyxe2w>wA5erGo5yL(A-L3rstL{cJ+){--_)` z+WVAmNn!C-1ZCqm^L@~stf5Pm^#5T}Mf81)aB|ne#geUep4}f{0keR9EJHNhiCX}Q zH@xI~+Stf|oNtbaN58(*kkfBRs2>%b$OQ z8)n)-zS&!%`#3}MUC2TpehIJhEaeG{ipZN`rCsc*cM|w9<^hhFRFrgwM>U4cz$Of$ zq3G<7$WKfkLYXN|vd00nn8S0v#9sPMnyLP=qYFNoAXg-VHFr&Ijc5rT0Lt$)k3T#f zwn68-8=$p*1PdpLlk@$FOAFm(5e$)jGLCq#E2#VLTAwp689SU45 zg9_2^>V(sjj6R?rm!af-oPfFkHx?mA8=a>~3c1z`Q&ao#rmGT+_+3wum=rr|En}k!~UX2wo|qXemE(@n+vy zJm-oR{OEeh;M(Q`yA-*+XclT4;@EfH)I^ttI)3}xsT|3$$sb^F!hJW2I*nQ`f$6%5 zkMyhJKKjes8x88mul6Q<9s;M691aHto0d|L3(>DkEG!CN*$2$6_&Ej9V9TM&D|{JW z5B}(bgGGNjwXJzUgO#4^=A*{O?3awjEOaI6?3|k6lY~%gei`n$dqY z&X#h5Sb7>Ggv>UxFShq77}P50b=M{7`1g{3^i2op%leJ=VZzwR)sjmKjN+TU6K#YvMv#kM-NI5Hcnh!n4?yKj6h z%v*c9Cp9qO2{4DsvWfpuXh9vLA%Rgaa9(xMboSP>ioe})B;Swa-){f4%TdSd*!*R2 zbSd=Rd_dJnb-SH>Af`mynY-O+UXh$s6PbyvK-|McW}-dZCgbeCu5?kXacZNovT9)( zK1^K~ochZ$twQF3CWrD)G3Op1f779!x++cbUrNg9jbAEP3jJ(dc#14VL6cfqT*DC(9 zBEcr;X?no;!&;4Qx|G0hwz&|OEruqiB=`jtn}8AdF!airXSUGtgoE0C9u^$+(BQOg z+ijM@Q-q2r0J7Cj4_1q6y)@6pdV^mfLP<9g^GWNZDw)*X`Of;8IOlMk5J!+SZ<|qS zkA5QF`+=*LRyUENBO>k5rEmMN(QK*H=xlkHzIm!8={B~Q18Lsl&?)u%!z()WKK8QK z*E{R4YLc@?a>3jjKWDsXtJVW z*X1WOI6$9v0WuaQwR;nlw82&u824E|^h--D?=TIKtvAPU-kh8`01c#W#8o_vhN_ad zVGv!B!;j1dqK&1_$s@O@=|z=`W#Lk;g5bmyKRjyQ)w4?H_}%J^OU8=I#vY+1d&6TJ zvc4^A9@>x%2}ch8S7+&Gm0vF;dGi;?HjQ#yW8;FPZdEOx@MJ>6B@A9j* zwyabcVOCR<>1`w7q=UTCA0iKJ`58nfXY>$$idwc=-QM`bUEf@26bsRbQBUB3ykKftpL|%o2-98yi#5a z+n+9W%}^2j>U|DSckDRtI6f2z>WE0qMbAUVrWd)Bsmf6-o%%BE@ayRlqKr@ntVWpbc=i zg!ZrtKU6#R_2}uS7HvSa5Y)Zb9Iiv#QOZy;bZ=?Y_|TpBeI!W243m8VWR#E?s!J_G7*Xnj%(~;ZT<6LUbNGI z&2j|J2|*^FP|~lbjI@`!Bys>wfW;D516bi{7rr2$o7qGCR{gsgB z^z2nS8HJjF^dd^r@s7Vg{p84RAsL@jj8MQnry6{_f@e^);nu)sR%ZR>7WyRdP2$xE zHU*>|mtjmUALPz&^_hUSq=>u)su|!vk~OB3XKlKS@LA(vtEG}dR-RNH;8qg172iWY zYp;zO6QmVdQo}4&O8qX9A7l5~MZ*KxaP6?hOjaUgG%cwBS_HJPHw-rB3W>A-(xVA? zho0eEey2_1(j`aiSNbkQTQv8R@3M7Hg}N*fQ7Gn_qx^6vL?%XA`7j@bea48^4|SjS zA_E+}W@+6q)aiWC0v%RWeltI_g;WPGfl3T2q^Q{;16aW2?T2024*-^{)!2^36Y+*) zsQf}!ApSpoST5xRpVNhb%lNfDm`R-OUB7hd>*@7j;*ddJgYg`cUAkYbEngZ-a47ne zaCwg`XD7?R6_Z8nq&FTh9+Ti&mV95tWIfWttB$51YXsUV+DxWgZ<$jRr`(<2np8)ZsR(@Zk2}hGEbzxO_rzz4% z*H+;fMCb%u+U zh~nJpYNdG#*VYXS%YO5#qRa~;g+6LAO3#{b#8CGyD$2)Cit|f8@jEH91wy}@az&Ql z<=m>0o!RJG2fJYa^8m|Wrlu%^UHTBF`|sTDJD>EQX{9lB`FhAni{PeI>r>NBy93j862^i3Vz&{aNB_fqdf)zYTKfYR#@Xu=(pW*9b<*fiE% zm8g}m<3GqTBPF9<-Zq~f)|;(Iot8QydNO{ZdmH#;IFI!Sjz&TvoVcfCdRoYunN~!Q zEA+Wj+FiLu!#z2bI#MqTb-KXuH}RIRoBR4pX&+k?3)ORl35`mn?~Z^LSrze2_t_ zg($Yk1lZjzI&>_nYDk&%G#akp4ks*y?+)A({}EgM_XrH22|+GJldUe78~{yX>F$8C zI-4E286G~^qPzVYL(u86DSrOK0s$UYc$$R^Wi3YhK$Wu#!bdK8?+S)c{k@7*N`PDj zJc?S2`Q8^`u+7a}2;uw#hS5T1!1fdkmi#`t=u@MrMj3mxz?5_$A zkIa3~>L@rOAwG;?wG_kUZ|@={pr0l99NKnYhHo}? z(INEIOXIjwi=Z~4##GJ3_~|gfsp%4aKMfw7gz$z(vFx{YHaF$;CW0pK@PTqAsOQQp z7{Z@8B&HIt(j6QU0jsaNynaibu!DKyF{duSert@5p>TcsZzaCzuPzp%4YNpZ^Fu33 z`|mbN_ILz%W-(&Mp&gg4uK4671;}(e%I2B1^WBKBtmfT>6HUPR)WHY=D0VTGMd!;; z|KZPHoaN^0GZ+Np+B1#Jzn%>5=;JqMlKVs5VDmyA_9tc*zC?7|1@MsKP#VOj9WH2c zRI%m01&5+e9LoNCg-WpU5|Vn}K={@hVMm%jB&ZFRJBA#Qr9AO7ARg~s{>cxx$ z&O{FURDk@rrbxCmP(tN`F`C0>`#By!9^jTZNag<90<9&06tbSR+}_@;>^Av~oN0H# zZB%5ZmRmwhLA?|~^#_}2P*4Q9X4X{)01gcK-4bbTFI@k;cZZyrJph64xP z6;MG>b);{vO0+@aaL3@q&27x{T%S za)HuPpwU;WqvhlC8(^+YFk~t@Q{$Vlw`xg*bwITtv_%b}#SQvLEz-huN3c4^Ih=om zt_IOaLOUT;5AvfVs$TCo?-9OBn7aYJ!c8h`J}S0n#QtLe;e29dNtX#)P*6g?P*V$8ANb z?fFt|V&X!6!k0=z!8w|q*P9W{AriI+E{QuzLa&am6?YzF zU6V4riz|~OKJ-8S?MZ=bhlRtj_|-0c8W_4nC!ipM>6Js-@>^gOBJg}4&jIbP9PCjT zT8fj)Y$BvAZmur80(=Bu@Ult=L!IwyhoMkUys&#FGv!*?0C9`W(GO=D?E406O!8sb z*FpQ3L%?eT&h?Jh5<4tlHC6P>e!tx=>a<9y&hURXwmt&cfUJkP%pv9n8Tyu2&kPYD z6#fKx@%n7AQUDY;#mbwqwa}hMlLD0zLsT$u)0-jTf4BXB3LTphaIdY z$asziVWPpFHNh{jrtH0Og)Q=)Vqfg7Kxa6UKquU_rUuj3hcA6N`}s)^4RC-HtevRV z-I#+0XWIhb)Pf2lQ;-)MH?(G1dXvkm)|xG~9U0tpJtLHo#^|~uN0dO(ri@J=V~Cdm zPd0+H&t6m#MJX&(G{xk+${y3WLsH+QzT5IH?0a8iz_Q07A0&YxzK2_g@2fcdQEGAy zMjnPgGBbz{CdNDmQ+Hl#ZMinn6@hw`RcaD}c4BW5wJfICiGSs`zn>{-b0(T#0PgS+ zMmW+E_H(MZSH_vs)pU$8tsGj=d^AB`ew2?--gVyw{^xeQ!sZRG`|}MeZPkKqjSj%x zwDLzVLta@Ki_YgS=9%|d2_H3oyI`>xi-)#Hhy+nz(|)4=`}G55!T4MMP~g*3oy2&U z12=A^Y&uL8Owsv*gjm8#0Lig~_`_d%@f?|;Vw`c3`*3*Sg z*H}v^6(MA@CxcvD+3MEZcI?XPNb(dhsy4ouA+RE%E{D0uz{b%<4+N=R^ByaD3wDXU_PMp>=AkeaGGFEH#b@s=96rl;zaF) zZY<8V(-#p@=fTN3> zS(~L<1C;qC!c1Awj`+j@yge-`sn9vzE3&y=2Fp04ccdIkpT{?_}1+NP> zqg)6^SI_!TdB$dS=nHY3pGe^o{PsAcO~8yUj}kQt`Lp)+*1poNOf`?-TwHD376WZ{ zF3^>0l{fa?MsSzu2(Daf%r7YTo|UELF>#W?Q>4!Rot9GP;B(oF=FCIJL-Bu;Z7i!| z5urgEg{xG0k=X@TAjFX@1^Qv7^rz_(@j6R#d`E%Gix4Bh6zYWN^Us=Il%X!0S4n`7 zyuCa&U0?6}hd|N=?$t=$rn;5c!GjwCeMA50|=G<&W%;vW~+j@nwhF!6J2@-f&^T5NU?Q5fJD@8 zj&vNJloCACB*Cz35OvzR;yg1S=Omc=@5wVT;Qb!E(b1vMmy5tkn{Ud(Q*Pr2T}=3{ z5aAIR_)S%6oZrxY0)L4lea3EwQ)dVlHSvhS^DQxVH*Uvqi;Sngik#_Kd2tG_G4>MW>y z(;Gi39Gxttb@hW~ZO`bIxXo|Q-Hy=`ptW!Hhruo~RP}yQYRTJkC6{gZ5=N~PX5?e+ zZkf>%>$c}o&`(9BdaYcmI>XDph35wMgc2=)HEw1dEH%H(C7zO{-7hL35qos^k#^f` z);04o(wv2ivzWgh8I~bbe-Cos=pu#LQ`){B@Px+lTW>b>`OF?2OWnfK7BMe(tnZcR zmYZ(~NkN7wKcNaUrm~UWDjBLeQ*$zgOM=~9Xe|!c$I_<99bsbDrNW=k`4;#g|1v)a zid&2CMX{Kz2@<0jtgP$3#3wMNQKEuyTs-}1JSuDtVJ|{}>Cya>b|orAi+-S40f!Fy zWR7q+=MT1%&?}tT6R3c7Zm<~PP#K~2Pg4rS<1^HbStP5e1*b$E6JZ;4^__}10m4>h z@H6DQe>O#zKs#g4OPn5&6zH6Dc#8IKR?n7dNtE3GE?)O-G&Q)JYh?F}~l! z6tC2L-Btva;fHt!(MEzQ73$H&nVenp_(CaNWyvRgy@LUwUcxBwFqSa5$~AdSP%|bZ zQD)q|N3xG|a}!1w{)ni<3K^*EYO9U>?Rt>9(K8N^rxg{`Y6G#@Z=9)fzl*QlJ<8hp zRa9;6Tuc6{i*l>#{IZBHw=y8HHo(LLoR;g9Ih8yjY~#`td07aCWEw;-a>ci2d1vnU z@2(p~e>gdB+8P|uX5{7(k&$wS!a?k|2MjOq)t%9To4$ArUi?gjlZnAX`QwPg=MEzj zCI%~1Iv4eOSb_GZPA;nd%N5t(Sv`G(W{#-yJk_x#^7eZ&jp5K&k!yBo!gmQ1_Nck1 zuAg1@rM|e6ugE4q8f8Gby-^46CxY-`j^Ymh0Qm*+P*ayc+#x1DxH1rrrF>Wz`kNX3 zTiAJm9PofhW{|n!Axe2BEGwGEG71B5hTQI}U;Q9TW>h!3+mJMmfN}N>2iw!?EUJJjL7mKbbGKQr|P`ySy=<1C;LZL0J1&wk?6pOd!bL%aM#Xf6%&JKZ3e?6 zpTpmgKG<%l(?59V#7R)m`Amwr-^e1ummq$W&?ciipqr#7(sT1LM7=oa+ z>N4P*9Umgas>d{Y76gM`5L#N0-7Sa;o5#=v-Lw&a!#hZEs0MT8wswloJ!ybO2dcRc zk%nNZcSHDpPmUnLGdiqSN~oi% zOf1}!ddyaYfgOQI=jTOCUZt>LR8-VY4i8#IHMjLV;JIf0z>Nf0L5XK-k3WSA^!_W+ z!2Yci(o>wem)Q;LH8lsC1cJ6n|DU$Go-(8KYg_c$En5#Lf*g2a!l=uSaTrT4mRUj2 zvv|!tpc(jyKFNLH@C3Sz)_KYba-me*P-gPuhDuK4QGFQfQ>TDDh6xCnM1afR73-I^S zCjyagv9alcM|^`89-jlDyf}*7wXvcNp>Y0%CxHC2bq3}B*e1^%Z%#Ilwx0HrgNmrn z+2G`P+i!~@@3ZBWWDg{@khzNL=0eqPyB-tmH3luZu^Q~JyX0$rYhts|KVv@(_COK| z0c@*V<&w`VYB?K@JOi1*kSgQ#_Omh-lqi@XWS@KhSVBZd0{7f zCt7S=v|ZO%;=el%^^}U#_Okw>Wo4ylOc+dw3w*4Z@=-mWft-T3a1lufw*xVgiwnk$ zG6IXxlV3egd z+OWIESZh2l5;yciW~;Rf8ggQ6gd+gH*!*b=3t;wq8oS(HL`Y%i09jL%fhO>NlpG?9 zt93sa1V_2f>Q{YiQnj$K*o&gUmJeUYLXrzl{~%3LvoKwLvD)cQn*SFY%h?moMgoDu zDB;iQhTVEPHF3(XDkjozpIZArx{%5{grtGfp_%~J-u$$>->*`^Cd(*JGp}_r*(NgZ z3UadglK8~(1H16xarb`guU=|)Lm#n=yuD3Ha2H&)qZ7)7t@edV=;p@w5Au`i9YLJb+|4hW*;m>7=i6@^bBqZP zp7{ji+mK9yr);Y++No9MqGr!Vi6E5s%f0og>H% zXR!z}eT2Y4Z@X05Ize#IL%B0-_Xh0)*im*Z$aSlyb@rpZi>2+2LD6;6bMaw~*2^6q z^VBEG*2k5bwP^{(!yA#bZ?@Dd{NE_o-tGfl<1F$HBg<)xn-|rf-OgfN|klY$>876bH zhL9N7uKwQJ#{i~fw9?yHjs>r0URyE>{w7pAKJIXK9rt)l0c~RpM{Q8J=&hTDGo+oJ zN#t3TTP_ZYp^r6Oe*FUfi(0)uw1rgB&37ei<<`7ZSinU*UOlxCw?N2Ti3VAYW*W!W-gD8W5hWZM2M09yt5vtX z>9KjVd!Ce}G!o7n&DnDEY<69H{Tx=6uE(}U(8&&+Bt#2F5-vHV4GraiFI)`8tS1Y-AgvT^$K)QeqvBcho) zmyl09@CHT`nwJQ5=@9;u0HJj(WU{3Xfp{iRAVtvzo1vapG^R1L=rT8Ka=R+m4m${8 zvy*?-JW(I*`MZ)u!4zgE^aa;wdh7X}YUX*7lPhqS!K+OB*~^)L(BKEHQ6Nkrih*%f z+)lq9e-JObD|4g~r^Jpf8gXuRuVcDLY6*7G;J>A`(5F@1@5}4P@e^5)JtHZd(9u5_ z*z&?3963q)+^dvbl&f<~5G! z56{y;iICevqN|Z-?g01L9s5}#f`ZR-r?_w>2Z>Wy9~N3*9i1n89jXuiQ1>u#TP)6( zO=M;xMX*IT*R@Cl^86KCaq()19F4lQ_mdI3jXR&0h35zjRHdQ|k)G%Qw!7(#CwZzMwx7fNO zV65^CH8XJ_fnO$8RWH+MgSaXnkY7Qa0du;1LGv0(yK#qb;Df`1c-u{lpqpf*4*+lU z)_nH9w0x{U8YvLHtNoB({PLvAWCro_&Lq1vtwzh50ChpqbGk$g-|I<+0O!WYu@!SA zUj7zRTfMsZsd=75ZUIpo1J}zC0$7K7-|qICD=by^&h7YVkA~qlW+-Cz;xPBRFr07= zm119(kVI*PrxtfDl&A6duq0Mm+#nk38il^7?Qn1vPK+);@wK)hxjwwnZa#lS*lg+N zd<3`?${jZQY zkWI#eB^WBPS>hw2ag>AcoB2l@lWM9OfoIoWdkK@7O56@MASuR|aYfHRc^RS^hftNJ zJpJBY6s?UVl;*Lww?|iLJP34?{#sz}ejFy^f58Sd){eja0?|^uK3w+Xiu>C}1R@b& zx-e3w$p-QZTgw*7tIZz!Hi$6IyjRil0{g$uyDzhSiK$y!1VAKQ)>d_5J%e$W)Z)9G z&Sjv>)csmCF~|3JcZ2NdrxZxg2QLH?PfRBWf(45dBg@4n)0G8_fDKCNVoZNWu4^s& zk>?!|2&rBQm2BsDC6f(wXK+$BY9mLv`$~G2?52IOp@nW&Bg^jo^O zcf_6xXJ0$mDedLp{s$M@RbT8~!ANdzf8v~Nf$VqyP*@PPDBQ@O9ezesz`Ww~C~A%X z#Gky|9V*p|Z0A#B|s#c!d^qFmS^MLKm}dYv&<% z3z`+7So33^%ul!>62i|}QJ@Cra$CTijZEz-V_4eqlItg}@>%vVvB5gY;m;|<&BHl<&)xKEKnlDLJg zfxzVp_1E%xOp1QBdsFJs5E?bfKk052``lRCc8#Sn9^;zoR$4tmJ))jPh|I=5zgZb; z(#y~csL3TZhq)-(>xjx1t*N(FaS#Bk^JlyXtZJz$nZ()nRXooVK zj>W4=aHX;mwyO~Ijc37o6X4*Vs^-wA2nSxTsh4s#Iz~)MfGEO(b<9)fIy5RP8K%CJ zags;XhN&|)o+Ar*3jCWa?pJE#dtUWV&IgXHkPO(VqERj%%n;!NcT;N(p4T@EF%P_X z3^~YFZBC7h4{xwAWM^?}TEnU75K{tp*57GnH-yRUXg zV9JpB#srlncU)R(%T5E8k11ZMd6)`Zd_0jJM1{1C--|`3%U4CWlkmIJ5 zmX-~qvKzYIHRxXV_7K@Nl%f~i4eqttGL*24h>yRyT)JHZylpMyb{M?vN?sq2_sphj z|Cg-=Ny6m)9tdd-mck7oAXQCBfIJI#)iipaeK%|WH-juvt?1gx7&_5lCDdGkNI`Z3 zFi|^ogGL72`Z#YtJ=4_EG`c6NTTOCDAIM+r8~_7O9i+*Z^CIJ&8sNb(LXE@1a&CI3 zwvTavUuf;gZ;LnB11z=0{A^q=JWon9*~c=7KI3Bv{-axJ<90vCRN%<&y;}K!L)q#O z%w%H6>Yn>r9o5hoXUJH+vv^!iJh>9rremBtJXsV)N&rGCndbK+s=@AYlVm@_5qjFp zqJLTxjJ4xthsrz*&Y_#XugI@lEEGvd2?v{KDbD~3G$2taw0#Bb6EG0J@9$?>a6`c&`u$B>dXXuT8ppnS|xPS;tF zq7Ml65b;@PZOT<1C)-jFAKBdE{-cNh$4>l`z_!{;b}zE~amVcG;o=Ai(4HK&RE{u@ znS*%<_?aUVkbV3-RG}6>ptL`!Bw(ft0kO1fl2mbceG-{KrpUzX%LeI}@t>A9Clb zuqmmHw&kF6gSBw1iK7*8phi9&^@}3C9G?VsS!XVj0Ls`U5gZ8*LLV2;eeNdZB=-g@vNRj|~)jBWj^u5gVzTbh$y8|q#V|JHZ<;2mki_GoT$G(lM6T!(v z4>sl#WcEyw=#d2+8zma;3k{Ig|H{LfX~iX*a|;kBg&6?~vjlPw5HIR15eo<(FAf(A z_#LWAt@u0Rew>ozWl!Gqs6XjX6Uw=nUgBmZ0ZC9jv$05`PiKQ+OV&q*f!3og%8W|v zU0Qmkve%_vP!x&z&L0ueNp!Os0_E3&=7IGN-eTgb8$W!OzORZkIF=3>s5*3#Qj!a- zbIhL7nHYSDQ4V5W2mnnV8jFYyi5n~Z!}sC*cACLknHz5bX_-a<*E^>M#ljy>MIR&k zT}~#?+2FXm&&F=$S;$nDOc)qFLfy=C-+WbI{w;0oZ5O50mUi{YRxuUN@iuc2Veglu ztyIYAkWty-Jztr@*t@E{Vx@Bli5#kVsbq5F&PxQw73BHScokM1+s1# zyl%6FLVig8O*c7XR`135{MD&)2BpDg%9z~OSrQt+XT2%xcR5V|njiR2=(EP+eJ9dG z?kj`A?!c?~W6;uK`a5sRIP{%JhFTM-#gjd~KdDiV>Uqr-r(CfQePY@x8Mc9=$|W9B z%!>n*Xd;(5Pg!Vtk>sv@R-_+C*gLt(>U>_TcG>nhj3~W`{K9rjG?5->W?~3$66l5V z`nYfEpvZi3>W(t%TA*>7?pGyd!+TNEuxK8lYIa88(fh>TTE91WtW^lj`x2a_mUUJ0Y4)3}`7R*fB@*rF?g_y_Z7qf? zP}+?{Ic5Y$fx9ZUX_#M@d$rAJ|c~-(aLU ze*FOWGCx&MLPd?OYzhKu*e7Us6!Re#x~U8ZZ$K+DOb$DVvA{-atS-Vucgc9uikFN_ zxq0ScfXV8aSY0mPHY~vxMs87wXoFA{t3(nwKN@#!c2l0rc()hqmUP1Og^I{-&^M%F zu@q#En_OFL?Y*EZb3*vXmgy~S3&fOcM96uxTLc3XeeZMW?fB2L$jPX#PQOSDQD_ z@fY6zX90}l;-aPlW36hop`ZfkVDUNs!x0q;wCldpa`zDm6rfi=_s$d>lZiYJoA)#M zQWTo^cpO?L9@nn?!N9;GnL)}3yT46tZ8rj$sFszLx$a%zoJs!PdTupR-}vY#=T*q6 zTlEKOacuTFO`WmhQ7fu-*VosF>=sK0-5yNn7`3dd8+NOO2_P`vwkqYl)#UU|m|QpZ zt&Tvk2WvPBg>pE+zkUD7v~NL5f|H#p>o(~D+6hj7)pr#CHS7o8kuOf=JQf_kS3x zysmK&L7Vrv^*@M=QfYs_D*px++eO=-8nmuKbjLugzo^9Bx2u*9H9WC z67}fHa`G@`C>HeK!*F0b=-YuCXl4l3kSO5DPev2+sG_3sdMHTonA|+CT&`(>UlVv~ zp~2cY>}ri~(!hzj5u8o3q9bhCq#Z*MSO|^Dl)k`{d^nrv8C+y@_to@FZFOebjZnzH z+tVv~mb!)e<~YA9FkZ!%x)UtfkwqqQ!%VV9y^DE{_P6({gs%K#zx0> zI?9S*JX}+6A*OceAK4B?^{!+P5T)yBg8)CRsQ^;;!3iEmWVM}`gk+%RhszG8e4RmA z=I_!XOcNk~#1yK$u1s#Vq^}uS5{PR>xgt-`sv!vmW~nk8cwWfD%d@ttTOwZcQUpax-*2 zQ=?=so7F#&D{XX2_3@h#e{5sOts{>6ih!e)J661wnGZHn)BJ9Cg2dV97A3#Yc^`?UXa)pS;` zoXEy7-sXK8Q)65^HNokizoI@d_q=zt3b2mp~ z?7!93I85CfNmpb)Tw!9EJDP?C5%bPd@vH2T+H2$q<^c(>0>1`_>jhKK(-uD`+Hx6( zz{Z?d*<8~Jh@&e0WIC6%Q^SncsMoC4qw~A?lK)Na6}58;V&P;hKsHy0U%>DwOAVJ0 zAG4tF2JsP(#S-R7r*rtxvQYw;+WxBJR_(yrbT9d%%+38>)@RUR>KDsv2K zEPB+(-%OJ!nZe}-K~_QM4NF%$v60Qq)m&s!4kMqaLH%^j9pe;9s& zf*zfZPnMnfSx%nea7yOOJfd=@Nmdi=`*f1l)Juij%h>^^Z&Q)fCGxV{nlk#@46JH;WzTU+H}0~M!hb#I3WkBicC62Rg5#EU~LRvU}X)jz@S1EyLFM2TBB zwg2ip^Y%M$j;N_Q(Qc3w{E^fKuW&cTVb0Y6>`jW;E zc<$$3)70lJ?*dDYN{`n)>2XV`*VmDy55q?VqC}9j_FqS`#sOr^UYvT=;N=E*84%^e z^rV;LFOE}Zu%m@Q)E*z#PTAN-uEo+~S|BTMEURgIY(~7Tzbe5-clvr-vjc|a6gf`$5r!s&9xlSTs`q4##3t`+n_CD_Z;W);F1DNnlaGnT*YLQS-)rR~- z-@|;<5&VC@yo$H}a1G^E8_`s=fpyQrbG!W%aT~(_dZ!cDX@PB9Ydf}gv=9jPlQYwg z;zA!via781$c;pfC{9#v>9`)F*qQ}toJbOZ|N8J5<(hMp98uj}w~gr7rcLc=YHH>f z=55-z`kalc?o%!0O1&pv9 zpC#Cc1vPz1A9J0xr_;G+2j3#;AE90@a;MJoy**1%w?A5k{&*c*pZ$+ws3VD+w5)d?S>-;8 z>TRSl`;F)s+pYETwnHiqH5Z&id3m|nI~EjDF+RNkPqipYappd?XR`_OjucfGGA8rB^?ZH{*@N{E>ku-uq>9UlJ+upOLVRX8#ZjfhK(D@>gp(T)!>gtC<{-s-;GU;1f(Pu!HI$5cIVHZ$9Zy8UA=mh ziXX2V;HkN}*-RjMuE3%G{(j?IT3XQB+KOGfcN?xMaWc4bk<%B_JB530%Wp&5ada+k zC!$q3q6`q_i1I9dAamj~Y(6&MO!#CeaKFjRwvGC%HjobjqRawS3yX|fkpiOU7wzuX z-sxqtf_?fQ27dlU!A>+_)&2%z1rldCc@yCQI@%K4gtuKfk_S!7Xh)eW)d~DnR6apzE z20kz_fHP;#kW1wZH@YQ!ca>o0t{r&(`RA~G$98T^+6hwDxKlnUFCfb8A4V+vKIQt{ zFRe5stw1N!4{UtuJvQ!hFWA$Op>1o^SgiNs08wkN(Gr2pv`8Q-kqSgnG;bl~BNvDd z7cRx<<2dojRUA8g4Rxi}*s`$$dv})OIdVG16LS=sB@p%T2zh=QX!5?1J9u9X>&jeZL8Jz?W?)kF%GBZ<`Ws&MU+?Y!< zwSXB<7A?nlxp*fCHP11#?SL~XCt(zdze#7Ebw1AX@{vfCYsV6ojTqcrPM`L^-m$|4<1YHeN#%+QC4K@RjpG0+>sM<0KJ4?a9W zP-GMCgbp(gva~55JxC}RU0rTA>hrU)Z*LHL4$e{+T|PQCm2nMC+A0l`svcf?r*#!N zPHpYH2b^;inX|BNS>|-^R>z4?t)Piv1SfIxRuOo_I49qfyHWuqCl?2VVG<`h9jH#4 zZ%qa~5>1y%;~`+_(Z>v0*ozUkj0ZVRXrVMVK`V&_r)CxiP)!aZF*S%_Ul6n1Aw;J2 zVPu9ML1sA&sAq~6`bNXW7+);GqOTZ>-V*eo7q>lE5#jhKEG!|nZat>wHq-KA3*UV- z$IeEHd#Vtj57WSg3^Eq@#!#7m2h|m0XlwMMv6dp}g^je{*NA<4>allkJ+1JO3Is7t z1x0@YI0FMS(grtFvG|M{Q)X~g=1!64e&+VILNukcHBhq+gqi1*+Bz;qA+R|2q(ymSO#|HjwJ zj@!&)u`rt1)uG%KRO&0)#;I$hADgoAMx|G$6zC;n)N({gU&!D6-QT$!QDP0(%Sbt; zIQO}!d8b^>96kXGBwtJ`Jj=8(`-NUmntYZ4QQUYI7ZszBCVle@*jM#J(+1o2^A+;@ zvPWss*8dmg%y3U1gsYdvj?2}7s4{{Lu4o?H-qh_OpRxMWKgTQDFwi?21!v*EJa@GW z&1rL!B;~pi1ev9j(9}$vVtG?I@zEeTG8S?EP7Q`;XlC5U%@jGJa^jQ52MIz&!!y`U z3sv9zMjH+tszPhChl*Xf3FNfL>DuJUBd);tWO>)AH8f;Ywuc%!yeV~`!|KsJWdB;F zt<>&na~8_zG1R-IueZ-w#?uE6ao%=ybzzX=ArdEV-`Gyyf#+X%4lf=#gx1y;BfgiL zldD2G#bTZ&UzYo!>gnY0C;$Dz$L62BhWB}Z?FS6i<_3tOg5;AYPvY3IV>ovF7_A;| z!}e|4@!HYX@aEUvL_K#&Gpo z3?F{fi9deYiK?O+v~Spg{kzKX;`1C+UIJ0S>cYDp((+iWp1e2p280q2guC=k(R(1!SDwZ)RMm>~5NrI+)>?dY-JHz!z=K z9dWp5)W>lZLwI%p-n%{U4)o&Ei2+>v_%5QMUS#`vP(qHMnk_pJtJsFlxlOn4QKk6zQ$Pv_t=Xd4d#pnF!?(4_T-a3ox{XsmpZ5O$}+9{ToO)t=k(2wS3iW7Ut z$!WQCGFItcJ5AVm%*fl>x9q)wzrD4RwOb8!6FaU6T^I4)h^ zfb#<{Vm?~MTXY{MQi`2PZ&4^))B6mOK|XoT2$9^zTw>LWrJpM()GJs z_-rjc%WJ&TX8zu)>dr?VY?q*HvdzZ}CMrPteh_L;_yyLv)MiA*W~^n><-J zg>HPD@$%N`!-Xs>CMd=krBeGi5h1U>kWg<|Br6Az06$od+=XxWF2*}YFnDnkbNpD4 zh>X!s@V-gv?4QLP6~xbl0tk645%N``*E@{c-Y!ggX7pWz*KLS-TA7aAXX3!3 zh^u@!;-ilv&l^N({sc-2Mp0HWM2mZKC@S57qLS@+>2NKM9I8b=nd}m@>}TG$1V9a| zml2JmY#&7qjgCYf#slV|&W9P1!mtXvL|CCUEJYMr&%5~V($2&yBTKnVxDo|Y`=G9y zb-QRt(rIp+oR~yUPmf`iSP6(qrsuuMyjFTpChnP{fZAUEEt8FFeP(aPf7P#I{tjws!% zj_mx{tTN#jK>^e3wpTd?Sk^A?^%1h__jA#!g=rCisG_1G2Z-V%WtwrNzVb!X=P7*V zGJ1ZI;#P}s0QMqQmvH2{UD{SN!7#iB^`Pv+@qdI`p zQi0TMwK*bd6TPEId^#A%*c3T2E{@>%d$)1wbQo7hTKNTS1fnWwq057YCT@thf65|Pg4sxEGsO*{8EHuriRCd7PI=Z!J2NY% z+^6v;mm1~7JjO3GllZr|q4d#2BIK7YT{0g&CitO2;@$E)w(q2J@*U{lhm`isn+!*; z^pHr$q3J7b1(WZ>$0$?07he|HDfI1q?BDh?rGaw<0gBznuOWa=RL$h(gF5W`6{7o4YxhamgGD98GMSsS*t zwh~ycSM`ne`2z0v=DB;nrGz=xk4Y>N%##8{_6-Q73j(3ST+0fO;&o%dfucW=0?xO0 zaNz>|#S)ymQjhL2FUIGmsB4c2{go^rIZ~O0%DS;&47HV`*uSS3hYwa$0e3D+s}fY= zz63<6c4qp~b978^YRm(j%PH=@&P}+K&V8dK^Kh;#d#~8cZRkEg<76pHNAx0s>x|f% zDX|F%A#?{4_ZeW+Mm_K#Y$LAVfb!Yl<^t zBjlQjAT~{rOFscWUpD#EXz?^LiXinH&JpMedGfK4Q-^S%f*f(wTShC=#S!`05Kc>C?Q z&6meUF6e_-Z^b9<=E26B4wc@i^fbLt_(DDQ-ZA{+KmH>*zD5j3)L;G8|Iglgu*Y>=*`lkF zK_Vw+f)UJ_ViGe&B}=j-2aP>4-9=s^pT($<1M3Lyjnl5r4l87ZwtoaX=I&&yCI0iFLIH z2M$)@?;oAScZWJ~p=~}F1k=fqN=+MSy+{vTLmHaUa-BzHUvI&j$=P`Fk(pSxwh$#H z0TfTC`dCiJQ#tYWmOq+(d;RN;BeVS6f2N+CyO*mkh>n4QC|J(qE(nu82k)iM`~KX>SjZD=~o5@?Mmchw#a#NAUj6BRn~65*9C5 zOdzVzbR-4B-T3ftwb=31HI%hx@Zc13&Tx@V!s8;Cr_Y6}@$lSqJpJ@^tRuH#F;ChP zSJa(1>Q}@;6fxp#(Ic;#M|HQhqw14=sQUCfT)SM2Yt>b_Mtwfl64Ehw={&4`W<7c` zi}Cw6Tkz`McC-*2pvG>@oKQe9;6luvnnH!;i4@JN#K&J8Ms;I5^+qkl3IS1DQwc_~ z9Y&%PbfQ1OAdz0ko9ihdF~)(N4iGA+krRkV4FMuNI<`YMh6qp;hM!&Z1;g6EU>FxL1C^G`4$RQOL zmsAT+B_u5cGEx!9C!k0DeZh+rXg*(xvUBHg`C>WJYFm&(OC?g24(&t=0jShq2RaF8 zH4xWoN+9KtRPKZtsZ$JNYT1GGu`+kgF6 z4~Wt@L2IV3$@ew(!5aNQ5q^)|?>P{qvQy`)f%|&Lbt>U(#<_Fn@Y!dd84x9oC!KO9 zZYEiYvh{HBmr2FtQdB-(mWqM%InnQ;7@S1mUViyyy!7HrShRQ%p8fH&Jf&!fEe5i4 zvN_;N*5A_+RZTrnAAR&Uv-0!w)6W=aHDTg-0}_JdWHKO1Uom}(+rT3}YZBstU(y@U zZD|+4B{zK|z)Dv40<^yQ_FKIA%BxgB*@l1nw||3xDCJvz6qcL3y6f$rDL0TQEHB*t z)GargFvX3`Eezv-8~2k3#gVjNf4Z_0(E{ZPIqOvS0-$6iJDxs<95LjmyPb9VLo8yF zp&3V`qDfgjI~sL#>MzT9eq!G%;Mj0tpS{?J|LfvV+f|(lToxy1Vx-OIu%F2zNUi}( zI;6D7il*OYmR`Ga>31`^sNg=Zn}5jxNryZOOHm!^5=c)OJ^hvHnZpK z-W2I_##~cRMddZX;X}39{l!@vJ=uv$D$qrEGAHvqx;rh5yhNUAmE4JIt@UW6j*gi{ zDcHJUGS;jr#9S&8o;i~Wba}d-tipHP9swm@;fk{d7*oLb?^G~9&+Ofd^~^tJdPhbPC)Je_U+q;OP4M|B6qo*psrl80xM{x z*KpRXS;igZxNKG83d@ZpOi912x_IMVy>gLvebc|LWAhm=k1k9{AMyP7%SHZ2!}VxH zWhVWVN2z~OI>02Bw~JiP4v5;aWeXmC^ik?Rn`j$i>KEL+#+AE>SoQBW{_>T(s~hKs zJQxHkIvG~TXeLMo5v)Ct+U6Vk}u$h=&$a?4L*7 zf4ZX%yT6MEL|s98xB{!^jlmO-&%&Cu<1uXtfv5>Q-HWs(ZlQqkAmB8PiA}fZI0|Ty zE$~E;jyJE-r}8V?*CsvDMZJ@uWE{v`Vxm@h?xu={iy!Pk>EFIYM_U6rX(AAAc`wDSjEy7#3pp2@Q#=t9*xwWuCZOtaCBE2q1P#sCv9x3f zmM@xvEsrE&^Y&zNvXUc;R_C=PkW0lojZNiGL_nf-oa;%SQWC+XZi-a(P~_{x@e_6m zv)Z~&VAeRlYSk*v8J9qF%j}$-2yQROOMeCeo@9BnPN;Svpi--c4U08+pM?tXto6 zOdac!8^Vb=SU5M1?|z!DT|V`b^x#{Ff`+61uq7PBOlx5Vo`6xZuUFopWI(pjgh z$7G(e7rfSjrq*V(P{&_FRUHzm>Iv-Dvt89Ak(&vroTGPj2GJA@P_G(wBJu>hF5jNg zx$tjVTn@oJ6~A^K62jv#38Rh>Y|WB&Kjp zLAmshjdcVpsgI16L8~@H<0`>>azz+<@;s;yu`xh(#tJaYSFYZ?a_nE$t~`AK^}99N z?AJ!U?-i!|*41^t5AX6rG>%21vT}L2Th~|`QoPPBHVv+vJzDkNIy!UT`2G0(#fEh!pIsWX`JhvhW!wqL z`33o$+l{gD-f)6QTXg9W9v~oU@0VZVC1Mg9Gls!dQl z7ytAk{`5b8!kRT}@T*__iYMbO^*RoA8tU^kNo;9uG4YBw-gpDAzy3O=O`C39QOlMu zqh6}HcIuTx00l;g(?R1y5<#(~{*|ccPspBUd11aacq&b<0p2c(Q$H=Gms$yHu@|Lo>%%=tx5ghc_$hua zm-s6y$;iqd0Mt{5VA)2u7&>B$6YRU0I2a3W$)-kWmxA1Vp3Kq2UcQ z9*r76%Qo&NmToXm2;P9ta@Pcb?NaSVZVB`+H-#fNHCVaHxOO#AxYh>D=g>bEKI0P= zsEunvD3Kk3k!tUWT*PR%BriA5`U-&-y-bfsGiqpFTe_9>DwRW(gUg9auLic*GIMmS ze!;+?m@;#5C@g&|TV9ojvt>y*e6*1p1!Xu@+JVNNDfBUpKorX)Er9U^qw?9+Ha77< zi292t&JAJRL-}}UMIjb0F2L+r*#x0_kdok?SQX+C^*m^t^~Kpf7nRc8qIsPeOOqzt zsz>G9>x%$bg8$CM z`U#n+7Ih{ig^-jg(Y0hWHDsWnF&))4Ayn6f@Wtmxuw&0*>L#3onbXOQH@65Y7Li`5 zUuxH$dVGC24iH6ds7#b%#oRI2_Q)IpDiblIIEkBk-00(&)lHgB2=-7RG?jU);rWbu z3;XxEhuMY&no*llq#d&_)?Z{JMtP0)zYJR(QSNgxQX-X1U&+F;XgaA>`t&=0$C>v& zV|UO-1GGAsmoC`pE|j=mXJFt760}6S^V|O3Nm@6B0VVu^CnEitSQA5i%&s1 zH>#_yRAK+IV`!pC-O?FLuxvpIHa(hvjgK>rUF1JvoD_CMGW#J1MA@ljoaY5-QwbQP zQt?td#qrt+Fi2g*8-ISoKxi#ICQ&3$;Nu2z(~A>sG7rt^;ijal@-3tKRKF?X+PZTK zQ{+j;2d0_#}caBj);g?h-rLhDyNcDRMt)u||NFp58Ru9e23 zmAy_5GxFvd?v_p9CoM4rA#zDcAAN86C4|bTqP(;e6|~_iSCLlVf}VCNJm=8TN%{z- zvYyB><;+Qn@SS2s1*z*PB_)9;Q5JC{dKN{|3qew&Qu734rBe57S|+w`nug7rr(?$W z4vf!eM9SD8L9G;it9675lQtyf_z~_1MdI@5k&uhl2%~SzcJm0=r)UnYI?u;7? z-E+L_fb%FzjFSlQ=po+scf(D^Ve}y4ip-;KOS}wD^dsZ?dKa!v_0_m95JBoU+6hu- z^8hVLK1gy#R(*lZIq##ga_PUDSIt4x@A=0tbBmO%KP`?XRqn%`uiLoe59AKtvt>oc zEa``oRo=uHBR#+ch55F|6Y#7xzZ>6NvNR{WPT*2p^RNH;&&GrzW#t3vh|-518TMUW zU_bEdJprPuyd%UZLR1B+g1dCADtmIBJfxHFqyW|?{+#@aGfI_0#*nKAgyZ+?U4o_)?5pc zDmq!wkp?QoA+R)^Y}{$&j!=hX13c?^)Wk0Vk5;{Rj?PqXn!Ky*RHk}%b?NHS|2z^u z@xpas#ZO^>SH-1tsooQ{a-dP&w~*~$i&afzG&#`$2zsx!t#7=^z1o`cr0<89r+DdA zoI{m^%aa$kqg%!Aed~SiO)%9r=vjI4e`lWA`{{Uf1LNtTqB;%d%hCzJG-Kbv3Y@HL zM=)H(8C)I$sp-fk?PpUrZuXck!TCy5)SbsT?i??jla0kZ&1=bWaxKiu!`S2wq^EXp zdviHeNI1=XppipO6+%8!il8Ed?} zt4#Dp*LXCfvQnKY4AH3$RPgA``(FJ}EZw>GrNyJy-s1at@WS?Ex8BP-SqaR@lcmsTx-sxLi`TY)OApi^=a(*@-#BWjK|bTb1-jq5tc6EB8j-} zp~KBMa5* zB916hso5xficTYX<#cP{D8U>gbn}5CN8<9(0-L&*v>*;s_mli2k_Zz?W4+8|(7+1i zpJOHgs4RY()Y*$xDtEnB--zljzQpA(_A)rVV0jj;Lhpn}kUeugCe9m&hK^pm{PtPA zx39tus7a$Z+_D+ds2^$?V`QI9v52ag%Q#(n9vy6Zi>58a;(4>Merp2OZA&1h73Yy{ zT?B7Bkw%fMM5R?anZ%hw5!wL5OCs<>tN~p-{YXm6KmOZCcU@-zw&K*ei?~qMiA#-BQPWM)JQjHt%eF=0)S7b;M9WS~ z!qO>WtX&brLW<{27@tlWWnY`tLCbv8ZxXHg3Mp_`eJMQ*iucUC>d`tKude89#+m)x7Xizem%PP{K&=8x9j^{dFY+oWIR7AGkfH-+`N1Luav|mDzEe>98=6t z34Bf=`FK|I$n56Yd9+nVakU0@RYq^BTqlQLY;qCuHkxF1G+9y zxqo9Du2Jli)G)^!ISkmc_2V%GR69m zF^2tn8s`FA)=tBwjRc~`wPIq{6{PYszMd4u%XdnzN;-*SUJ`Xo={d+uD$A~ncpGE9 zG21JrzA?b_uk@%4Rfmy+zD&_O`7?%gPZgW@7=cLP5%m&(Q*4k5Jy*8OO*Vp*o zH^eYeD$zN8tCzbbiC;GP~=$RYo$c3l( zULD-%C-U(i7cYF(r_!J~zO2$H6$?@cl*5w~Q`ip(aO&ooU;e!Lme+=iBZ?Toelpa& z{r1~rlOze+?6P1h3evmn~anB7GAlPViXn2tEAVAMI) z*Vg00g$p(*)daPJ3d%Ys<2 zRDtq39*Lcp#YImxa?^8>Hzt=NY9XEqLLD0sAS#o`&(9h^7IRDTuwvB|%wJqcpsE>J zW4ZI(+h$fAQAtz`tHofDeW3b5Z(?)%CYv`?C~mUrwd)iU&(aw5)z@Dc5GDO^8l%J! zvHs!p6w6x~<%F^wdM%Pva*@7SW$5~2xw}3@G~xOR=kC9{dq+=wH00Hc|5@Sp`SarT z$k5SU>^IJjd#~7H{dnnqkizxqj9>uAe2G?S)9J*C<2Xhz>foV+1bGe-bS$BrLw#VY zc|zGb>a8rW%`%DOd!V2zN0sT&#?gk?U$8zTw?>dhVp~d2D3s25(s*)UWTUo@oVc}D zv1|7weD+lZC&+o2R8Y*58jA>s=5p6Qog6gXxLC>q1u9!{siBQ+l}fD>bGhQJ;)LrQ zm3tG2+A;?#m*->ZgjN(4aFef_U=(%axK2y(jK?wLE&fQU28>C(D@?FNKvRIHvIV%( zH;x6lX^AZ{GtqS~`wxkk5ui!trd&4x-5vrxY8h(dnFK(_5ikhww7g2n{?=60;QGlU z=sb0lI0(ytKtl4|?MPYn0#YZ=L0U!%s%o#}y-zRTlOqJw$dxP+x($n_W6g@`6bJ6Y z*;1ZzRa1+qhRa6D3#Jh;q|Tl->l3hQ0~Zz)&uXC>h!iS7ACulrAd3AB#U90(5+KJ6 zGe|&9++duSQCyhN26lY*cf9qN*E!!iXZ@2Fq&j7}WOj*h!)@KR&D1cc|I(a5oKebO zU)ztZf0ma@ft9V6r_=iq#1^JHm$Ui`0%PKW5obY&;7S*{ZaO+9p|Q3HRTYFQITOMbR) z#z8nFQF4+>8OtKXdZU5~rXf=IUPof2;YG-_N8G&UyZf8O@=Ye^UINq5L%Irb&Xr6$ zOCp^m5JVH>Y!5kFx;Y*vQIA-9ODB>DwDyi6@RLqJh`=egjS=qV*wZr>4JT?*bD$jc zm5peij;Zdh24scHFgEcrkiqdjGk`j(T&NwJhECFLH#fsu+b59gZV{R~i_zXShKB-> zBaa+dY2zdU-^-7 zSLg1(y6|;%)|(sj<;m~=X6_ZP(x5rJ%F+W0BJ7ELrvt78L};GpHl=jcJm017X5t%)LK{`=}Yt7dv22)Sbh=cg_(@#t+X7%bd1~%DgWt7|h>tEl( zn>;mdI{~VH|M!3QfGF*7MSv&`>TP7V7LfGDU*3Sk^R$pyw|1SKuBRQ&ab&UAWKt)g zIbxThbS*CFV96Gc)zsKz`avY3Ar3BEl#;VcAe6o{LxQTQso`x{eJX~8j{>x{FZ(;5WA|N`G2=eG|otb zHsxZLys6inO@)hFarN(@U}Um#~CMD(0dPr@bsEVl+#QkzwY~+i+%K~ z`=SJVw96J{buO_hDJB%X$!Mn|mEeROlO1VmBn_Jj-Y#0Si0;^r`U(ZENiio{w64pj zs!m5)Sq2UrX~V94Rk$QYuZd*6NFIaYoI*^@FGNxb&n!v_p{BMR7pu-vaXH1-^0P5_ zRsmM8r$Xfw1<0eK*PP5YiZxv4B8b2}2;6b!-$e5SM6pj4o45Mvduh~Wm3QNYB_JUY zOtEN7N6?2Ken?$CP25~4B4^Bea+W-TH5`k?d8>(R4;M({h!tIESJlyn5rWH<=!tRY zk2m_Y*WR;k&BgPr_q3ztE|mc5O?4(tM=d(~IHHd6w8-yh_ZtW`k3iJwHEVe)pGW1H^9WX)MX3Co7*NcnFaHt7Zv5Zq zEue@VSMV3ho2iKW0`{D#Mh@lhvZ$+L{fdcLw`u}PFA*d^T#t*DwPJ5ozTPgl0PR69f>&BUxD8zz*nK-(L1~KED=Y@279YH{HYs&5O&pySQZ@iAP zXHKJ|iyTFq4;B^_Vp{PuJp1gk`0KE?4L%?$+Jl;x$WNqoyEbhns;R$V z-)BDb%X_PP-Lw3AdEicHJh|dRXsT<(#q(YG=0GM6oJm9db#nQ4vTy`6%JOgt3y7kP zC1dI_eS8olq>WkB8#Q@qD^**xkQ>j!cu&>@N1AiTzXnHEa%jU{*67~01ko<(KlvoX1-6}cHT92*2bu~tbW0-kz! zB_A-yNQ(5azB&nlhy%HAtT69G{BV3>zv1SkH+W{9xw_IjRiPVm9H+DU#^N2I&$9l= z(W-^xtux%W@vaKbty8@BUZ3jsD?fwf*QMQZ;U(Vs4NH$dpxbcom7zo~Q*AD-_v{CHWTYxvzjIaRo`NO^v;idN@>((n_zLCu4QyPKGA-x|gnokN)-{E?&4u zW#v>@K7Ink#WZo!L@p3M!UrFGfJeA6_$?90#fuknVL%1BtbB1q3G7j)(!?V<-}>uc z@fJZVDV5#2bqkhIpVUm=7ZenDKotEN2Mi}2u^pzDULFlAK#CksLd>Ib>PGv0)GtxP z_uhTai1A;3{V(`2Iif62%!|K6RX^+E@psN@0A6cicRUDz%3thz3y=A>Hf0psm#(`) zz_HN{lK$JC9>sl|;W#v(Go6-;sZ}jFKm4KrH zFM9PQt<)dV+Qu0u>sW1B^)FC7gs z?9)Q92Is1oZ!LH@*m?rQ`%kcPPPhj1;hi#&wMXHQ_&*HN_*hWh^I(n2kqR5H8=gZx+drT~E0XMETZrns&OWUZdd=h~e0XD2Fwi{p58Gbr7 zw(xVa1R+ASgnK;dp%_oFH5;6q8V9u@`-t*+Xe~hM;MpCdgz2sTlgn840-9+5vp2|{650)W|;8qsbdSh2Vg|UzRKWNREO(o=EoH*Nr&%Zf`Z%S)0yJ!-o zPUK+-%QCQfMF#aJHRF>n>u{!`2F)$i$R^;hY|bJqTT+6DHzncWE!@S{9Md)r2)q#J zQ-766&QG;-%e68sR85xso5b-y{oCL0`m3+t7-^uXxyi=+{JeZjn>GzEyzl~E`1uQ_ zPeuz=wQI+msKa5k+$_ju=U^%JiLTsZ-sdIDHMfx(a1i&Y`vABC;~8Xs;lHT)wiM zj78RotcSq^3KHg{y(1Sj)G>9niF$-GbNEdTo_}%yo_l5i#ufGO6y0lFxQYi#WlA87 z@rER_$|sUIdI)v~6Gc1fH-@4aeqct_$JiXL=1x zP^X}{XtfC;W&!~c(h((VfD}~`xUy9AL+0aF(|A9A@95{Qr7cQ{7NehD`@iuLS>(u*vT9kKoM+}%;<}0Cjec@xOCU=7qyvGEQdTcT z#@6b&!%08z)wMb6Gwy5>hZ%YdA*)rBR{i9vdjU~$*PF77L7Y6%gS}rj z<8Qm_aJGs-lnndjmE?F@y0Czp5n^!%&YwGv!^e(WyO>%ufgB0rv32`6tX-eSQ%-x$ zy4Wbt$bOtU{A^0@1*wGGFJ)zQ$KrD1#yju6<4rEOAe}vX7Dclj;`s3t#q%~qcBZ{u zZH+gBb+wV4j_Bg(Xha{~g6Al`-$EF-`sqDOgRhA+G&JJKp(9-QAHe6I@4)9fcSMzy zZ`-;Jk3aFaaaKngkiPYOKaw)AcE=x1acPARc)*at4wB=DQz3$)5`PWhl~*s|4}ZPD zg?JvObP1z z33FzpP)`)OU@TrPm6>)^5-k>=sNvi}iHjJoeJXv<$ge2W_l?~OByg?W^DAyBszNew zDnKr*)=SkmzhfsV_kNAg!hRm4@Xp`KfnI)v%3^C#KoP8m7A@kt*#x4Jv2HU(vN%?E zOZ-rV{hOVTM-eq$qm{*MAe{o|A+AyR&p4mv1a0i*(>qG^LW6P=wQCD~G=r|gzzrG@#Jlc!;81SZF zokqg3Z~b9LzK*Uz`0VCFBVEVz%hZ6Wy0sVnJh^gEdaYzhG*`*AP*G7~QaWN%&>3Dw0kJ0Emq2v53Qim&6Osa_tsl~ z#p>0o@rz&l!bJ0|;~*I2fT%_ig(j8~%lk8RN=Y}=^PEWNguU@pRGvwW28rcqLSQ0! zu|O0FMd_1Rozg1few7c8AU*CY5wD2xzy9xkkr?aoumARMoVa+W=IO|HH(a<*JN9aU z-^7nU9F?z(D{tM$YqaY0-FNa6Yuxwl8aIsCkMw*WbXJyDmkt((E0ajk#7lMDbVti4 z5|#l`Rn_F66A(oZinNoJlW7B$m6Lxm6hD?xSC2fu7v?;Tl<*$8!g9K}jLGFQ!nb z^EisM1gSJv3qfy@Z9tT9M7af=(x$@dON+&Gmw#M8XZ6R4hT6K0@qO>T_we#7FB5>g ziWxIzV8x0Rc!isuvePh&N7~_S{?`^rg zAJX75;;%p6ixciJfv5xf_hZM-&$(dz{01Ou@|4L&(rQbp&ym!rMH|V#s9vNm5K4M` zG+ODE4n63l4yNvIapyT8suaI}`y$u0xhT$K`&yojpAd+eMj-0s*(@^v$6_+Y%p{H_jwtn6jFZ!o0OK_9i3yT8o))}*{dUXk!X_?qldeAa^3YFv=fNBz@x6K_J4=;+6tszxrAKm+{(=>M0oLL zbg%jmN;`^hkP6rjov6o&i&ZGU+Kk1;bEyA_daj~CR4v~9dj-yxU!~YoJH};lQM;9OHYO~*VSfVpHD2oG|4KVpHX>+RQVQ&cCUZr!p4 zTWA*&@LITNp(!(V`5g9@_- z5nq3IiJWhjsK9i6~u@_~_%AGf^9f~7N++Q+!?}ev3J@ab+-m~27J9>BD%WW`Y{hEbLUkb*HYOqhD z@7#FmuF)4m-Sj1QD4#d|US;FTz_=ON_%-*@cz%`Rd__5dC`!NNTc4C`V1xh(&u^r> z9r4|CD!zvw-i5juNvZhTl)iIyI+8FPea6oFMDJ3+A|`{}oLq7_@?><5VPbC4THgHA zliG-oZJ}Iv~>{r2rK{>b}`Z#5e-BTrj<2 z+Y^i47t|^8fBw(^MLj38(p&ZO7kgm!yk_Sc=6orG`MssEiOG8FFYXX zF!mFO+PQ0|S#eS?T(A(1BT7J2m^zPS)IYfIU6?~&Bjc_@Ao(*^f)NCwT$>aS6_Pj+ zkBILBqRR05zm^lU$fBOMiP%6O>ba)~L`_e`>2o0*KhuewUsm9&!xe0&_EJo* zrveM6j>RKe=i=eD)ZMl?8M9{Uq)%U8ShZA}S)EH)}4IG5yOIlOyU#HG!y$CG+rz zTI@Sq%eip@zAG=J$XOy!(Nj*S^UJKLD2zOEMr~Yj84s<#%sQXJ!+BN*_m^7q@OBs5uV2J3x|2Y5D(MnTtI)*ke<|L_B!>mwfAK3^v4VWM`L-& z#wGUmUsLbPd1NJYL70w?%Uzl?QiTm-5 zCD)^Z8&clS!F-!X)(t;XUnx;Vfl+;iz62(F#BEo1ZGJgUk}f#^(dME!-Yd$>(N6uvc@)PLV?&1K`2-}i4ph64 zapf8bYV>lKOCVnP-wd6(Z~D#qE?=?nA~ikLHk%EIqLfuPRS4;TiX^t*C>X_dA{9dt zA}T_Y{b7m949+xSmYGD}fs|ZW$?l6#{9U9|t{mB%&06N$1kJ zv*+09Pq5QV);_$>PS1Pgl~?e}%P*UrC+Y53zGAuUSZl!`<+sL5O+O-S6 z``zzsGW+lUK_H6y1k}mJ1EMT^Umxwt$=pZqW9c4&fAbp2XWY*sX}Tdj{AO52Vf#nk zVSRMxJoU?mue{^M=*rT4qXFFNm^3L6;&OEj>47=~Y;fWLMKD5ayPWwMZ7bXNQ{Lm{ z@m{#OiO{`>`)1>GG!P3!C9|Ir2%-K%Is{Bt2>UUSmh?A}V7w@YptYM#*A3rAqKmr6 z#H&Zo$@3Vdt|lEP9yWa>T0C+AM%^e<*4)`ey%@AR2|~U7emC}??8N!29pD-0q;V=N z=Mn207fd7&H34}A0pt}1aF`SNom41XUfXPw$x}>6lukn3ym>Qs$vkDI zZl~1s9qu|%$_INt*t>zkyBT+XJTC7y6V9!Cb3dfP(oZr}pRIb-W>Ou+>W@;_<3WmM z?IMTs7rVb0nj=aJ^_w(a6ClTsaYU&}cneCM;wD|pR~v(9Z0f~pFID2jH!FG6d@2gZ zWMkFhY&`j+OcYN~MMY%@=Ppp($N^EQR05SUkw6r|jqV!EC`uzpQ_K_p3b1NTGB@wY zk;p}>#w~#ouFG=VE*=OK(=La|pBBL~eqc@^2;A=G{3ul0gun%gG*L=wI zTbqzdJ9+U6OkTPY-NlR1I%OdamI5DsT#0>0YS7r$$S}IGX5J#KSiA@`rzK+gj0EgI zRE_sPD@ExQ_DeLA3o@~hK-AiYCS%c(B+Oru>}?P-egmRdM_%{LR57D$>HLa0<)b&3 zQ#lZb`uJnK_R6cQ{{!5}yh8m`9zdk|X)))PQ>PT;+2@|cbI(0zb5HgE`p%onvi8`2 zh{K|v=~t8*4dvh*#SPa+E3m)6F-VF1b#E{c9j#ety_UvP0(mmx8QKb zjqBYV6o1rCJyl{;g+&+p_7tAxHoNd5(|eKg-uc+Dejex0W00GhNDeQru3QT2YI7LI zPjJ%8gXxnmE3*iV*t5B+X0Qz6wgUUYUm_V!yjR6 z>M7*&q{_nF44%S0i8^a1V)fb;ShIE|#*U$ub1LoUOu!PSva@=Q6qWbH_H96vc^UM_ zWz{Qpf38?JtRx2(d(n8lR5Px)qJ1nsHJWn)Mq-Wa`=kCN@9o(Fr-Qr3rr3q)u6*yp zb=TNW278W8!(e`I>YeftNvqb0TK`%9Kq(yQfxSeIsCIHe8b=hlATu(@nzePJ8b-uK z>0i&TZ2De1Z$J3!P<1@q`Wz~p+g*?@KD7&P6C%MjAFmLI5`k!*FZCM&B&7#fa|2-) znkS2U&gIK=U3YpMQGfj7A4h?xK`QE=15wdRXG0b%n-qVm0#&gx5_6HLlj{(qFszZH zFkg~|`*n)cNp5%5s#QECW)&XdbtQFmyi7U%mtK6yfPwt{eAD0Y#1l_&lEs}35{(p( zefHT7?AWn`+$?ow#a1nalXG|ij&w;$w8C{TE{)!#B{Gp<2cro_uXgm9cAI2q<`yv` zMp=if3yAv9|BL`p5soMktq|86jO(;`b#c4v4St7kaE-!wi+y(P{jRR_?B^Ks;L_;) zx@)X^%xCxAqf4*54kLlKz|>&R39RZ*^r%is?3tMvnH-!l%$l-th3mq0Wi*U99w;xa ze7*;ncI{Aul-0fBg9ZJo)sDC=g}97s0OtaziC@hdIEB{h&sP z9?T5&ez0%jyi_tW?+J){`6U}WCUMark#3!urEx?6w5)AZkUlgqb>l&t zD56dS_00phM?W0BxpO7J_MsEdbTXy@$m7S4*>TLf_w2^*J$r5dqICMM>m#h*eC_Mz z63Mnmz(I{!?NMM9aRKhYhAA!*W{yQ| zZJ37!_<*SN$v_%ykf(QbU&XlWWUQWBh}EmIv3YAURy^d|yr`D3-g5fAIgGWT$ehUf z9sUTSmkpL(M)13nXgYkH8;gg@d2j{^RDzX2{Tj13Z$k-fc;YOygQouPo@apZ_vNsg$M6h9=#)Z9hV z!=v~;Sb)viGjx=@^6Z=Q}Zo zDo!cQ3wwFMj`DB1M#TZ|0#{_RGUldH#qTH}O8qeb{}`jbnlon3XA{ubp2-c`v7`y= zF5;Z@vyXz57U)H3MGGo zWl|EkxW!}RCCie=A92S;x%_szFEy^PGXV+5bZVFC|LnmlO=4=$L3rOW5g&c&GY9L7nGUxI;Nzu=84 zeFUJ8)W+ki2lOh&C=a4vWzSj9i{5y)FYBt2m~h=od6jWj@5yr_&B_co{`8O7{NC{6 zC8eLU>mQwC?6Y&%)y3_u{&&%PmzSu+ZMsp~BYBMKh%z9mkf3co=lJO+^} zX&dPMZA$8W7fd9-!>QZhq&+sA*yrJdF%my6e68;^?=wz#uJN??6E+|qs-Unia*&#U zsK}va1fyg`uZ|;X59bMg_`@GYfv7<$;JyK()Zhg|N!N-de3g}zrcX)Q={2AyCF=;~ zBrb@qqoui(GV$d&dGe$!1lO%wOR#AbX3U&HJJS?{?;$%}RaKR7Ac>7qVtQhi?ctu4yn61g*YOBZ zZU$CyBJ#ZgqO2tiLN&3SYG1bdegR8IFtDcrkMxbnGoDHwLls&^Un3#xxV5T)I2x#={Gd@8I><4K*)zw0+5AKT@Q z|HRT;OgSqL=ENWGo;oaeN)rNFd6Ys^&D93lwls zgYHVMNUmZ#7klg1O=I3cMXdpHk9a^->7{Gv=& zTop48F4~Ym4lECdV(D7^OiZ+x99KrvA@(LFf3dG`=GnD()vK&d$E>4$@7;It;>$1E z7$uG3t{h%)i42oU8d^7nwK9v=|(>Wj7b)1S$q(-lGvxvZDY$;2a%6<|h522b=1 zqvmoKKHXJ@o%_nk4OKw#yh4@~xii>=bH=7%;gqp>XlWWAeT<5{*O9}6VoE7VZ2!!A zU+cTM!c}+a`WageGr%y*Geq?WL}?J_q`vb)1zL9RN8^FRs4P2;n(A_Nv#oXU{o<{U zVez)d&|5GC&13TM<-ul(#Gc2VW7PyfTFC(hJhNpvezbKN64MwYb<^$HTZMN%E=5J- zb>xgm!Hh{c*tlvE)~*gg<_>OTg_^CusFVrn165qG8b3fkJ* zOh=SBpO{JO>!0L-H#+oY{`~ni7tI)(Ve}&pLjzGth$}7cUVWq2N9wuH2*Q)drYWwc z&Z3?!DVf)NG>pUFg>Yzpm&MwBxl4(dw8Drz9 z03qwsEnO<#Xo{F10Z}mt9-zGRl>?$w1^UVh$uee7eIZ%PquU_HpNv7g^?T(aaMyk> z`QXBISKs^o`KH%?<=}aAW1qYFKJU97DDFNVH+SbxGYj~pfvB5{{rmluuk7O0tIOP= z_3AuDuCd|7KF4^!Esu&L7KoCYPQ#W87BRVKjVJXRTIUNhkahWTK$JxDMmeGeuabKQ zM6m-=r5gLAMld#ZaVkmI&e^kPv2WjZ1~h4qmrbLNkyM_Z(oMyd9UWA@7@6QpEKj*>b3^^^#7!Xy8KvDyqTsM{Bza_0fskG48~q$ppQ$(BeWnfnpBiD_~rXBTDU4`|aKi zlj4#~q}A%tGk3T=tz1|(R)4I+1|BxiP}hKW1Vp{`qHT0Y=IPY5y9GpX zsZ2m1$RglaBW?<|Nn=Fx0Z}i#SdZWTxem>pL1a^ebos0dYY2 z`ZMFw>+QI;&EwkaXLSASDo~963*-FB^{FYH#LD9Ce3JXZN##jXbD>>O>e;T1vLrqVeNU zG+`Xeoj@1k=7?%_9j~uva-!tmk~`2<*$@q=J*i#E=zE1AIIDk1tPzT5nu#qB&$YjI z=N5Y%=-XI-Lp@tM`#h;01~RebMLIMV(T`ZALkYuj(Z+S7%r^gTot}-ED)vUo0=NY5tSb~HIIF-ABb|{J2gV1 zI-*>O41B%kK$P{Fk;dNM-ezJ><&?!eeE6_&ENP)9tBHLwxuPV8nZT1J#!~s8#9t(b zJ$LS0OrJhIdL&{?a|@cAo4F%&%EFOi@}8b<1EEAP>i5K5C4g)3;>Bjg2~{|*kP|b? zeanNd(=cL>^y4Z@d(Tn8u5rrN2sna_dg<@uh|;NfQda%~m6gXmjn9Rr_>~N$MYoZw z?nl!2V!!i$t9Slqg*{vo_gjCb>jLuS!8zUQYc$VFuUEXoN|Gx}T`m8d0jQ&rj;NZ; z(h(K%PSTLF>QNwSSY>LSMoJ$jqZgVsi&JR~bvUM zi6bd3p34ng%pIm3jTaWTExbH^a1zDz15w4r#ioPsxo4jv5VfTr5M@B5(ymq7AZF0_ z@jku7`L?9S#(Ov7j4h*knTAN*8pE}LRZB7cBb=Aq8z4%pQDQv;qIe>YfT*iI)-GQq z5cS75>d{Cbifd`Cm`NaNYXRmj;DHG&&(@Z1yz^lxKGH->fev4~IPNJ=$mO4CJ&`lAi;G`nVTelGlXq&>>C~r={m*3Rkt+&tPD0NEZq<3Qa z1OiddEyMr%$ufcjA+w)+ehGj1=o~IL_h4FX4i?PJ$L94#1c>t3=dd55m2n(V2AnWk zL*-0B)GIH)$~omB0#OaD3yS@*?dOsE_2R{gxLA6TKu!rtO6Fkm=FNEY(MRolas+_t zw_~ozeC1>b8tTU-kl$Ik@<(8lfYM&|Q@odLZVZ?`eX5D4z}4Z{scsy*kcjeDa=Rs@ zA(bL!Ekc!g2?nNe9!>OQE0r^FwzPS1-8;g9O(Csmup$FxbY8>SlCM z@}jN16P1?|@a?xb)H{}ji`7?grsgV-)!+$)hHtg7E7q+eg0#T+TiW@oHEYZ48^E^K{l)@Acb)70H91x`wmPeJ9$CkGD zeD8oLe|pqVX{C#yiZk-lT)uqSIwS#5QdT_*M2&zfMC;!Z6Qu#RO9wC~uj*^MY00g?t7jydN09=GA=K7MSu=sC4?_6ETOm|5L;{Nd zQAq@%p4l`Lk8hueDboTdo(4NL@3T+O;^?tqH5Vd>-e*EmS z*t~VK?S5;M!^Q}46lnaQaaVg7$9bfTy2HAV&;!U=WOokZr%>GtlP7R@l#vJw&<(U3yi9 zY)e7T%LJMvcXuI~8-uOXU)03*bnRp*TE9Ml&a)K=U8l}D0v~CMN|3s+1QQlfrNW{` zsHjiDQJw&}cV8|3zKh^C^>s|h=)|lk3Haqtm*ST{S%PXRW|#fsi!!|V_cLg0@4?KX zd@Pw$h%K9o$oWoyWn3b;Rn^BRWsyV@+#604iv^;_a1kO-{Atss;p=a{#y8)7gK^`= zVf?u9*t&Hqo_^|S+a%4(&NB59Dige7BQR+-09f~Sn z=wb&^M6o_MP+wFV!J}3lnaRxu+6j1& zJcdeJgQ%_z;)4%^_~X00Z&amm5fh@0sNe-;rqtt!4YROy+ic7#379>4q!OQfa)E$U zD^8a4DDm`c{Nm~9c=EAH1gd%nSZUhc$v8V%c4-WaVnh6uB3=y&0-^%cQ5ES5ZJ2OL zrU%d5LE3R`T@k6R%MJ!aJwqK)o2jf^Is_z&p$Up5Uf**punc&q9{SgxuNyKw^yi~K zZc_=c>~$KdbW7eVASz@!qPXC+rEH=HM6ro9P*Hgufv7iMs>iE;sYCU3I+8{gP07Tz z4Fy=dkUDHK$mPMbzy0AQ{F$6WR1!r?fHxtJO^v#u1WeJ)D+=J({}`ZnX#xQV+Dw5B zv4p4oKyI<_7DV5Vk9Kt%1)@}rv?-hqB{NM8m#R>Gp%g7A&!gw)c?2(!tC-wUi7DJD zT)zf|v{^Hz(iY>y#Q?tD-_6tD>ab^jDK6F5Vrq6LN{SQl%bzdCFJ4%L^7A2-oeSer z0#R@8JdGA|yUd+30m~N_VcV8m0#Vt>%nl$cN2d?EL^4N~&mr=}eDncPhfO3mCnp=* zwrw+gP*O;{=gU3Bb;PxwfQKJ`7>_^xB!QhJm|8rQCoJW9z>$FINMGWWWu({!i{2&G zm9U;^t$)(3?s+v)J>DdeIZC$aS{U_>A?oVu#_pY+IC#7T)z=zvnL1LDG=UgDtqi|O zNv^=G+_PA=D2-x;bFp|y0j5msL{Xu*R<$ueORls)m|~sc%;RsAGfEGRR(RhpD@xei zGV$W-ml!4_#*g$~sdq89m9!_X|+Craj1V71)_#i zXm{REU%wrxpF0$#i|1B=D5($GayP8Z4&_X(9Wpw z^H0h_#nvWeUzz|0$-?c`3y)4r@^nT?PSZ}eBX?75rD<`f)9NJOu46cRc>0P?z0rhB z1E$!DQ>jQejbUiVLSlbPOSEHD2dA_!jkcI@>GOAdK0@&(GR~8CH8=WKT5bu5@WI3R98p6Ri4yGV(n`%ax1_C*$C0KbJ2DQB@P<(dpfI>Ag+@ zQGA!6ZDevVgwA2&m|ARHJBN#yIhZ{+fv1lKaPn9!C-If!AZf<&3*8u-HU_`=@k~7V z1c9h2VT$Lmf9BETz2Wxz5{OdvU3+(n$B_V0HZD2Z_LZ~39W~#R5@5aEOCU-hfOl%1 znyNrrk0VM`nffRYbp@~gg$KN}6D%Ni%iIZB*zz!es6`nl;GqEtk8U? z2*UJg(j^^HQd&+8-!wA`ME&L$0;1S|WhWq?V2#%~_$O#?jx+=@JDO(*x((60x`lzw0zQLrGXLdpcGv8;9*% z#$e5=G^C_a*{mIAsyujk^yWlEl*58 z6LsOD#aO>#6IQQYjTOt6V9J!qw#lmbq~bHn@x$U))UM2iN{0M7zr1>n-VLX^-n@h$ zih}9x34^-0aq&VB2fpD+rw5yG;6y2oR#A*Rg|e6_GwF*)frKhZ31_i%W*RoK4`20A z0lB%Zqj);S_ad<*1TuNDsr2|IvE&Ft87CQIvbnQeJg*9KC^MXV4i!f1d*x%KCQ@c5 zrpYt~Ii3Z>1e=)W1d1_UzLdlh2m{!)JB;JyT{u%qkwzWP(Nl@7D<C=10VRJneo!aOq5H*}ayE}f|9Q;nj=EB!?q(GE7=k=W=vO3xM-ZT)U z%!$q)5OYs}C|A+yAEN`YD{yrHz8dg`RK8R%K1?GZtCur15rsI8w1{xV?%1)I@powc zO4nH(st;%50Z~!WJc{Q@kC~COtIr78JvgN`%$&ON8K(Dp=`GqG zS+S~rKM>{8B_OJ3T#=`&Tq`gd12WX_+)sHGJ#ymgx)yOFap^)UaSRWL3ipy@f?!l> zStl+~%;WDny79(m-Kf1Lkq$0m1MOVEoJMi>6`r^?4{JBf<7rXkh?)#J^#>QUapO*=N*nME1cw7LLG z7iUt3CRGun_2Q#X>hbR9^=R#+@GV7=42VkL33?{}8pc#&QosF&L_Gg&0t(34A?pD( zZ0Av<+1N0M*+;j!6%fU#6#Gi5UMB}iBIjp`J-xVe@Ho!x`3`MoPb0Oi9D$ZbijFad zQx_$z26E1@4&u;bvSjADjTjhprjy3Jw3^I{%7;>lb_8Y@Eyhp z0am-q@X?+#jRK*RHvuZc$P<0`0Z~V|Fm0qF z@*+I{{PS45b}dewJjKIxPT}~8V>m`TWlAwQWtQXNb?bP5!zO|{C02G;f{agbM#lt2 z@5)T~gBj<~b=vf6PWqu07{$`|9)yc<4qRIk!kJSPEjxS-yT86bMelXE+B*Z?ff;=t z^;{;vQjUoQsaU;);N8k>o+RClg^N0oOb#`vvq+>!XCg&8rK`;2&QlqRFN%rw{`>O5 zHv^iX@~978J_igW&WoG*#utpnb^%d621MyNc8cazB;&*P6Y$wC;OymYoNwgV*jY|n zhILCP;;A3a;XxI7m^Cwr%F3y~R>LBTMdhQCk#WiLXWM^oo`(6Ouw?apyf8dBZ|okF zu3e&r8Sewm;A(WHteoq+ygW}w zl;H##x7gQ;R`jh0M2RD+^X53Bl(7e>jou$XlnR{{Y{ca{0J%ks4Rjh*S;;pTRaT6% zfj^v)$-f4B8ArGx7FkuY2+hKD-@A&}v)=oFC=0~*<4=qK-si>AC4$sqbyoz4lCG*- z1)}=JF@gsxk9cJ`f-oLbua16nbyjG(Xi4Crbdd=Fm6)f*^Q0F-Vx*!Yvnn`8XAf#2 z4wP@#?gn~)AGt^AKz+ye7>Kfbh#n(Al=?bPSvhxnOkvGM@{y0QIBBA3JUWAD7qCON{RLL>Ebp~_Y&-; z4jtNr&Q@BAiG6z*KzPz zJ*pcjsX4Bh+&f7WB^!gS)YG$h+cX?GLa^mX5MS&q!{7IwWuHRD?eiyK?L*_R^^tr6 zD-!)BcfC#rB?u)eFe>1*Z7bb_m{=fc98X01+0TBC&6_u&mIvalTSW@WlNVLEuD(OsfX0&vxpmVMv^=oB7hh zC<$#;@?Li(Ooi&y7j^h5Im+5`wk#W`8nUhK5hA!E5o_uDOQYg#o(8paPBI?d+KTn- zI;jRD8~HqFLgkb|>!n%09*`&GMJX`jt9R$r_cH1-^i8~QhW=`BAMwJBCY+!0eJ?q5 zgW(q5a$(8wt)eUm@4Xww-#-tc^a|V9RhCnC4bWAChvrYjBU|T^dn^wN79?TPr2asZ zO2}%4KWwrJzMrvo{al8A@Q2}&9y_IvPyz#UK6vZ@aOh}8eW<=vX)Hpmn?`}C2Ztow z`c64^^S-+dL_J{b_1*$es%Z71>Mv=H00jQnqDW*Ad9N#H6|((|tE^b(NEp_U@B@#q zyvdxMUcqe(4K&s{^V?_|{DJGW!ck`w$JjS?ch@*x_>yBgfhg&{@;IXY(-f%ROCU<= z95l^wGxA_NIvQ|S)v4|UM2VgRL{&>Pk3f{Tpu`oGP5luWI>TP%<47omP9N-2_2u4` zkI(6Ty;Z#%9jM=6fAoFji1PBlya@95|kW-Q`(S@Jj9_0Z|EUn4Er!N`q_g=;I5p{fPyn{{TrUqcNNtNdxJKTDV{#m4Yv%ZnUk`3G_HQVWxQf14}3FykdlIzQJmsz)c3 zb#floT#G>S71U5c`K8Yfqp7qM*E_CIH&hq}Q)VE4b_vF9Ux#sztYz*6c&FmS53b|I zS6XrCEOmWezkt-ah)6~9Onub9S9bos+xI%+i-{PyaZ!x?%fY{h4OeNCjkv4a zdU-0I_n40I(nP%dRxdvJybBezO(>_rVRSdp))TCo#M2n(V)aA$q`@SLnzOuFd>YEM zk)m3$7R2xso|ZL{Xe>$>_23B}{H=wdpP`J4cqo6P@4XUGU8&Pz*{UBO1)?4-!ib&s z-8CS}wNrO}K#Kjo0;1GQTjP&Y2{x(ok9TqWxH@xT*frwF;oI)C;89r4kBta?bHk)@ zkhHjX>>KwG@5)Y0Ae0l$``zyZMBTb*Uc9J=4zb~SB>J#lxbgfykMDh|TDrX!~+#L=k z;A&keni|rmi1z~a?7e_frCB)IIFXANDyWXK z_f;){s5X3eq6b$y)39bXl?N}<;_y1wuIVtaR)B3{qGr=djh5b?=*;~9LNH{ z1j^zi7xPLmc_1K)K(q&!*lH}20(Z|xFIh_3kVgGxFLf4$sN1TSz*BE&8Lk{Ti>d=> z&{TcN1ER(xp>Xa36tX;v9$t>3bt}-u)8E<%qI~$lRlM|49S)Z@p(EIaS$PR~{xON% z6=FJ12`rwTi7)o_U>8q^`|j{1e0%Z&veSZCvm_g9R~2I8rioa#LZXNgJ-#&{>gds< zb^?-4TmJbAFW}KfALRiBDdg@xJVQ3Rr>INuq!&QQt7Rbl(BqIH(H!!|Aq_pM#^GnCPXqh|Oe z!1A(o#NL(Rfzf1v+(G)E-uhIO@uW&he~h_h!O}z<;?flsd*|JwRP3^ zC`Z)2Xm$56PLAP&aYQYqQfgV9mbm?~M|q6K`%7X{%`_Z8oK_ZC-}465e6jTb2imq@#S z35kjL@z7x$K6D7zZ(PUSyLXixkqsL*V#E3kSifOCmKH2kb3zZLr^SA07(J_vZ$1_X zM9EmGWagL}cEqG%#Kxat=g(*ylZUpkJhb)a3a7&!6GW)zAnp7e_{oVo6|J~gM^Py+ z)fO#jPic~pmUCWM`)g(o4;WNL%TjAs}k(q?_(nO1tZ*=Y1g{YI0lkX91$5O488&7x2RdQW-?Ya?NP8 z8sUC5(D?3AUmJt3d7Q!9m)9dpMERbr%c#@Qs`#*TLT^9KA9iu*yq^M^_L2t1As~vb zvlS5K<{~@e+j_TfM*SB9wtM5z*mB%*{2&u(BJ84ZXU zQ6fr77m{RLDL(G|cKkq88?xdoG^Cu0H3Xv8t+fywGvkXd2Jx@&22s;kj@p)TmMsW~ zO7Y^~-ig9%uMrHQr@izP7M|mRGEc>Mg9O9okgAm0S3e_--M+bxKCeFdNk!y1W6zoE z=w@sxx`&4HYIL_XP+F=Lk?FCRO?yk38`mRhPA(#Ib5K>|K}9WXY|_yBzWsG5Y82He zFIMEl;NO2W8?U~SP6-ueN@33Zhwa$+;~;L|t3^pu1tr5=1fmiMM5XwFD3ORVJth!! z^{RNyYgG;@-g@&bytL~jWDu0f$jHFeD_3yk@)evqbqdE%99I%g0#vSAwTfQ!o+Dtf zLOE@)*}@HpC>i(y>7|G^+K({@F@PW$vt1lD2bhWklt2>_HC!S2Fmo@}552U%=dn@+ z+d|1GGaX1caq)^1x9&9K#@%L0%EhA9MIeeEQdRKwAktKcSut(cv?2!^7#A-O!x926 zQBi8P%*%uqFg*|aYbGhJq(IO6z#E%A`vAN3Jifod{EW& zHNofQc;GoXFWpnpz~h0>^Ka`5{0BlC52OHTrRM!Y+Yk`-Kr%h8CmvTKN_b~*P>hui zC}ZV+{p(+p6z%VR_dC4)#_P(Fk=P5oFGwGK2K(vH21MQ005Xz3g+Um4TsERK6Z%p$ z7?LhJ6%swptNEXh}=hyQY zyv#-Iynd{k-HJlmdwOnLCbn$NRBIEN9ACdwi_^!-aP_JKx5{Ht+ZT_F=s4tZ!THAC zaO`c96}`CI(yoB0b<3#!x+V@AH(BYS(u}XZao~&Z>?p4)r7fva7UzB->bGx3 z;nls7n2|~wQRxIoh(Z}EyGH2+h$4EzIt47PM;f~W#~B%0D8VIwmfU8dlt}CG%V;}( z35|E}p^-q;Ku0ql(1C>PWGvXb3$wRxh9@Zvp5!##De~Yh8!eD}a zSW!{wM0tf1*RM9=>a`~FMJ(>LrNJT2DI|C)8S83cTX$n|VhZM_CS&iL7VLS~O6jjK z+AH(f)l!Dic|FT-R6)uoj)LTwW3H4u@$rK&Mle4H7a{n3&{LI-C{q9sbY zS0z<9DiEdnq%T$cN6J6$9AY{&UI>Vqk}4{gX_tDVe<<5Og{k5G7voV(HpbCYm8* zzHhW^Lgyx*0&F({qQoO=b5k>}P~t^^2$6O-d7@!k!GgXOFDFsiufb~h0r4cQF0=XSBG^_B7=V?|4HD*LAbZCK%viqyj`$Qfi-Zq@EHvt}BqyDhEsoOc*sfBiM8tE)M-S&@~M zg)N)6C|gmvxw#6o64FWV&&h&mXPgfD)j*VSSb!)Gfhe~!PA;&77$~G$U+MXgK^ZcqN5y1Y6jCFi@yZS-cD?4p z>{$^=Nura9NGnwf<%6727QtM-8kmx2$pIA%2GML{fMmW?!>$-Qrtcg&@{lc^xlZ-v zBV`nPjlPzt$235Cij63OZHT6^avu;yl}`mkbqNqv%~xL)3g^wh#8;4l zA??jFM;A&D0Z}6rA>fhsZA$SZ>icvWc%i;VTHJV^uN(4&pX`A*1a8aCp)fiHNFz1Z zleQ#5hpXnL5KK8!JTP(dj$I&j!!?{6G}T9ZqRhS>q)oCs8^y zN`0)64>rm!oDYZ+o){b)#K6D+jvs$CAWBH2=AIAj&{Le4V<=t-h#CWt9_JESsJb`- zJ9_j8{`dd>e;*D+>4*6SH(BtifleQP%yejS@R%7rL$|9J66>qe(SWGv7<$d~0Z}3u zHR4O^8KT{osydBCeN|8!T(oY1;O;I(1I6755G-i0LZMJxio3hJyOiLRA}#L4wRmxN zD8-Az&416ib7%69$IN7}z1Lcw87=3amT}+_FVgYa%n-7?IwKUV*5NMN%q@-#G>3mm zLpBa@#V8E)C71|xJ>2$13IfUauTn*iZ7@^7JY4P7L%CfZ`Imm^KyUu*+{QEu}G! zVcv4f2HP#cKu*c|sR`fG%_8SaY+-7o6*YeqdU)I?dW}(M2t57jJ{X8l1ipd9rJoVe z+3u^Dja%)gW8g9Qhl=mHh)m1-YS>TQB0+7YNe~5;^qQG720J+P8m8j>Q9o)MxNiN+ zCotq-z}uS#5p6){K99Y{yU7)@1Hj;)-X{WRbw~F+4I22qmdr%9j4Q9iH$M&Qj3%hv z>Wx68T9vhF)|O@Glj)rziH3>b%5$Cf84i%E9@dxueu?!mcpn_l{8q6ExTD z#oT-%gkRAbo-aT8Y^{S1ZJLB9iY>X%fvp8t- z3)_bl4zsbl&V6*UC7DMaE%OJWKF?Y3n4q$F2`XcASlXj79Z^WgC}=mmI1eDaFF-=!pD zn!iv;qo_vHJC6>lvPc|>Mwy&40=R7ESxKO|^b~N9DSo zqC1+@t^s;M{48>8MtfAE{l03b@vN^;vBCT91k=zcD*ACRtUvJ zJGKwUO;eAPoXF+w6VGNp6b1Nf>0*k>d%po-+h*yc+81}#>yCs7VDy17#{%hfbOdPX z>PJI07P+FMiM>PU({13Z5IpPl3Ldd1@t?`2MTI7o?m8(y1Fuf#mOrWZ1Hxj;-c1W<`!}mukgfz=3Huo4qx&?+O{fOO{9XRJ2^Dfh7zdn7Is}u zNB3}oD>Nw>y1bupe&sdpl=F=M?Nv7qO035ralN%h7n^Gfol)E7oH-uzF!~lh7!sER z)hN;WSCW|H+*+QuRFy5ka)q1rHlNql;lD8?TI}O@Gumm8w(F0#_{3;nWQuoz!Goh# zY;+K#Rdf9f#(&OLqYk@5x}0$R6olM&)q$l=beYV+`H4(oFdt^CqfhEEFTfx&175g9 z2So0iZ~wAp*EjDAmgR(Cia1~Cig0F54aR5w3$nXvjUlERjgJG6u9x)oA4!nI zk(kbAEds)aFQQL6dT;+hF4WIt(RZgbxR0y<`5(+TQCTvH6VVRsX8a z(i>&nXCh>RlB0qNPe<$IXYiTW`SVX4ZFrV?&vba6`KPrQ#pMwQyg_7g)h^;;l_wk` zk+lsEN}G$W``Op~;{SMYn<&Xl=B+ca!^>y28Hy{}v)<`D4`XCyQi{*z^;mClMmqSF z-*=CBa3pXILoCO@#IRAeMwYm>z_@ft}u4u%tM0c%TkX%YH#F<#uVw!NuImnCZq za#q7ST2-$Hv!WW`@m0Ez#rN|Q4mldZLbO5f_$%|xnv|*?*Z6}mR}1rly!X?FoTi&5 zB7|g!`oQy+^$eCZ&s52KGFFcEB+cjXU{DGx2C;?7-Sw5Up8{P~!&1U;2a0!|Q1Ief zT!(&I7+YR^{0ZUt>b}!>E*D+i9C+Oj#WVh!bR?eA5tl% z0$v|qwbym~%|`t}X=jqJAfSG7B?|^9r^2s{>Vl;eR3+hO&tn3b;}cv|aUqmQ{`2hD zgCofi4Bs4U&ZXdg7A73M>)Dd$=<@YlYjMlIh@oUr%iQc4Fl{p~hZMvcUG)kh6x$lP zXrmTzv9sXKN9cUctOCN}sI1y5I~iwZfnNpGJw?U3hP8VO|G3}HnDw6TtMUE&BRD*OCB@#S@5#dGrc+pP|EzJ6iPU^aI_&eXT3SezU0{DQ@I*LB+mm z7 zgEa6eUbOoGSjjKEm=OFEhf0hhoMEWg`AU!}a`ZEvm8;oOh#myYr0LEQVo>VKMEGJ_XHze*>lQ+7>52V=R7XwD4oremaxJ||HgFN4%d|ZnfE<0#< z|C-$4$2vo@JEN;jl4tpjD$Y1yT~YQV9@w=Im6IXgufXzY>uCTW^S$n|)TxU01G-Er z+1lOlSBT%sN8%jRI}O6%V1CTs?3g?May(!RK z<7d4(j!z~KYB_32T$OO-=Ec1 zLNSj&8Zp>@ zKjvD=^XiDq-&K!t(Bd&-sGkp^K9Td2I*`0Xe@eR~m;PAhi8vFPY|>vtoVC=)n`DJ- zRO=Cm1lYt*Sh4OUp z9NG^p=sX$5_o!XDJkVI(?AqziX)_!uk*%K6lSW|!?LKrb0@6BtszdNiU-;cHPDfn_ zAoq8Z28SbgaD~MmS`<8;_Y1)>F_w7}LP7qKsx2D7tfu!B5lKfK|HSPgauO{4Amn~0 zhLF5v@}(7@;%8|!VkFoskAN=5;(;8lXb^iGG(H^^0)Vld$N1_8{&MTm9m87(>bYzS4Yxa#-+I)fqCOY_=+F%Xo z_c}Lc3LF}m5^x&zg2TclL`i^;t_QC`)v)JQZeu3=CVNjWV?$-i@@>IN-J4`*lc*TJ zKKi@*UJAX!F9R8A3fSZTE%wh`xyr=9fj@t$IVYIH@M+xcUDOku!GSYW{KsPD%g_&tBqhxSZdT8yE6w=jFm zaAJQ~2W$GJR7pcB`P_g;8=#|N1B}s)C^vPM7uMx;HJhkXtm>ZtNlRncuxLsn%9Be6 z0eLzkB7cy8-^`0TQIrqL<7fCL?L4stT5F;+EC?u(b<7fm0#S{=DE0Z2(k>6j6)mct$f=wL6>cg$8~+~6 zNR`&A!ztled6yP`0J_l=lTPc|(&CBG=SV65Tw>YYf!_Q%clb$rp-z)+RK*!R;5jk+ zc%Y`2g40mUy3UG;^4(H6u&d$2L-UtzT@bT`&380qlVqBD+Jgj2OYz}kF?2qwmh5`8MBjzj~0?9_?JWI%xKtFbEqi`H_P?N*W#PsJ{i z@EoQ6LKN+_ z-#hflh`pZ{#GJ`EFx&sjq4@D*P(=wq&(yS%M1@jrt>?Y5&{nKtj)ty*LZU_E@Q7l6 zMtr#8(-tbm43dC@?4;;T_icYsk$fE5-2y(OJv8FDyssNT<$-_-@da2lY}fOB$T} zNaZt4rn1QlnG;5?#kSl&+o?jZ#Qw{mDY}nT{PePTyL5NFi6w%*7+M zm*>}!30Lm$i-72S>t9ZLBPQd@8uZ583<*|3;u6UwI14h;GRF|_xk@Bryb7Y*%q!Xl zg0umnka2jPJdR&LPjF0uv@m)FTVlvHTUH@eyqqiAsD0Gnua8^91_S_brC)r;d?(8$ z^wxgen5Ee1;Ul9E+12frn8)KU1TTR6&NGoBB;4|#g0sk=ipbexn~vU%mmLI{u$9h9 z;89c@41In>{cYM1x9$u7j7Nzm{5?vpxI}|{>zb0`5%5UBm}gYZAIp^IPb4fss* zbn_vxxO0xUw1i{Y($9}1GMXh9A&PA(!M6!QxUIMPxH$=;)WlJ+&fJzoVYSU2+P?zo z%c4YO#K>W&M6`9?YQA(aNO241e$9du!Ks#<^!<|cW<8-9%vJ4vC;g<4R4og0(aRof z`UJUeP14G^XWI#E@Tun$*WTq`tUl0iV%b#txie?_SgP$$Slj#s$$rHAWpuv1(&sGf zvw-dCh~2B2f0rn9uo-Int4I`+6m~sj0V_#M{p)}ng@N0Af!Qv{Vg0m2U&t=YxX_nM z;YN$A7Rd%^^DFMFRiD$7Arp=< zo9Tv|hCreq>~|S!G!Ow6K#zAb3xx=-SNFE2u<4Gn;1ln=R+t?3*sXkIAGYhSc~7!a zDiNEMXKhi^fX9Q~9MX?P_V$Zc70F;1k4Ht!cQv);!L&rDzX4+G+E$ky*RZY@GHj-S zidLNv3Q^vu=H(=s!Z7{M7)e*lBqi0Oq0uzatIY2n$qs{mh50{H+7yocl2LwO{aX@6E~ zl{bvI~&P)ExEcP_&SnCrfX~Fm{$Ee=e_P%6e zI(I$@`(8TmC$Jdd*OA1|__=Yb+A%+opDT8HITf)+EGfW;mW54SVP8*IK?kph4vl6A2VpoCz{PN!@Yx?|_qDwO%2%*7qcySUZb72Wb;1Sl+r zWpETZ%BQ0Ka;o2C**PgdTInY-p4^;#hfVZnPwJEk$&`$Oh^VNjw*u7OMM@jFn)Z^s zcyd1(113C+y4K?Z{f>Jg0ma9@kDFyN^_rDvv1X$-f~Rr)3hrjNIX-qvQ*yE$S7Zki z#{K#WH8ltjoty0^CfqKGPel##v=l4vK3z5JY;5GH)7c{Ed|+2(!n4?y8Bi_9`5saK zp%+^Tx`a+gF2q6{HS=sxK2zXhfCS~Z*8V+y7ykxI>mSwhTM!MeQ6>mT!LbgHD_MJ7 zu85Fzr^H{lZEUvn9pNS_BSju|OGE^tZvYwQg3k<0Hj_hW2ob$L8Z(atViQxwIwO3+ z5@5++@1Tk>$ea-NX(M=?B*NGA;)cUXmQ24gv{Sgy!TPSz?Ds*y213IYxpv5n*U1DT z@y<>kS_>Ma442nE!`lu+Ge$Hm3PfavOIWx?zimpihg}?F{JtlRZO>gQ4uj#Ahd` zm0wwSg)!vWBExz=u=tD(W5Y_X?%rTh{o>Y6^Cg!Mb}mc!cVr7)_#O6Z-I85DD+C_r zcNFX(XsNZ$%9L&EMD5Vv27jn=JjHp`+| zX}WC--r_R}!e-tI!i)m$Eg-Vdq^;Vaf{aP}9G}K3YO2ZrYjVpYVqZ%R9o9QWzVGtx zYsj4;cii>HHl$`2?PHk&JoUJ-SA4IjCycwaZ5;@}g|u(Y4U`7jMn3-KcJo}E*4|Kl z)K$w9wdrg9N;2nmT~w85)?Hzid;c~hlfb1HRzgF>ZX>+~!Hw^=njz80=#ApiKSa=R zdMCv6dBV-wgr`03Ao&3fINX$E2Haed~_*$L`W59 zB$Ww~dnamG@Sgq3qTB+%CvKe)mVPMHO3 zlVOi|MFouziN(ps2%Iydx;{H(xTdn=6E8OTrD3#9o?N1B0(*A;6VoP2KEMHQxE%T4 zpQTU^01Ob+Ah-DB;BV1^9p9P*n`LL3m4KstEB@m4Tqkoq3n6y6sIdOQbj7jc)E2dNro3N0hP`~AKIB9wSM&DM6yb#V!e?JLgj2<}PuarK%3$902X z<5$zx@3_R&?`9;z*uYX6cUe(EIXj1us3kK}=_I7#_S$Q5qGjcz3E$b=NHVv!2Yy`B zd6HaoJ}Z7w$rmBDxw8J^=l)i+iBsXv(-PosUs}%M%?YQ^s@t@e2XT#N%-3(_#Qq5$ z5Q5UJiDu0Df+}w%zzB??Rq>BY@i%yX?&3qp&Buv(g0aK8W>L&C=~SZmf#vNl8E+~C z7{I5e2+FgbdRK=$!F3*#8z!r`zg zafzObouTyXpy#YVNV^i9_Syf9G5n#FBYi%CYU)Y$C>my&%Du=?#;32G&m^F+k1lNH zq{%|avqT;f5Q_%&dpF0Beo(!alO;`zM4VAC;TqFpsSlmmq@P$+2YE2odLI`P(sCEn z2Z-;Xe|$7&r90(+qoH@Ox9R%2!^k?z|eUBRF#pLzS)Wa zcdbbj8;&*0w-L;TTkK_2G#+s>FlyK)N6xges_BFW>Q#sP-U zCOlXs!rOy;Y2*rB!t)Mx8Tk5o<+8$!Ct8CT@GLC5Os(XUQqPr3;@)=^&Ed)*PfjS< zmMe&mEH*s^to?pV2hrLkS01s$Fm!59Ul31@XsxgV$JgYr__-E>=g1U=;ApnrB!1+x zw02}fP{nrx6QG5-TQz|(HAhIFtl6IAd`G4=gY8lZKb3^-5RWKzi&G<+l>=%0qvh12 z1x<1Y;Gdc0fk042t5W0L-pRZ3*k)Zi<^;h_0&(qBCOuhMsC=P0IX{HET9S&CiD5Yc z@pNoN&eA908qdik174BzK2%YMO=ced#K#S^gWQ%QVm4X;$*$j9x^QKUo5@Kzg`Kxj zFq<6~c0M>uv_0ku7x2$=LNV4~_gt9pi3y42&(bU#p!8J&Ao|f$)&B7?{lz+Z1g^9C znTjUjXms8FfjS%jT7OC+f-E{vpdOUgf!pu!CC-FIzMhb2oy2jYE&MF-F2Q3!twLmL zGl+W9F_30bsylT3Amh`|USvhZPX^phM{t3@wgSzS!t(nNE}c_G;b^dTLXc+KIzOW@ zF`v`c>CbNlaSNvaJR3k^#QDl0PdY}l3sN!W*1CK@jOfQ~{$hhD?aBKC(`jD9%gk)) z*-vS948Hhr4bw^9WJ4}UQ7Nbt((_tp6(NT^gM{Xj!1#JD&(W^##npcYgV?WviHRb2 z*05SyTs(oqP0MvdN?!hiT<(QKkL z!mD9W18pKWO`I1XFM+aE-t*1p7mE#Aln*bq>1B)G{!8KbRY6<%p|k=Ye2M16a9R46 z%L4(1f`Y=G9#m0YgU?(k^V9z8iWj{7*uu@$4QD1zo%2b}{I-pBw2ugOp1!C6rR|rG zygQP0(LE-Y#RAHxtJOF^K6Y5M;JMc>D=o}(+^xLm>gvw%lG$`4r_pJ|jn($D@_2OA zS5k@ziPc%No_;4XzoaT(F^p=vr}w=03S$RKJ!VoX{DL=j-98+&XC3*G)!Djj9V~dn z@&foA_yYs6*Aj&Ghc>u|RcTK=Jd@El!O!9?s@E@*2;d_tbvJ+6`}kzUnIUAfJzv8& zDA2JEmpu%)nfXpLzQCY@Bw7?fjg>Q5f5D^^UDag*@~uPUR?jrV?_%~N761W?41lTS z)oBgHgXT(ewUaxgoj794d@!PjrW{ht|02Qm8Rxc7-|KEqNW8<#v{tY~lrA22s>+ea zOEL|_B5dT;!Fx^oLm~r9jQ^h*-F!;j#ydpn=`fv6R5sz@O$Yw~^jf?L7{| zh&Y{C{8mof-+xqWCBlo!`@#sz^Mt*Zqs1&ZTD)tKpF^?P%_KTqnYWr>o2YUHEeON5 z`R*3r#3T*`L6|u6az11fZZ>k^WsxX{0ClcUD~J&c0&?IpF%?+TjmlL*SvJrSJM_}h zJ#&!Dq5no>FrMnpe5php7)Hn5IiDFJ3)-*t-%;6ne=ACj6iCBS)#BILNiM5bd!7pj z!-Ygqto7H7ZBh$yK`PE&k2rU$lTQ9!6M6-em!=WD%BygCZFF z6xH$QR^$Al{%_ zOE6ClW^=S7DQUfUxWWMQ8J|rUZ+hjR??#-H+IqU|n>0?rp^B?iPUk+>3v) z-iwbAn*HgM`KNmlPTfUvFp&`nv)@Gw8|r%{8T0v|??&8V%_XxHvV{MNAKU(Jh^C_+ zo)#iSVfej-=?JDxXR&^{lkvL4hZkyYbVd{}1}7-Z>n&k4@Fa))*GPFw)LS%AVNkBJLov&zHWDqj-4UgGM4@D2&+%JN`_ke4@k-V zox^<7%vVc3f?|rJd_MBCZsRET6Dw#;%B5<5*YWYk3VWxmS#`)ob1eklL{-{Bo>TCf z5+k04+!hArX;b!5{A|Ck9(w{;RYw5b=$i(;ZD`;BqMw6}pBGxVsr3aWlcMN*m_TW7 zJfBi=)#93wQijQjWot0p+@*)`L3x6J3kXYT7>E(ipE2o#hD= zKh#7P%nAk0DT?p^bO17UmwHs1z z#%Y$7UEF8dZTaqd|>G;AkW@R=I$0&eOY&y68P zuxq~i%`c&brMGeK;`~K8AJqw>*tqz%XlZdbKSL)@uD|>!RKKm4j?k zR^}RWljLn)eg=ce#zsd)+`1UnIVWy#-X(K{(UsresM(>kIyM`w&lE5<1$B);^yNwu zG>cB`^|%U~~m1CF8bCU2YnM6Vm$s4oeJ#|BumDM83S$!UzmCSjiCd z(DYUluN@0Q4?ApGL>=Po)T5hGX?SjM`R?~O=t9$jv6#mGe2QkH_Q0=fI`WamOAUCF zj$^V2^THWC@(QB_7C?%x3{Y5ddM&x zh!!%f<<^cl%DUc+b=FcmJje}cJ(JvK0t_}HKP6v6vKS$4!9Fe!RKecF+CkD)_exU`@Heuzt|lpWobU%6GzU6 zCS$KvaC>=qnUs_jG_2^8zLUiueer8?$!hmIrG9-fqMEA#O;HSsI46rgU7AmmsACyC z_qSnLjepK_yJyS#$%&tWqhW}NM(uGm^w2pO7ro5_JZPeeD4jjOrk(po`d@wkXjypGR?_Iii1aOFBN5XobN3j5#j_q=2;H0xoqa@*YnBZ1hge z?uZf*X4-ee%FRYFS^Hxvv%Bfj8cO&Ko6*d3$bdkvhWkyjhG;k|oj(Xh(Kmzuj<>2V z?41uRi!B>6nt!qL%|4Lgp@hnKOXwb6lUv8bACBO7b}rY~{$LgUD%*9kVBkPz7Xp-2 z$CId2>bEv_)lL>sqQFM^v#6?LJ{(VsCQ1Wek54ZYj!s?BG*h8&$OdX{D)M9J?-@ zWR9xuGfcYw7OBof{x>9*-0kt$YPhQ(53iKcR&VA80W0uY*#Ng zYgVSC1opp#N=d%hy_wJFs5o;N$kP_X$ZV;zktOi3o0K!6iT{?W7s^lLf1pMyT_B0b zBye}>g*{`cm0Xw_%0Zc0=ZR~7%Z^<O z!yzNm2}rzVIE5`UpF7ZS$5h~8NDzq*TvqiA-qfi+`k+?UNJRBTeiObfPM6PpoLXLv z7o6!DkiAikBFe-j7yR-`SK{(uq1XwoTGJE59AOpg2fGrnaDWk&P0}!k7~=tX+i+Kt zkGvD_zjHAq1O1qXEPQ2xf&1mW>1l8E1k{5nCZ(wRZxO+btxNx1^0@;M<_3%&Gh{E0 zFXhOT1$>N~VYww8^uz+}iU&C1Hqr>s>+j8kz1^y-ym!b?%8}m|Ov^m16x!1w!k7!u zWk7S_S-o|EE}?xms@3J0=@zzmy9g!{;MYhfjH%-A%2gY}1}o(z@S~#Vl*e_O7l{?{ zBlF`9m-v5xfU$REE5lVz;=cq}$hVz!d6i~34COk%xBwC|W7Hk0_Vj^U2h3=D$8wCN zMH#b94{duqi=BLV1);r4xV#PQMp>mTXBk{uBoMi^)|0`m&`@C|N~lmQL}OMr(cSw< zuZx}9pt(eYo{sp!Ffu1S*YP7w_8gzOD8_;`u|L6MT(`Z*zhh_31SR++(MDWQpQa*I z1e&XRQTTvzaRnzIw2rr=qj3cTftA2_iTa2^6>NT&AMtbAfypU~=?w$Xi_gbY)hlTO z;Y6ohJT$^iq*7EJvB!VigjLd_c;N~gUQbWW(i$|@CX^19=!$%UAzZNc(veR0)^2AZ zowmYfv9_3ZQ;)OASQ^w*>l;X@X8ogbb>BXOH4L;4k55L#8|~)pD|)E__{T}y8ne&0 z3Lnn{U#4S4t1kZWavGBj@G?yoXo_QCZd)60hU~;;PhM;eHj)^2PeYVyCH;JhaBZfe z0Wix?ClOv9Z3_`0r6jhP@FWI&FW7E8n4!+tRaW~ZBzM5`XWecvXihm|p`+oNUp7SM zGF4Hu1--2WEo2Gx^sp3F8alnAKrA)#wY8C)gJVLk)rHAu@gDIM{7wD^=EuZDJWguH zwpllWatgS}=5KpKjsQ{0UmBg~-2I#qGTxKTtiy}r=p z%5s?3mBVjz*7}aO=7qcdcHg-v8SWJE(ZJbw!7=bz`N1R(l=jwu<*8p3W$Jwb(8lz+ zLqoKb^~=U%8!a5AV_h>OG!hPcd^H5kofmoco(RqJ{)Z8)(O))Qckn( z&X<-|Aw>qV^^T+pqLEv&y4}u-tFojVV)&~D5C~RB_x-XLto}&-3pqAd z?T0x+AFHq#nep}|lVMQBbEF?=ZcS6Wd9IjF4CfwmyXDPTZ!FiijA=@cu15$|-rGxv zloJ0Bui?)_?vdw#ji&$BIO1vFCsp9eYD}McMm#1uI2sBGfyO=JYHt>9tjoE2(zzOND(?NdQY&2EaWN;pfifvJ2%6lM`E}Gu z1S-uN{P(1a!yl_V-^Fp%1`iG<$c z#D$T4Tt?G@q8Et0=d_IGp(l(oE%`AOmG;#eFYtLLfkc5XFV4W`?D%HE%4B|2Z`U$6 zDb0G{%gnOVy6;d^0(*F2=Z`m6K!+Mf_acBjD<96xCxNGle2{0DK`e>70wik_1Q|wN zyrF;tIEXUQ;It-8<};L{@WnWn8HbD@D80nW+ERG2Lc;dqv{{S$fuO@is~n~GReivk z4x9q_00a{;*ti(3u^-q1cIpEtF(*D{nh_KDw4h3!U ziCrG9s;@y`Gbx-e3^^cd)fI;Y(Q3_#^B3}5rPqI&?*dvvsXt%Ur+?ZXC3XfHlKjHO zPBVhjuIUT2tZ}F8@abZj5YXk7(AcB3wKBmLCo7pd-=$bVL|5tK64hM(oh}M@EBmOh zu7k&~)#(L%zV~kR_;L?%jQAE==0Xq(G_caY;Oq2fjjT4Jq}Cw#^DN-LV$G|(@A%4s z4L%CiC{NWNVNLUdb2JVIlRT5o;zii-ZaD41)9=!Zg^d0t(_sx)Fr!Oa&LP1>U$dm% z(j8Bu0qyCeXW*JJYkoh9zn51CzK8!EX3C!094q!5@DF+Zvnsabi#|^w=iMPTqWKb7 zg+#h7UvyLxQ_D7}6n$;5VFzVzL-wu-c4?^MWQ+^Rsq_6S zzLNLj8i(zCE$p2>wNWbOII9TH)bC6^Tczb!#;Wfq*Ky8ljxFM+Da#+kF z-(1rmUSB2!zXZT-WXa!i8W&w$Y6-g^6G`WIjc4;k&KP~JH#@)~A|e9i6-0dlrg#A3 zN|R*YCw2|EtdSyW52b;LR&bdtJn)&_7Up+UlMd~gyP+>ppM(oV0B5#ej#{cZjg7#cwPwsSvKo4 z$U`SmX$XiA4=LT48^i{H@EaUX$%_#fCuB?LewGEz5f*vDPrNnnSnR~@U>+JBL^Lcc z8Zn8PjaH|^>W>1h8vLA-f4&PkK7OeP!tW|6Ym5i#gC62IE1iQ0Eyx|%Mn7EaSuHq! zdX-2MEH7@$WMfHY9gcy>H5cQ44E>gs|LLbIGTbrOwEm*iiCte_j6F2ePy>fP?w`zf z91M}6pvhrI@7{AGHon4xNJkqMUFFTU)631r8fWy)<>K;lYnDi#3d1W-oB4t=0U~s? zon#*I2Bt(p^W7E;Yw(=RYq!41{qb1Etq=|;5PtQlT^DR;U%;$8tFg?gZIkn#65vy7+U8RwKTP02kzgpDgOUfHptWjUIJTI8O zM!kSs$!K2yyv??!{84YAj3W(vmocTL9i~nnQ!@j^9tdxt-~*?~?UKmpMhp#TmF4zp zR)oMMBO;&Kx+DMPGLZ?pVulKhqVvu=2{3*7Zls@BEpcKp0b^7pU}9CBuEXsw`jJm3 zEU}xO=CQMzh%W5M6I^AuM&@+8c@q!48$i7P0^?u`AD}n9W=Xc*-#9#|#GsKo<;PIy zv7EEOf9wen08Ee|YPoZz4&UMpl<0WZ%N!rjM{54gOL6)jWHvdd!gDinjPiizp1(s@_!dG-|}38Jc8 z^bJ_JTtZ}CG5mAD=lXfGezv)G5OgCR0#+eDt#IU^L6r-ttg6NwXf|;ESB)O2KD1+3 z%!@S~Ll9-^n=QT;RS#xZCJ2`>u=6@u&}IJsF@Qn^!4U>T&y5;6;+ja%@6TUsF)A1i z=5AErPLmhX3s={NKi@BGVxhI;*AdkzfpjrfMq(3f7>?f|LT^7%0e18hh&x78&0V}0 zjr7d=9Q_4hyOQ^*>u)WnNUr%Jsj*H~*Kb}8hRt?Ak7Q06Rl5U+yQr-o5ll%-xQIBF#{Gi#56VnA0&?#eDuqWaXR7 zZ^6i_^~uBIb9>Vd+Jl3Qu4hr=1jH#w46sN!U`D2}X;&c}>ZYB!B@e@Pt>DoJQAUji zR)N7_A!CCuAtU3kYJC&_b9K7Wea%=wuRTm3{^E)Qa%qydREdD2fAfZPj|8%yw6bBo zjFbZ! z(J4|jUJZ?iLe{>A%Z)gBBE-R=LJatFIz5Ut$Hr@ReeKBkN{UKetdmn4LoX86e4BK&oXo0y6kaKA@t@PbK5Fb=Zpnxry1RL7M$&c-;cf&bic;{L9seDC z^1iz0#pL?b_i&RnbgKWuiu@Lr*t5cr;XL7WS8?G{UGkIc!GW?)uOB0^5^r)80V{Kn zvF9V*a?YdkGlkCEM17}=GNg144(qeiZDfGp1T+dg_EUq&L~nrI;!HTxnEmjCs+_#M zILuDFt%>bUlTPJDDL9f;)Jc654+}iv?H`wW{IAD%u6{be?}o~!+8Gr0+Ds5ND+dT&(>-ETikZ{Y6gfV$l+n)_mDTj&Y_o^4Bi z=l_r& z^qZMWEw8e;3QiCF$h+f*{_T3vl!t*A#kX1iV*SxXuVpv}ZJh;l11gVB`K0Fe=#SjB zW-QIkf^qshot0h?6^@xw@1TkmZ)s5f>8-tbJ$6`AUk_%6UJgT@cgtgs6I`F__@C&3 z#)uiO6x5VPbR&7L(Y*wAS4fVUVe?6;JWmEoWcb~#HQ)VhcXZkr#3mxmWaIvPwa<~Z zy9_$2nAdBtPNq2fOL-OIW!aC2dbJcqicF35YatW0kz#3EK1o?y`O45aIrex3Cr@}K zW=#7h`&SzP{k~?rFDGn5w?C=Yh44hUDYNL4H{iEj*3iF6kW6*>43s3{l0MKpC?|Ne zWSMc(`ym?+PL;AhP$;=4d0?$B3@NBEF`&Otn&%0*-~a|8%HntDufiAi(x^Ik=-&yf z1rYhZxMhxzBnbUpJ|Efun~pJmep9GKJB`ajLxfoDSCWeo9q=EU)MiRARRbLO2>+_| zyAw`q#s!sBJo=JHQXS zkfyR^>GzVM_qe>Fwm7dfU~z}Mgu23E{7e0&9HyBKC7ej9V?EgO2^HlJwf4_wEB+w3 z14q?2=bcdjR8GU=K~{=ZiT87FezfZh7}PwziTmmgDr2kkjFp1_NvS;^ZRO zk6AK1;iXVM+y(CRvU7lq;{QL+4rQtEa#DW2s%UjjfrPI$*Jn(fYaD%hy_Be+}by8 zf6a^AsgOtDn=#TsGKL;BxlYf$I@eauSU}1*?*~88Rlyo_3&zlT#?|_Ne{-#O=wn}| zqX+g#GSkh$nIS>IOfPW;JSGc*#4Jmpf|W15vIuS-e1DDW@F$qH52OIj^*F*$mkQSoXM`qV`(O7D#RI*yT3uDR;eIN z-%B{Xsz|9T^&2{0gTCO{?%X-5>Z{J0m7f)pSs=6%@41?lt1#c@^q~}Ha`mD{nPV#f zR}q=|-Pp7GoK_yXmzf$_if8N&ncXZa+AZ4+tRkmrUrcL^vO{OJPAQ4ErlMjYE)IsJX|&XWq1zF5jz z6-nd#7;(@nRg0B5)ISLHg=&715JVsF@2BnTF{{p$B2*>XK-iM=t~oCRqticInk(bg z{fvi+sjYVW!o|u|c8Z^|JN0*+{=-aW0aFkUaX!j`Fb)vC4KxA#o(}SsHeuf1)#EW^ zmR8C0qDibLog65~G zEopped%w$iO5>MZum$b6XI$=_BT%2p{$3=>4*{&&+V5MquWEF*u6I+B)N(AZvRTE+ zwM07MMOqJvz(d%5T!*5IjrLD~)h^_VH;!h4RF_5;HGE|iggl=o1 z)_gqMqyK?iUNg<)>nLI9e{;8avv;?dImYAYK&Cm1YD1<^(uQT^1DFL7>9_)}31|7G zb+~KtdyLn*M3t8^$q@f%!p0KX0?h##sW9>OV3A_A<%u&9_zlg3-n4MKMrr6w#FzR* zfOs=cBAab%T1`DY*JMl~&c?tNk|&(xy$XP_r*YFey=fkoQ_;(H7~D1_Y_e}OUAZD* zEW^|O^3&zQO&%N#-PL0x=8n;PJ4&BWF%$7qe*x{F({{Dpi8?bOPtF3`iuj2heZ1y_ zZqQ!1GJd^feGE=4=JP*J0X483^UPR5CV@<&uwMy&>0T(%w!zE@LbCsBxEE8bWAXVn z-S-2G;XX~_>a?gBX{~tl!ayI&!a#3I97h}!l_kA2;>bPZhE{MoYx3b}_D~x#a`p|x z-dy}bH9n-KCD4jDSu<6OGw^Y&BbCRT!Pe!l+7(V|%OOb2#@K=2mFYOr z{#7HUV>?HtZF$bp39xinfU`nTk)RI!mzb7zcI>BX{j(X!IX|n4T z6vpU;*Z&`)zA`GxHfopdPU-HF5|D&;+ za)Qfkj{Hly5qIXs@#fE#sCyG^1j1GbNf2Pv5GXu}0xF3@gc^qLGfNAVIG#2+jlrjra(1%=HTc#%pyUGbg?e_>2snrRlwd^mBDip$%F`1+rUUzI&ueobR2PwZ3r(9*m=^Pdhi{V}0Dk=Ju& z$1lW7qXk7qjZFR!g@pMN?W>X#h%lD7q6cBVfs=2&zwvt-LOsTis{f?5hreG~!Pkdo~q9;>9Y^nBFNSyd% zqSWjwx>XHCxaG6~Rk)^9YfON@VgJ6ZwlF8Ls@v8BHQ2E_US^YXId&A{|LmEoaEsd5 z4GRi|B-e!!2C@5V`FfGFzz>A^Oqt;aQa{yeRR(n+Q-Zk#LF`~y9RV5e1x>s7V4reE z!E$^HN&0pb1{4mCj z{P?}j2}1P738jNBlOWAn-UNQ}+McMGju$nN{R3;+liSlRjqsm)-i=PRM&uAzp^IVm zl`B!S(YIG31d&@`hlh|o60Q=zWF>o<`-1~-3bEavd7g~6k>Mz@TM=Z~E0*VAD*u1q z05-OQ0Q?f6gKtWEOWT3zMsWVW%|ZFU@+?P zi+>5b_lIajRNNUR#N&Bba-wkVO$?Dc7sQ`YUWa;>M(M#RVXm;ZubH~KRSC+o>LRv{ z+M`*M>Nl?YPrrz>Q~}@cP$%+)s9PImTu$S`Au~ba7u1)bA1H7#mmcv?f!Kg|!sv1F zrtwGS>#ePrWL>PtneEEl3)HEHyS$)<);6FBszcqe^ZwIajwEgSb1D^u;IBI?cE9&UCy{AKJ|^vsT^2KI))eRP zAqh4s=?`+Zxm{72T+J?bd!|A{BE2Mza!@Q9s!F4nd9Fo9r+2*EUY|BLR&Bd`o;<(J ze^9vXkn+8CN5#{UtSKLe3g>0>sLGC6Gv0f52o@o$J}9CQL+tg$4l3<&1{O(wZQtJ? zj0uE#5xu)*gOltfr zYqlj&zr~|o|2VkW#|mv0)8eMxTNOGx%{OIP5Mz))@;ZFy=^uhj^~RIm_8pNf&)4+t zIqpQA$@Hlypp<0g^5Acwi#YUPn^Ae=KCZ$)%ES*;Iv2WXI2YK`e?wla*-8^cl~zju zH-RDod>rLt-z$4`uGnOgn(A0BnK>IUXk<2yoh2m#2bK65FYHhjam`%Ud|Q-32CDm> z^wIloVltx)R2vxJY1JQ;i*A~`+L>Mfuq{)P>$nJ@gya9}aDyG@%A$rrFyIUIAD{Vl zZbyuNyHocZ8dzF4&2hoGhW56DF495P^g|9n)+p^Hp(0l$pT&HsVR4WWn0d0hmteU_ z%0J}*BTgXC;ziCpmFQ3y2iut_*_RqGnzVT4BP(gF_eE{7R;$m79cpZcW+?{up+v%& z6%EMu-iOY{2 zM*-PKOIUF{IF=(qWca86IdU+O$r&XeLF^=_KdNAaiMZ?Z4v$MwCRAnZX(PQ)MS_#@ zHEqlt0@7a7i0|YkD4FU)R5C!gQxJ_>AiIYU5(G;qPrdZtZ8UM$W48*^z8(?-5@_UU zP~k!qdgaL@`?_&;Z`Hc{jIneVG&Nv+Amu?j(SWNfzde8Y?03OBjW!pHQfcr#+`-V1 zAXULaoQqh)!$~~uvIPy(NBGYBWRx0e6)1){gOrwPvb;$j@bt@;PA zBAjY@8M9c>qjy_}sLJ+kNxT>Yx)8ULVruur=%>u^DTr5P0PHP!!k<-hcfEgLs+~6w%wjwhf;aOm#C(Bd7`fA(}s2CwmAQi72KlYCS zIpEIi41N__d<^20DdhS9PW(Nd2)mpl6vWS2{m0bQX1*NK6qcXGO*)CxghiW4Bt*DAbr#qR6+pNk7g_)K>At&}L~5Lc&nt3Jp@{^sD``^eUUT1%nU7uk^V5re1@=%dwk#V> zlUp%BBM|13#u=etW%1f6?5{`SXRjjBNU(jA#b8<}K;1W`ECXA5q%O`JA`@({p`a)a ztNeIYylt3{PYzfe2hiAL9F@99J5wSBIA}#KYQ@Ifu5nl6h zwo<(W*5ylwFNOIN#E6|}!~CYh^{JK~-hv(-EwA`GYhN8wm@W4*K3TgbE;d@jltC05 zDVNN@-XO4ZMD_R~soS?i7#DtjisN_{R??LHx5tA6-GM`zt^r28%!mB_JS`i7o5kxR!{DE)kt_)CX*%=G)8G9EkPb{txp424%6k zPj6XP@5lx?L@13>W_cQ91S|t{#2G^zSD>9s(W!6ocSpdp{wxC(WPt;fvrJ;uE~*qb zCp5-BHv*2d>3TAAulDw?Cb{@LHs>Jdl492yyDpZ;#CSKGq2^X!rULaGIDDvt;RqRJtJ)2uiA(eT6VUWDE9&zLm z2uS@~_bVbe@6b^uKZXpCBf;Ujs`UtvD>n1=_p+8KWs2QzmFaSSLYr%>%bQtnRY25vq@{#UxXhFx zB79ZUjR!|E1Qv>wrr?e;O~c#&-qbl+%68zNuRX!P%Pd(W)OTQ0wZN=Wco&fJd@!|xcNG5a_>R!^e2Qc}?#9Fz@6bbr2xL)f0nJKO zX}AOS%hRIIea+N4!w6Z3r!n^eIkVM@4U%~nWVm>!{howxe(0njVjw6|+l2M&`>nvz z=HETlXkEm;?>c&s^pcHr;mb-GNJ14ijCfOE zl+|umK>0^unY_GO1|6u+l`*E9ZCs( zKS+SJ4G(li&WQ&uNAo}H!RpmqV`L^hgd^i+Ab#UXi{9luer3BbUzqZ!)ZXr`QY5nk#+_d7G=ioK*t z33#SR@s(dH?ZO9Ow*k33UcUQ5%k4?w7D=AJ1E>1!Cm6WR_NXO)n;V{s$gH5i#P9}- zhvZ}F@v&0*n(EghsqqZj5K=B3{sakbR8)EBZw8FrJA%k7E%%|?%zZYt@M(SPZHu0q zD_Y-&MXZy@GA#EGl6D6tJygegTelxR@n`8(N0-d5o57j&Nc=(Ta&O|UNLO93Lb2i# z9+y370rm2my(33LdIt&BM+&T%30JwGQbGj=pYsdW>POaZ(~C%m;J8?Nu8$vC3Fe%J zayx|Yy_LkO^_%jCPG!9lZy_BFGt)NLCw+w@VRA8wGO zqWTj9A*@NhpEnkby)V0->+ubDBHdao4?eggN`sLhoVq74#K+XsH$o!K`Oh1!pU+m2 z%}oWV|JWJK2ySMHWTEVS*Ao41;6*3$*X-(I*l5H_I6r?<3$s&uCSr``19PWy(I~y7 z$n$vzKX#XA0GS&$J1Av&s!-dKbtCLc{HETVZRco|;mf@d$8e)3Sh2&R+r5cQaDJdZ~BO zcvA-Eq7qFmES}^-R598CV<#r<0060ae~p5&Rux2BBSr^62}^M9R#$yMB3iJReK!`0 zQ?%*4bAI8I;Le-n?lo;!G^2_3SXQheJeDQ$!{u6$e7>DW)MGtLyd&IQfv>8(4ZVi= zqHGA>dzh_clL%Xj$EBiCRx6gvHJzh;h6$w#+C^Gsf5M7 zmCKrclrgwjIcjmPx-l6+@Kkc%; zwHo8!=iaqD^U2?ce~)a--*40Txb6sbEyd8H{wrZ!N=kN+_wvIYHO@>r!Le}2B#qe{ zdN%=>TV59=X20qFBQ-3^En*;*$*a_Uh2$LN<;;NE^l4UCcRHr)r8PUN3Ov_Hv~+Yb zlsfRe*7cT~+k`02E2dHzEIh|!ts^V-uCW$hm>^svDds_IEu0b75e*vsJY1aeVCU?h zNcQGN=kuB7w7uw>SCrh?c(vc#%k@+-DRdNFJ$lNy%npJuRJB$=balvcEqNh z5dgz_&Qa6h3nC$BA<2QU*K-5_o`IczJBiXTcjj(y82H~t_XD^aL8EmYjjFxPOYbkV zZ1KfF;u3Dr&%Bhn$Z$s`4k|-p_GyK9G)9{DZd>Of?wcatJ~MrZ2J$QuxmOT>gpeGf zsV9-(G@q>w6H`~z6uqVK`23F5$sQwPViTbf6BE0@N%|f| zEkU+v@0Lsz&Dp~i-)7I8pCI9O+K|48=9q`7r-MD;Y_pl7zfa#~5KED$%D#+%CxL8p zBRl|a3Z{kxR1f@ntRs8iMHjF-fhwu>E}Yu$q(sZ%3=vZmad()B46)Iv^wQjT2v>*h zIMND89ocx}6QpEB;RByE2eiw8^^)u2gtvm*Zm@~AaasXI z2Y)tuYO=XSAIQo^Pf&-MZ`W*y02pi-Ss%?GGugA^b^NK{Ui{IpIO`hOJj9a9S=d2VUUjOZ;F^fh;gePcX01_%pK& z&4inx|BE!M#gGCR&)Y7tZx;Jo#!)5fORDczVyC~p=>B&oV`GkGJgm$;ty3Ix7D%TJI7YV*_uOJ*v-#<^P6& z@PumbSO+ z*;x8d&X+#5Elcv*>?|i)Jl#*#(D`k!JWa9*tD5Q;%YiKvCoeIYYe3si!?tjSCMQFJ zR7c&mb{JD#fPgG-yR$nf&mQk4c=(_}0r_#DQ2o(3bo9^qCp{xr~YkvUWo843j9F=lz;P58K42 zb?W&dJx3Vnz&QPdim2dZsm0+U`_n6C=47^bnFM8d!*RI(pe?2ZI)()L{d$fg>FAelU4e+H z2}R$@ry)YFX3)UhlT2yc*h4&%z}$^^n!ga0nxhoFe7kXHfjRT?9X&55auF&NeI% z1qXG3rVpA*)1TQ)F#Qd3Q2Y%7wApN~R-;4)$!$L2^o>aVw^m#akY*=LQN&{dD^TcN zqh!DP`Odv&YIm3dRCRhIy#3D2daW~VwnPIW{K%}4EfGW|;>`Gs{tm|B<$2n8y43kB zTv%LG?xi5ZE%~PGuJ1*;hQU^Rr9NfW1&Ur9bE{ zw~BP-S#PI*E=EX!Cj>70rMC%HyWH#Oju#*K-8pqRuD22sLGvmL8S}ii173mGiJXEj zDPl5(c{qGT-yQT?*xuuJbaN&ON#I1bG0V*1U*4Z-3q8@6<3^LpK*;s|KuDKd^hf3) zGBA?Hq`@EiyzcHu`@D)&uGITzc2#0}iw+AKl!rs`gx+Vxll9fOuxP zRY|{()Uza*Mv!P zGCsJ8n3k6ImSu7>|KJ8linShI0xW?ub&1pv8(TVIpYR~|0Qzt$fpR{VKKjYQu|It0?+bAGNXab^sWa2f`(CU3;VfPl7+J6aq;}kUaet5UU0;aJ zn%~;3?f>5sGc0x85L9Y$heIY2lul^9oAUuL7@|Qf0oclX5zgNstJ3zEV`LbWizXu6<=9ywxo9!C?FD$iJz+=BeUS)|JH9ObwP|c5`xXb@Eox@$ zrJf$y0YsOBpA1hgcU?-hwru`?SAJiqF8?JF+biV!<{R7UC@STZhMYfc^>%eLDwOZeA4u9+%gP=%t8&$ksHVhd;&SzHWup$;L zg`NVPGhl(!E|@8Ojhv}62fqN0z!1%PqEJd8=Rv*tJ7JUt_5xo{-27Nfol{26dU!<| z4*k)EE0;%3oSZxUUt%#YSmC?w#89Gn&R++>eim-PT%yGoO{9k;m!a^eAnH5(Y3G~@ zloya#?r!V)G)$3xzACFNkDH8XUBbFg@BT-PxucHE)sZ~$^=g7_u--+~ayha_Oo|1J zRHO#TFp9`pxblX`R+pvr&{k$2_F96CJB8SS9J((fHIbhAX?Siy(ozknCh`zkB~F-L^fIzOiO)vg*lZ<~GibJN$0>x@edP zI%{K;&S(Fnmxg7N$|3<#vFwu>&eVduPK`Ljm~SD7#PH@94Yl2e7vJKNMzPi;;P>B)J zObN8hl2nlyp6j41kuvQ5EDa>aCTME1>}#^k04GXgm(~d9$%G!vry)w7z%uiN*K5)nAYmo|=B);&)^ks!R8 zP&#G;VG`{LVtP)QDE64J(DqaYXGRp0Xa<7a9?c&Wt{YlR)$0PAdQ}u+9A)X5DdAO5 znNNdR9y{bj*|w_!v3RN=*Xz*6$Md#J9pT76b2CQ_K&^y=Xmg@6;%*Yw9 z*m2ahR5}-HD=c(4uW1_z60nD*#3o=_du<}Fw0t<+RGy2e8vjD`HaWpQooQ4fP=D@9 z5edQr1!A6N6dlRchQLM>#*L%#DUK&C-uamNyuzD5Rm44VVr13XC9PTDo(565Lfm^_xzj*w@6ADf*$VN|Y1rq19_R zU4*=vhswgd4da=b3mwDE&`xq(WV)75X@+;{0Mas86Ra@Oy z2LiQ|hXloycR|OrK?|^UOi#NEp1_!W?wypYt)FG!6P_|TNH9g%PN?@oic|Zu8G~Dl z6DQOLYVc&xp!+IMr@B)25UZ~ zcQIn7r0?%{sjiZm1hwAb-v#fVIv0fqShl~5?ggFp(f=d+IRLMudR)cZE2A3HnA;R8 zS_fD6Z@FQQbYjAjt7vULB9C{XRdR!SGFfzL?NlW8c$yevj?$AQF6E4PXFQYbiLEwC zb5$g-sxQAS()OqjY|Xg>2(iq}UaCL%6pLVYa9Tb})KwVmRvtR`DMq*J$J+8QvZt|+ zPD>3@)-TLA&EjDpYQu9J6va?EmX2iQZKjxU$f(L7?cU9Id>>x7fK{-}9mQISbq@Jv zBxUoKA1hLFoBr)oTiRm)BN3#n20fvT=BVx|gS}-)%^Ii~2@$+%uP?0OcL4u??2Ho6StL3Nv^+1AjdH#+9u41oR69p~Un>!fYBntUeL%*$) zdTe(2NtkT}d2axvrsSi!Y1bp}+W9v&dhk{8^7#}ehpF7uLsFc*nheyVDLFdHpY2oC zAH|I8^T98}s|U$Uquiifpk3QhMh`M`lUZ|6boU{)JkhHx z;1ARt!>aQQGktK}iPSFlD!~BdBq->jlXI?{DKcVeSdTdl zJ}{A!$Ee%`+I?vPg5Y-QQ0B@;3CZl)^AIdyTU2}JHvct0<^!sia+WxDlQ5TssVF{e z=RU)M+{D{peBVV?!vm+Lh zLf}F(A(4C6BT<(l7}d~}{^n8~=gvS@qGnvphnl^uHGDwt+E01o!RgZPT=F(6#fqp0 z8xc;zOON^%O#}yI3NkjP5*Q}D-BhAW`e83FTM7j_y1Zmh*G+f6{m0C=m@i4kj7dkA zp7#>@R02IBS_&V3ulrH6;ct(oaJ6{fVgVtgQHFxH@7CJfclK7~)=N3SA2dHHjEEL( zVHRv~HxyN~80Qp&>+ z>-f-$5rhiQ&FLIw9qKV|YhlfKs*kU$0Pp}rUw-02JTkf_>L!Y)RIOOB#v?<*0*9K8 zN?5nd3##9r)=Vt5Oe?y}v1K#glHbZ=&yvx1vs=Ilbr2zHx26Mri}*B_7p1deTW&l1 z{i%Uw$OoNFGNC<$x-`%U)p!?>x)Z6y?a!h!-RJLT-+&cPSl-Hp4qqash73w1m!O9Xfr0|a`N$-I(M!}R18Rh-)}9Z%Wl>Z zPkjI9D}aS$SE8@$+Usp&ue?qee3gezeG%h>enge&dJ~Ch?mM9HMVM#PRWesjxZMc} z@(Vik!@Gon91}FKf}Z$oV=z1gbM<8R-Q^4@{@toF!Dk{B)L)^VzP!6tFc1bh{0I|7 zv#LMk$!_Y7EvheH;X8e)9HZV%WemUEWaA~#{5sKy1`j0$y`iD>1-zg)al4TPpVLL$ zpN|%IoA38=BWE6Te!wx)ZRIwlkJ(OGtGi}nG$SfD!4jeI7}0_izDeiALUyIs(=EaHLkV~r+_>KOzYA4?o4v& zyKTZ&7}42?zPVq@?iIhyM5aREAnK2`>gAIDiazWF`4Xnj)Ug5ZVY5yQ9(EBguxVfcRoEZ1mgdQTq}VU2HG&j1R(ZaXo@_*AsLUVGEL z95R`WHBqRVdK$ku0v`mCgfG<)(DX?ULMjAomORZXIt#R=dIB4IW-o9v>Tq(;N*Cw zNMWRC?RTITwQ8cD&jydczNws3MNgx`ivy~op%x7sr)o;7-*cfy|5T75$*2@*b4x;< z4;d%<3W24U)eMqA$b*X2e<-(Uw%abCsq ze9f{P;)48cZ!0_RtI^L-#9J)rv1#Th9DIseQDpaXy^>gQLWh1k7Lr|&%^O?l#2WhA z8l!vkExY}EO@rI||I(H5NZ3Tq0esa-##-eg0Mie^U-6N@(T~$loH7;VW}-M(xPnyf z0a->H5tT(Rj~3ztht! zz9#DRozCyfnNsCdzjS+6xaNx#X%w_sRSix}Ty;CLZa!#A5prA}wy~;SmXB!CsT+bl z-w0;p6vtiCm~X#ZA5%Ib!G1(5%Tx+nRne6#`AP(VF%om+47q+mh5(^XGnYxqAi_v6 zF@3aI4dLf|O6r-R>FOAvxt~81Gc{2Rt~@12v5s?AnlI-U&9}2^x*&JE8572DwvmmF zeC(%H|MTqhHEAbg)8%rfek|Q?+b{k5EGa^}*&F#KWcJ;KLWUN~=gYD#H`WBI?wEJ} z@K%OE9VH-ntDH{XdA(=%3W%w@o+cjN59x)VjVrrZUC$tLnPQ zR9?&Ez_jCcjfVs#dVe?xNcTi+LXp6ZL{;`i1tpDlCKVnvk7g|`M%3QfasM$ZF#vw( zN~)uL^jQaz!RRu?r@aCMFFYP)We)~kGmOiyspwq>)c$`+!zux~MfuF-gSo52RGQT& zpQTeffr$Y?uQjWYa^2MO9|M4};2qQO8S>%(IVet&kP5K_M47qg;n5<*(I10!DQ^!+ z@J&r5ETsmyvXx@bTD{fqHU68T$`||r4<%A^Ik;b z{hy_<=TI}4ce~>Y70bT@NhW$&#E}jUPgRTeE+>f5=3kJXsEdX4-gs_7cWE4zh~;rp z6=16QIs0zpJ5<5b{owZ_dzKAQWQa>yNnk$?j_V4VBaSromt8`ik9}2;t5bw8I!gf- zwbGnWWuC)&bc#oV5Kdm>I{;(!e{#WKZ7|UGLv5W z8o9pRBBt>TzZ?tiNZ@R#%CQr3!>CfiFDR?akf2n5&1Tb`p%Zyy_&ur14l%ietovKP zx`fC+-q~+^W_+7J?=IDa{h_~E3EY!Y-`)Wt;~f93cg{b_ko=#Wv7{cvGgUO1?cD|5 zI{*RIujzL;*bcP)h9bUoejz5HmNC?otf~{vOP|`c$*6T#eY@^2h;G=>{Y%;!0aDEl zF4xi?Q@fDE7^54qr$3r0dN(hD7zP4!@JPn#T?-jLxZocBDNfkDJaVKwfcXfN41WZ+ zfcEx-Y39BvjRQ5qhI5sXp+M|oqNhK_UUC3eR(YO7C6;1YA5Ox4(EjEr|I?E{ zAFl0$C!+yd{?Pk&oF)q|*wywEms$B#?7A~CCkLr6>+dU+1!`ulE3pkXPV$`l`T6N5w3{g%@DWgocn;mzkK>|z`ta(ju zB?=1*l=XPay>M@zTU^%=;CR`w1D*9Q^wEbxQPrh{E2^lhPgmsKKzZF5txaC~ zX0QD(_$To!o0mvobMW<<3nQcL*IJZ9&BIoDB#?S9R^|qC*pW2wuZs#*j}lOTcx@z! z-L8@bea)jvl~CZ!IIdP^7OQOL+oY3z!2!;E$KHwmEs74(?fM4?7#SF3qh>!z!pZc@ zEk3XOEV71Hy^xAYA+r!TpjR&0;zw?wX(Ni)zao3V^8a2W?cN@}D$wlm2T8W<$jL|u zTe}oj7>AC2mb(93QUP+k_^E?~V;nF(U91t+fP&#W6n#T$;?;N zz?Lp8w7M%#kPM=27~Ff1NVv^oci<+T_Kmz2w-ClrHF|K<_KrQHsHw4r<(Z>d@P_1) zdnt|W@#7|aZ6dK_pVE2%W=O&ohRhN>p@KG$j$23n)ES5**!g!^owvvzDlC#8oNXW| zFwQwu%i5 zhIDo%K<8Illi(q=zUw*khS3Dl(b2Kg_$iH%r^`J?+qT)6Uc?q_Xw?gaOyA-;{5GB6 zukD>*hJ#-M(U9F`_+yX!a zai?**Jb6e< z#-jZDL(AsDo%vh=Z94Nmd?a{(Wjz|)(z3NQ?PwM`#+j;(;MV?t4N0fo~=c17*-=OGHw!+wd?_cRq6g| zfe=79jGAwMxZdN^+SpAq*CXP@inQ>2eEzYwI=zLb8u7ms%A!W4Y_}Ej#)w@Oq^T=% zsSjQ*-BZlFGvQ%TFUROjuk+m`;x-nba@1R?3zvZg09?&SWN5;pO*6XfM?3oH=Y`Dv z4tH)g(csaYNTck<7~Si?wVzdx{Ln;}@Z37Rl;4~Mb*+R1J?g>DQE_1JTZ|^RDswAGOi9RS+kxvM-=^FHdnLo8p+;5OY>8j;wR3%qqadT=C@Zp&QHncHz~PT@ae=kmi<#@+g}j1ZEr7_dOKgO*0vswo>9a^#C=Nh2Dd}Af5r^j~!tHs$@)=GiJPQ9+FM7AGGQEkdwpj z5Jay2bad@Tr$$=R+Vf2F_(CL|VX3+W4cVNVN`kHjCamSd6noe8rw>Mi#}%yfhb*!_ zgnJWH14d12?#CyxflBnW-iTN&5U5GT)h(mwxdeSHle5aQb>~(6Dg`5=^@E)y{L$uv zI=)yNhgFr^_yE{8j45@ZXDX7M+v;DYU9}-d}C%#P7fB%?q>&F?4lfqL^^%X z26e%tIr$_*6vN_pQ@(>~j z5-90>f@lbXLh5;S+?hLbJw$hm7*oP_COC)YjUbP;clgGsM?qILMRVt0toJBzxR?#d zn0O;w3i%J}r=)fZG=Y6`CMgj@DILC9w(?N;d=vbe`i0=Yqx*U*f}{dkN8OI!p*gxpvMc^2>GfhvxGV=rO>af*s#d=_9 zIvaOQPQ~6M9@u9~Ljy^9@=gcGn zb>b%HyDGnY>^KJbnTF9mTyw($bMu(1up;3_ImH_`vL(_{F(jKfu5WW1f}NrD5*1_| zn&p!e352?@umNL?!eJ5&0)_YuMcK4UUtQWB!lI9H z*Zl3dyHBmq395a8tec*&j}3iOESo*faG-ka(7JIUfcGwXf@J6B=UuJ5DgVpEO{vg_ zk=p}q>W#a*Jiu7Ryn!xCSdYP~Ajz_iB!Fu!7|1@F(!F1zu2R0>?L`uB?M=m-{joP= z)?L)U4UI+;1-{4AJEI_2_pT!(7qkRZyu^E~+s~s4U>Taps8}ntvqugWeIuIuYij#f z4h55+Yp^m!qs7{?wbOEPOm;Rq5lDxprUu<_=lv0Hjm+sZa;c;T0wkUU^lRj>;WMJP z2)BH1rDeZOVNcR4)UGfKK}2q1-7PgF#X9^f_7V5SLUK0E&zn0LwAn3l2@6t!MYYN_hm5K^!8S|<)-!dLY=9Fryl3Gj($zNwT-DuR6r@HL~WI!May zY^E#G{Pn8_Sono#yEY&Hls)#=^KYp&gj+O=B~c&e-73*7RNuOGMk!p*8C(c#r#!@} zr*0(GD-TihArvq-{e7=o(k}`?1&9cb>AVoS1})C=w(SNwrhZ zv)LDM86o{7+n68lSQ5~?a^7C`2MuqZopVc|Ju;xj1fT`wVJ+esa_8XSxCn@U#_0O@ zd_JvW`SbV7pJva1SiqGvNv%U>dgv14S^-1;Nc(?|XmoUxwhT0s>FB|UqRm|Oj8%|; zMP091zwrjxHOrK~rY}#U9_XN9Jppn<=9^PWOB;JWPRN6OiS|e?9X}JXuubA_7*Ozh z{$(mOcGepl%sXzr)XR5;$L-I7?4`plONf&5IWC47$TdEom_KiJGk4tXcglyt@EdRC zmmW;9{g>wD0As6$S(68GDuK)2|BM-eN>Mb<3W=M>Qa26}AZ@F?$3}btptnFvk)&~d z@?CR!VL4pF8Ohw}p2#fV*}c-Zi??C;CpHPiM<%OkXBy4R(!0RN`^3VVdQ%T~4-Wdg zfIt(_4u+WL0X>VShIVFwh8JXlxa-|E8vA@Zb+VGQGUE}0YdmV?jBINM*_JXH_*J7$ zN=4L>7p~~%O2n!)J?;!id{y(zaP=(e8;|0+j^x9?_TQ-f-A>SJn4Sp$Hu+!N2%#QY z^)`_fH4&VOla%AirGv$BWuCVaNNOW#os*~@##GCEX?dqtET2s}BL6s&+o$j%Lm-F4 zzZ#HG&z)qP2!jaAw}Z2_5XFb^xxD;H2w3b1{NG|ve&ssb$XCpkScwp99v0aDvi05# zQe~JN>ZSUW-o-3qPtM2ha)sk{a)JAnqtVi3DrKFr`>(pYo12ISoLV9GNa* zno+GMgp;fT7S~b;jMK?iy4!#Xu$^+q>-5J*4-51TguLD6vBdQ3*dkSZA{XPJd9Ji~ zn@_FWACY{4T_}!xj@kxYBd4XgfSytUSyG^uS(CJwQHCB@k$H{T-NunHzD9O?oE6(g zcz#sq)n3L$ruNTG8Vh1LY6nM0x^&Efkx1e9nxa{O9A(Op?BeYd;*lR{1#%)c$OW{x zhH?*|x3;CFRc<&42k_a1Q`UAO9J(n0%V-JBs8WYb4J%(xK$O-`R0*2=Em;5ea&n9Y z1&)-S`YpUY8?=Bdo~f`WQ~b3%we+&gOCg#1;gy7gsakQ2wtoHOq6|pMM+tC$6wv*N zQle1v{P|fL^55QbFavXPhZ#!>z$~=hAB0O}1hS7fSnCM=!P3XZ=qv_k6AmZu@7vq+ z|2FQ})+0jh#!c&8Qg2&~zQ#DvvSg9S^y6ZapV07V`JZ<>_}=s^kNL7LcH?c3Ad+_HXMi3;@G|Q+$tDXD5Y0gb63dVawqf=D z#fq`?o{=v?SrJ9Bf4jfs;_ZUpf1gOrP^Zuoo*6)7Ty7V1i)_t5#TR-Z1kEF_`xv;sBgeByDU+4KK!JR9D%lFaU zVvK92G07R+WlP5r-AUV9mh1u3?j2O3A3YhBX%Iw}+(|`x*w#KFg++4?jZq0+EM(1! z(e@|NjmG3I8$qe1qL*iF-#L5?D=WZNam7?FG%~$vd#}9KNjUjr5|7BZpv*x`H8RiB zCj(2{^a;0P-n14M%N@3NFGEk`TC1I{-}^%NW9f}nz6sJIOr^uK0e)s;#$jFZ~l8m#@UVE)M zpZOug39Vv%z`IL<08Xq-n*659{qy?Y{<5H|-o&R#ZW?&~Ol=NBf-M(pM1V5t{=*iL zn!59kxym7CgLG5^_UftxRHOUBxb4~;c27D2ZD63(p1Mk#BJ=ju=p1*gF4}v|9}H#f z<%GWX=!PmtkIe?(h|!Gjqxz9Mp2v9cBac5Z1KgmwHnd8s>9lwqGc}`T3)4%BJHS+R z{m?fF8q%R!f$&cK&A-b!>1z#hIM&3}n5i?o{x%_jWXg-oTx}FIi{y}o+USiQ(hAlx z@0hcc!{H0%PUL|Yr@3OWY=fm+j%99J%~!Fzh@~+FVLtp1J9aK=z(N8MH}F;iX{enJ z=h9$-s&SGfrSb3YQ9%6MaaX2O&GO~+i1SXhINPZ1tn{Fo0CgNFomHljK`ZqyD3w2w zMEiPbfAm9YjMNHDvm{e&-<<%x58k{`ZhVLERT#2H8S^XMlkOR5H(D%apx*-oPAP+1@!j4un9tAC+ zAbaMFzRdrUojpTE3?`L@Y zp54^2oMjOEb0#d9J$pSuh4tyRB%f8LLRqTJdC`8!O9R5hs*v}KhME?3{f!BL4oKB5 zwJmM+dZMl|>xevBtSxS-(I-~HwIm;;tGiQ-qu}5xnNj=9EeCcSLk%g9%J{&@t-)#b zXpIDUV^YWG-pI`uo)j+ZMH02jLyuyw3C8GhY;ZPf6r;|_g!w@od z=ML1`PF}Qe63)6L5{QLAKo-j7BK-5a)E_zZkMwWpsO*VQvkH*jR*Q@*e?(msez(0Q zvj0UilM`|x*OaNZ@k>PJ%hd>WNvf%2MrvyIC}c#%lPPCbtY(tNYIIa5`J0NRF*oYp z@qUE4mO(GHg2MmGP{QkJJ|5RV9P)EM2`v=pT07lO5jq>u7y!)T3BF-GdKc`N%8Pe1 zoT|LWwnX8w_Gc&vp%<@4#gDEZWQ+}5-eTo8(r}ns_L|6Xk#oYUrc0d$2Rqp{A*_mq zM*r^hFNY98RxOn46dyb07uR+Gq;3P6bhb2N$(&qV5Z^MA4)4>i)Yso|Xvsq_j2ho< zrzOci!VmfkNNFgG`^X*CvDG5Doc&QE)yP@<>3QtizDjBJ=glPU^1WBEq;4_Ww8Guc zccAMn$1#<(8;tnS*1Db-F3f~^>;8Oh8Zz!pZelPoyw`lm?<$A)Zn|0Ljr#n>tIosW zL&8fLznnf2VlT%lUM9|40j54eTjE3@WKzN;Nf!-vQy4QGK@A2$z#4-rkJ?+inAsgz69?8ze#Nrck#2Fe3q64yRy5uLDhQab&9}GlT zu|%`AZ7-;m%jQH9<)ky^A~MrzQ2$eo185;Dj_YQ$kRj@WlZKq&hc1cGky=Fd?E-;~ z#u$366PTSgntH}d>EBqjQq0-@JUVZQP5s2n+kzDZAxwsz*Q-@cE{Z`>`jwpJBp>eV zg}msv6?{oWWWItBYRo=~+EVQXMvB6qg_s`NF9d~B)G>+no%O%syo30ovm2dNRHBOq z*&-Fmv5h_w66!Gr0K{e0!~e3BpKK5lfxCq-kKEX+_XD1dSfroSP^l%vE9B=x64Z3g zpZPAzb<)D~{@Sz7ICW$PBVgTq=*+pQsL>>S+Z`hAq>y2fuk(#3m)i(imm53hq&2p8 z6Tb`hsZ6t7|Ed@%zj4qH2i%3CLkuO0_O7zhXa8^!>I)9EPwtr`b&x(%O@{f-tK=5*;+VO zojP^rv~XIrx=(YVB>B?Sb6V~Cci)!q0Ofc72<6gS_;YZ}C@jw4jv&6IC?jHWftQ{; zZ8g@bk+hxvewwOJdh|)lYOHWY`~~=TEc1 zq=@e`UGN{7uGa17Cl4ScQ$z2^x8Hu4CKl_lzc|`PCdVQ8O5X%nOsR(BX~$jZ7Pr&o z?j$%>S{4u>w{P=84&UG$N0{<5cqg*eDrKdS)HJKwdUL_4ADVXjUQ=bdwrMY(D&Zy= zeb+@#E2GA}z~TR7%=DQru6L~23mjoYOs8?fk2$VU7R+Asfd&0x%1pU9SJhaw1FQ9j zoP%wXy@}-R=&K+URkPr*OtA;ew1%B%(64SuCH=%|tOBQ!mL(_kN5Uj-uFBzQ|5ho2 z+bp7St#&WULSl?~LWT`(^s0B$Yqee+mTu`-Wqf=3m zd$~k|4}{Cd70c9K0?iYN7do-wst&KWPH{n9FWnCpF!heHc>9T1CC4Q!y|B4qOKMx~ z$2NQjew7v05t{8w8;*Wv+y8V})Tnc+OikunU9HeCbN{U;{mS|XV04ykM!i`q#04dA zd|(-hs_#B31}Bu0jt;4-%;)p6^A=vZ&z$yS=lIL`w@?VJHAUOHzx8sVT@T_)aAc^z zo1V@+A2yq;Qv$F^uu+{lHEk9rX=Di}z(1HK#YIR|E^Iu!9wmVA94#;jW_tuAG5Mw3 z)TLc@cJxP0OFMrLdTt9jRB*OGa2bXhVW;${1(8FnxLtoES$lZv#rbu$*+E zH%u(GmDLJHMpR%mHS*UBYFy?dpV!`%A;+SrXX|{&52E*IY{bfX#~DU;(JNQAySuy3 zp$6tWsjHXrPrIz6){z2oyIz>IG&UH04vIw+lg0hml(SE+s=xqv*Xr9M5VX)7_>22? z`_Bxuf6pa}%i^`Q%cdlEmRN>t1iDF!@o1OQX@`hd=DXhZkJ677F=s@7 zNs)dj9jMR@W8`M&-(>sd#o-A-9N3tNOY_3}Z@4J#24b3$;%yJ9%zL;r zuLp`>AWUx_E!DldfQuz-W9f`l8eB!gua+iOl)$g=b*f+AM_5y`%z(+9{$;;ZG!!YAO5-v@$u}y{jk5Bob9riqh?v1;*c_diL0|l_spW2 zB7q?$86txWlZ*tVFT6ukbZeqsu!0ZPGKm%{-cg$p=z-up#7dmj%){6_N@4kO4 zQ#)?LppZ+$`^UzL{au$WD$BcWTU}=Jsy&3>WWRRpk1%6yUl|5Swf=DQ5E7fk<&yIJ zikh00XcuD2+?VO`_=R$q(AWK0hh}QcelOFGuq~T5D@A#%(O6mK7$WZ3Z`63+pZ#2R=)RePELQQV_R^@-FXi!xPGPg5LpjS5Iz0b3& zyJa9K>ho2m-~5GIkTs@8?HtMM-a-ZIhDJXv3B~?ve2UEsY=kf@4-xExxOm%X?3Ds#hOBV(4 zfYm+i>_~jZ@z>6vPsaS!?Kjukr;dJe z679(2-M15S5grW04FPfizC8kKueL{09Q_-M(L~-qycTh#-<#qd`Z1380Ch|Kg?0|!oAxCXSFOV)% zGyTifkTdJ>FpE$M2}Ix>HFpzCs-qQ@Xl=-+xn043pI2F@? z7eSaYkLVg!8zo&#dWEvlsB-amlY75(@kTFj4l^ZBwOJgjd#|Ce6A8QS>J<$|ho0}! zzg#p6KlZ$M5eKd6hNS;-Dp9tD#0ucMc4tP$f24_-vvv6z&W;v+G50eR$&EUiq#0h{ zVa0gJY;0mOiupMakxGrVYVj$-nTfo@p#pxQz(`d5!?QL?T>oCGp?XZ}DNnqC2gttt zEp_Q!2fQ!1zMmR@mZ4qNG5t9nVpu z{%pEPPqIc6Fv!6vf$4Z)bR@nZC1WDa1%%J0*WtyW~dRsg{vp&#VvM z=$kIb#`G6m#Yz&}E8c7d^!U_<`ZH_Q!DAO%DRX5;MR+8h88bveMM-rFNKIu zn?BG=`zC1Knf^a26seRk#0^XeotRA?95q;kRPU{6F^~C78kV3<4-3Skgn0ZdtvJ$Q z7{&vsO2IRxqg&a(1S$^@-HS~DzN`j2>9ErfmCmsl(JxQivcRy6DlV+fEVJtOKM{JJ z?tDFaN9i)(@*#zgbwD`{mkpJ!ZN6ZMzRA-YHcD{*{k0@gQl|C)}uD8BN~w<4jYdI{C#PVWah zAMLA*3PNqiXX|`a+4_?X0;y3d#=RqkL+ zN&OY_LD^Pk!%PV!c6s8B7m7AMD>M6nm!g<&Mhz!Nd59cIG9e!40ei<9JQ@>Q zUzI>ASu$H2th($Bk+?CM0BdWcj0H3wEKtDt0>HHLus=S}H%p)ytJaCG@2A1qPIGK& zQojQVIhCCaBr`g0{}Gi{Mrg+5NKOGL;HNaf}iG-kY(BmasNGlXg`0Z0Wxb{jUfs0eur zZZ<|LJpRgflA8t4+bEY>np=stB{tM~S(9wd`Vr@9W^lt9a4a_wi90m0rGE6)t^`>| zcE@*541C*_VcyB)`5{+JA3HDosMnc^GIIJ_2M*Z)MJQ~k`6gmYDGXp%W4xI1LQIfZ z`$xz^2hm*6*)!(O#3ynGsG@oq7VIxCgEB#K%xc(z5X@=N1#eB>JmmmfLn=a(9-Zq>NXW-<0BTC$Y;6nyNdeM|3* z%PWf`KX0h}P{8b#5!gu>i4Q`7=V_e;s=L4>2W_Ta%}5XdOm@-NB7zwPdYn z+rDRi`72}4d)PidjQF?goI*KLN_7oRQSeF(5N zlLQy$rw{|Y&X9W5f&#PW(2|(J;YUpKFFC{()^__vEQGg@YI7iv-yjz_+r&g-UxT8m zpmIT?9#^9_l(s(s;SHL#eI-Va8B8Cv8{6c5T$2la>1I$HH=6 zE%<;?^zTYQrF>!lv5yuB#8zgGH;&gT^;GLzhmb|0jZ+41t4Q#svfBJQ1t1{-$9 zPv_!0+(t=D>R=WC{&)F6w(L_BDBTsFPR{5yGm&D9N+y+EqMzGd7Uu9&`qoD2_*uJy zGq*1eh2}Ku!SaoMRYC|?1(@Nre`J-;^uM-{i%{ zX9;%xBY28(P*E>|XF4$sq?W}a7=^^)4LX37HXX}!0&nhN26E;3Lbro00C=vM3+d0( z?fS5=akX06$9aVOg=MaEwKKK*-6v8;$Hf{3@|13WLlt#(1X>lw#%W#xdwe|mvd_KA znd)v_xt9>XU2r`*g4sv&?rdEJyE~<}oP)iUg1(#m2Y>!!(e1yr9n!S60i+ViCki}I zaczU`!I(=ZUDvNLiEnAz#)aW7`VJx?-Dv47qweIF`)zf$`%Yy3EY}S) zmu;J%%-Ri9wgH%lg}NjD;e}Jc|0mz;xh82^)+j-l~DjTC7|_vJ>hd7aE%#mHI;;0vO5y@qKYYEpO+>P^mt#nxEU zg>=^hDJQ0NqkW|D*^-?%1N280|7`5VV8yK0xBJ_>koK0}*fltzEZ%#k-5Bd~KPcd^ z*RJrBw*K!ZV-jI@o!Bpo0ytvXUN$A##8W5zDIcmuKUAV0q@!eiPEltZi@06)WbV;s zt-^Sfo|P;DHUCJ0_<9_Cs-Kf2C?J!s5qz~xm#tOT_VepRmtQsTEsWyWM*&{$?81pb ze{ucG%8U7fBrMQ@%J4n#fM7vr8qxCJHvOJNl$YM)(!ZHBepiXiE>z}TUmnaZU2>#e zKDQ9l?}c?A(-L72U-b8sc9yPjB-o1h zqrKz##*bd{$AioFq82|juoG$3r^mnN)-In7(Xe_Y7NO}n(N1YIJ0|H&zW=^ULk^u} zsUtVTYUIKUM22;m=H788(*lQY7N~aOb0Z~Pc_Im3qI-`3e-5s{Bw;nON0scfIgFUJ zkoc+@FtIHwRj{K#2;dgWOHm`EJAj_FLj5NvS__ch#UFE##FNVnGMT*pn(7?WV{BH4WyZ9c9lyL?D0x({jL()^mYpj4*oQzLCoQ`g%3B zz4)(Ow$t}2VeRH{zfS?owp?ySahGV??q!7E#vy_M1Lrg1mOJW{oB@i<4do5 zSzPCTz|3u)7a?}}01-@ZPMS@oNW`Yll?+R=X4U!aZP4@p2%0bP=fcD><22+ToT#P)n7IqFd#&oJ9k6mP%S zvD~s%p_TlOUc5wLeO>!v{d6#B{}a+&gAUpM8$a?NMRLb2Alkk3#L=m40}*^SSIzZo zW>G~+)&Vby0p^+Cq!ETU%4UEY9o63?Et=>zCAp!M`bLWg8|i3=_8^ckHm%%Go~O_aFbHBWW~AgOP0;*Q*W;7%Kq>A3Er~00}}7`b}yL+4wJY-!}cP~R~+3!JO#knJ7Oodd%=Ye)aYiD@|p$3oPIh~PT z^!&2V^<;ty@i4pJcndihmkQGwF55G+y(!Sq+J*L30&Bldnuxe>@8N&+_U4KqhLozY zM<=JGD01}3d&rW%eGoM6%@x)=e`aN4=hST0epvcCINvdG@bvVwLr^3n0N;-RK{Yjb z0f|F}EZ~P4pMKRKQX+749$pQd+Z-J^*w9tuR+NmG=RTBlmKlobWgDM_98tic)`o>_B2kh&A^^VB{ zgY!q19VSMNIh5kuA8j`>7UwlID=8F!tKGT-01XnI@i+b^8DJ}=ss3exl`2|s!+IEo zhIc^txG@yMAhq)qKCnEd!#XHh?|&l5ZIK?6!Bv$dQYiIH6nTGtvq5 z;BT9lNpKlf;z z7X8qS8UDO@EM?CY-LWLr#}2Ri^ZvlXhv=EPQ{~(5o+P=2%KAEjdlQD?inxt;$i#+x<)x#UFT({6^pi*Q87!X~vd;vohI*Aq%u3}}AF+EdgEPRY)zw5_j8c9CY9 zHAcv0hE^o*H(5@D^`&su{{T&6al&C!nGC*H{nc^3k8DU}79tNu{xacac>e2p{;B5o zwf4?%8W4HyRVY_qk1?~8~ZQ`Ydf zlUG{jr%)>9Q>Pc2pgb2dOME~~Ow9-MEq9E*A%}Pslq1G3ic?GY`B9dz))qQMhM5mO zyI>cewtjyr!HsTy@ITMT%^>1v7!+#skFi}6F|f1mn?>i%dApDCg-ceIgs&$3TTxXF zoo|I|7C!)cRaj|r@*C~1CK;^gt-eCIFG=lNpUoJe&*Q_EknBG!Jwr({_;2@5n0~eD z#d49CHg($$#{V*`GS3J(uGQ-O74ewkTvW>H;@B+kq0t!|bj~h7?9t9GPdOh`e{U6@ zBvur4Xf&(AfDAj~{T*{xI_}?8w_8B(eH}1}3cwv?WL%K>q2&;v8LB`R`>mp)J|*|c zWNf}mMG@PQm321&Iu{oks{_|VVcXf+0qS+C!v$=0c=)n6ba6rqkTXnq>(_xa%U0~N zP*+!mRd)tJSo_TQYtj(_fCLKRZP8lTkEB^Ql#NF8XGki;OS+IB9T~wjV~OU$z_L^_ zM~BOejb1kY2Vb$N&o|6cyflj0FrA}bu38^pb6WiTm5pf^1!J_FDyi{=q-PO|&|91d zJ=xJBr`b0Uk7((Y-?H2l$d!AnmUB5yWF4-|2x#f+HR&kfB+4}cN?JAH@AV(0JYsc| z&GInVRr@AcIA zmX=OsR%J=2J^fTtviCy;GTu?3!HjdmRaTN3DOc*Y%ifEAY|8=dR;ZNut=B$FlLp;t zWk<8T+G8^$X7sUcn7v?|W8O%(BO)5q!EIAEC3ympKni0V3wntGBoKyxM}FUGJVs6) zA)|!K75RLZOp@slVWQ_xOalKr?c+f>@>8{u-M>o7Py45&VNu zrZjJ$qvGW7YkOrx>c=TyN`X*g7txi2z~*17pZ7*GH5R9X84dJJge{ie*FZ$GF?mfK zS&+Yd4ZD+ut*uc{VrjN1hzp6rcKRbkvtw9^-*|^BSSz*ts?M>KTdsDYm7Wi_W|we3 z#L@ogB*&yTSLROe_n;Wc7Z8v{SREkED!Ss}R7}rB@$Y=>GYULYx9ggo{XDk4fH>$+ z3z^}7Mmx!m0Ih4QDSm`tXI5_}oDB$lLA;e8H^M{+8$PPWUqVE7$`CE?&-0;S%3T{j zhTW%5KG5ayDg?~aFdG3Cp_c_m@E-OL?f7oFuPZ`;MjyBi*!N^B|6&sXjw~5MfSWCM z(=SXU5Oe6qnfNYOB-}R>OP#$D@lG_Vc>%zVVMX0#4tIub-3?N;~fH8TB0&`7FG;^n|~+gQ^4pwqSsf^ij?_K4u@-j1POL9OB2fQK;4(H#>AFn^&>cHWcF1KHF zX5z}yAvio`F^b~5cX^us3=!6gU?8?us@0ua43M1kB^l2&7}&rrBJ#=oOdI$4E>l9( zLOMLX)t{`a?Cto9KA5^?X3GM@qYYwru3bHzu+2V-?7c;BBG^zUcDd1HOLEfOCzm0v z`~_dQX(sj^-rkhzkm-xiMEjEnNTi_GIkjCx{B276@uJH54Oa;}AydNo*x%g0f4xn= z$Kh(@47k>lMz@dvFFAsuQ+Y56Qhok;vD|MuzGhhnG5EQ!Tg^e<_|7E70<=f}f$#T` zE!GbH){@nQB3DfLgE7~Ak-gN3KMetGSEO#~!U&TLR2N+)PX%`d5bZXg;j&`fzp}tG0%}?D(-RO;@kHhn{Z(k44B*2S(eJH86D4w*U^E zd&I9};Vx__**8FuDz9w0zh`*MZe)yE?*(Y%4A=YX&h%l z!Q7_vatp0(S0A8D7xgONO&oANLIB^b-ORNOPB36LQ?GS}>aLVT2u=`ZR~SA*+g}7* zh^k2U$;&B>3*7qtl)eRbz5deDkDpme{-L3A#Qhbc)iYj|g~9h^W$~D~GnreK(UD}9 zp5Y#}`0n8wb_Ov-kLZr_jFpi8zh!zDGY|c5D}DPD|Grx`y(LHawSrhS-{2@ngOA4S z+CpFWV^W7<^2hL=m)6a4S@RzPYAHMS)(}{Z5W0GsgDzLw1;Ud8OI`nobF`7k&$Y*iW zSi?KZ(F5zuu&~I{U^}syvgxaQvgs;pS=gZLxjA`;l7;c)F} zp}!>VxPHm^x2L;{?#LZ@c1qj;*w(Ae`V_&EzW9Xjz@eq(5lctBa>p6IZ2Dr{1%Y8L zF+@|^n)^GyWX-tvBYE39r@p9KxLAtJ!d@^dqY||A@?}qNPp%p^1nF<_=TBI7 zQNg3wF<73HiC>ObysWfT_gXOQyDoif83k$9Xek=Bp`CqJt086aLrJ|A-Vnpja6zI4 z1x9d59mYuQXW0gOrmD}c`}UoEO`<6A4nm@4a^U=7m6lXZ<=YN1K)Q5fP;+WkXVDA- zXSsTI|NGD_MAk$8qwrS}#^r`0!d&571d}yU7Rn8OA3Sc*CFfpMr7df`|f2;^1 zi8<@n?z=c`J%evNk1I-r02{4;32eZfE!UCt@XejKg1*gd;P zDuiO%eUwPkQ);V25b675PXrPy?J!?B+XM(v?run=co4?bEciP#I=8lyaIvY6+G|JX zyiJ_0>3w5m>;+gQEKQ@B?u7w9U~xC%rSmoRONIp^w{(<4?zIzE^y(D{6R*1*?M^Jpziy@b?r5yD{lK)X zoBcM=>4O~77!oWVSp9Tv%wu|uYyk(o^+ zTfyc$?Yp8VDyhmtTT0zB1#yY>CEG@U`k6)lok;E4goDgiJZX}j#j^D-ZPckWn8E6B z?_}@d#9Ue zjK&drhyvHD(Y;kzC~RD!L(mg@~w>??JHnm&SFTD~7{3TXZAkbkXCi zk>&}u_{_pXdq&z>$Kq#daw!WiCS|H|ytv$uT^I3oqj=fWtmd6(RpR{pVHFFz+nB5V zZM)YIlg=~-Q4BKVn`T@6n!~~0K(KW>Ya!a*pZ3Jv^YPG-b_3kD@l3wC+@Iv3oO(l~ z1?WX+vO*#vb6?yrZBW6SUIOnX2I3C{@Q?s!s*!{2lv+x{a=?nXv75vt)zi4S4nf}4 zFD(O-uWq))b}JF-?mCx^{1WWB<~Ol;$+lyxKk=gY6WZSDQdV+Oz2hL^CQ@8Z84=?m zURWXmX*eTEcsFlX-_p20jv=wJ?ptH%;TQfAjh@tsEN|JdjW5nGC7QCpBmUvg=PkkI zw&O1&j#}z}3le4`WP3w_saf>;BZ+&uKMu){9C@KG+Yl)rf%$7h%II=7F!0zn{dJ^I zPeB~2-sVzbKDzWJJqGNt$-=;3Ze$6>$VqN-nio8dfAw~0A+{8)Iq2F{@@H+?@YEIx znA*01(@$M6qc4@#=J%wi@7H`;Up_XwvSOeN-E@z3^nQ?$eQ-Hr z2=E%;dbxBq1xwO9$i^TILQF@j7R=aTW5kQi1Fc7Rj6$9kg%c>n3C}e3A{X3Br zTyCZHMgk2Mzk-;kLnHxL<@yftK!Pyj(6lBYuZIbwV{1sNs}|C4f30Q@KTGt|d>z?O z_T4z@V@^e}>ylOe_Vn+j&aH+_!5V;>HslbXo{;TQ8~&>1PJMq_=$H6kWVJ`raTjw5 zcNgQAP>WLh<_lyLP4!A2jF9pJ!5Yo)6Q^<-EXehH`VB^;U*8E@?lLo&zfAf|UY7&| zOH~gvE~NuRA<#mSJ&D~d;UNGU5$!jh*`BsRMe2$!oMw8oFlA5REh2IE%Jz#=#vvS@3SiCwvgT9XWmWz0+NlFcfnJBu(OD_MYcMR9C{K<;!H5W>i3aotH(t?)}UWm*71kl#_nxtfYdx9**6yXMcMA3ZX<>l>WwGefE z6?hf&?1D}2TawJXfsPpL4r3=$vQljlXE+&sU6u|E4|LzhQe!@gv|v?BS5+Y-+Q)Rqtv;KunCt87p-=ge*#|j=%(yyosX3-{a!fe5 zIIlfd1X<{q`*(DD(kMG8Cb&yVbWp&j1}5%{nZX%u(ec@vx-N|1Q_@$qh!9`JbR4i= z5wmqfYP6&)Y3Gc7DoCMLc#s{ltswa$W@%;(Do77EdSyA{o3wpt6VbwK>YLXB?@?Nu zV*5$8hNy_Zvgwk4^?v@KLPpN7?Wr2roO`l=1>F3E28u{Nz_)VQcnwyFa@fi3q%9og zg3k40lMRb7Wy7O6n)-Fm;xtBrTuA?+grZN_<<0+*zmm6K0URamE3AXAKAZ>M>+tmU z8-sILx8e|E#{*(K*^ZBm9K_dEnUP}^6sF0l3!~WFg~8=a&A*63%H@Jcrt%I47A+RE zIlofb)m|0Bd7>SfJ_*_C5G2&wZMW?^ta2^Kg-FZcLI-eAAxar@NI3*VwpfmdZR{8A zs!qI#kM{_9>n=#r=6>WLmo^yeHC^K8w=+WQ|1>Fbx3}tAuGALn&h%5Nfgo4d*(P7h zE4Z~T0ElW|VH7dvc{8-X$oh%J_yVJtqWmxh=WAOdK69ev4olL9qbpQNz$dME{Oi;Q z+^v6W$o|*W47)oakuKr{XWopslOvjcd#~QC2;>T5zyEoEcIL-${Eavs9M8T~6~Fv* z2ihJ{a%D7#AO@}Q4JQkf<(>~_QaaRi60lEsbUG1OO{Fhq@q4zUL?5Pspt_j6g3XMG zQcBg2rK|hl%)54Scuq@$#X>^IkeV|8e9VQ%U62<$%L92GaurSY>_bNMn@KOkZ>I$ncvXL#94T=%k<(mE`Pq zW`K#&iXwx7)FsCZC5ttpN`#5@UGZVVyv3!}sB2J>W%X&Jm&YLPfyjjWp%40|c+s)R z*K#ZT$I*|kr05Siovkrc$WJfw@WRv{6zXBHKG1SVyU#f@{?RuoLa%l{Ch6X#K@P6m z*oFq3l~E2kZ0B9|97*i7Sazxyz#7Y!vHjAISOA+W>?cC>-MFBXjTJqG)M^ecVoxbX z@H9b2f4(g1!i+a!rZi0lEZ!CGBxi(E2Hk(b9j;vBU}b}GOAt@HUThw)`=bH!mgHE* z4RTRM{l6eMbEXjtiMPdLG7;IljGxs;6R7+|1!qz)jqKS!iI&z2hduqGGv|!Gr%n#8R!3|qMAji_QqzHFmB09eTpe<$9LKTR@J?1?R##e}s#qCW~8t3gnz zLwLU0y?e6%J=Fg^QVL5 zKP@7U=-&GyZY_JdycFJ3DW0v?cwNJz5?`PPp-`$a8`j}wQCG=?sd4jk%t!N(FiiXO z7n(%dVF~vd7`|TqTJ$YivWmHentC5v=np=r?ZHbv2#On++NPgJ8p5E$Y74lVCx;!7XXTxK^22Sv0CyCANe^AFO3ac-WohJu_21%ni*@&9` z$r#7pd|s!tn_uK9PI-PXw3g2M75wwY>r-5u%MH{?;+ahQceVYB>Z@pYRk`4{Hm{70 z&A9?%F;NG#|K{UR`fq)$rEwyvIq#T>&nd3B(QgZ`Ix*fi?w{y)iPu z^pYTnc9eJ4s78j_Br)+wO>##@s)7`?fY8~clCAElQySZ`i{Q^hq6 zqD6syDj!;1qE{AJgMtMfZW06ku9yr)n38MKYYlDUj$-+}Nl8hL5V}kib-!igsYG>s zIc84i`$-BKgB6`SRpnc5&Qif4l}20MV0O@eI9R8zce*?z3T;sI`<$TUUuGE4fibQ={5rTG9JZV zpB9<4CJbY9TPYZ#Yy-f;yU(TA%2PPlZ`wa2OHyh`?(fk&D;j){;%FyI&Q# zww}y?78K6DtkMy1xw)Q|pwrv1k5e5gs^sKCxE_PGSHR-c_4O&ouL)9R(>fk#d5PGx za?q%l3i+)g&*KeLaZdYWXH;wseJJ-CpAobjzTq#Q(H7GM9eK3KOS8aF`&m z4`6daUlr!DUvU0BD|PD=EJm)Dnw`cz5T0j7UBg`3|Q-*uXY`8Q6PLI(JL1q z$zz2+$;M=GIgl93cs1gkCbECvkA~2 zM`B!+%H!aFy}bnw0q{VOb~V{_T|%paNjI|>C_?0D zu5ya}f+VHbQrr&5aecbxyTdI;(x(!#_;+T!66=S9OTk-0*~T2oPX%>lF&nv6l8-;$ z8^&rm?)Y8(6;@!XG2742l4zOkG=Pp09%b{(v~y5AZS&d(?3FJ=I*<~ED)@6ffrWkL zU^zp$aRlL%M<(Zkf3`3?Dzi=qoXE}%o2`H@tC!gnQZ<%no}7gQ1DpBIW1ngD#E~J+ zcYnvJQ6SA|u$oybWx~A-UPOv4lG)C#%aAdA&&;!>R z=(k}(5Po~g;J&bkmAmPx{Ndp8j(IF@77NPghM_SbDz_ncQC>3kb!XO$ldr9M+Hz64 z(%%FFaTb!mV67$bx>XuvNCl}5B8JqMnsQR)P}}9>G4j`atv375n1TL`V+Rb(P4g>S z0{2H~8hiiBYi9kcF)dEpgI&GN1|lx0M2*vW71apLzU*5bhuTQ~bE4H@YeEcZ#?E`E z9L>i|L(XX>CHXMNGxscaaoR`CGlGBlUnNKu{dt+s~tbai1zb$V0u0cGLF{BZDpju0+=vu5-E#Z$7)77 zOuv~?(N>0IBVxpCc?W~bu_8`}5}iql6L{M9q))pIa5X~2QGi{knjRsbhI6P^MhAS1 zbC`haTf-AHsF_}4Qey}sUH6-;bja7yw6a&ZT7zgsVEdPfrmA@rIV#khQ4T0yoXD)s zN#`Hm+xlfnT#lvc4}w=}UU7(Cp`h_$U}}4+V*y8T9M9V6EASujPkwx>@%U4M-}AFm z5EW@$TS)n7dCsi?e2=cSeO^-3N@hhhg1X! z(8*iygf{clKxDU8J@AYlQ1pZ}vTF zj%7*F(lh3Aqe{Af3S+G0{H6kr&wjqzQgaWnfr&gCgMXGpHJX5(Mz3xXo6g}lGVJm1 z(SXI90(wex5Jz!e(bXlw{l#7A7*f&}-SbhN&L$|xU-1B?@HCO0PF{9px zuq%I#iW=6TccC?&ddPW_o5Rmf0iuCFwJbf57S>Q?u+QrJlQhfPe>Etr#B+W>jQYyl z!X(U$t>w_ca)X#6pBDvaZ3z8_1 z+8!_h#^m7NQ~13Ky0`!o6gS6=_DIrGm^4p!3%#4CQ|cHFkZO_PB_lfJfCrT4H@{-! z{F)=eJMe_fN>cH{fE!Jc5UAuVh1e-em8__IJA;9?A0*lEw^N49n3n@`s}6N~U6fHE z3F*T+Kh*M~H_3Y|Y)-JM!v5?#h3@RMPns22b4B)%Ky+}x)w)W4U{8;Po z=^KBmA?={Fl-Hw7MnZw0gwjxb&z*7t=%HcO=vI zC@dFXP)WH_Gz)*O=N=Kw%`meJ!K)nQuwmb&Izhts`ulH3w`{nLRmiFR+86|R>s2u| zo36{y320&fsJPWJv?0KP!^O~0lN#01uCPi^Cetn){~IHKGzk6C2Y&#GRQqeUw=02=u`8*L1b!hE=7xC@V3A}YbmuZIhF%ePlN`VF zsK4I4*M`lS(1oo4c+R0JZ+q*g_J`p;=^WNXdoVDq@D-6KpYLDI-vD!M=&D`*x>c}jRu@VQ0$@%RbX=cOOFyz{U>S4$!M&_Pc$=-Yt|Yuas{`WM`y4;E-b zWpJ(?ZqYi_p2Q9ikg~5XNQqkv6e_g1h%0}l1idR*w+g$oUFK!J(u{RIGqA|d28JQS zbEf||KN5sokQ*{AcE?{ieSRi6sPR?6zfwJ%r?|pi9)@eY;tEdTn{?3yvBXWJya^@AzvM%BdrxvtZVqVEzTNvBHGh)^aE z6!EkGm9IEkp?ZYY52?1%#Y{eg#UdeUK}x%3$E#@Xq-C$#ycwf^ddVyt{uw>BB)y?M z=@TiF;P=)+?y}Jla`nad%yY|cf!2%t4kDW9dt_}k$J```oy9E&M22*DEo@u7T%vU^ z8))fmld%q!S&ioDa2rCwNd?$Tbs;1IqfH9?cFQsE{vS=};1~J-e*MhNw!LBFX3b_z zP1|m6vu)RAZMG)c#%{K2tI4*_{mtilKkmO_=6b&_obx=7C~&1&XvLICUtFa|OP3F1 zW_5*J6CHlT0Q>68DxFnIJolfR4;*6i&W5P`f1X8O6Mz4z9U4aIg`z5UM^DJE53p=7 zp#v7eVeR;8fsMDd7M)w#tvw*V&iH2o7m|Oon^kmhFO_!gqQxK)*H4F%@tFK@zK);? zj4h`H>IJdj+jrvrb)NQARHxOkTg@L*3WzD3<3o_JVx#v?r6lDWS|(Ng{LhgNmH2G^ zS4x4tmBFasx4bgz(T;Jg1e>t8L z8mO`^zaA==#34~Xpn6-{F4J8LYK0u%_ov){B){8pta8$R^^gSg=^V^c{DYu|uB|%; zi6D5-cc}r7A=3LLt&Blm^8u5bx6{V=DM-G0Bygq7?mMcxi>hSYjzrwkFcJ{M} z5!Tc-6WyxbQ6MPc;GVC>A4P^a*OQpT;|o$MW^vwLnkp^ zai=d^2SK3Y58Aqi)=pG0UH3DGr_B#!S3Srvt?F~p6%-TSL_%_Eaadb^Ze#aop>1hhhvNMm1{&P3D~I~o3~;Y3ks zJD!e3ou!PE&M&vTzDyU3x%cq!u(z{>Nj9eo3xBsBBaEYE%M!FEcD%d_Pq+tr7XBs- zyQGt(e`|MPNl|0B85~bXkTEBHQ6eEBNpiuarh5ms*fC`g+!Rwc6U zxL8OKwlgWo!{+FP?Jx4bpw4~{CFZZJ+C(`%ZeX_?n zGXEd{AhMY{N8h@C2yKmcMNQ8P#xX||l|vj_%SnRa8*!5V0{%qtgZ0y;YdlTIU0P?jZ3BT{6|76+ zcGoS8HF^1zvRhR!PtbJ_j5~G|U{^SlbPV5`8b9L#oicE4G6bp%yE*Zq=6^#tc0}R9 zHZRR9F9||Bxn;!IeDAz`EZQ=Z7~#)v7yeMWU1t`3=17Y79~!)jk-)WB4a&3KUb`Wd zWn?iD4Wf@lYZ(LhOb!_^9{CgQ`>Phj z)apdaS61Nb1WQjM*@4mfstvxMBDw3MC<2-H@`;i@4j0f3b-JkGP1r;Zr|ytJ>~v?$uk1_0_tt%ZdIf}leNXLM;+0enc(b)eGIdZ3UvTHFd;zQ7#DlsniQ2q6bEzWY%-^1rPR%0rLCjd zSYn>Jk$!ESh?TWel=uj5RtKG_pcfT)iS+%AJ!_#~2uN>q7gs;9r4LKZ`K z_z*45iziBUJ(Ls_{}{i!*V$d_?G7|ir=P7VYGb8L0A|O(GiQhswat|sCj&Z!M=X(k za!Vu~FDH$${5(}dC9fzu8N%`=tMj+Vo7BYEw8*9!E7>!AgG9*i*&l6tD6!ltghxoq z6uc-Woo7YQU}0Wr|Hj(z(FytY;7`@7B|fiC%1Y2?`Tbjm4ddU+w7`L+a_#!8X^kI$ z0?=-Ixp2e5w~6y8bb)J8uqC>@ak^2Ews-)DGH_TVNJJ%fOT^;fyBk^ZYAd;RH{sL+ zZZfdL^P=lPsj|A7Up;iLSh=qtPE2N`bRlh|osA}!^nlRhV*#!rSa?FiunIgEJID}R zK<@;7ukJWW%Vj_L*ptEpGIKsj;yUf`z>8O>-AoeCj>VC>F5DKjFk#AKVr;8_L7!Y~ zoaHbge;$Sx1f@<)WdwNgh$8H~rU`5WgSTBEDT+pI$lv}oiVryY{Q5L0ec|IMpA>G@ zLu8;ocrMBZjRcca9)tPIY4DQ|i`{I4FZ?SU@PM;rXE@nRp@0v!vMX}$#`kgPw@$!8 zvx>QxCLE>|UPlHo)Dwrf?*(55`~(3-^4h59&GR{|fI4uk(3HY_+QXYuEx z%@9kRo0Lh*PSPoSZgdrVM;8uuvXt>29GIJj2L~QZDe@N^>zmj#OcCm-FDwA#-qEoq zLP)PBZ2ORaISDWULwb){QFe6V6fg)Sd%av9v{Y{@lQP>KT6}RfN9X6rj!kX;_$g|B z_XDK6)NUx#zb$;~VbL)^HC74|;JK&e`FLl49iJ;Lk5;|gNt)MG$|I3v)>k-YA(2#l zNm(Xofyy33Vs-2=J7p~Tl!tkJ|1*KOJiCPO49cu?ZMsEy@l-P$3{H0)2Kds_?=l z0#by)qdB2FfRf$N{$vZn=SAJFZe$})A?!uYq?%2O%>YxLfz}B-@7s8aDs(?L}NQ2S;u z&P2P$n8w;xaJb(LN>u*t?5L{FF*_rVRwz!d^5CR*e$60=!wAHx<-dh>3et)vKK$}L zPcrQ5!K0p99gwPjyv;~}Oa5b}*u+?bf!;R)Ge%jo6#MnUD6?CkLzIBvZK^780SI6S)_KdpI)%3q~;XT1xc{@;xMt5z zgS9YC2*SNy7O>UjBO;^B2wq0FXwAxb@JWI}SL-zeL9r}c{iLBm^(^?I{{+wlkigfv z(6qhFJF}zMyY@Z%O#612z3PN@0b9l@euP?S_4$AZF|6jP>3SbXu5tczWkf zY7G3Q!~5BtoOnv|L3jQ;;SGJF@a-3qL;b}O*y5;9!}Kfmw~>zopH^gr&C3EQdmOqN@EiejX%+6!pKt zyxg`nC24PdDUksu9wXiGA5O~#>#jLKGmK9=SnR#eu2H4ylUPCs1(Uh%Zkixl?xY0-tZB- zD2^7oeu|azF%Y*o@N0hmU!7L}uTICd=0C9F#{JbQrx14A#PWX(#@T_gH2p=WN0qeC z)zhiwO(uGSLK;?xvG4N!-cF2}A~Ua*Ngj7Y$4e)76|T{xqG>4=2@q?^jqb1`_sR+x zcTOmW!TCV5ZR*v!dFssUV(9rgzsS|}htB6&T*%spq`4N#0Y|gZ3sGw8uPSLt88k-I z;?2e1IX?}$git*NE^LfV!x!AeA zh2B_BwVo{HG~nTSmROmr-fx9H?vVNS^Og6a1bk~ZVQIEoi@YQIOJ>|20Wzwm4xi;h z7tUN#^*kwNINJYc62W@isW+VA`%WCe%z?`QTZHN(Ee&6kL;ut-w<(WHrpc?Iub3=C zqH}(H44@I+Bp6-#%n*$q6;)ygX)H?1CJZ^rzXK3j0@r>a;-xTv>| zWA_g@))huW1uJgGA|_+oOGOdhM?{~-z&TmzndPLQjOX#MyERZ!Tq>eH;}~lX*5K!R z#QrEHYGEEm!Q72_58!PR9krL05O zcAS(!=!Ti4pV^Wh&J0%k>~WeA3P1Y0<^Q%K@8euZc!ZFIR-bV7SnRpf=*cl!3~#Ej zyu&cuM=DIL5bPB!kB_?-6Uvz;diVVYiK4lwCPiVaJ+2H4Fa*(KFIfxfMxG$)rDWU} z@SD5{Ne4N2s~eb}S;g@Aw>bT)f&p&R%!%AedwH2SkNnZt67YaSi2pY9Lt=gBB34>a zTIARo+40bU50k1Q-vk6ZsmBf=TU)(D_WmT8j&#lBYPh9KWh(>Jv?qaGCKsP|LLLvp zanm%xf+XM2hcbWIX zngAY!iG~~V_ZS;S9(y*0f+W&tdXK&y{3XhtE%*1ObMbvMIT5hn$s1OdaWEw!?wL2icwToxDe16*@~l2HtWP z5pVz0i^OmY9xqDdmETVp^7@m{d&DncB?K!z^qcvpbK>%C1EAZH)AQ%9i-ht z)iDW?+_=zrdRPWO#NhHMEcwxctjM_h*|A6zu*pVNagc0?5eNon{%c-GfxCfhssdS2IPgpsM2xX#?zt?&?@F-!qXq4&7?PjpeuuNy*NfS`6H z9TOdC-OJfGTA@|L&&!_md8TxaK#k#Ja02I*5h`4i0QXdEs$_Kl9NG zQOteDE%^^m+uc{e>oi&9@C?Iq9Ay!0N1oO2NxJJIS(*I&E>$RaFlkW)Ib4C4ADmGt z#fuw$Jb1%avvoDW4jRjhCUK5L1u)Ph&zhKzty~@vX*RMg0I*EpON;Anw&!{Aany83 zR-^Xv*BV>qg1q?uz7i=7k_0V|c#A6s-ZmyPljc*_c7b2UA#^ zx9N61Eju5(mz`q=`%7jm?m-Z@i~w0mg}ic*2rNBSjGT2(b;7l$=Pt-a1sc|V(QV!T z`)vjB^s{s#d%z;j)Rp)f>o=4pG@v3hWB^3O~n>CvD{Xcn_ytFTN$ zjOYAvkEVPsLdJg9_+&G0{sjR6he)ze5oEwR^rj3E$xT|-@+=5QvPA%oEjXfnS^>Q8LCIpq*M{vhv$_qDEjvOet1OyUFCHA>E(&%Bzu5fSq{aBH z?pv}J_S#7PF`W<5I^|%iZV2~s+Dbu$<^L5jmpD>5H|M;fr;Q!|%NCyW3xuql&uRUy z^)A3;D2E7xfB~oIaf=^0oK%zcSPU5qYCNp70<`r3NF^25h`+24H;8cZb#giagBH89&DY50%rjiEh}<4gU(Fj0?>5wKs6|#-%8)I47fPWmMkDGEXGs($sHde zWD6nehXW#L)6&FyLnkq`UKpS_!qw3|_C3WzL2*gqV*BM7-3^s#bgtn6cI6Z_I+n8z{=cmx{ZqlMFt-An$2AwURC6$q7{|@1T3kRRory5XV0#HBB zyc#xgF^Unh!!8PDrZg8*)b`)&BE!zAc%{F--b`KHuh{R*7Ab}jp)(O0t4trc8F81oWKEEqUw_$x4-uO2vvq|{ zokzb2#hFb_>sg%1&d{`XgYDxeHUtq*)9jxwxv=--0Kkm7rSQ>Dvu)5(Sh(cwEhFei zW0`2#b0ZEG5W$~M`vtyC4Vg-MIGvR>qLjpaRpGhljD{ppm$%Zx# z{e zUAG>KkRVQ$Qbtx}k@YK=nOcOKeB~4-=8O#(T*BjVpKQje^5s9P7N>t!9uS;*9X2C4 zM6~{8P>US&7R}9=)oY6;=5g>r^Ja2Wo#C*DlSB~jn(KFTPGid6?28&LrQZ_lY}T~_ z^jf{rLkgCi&&hOa$DcHq*Q3LQ!`g>P_!^L+A~B{MgErvZ|B;TBx4=@ei6$4@ZvWCAOM|t|~xW@9mjvVfP;|&1avzlJuFa%USXh0~Q+bnymPWFw6AYtQMT&NBR#t zTj$&_;>JhVvv6YcXkHZ-(+~BUEY}DySNTXictt4XBSlzC$R+iEX#`^z9r%bf#lRH# zcaV6ixr$K`9Lzdys?oVoRs+5uGn8(t$7iR7TDE;p`<@W!8s}MekIH%G`FwbmMtMWO zJCvG~YnNAdjXo$de|3!s2`43o1!Vu84m1W$oX}xw9$NpIU3Pptv*x+F93rSLq556uWjNJ zE2+n4MR6jgE)bK&pSoii6M7dK_98r0+pK5r(sQp)4+n zqMv@F*1UV+==*wpsz(4g#+ODk1u*mUq<|uiE^gQ5QpN)X3wc4z9{^8#jG0k|)EK>( z+vlhJ;%fw-7PzS{qiE< z1~3a?U^s_37mF-!uD2Wv8d>WP6oU%+luz64BdS7j(C~M0P64({<5w*_N_R zj=;2^G4KrsW2oj^8~&KqM^gjoOv7XQ#{&-)lePu@YNWagZ*gOyZgCI7ja(sFm^^%E zvlQSNKLu8m!r=U@NBOJQ5zP!NnBI{^^W!#))w2?gg*^p8(HVLG=i9Do;oLfWGTX&z zWo1+8MW0d~xS2|&6)Pe_ji!`0BR z{26PV`!79>B)8-un7`&&stU-BHnXqcu65g8F4Zc|SX!unof*pw%y`|vC^EkP-X3Ha zz9y(c<&%R6P*;fOoXj8wg1rwTX^Q4L$(rSgZwEz6gpMdmB4qvCuK9lTvZ`;fZ!-S( zW05KI&l3#^&@c5gQX+a(Sv@5M<|kBL%)BBFf(cg^kT64OV*wmdd9Vf9FyK$345xcz za7uE(-AQ0mTp<6U1-c`*?G%H&5ZY&Dy7yckkV=iG=4awjE}>UMsaGGH~zbcgr4L)+FKJzCNfCIq9?n^_w%~L=A_0VU2nFgPz+x zm~$h`V}_+a);<`{3b~oRlpQJ)T%q1peTUc>VNPsUl3ZUiH$^xA>n;mR8hSXr<|}WH&zY22Wz}Dv7PRrr zJ-I^6q$qX7addJxB%x5hX8*0B9BI)~Ya3Z-EwTO=aVO;M<(! zoS%C)vzHaAWjPO^;u}hM0I-~uo@l*3xJZO62HJ>p@}Py2Hp39dOx|aW8jbxx``|}n zy}A9&+HA{&eRm)*<5Xq(Gp6(e7Krn_x;;t3{%&`P+1K|mPCoZP6)9Z;>fGSG;8R{# zRd(VnVZpm|#G%KdL64e7KkNjm77LH=aW2v1PHXfca z58`Cf9Qs^*0-L8~17Wv_16o(y>^6t>tgr&k_2oKCg)Mpz;c|E+61X@?jgOO^{hGEe zTUaq3U0~_cg=3eJ+X6njTR9^8+t4RHdH+(1>CChM=H}q@bxDP+I*M#e!-I1eOme%S zbVa__zsmtylu<*_KyEsAHY(_kj7c%*Zs7YR;F~JE=8uLZ z?aD00{!~EqX0zE8arIf1x+3-1!_?F?P0W}yrAAkd+KR^Z^CvAoPvt@oDuX?OOxe1X zrO5M2&FfNK2j0-w)b?SK)5mN+97RIBe(iYavaF9n^3*WDPNl)1bY5|qHKg=h>K6hE z^vmk958K;qFbqOuSIb(dj@1xYaB&L#oZlMgoAWz3h$u}0BKIRY zP#!N);4Q+rSJ1s8`F4aUcQZ!3+lW3IK|Vc$qf9QO-;D=&iNWae~rsm;{#=qZtyl3c&YO@s0Xufb+ZQ%0e!zgVmurk3mhv~ZmVtr}(Hv@BJh!uy zsuJwLWu^Jsl4*VXUzx+5k(=nZv-Kz>Q>@+{nFAr<3CfA0hQl^Ft%?iqC& zS?^q2O@E?lHGuPbG^uvdV`YyYL_O&(k5_?yDmNu|qf-n^)jnMYE8%uMZTKqUmGRxx zhdRTCfhd`LoXxv$T8BoWTe2{HKAMye1=~r zLg^33vVlW=0n7)LHx+(r5=kw&W9G2H#+@GKoq4fpwBH+R0T=Fk)BFoCn7JiM3M^(CiIdroAiWYmc%I^>cn1GZo>5Qm|eZc%`9muRmb026Xi8tBF9=wL> zor27od900Y@~*g7*I07IvND_ef4H36mkLX@QvzSg3CU4pPWxhfJWMs*Rg zSQkAl2Ay%EV?@yi@~mULVPI;8MwWvM#XcBgR!#Rgk;M;}MdS-=6Nd;GSr2;$Mpp?T z-&!ri7Ou@^mmWXBOCdfl7yF_PmWq&d)t!JGzgPwN`7~5SVWL{lRi4xSN5W|>N<&pt+!O?t|2*iZTheIgn6rqVofb!TKPNBC>?~Gb+@t(jzYi79zLv2fL z{kI9;&ezPcLb;ZR;u-GWNa0Xq_7{m!q#eVa9>Hu4+R|-y=sKSf`>x~!28fVvQmL!- z1Clt3qq20}xEAZ)K^d>#s#I^PC5x5p{cz65f2NWnVp@oMb8{V2B2Mz1GcUX1wb!Qr z&N{I4&}Y4LEym-4efsL_VHM-16;db@LN6xPd8CGT&DA8yjZ4MvT#=;%qm6kLmL4+& zm|2zWGSttC!WL(NepdH)#z*~>;~!53Mi-vG)wRPUGBT>WE<_~`9bcvX#tw(Lrk{l! zSCK2Wh}~dI7B46zTFyo7#P_9Ij=z4$)@r0pzsMBkBdh6b{$)(KpoMod#TQR*7&zsS zo%SkAWbBb2O4Sxs%4Y28=Alqm@JUU=R$}H-?1kF8QgHGo2Z}B=#w7F*P>*DIc+RORNxy#0WAWE=j?g-PEMeuq>z06^+ zqL-PWVStreY~4K@0RntAD6hO6ZJ|+IL(4#Qtm-@zT0~9S4c3NCtqVI3i6YqA=t5=CkWIbqsfIPlz)C;2T+8(6O>JN|xI_ zQ(hwFFdS+Uhy1RvNnBWdgzY7_X4`fNzR}J;-?uI^5{z*oZo*ouyedU6jzrSh=+OtD zRbdyy&l`k+?#Ftp4d0EJ^8JcZYui6~Y>9P8GbSJPvZ9`D&{}KJD>f1?!UfY=izLt& z+$kcMb7Y=IU@+AO?EeKaD%gDGuCh+clDzAgrH2P};Ua;95DKc%0W7vn#zF9Xz3kVK z1sM;Fu!{wt5t~7-1rZ`_0;8l$McT88JN2=lYK@%+>#<&2ft4S!!e_)3;-NLnZ*Jl0 z4(gd_4-dvSgA=z3?ITO(nX+WI>Jggad2KP^&ofJ=bOtOnUlkmExIJ$`p)D}$R7ZUj z-9*!t+Cg12Ny4j(nK~dsdCwV@@5bUUC6rm8N&Bm_^~nXvB=}bBto@0uHIRPgQs#Bl zi@+6lrU?tZ2h2H_k9s@JFob&U>$=1euf63{vy5XfyFxV#MwB5dTm1a9eC-m zlgVJgxVR$Z$ivoRU(5`Ye1vJ9Kk2Nm$g|y#vujA$eg)nYi_t;t72HRZ;be4oHCI7b zIdXvIX4@7l1P1#mZ0KYD_t53UeK|0AoZc+1^;>hE=Fwz)*8n=9|h^zGG=N*s9)=x#O(%Zlu=)ZBCDLT~euztdH*91bbXyzyiBk zR~<2w8?EcCnu)M#uGK{ukt?+Dx33vE*FAz|La?TntT{z55!>tX8k0i{b!xZj(wD~5 z;$^5K*^Cnz8a{7!+~Q>5z2gL)kia`(2cQjTXwy{3QR8VZ7 z_Nq0{rJ4|xA6A;^O%Nn`?AR#WOlKdN3>sE^Se=o;k4YkX`MjFJI9i_(vR_;IlZeR( zLVOIUIW6F!^jlZ^)u=&IIn*qq@Q<04`nU!GY=LJv+Yi-t9fzdq_ZGz2@#E5nE;FbUp(D{alSwmAnvMPMu(0-1M-WSgNB9#_+}NMi4^8@Q zP6GfE8iCN^3RV^z&8YQmeT{P{K5+-OrnD3#ijci`dmt+2jHzr-9%C5dKU=YC>el7e zZ^ujFLM~{20^vvUwrQbLCwoCnciA13ZYP2YO_Zdvoqw7Q^?FW+dHNcvE zQyj^E(mjo3`O;^CRTHi%dk6W)a{pk(@Jwziax7Y(J}&6GpONWaty1WaTVhI~II)t152C%_ovsPa z(Z_o{{vBp-QHv!LjYWY{*IMkU?k_gts4yw}lOxe8wcF6xv?}}itf>aIWzzAnwL+Nh zN)PZW8^Q2$ZMc{v{+t3d1$Jd#n&L%)AtIKYlNft!^zFyftG&(UwXCr-pbGR`jM;My zD6m8FZZcR81aCk1ML{S%^KsQlfrmXSF=jzAvDWMh9D~71sh?his5l7RT@>nu(E)V` zhBHEt5CIfoVKwd)(mM-oh3d49=kq=aS3swaqU| zHvc%({=_DlRT`DxLoJJN@fSPv|5+9n)1Vr!b30S$AbwSB@3G01XoE?*g9=!){Hk2y zCBP))Byg|KDuM{gp$92?|XIn=|IQU1Mj0R!jJNPL}K8lX9kE7_h!@8?tA9 z<~Px>5&liRQ7ZYfR3B_e^mdLI(e*E-nPa`~)THGHH*#V88+}^e){$^fT3S z<$`P9IvdHbs#x+704%eN^w4aEV4j--hLR^D6h87HhseSY$AqxJq;S&PTgM(2S6X?o zX-e#!ryGjTL#-z|-47M~q;e0`bbXn(JHNk7@(yJwquW$Whk zB>lly?tVvVi58=$-e+xXTX4{!fLBpo5sjbJiHP>|WUnisR?UEEgh^hMVD4SxYWGJ& zjq|c#ERzUS<~ahYZT$4%$7Fa3Ib(}Xw%bMKitd3-huOJf6TwUL_dFTQ!DeGQIx$S~ zeI#&o6Yrb~@fkr~S87r+2^sLdI};XIZ2MVUWt4Hl2ZAW`r4Yjw{4xBy;f;O)rXs$g zQ;;9Wd{H|o+TGUbGIloZ}$RXCZt97MX(%x;-u%2q@Kx4j*;gnHts91uJc(?r+++L`xWn` zwm+57-IfncFKOK2qM-75)`Ky~Aq9vmyyI?fUv2+q>*By{C@wN|0+On$@5J0DuCtv6 zF!0_^*PZ@DX%%a=4`|+f{p?bRSi-S55!TDr0d=SOse)HQX$7mE0aE zf;OP0`+an&HG|()s8~5Waw1c}_@*F^R$M&S5dTCg;5UlOwhqkb{-WJbPJyuh4``gY z7T2+HP<$k5c_#|Csr{BOoTsudO}%H67xvx|{Aa&TiWf|+&CRw7Uj3X%JIEKdP2?1C zmPut+ZfFzR>|wrRKn~@KMMo`RGKTrI@E?BsuM<#P5ud#_tp2|F9F_k6Ui`s<69(y$8;U@8ywiXkQow|V z@Tv1rw&`C?KR0jlvNxZcW<2?hrYL54d5dkv)bnfHqMA6C*PxG3_~{5#j1oLV=N6zo z!YjANLp}OMfrrS{{}V4$GHwo`Q38@2x1+3G&ql@*kqeg`w5| z&jNUXD?PKMm0FK3S=`%xs%rbjC63cj{Oqu6i1mK(&!YF9P62s10&6RN54KXD?9cX> zkZ+A1w2Xy}YH(6W(@nZ2n2lyQD11pIHUA zrmfQ$NDL%QgN{LA1eNuW(uPI0j+ahv@hs5i9wXUBae-0WnUW9IH$yg_j>Onsu%Vj? zyubsvq!cKdcL?OYp&ZCuY&wLm6Pu6Nl8A0KMg#EXwK8XP(8~KrvLRP5ZxgOib6Dh? z)!J%T-suKhz$vT{<{4e z^^VV$SzJ?L3TIrN&Z-@*SSICeaa6@6*6ps5qR0Eo46X zLM<*Kw)|oXlk0mpG?QrCDn&3o`OY7N?5D&Y;S38rLuiDI2pnfyaQSkjyA(KwIKqKV z=#EwWUlU=S8o4OUDpwhB7*M4{^PB-jzJk7gFM}my?ui@*?%oGzqLvkb#)0zD==kAw z(pBVmcb^!c*Den17cr&T$wV6}s{>ylD%A#bCpiYPRF*Op75_57&=bkIzYA|X$I|*( zMFH-!&PV=li~b~BH&p+wsIFeor-YpW5L^nJ(_N^!dG*pT2YMoNFVGkCAeQN#3ScI1 zZ5$a`qwWb#D*n&@{9g@&I*i$(EEkRZrt_RR1DJ0@R+5z+3({SjD?H0T5F$%c=+?SA zd{R&aQU(Ee4Mm0#i5IC$ZHe==d#Ssh@gL8pv9a&A3)(!M7NH3{Y&ZjWJ6C-VUC^Ay z*&th&m+D{A!bGao5q-}Slu#F?3V|r;rs`gA{ANXp*Ym2491aE`{X+)55|XsOxFoZJ zHp(yVF&BANB}1hzqBma`B_bkJGcH@)Pt=xq5dd%ZRA^A3eI6fCo30NQQ~9k$L3WIS_XA**R1FoWow50FU#H)Z!)JNF?ddjxL2OI1Iwz z4zC?R#QNXbPtH1WJJv-Ph5ZX2N_EX}=$#zn86ijSc0nrjSM+xs&Igltx;3BFRqwP; zFo+pO&;rlu2^fNh62K1hdGv^U19DQzA2Z~Pf47-J@iWLX2PL9lIVZr8-s zL<{ndl!+xL1knd;i)$}^l&Fha%2OB}Mz`>LYCd+(R)NgR;q|z{HXtt0>kWl^G&yv* z+VI4(l)RGSs^Wdb9WFx(lss35m>10?DpuhrhkiyK(~QCG#q4-^=dyE+h;@IaLW?pV zNM%7)+P+WQoKn0sa)kFwTo4{{faLOao^Htr6&eq7n0FJj{@1KuGJ-`Trn?*b8G4*lqAV-;x*D_Y%Cva;+TWSGHy5TBIBGsN zR_FU7yI)|T<(_JJAwz3*Q;;U^FV=Mgyvx{3LWGL^R`(n(R!-c#PaHx?13uG}M+5ND ziNy9?PDI=mO6I11s$Tj08hm|w<tQ^ z_23xaMm8L#UWA@dsdvH@5C2zAM(mEWOyE}$a4Oyx*-)%Ha^7&Q3#WVz@>a`#ytJ2 za(kNkzLF5`v~a~-6Pw*0$71*xVEY#a*jVD&QSO4mv?<^cLa4 zyL_BK=pv)i9%~CLj=x#TJTUa>du7AFM6YFtgv>>Wfa}Y{CslVFyB50^x<}BD%Dn1& zQtAQ|7$arlDEX{J%%^ffKvyQe^fnXq7N@;buaK^Bi|nAc!ZL}Haz&Z*Ct4;aUY)w z+20<~OK9u}wvt3LC`v{pez8z>_YUjN*zF7A0v*UkA)Ui~5t7`bPM{egG$)q zr=XKJTmdshQ7S;9)Pb_Ergd+kWQHG%0_b`^uJHNy)hm~dYs?}e|2T%GT}9SAzUtph z_1bBcvbYciMaPt7H!jKt;)qzz?#Ef5d~x@8@=1fwabb&<1CX%AA9q%eXzi|9nDOEd zTf9lJnll=Ht4He}{dc_ds6qJH4AQ%!6{zJJcb4bv3w-;z0|Kl$?Zf-hajBBJ<);M# zU6ejg-`T|07Zf~yK%~%%sM!P&Lyj6B0om>PL0?6?_z+IJWt^l0vwjk z;s*+$D9(Gzy)b;JVpuOBF4eCNCQe+%+k>|-H>0OzjRyO!U}gn+sl72?Nl>t{tgf1@ zuiTBZVKCbfBA6Jo*>H z>oDcH9H_v?A1zHtgXe$hQ*T&6TiFjWq=wuX5gi+X?I0J!+Jyk1m_2SF8AmrgK?q=e zQ3E>F;0?vz8ZUCFk2huQhV1^d0?opC~+;aMPvIBvJ_^J&qi&3|t-*^jRvaiSKn zq{64m*%Snk2V4y3@%*rUDL4s%^EaU)LD+==p08=Z3O z+-fvc2j)!`_5FEDjHw)=a;T~%x8_c`a`?*qtoaa~{chIyan27VuT)ejAXoo}F*J}_0kCFGJ*rGc@aGcPsvGM54fU_g{{dJ*r@oY~ z>;9(3CVF~1NH3)av1jid6KBt!LrK>;*sx(e9((*Tl$4YhDMo=$HXV&~0+$smznX*b z`WdZ0#0)mr>(M}z?y>jj9xd4Hy?U0{#9gNCn)?RHU;Lcm53$XLsA3$%z8xLdv#T8! zYx;1aiDFK^bfi=A&+AD%5% zUh5=>`7m`-F19>19~(DJM{Z#pawd{yq@B<&vzAo$Z2rRA=z3JPqr+XHdGt$u=Ev@O zu=Lhe=VL(B&yP7Q58QJgN~Cu6YnBIX4cL6y;|FCMQ_Z^@HOWE7Fbo-L%s`a#!{_Yt zZpKrm=sv!ktecKCG8*1a3O~PREY0oqMnIHordVU;@}OrrmFtnrOpdO1F?Rlbq=0z9 z@PQ_koMhe!5H+Uq*$FHkvg1@_8wR2Rl!`K5tZ3K8Z1;Uw6}x#`upf`S9BB;t86v98~|=v!fsX`JX-biterRXe*>FKM}A0Iu0+t#zhIs zDgZ2z3)Pf30#UXP8I6bC=hPQc5-P-nBaCXE3Zez514PN?yyCXMHS^t9ai*fzEKX+? zrQoIK^Qi)qgWP~n;Vjt+2Z-{xfheBU(nEj4f;&I)~r!8k@x! zS28yRqQW+!r0SB8=ol-vyyEV2Z6Bg@3ijA$%e{3!=RQAdU&%24_FeXxnLych7>;qS z1n5;wQo8bh*G9<_863ZO@sa_bBmq@^uH3kM*SIA*%GOmDjqjJ1lwsQRX;{i~$`({| zN-|RDRV|Tr4iYH^CE!wISDvjzRHPch^c+zy;mjHcLUq768eJ@nqOaLwCF9=Lu}w2_ zKAZ<#8xd}FjW?UDiN@i5wfXMOF7yzHlC+p;m`gRqlBtfda;2{%N0W$hQW?tcu(G-G zA&Ej^P@rYxP)Ih`2t;`)*~7M{pyvj7kL)MKb+#~GLsw%9)$Cf(dXe7zPSg8cWea** zFCo-jgR-O`%905{1^Us&*h1q|*VvBwnT|pm+xI2fda7ajX5uC`dnTZXeMvwoX$A{K z&7L{~FTOmV5>YddOmHm4+PQQdGpOB#bL|Aa>#>(W)czA4ID2&f^Cy*IZb>O6h!W|9 zAOY!_>{pns>Pkk*O(6fc`9wgJ+Th3U_u#+&qZ>yqccXKlhrmETmdzQ!qNN^sIV-|L zD<{I2OdDBA-Rze|IHnS!eKHviycN&qC?wtUW_8VX`FyKR1M;z^#`Eic% ztDTkDcAx_O!7LzQ3fozD?iQ${dBbl}n0y{Dzwi`(`O*_;xQT#ZB}hV zvB$T%HJxf~(7RP~Meeiow%Z#4Q8G}jD6e@jASyz_2WH3efEG_bCJ-fpnsutST(JfR zJE`8%MHRMWYS*L?D00;2u3TxS%kx^=i)qE4?}Ip29Y-U-MVOd55ih?KhhM!KM^WPd z+S~ltyUR~ca0A$R*@J?lWXvc`!rv2wdhPGyXp@C%##|KA?-`Q07?$U}pWy>g(%JA&+Xb2a@mNI6ovwAen&V_uW-(qOXj>eCjD$+?U`NYJa^3wRU)}~W+jU49hFzMnUFt- zzMg&){mr!)VC-sYL1$w-`f7XsfA-#kv99V&7k+e(j(TsFEX$VU-i>Xl3)nz_&>;|* zB$Jz&%-s8ZGvEC=cjo5i&P*nRObRK~&sYcaV`Bqa z(mH$ZwO4&tfA;&n3(-1mxZ4QIjI@(usvEh>f!TmNVu`o{Xv$kNoX4u_efdQcxZ zUXF(&IL}kuc;KOAq-W7TWA`ZFUA?~R z(LsqiAnMP*AH@ItKYiFok*Xnbbe5z=amQ`r*tj`_&Fk{9acw>#X#+@13j$H(h!POR za#;N{TD99)rC6!1{^x3dD2*3>fo6<2*j8usbgeH~JO@On--~0;fGC26qZGH4h*51# zEna!$6|)k#)ybGUcJ9ElJoR(Kh7BkxF0wU@8~d!UJ9f8g&DWK}O;)+*(`yuyq2k`_ zb-b5J&w)F7n(X@$K_#%u-w7UcF**`LO9Rl{NRGRA&*F93^KH547+uH+2t*0^8gEAO z&>obeoW~0qiz?DCn0Vo#jzx@m-AI! z*tMq-yZ2CE%;$YLRyT@e#pG@wcfu2o6YO~^5yR1bG&FQ!_ot)$N*=~%bx9~75VfQ* z6+aOW^><<8yoj>h3y4ag{)`w$lr6PI4V}`&X3pLB#3(r(Xl+rZ59w4^?wy)92}DuI z&%mf*a+eHK4CwXW_v1f)-h;yz2Ds52!h)LXau2t!n1t@izUT6KFkg97?M(Q5lPNv zKkmZFXcx{V4B$ut0V|%iSHyHi30$8bU~`^omy^clk^8BLDTmqHyv?-opPoE|?2LXa zD$B?E+qYxw`i)pPKZLSUfxi;g4P&@x0)t)SICQ8Te|fJ4yZ5)^JP#vi9SURTx<$C_ z_Hx{F5BoLyb}IM!lR%Usin}UBW}o15#KJVASfv%;+_ls|BJAjG86|*GAoS8ZXzy$wcxo5T$fChfIQ|A&Rt8VfpSl?Ald}1IIG)VNEe# zP_#X9oS!(_kT-G^`QZkvTe%TyS8YV7qXy`>fEEJ3^({Trxj2e?a#&^a6s^a0tj3OQ z1fo_Fh+2LffT%0bVM=-D9!$^C}vh!S-) z*2Rr?UkjpriA>G`QD1_1(*|`D2OE+a?KJ^W3agfQ0~+IvUIa}`ldrj>>QTmBuL+1! z1g>r9UgieWuNU#$?~S5>YXj<^nxJk75OsxiV$Ftrl!wX9u{LbnelbrvVNOttqB(n} z10Q`{i(R`f;)_EaIMXTgGuP1h}P+|E!ewj6z{&5jDyXoC`e96 zWlPI(cgd`Gk4Bis^4TXxOxH^9yKu+iQDf4_74Q6_sbsej5arq)3uLraIW(Rd=L1FV1W1beLGK->Lodb0 zdb)d2S674c)#vR*yqfA-Dj}~kV5+^d-9+n>l9MQYS8leVq5|a=m8d8$H%_Rcd4=9_ z!xYmqdN7?>UZx?YE#9?&r&V62nD}S+GB_3n@A>|6X}RD^YqDQBSMMr!C9CYnXgGIC zIQN;dW&Q(U6i$7<&j+G9ItWBjPn1OS7M4p#lm|owH^7&~?GhIql@tB5or;-8K$J9~ zjZ>sbO3@Q|id~4JbQ9e?jG(m@W9=P4XFpH8BWF_!l`J=RqWNMqE;d$UEb0NhJW>Fu zR4krI&ZY?h)JkqNb-vk1qz{S7y*Nc3QTv8lc!)q0i;^kAMlQ;e!#OxVltT`xc}R#B z5eOsA4AW(QW}i<_Y2&GR=TSoaHb#^Qlc0;2x-yJ7t6&xi0? z4Ru_RZcDO4*l|w;_iRn1&MMD(qIm<%Gsk9*0Ui*Q%6K_O_?4jX$daP#Y|YgIQRaK-FY{D`p#940;4W#=qW*+Jz#Vqr4;jzaL$olvLq_v z*U673kGGMFuN5EfPQhEBW#N1`=MjpMr=bf)V>QSRb)dMg62(OoC_oGH5}MJ~-b$|0 zHq`b-aV{D`dO;zcBoMW8yAMP;jwt1Wc`%MB<;5O&iCr&KkoZ?qixVi>-0k(Gfa^nQ z?;11afT-(9-CIAdSpBo^RsUZZN0jT|?t1H!>bm4`4v4xgWDG>&CJr_vHRdY{=rDmWFZkcGo!|>RZ|nSZvn@w1LzFbwhxtE0EVV zuN*IQ)kq*a?r&t(y=|=E7@-ZsiQ_GJn<59F?ykkD)1A239>w+zJbHceMuIzuxcwgL zg{kkr!NX1X;gFqf7}o^*gl_AdwR7 zy4rfP)dZocs;PjSr{W2ilAfqA=bjYmc$znlN6(X^r=pzTQ$+MahenrW&EEwYs2G_l; zl61)m%5+9|0Qt;>d`BM=R{YN76ak{M>=Q`-G2Vn7d zIwm0;it~;0;Db?eN~I>&AtUW`6y&#|qI40KR#af~ovUeA*@ixeoOm5g6KJX*$KEe4 z;*EDsWB-W`^hYxpe>Q=rVr<`1g0&kWSWlZojL74NQpr6Uczsp(*87Zps{cO-i2B(O z_V_^5N}fpe$j&6(dv64bE2${DoTA8)0ka9(@iRW1rkM~sHIFW8kBZt$iZ`<}R|KL6 zMp|3tc;QU2jb6^pz5B9P*C*r4=-f4DX-#_c$WgQJfABuufA4+M`Buh*2Lwbt`q-l; zqL-SQN_}?}&Gg4Wm1Vl}eAzrt8$P~{CP`}E^%xuCr;R`!XajZO>Rv5t%;&TV6KE5+ zSSyu}%YM8Ic=P=*j+`Gs9l>Tqd$BCB2lJAK$uXLZwA5@YD@(wVg$zS5zv^fe>N@*S zKNdj-#hAZC(Y)={5mmX098mdVpd>lQjz|E&8tAnL}~-W(8hy=m+w4o*61%wHCWiY*}AqMrG6ZnMq0oABIq zw&B06{vEyD)on0mC7LJVxwhd5$u=@)zFrh?ZNPv4PEt1yi1IgTKKZB##K0)EF*P$S zv_}c@96o#zuf1`S98uL2$7BvjVLHYbF{P2ZDy!azuK{DeNycFgN+HqV-?8o#r5gbaOSfIeDi81;gr%$(2AP_ZS zK$P^|$OuBBXr6RLF`u%pzcN74ygqz>o+puU@t+eJ#O;fLP3y?Db>DpKpq=1m01;Yo zUx{~wTpE`JqWttP8Sk#t5B>K>VSf{LEkKmoipC0C%=+WEYdLY@n6Yy$kYpAHc24_#7WBr~r@taz5MfDF*p))}x0VWIPFR;_^ zDi>E8M}$ty5?54yLB5IM2~0C!AV@EbS^nIn{JFg7-WgZkU^y7kRO6nf8v_Gwjy~=> zH4-)jpFX-;Fvc4Q&Q{_*D>+%cbJn?$jMkp{YKk#`fyi{L_|)eIdV4PgqRJ~s*DOB{ z7m%A7wnL@mjCT^A2ZyOA$cO_p(ZtAV+ zZ+Fq5n*u~#1Z34K)FuX#7o#WbZuEuJD{@K_h-z*a$A#)~o|e~uH{UykBWF9=Mhhv@SBU%XEaE1;5Gz(k zuyRczA_AgVW=AR2kVh%irB`!o?$*Zs_`4AUqCTsMl139)ofpP44=3XRa&(rJC8D&9 zV*$q)gmsvK7h}Rigz@oIO#xDVJE4Qu5MtE3`kUDTQL!}Rl9WU%_WAR>7 z?q(4v*kKgRtI}8mdUVrE%rXAPnvhp+d!;zl*=fXOr?zF>a|AA>=1z9kt|;F6%Lw)! z>cQ~~JXw+=%d6NM0O6%Ub9nrmO6iUV@=ZQ{xj1x7Qhe4IOfcar-1btHW0OU^_e*!>c-RjR!SjO z|Ezn}{~Slujjf$IAnJP4*G(LpFw~fD1Q2z#SyuW%V}q(&kOg1N-Cvdhj*jj+2Si<# zT;J%It_=vJ&;)hEfG9VPh?-NoF(2i?UoB?sj``q_dyj7?2l4JFAJ@M*_fA}jm0II z`2LF#Jom#SE~u3%Mf3OtIijz~O4+i(4Riv*A&U5rAZ8Qzbr|DPAns>S984i98t2tB z01pMM}BxA*)#ghhDmqj zAjHLgf?2_1zL^l$4s$2Mn9eg}dqICc$h)b=`M0*fka`y9nYfku$%WL_-A3C^ z@NOPC$tsXeCGRmK&rHB{Ju!b06Ov@9$FakFNStzjz)Jrh2FcYlOgm04r!m^vCW=p9 ztVIGv@zOfG5v4d@Z}%X^2pD8UyOBmNCub50OA#tsfG|%n471+46Uxvyz81CJDY$Uq z2%6ezkY2P9sq+?M>8gC%Jn9syV|*tGHjS{(^D!_`jD3eIu>W*1>RbEJ(apX_<>h9n zbB?S=)EjjH*`d8C%4x*%@_ejbUW_eU*WjLQtC2*mk_c@>?KsY!93^LE4c_`-KTcif zKyGFk<};7?ZYjdHt%WEj2UB?kbyy{7L=liJD zD*{pEinG4q70AnjKM)1`$R+(^Hkr6ezmAU6dDooP!?xSY_V)T~uj4gZ0oUT7)IkJK zKJg^EP`BFnP+a2aic+~;zTI`YxW6hlk@$*0lsqZlex|Hi{0DYLy=3cSf1^r%!l?9@ zgp)@n@cHgB?AuS#)x#Ii+R}!y$QTL|Er7+e{>~*>N3N%fXD>_vqEhn<$icfBn>H`T z+Kq`=O%YVh%L2HRtXjAwuc&lGYt6$Pb?@Ks)ttGx6mavJ>SPXxy18|6Gg6P${~QqY zm5_f9h`Qcnc5?|Q8#U&e2}G%AZUN*bId{F@#r`J8=V<7zb3oKLxwbD~HrEEU(7$0o zlp8~WS(#i1``cmmZRNpV$ws-_6=zX|6Q?$WeN>>@)i;XIKkvq?f8-JB`>N5|d5~gt zjd=Qrhw;>74`IQgFcwh6V9)30@#-7Lap>SEYU_(AN|TS$^h_!=&)_lbDR}w^$pnn3 zQ-eT;Hk>H}C7rCT`a}i3`(z~&lDmZJ3^jd~$U=a*89X)%^BUyfzV zmc_WBvUtL07C|T#TUn9f^HG8%GN$~VX{xPT{scn#^mBQ1R|~)&S0-IAG1E9*;wLWt zOWsf8V0n`};}2G^YhTj@F(+k56un%w{8p~kU}3b8@1?k$Y~MgTEy0#ti8odtl_ITE z3?r8KkLhir5i3wu|Qw>FGue z6_k(hc)Lz2P#&8IAvbXd8DWCIzR6pC8*KQJY}y4_uN}ZJv)h{6}3u5q;*bXgNz4Udo(7E{95VdiDbPT$KHN*2)})K5J&3< zdFtN~R+ohEw?E3o<4+Sj&7h)aS^?tY0>%9pO^A3x@}Gc@k_8>~0qcoT2D{ss;mK7^AePf{ee1P?v< z5D$siigjz(Q4iP>ZwzD@85fVcn&VCQQEsjVh?=4!N_C^W@<&x8#pNSX-cOqp&ZKy0 z1{$lwIDY~-@I@m&`t%s;&eu~XR1`TAZtenBZ`pv=+ipYS*}5q}R8npM)~s2D_3IX6 zGxe8kzB^*vd*V)3dip@5u4G16wL_~L|6Z54HbbX5a}y|_{v)gUm;<72LIvF9BxChI z2Sj}(H8BT7U2igLa*^RgqsBZ3M0w=+I{&I3W!!ZRi26F$=9kO6YXjOa-7p|ZS#;xw z?%m>5_cVTMw5zRK>A&Eez*anDDi_{(b}*mtlQr)sOv zGuVNWtYj=*kb&=guM*EbU&*~Hk7lP8myQ%88#k0~G6Nh@4py)Qq^PCEzhy$Vp799i zKTLD+{i(zb?3oQmltkL3C(4ZzwwSewnjAx7d13ORhWv_SNq!CFb9wc%r*>z4=&y(1 zM7OwcD1z77(TPTa7#A*7QxvZj4ZLq6pwUawF^SuV!znj67i9~|P+smSA78j=A?8a5 z6oCu9mmU~#K#8s<>c@O2E#)kpBg!_}R_`7WU4L*?bQ`H)nccf!nPYC#-300kHp;0TrUcTuksb$0bPx1*(nO6A*nkTKAQOxlL-1~k%+ z4)S!!p>c#MUKUQwKr)q~XO?Cny)ezv(NDqh)hJl8n(s2Hh&+O(-VB_q&%wdd0|c25 z;`rI~RJ6PRB?Sw}tx<%{cNDST4d8*>lUSY!6e~^|myGu`tKUn2sN#8e@x>SM z*kg}j9`9wXzj@;&Kww_0{1%n_48wBtZPDPVhZLZCL@(&WSVs9Et-$wic+*( zY(@2{YSec{$$^-GP*xGvt**qn^$T#%mI&_NCUIGPs$pwp7Gy2Q%8r)}yPBK*c=dFd z63xB(iYTD|BWv>*!H7B0yswDxw@5Ov`kw=$zLFZ51EQ`snf(bxbDtXX6@e(~Rf$bX z%8Mo`h4p?c4mn@zq^~>#!(VGW7Rk5t$I;MTwUE=jHm6$9wY0RLfgA}^6fE58&Lnep+MASh+xfzOBOa-ubc?FS#8!*70f6#I^jpr*T!dd3T| zwloiGS7hUnN0RXHW8BPXGfliFOxYr8zVH^*Okaz63fIv(kcoK`5an}3sTdOsGcK+u zeu17e%BTluk>3V~_K#uLN8|X6U!wOOJ%zgVHWZV)V{vH?^IM4@{$Mc^r`U}+L9~J8 z0)g7gnGVNKaX|UT%5PD7Ts%tSW&lwFqtsSpZ87UtjB7u}k)X|?{E$m#l&1$uX}c7H zCq+DwI4hFM!r}@H(b4PD165y71>|+L1fOcCkLLo;oue2Y?Zu0Y1UZH&3Nl8Hmt2b4 z<)EUXg0>P%$=R@U=~B}PRY+YXnOOuaLP|&Cr2?Lqwl=5I^QF8B2cRMK^b<2dAj*}+ zy>xR+{MFtE;&A?FysBYegRx*tCm8%n98pR}SqoZ)Q5-f0^LLEnz3N6{HZnTRZm6%9 z;&c>Yqd1d9nsRtzR`EgtQNCziBI%mSdQ9eK-^CrRu1B=Gj^JTG+IpzZi;Bmi4b|x3 z$y<$`6X@(3!~BT>l+yN&bf72Nf!@&&uLL%e(ovX^jl9x%NWZNTsVf#(Ui4G6cnRh$ zUP_%yNc#ySe}ZX{uEM|mn<2P%^b zuqY)D`CQlK=VVZ1IYP10M2fHWqPeXL^@9=Aj1^)$eIC}W5T_vf*u6>EPDT1sl{l`= zEE5cgGs@+WS+^-6&@`3pua2HdZO+U@0h^cI+|Bx%1EOZ4)Hl;TR{!d|v~xP5Zfrfz z0a4eRzM30lIN_)HT*<38A-+BtSSiqG~&sT-;ryZ5)^OjA8_aR#M%9eCk;+wsEpwgwt;E5M_@ zt=;swT&THVizA(aCwFm22?)>1&LXEvjwvG7>30hjEI{dkQp_*mSA1@i^YZdcPn3W% z(Lrelgc2BK98nU(bMzAtd|K$%jKcVN)^n^pMr+TDE33O+5{Kt)=HDyT&kP|g81p+B zTrH1HB<5djVP@mEUgIv5PBa5YR5t_x4Xoom|LuODZwQ05JzcHTwbX(f>W7)PU=h+t z*Mt!Qrh~M6k3Nc|j*(M`cDSw?L$%H5>!Q9Vx(`qx_;7m*Mf}Lw)<25=!BOOMrz+?t zl+L`;j;5s1Qfw$am*8OmGRSq4v9biI6$REG1;}O)1k0f4WrUk!0gH`|Jfz_GDD~WQ zQ2Fv%96C{tl;ljLGM=4VOR(eK`B=P^O1>$Uo5nFf^?CN}1pe!#3H<5Z5nSkLrQWJG zABbW)W&}csvKjzPv2K-B*ymAFJEHW4zkY?D4$ns zioG9w^idSg4**eYB$sb#SDWIs`*ZzLF<3ujnboERLdhEF%zEsg4l$>+DiKk5nu-i~nGB;5 zfPI(#CxIx9uWT#B6!)g>Z*9XsOFKE7#&G&r0*;<;!;$K0D(>&5lKymLr(|Jy#X>Bv zETfn#b+wHQpstDSvGF3B22#-(svt+=0<2nEgtcq(ao>GB(eXY9L@~F_7pFiEh*BPv zb=ttN=|4{`Q=m8u;03drxt|+K0rekQYvUYK=YXgiO72@O@>u<|?&pB08(%$hK-Bf7 zv71LYgQziI4-|VD)I0B;#ee-;KvX|!y0~FY&d0s0%W&7GVr=D? z-L3qxt2D)R#WR;^DK5l~q>NWOyQQ1BKlH^}n;uT!zNI5Y^8`f6zqb3@&JNRAmK%5K zi>j;UX85Fls9L=H$swGoZb4>pE*2CP;72c1;%|OXK~WNNV^Ob+iS&5;S8k3N-}q#? zr7tR|GfHV+vSFF@Zh4tf2)X$0RmX1gbwwa*<3>FDy=U>j0}qg+iAU2%JRnMAMR3FB z+K+1wHkN4j?VDIV(n;^SsfS1$3$o{{&!hT0Pd}t$VF6M7{rv`1C6bFtTnvQ-B$g~$ zg2js$oBpTD%1WMoC(*ndiq@ndne9;&)N2FYuh#-6WAl6(#A3zOscfcXSO63^ ztJ=V;vnd`{3AxuMcsk)2`unIzd!Pv;v^f-WoHwrwsam-9c2MN54ZT&(7^rRI#4r-pXHY`}LEWRH_+oz-_Ut;3gC`o0 zOpr=k9QWU|5ch3cgjK83uyjcxGO`GEu{@_wkK@$jNrp5#Y#89>INgWMj+Sxw!j|`8<_vz5!9v4W-%$ z0#O3|C^<&j6Fy>jWRIPQ;@GiKeD-N4KK--}4IM*PN9$$-MEPTm1)Qw*S>H*Q(l7t> zmpFJ(KvX+Qic6*iqFkSH3AldZ`h|198CSJs{R#0?zQlrC#PahFPhjWhm(@oj&H-ZyKch> z{SVU~J6DCzPoG9xe>x&5>&Riu)AAPQW97=+01(A-LpUhQ6Jop8Rpd7lHxTJ#PkbBk z=1kAKm6TyGS7JZrxyzTNfScc}jdM(&1ERhpLBD3fWA(53oOX^Q>c&>!*A9qslX^T^ z;sfEj2p_HuxvOm+ zS+~=P=IK-_iM>eo$`sK&*Dit-xdHVXjDGI^`cuHQ0WE7aLEQ`>N~N*|s@jhOqO>t& ze$4Rl$;Tr+4QUvA4scT_E)42iT2(NBHI);1_@QNZgf@|)G-1lQy#4kW{OaXHIB={V z4SgBNrU=i2n-+1=&5h$-5n7&_$B1R)fhaFQ{c2mO^h3U1ExJ9cx29vtvgfV7JrGJj zl&7@3xgMygCJ?o!9a)tkf}%Y9h@yEvAXk(?sBlDdXTjYfevD!kv3|t# zv~V!?Eu~7sG%p$REFa$M*l#QjFO1w($5#tPZ8RY2d$|8WABdv(hT4j2FD?)6*+}IQ zSK7)a{{{vJj3c4Hub)6izlqA6I&}(X&YVFl#qo6HdS_>+EsUkNMIyij;>IBdgSek0 zekbk)aYIQtc?!j~Qd5(S!^F!&pzuuB+Ho*5dL2)TKoEPUa6Zx9)fGioS5~_Q!v;Og zm9)oI002M$Nkl0vkrqDbx0!^l$DZ!q$ok!?k+^B8>zqgA_f{-F*YRNX$aBY0gUwa zW0WG6VoL`oKX}V z)jCGt+Q)zW*z`pSjFOJIRjXFBPS+ck=l%EZH1OJV#;K>+zsA}xNmN(B_-I@e#@>sH z@s9D&&a-pZb<&Dw*ApyPyI_J8Qygb!nP_fA^Zw&#p>2;AqcgG`P2CadhiXH0YZs1d z9A+DPaLb+8x$RCK<=DYa*G{nYGP>ML=~%l zttV-}G9XH{aYNSEfKJydi?iy0xW~Mmf z{Y`mxvjmHw^kxl2DKbB-n|Bq@HRWYW#=M8?70)zLe`B3oyK&d)fv84`#zc91cX|wn zlCCIMhtm@0@=bl(Aajm4mjbR0Xi@x?0#R;U2^8O&kA2zp9L)Axq~7G+@FbKv(!$wtWk8hY(|h&+Epb16bA-ecEbU-bQ2i9}!8D{(|!0z{GX$l6LUUM42Dm=&eC;a1!lCzMVj^*mj; zZ~^so^|(l}kJ{QgazpV;J-MKIc-*=+h~jFJ701)cl`HI+b#Z4D(@J4-0lCQ1($dV@ ziER{f5)Gt4n>Vo{+l|t-#CQtbPb1WsJv=ypj`Qcu zj(4;o)YD0BsD4cJQXG$)*YVzVjP>ypyb+24@zlHUSPu`M>%jmwz`ao_ogWROdz50F znb}yrcp=Iv7h-flC2a-LveJ;Aor)CdVoFV?B6*7ZjZxnV!|Dp@;d`MkQ$Lp!9D#~ypxc`pjxbL3jSiPP=)M^4zxdPKC zaE2UFmjY2aEO;(SM=mG>bJ*vpDBO0_Y*Xsu1*v@~$?nIRG8?DQjpC#IL#S=1 z2rW5n<`L+6YG)Ge-;sjV%hRxu)($ujfKGy{jR=_1shZ+G8yV$EV`GVS(qJOf`26!W zeDQfZPxKrjmlu^ncM@)*;++i()A2w4v5=>F<{1zbjsv1J3Xw|8wRBAd8sX&{L9jtg zbMJ}f{R;aJ?5AGHW^%yI!{5C4H+bUlC#HzzO$q8XtSL@6%tIDx&NeMT|JkH{5u!F0@(m6hR{XP&{+&pd4$z5>5v{hM)pWyX@4B&Lm7 zEXVXlbCawB$;u!5Eq{YR)C9rc@e6ertEofNk>h9}sD#4hNLsc9?OjP!T3&|}XPWQ@ zPq92t(0Cg;!|uLwBeGLRsB>+ET!iF^I&gwI%%bQY%13%?G28e8tXorz9c=UW(u$Ky zA7M0CC1@a0CS;T)mpyafW8AaePne_cK|vT!-sa4WrGT5G)z;^Ls2fY`TQT-n{cGN* z{mOwT5k+Ifx5V61K$Kg^UXJ#zfjGZ5P-w7-8?Y6JTVPul)oP$(T{!u3VS{l7-E}`J zqnSdHJQFqj&(L=ka1a8pUq9qHom zOuRq2D#MIJHX&lRiz;c_E&?Ba+=Bo5-C67-5S5*ph=nC-_|fx=@dI*2MN%fn#l@Vs zmADEj5K7k>i~&(X5`tcW_byy8oBn&1=n{^o#wG)ZUVZIVa*_RtCwjG^th5XQqMo6S zsGSe&qgNe?)Deu*AqW@w)m~p@ z?ewa&6yty@DBw}yt5;*gZ5vQgQGvq3B2WJl4@eLQ<&mR^ zV4kL(8?Hnvi$)RX-@Cea)IX-soql76UZm(vSf0r36s7*0C`BSi2gp%EAgaBp4sBJn7;fZ-wz(GLRA4-z zgWY&4-q-}esEJ`j#>g=-7U4#InBtM-USd7;lXIzeB7#1GE~(iC6m46H$`vaxR#Azu z@(Su{BbQHvSP!|L#O*`8(lg4Bzc{vhvd@o(c=}$rhu}>rPqoZKM^hrIPmkdsMf3jh z{&{?Kq>h0GC{Z_v2k%^s`?szp5S4+YYske#AWCig>=^=4zl`D!?+)|80xByv9Z^}# zKsLiNBc}A5G?*CSGp_=olqaU0#k5y0$idP@xu|PSz~1U{et;8|C$OX-gl8U3!~^#e zI9-^C%0-Hcn{&}q9a;55abGIcBE3clL?u!&JVi$deubItu3hyM8>_?7qvJSoIuXsi z5hk02jSDmI-~TZW&pe-FAYq6!@)VT|)KVR5#PWbBLcJdC^y^paq{G$UIc4Sh_wU2S z<|YDBMLhK3hf{$lMaQB|G4an+UVb$XMsFqMmtP>%Bu7-(bVcd3%`ZOxoT8O);qc+Z zCia__o`&b2dmhg{_nZOT`BYji(OxrOWw|b?H?OB(N^IrKiR7u?H4mvRdc2Ju5T&+4 zPFev`H4SE)&sL%N%sHf%uSD*~ZD?%|L)52W(+Q6BKIv>fZ#mhv=7>QJl-- zd$nR$XL6qdqGHs!p*QL;ZcfyAJI4`qL&<&1MINhvf3BSaqHb&z-7-K_Y@(c|ylz0S z^#liT4eqhQ+{S4Sh_X0>gS_JM2lna0SWJ4XLhlFbA7uyaM$U9DDTv~InlgtZaYxPTpO^y&PnRJi01iY zRE%=*V_58kf1}kXjT>*YryCpLhBQjc`%yZ4^2sP(e{%%;jvjn1!5{T+We>4q?sF&t%pReSxY=~AL3>xOl}}4Snlr*p}Q^2uklUz&zDc)lM^i- zM^sTJo_}I7o_nei*?A#k=L=Br>%o91MmkF%YC7*eNxd8f=8SkC>SDu1DuZsM*yC$> z`PVO-m|Vr83T)c68Bad-1n%2$pD7zpzaB?IG#a(=om5(VzN*^5 zCjn5hI*GHpyPINq{X8vi*f^(F5U5yAJFlpSC!X=-Gjb~|TC@<_9HysdAT^DfA?l`* zvU34k0-#2<;iQfeflzYSRrBbSc_3It@omx7+2yWQOs}j#ZC%n& z6ZAjby~~H*>E52bduzVD)%lK5(ncnvcFL>M2c@Y##DDkQVKsJKIE|l$nO&>@>6w zgwfFBJK-4fnD79G?mfT-Rmoh9=;I5@#=JRN2xz6DFd6AX5#ODoQWr%PG^=_SK=yU?RwT*hk2Y(mvTf+*VGvB zie}b8loImm=!%hl1s>cO6ucUMNBRv74pQgbfQjho^t`>F?KSR99hM-a<&Ql4FqSP} zPP@!FqheLa@+rP45J|UKxn8`HbTtI@o7By3pU;i9Xs$;XI^rJg?sMnzX#y6Oc|g?XdkI9<^r5pijm(O9Shi>p)~uRO z(f4FL^axK*)t?VUi91+hQY_o?W#Y4qH;#UMR!i2uGjl+cqr{E9s!h9gJqJYHSX$qT zvB&EFW&u$eC%#4ImH?t`LeYd~!|vp$tI5r6`ZXBqy%z5yBO~T6u?8)yZSl>8zY_y- z^`}juDP!bmLQ#rMDK2N+qC7Fouh(3ldy7slZ8bufpqmRf(=`~zCJvQ{@!V=alq=Uv z<(PB7lmf19-PN^8iPWh5Y11gq1)W+Yy--=1S*E*XijDyLKm@-iBYa%k-?G6buJm8a zN3{WK2OKK2K$$fVrBcV&`{a=4(Io!;C6rRR_nqSgzi~!iU z01{$cvcr9040I>*^rnmW*)NXaqod8pNKHX$Q5K$lUkBc=+`C}?Au zn0n*wn^jqp?gFBMB-X1KIpxh9lm^SAGSNEGyvBw`>+7$*{u+M$U%y6AcMld@V^>wuMICSVR_3Io&9YyiPnJ`Gb zLP}F}n>d`L2WsoqZM0hnLKT`a{G99@o_a`~K~zE>Vwz5Wi_%fM6ab|$NmlcnPV&=u z72~LJBncA3xn1rWprv{9>w%P-LRj0JI=}Af;+-zdtMTK)&vcDt!MkB|BvQkB#m)6Z zlw5ej1frCD*f{sd=)`q_omfaeY_^E7PbAWMjg0M-AkrNyP}c}T z-2_lbQyxi&34vAA{lrBE=^Msih&pBx)6o@4MM+8m=JTkx$dYm-(H1N!#k@tuJS;#U z$p8~%e@UY*rnDTN6N;HIWir&6#JY?!|72V=qaK*Ze9JoH^sPyRE+L#k?v@19UKqvk zqdoZO!y4?_SBF-L3AXjM;d|RR;;Dx=VL7=Y7cLJGh~gZ^LRVFd<5#~L#2?=tz$nAiqS629LJ_*33&2}M2Z8G z`zj+sktVIRJUS~17LQSl&{B^U~I%!|0^ z?t5_eU3cN`d+xzKTkf$_H?420?z{@L_^x|~gAt0BQ;c#w9dYGmot{_KyR7G?U!D2t z&0s99`YM681RfeNP7X)e5XHg6+37e_-H#7GXvD5PO*nY64d;1UmE|Fd zMTaQPdLEzcIgXl|0d!Mgd15#p6${F+VrdD%*AzVVxC5e?GXLHFL?p8;@iN7z3WDY2 z{TvWAg+gE1gX=5SPdGk0jwtDE%;$j-xjc|YAD!JA-#$7qch)byvRuw3bfYK`tAEzL z)=OU*N0i0}8F%%bzVW{|4Tw@jTc`C0UYpST3W(kF+4&h57=Ubbb+svO)qNUI0@BxD z>B^9z)(CefT5wx5jK8(5)x;>IcSB#XbquzQ{N(e5A=wIk!KmO@WjoG#$}HfeeN6+4 zCJ=vuo;46R9xa*gQ>RT1m)q%TS4v3PDsH`jxh>Gcma)U~6ks%5? z_iq(7zutva8*uHwfGBQiXLV}cbj6Qv2l4IXk}!TAVq+(TQV2ec(f0K5q%~RrQSZDH z#X%lJUDaBP;*23Y_qe{)7NN2%4HeX}($h=-y};{l)ZnGxoW|j*PKxG@V^vue#a>q6 z+2_i6+7{J`Cu_4xa7DmBcPkzc#@oP?J*b|7j+V`Ur&zXvbmn`jYv%uQKvY*}7b+_%v6(>BQ%^m~4flOqxQNS( z8z4s;zs(Gi>!7c%&lHf`DR|_3YG|lOeM5tRPXeH{(AAtFCFJFc%2B$Y6cWReV&vuA z2rXT7o;`q>m^bxa4t`iOWZzp*Kd6yM$nrfG_W(jpx^B9^8>DpRxg(1W9pK z_kLNY_zlJvyqBk-|I4NA!Ug>+ymQyRZ~Q5j_2yo)?#N-|L=#CEkHd&zJ#jrR64$2_ zg!Zsm4OKUo9q#O5o9v?)9=V)`qtsE{hK}l!=xw-wBm%a{wCPC`RI1NY^rGCX3=!y} zcw9;nMcT5nF|;5XVEkzRbv&Gg=V z1W$XK(Aax121KnS5VdG|7+D0O*tKzvK-5bw4U!`&2t-Lo6m1OjVw)BS#Sy@xKl2zO z_!gpQokaI!xw)6vEr?5%=Y(*_%0xW#q&T8TuOxDX(S}(DaY2gujDc2sYSIxE{Ntw6Smc{d^to+3n@%UqpPwI$L#41$K@Y&57LFd`rU+tRhs?zbA zJ!#>8=r!URDc$#bjKH1%ZL#L=Csx6Am%NA1{y7E#W>cSAZdb9X3paA8i^Eplz;VFVpPd?65 zbM?ohVsng_6-(OtnJkf-sG4%jSQh0NbFtgNqgRH>*K>E*fdZ~g>Z&%V^+P*P0Ij`H zV<*+-^P|ul5Op00eG5mSy0`k*JViSPMBUiRx+y@E>*zM{vXY%KcdcXmMj&_hCAz(> zohOyFQtMFQg>!cycx*y^fOkH*2kW6xN z3KlP2M!Ou_?zzjXA=@?!u;KZ$fek`aW(Es>`5(VHRt7Gp#M-P4$VXHF`SYLu+(a?{ z>7V{zJpcUjwt)zX9YA3w$zYR<(SnnfT`!;FRlg0E>#76Id5qP8tBcD4QE3@z21M!9 zyg4B1o7Z@(UvqqsnKcllvCa!Rl`!#c!LeYfPkXWjxW)!QG6k2k5%=6^Ya2sL+cx2-mX0#pP z>0-tSAw3#N7##|8!ymG*(Esb_NATW(Mx+r0E6Gj8BU@JEp{=V>xhfGAs|Z9TtMDwa z(x1>qbCO{G5bh{Op08yRf9$CbX8RCd~Ryv|~?wpdI(spe| zqIMTAUW87;(ZYEk(j`_Ph`lWV7OnqQV- zOx#Z7#L;*pqqH=i2$*t4Ae6YHL{MZckmWb}4%;oLBe(?|R9>H95gXU)|6RErC}bul1n)!Ix{8W6>JNPu%y zWB4V3s8@nO6w3l`t|vL5T#CFZdF`$f$B>vp@QD2vQQC0=Q{s>!2iW3#p18R-8P7kR zj0XusIU}7{Dl@CVj5sIB`^CB&r;aGrAyI6J9*Se_*S|hY5!k~xUkx<$W}qN#9>=GJ zxMNcxzVm1j?%qBb@3cUa9b_Qj%ra~jKUtTZtG>SR`WyJqU;L+uuZcrK2L!zE!V7rx z(MM+nqDUe)USCZ@ZVYvPgJW0lUhkb>=kA_e*x=RPvEZ7soPWL77$VL|8y7gncTr4O z>*NFb58#h~{1Z7;KeX{g@Bi-a{tkct_kVBTxWs_JtgfhFeuMYQm&>EO2AaEG(}=1f zuCH&*pOd|J{x937ov=E^(Snk8B!*dymDGI5sKyzGL>1LOkDuryM{ylK-qnV~r-xA2 zF@f8bF2wrPWzzsrBk1VKW7q=f3oN4ebOD}yEE!KfAt1_2##)~q^z7%=F20++Q2ofG zGs>b09&pob;L-CLjKhVUyIvCoT-_+J?$!Pr5LH8k{{0k{7Z8<~pEt)5bxjohdIVD4 zTm5Uiq@4qzZfw2XbRf!#XJajYIH0;oTa93xlZ+iR%Uza0r8B3`@Ce_1wtyex;!t`r zmM>qy#s3c6apxVTBST^g%}vc{BJ1?=zRL`2}PH6%cON zu%2I^wb`_Es7;z1(AdyL?$0hN zD-YxK_mXj>ZWw(7omiSXiXT0fL%mPg6e&sJ>1wH{xiC)s7UOvL-CF#KdZJEW?BbG~ zV`60%e){(-@YJ)5$UVw^D#dIfi4+rKd)Ee0e@@Imc?lZP$DLFrP9mK^X53KX@*p5Z zC+k1qgeXBS>2&cFn~x4rUkMmFtFU$RO03zKh_#y{ z{Mewf`#==)qK$+zM!p~od4I{67kuvmPII-ojsv1}lAXl!f;yta5hWn%si&VJN7N2) z-rxdOC*1Xsqo%pJ**J2=l`9~swzd{$&z`lD@br;FbA;wHS&941BgaQYMTO~OS-5Z^ z^ua|OQud)Gg(wD%(U}00=11cWGuKJ5$sYM*B6fiXRQNw4%R@`kuO}r>LeL(b{?pQ+Ld8PaioYq)eOfj*(+$ zq?cSfgVX^Pp~zeWMY&0|1c35O5G`0pl}d%=`pH5Pbv-3jQYX~HTqLLGA&H`Q(J zw9@^p?@tl-r)1tF3OH1Txp8)oT!)MIv&jbIpLL^J94F*W!p8M0Hyq`q^%I zoF6iiv(PJ1JFz%Q*|LlPC|T;Ts>q%|39+iG=5aK4k9}(pm0kNl zls5VToivW9>|VbVs3uX#5rP3aH7`W*JP(MX54_@YM4dVda;2o9ET;%t)-A$4cNF5T zdy}w^V}crw#zKu36SRWt6xP7ITLFktxh;c6y;=QSGIj+*yEub>oLj)#lv`WVa^7-A z>tcaX8WSWbFf>f=o~~{?FhOJ7haY@s+#mwpo_YEig6+?ko;qDME_|_e12SB zgYLn57lrfZuGT-?OS`Hqsp2mOM9HJ(A70d6We7fbRY6AuS8L%wBQ89Ngi1^`k!|zj z2`c)3ryidKfT%U)WmvU*A(m8x_yIh`lT90N{Frq54WRB~GRK50RF;>_KP>^Fn4z?6bQCO-CKWQ#fT$n4v4xIihe!AsP1F+ z|5XD~-@?9pbAc$fQLAiQ98M0gt`X=2Rz?wB{sQ2Un z%CFxIo$w)h^vF>hIeY|%4j;0wSDIk;g?T|~sex5mxF0!8KSz&oLRpH+CCkWBbsJBT z+RRNrA@k(rMU$YcHdHR3mT=(5O_X{sW6uh%NrrB-2BQ2%Xz}@RSi~-F_i&9@m)~m) z{;dw?>R4AqiP=Wei|1$`Up5BVbkI~{N%@rDT=WGVR9dZDSDJ-8)t10DWb=Xu{L=#8S&p} z&uXXm1%N0iZRMWF+#}?qh)@j4D=b9|2}F$yM6h>HJAU=+^VqfjB9*BR@WVj@Hm+KM z+g7i@UH6a!Vyko}smwtjN|ZAKUYaF2a}1wi;vVgtUnent^ka1$2ShdL)I5SoufFP? znkOzN>4>^x^BttuhU3vOd>=&;M z0zm{s38a`9pw7sSehk(&p#9(hv>!W;j*C5LZ|XrR0jD%_k|mIC6792O8KLEXYX>Pi zZ>FBgiv*|&OY>2JNPvUQ15qY(&*Ze%Hd1^X-=x88+E?!O!B)@5Pk>O|z`vmcYrRRW@ZOC3?~3{#YM82vrN1kaLCo|R0I z!$h=^TXFIvL8ebYP0GkOP-oln@(>Q49>M-va&nPt4C7Q_p2Ab|3UdfV@vs2`Q93nG zCu)l8DVd;lGRv&G;HX6_AWEWn0;0kMqEthw`UKMv^*VJ#9X~mN;|(cTO8S0xTRFCE zDZ-i!JcVzWbg_{>Vrk)cGC{!mRsy12`*!`xT_YeqKfK%`}KCGVIdtLP$?)Uw&M`T7#*-6qcNkVrUq}l^%g#O{{x&leF~>fpEi*F{+&Bb`e4It zx0%SWOW(z3SO3T5#a*ZPjq?-Czw@W7ySD}rjNI#u);TPG8$70Xn0(+^q`6Th#tG%W zl|I8U(qojsbd>#5;^+G4a_U4k-X;+B>8^HZKvZXEJ3r(! zQqg}ePF9VeXE+s0%NAhu%Hk^mQC?oWJo#C%ORT)k(d!8Ai3OOvopMKa8y{zSKgILh zLp%i>-CbLay(j(kZVrfwQRG{3qjn&xu~POc;fQj5*T1^9=-TEtneaCSh!Q~^k-e)b z-Rtn|^E6tVP)R3`SFPt_UOF^RpE`+C1fZlxqn$@)>q|}&#Td%VEAZfV9;6b*yJM`9 z@4WpE{_>Z<7(k!}|9md$bUuq%J?-Hl2sn8sIi@5&dvYJf5ziX3;1^^LZu%go?cWa@~@%E@AT z6n7nSC@W)a+q<=2=N@p^ogt}+lx0F-naDyv!4Atdo#9RV*6sKtvbX&0La-u(Hc#sQT~CD@Tj zQ1r;loV6RT_+HlID}b)9ZCM$#Q}<~iTBt3`#M8xvv6uc&yr1B^8Sni~pS@Q@wtw$B zB@F3c`4g}rPp%GlWwlQMqV!60qW)y)+l;&FL2ne56<2kqd%5#xu&W0{UA-9V>m~@* zjp6Pg^tV%K{KXE8RiDNv>#4VMfFRBQQkga-%PcNIr4tdhdFqWxN>4>PmBS~J>$;Zu z*y^}>&B)0>W_BhPtzL@78&@NXr{M`)NucuhL@GW`Or=;IWm~0MX@p=&lvY5L%B^}x zA|Rv9ua{Hr667}Y>W}U+DlF?S!3t?E-VeE%FX{HA5PDCqJ=yNZDX^++hZCPh^`l(N+3uZfT|>?$2oVV9#f~(ym;&6026N z!Zse7AkI&5YbFVBWnEfcrYWAwRp~x?&-?TvdEu+ zD9@jsY5j0I19pslbXdVC`=&Ue!tAdCqTY!EqRNXYmbZ{xQA@*Eu`EO}txoPonsN3_ zFAkiDqIobG%jTD0HFZQi|6~fDd&U#ZbEB_@#b6O!S(SZfRMw!ebwI!=IJ5@+d4*H4 ztdvt;%{^S10*>yN(2um&yAE+gU678b0Z%k9FV8*_Wn_A5e615?W{fA01?MN=bX{)a z^M0e!xh|Q#g(Gov)Kzn%tXucVP5SXNxek!-PBFgdBZ%{BYb!PdJ&S=x>piJq`1gPR zcT*?y)1UqnPe1dt9WbNy-4x@xuDkN3#Tz#!ObPQ1dAMmnl;|fSYon&CCtje5Qj@B; z=pUfi!oGb6xM4bo-tJDb@~eqYvbwE2PFaij2OsO9(Vvh{_&4Y9Kr!nN=pO0mp^YJclGW% zxx1QQz6?Ig&FP2|5cRX4{mgVk{qsNnGj$8h9*A;jU+YzQbNLI#;qva>rt{<8&2)7% za_?On?&{pXj@KZ4+`Xpu6fn2t*mT1!TIlHv$wUU*=kDDjX7_wfT^I+d(B0dHw8$VfF3ZH<{%`|NgIb1U>a|HB z2NHL>HZF%K>S91tFoV3G@<iMD6>c1FyUyAgTo& zeLU@yTpnwdR$$eN3hX2Zwd4L|PW}=(WB+5S+QYLNY>eiQw`W(bHHNXX|+KafK3dz+We^NfK zgElHFD@^=O0A?C>uO#ynJRQ8DvE`DyD{n5Z{?)bH_^Z6iIQQw|n$FD&<^AgYmHfE) zgW;y!s}4lac*FdA^S_as8J+ZFK$I$0PP8hjHgsGqSS)h3mc&P^UiqO1vuqpktot!; z5MbBSqx?-VR8+3h>k@=^B}hk<2Sgn|+Doz98ho<1 z4lO+`Xz6RgV_P>7h}wkp8#1vn2t-wRK$K3+t7_>+AH}nZ3$n=tl7rUH37l+UUsZSI zM?33uBv3B(Ty0++#_b!z_;}9{-Z@IKyf`50b^=k)kPCC?{p9?TcrUH}xk|HwNMD>g zHIE!)9M2MvNt=P+{^kgNLwmX!)ODAR6(t@Jb*}@WmJ)~}k<1b)8;=vslLB>(HvI97 zyZVo_xy%}fvV3`)lq>cTmp!A)^tlT5L&fLfl)Kl4Cf(v=aDLS;L+V^Ka`QxYr9+M5 zy2cw0s2ZnwdV2Ul<1CI*S@~OU{lz})YOO8%zytU5V1}o$V&w|cgK6^|>nzqz;}Umi z$2nj2(UsL*Re$O;&R8}2sEoPB8o{I=7K-&QpH>lGP`~VIFjjufM`N_QR}ZxLgl$`* zdGSD0NnshvDTT3?!0XzTRPQm;$<1X8_Yed4?C?11dy`SY4^XQX=i>*@rr^cr`5}r) zt4k{voc?0XP??#IF0t~;1C546S0cqBGb0$~y`KC15)@FK1nWh8L3JY0REgAU9?#38 zvhrN&h{{ak8lQ(usCi8TL+s*A3b;jpD2WefVWu^XPKogV9CiMWKiP#(KHZI6 zZk%$-W#TDfO`uZVR(@$dZ+bHxdE^mO?3%*kzNJUwU;gD^@Gt-CU+fF>gAYE4+i$tKFu@yxPnai(!yZ#|AE<(m1l zz@D;lxyXzTOGi`^_V4S!pa0+iQEh!Z)P0O%)l}BKta1@QI3zPq$?RA3FCdC5@-SET zA+7LjjMmVr@pN*lZtZQ+m#>D}enpi?$g0Z+^~{bU9x{<}rOnCS~Q~i2CE({its4Ku;(2$}P&r`W5+TYUSyh)dT1^o$WfM zj$C>i=TfN$>cKT(+_fo$PxlVv&7%awMhHfcyNRe1il{?qU1c&JeQ1K~E1;+#6@|1K z5>!=wEwXaO&DGEH4{Wu)b2OA5#C#C2$9J`zKj{~9(NR+d^o#L}4_`!=mz+;a;Mh@5_6wWL3 z<^XH3exB4nRM%H)Se96Si4UWO;!G@FjZe;zVOf{cr6)JNlMQZ`B(`f@yP}lVGkh$6K;-tUM0rtv?#o=dZy1Y#0cBeS9&3^a;|<6(Tq!I=A>ZocrAMOHzRKqxzUqCz^lQW;!_@N{Rmf2f;kf z_c=Ma1fj?wI}H#OABW4;boJ}rUF+4wX)V|_Vm~r_H`iFMp0uiejRb+K1EQpNy7^+W zy%(3dIHIJmUd%2*ASzZLY)4{3(KsrM;otu4-#m_}fA|MH^UVLx-h24Raa`+yX9hDE z4V(Y|_rF&)I08`L{?@l;`SRsbP*|Y5nX$D72M5*QEWraBWTaoTc#(Ydp|3(@ zeX;Hel9icd1|^*onE{GvEu+~^Zm)SSo(tnyWXPR6cPcp6jYG|uzWgtFJ24{{ zBWmY}m-%>MOzTQ-qeaW=9-Lz1x$oJ86FiO?z-^_zKzj;|hXa}jbwstj; zParB4;u=)R<1UO8+f+vy$I`(~clSA>S~}Vz^RR6fFO2su=WH70q4~s?<#LH{_j_zh z{-K{+I!&a?N=r;q2t*Nxq-S5Ir`i=?Qi+L)Y)sAW656}l+-VO+bqCvWFf3j;@3YLt zb1^IO`KJxC_Y?R-J+k{mKh!NUbhn>X%X4JQX0P163Q`FWElz~dr&nGL$xCkx$ceKp zu)oqIxd{!jV0r@#ZwKUoZL4J6hJ^siF)@e7@2e${%w;YKm z1)?Bh!rl0y&!@_dv2|ke*1i{~$kF?kIk7xJ3h>_oQE$Haru^;sze#0frT9Qg_WL~S zrb7e1lqTrz>XslTA)$ew%qX3qA2=ulH46X~4gK={l9`cd#tNiKfLaW__Rq_dC+@9i z-5ol|jdb;aTIZ`zHsKV?w=}j+R6<4Q#x@dpMS&>T3FAtR*aba<>4yfehzudUQ-3dw zE`#O+4IR>axJueiRY|bFS_VSZU^M_JLjei(G)t(fRz?PZVh!WNmIt5{Rqv30d$3R1 zpvs?KTqqeZI-E6qmSmUAk<@}*Ny_m_a#oV0Wu!t%FiE;G*7ppJNDyDhxj0GBN|oG# zEZhr#712k)n~6TCwZfn`pi=dw4^cu3Hfd-F2^B<>Yh6Z=mr>(IIQp0J0q(P&bY^T| z&L%!0XgGgh-W!(?SE6kyZ=wWyywcSik@IJI4qxG-3#(%!KKwkr#hq@J8a4b3{*#;lSk<*(CvY_ z9$B}{BcC51ln>7V$O8~aqv2XUNF&Y49+9o9`(*9fL0Pmg4>mnvv>kP&nxgGnXbiMX zFZckexB%ovQ2*hP4A3K8UZJt_mrqD_Z3I$Xsj_xnk$mslGiCFpJg67reVa~oJTQRn z$O$z_kJ(|6bTJf)Qj9@g$XOuj&|&PV2#|(A)OWx8T_Gq#DOheQKzpQWd>&8Iu`lL{ zSM1-mS?$qDKgtOvKxv0+^Jt_BIS!Ji(4KJ|rUE|f4Md35(+|PDjj|peJoqE}HJZhX6 zn%F#|_w+I5S-gitde9#y*uJ{-F{o>JU+qq0aY2wE>OMUJdBf{meZ$CLnnQ+>ZNl>58B+I@kAOeCnG%Z#1ndt>U#9g zJo}9N>6t&_Ww}*;_OqYKvZc!;8TK8t;qffKXldJ{1H0n9@WMajAOHA=sz_|!ycvMk zGF8vx?nTN_F$+}t(z6o-me=m?rxSuGCmH4$g6a$za@R+@O=XZbDC?D@^l*1?6<#2hYUkBidR2mKx_6B%yL%B9 zp3EN$96ZE>i8}|0F_J4RN~~jnA*BMNJ~(k4 z%Aw94oy#!?EgR~`LNguv>+|*Lx5f|2WdN2-%S(!q zf;Nuj0f)S1@rp5%ACMG?!ft80mHJ%O%urd{Rn2zFy|zT?`}fp;nco@=FTrpQVc*(u>eB0tgiZ z7!{PPX~mK~y;$;R&69#TizR(hjs(DSiBLsL04T<891QiV=X|5Lw^x$!@gW01L}HQw zpSe?{4|bF&u?Iyz(18G{if~1NDE3|2UL%#vS5?$a`I_+0rg$7^5C=fT-mw4G@(}APUY6L{($L z-PzG1>z5YFrh5tjK6J{VV~tYL?3Ml@Y>_7!CKHM zg<@4PCixOWa?i{TS+O`M>o*j^Ln<9Ki70S{W+zhsfbtCWAPs>iT#h72D4Zq(gX!|d zYo{QMa}st!A>G*cQHN85$4kwO?l6!-$(i}v(-_|7$T!pYS;Jm1in z)gXP96G>`OAnMs?n%P9&PH>N=3oOgfhN&2q~$aC4&oe?eaEWZ@%|MZvgPCXW9!PihG9^j z&W8^cv~lwO`|rsI@9&V~$4|;JYy>oQ$~5dYy##hy*UQ$eTXZ9!=vc2QM}OS!Rr?Hk zm)CT9R9ZWCSg)vO@l5#;(ZsjWG_6U`JhTi>3@55y89JLpZcvBu!&oSWA?alu?Z2=O zS5@@@gsO+{gqpa>>3Y~x%Yx)9#)_2-VMlQZ#(>^N08!WhwR}j9UC5NGUP!&B?b&x-P7B6scW5+lG}wLHm3+*plg#q&n0t3FCPo3$&_#YG z(!Pr^x(n;hhWdK+hoDLTW?+s-X&9a3$D|wOL&KZyhg+U^hkc>*EAfWjH}45|x$HAd zzu{F(#le&8Ltxp<+>1?P>U;gue92`%wUkyk+V-bl3_a-;z&wvYlwev~!?AXgF~oG@$AZ zhYlS80CftD%t=~AR~#M98@{(lVAPnSNMXnM0W(SYH(znE*LNE>gbZc|KsoSJicsCpFUk^<73(KWx8^laqCK$A}**ekjYJ-jpJKq;Wzym5S15oH(~b zu(l8yiC;e{#XxYhrG-G$kg8+R&Wi$3um@w?Nok69A$@cu!=~meg>4?=V)@Os38Pv1 z+Av<5FPWy@Y#bilaTrgpuc2L;*KO_C45Z7YO)+k@`GVp`1L$ee0cnE{s1dW>=u-eb zWI);_i9i$=2LP<}i1Tq>^zq;i@(8A`5SlPJ5Ekf>A@U8zAguo|Xk&LQcxDFv<21Jy z>$tvdkqwxrcE z6NvI*@tFWsoI%i#ei&bmvEx_S`EE$TUX;%dx5&w|pj?1t$CT`;Qk*kYzV$@1eB+zR zl9J|u$TP=fNWeg{D#43|xF6?Gg^EDxMUc-WP9JFI3W;W@+j6^x!L z-Dl69h1$l4^7cD#OLa}P#%22kuz5yWYMM-e>fIC=@|{sqf)5-eP}?ikUGVbr^Y9go zcAz*e7#AG_@L1B8|F@D$K>O12QM_Wq@(c_C!}bhl3rjw#MF(s`r35T}sak447~}x9 z@I%6xARg_IDTc%NxD`P>=mi0NqDrT6gY~U4Slr`P8%*ecN|c6TiRpR9 zk;VWg+TySqWt;)2A_P+5smkiX&U6ImA^>KP89c&p)Hp=ukel)>_@7`DZA8(?_fQaE zRJTv6F7#glL~YvuiKwm10gR^0;zfQ)ZkoP43Pklvbz_5cw$(%OW3sGXF&T!d8|BQ| zGP&5{m)=Mz9-EJvkzm)gCO1^g%U9cPR@II9APdmSjQu=Xr)T_eqA=Xv){@%`CtSw`MuO9lF&*+} z_O>5IpU3Aq&hQ5L4`Hm6b5F-OJcI8rjz21qh%^jm9KOR?XBr|OgjCcK0B=W*9MLcP zyLWx8bLsrN0?e1!%h#X$x~yEWQlF^#+J`$wn;$QkXS_JHOJ(k%4EQs(s`(@3U{d_S>n*6A${BK(MBGvH0!;F@C?D!JBKAgZROTlVgUq5pkdvU|Tr zPSwKLepAP>aKKbYJd+9F!2Ag?m8E3Xpczkq61A^aPb@LZt^% z&fF-AKoqqdIKQVh4*e)2+8joYHXqwIye6-IX^w2~^gCS_y6ef#z<$F1#c=mMn+9Qa ze9$sGbkR=e8dG>r>xy(*SMa*q-BM+6#($Py$0gLMsi_G&(KhKjf%CU?e7NGrW~$e5 z<1_`MNGr!PEyIWpeER99YOI_B3qPc4-s4ow3#fV?<3*iiL3@nexcyIV3Lr{RM=*Fl z#NsJ2RF1FApMLs@oIZ0(N=s&7SE8A+V9^3uxM-mog5CSsJ^)dtp`KSGnJ`XHoy$#| zHbN=^k_kvpaOv-V|2x!69*|%E`qyf#oSj5F589Lr(v2N-s6O%h^Ute_#Z+v&x_0ea zS+Qb;EL^-$#f^1<0aGwOU(R+=G0f>vCZnikPfw3ZL{O58hBnpMCZ7kVi&Lbhar9ST zeHCB%!YZZp#Mi%$H6$kKn9Nz`wMUK&qvx8>hBo4#uHS@7~F^tZJF&~E6d~H09gr9hA z?2Z$ApXp-5Vz1-JF%wC{Cjj2&}Q3!e-C zG7b7;1SS$-oL46^h;Q5F@{i>>#f2vnZcwiwOcXqW2;*EC!4yRBMzDZ}EgQ5b%(Wz9 zvG0?P7O%9odI3Z=%Z{B*Qq|A^yD(6-E6$Mzw=98*%`}-k-y>5?kP2u3{fn;;%HQ4` zk~7uVioPo>g@H<_z8r!?RKIN4c(*KBwm=54C>(+(@6cOb;_;dtfG7`uDDlBSaTw)? zCjc-UfqFw-AHKXd%Aq4|viBgi#jY8Y%=98D$|#oaJ(UItgmeIX0NwhjIs${|u#J;| z?dyF>IQQer)F8lwFc+ibuZfk>_6w%5ZR8GPKAbqPU!OQ}0_8gnyM>>~N4q|fdVD3N z6avSBRDe)9Fk-r3(PEjuV391rdt@n8zB4k?^gb81%!@q3{B`#h2B zA+&D~zzV!?kyM{GR8=cOm9=uNtWJ)ct&=`{gh~gPkpdvdHod}R0Bw@eU_UZ7$$UIO zU+l$uxV0boL7i^e{p)1%+GUcGfL(BWdDt~CC`kzbIAG@}?8DAiNsw|$Mox(sN6|N_ zM%RuH5A>X~^auM@U4u3#4G_g0;0Ul8Q0bDk<<4%{HBxOwF%IhP!8O6B2(BZrKjk5~ z#5e$<6nH|7H4YZj?tIBlj4SY7*lzMhVA~Sg$Pe`=OKs(V?Al!g`%Sgj39nTyw6@5$ zdzQo4G;BmI0T2Z{H(6PDmw=vS<-_v)i(z^FgMO)Mtb=M^oy^5n^~)Aafy8gER92mW zYFt1%WFD$hj52eKN|5QfBQghIR71xIcGinXZxHVufY&O%Nk;I5AobNM(=vKw%UY=V z!N~Z`nF%s$2F67{q&T74%s7b&z33Dnj5n}P)bE9qX@<0RWXikmoRK$ooR<2w9;mqv z$cFio!vMepGDQFjeuB_u5ozeo_o6wQ$S>a`obT~S2}ky8 z_FMY*-g_4xIsdBtpAr(3nx|O^e(>ZDa#Xnu1K^}OhJ7FD0u21-21dp!2gzk^hS@mU zzLuF0$b8k~Tt9l+h^#(nsnUf`m_FOiH892~=*@e`kK>#N_w2j`ncAH6$od-TK2amh zG?PJfWSX&{ni9vab?es2_rL#r{eY_<<&cJsWwtJM9ChEbacntl-A7Z~7_2Ki`T$A| z8lkSZHMahsi&ICNpG}P+2KSH%|7uUr^#GlNIpZ(s>emHgKx*rHFF2+;eS~v2_62@y z;K$}*Fr-pYl!W5^jy|4aezx!OXxql-8!yfE4&$@P^B$}*6?Bf7Yv{Tg;{ctG8?G^c zV*~rqC2L92g<}ew?QeR4AKUK?xJ_Pm?%YCUh+UHrgd{DR0Yp(XkK-Jr+$j;432g(; z3pwT!aAF(NTgUeZ{b!$jCeJjlu%i0frbVb1`*2sRsvCl||k>~gn%|K|Xt&SMeKpb}B{-S-t3 zBwrOZ4o2gO^jo)Xm7o0NCkkNcmo29QQ9_A;RR`2jUU=~ZRnIFaDN!SgRLz?^f3E8P z+m1wLVn@}EjY6B3IDoUheg(g1#O@S!7r9VYre)yQRy%p&7hf(=xvSb~s2S48+4u1B ze)y{ogJ}tHnMsfCFcqbVojf^{4i~A|yBW<4G9+A-ispp(^lVHb6M~>IbdO2OOFJOz z7{(tBGvR!urGegv{*0E>#-`be%OXOkn<$QS=!m>+1n<)X#*R_-s6#BbapY#b9WkE)7i8vi+zTc z2S2gxXRh7pOd5ud<}|D)2xC#|gW8QBNED{B(00L#5of*#7kB^wFcBKY0<6A1RT}G4WdDJS zvhUzU>~z&8J^dXrcS@dYUAItHE-#enr6DPtJb;%b)%Zr_)wlif!h4Bwws9D?ZU96j z86axe(r$qF^JM0%85s94iGqZK)q@`ybjuTJBKqc1>`DMFPZOp*x34~Da$j+2Wo zPlHlX*(9gV5Qypn5H)}W5w^-rPLpr_+a!E}p9G+92#fzdlnc@?LOWO?@h9Vpvmc-Z zRQbX|$kSjFW&45c1LKv~^06(iy|#5`ec7++xpNLbfE)n2Kt;be@VVM9Y-?-PzRs^> zQ>IK+qveyQOu@TqiWEWxZxTF3x%oaYbR);G503Ujy|53z#g2(sI3@8NhH_KEg|@*G zQ8_}igr_LCH-tEY@LWU!cEL5k28@+M09E_|cL>%-MhHd%M1g7=7KW;`6fX+&IgsgKG+%x(iT)f zviRUrA*q<2nhn4R{Sy)&{!FOsPs@-%Q98hoRP}xUoAd*Ccf%Grz+M7bKJXzWjtCS9 zcBaFJEO^=g3k~!u2$_`$yKn%nh5>|`u^kh3m0XHxR06T^$_MCQbgEj)=(LrkX+TpI zT?Ew>^x-&SCb??N+{u?br6P{FhdulxfVd-2X$yz)F`x3v(UTYD*lEl?D(fKCQ74;L zt;7z)cgxa60a-L3HkQ(cq!*y>g>nyo7A&auiPS+Fs<*pA7SAe@l}m~+Hnd=Tsl=G# zm-^5&=^TVAqm~J{;!a+H)KpTS7o~?yHI$_fHm;gm3#Fy45K=g2<^4Tpp_T`6&!Ld4o;z9o z$79Q7_1#br4AhG!sTF;T9|gPsq#(TsPl*_vqoEkKpT)GmxR>nnI^T1>-`RJW-~N63 z<-Hy6>rQg@4HtDhSh0MCs@>8KDLswT($neq13H*C8uyXW8z?ULi}6W5C!KT6dZ0GZ zahT;KID-(Ap66gp@||_&xy+UKG=g)>$(x9dGcRFI#+iFe%kndS&U5MCdG{Ucp!beS zhV=IJs^-9>*gbF6s#Uruqm+nS-I)0?y?M4dcOIe#4YvWNn5gZjGj%rCrgZ#8`S5G< zb>f-;1Uk=B0y;7Eo|$iH-uSWfWokXU0oY9& z0r0JeDcZ=ity6YwU-Wr`QEWeW*6wN@X~pu7q3P9T@-H0U0th}xn6tkdez5I8!_!dz zhMFqZayqx?y8}Dha*h}4nAYui-(HXQ>)2G+|JwF{b432pzHXjn@9ULQW?Kp?9HQms zK;yW}reVi&P-3P-rA;b?-wI`5@ngFlK{o8bV; z<_y-6r}!?RD)-ATzpU?tAN`mTQARb7^TII$9utyeqvW<(-S)?S3J|4C>X0_dpkM;3 zJ$&@hPL&>Ngcux=#w}a6$d=7pbXTE3azNu8JaAAdDk@Y@pJH;WSFe`Eix(@Ca1eR- zU9;URcfx!6>8J5^dcHD_50gYX4koS8_oRVgGRRBtvu4dw;A-izrMjaL?RcmIQ&=F% z1fZ{hIqCUTj0WsZo;V3T`u7$2Byvt~0STtHh$)|2T2iVz<`F#O7rp@)W+w<`2SWP{ z9_`@erk4$4hoD#bxf9{s++(jA>zH;d;5GKX`-=H`IjF$dG*^?aeJR@Vy7RtO&q)({ zJ5e=l>{s!1^A!}TB^a2fvPC}R1bIAnHEl6o9t=16jGcVia>k}(d$JAfvw45KHnuz& z%Lg_M!`a4+cdO+aOP6c8cGHEME3o~2oS2~PIZ>gVAjYA(rUjcx_wk&&O~^ac!3)B` zaz7+|QvCP|mk0m}(h~iU_8}0J=*1Z012pA_j`~O{Bo=a{syatbpRblv=c_Pj>cQ9U zkj$D=AnR7ngY-iV!2Ax$&c{L?EBO$<)V}dvro6N>3u<{N7Yw!*CL17X!Mrwn-Jd3u z@L(P2W1S6;cP}<>yldNs0$9iasj~`PoiiXK4rd?b-8SkJ)GH1?R03~3=6z`>f1($>|AQ?au zr(gZ#Ot4BS=$P!{^&Xt}V4O$-AEm<+nCe0r3eKda`|xguOci)|WH<%3o?wRv>Rp+^ zUdan}${?f-o15FEzoA7^s_Vs%V>g%2YyB*OqV5~O{w zSlWk*WMn#aw<$@M+``FHm|r53Cry?qkZ4Ish9qII7Aj@U+P>QN5}^JE-`5v{N(R)% zpjw*&^}J-vKdAl|0oW7j8w8(mr@f#I03b>91+a@;D)Imrf_MJq`nu%{%Wu4n(sx`8Bp%+`wV+;ul zNK;!F5>YL))oJ^6r?k4o3CRs5jA3Nd|U=iH|)#GMqZ1YN0N1jymLnM(BNEC5{ z%`6{{$vbX{;ZU#hB5YPC!5y={`04K>x=>9S^dx7@v^8-2tyViLx-)YKjT zh(S#F0gQDgNMmy;cIzvZ&kvrH-N(;MB-DkD9F&!Fisi9~R-pV@kftg_TVDj2=EDYu zJ^>yGAPdh1h|m7dVav{4Z27KqB;7ertv zvkv#)f4|&+-~IYgDhNAebWAgmc8e_&)9{^Y+n%cx!z*@N8XeOZZk+;Au4@~9HAhok z)1KsGx@6cvp>+2S*ooS)V+VlvYH4n1mZ{UGLfvw+EM2-()fDsd^Yx+4UX?Xk(y);uSZT@ z@W|OZA7IjK33{{S{<$5pdRYhP0zSb9>hcPaJqNsUx{3DTV9X!V4*&Dt2IRZn0w{_1 zEZ?_-gH%HYUtsLBZEK&cs)Q($DYt23dvBsgroCETpJ?8@`Q9FH^z&|q{Oy?FrWxCq{nf6AY(3fjerO}` zK0&DQfGD>ANeHQM+@u8fk0BVNKomY|QcywN=<5^XgYyJ?v=6+^k6$_vWjnNO05&?m z;;@mk`-MXP^XikcFhpAd-0{0h~k$oE=;I9OvCC`RaHhb+a(dj_30#cn9wbeHP$cICtcEFFaqWHEq3reOkuPtPel#rpnaRW4 zvuUm-Uw663w0Zo;-SnZDx^O<2Csj2QHiCGYi&Cm)(bfR(kMAbf7UK;_ zPFa+;Y*S|hyQGa=>Cx5T_`_%O1}9`D%(j3e>zMo7sBwgtWAcf;$-?3WhN=_8is?a>`kKR%$nDVk4v zfVGf};-(q29YIGiZN7V^O`EP?%s8Q?GyQ@mdUp0sJ=NuMT> zY)Gf(`e9T&6QD=7s?MfEl@fDF*l_{iH3HQzR)W@yA)!OhFP-55O6^hIn(CFwXiuoN zqU=4Lz0%XwE8!uO2fUb;njzVldB~4jwzJQpA0tEhQD;I-m>q-pOvJ(X8RZoXGWWHg zF#|JD^K4v4j^mzjBZH|D9LScIRzD=2px%1E6;d6?W$&pIvKm0ts^x1SA(<>ImJh=o zmLm~WVI-nH+UJp)j%MlYYLT@IVFzd(Y%u|p>xUX+T?1_8R3*!qc04Hth#JB|Td>g1 zO-YpEtYm;rKFQ67;w;9MW2ft+rl}omlq31@_pbHG#!X%+ECRrX9WaxU0RZ?1AQ6SH z%E&j^n}EfAmXud!0*I=C{hb=9IJHY^LYJ&rI!T^ZVMzE6^ov}}usI>x2MJjZRTxq!dB&a7)t}>u`b?z* z<~W?c1|a>B2)_Q{!w+Dz`~!e9=X9=1JF1&EZ^kaGcf%Im43!3@^Z*xbv5uu@o@2{v z+Qx*r%kI?lN_FA=OCP0=W}fc;~O}y(7u!+ez}^f>znEx)p5?&=W7GbFdNh!N)LY-hh6AU21c%v*xd!6#4h3F~%X! zA*vQbl|BOdbX3hV?K@g<_uMj;KJIc~{@l<{(_e{hm(S>5@-C>S^=7~22V@11(00^v z;5pZNy^xCGdW|2M2+Y!k8l_{Lq*1!D4fGFv$G!`qH@~D4H*bGQkG$m{6WcFYAsc3Q zLT1}?-k*XsUIxqp1u)l8JC~RgP$G)FVja)9`{==g2jqo+yr2?w6OxEx2LEDx*aLe9 z|GX+=EauCeFMf9L3uWc<+1~y5>U0>APp74}x=K4b0jMZLz#b0`MG{Qnpg{=)-p|Q_ zEtChh$pa5O03d3If>AV5{xATa#Y-0J7aLl+r{e^Z+i*8EG|4|+FuUea#G1SB(O7v= zagkcYk7Wi0Ai!J%fXIw={K_)~sRv3uaT{1ND#gv|bTGgCb;I zPr$&soum?kA`O@)7d+#=Ts6}P{J39imqbTd?4WzeJy*b(Je)LR!d!9nbb|TDCcEXX z(VqNLLR&zboF>3GH#h5UT5Ruvf&%3oE53W#`b~sph!e|)QT`a6%Z&dRrl)g`I#Dqp zcYd#d0#W*b_Uy0h|7|U8uxZk&*PMv+1(lPFowfq;?FYCY%b~(HkvYK?2Mjo>;NZ2V z;{=TqbCJwDTZ+t_MDRh7;Vmn&7`ICi)72a3uVQs z$uh0P1Jyi?FV6V%n?DZ7fBtzu%9>#59MUIiW{dpzyD74Db1EcNVB-usjdGNWv#wzA zzM$h*MjBs6Ht-P`zoKoN-oA*m!S2S<{?)QE8=Kg$Bg2EaT2OX<+9b!z+R^x!$DyA* zeou~UdmtMdC-?zgKz$DaRvgnv0YCa{IOu`IVMLA{i^#!4&9eV^3#7c7B`v8106?yM z>#0T90dx|i)`IW@XcyF+iM8)j5|v!WFa)Bg6PfQ=N|J{;AJaJ*=6b^b6%$cr&N2DH zp&cKbKKke*dFId0z(mA;RnN)K%g0VgkE!jCA{a2|{E@q7#%)sjpqu=tA5g*PTukXa z2igQ5?fgh~Vv~kr$ByZ4)*S0LZ{Cc}E!N0_`3nF>%|v^E?i_L_>aMbVCYtTl#zQsH z<|qsYGx!eJJFBf51|JT~TOSU|TgNcxb8IzkTihgDHZ;NDKJ93wK#e>>UVnF3&eQ{l zO3K0pA(?6;>c>BTeK{8>&EC&GYX9PvG2So`H)5PXOG_Nd_jlX`DPU=iqmCIinWZPL zb=N%D-3;MF6xHx`*E~o*(^eGw3O${sXMQ$M4ZZVot5Se{mH+iHt;3DdIRB&83wKDR z))aTh=43>9fbR|rB$kJ`HW{D$$OmSz}ftGZo_zf zJGp;85QWJCzm9WZ(FiG}3m3}q)u{qsoU5e?Hlo-F^k&hYpw{baV3Vm6UrC8l(^woA z041d*s-j1I_19l}T@8a%WSRyQsctuK{yby%39Uypnu@Xt{i1E9r&g_6El)yvir`gV zL7wi6piDtt;GhDp6BIC-)q~ds25xbpLk3g;$}$qd)j16H@$TL7o8SBfU;A6-r$7Cv zJPy!{^CV?-L?nZ0UAf@ljjM67&%BznPTWf-YuA!zOtEd@Wfo&i_yyEc< z$C+V(IE>=s!Y$;HgGa)0@aUlI+I3#u-E&^jVZUN}b^>g{OoHL@*|G$Z1XHH^q@WNI zLtOmB|Mwq4@}JLzq@oqlAXva}T;P-c_(`VRcW;`0?W0s5K`0jc`a1R_!T_|u&fMuS zO$YEc0BhF0Ko^c4>yzLAp;7+6s~uy!M>3N=^6yVflJ5YFDx5?+Y_tml1J(edJg_%q z8~`B5+>Gv=n<-qF8dbdx1)ip0!wVWPrek}v z9XWAfI=(CP7|lbY-8w%GZCGHPAH^^Q!&p}Wr2HcgW$KIgXl5?*hG|D(2*5#qSbUIt z8iwRkH|%co;^WdtU5$)fti@MD*eeUdH+M>ZV>={|+NC?#1*xSWNrnBEltk`UYc}NC709)AJ`u26p&j`>~r5@SvxiszJ;- z2>K=hq=FeJ^A2YitzChqyb46I-6&^7RZ9Sz$U}iBOe#Cz`=A2b7wo~fkN!1fx=KUx zD>~a=VJGCzCTB+?cN+Uo4090_w?`er>6wUrBF?1IcERZ|M9qf6F!&81>LeD@N00T$ z&OL|Z{ey>O%>vk0TDDx)t^p9W&JT56zQa6HSvf3!dod)hz1Ih0w!V{qdmeuR`DDqMZ+foi_mhhzF`)H8WKUXi1&7`97UjsgHM#gem?8@nCSkrs`)gSK$8zNA3;!tA2R9r#hkr?jx9goGMFSzVMY%& zuhEd}f2QShvgH`4bRZvljh&POu+2*Qtb6zEmA#+sRdW|BSFThbYW@24I(H_sli#(x zF?ER-cKvHHfgF_|_~X>MAUQcBFHL^^{UrJ6j{s7Dj`VzwCV(*ftYrSR z5QcSak)0rWc}+*sob_>d&mOKRuYZw5qwn>x6=u6>TcO=LU{koR78_!qzfEkekb0uJ3nu~eG!8}^Q8ZT09q6bQ(EzC?+T)-ts8vwI zD=NYw1>(Yg`|IE2uYdguR5;R9U1B+Q!dtg~9d>KMmr*$Gba(XVQ8{*$c0LZs=P*3G zcI`U(`V&vWkmdqxv7H%3x*6XxqoSUepwQ_TZ|B9q$qJEAN;UB%?0%suK!wSz-NKPy z)PDHGALwo?D#nb3BnK^1wa9ctjqTq;WdK71J_8%u7^h;HE{) z{R!oHGerU|teCCx0Vin6n_j498X$^5Wj3~F=SzwM6kk%d{Vfl>rpDhqY$;u|E=W=%vhUEZ=;&$Ft8#a@9^D;@2lSc?dcJ^gtrMCU z8gik_mmFOHJQ#*eodXBMP|FL;u20J4o&Dtk+siV)G#NltK6V0~BJ=0xNO7SLl3EF7 zp&uNP-#;@T|MmQURJB8*XmCKbEJ~FB^OqTN|5sA99%{=X=GoWhlJ&Dd6c>$V;YjH( z&gU?U!bohd{OA9wm%r|4fl+DDG{r05*j^xyKQc+CPfG;Y$9DpEN26t;Q6LKYt|1pn zL^02CfT)-@&^jUPa{VKE4+A{gM1iO-*v`RwsvUp?B>_rGN>m!cL&O7)Qoghi#&$O< zD@KwwUYpu7=@=F60#9LdNIh#zX3iLe(GfK8`B8u%D`p9zpoVKE6n zvEUI%Jh0p>FM|@$cJypx1(0y0+?3W)t4GN?@DkqD%wPx~&N@5VArXfSPq2d+KZ;E% zoFpZsB|7GFF2EhkxavqtEm~0f4n$= z9qM|etiDc~S})4o3)1ACHEA+`Mvlyxo+szaeDdrY1M+b>#vafOM(E%HVvj(g5-LsN zPmyg4lI6jBlI5;a?8uh}%Ux|F7?VP>=TM)NBhUJddbz7OOXihk$?7#(vUX#(l$In* zW`++ocZ@n+AJlVqzc(nm-w(^l3pH}AvPLozyJT`+F957b^6(>zU_zlt5&{6C5(z|^ z`g;IEL1_YIBB<>UOUZ06#wFm`8!^$f|AN{1{^y5>Lx&E@OE0{HFWnzQYNl4Yy1QiF z+<7u@-dx%K&_nRsRbqnk1Uj33>_aYdg=E@?+)?6%x$l3$^XR<9u;tj?*e?)r_Uu`; zll9@w59RH5-q!g#)sa_Wqo9Ys_OQ;w?Kr7NQ+>@#`xbL?g^hj4mwAOsa_~YA)n8jC z9ESlALkBA6f)$3q_ZP(Js%J6jK%v2$(P#0K9vUP=M>QMXfm z2;1D2Z+)<$7bt(#GUgSO#yd*z`2fMwogoOEV6TO zf{@&lECIYg(<{`jqWKUWTcYK7Lsgn=m1#$Em!O{;%$ z{{MU+%IWOvv}{B!=GlP!`V_`a6IKn5=pn%haPL`IWP#>*@4xs!6!=BgqV7)05|}U5!>~8O z)m9>ar~z!5zGrV(KHEPipY5xZ4~|sI%)A6yxhPeZFU^BQXpzjBl_fclkV;LZx(pW5 z@X!8rKz;)$h~^$FD6xS3%94QmU%yP3`@TY>%+aNZt+qZ}FC3u7b>k{eISLR+BN$~C z_XMHnIrAfZj~(xm|NH-`m*?JV!Q?(casWm>{*^qaTIXXt55O)93>2qw5ef^%4iLo> zdsHII0#PPE!}~FG93AG69?p(`Jc+%>+fJY7#Ds0x=SW2HOKBT+ZDV+8X{qk)YSUAF zoJK6|IL~zC85A>PYp8xv8@}wFBo8y>uIe&@+MExZWzm@ z2Pc1((&GdSk}{Dn+Lj+>U>C&;Ag;e7B>ez8`@0}P)ZHS(El^{<*e(Mt?b6=UDIMLg z0oB^5J~;`KyJXn^!R~jYA9q%y(LC7d-$3bFg$q{0*#&MTGS+!+9-a%2*u zqB5{sRdTu)#)eTgn&)%CB~yNL`60UScsY=4K%{h-T`67RmgFq#vAqYlkW||?X80+}1VEI@cLuaSt zu@PO@h!2p2;1})C5Qw1^S7(PuPD7%DK-8NbLQ-*o*3+}XJ@8$0Not4WgQAsw>23T0Fh;y41^ zP$Mwto{}M1@Y@%A}`gp5W+}Fi#dOEdW66 z0-_+r;)wuwv=UKTK8Hk?64^z&%b$*UZ#wy$J&R3sKHMpL_Uw@($BwG4C`v-pKl$X7 z^3*q;5*jh5dLH|`8B39PqUCVPPF{>U*J(8DI-J;kAFZdWj2eb(1=R3-f^J-pz5Vvv zYSMxR%UMtE7Wkd-d`Gr#-ySWIF3!;h$m?djKt32lZ=LGJ?($&k2qzqcmsYI z8BtoYACgbpP4e71NJPCpEIU3KlFBY@E(B@L2UZ4U`?h}Al1+ysW)Aw7NB;C&j~u*! zz6U#UB{@m*KffQqj@<;J&^_P@LXo$>R3M7Pc1V6BY0t;p>MqLvPDS*62R_igi?&lB z3cKY}B8niC0#WH{Y73NOy{`ShQySknTApH-xO2luG-jN*VNbaQGjIuE0X)X{zP(MRRpuiOg&z<>Z08>YW- z0S3fjXNrt7ckW!7R4_>gjQ(K1lwBypt{7zsJW*0=F;w!F;f2cWwp9&~3kJ&wb`0S) zy}fn{&+-v)A_Ll6`kuoTjg?V)fz0^3-~LX&o~vpews5qApB=m`4K!P16mRfi96pa} ztg&*NkEU~I=oD?t%iqScM;pf;?em%cwYc%}y_URgmNagfkS^Af5mX||rJ5HPhyqXW zMMc`syJ>qn((7hvw;NRscl+@r#s1BW51JaAbzESZMu8{*=Mk!~z-e1MgF|fZ;^Njs zG6!8an^UA49fo*j_>rnV1ib-YIjOgDEKg^#*qQqa|q|3=b?1$p7*46#2?ls3IYvd;BrabxQt) zfhblElXl&n-qam6!B7v6M^MG<`0;-E&;M+Yzr5E9X$we8K-%oF&9DRb)f`A4B+88G z*cmMy3w{NnAkn1`Ko2A$R4PKRnYZb8JdW$!4PvVpGX~mzZ-FR&%%Eys2c%)B`%loJ zq?8g-#pW@{hbmnBs6rr$6BsuSXe2%h#d6cxBp&@`6eC2#SmYFhXdvT^S0_Z^EqJX4 z-l3WZE3Ppq$PDz16jNWOU|S61;n3oQ6cENSJlGGOrwSEIW6Mp*1W}L$xCFaIjbNv_ zk)9xgWx6HO*DdWe0Gz7Zp>BtraN8QBkCH^)y^u@}Ndg`c0ch3J4_jOC8Gd|a4x~u{ z*5~=Y_d^QW&&ghXj)Y66if1}@y(`GZ&UZQDO-)w-gp$(9*m=*N2p|J0USO4I{k4AX z@@bXXe^6ppP>E~mgJ>ou!p71G*`a+k5C`^o3q*CoP8dCb=jo-8h=L(owz*0~LFFw9 zMk%!nD4~xb-N$jtCnl09r&4#E$P6a&c|aQ(Ni38f_OyVN$>|eAa`Z^Qyt%U+Kvab+ zn^g)Rs#MmlHbB(msgQ_*sw07@mtPCX+aHGHTy2lkxAw@|)LPk8P%A|xnUYmHSt{Do z6dk@3*`Q-CD>dh8=D+p!v;U>a>BlsVB-cafGDa^g6c{Whb*Lw(&t)#M%x29pxNqS z%k0$2Qz}jW{s-^N=bwMBHl#Rj{N^{mDc}Cqw{^oCE>_h}pnbfukp7GoB_12t`1a_; zHe>K;((8S8$@pZ;hH~)P?btYg{t5;loH`x|HOm%dejf zV27+E!-sgpmjXnMsVy$ZKlF}s&s}WTzxpw@Z%63?x+%SsO#nne0=9-g6eOZ90iwV! zRtUl7$D=)u=BdmVy}CXpPW#^IvElj@_6Fv{b~3#??nADY_ig+u0a12$WOvgN2OxM) z5Q?^=uL+29_1m}=y3GP_9v~|A1;v(y=i*+!E@HvY-3-p0J|hPY9K@E0rxa+SloUmw zH*MNvBvBxZQdR~#QvjKc9X~EdjvQ8N_1Rh3DpAFkBbkE;Hy07qZQrnA19s+{B~zzQ zQ+2+}%n?TicFTFrfJMf$%xigs1Ca%ycJ10F|NWc)Rv_x1~Dg+ z`@Rl#m>@^v+Cj;orH$*(U(?tM+Bz_TD{X8#o4-3eHq2hTpA~!VP9J;kX1=!N=F#mb z5k)_)L=?W5kazWqA}VNUWb?Dvm#h1Dacmx!OY6QjUOw(P|BB~VOGna(X-H2lP6?Pd z!9Ems;Iz&SL~)YKNrJ{l8g{cWL!G-1@}A4v{G6_7c#j#vdjR54hKOHtd%7anVQyI7 z`EXcHoT-yz6?L+_#4q>XlK}~W9PF5vkFB(|CXUE6Ux!VTk~t z0vPjHAmtBCwmjIR1G?z|T`?i=1F+c)n@%k-Fy4htMPTEpvj+B*YN3h;35wy?W@!gN zbrHtL`w>6Wmn10(Fj5aNp$|Nf0^`4_NvYU{E>$wqVGNeCrMsT zE_P+h(OnWLWni@CSQq}|2aaW>Gj%j%V33Bh14ca~a}{dRF-@#fGC4pLNzZpWO$Sht znnr9X8I=#i&1`>8OxflN6cdPI`H;v9bvZDxju~U~H{~3CKH~6!E=P62OB~A|b%>8= zD34+iY|5M908y~BbT|kgs#@OtyhfJHm@2F0Pn8X8Q(!v|5>Wu6e6Yb*T{|K#z6^;d z7%M+tAC#u{e%TNxlPy^nB(o@0e3K_hO?R4ne$FrF+MwPGL-Rq_8@U^dk3n&rfWCIA=$u*)Me3bJI$+&o#hI7#kW zJ|d;F640(#ypQXXyoZx%1}AFMsh%`NmVbZL2Fbt#bWZL%$ni0ju3wRN za{9A}ABxbubPPdXr8LwK!ouj|Vf3Z*=ZEE`=Od6P1P}#)oj}wkfUWm!?v)vHGSPqX zprtV^fBG|ksPj+}4`f0$FJ1nFK-7=$A&P~;j|HOiv8457$~j*7uR5F$*8+^DywPni z`lMUqEXwoo*oL%IrV(8))>hX>C8DVLkVc6pXyHU9qS&eqgW02{LhQ8-zaB^1ruKL} z^1RjZxK{ecrn5A($IAgxS(t;UL==eSW*@Hi2u58K5M}$TJ>F^!agF7@X@Dq}-!{Ij z3nz`-p^Oqm{Mtlo^)w274x-T&6_uC_)atH!Yu2ujrAwCTPES;a;smi16U6GODgaWn zCDovl2kve}Ac~H=9?&mbxKI`?S|qu7xhihw$99}l(YQ1 zcNt^l{CXY_h+>C`t$%DMVHxyUcpmRrA1$ygn-ecuX4gqHPg{Q1z1WwQy%k$78_uK6 z?{aZ$d>hwZ-wH=tFZYq>^jB2Pivgly>ucN3<{f+g&h^bn0k)U69cGo|0#R6)5+rAz z()e72;*Vn*l8-v}L-u_qgh%T~BbhU`4aF^>5yO{2MK*w(m^62GL}15aMBV}zb*8*Y zPS-Tbn!8fuq5EzPodRR!NwRgbk%)@EUY)|R?EGgvzL;Z9@qws8E&?#-p8yc`+yC7v ze}2Cc59C8filt~2RJWA*lummMFNpR$%eXJKBS&#vr@&A ziA^9wY3W#nc;y4c3zibqOB{oxOPz=z&rIu4eUl*rRhKdp98xmzr~QA;-V@e&}S zX!E*m1&ou?m4GNFQBqra_KLTYzvQaRO14in>rXEU&yc3`xNuNCd)IJ;u2E zSMaVqph zgDk(;;}^~Ec1|C!8AvyV!&7kKYJsR&o{zo09^|xh2z$I9dETmdTnl~2qni!C91um- zJZ?(Gc~I1WR}_fCIC%$%ic;l@CpQ%k#nM^^;5k+E2t-lLmmpLkw$N>9X~9;C^}2f= zK^=Hsw%7G?76clQcWO=pcd^$(NCQ^RXs(hqvH2AgLp^F zbR3}QaLqEu0#UY8@FmVV?B2ag{_DSfqiP)E0a2Qr&XO_q=}StVaLEs!$NRBy+_bwS zkrNP`X1sXr@XO_E^SfLeo0pAiuWyy3t(*JEa}HAEKiUT(KzfO4-erI&OA8)tzPAcJ z{?*IL_F}tTRw61Eh;sTX(~fCxgd;P>3OKab;l&=^wB`bsVr(~DiSj?~Lx_+6iR<=sPE z07F^|yN^9~cdGpI$4RnzlM9H7SCDvN?t)(N95hh1Jo8b2(XB*O7(i4AQZ^?~1m%za zU#C3xA%KnuZ9xsn)`cUoeoX}68tS!TGIl1UIv;^3NOkFq5&iL6C8AgeI$Jk;G@)jU zXS*xt5eq~a)x4-g6w|`F0l;nLDESxv^?o#p$59qE=);3gm`#$>0-){0{GxPsE?Ol{LoGWL5J!ZBwSf7 zLrtwR+zw;pO>NRxRWGd79Su!9+ zlvtD{0T{6k!SMJ1q@Qw&3b6S|0r)l#cK7h*5phhJQ67M>Bgm8G@S+R`gmTp0;*%xX zuG;@BY1mH86=kEhPJ^9$Hq6qM?LdH0C16|KblDqD1Nr7pEbLV^IY+0}D z-IF9AA4rmpAl0CT<*vzL*|0ezE7tgB;oL&Wf&Gn_UTA{NDu6u=%~FP4N#_)%%gTlM zkcgTjTQ*LTIdidFl?9@dhM@O#l88c8FYCIyyQK+bY6L*WExju$%4O$AJK;Z)IkV@e zr>TgCzWR`ql#~F3Fhn(Zq*=KdbA1=@fVDjQI>;(0|wrw&US_RYKDHX_c$m>SCi2zZtWw2ex z4McII?sHyWFLyQbi0k#t+bN&%=x4*P1VoLo5#@B{J3!RcbI45xM6n8%33yH^ z08ZxlGNZi(+UB5S6OG34oE|@@&l;y!Sij;!QXDT%PqEPv7Wo|5!_;4IryB; zZ8%jj3R|!eoVqF?iiM-Yb68$?navIJ%d&Ilq+Kcz^% zaxm}l(wLH(--*O=$G;uVW9e&Y>OS)PT7W1weck7`BOPz{I@$KL<(x=+FbzH9UK0?d zW0Ny0)QJw>UYwBPpOE( z>_oO@ak@PID0a*P5LG&jcB>%SG7Q@+-9xaSS1F(Esg!+(lI7!b1n$!%Eh$sJwkl12 z^rI9=OJL_Y){g~XeYI4kG#ZM@^@N;_=2X|6#sE_3Mgd<2^I5L#iK3P}m_-APNLQ`UFV>-~n}^G0qlb zOkn&AcUfKM(RPmmL~)YJchj_z=>SiPw7KkuiC7@Y{ZKdmMS0I*0N114Nya}%70E_) z%!}KQ8@}O!2P#xp@DDny#zWFKvN%@-q`GlgkXoKty3bM z*d47O(r0~;e1bvp0jT7K>gpwgUClymkbr_cs6p7!2xE7taBmoDF4%Ac#;hX%PT9gf zPe2mADH6hNlAS358BR}zR2w#S$jg@G!a_-b_vECB7d|-ywxTjp@nH!Yhd^SA_M*6B z4e6}xhdO#W2HU>K%G1a2t5eC*gXLW%Fn)NnpEP+S4b21e785ea^aeh|08uIpg?R;c z%;PzYHcy*AT~d-$Aq@hVGL$31s^)2GBqR_;{$ZwYq=^BdSP1ej7yeuZa{+JKkH8%v zKo&+-^pG#nEZxP=$tmIqAvQeP82?BL*f0VbxA`1nU1-(`((0Ls;Wlh**_1+ivXhPFn;v*w8^rfWLY^AJK6z7g!wILhRvxn)gw|1 zRbaIn209H(K!(t+e(;zdWnG_kP&QBACG+kYlt~L_O75JQk~XDO{JF)_)-ouq@H=;T zs?aWP$}ij6#%R9W!2IdvK}^~ zHbF&q_H68gmDY?LKS7Rlnp3;!uVlp*3MA>HpS zB@5_>H}@C{T>?a*eFyQ59mczs8!%h|xb))R!}7)lVJU9|c#d&xBUJP5-Pk8H=VZu~ zX?ZXcl3;)+fL2(9z($l`e)LqLJpG+Sv^#d$g7@J;2^e3{{o(lI0Ov8~8B@3~dg105 z_xTsi_jXJ_mMzBiKMc*|0#WHu&C@j=ZFcfqYck@|o|9be^Xo}I_Eqh#PNp~NIoGqy zH)~#QI@ z!^XR2+}Jn_qqE`WD*ms{H~w7{I*~Y+OMk21vvjm{u-EP* UviVv1#9rI*JI61N z0=7*j+7>oGOL)yd6jvFX7}9ebQ_mbngY9h_Y8I^+qx6r{Simn(b!usDk*bOw*i^}u zmp{yw=Kfac54Ont%hF*yHeZ&lNRp{jJlMq%V-bL;uFkOR{NSv7^uakfdNxxI)?^{G zbSX+omu+j(<>?=!$@+Vebi&M0)7YnBX{BAr+;gg`>d z>tHGDNmno`ZkZ+$7*kGdBbL{Br|7!}?;p2n9&N@jd^&)L!lFWzj%7NVhL4>He`y@1 zGZ@4~N^9bf)((imJm^R1%WJQrY61hocwf@7nzo7X@n3<3WZ2xHPr#0A9!Z7=0K&Yw zdL>*|ErXR8CDPs_!)?9N4c_YwhNP#qUitw<^>#H&-*6Y&Vn|XGvLxA;2GuD51^xl) z#yhYF??8V-2JS(hG82Z!i(uoaI9GC}=S%jK0!f=xD(MBVv6Pmeo+@l3py?2Z5e7ey zmVVf#@&SP*IK$FYxCl{jW}Tgs$2Ow9&!g=@q=6x}_G#qr(N!taTBSdejwuLE=@F-V zpQ~*s0#VR^WBca=h?)+GsFb8Mh~y(@@G)&K!Tgm;$6pj%RrB}=Eg}Fb+Dg+4Qzz6G zS5P-|z$hb!2Age^VjCeHkWT{I2hvAuSLP1W=>QsGj|)<7C>k0QZ8w-9ovlf7`ZOdU zj|XMP$7S;2p>ioMD3w{orLtvhvTVB-lHs#q^dGy`)m)6opPz&MpZEIZA|%N>dpcwm zwx_-e?Ua?~m(+j4eOk zK1J57Tnve*0=Z`uc0!&B8Ye=gPJt*>mKzO3+5T*7L>YTA{E!)f)Za7DJfog-O-c@J z-n>~i(OJ4|sZ5zNMa@2No=R0+e)ROg7{5Bpy!L3xs{COuoMXJOm?+odQu_nSqvHs; z(E?FsZ1DnsIs^&-kLBRO1F(;DQbGXZmM&W%%U9kln>Mb;M}l?#6d+3bC;G#vV-FuC znu1Wcbc0c`Kor&T_%VdwIhPIP<-_vVzknCt8<0x8JA>f;6*GHe{fb_hw*Y|X`~o?9 z#y1K?p%d^Ut8Vbp*uj-#Axk~b@KyJwsAQqaA3u??Pz2cMWZPOj2FBYUzrqia?&tf zG%gb(KC__b7k}M#j#+Z>aOI1j_>KwPPO}^hw9LyWHcw;7juKIq0#S^|G`5WPnnxQJ zo2UDFym$;B&)Iyh_5OJ2Zl~~A8r!ux&cg_OS6;sw)Cf zR1?M`pJ|vsJx3rNg*a@`bF6a4ADn3rC(3qIF-H}1;B7da?&xoCcSvd~nlTaX#NsX> z&+h>+!|mIl_Vn-yzdZJMk}O@GEQQ4>Fsd2Agvo;ibO;7^&&ZA)r{&c7G;EEY20P`s zG6QNf_pQs6Z+;g$?XAVO<9HIiRv=m$UgP=K6^Jr~;1r!wQIzQS=egnR zXc*g87m2vf+xRhyRlUF!|G0QG{n7wYFjTHU6b+WcSUDx4rcxq`yXM76L?Ii^1NEV* z9*coTYFWofKcUS=JOH9VLsK@i%rHQxVcMGG+y=cw^MFJYRN;(c`}KoP*r^bp9YM^< zFhGuQlC(GbJu&FL{Mo(%Bu5_jV4- zu0vsI?CO@zz8=X*#;#y#8L;I9+9yDw4jUcx^uq&a>%)TvK@JTqRd?uki5B5BxO=A=4KpwAgvA>(jPiBsDAIEdinTpl{A5$GO&Q3GbK~DZJ8nq z7v#yF&wAyP1HIDNdQoaR>SgupLfL%J99g|0Tb3^J0o*}7RU(R@opD|PfF6OpyJ-8` zJJ;uE#{dFRwY9YpguS!8ynN-!H{X0y-hTTnxp?uS)WOsC=*Ep3WcBLR*o}FGnt$M2 zkn>f}JMBDG-#doQ#uk#S8tdYP#m2dw*G{=uW_oof!`ZWE)i&1Ny?f=8Pd`A(&Z48h!FGwORLmZ_e3+bTeeu1O$@wxO66 zcL=SlfbF!u0f@o}5i1cjzqmz~FMz*0UskT3CKt{n%5VP|lznH>ZvjH4r+DS*?IZHU zV-ZNmrb%%zb^&D{0%UBS$zMuDaU8N^kyGUBc^Fgi>zVOwn3rjo(Tag~?C)$a_R%{) z)F^3g=QC|{RL~yp08w8~Yu~&;lzU)spF4xAP73hS;0uxyLw>n8I_wmA=7bNEM&~}` zP$XI>wH#dFG%hBEoDe9pAt_OaKuD_w7vdf9eldF=T_+rY+W+RFk_ z*v?&zm2+VTUSa<9T=Mdd|LQsHIMOW4)0r0Qk=Jy9X7EdI9i>9BJ$u`LoITMb#}2j2 zJG)>|^)S?`V01h;Ayu}o8j-I(F(`|cBun0;JZ$8U<`^~)${TN;k~iNzCFd%V8k0V%81~rH0UmTFv zp_*6IR3|;{7iIdSklZyRDBJFvA&)-15UOxccY#DyL?xnN<4=JoO7g%v(jq4JYxs3n znH1oAgJB%k@ou>i5XE;7o#mHH_{$L2Bf$CLjW))XH0{iD#Nq$Wq3}$WKJoP+``EK zMKdHhK%0*QSB&>y0q2ERryv>%9epRWSHLOX;iwnR!8zA-fMg61MKFqvH|=7N1f;iN zHX#XZ@8LAAv#M~kwS}GtTH0Onx&hkI6OfoTb(+~V532Z_k8o~5;E5!rT{o)J@tTWa zOh$C>G6FD%W%fcc$^#!sfYglFN*rON2q(+P0L1?x@uw12Q1>JMAs|{(1+(xx9aj(< z8N$6mue3BowV;?BN1 z@9YHEnKA4b1_P)#Dk>rfC>a_$=iE2G-(Q_u-M5cYl$ADAC`4 zXXyN#Zw)2Rg&9%6)6pO2fT$Uf?TRyfIe@5Xx+z9+FGh~~B~Wh|2P!3X@7<kmK%mx3PdakwOyk7Gz2t+06 zrgg-DP&%1dRM^6DrRdWHLIq&EmO6dXrXdm00}!=;Z<~GaUZ-t;eZ*efJBnf9N}E?$ zY4>gk*~5=V?fMnjsO1$~F1B_84|^l_-18qhFzU$hd^}R+TV+ADEvv1wJCTTb^c&gy zf*+`j=-Vuim+|c&fs{)IqEa7M5rhfVvEX_fh$650c;aN#o_THzBe6qv6t~GOElpNm zGiuj0j@bhOq8?pk4GVJtqWYlH7_CaG=3yr$r06z2Q@<{Qx-R;6y7n^P-Eio`lyP@J zRR4hU&f0_6zTQ1D((6_8^v+Qbzf8+t0da#eC)FqV1}$_4Xd#@$m!~_b9~RJ1xS+RM z9Gg&a9vp8b{ntMy`O8r@Po%mP@Go}&rP7gjlGKx2l81?7sAP>{@2dA~i*@6kKCP$E zO0fx*jy=Xc3^ey+V{tGXw!yK8Wn)V!n+;rgPLZYOm0JQEI8h1jqQuhW`7Xc4 zN(*W&t)bXL^(B^vEvSMr>_Nec*}QX|_q}9aolP>@oI1Z;2Sx9oo0Dnf5_#C!!qSDF zrGE~vodBXVSAxx+DiSgMwJ+7DCmTYJAo%-~?088VM%6(dd7n!vMrwH;h^nltum$xC zl0Z}vT;h>5KteZP)eCKQDJzbeo!A3GFBiq|85w|4fP3h$Aql4TD?eS1W?CWw$jYWw zHmA@U0t`e33dtnQaS<7N5?xf8;)O8z&|2&1l>7Op9XdK$ry#S1sRY$C~vNY5Q zGtOFh0rumtYZOW^wX+@h*3_S4T}Z{niRe}a(b0`Hi1w5UIHZm)Kqx~Z4jn)&%!REy zyU=7UhM(2$oXh}->g$eMUr*e2z1?gty>`;}9SqxX z>W)*=jq^%uK~=7GbalJfHxjju(U?87zTCd~M4hc!lW#Ru=~h$%uS+ctyJo={Yu-qu zRFaWXzUOH7c%U7Z8^oK69*7Dv7v$_l>+6vtN9@SqBlg0JFF0e~nHa6Et*y3A8#md* zk34GY)~$1Zm3Uv0QJT*e{Pvu#oztaVZf9oloTppz=-cfa24N%X_19mw-#__#Y$Sc` zY@{t-yx4y5gCE%UzW;qVgaEC??~(vh5!0@NGik>R^Ju+uOnRRDo_w0aZc5Y2kk${@ zG55m-?Q}K@1w@e{3t;@jiG=-5K-9}4cDxPyw0(HXEAO=H8#<79tFe3TTVzL%<=9Vu z2@rJva8?BaME&57VSDJoVY_Y#Kk_WC28dG2#H(5l)XrcXO11TNo@QTuvhT1;NIk#& z60hASH6*D4dg=SijTJ+6K^sx<%jc<@=bNpy>1xk0U)QyI^xq%;cp)IldCi-%5j88U z@Z|uarddR_NQ{4+Cl?Vd8k&f@=Yl^lLB&`uazokOM*uG#UAPbX;ECYxH1+u+eKyai z7o7N%Eom%)Q9E`Bi2CU{K$OZ!EyI`V>zVDN>PoF|w#&a3%kyKBder$i5QQt}Q>RZk zTM8u@&Mz*;052b>1yj7{O-Fa1=8xAR{l18O@?&|aZA*Pl>&AJ3sH&ty6l;l|(fBHA zY4L&`?!uuC+92zrN83nkCS^@R8(*ztO4r6TaG@PXZ9pH*vN6(wJLx?iw%U8|wcD$2 z4A|=*3|ei~0$WtK!0x&;+wOlbWQ&(%Vz(xXUw1J+O)T6 zHW%8%k7eUVU52Wul5p8TRPgwD|DF$sQg2mvQ&Y@d!j=51uMgS&Pfpu0z^HS9s600G zIG_NCQcI;imFA3eKCa8$N)f;Yz4`KS~|eWf`$cF zgTZaRm&V^s$%6d+_Wa|or`8i(C)+MU=zqW-6IpfJM^0r&DZ=1JI68oXXCyEsa7XHQ zP8CSk0!2vE!wK3SYihA5-t7k3dTano)I&XIiOoo#bz6UTpQR7StT>Ws+1T}oBHa*< z#%vJ&8vs=pjp521Fe1Oa*oyFUmybkHR%xXb!1tvKYODzFY$5E9g#fCuO5s23rljX0 zX~za#l26*2s(k@}Yg?was%;ktqQ9aKY#;;GHa#bJMAwog^3sFi2?3PBTnZlZ(oGX} zO=|}&Nhe>`I6qOpB%*qtk-#WnH6Gy}ZO_b!qmro3kwbM8gBH>+w_tG1dNVQ-x7PNUHMbC(=k6%t4HGf*~~lCXQiWIft@~QMao_ zGKzaiX(tkCN5DV10Aa`<0`o-RF{IuY|54>bLMjbo0|rd!N_DD*Y`WzvNNTC_6!@S2`JcA?z1>z)Tw)6w7TOPg_(K;3#3?fL z<7?rC*Ssrlcras98hoB2MMf>HLi|I3zG+E`C;`^e$`cr+j%!UnaUyQN2Z(xh`!GiH zk@#f2udf)jmGwByxV6IWxVsLoiJA5@RP)|Gr1^mIDMEzbzkSdi*fuy0MCAZZh1?G& zItKiz`m}EOHJOXq4eEvuspmdz?l?h#schrvm7D|T1)_?QHllbZi2po~>*&u_N$UAT zrB{CDzbCG|q`4AA0Z&hVyciHQ=QVG3_~wfXM5%vT1pI<9O@BSJC|~drn#iPke)8+w zN9FK~guCw-Ab*^$zG>2Y-M)^Anp4gwGXSFEP9o|jKl#b$3Pky~`eRB<=T0v`0YBEt z;`vBN2So7;acgU&lBx6fu0qR$% zU}=+|VDsC{ru3O-4%ySs9<&op`E~?JgvRnJTeq~XA3qL>Us z$v%|8sLKv&z%;>)d$MsFcLzlEArZxfOln$b&{z^NGX_1KFdrB^4Rj2gF9fNx^^zDHt zZSFh}6{H1u1o9~QAYcmpRnkPKWML^~`llQS;~#Rz$dmbjoIJc$+CT|+L#OM!r(og0P~205UZE?ox95IM?b2z8&>53_Q96|?Xaf> zV#P=%H}(Re+o#n_7DpXQ6En)-UqdN-@hO>OY` z3lyufT-U+1rUW1|6^_408u@*up(wF8sc{AmNL8J zo*ICtbo=SA1VphyqK23auYdo}F(jf!ZE<6%EnbBEyKKGTB)O{4nk>Azt}+3bc2+V=9$GMv0&)+ zFF zD0Lj!8goEY6F?NdgwF(sN-bOToO=CLpz-J3M?a?iIMXrk`Q5m&k+^h;DEP-coVvjH z^Wa_p%4j`fGw7lueux5q*la~3Y&^r6Y)Hp!_d9L&-tKmLXK%l~f4JW^ty*NaZ&+*_ zZppXxn=;rS>*HTMMg+i;6xCCIIBb7>>ad+`3)!jOG}Q8H?UvQ`wq;X^-M$r%RM!JU zQKO8IF{Q#RBpk7yVd@9ISws>z~ltrkPoE($<3IM(T68qzzN@f<#=G65XYk$%Ey zA!=Bo?DO-G>d33Bu~6v}ODkDw`8D}gSeI#q71+&=V*pJPKvXBdZYRdtt7}Vb(c)?=ERgCI?c~2)wrAii zOJ${&ufD6LQqeQOD4ApGM2)Vq6Wdb=E%o<6Z%`hbvDtv6PmsKe0Rp9G0sPZDJ;}c;|WPCjkt}!fUF2(7fI-2SE{yZ2Qj2`2E+kTXQ-db719Bx zvgap(DEd#^iqf$omD!JaWghRfA{z@2SbO(L>mTZH{1&0y-cY0Ur!As@fIg*}?Y5xc zjICXnZFk&JZ#S+jLlP*>%BvV9vZOJtqX2H=sjiN&wY4DC`F_M+*`BZuKLyMI=!!%K zEEA^5#516iP@ykR+=WEcKUCXlB%*RL1`X~3TS(POt407osSR4=g0`qrvl{}wO#!0V zWH@!)>KfV^ILvu{$LmPH@4%S%hqiD3J}W3Fzzg6yyJh1>Yzp0ujjNlIjS}C9X33Cp z>QXdZQ^Ry=Q}fKiwVRW)$E{Ur7xgO5f6ID0yt(U5`_-?0Cdo%|<5S3hI9S9Z1yKEYuYBp=v z$rIR!0*HEM8X)SnJIZY9wi;|?W!O)CA=SJ9h|0-Nx4*w9WRE>;c+$*;M{?j-fPLo; zQ*U>*QBtAue5v_(@iw2^iy5SdUp^zAnL%s5*jZACK)M590 z%28>v8Qfe=7N~Py-)z?LRVvHV(;sIHM2Serx#oZ6DtL zF6&z3nhHe8i;jNz^FWk-4LqM}o-fyvZ|b#ApF3VX3ivVg$C-|S@+&I8HvN|eM6tlQ zjdrqsDeH|+wLcAHTeRsGl7JWlG594l%fh3XHrStGr%#R9yMJrLNN&6B{j>{1!`*iG z`s?kU+m~UJB;Rhp)>B!fHr((l1xv`GyK~H*{OvLOpFbS4vpo?z(;voz)_l8T<6`WY zl-UMcqc=24H86OuYKy0>-K3Dx-bv}H7k(}EX;YukeV>PW>aP^5)LN-*b+Iwu`%%Oh zT7G2*9=|ZQ+)y32Mf?(d|J{xD#3L(h;i5c*!`Mh;AX}}}hBN@8-6;msTcn1 zpP7=&@rmwH*2RFRan&1r#7+s?glIg*gUVArpQLktDPAL^=o0V)7b#_u&4rLd@t_^( zLkL6J($k6}u@GZ(=%g6f_$L6N5+5J7fwLXf-aBIbz5N!$_;{RO_=THjya(e$sND?# z001PVW7jD&*CJWzHU<+6qK*|oWvXn+A}e3oXxSAjEvsS`$82KU@(`$z)Jq;ld2;~~ zvXK-`YIX(Sm>Nqx!TixVZAwPh2|At9HJ4cizLn_c<2su})!YN3qbMUFA{cumBeUWD zx-8rcY(`04&j(3ENfIG=UPojfl4$|G1CAHxk5ibol3#;CjIy!rgMPiJ>2&o)i4mkh zimb7bUq~?q69zlw+lmf=B*k0Q~8Y8*O{ltra+q@Iux za!p4{$wJHp-D5l)BFF~Y^)J+G`Dq=Nmp+QRoVuFB*jHI!ycCd%Jg5yWNN=$fxh+;+ zoNvYDl^Agzv^IdK?*2|24M%M#oMj!h+s};4j7q^&gd{|d5U8!Ym(YJxIb#Iy&Sd=_Vzh1c^!RStbs+$?ILJJ+lb$~tJHq@ zqe@$~I&U0^0^(r4D}z=jB;u0eqsC|rneE{DbzCA!K$Ik+YN{QNYF*g((LNU?E%eGO zuh{75s5LHZw42u5WDh<3Fm{D*chW;yNwqcclM7Q9S)ZQTiRsc(@6Xb?Tk9a7pLg0= zsht7e2H!pU_IdZ+ckMU-{TnCkFWaZe^Duo>Tyot~yKd{EVOvoj zvD@ybuzT*GXU9;@`{^%6>3p^We(@L}{R|<{Z1$8Nsc68h-aOVa?*l zG_C7rn$EZ=!GnB6e6_!mjVPy@=ZT{EMwkPl0yQE_K0L10u-NulKzAhE&b(7n*; zye}`64nEBvQ}4~4Up)%=G4;nwsY%ahye=Dva+{}QjqYPHxydC-mvJO15^TbQkJbqw zN|FpA%eLVG43&4J+3}-e_O^hi_uK4KY$$ztw#l|`SZiBvTWcHE7qa=uvhqso&`_%E zUW}r$)82~u$RAGFpZ<6fH|-N8|SK{$YFWFNf`acO165@(iS+GHl!34M;>S zwM9$wEhA^t(lR9#qpwHVv&rQz8*c^QPTiVm@Xsi}e~vWAC%Q-4#egWycR%NSwc?lY zGL*>1)6IF6$3Op!%BB;lkhH+ltF|!0ER;V@_mV+p?ovn+8~Zp0$K$AsMLWA}5HEK_ zt!+rqpxPCVSYAiF6=Gm`6m`P(v6%G_BRw+|K_G_vJdWuhe4m;1QCCK&z;dt|l+PMg zFdx_BfK4%M@}w1ITlwNeR<>x7Wn!Q_E3X168l;|b00c6*573Ya&>#@X0a2W*y=tQ( zU2?(EM(1wabtH0M{h1UT5Eb;Bt~(wHfLZO@m0NtHd7_8?PTm#liV=Jl$D?AxKszRd zWQFd@U`}a67yw(6SP(KJqt`);9L~o8NW&;lpTkZLI&yUWGV51|0j70&W`uRvRjuD60phLSvKKBK@4moMXk+A|BA>Y7o z7$9m4l8XxT7U;m43xa|ogm=%dN29THLK`Y~x4Ou8T&Hwg!RaS?|; znshQ?Lu@FI*~-Q-tE-9eK}}Jp_Q~k-(bHLWv>VB*!MH6C9kR7Khpe=yzzT|M<@V0T zGVrK3I*cdFVLQ{6u;#>dcuKt9@v|G`7~)*9c3W7KZp-Vd?8cS(Y}n(rZoRpW_Wb-@ zyf?;?h?31a+C#g}o?)Kvjo99OeNGK`-;qv0uX1cwq4KApqUYbay}Ktj-fGiw`qXI` zw{PEWPe1cC;9`rD6uN%d_4fGVk2^KJ@``dRFUP>YCWIDQv9B1M|Kq{+d;BUmnJ#Tg zmf5&;?Mi8rUz-F(>7M)Up|2l(^pQRL?6XewM4t1crhMm}cM-Sp?pcE**jkgFEU%jP z*#l8p9VS9RUe;QYM0(xzKvZxQ$7>!6bg0V8uAYFXrV|N!@{gnT-1ZSW+S-luV>dRU z25i~F0o31XZ0kLX8Sh;C)vv?$>c`AKEfzQ)_{PRDyYH^Bty)=PD^``@pg~ha?>7y& zhFVgXfpLA8pfvHoBqs28F7xO+?~j*R%va*E)VZe)i$BC9$$9W)0;0YW<8_rg>BgQq zE(S!&CgeElBu}(n&Z*{I+5lY>Kvb}RU%2C*v1XF@!X;h8T^Lg@Vf`YsbLUR`+0TA{ zj*Y0PrTKPFO`omn&$R!u)#%Tu98asMW8$xM{~REyq|`}86%`AJLS5n_K$N}}5>9lp>1+9Ik-?nX9Xy15Zm91Zo z!R7fGR$3~_4fic3yu`&x^ik8UFsKLzMv0bOum#{6(0~gRnrvt&&6>}cee&t3J^4R} z?5P(HT2)D&)tBeleRnRfM;~pprPm`JQ540{vv%Vmza(P<4=w?zy~dthM=zLMXu_X}A-YEvk?! zgr~^Q&KuJ`#L=k5d-^Skx4SU*>iSQduwLQ_QX504-W3n`TNN=H88bK)=@%Kw#{4v( z#$Y1Th5+cNY)6HW z_KE1@izca`nQ6c}#54y)0SZtb-EtvlIvK^*>iGGBn1T@O%_!CJg~nM?T&Yrh(0x^q ztR$Hn08!Y*vO%Abqc1~wwHd^Cx(U3@qDe?aIKanm5QFk0&@l$kCsnyoB$Y-+6WD4( zA_$2k&1T_%1$h}(R+s_Uo8X6usI|4mt)o3*9i34;Z2=4tN5@J5u1d)>f;3PMz=;6g zVgM@meX!q#0iNO+*w(_JxWJx4Ssm9Tkz|vI<$xv;j-dV`xrPOJx`aMof+(ZQkfs;` zDTc~PI>{(F#agp8@FX~xfeKzmp>0^2Wp{1Kw3T?bn};1aNhiJaChD-eWA@3ZQESE{ z=i1PFwjpmfp7jclc$;rIW#yJrQ(!%Gc+bIhBru1qC2_qCrvpU6mwB0Z9Yd`y66p~> zX%)GJwyGh^9(gcgTkqr=uZfk|4jYX{0Manz4pU^p(}MtZEiG~EMfKV9e?4Y9-fp+v zv0Cy0ez_2`uW!k*fBDCJyYYrh2SjC~nkQ+fbi548^O%6B2!Ne{S9wI1VRXHl{rWx| z?^l(j=z%ENNfHnxi6{qr0nYUH_Tmw+&t81-MSJqeC+*OoLwGnGwz|4Hd+f1C?Y{f& zLxppZ$ySsDcqq@m8z!;ubaP|6v?PUQ^WbPEwiA!>-+#mS{(B(m@ZrO@bH`5G_0}%? z;DZmai*?%8Z@2|%+?(yrJGZ!)pDW}20ndIuKvXKxv^r@fCEvH4O#o2=1;b1ssg61z z3Wp$PPA2TBKabh-08yW|bX!|jkIlzx-gWgIyk~I=a`!UcsfG5N-$m`EeE?BWA`Sqy zt?I$~M=uh_^IXi&*SpF8&?2(x+OIP~-Oh6#sk0VRyPkSJYZY8W1x+P8^h%uvb3oKJ zG}bfdiW__KT?mLO;TIg)h!X2K_DS;46#-Fxp8Deq+IlTy`BDQ>U-$ulF)s#0iQ!W} zlKcd?T765c>uS|;t(WV^NVJ>`L`gL-@S0atf@lu@$<(^ty#~x zF=HbYMHQ+I$rHsOEzM>GL{Wx9;1Nq3CY=W@nE;}cpkJX;!HEy@am=O}iJ$&%>_auB z*@1my_Udcxw(I>C)MbuX=fF|B=hlsO=hjWO{-$DEdqb9$m9ryc9g;LuXIGTX0`@MR zZni(a&}@AJ9oCDzmj^aC+PA)Sqpe?8W%Ft?@c5W)54G#vntZ>GAGIf*QSc8=li&51 zf?S`u&-NaVT>u7bF4fPGkqm2XPPfBH!uGpA?6*HWyWgrx3;8v=(C)mo-tNDz(XL;P z?V8G{mnT2yS{Po1?Tn?%FT9(N4E625Xx3vR7X%`SV!BooAf++q+~-lT$sl^hL&J`@RFxA%^pA2>RwtQ|z-wFrWP|(y zuM)JFt*9;?ZZ$9fsMG_f)P>P+q=0(xMAz9pg8T808AcZfa+uv&{a}aNbki_&r9%J3~(?42pB^pZ8Qc574?!_YAl;r zNj=Fcpt_C3Pca?|O8|R{b4RTpf7B|=6NbHL>~x_X2^a+n(bj~u0f-$q9=9WaV@_X? zS~o3Aw{7=iB4Lz+k$t4HQ1^ZH|a-H3s8K_rJ3-)4un; zEV}_C=*6XgUSM#*XAHX}#exle+<~Fu8Ng3KD90C&YCKTRIU$8#Cf%DRubZRPaUmc| zs(6a;{Ouik`Q?}K47i6i?68~fw_>n-^X5%<3qKaza`Q$pUl2G3Je<;k>Do12TFN7{ zb?V-WYLn&^{~cgPzg;?&xc3|&^Vu_Jof_gh@6gv*UPhIAuU&ura^f=7^B%%m;6vC< zV|{U|dCW9`x&UmMt(HzMCm3%UJRXt+^GWXVd=gQ?L#aSiwt%Qp33zhUUU+rXK0PyN zEnP!ai4C+x)o1OlyXMXN&E>eiN}5k?M0mlnvX~>rUII^`~v~tt)KvZ7cZ} zl;ow5U@a;lYakJo7Gm9*6ntYRC0^b|D!-(jUtVd~_EV{3*SVHTE$*C)-!B)464Bf| zN;xWRwt}CNDlheXw#xsimg8wTV<0Mpf98OwOXr$7AnMX-HuEQ7&Y1vFD$p-hege$A zl1t0!>$$Y2=5nV}z>kq=ITeU1!dr~96ID`tUK>%VW$9ey%#F)bs$9Kmjh`RG%c(`r zx-m-vQLW9b*4onQem&8zzGdY|L{(Qg&lr+)QSf6tE)k`V9H~06X-e>mJ|(hP1bHWb zsGxPRSRcYKeQfZV)!B0Z06+jqL_t(DFn*ki4Vf%EeImp5?HRKdUTU`;c+MLQA3@^c zsNH|ZCcF3EO}1uDv8`H>Y2|F%RP@L&k{az%>{*Q2GkI^F?ngF7L7Pul*Ob~)*`m5=Wc(@BaLuRU>J(0I7;wZ?3nkcQo3vm3dZG7X=s*fD_pHk%uzG zGbXpmx5XbP-<{FbWdl)8vMr#W{s!|rXvjq0)dayAfN;VKAf}aLr zW7ZSR!RuM6Wt6VB^wM><^3El;a_bVyDFnqJgz|u7O5se73Q~2-%gk_5aE;`FW)d83 zlA2Mx?_+9u>bV1<$VZ(4l%<=hFSSmMxyGA3$`&-!9fSD|MUhTO5NRwxl;$lPKs;MH z$wL`7=Oh%*28cq{P0tercgbQ*T(-54DC+2l+p&`|JJ}Rt(}_CTS$V7LvePX9f8&91 zNfZLI0I9~1ZUR8;8_RbRXBNi@RE)@6pXkf@gPg#x=@{6TM>}WF32`RCLKj_sX_P=H z#!k`}p^Su8V%Vt$K(HDqr78@8S67E{G7z%sR)kQs3ueO**-xEL*pXv+?cIePCTy-* z6v?S@w{5|0(<2XNqC!=O(f@KA9?G*9UWnSOJICzMsUB;_9!_KNd$z28w_OJyd0kPp z)h$?VrOR%%mZ5Ze^3N~Xi#zvWL+mz-=WMa{)wy=V!W=u<(Pw`<-45#pAR1bIcE^n& z+qfYMublJj*3ETD(E-X41r}wb19BpfmWburk;4P_+u!fCXJ0sNr}|ggV0488-6{b+ z9#}_vpGdP+Yt!j(242}T=OyL^Jus{v0yvdaRERPmQZSaOB)-tO=Nq3#yfjVl?~U%R zZl{VrokWy>Op;K0-rr-pcJ0FZ=MJQ1TLEa60{pGEhaY;(9)9pq#|}>VQ4jex_`3bI zFEBMvYT8vecXNk!xV1{86bPk7IvM=CPhJ6KJLUcN-?u+J`3KvvbBE2Vo9E(pzxQ2J zEarPCija{T>1;>yS z3|mpwalqN*cK^2d_VsVCvX<6j`_=!A*b94-KvZJDwk-VE)~z~#=i1G7C$RvaR$lXh z)kPdC)lqmB5cR5s)UKzVU$qLq#0C3#=a10K@qBU~TnP{*s`&4}*``qNo(oD%J)iA* zzG~%pTFwZF5|5-1NPKhIs(F5%`eRDD*YfEc5Op<27w!~83XIyxOZulj{n@x`p1g}F zc!m!)C==ILt69FDt5yD2q1@ClyHX&^kB2{g73lYQ_tB4^KVE8k^qj^^QZ46|i1I*` zKH&N9^7G6jAc~5eM3mCCAr7*lmdCm={sGN~e;kNPXXBP*z3o|c>S!h#9c)+p^{oAM zU$Yg5S}{D_Vs~x5$?m*soh@HkVAm~1YNA-MMhLY$Hl#6xU305TE|gaU}_AGTQkhz<2eTuem!QL7uUq4q9} zk0X83-flVFZ5Vm#M-?xDdQt+_s30z zf6Pb2Yo1jtsj#ZW<(84HO%vV4?o%QM$SG3*ne1<&N`+KI78^>44KD{Y3RDI4fchsg z1xJ;UyyEHLT-TFNgT4oe6MrYhO{D}S1<%>|!R7ow;5$r&uyV_;aL zBfuBf_a4JARs?m`!NI7tw}-LOgy%p67SI|4=wXA1gi{R3vk1UmcQ?`>t=ZPriT$U+ znDy{XSMMMahy#=@x@f*&lo>E9f*4g84|g%f&|+*dvC$ORZ(S>1?dWwyX@>V-L!9Q?WHJo`))Ikv;cp z#J0aSYM-3xw$_ert1bA%7S()e>#oO%!SaQ+aAAWL*ECpD$B_N{zhAWHUfBoV+>Xhq z+w8W*xpwoaTd6RrJrq8soH0BuDbl2J=?QB|sOv8cS?iYogJ6Fh+Hk_^dZ zniSfJM(E6*(o4;xn9kb3AV_XOW1S0T9)6y2*|lIb!d;9Y{tUJ$A(XKsA5f zJbUEP$L!IEAGJc%_Y3j5B~?O|t>E~6yvCFh-@cTjt93f5Eg}tVn*>C${;8dVcy#P& z?{I2)zy5!}wwGRd32ERmD+3_?;SYakfA_<`LmjgMdIwUT!MIEi*w>?eoVVYX&`H(f z7-rHl5YAVr^@$)-iriWsE(S!koJrUVFOJ#voujt@=pcMKh&t&htIIoS58mHk-~RRu ztP3T~2Y{##HNV7L zOpZS}7jH@m@-(WaLxV$@E+}iO6oU2)09C^b##vk_9~Q0n>BsB1Rb z`+1d-N}HLq!RMa@L}B(oYjvuza<7_~TILl4QJ>*jpW5!v^L!47x|-By5p$kK0Hfs6 z_oqMo=_DY^GrOAL7mn1l*>0Mz!yjk6{A;zmsbk`=MaRnlqNdV+>h-ls$1hU9{22P< zOvk|IS6>83oYzLw#egVJ4EI&cLZM^wg9VKpnT>KE%KAG2L`i}m+j?5F?Bt;=dw(~E z$6r2aI}V(&y8J<_D;eaYccpE)bEPd=nr90ZV7mrTNmhEgIMYU2@fG?0Fi@p!dS zznbAW4Esv5vE)M*wsUepL(*jPX&9L!)V$)T+J%u&Y1!9qEgyC8f!xjW#1Rk`?9UX$ zhOGkcff)cD9pP;2j>zT{wtU51GL65mdleu-EojuHhc2v~*F(xis zPi?KEw(sLE)TjEe{{;7q04e2^SXOQcMvF%P_IgpZ%dobAGHZ{ZdMD6G5mm>)9*jUG zqWY<^7A<^#+{RapQ2$65=;WlD0H|c&Nk+z_cpGzSw+X}9mX#psRG62JcgQ+h)L3Wp z>a&~;r?QHK6%>&NkSQApp$q^)go#j@lr1RcEaN88Lh)24#=CMULk<*M+oBGLdiwdW z{omIxP(K0?g{t6|6+`y52ZsT5N-_Gs7*L_ip2il=i!Wmfrx{x~Y`jYFm{(uc40tr( z?%TG)mNr(>wro3oyv2U;s~1u4-3MrWhvgOAZg;QA#q(w^>Yi~sgI%mcN4xF4kI&et zzClz7b8SA-d|Pj+vO6|c+2Un`ws^&WWdm|*kV5b%khwLTjw9iD%3j^kWuF|YwS%2C z+z&!c)+ucB97d`t*S`KWyn?Q;#$Fnrb-I8?jPwI|g|KTDiWfURm3^}0a_S23EE>$~ zRDKhuk28y}ZrY>PEXA1sQQEk6v~}RobT^V_FWBC_dr>zY!Dw|3wxS*RilV z?s=9O=U=hW=M?-q&aa#Pdb~N1OZTLLIM6@9du5OP;upWLXP$iquaS8!{^&C&*)ZpoU=$g-GwFuU>yI9Yk{Yt4Kedj@K>4&@^O6-@HW204{N&NM z;j1u?b3oKgxbt%Ju!wmeO2*26@{^x9AnM=#?ccD;@~!cOL&b~PJmXDQ-E1=BY?d`$ zTd%dWspFz+MS)OrK-8CWwEdX+qk1uuc`+$JfJ6)s!5b^rw~WdtMTM-gsuI;aso02D zl%Aa9(-|vwFCH>*)M=b@9qy6bz}@0>-q}5DAMQPC?;SeBMjI6w3=4nfo<;W0 zKU!lq-dJh5g-E>Q2tII)Qjho-1b-aAl}w+}Vf^7Bx1*!4f@2)}P_a-yMeAdo?|BDA zKoHh8KR94Og4a=gc;>c08wf` zm8aI9dLA?6r-GYQ#*0y)SS9OhTD5BcevLwsiXTupY>j3W#!Glx5b@hbpRMU{1!3&%u$y8oiCMu9wsM*EB*mWAR zfk?V_M+<2L$d3$ytIaA*Qctd#{6PxJsnR8qprShKaWox?c}PU$qgq#l3$3F3BFhJe z${pm5h90E|o zlQC2YqX0otdCShsLgGvIp@!`Q#>bz1K4ee576MS~L0|)ks1>6~M1}2^4W+ht=|USB zEU{;wM)KoTNi_A?iOwF3jducWciCNc&9jFey&hn!6lu6LJ9@aqe)V5F?YS2ZT1nnI zq_>d5+*oLL++Jkq7%U&ep!>&%x@^Z=r)+-{mdMiz=yRcMTv^V%Ew>wQ8nPSK4Y|H% zW@XXdT(;(UeCUVmuiH=9YdbsatsbP9sY|T{WCfOkh^c6{qjG4Y0o_K%s4H-_r337)9ZV-a3RhO*tiRfQb;XF z=f0lQx{}pg@&G77*S;Yb$BU1pc!8?n8GXa?vp`yM&XUgb!DA!Sn(@eF)7jpVu-9J? z+Z($^Z1=uS`{)?JaoSlc%{*(5+_#86uE9Wknf>8UG28xOn6-$7C^lqUmiF6*H3N3X z9Se|(T7ca)bw?6Ws$FZTq)t&wowE@o!hGhz^WAvGQ`tuRAtoVRyg3I%jZ^ANcjCrz zhOPE_{c#cym6V9`K$O-sNkokYO>KhnF3PuE1oH}E?0mlQ#vAs_U;fg%y1MMgKmM_O z?TN2BvmMzv!I~I6#oy%f<3}Y;S%=5-USlV7K-AS7P!_TC0a0Ex?_$-bzMxajFZSH| z?)wRLzWa0O6BO|Do=P)aYg~g5-gLYqwK|&-l8%{)jVNEPuW9PFPoFzpJqq|S^~dwo zG<9rJ^J~+P3PeeDNwGvgRAnW<_~-CZs?XivV}@Jo$7Nl|zj0KnzJSX7W#8Pk(EjP~SKF#p6_y2Xm5%C<8syr| z)8}l|Qk$_jBTarbp*l}8Nq3T2j{fpy) zD}n2>H~>Jrt;@~;6z+fjxOJawu_`t;<F&S1%G7NQ{k*#H|e*PG?$WL^@%^{dffI8?~OkZpNk`RmL>ZP@#>a0W_f; zgT&bASdI+?E)4_J3=v1@(hyPQtF9=U!zgMqvJ)jQdg=?P4=qto$)KprE{GOH*?>ZY zmZ!O=1`_FZJ^)hzF^@S_fQn;YR@|zqijah1ji}DD@-iG;AnBA3z?7dGLLw0$su+nT ztc~Y_Or@b7DX|;16=;-XWlcxsk z#qD|a+|E2}>FL5r0XCvm#_iDuLwMILwdy4Uu%_u2g1UaKzY zwR`TZv4_902ynZ|Iqv)PlMcY)_w1$ZN39}fu~iXozrEbH++BhC8S2Bd<>LdL_P^Ut z+U|plL8OrNOdj+~sH?;_ZW^(Tn~~zH%CUUZTQW0|m|o{3t0s(KIae2#=#F(dv=rU1^*5649 zf>zmQ}f`Qg~hMoo-)i$TH&Uzj%k`d zfKfi+Gk_lkCN6SniiQEM4Q z;*cMAZfWeZwJZ7n9hWkHu0w@O!zsIIs!OY^?Au8-kHsMw0vf0fvlP@pA5zbK+T3x1 z0;y!zIrMUp&0+=k^UDN8sZ+BxrzQyWqB_rZ^+ zKhAU<{Mc*ErURlRjZjjGq)8Hpa>mMevG85XAJqcyO!_!Zf)@HfPJ&hmZDN&QdHELu zh=`%SlZa=LhUCDBG~4%H+;+d)V>{kEYI~cS?dGM0cH`%<;Sr#*UKz5U?(t8B#z+_UGh*=5u0`bpiX z(1cp#!sWauUEh5H^vsn(@Axj)c_K8zW|d!)*<6cIqa%PU9ocsBMBJWw>VW;>xdTXw zWfQY(#lrcvX5}I$&9UXyEL*fl8&H*{LYZq67ywZaQR5_FK*aZLP<<0knYd7*qVn;m zz(5yV0|6V5b_wj9AW?&4LtjsS;I17zQId$NZ&-j7OASQ`D)0{nMYtv1nPPYWFjLgAUT3(+;ie%ZR9vQ5Xu2j6fRpy z3e@4q$sZk6nVyqMnS_jFqg`fJBG|gZL=)cT0GCjq8v#@akI80J#I3UefX7BrcERS8 zJleH%Bn+W38^!VB;6Mbh1&|P$4i9IzI0jg!7{#bH*0b;yn2zeAYY+{fZEk|vIbc^OuUZKvV_Nim^52hHWlPJmQ- zRlZf$7Fl_DmNP6~?7ZAz9GQE0I_DXIDSmyCmpv^Bl155by4%b;bLxzZ+T`1r94Xo_ z1MH(9Y@J=5b{c@^rR@MsI}5CdUu8S{x&Wfg87seKLowh`H4ggnZTpL13{H>Qp%Xo} zr={2C=L}g@(XidKt; zFG6zb$dPV)>9r<%_rn2e>MXLeqXpJbjFe_YmfgN-3@>_PR^M2NR9+c2H*y>YojKiu zouNa3VQ1~5qYZYrqaF~BH4o2v7Cy<~9<=Lt{+1h;+Rf|hY{RA;TYZB7Rkrh)P=)c- z6m!cb{O#tPoBNQ+1+AvgXwv%Y@98M|`QT~luQ@uN4J4vYpFYE{-H~&EDEB_08242D_5;_s!VQuhBp44>%3aBW;L*Y00rKm7Z(*qkdv8Z2RNygyO=YI!}K zrlYk!z?7~Q6I=c8VD0Wl)Ga6z_v?VV!nLi zj-}c0!)AMT#o65S*xLsV+ozppZOf`s+i+8fZQ4|8TZsAjDl_7K)y+cvrRj7CW5lSw zV2t=EAk-0z5m#k(SXF)p8-{v&{Oc=h`SJ?X-!d#GTVO%3X$wFGH993sG(RQr(oR)` zi>gQ8a3SpFVCP5@9{Ny^jHTN^7g7=!i~Y-APTT*!blTebhOK#E*p}4HvsKqEvD-G5 z+kN+C^Q(IX8&Clmk_Hh3#L-Dau@%)gxy>kjP&cU5)knRPg3^^lTLeHQB-Y_}vdX1V ziXmk}+Z-uEHUP-c3ux5S(@X4eKvd(R2Aempmi$O)IUqyN5|ULVupbh~m~$8aYoNW= zhC14@|AeX(WsG(9yO6O@9E=B}`jiEo0k5zF?=Tl_w8GIeHeE^JiGG1u z0(LOs0;7nIHys}Y+b5~$#o@(-Y*>*u9d*6{u#uXHAgLsIQs_-J!tavcRFJ^|P5>GL z4+VlLL;#$^q=Cg*|3GjY;@H^}w`L@sIy=W~sAtdydyoXfYv2GNUJS5BaWsqpa-NSM z^%ROR`T$PDsHu$#eB%BX;1k+=G(v-?3TeCsGC3{*2&H>I=pK>(jvk2-8^voS2A0H5 zs76Y<$(Sc(i6P|>A4O%4oDgE{K*CaJIX1q>`>OgjOrWJesZAM{_~eR?D@YOu*$-fR#CXh?%G;ycimfM3+5x`RT{#JXus|LpvB(% zaK!d}QfRwd07;qSIoNZ$Ykd?TDhh~HhEs(a_%n~zC+sxd`ks6KfNg)J$qpW`wv)0E zg?ecPYNoNVHUPy_Rss*#0QBFmtjr#Ku+(nfT7x*`1~4jhT-k+_M5Mk4+_!;1RR|>sN;xxVZEZtE zZ@)eN!t?glTW=xNmgyv*wr;)C?z;OfTe@^9z*Gb3TZJ@RV1(;|t2Oo9H{-KB`gdJG z)X6pL+cv^xOSW@f+5R#rY&-4HC!g3S#7&zv5;qe!*{02#@N`%OJ+#(O&_4K%5)c%8 zM@=sM(yuf#g1K>>I6^ZkcP>|w0zyTj{In~H zsGtA*7fw%9K-4$B@eP+l46g;_e2a!p_eVYCCrPr3OFE>Mb4d?gW0^074pZr^Yd3D% zwDIxTCe=JA5f!(R;!-CSC674yNG44E`0`{_{g=`P|J>Yhb}8V;_F`k<$6U3$vDf%9 z{!>-+rURmUe%JB|gF5a~+a?#aVM>0aJ0NO&FQSheZgFoIRipuQh>jfKSK8O(7#{Dn z4^JGi(|yghbxo;l+E@YzRcD(wql(35RvRV#s+)x*Ow*~5{qfIXdwx3~%Prk@7UP@q z3Oa3JWv8=aao@wsaW7tu1P4GAHlpYx?NZD1(LCN5*JgciU1{+9Lv3u`<^^+c6<4?b~_A!_DL)4E~~YbiQD#-I4A0yE*K1hh+{y~eNdNZ+_{`4X$VZUJhF z7<8Xk=v29~G8jRc;ku6vsZbh7X7bnnIEfMLNkzS+68*{o1OXd?Oi0uufi%bW+=Dc3 zlP^zlG2Uqcq0%T{piUsE7x0WoEP9J)Xu4w+Nzq_#36;1gw!ajy;RNm|;7L+O8V`B1 z8%4sY5ATk>08ss?)C~+E?Sz2A>2~a}b&Mf_Hs}DrjxcJ95u^)3*kA*c8%GS;&<4^? zLfa%gNJPcXS@c#_KB$qNiPcDd?(he9)8!Ox=Zhu)r15m@fTfQ(RXc>vFa{1rl8+h> zfS5e%)l_BL!UZ{2yP(LbP`j(G%eVQJ=>SpCf-)4-nEL|of*MpW>Eh31imNpF$J0(5 zSL9AyjsWb_({40^oUUJi1YYn?Q6~tb%RWVKZ?83<9kS&6f~HZtDLx3>=B1#_s!V%VqJ zus8~69<}uws!%1KZ*_GAmYb8nMpU=`>6rtl5uUUor%PF*O0A-_+Llz+poTeMoxL5- z_E((6V@Y+kJ^E0Y-F06H;8(WIhxTzk{uLz>r5^=gc-qU6HanWTKhW+RAWAnx$Y6d4 z{3JRm%?Fhey!X42Dm!(m3Hk;=R1L=X(mW6a7_N0k{QQDd=pQNWe*i>*VULgez(CxNpNaymjo8b7Jz+2I#Lm}PAHZmzJpmB)um8RV zJ9=gIm*=APCiWLUZSCR5gKoR7rpvBt?6SunU1eW?bhQa6>r z`5YTjT2NBL6$4RI%1bHwnmwHZqAqi2J)=(dcghraXCPgr@udb)#&+U>#raG z)T733)`6%bVcdJjeNPJt3ciYEw0Qux@jZRmHl47x!B*S0zQ}Id zf@poIZ>eahCN&G${1A?!eW>45Y7_5+8%IavASIBH;@q`^762H?BoM+v zE@&u%C}2)t7xtL?kdo;h1dQqiN5YdG8;siOdDsT40{dX2L5xey4(X@CHVm4#_E~>> zn+Nn1gx zf5St7sF+Y{ZbeP&Y%lbRpgxD^K{`4HA|=4o+in`g`1%L{RT!1Sv2YHXzI5wDHLsU6 zrN>nus(~&_ybH+!7uQg#k>yhg1^jtPg%oa>K{d`bAbo z_1oG;0ie_EFR!NCG1PcZwKm(WD>9JQ$hVEM5w)}$bx{FPVS5uG>Vt!w_TH&3tIiw4 zOJ&%$-G^%4x977y;Q9;FANm-tdB1$!o_YRbq@fmDdC_9PDm?2wumC%0Sr`!)ND)O< za@0#FV6jSaT!`a;yxnCl%q_WS?YXMcI& zxSeV*wD!INTeG;{ZeCdr02#B>X9khx8nzw``j_U#Y}5KIyLn>{bl?fuAJeCb6O7cX9HOZc&1+x^?@YhQcZ8Wt}6;sQ~Q zs`Q6{l88DV5cTS-Cv5v0C#`R|4_keG_V_lu&Hn2eh*4^ROUg3>^hk`;rt2(c+$)DNdo;Lodil?Jd>V1EH$v_nIOww_e zrJCpGs6T#Y6#D!tnggOPa|}GA`lByK44%s50-?q*L@OZbKmOxC91xW%5vAv*KI79; zk2+UfsbwqeVqxktm-_t0%Ks|dpE}06c66NsqP_~lpZrh^=ASz3=hS5ZQTmXVR8%r( z6XfGWT5u+52rAP8L9R3hLUnXSY~NlCAif&4_dgo2t|9R+sNnku_# zZ8hK%wl0uf(R`OGh=8c4{uH*q;GX?ROAqeZdu-+WK3j)D)mv`C#q{Q-wxFRD*R*)e z<5{(e%3ZxQz&Fh|Z1VMGTqOk+CY}UzN#J?R)tfG0DGg6vA?xYn1OJ_NjQ!#Y{o?_9 z>&SrB7FXKpMr^FyT4E0YM6CvhN&r$M04YN0(2N)WQR)Mme2E27vS0hO;c(sawd>OF zO?A%r!~{mUaS|;Qf-wkWPZ$}1sAv}+)sT+p=x$}xAGV5OB$EnDEs@Q$#AtK7Mb5Tc z@5v79!Z>_S%NanJ6E@n9F{23TaJsq`7NkF;OVDla15KR==sN-c! zn;{2WI4Kc&%D`yzt_`MG&xPbshX}hg7q!7A#=s8ISOYX-n+3n=UIyS)D2nPIs&Nsj zR(JdQLQX>Fz>zj&y!YHTW7U3wf68M58HRY`(0bI zWXYsH=~->q6uqs@puo%j>qq%wC8*`eA(HT%8)ZA8A#tYUO)N0G@t=ExK-ZNtRm^ZDxDL~XCtL$q6q9hUJY(#TGIO`FnEpT{51 z1)}ipnupih;v&Zf&TC$BDP)4XFcpY;{q@(~-rsx8d*X>F-1})JUh}3j@0z`w1EMZ- zXg#C)qc6rYxIYSn8s%5tR3Pf#|NY-nB%-v~ovS17pZ7;!{?y}z?w_x1Q_GmUzAy!* z(oxrndO^)ZBFfpWnes8Ial6piUARSacRx!C`0-CYy76QDFIhEj%AP{|=7igL(4*vw z%|AWx zu=fu((Avhai}IWMStPpacWQagJDGr!U_FchW`u`P)xs0n`|k~)hB#=u_O#lo2U-E5 zDgdGyoJ5p>s8uVGK9aNyzPHnm0#ek*kjY7LYQMmR;{dQEp=m1Tmqb|xDl)#msQ^8RiEgu4PMQl4s^ecG8VtA0l zoFVTkyvY&4mE1l&1Tdx`aB2)Xk718VHko8Vyt|V=wIij{H)y>>gLuti4DsZbhybEd zous0MMzaB%=ob<)9jMo#)rglmq@4h(A`y&2NpBCSFH0*8D%5~L3kNzmi6+&qMoyI; zQolT?;PV8aLIC#C8SFc`C}0a)TbTfKl^LT}fE~0PzzRu^m6s$i9Bx)u4cJrza0}mL z0uai;cy@N06=2_`5Q&B&B%x$`EeAES2(*g8Z{3}J02BS#hRU~vjYt$0G8ird5Qo4h z9|HQT%|42+ruIp+4(J^`=dYD_$}Nh~`XF*Sl8HrGlf(j~1i#EOh&??~d-3JCz3^(> z4jyi?k59EC5tW8&UM@gXS)iH+5cS$?WA+9%qCPy-Y44+&SCunj)djwU+lK0{(9J|is!lb@V0sO;6wAQdR~U*LC0>= z8PG8RWi<}s7fGk+u6Rk~732)gb*+MwPlS%M4kv*qB>B8Vl%%2bE#QaSzbo7${E>>} z;ZG0SfsYSh5PpY?`S}3JdHK$0xd5Bx%a^+iZXSA{UaHEyXMzEx{?9gy_kn6t*H4%3 zcuzo*)`L;{*XL|S{rcCxwqO6hUo)S|ovPu34?bky{?2z$`@YV-hvbRQ(ZunsXdA5e zu6$jIkuNg@W9XRwf+e_GHI(FnMT2?eo?y)*QR>j*428kL1X7%+!yg&JcG(Gg2{5W} zu-8V0dhL;Wme}9_Xf5kSnZ2_sW*=Y=Z9hO%3kJ)tukN;`jotS6g@7o_rEU;g7t|Wf zUGds11r_N->bXywJD!&U;zP%a@Q1#=W(q{57U+4}A5-tmoqu)|7$3_^sM4=PGX|oP z^GnZpfZc0D$!p%Pe)TJ-j{Q&n{7?48*T3$x6tc7Q;WnjFD(5RWSLcAJDSR-~OV6nO z=$}hnbaXBtO73iT?AYN@Q5m)s5cREZeT#)I*k}g72qizDlLh&5rXF?M*Xi&1y628p zhXS77zI0tH&IE{Z_9FOLQ%D^zf9{XI?78C?j{<)DQ;!-qjsGPBQB%4nqtPxZT|0Mz zw-FW7FUF)v%0afL+S{XchL7U6-{`StpKiAIjt{U|&ald|9J}ZC3V^5zTf8`AOBW&4 z#B!40t6H{xGO;Ce{Dj$WpBlA43y5kDf6#a^NRkQ14KDV1^rqa&_D*KqoddfLYijpo|t{~Va#^!K4vfMJ%+kaxvgvr zRPzKxtptdQ0*VNTO3w@fqzTvnWKl=PjU;KjD4yu%+;m-1)kI3NcnG819NE&k7}!h_ zXb^;$1EK(5&U9GoNnE+h_&X?0{>ZR39X(~u$4;?XX=Uwi1Dpz5IY3b~k!PLJQX4=L zNg>AOwkuR@U1`OZ3s91a&7VX@G`KzEzY%Dt*o&Q}u0B-cz;K)<8DpUUJCX(fHH-}>85Ad; zIMr)Mk9AlRz(IR&Ct#H9H{~F);sF_+2}!aEwJz5p3Xup`8g8VtxsQWNVN@TB>s*2c zT~ZKIHo-FiR+>1>ZU#m^?n4KPLHAd?4UL{H--fQeVMZ71Yz;AG4QUCcYN6eW=~-VZ631 z_g?d`5w#d&<=BXN4b{AzyO8Sm1Rx64yvodB)DuVS0f4Bl|Db`jB>PyRP?eaXk4eyr)cnjS1Zq(k{i==1MK0DL0-@ft48vFJ)*C1(#C+e*9t?v=KDb-Jy%L27xd9pYJ-S5kqYH1UXn=CZ(KNv%a0 z0eHlLP?Aa$Q9TglGN=5RJZ=J_PHWBsLgk zpbp2t{+OFw-wM7964%nxW zbiyE)DF3AxQR)i{nQhu{kKgA`oceQ3NCbaJtgWehI#t*Ri%09T3HbVy4%;iNwk$VnivYs=KNB`*!N= zn@rW$f9BHF-8Th9k&f%qj0dzVeUG|jl8+n3Fux)zHZ~>g=(!QC_o90L_b$a``qWc`?Q?b(;a zYf-}9+xVru4j479sKRb)XaGbj$0Jd$GtEoF&^zbt58kAeAzG zkH{feZmIlrSbxNz&_p%M9pGbB6DK6BTpWno2r-5Cwq$#sHJxs;qsPu#Z!@M$oKS}5 zQx}5dJ$$&v271vr0xX1;QNVo$v!d34`B~ox>>R=fwp}B5*c`!idr^746;;&R2(IiC zm`4`XP_GU3PWZYIvQPn&`*4ofYH(~E5EW$Dc?aYXB_8g`LvA9YhvWtTCINE?rW4z2 zIxQ!$o&+i>=(!!s3D8pPvtGQ^b#x9O3>}BrHE6NEA zT*-&|mj@fAs3eN6Qx#uLmZv7V%rC6RyKo8n3T4YDgj2fY>Tr2!@-0|=-iJWnjE zsI=*LP!r2Vg|Blwh{=w0P?|xyqtEpfeQOki%1pwqD{}1&EbD8bwd83?@zurm#h$jHo?_I_!&69af&xXT`a__M^vY?73ew0N52{ zhM8si_O{vo_a8g$FYjLrMAg8EDuCD~Pk|0+P`8#>!|tT**x7440GW2~!L0b;FlKZi z%a4R@-i)Z-z63Lu!d%;T2-en#m^F9qv*xb-_Or*A+OzAIqMwuxdnm+MaNhp<>OT8? zMr#90!G|!B zUX3TgTdc0G&Rwg!1>lOxQhB(x!R4Q482wI37lVH;2PiQx=pCi!6VUd;3oqDjfBRd< z4wF{befQmOPd&LFhZ2jeyrPUcgzcqrNvC_k6ZtaZ*knRbR$o<4zE5)pZlh~5uSoDb zLqxp+6vPf~ZAy{Wj=JB!W0m7l?6A+)3Xr& zoEoOCu<$ZJ27E*HOP@sMIodZd5cO+knwNQvz^KeY%cnDbscXjH)2B1F{ANqQm;Lzi z*0$m(5GAj9h>_}pY$6~^A8Zo^pZ-M0ruJQ%67Y2}zK;EV<-#A!T}y%(P|o zu;X1ruyuy*u{(0@$tNP1wxMq`H%#00 zleLUba}OST&FaW}W>=)*7I0hbSf z&%IpRCvolcgT~P}>I~&uEUj}SV5zje%*yIYt#saUE1!Ftm7+0J8XaUZk9l5Iv1R2) z9q5w)Map9$o}UkR#j^^G5}u>F)uem;JXNNOIwuxGyNQScKb{**08jv{C})DF0#Ul% z{VB}lQr3cp!shcM)`qEB8?293p0TB)p9%k<6B?#?t)F`720)e-}b4ex3%eaU3kG)Zt0u(Qb3gYT~ChzL=D={by|F(KEJYezraF zK)&5^N2T4gWIAHE;L9PWv3DTT!^%@^ZUu{o^(Ei(k&Rd9z9^L4Vx02O#P< z08t-a3`EVS&#_`@XhksDf}u#l)D5KouzdDBqTOc!l;4iimj|q|CuThfbf_?ATr#r) zarXjD@;DD5bYS2h9`X*_vyU#er!jAuJ-5KBFr7Sfw9)?h+Fmr4n(zh~vF4s!z_L=> zLy7&%Pp8>0pPyz`wK$76D+4(DcN9im-1y5T!<`ph{5v1$C%B z&k$ls%Elt!Q#y5=2bCmQH5Ooy=d>x&dS&!rESlf!DKvXk8)afZ8>N={vE6$3q z=kayy_bVZPEOV*jlLMlH&t;#%6rhKq@SY&}Pi6hm9Q>M|4dM`H#(m}#K-5uys87$? zt8eYM1LtBkr)q&Mm^I6O@OX|r{KE+PHB6S#w#jGmm(Ml&$QB53=t$CD{QZEv!esO` z>=heK*griOwVyo~wFUE-q%+AA<3PE)Acx-o5S3Y$qfe;`jW+z8z=2RQwF)LaVlfGb ziuE(`<(c;r-@z2qVYmHA^KzrotY89s8BYOQDR`u zCh_f{9yPz<4lWy1p#!4$0o)x=0sP6Ocoq|=>;c#}vA7N4hJFZrr{T6P8*1&cVf3Gd zd%G>G4>526p4QerJC3KM&aOVoC2?nv2ACn!tlk9LNN6FAfRuy^FbB$wB0ipPIRGXl zm5K#cg0@h}G}s=sbFFa392h&Wp&~<;3*eMplxr!#l0le9Vm1jZ5i>5yukR}!73VT<87BaWxKI3yA28wvPJ;oYo1t@+f|nG3@y z%48WGtG-_AjSX1m;E=@t;J zH<>LhMbC^|NAt6+05h;cmPN41iZKTgvqt;DHLRp8%do&hdnXG<2EdRoGD3*T&jxw) z>?gHRfd&F7ljJA(eNHVU80*C*qo|$sS`I?xF<5bNVi#;E#j>(#Otc%)K$Px)m^oML zK0b`C`8`^yfYRH3nR(c)Pkg06&9!NP6<{eElhheT1fmkeX6!|$={@wH-v4;ecI-Z9 zUmQ7at7i|}ay}kH_Wmwd*TN*_S5I)*z8$F z4v5+dBkKSEKRfMjAB_P~Pd_@%*8Qm3YU*;(h@xx(qFkAghX`nIh<4M1$!9N`JMRI8 zzk`YJu`?ZZwxb=5oru+z)?mt4VjcANb~H6pgZnTS+-J|hh@?bAA!cI$mlBE3#%?u48xsiS1fprb z>Om?Wa_dS;GADv8Aza5gx`seh=2-3X&4UM%X%zv%Ka+b;uuuJFh;gE=z0KZy z<4t?>%{Q%yALkmI8g2RV<@VqM587?F-DdL_&bR7nkl~3!W?7}zCpztN`-1mYI+GKg zNL{%7{7s+cKq&nhln%p;+XAE1I`o`!zR-_3a%1Cw{q>cj_R3$6VY@3bv?c6+wU7~5}Z7Y5gKvZU1xi(KTb(hQ%@OArD_2BDV*Sfk- zf1q4FBZ`mSjPH>V*di&+izJLa7J_wmPj+UBMM69ctLgB;1YVcU*z51_wqwmPySaWb z0_AftNeSBnj|Bp~U{H>QAf1~8Ud?*Y``NoUVZVQA&|dy@$ogRG2o(6&^%48kuX1e` z<}}5CB{?$5yC5HW*Z_bS%iA}z=I|{gPgVlPARhhz9W-yx(gUFFbSWSzl2dN8sv7M6 z+nIQ-i`Ytpjw1qT02z{)<0R3A39}J~?IIvbYCR5M;JNi4m&u4s7R7z-sTSLYi_gn`I9zq9*u}t41JJ(izER%(0odvTN6VorkiD3s=&Gt zpA7+`gn(nZhs$7mlv!2<;M4Sc%P+>;N~8c`>k^xLOO4gfs{k+wTOMVf4LB7>q&NVZ zB)ZOf1T#D#Wzq=~(3Aj-lCJk~KNBRhOTd;4t2vk>feDGgDh0g7J9Cn@))W)M6ax22 zCQkj<8Sg>c2z@Ysr~!b;BrKy8WiD}Ev7H7+$}K*EP7`$!0%T%=kh;K{Y%8W5b6KkV z1ab6pypI?GG%A99mIuP)%au|kU37X#0BjG9D8Me_un^H9b_gkR?MxsPOed!i1)D0n z&LdF8)}76^@j$b!n$=?u-`i(*tg3*mauaQ~+CKSc$TocnYbp&yO^^0i zMRB)1@=%RE_2bz#v#uBi0*0AvoBihtJM6WO$AGA39-BsAthS0;`dtyADLPGJorx7D zlwH;BSdL8kKl+Hgke_{+2_C?#wLP8-_K4TJ>~ce*j7CG77~G9^`EGmu$>sLbpWbHk z=H}wD5P&ezZ_O=Tu(F2j@2?ivyItL59hPv$DMG?DeCF8;Ba$C8o3jHr3bN$?2 z-a`coN|c;?!Qyj`+_i9(QP6MLnGU|@lo>^BE9$&Jto)K1Q931^T;@B2z3zJ-g^DZBH|JFRxcbgQbWa`o!!mU8s(D5dMt^9|Q+ zee-|(ea7EQJ;CQm#iI2=1n8xsBa_3A0oV2)IAHtt@3TdC1-$FdyJ6nlVYjbD0}J-o zgn>sIEwA+Ygy&smCndzubZ4IMJmp-cQ0M+sX^CY3Q9$O7E9Z2g=tEk9!{d1}Zm<05 zfc^Q;2XMF$wwB(otzA0P9)ENJ;CHc|KRaT_j>l}rp;kNIdi?=W6BftR&P$enZ;R@4 zR|7=(KI#)5zwP%=Ew4=p_9~Z7Y5qAZmO&xp7P9#?HB~+pqdy@aK)zefk6Cs(>hc{0f1|2qS<{ zP8fR>0J`wFPEEoLN(_eZx-@8ecg1b<7iVn4X9o~P9kgZhmfG?q^X-900HTO`cPZvF z3y(5sj^nUR?&WvwOxU0QGH8F=#&5n%97I?7-#^Z=fB$uk)lJW_D6@4>Fr1=VBaI(EvX#z_($NUCabN&_Wu34b&2@ zwXW<+%LYWrj=*AyOtV2^UM(!0S@~943S%c6wP_VaR==Rqs%Moli6cv31_3Z99u>@{ zbcO^0YLb)ygc^eK5eI2sTUoWIOq_k(+0!_8K9a$vC?4(R*Yp49YaLAO8^M~dbwya~V(ez;b8Nh>PLg)kn3-$X0a2f9 zL^O5NkbSYe$vy@ET2bF&58mAc5LIQ%mM?{sG#vmT0HStbn)lhsPOAlosx0cYM<1@S zr=OXPFn19^t=T@j=Kbb{Z2(cntOl=nH5D`LY0USYda~9kYH}=$XF&;utE^NX{t>eQ z-LvW6yLK}k5w~wYYuk66u#-&@Ye~-Gu@J0R5I8xoleo*CUw@lD_p=o?e_jL=%VGL; z;Dz}3(Gh#&wIX}}qcF}F8tr^XBc95_wxl7)?p#}G_uf}yv*zGwvS^6B057PYQH~** z=fT<=YXOv-t1(~iDraBT+NbD&DD_PG6=tiaPMxFAd9m_p2f}L7l9^QIJA(^dvSJVQ zV9wctz2tlEy@zo5dv@sXVbVKk4Gj(U_~Vb;-FMw>H{HC5?b+$eg8cY)?b~Poytq@o zl|MfJ{=WVue!udeV<`$(X5@W%4&A*JOHNLNm-@Yy%_IsWwUzb<&n11}30-~;_ z)FxzoV{j#X_~ngl+xEnEGO=yjb}|#&wr$(S#P-BaCf43}>%UuDwN+hptE<1<4_&9v z^ZX71uF;X%CmJ6RmJP1k*l$e{1yq13E(LfVXBR7iL9G~dnBkMQSkg8htqK9wUUt&N zP5O1kjJ`cxof?8CU`LTb)N;re?ecjA0=GVN#Nfx0*Li^S29vMsft`2+(DBQyWxFgv zo3LfaomL_~vv{4$rw|#tk$Z^n?c+5tq$0n;)#g%}%+n~v#qESf7Yk)zB+z3F$@^3- z3s6F`8g{w+%>XQ^Pp=O;0IzLUjNHP^ZnVRflSVU zSQT*J?<1!VwBr?{n0)}VYoMMz4tcu9^k1v7ns~eIFf=wYOG2K8#xjtr!!^Ze48a43 zna{|>jqkWt&}0e5>I-#0KRs#FxnX43Ksnf3qK~`5Qbiup#%i9oxbf_*8cB3(sSKqM zM7gCANabhgb#viMB7TJbbcVn2kP42&Q06Y-P<3pgh&s`fhpEo~A)9P%O&_NjlA-A4 z#~28cDQ1jG!iGL_$%sGGARt810qtRkCeEZ1Pf|!JX#~RQNf1>6LY=`8vAq&uE`_B( zmbsZ(({L31IPeGexH}k(UbQx;H6mTPVIO}QY=Z1fj>PLkR2&x+bDCs&!BN8^nLnHG%!=fx13&e1-i2bxUY#1Jy1Ua(sfSR>8%nPw&G3clU zMyU(Lmaeu8H#fj&ogfhIvwo1)2u*E$(2GPT+&|%8jw5ln1&%i8>hT{&=Q~8~2mlv} zL@r**hbJVQ7BEeB!%RIT{n+t;@Y5i7*Qx%t+Z3#CUDQzYGp^sq-{5L&v`bw*-Afq!Zplp1i{a! zc$N14-Ik!#Ywq*Gmah{73_flxwi9}f6V1X)N>flNZ$j}{RD;Ak$e@=ZMJMiuE=rztq@`4kk^h&08(rw z3ybnfc+Kvgd ze()FL;wE!+hb{O*hg_%qlE|<7<=y=0U!6}D?c3M*NMa=FjKr{%#la(0Hh@BG2cVEt zp0r#;8IE?0qQGqgdGCQ?4f?c8DDtJs_|MI87qjQh zal@7UEho}<5!Z;m>&L$Sjqw)=Ek$OTZ-^pIgM`zz&ZeU9x_KKDpI5LUk62FYl>*gv z`<+O&a+TLst4Y9dylcK+GQIp;_Zi}re{yd*n&wNl?_)NwJeuU(M-?N@HyOCIN)&f_ z1?w$%Yx-!#YhM71kCg*a>J7HvDyh@?2H#Kzej#fWt9?JqhzsuGC~uEEO$Ogp`;7u|QiA42_Je4? zcH;GiU z8ET-sv|MI7_&qIs-MM*``gF@rFQCqeF;hWJU01^lW6`;$5>)~P zbaL>d_>(;lM-Tt1?5UOH!t!@TaEu;buI$aKR5~Y!7)c!XpX3m8G-C8jh3y5uUq>qg zjU`1Rvu?RVve7WHxoOT(pvmLI%6k#@#ip1%D(Ph6Lw}hpGBJ*i3q(Uom3fXymTIgO z^<2T+-3#W?B>(uve;|PU>?j>{YN5hKsHW0nz}ZuSlC2Sd`Bw}mgkM5VO}XE%hFw>t z24|)PC}!$wnYt}g$hNy6Ah-j#10x)v`i0f+R*VQ(l>PfpRxeZ*c&xPz1GxFjrh4@kNgUHAw?-2+XL(}yH zO*0(Wt{6up^@7%bLgrQ1RWHxOgDx7V$I~k5DG`^;)$4&}vzHZ$*ecd-)KE-m?g*gN5Y)qgyle5@=%4ZVFqgKT z&AtAwNH|K2g{Fkb!z1`|>bIA>qeE)X`@WRV=R=Y@@~DY%`ycx(4SO36)%6;>d%JmO zK()8F@UJ@vz)#BG>!1u15#G-IUq#AVtLln}gw@cq&Rwjr5h!jHLaK^w1Iyaao0(hG z*K55=?L!=PZ^>`3!$B$!$FnY-(nx|I%=t?MfLbM}&Q2S4SsHGrd#KmP4#eyGnXkv! zoYU>`#rBhVuG;()l>U{iC0n@|xl@#0%RZkwkMQl2^~+H1`tIvSHwFGPK5*FJg-32H ztYi5<{5i9$UZ4h~Y4X3jc}C480*3zT(aZHw8H(MRfIXHp7}V7;3lh3|Aa2|Q^lg6K zhHV3}>Rz1nD(L-KQ%fnqtu1ctj1|<0$yBW7H_A~EwZAg4&3W2n1vaqm;rEuMq2S>Q zC+3GJ&A{}d!zJYIZm@5F+GZYTq5Y-z)8SeQUx?r;6MJpNmzlI*YB>@9{X>E#HBGCt zzwg5P&LhKHTA##WMj>B>^;aDc{?~)xH(IE7*ym=QznQ}K%h<>5?`-h-ki8MK>UaP1 zG>ycwn*nYWp(S#UEVM!$;Eq5sCqgHb*6mAYJ!%}5P!F_wa*e6}wW`~PRo zynAH*s`&6Ka?AS?>M$mjHu;5z`LChEL!+MI7_^SwzHGwe_6eq+S}qBcx&$I8FZCF` zlUD9&WwUHv%}Tte5RZUht8TY*O}#GN;&}_tNlAq|6Mq#_Hh#3}vo*jW&2E#&6p!P0 z<9)0k?v$f>_q!$bMR5AuLV_Sk^w@SbRJ_CGm7)#}L`m2GRp=WVNvtEx17h#`W>P5w zAu{NaSt;3y5DfxKYy#ev-1v8Ul%Qw%2vBU6^WR%}F zc94F8u#dnHRI~YqS>&h!yOSN}VxqFSw;FbOnY2EW6f-PgSwkJcuL$1gj+72EJe{Km zG$#88+)z8T=&MxdgKcp7fr&)y9{$b}n?43hJi?wyQ>mceH0>(G7h)8&b57^>%g`XHYhbH8xz;06ra-=Q^RAN^lO@hTy>oIQhG+;6A`ZhX{GTwKb_a(t9mvtEQ1K zw2@y-fztu=WjOU^Y5Afzt*GJF8P7l+5WW3|`;p{<`Uf8`g!H-ZEz1EKYM2eH7E+(ZFN zTJ9&A(mElh&i3*ULaL|@_rjb0wqV_tO@&(m)7PUQNmuQ{LZr+0fddKoT}^l z=3e-+3-*=7b|zO+nDBTfHwAzGgb@OA33Low~7F8iu&-#QC_7qE?1e*Wa8MFS}2P(xl> zRsV&^1Ay`ppTn1Wi7t74Qs5{RxfL!gg)IyOaApg*;U;yf)E5f4Yb(XXoMdE+*zyHiEM#%iFdYTYR@j)uv!ZAX~HFU6a-|SKYgI@rE428`o7d_>UeeY^Le_ZF_F}t zda!9{{Xa8(F49I$@B_x!uN|#jL%&$|j(qO8ZAp<$fYKJlZv;S6P zelRbc-I=`a4Gyrt9Af3HkBl}YdUD5uhdri)SX+ko%px#x-X7I zGG+2xIR3ZD{ieUyVd`v5j*CH?ff`cp>|=B7^&$~98kmxqx|SNwMYstH%+rbVLl%YtFk$Yt51))^<8~IBd9sxLU!2B8wIWAh;!YV zGSTKHdX2zipCUF+!A}KBh1$P_e?A6AHp%YOx1Ym-u2s&W!NZxTOY7-^C}yqivyTih zoR)g{VI5p3*(5uDV;P)N*r{*hoykb=#w0#5OA`VI0TCt~^-~fJ!ieYt$7nFpJ z_i`-0L(}T+&y5?wJuYvp`|4KMq&7*y{%kY5plw%`Vchg;W#;rIr&v)x>UG9`^1xjG z{$Grg-VslXbohoMQ71(YRC79u6%tdp#s^bO8mLw3XHtc@LnzZ90K7y!fPm;qBKy=v zqs4v%@*hUtxlqS_jH;@(%Sdan@hKx4bj4Vbs#*#d5TW$R$0zcL^o9L_+9JV`Cgy?t zHDbaW9+rlSbHdiIYxxT(VwV8HpayVq>DW92KAO0edi)SDItj%{r0y%#*45Tjs6U+Oig7sARh+A30v-M z#=uY&<&8SzvZ}zgbPfOz)$DFZeh|Yp_RfSW@-b{vu+vl-3S`IrmyquU_1ucCEl6ex zFdXc0Ca|o$z+gi8xcY%)u*OF7H$PjCJ-(i@xH5@8)o9K9T;O+e0SMbKZDdM&AYzqM z2cf9hyoLajK#`@sow?^3>gXN&sz3^Vs=g`4>iuMFG`xHq8MJ(YUoXoFyKJf{yE4I6 zk}*%;?&5$YtNe9WgvmN%%vPuzo-&jR9{vX8nZ#RBP-FT!-)pY@`P{Q?3en|$=}$c` zyEh`vAxn>-?=Z&4b03SgRpp~P6oe0h>Br&#oMJc#Q|VI3`HDFwmcd~G(C~%d zDuIaqRt4V3&AvaCd+m5YflMEPb*@@9>WEV3DxfyYPVoB`KZ~2!ctkDTP(rOTu)BE% zByek`6vXFnX7Oo-x9rMOrIz3#I{pMTOHb3@gORCzEH`@1t_q~#4%=c_qoSXm8ErZUBHHp7Hv1g9A`>Nhb&1v(T3sMyUja= z6=?7_c(-XP61ZT<_viL4?)wEv1-~E6SW1fKIFAlkY5#`etwi_7eaPu|HtTKgM5x?( z5cT%hwv95k!SM^Tz5s-n(iWqjH`9}QSrGN~ z!)%*mO$D!Y+iVTgbWV&wwyZjW%VN6S_NuL<(ND(e>(&k~aL@CJk=CyX3VAYG=9$Iv z0||+HI%3+H$e$;EK)@3g}Ueq0ZCVjs0A>$`S`!|y4a4jIS(6QxV~LF zW~T)Kg4*N2-W*dPBz{w@L8pv7JC*7m<$29svWw{rQS>GgGa}Zhg{L$Gs~r z8Qf!jmnqJDvouC7{qb=cmKFnZ=7PvQZ(!dGW?jWN(y3 z?qhV6HEky1{P>qjdV814DOqPAa`kJOg+nLOnTg;}m82^0=OgI_T=4j_>t7UNw)Qbv zDmGg?zI0YVg)mFoekOevgwsKohWOzSGM1+@3Bu8kDl~G)vzbWttsDflLEJx9WKW7IR8L+bIq0?o+DU&9ZL)b{` z{3=8!i%^6JH09F?Fu-6VuE^=-b9aUd6R%YbIL$r6Q^%ZSDE%_gtCJEE1Save>1Nd~ zp}Nn>5J9ow(T+%J(~lFe#OwKfMIg^%$H2QV1&Ig~N7V-b(r8K5)eC_snVSvy zI6$`C`f0 zGfb?D45VnxZD}a9KX@S%cev* z%pJi<-Y*}F-Y=t!-v2$QJblfowB}m_2{>kBOI6jWAi|Ocw~5$7@7j-3*#{24b@QVH zdAg|!pdG2A$s$+JlGP%`P=I!(_2KCq%kZwdZ?00tNH~RkjrHPWjTJgGO|D4b6l}dn zDES;BK7+c!8_TGmI9v+X0+iX}p%mr)W;g6IMz0+Qd-&QlT|UA~pV97L1v`8C?#jkN zNe9O_<(hk7I%rJ4F#t>@8b!3#!~zS~Q}1a#HMyrt0d&!G?Kew@v3xGSX8^i`9k;q5 z9WNll$jc0*-pryP0;;^aIeBO=FAUL-2=2T;PJ2T+!&?IA*W>9wm9Y|g<++<8W?zm| zHo^yd5|lFeKfPi-?R4FcZS`&g`zZdVn?7&*fbWA5nM)|am!KNmj)lsqGVZ3-e01MN zVZmEJlAJdU`X4qDW#*>lg>(>?@8yTKl#6x?6Ki+!2~eA+9472;S}u1#enZVw8B-aa+V6SubZX5Y%~VuvJX6MVcQssB{$8cNS0VG(xr4zp zTnDFYb6Vb}l+Rgu&AS{NftoGgqRz~~*bF{w+tlT>>~^~j%D1>0W@0wIdYW|I#AaQ} z16MjSO}6_C18n+v?fxPGFG6vCFT!X%bCj|F};4gFS(DA2|}vN%B~{RgUDCWxO}J{W5R+p`6T++ox6XT`2#I&A3fc7&YlcZ~V<<|+{bbTt$NyPYr@nj`vhB)a zzB7wqdC|7UFUP&NFABycZR9r4;uD5$oUx_*XGhH6+4_X;vlUpC3UNxO2?4z6^9IJM z*3wHe=y(ks{@fvH5CeIHx#pzd$^~105Gczazho%rA->Tw9un>masuMAfVEjg!7}FE zv&)Otee8dv9YtwUcmQE!%}Mx#a9lK}zzJ5yZ~8eAuaWv>=|A0-4WSuL)t#^epa9As z-Pz%o_c!AGQ-5sQ@m<{?!+=y{fNsqUiH$9+7SmkbFT!QPHM^5TIa6GaMmSKF2YlCJ z0Idznc9wopBQ0AkEL@qEk`YesB_OGP*S8!HTv`{utr`g3@AU> zO|zl&CZny7emc}oS@MH5bOTqEO=`%$Iwwy_6V#$PO-~hulYt+K7XGv2WJ(^2FeUB> zDS&7Nq0tFLsiDh3Ej8ja(4za*o;v9X6yhTt}%?a5csK~CF zWSU0JaE&(Oq;X}{GAROt^Ppp)s`u{JYQfq#%vlR7iwLJa~%e+Ej@-@Hl^&GdJD$`*wJ`(hIj{ST&<5pLO;PM1PE}@5Q zU-HDP7dTAMq&*%Cr7`@o{`MOFnTHj6bv5^Py~Y1 zKzY}E9ke=TIm3uF(t+*rFU>Ge7JlNRL?=mbWUjs7clYMD&5T8$dg^F+(l6(wM0v53 zPhI+iHd-QFcFFyEvuaF&flVt|>q*CbO?$nEWuWv2WC1;u-r=Kc;q*|8$m?8!uHU@Ov z81fYTAL?L~5#dfQ3`k2vWQ+@f=DyxmB8hwdwGJg-XMxpYL+5tqJNhjCBIp<{@EMj1 ze}_ZiP3M>9 zC<94pVi&&!n6E?K^42=wb<<5}CKmIQ;;Iz0`!z;0aB(8_$#tBTR)rQ2YakDzv|38| zpWGw0>Ho?-rdAAD`M)6PGSwigx;|xzozxs~gqB{LV0fdfcJLf>8+Hf7d4|G1ryGTJ z{wP}7XfQUWw6U*kK}coEsU}9|%DLSNG1(8|u}qz{=7i1k+D#gwhl%#&+zd=Vx&4tn z&cI(9tZd=y9gK~Q4I}8wRxqeILypv=?!l{V75lEIG#wX(!OlCwHe!dh>pGdW%B;dx zL${jc8JhYpy{_tjXGQ>3ko-1)k>z6GA0rEP8?$RHO7}Q|=}dirBEw%Cpc!+;P3QzApwp?ae>x^4UAZ%}f@y*?4E2AVq$2a!Qd=q*oyvuT z)20*(QlMcz%Nv1Ga3rUTi%Mex>r-8&HjpQ-u2KMOnd;2dWAQw+;p_;}K<>YsF#%go#^S^seK zfPaG*+%du}_%>D6rdcDJ8br;T$D(sQb#P=+EvGCUMPjo}`JUwT?%MXNopI6#N~|Gz zAT*)?Wodoqz}QQR+dRyzwwF1VG@%Z%P{QTp=BDxJ`jl0ec2dQ>ckLh7?{D~>a#iL))YsWO{zI_%AEW|G$DazCru-8<$=AiZAi9rAL~ zE*c98w+7pBSp_}WEiKU zKFd&x-%(-M|3z&0cxI#+?SZd_DPlb8YW4T44U&01Q7?b^>wP|fz_v{ok9RdJoXOSGMC`V^**n}h0=WQ%2S8k22f#;OqY=}$qtTmOiu>xo6y}Bt=i!$k zmcAmL@FZcDPQqWFqgmkbeJS_58#!s+A40l(xnruqRuZT@$tbEHkLcBV+Xz zVmaIiLQ5Q04!wRGU$@UD%yv9>{-5>R-Sy-4eRc`kovx`f*%2Ag^H9b4uS+v+VDImj zSHQI$RaTenTmpSMkC9Dzb>ljF%F~dfbNW_@QL`y8Cfoz=wUord>wMk7;TWqQBQIb7 z?zo>&S5J}8Xx-^4Hu6!TWEFM9YYsLm_?MWG{a>m6l@ugzJd4>i9fzI>jhdMO07vo?U_EoTjzYT<?)7bDYE)1vc_f(6h@am~y;lj*?H zjcHU`s8RSWpiH0*VJ3Vd2%NALH19huD?NvQMWSRm;`n2t_+&7)y1EabUliyXVbCaK z2y3|{&|sk5g0j`p&SPb18T=X>7MZRR;i!REB#yHffsrNLkW&(BQf|(nwfW-%8b2u- z&X+khoc7KdpswL4tUVEFyXME3`}P_clr=IdbIRa92yHF9K(NWX5-051!GkPJXzsrAc%C6y#F4@D6o-+c0Ji z^js7|A3Jc8$tO7rMyb{ z+&A#>trje@5iqwhOg&v+Ht+Uy&+QDV==o{&E*p`4&;!LF0<2?^APhV-{lHTvZKiLleu1?mhcF}5r{~2`m&qDjkVisk0eRo2+4|3qj&O!9jQl=w zD#NXW?2X_DYv}f-tHofu&E)!-&8*9z9*b(M)~(A0>n<#Ecf?V&;XtPTJm ziBtn!1x_=%}xf>;!K1BL2*>Jy9 zS!h98=Z8-wLkG=n>K5s-QCZK&B;&i|lvC9ZUte$KKcJ4?Pq|+mAQm%s0X(m~*zeM> zyrS#mn2>q)HWz#K_pbQy-Z~m4vwh>ec{4S}#H2y^h2NJA)TGJT0clney~VDgTZh3j z!WNU8Eo`_l&DPq$YFz-V9i2QRP>_a~aUpP3an!;9+^K1(V)=4*b`l|p<;(#JNt3_} zJ#915^C|*a0~N1D*W^N-FaLZ66Oi|Q&*R80#@^96*D+)y*|jm!IEfrhr7r)FiqP^( zk~QX1YLR zII3uV!c2y+E$&WVYnY{gl|k~h92afk01&0A2)2|05YT8qM8N_Tom}&M$B#7b_`H;i zjcL&$T1zE1za}I$$NpB=)L;N${mOdJJo~e*v5~he-II-0I0T6X_MDp<&miQHyXx+W zA31ZH@hOoaKO=N6a51UV?8M^D znk+Vj%9jf3i%GS9TZ&UKNcX_!3$g}6bq=80mYddzgS187&#w*YWT%TSSlp9@NmXOR zL3sT|kWeBKk_RzV5ZE~wCY%i04ld&2yM#EZrlXi)@JsyCgk{AtzNvo%@%#r?2~(Vm zGf!+D40cz%pFhbHL4ay^ZP6JUlS`>=oSKs4Ddo=?h)RrgCOLmO0fvk!LotaE74=~I zRxR>h0xfKC_7qEnia`8|leQ7cEXJnP&h>qR;iOYEjq~`2mMm2Z+?R^!fZ(caxg~>I zpSE&4Vi8=0yp#eUGHbmeaA{>UlC~$a;rEcW%{8GcxU1l*hTcYTRYdnS(`MH^vMv!o zW8%K3WAhwTm0ZQ2+nT1KXZT1~mlgZ}kFvuuKVfg+{|LVzg6vX1juRe`+i;Riw0x`wv_sls;5m~h1%Zi^gPXO-sCSoX86I-RkqcwuJGTH`TS~k z+y~XEcPs!abM0}a;86R6#Cm_~aF0Om*ZbQ80CUcf){)|ai7gMB_H?;!M_9&3LMK7kQ zHR}$3rFeT@FWB2Wwex<74Y12tR!doT z5zMg>{IrmLpk=-aeyo@mzbPcHJ9OcJ5Q||-xUtr;)0%IYxWEp-_xtC3#J2wB+QH^f zY?5L2_u`-O>+{Lm5ztFnk@#l*tneQ)0o|QcoqSD)z#FubKQS#1zIrw~ch*7W)9wYR z*nNH`DU&gIo73Jsg`Imq#`M_+5UXGVWAgR|WmPH-X^=Gdtj9sd+4;40TRJzlA-Nd~ z77f1^DGuTO-uT1cEH@~f!CMug2a^O67j0o?f(n?van<^M8=rH=*5&4&!=R;Vfh36B z5Jos2G!ul}O6k@~G$*mx%T-K8{KM|&op2p@_jfwtJ&(H*rd6=2gnwGCoMcK=d>^@gL6$Qq~oY5C#F8l)g+LKJuL3U+gb=F)1O>EGUZm&V4c zrF>xcM@2HM=(MB*@e>XO7%t`5Nj>NH z{^I{D3Vu5l;ryVR8D7DM${bAIoNYSsfyUY;q=;{!GP{@qElN8#E6+!fOVD`ylbKxuyS zAwVfCZp`kXjLL3^Bd}bN=&EEj_iZ2F=j&T5(q1d1C1 zkmvtqLb)XftgRibD4CvR?nz4L@ZBg(85kqBLJ3*edHHk7>*D$fG`te(lbq+X zGh2r6d62#&} zyL)Aj>h~Bz`2dT<+lXa(uNXH0uQ$9)Ym7Xd_2!dZIxvLvV2AFG%j22fW0U`R3oKvn zXJWI@SA>+S_)QJ*gU09TiO)Ym+RTVfNr_32aSr1!B!X5^D5UjwBHuu%*Ik^G(5upr zDBI=A<)`5|e@l;Tmo%{Rr8u`3uvJyWXsV*;sh`i%>S~l}Q+vSt8qh^F&;=YaktI7O zLErADH;`_;LKL^c!C1DGA}9^}2b;;OCyLk8YMAcJVN(vrXt#`B8VBnAU`sAl-Wl{U?^Xl_nvilv^ zoL#QV`1k=-!2LPkDT3}eIC?Tv#wuN%zIkQtcsilA5(hZ)8LqnK)-6t4f#*I-3mYmfm-s`16+NKF`-9 zbpf9?@JL99MBjHrx93%Lv7rgKm{BR}x@6ZgTk}7guy%Fe{yw*CMYU)$)N9wAUR;O+ zV>K7f;H70I6_u5L6(*9RqkAXJFw@syZEkAb(u76j! z!uD+UoL-%U4DAOFoe5cK(a_S;?KyY!KQ3d_dCMVt*m@~qw47q3&;965px`FM4E1p| zfQ5RZaQY{Pgs68altCB7Pz6`-WkN%^r5v?vGiB%m4sX-IB8OLfyMVbj_=+s>Sq=Bz zhueQ9qvRTG>h!$;S*^DnIM&L2w^k&djHzQ}p_fjO&N4=)r$k~|cVU~t=6p3w7yGH}sQ+`zld`Cq4~>k%{ZFY0%kT#XIV4oPm4jq+3&u9q)PA#Mi$(O+ z55o%4z83rnS@a24bPkzF3h6;Rj{%d1!F}4mA-(b5=6(dCOK8%WzGMo7vLU#%B7iuA zdNL-+(Gj7lI#yBX!tZm~w-n9zaIgsQP2uGzzsc604GgIBY=s5ng9Yfn64*o%;CB(Y zv&KoMJ#jdCL%d!;a9oi}=dq&6vQ2%8MQ+!cZn+vAH&7k5lWyB>sU0_sPTGGj!%&Us zNGXBP%D^$#^@1a~L~&y>P@8nX!qHRT*XLbHNJ=LUiuCIMR#rvmdWb)%i)NvVc=)G0 z5^>=U=I+vszncPLUX8o!s(n4AG+$YxgH;8!q0-lTKAHue&7X=L$Ms3+Z^512zC@k!&&H0ExA$FOgc1Z zA;*A}$(K4Eo5JQ@-3&nO{_D>{Fwz%>*I7w9>^Q+Ja8jbs?p$c!LLJ)w&A@dlM`x=p zcoK@lB+!K&@ZNU8+}4UJ+S9+T;@|x#%qk$b6XZo9zofx+_mGx#`>>j+sA(^`l^Oc? zqMoB?RB(Oh3UI!$Gr(*ZvsOCla5aD{K3oiq8=KYv$_0XMUrtqZPN3> zbOvjARn=j8X4FYufd2Yqr8HNLd`jN*Km&J~jQ54E-t4?b(L9^VWPVKxLJdRB%Z0&r zq{prgmVX}+!UJwSFg?8cWifAWUb4-_cU_f#!O99M7NMEMI&D%0{|oXlu6OvERIj3|;o%FplXkDK5)t-x_E3IT^&h zw!v&?*+?q>ykuK}8>!|_Z;jtp6m*>9lXb`aAGsnI*<8_wesSW-ChfGz;GM0YhBL1xFh{b*C1*ukcTy9gWZlA7mGCA z=d0wmUrg}J&)k9HZvi|)$$y=Oa+yyCB>BoF9_R;92+PwYBlE=~nVOjd6^wST(dBdT zhB;S#lr)n2$)0)ZAA?A3H&nwg=wQUOen%4}qLfwxl!9p-^+A+!V8eM9@g?3JA(3|4 z09h*>#_vOnwgJNtg{13)GDp~Ih_8(-8d;7e(N%i9J;Tt@6q35vyH-m`dPS&w3Jv)5 zkcT=HfW<^ti5SG$N%Qcuh~-dhqyh5&)#a#Jm$bbue}vWnM$J$k&+t1E|rM-lxoz3?t0BZe1;$|UOZjbVvn4U1M9iGfm_koF~Bf8+Y{PMh<#F)Q$_X-pd zk@!q+iO-!Lgr>>;hP0xQZ)F+{`9#S^!JOGr#p%&SUAe*yi6e!7DGeo%8&9AMQ`&2; z?K&+VOKCR246hOTgW6ZnBiU42Bn*XaB!a4@p@Bb`E9u6Ii+5nCrCc77;$1R=dV!bX zBl3dK^3p;hswVR)>6(_bI4y!fh)5AdB=|ccuQkqV+conMn=wc|6|>d4qJuFz$b_Oa zb^Ns6KCB^Zq9tK>c6J&T#e*s4)qR&c*r6}~XIIPRolWCtFbWrCX0)#6^^a=`V;Q>- zHS{Q{^5^D4B^RjSJho7>t_@uRh0=~pZeo3Hb+C~zJwEF}Nl-aTfS|+&7+<<-fxSE! zX9dLc+h!oOlrGR~kL#iGx;(-fwtSKPQenf2EFSnUOjAo_vG8K7042b;6)Pfxj4+~P zt8WlOz?)WNWHd7qRBnNJ=-}T$_;5kHj|V!NgEK(1(-Wu=3vAj5b}1QT6(^o7_XxEV z;t@@cy#l6KSD=9xeqmD~vj^JnW3ixLj&wrMHCW%l>N-3eTDKuZ{AIRXC!x>P2!`Td z9PC6`*6dB)TTrG8(u#Ee<%YdD;Ip=iI1q6G4@0D?w^4w#@K(m(bz1WN;c4kdbKTbm zezCe%@6T{jy$TqGm{z{Pni^J9h=KMq+nOTa%~cNs8f@IjjbWyvj@O%?}35eP|GeLWd=T1Zr$>m%mKY`fA(FuwI;XL zaPnp}LwE0_(=>YU`s~t=`EM>RL<1ZI1>R1{x*x;ZUK(nVmerOuTddjrrHO&gE22a1 zv!KnZ*_Pi*FlS*I(=Zj4^MqayEG+}TMrIx;u`{>9LVYn^-51p9N-PqU7A_Qc^ShB+ zj?10p*rb^eu9bm0WOpW5*ey@v8nn9JJ)s~A@V?J&8sGMJ+Ercu=mV$;gWio`PXC=? z?iTrW?l05yo$lZ^knm19lcA+*kE0S6LGFj;OhG?j|IK9bQwq;5ye<&QDqpp)-F7xG z`h4d9woRGZfD zUc?BsyVtDlH#ZcUjsv3P6^53AoTT#Vl0+Mpi!L}qnIZWr z&l-(S(f`Q^Kj4#mfT_V>_w>QYNDDU3mIAq@BtEQymR?7F(9_6FlJgK;KmO_9qk~w0 zM0{yr=#$HbJA76MSE1Iycq?ShyDth|P2RpV=205)9OzI}^;Kr%#y%b5CrY{wS1&gi z9c|cxc8b9N3%=P&aN1_tXEVI+&GIfS@peEAg*7viXgXBZPA$GSf zPVG3e?mPgE0$Zeh4Cgc~Da@anxHuyt&mis{nmU5+D$O*ft7z&EhR$r=9HTa8s8Z05 zEy6EMtV3o4bJK=l80C_^Mjzynl98bwaD=kv z$c1W(5Of!gsKL%nxW&kkp)jN$TGzdnutVY9Dk6l?14yAA%^#M^LNA3eR zC#WyhnxGfvwJTotR9A0M6092q+xY z&~(PRF)_{h<|QLOmxV2}^0>L`9}C;qpL|i&z#cw!TlReFP}8h0N3`396kjR;V_0)2 z4foCzT4DkZuLQj_%;x2kB|fJY;9vOVmCfZs3ky$t?p6@)Ow5QLn$0P%EC!Ph-(X!o zq>AU#j3PE`>Unz1*VrhhK&Y^{?LoHYQ;t-#jfE2ZWPFm!?)g!$Oy7h=H5X?{-S35l zl;1rbRqExY*-;3u)5_ampY(ev!u{7Exb3?4G^VI%G5Mv!;l+@X?}rh3*j(5=)-&rn zHle2GFEu*p`j}*;IKID>eJU0qak-%~iP$j#cu;Rd^ zq4JuVqYu)0%9Ip&RZ%KVch9OA|J73;Ehg}2)PNTETewceIfD*o2%@he(aW74yq@CL z>$9tYsgKC7$*DTSkw^?n-9O`TP~alYL(WUfFuSB4&D{%_3(V$44;(&OwVwilzGMOr z${|Kx%wm-tcXVH=g>Lie8XID#n994yOl#QLP5tA~woXP5Tnnc|*|mj6 zdo^*Me{ht_pp zsyy9j_Gj*f)RjXPj^1-aMs%e&T}JUF$#a%ZFB)Q15zs$#1NW1{${hEo;*m^&k`kKJ zsl;Ln?u5@*-T71e zig6s7{%2L)B8Rf5mQ_!&=|Py?FJ*aUgaoyQrJzh)UJxSna3PgMVig?&Tmrr=$e(BE z#W84gN`@pLrCjTm#`EaLwwso0K|zfrog^Na4Z$){^L0{7-|7)tGIH&B>~zGwi2(sx(>@$)T5&( zgX^tPvJ$jl@7JvyGX`tk3tTJy=JoZcCq>lA2!W{c!}#L|=kVE46A(qpkDtH3$Y9Om zDk1MiR}P30=vu}V=^$Af0bU%mPRpGL6%NFTZe+d1a^c=P#H_}R;= zaQbwVtaedcBV|-;_Xwh#j{^2J%`d`}kCl+ku8=?wLE|~32;>6fAQ%+me2s)NxNt6o z{ks$R=2#HtT6@vr8%8}@3F|7IczSyco_eAN^XI!zQB4*-&Nl&-l@Z)qVXx9tGD`SI zKthI!^t~KPI|xK2$b(zYKCdAVWmiCyj3-9Og)@&EN!NTY<4gllhHHQ^a@|fg|Ia?# zMfSXX3Y5BX^$NCZ*^JFw9>A8(TY0^e>r;&+Ic9Q2AM^O`SLX6cL+J6UQkI4hBl+rU zxzAmPLt(NYhp}hRUi|rk4{+&HGeY5@0_~oA?m0a6*kh=hTc>P>fV_w`kT%g)lA5kD z%4aUj_!PzgQ5=dgkJ9W{d4H*LGpb_EldmX5y0f_lHk$*H2*@5!Ad0N5U!N+(fh$Cn z@_?w4B0qlf>$7e*ORH|h4R;-}XXcKi97i)o2)k1gk zdW^5tBzHOs?M@PO_K`6^jkY(gW&Er0I1M1m+>Sae?V6w6s%!HcHDBxWb>7<5{`ZnA z?J`l@Ox6ZE{0|01-D7ih7KoZ`G*0qN4^-{ypfch0q?c#2K$LEoJJ-$cW4RYQ3Ph2d zzN6#YWki`8S&#!#Wyro*So30u6ymi1 z_V4}p-G7kP!7tQ2RxGYB#Qhs9v2lG7)~~W+=^{DaC0I668S(2ap$UWo76K-uHaHo? zXJ7Q=>*Hj5=^G?fPZU4fxePD7unbF@oLI8ZL9oNv^o{~i6TAdD;#n$!G7Ka@lz>jc z5+m$2JVz)lJPkyp$c~nZ@L(k$metvlhtM=nox(089+4>0=Px09p_wcj9q8-rL=j0D zs=aQ6g8{U5cEaxqQ_fQ<53}XSx~h<&4Mr|gu2M6C1df6PmwH(27M`+)d3dvvM9FF? zLOisb>~PCbUbBRDDQfGym|IVvhtxx*Xc! zXN3xbBqXFnVv=z1OBj9R!|uV4)ROKXFME zrKqpGbOkhY5?FH3S{-ZvIW%*lEJlqX)ME7w3&~}ia)A;Qatffo;uL2aYxfP15uJRGt+B@ zK@pYZp?a8h1jBWOxqY-brFvsMkQXs` zJ6#}(-@Tv^znmeZwg9Kp(hQs`hhwJ) zaeX9$FoE1^g0jzVtHh%Zmt*k?JC-aXm_&h8GB;!`m%q-IEKZ4>sBZ$K@an*!YrUN3 zY0kqmUf8w(JDyxX3L_7i7TZxk>cJ%EafWloN>Exb2GtMzu@bBxy_8zZgq>4SM0K=r zZBAe=DWYm>=cu(p)(h2lr3@H%HTBU5`Dv7c2KN$EHdVmET4xer~?!Kf4w8y4;eM z`P!WJ?Jk2kuOHjBZWHZJwR}4K_YOqqd8*y17WfViHw#3~umkl#)viuPFJy8r*Fp_7 z6N)GuU%TdX#c$Spe=U&T$8s-LUQkn^h|1)?_L)np`%}B-XS3JeUkm8Iov`xEj*KXsjO3+KQ0WU0Ak+e43}MN#Ii~0!9(dBEKuF_{f9jxc;7$zjtE`n2 zJIfc8;Gr#**tD?-_fbYlQzJJa1V6IbB-b2Lu~;1#8Mg31lO@|r2w&{(=OJzYokIhp z;vo?A{0hqHSdN8_4lHaS5JhSLF&xqgmoVDIsG~kK=Ss|@q<|a7*J~T=FMkEW358MQo`0r&?eDu86*|dAkqYDEX9TJ^RUnp48xb;!GS`=v({1|z6jam zA~-zrVe>Q)q$4ZNszNMW=)@dSO^942VW}hWm13C-lWlIWH;cg@%5vhtILUISgJDCKh`?pZa+t~S_LO;2s4Y%W zt`jJ4ilXCr2yw8Ds32VL5ak^0}}8%9nmYF_aNkfB`cQCGp47P+#X2 zTb>+_az>)js#MgE5#Ah22i5LaSnV^3%Y<$UM9Dc#8>a|69;}=aRD77O-z*(w09*7bEO2(ViT!2j{A|X;2 z`UEJ7;Df*T@zsd|^!hp}h(Cb;{cl#{zx~%0Y-7qwBc6Nk%MtAQbO2|&0vJig37!KF zG!+ntFQnk>3T3VKIKf$AyQR!FB1!&X8@k%ExNsqkeTPSI`1A^Luj05{#dTJ~%Dam|oPcY2b7g!PO^uqHJNmgXmy9=+G`}RHizH!2fhbNO zwQMqsS^@dKm9M!KOTq@q5E-CzJ5(1|6&guF2rYNNfE^{EI`zb)egMzvYj6h z{P_KE&*0CyuftPNgpz_nOb>{XbynBkTyiP>42-#{%-1tW>RyX7IxpD`vd5nVqVCKQ zpw}?%PPG;~{45YP)fW41;bwuT8MdDusM^)Zm|voDEnkIZqBYN)o}^<=S3jF|zn>P! z?_;?atAHqy;qNbe+M9Hw7;2t zR&BTigc9l*{)^?IC(T2TP%(72XDEv#jgLOPj=y|rrmKu9v$2U65K2G<+0ct-vxtv!l?F5LH@Cun z{3t?~n~@wDLWQ8SBmyCQXEFcKx8XyKE6n> zoJbo}kT#+b@(F7(8$}M+)aXYrFm0h9DLz(IyRf){a#5OW{Q7St3!asN&v^`IJ1KC9 z=NMOMhRT<+s4BLgQrPUA)V@WOOjsVJv8BBYBWsQv<^|+nA6pC-v8*CHlRhzjNoVO8 zF;~LT__-rm&R=?!9W@S!lD08{PPv#9I;!7|(v6Pk2?Nqo!j3P@%|aS=9;>twHy2v+ zk!HzXk8hsX^q!2Xhc1J1jrCqqlQ6Q*kB~>r=kt-cFMu#@g$OIJooC31QZi=bu*>pF zM<|3=CulB{_-SkQpZt0zK-8t?G@6@JICLP!gLE9-!x!NToy4YPr94D$B`DBDYNQN0 zddGmMSklLNH-gu8EWzLZ{RV1cBoIYF_UxIV8-XaY<-PGHDWXaUM9DhDYTXD#8TBIE zz_o81M~2!%9X85VvlStebdqh>iuR5yzC4t`!6PwT zzSKuHy*@0ds6oS=8a(=l2Rom0kj0McE~l5k>=4R93aqn>@P9Yw8NuePXjYKEr14Sv zQCDXN0Tc~H)e`*ToHkD#HRk2VsI&Y|G;Ym)axL296zeXjt@_BO{GV_ACq%}Qj5pD` zBtX>bufL9s8#fXdtXFcDR2rsy#&R^qtNDI9*OIPSW8N8c|JL}q;jE}lIZrNLyntiJ zj**h+5ZT)HAxL3Mk8In9haY;FAmIJ9n+WJ7$>x|;0K1* z%Xmu(sAM#|JYlztnsGpsJfoHOn}SE>V+tb*U~kEzh!P-5Wd9vI-h*Q&d$D(aAwE7y zil`hA^)!K~*MA~%%6$0!?@!_5Jy*#BUP8HpB{u+3f*TrCffIF@v923y!f3H)eqqkS zd_D6N@0pm!T;#}*k8QLg!y`)0nJB54NNb+#^TmvNhve?_{ZznP^rPl}E-mx5Ir(YL zUvtE};99qdcBfh;9ex&wnre%Ew{WvS)C}8C4^-{yWXy|>T+dQO>6W>3-TXe5d$9_L z;vu7t0!42IMClEgd0a?K+{-VAJ7y%9HnFr3Q<&2hwcEW8mW_e*biq7Q%L zp2svmXs-UE5Tz)h4hPUXbPa(} zGwxqnMj&c4S@Rk(OzOq1{wTiOOV+$Ytq8|_6v97(pFN!eqDT?dPs+h_X9+}ocpke? zm{{`!i27v?h!Qp{R?AI5RR9{Hpftvv(Pu(kWZ@j??m>apIz%+9bOP z)&}r5uPnf8zgVa!7|RJBpFbJJ*Ly=adSVF2FZZLvA4WCT*EwZgY}r_c&7146V0i*f z%j0BU6(Q*^u8AZiObROagmph~DhLlLoje46AKqAir=KjsvZYRxmr>?g zAR$tXab`SI>lRp7w;}dMxWn zuXMR2(6rKFI~aAz@*Q-I!tKxEz`=uxx~qR+02?=~r{==@v2EKUwA)x;F0HJ)G@oM4 zn>0UDgX#$>1*Fkyk%Umwl?h6k+L(bT0f=QDW#pa901}=zEP%+;BSjQxaFvWGdWqIN zc^{uXg7BHZg}9PAR8Q zD4-cxF7nJQ5S7;;KiI7vzcPSkN)e^!jCOBFWz2Kbd~MFte0@90@MBMNv@fSoP~Db4 z2oNP}(LH8nfv6dFxE`q5)yc@D*Ari!&B}<0fDawe_<3hJY{=N2} zb$_HSz)gwjd)ctkNdHgDnkPUMzqIPHBK>WA#5Fd-#wM8?USXM1+hK7SMu4cO70p*u zxNU;w7XnHlrj-N)a2WiU{nq1Z@~e*(t2m0S{#xX&|bH)JMHM04E6YaLdQNJz4A= zrAQT*B3WO8WHrA$i{Myp+`IbQ(AC#Q!Nk?1Frr{&3L+=*1vP3>U3*(E+WJGN@HU~M zV4+gC9iqzZ7}@rc6c%nFm4w4tLROn1uFnNb&50!01QW3ksXkm3KJG%4BoT48qsYNB zx`X|!03ZTJ1dY7p=OE6f*y9RGMONaX=DLb<)XuF(Q&TyGzf*n}DW61$xybm^;F6c} zraU5ZO4xj80=4=1!zn%?j2(8MR=5EQPJDS$y)>6#lX&g+a>r8jcL%;l)LGYFjng z^t@QIl;CkK+fRi03lK%YZZ_eiCCDpQnp8e42y0%qrifyn*UTYB6r-u0*4@c_)fdto zIb-yVzPr(t=gLZJvE4)~1Xw zT>E645a^Tg%lMTxq?u}dMretq8(;g3cQp_tqfo}5ScBD^adZ7-$+6}s?RoOv;i8$z zh_G@yE?i2GT{4NkejdlWhpCN&?`iT_Lnxwt`8t(bl-wvI>Uqi`+xhfDEM4ryyt(`s zA+Ix$AE;)<`0~jZ)0D0GPiAzVtCNarzMfHHcXuQ`*7cZ^d$DpaYv@#2^K^XOTKV_d z|5mxW+>)NY)_H38R^@f4rlZ?sD&^NqFo(C z28~$luUYfH{PIiu`q#f!3)(;a<3HflS6|gpjKz){CmmNF=)srojz*fj_}*GT_odEI z?#0dmQMyI$5tsX1)%Q~bqMQndGC&O(D`GinWXEh6dEt<{MzQ7@+i>wvUs~l0?1f7y zbx`}{(@S`7&m|Olim<4z4qG3n#M3(|`-mFzoJz}@$gEB&OW`KW$APPtGB|rOjT5H= zICgdb7uyHOiq=mMX^b^*K3VhTku^`th)NP{icv07f}g0>m}gO(3Wy?w4*?nZN^eOe zU?bZ|G8iHSlpj%F0Lf4UaeoMb&R+OwZS8%qw)c|dE`S1C7{QbU9dS2;WLI-K9h840 zfC($l-G3l%Q`SOCFK1N+TqPxNQ{zyIfK?v_Y!4Bn6OD5M?4**zv?JW`mr(=JTyEtH zNHt)^z)%eB0|eR#2ox8(P(-QTiKqw3h=)`iPRg62jE}UNAG}F%Who@MQo^`i*wSRB zBej!3NhI(OK?ato(2+$s4-7@L9&!qLNU7u{TcC$uvxNgrtczz;56Pm6iwaO$S%Eoo z$tJnPM(s#cP0zJKzVbU6MhGfw1l~k*olud|M{Z#aly)_Y$|nzb8h4x9>=-%gSoyB>k>r#Mod1~jWA!mTym@d_pgZ7F zH;#65MIHx4QB8e-U{qCgHHAsfS3p#TKoy4oK`6G4AdELPlCZX8fy~)W)Rb~)HisFD z$-a_z6GxO-={b?RlSo)_^-7wcb_)Bx8o-{z1L*1RfIrxVjY})=`b(RzW^E$@;|%%; zMD5<)g3tDoA}Zn|C5Q=#qOfx67Qk7u(7pHRdF(mUig~3}22fFeHw1_xMN}by@i^7t zaSO!pFBDM%L>cRzQ6`RW1w>g%;giDYvq>C37Q>MvVKjG;`Y;tknJbN-K3{|vUMeCm z#850pIC>RzHEI`(%KAb)mqL6q8{L~EUqQEGTq4exiHatThs(zjuWu$&|bADR6 zrjbC6lwCFq4Oy{kR~ox^r*OHe2Um%zEv|CmffXg#w62)!ZpCO?#tltsr7G89X01|!3!_Gfc5Lw ztNM$-G8`Lf49NZ@w-+@YO#fHC15DBMUex4u!{un+x%XX9cMsZH+pv#pdGEdV9z+9R zW5av`XiM?TGtc6g9XmDFVlgXbluImAvvZpKvWQ1ri`ieeaOQY{hi~r){lieE4Y`|FNGy6yIx{MT7nL`}QcM1@t%P*Z}zP{@_Z;}e;uVa%0Rcog_*KvMGAWE0xUg*bJAZoHvImt6U zP_=ur!7>X(P11;W$Rpjyy0~&Lb{2@zEpnH-Q4Lzl<9NOL&M~ zy%J^fs;Ci*z!Bv}oxaw|a`z!hswS~D)O=S?&LUP^t|y*p37!fTpBebG_at@hY`y-$jG&kruv$0&}0~%Mhdy> zoMTRcUXrqrhw*&EcbF=eDWd5z7b};z$+;nn>DirfsXBm#)vl@BW*|xlD<=?DT}`cd zJYW}+_eQbfvSHPHm(H9x8Rg4RkIFz4Sxm{e z6|L7(Xd&?PC4s2D2m8_4*Ggde8rCkU#4BXYTeEfnWubAN4#n~Lt`>ayWh|((Ny8U{cFhXynQa#t}COqO;S5@&S%+%Vr5MwEuT)uv%O@T zi~&(Hcj!$JGs1Uqi0`w$egd_$?|+oQ@4iUzUB?Dz`)*rq$KU3FsNetY5j)^Rn5I6m$KAS%CuZZ>E0 z!`X2gKR=!pFz*R-F9+#&JsxfbM3t14LVzeIztoEwXhu+n z(uskn6gRvEslM7stDP~wz=nXsM}jy+)#G1%-GMJobYMT%K7 zCahZ&cx|I45M{7u*>LVu245dc;V5N99lbPw7HY0@St6(^%HWx&8mU6Nk-~26n9HxU zLJ=hbVr85rsW~b|R<@MLeIlElmF#OaYK{{YwnQ`tYtRRKU>L#nE_65ZFx%ckYN#OM zA)-$?V^0^8Ri%V7mXh#O#!`qI{BYVyLBbxYcQ1msv=|mo8LZwi9z3ZHifXX!a~ok@ zxP-#HOW`H;P&g9ArK{I*mHGI?3HT#P0zCzoL(Os`e@VVj_x2Nr>U5(gAZ$2Ms$~z5 z{jHhY5|`n&R4N-w)sZ4=F2N`-DLz<0YPf@i+Vw~oC3O}#?Pb<5iX36e-y-z|Spgg7 z+p%adFn2yc;wz9#kd#(J{UpF6KZJ{A+la7YIV=jxqLb7YRiq3lWf}(5#DtB1?kfx+ zN}5Lru$Ci^Iv}#m=_gi(+NhNaF}X1(7xFh|~4|sH*Bp0#Wl6MU*A2C*&m6`aK&?*%J=2QaS0EHS1jOkeHAg$CIrbBT+V@pI+Pbf!Z}=)! z3lR0v76LF$WWS{V|KT|P`e_H**V+m04j~aAq>QM=N?3UvfvE15EJ2_V%B;JH{R)Wk zpuSRos3s+>yr_h%sW~7@WVi`XYe3pk5dn1wyi?{9bwc9&c~U|h3*(!wBRG7N)IWn+ z6x-dXC#d`K^AQ43QB+h_p`0LJCT%5DYH-5j+5BEi`wu`Mle9Y3~?VeEFwU& z7L-3!jm;0#5gc@~{h|be$%sphbLq4lXHHTv!AWZ2JKBML$J;3jj?YLzdS62s9@$z) zO{8U5%yqSXAwg-D)c~SIVFRr!<+Q?@*V7?DRB{xE5-n_M_DRQx<^AY;f*$%>yYlYW z*9<*sw4Z#y5G(78*mvG}N7?JwuVZj<5KBo>^x_LI;^BuMrbf^OT*vEG8Y*1@Rpgzc z))*Ei=ZQrUI!U=#d2{T`Ax?xm3mA2X!ph%&?|sTyI!%gLC)p`0@%;18 z(LPU&g_WE?RqQ8@6+!uPM(3NKhkl;#P6>!ok!01AwU-^m|4|@H<`scQ1x87a^O>-I zM=9_=LXEY-Fcn$QzWq)Dzx_*`terBZfd`k_@HaoBjIq)X{{7#Y@#p;=q@wkph*VKK zw#}!2`T1C}+=Imn9F!w9*6&9BWU$;OV-(Lw+XipqZ zY}V8J9pjkML0?JoFu>W#zk(E zKZaDtH6&?A20GyDZ-+ZV*(?d}%BlS*LUz1pILS4RT7{Cr8fKVawh|%QVakLWBEdq0 ztT-tGY+eF%4J(^ax0DC=au>X`ln%lTzZHQ*0kr}aVI<_BCOc}d^Mw%z_P`$ymb)1G zM`C1;D9L>5&vRgaPMLdvJ2 zJSobm61g6B3t2%3euX%fc}hl^-G{l(5v*EPNLH5$EL!5moCZ=tRq$|0HSRXD>J@q@ zXqFnZ*hGpVDnj`!Ap#IFf^*yM|iu)Ed?7%QbdgbQ9pmPiSn5Uj^}_V(KaR^L zq9TPOM@XS`(t+j?9_9&F&o3ho^=yc&c|nvBq$nq7A(Vp&DiVkhIEqGr>sK=P;=?5N z9gO1oa4-6OJ*cPBh9=6CdU#7Mwr`)W*zAhRxF&dsK(iPr3NG*M@K8B{8wU?{VgKPS zwD;Q39w@-v!Xg4$#bnX*;=#upSi6bxdSuQ@@m2Yi!z)rm4N+@eJAo)_dYhM{h%)9i zA4=bd)qO%&YOnq$n#T;9Z;ZXA>@yfG7w2ONEdS`Ek0|*294=qEOxENIY}vd;vFL5y zLSgf(R;%}stfl66l%#C{9!4(a>->E4?{(gj#mUc0(hxtjH)7uhgF*O5{5W>>7(V*= zBOE_|ob$%d4+b{;^rt_?Pk!`|EpSj^$4d{Zw4l z6UsI2jIaun%JrL2?HN?c^yM0x5!O7)7)!+Yre?YLeFne(eH{PuKgkXrGC;Gfd=J0* zijxW}!g%NHtN7?(H=GW#%{vOPeRD0r!dk3Z<-zLZ4hqDVdNCnoCM#<$$aiscHj;+< z`n#lgx5v$Oi5k~40HVyzqvwrw&ChPtwRujMuO-jhneVMC|M!uO>dPsvy}CTQEoXr! z-6FTwodu$%*}i&!YWHT*^+GTUMBS`~?p%NQQYrmE3q;+yeK^ySOTX*6KMF+k^r5e( zmy|dnkeWhE$tqDsxj`-gqDFUs#$hynKWKnZF>ZckJ4`T#s=_k~$}{Ot;t%g!!&`s6 zhRzWSx`I}$n9nc$8|Pu`<`Qh#>fo2~oPbxxwOT0e$RhHNoIG>6@Xa@A?A}8l>Zk!k zjgVz-^O7>GraYAURyt{2sIIi2nuj+RffhSYQYlg$Mah~I8;KK$N|DHb!o06sK>Ydz z4E466pL{t5@es;0akw}K#3Y$tC{uHy9%OqLpk<77A*j z>ULxzJk}PH4r&gurBalN);Y?S@z{FFqS(iSE-4}S)EBNsf0X4(7O-vE`UJ&n1fhyZ ziAC-4Oe>2LYd`87eOSM|01s>?5Vg!p0pxbdexi&SH;>IsyU6XJ72uD_Fq)r0#4t5L zg~MbCOhy>SiJF@ERP9_VNscp0!=O+I(0A;>${p{GXD#-h9300*zwr=}|6GFS<(Zd) z>DCl5KONH}BSLEvU|@=m;*pz69BHwU69Bg#ub_%cX12=pd)+yQx#bXEE{^nuQm zu6~xEhW5_|RWym;sv#UW)J-5Ng(IiDxJE#z)?I+c zN*7*wHjL+f5=LoxDOqDn6$@38T0s?65@$(YC-BwoG!7q#;^dWf9B*r<;Bugxb9Kww zIy|bPRk;fg)uw@{`Ba`TN4Ox>+%+a}t|O!aXw^GF-28|I+{NK z06+jqL_t&*HZ8;gQgz9A(G*d--nx7f<)fczcicSFp5t8A6ZDaeF^mW!mp8AmI5Pzf zFdm9jpIf+C%WE!0*4DJhgCeCaab5hce~IJ&{#^{$6%dud*2Q-G{3isW2ztKvUMoI5 zL^+An{%WOyjEC0O@SQ?o`0G5_u*OND`V%brx-hre9jm6f%C|a~yDPoi+N#FeED&{9 z^zBsEj{J&B95MPG-qqPfP1IeAYSZiW@PkV+_j={El?Yu5mx(&+2$BS=H=gI{rF11&N;D#=pfB5A(f`Wl;L zqiu{=oNgxpkD|uLm!M9T>?29aq!{QW5cT$Ty!EH+=np#46>(yHVhxjo%m4yy6beqjDHWqUsKGvDhx#Z#hAeipt|Zl?CkcAxfT$?t zKJ}9gZtyrrnkQw-kWr`>54A3SarSzvC<~?-Wn`Nx zDbAv-B!aTi2!@7}WD7~6v&)8-J_o@lzU@W8i<~5^6!>H-P*h-|$gUtoxl*YP)R3*H zuEx!Fb(5Nclo<;NNHrEx5P1R0i|nW%%aFit(&WR#1L*7PRzOsW0?*wPxLZ@(KuU!= z)|X)noKAJJ%yS`(5e7P8_)+@~=1XtmPPrcjA?&b3hcSaITRO>BOl)e75&2zPZ?f`m$oot1KP`qKXMbCC33#a?lq5N`NuV zn&)OycyRjkAc3eJ9R50nL#LdiO!AK?879D>C+$)miZz*`BvQW~U}Z0`;V@65<@unrWaF0z{3VlfYLh zp2Ymdh8Y1-`FqCvy@0%9#413BW9Z6dLumQ#J-hMoC!g?r(@(i{g;=?AC0={&H46QH zM%@=uEt`^2CJmJ{I&JN0|8H~kdrpU&D1LsJ(R&&0T;OD`2y5Y`OP4tI_T%frhuQC^ z(Mxd#JD%P_&3R8_<$WuaRWcQGta)Z2N~ft^U7mb*be`ou7`@jk;8@#?0#PzIrOXP5 zA{eERMG4P3aQ>vzd?*+a`{G~zDUSc~y9D3K#&~{cp%t&Z=;V7pj`u$3#wP?h9c1xy zk}C1Rb@iNE_1Lt*i%shZL{&*5-;)`urt#AHp0d58vypK?BV+AOlM$uohn}a}HEMM4 z{_1wouC&BNZDW3}ufJCyO3zpA-a}nB3q(z`v-JSgt{%|(-kh8~(-cv&TJy{;b7x=Q z07UinqJuIc(%eLqQm9M`DL;xzicnCP6I^Sc1*4VLV@A894`wfZ)GZ)$TwB?+%4S(M z+I>6}$iYBuWLbkUekl=|7cPPm>Yc(L0UczIBljkZf_~J#qkt%RPN0MAZ1E7~AN3^h z)?3%{AMajAC`z_9QuM5ED#O;Tl~}jYgO#f+m{ZS9vH}SxAIcFUFk=8wHXia06NuXN z1u3GA`Ei0WqT=x&Rh5IReRgahm?hRl!Q*1B8IkW4hVRNCddOBV(%i>-4Y4eKSou{) zY|8FJ(m@I@9_F%S-&3E8S(7k8<@0fiWsP?b8*kVpi9 zK?)cfRP%ABzg#}Yd< z+=rgt4gygDHbsK$KVHn4vj7#9)aJ+YiBQEDds?AZlfGp;h-JCO%6Jf?TzzAB83RRM z&(ytPGsE^&qwj_XljOj1s_~U8>?9$7ut)htn@;s6EA-9MrT@)h$`|@ z&^UqMxBt|OfBmQz0kY<$XIo;W#(&-b0e(dO#}qDnEZs#F0{ zZ{#SV%s>>y{;(+ogpxTf?IP4BUQz~naOyNEq7HZC5M@N|KS`wnK{u9Flwnn437&k$ zjwg27DVxovlC6Jr`RD zL_Ph29jn({DX)(+pHtr|@~J2&y_0N;9kd7bWU%Y=3{LkY$x0koGW1>`wdwYU>}aCw zA7OtMg>)iEPqdl|w5NcmR<0M+9x6c89BQ$f4n>rCJm`I+_7hjXW5m@5q2Zw+3=a=)d&Qb3UlG`$EH;ZG?^yZZW27#@{^_5R_&h+we2P+<(BaUHdzsK<+vq|dA%@S-;%`d z;zXq1XMw1@ri1m`pk#mg*<=Z)8pgrX_dRXCg!=VujM5rTJwY=O03eLM&Z0=iXy6# zvX@8^B`+0O52SfyXDb)xkD>%(6bM65M{Rn^1`zSt(9@Q}zrA%0|KI!9Ne(R3JB0+1 zD)7kmDy&@XMPnm@mnyC~k``GA9QL@f21S&cY$s`az9&h_s9_wv*n>=L5Kk>7Rn*E9 z8hQ9^Tu=!|*A+NBuTbff08wOLA=Of9m?dEg zhQ~_EP|3td*+khH1!YJ&ixH1fD;?FO54egj=q!TOMK$Oyvgxq?f&s-S=yfQN#vs}L zVx+1P*-CC|(DM-4aXZqa$Vid0%V3Kjha)_~ZdXXkgjx!-t)uX9HwgI9kL)r9JT!YL zfY`$}c9U(+LqFnvR3C2vi2~sBQ?M-Uxnpr0I~3)?+mBY?Amvc;Fl?*lsk8zMsa0z( zHS|TJJ|60P@Y4=b`(A-Pjk*%%TkS>loKn=yFU5V!izpnvm|FXws3gK+AJxYTYhD0x z%FGhM^gsC&FYd};b)YdWc(2CCbT=Yua7kp7 znJ|qpPkkgaAIeOzbC)dhj~$4*vCy~OM}Q_DwVC;;EzeJRH{uHLJYyhA_up9eOk4-^ za~(%Qn*Dh@9*E)^K_DtHLbkh+EOvj{huwR7(R{4~SG(GHRCOosb$ng_T5r<5tc5CuHwDNjZg^uyMmiYWeSMmhY%UH;wR~4g|%GPL4v9Rto`#p#qd9V8%G=8XA)`C zTq|}yZ6g~gHBRoOR!Xw2#yK`J1U9!Wr2u@giaxl-OZG_@$BL}?-;+`0XI|R~{H}a3^TZGtU$AJT+h64Sh4+I*j(^G$QJ@l(kFd{PzMxN%>^1-h=aX7KoZ; zaO%Nmp2*ryyE?iKBmQFLUhM4vqIBLmPhEyt_x7|vetYXpqAXDIlIoj;B1%B0iL~bF zzSHjQDfw)wx1t4f|BI`wq$@9}G|69jyL;6}Tgm8fI!K~lO3E0@h@#4HeokfoGjMK? zY~jJo5P+*oMiw=)rfC@}2@2v3_uJ8NEscMD>ni@|hu2U=0o|1prn~k2Dm?x~4JmcJ zWC0^f89^5dsd_B@(r>fISst?3ktWH?gWfmaq_AgCf?D?|3x%>=tg&vqxO@oPmjx-u zrJNLdWw4z)2>bbiutce%kH%YCiITcTo*;`UgM~oLPz+huTx30U7>H)jPnNk3>oT-B z*C9lz23y(>w=+Yb-sSL+rDk{}L&4%{wEBn878>HYktf9rE5!OKL(mCirz1jTJfm!- zVs{~`T!knVt#l;>)JT0Gh8PnMfLXFQiUzAH%q4Ip8tg=^dS$5%mF3j-$GWQz=+eGo z)TUAT#kiHI}s$m>VBb<{527B)-{v>t=@IQe`w*K#r|@ z9Ej3$-@Hx>5T!sU0itL{X!(qRsOj{Z?yCGa((n2iFUNo=p)6!zVmKknnF~?5-0uB7 z%3iqKP4>KQEU2%@RqfcKvY)LklCDE16_(D>YxdT>JNLcZC(ZL zCk5goJM7r@j0iiIgCHxVzySfHjEZK-DwQFtZ#+Uus=*Ap2PhNouQAH5ic#4CS$?_h zRu%Zr*wCqfsHdM^hRs_RaIH0T_%R`64((52*T-aGrc#Gf9RnC5z+CH&VL=tR);3`K zlMSe^chGVz;PjO_<0ExaCxw+K$(lEpni6Z~)KE*PXzpZNOW%l8-4t+Ayng1{m(6KY&#)w^CinI3^C0WU3-5hd^1fBEMq z{;%Kg<3^CrGNibxvEr%iKxsuBhsc)q^#vb>!yKy=tiOr_Y2(UjJi5(;#~yQ1D7)$9 zH2q>uFNSVDy1FgR{WrbD?(Wd}?IZUx2Ngvh_xYmzv8}BQk#I!G1}ZBrQ^2XP$0}CX zJm6Qi*6nU@U2e(Ge68~rSITg^%VEy%$8@dRM7vWhn-2ej08vuNdu-0m0#P>^nR+0~ zWAh}|{@R@=x;)d9|8@dV`DL4^EVF*!tp&{etjEE0fGBxMO+*o;`%b6%-AXwd`*yZ~ z9s}ZPEBQ?dL=hU8%54fxjnLoIFb!*Iz`zTJd|a*SvNN9JfAsuu%axZ-VVwH zxtPEo-n))}{ro!W3iu_p*o{XXuHiwWp7M*_OubcD8(Oq3iWYZwio3fz#R*W{rMSCO zoM6Q%PH=a(7MJ4gl;B$2;biT7?sx8E@|w&s=lE3%BbTNG>T9B~qsTu_6%7I;g%oJF z71ykj8H@m|-x2O_Hv1Xw_RR#R_K^)Bp}0^G70{U}wC4rc!AOVEHOIk~2b~?dXpRMb0qG?> zDl;tu>Z^h;G>{ot*Sav83TosPSpkbS>zZp-;6+AL5s^b#C7`(V$ES=ypTic^TH{gm z%@@k49OsdJd$VSYv;uD9I3Z+;I=Zh~o)suxtx}C-v1851d*2EvF?_IO%yId~JRBT$ zN;_zE1@hBb{8gGu_HAMOkl>-{R)VBjIO}>tVJ2b`rAl<2XHCDXn&47R2eQ=IAn;g% z5m8D%fg~supOuM-sJS_DhEm3ZtCB44ETKETe@&zx-!Z`HvxgbY;jf!-OQmA!v!y>p zzu|TlX%aUuvY*6}P^3hKb_9v=jKJWZ2_9+QZw#H<^sdD{XK9@IC^KjhkD1dI{3gVN zco0W@Xu>n{3gXH?T8Z~9v%5TaRZfbq#(#E(r(`(8fn@BBv-T22UN~42d?S!i+NlaS z51GaP=qm6sz0)h`wK$t#{Jus+&!zR$+=!RY&@!9Ia&st*E1hgkPJrG(Ndx}z*3fYi z#dFzKWK#LD#{8vQ7`L>VK2+WRVQ_YhT$X*A{p3tWMUOq5tp(y~)KULEAO-)8ASIrE z(o_0u{|3J{jcFV2%R%3C))e!U3>1Vb>y_1XH`tO`)j~+k z=DUJ&FQYnzSoFHXrCdxjv@KaXz7&qF3TGAjz9#r(vHh`{HJc0)Di5N2xPJX+W|>H% z&1h%(1PkZT)#ZU3~W|pH5TG;DM-BgP<;;(SUtt8J!g(#%F=HS(X z$mxLij;!itvR`G7-H281qxLu)z*=YWo)IpaMAyG^t1j6<$qG0kiQK@R3jlC6Xm=`l? zP-Go9mjPW8U-#Okk5;~!s6OHPM1cHv;S0O-wwWi zk8*}~-#!v#t!>rl&xQe%6#tJMiz(^Gsrkc76O!f#=V)p4#ifYJR4dXXQ5Kvx0tVHa z3NN~sxn4NnUIuRf6YtwJoMQ0MEYW;-8-(nV?e-2f#{|qY&effBVjXNZD6Od_u_@r) zqA*aVD3Jah2GF2g{=sPJz>_S~yg`AfqoEkjtzAJzH^ zl^=?arw*36DV+ z0wQXBB_x3n%tV|Zv5mImR{If!%6Ep7#7g@h(hTsYu&vsYTZNm3y|Tft(UEuA^&wCt zN7*?dB1rJ+!j(AKp*#OwitS*iDfKHR%CnIU4K!Y(rvAFhO9&&X0wkdb3kRk$v4 zLC?Kv^kiV*SP`W{CXN$e=rFV^$A41c$gcFrq@+E9Tk(5v-0Y949S1b1n!$8z7#4sW zmpo8~>r3U%{Snh|*H_WKcr!nlIN%Sjwf}M|a-p#-^5BVgM@%^l7ft**BC7rnesqfV zzExA^=d*d^wSsSx$QPUg?b=TIuky+L?I~Ey_d$3gThg34g8t-(*@;E9-H3_e-9*_- zyoEtxhxx*sidekZbT1Axks0KUgTWu{kbkftaKaG|G?k!EZOyG}Y}falsxsAGARAxL zfr|`@=4wwhH|K;2oGTygqs*bzw4Y?287&Ln?If)wj3Fe%AJ}b4qWlHYVJIJ8-LX61MHn( z*_2a)o8%?%ph0Ve-^+>3CN&Evmg&F0Te3~$j7^e=dNo%OTPIT>L0W5}3oXeOwFtgT zNC0-uKYv|t4t_8gIyv~P=0>)!)$=sLe-+CgTxh8U%u$5)pkakANHUM-J80jynJ5{E z=>s|gt%K-d_C^+w?1NPR*r=b~wjr8oD=XSTWK7!D*4A_ih0(|!N{VJCs&uQ2N)POo5#+&5A36e7XA>{u`{(& zE=7qJ0Xq~%Ow=d~0-XG(F)qI7-&Fuqz7b9-b=ogW4O(2t*aW`^RKBK@yrDXVM%DNv zM`>$dT2&j<)L4DdWo8WN#+0lSqEHZW5#^@HkZ^Rdd|@smt+ZK_E9^z5iNTFQC2Y&Z z1uT8m5PBW#=5RJ0|s0X+cZ= zl$B;k3!0H@^j%6M25qP%-AOyVZnUpH8p$`od=`*+%&LC}8n;5l8_Oyw6Zf#03F8>%$-1PdC~x#Sq?u@3#heDyh{-0-V*S1W{-( z1qnGI>fapLDW{jyi=TO$Z+U^G-XEaN!nE&D<58^Hr*%$|4Qv);*4bfVsMK(qQKY_8}}3drC?9a z&&nH#gNuSeB@LL5DY!Mg^Gz_^!F{Aa>>IE>C5oK~az9f{x?nQTcvCF5zgW}M6*r9cx z0dQr!KjCF!ieid#DHT#Fk!vmkT@gmq5_dP^e?Z$kII)l9kqzm}!-MUQcpq=4J2AU( zapivd=E_v%D~P2RjaDVT+er^TYLnZ$DS79h_HV9eQTfForM< zq!NjhgT7Akyo|x_b_~HW#X8S?JAh>4-0cw1-5uXl*cI1xru@b!fqN+` z#WtUJVa&tBvjeeRmiAv$t9m7$O!99J8aVgLk{K@^z$UEK2-5vid1&5R5?>cxoIXw& zOMkpqPh>`y`RO}Acw@rMo6jOC8Wa8e`2O1UK_C6`&<1TtglZnQTe|r4YYOcZDut|n zf7om)$;=}Gl~Rgxns=hI!Pb#CZ#(yUMm{~Jl^|$gfnu#f)2)=ExTG)<#|rf15IjC5 zn#U^YkmG+Q&VXrk+W6N2d@q^zy=$uDq~*y$KxYfVb_A?`Ao=VtA>u(fjw zASRsBEOB@Sve^=`P9`hhYaTi`bsb^8h=Ky0i4qLROMkz_iEacR%-&jF)jlXePujQX zbohrb0P()iNSPFs)Qd!_|7x5*e8=2RoNrOUu z@ceiI(u#vYLXz9B9GmYH{JAI2Ki;p#+K> zP1G`i41a%sFh>>%ip#kwbmXYLR3Z7j zS@bVMaVBJq`tC+td+meWv9iFG`lK8jJ@Ppjd_1J z!6Zeg2=X0n$dUJR5{N<%P+=>6>k)7-ggvZlb*(-yA4&II>8^mOT2eyg3km)ptMPpA zjSvDwR#4l)U5fTWFj^cqJI1VKWvhLH7o=|h`2|#v?*kM-CXI{|80EVjG{)UvE1%#6 z22Wq?>~(xL?BJDkZP)6)>Bk0gq!l{x+O()rLO~;e$)+l!2a8uK81z(n$lW}WnUgX3 z3PZI*FT_yqeOzykpzZ@#!(x{aT)KiYN%<63^mW2mPnqjqB52M)4>PG{-Glf=k`!y} z(l+fp3b7$LkCDS@Q(FbSqUkruDOdaFwktPMOxjBTnYOI+Xw+HrZzRiKPNFMoxg=7< za;vPqQ3>M+FPT6_$B_u`VO`)y*SrTA0w~TVPheb^=wrPns`?(G@xg67xYph~`x{f0NA^gm+6${jW<&xg#nAu7@7d+< z*y9fD!r~$kr?jh&UIIf}o9BA#n*Yi+pU2YlV8mSM z6xj)Yh;lsO2-D}VdR@Pr+OX~J_pk1JM47j@55(QzSH9@TAQ-@2I_o%09_aC#v3BYb zA^q%{U_$F(HsyE^3y9j9^)!8_!-&Y|_fa%ZGz!7~U?ca7a(uivw;A?4e(wX3W0Dtf3wLFwAsu~T~zC;`wAOmwSR02ahn(#M#bSr!(HJ-XnW6@lkXh;b+ zLiFy7jIg1g#S-Dz2EAh60EzU?7V?2$Lo*JR!Hfk==XgxtV62lJnr{$Ql^I~Iqi2ujAm*E231)z1-d%` zz#3_NciAjD2laZ_W{1LEU>oallEF1|IhBCgpi z6Rs!ns~IJFWlQ9qT);xUqVyZlNu=%3;A$1wp2HWa2W(j{AXftBiJw0Tf=OGe{&znrL9Tbr(*6lWucXjzC|0YaV#x&5&2lnZzOT=yO%ZL zJ@aR9M+q0&h`U;EpAu^d(I~N~DUO#^zY513Oh(nZi&y%nzz~vADpDqZyWw2+FwV+A zS8ss=o)_q<{LP<*sY%xP>xK^KnQY?cm1^ms0j!S%`lrp~>gJKlG@Wbmzi~aun9VmkQQ^Z(p5agTe3Fpu-X#U@V(Z zo~+TTc$0-U##kS2ZF7(*RpY%h)Fec3!DD2fSePs)pV~gIWmerjZ0heXd~(W8G*!-i zA1DcRj+(Bm>EJ(x-Tkzbee3M*I7Po~mkc1R<3d*l^GNjdO|J4yrs??ZZTkLk#^xm- zF;G!e&hm9D>L5ZuC#BT&iK9ANc6sxo-ty1rtl9FXI9;lhoopnwOp5j5qa1IwEo~Kk zd$|u9LOQOLDNb7^2@4wwKX7$DPf1{4o!ebVYe?$*$d`Pb4o1AD{!}x89X(FRe0`u# zfy{ulC0+8g$#d=MAF?qe?Oje?Nu0ebKnh^*$qWTDEm5y+t8p8h`xhvA4hcQ9#2cVm zmxTBmPDfEQi5*z*(!b~3MQ(pKs}(G?qmU!%mA(o72fEjrI+RN<##SSriJu01h%*{=U)w2d25L%tAA8IAwmKV{t8IWEQC zBFDAfD)m9a2o%{{+}F5e{bKL%w)syJL6!@H7^WMU;et+Fh}fJ67#SfoTJX-ucu!U! zU_>vNTkCH(bHXT14Ay+&{W#F#%3=)SpR&*jkIF4>#y)Y>Pxy0YPL9l2I)LUCe)fg< z^7za^NU#@(LdC!gENGt@2(!gzCF3;tmT9u>YXf3P$Y}IbVANdT<(9>aBvo6eNTv~` z$KA(~|M837@gA)#8P_I;AyPmYXU;NuP(lYLx7nJ12RqSEjwcc6z@>oZFvOJWCu~x! zj3wS~aBW{F&Z^{N21qf0P!qfdcdA-yqk=n<;JI^jg-$Nf)2^TjbhvNGG#8n$Hqal0OQ00?xdV%OIR|gMS2e*fYk``0rk)+3C--bm&vL_#ub>$v9Z{-=>so8em7IS=se8|MJ zK51^HOooKFt<&Sad2^*a-;_L`Irn*0cY>Obm*+@#%HNa>aPv7T`~G5NH^DlP_+~cK zCeP;+FPM~aT%L9r_eoSHSGmlE_|eAy`NFcA{? zu%hh-u9F$k9_6nt)~l|zgzZO>Dt#64J{PCrVE~_8toq?3^Ie~*w{Lfw-i!q1 zXA*~}u-v>#cj~tF6Zma@6heOcqQp7E&@0@Y*tuPr&zpop?ez)-B+Hl~T0o}IFupASfjrtN~HHX@RPTBnxI29ONS@NQi zru1+6tFKHFl=jH{`XeqC{-T91@P&K5Z~VBB(j?Cylk^OvztMY>iS8<>kkejN0<4DW{yj2=T#h z%fX*BX2oi`SN8`06!u>~T!{r*eWl%&6@*(yToA;|Ui-TB-|1{B^#8NoJ~(p#=sp2{ z9I)Ar%8$r?m zk5>)m_-mJ+G{7gLKn@X4)^F>xcg25mPmh*az2+Z5u8 zWdH{{P}muvd=ZtIo3)~mf@iO6W{djCu*n!k+B=R&vp4JV@7(uk4jRC!U0ir?n{-QmlLNVv(Egrf#5X~$CaVQ5-0m|gH|YQg~+s4 z>T`YZMikXa&G@LLFrqH)yt!erhly>N%H`*OuyyU6#bv_{HiryHOOeK^@>V5C(T%FM ze4APpIJzYb3j42o>^5XRsq#;r9Q!Iy1`4HU;}u>U9IKNi&>G`|hmxjFaR`uvSBPfI z1A{FG9%FzqLpOS41yd0@c?>Tt02qD@~|}>gepp&qs#9@aLY;IFthWdJH4* z>oXa#1oCl~(vG8rBkK}tU5Tgk$-VyH!gd8N+bk*fX}En4^v}QWOGis1BP1BaJ1Uih zbBD9Ms?Hw-NQfq^=Nxl_R_wE#qz#f(+WI!FHeBz88oGC_flW^YF6F-LWxVS!0GJ|F zO4+IMC}bI0u@V2gF(XQ*KVJ4ZPoqS`LUfgRdk*#%0M!!Bia_2X0^1u2opYE&i&8#^H7#&Oh*X%- z*Hg$c$LjK?ujpw#-r*Ib-2^7&7sb)rP)_O@MvOH&?~`4gJ};iYuCy=-wkQ%v17|h6 zT?m71e^DyPF~gFUvcgE;Jaer3)AcMH=XQiq+b5F(7TsdHY5H%6==9%;vb_HEn(X*I z22r&|s~7S49vm>K-C8zn>B&RSt*2Xq+5KJ77}fO0Fyr1!Ka>Wi)4}$8@Lu$@JP#ZT~~itQmG8vb8<;2$-?#`~>Ok(Xja&eggw)ht>)b7GuFXd#vvx7@**X zKkIHS)E6eeOk=O|t4EB<81wFC8T7L$r-!Gc- z3fPkiPh&&0n6%8B(yrtfb1SXIG_JRp=(`!_;6)bCv<zrWtpYiDRoC4Ag0?@*`I~m8;=+9SU^i-2I$j|VA-YnZeV9>$M{YYH-duzr z%%)>ALU?oXs1&c|y9DuY(Q)~oKeDb~Y$xe*74E=Jr*gzVJx4Z(ccjt=N(9E%j-*FM z6tyVRwtgP|F8*UOV@0hmwx>{l-EXL_Nju3FEJFY2>R7!%fd3~;9+#FU9s0pyY zmw(v&4t{MQ5*@%5Cnfu}KE3$&<28G7ls@C|E}dg)8N=)&DZ70p06_@_q^nOngdlDZ zgCTCHkidY>0{l&^PaA!(+7MJ0WByx9^?kB}P5+<$z<##04HpEuE#Ur#cn z)&dj&3%DgK!u3U>6~`hxL}({&{-)q?F9FfAFoRcYR~@dT{aRh9J`ZZ)Fdti22u~8_ zdtJh;f|g}7NT3dH+M#NQdwK!%P4GpTQe_w$&J7Li*`ltzf(obH!L^(n!biYOR7JwyuQjn zKbgbV#Werz0>86f$>+mRNf`1rCo>A!8+3A!(L~~aM8m#>Tw!mshgzc*MbpEv8UuA* z30M0A9p5VEanZcZhZ)ft_rnI)7&CM77lY#HW&7jbPLQ&_zx_k8ktwIKf%)Kxz?b^K zbuV!K>J@6_QC@g@2jl;@j4b?LL}OjDZu>e`BDG|u zAL$TQ<|i6uU;XNpS%qov`phtUq_`^b3S=p1;X;>5YN|*veinG$1CGbL%FsekQ+@qr zg(Y&KFAeQbvi`3y-t8S1mzOf$%d9639l&XH!(S~`tfL^>c4c%j)k8Zt<6voB}BM-pGR;c%d|jh*A6|a;`WeG zh*wlJ*3|xZ{ZxChhoeu}*kw|wQKlo6WNP6uhNze&xgxoCz<)<{Z(qB4RPSQhN4G{+ z1y3odDBP>%6(>9;X8y`V#J{7HLFY!U=3J>$YRNd**paMPsGGYs?$Dxq2|yL-PK=tW z3vKuLshyi8?CS3mV$vy()L3Hb$k~x?$9#2?E!KUVp8t!|(IW}=Odob~V6>HLeH(f^qv!s#_PRHDwW@7!**;+7YQtVXa2djO&_12lD}5ei#!QK#I~u zzUOjl8NasxOnaTqg@Ags19^w{J0%$=ppsTa_u!iT%IPKBQ}2&fPv+)_=BEwY`?Ukt zWwTx7ZF3Z57Ih+5Og;^ko;=e96R~GRidkpfK4=nthhMduT~`}7(ao682ZGdJE)0*zw5c7Sb$=}R{OGrVD2CJ_wuYP zS;~{Vk!$KWm&BeY$e^!Xc`}tI`QVTi)*-hdA^#R^-I-DH9nE^2TQg_!KXgJS_fp&m z@}{6yIfrT~WObtN5;k`Ie{*70#m)SZm+vf7LD}H-4O|p*(6U|?fggPWs!f3OXWp#S zOGE+3QBY#bDHzib7_D!r>h^^w;eCA&uR=!MQ?62QiU`Yo9zxs*;2U;~qT@NdJvh1_ zI5axwfMk|umSjYlcvn1;LFjK^c6qe>;^id;j6K6^K( zP)e@6evAam1a`;1$-VSt{4}9}J;hBHxS>A>n>n!N5~;Us>I7--0tJQ?g6OG61!=zu z5&7S;U}2(_^_tGT-B2pAb?_==DBS-zhcLY1{wvm2mUc`1^{O$5>kd=t5zWyutO|rF z^dL-KWMRMAasuvZ&C`I~W7ve;2x_+Bwy zsg;`QS7AS_6le$sU-7t!8B)Wu3tWf=-%6j;SWy*|^!!EUc=PN85!$ zm+es;(TQK!o%Ld zoiA?pJNF&h12b-|s|fvLot+QIG!Yt*A@8!cN5<3aRn%%4x+|aJ^RfB0IjD6Upsl*8 zLW9#o61|IT)BYjS?kBksz85XDnlM0bFr)mYPQ9mI%{(@)1U?>={iq|;&48lmr=MSNZ`DcNr=gc6Dh(*+nyz`{nXbb2CBpOMObjn4-S zcfbkHad6_x20MosTAV)~2nejuyH+g^$qrHQt7WaAvy85P0uL|u2>+M2%GMrl@}(3*XW&u--0 zGyf)SZ2-Da>7l}_tocaOvHr$MBR3-@@SGNL9}3|2CE$a@S!?{?)5Y#YKNR5ORZa8p z{3DAC`F?#wE=g82n0M$n;IK?RzW^BST2eu=y#4~1Z0T#|qVONXx_j?x{-fUoX@n9> zq5wO`+xv2hKW<#=@Tdj4PQyRkB{t-XNARs$A77j*PY=~vja%0dd}rWa3~E39j}B>W z`JXj|Y~{jdh!qBqE`>t>3UT+6G4mM;r0TVc&USnG-)XT|AVL!#_Z*eBu_a1qVGW^Z z*ha2NQSIW-z3T|&HXrArMsnh5G4<_n|Fx4Ay$`%c%9_rVem{b{9)7yZ6N+sdyGp&7 zkS`U_w?|5QoqL{9&ons~6+}EprRr)$KTd0jE>5M+(TH@h=a#Br6+dD(t#4UfO22GpQQo2g>td%8xiLNO zwdlW>tGdakxW;LEYeWN|lz{&RPaL}cRZ}o)hciwsg{t-06b?;6H>0EOEIN8VE=FZD z)@COT<1>Bq3Ppks{aspm2$+=+)OEN+_#bMA*8P{Us(1Z%P+S6M;=tWhh@^{zbd(PK zcLdX)T;EZLVAYz5C{Mg7?!Za*_Oz@jL61{zOtrn@5V7-2K!ONsfuU4?>PQMX!%MZ4 zrm=GTbNRF*a6`vPATS~1BTYHSVY5YQO%i|5eN2X&&N`gPUO446^^u9)1{ZR-31CH&jse!V(s4+f0k zS5pbM)68f4_P0~0i2FvD(fd1taK1IO#k}+a9xs;^$B7s7`+Hk()b{)RrR^g7Vu-5$ z{Tb&oi0{YxmtR`i_%*YDJr(dWjBw@1lGXaR;As!%>~A+~fo>OJ|6dk>NX%6!{|S4S z)13L~=*kKq^s8|DtOsm<@O#Gz*l*Hx97LMup1ZWI>#1W>4KKVXopiMl zGhOjW00hO&yhu5l_hiKDlFPPPt){(B&=rkHuL@)QW~k{1DE_!+$9WtH&XsXLMI6$R zx8WF+2a~PBfix=U6)zV#PU>!p{%VUejmhdN0UmnT%fMj|5J!{yR(31AxXlr{)5R&p zZ7E8T8)P!XZ$7!m&`yO7Zli<=CF-!B5nBy(w9nEq)Sr1u=E9++ZT1T-Yi6_CcuAq z{|8)9w}wqZfD5vX|2I(#A(1yzP2JmhHpX2&%YM)2X?xh)Nxp8qya~ z+&|Lp<)mODTr)lW2redRBmHdo{Mgz9W3ZZW?qJ4b^MxEHH8(Fowq0ZSFFyF`J{cu% zxWdL`&GKzV+2>qyM@@rOs{0g2-d_oPCnAPP()8vb<&^7+Q!MN)T1e4c`!x86x>a0c zmSmN(TSt#Ok;Zq&ruek{YT@DPiwzi?k;duNiXAf4BUS2Dm?hLynks>RtfMP8JPzv1 zP{>$3f=?YBVL& z!RfNL>1L-JQ&E}QL$w)G1jX>oFGRXwc;&Bi%D&{pb-YDaiYP)|^E0#Z=qSWX*)&I) zKa-{2c=Q-pr;6tucz}P3)eC(QTW)EGhi40(Q`u#wjK)9mqDEbs;tE;UWs=|EpZ!K0qw@XNwEe${5^{GcfOU_S> zxSZsCcb_w-cP)%$v!{IWvWz?@NZ;1Lxw|3DS^y;QMPQpYi@tzhZ?~BgaH#s}v$Fum zrsr~M25}i02Jlr7lKIKieZ8wJf%_Y(UFOEzVmkz@!S+0a1x~-5J25eO-XJ6tgL*I2 zu6I?5Eys*hAT?%s>YLkI^eIR5IkSAd|2ih01v&e=p!Vf!(%uL;F*jE~&(t0s3pnT0xR;sm%Z)ud+T zSAA0i$_Ov3ld`TZ;toctgL&{<2!2wPIjE^&1bsw_?)@R zme=U^x%OcB;<%JtF>~_wrP|H@yrc0VcxWNJX`sPrpU3+<1y+q6X{x*OF;@E7c`Gy4 zKGDnG`-@<~nfHs;M_7)0m)FJMx^th3YEwJ|ZHAVYSF3H+0!gNK`2MGO{!x*)$2x&r zBhCloIXLi<28*DV52@0LGIQTtA#v)@PgTfp{JuJt(Q@pdqOOz;~->&lN&SmOPo zlgL(qj~%TA zXZn@{kA6JT3fUu(kS|eXo}oeip%B=M|BFJnFdJ{Nm>Le^e`ioCjKE=o0iYb}Z8@v` z2UGrc^mor@myN2Z$DsgIW1*+tn-ce*w19#!HGYJxFFc`}jG3b=K z+**?K3N41dn{rjg+Ev)JA=Y)Djog#*%&NN9lRjITWSY3sW?|aXTz+|Hx%<=6CR8yg z*aOJ|5zG+*1P;v(=R7UYgLJ>0Ya*0&=;pTCl~&L>KJBaUe3WM%msM3uGuIR$Nu-Yb z%v}HKGOXk;-@@Kdty;CKK0lixR8_twpcs7T28YmBdW4B5Y~qmhYw?|PkJg)-zX+wu zF5Ohtk++h$0=>7JOt52NJ#AO|Q<@VV{#VUn8j5AMmZFAUG8KMA!mUwxrLyW!&lx|n zA32WAc^Nt1b8ZcB_pM9^vH;cV9Fb`Du}E%7^GvY_UdbzY9e;ellFC%QNN*}D58SE zRrLh>P~1ZGnPwexE0`kH+`QtJQAYjg(?MupE*e~NIZZc=TJ@h1;W|2S%pKP2z6J0g ziJ2*hnu%4A;&3X;B~M}@B3raw1#98tPmtFB!{5Wcm5}_8ML8zs!$(xjGMr0x)M02) zyRpkA#|rOq?EE&IYvj^Pf~Ne!Y}4csDXk7tJVmu(R=l@~USvjIE>Sd)*lHi09%Q#9 zPVa$81-~U1!$0&Is+oY^?xEj+d&I-Dk$B(A`TFl64+H|Dz4T-p$Eko(Z$tAZ$}O zowCOT#`ZRW8W&H67KzLJ)QV-TRA{o7WNc&~mHlRqFgO_J&xN3Dq#3aLd^;EsVpQvY za<_K5*s#^o)>40%lRI1KfMxH!rP8i7jDcD%;JAyV#ah7UIQF`FHc#^UGtHkU+*h0X z5XKe_#zMr=Nfn6hdp$t`J8#%XYHD(OU97}F00gnTfNKRUc0CwZ{0YCjdxJ{qhQRqt zaNH;Nlw+h?lZQEe#awf&V|)uX$!I?wx94aoC*zy)fPnPoFZQI=K_4RuuZQ_`fM7=` zH1Fq3!H`N83Z~e(@;H%vzqvWrR|oznzWaji0>p_4WXLiQ<(D{Va2v(fYqT!^Z!gn%IViNH1j;Tuj(WPgwrs z{f9K(X|OYr-4|0-c2!NdR39uXIYGj*vZUM^cITJB4Y`o*G^@$LFFKq#-c z&y_o_bluF*KDoBY0B$(Bq6kEMx{PNIk@(gyJlWhObe0_jF4*rrz^~%_|C{wPl!$8G z3yp8CNgPV*k^=cfb8IpYS&MKZa&UrIjxm)4rnneZv(l>V73Nn2_O;HvV}%%>9a)Hu zgIre>Z5vvZtG>_H65rZ)HhD5EEu1N86HD^Fr|B?JU;M8*P`7SLwHUvN+A5-m($ z6RwmL6#-xMf#Z#UXJa>B=zToBz2ec5xm_vhceg`6j2_&HBZp}zg20J$tc`XRRo;_a zBJwMM)SW0# z_RCKGO&%wX3`P-BT7PmnB>MQ*?#J;?f(Wh_kAtPInqAG#As!Nz0 zrgj=30OI*3_*<0}ZFgZ7>U;URfL|@r8@9Bn+K`=_XYZXIL@ul;7ls7DO}9PI@d(hu z|3b?&;rC}{=_nD+jr+dka_(6wK{IsBj0;cE)mMXSncvOhQ)tS<3+|vbMakd!>A4EZ z9u&0ATn2^XBB^6&2ft9E#yq1iv}W=zxqF5K9c-AUi1U{pJV++Ns-l3iho@FE;@~4` zJq?1B@t&2NTQ`T`N^GSixcEfOUqDQW2bsB@SWDL-st_#u(!v<%w^j8>^uyF8&37G& z+YQ{o_pAxMcgO^bOi966;9ijc^nVI?8amwLc_uwJ6sfGLv?cpT)O|Hf;$uFKQ;cx; z0ianQi7+syb1OyHv7vezN$`DHKWOU1qdRad>!@=SZt+HjgCRURd=##yKtR8+?mCSR z25P@=`JOsjoY&RXPW@rDz)G^J&aObaY8EJTR5oWg0S=?5-Jzl$7I?sOspetblD6dt z9}J)<`LJM?9DaE~2vz^M%U}fh&b7-L(BDMbGV;QHrTtlMkgjr?%(zgv6qcgn4@g%7 zoDpK)HNnkxcU>Bl86P^I(Or}y^dxxB<9eHj+XRXix)Cp56FbL}0ump>yz2n>Kc|+c zvzPz7`yEoBgTVhIhnh#9Sp_m0{ojkfe3jwuaTp@)PHT@*e0_V=u>9M$F=bCuIf9Of zS31JE9K9B`a{nxtPPsk*psuKT5GhveOXGN3ctaEUp+VLr;%{$z;4s zYkWKsU1OhG1O6o1s`m|39Jlj+8b91E1ZVNU=acJ<{G0cPuw(tXx@woZc6rv`SH&oL zk`X1G!_E#+si1+j750tb1E$)75yS`&9_c2$P#QkZ-rEw8zKFlUd3_Efv36>q66Z#E z5)^!$Q<*=H&|IiUk;}s8{8MCO#FQV1jfbdqUG+gj7nO4KhAWLU+qi{$2b$3*R2gXV zh@VXj;D3e*WB4*A6~u%Gc{Klv^+T7vO9sfl0VcH7U2nPa8|n`kfb=$F^PbTlZDNaE zC)dHREA(Cigt9K3;M-(`poy<|^z!BpU?gtC!IP}d`}9O5|7jNtBvOCTQ|CPt;Z4qG zmJW%u8tl|1hWyAFADGTNDfBVM5CqYUauUfbYkfi^!UZhEnY%js*ebAjU|`0793R;~H8bqwi@aGL#afgm6Zi>+8-OHfi&E=^s`)1{<)msiwAB#RQ|Rt|0Rl%&X-da^D#S&Q6NZw$eP`2$H#)6HNori z(0sg*K1$&8G1}g61;{2dAOEVGhXo6SQB*S)+bTzaPC-6+80GKUl%f5lVx)$Ln<)Eq zRHe0-a9RYz!9P#vFO|hD_+P~QPU4=6Cn!44LwA-kJoP6^+?+d>`cdIy-du_FbR2t4 zgG1-f8M>UO#8v)!MQK>>w+_C4fwQho;;)MEDJv&t#J1>&E(De|zm6tR59f>c zV$-YUaZvfz^*j^j56tT}d9kKtW;9{JgzL(km*@mu3E?>5BhcaOUcS?K!v7eq_#;%) zA|i(4+VA@qD&KL7bThi z3lM?wxP~%?3f=3H&|(q<4er)mQHc`3fIu*yQ3YOwAxTXz_^5p&ddZz&*0TpI(6Nm} zmMx4Y6wMZVZVPj99^;!!0^##*rIa{~E3(6pgIjeJ_oRcuf_2WerB({g&)U ze|vM##A-LPwHHhw>CR+F;w@(c>=@zE&0jkU!VGq`SwC(1gq#bSM}i@NLw9J|ARt!? zLup353JFSsml1wCj!30$|K$k``O_b19J6Q4=NHgXy29f(^#;Mf2?2e-&KbowDzK)W z7GZ9Lq1blL0`5XOq)k#u_JBEAy=_j7IWWj#pM%;cM_q$UnT-z;sr0N-wKZ|vF>3HE z`0SI@{AiL*n3xGR_j23pi2+WhIVYS@w9!oZ3)ZY+pvp`}y>nw7_1aEeoh4mxOH~uc zRx72m?N8^N6kHAhfWv{F$Vcdw*y@b^2m5-D5P_bGWWep1W5BH*v%a95^Su{1g8uYh zQ(G%$G*baD$5fOY3?ROzUByUTscB>sz?1O5N^9>Bh8QMWO22NncmXN0f{5MTNb2z@ zY6Mt;0EQ48>nxX7DcDk*)Iz2{xKo|foqZjp1`BU!H)PN)@jTq#anW8mFqv7AA+>3% zUh~tA2H_2;?qWjXCUh;O{UG6|5L`ce>1%t?YGNs~*nJ;tl+9CJQ(q#f-W$Wz*f7v) z;%X4bYNaWAqr||Ll=A0p;4Ka;x$=zSL19?n<6{%soM{f||1kAdVR1IVwk9528wu|2 z?(P!Yo!}bW-Q6KLG}br-cM{y)-Gf7LpZ@pknREKCZ~EqYzUr!4tKQ`wHXv95qN;EF zMNPocgYz57w^##{c#oejq5$YE9CPH|&MhDcCL{ggBPnV8aQ0kYbl0drdTl@ZM8 zNnip@>xgC`%A?!vf zA1`l!V`=*rD)v8%nuvUq(HG*AAo@~xBdGxPr8;?_ zMV0yamXsY)KqVm!o@Ecj8In-rS$!o>VG~s}iTvjQA=WvwA$db)$ygN5*bwtgqPQXN z@=Hy%3w7Lky>mnEH@FY3-uO0o!Lf?%w3gDevfSw2tBm%?vAoAE4Vs|`ZSNCz)`MX4 z7;?8z2~{_@2yZW9GMNEdDW8tnnbk?H5{g)USKHgh3Lg4Y167-qo=8F~6yZ8xPSD&y52f2 zhv!OR%4}0ds165HN{vqMV^VU00XvQ0d5SIXnzV}eI{M^5X^!?Apu>rDEKQrp?TCyw z(;2gK-%Rci=92$X&HxX?vbvE0f8TLd&{buS5iH|B6Ob zM*gl8S?3p!>jEYPe1C-!suJ-^lb-I_pmnql0aA0m@3Vi2@^Nv6FYsFmR(^0VY`(>D z^w|EB&%|(jNw7X5rE49u3Kvs}Kid^-w1ACTTxJV@)zgiC)!jJsH|k%~xSB%n5~>xm zjWEVFDSRE*?aneJ;RZ=xg=;*oW?-_(SL_FMzWWHS(iMq@uJTrF%rKxeeJ}{VecHT6 zeF&oqs)e_8g1ujuU`o*iD{H&U*iUKB75M1laQlO3;S|TT$0Ugm6lxTQ>V0$n+rzK9 zz-J@d#<|uNQLMIzPq$sCn-R^|cyh4Om(uKz;!83bS!GwsT9vw$5ByIz6=j_J>*kWZ zDKC6J{CU;%oH%Wx>^_A$Wffg_oH2#QwjtX|051M|Rda?}h-%^hGW4B~iJslPDOvnQ zK0#DWT@|B6UNjc^AiV!hl*-jS42pr`HS}<%ae!QJVh2>6in3v9gDB09k8XjZ!kqmADC+g&>nET#oy^@MiU01>^tC}vSV2ggAzM4J zlqgf*N%bv#!xxZOM>pAj)XaBqARh~@I@s>5qq_G)(*L?Bh*rpMD{>1$Rj+M=A&$b&?#Q8*uTE$XlDe2v+*%GVW>5XHl9AY(xP(S%!I!!x$Ewmcwx<4sT{p`=vp7%iJ0YS6~xr ze(D*dGSX2W`ax-eG!K5An&KILtqaB0j}IvF17_MopX7ce5Mvuz?m)jX_iqrRfpT0blAZCr7m|`}fbYtSqRsSf3 z<{`9S?0scUOrL7wlkr17;-x5_8!d*vZBP=BOH)+SePGhW=fS5{msxU>S?i9kX7Vkp zBg$K9F6;aS%e9uAdyEdVYB<_$NwwTfkbuQrYM#B5!w+q_I>&#PzIIret&?_2#rat` zhCQ#wsee?V<}bd|uyxcIOM2qENu}Q%{3Q9ld@=A{3gm*qu{V8? zJ?phFW-(?Rl4L}78jqNaN}e~@!?z_>3t~3tAl*mB*!Y@Y7AIAOq<%ei>36=BC4oAu zQLXc>mTHQMn_#*2UR|-3pj@^Ui)Q{uk-*n#oOaHq>oN7>mFII>?i!}Sp=OJPi=lv6 zIL30})X9iRmmu2L5kWQUZ?&}0OAW+a8wrhG#OuZc7)X$RtKMlKWx!Sw(2NYPk!yMLIzFr!NU}tn5JNmtQROT&Z3^eIv*m&FL zihGJ^X!Rbt*SOR5HP<#YU@V`Ad>ml;-Q5hsththIsz6N`c^_g|8~1L_T1i2uyM8km zEPJ!(j21HV6eu&cGr1-M&%6mWvz*Pj`3&#-gAC!ccXM zBa!f1PI>2^_Ha%#G7g~}6IsT)<)N*h|4BepYH$8HGZ%Cwv^D{VCId z2G}0a;JP{G@T$*J!HVXa*BEtFN+|&J7U!4{>CvI~78<N;d#@-*c5>MdrRrMGJL=O*U9G ztERk$kM`6P47C@hTa`VQ$E(xUv0u6zwF-o^6Y{U8bfnk1C)JmhW2;154JJc%rQQ!b z(5lXF{+967hPls-_^~@jdRph@T*-&9FD5dVN-M98{yW3{`+_UxpEb>Aoo;qCxe5tc zd4iBk`O(2qj4XL66JD&;Vmd$;Bpe*jxJJ@WwE$=A1BlCkY{Se=PEi5e2jxOwbR?37gOHqbN##w14MP(w;X2Tbl?1wk1~F< zRi#YMHHa~3XHAXn-iSsN`mU2L5K>A-@w8*baJ?JJ5SQYgbSvY!20@&$9zz-V5uX70Zyv{uLg5aAr_-~#n^77P0)NZH zh1RAFpG+g4XR7m+hJKxr@$!|QyK!c^i+MV|V9l~~BemA+P;SENmL_7%>azbBvxIAS zz14Ac+mb+}^m8C;>+s-6l)q-n?@Y;l^%v~duV0%avmf3eRViyfbdMR6Zi%vn2>rhx)KL^4ux9 zV1y*O7$cDMU6fE23P_l-v@#h0K`PI+-ZOCd3vWUZQb0J}cDR|S?h#3{-LBii!)vU;pny0fx9?-~ z5jQhc zS6@D~`ldHc!LehmvB@~psDrV>t%_?eY8Exnd~6>8O~}(x%K6w5z~dBNF_XK$cSKve zK`cJK0-)yo*5#M~m9ZdiuM}Q`_`d8wHLLE+dTX+8ZC|1}y<&!YJ$y~bO;qSY6M!;x zU5PWMj;RHUJ2zJR0dhlmtNm2h#KvPPwhRggc66!feAEEFGl(;K9v=O~UllDY`^&)C zD^Y+Z(Cs7AJBVs`T{Muo+PzD_qBi;+!3C3u<>s?6_TAHLVZrad=6afY@7^+cej- zvrHOAAy>rqvZ&qt@m`qg!(kX8KE89uGZdfc-1S5%LA|>x_HSAeY+-d@%-=VF7?6Au ztEA7kd`aRSD1%}w7i)u16@~}d3Vm5yfw=KYEE5(K&|GN78IV*QAF-nWutJa|5(bFB zADVJDKL9<=0bfUn!FJ*yeU{9fX6;y2S#;jsv@)U)Q+#sx{k;>`o);v@>c)L*U_!;E z^BkE!ltp{$)6RvS-}M$dAf1|mDimEkrOnIBIMjY6W7V>La_ATIJ_nA zn(-!oaI6zrJ$y85E8pnu?qTm%S)~8!<5mP^Cw0Oz*^RmT`VZ1dvmLIKe{YGV6ZzzVUe1g+|kzjhr!@b>fge})GL@bIv! zIGApUTL>03sS$;?oNr-)j0)|Y%MamJ5}s>&_lb#6+4GKdIC`X&vHYPO{GCy+@FO>> z%JR%i$ACXSBoU%wYQC)PC#Wu%=l0a)XwCa{VEnxhZ|g;Zo@6>m=!hs<@4r?|`@`STG~LkWTQ#gUy0HXrdFnNFmKwf}w+whON@5HI`JZ4^czA2YMwbIELA~ zK*|m%M-HP)eU$jhZwP%*);jU;D7pH$o~~4-rmdiRZMS_F+8APpyl=QQ6^v9%8y__- z#@ZfgX;R6n6e>dFrCv!nSYTzcH$mt!VeuKSO@Ly!wXQM*n0| zC0upBoi!gu;S&;az7)a8zw-vuMu+m50GczL87YfzvY|_e`M}7i(BigLn(!@*Y8ItG z+kQVI^E&6QpED1l)&g;(*4kTeoO+*N#HRcV$k5%}Euc_ZUuHNKl!@d`#jeCuw!covNvbKe z>4UCyz28*l)wJfykEmJ#5;C^}ZAu%_rb@;Y6bpn67M+CW(#E^@A-VyeWe^27f8i z`NcpaANY$Hd|_HL36zCHx;TJ~k|2bSf! zwG9`w6A9jftNt-4*jDonpf)G>Q|RNQvAFmI)pPHO9}>|Nm8GSyhMR_*Z}ka%N7E=K zS}L+PRx!V2zhoTc@hV`YSFQW#(D=8%-V(wDWI%>I?S034zrNsiV> z=4av_vq0f82Lbb1o&V}kthGzis2iKOvoWzaGL-~Jw}W@WN&JMWMv$sgYD9JmXag9f zYYu^Co_fefWkEybUzZ6H@ts60No{MNkMrwXAH7V=^ww6c1AJ|6S^iTc8vc(e(QInw zOi%|a8UP;lOJ?>zeT7BSL}@9Q`y4xs5g*nf5=As|Jkb7Q!*nky$Vax-u4Eee*DPoH zI!j{XV9$nNO5K*!$>r!11Klq1io-!{r)g0FE*w&!6ivCF#JC@CuxryBA%Q^r4^bPz z@zDlx!W?=@Q(bJWYP}Geg0Z1mEB~40#o1(9emeGt!yeY26_TNvTFASkPDIrr%(N4r z1Y^j-x`Fo;ghafZ+cFEEzl>A<>UCL{GJTtc9| zFYv|}sYk~YXqBkVQNUb8E#@XXS{I6waOJIf;r3+YB+;GGLJ6b2oE$v zaD}OyjOpNwggI^nN7G&WGkjF-=$g}X>}afD6NaQ-3*c?n1b+CT4_ilk{Ec4cbvc5% zKe?;#FnCh;#;ed1Kb&4%>6wqc@cZT+E=sS75cWs?0EEX8xjQj|e2Om{IUST4ptpoH zFT=V*@>?YkpiLkhhnn*;Bx_cWj7{hBdHGH~<6dep8cad~3R*&V$4-Dy3A+BvsDvpVHsN1A|oKYds z%0MlwwS>6pYER$?E>ZC4^B1)({e@tGNu%{3N54NQfPT6wrpqlFoIwKTlibeNTMbJK zHrAv7Yl!uf_d6t#hGiSit^qUoKCKjK?O?&&ipoci}(!Af&vluTU>iy zjNb>KvH(ET7E*V*QWX(3djCLAfZ>HHp}=aqNI(Ge@aY#;(OGL!tj-MF?`Ium=RV8` zoko<8rug37BiM^{-=XhSPuKAanG4|vJAG2m0`OB#c(fP?v)AwiUk&*4x6fprF>9im znnxeQBDFpRVcO$(Gj@~M8&e-$voAI z9Nxdhy$Zh`<@={eIm{z$MP0v^)kfx?~I=lBC6frb=~f3{aQP%fbm$ ztFBn8Jm^b*XkUYqIPZ%R9*XwskFu;F^`GP>M&zV>adTqBKgDph0jn+}h7<({MCI(R zJ~1wbWfq0BJo5AN05&@4$}v|}UFlf8L!fjb&OixtK`BH#(%W$fU!$*(d zZr!rK@Yl>v}^zbG2&^pk!dCRdzZh_ZGf-UqF}=)4SzUmJbd{Mg@`7(Y!5~a)ghg^tT021PKty zSzq1EExe&SqM%WX^MoLO!pp~ufWt==r&<)N4US|cQ_R!S%8E;P)A?;d=X{Yd+^bZm zi$5tGCT+Ai3+FRGc{jbjPM34O=;rcmY}TZ;UrwIaj%j?qjj_4rJqZt3BYWJl-2O z6BGH2{_>qbH& zfoi(RAv>1Hn=t~@m_I31aRyTUn;4utDIVI9KMv=J^f1rK@Gzv2_^2{*nWdE2f$DySJ(u88J3|%l=Sf$i=k!4)_Xd1AH>~0lWL=#`|D*Y_Z5`(#wIM<73b7=5+CNowJ+^=lg)i!GV$KpQ-Bo|>-!Ivm_U)~m zzAs75{~&O6`l&;m-+wn6>Tetn?*H0T(zb5nf}bbj?#{L4`zSPbt-HWnRWw!VGR5ce zFvttMtWho&WtJ{{LdpHmnVU$HvAH~ANc1jU<+p?aGJ91pB#ACW=e(gi!`28L=ux3- zW*J9quE#!+(O?<-EyhBZUtv$`|7oZRfd6@yOdt32w zP5-$kVFHkUZ9_|r+8Wtatuh`S9VDjH0*vJS1dL>98Mw7nza`N^kb8Xt}_v5H>?2b_BGyMARVAQ62X)PEx{ zNZd8?$i2jg`d5~&dRGcHjUMHbh~t&NkqslFY#l6zHf4ys>*pV3Y~y=#Ut#28G#Eq+ z4Ugf+PJ=Ql$@YHO)zKHhQNb5>pom^i_@ds$nK4Mc3{CY7F<$ryn7rx+=f# zp~Zfw6ftrZ@bccdKi#3b!O|Du`#s{n`)0`+*;s>7IPe`fN|!9ztXh+M=@!)JppAH? zG=Ft;$1PNRmgz9x-Q3Qu)R~JAl_JF)4dx|QNnDJuVh^B&{V3`o`hsdO*xncls9=y5 zXkY%9GMAh#Y3HNa52_{jy_Vj-QePPs+2?keLsln+>WQCEYExGCcFxs(C+J-Y;1N$^ zO@U+ID6HXtfi&WA0v|=FL*UkJ46PC@AV}B7(021J{%iE%x<6rLDSevxgMX<+=B5!-145lM|vW3#_7-j?D z53ZT9e1LmTmI+A7=hWLD&pu%Ws{3uTtBLuu0oBYG{lBt>p(VR15@=(NRC(i!_7z1z zl2AmXws8jO`&byz;M8a$Rg_63fL+aSWu;r!^N=)Hj7~E5#;jy`ANpfBGgxaDOv`bg z(+G)XIfGH^S+hjlxMf?th6b727?a8|onjrDg*9Z59l5j)=loZe;5RHiYwyqKmrG=d zv5eHT5aS*}={%|Lv_;~Ncew`0u9vM_grYKMtZ@9J4J-WLYDdWYT)p8}SGi~>4PuU4 zWv*Y&uyh*O!};qG+i_(nWL5#o$~A*}sU?l$7@19t^KSA)9C_*r7EwV#gxzik(Qre9 zNtoq4dNl4*PBHxN%hS6>7%nczm_IfW1D}Ss@$G!}mTIc22ey_U_wJXCWK`vncllGe zK(D)}QFYi2Wh>qouV2wNZd&5R2iG}YbHP-I5a`H+or7qnAEyfl0Bk^#{u%c9T00g2 zw_~Am#9^6(2MKns+&THy=Rnw(XNODKV8H6Z`1xPxac|ixBtFEiNLLbot48oWd4atO|JfWc57#=zL9p8)My_F8{M* zAlS@J1$~I>CG?B$_390=Vgzl#F|G^%5(!e!GIVnK28v`a z!G{IN*-Y$v`|KU082>;qP9kk;Nyb;=;$@9c1f-W#q0ig%IT;HG;z{n zAARMBj${BQodNopOV-R00uSuRE_j`EF+~ zJf|syH=-p2oWL+DHhtYTyQnGFSJB2Avp9ZR@2ttDRW~KNY0DBb;!KSp9c*1Bn`Bbv z7AGky<5H`VHitDy>X}9&!AZBR%+_6tnw{x{v@_OBY|yzCTDwK*B184vgj{werQ;88 z!Wf5|ifYogT9BekT8U~HM@V`V1ppj&3+c~3$WY2Z)-VS+YlV!o-(FRB9TkZPd)t3Y zeD6^ZO0Bjp3(C)6s4FTPdfj{j*2$a)B{np=8eiQHLr2X`%!ousAgq-x@`sSbD}8TU z5|k&6u^ZIJfKp9`i_%jfJzef)9J+-8_N*)`B_udDZJhMoU!vL<^IqFcI}~ya85lSK z#ozT)tT;V1tqw)TMEyBPd{;|2!QOtAeFHJgGOw zJuPFbrDgNo_eXA%$4mMJE%i^sih>PwQy37)0O$d1|Ef%=j<4n6WD!9WOqo-*J>&|a zOZ2w1jd=LZMtXW#A7{ZG9N7^)|DjRew9MswxcD?5+HdRi@ zSV3oQ{O9lAb1Irsm_gK3R>hg8#%bT1V~K795*NN{m+L!QuuzUQG=!q7W27MDXmKJ7 z6n71*gz#++*})v70&A0&1D`+Ll`w1tZs}(MrpA+{qmy>;YGGJ*;{-3Pwzlkj?&eT5 zbor0Q8hQbH1I}@A3HAQMEkaevtuj0v^AM#t2 zP@T^Wd%uG&&tOf!L@V|new%=kkVv~8Fj^clir*c!6+u!7Gpdpt_Z&RjWh`6lrm_%{ z(z6I88n}3Soh`b(z2Vw`Di((sv>bVX;8GH?1pW`mI8P*ZOI&`!TU-f@17E1h*gw(! zeF0tBEXO+8MG6#j2c(IntyOuv0rJ6R=iZ^1gKQIgYZb6gstW_egl~fg`0vPShis}C z$)i>osaVp6 zW)$@BPWOI_jGVux?;I%1s7)mzGc(|4YcV4*kz;8^!KTgN_9@8Xxim;zhLbM`O zXj;$*!zE(qVWOSlefSn~VLO@I%PGFXuz^ZHx)WZpBSbMai~Xf87~sTa%ZvMTfl@h0~sXccW`tA5mkaHjFP)Wm6FBnonT)AvS38%DrZ?{s&#T)Lf_{icl6OA zCAFC4a$R<_dx9PqhZH{rV#3z3)XT8g=Q6@~$XQNYkC?=23DC@{G1PQ?hF!42F-hY< z0p>0|Ga}h8b8m?26heL)NG$TD3-HzyFw2@pN1QJY^D~d0_?V(~$el@fBi=TX>!wQN z<)R5sK2xB5a21&RxY#eb*(u++McjU*Dkva~@(Chb_@&Y739V|q10il~cPc|sIgNUS zQbd<(s;wibKw+!tz49?FqP134cd)*EE#Xi1%f)Njk+tPQr)Oo$#{vakJlt9WQnFde zb-M&5F@7cHpNIbJ4~CtnKZ45OTLRhaj5|`EC5WI|=0iv~h>ynK!9V@~$<@7|%nNsV zpCxR5J+H4Bk3B~V)Jde%s#(;Kscr%=DSwfaf>a8cf%vAeXlqnuhp;7X|-Pb<>+vzUGIKpIC23#MpwH3BE7vM|I%GFx~5|QSfN@&#{Nqhz_@P zPpk6x`CfNjlARyRcbpK09W};T7M(2_ zg{zGtTD23fQTVM*j5dXEe6ru;Q0;O(-V@`|=)diG%7#-T-o;nh(^DU6Au^|zeDHcI zKK?59j_E5M&#b#PTCs~nBl=TvE?Cw>)B?s);To^qV#3_B@LkKG-Mi)t>~DJQ9Jd9W zrFc%Gn1c)LjMifn^BYIgh`ONfLvCI;q#xM*_HdYKoOGY$u+}!}alT^eYZS2BB3{W{ z7kKjZB-%ORMNx3uiRA7)Qut~ONt?n7_b3R|XO}M=VbI1KOK5d*o$Q?e(t)2B3<7Bz z(YBV39|eQD-puTRl>d4{s0MyMuKvUaVhq+Z@bS(Ievzzb!Nv^&iT)M2F@8xn9k$V) zn<9pd`p5TpG3WGtL({D(OajRFASS+hD|qRu8jnm;cMbcLU9Kt%JqKTE>m(=aJBU^F#lyjP&OMSx3@e_9MNi1EySi)s3PG@S{lRCO`G&aFmgt!j(1CZg{@TX~OqM^BxrbP9R zSXQQigm1NwQF?Z*IxAAn-AgL`4lMS04S52;>|dw!g5nVcT&Yo4?IwCQw`~fDJNp}d zF|o9c&?C9lU^=EM3O2EP$L- zj{O4-CgH z_j+bJWXDT(n9jBu-)5HsXk#Fsyq6V|G{)t~W#2Hi;d@TX)5f>{&(v9SsW7oCXIwMd7J>{#{pi-;f1X9T1QuIu} z%po0v;q(d7o#E=`%#ZvTkMw8dZS1m}GafKx=OW{Fhkf8&YOKg%K&(UWSS`iemQ~sV z4wEtL`pv)%oW(MIs;~vv1zl=CV+_uEM&y}e*&6S()NUMcc3km%1PoiE>O2$ez+`OM z)KvORxrJ{p_WmLWzm)-P)o7=ShPyb^qxT0XN*mQyg66Vve~xd-t^&@-kH#NNNXP6l zqVxw^uiC$q9|c|xNW3M@U|*(3hzy@}2GeF8RSd(3YAC!yY~j6L?DQo0-!CI~dik#T zlt((izCV9HNl=-n1Yf*%5U7ZPlc@;R-do&tW*$0(V_ktAhK4ht&k^!H0s+ zdPH>lWKC`9>Jr8{X+X)IWPBjLHkTG}qDvfhaK=Ix=?0#HfI9?;I1AqKf-Fe>mt2qr ze;#8G@4hFps7*#hwVPA389#jB;<9n#YI6p6=gO>Qvs62}>hWqq{NcmgH}49`vSi|M zx+o4}Ei+3)>jM7`tAcmm0z=!grbf4sxm?C729^O|%l7VX?c9!2t#e~G4D^S(jvKS^ zsWRO`d$*poFPN+DuLscx9kI@c<)9)iMkdyDi7NmscN7gT4x#f&dll~%s`kPvhZUQ@ zfbDC~^AIzH^y2cezQ192_x*!Da|Sff+!9zc$Z_{ARWWt_YNPRv_tPNYH6YpR{L#^^ zpjH_cSZmad82q96CBy&W*~&UQK{t<3*nZ=$SGAGfiBywQqoGERTkmw}_LPv-d+V;d=DN;9MkKa{Qt7jPXMFD2`zds#CX9?}C`(-K zCvv~O6I1ZMZ3P!4U+X9Lu6rps>aFzQU+2dHp*kH%B46|Ug26Uu&iukO7-TNjhHEev z#{9hT=gLYOs^>CYVlj{&ovJYs2qb4tky3yWp39l1g|j>&1XhDy@N z@%bLOmbY)k#9$yR*$->Cot27e z^mCjPG9@^xqq(oNtuTIi{k9b=q3haOf(&L)^~I@h24cm&%x-W6=rM0LKxn8M0lMgr zgjgVMb^PVVDOS%Jurm>B0XqkXqgu~1=EgT$qG=hhTb$FI!!;8Omvd401$Z(FHUklG za5rwtPCKCx3bC`i^uKeK90YtT`=^X2n$&qX976n#NK;GE#q0DfTAU3t999i%?X(X2 z!DFi2R!KN{koXCs7X%zM&=XR8j3U2(Cp1MGLCXt$l>(cPWK7>|IFHV*SIB1BnI;fJ zJ(<8-p*jA3W#BG}X^f?Q@OmLV;}9DEXnls^4~Q8Srja<=QZM;A?V6VbeCDn&mko6SN#`x~{&1P<#cUH^EqNo>ADU0YeGchJ=` z4}8m!4g$&R8>Bj7TU$w4w8*D*EiPEvctYw-e4F_xs~<8Wmv@}Fu7nwu8vEd0dWm#7 zV@hIaRo-Tps|6u!z`lapGJZ_%0a^F+3#w7WyG-4hV#$gnYrB4D$)A?m+Iow4Hhqn4 zt7Zku8V~1m>;s(jlYT6Zqmi(S@UE9z^-Rc{#v0zvjin{+J-M2-76*&C4Lq~BG@UX~ z4xI~SAKy%rT7U)&Q-Gl%bp);0UIZbbcPBJf@|Vf+blF4AB*8bQi>i?rdKT3;ZU?V7 z{!ptWWk?@X65(^sICc*9i|)tm(1J7ns;auye~5zJ>{Bwc54oi%;{th3{f{|yl)Y&8 zV4B#g-;7gW_ZmncXUxIIu{k3H=M^XE{FX)73Y-&!z`xeRpuKh#@F?KBzwE?|W{DR*xCK`i@Z=dmkJSrzjy1k(I z=$z0-whg37_99tAnUy}?(OW;vSmdI%o9AU=N@gnT13h5!odi7R|0I$qK~=a{`wxPD zNv0~q>PQS++={LsRD)Drd|1R+)Zn$bW*?D|46FE#I8$?MsOPe;K#9YUMZkSFJ3g3|0IRjZ~F zO!U;P&z1ozr_CqV@g@4q*{Xa}ebS08s)!W2Ow?R0Yy?XK`FJ$(x)3P-d$>nr-Y_QV zFvS+~5R$NZs)Q7M@=^nk5ZbATsdh|bvi-Mcasvo_XKv_CK`MFy)Wm{v75*aVrQuy6 zwP>QWHeclI#82102dPkm2C0O;|0KMJehYVA-!vI4O<(e}=*zA{VTEK{_gtxV|1t5B z{M|zufRe%)HGX@3FT~Yir=NwLAz4!hXgvs00Yi!6Hn1R3H*j4hRB2mBwwuxCdJ8G9 zWs1la<1)ewoF&5VKi{=6s zpp6uSkxVj`2rNb=m^;)kOmr$E5@%;Ju6TD@atL%jbO{9p)Hc!^)w*x8dV&nRsdTnq zAm*V}QFDR$8rq0sy&*W8h^NqRfp1AZb#+I>$~XC*@~DVob<|m*5|yuF1o-$N0G}16 zy~E@QrVO^>`{mOY8sf`zbG3HO?{n7(w#*=MG)a`idTZi%vkctkz)ucT)Y=4{ThW3= z+`)^$SO4@2?}k29|Mh;aIcRh)WOOd`9Q>;DMO*?1;J=z?3!GH`AW*&yL6#^*r6Rs+ z%@pUAr(Bu0*r%p{6_Le0EGLmtwN2Ag8D!tf#da?Q;aB{|r@Jr*)3>MntIQRKx(-pE>%5@QvX-|#-7X@$E6IGxk;YLE&g`F-T!PO95#n&X|8!3QiS_n#fV`yHxh?AdfH@# zITPB2sY%CdK=O7mdXfZVSw~bcJK328+U}$nf9-5*#kLW}&_z&ngdu`lV9~ExuHggv zS7xt{fKJ62_Ydn=yu@XP3>n`o^Ac~vXm@y&DWHj?<{pg5p8dV*ZuyU1gSO$mBi@%! z-1e3uZ3!rf!bFbFtjpHUmwfHWMG(T zy=78g+K>>kGS^4(SiZW9S&<=$aHhm)!BkYf{TK3!A<jI8ryGo*po8J z8mTs37z+I``orI+r{?vY#JB4BbHV$mVf>A<;CQ&%gfM_Jo^}$g#O8HHbb+P5PMAY< zA=O?|L|V@lgcty>ll&0yVR{h2F1P$?2U{Wivaw81(e- zeC-wxs-;T??c>>%9;>SvHUcoF?jF{CON%IfZjvpox*Fk>GJOP~;N1_<@m0(997sep zG%w?7j4+R~)z)wI@|cbl9PIfg+ZlQn1%Hd%ZA=-MbVf6-R{V|mCw0R!6@VuQb>tMRJKS1wiR-+ohHSG{ai>FgeZblsGsTV&g% zE(y}Rfavob*g6I(5+m2QNfiX2{JMCGrXAERRr>%YVq0Z`K&C+;rw6HvROMoi(|=K$ z=Vy%_AwS>WovO}DH^V&u=%?4a#C9DVW=j4PEe%C;M!prqw_Acu+ItYHY@KVk&AX!r z`npT@<7e4K==Z)|N7zvmh$s}`8C4W<+VaMNcQQLWlI?<^L0N>THSp7R<1!8?9re6f zn+^-18oL8c-y(&co@ts*V=@vfQOm@?km`T0ijUMAQn+35yFfvR*nmKErB*W~W=_g( zFv4btoLbw1osnDDq~AZwQ6W-a1FDL;0-kN?CqeWZJ1I<8_4w0890WFYD;1n=?YUM&boZF9rL_)}lqsAp`7gHS{Fmt6jq5WOCY ztk-bhR--p|bj1-;SH-dwRW^TE=vO;E;|TaU&k2jnO#*9&GgwX~`lyuvMn(XWsp70zBky&`pz2c zlp2cWyEeMm@1HX2H_{r#}q+g zSk4s$dn9nWNnS83<&s)Q(2~;cXgCj3s$4Gb4Fr>yl$Vy`pn-FHtVWR#N{g!i@6Jqq z>fjt{R{1sK@dPBj^FnNHc0?M0d%p{D*w)-L3uR9ygri; z#3ELc-KplSBZzFPs~Y;DUu8-iR{zK<{`wC3Ugk&8cP0fLo_7^Fske>gFGhe~yRi{1}_J zu3r0u7I=Hf#FAaJj`NFtf`MV23|boIBxzCsi-IzNMXSpv0XiL%JTHD9k}02!N6htI zEY{{9j^Y|6m)(gaRi0f(A;%Ncuyg-+M27GlsH1y=bKJW_#V2Nq^Xz5*G*n zeNndTURvNAYG>2$1vvS1X6|&6;*!!^PPURV;?m&n3|0Q3)^9l|lOs57C8-@2)U2UG zhyrd&SidVOMO>W58+E#L8;ZNTyAw*GP_(#1Lvez;ySuwfaSaaL`Tl?Q%%0gNIU)yP-nrlVdDgYof-CW+ zmiXNFQwcHS=+D@Jj7CMrQ6t`Ij$}c{reH9_*&Ngt>Ytm#0}i*1oplOG)OA2EoSrT* zX#H&5;vr_`-$~xc5v!szNViL7qv<%22PrwRSi=yEnIjiIW{n;9WEHY6n)F^Ct~K;} zkmQRzvQ+~i&W(KdB|HnvN*?uD?GrWj&WicLxViWM z%1TZYsV4h%O7-c{$r!8dY&Mlzfr7O9daup55`! zMMvrZGV9We_d2F?~zMkkj|MZiDeX{`7(5`hV=(ze& zTdFfF>$yccQuALNnv6P^zpmX;+SW{_Q&qx? zthDovHaMcVEOiiJq^V0#`SvK)UQws~Y*KfYjw+0)Z04`@-d=cZSa(qAHS|wj&tdnF z08+T`tFy|ZUH#QUtCU5hxW1ms8b;6{$&OfooZFs|Nc5To49MyJ>DPIW8dS_WAz4N} zSgJS!Cuo6|627cARBBHp_+zcDiE+H+RcKRG{A`iVTvU#E2<&px+A07i9pjR~n(| z52XuisZ=4SgU;{iCTiEd3D*LGtcoV;q)mc)*$ui^b>ykHuwPVsk+cR=-Cg-1M!8Ng zKC}iMJZ6vm<|*0Y?|lWIY;Cv{XqgEHPl%!(O(csCQDC;Ut$1Xl;$85FnGE=s;NMI~LwZuj#LkP%JKodTOuMtm%RxUsr)%nNJ zzVb^+RQV7$)}q24O`NYPwi|jNVfys5lTHnfrpW1;tmsfkl{JBHkNP z*^Oj86*;VbXbW*P?voN;%^>E`vt1m24Ie&Ff-to^DV@M%`|C|G4wRe<&4r$9a^S{1 z!?0rxqfs?3@NWP6>u3mSW)F*noL_i*&F`tVgGT&28mkceg7{=^vAhd;rVex&+qQSp z6!^E=g}LykSqEsrq1BSsb02YIMje;;G1HGmaEnkHs}v3dRMr!sog6K<68$pih~1u0lKc7&L*g?)q@0TqpdEssK?3&9s%s>%lDlndOE6h-hBfDyAP zq1panyuI6m$RNKK?(*-wCoL4o#&358qt)k%#$<~S_8JJ+i~@JZxw%HltUT@cy8Sf}I0owiD;?DgRV7?>VE0k`%RuDic}hF2ZT+!0S}NhxA5 zNzAR$yNeI$gO8e|-@OD$%t?xU3TXaU&Rf4d@8MUyZ>6#PGeZhRCfhl)`lKCpzZ72| z-_<#e@?-Net(_ss#Q={Fm`Cfw?cm^C+uKwiFBwuN#vQ?%*muN(6<*K$yMIj*bJ8Nm zB?fMrVpkeDcQ=Z2ar!HEv6T;hNq}*1G78bhWu0AbEimO$hVmNYYw8nW4(!K?5eIKv z_{S6nKHrIQ#xVXHo3nnjW_QRfM{H{gEM3u_13;;$MuIix+J~Y0!Osvif753NrLM(x zw~{BAC~Egpc9>2g3G3IiZPa^Jy~XJpugBd<$jun>0$%8talTe_K&U4Bs!8>JCL0l1GV`^VZIW>@>~y7-oEfJC~WS+GpGm<)ln2+j@g@tPXU?wQCS(bU5nk9Uvkj zr5PK2?wzgd=daDU0K5XsB12%d8c&7VF3AK8rLRcy^vWmpjO`cKBhjvuI~!5?s6p%V z6a_~55OyW9aN$$tRk2~Azu^4sv!DeA%XW*Nnby}R9JN`dW8GU zmf6&a5vEPh75rn6jFdCT-m$S^xbT)E1!4ce$?q2>MCl4ae9i&@OUye5PUMlm39}EJ z1OAcsArfUa?^uWW<$S0s>R%DPNq4Tj6UmN5~P z-O56WQEhlj*^LBVq3_kQZw#ZnRxIDhzENKlFl(n2o z`SoD%gEx}GICz;3u5fyhrWiE{IvgE{WaEA6)=6%6f~+BJ?&>whr)9mo8Cdte(!E|w zGutXTDt=gJu0PaR_UuMn_N)i$dO}40TReJs1R2!oY31DZjj$)xo|O%KO7yEl(lxUY zP8})SnU$+5b|EGDRP3zU+#+7mS3<#x57nqU?I1?#?G_bIpiKH9^!Mw+&&Z9z;HRbZ zZj8~B!^?>FmurgWzxkUmAwVBe@q5GfyPJWsh_T~Bqkbp7CO?Ye2CU<6;@Lc??4?*O zqQ(qud_{STTvnAmu?-e#kBfza)e_g_+;)YWLuS04T|3hMe#%uAEA}WIZ8(rsz%94) zzqzA{s;g*J;cIKm(1{YUf|CAPB|~3$=GA$&(V2Yg2{ z1ZN+1864oS294QC*a7s7Pr8GO4>X3mixLA)2Vc%|FB-)UYI6^*AHB93JKhdMihtZ^ z5W;q+Z*ob9_vmM}FpL7hFUC3kjcc>|)wNSa^x{7EBX)uH!^^`Vn?r6JqWXU;6UiS6 zL>XJIqSU$eV}-$U&zIp;6Y72jdN{kFHzigmC6dPR@u^o%5aNfwEETjYohY!zQOs z&Z}{P+Oox(%jje$a+`UNyMd{Ij6Ou`9yBiNEu0L=UM34()|Q`N5=Vxa03Ji2U^**v zo6qY<>2<>GxC{IVrrESUzUGpI(qi+h4R$Qk9VG+r%iG?$8Mih6lC#C{gT!Z~;_a4H zf^N}2Qu7n?f9OK%QWc2)hyhBHx(rf90wWH+i=38H)wcOf{9?|4Q)iKB9D%%Odq8PG z>44Nkmw7N=^!MxZjtnR|GtH%SG2#h!MwfcV#?mq7kD6Z1Z&Ha{oi;!6I#-|5YxRR9 zA|0Ext!nO|`RtY&tX6$oOsS02-OXSs%1(+w&g?28!ZnkpP}ZC9Y)9DrBT9WKFPKC? zM1@o6VbJ4RM;We*hZP1X@*neS9e|)x9Wy%(>aWOs>fKwO*#jHp=V?JN_1H?w8|ZB+ z6#N}+r7L))oQw?it*HxejjX1_L6sB{Zsd+-M1C zQt~in+lq&IoW)6ixj`hMw079zF{(w?H@V{F)r4NjOWm)cURx5C^-$Gi2sID*7(S-h zMPRj}F^$(7?8(oAuC|s0;c#qx>UX@Gc223Da{4YTJ(-;+F8DpE$jnG6%32jvTw5e` z_Wr7JGj?fk(DGY`GrsRW02l`Q`x}Qv)fIhU3;y0T;jRt3Eyyhjib!?*#7Gacrfag= zBbjRF1#27t($GdKL_@w%11h$H$bp@UO<>M%C!gowfbTeBI#LI80*-h-`dNd${`xcq zy4UpTwJ(Pp z^^dc8!jz@aK3UJp6E^A}N4NB2nb!RU;SIl=R(K{D#k*f5A2GiPE2f9m+QrF0l|q2- zA+Y{VyaY^pQywwQV6u;Xxq)|Kf#F&j_U^Uyb!&Aor2H$DM#1Y|urzVf2R81eJugxb z;N*=Uwe2zWW5!lUH}CM^t7uT!*h$+pH$t4EpIl3nHoI|kB7^Gk@7^Ca!Ozn?`Ct{D6kInY};#7)++caW| z$#}pi+W1mhIo7F8gJ;J8Xirw&&j$iJC}jX$Z1E?nDO)YT((%k9cc8|O8rMUMcBY&h zn!D#EUG5F{XBJIZz5QS@X?^{n3hl@uR4PzBVE5Kh!uw&i@h?jkq4tila0&6_K*gDPvpHOqy}^UbT(t4 zsb(@rZp`O#iUKj?kB^EK92i`;&qy^e^r_HdJ#C$*Ul+R%pgQGoOaX|OIzhq6=twsm z4G}J82|5cC>QLX!#y~0+xZi9d?j<#zTM@Q`oZXc}P2B`O@!8>WBkWb8eDJ7M z^r;*{FM}XYBpuTq*=&A?bYQyJyGHb5S%K16E#ST0fu^sOL>YAE&>UJwBN8Gp;<2?O zmjrYeUHFw0ZOI<whD0>%KDyp;?sF1?lrDzf|-uo?WpxwGyUG2z1G6Y$oyl&H;#uW0)%KQ+U4@DzrfL;tJ<-t zJ6apD0(qUaeBuJ3wEj9Q{gX@woY+bskJ%f!y0`v2~wg2RILqNqL z-Eb&!!{!^IZ3hJ%;yG4K$>NJGziJ!A5MRv+U}rL4p76%Xv{xv4S3=aQS3&JM^NrPM zTqmTF&?{vZSUK1+;BGY7)dY?0!kH&>k%`Pbqv>1cKiX_h+f|jb%viMdtZ%>Db|%=y zFGo&PUD-5*6@;IOV^J|@bMD7R8B-F~i{}zq{xUL+LQh%BVS5AsZ5zm?4triA_793N z;Kr~Ec;B6)f{6bL*(o=9e+hj$7p#AM+_h`IrA3huWSX|xPgd7U1r@XyOCS~X_0mD; zVy;4M2r%#Z95&xDpGObbYy@E%!|(5$rBe%<2vn6r4aS}6PR?ye0%O>+gjK3O4|>jh z+ZM<5lO0agwJPmSNlYWkjj0VhOX$KR4!aEzj^IxDPrca$n>e1SaGO99B(EtFUspA& zTpg;{jeNF|R%@-XHUQd9H7B}n*@ro0D9j3rA%~6UTY+zX#gIBR4?H`?rb;*zZj>#~ zRQNNdezus%V^W6nI^;s{?f`4$jWMKrmy(tYt|&PcP&m3l!;23p%$ci)ag&*wo%YXx z5=ot3?&7{vb;7m`bwTjV%vJ<5M_odXNb3fEO&KFB!H$Kt11@)Il`;>m6?J?$qw8f( zd_vQT3fwHMwkQAPJt7wet})6cOFqN(bdsphAvc(VEU$6Q{aQ=dpr#5x3{7Kp{twS` zlfYx2U0q#C*XW63rF_TBUw{L*78C0Ty@;O(qc zc94XN=VJsFv79fDk~G3^mFM7&CX(n}am=(GiuM7lf6J$@+Bb@L%CgL=++^fK;Mvc6jJK7g_xW8q zRQK~*xvclp*;Z7hBH2c<8;6!_(P516G9V_L=o3&zsWuN$GB(-%s{LKSRnEExlJO`x z_P+Htb9LOyT=`nE&i(TxfC`q}D1{pB_K|zYE~`HariDg?rX7Yo*tOWWW+!WFUI{q4 zL=lTBVH5gM1EjdJ+vdgWwb`+@lTQn?1!isALoF9LV+ZSBSj*VQ2iot;9hbz+N3|?; z&cFr_a#Zz`L`YTeHj3W`(4Td|V}!FqN<;vd4l5GeuVd5iv%uP>>K``pr zq`Wd6Vdr>Kouc)*)OkYh#8D#o3iYJlUXyRps)VdS7JDwWdo;nCMa!y}BgHhz{;@`F zU8brb+M<|kwxYKbH)q@(f$%V)gh#oUXCC3q5S^3SJhDE!3~fHV4B0U`so@@d)Bie% zU$lLf1d9ScLfuJylUj}TM^L#s+mHpD&30RG-9_E;79_1FE0NvZM!e8GSN3er7c{JY zrj^8P{_lt%YD1sg>pT}_s}WZ(T@h?;F|)wR4!g;*E9o_8UBIg$SW#bufvyfSd|J2q z=7ybtmqz#j3iBz(#fK^%_H96ZD1XyYz(S{eSHgGDZq8>!DrT12nUoZ^>Qtiqpc~Vn z1_z~HY3sfk?ri{kUVKZg1Y-u>1GXE(hC2j<1K*r3+)0m_Qmt4Ee)*F&31YPgn} z2(-Nq03eTD-5tEA==s+VBdsU;U0Ob9*(5Qm>F%#y4>pb2LZYFK)5@))IkKJO4NoJ= z{?Prj_9wsS>Q5*)Yh;J8U_;m2xg)XXoieR=W6$NzR1S%=#0|}+zaaX}LtbYJjfNcg zaN&_|bO?;mte->GU*!@K!%b^!bAA@rl;wm%f^d;!#yzXHN?}C#zBjZR1GjiGXJ6F) z?i4A)<9@ku^Hg@05jU3d&_1qZa= z>U(#(C33~hkR1z=Y01Zug?AoTPT-Xm7KUG0m$W~v*xwzORdO~myHJ$Ld^!I%Qb5T1 zFYsYQB#;stA1}rtiHOVVd8FtBDE25AQ~b3k^Ym{dx);QE!3l%I3bCT9VC-4Z&Apub z>!Vi43ta*N<3rgz_gxu(kt6rk?#O`1#-PCODf79U3qQ_D(SslVF1bukjyLKv9xXbx zRc}&X9fIi_@qZj3gw2TRzc(RGpogU%}6KNl(Ib+13TG~B?avi$CO7>_nx!b z%oEmedt4#d^0A*g$r*3wB9m*W%j`0;TM$lj&Gq(xhcKuY?(4O6BoFC3NWoFvX4i~{&3b$Ya90C*^q04pPa zjL&RnshN!V@JlW= zr}ui1maLjbVi zGncOK>(q=qjQ*?>RT=6K$#hZS2o%|86P?7rDNa8MQX`Sa#T<&^ zqsQd4H)!Bw5DuK{mKC0SDOY z*1qMxSXfpS*jFV#spV$ygAl9aS!Lm{RwQ&fE2{gF0M$~KmH<2GT=9) zr@@u-V8m_gmm%Dph3LEVVJz>n;MgCH)>+E-HxN+;PoCJwzY49V_oBH>m}R;50|k=} z!S~F^Q6-R-JdT{}BZ*=Ss*z;1Fa^XJw~!Od58h?3DeEnsq`2*BoYOCJex{bW$iLT` zTti>)@;4>P{(&_)N(UaL(q|3O_D0+_i6gf*!n{3Cx4vH=K1anq2*z%DI%2;Nf+*& zRmabg{ZR9;hEo52O7aMG)F8>%|8}IYkC|&aiHR-z(NUv@UiM^HTUHk4TNpbV>Q|}b^Zy*hq5S;E~ z8d9O}KeMx<$(7=W?AoXYzm|DE$91#cF{9%VXYIsZ?MzNTFuj(obB$}G&TzGKS8QZu zFMZ!#NMV2-iSp2^w!<{7DBB4e$XB@lKWerMw#quc)u_@bg`}X}_vu~^Lz@=NP2Oej z+mpXbXAK}q^Qg}wpPyT^RZ%hYB3E-*T(N>6u-cN)WR%x6v6ZFOJ<-=T*pAcatBr*o z(pL(6BgQt-suU>xG%HP7oNwNf;p~N=jImXC3E%=CUgUB`J>7*r&13NZSz+X7AvNAO1Bg&6kHf|O}=NU~H;Q9rR z{_;l>=&G0nq|fWKxBj#jaaJEL4d5%gFJx%4(XUQ~uY9a-ew4eMq^rsf2MUC*B;*t| zgo08<>hjmVp#fAK4X5FN3Hme7U(B@G9;Aate?P`+@SeAQ485@qPB2b@d>e3t6)fI; zTO6T;_rQiN^h)B{)lv{(->`oCezzWXmIqYK1S%%yeYNqqT^0raFFNR{6x&q_Yv8a8 zBTrJHnR`#U!FjUJIJE%y|8hKmhpQoNeguztw@djks7Nvrq zt%T%RVLgR2zLun^m^M9Zf|msIC<_o)C80lPd+;3aDX0nM6G3SP!UX*~1pw$_I>SpU z$6{x~i2P$A;&t}lY3(cFphHGM+x z3&m29MZu+x*O`F}{sx)Rdd5&z{Be3SDUK5Tv{qr*YUS9tQvUmQ_kR?Dbq>R~%crNO zEhh#obxaC@RIoqg$ER@2kGYG@dx8H}@99&mEx$s0#eWq>;puJMyxkUwQ`h3gPKmGx zlhQ!3&U&%LYh*#@QBw&cfU5T+Oq|V#=Oc-$)Q*Pvb%rjP{-gcm*`rD>zAnoAOksd2 z&FnfpPA5J%E+e}J^h1v2eNt25O~W6LeqsC802#QQIKUmo)>ikj?F@<+8%2X?>$Ah4 zD%n?ul7<%gu=7B$SCRKm`^s+f+_g=aYQt~Cow;kcK@CigUJ$-#5qKc`CQ~5PT3=V~ zw~0HnvKhq{Hlfg@R2ALeA{0LiqZ7h(d?C6ZFdZdz3!yL*zyKoFxi&P~GS z_4`4>hRI^YwDhMIZA{Hz7-bNHAjQFQ@y9tNmbTz@bfoiFC~>mPthk|D=Z zOLi+;UFk+o8A-V{k6GiD9+b_Z^WRCX{~1r-7d@wHeCxwr6ufXkMvMv^EoG1~M|nma z)+TXd_9~ZSf6WK$41NYpai)2AB>=&5g+YdI5%-Z5%a&{%eg35!lNU6)*+-JDjp5U( zeWu3?C+(%2<##_ee*3XwU8=c7GsWsQz$}-D$?zDa+l@z8;!z3D$uX$yevgq%7CR$O z3Lq5Dp8?m!+{6Q}r5$pgVw)OqbAwyD*2&smNoa8>3tL*l`I9=S$5{#EB zM^EEy>u=MYjrs5a4iA-wyzd#@gH}8(PCWcrkcB2pnG}oFO+M5|X~II>j9^gsXvl?K zAe#+JwX>Dc)S@SdoT0!@=l7LNgXhRD!I+E#8&bRH{_bcZ7bmLOm6!5*d~y`toayFG z8?uzJGca_pPvPhu_pgR*;580tx*GJEw{3vZp7Wp|Nc!GqokpA4CD9JQFIYgaU$~%Ub&1=5T_cX$Aeq zc^YNnd&$LO!{e;jqqvFI?BHABhnUq$}|N@=t0AxQ}KT>qeA31&`L9O^B|Ui%_Q zbu}%srX`i|8Ntn0gcBZbr2J?q#1=({Tmb+)I^w=NxA(lfN?Hw@1pp8I&Im|;WxFV{ zv9mQml}7*S3)aO{c}i<+Bz_uS)mx3@vw)eyuobC_!2pHy(gGwhVA{c%C=U#9N4PXF z%hc9bj%uwv)9%DvE}g%%T*(A!6iqXHO6~cMIPirc9V@ZwL}}%lE>gsMQbI(jqhH56 zEh+!l|5BjHObfw&&nPWJsMv*`!==6+kiD406<1Q>yI_T@x!=cFTf?zfGK-hjVEttA=|-7Z zN43VzEUUs^&>|JGcJO{06J8 z;!I?pMLX?E<9e1wX|E2*f>7bebodBz^hg~LM)@WW@*30<62zHo2$`&UTkfV~4`O=) zfS3ZB0w@rqRjcTV8%~1p+ zV^yqc2(a|`IEasFT-fopH8m#O!7WDLY1fS>cTqw_k&u*QCmOT|9C3wlf)ar|z7<)aEc?X* ze+D4!?o&>?m~H+|v&eVg1n z9gr>&CKFpgK}b^fH@zskUfwnkVM>EcotMClBrzLva}*Jx@xWeSBt5iAyb^)}mXpyM zPkn*?H^DSM1Q!69ki;`kx2IYAOIdd`;nSbKIbA&NrqM&XuLO;Q`lmy~1SgWaW*$P{ zmd$^$!OiJagQxf|B34O;oLCgOA!K3@T^w8%Ljv7WSK~^%ICv5r{ttajysAvPLqe0G z#Gm0EnQ|)olh9ICDfY&l5Md!=+XBASJ%uQPAGw<(_3j|{AoJ6Bk$xMst za`STm{Yqeg8}kPKH~BTszqY3ju*04MmW*JfFZ>@s!YIquV`*6^;U|6_lZ42*<}Tb( z?NV%Y3o4vR1mIBIjow(XI0)Pv*BUbcQ5k4)OJ9p~ZU$nvE8SwIoNHzLakrOZ? za0|uNqTyw-Pvu4nU}eo2b>g`hb;AXI}F8FNcVVH$;u*ipo&L^L^VFY~7r1svp;rmS%B| zRBR3AHn|xF&NlzqcHL1P7sk~|J#AY5y49;wu)m7cva0OVak5|FKCg()>lO^T1B$Q7 zbKgB0Uprp>@~}U%4=1hY=bPiGf!LQ)vrjgrdhP4+iuk6)ED#t`sXWO2-zN&SVUF_K6cR__B}#kgy_!`?%c^d<&u&&jm{GL4K# z>4aqDN}>xV+r|do%qW%d##6Z)l~%X;(}1tZ^~y;)wpM%@e?Tz?!qIX`9q32W!#Vx= zcRgMkgTl3rCwH>Z=}2$_Ki`uvb$~h;$OGV#oUShzUbAvd{p{3!I=wG?qa5Vn`2VMv zIQ5$i?5J22^!x|yHoB-5CJb63Jrd?_K3S}FCG!aWXR)!!+5BIN4HhE!;kaPf_*jX$ zK3k-7<`HS%Aki9fycYbCsVxt7r+QuJ>o>_*5`CmFnjy3L_W`x_c9K$mvH8a5_h>`g z^#}WaBYJzP0cK`4J)k9RqAeeyiOY`9+}mrSt*{$xqzSZ%yI{$>GB|ZroDtK2s@bwJ#3LQd;qtYYpZ;0OiDL;;kwcvAp!$<-2sA2V1rT=J9)6>_Nj3ZtLbT<30c!d-6qj}> zj&iYf&RxzS6%Y^vm8)Ey5->0y&IEl>ro~qLet@=u6^mk$B>a#q-lDHQcNb)e89@@x zV(0T7@X;(eiW!2ZitqdM;i!s$1Kz?Qar!9^as68c<;*Si#TYi?KraHdu-9n{xj3@! zMT|$QFDVAUGC@=gcX=t<8)P20A;2-(kF{anXCV{qc;YWE(xX=hXLSNUBtc9ptUi?ot+K&?7-p^RRgU4Hw3pVUn z$9i>b{Om-A#lEobPJL7)9PSgGw6!;uNVoZ4NR31!{fA332J=^~jRMZ%zsff{r<7tM z=DC3(wi{Oz!k+Efg+k`e9q+JZgWG+6PqG{2pnylF?{sx>0l-(7=xm;LpxQl4AirBv z*t<~i7f@$Y*SKLPqtA&zTr#f2@{{j#U^q-%BZ^$Qn$7pR9*Z~=UUCc;+^{^cA33eh zR+?%XZgdp3c2q#PP&`kx${#vM3PN`L$f)e5Sr%9fDmkOJ5y(=?TIB6GKZtE6ZI&>c za~-F@8Ao-S5%~R!3smT`-NkvD^vHs1b*62uZ}-!I zH_&4>_WkOc8)6Q9`j9H;ME}`kw}&u%MDU$iExEl@!wNj;uEwD4Z}Mv8oyPJAZ<;3? znywS)*=CGH27f%3=dH{X$G$_yTBO0TQ1Gt?Z&Vgn8fx_6-Wc3l4xH~S=c|pAVqqM| zca9>yV9v#*C7aIYvy0P3=a&`1O-A@=4`<|IvTc@@!T5!&0Ngl*jfWGDvDXF1$mo{m zfL9w68u8K#rPRtLLgN72=X=U7&Ou@UXbV-(58C7Qdk5QIb$hCV{e4|zN(Y{Q>bijx z3AshqEg~mB;1|b54a6^S3>I$XZISsAcd-Y-(ZTTfEBc5sVdc#Qq=`^{ul<$s>~^5T z_-3c)$zO0YTh;umC4cyA=LiTCk-x8N?SMd?fdc&2di8+Mx+q!`j1 z!0_}}Ej{iKy6g^BTZct3sC5$jw@oEg2VXrx)INFwV7Kf4&-j4{?}2rUU)32t2W>j% z8XvuUbDOZ3s}Jj=gSvtk)wC+YI?a%al^1vlVPzz5`^J#x7vE8)vHBiG9#*3bbEUgB zi?2R#rSOV%P#79CI1`Q9N!z(Vg5y$8`j%FBz!()ytn5^H zcH8gTIvNr2^0+tBubYiB?&CoX;cx@w+ZraXw#$|(6L4QC+2r2-Iid*35F zPf>fq<}$;x{rlnow0=ZVUvZ>M3Me-nI5*>6A%I%iY-!+|wP^he*C2RNFcp~(%l2+g z09Wnr)y5-W;}Fr!)_-}YO4K%jG>X>Q^&TK-Eazwa#fA@UMVm8mKVE>dF_xH8AwC&F z3S(FIeLYfB;s^lzGg~Wx*5K|4Y1vx=(OwZGO2E5=rS#*6Lf^pQgvW2xsh9>N5iV=R z@_b6O=f6$+f8zAU!9e{r0fb@4WJjunIk_!`5EQgi;7KD$S-W|DhDoQ+j+5gI;}Z&D zx{9lqK#{By8GSrshUyjZ*fSs%kJowLXAVQar;N>Mv9fO}Hgb91J`rTzyTJ8nfbfk` zkA<_V+e{fLDvv#?%h#--PRs${5{IW@ro33>dozUzSq^6ZSNfn*UFC`-F-`D~G214A z-*j&Rt_qh&!rWH=MY(7xL?L9^|N73mN zC#aa^%%j@Y-&{WXznHF6j{DUD`&XN%zAd&WJy)aOY$!M?SeC0@@AT4f(~d`=6cTfH z8D0;)D*&+8a;7t+rUzcR5K)E`xgRNfgw9E5ePHU3keAg+?Cy)nzu#8RI~KK$_QiFL zMo!@e2J4l1qBb|#n*m(fYE!0LGI@-o$v(qhE zk71Y(A<3C231rG{w%>PEhxLIt7?w^e$@tpPT=6$qM$|50;UYTS-~K`9l0O|O0MzVg|~OSkg%A;87CK{npkt+#wc}$irD% zVBAsXheKu3?zr(Y3-&~UQ`+pvy!SNDtKEYGa^~(ryEv@#1;k@puP4?yz0(szgM&*< z>_+pW&CPuZAD&Js&vxU)2Yh>Ul|6;YsUIlc?yxXlN+2bcV^Gfwe=Qz zO}c&E#_>&|;F9CdA?~n(qqCs^*t9uJ%OlG%g>0GztRjo#z>E7d-BO0?9U`z9+3b5tV_j&obIUpZ`KM9Br8H3&hB9Fg*CrN5aU zAf1Nf;>|a(d1b^kdBIm7n}||^0tYmD6{){1IirKV^t^F1!ih_I-sr1PQ5w>YAOJI# zYx-(<1gvNR0~b)SJ)yImI+OKfDPOakk$73{jQnTqj00zPnso`jTHxTxhwdLIH=S(~ z*6%WGL7N55_@8d;jhGo_9@6TD{H$>g-e0_5N*ULU57O3WdZB-^st6l1@K2G$GmsXu zk%95Y)@ytExGv=GCz!9MW^4szt_EMRO!XF*@oO_xfCN~$X+RGts}0-sSI(0i19s!` zD0FH?dG`{6j-;0UWgBP`ydIvO0)Bv6-;%`=+YGWLa-S$q83L=YX#WZIN+?i#N2z(!)WI5lv#OIri~C^eVjf@mpR7<^^F^Pd3DWu_Zc$MkX1)O z*(40IuX5zgPTTQ`IFlNT= ztOjSbu6>iwVMJoIyyqwS^_l7*>jcTiv#sAJLtxY@!C5Cv>t*ITMt&Zx<%%=kyO|SH zo_s*MsYF}^fStY=!q9lXUjN|ja#8MbWFo`q6Z8ag z%NLrg?Kr9A@331K<1@SZS9#k4(_1@O#qZk%t-_BrHE&T}x5sN;=;~b5va_RO@AsP| zazVGGfV08!D`rZKhHgmRIG^)!kFaA@au-JmMr5<{BhO%q_2;00HTvP1)OfWa(xY^?PwkXDPIV&g!WiI+NaQt0K zNk&@T98M-k%67>GM$?qct;?<6BYg4SF|8Q;llAf(DgO5`HSgFM=y(qdDV}@#)$)($ zPx6{ka>r;RDP8WsY|xwS#QZ;aY-qm59qcpB?2dfXIgqOap$nF)@V{<60pEB(GOCfz zw3oZb4p*UZZDN@$_w_KI-um04L3 z0*9n?fX#1*oUq|^0*09!+kT$Ccjt>(l*HAqHq!=nhxUO)-czO>HC8p)bZ@Y(#LbRb zghv;?t0i8ac zyY@t$rR-)RDO-?UeS^K#M-c5odG4uDry9(Q6AozSV=(hfwh=2&dQ?k>Y*5t9uTB~D zyr=^6A}v-HxV|54lM56VI=cM9Yust}IyW4Z3sO`HA`p&6c0};5V}v% zjZV;RnzHqAU)}x~7!cUoC+8$6298-wb?n}=DKk0W-ReeZEXP|>OfpXvV*X?bR;hsK zWm=U*o@f;!A-h*twxqP`PS%|4K$U)Icue9U8((cjw`4x*O~^DQjT4{1QWj zlQo=6;F9ziDd1;!C&FzO>`(_Tj$}VkJl#w5kO-XDU9XuJ+&3hFE!_mo`dZriWHf8%k@?%7b4kx@%gK01SQI%=Myp+$a>BdY5vc5D z_@uQuoMgp~ZtN~Iw9&B(p1xqtjnMERV6FV6>blKVcs|Y)zMF6KKD8SK8Mg46a8&5O z*XcmJ+5R9hXu6_DpK;E)a*5~oU)0na`CKs)oa6qm_6^Lb(v~9hNl`EC18ZSpU!H*# zLZG=wfO7T>epSE>zzT$aGI?voD{?$c=yD@GKB`IW8xV`hItWV z4Qr+4E0>#D9=*zWDZdbi37ke5FDKXr-}9TUHnW&5r&&j39<_GQ^ZlsTd^d1AM}X6V zw}2F^TgC6anpMc>mOQYGD)#+!{h9Y;raYNzv(JTArBMv>0kZ#Y4F9Qi=Tq`%+~*#s z%|8m|Gw+Vvhe6wuifxMeh-QaY++pqUf9Fl>riAPU9=-{~TVd#j5SR|wuWcMSZ{&Z* z%fm5Bu9mbIG2{OAW+$iMx(p5Xbys+CO#H6GczFL(V(xYfPhyTo;*83*>j|Z3TlD+x zg;{u@zrZ5<-8J<))k-om_KPEfrgmh8K}Q$A9xv^6EcLrumzBCt#YX5^7UgFgIC+V>FNkizc zJu3d_E@bKOFrk7m*UM%fJ-+dHXu1hubr^d$<)x-$MbZUi1f8fc94ZVF!1k;3L+?zz zL6|=e-3}%J2Ax2Exlaget-zau2pD0_Q%4jyKchUB?PZ$#@j>#pa+xaGomT7Cs`@AC z`FwMptF|)xyCLkv5oic91q`6#*aqFUNtM;=UFo~CX)R$7$PX}HYg(*#ZA*fIzxiTa z`}08)#3(srnWRn1SFrn=lM}rJHKGjDQ{J^LKMpZ9Q~tn$$==))gM^$(Qmk!x6r7?; z^hhnmNAyPdEf~9m4l_CIr`3C#S}p$Yf4*|9$gCl2L!H;u(C^(r({C3XTyPj}nCanR z;YjkrT2T#SeFVq~t;kPf{#;o?Bq5?D4hW&BzgysJMF^f|0~-`$MI-D~>5NT`HHr|( z_g{WaHc8R09Wp4F5-zO~aj?XnNkHp$hnL4+5!MwP5iS(4!70JiEF}KCVGW4QB5Xm# z#hu)Gt);X`PPQ%(d~67mjz(h70+!WK z`%Kg)%;>g#hI^0{5akXH*L|O0v9?rDq@?5|hBz2tZE-y$r-uOYt{}IqIb2DcEORTR5=4!VINwWL7~nwtgcBr1HR3xK zS{(3~;WFc}+l&L*F;NB25Len|MKP#!Unk&a13#)y*7oN^EXtUbLwN93gphmleE4?2 z%Ce69W_g2Zc%pEiRd#Rt0{4tPeX~y`VuT_V5(zNWM%v3v)xl=Fed&`8=_1y0StU&L zuhi0~Fd{EFqW;7$MLwxqv<$FnYh2mmJueKrnpd%xf4=x=rwMzb)?#hynXfjau5dLC zjQpV%6jm_W_C&W#@CFf~QTMpT)NjIp=f2wP@L4X|rbzc+0;tSkIK0MS4$zjQBo8R#2kJnBSqa0;)HWq`!RcIfLYJM>MaU2h+< zOPxbjkTGnP#Y47!O}@RjYl*E}Tk6K5%xuhEuL!K~h7&H`4xdi9p-ILf%Ds76)ZTqN z4ncU1)h?;EN>mDiwx3)a} zkh*#ErZa!5;XU-h`vFmSF%C3}i}|3zSmob?_nUXm%(d{Cp=bDbKiDZg)NMJ3Fp?iKCK_ z^6xdG+S+@ZN#5`Kv|Z3wXeudck>Y-0Ynw>aV0M!-MS|rs|SqQTs3MhZ5;t* z%!Lzek<~BdW#?W7g^ljEZ({G4eo%mGop0cb1R>Y#IdcO+FOlL>@g ziVDI0{2=br@o5A+8uP*oI%%+|aB1jW<6oNdm(BlD(moq(gM7_z{e`LdSOB8DWS-xx zuWMfd-?sFEQrqczNUwSRe&5dg)*oNkKI0N#3~+5h{hxoT|A!$f*FBDml<`H}5dxzW zG^C85yKbY0&sp!q^VZRP$;OAe9Y<6_RrMSY6;5bGWdcOWtfsqj)^RhPI@M=;_g}Sx zXK&-72iER5q~vfEtz2AWFYivb*Izfj#HV4RmS)*mOm^i#4bu|}!IOzvsU`za8cHdX zTmA4;L3vCb7Ikal?qJJK2rw#6oScr^6o5tx-u&9&7rJm|(9U1&vFo?`thILluYWNs z$tt%>7{=GHE3q{jiXk9Rvsz-!VobS~ppgT1f?^MHl{;^if2?=AyWzqj-oPaB8nL-$ z+FClM?G|Q2{b(|Y&qaYET3vn&k9u({hZwya)3v4bX|{YhW^)aYoYw)AlnERn&u~}? za#4(8VirX;NyibdTSRLyDnSHLl}b#|M(-VtPmGQO(2Us7&IQ5awl9ysLGu5z z_nvQh9M{?BnVfUP%m6dUIWgw|5~QF&QD zjM~y#%%bisu=^f`)P6Z&V=??cfIOq4V>Uqb4$ZYQXUDC1aMb#y z&>De{tDb^bl%Hu0wWWj-TedF6mSTEUx7Z+=$AA=5!zuAbF29Sse%$6D)zpRBzP6SUzj>lp5&Ec2`$=Lz&8&JooI2;7O5 zN9xRoJ+gYx?znRZlcOpo*j1K`Y3DTNNa?f(X$vLr0NL3J;r*Fmd+~*1_J@~_TjwZR zcH=X)ZPPM)cKdp~h?QFd9_C6G2^1DTlnB1l(dv`g6`4`J)r5fdh;jjN zLy(DAdj6;_$Qzvl0E$F%LN+lMQ`8Q0GqsI&J{T(n=m%Qf0^5oTIz(2%@$Yo*Li0%;E@ZFXSk5r=!UC+ zsBqaM;GX2)oa^r!u%7N-2cmxc>tEtLVIO9ggH8x8uBbo#(?5lmuEx2dR5sx|c++DT zrP&i6rC+IBa3fvvLfP8fYDeHpeDTE>F=gE23%V0%?S1#V-?hK|%fIxrI7gHgc&-IR z@q(L9-@L?l{^E10drErXh-xNn&1h{6508?r3Ap`o?GGwH6@i!L5V#0H%2l-dhdN723<%6g3@R1hP^=b>gFLp==dTe4L!0j~e~w{rL}D z=Ck>t2qdp)!7b{0ZUu-^JRuEXKO6Taco51syff@S!B>81qxSNr4)}M6_J13Q`ecjx z^9Mw!=hT071PalQtEHd`K?v9Ayu`eJ_q+7v;H^sTIY#l*52F*z|m)U zxrJ7U=1|R!XRPKc->`I6(bEX&nAM~+(3N+ya}b3eInrmlcAd9(_qSLx8Z%>KIgpZ9 z+RDWhOlZ>W$tPxP#j-Taw=yjov#+!inZPmFRez`uW~@Qv>gRmc?^A}^G4cFv(I4m5 zP^*1H$Vus}D68F=ZuJn(oP|FFk9w!i_1hUt%$hrgZFpqN+ev**g)JtXweUyP!tu0Z zX|~m`6z5Zhm1Aa?mxs0(leq+d)Q~i;j?=`{G(F70$hf!N^I_~6CY=Ft_ zCU;z9_xmk@Wuk}P<#GMGf6eFYFwSe&qek}1nC$R=b_J_3Odh9;!U z@EnWt??cF=%1)C6hj4s93_*E+|A-9&M#;T+8r)p9byWZo5fCMkW_hcVmX#)o{v9KF z6@8@P!CplH2sM);;&SdF4dRPRh4{R`cfy*R2JP7KQG0#Qr0qGFunxGWx(Ct10IaLR zGu?)DMRo_;B$Ls_sBF)Ae1J|0-^fRjQU&wQ3#D{=0WoFa-A8VZ4S~0c`4R5*pG+2KC8k^Y-wd7+EiKAk7-^H zKvWx(>#6Bsdu(}+ZQX*I-NTFRAwnMg%rqu|GGCQfvvE9qw!$-Z_VlpreBp?_^zu>b z5x7h>d2;h|d-mxVh*}Lu48NPWtfpv>>9if0mMRl70!k@(?}wBj)d~ksITz{!zvCvV z4D(#Lp!?b4N}oalRETb(%|%f~@e!}brw)#7nmh=Q(!Jh(IV~Wnr@IfL>PyZSw0Ox9 z`l~AIAdl@Ar|kEyUbNr7-sBo(0~1-cxS+^3Ei1P>wiMcf+cIq9ooVpv8G!MO?S3U; zyD5WHO_!~)?VRQ3^x<)D5|F;g?!IS(ZQQh+c9McNr&6P|sTKHPlzbg4tx=-&E8gOJ zmGtCI*;?S7@+LrKY;4R995`q%yzm0x&)f8|=K))W?5jJzYCFEN!`7`^XX`ht=UXE1 zpDhwobgZAT+-6TC9n7{*-amUBUw7GZOsf6N@bEA)hA{v5ar^CWe~ZcB8?-Un8$lq{ z_x|#Gcw((bi?-06J=_uyH80Iq$Rk`M8OeF^^djTQNwjdO+byjv*4ox=6Ye?EAgs@| zpZ~Vl_FmFLL1daIAgVAYgFbP{dPawAUFC?~vvJgcs7D^EVsWI9cc>ncZ#u!qG!F^r zqwrC;kdJtuoR^Op^%vp!`St6T)2#BR|8Ti+tTFzF1)}uskDQ*H$Ut%#hxdj3O+0@4 zmU$A8JQZ#Qh*A`KM#?V=;*%42{^px++K+zpBkP6>_WM8hfj#%F=PV0af=t2{{f|cw zCnU7t_~(~>_qhS0ydlx({bQt#Ao(k|P@!;-Horfq!}ZGJg9pFp_jqB?k0XBGU!!Y! zx1I~%=p))#=Mr2!@{~p$Dqn21&wSNGMlR+|gcJY;OUZznB*j|MGB}0TrrmI^?8CgK z5uT#X{)Cm3*VxjUT6^MtvmH-P*ou`IfGzp1osiCeO27!6Ry0v#7u%jh2~zi`aj=ht z<7q+Y55qoAx*qk7gD8Le^8OPjWDEdFJTh$wOjyS4?70a$erDWGHFnvV#^ZL8d=_R` zSwT*fl^5n(MRA@jU5>}7^(Az$B(V2}pvc zS*bEi0;la_3-9WJS88ks%`0hsK$XRx8c5Bn%kr(J9B+MP84w~*L#91Q032Cd3NTX2 zJWeGe^Rh@YDg_`XJuQK(luK#tC}en$RHPBrKag;easg4J!#$Y7%>YDI&uTw^s2*P1xS|M(q6q7xB(? z5e2Y9c()2|btT+7OG|CbmK?k90Z5M5VBQEPRu1NeGia;KU^8JL$^a5~k-0~(5SJmhPk}Ih6fj{Ft(FUC@pgC=%_s=X zn@H;=%BBTk>K4GmEMAmB#%c=sth}VxmY^L{zqr~~t;x6b8_|M811#Twjwzc5i)~ZC%@D+n!u$PdvGb`bVD!s46)LOd3H+?qU+0#HkBP#Gi*QF@fMkh-}ux<^mk za8p#8a1*ALUx1O5r%vNRZx8|sF}vw`eR_o_RC-X(su6LiC4l74}bohKexa5&R^K_ z70Vs`6(|-!gW0%eBVOnrlAmAU(37D*o`!J$!ue3U7pGnu=JTx`&HnAoNY6ogEZhG5 zf3j`gc}z+9M(5H_0ua>$nADsBA*6zYP0Ohi)}5VT>Q@kbVnH2tY({PcOi16aCqU6XnZHH6QPo8e4h$ z(Lz?z7UD@d^{F0ySUG&EiToVDEVP+W{x_o$6|$pxqrO7c5&?+%*MI$22crJ^um3s% zqO!6U<^T+BIP62DU-JFu2Z++Ah!3LFvV|m$uxz9-%F3I9cMNpe@}MGn>MROUWVJcD zxxN>PVrYE&sOkSGvle~OMi>n#E`dT?ZPRxr58eX>?@aRY-TQ{G#1j94+x&{5SIqnP zhR!GK70+!T>Pl%!W}k;Gxr}aI8>v?CNb-ehhbsj%qZ5{14foWAiHeThbY5}3XW_92A znuAaoxquZ?A3-|>iwWz2O!(}XF?)Lt<`nPs*$D{CFLexBSp^(SH8u9weJS?TlL-j4 zGvL?Ar;ijFcLa>Mwt(8}wXrCFAV=1*2` z3fw{jG^CUU_5Xdnc-Vs=y|W#y9LyA3A<({Xal)D|PgrX^-o83VFn%YlSd% zjKCi*@E(=dAfUkM)03EDj@ny$nrzp*m#lLr&j!a;riIo}Tx1(prrSODOxyZRsaC%v z8=k5RCN_X^=|jYk0T30;4D}ZMi;B^|lb$k8_@>E_g03@=Vr)GD=rk3yjyRu*=2s^9 zni4n&P}SK2sr5wwGxn{N$3=Lg&NfmWmmsT$Kcy87sY2^!Lf#E$PKhm|ey&)NZ5uWw zY}twwCX=}g>=~40$(#_gDZcHg^8Dx%=?Dmr%ylM>`s&yq$FrMcdMleEx`{2cbKM&1 zbU6OZfhbRi{w%ynB!XzQtOpg zkgq;3s$XiWLxY%eHcmQd{`#v&?X@?Kp%F#9#fN`fT3hT_(SK zdjX;@w_$b&5LH`6pHjv#8Z&^i?;q;4_YQQyYcyu>qQ%%dl5UmRIksj=jy>^orakaz zHX5M0R#TM=58R|3L!0o>(PlezbvttS5Sput0qvLAjvYH} z$5(e)MR^62s7%+o3~j^P%k{(`C5_VJAU?jL>+uXlc~bk5Y|oxOYrp>W^A1EcU1~xL ztqC&sKeIpkvp;hp^(FO7d<=g}K-6p+qeQs)bjbPHOG!s_Y1Q0BnzK{%bIlG$Wx&H% z0LlE`y;=4z|DW0JQ}kDqlfE})Xa-6ns(%nt^O0U#Q#NAjR*eBf0Z4AIvo&kch?){N z7=6D3QSx@GZ`@4)hzphIT;k`h#^+Qv$^F^f4PU;aP#?qoW^*`SK0#&yi0JL^P1h=2*ck<}DXygWq8EI*|9<8`ly?Ap2-IlA4e} zX|@*Zu-n?&Sy^vqb(|GiLK-Wk@-QU#tu?ItD=cCauL6^l$aE!IMN_=3t*v~#E<&_= z+2iU)-FJL~C3W7l1eNN=d|a0{G}zLm4e(ZEGXRcUZeO#=L*-!agLv(Ib}{$F{KhXJ zN-EEeodEtGxnuhS)?foYsfl#jVV-M{woDcUoM8UxQhCmec zL?0#HH>E)*162i0);MjQZ@ptJFYL6|qbC{M(m&B(l$YjO6`CWpJO0G#Fwe_?G2i_I5Q1ta!G|fcu%@L^5~4MTn_h2F)pR^ zFw}c+ zZXp&Dt)pwq8qf6Lj=K;3qfz_d7~a~Z1_=X@j_2@EFR+Fh_@mZT!EIG&RZCKkLyA>n zvQtHnri`?@CKIfh6Ym%rQlsp9(MD)%2lPN2=fYXIiy9NwgGNp-li*%FTlMtA<-r6Z zHEjk>EHsxYrmS|6OzFz4rml?mhiy^S5QEEXD=N-+Q^q_O z2Z-wFopc~-1TGx`QFUlURa8bmRM3b@=l)rlg~)>7BuoF2%z;zjXB17Wfq@`#(gYFw zjCI11_3plYCO!Rd`Y_>bQe;`qL$eG{tW^!eXp*JCw^M>?Pl4qYCM>rAEjnpi&1yb* zVe%Yh>Hh>!B~A8?#T^NnMduu*F=MT_c;>&mNI!-lI#b5FkomVN|~i&yq8C{?sI%#fEIx z8%Oa3dCa;Y=k5k**tTUArg>Yavz4|S4~wPM(il}gNe%!%XS|L@nN5}HCfb8C(F?Il zw@?2*+?HGiR7vz(l4EnNJ8D@N+X;w58_5?FxTR0y)8;nk3{smHFWi)K+DSWe6#lef z+wz5LREooySz9DBkRVPf|%+A#OyHErYCay&|wIY{5zGh=)AU$8g!oU&7AW%9a+ z_m|qTid4=3jc%Ab z&r!&yo*w{MZ)@wY!-o&sZ=Qc1)9*Lp9%{zE{oJ?h+u#1S15+g>#ja&5(_f__0=2J* zcEKMZg}SKs3Pkd@MK=5z>C<^>mrDcX#Xr0VVEP(B{Bb+MBF5Lh_H`#u-@F+Ptu?FZ zuZuhm6<^55f-k<}WSk1#72fHWC8Gu8qidwd7a9dbwJGqHR zG-f-G0+b5)r(DY6hblpnFaS}jAg*7ts^1=f|7-j9scKu1R%;y^DZ>uOl8>00iFdy zETjWZd)1|5`wlKq+nBZNzO*<9$7!Y?^n=K$IfAMw`~9 zFWdH+0#Pa~-}FJC@duS$dCfR=>J%&fXPp#KfRume7=$=i0DW~~0Uv?NDgdQ=TZ`@b z@)axb*plljB+{T7L$l!Y>C^D29JLDfeS9*y3;8U}fcW zEO_O}$cR>i7cA&dG1!N+hkdwze&Y`sQF23j8;FXeG+$;xcAw^6AsKSLgqQX1EyTd-5zrFu#Brsd13%owLjKY2Dk5u+I1frO@ zNS!~y>Zi0lQ((hZ;E;hR=4)@hZI^%dB0$tB>QSGK;Uc<}Nnbf&($c4&wTA7_I!ASC zo;Zi#`(dCu0jM*CR?r1ZUf$Y=R>Oe_I|woO*~^$fm15#nTV(g&lWC7U0#Wx0xO&Rq ziOT0$K9@dm6A-1oEbhlN821k;e{@ko+z| zqY3YN#l_-0iqfl?`Q)>>Fbyy?h4;ECYdQ^w)EPX_^)s0Uz-hw+-{s2#{2sAhP@M!5 zxuVQeR;$yIOA#7mMVP`25eE650+1@QjlLPyZEY4g*6>k{n9^e0$^m8 zcnpB&`0<3j_0G7x@!puV0)~yii&c_30T<1vtz4RB58V$R4PaF5Vu-=(c^1yBRIbk$ z0q&N31Nf9b)WhyK`$jF5;^pss|t> zO~mmcd{?~_fXX3nA$W56gP=lt}Tw0UC4Xb#G|r z^WzNXwO9C}0#TF>8O|XO*|z_Evt6&vpiPMe&rwYCAS>Ur46gD~E*nfkpPfgEatAXv#=VUM~cg14Q9P z^TgpHd+p65_UfJ^)Prdo0BG2@b*25u_RV(3UG#Np(gC7miW>n@PGk?Eeb`dsdgtRm zPVxq7UDTsR_o!yX1s@)|rM;e2%hN{vS52c*cwLA(KVLYQqD@2^QLRigCIFw&hysX; zG^SE*5VOU>p(%U&^#R-YyIwnRvePc~v;#DZ*W=_yr{FKXM6x zuF(!2NVSuVb=E#yVwG7lhSjir^=oPN)n@_e&>AeI3hw`JaAtt~Bpm%D8D?zilHDy+gI4?kj$KJq9Up!Wb^-bsI35fwXm zoZoKeMR&!|WH}`tUvZOu#PU*KJQZ_9iKx7}x!Fp}O0BkjvF+QNZh!yxgZ76*a`qs3 zWLOm%Q6>2q)+f`v;eK0N+H31p_c#&#_9s@^8o+l4qTuwC$$ey+M}59oAS#q;*k6_K zIeFZQTo#Dt3wKK8dEGKi%2AL_*oRBux9X+Bl|WQ^5)j4rl6tHVw(xH4Lp-wBi;5qQbM0M%0A8K_8~Me^*zR$u#e#G@>NP zxhnN#5$iSc@tFZpS2R#Mdo>z?L_(a~THBnc@C-oI5N@({E*HYg+`L@O^hQ{tU??k4t{(h3!W{T1m?dLWz+oxtZ2hze;;O72 z+1cqDcluo{Ac_H+fGE}1`5&q9zVQCA59e?1KN|^nSyFysOD>n>cB2vXyPcTkon(U3Ys2zJ#bhq0s@yg{^^9%Y{)|l( zqX#G_*|$ z@gkSbAXmQgq7NK75EuqvqDj8@i)7xpLew7%03f(_1L@RUOpm%O)Q2i)^S&_Z50xiP z%&YPntVZOm3xph2H?{!d!0{;6_?lT^$pU zz)xTv2q4wkXKmf1);)v^_VH9qATjTT$E&Jf(#i=%1v1qJm|C36WGl-W>eCG^e84Xt z8$7*bp(TZ=2r~dtqm&om3S_inqr-3=rCN2(A{I2zjsO^&MjOoek2vqLb73X@K_ z_kC%07aGy1dwcHiXvit{iE732vgZg zD}^}x8Lq$|H3g3p(_)`c$~>tL@Sz8-n)4UXPJ>wf!ubib_aI;I9JiK!zVYyQrA_vt z9hHIxTrFi=W;KgP0i#9%9E*{AF>c~9DaGqyMn)tc{grl^D}Z=?BE_UH5dLzR6Wrwh zh$N;QEwn{f0uZJ0l*|>9+j;Vn;k@<=0f>?|l(e@$b+U3LE)q*}GG~ufnju6d>3cBE zlX+fRYL15kAEeluy9^+z+ul3agxA9fTVB~cqf`}hqzR>Ztd1!vm#A-ExYU)F>u>X) z<1MNbZ2m^dU2{#fi*CHjU52cDoW;%>+(1eTGA#oDj*x)cP5f?04~^RU?~d5M{TFR7 zDvZr&!q=9RTm7O+d-%S3d+>oJkoc$B;w5SHO9OW7bg#XKcg(kT=i8As7AgQJO0pC7 zwTBXD&?L|hEwSY*ODqHPRdf(NRdQY;}n1iJg~yRE9a3ZPj1o66uOxA0EMQhj&~ zL#mos*_N^5`Qt<9Ncgvs6#?jGm3^z>U)q z-ZB5q1<$K0@K4|RL;?;xCZq}_^!0U^2fhms_5T1wz3f0#2K`{V)$pw-DM*8BZNysn z5N)a$u+19>?Ed@m?XidJaV}9zj5H*iRme0?BdDS9yvSNb|d5yhsR$@={kjjEmo&r5}|Am->rcXqEo(hd*SVcnd((4chgm zFOg67jh{;(N~U=7m~rmhc?wrR+^xtm$SXYK1E_csq+=o7EiJ7sy5i!P zto#N*lx|jhA8Ok^8LmETbguTw|9>0%%>Bc~mhOG_QJCiSLd@FV-vbaeW+Rv$r$K;w_fucDySIPc#sOs}@a~q*gpf-%F$_;qSBf<@ zPTQ`xC+zL_A-si?r@0%n0uo%^^voS;_RQ0%fb3~b{4Gr)2clwBMBVB%6Q&swBhW~b zeD!Er@mD%i0RULsjd*$Z?T=r9sRBJMGN5 zK|9@)VkjzjUX@t^XE>pQj5!z4<=d*7T)S&?maSh4xPzy?np!5wczG*Avn(CnC z`xMog6H|8j*c9IMTI~04p0~4@?E#lr0R-kX^gGMya_#A-((S1o(jY^#tBA=_`Y;$x zKSI*In!qZiXy~jGS4f*F;H=13F+-xBP6|lGbVM9hU=WlYk8q#7jzzUtpg{)Oe)6J~ z4#Bhtm1V*hnPv9kRj&ulnzJV`*CU+1&~K+N^}yjZ=o7RAz+_=oDJCrWR$Db_RcNMd zTwh73LZd5-Z*e+W$^al_JROsKPlGCJyv>k42crC2EWvRNb1v7W(P6mpioNb550rTT zqvVxMQCzD(4(&f&7ZBwj6hKrUET8W+Pkn?Y*WuYKlJHS~%!y#ZnACnl&kF*11}}z7`MW3mDB3%`3Hm@>R1q3BGNY%q^C%|uU>qMaB z!lk~Tplz%2zALNM%<9qK;+Y7&*wmm0s#Gus%8?mR> z4%vfu582&!)iOp!zD4u{nWOY6Dq#Q^2cgiEg2OKA3ugs}q)2ouj@f!RcX{?2;)_5b z8m=yz`ZwCz z?6=t?y78Y`ncU!3edm>4nM5W7QKc~u_0HZ5`@aFAUYpg3!Vv?UhGm6l%l84k58;s# z^Y1&i4BCD7=3$~)3$R!~dZnqF0O-g<=F)bP^dmWV&#a&GH_1`O>U~~xF&xj&PdGn6 ziZA=``Et0K{LYt^ek%kZN@V31o5T@?HZNndk`h_aV1dKJpFgX5%NE|99A7vW-EsTx z7eNBa<*zy*tCx0y`ld|AdLpSWiGe7!N8dtwjoYWj2?C>J4fRj|^v|xaa6^r#5LeiL z5rp+Ir13KYqGr<`3XlCH=;1hgO44-Fhp>mnuK|fnQiME8D@uGz(quY%^a!@&uX_dA zuwgysbsO!@JMSXgX)nM0vh95NC10(SUH>8gsP&lN)z#Jc;3k3Q)xm>@7>pg_!xFhz zeCXka>>JN~!&QzwZEH zS#=-9{dbmK><19gfSy75lbaIu%vT^F-i%pWLq3Bi$jTYyN)IM%ygmkrnApXql~#QN zl{Wz>IvobZeoJ^f?78k^V)d8&BWrp+bzA4938wrD{1E&mt%e9F7#&8lVkq6Zx<{<5 za~SV>m>OP4L5s!=E^})^^Ji>w3?Kx}092ui>H9aWAFz#E2W-VExTKb9Fqq?-NHTw$ zL1RKI`BSLmOk&=syg48;4v06F&9?y4y>4mSjzc<%`Q9Zs1UvA$N9YDnXdh&vo&o@t zmT!ymvTSL2y46)>q3w{*%72bEG(ZGSsH&c^$|?a}IMl$LX_U$OIFs@;P?CxYR>_L; zY!VPk0WMn)Gk_j0Q5 zVU?9|I4XXju177!Jkjesb{ofNq)=_esN ztGq==0f^E>S^Q8}Xhg+*z7miOM1?*edgDj<8zteo5vUGDkWIJ^vhtY$%4LA=As0Y1 z*Nze!AEmveG7{V*O&32TBXdBML=csR+7e|RmrIn}Yn6O- z^``#DlhAOl`ZwZ4cf%fi^#!fOsU#E6N8bPqWu{PEsDDcDfZWT@YQbD8j>M z)qp+u=rVg^+cGqOD2s||fG@S!SQ6sWQs8H(qap2K@8@;9Htmzer2OgMY`$lx(*rC7 zpR*Gz*uJ#$B_|Az#^Aa3)b^+B+u!;&nn`P!h+}DhX6ZGz_&u}rU%%t`tH1U|3hIg$ zDYW^0$_E86Ylx-`7wp7|llI%+{)X^7|EB7F-}w4B>@WV}&q>32Kc_juT>3q#5A`Rx z5137JEI0MVO1>P^G!sftmkk%ltk`2~dSxV4F>E(zS)oC0+i~9VVCG zt!6G+Rv{iA2T=w+y@1bXL2BWtqy&yA#&~(IL4CDpUU+YaBmBO-|KdnM^EPcNe`&-8 zAWG+jNobCzF@8RlR@d6ZCnvfV&HexJAOF!hIy!D_niraO*k3F1FWLFe28fC~c9&(+ zu?l$#Flv&eY^lNOw@>bv;Hfg`W8)t&9+b-N&;RG=48o5w5GdmVU1yI!{``%xD&j}Ef zE_F)5tSWRU+AH|A_+yaVd3k=4{^(w5LL@hJ1Oc9eR#d}e&|U5$Q}$b z44qVWSGR)^BHNcI$GrSJH_sE9p(ZU_^$T?;SyZ8H!@2pt!};6$PhJ9{Ot1GQl~3}0 zDt|dqxE>JYb7h8?x>uc7g1V4kA}8W;&q8B~AAnUtqkO?5G*DtOKN z$_`unm9JPjfJQo8BJw6RLEqTR>UlfnXN{-EY~Q<`aElDth0ZcNKZ0$GHa=qauO7rB zRj=KBcNS&=$iSs&xbJuQpgQ?`7rNrG_q&pBh#tH8?-dWkmy^y3?3kVz;e7(5 z=)(!A@YG=JM%#!qlX~$2*ok+&!-pqr_nrwmaD2ipbVHVmc~IC^m0V<@;3AW^8hiY) zHF&%$Wr0Fo?%)@c_6{@P^t3^|g2A30Z|Qgl%SQ;$U8tVL z>DOdU-$G5!)AO{qD=^oZnUhuOOflLl$jZxzBmp!`BTMbINz-To?We>fpeBH# zJe$p*_-d*)P2JW$q<3VTm6o4b>F?2> z>oSp>!qp;WeXT9>z7_#d(LHL@if}g4 zxkot_&yOVx0>3F6_32Jl9s^NVkd*^O>ALO}5EV2v<|6&*M*=plx2dM79z{Tf?$n@K z{7^&GygUyl&`^8t{Yku|bpm``u;a}*4oI(~=&LXZ%dqMsk6-zjcyh}xVI?>M946?) z9EgH{>`}C#?zyAe?zp1{4WC-)k&+_;@uP|Ge`vq}p(f#^>bKW+zim6;eaBWVy4P0J z-3t&^h_}6TTecECykg9b;eBNUNd2LI1n`=sJ&FQJAZP?0B3B7kKlvwEU2W-O-8Amg z*iIqd0{;cv+xI#(_EE`R*tlYVJClD=_`q+dP;J*FMfPQ`U z#@oo^0+FOc{zQ0gQ=dKgSf6deG;!@FadTzb+q)BxUk}*+gKf6|QU`4xM2qm;wzc-{ zZ>)n#BF~ntKvPg!p$>4*rPJ$ZNOaQP+o~H?&Z*0rvExt%Ct|~p79B0z2KEh!Xr=+a; zM=I~Rgl5b|Oc%uwRaak6UzP?()PTJpAPRFynM?*Cs+Gm`_5lFJl78E?s?Q#JpwzZM zxt7I&GR((^-FZ?ToOrn`HVM#Ika?bi*i?KUHz1F&=^GI@fpBVeKR@sDf6w0dB|ivt z>1MKdEg4DfDg)mTzcivQU%Kqx*WKy?`i+Ii%ELQvB@N-3k9+@lNW;gSr%xk3)d^t_ z8eMpsPXeMe7SkrvysAnxT-h(!9;q_{KaiucfB1)gaOIlY8c_?E;AaCwkroy5)tf3n zR0+HyP$AM7i3Bo3bqpd5RAtz^cdz~A$3MZO<0Rg9mZ74%iowtw9t1)utXQ$ao_gvj zI0!b|(xnZkP?!5FWlA9;^v1J|?pkrzu3fC=-R-Kr;*3&9lbxOIrX@l(^#RwnKr07SxD?3BAP$OM`k}-l&>}~D?V5v*B57i0Mz{aSR<;q5VSm+lq>{9 zh58ZpQH+Xo_UQJ(rzwFOwTnT4sSL94S;`sG)js`otKI%JOU;BF8n0~3&CuFWeS>%9+zg(mh5^%C?a(o} zj|LW5M`BSVG2XYeq2HcT( zQ6P!tIB|YmbCn6f2pSXW+gu(zl81>^Zf>5h@M@J;CLZb%1wc*D02DY7r56am(106$ zA(6NP<_!&`!6%aevA9{|`AIzML2wMo@#zcW);@$O*XRIl&_}GY2vY9lOx#x2z_EhE z3e2}kE7PpFbjAvbrz|&n$U~eP0Iw|iY=IMzx!L#_9`Ab7ne?SG$->(np{c2#)y_U^ z?c!a4U)=zG{X?mE^UJWjOh9G61xv~yCaxkZ$@frLG);aJ@Ks^12j5K*o(UTuRIgqH z7{XXZgypH}XpN+URJk~#d;=vhe~i8%ejygMr&o20-_crJl!Ite9%*~I_c+xf-ACx| zk}L5kJ8=X+0r2kd(Gfcf;eG2+Ke8IMio!wLx*mXFV=bBk1@Nonp?v|z7UqJf83LmE zD3@d)s>o6WMET0R(gL8Ard9rE@TD3v6>~xf00>$P+!@5po&lU|z)@$(vcmMFxP?;T z>;eeHn_+Xyw4FN(sX1nnmo8jHyPyND(mdt(^N12CWABw<;3q!WIflvJ6SsgJl?BTCuz@fd$q2fb|g`_VQ@EZ!(L@6Xi0;*Bob$EB{3 z3J^7jsg<-iCjeMW;o~bR1egW8mg)2~bzgy=7E|aPfE4)qPQvB({)oM{%j`Ae4z^5$ zc+p#iCfOam08y2;X;T9rae?)q?RfT7KSc74XggkpEPl!cMknpAHOuV&t;^7;$+rjY z&$8-TU^w0>pw8P|XoH??$s+`gICMG1bx}{uZgDolcw03`S=aALz^HDxaejx!?(g7> zI)AQ_Hhb2=pY2a<2PD4NHg4YNmIjJ%{#Zu8BU#SA?WzM^pZ{FANnn_?qC^rbAna%V z^D`DVN&!|FW%Hwz~GY#_Nj9-xngd&OQ} z`~=QA5Jj2G99JIOrR1OmX9dj#HO3Fy{CX75f13NN(r}~t@@XdS^ZqV1vA8b@*n{YT z6!h&^`;DVNW=>9nw8fH;RkZK5OG9x-ke5M+;%_jV){7K_n81up^%jk z4bWyg*-(-phjE9i>t4c~cMT&}YWBRf$NuZT{tKRzMg~AzP3~NmFJJCKAk@GA`@iEV z_kR2CcfadEl+0xU!@Yp4p6(tGzy9^F?N`74mD|5RvF!;41e>gWX}xze6MP5-F7P>E z(9N)j)sS?Nk*K0l@sji59}9gjm?$WOO*Z8+&l4*8PyhH&Odh)I@BZ%ZVjwDtWA?+N z=Ly=v-m@N`3vqs={U2c^|48zRA68jw(|&##tAmodwtLMh#0-W3N?{RR^Dt*n$2A{_ z3S}Giig)%nR2}Vamz6~G>1@}Nbtn^3az&dLFhgH*EsZDvQL|-89Qr^xVL5eZjDBT2 z5dl%{0-}xvji_mWs2p3gw9;yxe3tMGW7`Qp9RLkLB#|Mtwxrn6!_#)?@SuGF(eRPe z^kw5qY;2}Jk`;MbQ{86|-_?m%G6=pmR@%~rVn9+>UYTHOqNx5Wn(FZgVcOL;klEJcB<6FIIRxMf$lANnF6(K9 zK>cjD9XZ)yr_YRABbp1%Lz)N!9RYUaqznMNda5i)w8Z+QJXrUt!xGFUQmkjm^R|$kzb? zQ!q!I5kL`bsnY_Yig=gElG$Vm8bW-J54SiS<;80VSLO!cIz~T@AOKFs0?{y0wQL`( zX@WZfhgYQ4H)@v~yX?a0K0908Qfq0KMrW^GsBbT!wI$}fsjPss6rla$9q8cB#$aZzIXJ6xD;E(ny8EOoFBOuBs2YJpr=|B`(QTrkw>Qu|P zjc3%^bVilcpfy*XiwWq+w6%_6ZqB%;6w@JPt9N43`sus8LISjIha>9l&Ak8u)$}#h zEWR*V2O!LZq(3Vw-3IznA|Pu2oJQ2TCHLCeW%t?EO@%BRsw^h}q6RIyU<&@Dd;peQ z*QOIE)m-tYE@@Fvt%tJrHpCC#RMsC>&>Dj!)n6K*f9ur{<4uR+wG;3;Lwy@X+i?Id zol{dOR*V^JK72ri`Kkch$>~w=)6!D%;M6K&0-I_VE{)sagOm2k%Xlh0Fln7*y=Vyb z+N!E8V!#9rRnXs0`~?NT4@prqE8metsf#|!Ma zZ{{*yO~*Wsz6n!X0mj}@dwL@YNlJ5@pG zyK#{49(~L{Gy$q?-I{ffmp^Dvf8{A0NUV?IPik;#FSBEsd9S?I`EXnK#_IjrFuJ`!LTNvFxmTxNF53MO)=h@_az)QQD$&M9#67qW<_nNO8QMtG099q9VS%T~`9$ z=DB13*gmui(ZmQ4l{TL0o4_bJBMJ_Q0uZIL(iZmq<1_kmRT@H_`82CT^1BwQub+`@ zuKQZj9O{GGnCgU+m7|@h@r$?%VgA1xCksFN z(T`jS<+>VCL00iTq~WS^yl&#Zm=`~FASwtqc`rc+VGCVU;j81-1V?61UEN*L9uPxdi1E@bKiaUvr4nsJB1whMD)S>@BjX9d-Tyq?fc*VzJpXkE;F+t)oI16 zRm{PGL09?x+0TE5w;nv1@L`qq)auo%eT7piG7dy}=g(AvNuanuv}qzYfo9b(S^<5% ztU|Z8IvJTJrgGJ;)nesAzXfQ?gz(i@Uh!wY|JUEQXPbI&{0 z`iGs?bE?UD`!$(?hp48&7By5^-TjZ*VnYA)i1kg4SQ_Rs+3**&x94C^4B_yh5j%(` z)!}m;7$&V^QoeFFZM8-1cE|F|Xu+h|nsoqCOypU_Gg(p49eGGk#gt8x7!oCn!$AhV zrUJ}nH-H*Vtkcx@Wu`e{tNOi;j&@eZ8__6gbq}P{RIOfAUu9`FyA$M+QJk zP1Pg^Knn9YX$;ITvD4&k5)GKiDR`YGFln0*U;$vmM5qt#sAGq+?ZmMZJ9nYk8k?G} zZ?w=l#|scqy5#_jLEmI`m~bsdQ>JclrhA~OtsS+Rx-sXDk|#TXA~OJ8VWOsI)6)f# zp(Pb>LrfNjd*G+KJZNVx^r0Pq#0uyTgU=B(zeFUT$%G+;P?ncq#e3As zin0i$@DS$Nsmj!PPRaPJZ4>JZdBzLTNU8=Ry3mS zy^}PqDzKU*g+`JAHL;UR@8y6pRv#s@@~M2vhn0DqQ=jFl@}!FE`c_Q=Qi&rf%(3#2=)ULqeKjq8*?iqHn3REF1vD>}q&$(%LWgTkFLUJ9VC#PAz7u>Fq{wwY!a*v;rswGoXL!<%kj(|Lw z*ub4RlMOhMZ3hqa*?}V$>}=bZ4W}-)>GVppIZ~_w_I@bUtOYH$Eb<}FD5Z4}4m)W? z`A9o$(zf9>@7}GwjIpX5jLJjs_G zo@dp+x!-znc3bcsYK6;Rd)*lcE;<)Iss39l-s&W&3iN@P<6?fOHk}XPkdv*k+Zchd zsepAtRu&6U*=W5CXIe}9BpQGKt@|?V&{0F{vdfzLx&T>Q0kT?b&6-7kQLAjtYCPjL zh+}Km-hJylCVH)Q_*9PVZ&sP*Lv)^R+qUM|SGMOeM$N(0mWeRtjJRZ=-cVSfzRHRK z*+r&a(Rei#kW8TPwKktLF@8~fmF9n_hnjewI(-&!{;ciB&EoDi-=GfRX_Q3=X+(YF znXj{WyZNeU!}DI(C3lrdybm{rd&2LqkJ!d765+#d%!?3`Ea)A%>`~vA;4cAzjJo332&8>J6i+fd~bRDP%F9$VW3`|Nb2N z_aA53TW6^B+87rs%FDp>YbHR{u(b~lS#5T^EnU=X_uXA=Uwe83GMjjAHGF$bOA>7H98EJuiht#L3s#UavsCE+c9$06UdKolbL zvZudM`xiHq#`&5P3V_rYPjxdhn>i(A7M_=!qO$U%+4G@}sS<_a2xSqTo&P(;rTw+; zxn8`<oFP5Zg(5TCrgyGjDFjJ!S|WO+@L@`|<$K5n^`e-R1?ssjR|GFKs#{_>Y5d-84Dw%HGU z@B_b=jaL&932PI2tx6%!M?d@7&pgPZ-aYr+V_UXt@fDuxMb%E8uJq`GC}2q-l&k8g z^;2225-Jk2GiT1&+i$;Z2M!+aN!jr5Faz~Da7mq4|3JT!m1(g0o$q`HJ9|io$%h81 z8JU?rft_HoqmQn@D9L2D0;+a@TpQ^Qacdva5LR6DTS1#lL9|8pB()Addvkwo6t7;T zbm(0g?CD(+Z^*k30C`nNbCeb)bCgL)|3c~gxZ{o973W#$<4|c(7^j{}Wmg@K?vpv` zENDsoqC7>iyrI-?^0phsbNhx{lR#V#=hrijB)LrDX5ja!eNfTFr6GV^V6s9+3`pr& zO}^E}RR{D>15DL*j#R0w^PL0M^3q#2*wn(kOxJTD$gV51>V|5oU%$~BHf*$WBmH&` z)3i(mw#B7+0Q04A8&%RDPGXLA42_{yTzPDWLY(W|%qCl1cG{LMnWm4F*-)-kV_sHL zJZU3i@Z^o+(JdXoCLIqdSyKnV9ON08AvNhJB(oonWCMAun87O%gAl zOhF>RD~HKlB2mD~b2%a3TASOg^>POwQNA5)&&Q+@Bn?x))D%`H$pf6_c-PCf%F=9G zy*^KJ=Cv*_z)>jgp$_0Dfp!s2>1cgUg!{5}{TGW{J!5eUEqjUY|b z#}kE2YN{}!Nr$_n4Z`;>%zI|+#6@5|u8Yg50l;QO-3*i6Vq3eh#%de*=H#@Ybks?i zYVm`tUj^1tv zTE$r-R*WWBU1`28D$cj1t5d9D4aR1GzG+!Se4hbpQ(9!mHCG8!M7aP2^m*2|lgRP{?4kEs3Yd#~~h-zfb~Oh)`&dY{TnvI=b} zeB*R&wqMbYk7-jq8&8OjX4v_BGzk<~acD#pFpHV;fkq@@v?Jdik!)!q)hc7-UozA&?XAJ7&k{3+(cREZS(7 zHC^sPBj!B7-g)}y3R}BwxvgJA+gwe*l|P9_XdgiTus^wWzIRc1gng8XNS;wSC8ta6 zRCQKuNo44f|Ld>6ie}bpjI|pHXRQH`eOp;HmXo4&>o%|eQsZfuUv|my&K=La)63mU zbndE-R1cH}ZEDAA^8(Rj;UJ!>@o{}OBhJ2~M~dyYFD|loF5&i(O_SGZc-BhtGXd6n z0CamSi+-sx2Ow%osr|`Ux3WM~Yy-pR;TLRWQk%&)DU-HC-@`Xi@0M(owq%(q?&SKa z@x(Q^1ujKp5XF71=R*9~y8dN7pIp`|Z~fMHAoL|sS@2DyOuT(i#%f~<^NT@p4s)ld z{NiWgGL61N^Y4kugtO*wg%`J+0dYX=S-07Us!{ z>}LW*UC}s@nRk$CfE1ht8Y)VWvWj2n`0?YAn;vI>0$zjTt}2{J$kRk7gTF%OhkER> zZ4MxHcXuX-J*U;Gl1(`SgDL@h11AQBM&#!$w&()atm(Eh_g&Ge(`1wvZ?Par@8bRsx|O z>I0-Qn?DFlPPpz>9o2m!fRJkQp*~3SGMoNJ{e}875ly@IIJGnWF@)h>4Jypq-g@6I zzVNyYUu<#EAPbPBux^nRHPqSiO=~?|fb-}4aKB}s4OLiLKwna9$4->nAvh`C|KOON zJ>P7W3lNn}h_|$qCacRlZOZ^3)~>CFL$AQWx*{oWBK&2l{PR~Wc}U!02Y98jahhG%Vw2% z!g|p}9fD(HY7CwuJmsYWnB=n1uwrSdEnSsL|BdEPO+F^FBYY>2T?XJ4o3yiX;UAJ& zOW39+n6yo#GTDkk0$^t*QHfW-OgNZ&&_Elst_~*Vcq$yAt@l&j-Th+#Q==}ABDAYY z$Xj^@nj~;mRh3l0Z&YE~g-k$-dRak*j5$Bc3Uc9<${xr27-n&rY!MJH$zZ^X$xkZ4 zl4^*w!c+jsJr1=65Guz*8v1Vvx?ck&!whKJN}1GTBBw#?Y#XtYhg0AXqki>_TJylD z0H5UV8dd(yilnMGBoBS5fK|$ef}7PNJGGl^7Lo)yjN*B06i@ZzV@r_# zVpbh7`RoGtgS)GvB^CKkSbGoh=RWbOXt+%KtWK}r2HN1Ta(LCKUx8V6bc$1?hwqJFE6tNn_EUf+CiLx!NXACV^G zT!6921VNxnS!ua1C~30l@{ruPS74RK0AUN08#)i(l?0Ia?eo6-WFY$5L^4zy;kS;J zmatvB~5(B6GI+kGF!mpzNNVoFKuOZ^3;eOJ$2a{FOOQwcscd5#Hx!jtqzmZ zF1XSJL@DLoU+KjFKy+z{kRJe1Pp<97WU?2oAb_Y%mDGhHfT&L0;93LSUAeaF)ojd{ zChT1ETXwGHE!(tmjjdn11`w*&Hms?(@+ubN^11+RA;$OIsgH?(D6D(kQ=~jMDoFD( zfpdWA07NAT195tP9Qtt*;lCv@mlLv*j0C#OzsJw(-AVE3c~xBXPXga1P(3G(JZTE4 z?&P6um<@l{6hPk;K;I``>?akLR?2SF?)-i(C^=Plv7R_L4n`UcPl+mv* z28_z0Uv8m)?((sR(?@86%-C~^cTY|OxKsXVDYQFjhkB->KRTXmA#t7e8{#^pI;>6O z7=;&p|AM{n!tdNnWf1PBRV!CI2dk(tv?yGNxr)nC1rcv*>pph&IIpbRUMAtjEB2HT zacC?h&Ox=?clW-7X2Cm{qaQ&N_^?$1_ODvKf^q*=yZ4^^ZRyfwQCY{Y*7G;BMfY8O zug-_>f0TYLDrv!F(ifY>k0|2u48HTn0is^`L#6Gxzyb!(QDx!i1BgN^s&fE~j^QrL zO=-3Atjl))9cA|HH@13N4~|?$BdP-sN{b_yz5+stPcJlFWkK3FSL7xBt#enLznRQ( zPjbBvkIau}{_k+#mvx^kOO>^P>YV0ol9zt#Sc(zaYcWE6dD4DYyO=MpAY)Z|A3sr6 zY6tpOU-_=6gAVm9dXD1few~Y+QJ)o^ll*l~+m+A6{hDrMOTK4*+Wdywe{N0!h+1O; z$y5E^5L~7DE$ks1UN=$whznJ9LLrn>By+y))FF-kKltDS`_-?0<=>2(0-}_u1_6^TCibI;51WjfGRwdf>t7RER7?%J?z3PPr+R#qlqMP=*Gr#UMaS1+h%v& zbvMteGR!!!p*($Te`-5?O#c@vHk?KCf_P<4ry$Tu+Eev-zj*M0*fej=YOAWM z@tOisO5G6ChmsnBKhwOWQ^*wv` zPoDKOsWX$7m4e=-L5}jEcYPe&g7PNf5PjTt`Kxp;`S-{1e#LP!@qUf*4IZ z9;LpB>Z^&3IG;2DlvYIJxpVgJd+*x*58g*>^@tPMs=h18*+X%0i7i{UoXNr(K(H0Q zU{Fy}LYz$Cn80Si_ml+@xHM@Zf?o}+nfS<5kn7WUmzzwK0uV8{2cS<7x;trW?QpJK z#MGr}!Y*F!wHCZOb)f}2%nJ25T00emd1wjbG09!TBzKXm#58gFnuHaVXo8@Xeijx0 zWm56@6}A~n&BPrw1v&ZTlqP{PugYcMnT96oIDi=1FHr1^52aYgK*BmOp*(uD+ulFW zX6=3B7@nn~9hCvlh8uQ5KH52Xgp%@p+|u_ku|#`k2^0M4OuTGqf=+!G4Uk_Yd~k-V?pfyEFxOwFqsPRW*xk{i+hX^S&utzXf;;jk26<`VoJ# zy;GfcD(2cp3|ZjVFCFs&l;FH+_F}KKh=_-K&eCf11&xCys~OMxBDojgXaz z$vE6~T^)H4F6TiRFk~fIubm2vvYa)DOJL`9z9I+GW7RS6+e}Y0s!NHXp`I;$eGq>tcK4-o=c|s$G++ zq@2M#nu61m3%T_?Xrd?YW1NV@r1}nE>eqR{x{6c*L&>s=Dx4?N|420Iyy74F>EG`7 zl;kHlhRu(|PwnI9b>8L5JN5h!+VmYbC`kaEmsM3`=2}AAkcK9nK>^sO2^kQ)%gdnp zmIVE!fbOY822L4f;6rP(!-w#SceusgJ>Ei&0je?S-?FySo_L}G56@`CVs@@w*rm=EJKx=61!<$0Bqwa$stUXBzEyaWggCi$01$Q*P=xmajA)|lntN)oE)(?; zQ5z)-UY}g3o_A#wnMpAghS3hq@PJ(`?@a=t zNP_C#6ow4vXA`yJ=AmIc*qAZlTme?EXH(xwI+6`~3<8f0lN zlNYT%sRIxqJvcbvV3atQcJF=*5TMUhgx9ZI&j-20NydNj)1TN+e)1E0a=U=2zhl6& zg~1o-wU$Y#Ndkjv=0s%rs75QjLPhzghmAPG zZw)XNUr3+EpFW@Rd-%l1lTZ)oOln?qk?O zd<#W&y=x2IfBW2=1SC7vffQEE16jGsx~Qm_4ywpaHJr$h!Cm;E%{_hl=*u7hwOg&0 zw+k#Mgsqf*sIsaOt($D-YxECv2(B50rb)^KEt?=9Diw{9rkyX_sUQE;#sJmxs7q=2 zg*LKisiiDkX{(>O$5w5-8?bwbesGwH8X7C`8@0Em!Kni|_5MD4<<--WJhz$UFUJ&M zd93e2og0T(aqOb4Uz}}^J+jR1yBE()8`1%U80`9NL>&|$lz=EEBEA8_q(I_rXev1n zMVBZ2EiecADDEK0BxZ_<)%goexETMy-rK(q_tkG>I(;|>+XQSxt3~o6wqnH!c!^fS zgR&Yj=Q`R3AVQI}GUWak&`pydQtjqYbe_{QXgz4TzivI>t>Ikxex3^cSb^TD91ZL~Abt0H{8%+}70Q+rtl=-E~hIY06>Y1@p-~23c?eO#(!X14KEunSdxj$P9o1 z0Wk^sIEAnUkV%7K-;_)pv)A)-(fFCjzT$0Lt;_i|cML`4FutGw^ z#NY_)q>i7l4-O0fz?LKbA{KzO2&DQk4qP{mS!532Qvo1Uwr$yjR@_Ro)5Zp zct1fv)CA^50f_Pm1LdrXGg_b`q>~PDpHBklO*&W{0a0Y%;XmcUSGCF10OJsa{(iLe z;0}=o9o6^zT*%6)Cu(CeYB&nyDiTSQHx*|JK$mYqzhZesC;ax=Lw#q|LUc=*nGYF{%c{lqiC#2#;M2&K0h{+fIAQ+RCa z9Zj<;Cf5zsCCD0$s6m&Q157G)6yqWgN>~Fx)Ymq5+oKP5Bll|fH5XY9VEGKPn*^+s zS5URp7ypp3*LRNqL^WD-`#F31o>JTKSee~%S0zAb73D;mL8b!iy&oXO>FNswu1by) zkpN`xh$30=_85pt8kafflJwh!#*MM4^~_aGDcs{1<3DjRMM9su5CFv<#*G&*UbL}^ zarmujtsK-SEtU3*Lkagvm?F=FQ99Hl^_*U#)%5YPNq~!Xfb0(2^=6N~@^-Ivy0%}! zHq@8f6OXU32ObcJPG3=xX>Y$dX>af0nN#QN@ac0lIX(pNJz=ZstL%Y?*4pN+Rkmc= zq*d3URR&*8CO}j=a#M)PbZn81|uC<3Bd4#d_w;(OQGphT_+`LUWO-_?8Cy#wYy9$qmYgg_y z-lJ5hmzOSHru;8kE*vrCSW+B2lxzRL%^y^MgUNQ%BwZbFWNsAjR%IKj#J^JAS455@Or zH$R_Am;5l~cmDZ5rr)97Y0R#=r=n216(^W1TBP|dJ~Az|NxRg&riFVE)U{-Mt@D3O zvi&0FRbzaGmgW`~Zkjy{>I;j|{w%|~Nq|)HrZ%LyBc%j^P_pWJ^UXJB=l(YZL@m&E zli%@WJpSAOQS*hXhO16h8bShk1PW>Ig`2>u5fit4d-pkcp~%DXSe;n8YNZF6+KGT% zz|s$X@W0(OPwr8jBZ@*+JVDdy`RAX92=RH$71rC19XtHq+PXR`E-K`{Xmv;G&QcSe z-RPX6p(XvjKG=+uqLm;zFXC5aRQmPpSB2EIH{RG~|NPJY?1bjxt@_rtzU64TfGGd& z=qsZN7%HKDf7C6+wLm<{AFl;2-#&E%33wUDom6`}Uh^23r~@hngp$`hafSqs8a@zJ zWw^b4DI^dEY_|$TP1B#Gp)HY)*5nKmZ-wTUUbCj3{K7`gH3BA}4Ox&E15vDYKY^R` zZTDhIhxrl{X@TDM_$r)zS?N-pX{{q;s&cNZvgaS;z$@6XvTc(oUI06 zc=Vx_xcsiRt((&^r(m-06E?aU$h4hM+h=EVLvAj|B#OO=s?~kyUJZOBtcG*Mtw~Ee zTB>Io&%zURz+QjtHQT%I-C2IT9J!Nr%%=bkj=L`}6k(i^XKq`_7RHEWY z6Kv1;dTsAHyFO?CAA8R|clVz4jK{O~+IMC&8fA&1D2ZYab56)P=hTh9zvrzkpaFss zHP&b-2}ORW?yBmlFVz>G?|GkB%pf{xnNQ2JP-Ru6tzWm!?!9j(ZS7V!<&eO$?nk!` z=tDa%HmF!a4E7~h4m3d1D5yeHalpI@*ac`gjf|$)FrZX>`;;}`7_%GKF?B&Zq`9TX zCT7>z=p5~LW{MT!`D-m~r1cvLVP(m~UK-x*;+9`BiAfD82aKE)twJ-Q27x2BYU4E_ zfGMLq04ND2WK7^RQPZRdBGnY&lmMvfmq)C*31(J1U?f=J$RIB7hf}PNg_ADItOPbq zQRW-~Av#h8FilG0R#hcXs@ZiLN+EBFlZxICN5?3yvW zc17*J-8Ht0P*fJN!g4{6Di7+Y{;7?l@Wr|cO$$^S;igt?zG>sI*BPDUgx3|yS6|d0 zij@&CGl-|yU8GUdb=|`^(xGzZtmnNLdINn^*3vX+O^wsA?lP>YDVTSKWdHy`07*na zRAP-SgVxwS2pC0u05nR6u9cY?x9U~t0Df7valOU@g|==z-W5qx329Ovtl(2|O}zc7 zOv8!8Joo|7kw%zBNL}~V#1oQO!X!`e57Hs#vH&QpaNYz&!HCuS!A%1)N+NOEd4B52 zD%&s%!&#-ihnbgzrTAr@hsx*RX1Y(1X^ETj(}gX#iMJJ86g-psOc|vtWm*6@2cSLB zPdn0+whR!JhFKn>*_9>M1rXIbHitJ(O~x2Esb~P%oX#ht8ivx#_jcJ+k9XOQZ8hli z)G(%jQ3=R416VzYu=$O~n7#WJ)&w>?UhCrx9kAo;3~l*mHT_1T$bi9^Y!lCJXmgx|w!!o8lM&7T!~ z^hfB{#7lj-7BHIu;-wQ*jZ=w=%2Lj$E>RaFuvQ5n2qea5P^Xn1nO`xf5tEbp`|i85 z_V)WT*46`~cB~(h$V}U@b(P(FcRAkG3Nc^IvtG2)dI%qUc-h`Rc*%PDr`?2jHQq_@ z+P>a)aP7Sh;3XBSYyrj^r)IKOP(FEGNlFaOh3B&~QOWC6>U%0}hYP^-E;;C@Uuh!6 zBuej$#;6L?1C$=>p^p#Q2Ok{pF|>}$xzA62@)I}H%Z4G4Ed_NiFUpF7^aVRI(c{AL zupTcexou9{pzg>akgOLpzMlaE%)|4>-yIfjz{Y}4}zsdLP1Np5yS_(uB3=RN5wlc<s|cI#@YPLuMF@2z(qs#qu8tyUQ)NlS z%a5u7N09Qb-CL0|+ zEq0?5QP<)u%wRU!!w*#2?%nCOeG5z*O%62Jav(~&ESh1e8Oi_#$@RShAv&m$FsD_| zeL|=b;n$TA@BjXWQG?<3M|kJVydXDX#?j%d|uG^y}8GwP&B*Z;!HyEoTr4 zF02dCFHNFZ7_XXvrZRv}!^TIe^$OgDzW@o-OymeM+m@}^@E~AROUxRt4$==?vMZN5 z&=aahyQ$VjCNM{v9K>r}zO7;9YU{>an6qfBY>!xVEkI1A0ES>vo{}naL4v0(0HYj~ z6CjmHuVV|OTNr`D2+XL#zL=W{Ub=$*&Gne|wgS*~#;kd0z%ChMB@=ZNxIzC;Akf){)>{QQZ=l7+m8Q`nTZX z@Ls`l03yZSk?EoGo_8cgfE8?+p#kE4C2E&1PTGl6ZFb^J8|>&T7zf!lidg#a%qSDT zRI4ikc&sZ#uc#EQ$3o2Y(ygAL>=7Y4U^Ng6qNA939-?tI2mLBd=CXuY0I(=Qd@VQ0 zgZUv~Gyp#M4ez|n@rUueJB)|FkP#*Gewk*A29`9>4U+7CRceV$N;>L?#E?>i00q2) zC7)mVSy`E!olDPiQm2*Yiih6scRm;70pmx@60rt<_ZJ&+oCa&ElQ1Q0dBJA>Fd zK-4Tu#3&}cnN+eYg1lqK0k?zttanK94NUbW#wJ`-^4+&mVfdulmBwys?QZ5bv$nc4 zkG87Fp4kWE>A_OKmK55Bi2e4pi!7L4L=P}(?UY?+W~tS&V7g;Ri9PXjn(cm=`bwLr zb~Br?YIXvMQtKJkIj;+prP>F9*aBd=jNcGBfW<={u* z{rBIuUt>uiM?!KCR8?7NKl|Cw?8TQ}LW8gZoxBP%%L~)XC@3eM5$0=hekXs{d4=$p z_Iwv8uICE){lzbS;X!6nn(#gL_+$3p{@Z`^MdyHhMa2l8!_T#O`j;H@%|bE&&UEe%v2$;FydnUVFu`_UtwFEoSX9DE8OY(d#SRX z-~D4E~1iZ@5oB z_Z|OyM*&ePUKcARGTVFl>8CKqd&++G ztN%^-XI4bl+mrjAWWaNe+mox4)Hcns_BA|jT)TFSm7Nc~W0fmft?I}NhfMqgTB$P0 zG|yK;nEdFuUNQYHVPnNLR2-kEDbjpaT>UqE*F7Y{yDSjJYSN<0s0tWX!mx5Dp7piv z!e@M~H~oIxY`z{UxvGmaR1QS7!HA;cDky*vl>nl&VxmqeEYp?F=-XdM!t&SPR%NgE z`^$hR2~$fSN?JH6umlvaA=Aj#dX@lDafEAQ4cjbz<2I{(V7t{mxZS~}Y0(9!Z<>l} zmHgTj!!$1eL|yK;d)C(4&ds$<-L&EjP}S6Cr>|YNTufzltY3$xr3!oMi4w!`V|>p6>a7|f0(&)W{?Qva+E5r;S{-a+b@<@HkL;6AKE;{D zdAo>0b}_Vd1+C62zXbeGPE9&6yKy}L+s2LV5JD`}RcNfplc>NdJtNS|W8zQVikYL} z6AAVba*a#ORTuJ~d6H|c3=K|VzmIpj_7OXGJ|7`>JneN4SQqBk8rWxJu2Nctlim_k?w~r&w1PfEfbaLvm@4Nlg)6Ni$;MmAOpZ zj65(Vm56WG;CZby6}=ZA7)S-F2)9Sls4ps`6sTC_ff^HOYRM!t_^xB*iF?Na&{H2u zEYnl6Jq-3^ZUta>{tTj-$76Q(VxL`TZo++hzh!f60W0@g*4NmkjkWg3o(vC#C8?PB z(BC0o4hM`NP#{b>$Ne*pWfOx-6DZ}1x)og&2AvI$`B9yi-xN!2`pb0=cxmDuq*3>T zU&1Nw%T1;x;s`xs7TG&%ZEeHQ9wyzX0G4uuXA`VRIQpU^|9(l}x{camG!a#ZFH9^h_Ob((# z`2l7cVAM@O)X8Bxe6Sre+Y!46OKNaB(<%X?)~znFj-ffbF{(RIy1b8K1l|gW+PKvuASrcjN0e#qGGj>5%Ybkw^=&(HEszSN>F+*qUM39Nvo+_Z55d2 z%}HYp24yCCV;LYjVnl`Qssn)@*MJ4+EPwid33Bb+$hX~)jv@B!ViOy0-3iUQkn zZ;d^G+1-XMskV`D@=ULtJl%^^95mmK4|6T`I5*$c)#cg~`?6Vp&7nQPb0{I5N*tKx zDTjzhP#rvT^)7iI=IumK-zi!LpaS+Q?H%9MuL+1!+pV#%f;3U}{nNvr0ieA@|8s&d z^cA$Q(rn+pefHR+k6|i!Hzt}pc}d7Eg14D!ua|Di9P&$)ZQ(iX6<_Y7{$?5$)GvPi z3;X%ce@+|F=GtuXbp5w~`?vP^R`G?N-=_Cr9aajx7bE@&Tf% z1VmlVvETh$)D9ns;TU4hI-n3{Q3hG`fBgXD@tF~;%IUU^m7VtJBgOX0%R3PFuLQh= z5hWlBmy`+)M5#SpF29l^yWD5x+tMwO5A*NF((^0dm(Ky}or6m>NVRvRiZ!q;j8v4tfqhb$A7f{ zMUW?(&0DtEuKVt@haP#@SLAgU=}w)&^TydTXYKIe!yfh`nDNt}{?xW_-_8nD9+Ne# zUIm?L_+(W`bw=Ul@s&9VaSwo}g>zy2?>HdpdsxZC^7@bNlk2VDE73>^h?4zqOh6QM z&Vi`H{Q1?Auwe=7`hPSYE5HBK^mG{{wZaC<-$Z5z0O=Grj^sVs#0gqLwDK-7ne z7*UbZB1_$LpJi^@X{&awwF*KYXU#C0`ld;OfT*hgQOA!bfT%0|_UMi}+^E;iXUw^a z?e@v(MjJsOx30L(?%P~yKYTe3FrPxbM8ioSDf&7B8iEOvzy_JZ35b$;TCiyDCzG(xb^5~$L+{xM={y>(8FqhORFlq4VBJ|%$M3b+kG#czCyrSv7*%G3XD>l zD_u2#@(U)=Jcnm3>XkLg^q@Y3=krw=;(NZ2p=Wd8y&3!PfEY^scD-=`(+Joy@@%G= zF5BAT9D90il|AxEnKd*-JY=Dbq#)0Ab4(zy1i_nI07yyjIs?$c`yxGydniYSN29o9 zkNPV8#8{s*2=cNkn1mKvcQ57{{d0EaXw*&t{v+ zCh$l3l=z_o6~TKn4Mk@L^T>}6MD61bqSn&YiD-NafFF|4)2nQ3HpfOVn~IRf_pU3l zyS5hD=8dr7HmBN}S~QTV04H;~FaKk4w4-7}@|11$G*`lCro zI$%@)MCms{g!ET$vdTnEI~g7~UI6Gj4^a0>yS;JfhF$C$=ADdLURJ){U%%FNZ&_oH zJ(*^YK9z=<^_=w)-g%?V{`LRdu+!~me$l3t7pL1(4;Rp$6=LRCL4F2{t%{3^P5p(p zk2;XFDZ9cf(_xX$QptP=U&&+jYZ@nOA|>;?Z1fIYq5=xl$x~GFR`g&dkJr4P?6e*CRsrnc5Q4g$4vQ^aHo)HhYEL|s z_S@Z-q$&KFrzdglmSqrLys}@E1Ijzq9gT4m76VZ@2q;D)3J^lT=Taa_HwyE6>3-2e zR=(VEIS{r1;XW+?uFfv&>OgmuIw4Pq1iaa{3Hyfk6 zOo`V8s>3`ZiV4a*BWf8SO21oLPr`ex?7tm3pgIuN1C{^nh?Tp!iP{SRQIkw$!F~dh zh!kso^MKv>U0+~-_G-56e->|JOkNa(jKu|r zXmrlxE-*b(=ePhg1VBKd&C``kM%C_lTtGpFXsa(?xWt0M8APSufnEA8Lge|bkycYv zWA*h7+`Kctg21e(N2jb1-KO<5**r7XwyXu9 zK&PpuA;oIz0i2|ZPSVK@CdHVlFwvz6r_E=AnIX5mnm`6+FglJX?eMglW(^PFuAY^$ z($Xr@U1ku)V2j1Avw6y!>heM~ zj?f%gonn=%V*n=E*08RSiB%TQWwHWeD+6(Rg*d{<9$eQ-vpLhHq){0t^JGo<&?y9{$6V{(V^_m*NSEeFub znqd;B#UV;j9Ub``m(~;aRo+-Uo8zIlx}MH8+)MSw^Nu6VYVrD|-|IK}A=hwD8!6%s zWvGzYC~ZC^uF+{fuKGX>U>45N);3*Jc{B0r9=1-vzV>!e=<}=#?}|gzvB{Z9D=Ex^ z`Ic>KR%Kev>P)MzPe+>zMjBw0MC0=cS>eo_0`S8uludCF14=^7`X)BcB7jzLVZmX7 z`ZR&abl(6Tefzr^l$If$ToZ_u3sX~smAoK{e9#uABKQ{k4UQ!r`O?of-FNXXybf?% z#oXVYWq_!Wp)?!nOS3aDq7Hu0ZbwfnFrq>rsym?(rMm}=C?1TX1<+2CLfOF9`|++W zd+y0D^o%ey-BJq>#VRlLZ3re+XD8q%+GGblWL5Y$8eanwctaew{rAk;i~D90jHoIY z=mB$BWh<;pagIa;00lw%z96W5A~UHM^Nc990X*94o(sMc7yZ|PKOid?=iKt&)P6Y? zj?;RCfGFt%NkqG9O%?BG8F3=MfM=-y&8e;trFyTc!=O(=ZSpZAz}o<9Nrg}GTKL|< zRy%ub)NWvcIyIMR4F#p>bQRlEkLTIGClE!(L@$SM=%YdV?XP?6)a4#)8SbSYnY0~i zbI|B2v`6;R2kfcCln&jwT$%JL@4QB{6JRVxR**(=%YiEGwaHw*sOXujkl1ug}?MM`x_Dd%|wu zX*Ct65D|dWc_1pc-?mis+M^Gb+RHGa?!seaT;4lDb^{GsEw&3}rQPw$y)-6Y@crg! z`^6sjq;sB+UvQh1Qwuquywf;Gbxz?A1)_AvFyF)d!c$g0-AOr+{H}+e!}1S-C^4ea zSZELswMeWy={-}MBa?q=+eyprqmK?bBWeYRx^-!%FrZ7y!dqYXb(~rHBC4~Pdk$YYe1F=;mG8fh}LL(P?7xjH(5NV|6Jf`Y%%#mY~eJZ+~= zo&=~miHq|S-YMRTds$6-8aDhI;y)bo?e^mgMD{zh%qZ2?hgF!U_uGf_;8q5u^cn0%$fGHCk!0XzRszqX-k zmn{w;ku5Od?)zav-DAa@*ILn*wFdbE?vhXO{XU&-al3G44k2pvIzDc;GcEnLe|Mcd z_HZ35*T4^iGp7gaqr(V__X5BmzPzO($NuuiW%klbMVKt5xS5jTqj{dvp;<|gFRIi@ z8=!%%3pWkU)X7SxNo-Yt`0^rj^~x1od&|A|@0rM8(#HAwV4{loRDfPuZ*MPVd`+~+ zCt*okX2QvR2x3pI!Zz)p2OhG=AAj67;ayLw+R|9lro5I$$Q(%*yBctnz7Dq7 z{lxXbR93f`3Q#U-FgjARm_YG=2CW+&jQ}sE7I@v$v`X1EIWf(m2_|=V)9LT;VNx+? z)it$Nj+voP)R`oMGdXC|(HgbJYqR8$CguPrt>{UO&RE~rq>WC&l$!2gQlCTGa%?qT z{VEHl@tRd=dmgEQ(OUwzWh}#mA&!nFdkTu++p#Z*?wi&x}an8=2Fgz(vTOZ7uK^C=! zs2&59MFlPaO9`9mvuw-OOzIil^BfaW{h$11)&Cr_DW~0kSBb zfCw|r%8CIlwj7eejEaH0;u9N(z8A~s~3Vm**ch*9<@K; z)r*;3FL_#JTees8jsRp+PJ?88OMBGLpPhlZK5d6SpRwjKT-zh&ynp97K-4%uRH-wf z9EeiB)6N7ylx{&?;++Zra+OO$BPuag^w(d2CUH|fdwam=ux-9Y*8E|I1t>YF#ViLH+$Nxb* zrS%p#I#Qn@_CW}WEqZ(+asJ*@2ek!#%R*fW>(s4)sFucDJMd-sRi4o(AbCOO-+QR#Uhx9!>7S^Zm+{*sW%Ym?r zylSe=J6K6c9B&KJKec zE!g6o!5z5hx9RB_PIp!TD1>&Gq6{mDBB=?_U3cAu4n(C>qo9#!_~R(X6}4DQ#D_HME|S4 z1G-+p-)}moF9)JD@K-|-OteBE3fXN-2L)<<`=DLAG2d;JFKyH5KmNPw(rqWKpkm?Ts9l`F>`e?-EgHP@&b#*ByYD*aB(n+W?d@fPP+wo~?dmw~?HQP;7cN|M zFG%g39d5>=$;x{4{B~^Lkc5fq$vhAk0bkNzOT@_INp`Sl@FyTj+CqW8P#iXa z5eEBV8xStR$T)ju8enPy&|nPRDA-BElQzI=e*<9gn$iN>wkgB5Y|da(nF)}Do>Vz2 zUL`4*>oFNiq+N`tbO0)n%p@)a_SFpi%9JmP^!1=mL|oR?u0f-vf(adYslen_=5x|% z>g`551OTxehEzvK6!X1V>+G4f4$N`ddWLM2+5QkAhgI_Yv}vmWINZ3Y9F|SK73D^( zxG)v)FcUqREGsUJS#cSY#&i%5xN@m5Q_=y}B(@!ZDP%!R&Ngy6wpcG_cm$7r-J{lY zebz1>&$0_=BX+&5+pcu>SQeA%3?@d~H%8JiX7ZjZGV3f z5LFE$svJgCL{0@{PAEnc8edoL$?Vs7_gY(5>?=9Z{O6w zD&_*z^_qE~r|kf%SC7T zW6MXK@(Rjs`5%3MkABhkFFdDmUk->GhtU~$%}bc(-3Aa9-ZR`M*QxJsDcsp956dWg z=a&Pb#Ddlw&zpE9C-J^{`vogXZM@pbuf&K-+$X%J;t|#xKXr?CO6R`K+c#>OwJB z2^*ELUVXtMR!)6`IS`g-xWC;;>w15`X&1g2h?3coCWIP72W?#lM5WO_rOf~eeDJX~ z{rW8%YrO$YYRYogRa@07tSCS67@z=?2|$_|sKC?g$05Hk4#Hc}oE`j-fiElQ7u)*q zPBm=L@6ND&dl8=AR*na&3fj-8z5eEe9Y50#$iPIId;j2xLVI#=k=54~(QX!D@+G!Q zzyOkXvv<161hs34{n9)M@=Aj=(vz5|%VbNdbK@}+4zcV*HpBQkDr zCJFITt1is3N(7U)!a}-hXOT5*$g=7>z#o`n673cUrJE~Hq_-sCZU$6v66*EP;IQ@g zpb-UFR$YT|F_Y53nkWIl0M^XnvVCTnFh#&La~Q3c)^v6CVgEVUdT$b0ig=gVJP7RZawi^m%`_Wq zk0S`Kj7$-jkpL1@$5J@15C9Sap%l1=&G{LAITK^;nN6$y=|=hs@xj?=lQ4M30HylT z=<4c_sCm@RTtKJma?}O@AG=|oW!Sjorj1!i9xN%!yuL2WcI<*}vNN3tMj@fVab_raZ*nq-CwslGV(UdkN}xVi8#`LAV9e&f z3l4vsf0bWu0<63w$TY91sl~^c)ir@el$+sEzomhfPFo$A5C`=)NQ>${uwhSi*uVYmoPBn# z1CwKnasf%V*HuvtRrb^~#rE`bC1{rj47u zzj*$|=Uke@@56lsM9H*Jj3{}%b|5NGCC?v#|PPBnZPD4Y3)z{ZqU46YP*oPG`Y%u)0Duen3f;wSs^T)%_ zesu94-9upoh+3R4-{xPJu&yk0B@qVip=T;j_sK-8UG+F^Ny``eAJuJ`x*Hh`$W zi<$Zs{xM*g2cjlNEtSxD;IK8n_P&j`HDeMsW%-+GtokQEv{g^-vj~IlR0cRRtmaOq zWdQbIW;AGa>Qv0$W(D@MGgH<)$m;9tn7y=n#`ZlnV|U-ZhE?G;FhS$?`tPUh2xcFb z8rv-$G3Lj2X4ymc;4yB?Dm*c*qJBo)HMl^iR9Vyra8Go8KKWXvBMkFOZKx&(xhyx!Ua7PlNEo*^5rqjt#_Mx0-_X@-U<4u;h_;goqirJ)4WP&NBF>06FFxBg#%Q@5O4}41+oKqfMyeH zo#yLtYrZCy)QE?nAsA+uFbz&bt#=X@3FTkFOratM7=5LyAp zvh8|LHXJKWOml5#U79_yFK)XYKv$_I&#G3lPy-7ll1>K0s8C3OiKctU0FI(DfEu8l z^i+w?Q=yb}z$lqnxjTDGNMMvEyJCzvP{k$M1TKa^l;(c|p=93YdB#&z_VQ@xKl6dV z-$ZwG7KgwpO`xMBaS|4fSZLj_&@KW*T|_XuwH*`Ej&U0qAG7f(UZnVpWdag{AKAvO z5nI0*^QLMRwyFUW%OX}@21rXjisd38Ql2K$7=P$_nk0`7kK>qOwFw|9 zix-pYyLw0M^0gks@ki{pzemXVLIls1WmaEWYESQp05(S$e@PDwfC`gW2X0j6N)_>Q zlUskcbs(|n<@dBD_Ti4>`sbV9AaVWIwj(~YH6AbGHV;Ixm=FkLCySNCzL9C0&;n8UX5gZwbDMFJdAhCW21KLOoyFr?!l{?jE>{>%EL9b|H)eN zEE9$z=BG{l_SSpN_Sx}XYweoGoDY*;7QrfDV*lXza(nS*n6*`mmGkk03RpcyeUFJ9 zMgHhnsW2}U3#ehar$WP&X`#y)62mEYtbzf%6Ld zYD6pOrLmsGeA@&%;gj-QPlycSKB9M+6oYrs1M)JE*#G+ zeVmRfgh0fyKoo2!nP_=^rG6%F!Mj3LPrN_jKKYuJ&v$MPEG_?eAc{sw9`97{CG=(T znmFHvCEBtDMpR&ZwE{$ac{%^-fT*Ong^hvhhA_bq7^MlzD0)!Sm_SINJnX~-MyX>H zGfIGzfGJgs3|1?(;-a96p?iuMB@Gh~P=}|d(9{6z(z!g4Yz-P^+pYZ|kwJo_eQ}s1B+RD?rq@wM2t<;;Y17bwI)2 zZvcreW<+H%_-D1uAE3cK6Xk?PRN7=eK-7S>esIjL{^lc_Xm7>!{FIddM6LPpE4KQ{ zCz!1B96|_04GsdR^kSCxdCY$QZqz=4O*0NN!{QV6%I*<+df$lcxT_Y|&~<=SDfad| z(_A}<3-vCTIK#G;3Cy+)>2}}lT6B?Wth9p3;VOCT(ZqsChHV?q^v_|&@Ksw_|MfWp zqVzeHLB77XG`FA^)#|I{zx&6??{49HqUoc@vWwG^4g{-DX?1Y;#~YKR=g=MKC!b7Cs0hV#J?zpZLT1 zVX`F+D@~%9*us!fn4U~=uX^2GF}rdOCepcSp4np;uJu|keM~#RQbA_6l{1;EF3+&~ zH7S5Ehz2(l0;XZY*MP^hdNiWQD0MND2o-B}RQ=QdK!ozI3e&8L)p%_pK0zHx=-fCY zAOJw%iWpm|=vXnQ2Q(SO-S-$wp4PT$7(7!BnDqltwF8_q15R}h@*D)B(P6hN1hq4> zW?^sv3YFwpLv6mTUsr$^IK<~m%vadK5HQ`NOkmMPD3_qE(ga^@m{IZuEiJ&IDBcuj zCvt3bFcp)aPC&#im}~`h;!1%HL}B4EVXn!WL{n+Vc5F2~&sN%9JIdT-F`xU-iY){c zDUyPj9?S|a3(}X8k^umi&oKndy$_{W+{{X*R;tgcWJ%S_>lViZP%#fsmMw#n3WR{!YU_>+TdgD$1hPtcSLCChgrUc8$Qq zo5TxFeAtQ*fi5dSJE~!wZ6d7S5V3XWN0q{eQ@&CysB^@D_z57<7-Db$k9qxLnCA6* zkXZBP%^R&SztDjwu|QM@=dlQnC3QfV;=yCBnERQp^hZBg^fT3e)w$pV-~15^K$Msz z0-~lJq!oiqz-ww+rky=KVy`(6HFOgY)zXJo%n|OTNitxDqky*pqSmiM_`ibs2@{dH zboU5|>Rte%E=H`Tyu{X5p?S17)t-7BU=@?kBD_OpqQ~a-)N2TjQTwCDQq;n5Qw31) zv<2x?-ufYq`R|jnHvHY!vL|na(6A|PGRi zE~9ltTPXnD%ZVeZ6RP>cc-ri0HaiD6_||(ZcIbEy9w4)91aFvo*OlA-cU9P3_rQF* z4^wRr*UJ~j>?GxP=;)w*hR}H`??XD_M|+Fy1z1rVVR+Uw6j@Gz?mosd$Lu%1{k47k$tP9~gSCpqVTqQ% z^x{i^VU<2<)A-yUuA6bwpuCgrtcWE&ET{tu*Xg_dNo!Ey_20d2zx?N4dVeD(?Oi)} z+JFAfe`7EI;0NA62z-~OtiULJ7KrR7a6wTlJb3B%g)?5(`s#6EAA%AgBdQ=_nm0U< zYv)eUFCQJUgNHBM(JR=vW^AD0*hphV|BQ#z?DSq+U(f{*mCJ(Bdi2pMXtx2PDwN06 zEw5iIKvYupe7q8ng1a`RB|0p{``$3Y~>;Up&VFR{vi;hn`SV6 z%|{2g7@aWT2im;pO0*?k3lQ}M?UFz6JND;}0iuGAIgz_wsx;8-=Nkv_y@HO(yGOq! zI4@eH3STQ9$v~9u=G~V%F)vuH@`Qt)n@ckJzB=mz1|Jm%*QzlI8>yRrz4%CY?Fu7m zalU+;zs=W0Rm?>F(|!er`u3J;Sf;m|g82?gZ2<%L+XJF#eDt63rUOyZmmXoTI?`!v z2T$1b-=ndC)<-TTRwbL(*qR@{V5|1+^|p%EY95H{>oY_X&5j(MwcovqH;yZ;wz`t= zto_-8eYXGUK6E+i5e=@lbLUd*g9Ed60wC(r#V*8yVQt_^sSe=ju_xBrqx%|ISx>dq zYta7zi1PTUk@SX=eOSl&IDalFlid7EtAPAe3j^BZL_%iNzx~Z`>^Foa*iOCuy-d(I zMjXJZL4T#bp~2kT`csAnUkcXbHv8M;agu+ST51 zyVN&f{Rjuo#+1gbF08#m{N-|lU!+ejjU4!;fWff+01rZNo zjyZ@Tv#iJ{PlCPV^LyOPNAdt{GVJ=LLA!o=0R5GGJA#0D2j*?P)0p1bpcSWg+1lzk zdl=yIzWY{N&4yH~S7m*u#B z;hk6jnsfm*ioiL6Py`1*{2rW8e(^tGOlXoo-ojW?9_p?FV&Vw%13?l8JcTr*7pAT?X!C4C%d5z(aTLb{?w}~M=`Se*lv~)8 z7#$C;SUCO#pTbMSyuxHAC`__QHb)?^h zCZNks4%)-p3+%D`3+&$A6?XToRaUl&9Eyw(5HR;l)51Xx&&Xk73z{ z`{ak}SXkyOKvZ(heD^=A?32sifhZ&{^tK9!5|QPP0z`%FQMmu^XSJvB8waA6f8hfl zDF&DntQM&O2mm8@bxWmiYA*xP&~uV^DkMSoy9tO=(kMtx65WL>oza{|UmTMei8L(2 zP0tD0P~J(-4-)vsU{di3x1}9ucwGCiV-1gm-}QTShzAZFu)qKNe{j&^@BZ%Z>_p@ta;r@10q3gXZ zpgp=RAWCf%@15pWF<2TgO*lH6ZMvh``i`8jo{vu2R4)vvOgy)3U`6@WeO9q=w`HIq zq7X8oAQ8cukznhjz5dRyeRdrnDvnu2Myma%M|g)!ACY<;xNK>{EcK6a97? z4WRa}0n1`CRgsr&FFv=jp@V_`<_H>_Yv4pJ8jdZ4YY~0^{__d(pKiz zS1w;c`|6xsym*ngUxrc9s0ynpM^|g(l+|w{tN{R8Q;b(k7)t0ejllY9ZS8a2mWH*J2%bY1ns3Axrkr8} z`C-?>2_|C7I~`P$JPA`yCS_CXr;x7d!rZ12vFFxSyz6zF_2L<>Z?w<)0Zt~z%a{a~ zVeTO>dg#(InJ>fyr@S=7YAOLwsu38kjaU_d@sbt5_{qq|#0;P_#V4J5tol7PozQ9; zLRfluV9HLPfE{%r%`OAlTxy-Oe$ti_?XzM$`E9DjbJxaVyXT=a+xZAU7hVK&@XnY5 z5EX}2l#(LxWA)keXK@~id7skf<=`m{>Q%sq3hJ4s-5F0pjrd6-FZ4;EM~Z_~x(VNP zGwPf+{SELNDkk++U~TYoT@wIXVy@{}6rgr?7EfP832m-s%pq^!(G7sFy?Y4HZliXC z&&|WrR)qOo0h(Nuu%jx=vH(`{ZR?f-z$k<1HqN9G?Wnw5XY`GZV46p0YiqMM*o@U{ z)-V~~iasDf6pSN(H;AbKB66BN@xoM7BHTe_gG4wGr^I*yIL3zrrlc>P)+&AZxTpCN)C0#TbQOKj`f z5_@i6I$jykJ}ZWeiT0E{Ri-E;hGju93mgd=o*=pU8>DMK1NiFaR5!E*i48t~t$%q( zsb{KxYWKv5YDzGoBvxLrDwz?LtPz!n*L+-p@4?tmWg}0YGHZpYkB(4WARi6}dVH~A z7~%49JnBX4U?c4`b+aTZ!|vXkh8~iD(umd8rJxTOvp3!z$9w7s^|+CRibnUKx3R9! z_U^5+eNWd|Ljx8B*`t6&GRMPmfG~?g2bt2QqqUbodnq7R`g$r`XG1A7mH%NGgn3L_ z0w4&#J^4@?I_4@0-w+}uzfO&BTz-%W@D)#XFy>>5-gzmoQZcLnM7d;E9m9*FT zr@Wl+OOx(DpIwO$x<;G!a*iSGmDgT-&4H+M^ck{zSi5$u{ncOn6$>6eup*dBGUry` zta1Mz8;F{n$-@za(S8ovuU|WF?;LAqwh9|6V-t~(N=)cjKA1n-hEM?jPoO}-#6ln*y;x2pHII)2j)zP|^O>(pK8Q&azMiZ5>Dgh0)a5!J3?jl`FYK2) zu46&kVz3hq*gvcQQ41ONE&LSLUoY!$jLH5cAPS-KLV5g3c+~K^MS7R3Bj3Vo_|8OG z3bNxe$_^=U9r(q7i{$Sd7Bx+bRsj;veyH$ zyz($&<#z)d@ja3W5S8Iz6ytkqYKa3djoR9x-r8RVuSj1O4ze?2u|KYVcj@L`Qr z6PlR3oIVw0BExm3n(bN>00tmOUV5he*^BG!$FHup${N55fGEfjv{P#Q}LO-UW*Um{Rc*-R00nAK9UU2kq#wqll(|Zkd=*-+lLeCeysf9(}}i-Mf?a z99<^N$0z|W18Mj*Ha21&cG^87$y~3uuh&J;%b3KJVRNQc@2y+6+J^Onbz9sdMj9yT z0C96@K^dl5sem(Sn$!x9pnT?1CJ5xMgHa?2^OKZ0*gDZ{Kq>UM5bi#6Hp+8hNS&Xy z^A|CZ>mRcI$zB_0qLr6cV)+^Qu%m{os&3eJZmzPOTdFa6L93-U1)V57vyr#6voZ9n z5P1fu@@_aO&Ls{)oHeFlL9QM@`y7}@?l8jAYSa^^mKm$ z@4$_`n8R3HK~L#29=T4P!6V~YbAYB7#)Ae_6_~--lxN%CCsXZ_XQ?-M@T*z{D=m%u zwGfEXL@I;2B(prUXGoBqaq}jKM3XP&gBR3Im!volMP7NP1$h>rxm-%z1H387MZbg# z7v**0r(sS9jO#fj`Efkz!iocQ>_Ru}`n75M{PeJ$ZXB_p=m=(au<;_8{qx@4Ra0zt zZ!N*2V#L;NoWLt$3KQyL98u(vCzFgVrmUr<)mmCxZFMEOYa2Iku8{Nx^O*?XQwO=d z>LS<(^(86Yd)9t)gb59mYL;i;1Ln1JONu>s zf12%iG!qS|RP?=KcIfb!eSYGsow{(w(sPQeAh*z--CJX?yj*YFwuv!04sZ|4F@kO! zb$b>Q)>+tt%&AzIRoaq(C?!UHqYzbAPlCQKOrgqye~JE2ZGTsH7fvcZu}?qw6t?aW zyvH32yisE=_voXK+P)|EVTQRT_)Son^EV6oQr%~{E$m~wT_jH7_Qo4;*e`zZ3rx@h zhZn0>t+Jo|_$SW9s=`dR8q;o#y)}Nnn%aiP*t>czON&l15u4lNFhk9ywv3bR)DDF z-1_c(R=Iniu~56DI?w|M6#!8I79oj=(z4QZ(jUnS-GjY2pOUk->8Ww)Y2dMR0m&BB0E$3#6) zTa<#{PYR&PAlgWSfGvY(F5A$lD;6EaixKR|q7AiH{pwy@{lvXYN?>m?fsF!C#c+e& z&LsLqV+=1vBY2|fwNo%=EIr$5iU60MPq9~DW};kPh}lK~ESeN+Zk$8AqTh}lZnE>2 z`>bnNW+3VI>b`aM(*E_XgCi}RjI2auX0oM;b6_?Vw1_@gPPDH}^DF$WfqpoV&^%G1 zSYO9lx=$F?TF+?dmlqV%HHd zZ}v(4AVTH}a+h04F8_d}-Vv-~_7R9PaKjU`HjL}6m_%_iX5GtH zeO0E_RcDfCIQAeEmLY1+q^AsEYBiy#DDVjAW|@hoNSmsUytsB1k?$*WfO1oI{?eE= z^-mFB*g%MP@7NFp5R3vWmZ5V}#(+F-*?AHK#;X;H60np8fEoea^e#M6wSq?^zIee1 zt)W;nIaGg6ek}kVx|&?_%XQwr`t|;s@VmYwPAN}=O?5aps68ACZY|b{@&`|cW9gV@ zX0o!4hrltwK0NE4Ix%VIFTjq26(&utVI~{>ljByN1GB6ooAS;ggLtcw%9PG4>wNV64O9w} zw#4;1!gV*-o}^3p=sCbo5;@^VEEQHDCadA539rJrvm^HVH`?qFrg>*?n6(dKGFMaz zpo!N!*ic>M(L%Wp*JL0nXU_i9lj-)#i|MYZR)?9dfGBD5bal_r=8OVN4BP8(_1h7g z1MF<5v>h8)T85HOf1u& zA_RG%^f`M6lfL2MF}r%@D(2wl?ajB|w71@R%XOlva6BO(>e*+XwG9Gk85hYrsuqPE zAY$CDej^OJ=hDsJ6&{(~@2V^gve5C`Z-46x9ZgM*^tIV|Vtg9&@5gQX_AR!3+ZKKk z+|8{k1a<}u%Hn#HxMt~d^*!w0!hHxzGyzC7H8xs4{Z}R4w`GPriuv?eJk@5PQ@4TeZRIWk^YCaI8M3um{kD5+Hd>Br@GMwjt7_4qgB2Br4M(R${4!_?g~-m= z_~oK?^RZi{;a10QzQgzSNLaSv{-%teC{#cD8Gkh2CJ;4W&$wCmIo#iL|CIxGWDbOQ zLHN$k15q?8BE#fEGH^zeG@`=yjJ@iSeygwoMBRST{>g!;r42y%!Y)0oBUJ{j4!kC;J6=b_u>$)Lh?-+$SAc0oAp@@b!hC=zCcG;^)E!uo3sDNobm7Pse@eby zoz$&>sB!^O=v2&7{tiU3;;GIl74wT!R-=0XYkE(zntS$|^<8MRxv?osoieR-W1Thp z@CmElw`)EkaR9A3LR&}NuHA^*p+hov>9%t%V+_C%R<6jfAN`=*UVf#F4idUQ6TC^x zyG9T(;Jgm4BOU+rE?iP9`~<0D)H9 zYCM*a&gK1o85dcp`8o*2{OalfX#6up} z#4roF+k&AmMq(bdkXK=%l;4_vDE-pTQhB(iHW(I^4(Y=5aRLqn;VkT}bA*-_CaW-} zT01A~M(?n-jKhwK5)iLn%>b#UAlFK@dJCJZY!w~=@zS)eA!0i=r;=ZIpv_B#t+o&s z=GYJ*03Q(eZf?Pi{IMB(@4$o|y*go?@-&Bc#^THgtIC~#)lzTIzEE%VYY})S-Dw$^ z6apwJ&$H42H}M>H^QM$2Eu2x{TCrf1)}X+WexaZ1IR8~6weit6oeDoE4kdPiUV^K= zjpp+ld4Wn4WirFWdzvXYx;U^-WR@tPu)hyR+{u`oKNGViO!k^E-MfaV-PxWN=7wSr z#T}TrzoFJP)Rf|GJq0tpi0!;5)pp*SYMp&C>j1>e$r&fFN11G=P>*u}CSjfc$cZ5q zZgChIk{U=(QNV^;NR7TP07&647w;ACFrACf1mFDkWW&OJcqgQ#B~OQmEvSpBumFec z&36JI>hx8-DE6mYSph&4^`-+6{T}L@mzDpHoKFIxvH+s~Gwh}xzMO8=s}Sp7jk#)e zz*z4@>+I}>S^EqD=QrPLvSXL~?H)k(o!e?K%>#&fDhtN27~_fZQaxD62A;N%PvK!* zsrsV}eXj$-&pmd3)IU5{posnr^b3fRSosvDxB{Z^5Rll?VXtPuI#pVN_VMNjhCq}+ zia;X@Z-zF>odpi&6EL6S+Ze3K_g@znHES1}hU`=a8hlf&SbH_uZp>tV{Db@Kk%#JN z_w+_g+5h{CbN2uI>YPo?mDzZ_%G9;6Hafdz7_FcS9*?y4InK85@F6AK@L z@=L^l!+N$t*uUjt0=Rn38i4ma8y`;LUFx@g`S;K5^#jc|8owJkwVnJ};4gydkzT9M z=%hTd?Xf-em@Jmr+VyEHr05-h8Hc@oN-AddcpT*+3z4{;Pq#|Lt&ZQ$J-;W{EG^@u z$yPt2GQV9QD(H6>?h<|v_X}rMKHbSVklfy={6ip0aZU$_5*tqDnK`*)e+Mb?y2R%d zAnL1^?4KNnQk28S;C7=QT(6EP_=PtXG#EkU(Ew)g@tb?0<)68x0*UaA3oJ1&I1~l;5pl8J6p<&inDOylHd7>(xR1p+HnS zY@znUpV`nQ2Cdh-EM*Ed%OW6ZH_aBS*IL2OV89Ph)6Jx}r4w&?2m9<_|GmXd-hd`v zP-5$2+%vvxITUCr8P4I??N2~)8XiaWTpFZiKv!fFYl1^V$m+5O29-8Xv z*I^Qex3i7wZEZun4-QI-OBmEA99K91rPXGcNhyv@@uIB!Gl}An9>l&-5c_Bx_EASW zCR>+d=vz(ORr2^6fL~XCpLGuPG07~!dmVX>Ao#`&aab@}u(S#g49~H8%#&*H1eS$% zQWoPAv9MBn@*m`>CjWs+R5&424l687Jlwej-k!)#R^DXhr1M%;XF+2o@CerhAlZRd zSPu-Q-fm3II%b^_(T=CG{?UFLhFO*xFS2w(Dnif_gU&J8@>*&bJKNwSi&F#JnqyaQ}9>Os}%L zcV^jLfSF}@fAYCxB2OcLB?P~Ph9MJJC$P%Sp=Mo#Y^WXaQ zerf?~2`&jP@S4j-ep}ckGJ%p9bd-s8Bo13k`c+K4nSH~=1AGKD=_Vh=2pj00vkO-S z?BdlyYwzi|u7N(-40%>jSZBrgWt6QMWIk9Iv$ka?Osg48JYm>XRmYfE!bU45>S(5k zd6L5W3)Ja#%-;`UBG15zSD=-p`sm*hDI|GGKon=^j|cgX_?{T}ct5mo#r&t6fhg|l zKon&mAWR@BlU zbY`G)r+2R%?}TU1!iYM8fb+o~`~1e3J+QeJ0Jqkjd@R$RdLonhhDVr>X+;g7o%QCM0VArtqn&oNgLZz4J@UxI z=vv(mGwWVA(G%D%&y!*nD5&jMShT5lwehH+Um@p{fGBASp2jTilTSXe_doamGuv+4 zxM{QP*s;@Id|^M}*M5GOxQW^VH5%bP6ZZ}8@B3x`gk=}*y`Q5^3K>xaFrumvVoy)Y zgB2UWl(OG``7fW_Ywx2aWOvz2>RpO_keAkNt0HZ7_xdb*{1F^*>@LTvVVc#{uK-cY zWc@dGC@kA>f764hGpd`n3q87%F9D+NXW-AI1icz; z^q40gn2GnVu7Rk1_+h90;-9YAu`B4-RIIg)b(QwgGqd)>von?f6DETRNCxIX8B8>r zt`B1#*KVJEHe^RnnO*2gw+)2=Dd@nw^21E~!Cz!qNtq_4n%)HyBT}i+R1m^LVd9eZ zVP1G=&99XgVx{_bet-J(8J>NZXCHRGDCsNQzk9c9MLqoR!=@m8K23-PUU|%f2iXpZJP)H!XyABLEFAekfDB@l-WfU{N@Of7BWh;R2;Th|Ee zu5#-gsjz`)zl}!+c*3|9!VIcHzpkNrjhhj!t{X(>ier`K0BL0iz)Mp~d7!e4TRZnW zdrE@$#ewqUjQGmxsqWz|c6%I{|90 zfu-2r0*LY$Ir2vQeAABz`kx4%M()3K^BUxrE}VEJIimdF=m8Krr&}QwFVHX8Z)D`45c$-ZGg9DPWGS| z)Nk*8GHRzW!Ya!U2B%#7LZy#7qx#FM zHceZk@Nd6vB;2se?XdPn@pza~Xq#Z&?%q*kKYBIO_UuW+xd9Finx^f|*Qf2@4glr@ zw&t_Av1@(0J@s&!-G5&iX3eSSTB)TEn1az5dQk)cr*h(>XY=ZMB@4Xg5ij+5{34PD zQzz@X(`i}pX4_StY5M@89=N~4w(dx?`gOc7cwmj=S#O0AwX_8O z_}{~_4fn}U)UmM4S2UuMbLPAMS!JJG{_{W-Ad~ve!m z`xol?R)DD6&aQ98h2A)Y0~!sM2=hP`6W+oCghH9@$(zQCY2LS@NN+omKJQ6%P#VB$ zka9bWs3`R!3L`@uR2rsXX_)3+KlqVd|L`Llzus=qHazCdVBX`5sCuja;Zs)iN(j?O+y|;?Lo;L?rF(LBivkUxrK9WX>ZtRKSQ*LNoy<#pJQl0nLxPrnD!v;1d7h$tRwXML<;I9#qD-3W}R47ZsM< zl*{@bR9-QWRL+V9fChork)Q)AbFS8W(W`#kTAP&SIlFPa$8KC}v(^sYz5X)m8bX(A z1l_P%ymS?eViJY+S#GJ7=9DtQhH-MACi!WY=Vj3Lr%^ZHzX2k9dWcF2d7`?Y@6L!K z9&>uJ1+pk}*fiz$Nbxs-Ds+_1L8&0Vj>36k#Nov6f{PaZdi~O^v~gZM_O|GiH87>%eSmr?+tFgwUA$E>r=24iU0Kn($(H(X6;C;22PGtZ_;fNu7mhlm^A2L4`&|SJ> zdLNa3T2=z>0pA4CsI-H66XcU}HDs0P7vIDdv=;zT(u-+c3`B*cEYm!N<;x{8x$!bf zlr9NW`htJ@r1}Aqkbf!EjXAtN#&{18eAMmXBn+w3*D)2E&9EZOwYSw~*h|l)qq_&Q z2p6Iep8dvertNotQ7yw$){ChAM!?Yrwx*#gm4!)I0qtWh{ltu=5uyO=vxHR2Ee&&8 z#oIw*)h~gmDgf^j_#m-+_r6FRRSdkpb1|F}0FH~jDeWhDJe6LQm{D)M^@amft7wZK zc;Eq8N-x?y_uLB;F2}Noy8t;YI_R0p=9fPsDA{mwr}o(yDws!hb#=Kn>VNv>Ke6a> z8iy9;&W`%abM|Kb17-kW&WRbA=6Q@v#MjU`K#EXjRuz%4cg(*;5x2~CnB zsk-&@DpeWdz46}PQ+03Zja1!xE2&CDAV7lY3>X6jH@NR)S+-hBR^LnK=>5LA&pJMq zExJ@CfVJ$U-JZ2qzt{ZsoZk%VwPgBH_fZ#%Lf9q_Q#axL7PbMDNCHu4MAe}Ym780L zS#mm@de`_sbjY52rNu@8qMRp6UM2-Z#k(zgrp>n10mAO8vmM*Z9f)dNJ`Y5t*7=`% zKeVl$o4Oy4)#jg9BTByw{cZME*XF~QzXmklD1Id%j zFE7%j;3q^8mG`sQ?Y8$0blGdKcUaTaG+SOP;_iAld(zQNK~!U*E+8le!61h(&R6kX zb?S7d9sX$C_P<$V@1Dy;qi2A5X~2H^c((n`kFu>EQ>{|$-Ni}drWi@&Nvn261oucn zRIzUe;k>reYSK0c7-3wxuS8>LU`Q)U zfR-Moa;T1{QU8%CM+aZQ^(FlD>C|LW8nN@Iq@T4r#E=_jD~jg>W{S4Iq_?ITvK%$jTR+CeSXML;yty zz0!*pLNv9mj9M?IOA_G9FvV+FI0cz`hTXMsx!t*bnbq>OyJjh@P*NK3)rvqRnc%4Z z2tq;o2oNf0Na?I>nZ|QR6lS_A+V04%`-GG0q@Zi07?cP z;WDgmaFRF$C^cZst-XL!gVgOXd4|s}AEye1#a6qp!WKhL?Oqg@KzLt-u+*D-ScP@q$xdZ?X?Y;u_hp5yU zX#iJ{#=FKHg%EdAdU~O6y|5~hgFsQqRZd?33LuIK%^B5$w42mMq3%?JpCRa{iDw8f z@OhhKB^d``QB>cM8Kb-|jsfnCkIh(5H{|7=qqI4^QPkzR^V4?X{D7T=k1GdHj5!&@ zR*Xl*f}A2-QJ;=?y)??7kBLwj0;*hlV+6P$S_8xYe=>835WYJQND3=2h_)fro()7T$e$$XQOc{ngv}%1q=H7IfG8kg zKUPyE3cxn%5Nbz(OIc_c>Nh@%Sk+^2|)?o%c;J zrJWJrjpm@nt+b=~oZ?aUW)Rb5%4Y(iWL`&$(Z|JsDxvMSzx}QK`q#gPJ8FQmGi)RC z@?(!Z1|YQqbGFFA1c~_^p}LZ=ub?_sNYKp7QKlzFM-QWG4SF?{R)whyWTA}Kr$3*8jeX9`i61LG8P0@(@1R!c4 zZ5`7zgyjOF1h~ihEpO(kZK=xwh^nFuJg0+yN!=S+lDHb zeXM?{cK=qHK$-h9*k@gM)uy64HtKUY0|8E;O$tXS0O zB^3m2EtE=FoVZ35i1|Da^<`|mFP0~*>0AjxFDZQ~=2&h2Ng7evA}gm)Oz~n;6cCjI zfRKYAdEuP{cK)4rZRFe)i(M8FH63Y0ty*eJp8h5pQM)8J`j=`4q7V{JV;*)G?WPaj z@3Q@XQSE*36g92^bXjVTd?OPrBMC3$l>eD5?6X<04-Sr7dnW+a@kx9A5Bc`?p-gKX z>$a)!ZhPkbO#9wbkpNRuhj3DWHkDq!N+2xQwJ1(#UnKketSSsIZap~KS2kwc)$!oq zpu5=KyZ06He#D8$Rc}u`@wh$y_~W?Qt|cyZ0Zw_BDMj=(O2UqKo@6Q(eFc|Syx!S06PT`!sp})w89h#A17oD8l0+;8PWz^~wPY%d)Jx#%%GDX|#K0 zFon$I-DURv2LtvVp3u7bNOKT=sk9LY%rR42T4>w1F0u6+%dM_4jo$*XQPqkW=>T8p zLu6NFpt^A%p8@YuI%cOTqRi9c0%ZVbqasT%rC13d%8T!<05G9;@*YZ`@IC(cuM)qE zZq~^tkhYIjZ4=#E@`0j`)eT~pooP&GWGl~6I{NV_9^(cfj8@yXT#DhTaKet^W$yI( zLF*Z&-ABd%Qs^=KwhryL`s%o?T2X?>u39uRFwb2CCr<^uN!c;T%Q02VnIV!efTw;Z zZK${eRYsjmW0A4RtH2k5l_4lUQJ&Nbqy=;`Fv~ez9jyR&^HBZ`?%A@ilP0-A& z$lUC+W=W-?fZp~2h;r>O>UtV8+!(PJt;fE>xE*|V!uGv3VJDlI2jSr}Om5fKPuSX3 zhVz74+eJKa7^3*YaXWOZ)!sjK!G`bvS(%q*tLjVb{yhzL_s$xttIxE>4WuuSA0qz@ z`lNs;brU8P{zy|N%g3caD2@^Y=iC#3D485TQ!T&*z^AH+?cL}M*6 z-u@&YYF1i0ydA=y9f-PBrG`eo)wM6Vj~J7yTq2LIgzp(?9)_f5rLfPk(Ap zKl8Mc_vT z6d-|FN(eE8gcB!vApaE*)s8o+4(lFDx3w!au&`fY-@uLfgAk9$(2SXeZ%Qj!@zdy~ zs4p`Yn_~9Tb2Ikp+tYTj|C;p=_1Z%?=6m!Zb}5tMe#f-NQ3G1*I#!Ny>sWz`J!$&oFVtzbB}8<>1%mGK_P-rL|m)i zgau%7E~QA~9#RyMxi}jnbFwlqy!^SNm|4={D66%ygT zA+)FDejO9FqDos_T4^iSX4}dQIktRhhAnRd*%s6z5@XxBwFNX{%Z^2oFviK(Cbi7ue;d zDco33+0o+@cIeck_0W$-CVH%@FxQr$>97uMpewg7QsE*QgpMI1GPEIcXh2X#9 zkGgjV-0neJfio_HCoXCn$vklk@^*oHU7gc*0Wj(uB=%?7o@t)6uE8F>%k@|u8egT^ zQ&wM94jKG%JUdoe?b39sZ9prodIr9q_P^I}2aW>Hcw?cSaB@Wf@q6NmXCKooGF*Fijvc`hbiE`y6l%RwkCH0;kj{UQ^%y zu*F_~`;1-g8sV|I%t>Xow!$ z6=-{AItO9YNj!a}8y#NX>fy6O7*}B%gwlwt{E`*pwV;Ogj7;+;X8}>-h#JpCBMOZ& zDvdY<5Y_)FKvcvD>3uqyvS#IIj>Axv*_Y=!Kl{Gh_&Bt!svvbg9EUca=ZLz!I*Iy% zVrc(Q1)@|vzQ)%YG6K!NkVceuyhL5!M&tKO0YrJ-)97ENFniJpdB5RB%1L#`$;nB# zW&iL0{lCuxQK6!~g4>(goHd3fDos+YS6Y1nk~gn;ji|3+<9_~RbD1ah{71OqJ%e39KwF2;<27wtZKE5hvV`>(FsEEr(1;6z|Es@0= zHk$JkC6tLYTtZtAOy2+C1H93l$IIO+TeWHx9`yFuo;`aUAkr6XneMqdw1Z(J%cJ$x zTv7WPZ?5)?(9?ryhTN#1J#*F$9X^D)-Z7tFWwIgerd%}A1U{|7L{H{=>o=^odNicO zDWz+XrWInYYhFb>O{^gtD3F&mwRe_)Er2KqO{&yB0G-}`Oi)@e$wlkv%=v3}cr?07BSls@Zx4Q0;SM+z@yd3C?xBn zS=Mtc4f94ce3}7Mj`gGEGi?0;Y<=SZE@)ni0%YalcD-mpjujP5V(!w9usvg&@2J8{ zV402M9cp4Uo%)^tWPlvGs~63T9`co8<#~WGHHEel((Wx=GHl7xY+KSG&YV$?=?J=d zKhlJ*0VJT*K?cS|EWUs$R=J}fKtk2dt!^Hqa?1mud+!Q2CASil1w@e=^${>sU5-;1 z&I`r9o~s1awUQwm>zvnj@`~55_dA+i0;L4}4%J;t+&(@wg{dN-Zu@1sKpaHtWP*Aw z%PqC~iY2zBy29#~$}3ieEkpZc8QbELEX+g!D|1LtykP(?3d)xQQR>@h*2Uw1lk9t> zUS;}3sXTk?6X}%cx@n#k%<2nKxn{3F`~hA@{vg21G|x4ns05kjiOcC-v@7?&KVbVm z#8YA$_fdw-{1OMsH0%ui8;|N&-Xh9-%t{Jk_J4jS%f1f~RaKH{3(GQWXb^9X0G@|G zYO~k(p0bZV?zSs~`RMHw*<)x!?YXDUHgC@MxF8QRG@0hnZt)qJ=0!l1>P4`d09N%6 z;12eqCnpQbl_U_Qi^}JJanN{E?CI(8IW1^lR#z|bC#wzI`2uFqw`_+`%^!145{QzC zCJ81?yBs8?&Dt){SkpPQoemA!z5`e7pxB*{%{Z&j|$E~rU(LLuq z_N~YG2(cRvq`Yg0A*jxh^`?iUgy`de=74BiO!0A7-c>(5_@SEs?tgc`&;6>hC!c)M zzWd!Lt)a1=*oa0V0C#wQD6>kN`#gkg;xKg+)_Y+ap54OxOkh-zJhuWwiL88bG6RPe z(ug`@&%+Tlf>~Y!MDYN9g#w7mn;Edpi}6%@ccpFHQEclsF)yqT;FlmP2b@nM@+Yc? zS#^+_w;T57D#KjoZ}{=;eGu9~iH4O_R2clX5 zqF8X;3W(AKrM{5bH@@06@%735O>H_?(P-;vU8grqbd%ct^8is2xN-pqWSZ9m5OskV zfT&E!XY(W-A2YU?2dJt>@I+) z2Oh|=`yb48GE8UuH2R&qXdY=$Rh0QN8nQuYBJ``OvvBgqy*kK^H(I99(Qh z=tB6B2A066?w)SU@e1%@x6lEol`B@l-y;BQr8PD-y6J4bc-#=K{6Tss&r|bCyNKoj zB!~pB7=TWEN*Y;!g41XkL1sQOfGh7y19t3Ghn;U4wXUm0)^#nV=A) zOX@}ftMV#MA)OcSB3>fE9ZcPHA1`^d6+|YC#tH=I!)W;QT#Z@lMKq%Dv~^YHXPEuC z=e>4}rSMiLKqL)tDL9|s7GSu@&Ur#eP#5X~WjTz^sS zjIFC3u~o~bZS$52Jjs>QuG3ZsmsB>uhrEHM3s6df{Kn1DRAzy01!TXFb5Wq$uLDse z?Jx{wbRMs8Q*xW=C~7>)?&fRy4N+~Y`p_K=S0zLm$shW@+BvGbaGoEkPF)K`S}ODb z1agtsk5G60{c-rWC_7q)XVGXphv&=7Z4=f405b+~P@J7(B@1$`yd=jeN^`AdVZK#Y zz#Rpl`HHn@4*?RCR+#1FMH$gw&l|a&njB}nFoB66T4OjA5WweT#{$$6*%N-H--v5U zWrsz`z%A>NlOEiAZfiP)u(wVhvA=J@^VvHm7f0^n{1<_8=KJ2{^$PD zoTDfpO6FMtq8b_+FiEWDLApk@IH)Zk!OwVEqFhAzyeUU2N+Lv>P|}E#R+KIf^-TWx zuSs-x01uA6nSk!Yn5A8{kI*=~&^l-xLzA|?w%%4YEU~TI(Ky?c#r!t{uUWqxJ<@OQ z9qt2+id#iN8Qv~S?V)>$0i#N+wtmJI*8>3pK1r*IDVsT4pq0iAVqTys!tN3`dij49AJtIB%gtiUa)Y{Ow z(B|_%RBFw9{r9zoRS4}rClH0EX9(Vh7;|C$tB-(sN4)*^+xE}@{Ljv1`VUw`J@xd{ zH-hl9rX-&)ZnLrb7X_l!fMEg%+wc+!$DxtGEZf=no1M>aUHR31=!|c^`KHZlM15IW z@r&hSc3W#@qlrqBlonl@fFw-M)`*%1qP|#t|2ckjQ=5LmLuVq%Hd?UK_-cDOBM1bo z;isi|Q4>kFO!HDTqL6DX8xSfRfZ)Pw08zw|=1z-u4dG2M5A(F@2#EULomTzO>L@w- z*vMFx$Bz#8*xT>4*^wh1@YHl*s)2dMx;t$1ovZAAfT%raM2(HcJjz{rS{9sCXhh}l zg}$@J?8WCM5e&vKCA(s0x~|y5{2{9-8L~$otg~mHg!FuMB_z{%XfX){(VI{LP$cZB zo+4o*l=AxAef`Xhd;St<4iuk9_tkDZ=$&w(untlv9Nf&8T$bsO)uJ6aa+5w${JU~7>vo< z45Zh>{-hk>MBac=4nTPECDh^#3vH38uWEs$oB@=03_>fX5<#HE6hM?BP4CeGpd?6T zn46jPb_*eLQ8SPGD|#ZNT~m`_Yn`v_YAc@ccr&)iay|q>i0eVecnk~o$ge61ifKYL? z1Ar2}c|lCs788s7ST*l`M?x--kAhmnQIT-s7F&Te5|kCGORCD-k@`?FF59U%`lYs> zcqHii50WWH&ylH=n@f>qIxgxXa1gKv3a4%~qq->j=`&p(&z_AlCINhhr)+F`#JyzZ zAXMgM=AkK80tZ*AZM_T6WjnHL>B=l?Xvnf+G~?9fV6|jMg0{37CjgQs(3pdtELWzB z;*k;<<+X`zeWFDm=NaIVIU%Er*uLtc%_XvbiJ*R3!ftkQ{6ayHZwD$m^UO&)l z$06aj+!9OA13VHCrI<{TGyvrMp?F5DD~sDR4`kRAk7O{m(s5;<(G+~|y>@%? z<AS(G_T7dTRJNe_mOUqvPMdI}JpCnHF=WTorWF8a{b@Adw7c!)ASyNNvV^h~7 zElbt4vKD0~>SsD}i;$9E0Z{Y+s+)1-L48xEvm!801hkaW&>XyQcGTW|r;B#$vqQ(n z?c?^CmF8C9Nw31b{f!)Z?8zM0xEw))@z9|@d*P)kb{L|4;7{hGJbV1Eg?9hWN=)=J z?9MHWO8{g!iVz4QvUQo<`N*J5nm-lOL{3gjqc2LK&&#O!QpIKCMb?<*So}@>a9F+e z>Z|tLbI&nHo^j5=O5Tf)Jo<>;zh@8T(kpERz?2Ja{%raI09aICp}^5L%>B_En0Ou! zQo3)v@djQW_w%9V2;6wBc%<85+qdnoUAynGdx!-h6c!+)Jd)8H(od~_%Bm2qhi8SY z&q+)ow*sQ3TqCLCllZ@9Q=p}I0WxQjJW_r1tpZv1w@508@3_wule>%2Sk0@>wB)3RLFO@ zu4C=b15u%7zWQ6AXi|%zg-v3T`XnHV6`hCFzLA>D{Qh62210v=?I-3!t84|@QVVoi z-rHVZW%ZI07!|^20iupQ|Ehib!mBpj)@3Q>c9gUKnGd`n>XHJTQ_5pabFG*jVQdhjX@@oj_FJWU%6%S zlZAlS)tY9nzcR(w88leV<3;asrxj)O01kB9;}193kG{9T)~>6B!w8T8E}N)~DlFyH zC+=H>Ppdaw*S{&WLdEIP)O69^dJB}l)Pi{f@u3GF@-Nr|hQt+Bjz>K$!8KMiwo*g# zd5Q7l*SJM(Fo70{K&Q60Hu#U)oy=UW#G5WOxzISu^K$`%L|VRV*)j*dmM&Y${!*)| zTm<3pA~)xgX-yh+CZU~7M2`m`n2C?Fz!-B4ugna%RVFe33^LFP8s?dp$MoQRYNDJx z6rd%8N4<-~02LY5){QnBLQovDw1o?Xtf8{Umeft#l4T3w5Guv&EgLUV*;Y^(5t@q# zGsC%)^lV9ciXnuaC(wcX5uzH7Kr;bQtf0KjWYi>ZLimHCKpYJ9qRZSjg=fGq`jrIL zzR_vx14wFXMoa2a46l0=*4H;?m#$3OiAz(~32C=b9BDL_;{~obA2U)wr3IK4_77!S z+dvK`i2_T=5N2hTHfZJ9^gEqaQ2&d?1)jhe)t^nw!IRllJ4ft+TdBV*->&vx`q+z>8THr6 zxb6X1D$FYKxUvSWuq6OCOBO(&UjXkGpwv>#sH$YDiC!33m$=m=^k+ybMJBS8Pe2o0 zkoJsPJ2G*UwveupUtRZlP<~SfhjJbDpET?o)vpCaO%pY=t^-k1kkF6Y+Xn{iP|Fx- zIg9HoV$kMDCP{u$fT;S?Y5V>+rtHbbrfd;rz17tP^c_R9E{+LtoBi&^Q+DtyCo&4H z1XI5Uch=eNdunaN`YhW-%*_FKLGvz3p27>{AY&T)kw#SV!CpGmhC*~UK;(%wjV=Z3 zCvo(jyYcyqHjuWZG@>MEG&VLmA6>YnybFx-j3hxp^}Iwr)#pM8#Y=2wm?NUTr+%(- z>YwUIU|k~2;QbRb#;y*$=mCHqJv?Ij_Gj3E(^0<{V0rHyc+uNs5Rxx|4ZM^8c z+HW5n>x0X#$Hu2dZ0GW7K=DPkdv}4|dtV{u!hqHcH}yI3i7A^=UerbavdppKjGBSR zO=XEp1u3Q)g?qh(+9rS~naxRK^`j3zgdcSujw%kj*HmemZr{EQuxPvO*l{=eJG@|C zKZ$gdoNdcNk3mX;RxnD^d$?>TY#Nw@;ntX@l8V~;)ln0@Qi^((E`2M}dx%dV#uzlKIs zr){XrwY%@E!?8n!ZN57KqGtHO5uXH<&jw`VqlG5y>-BLxi8=Q|Kbn2RT<2%scN-sv zwhi0Vs?fR6=3f+uQhH(CAGWE_nBV{M)qvVP#MwZU&Sx_36yl7kth@|IE`Zz$j5S@; zR`aDmeaZgPZhrgicRssDR2Z{i8>RlW|2q#veaNW&f2-48{X>hL zJl$!nkadgaXzQJKK>oW5^ST^_JUF5dWXB<&l|Y}J3Gash6$JXL9qG9Ko`&pv+>RaV zu|seh*-R@qQ>#7sjb-+?KiZ6dD2*t9t6T}Ukr))2n8PLFU{nM`2$palO7$Y_A)%?D-)Qj?b2pM6q3J2b3VjNAoRvvfR2mv+Zni98YnB z_HlEIwKBd94}q4R52+pv+kP}RfAhi#`>5%v6`RQ3uMy_~aHbLS^6(%jpat+G76*vJ6f6QV)CTIr*DFA!3nh$T8bPs9)Ll^vQxn&J za&z|o#4}!(%!{c&lr*B`7$IEKBYe*CW+5|dwX45T|4W{TGJQjS>5E=~a1zjkaVyQi z5Hx0IFx?#)9=CyOI7&D|2jLVUK2WaTl;c2A$_xBu^dp0HmDh?;F~Hn4NCwWTSm`M139F zw{M@D=1Hx4-fQ0HZM`qY{j=LzD}{L=>dVnKUnCcyJ;U}B)9_UxckrUof?3N%wf(1Q zL{0HhnnZA&Mv#;|ERLvLOl^+-?o~Vb{9c=ytr4}h(Hfq*+o~UsMidKD=8&EqG;gkD z;AXuQx7Zf|I=b;zHiBkK0c7JF_^Q0ZcH$EK?j6}lFMUov3lJ3%LIaopFkCnTK!WMj zTW`198}D`4*i;(;M4LUdYlVIPJKF$ds%+8XOumjwuywHj!IOfkxGFJu@jf3dk^Nk# zyRh|>i9eo(FXl;rpY~$6bMnMV=k<8&?YGFsTULfAC&l~kzu&(7#1n8ht%NJ9z_pW9 zzwUZl>4o~&KFN6-Xq#9xh^tHc&gn!xwQ!WnWf7SlKYrY#9VIZTv$M;+UFqKHnri2F zS+{mA!tpw5XlSt7C3TQWms&OgK_)6H{#Xa1#t@h!5K5d(2Yi|&{c#%_9>bg72*6(k zWX;tG-R0KW6}L7_w_5P3cj^4JwRcTeN6$De*ss~}ASS%iqX2$IJg3lBEXzkbE8mtZ zDY5!m0E%k7kD(#60PI3Qfj|cr2;pmr8bX2}JW?|<-=lv3MCeQeL?v&D>Puh@{~fEC zkv3G6hI5brvI)cycs0%9N`(58qrd_Xk&nVNHZ(GAt(a|{J{f}tYs$I?(DFgkr>lF) zF89Il1pPF6LFf*Z@{C19z6=TsQF}wU?0}W}FZJ@!sy+a>KC~2yZRIim3pAs07K{Nx zO(9HDo5D&RW&q;D<|m7C&!G7ci=mZ+mW&Sr5hHm?wN+5dL}k}`I;v~#rD2Zf*OEXK zwc|h(r~NnKFI#V1WjO(Qa6aH7=W> z-yzi2avsl$5mi|{ZU4vPQ}%?E45AGdW{ zRsM)om5tbzyQ(1tUuK2*g_z(13h~}}>s?Hj&z^@Xig8$2Y4_i=#2&b}-d3&2vxcRZ zoD^wJAX|7v#P=Rsfy#pZ5U!^3(cEETqJg5mNjC^>q;?Da&&#eq<{uv}H8kRXoc3tjckXsBLIO zIS_?uo;0Fnf<~0IqM`xd&%WM&{P5O)<|@Zr=Wm_LZFx4dZP=z(g3g6D|5Jdd(C5N7 z^%?W~U%nbpyNCFBfGEu;0;4oXNiLY477!&Xgoqa-B2rEse_x^^b>OLLV{j4TA=73ZU0FeQQ2rLC53!mPSR>{uX%h&KD+ldJM+qG zH*-X-U263|*ksj@Ky>Ph*bMp?rgfNjz5ePYd+zsmBWeQBzyz> zP^z`{3SdE3a*?@q4L}r8=7HO`ZNpS<3EBZgfMEiA^n85LrB5Kp%S1+k5-#fDQR?jM zMKg-8*|hC~Jn<*hT4_looLDmeRB^)!#s=VFy4XBzXPTxF!g}oNg%-OU)-NU#*PV$2Ho8$lc{&OQ6G-j{)5--AZDeOA?`9_2m+tbR*DkWGe{hb%c6p~{rz_{?63ZcIim~`c47xa z<>wuUYO&w{9<9fwUd$I3+oFXv_R#Kyw&&i3wqkjfty%_0RE_{X>Q;G;N5t3;oU04~ zkBT&*M^4QOIul}a$&XT+Zq^U}w1G3Sk?{)O@iSur&gr>gsB7 zya5nJw$GpMvtRz|guV1?o3#$Dw4v!0{95CN81H2o>99?e+0GHQO&n3uh!PORe1f_e z?ZJl+IHIV$M1E2_gDQKj5M}e`t8<;d`Oe$+OlaG%O|1x>3vK>IfvC{0!ZtPi`TZ|v z4XE8i{JcPv=9cR~)U>Zl-@pHt34%z@tW9%K6yLz zo!bJ4Qd5UUO=y*)yUA7>g$XQ6kBl z%WGa(_@wrWzj#6BGvGCFLwkNgokXHQbVKwT#<>>GtU%}Dh!T)7g%BZAo+)`QV?PI? z@@%v=PQCK7o%rL+Hqp|9dESKOp)FBTT4m+ymRjADTdneewag=kVVEX$VeZm-HQo09 z@uL0ewbQC-A^~~dO$Zz}Rg>SQ z8*d#nE(8)yK`K6h7J&pg2ciI@1QK<0b^xMnwMQO#1T({J5Q?w1MT^j~Nd)I3ky=dZ zBeX^*k21D+<7+@IgiO+bMr;q%){+PtSGNYa!0LN zy$V4YuX@XtqcOD@K&rs<@a~rhsOP|*Kog>fczak_jE(?IOhO6||J0)DDkrcMPuKXk zG>p(t8_UKV1&?%X08wWL?G$E_7h50$AD*p(RAhx6B(+(l>&BVMEBf~86l_uhHv~eVaxyhlx z7RpKgSAJDgK~E|vBTuF9{nT-ZWs@Gus!B0;D@8-aY(b#_R+U?&7Bquk zD=>f~WnJf0$f#^OqE;xk+Fbp>e?=eAqT1&N`hkefr4e-nji`f|<{kVHji`@??EQ-X z56nd#m9lF>MNhuIPoj*6@}ju?-FLI>uYQ0QUuh;9f%Fr+E}o^2?BCyPFTHfgPBiyg zabdmHRMpwT4^-FyKS990gAZ3&11{|A>i~=aSz`h?NG@Gwc`BRdSLu@lH^+>+uu5@b zNaQIhyW?d<8ez4~^Gy>j4+UBhFi`0^U6YV3|x%P;{g1>n~_ zGHh?We$Mv4*9@20h_&~Pz~i>eRxVv`_wA%@9z-j%A;)szfy>NB>kqEC8GtBe4$sg` z9CK7+)c42+eTXge%)yV@-o1O>gs$asi|6mrM<4Y$UvsWv zc9zU>L3BtXfKXx0dT4(wKNCo1H;e%<>&U|i@zs7Tx0Hk=9y>gd*Az> zH8wU_IZi2L%6>!sNH3(zZj^uRBtp0rwmxq%7tIEu@)uy5hf{|O7kcfNzXpifd&OD@ zSJ=SRa#E7k12GPZf2_;aGoNqAQN{MHCAMRCwynP-0-|Odh(a)R?~wwcG|m%2b(-2| z!uhaGt@ChB+qurC-gBGphqm?VN)EcHQgkh}`8*JHdvz4eGYX;oyU?WXLeA4iM^QHv z7Ts)`=i`krHyenOMwFCL0uc4&Q%|A|ocpOjl%DT>&|fAx`uc|328jC4Y{JyZOX;Q_ z>%|#fp1LL=N?-lwfhg6+*CQm`o5g`9DhHyj07NlK6&DxZTmA0ihJ%LeXa7-c>%@&qGs&nmzwMs|8dgJwf9*rCQXYGRJY%?8W5+^fv9b+ z5fz!<2!Kk%#K{FzX;WxX3V%*-_oV&u-%i*sF(GK}O|!Nkv)VGe$t_u7dv@X3>bp6% z5urtEG8girBzz(4{dcYfvC^L-NVpIXrSYLO28RYI%ggri%P#{Cox{cWIa}Je)V6Hi zVmo*3gmnGB$eR+sQ(cRcRwUvogWKV2+=Z93&T)^@4sDpc#(lmh;F`2j1xj^wcG~Gv zr|s0KQwT37?8M3Aer(;NsBgN5?85N<-453w~cy(3N2u{<~MLuRTXvnO>6b2K^G=Yi|)E%gikfMf&8bei|tp2Fs z5b#xY^?|6LdL406msNF&iS8Ap#Bm%BsCa@$DiS_(NMiwQCldS_B3IG&8bRZyvu)Bk z+9&MzNwW`+r`!3CLAyHGP9K|w`v>#J>?(i0T42G_(?nbk)aV{cKS4cOzR8?EnUq6A(iDoH4fY9XqZsAs4!8V}@IL!bIgXZ&a!IaxXVf=7CPO9D~y zoOfu_4qOs2L@FLN<^a7MtklAsAGtOR+stX^jT!rI-^sMUdOFK0AiGvsF)1!j6#Xh;DxQm51O7v(w2Jy%K_k4I?Cb244? zSM*fh-uOpl4>7vpN1xP=HzqLW(M|J6;!d4c6cE+i9FdiaBWgAf74=y%LLa^!)N51n ztKHPgDf`hbfAwG0PSi#avB9tATy<`;nT{!Kmi53(cIC3!y9e7mo^JsR1T@ag#sn_E z!nSQFw1*$fvqg1=sqzpUgS~e6=t(<-nRGGQY9+*n@2RtIe`^VIUm*Y}2Bd(W@w9&C z1i0}4gLyE0setxjK5}r9Gn7HovihaBh59F1^r9u|O7pLx>g(W#2knFRKd=MuAFzvX z_}vXzx#EtUYM>UN#}=^7{5Z6f*K@ zTk8ClVXpJHy!rM#8QM0KKJ{4pq0PSt5S7}7sr%ts^V=_P4XEu?+g~3{J3G4kToxY= z3yUzL$J{)XBPz@*nv+BoF+HV^uaRlqX9A*B9U8N@;kca#qQ2l*NS&~}|Il$2X1~zp zfhez*uhpMq+p})bi>j-u%UT6QF#(CdvZxp@NthPNwWkZtiHT+YW%T9i2FbSkl&mG+ z4SGRwuP<2>KvXwhO5`=q$3E9e%1WJ=BAc%s(oT{lRLq4!ghOeL5Rbp`TRZ;zZ!Fe1 zXnFAR6w_ZS>&mTi!*W~r;BG71erL1@LSpRfiUCB$?Zw}pxBvC;$E~?*z)BZnTSHA5 zrerGtqU!CAjahh|i!`DnY&rntKvX2jNC<)k8&j((``vF(*$clrjdn(!ow}Nf+wV%N zF0Qr*?=H5#`s-ZVcDGF12>KItTnN@l1wYC5#)Z31>&mRNE{MqFLN%9(~ zyS}fjk2y(91YMVaa=GO)yhoSZ_4irae>Y!h_G4Ys7yMexEw*mmY8y6gw1#D9s5R81 zHHCQ#?s~H^{ZpJ69|2q#u;F2d$cHf7qkbyz99CMsfc8e402Q=MOt3OBS&QLiZHh%n zH#kl6g><`ke!|W-b=k#B1DLH8qajmlgX6u{Ki&rc_%uR#+}5nhwY%;pW?KYj6t03R z@)7zXPimRjG5D3_8BuL2F<#Q3wvpx&1x)}^oZ%itO7B8#s4ksxVPDtT*Pj{4!v#bM z)QIjwD1y^yMql;yd(w5Ffc|w2V6?Xf(BW*%j-3Q#Yw5Sn?k*b`#LQ%-9Kosxvl%qt z#wV?pviAevcs}WachzLto;?|M*OnXriUO;yS^y_j43CW>;U+)SWjY{*yytlyr4=O! z7mlkLaa~C;C+eCM2YlRV2cDrBNYiEJ<)BSetYrB(ymbhba_g%+fE%ddI9iS3eUN6~ zI7CFCJ93D7nb?M8gwDVNC`gi(73=>g!+D;G9_pULf#W4m@ zHx{=MG^8dWLSLAN$HBq@w4(6rxMG>rW5Tv%Ssc@)3_wx{r59uYDp7WT=%{U#X^kw6 zizuto*mHA2pL5i19Ht5Qi2!B+l&ZT70JhfFm>v0e+CDlwZ3hm zmNK><28eo)xUdx93Nt=w;|a)D-DJrWi+1<^MTY6>9X#`~ggy&cv9~C}6)nmtr_<^v)rvUu%>M0Y>jkQ^fw=7!$FINn1xxv90bMI+9 zC7!mCDUM^gcJKOXd-Q=?cmhjp*$T+z7m?RYG#oQAJ?1%1hL5@IOyH&?Kbls&o!Dw7 z(%(@3J{MD0(b&`)sgpi`7A~g`?T@d#Vuz0$wq;9~`3H!Hzwxj={Ecr|d09D{r8r_> zEDO9+;bo$Cz5b&)hzovBV3eMt4;=!Bo=3y>wbx#^E1+^Rzm|sWqmMkwJifufD1Bt` zwoTM^XlHHp3~5n?5U%Ms?1#DZIuKQibB#JHfP+f_ZS%!``}OZm*dOq0d$D_&T^(IY zMwvSmXHbI#h-yG{aPvx>RBSG?`yasT?N)#&d5%nKMCFi|V44?l^C{a~^d0}jT<1R} zx!dV-XxmWc)MM?3HlGKgLJi#>TeW>^`**Z=SZ6y_1cYq3oeGNq>{%23mjF?E$Za-u z=Yc3S`WFac!V24vM0oLr<9Q$|)Wp|kn{0C}z*vpV15sa(wv{mVNg;U^K~6z!pUM%X zg{;7nV#rv_`C5_#5G4~j34Q{j{7VVeN6^ez^9wI}9D`>lHa2YqB>)bMHMVHuN~^eU zyOnNP&q|+%07P{;5EX-S<*fbdFOK4gYs40p6xhnfO1pb!qixw2_u8nRJ< zsFBfe05gE7suDm*X$**9coKn1LPa)ZS09Ku5%_R_4gii^+>a6`0Hrd~l*0V7=aO|? zy9B^61Av`_X3dP{=1tm?ntV(qm)oXIb(of;tx_`^oOW6Nd^x5bmE*g@(d?$cM^D`f9eMUp|n-I^Vj<^cX2D8i2*j_@Fd0Q zqY$!p4P%-$YHe-ocZ_mv(E9oYZDhRK2BxcRNS^S>Q(4xCHI`np#`+mZk{2N)R@mZt zH1miB3(_Hc7qBL?EzBVq1K9#z07ByNQN|IbaXdRV1z3USF8JiR2M|L7D;~uRUa81* zF%WLKdup#0z`>`UqVVr30@GZG37+-Lh`KU1_#3=RMJWs zeFJ#D><2LD#1yxqYZNm0Da;&a5MTi&0rD>O3|cPb&PDsJqPW6ieLZG-%f|r`a%}ZV z%r~nSxTnF$+aMzvFK1EK`I{_*Kwq_``XQ~UO9Bvx-sT*;*&F2&$bAyv=*W>c;L(g7 zz{IOZ4Le1o|KeUDQEy6I9g8S{h7ers>Q!{-wKHG-zBo(3w^8^rxuHHCv6>CmTLjGSFNqIg_Xs4^z5^vA3>(y(Q79$v0b|;-!`u=v#p!U z(bg#kj9Oqh`Ekq4)7O0>AKB6YG8GfEiZ_dzKxI)ccMdE+jsS7Z`7X$FQ-6Oy+H!3; zsyK?5zn9#bsmz&kiQjts347v+$F07;p7&;XWTK}J7Zf^}T8B0XTh)%*#OEpQQ`)b+ zu@46rZ`+CE9}|zcX6=3V?y;@gw%TU+|1_s-{t9WNZuMSLOg$I1!1cdg7RGe|qKZq3 z`Dn2iez-zj)0upX9IzMva0XAK?RM(YGHdEvMkX~GFrUSw5p~TL0oHC`U14``0f@Rk z+qR$)h08qhHNkDXFERpI`Ss_1>fT&^e6I7Kn&9noLuhZ6ICVc9hc^ErK$Oym=BVpi zotqC|{u)qUPz>$g-qwy&gm#}JWL8&%vysyBQh(nkOQZ2d4DX4Ej^YbwL@B}BZ0ybh zQOREP`F6sj6}I8mns~zGqjU2>RH&J+&oBVYkh0W+I%v@ebw>#$?TJM6>#g?8Y>Lbxon_|3LG zXjJ{}kF#vo9^egR&`c>q5F|hafkQ{3|3~xO^@{U4;!n6Y94n19)tk0l)Qei0L?dvS z{PLH-aBoNASd&K5h7B8>+vDDQ?{&>2k=RPoNu5(Yq438a5)RZn(Q~v_)bGMGrvRdK zPGsf+47E^*5d}hh@WBUm{KRoPdGaJAj5zW6k|nj)*w|oq-fd*@L^*ARI0Q1k1$(R*o%hn6R402~1hwmqK{S zbODA2b0A8fmwKJIlyCLN+l0QPEl0DW&M8Pc1;9sj#}WDn0GS9%-Vt@3bM!3ys<t3b>K*AAqQd2{fW6N3E~Fm)M84 zQaM^nwN_A2fEg(@Ca}iaU5^qF6*!RKErT0uXp}ji4G`)~nw>c{j)2}{r!Vy5gdo!f zG40Dp&$TQ}dTL6>7~6voPG>`Cz7Q{MS^#I^aWNC~DS1~^ALCKpz@Y>HP!OC)U{nP3 z#N#4=&!gXx8_CAZ3se+bUvX;!JUaGq%-(uE&E7tW$4AUmAvfc?Kqz9evgpHrTjI>3 zL2PM7hW*3$a_q;?W@C<-VGDB6_PZ3bk55k7JMY3*^xDUE`D(ANYpApJYijJC-4%Av zy%lIrWl>*ftQ)Vc+TF%Va zrE_sRcX6w<)&HVq6N0~j&gfw&tf>GO05|0miZ-oIH25`D>cqCrQw%SZz_il z1tQWD6W7=(v&<7ZC4fg}(fxgWcINaMd+84^n+Sa6xIzN{H^2E!d+f2t+$37$?;RQ|i8s^^B`myX}L6AED)S5Pq_^09D_{ym_m05AMEqx81krK0w^+ zBoL)EQlsA8%BR9j>HAq8qxq9~9f&H5fGEs#fYP* zTxjdCO|1r<3vE6RM5Wfu*MDDauYW%GGv)^ORU3on*SV!OlDo^#vO_Ok80bk_n5Ja6Au0g_`*KY?E!Sbr+MA15pUl(s-HY zi291QGi`ZONLk2fz3+#-pb|UY_MZ)i;wSWtnJHdSm@dr>j@#uwykV^`zhMJcA-o23 zC|+1*OV=#7N&u+*9UCln;|e;LI#?RoLsQm#Wy<#c;e!3<`4iUNHwr&Xp{-vH=gOm) zv)xyNxeH{$2&gD+@DkJu6i@*|VQEAu$h%e?^MMJtemdIvti83*{`mVmdvWgq>m6q? z4B)VBd4@fS7pxukq+7+pG_-r7g*R_s7dE2$i5BotB}A1L30l#geqq+>>h<=x-LWEn_G4Ms0&T)iLG!q(*`y5cz zeG-;*9u6!WqnxUjDELgL+rXT2VQP`%c4rrIu?tFgAeDLBc7Z5U3MEVMbY z0gv+X^C0BTuUfzo^8PHWb;a^@V_U`L?JsgFcBS2by6XDVNMOT@wo8_Xvoh zEE@X(h~he!X%r}9Kj20C)oDBaaoqm+lG*DAG1r6F(lw%__9U~SWMzpzN}5tkGC7$5 zQJMCCeLu(k?ngOjv50g&&CXo}2su6lA$E(s{?^CV)-zolnFJGe3(+ zpC!K<89qfNfGFiYYPT@3X-DOjlhIZO1P&5sqT|H5>j#Ow#N2Sx`CHwexc64`huU9r zy})OY&R)KJ#m9YPW21Xz3-e3rb9`P@KBEHpCC!H^hpD%-A7wy2CmB+9bx!k$>ffIS z_ZPUZ;VZ#oYzhrshW$CT+Z5mVu)|(C++y9s{fxCqTZPus13OpP=1ohOgXo#WH{ZKx zdq2Er6O^rhxo$JsI*&YDXIrg#6=kq5XE?Nrx7Wc*RI-7T~2MGe|l4Jm?%n= zd99ITnk=5a%PlSNrS1bP+K;K;X*Z9S7OdubZMWaOoq3?r=dk3vBT7-JdI;^KgHXrP zxH<**-_fHV+sl7=39hJ@ZRLuU0Jy6#`+L~F{q1kN##K~r5m>KzB($4zu7Sygu zGKB!qkJlq&%Pac;qu#OszOIiV)Rr$=Xe&3av8p@QSmu^Bma(?cm-JfNpKqG9a~G!U zjaM()i+?(ub?pB zUB82;dq`B1?>EMSSBJ8BQ@UUg;7U%cawQDDuS((J7dRCNp zNYEcbl3vM)ZFI*?0!8Aq3zRaIQ_$~R2;mv6SFYfK`y8&&kHA~?KBVTS091NyU;t8a z*M^AMJ-hDlxN_A>YiMk6a&vtR&tpL%&VWL`luaYyDP}BsY;1TMIO79#XkHQ2p)xVraV35q#z zk!8YD5Rtiym|TFTxQx;=&}b2#%uNBwF$qHP1sKYpz z$MmqzV?`zH(Xbe84hZVKeg&}vtt1J!sx{S->Py19M0Rm-<=V&~+)B-HyLbUD7WkTu z0_61c;F%EMu5S!d^NDWssbZKk=2`v10ziTi+k{3%Lv6M-)S-=pR#aXgsi8TR4H%RL z2sz_Gl%Ayk5Cur5m_gYyL-{F>xT&u7N8DA<{|1K$n02)R68l8q{7?ca6O{wtDD4f` zhyt`&UYTY8_YZRI@Bca{p=kvV7DVMAemrIGesI~|I&jRo21af3x^;Hfre(GVkDQ8` z0H=!Hg~(|HL{TGZo@CPqj^Ua=J34v8f?v6seIhEV{$3C2s&j=K+MJsb_lEa-*oHNo zw4nq#_W-b7VXly=Z)0Nuh@x+W`@`crf1dS3p;GfQ``P}ZsLaWXgoI{oLo!N29E791 zS0+HDvY0!w0qxtH&}us$x7XjfV!wT($xe0Pv5kC}p{;lSrWLkzLp>fo-ck|ds+r-2Kt{vQ z1^OREYv~{wsP8cE?|*l{&-Vh19(dpZ`{rZcbiha-9#nrCvq=Csk?0Netg2EkAJuS_|>nhdQml6P&M{AW`EB<`z)sG%RQI+y~u>)%;{0SWCBQ^1WXD+ z_k{ixo)4x9^}*f;=v!*{&jUn-eiODzGj%`p8T0#J&Kd~)L2a*B z&`laq$ay6}BPzNjSrE-vTHnfv!aNX_td>vQnFpdiv3lmd7&>a$hC63ZI0B;dC1~Dj zUZ|n3_V$MMPAr1vfvB%`n|{{ZM@w-D9Qws|AgUX)07Z>`@xnwvRKyXbTh(WHFJW$g zIR&fz*wCc4zVw>45eIrYZDexDD(b3j)t1cwQ5(zzLM^RDPU9b|{gbDr>=foM``$um zc=J5k663bA4o(luD8BJ1Lc^{q%S8Z{Mgm>Z&Vg15nkE17 zuW>vL;nC>Y1iUa~wybQ-cHA}L<^o&qsxFH%s(Xf2yp7{y#^rFY8RU>q9JwOPMtaF;FNO#UF&o0hsBE*J4x-5 zx+QKtScgX@dCpo4$$4evLSKY9(3Ot4g@Zu?B_wbIL_z*-XhsE-wiq51r>E1c2NM;= zF1(JlH>bn3GYHXhhXYcbGUJ0cxFEN{7UbpI`uc2J1Bvw-Oxo72UBq+o_J`(BKBii- zq>D7+hVgoZOTQT1G8T zWz5aTJZ}upZNRD*X5(c|{7VIRrAw#&(=dOdE{HLH7XutonZ*|+)6uJ!a=1!kE`;CPdh z3IS32F};jbq-Cb@qX$Lxq_jM7kw616O~UUp*f#@z6d=%*7}|<4yM%|u=8My4D~(!5 z_mB;sA~i{+X5&Gzx+-pqYN!jqubQd~TeCXL)~wCOWDo7JV!)^zfrV&d2~6WrYCoBA zNfS%Lwj2g12mCp@CEvwA7|L55p`-i`U zAU@FzjzV0201tfcf7E90A38~qEajOFT5YxHf&R~qjRCnKMxS4G{T$_ z(n}o=;oSW8%UJ_A^aZ9p^??9HsU6)k&pDzn%_~3ydsZ<5crJ}7%}ZZMBPvWyv(o;$ z9?k<%U$A9EXARqs%1Uock)Gw`rV0Y25<1}Q-W?wB zr*1>~e`-3n;qPa+wPqkqQu9F6?b8`TAJ76=Z7)rk9zdv`ZWyQ&L5u2&g$sRr>wc}F zMOH51d=iePsZqd&7yf7+#DQy9Y!vQ@ils|z_1(Lz5^r&FG%IFms+@-?11bB+ktsWR zWZL#0Xtmegzeu;6uuYieY~NC54?kFIJGL!ESYfe?G$x;ggn{i|*J)&`5CWif-0uO+&oCa457 z;YW-BKcj63+DjgV`6hWHy36a4Yn`2)a3ytNPVut+im%vb&z*IZ<`pYe*iU})6MN?A zX8`t!J%;pe*e22s>4o;uJz+o0$ziMWiqgJP8+u5|pFHOc4-W$bT!ioAb$j=~yX;>g zwm^1{Ng+|hw-P|tu376I_BP^SZ^gG4+{=;H7iX-`4m56c+Z3cy62f+%xI zd8C?x9C`|p=t<1ACWkWZ;>BSE#4bB>yx+;Bk9SVde@F|$?!wFoTa+_y+czymuwQ3u zHhg1~v8vuyufXN`_DtJ!X9gx|Xmb$VBPE(383@Vh&uU*!PoM_p z1#Tn*neetIAFiFKj7u|!vN!;u8@({vQJz!^PN{JE&rL}nN_`;VHScOCnrmJCm~NI? zJwQ}Z5gb+2txC;kq&@^o2~v&(btM;q>PoV(p5#@^i3#S0N#b!hn@$kVqhZw4G;No= zN34B_XW?DZrkQKf(4s7Aw5pOu`__GV_Q->Iwqz-u>+p7#pD#dy9ME>kzsfSH{zbmC zsAp+!s1a4~szYgcojn`3fB)Yz_Pf^rq5#XMXopV)qN=j(|NT*}{lky(4vNWdY#fs8 zqtmwU|7Y(#pY*t{G|yAsdtWF3Rq&qh1OYmL6zD{PR_dPEnbyp-THO;9J3X-(t%bH@l<94k0w#>3S@0^9J7uN(hQQ2I3l5A98 z2qGbFFCsPs+qA*=XTMYDyZZ4PzF_Xpz3litud{MNS3r&EYfK>aBjM>}AMja?xl#y*~=cd`CJIwC=7Jbu2 zL{yu;d{TdMZA|Sfu`5~QstTzxYV2TLV~0C}ThZ9si5ql7eS^L5;*0hoNgrzUo-AI# z9Xoc|T8PC(TwYvK9EgJaTs|6@nEbNl>XQ-fT^3HV25l#T@jv{-Ke#08bcI=0_;$8II@qx?1bx$Z}4xjnj)cw6Uf*~gu_x!e7 zU_JvxeZ@-l4b{(mHh$po>oY)L zMN12$PB?{P@24WvCVkdyA0BM5?9_4Fup-;;*jQ{^@0mrUqcSW(uwp>bOoFQ=Nuk|Q zN?cpxMO(^E93U!&MN}LMoMgbIB+{-wjN7hP$L!#VZadu6X{qsUt1auXwJS62u}7EL zU3b@6919Ff8sJ} z@I@Uya)iih&CbR3;fEf!`|i6BYmcS2bm>xeKYB5^Y*PLt?l71qlm{IX?z7YTo%U&) zd(m)OQ;@5+%l$?QldPi@N$=dbv(7r|^r^FU;o=1sSx@?lzKm7C9aURfYl{~zw$*D^ zqwFjLge<{ju7vB$;Zbf!2Fka&XjCU5iY) zy9a{yGZ0$CVRQ1tgk8Ku^tkqM8-QfI3;wKF6aYjiK4h8k0V|}ViV>WMg z)M{qsx>QhP5QZk9Y+@xv%E$_$$T_MPhw|uNq^u?iE1g~|v^&+GTp3+^!ptPNb6;YP z@i(PSIu`BvhJYyQSOn6*0{{d8Fd(7$Y@Lj;l!%M(hxQ@3NM#!xP9Y^@X=MQ1acgUi zS}S0|`NmN@*)U`m+xl&Ipvy)^2W%oG%c99ywsLN&EnP@jT4YO>678`%%LSbw~Bxp9Ir z{8@k~e{;S}fdD4gs5*CqYd?u{Y8;X4+~k-q5s{iN_E`PdcH4IVYuXRf>~MXujYbre zF>afdW!U=FxQ0TGosybqr_M%gKbE%_7;CSU zBr7NfIjfT*l|p1-MBdyU%Z`X)Pi68^)Nuod( zk=~Jzi{F!&J6W-;15^y;rzE9LvWqAI3>?_M-#&c*1N-c=y>^Ju+atpxC?l(E9rC#U z{`>iQzYW)kL}Vj(u^>Npl|;T;4v)v-W$p80v)}I5HCOUuqX4piLquQOBhEVN*fCrP zNqhIgZ?bm}gxn&TA9ijYQf%}E|IRz_bcDN0mn{N3Tcj(xByJ$=;1X-97p_IV0;*y} zgNvsKAfV3pi;QHT)Z^+D6HpMx-6Uqmk4Ee`77K?Dci5rhoz^)xY|UI-V^0R$CX1_4 zDn($vGT)ZZFSkW=2`gM0BLNsBCY3>;7#Bq;(zO7hh|HFh4A|i7ND|Pplczs(+MH`j z>vVVK>mhWAJAE?0V8U7<#;$gmttAF+kAi5^#54(Cg(d;c5k)}ul!0;}p(`z- zD6h)w`luUVR0lx?xqD$T3G1IADy78gBpTFL=-2mgzu&LBL#DUiL>4;MAFtzdj?y0s zMEN{j8Kz%b7vlPA??L0x1}2UR2MbUUl>|IR6X2aZ$^>@0WBGB`x3u&Ao<8d#Sis@K zaeMdu9Q*7Dk@7lwtb2ICR+OdK!kQGDj~m{CdBt|ACCQEg5TC|%_B3F379Sw)TT_Hp zY=LvnTfGiImFuV(r?QYnazGT<3;x)r@=BdZ)SJd9H|ZYO?&Yd`93W`Hd+&ef(&q>E zG5&vMb+xs$k@dD^^A;j3-sQ-~gRw^7DQ78frpbKRrb+VDm@TER18b}2pMTyZ0bb&c z+6>R&w;%bot-5WMRnMw+Zh+He?AC+qT%P*z_2uWfAEoI)R5n0VY=UT)^qcyocA{VQ z+s@aD?RWb$o+%?GNdB>A&CX5&h|07()@1%!fGA&fSB{yVNeQ?Ld zgwxJS8nPvGv+e1pm)iD+YB4>I!aWql{RxYxjI_Z0BcXb@`z2fV1zhrAniN|?R>4+@ zEjU`TQ*vqc!&7q%HDLjgv zA`TLzl%OQB9=9$%y zav}Q8A&KNWB~7lITpS?E0beQUv|)fTf8&Wdaz&gH>EvFwAmuXnM}C*@@@uM&@aYp+ zgHO>dH6?OE4mWRaC(z1-W@KTuIqE;&Kqs#4YM}6IN;Q81g2m z?6Ss5*8S5@95SmytMLBD{QXhx>j$FpT-|{#(!K=%1z?xJC?^!xwt~fgKSrQi0Mbd% z9v>5DRB8Z30Y*i}d7&l3VoMv5(9TEUz!|sB#zAX^L+r%G7CX|^f&~lCx>!6ehBIpM zf(n~omv3_+F`r$NNhH54tE`|6AdhUs>n#ygo>YJ?jROMzAx5h}!RW0z_dIa=N?O3erdI z0mi7iHWy>LnFIeEV;ca9tfKT%FF?#eu!ulSQ=*sHgZ`@ukpjnza;p6#Bp1x66r{^G zt!kfJ25m1Xl;7mIGyU3bXK=;f-dT3X@Dn;Vkbtc7 zNDkPP3ufY86Y_}?06_d{;%HM~it}fZZQs5uI{=CNk&`WUvZWIjy$QyRh^<&S$CfRc z1K^%!eS>j;lwmt^z8{i&I0Gw^Y$29VcWx=NE%1947K;B6H(1)GfK~AqIyZ1+LrV{e zNda9kRBTsq!F{;#Gyx=OyLb){9y|g$|6%*^gZHtBeGh)P47lK`X(Jop27J&(D9z2w zW&Gqhs%NN@`X`giFR`rrJP_4MM8h|BzJW#3n*@;InRfA_bM<>*`*!B*Y{5bz)4Hg9 z#4vZ{azs z_dnI4cg-tuWaS}_C_hfSp@nB0K|iGb%Qa85Jc_n@qpo?b4f^p3@%VCmeI)g#Danj$ z-dB{PZxDX&vr$9!1CF+Ni>Mj0axbB8?tFS(>&;68)%5~V;db%OmBKAla{pin-LiZ4 z^)JBGy)0(Bh@#|xD7LGO2#6|iKop8x@V?7SD2qhd8b1PW3hC7Tqjq}V5gQ%vNdQrc zZTZ6wSQ-2nWBEk@QTdZsedT2o#6LuM!Nt|0qs!`wQ|vDIp*G!~#~0)b+;QN3!t_5H z8G^7Dw=7w@;8GK~T}eeyxhMjJkcpTwtLt`(J4m82@HC@|-e5;kq}*Yb0}+n2}Br|+MB zoYr-WlH9RGJg)HLOfFlMWmiXN%mRke~ad&BR0^j*?AuxEQXKV}t27Or*K4 zHbTdfj+~mX!?;p4UKp^8)LH*X8+lx`%=D<0=gqh3(i*OtWUJOB6E&(3D}X{stcmQG zi)D_?*}xHmM#iPV0!Zk(sylc6pb)MkSNn0+8HrEcj?uXFB|tfjQnVS$qvmOw;_msha&x! zi?vM_d|9*MXR58Pv;}oJwrEL;)z&3jWo0sL2iLSr04b6z(qs`9jg8S~36;)0qyfaG z$n`8ne~HU7EU5E@L;`_G9%$A#21Jo3Korf!-LI5gfsk%WbO9}^KX}(nt!cu;2-)b; z{82})Iw;pTfYk7Coc0&93+Es*KQnCm4mM)ta>05BAWFuiQ{Yl2kp-)Y;MIcMecs#x zTeP6a=FQ6osKY{vlm_2hs_;j~F5Q!})?)p9L(G2l+^D^@YuwIvAY%e5TmeMIV9bwV z&L-eABj4)E^X$KVFU$V!`&l+bxrRHVw(ISfJ^y;tKCAC18fUxZXAar}SVG;kB?D`y zO2(@S_9=d0q zZQoi44;_6AE5vj-*(47=L)3oUoa+WfWgqP}Tu-i~$kva$dS?>P-h~U7>>`ow-gx5; z((6u9lNG^jSS~&B_>%~Oy7lw$f!gNl{Hp>{ z>L-2*FZ*pX^RJ%-d|L?De`|BAwKTW5!luDxDUPUOq9o@+R-Slt2REYXPCQ3M?=S+O zFCgk?Kl|BN0;0Zt()piLq8T9SE6O$8Si@Opun7-1GeA^WI^XY)KX4FR6d=oyo868f)NDA2U*02AZ6Wm)W$wLX6KKc#Ukm9 z4Fg0)QwFS(u-eNXzCQs(mDpHzA$jxeisisdFGcM6-$$&WWym_=Q(B0Ey#-gS+c#v{ zy7gH^8A?Ne1&G30Ar)R1C543#fT-XlTjd}tR~{*T+B%E{!*E}W5Z=x9{3{K(X7pP> zE;glnh2FMhE}^BXZN;ioTfUOu@kszCxDm8CFI_9q{I;`pQFj`!e$54h-gjw=eKLI9P{)g)j{ljyEE8)t zzPJxWv2YMy5WoTH?Abv(ha1SnmNskcz62mlon=&1jT`NUp}Rv`x)GFa1c54Q<9!?@4i01viRpsmM^zaaZsvFk{A3yj zuLv>5SOLaWVGKjC_p{oy3~IIFB=pm8E)U}JGXH(g`hh!pE4pT?tnAJ7?&$D)JTGlA^k!okEx?VM2_g7T z6aYe}LmX5+(yxA4cRlGGB(+%8616HjQoMX$lbPe7VP zol6>;R0_pWLhF({`D1V9hX{&kkjr#MubNgld~N5+UaeHCWD?e3XbUb3FYImZID0T` z>6q$7aKH?{xWH(Ngsi6$N*J)IXUXv8Omqe)vjVdy&*jIg?Gk;n_Aolo z&E}?yy-FU$bmjvMnx8`bs~K#047G}~NT91!O&EM2+z7UR;=QE;EfO+xo5D`x(KVz& zdBm48^;~loqSH&&wYM*C&2iA4gTM2ucGw!&-(hGRg9Ax zFe5YwLX>J;aFsxZd!P(m#GdcJ`>&zgK2?1L7Jutqz!zvyrS5=DLdN6rmo3QW$9o)t z9cJgtQP!g@nJ;J&EnbILHDZ79lY9GrG?sSOzMj0f`a?MI4YnJZ`P=W+hYc<+HYbQO zid-nGo?PrH!YAr8%9B&kh@JoZjfX1wM)z(QH4O=zrxyyKV$0bN=IszRnJ^`EFBUWH zX^Q0LrK(kFj9u)nXKyg^d*v(Vq}hvZ81zi8B@GfV)-)iT)cuvk;Sxf(Aq2~o#}A(i ztsG=)$UU}hY+SRi306QadrnlW!@QK}q>RpSS@H-F{g(7~NR<*TCea58t=OYYtD4pg+dd zvL$1$X7@Y}x0L`Xg5;#`C>0fxlO}tqI!4+KjpatxM?w|#eabek*SWhdpiXOplg?j} z275OmFOr~a^MM4|Af{RCuis>-vmJ=@ijffTu8CVVaWS(4r<9Mz2X8>H!j4BpNCpJ; zL~sbl{RUn5oykXEHORY?Ey+$z6)ecjDc5H#00?y@2i8i{3{Flf=C7 zjJ(?i#fSc#+HZH>DEU>CM^zVibl((GcOp_J(y!L_eQclSnVL4-?55B z&d!T{lp@|WaaTKHSW>LikRhTQP3T_LgrdVKUF`ccKSSU2digT%8X@s6GZ9@UuOZpa z4YJ7i655JIa0Q_uNU`?Qm1A#z_U`q+YIS~SvL*rUfjP%1s}&sSYRf${%0KH{b1H2L zVnNxM80j?|BgYY!z~)q^g?Os>yh{v&N+>r$9`F#9Y(%1VHp?OrOMFcW$=-M5r>c^e zZv1&v^{=<{^wMJqCl79e9&gD_{4{K8?2R;xJ$pooJp3;{_Nof4!xjW>xO)ioHIt*S z^y4Hh)T1OGDXIneW>ZqkCgaSN z1_5fs;ZdMj`D>e(+X?Uk9kj+l134E7)<)5(?fSpUmGxic;*i$7U14aW?&u%AnEM1Q zd2o7y5J&vRGU}=D89(xq@iQb|LiAgRJ>;brvYcUja)nC_T@zxpMARmIKP$YIvA5&$ zc8vANU<(hc7cr=gX}13KNk8oOu4o#9x9e|&qsK#w@EES#03RX;^?yXTj`c8rI=1~a z#3E(7BpUXLVoyaZ$G%XVOf`StN)WZPf{hI8j5b=ti(6S7%`JTOua1?0BErizj-{84 zx)=@-En-zf;LL<}3jWeb>AhXgqB*okuZcEULlVlCs0mElb_j_k|BTj`Toa`6`=Qln zafNVs2?bRCyMj)9#w^!&842(P5RNgq2|%+nKVc14!on9J}9_0@>UyFUDJHw6>2J$ zrzS^~fvn4*JRq0LX1@2zoKQ$GikZxTZoC|)F>`c=t1P%CQrw~`Q0`>;peS3kzsBR*37(p5 zV?O(lKFFj06?{4Upc3I+_(zfbng%AR`ZZnY7{;HI{EUw8c&J>$IL5oAmZo zBN_DBwBIS5f5_N_L&rFZdpSVTno(nDF&U_Ada)mS%i-{BbKbT$4wW6a1fiiitg{?= zAt0psf6^qzjk15lg09LK^mTI_Uv?_Z2~$kkp~e!~gg#gBh^Ng^%%!!cN9pzv*8%$h znx2M}(+F;TEt3(4(kAMN%?|gpb^8Eu0@8@Y8b96N+8%grR9 zb8?_^&bkL7Entbc9=Uc+TE>>gwq0WOes_IJM?yIBCd5IF;on#OZX^n!noodQ(n)?) zPxUK8DGl{p2vAO>QP`ZzQ>y^^0e}A458Vzi5TEqmOF6C2_?D$26r@L7CKf|XoG4!~ zOPz&HaH(R}K1nB^>OXxVy!))bbUfF2SO0WB*V!*1G;(NjL``tDZx-Ji;S222#3RJ# zRH?iSVdKs8Qs2yw)_m9J-HJfBREOQm&-k;@4>wlZ0>ReH_!Y@a@^3zpIp+FmJDOjR zNK`<_^ymQna`CF9^MSJh3I2?E~DO(w)Z!)Se z3)ga(w<1j5|6694eDwW_K){wL;*fcBwYRFggrZx^blG9;yQ*fho^EThdd_Q5FS)}F z)Ak%PcswI`YD$}wUW+a%Tb|^LmENgjI38ktMPzM0`CZ>l(%SB}STr+h>lm7^`LV!r zp0TA1>j>YJ6GDUSV&u)Qkc63KiVQDhjGm+`C%n&Qccrzv(d?%`2+h^}>Xi|7;HP|z ziU7+xL27U4<{c|LE=p=+5;5xxXmWio*cE4T!(59;*|%K0F78yrcs$e5rG%!|SRUN= zAJ1XeN2RS>4@lhaBqZTxU9mV zf%~(;muNBszs)_`{xr+W33t0?n?sRY6Gdp*8i)k5+00?3tx+U7H>2jH)+pI&c^6lJ z+*frPC%g@>k`stoc=a`J+^AQyqQ|uwtl7uXiHKnHJyzq4fyermcBEXs)`vNdOHyN3Azz49N|{@ zH=mCSKuV*UbgB{6u`GiG!?&#*ADR@99a=d6aKayFvFV+Q-M3M z&vA~wuy?=RK_XTexR;Prw|5_{n86=e$7H3V)xvX5RhFw-EEIJbozBxd z=Lc_^9cszfiy_t%{k8klho(>Jy6e)PrL@&z&kilR^Fumjnk^8GhV{Rd2^Vi71J?aucx75q0sQhsyw4Qf)SWJWhv$9pDV ztIR|FgHix^c%%_5g}*0-P{^e~4_o~L_Zx&q0#cp$)U~rGNrfxC@!xEDk=X3Do8&(JBQN|v)yd_|N!m(erBC~P zNp3W;VujbV2n;j=Pdq$ErkbE)fRFUiZApMhBBoRAXza=RTD{l{(3 zvWsgKGTy-kMUOD|zZy$$@@jG;>PE;j?NO!?Nzh*;eLaylD)~`|wPbr+htit9XjD1e z%a8AU6x%vQ={Yi-#@<`QT~)N@roj2{6jlCBSLYFOCD0c?l?_}|Th(3~<~50snv$k` zdD%@Tc^L0ha()!GmeT_Ti;D^rL#cz(JlR3x?H_pU%=byWcApo@Y^_?=K6?`5dy{@h zrKgQZ6q;c(&i*PHM=fI7`MAS-fC7mNqOJxG3WTA zfK(b|u;P23YvwW@yxV8}?dSOXed%OBQSH+?LC!wimQ?OTtmQa0LuTS7?*|J$6{;>M z8C>6E5*D(7<>f=Qb#$ z$)+!ew>TZ+GR2cUu6CS4}WWb5a5z4LR>uZI1w92gg(D+8$Q1^6Dd? z@eDyKHmbG?JydLtbcyE3!Z`w&gUm2HB)@ZJ3Mt*Hq`o0#1D0x*hQ_-7F(_Gl%34JC zuconuZrI4G>}?(y?{Co(YGGbT$S%8}rx8c~ppDdWu?ELpfw3gRTN)uHJY9!wGm>wl zM2PRbD6mS*)V_SMNxs6%Lh#F~fx%@_rnF|HD|0&_KfA^NQ#x=6Sr*%+^!Ni&_=&fCT&-kV zB~5Nfv)&_@_V8g)MT(>2anyp?157&}+Zks;j~`-3D#8m!6lD%tAPjVQ67W>|4qEh1 zy2u|eiPTlr^t9#5KKqCL!#_KHU6NXb)3fUGo7j2S9ce-#y0oSoo3K#P^*8|(9+w8D zj~Q8vMma=DNKgcdz?+4p2Hu^KttH4NFhQYzqNbSBhY3c#?Fo4O0;ZyqxOOf|C}X?W5Z9 zK`^3*RnDyjocVDb8uhuKW00wE$K^lrc3hIj@q&1q;Ba`-R%N9pM96%%CQ0o0jaltf z{PSOh>pZ%r2tG>`shKiiS*l4xRSWS zznmXbn8R-jU4F`jkrST?A`qt#+Xqtg)fOsWng=gkBE*%!7a<&0-ra?0uY@1HAnNDU z+kziQXd`7lD-iRYIL4^>z2)29)iDxVZ&|XB-%}vb9?*L%IETTeVS(IVAPTR2V^@@#%FO zd;Kpn{T~X+?{V^wlUvR8rNnIX8)HlfQ!GbPH8=e=Ll6c$4TIsg5#ttQU<3WWG=*S; z%lv=MH!E_1R2y}|?hLZ|KmC`kRKxvLG0tLUK9&xvG_ukv)hOf!WfrmpCm-Ct1a;;oy`J@Exy|r+$jbtPm&Tn9Oc0Rx`;QYsY@NQX|xBXw@$zuJ;UmkXi zmDDjOxfL&Rl#`>|lJ-SCrRK^b13CI+9eOuZh?;+9E^CGV!YG~3Lccm~n!S$mx3%?k z0&#IayssLsriyswH3%u-e*g-Y2gm8PJOV$C1q7o;edjftzp=9%pTR<%gt!glK0`yN zfLtCC7`l1~08~RY3zv%?1`ZY-!LKPK&AddBL~R7L>;{aVsy`_9l&}hZGbKhI5}e0( zB&c{@e$sT1P2Esi7+&7tH8}p>Wld-X+sjSJmnUJ8e0!c6qs&oX3y>~q01`meMr6nE zyO`y7ZH5Jo!Ijsaw>14rluj)*JdpoD84X_5t0bNAa5Vnr9|LKo}y4*1Wfz&E`YTK`LE*Z0E2*Ddtzjas6JK%wSwwR2^H|1zqBMh z+SaHdZ$U%mRln2l(l|FCm#`iNn0hgvWb@3~-gYDQc!zSP z5Aj?U)mP%?pflFI!~p+g@Mz#OJ*itDE4y)-9w--abTSvrT!1y2&EWExmj2MOI>N@D1~q}IHVyKsI=5Zel)TkzNR_k7 z-3ct=7Lc~mZa;r$!&#o1&yP(~7}@G`A)QQ@lx0U01<2-Zaug8cn$^Xn%w9Sq^=Pne zNmUPS*Le;Lr4e1bk|5>bL!>Z1EkKK`cQQC4v6wiiCfExJwSq7;{s<3%?pZD&f)2UdD|WayvP{O&_cuPRB;Z1x8B^DKT2{>NR26f~mwz3x)=xE7^b@{#7 zIK4l}X}_M;KbwDkdO$FaiR-Mns!mrdJsp~-zoqi()$~dPY=cdFxMbxh}C(omqUHxp{Hq`2M#dT~mf{BZk5_## z5&7ePR+BqR_?w>d0mMNMK?^&$=7(K~(N}ac6>{Nzyr+X9r}ev4UdNLh5P-aOL@;qi zbb~Xe%bNi;roL8_fdt5?c5vU_k={+%-F^mjNg?~@zG%=7uZ6ah-_t0W#YukjrZ2%3 zdOizyc^GHlkYEhPxArYdm%Nia+MB*v%SX5Fb)46?DyZF=`s+{{q#!aYnGA+lpP+atALAKBF6qS!XHL4d7 z)yt}EBrH!?vkYPp{h}c~^MPbtbH+#-6|pQNIfOj7jrrdiWX8(#A&+x3j9rd3tgWaC z|6|fu*N+pEf2|PzS0!s=jg8tFqsnjwkxkg^*aO{m;By*7j@S%Mi?2-jL{3;~u5vkv z9(=ugCVKKz>mTuR*PL`a2~Tc! z5c`^gz~2#N5+%ibC#p%+{MbGd>85SczVqwvsn6Nsq?y8oiKr#^E_Yq%CHdktdWS{4 z#9xY2`Fg~H32^5;Hy6(Xv*1 zj>+2;*qC++(8xzd$J^YkiO29fSFEoWee=F+`gp;0-Tw1QVsbtyXR5w-!`F5ubfj<~ zB?=UyPUcSSV=*AMIBp_xE5Ds{b4i$20E~oQ_x5Y&;e;`vtDucSe3I&ilYf2QVhi3t zReoXrL0&Q59&O%=I`|0Z$v7PDv6o>p!igM%B&^u|TgD>c1lNW^fYn{dXMc>AEZTe>+*$HWTZ&WIK(Ov)%)2zp4o1h3j18p;?RpHW%W;Kj?|B$-JoKoZ z%JbBW`RsNGoC+<-mNp+XGWAoBgp=gf4Yjg>FPb%D`l&YVBTgsC+tVbT;6eJMcr#Q| zn!>hE?vtytp|B-ffL55+jKS~PJyVt6%x;$s7si3xg`Gn*&rqtYQpf2D!}Op}TVX^W zlRv7Il-{D8gbBXkhb~!?SLpsb3C>kG>5}PUTmGSHWLHJYHQKA3gfsWa-JgamfwT#u zkQnFnm?(gsg_DaQkl&Ju4E(dm3)|WA(Fai)@uG{O$+u?bNg8#G&Z-0M48sMkewha9 zSe9BAEFuHI`lmEOnPphmiGThAqVL1f|0efn zu4k1#@(g4cELPdkPUONp22M~+b(H}j&62t(?o4y0T8XDUE73uaqP8@hm~GBy4*7AC zue?Id!RYbx=yZNTnYXMBo@WD1S=XZHR`6l129qANw5X`4TY3!?^ow<06@OX>WQW!Y znTxF!M$Q3{GE|e`I|?mNfBCOy@WW($-t`)Ul%TJj6Uo%)>qGl@Dl7S#Z3%UJ~XdMzJ2jl zmOhag>O37uqIXNP?ZYTKck63yaOEm>lx@p(#_ehtfo#A zhCSTtzDR=^$Ct+uJf8i1fWgh%ibC+J_WZDn~%Vt^rPtO<*XQh=m@(6V@ zr0k@>zsimxa`EnM`}N(Ia*zFUdY~anqEkfvMQV2L6jfjoHSieFYW-(5;McY;{mgneq(s zBT3yednucJ8WZzRX=JSt_&Y;wqcDGnQx4ZKiXz6JX}Vd3f1WB8=z#71;#|x?FbeJd zfJVh%ai(2dK8%xAtMH~HcLGA(AC3uDHo$Vmztl(J5B4F=rRzV0hu?g! z-%@l)45%UwgGnS?M`uS>8pG+1>wOyH{#1+@T#$iDmQ`$i7r!$Y6KF=H1kJ23oF+Hv zqedhG+D7Ze?KQHedx&Avfs)0GL1eElJDJK{gBk+GUqz#Q5E)@x^d&e^q5FR1YTEi>)-6HMnr|8vDwJXvnpKv*)jIw zDuGLc|HG4H{#rp}BWCJtm?fW{gI;_$Swz6UMJ6p13Yr$dTZd-n6R0@)eA zQ{P}3G4J1~CAaHOH(3_NT{$Jg9Ia;^2%d3+y+cgOPEo(FiVU4gbVc^Z&vGWs2!*Xf z8Xk@4wxngUNrCS~yT1Kp>KMV#%4+6l^5!qGi)ObX8;ewWVFP}i+z#qnCrkvS4H3Uv zUSm3RR&RV45b8Ttkjk!ldGG|5HGir%3!DQYPk*uloBXoZ4XXcZX5DaN1ohL!Pe9N0QsTF^YoR<3#{2TwBedhnyyP@N1A`TqPtL@7p<3bQDp#z$a0cWlK z%2|%c-sQh!E2$!g)CN!tWVkCkzu1ed)$@GS7tQo3mr7SZ5;4=RbuPE}K5W%)bZD=2 z`F5#7POphh4eq@4%6rZ8lqZ#K_I?6(-nX!Ve5YpQ#w-?>rc(-yw|iAoc!AKc&?kzD7j6;-~F zV45iifR1SKv&-_6f37A2q@X&`_fY=ZtG-?3txh$SX;rq>(UOz9p^& z7No;=huSw0iHq*yAeW&gx{F1Gjk!Pciie#u^a$CAmS5ZD>Mi#rJtSalBI&kfk9+{YJ>{ zCS|Nicj{fJ8oRWyg}BIB71D@%bRUXgHY+6e#Uw|-N#OHko0Jv$rj6z7^{Cj>uip;r zpdHc6|05O=6e=Q%$Kv8-U*tE?BGwHmFdj=#)#O;IC2t+RvPe3TI;9^^jA5@$eE5Vm z9OH9(oCRp3lD8ygOW|8`WilPp1>xXai`4veDH9Z2(YCr-)(Vo>Ykq8IPR`svv4H zWfamy{kORCkau5wR5SiQ@Qe$yqiU=0^Q)xKb~g__*VhPIKm)dA+2e1m-v4^yeUXHpHi?B+>(L1r?6yF$4J9S}2MGJ) zaBlbhJ-V*HZAMQTW_pux!Lo6vLJ*@WIa>Fw(OBX>z5TAA>iVvGg2pqs|B;n8;5Y5s z-=?upi_V4$GIBGCrNJP($M2OM4AE?U6zW71Kc)t9eeLK@o-yK@slSp6iA`N_>kA?o zRjxNH#~#`_9kS zd*}U8=%

_L2U#{dR582;-x<#S(?wh75tDb?t8)*0WQzGA3b+hdQ{|)8tfxd4G0+ za`r}|d3pVKx8Da2SWe3QJ>tI6wpt4BlDp4**u%3eBe@$)6u8=BIf8c(dQzs z%Uuy{cIUWAT^;v5gA9W9!)Z99RE?ne16Hzoc`alhq5s3CZ$Z4ivNCmAJ;k!}6QV;f ze#NMqLwj^g72+7G7*Qh`cN+r2?Mzv&}jaM#Qj|{oVYL z?MV5%B$_uazwey7{4+43fn!X&Jbu3IPFG~dqGb?)SZhWmaQF1QA)2g8+c#J^_aFtT z_EmqUtU6sKwC$s;QhBr;k0Ri#UiJ{qU#t@3>N=@URP@n}f-@7B^TDTTt5&;8UWX~0 zP-Fj$8~0c=r!wE0S%K-Xr8Lh(b4@>H+f<}h`mLqVkJi6D>UdoXy}VAle^p@g;kaHX z>}0MIM}I^*13u{>#5Ghk&>`V)vr6s`b>^vv2ExQUvo7EgHYAwC;jH8Bu!+_q+cI(m{gC_9-=u$G`W2<6u73Y)_HKzj)}war zluiWi#rapZf%k$Ge4M07=;$ABORE{UI3qQ$I4z2CgYFuxWgc#Oz&=N@d}7`WYdlw; z>$Ft$?z-JPpB2?Hp!9kiw4$jdbU71Mmwg`#){i2m>=E!|#RNdAc^%7{O zov9tr78-%P(3eXB6|dR8*qKd4T%0+om$fK^-h<5!x`WZ}=Q3OECRQbMzmEyeKd?&O_VCiV|lyGI;8R6xXd^ z;4J#c2XSgJy)$q<`zOQc`-9H6&i?=2HFR^ze9&ldHQtheg%sM2Jjiu?UbalOj*KcN z5BF#z?td3~MTXA^gU={)UwSDawybH1HlvO)_M(PXq1~mVwV^89%qeav*$gfcGvLUPz;}&<(x$KGU-|ms zN{9)waJBI2_gE+Lo8=QFm7okA(@|NT&Bz#l5NY4>gH2< zf)c!~v3Pt4%F;IbwE;zFcfT|&S3J`mRx9&e`DbYaEfe?YlsoWMccA?%a5%~sF z=jGET&n^dj^umQ>BCg?!1meffgk44kgejtn{7%_JNHZV9db7kc7zwr%PH^N_$NZ3I zCEqE&(&tXoL`u-m`ix7DN+2*&*2drC5*^LeNkP6ah2a1L?|Cl-KUjEKg=oyt{gw9@5j3M6{$TJ-``zE@feo!h;%VOH@8s>NnL6;s9 z)p#_bB%a4Z*CDEC-`e6M0>~+kW>9XOFMM3@h+xK%UhD2>5`%UpA<@&jslw=xtWahR zN6l`FQr`^G7bLRPQPrE44b(u z)sy|+JNVw)e0bThW?RdNywhYv&p|QZX8A@1aDYl~` zg`QP!2jjwZ9@YS48L3fwivBr$jfi0LT+ONS%k^CNd#NI)dtALaN^v4JcDi7ooDk7` z{j9Hay?e^^MM9{*K9%%(u|=y~?q~D@P3Dmu+@7>a$poKL!Cpc`W<8xqlNOG{NomUD!Q9*1o+x|M3<96=imH)D!-?P0gr#fzKJi6m&oolmMYAODca~F-X^wp;YyEYr| zf>E2D`9>?nOM`kx=atgkk1X%BR8wBgSM5tJH~QE8^=bijogw_*`_jGF{<98er;>KL z*&<)G?)0>^zgwtDw)E!s`bKJLB8!mX=!0681KiB+iDD8nd*_^n%X|~7Q;CEyblip$ zlI2s>U5o!@)RE-W@lpu&$m)<(nRLVipn080KJ544ANSy|p##{uZLF%1e{TP3^j&a4 zmyRq{f+jHBhYqZtyLSvAVSpwjF{|H?1L1t9A{LPcVCX3 z)|m0gp9v8eAe)ulZx_afGLLXrS^yf>!_xThbcoFNMACJcjSmuJ#S|%>=We8vx42+W zea=rm*<1J{K8@CkX#s-12_S|`*0=uoAlQItfj$ull8+8K)3zLnIPTqj@uw!L9Ev)# z!bl9^43tKdk}=Nos`?`ZyQ@VK18PpYp-0(~LE69oi}3(}6F%SJ;4Ff*Ev zg82htzOwwPI-8T)OM5>+nBn;+cYRT9x^%e+u3_a`eum%_vL14Iw>H=m1DA9aG*hJv z1TCH1Kr#rc*|_8ADv1>he9tbT2fivIuQ=#34g{+LkoNP-5wZaLBxztdr=dt_BbtO_ zIfx*5J71~GwTgtA(--N}llKy9PI(ZN9QE4QOq8HcLtO9xxe21|3w`%$hJu0##5O8A0EjsvEV-`%k)6 zqI}LBN3A7Iz1t(_S3sEW!LMCsz3OJPf!NnVu~^-gP*UGWzb~JQ!^5Ea~WPgmz zb{F2F(bM*DSB!X^S=Z&IE!w~1Hx&_=?eLo*dYElYo&SrBmX@sNdh=bttX=c_thGBS zInwABKup=}1~yqv z_xUk;Ld;X*Te4$F_}}huS~ml5jggxdy^z#+X>1s4=Suw391u2$Ir6?|ktmK0LI2p5 z|A6$}oRl=%Wvp~Ol+i|}MdAv>VORgtdXX}V^XNZS=$ovMEIVX8T2@|*Cu*n7v)4n& zmSnyw-b#pq=9eppC`w+KE0nJF$jobdoihv^Ol0VCf5DpOJ3=^e>~vR4`ekS10Ps&V zH^ylHt_#>n!WITJ3#r)6a0YTeNi4j1775?$d!FJak$bpKa1# z0bxYV7l|TqFv!cM{_OdbzTo^@KiNv-fFkoaD)Gu&PoNjECULa z{YF=p-B*qLJ6ETsqarQ@1{&;n>duS_>z(tK&%Qn}A3QWB<{00<58m6!Nn7e2Df>s9 zVtCp6;P2#SnwOTJ z-b~aMvNTgOpigX0LfkzzpNYhbNV)qe9sNx*9;T*sr8;YVo`$GbN!x}s2`9{KK=nN3 zF{J%(zp9Vf-jS+vA_GhjgfI1o!Q*}8@?bX6`i=fsX(q7aJ{nn>hc#+<#;tfrHAg&y=DEa`C z*^8M9<@MGv9%T7F0~yDc(@+xvsy$vOSj&Vj}*v)vp8M+7`41gl^V7=dtZv!;Ze)Vzz7=u(kQ4t@t&>f_1_D;34apW1D z_5OIigg4QD%7mnd9moxe~TO=HmSNUaZ~K8a^7J*YTb!IdA> zy!b*Iq&V1v0AqHnSxM4FxcCiT)%}qF>IA|H(ENsJ#@4UcI{t37EF( zUYW)K`m?EiCqY{>faET}alg3YQIXOzHN)y3>cu+p=V~^h2YKyNONFLAHAp!~Y6<4X zFEN;e{W4~o*(a`}#GFWps#Y}V8&H(tOS)wP7E64?yE!{+m@{&$k_ca_ilRhcSE-K0 z-dnOCA=Bk}5{dmt#7#&q0(x-YI0E`JjQ8wu6;Uwf^B$ z#T8-el}>(0NC4;u+iE~6f_^O~@{U+sj+FY@{3jg#?+6-tB;3Z;ZM8CYhodl44%gJY z*|>kHMFv+Ot%~v^8nO;k!v~oW1SRuXW_Ruj;=CF8zw_o%xhj6i{}dgKb3W)DxVPl1 zN2oBlS<%(_zP{*6{U_zh_w*8$$SY2I=3UK6_$L4Q1sXgCK55sR3e2K_k0>MN*~{Lk zCP_Y4O|H(ncDvMq${K3O=u0qa91JdJQ6cFCMkpmGbwXQX0NCFFf{bwTYuo_L!q4 zC1$D7>Z&H>Zf|nEqki*R{=GwRAQtQhi)Wgo=!2->cQ<^UHn&=RNHS&QyTZzCNor3B zB-cktx5Kwt;=BuaT&2>%DBCqQiT^dZ#22sEp}p;c52e0W&6S>*YJSfnP&QBIl{ZRz z_m$Thd%;|2<|+jU+LDSdOB6{FlSA3J4MJ%OE@u$vbx%dZlH;0O%gV|ZcP#<%l}q(} zcR8vpS7oL8JHtfV3r4>QHLg~ECqS5F#i>H%ITP>*jp0Z@u(vA2wnpNCM^Bmj(IR+d zhI3Y053ZdEL88}&1}TNK)D!AAv)J^Z9y1ObXrH3|*k()Bt7)5*N7AY4h(s71k80Tg zrYQ1gNxS15A4(mV=V_m{CN02BdeJC)_L{x@E;k1!0~W6Imgtgb@1BG$!_^uWH~OPz z`JysyZ5qZn$7;oN$d|(4UV;G!-^U<48ducA-*KJfxRe->4jrkn`Sx4ODmmfa&Tw1C zDPyYbQ*x>eRaq7lZf=k26QG~-jCa*}dV~eBHSgMm#wF(KTuaob5_EbU0DYr}fVNcT z^g8DIpWBo}*7Ko+7Q6zCXzE#2k)YR_5|Npkhmx2yf_*a*1S@H>q0F@#IxZ&pgnRZ$56&EWqwEws{?ZXLv>-ySn{>t)pOtXOn z8JMbto&_I_w4a_!XKj42R!?5!x}7HdI!(=D-um{JDzc^D{lfQlFX(lbM0susUM`LF z4C5<;&xMN=UCR{oc9hzPbb=<-IhNqRNa>*tYga-7rfcD-RjN8umGG~>LazFhe;zd> z!+p~Y0^DiXbZ`8wKS0^C4+dzZ@Le8qAH+mdLwWKBpvZYM)bl(e?C5ex7e1x!nq^$m z5eA-*x>8%m%nw#-h1nhNY{(y+UAfDc5{*K~D#wEqc&2%bC}9&nTo(!1J-91AZ?)cikOon=>CZPcV2w_qW- zySoL4&_HmS;O_1k+}(n^HSQ3Cy9WsF?(Xg|{mhzo&8+#-Kj5rB`@T=@s;hV$B`oE< zkBU-l7OHjUr?4+!gzx%)+|T|{Odot-_He-2-$QUOZvW_tONK03*fmV@J)!&!cbyI{ltf4^k0EkoVJhrjSNFFs*#S7GX2l>e8{$}K?%^Shc9h5~ukGQ2+ihYf#F-A5343=q1z{c&j%uA~a= zijYQ~;O%7fxPSa%_w)RwYYWRi@9Th63mOqzGbdbBaQNM>f~SB;nK%F&8iGYWr<14W=W= zMzH_QM<;ECU^`QU9!AJlNpY?=buBX0XBP+W>TTZO^}zOuzo(r5q~Depzchn`2goJe z(G410zYKP_iQy_E!L*@|EuApvk8Vjz!R?rV9hQg5F?E)fmsfO16Ej1nTW$_&sag@g zDjQ}3%z12=gEO}!lk)b^f+LOYDfgZgkH7~fx&!LDkYF4GlR0t4%VhS6{zI9cyO$uT zU|lr@Y~;V!*QcB2;jEs!(-)jB#L6da~t%BX&)vC0;n3M-!eRgc7}vxL7t z7SiQ##GLwzP_n+X*s2^#cw4T6h#jB+tYW}cwmq?XS_BSdy@V4<^bCq z^NnSOXAQ}~%e^=`wMd*N77j~LqpW#+z_JaCE_Y{V*dLT$_$kHliZEG1JR0`n#{(Jc z0Zg-!f&qJyiM%a4ApuDfW_mKcj2b*9Bc~IS2;~aSghIV3$`8k~;42#1;mA$pijaD% zd7b8Xizs|2d{=`=DTE*rGB5f&v;~%8s$L--ALLjy)>Z?+E#^hXTK zuZB-OhU2!l7{~w$Y=hFHgr$m_xTWfc&@&UEyNzH86^?l&`rqNuEwKNPb>1+3`O_uY z{X+5jsTpdkmuM%Xk#YyH%CQPxK1aby3Bz7l&fsb@cFhpFwvBCJL`A`80)MZzf#TmL zC~6I-%4^9DdR0nx2hygxvR}fUA;X~yzis~0G+uS@TjPajuFr2s!AXv)$=KIn8%z0Q=JE=o z)2N;a9%PKU0jES$s796n*PjE|1S{U=v*%>P-;^l>!$&wd!^;rWEe}DNQ?1itzT@iaxz~L&T$A zKp!EusM#<4*-XMPzerRd z>Q^Dq?ip?a{&u9a(-$(71bLys?|Z5O9~BFg9-rLFnr%m9r#E+oYs=?kt9H+;QuzJy z?_vil8_fTqdC!}@JTxxX{Sd!@dJmH7cTcvlb?QWe*ZDXk z=~ALS$7IS#hAf>|YV?5VFKUtj{Y>W0@Zp`paGKb4f7>FE5h$09ouoY?_8}@lwE?4H zMN9>rCLbdGeNf*)_i4D%Wa{%utz*y+1|It*B07q!av!~XM7{kI{j0%wTGP~DbGXo; zzoJ8JsT#Da{S7MUTe#8mP*C6HzrL5ch5wTn_rg0bU2Ah+i7$|P`Z={_LZ&WMWa?nV ztl!z2!lDPIK9BspWt5qg6c?+~ISaO9o*s_X5!L;u|F_vYq#(<4Xc|$eyd*04U@jjf zSm|RIoGlndsNf!=i#JvW`a&-ek(s=15b|`_=y~*6yWS>(SwC4;rs*>v?MtOUFpZ?| zx2T#Wy#`59_#a_-G4A1HRFA)C+Z<$(uIhQf9x9G0*@!N=LnjqvMI0y$=}s#JI&4jfz5 zpc7QfZzfbm;;X8=okqF^35xE_(uDEs*riS(Os4tJs_fDj;@cesim(`{+6Zxadg_IJ z(-KX2PkyX*amrozh zzJ)F0sO1`6{^AkRpB3^It*W2ru>FaoHB6{zTztOR>tdf!^^!L>P%X7xM6bM%#w>0n zX5VXy;|fHmXz$S~~^dR6CyTvKwA0i15@+#8?Jw zu3EnHZuW*iSdU??-Id6fyF0l9>!G{S7>T9j86$;hM z74v#+71(B5U&NTLY%FcdggUJ=u0q=w#JHxvAK{l-NEU5LR)T5<)cKhi^Hg$^=@X3W zp=ruG2Vhl|!X|{@X2*gM&`5&oJSO2BHCl{{gx()_?8a+qYRq#2LcY@`K$RA59M`Y5 z?m>6F6s+Cfuh{?hkI!P!*YnNkc)n&le~?XKsSBl+Jsgh=N5mLtD9S8?82G$RGY7^F zvK~@IzubiBfL}cKPu089YjZy^CGpSC*Vo?WLsF80PG$c}lm7Zi1T&lGp; z$lhU2B*+-bI68MSQC61aMFrEmu`%{Y{?NVjc3u(J#CnOm@UH3xZa)ieMpKdCbRl7I z(~}*i`Zexvv|Ibs<~$FYGnLS-MKW+y8SOAsc-&%+0>Y1p(a8}7jKl8TFvm(q$FJ3% zO;E^0L41`c{-p>gXD#N_HfPJ-02Q9Q?-!(ZLGO*53XPiuGL(Hl={Mzxj_EjjQp!NQ z=rrC9eha_1%k~C6*2eLC3T<6o^Ao6ooS#giIlfS2Ih?i5STBmd!Ybick z<7LimR6)x4&C)cBgiO0VsB{kt#O1B?^17INxA&bbE%=n19QJ?RZ&F@_L=&NCwc0%I ztZ0Q_{!+$ma;O@F0C{Ez-I!TOqo*Dq4ynQXMb~H0zM^zE>KHVYBPk`BU6DiL2|TR6)D&Y;lTSDavfXp%$pL*NA1fZ*kA8^<&`OV~OF5zv_7*u3 z7|)z~-=y7rayQVpUwMYVo=>w~X-ewLVJwMt2%_)a494d^;~L+6PPLoD=pE8g^!TCD zBJGk`tT`cSbaz`kbvzI6CJ`;Ik7iqa+p!0@NPUdRoet zf12Wbc<16XYCqIW=JrC=G|bfegEiC|NzD524z56A@w4v?T8QyCwRlny5-i?gs6WSO z=dvKZdinh|SlZ8DW-Gr+_OSPKZXRy_^zB*94$3EIBa?e-F~55LxI$YvDAxUsOhKZPp^0~L)8 znTEQrj~QAD&ITFK0TpgklY23T$u%@0R1?8>d3!X|jPgFPZal93N3dl<=&B#0_o3_4 z{OYqBMbMC$_(eiVO?jkOxDh4KXf_uBgAmdB%2<5^};G#|7 zCH5k{>8>84Iopylvt3FcN~>=19y={|l+brxfQ%=d+?GT?@0VxS>xMrQO-~e%$Hn<@ z-*|yCe0C8)7bA-f#LfeyhFI%e&sJn;!h$`Rr$)1q=Sn?Q~(o)ZSKVB3Sz(oEPR1b60}`QP7un0R$j6Ff1^pcY%~N_YWHj zuq?SntgOx@C{*|{Nt_nrX%Y;n`_lVFtAjg!9p{2%W%Zv`o=VGF;uVzBGTNDl zX>7k%T5HdCcOHBXmvhaL3w0)=?7xfZpyXmlcY?h$+tE4S^>6yMZ!cP>hfAf|mJwP$ zmQ_{N^u@5HjD^1TIT`J_@q*_;N>Dy-T zair0MI)plk3!7HD-tTJ8AgK&IY)rr}ey{r_^X$h;@aPe96CR%xA<}9q?{3nJsTg1U zlwXwT*6SI%?5m_l-{1clazZO(7h013WIuL@Yy~!qmwC5pZBM}Z82@xgYqTIY+VmB0 zdCVgY!gPD>cPxoYNX$0o=H^y|(5y}tYTTDWj1g36Q6QSLQa;fyuX(kApjQTp#NN(C z;swyErx*#99ZSHKqmHDMVS`S4F#Jrsrhq53dlgEDTXn(EU~$cjQ;0>}m8nqtQKKD8 z-I>3j07)q<-sr(=D~<*p{Mn~!KXMn4&h|3{xrD3Fo|LSboD_Y;Z zr(~`IPk@~wNp8c0aAXU{t^65nWl0lKO4{Og%lqD)inAwOYn!DJxr$0uZL4{rXpB$d z*9qx?bxdj!(37CHF-jtFyaZxhP9DTIaxSdj?0D)!vC6zdW~cpoI0EyY*rC6=d6?`X z?y>0Q?-~eHZ(Av*o=*6RoHV?=o9}=*e=EH&5@Bssm|}jgyH(~6BkMGN?WP+ zks^k>2%xO&A~^T0c7pU~&N@a;OyqNddn1P*W_cs~XKepwZ*{4D;U}Brd&owSlGfAa zVjvR$YW;<_0LE$&F_H|JM~dHm#UZ4+)6!Gx=UKomz)ZHDfYuSYbeNSaF|+yNK!&Qs zp<5jZ{b~E(FdHCn@Rb?YN4jg8!b>kI<8aVd&T@Z$h50MPv zO=Sz10qQUfe?GN>w7jDSI4?L$T)h{#9&pF%q4)gmD)d|UHtLL#t}l176qmc+RzAp; z25>~57_df<;K>-)*=J*E6|(;LyxcFX`*_)2tPAmkvaKrUX`L?C^})3-ew#!=2bL+q zi_UtB$lMa|Q;y9*#y1!fYRRbvg^%}OAtLSJr3n!ls;#mm_czMf4A|T8*j0iP0P4H{ zJ1%Xlqi4n_4V@1ynS{3UmH+1?!VdQ5tgR?NpEc&!eYF={k_Vyp)0O#}#ENe(I02=* z1T7CuJ|dUa8}GxSkV+oLeTgjp(vVRKjD}jt&gUBnjJr8kml;ZLsXJ>wC5N5MTpWDR z4foaBhSuV|r@=I^0TJl)uyS8a{oVIHN@Vs)n9P}tO@S?N>fz{!rqaWEcw(Z7!cO^f z0uJE@^P)u}aO{PFi~;>Ew{!T5wfI+$2mO_^ovsFL*@Z&xJ2@>M{OHm_ey_s-K)97o z*`YojHeMY)-b)!9lZox+>u&B|kgF5l_R^HheU|d&WE9diSC9ksA-)9VAwT-%+IU=gl1`mK!(xft zYU4WjRAH_mVP&)vvv*{aEuQ_V2f@!3yk2D?LGLsjgf48cLb_`AVBbPYT)`Xw0&g&g zTK!c}WZdx)kD-^rn#X+j z;m})oxLfy9prl%S-Gu5H#DAqJjP-8tY{#=@dIGNZe{?PEBy*|9B#WmZP}YztU6AR? z#b~{&_V3}`)!S%6=zI)v3|5NnS??1@iD@=^BnNOn*L;KQwkN5gvHj5*#30Rx%L?(2(0Ou7Nx`}Hy6z|^36dq% z>NMsCFxxPGMb;71nif)VVH*6!{u)j1X1eICn5WA9;;7Sl8 zYv8gar9xM5#(WR8Sm&D%2|>*yY+_o-sG9{XPVt z0Kxred!)5ZBpw&=$A{wt=Ce9(RO2uD<R&47{N&{3U@qy+@PW%)7_o2m>snK1wocA&yED0d@=Y6eeWw~o1nj{K)2UQ;^=8X`RfJ!PHFbLh4>H=g1+QE77A0 zM_Lj0=^7XfYufM~8Vkxm;k8?}Xv^1CN)b7R$<8Fz0~%{6>6s zeEvMPPO7h-ik1$M`29<=qfsN7kTKdjILw3s8S#Yxz(zCdCt+}R_X6x*CqmG%f3O@1 z!#wXrlSDOQbrC3!houaFLPYhZqt27BJ9|(=bdKP>2_|SzL~GX%!uQV8h2e!M;f?*M z=+fPc7WbyEN%S<4S%gkZjDeeGJ;}(JvZs?oMd7-S=bDe->+5=Or^3yeKC6v&j`?uQdLyt{d%umSAjhExw7MfCw}{V)kp}2{Uk7785N_!NP_q@ z(c24NayD`gbN$?@FK9R^fKiSnw97fp8TXS7?}C(Svxzvho`w(v)o$!FG^Tb+!_FxQ zIhZ|JH`Q-S-_F%-?@yXm{`v`%pWd83y@=mWk2*J=cQOSV$zCQ;IGQIK(n`irWIah} ziz$bC%e>>rI`wS(j*%{9Rafs=+m2plZZSVC)gS0sT)e$J?8w}v-`(GRF0;($RQQ5q z30c3K_X>`;)xYp9)!^z}Tl?IeogXK1_!5)J(B3b|y}r|^I}gEP4;%&g9dlcuAEn62 z_kIEdTU)gTkN%@hT+a*C|LZDokSvhHg<@qjd9~~!a#suS{OL&q24bl|S^IxFdZ|Uj z!4L4q@(1{0<{b%Et9(!$ohZbNEwRawu?K2Zk1wt((%MeEBen4?nlOvY|M7@5EmqUe z#5p&IYngAR8f_FwGRkZ$)^J3^{4fB@5n`@<6G!7ppyR;6_E(_Mgeqzs*!HIjAQt{e z8{gLX7jUXf%_3$5-3^)mUx4qp{5w^L8Z_H}=1-uJ2*Vg3l{fq;)^>L1_xShcRYf#@ zY~cQp)3nhF^}KeMl{M}eej%a|5DOqE>RSz$o?(FR3vUps!MldM0)@X#9!+6V%*AY%s~e#g{JFGora+QGv!%nUGD#Qw=DHqekCqodg4iWV1b|7BiN+VOQV094sI4;H*>(_}9T zr2ayZ&ldEj9>8J=EW$t}GxB=qyXK!V3Y*Yx096zieSe-J0wfZ^@Cqa8?s4Q|PkKvu zu>avOnh);rnZsWtk}N86k|W=%?%}pR%iz=Q5H>lXJJ9OB`PYs#N(OhXHG4>uSNI%= zr4)Cd*bU@>5VmN~iYMA6KG6%`h;$+rzHDc0ce->bZP(NZSbaJE7ry zPRsN&BVxR%h5;v_fX@nlm(6OuYH1%E%lM{8$aiB9nUAMC8vB_sz^R#3yXv7V<*o~x z`gtBCxuW7|KWMPqRZ*)Yt68BA95o~C{KCg?DkynAb2;!&E{XfBVm#YuTU~FfeQZk& zx=pFV4=Ka<*UQJ)>2b24Rx(&nBLHoaXZ#<{`OD0C1022wd&GNK zU=x581%oAL#mTjQ3)-NL21ZD-!svXcfCfN}Ss%+q3?3GkME+3d~3A(V(zf)kiW>y^wMEK^kcht@xhHFJj2>_@l7a94oK{_u||749dU8&*=6-XFr9CAlNI-~ z+ADV8Z2DvTwVt!K08BVz=|OpjWA84tZ6CW*!;TWq1X5A-Qu3r*zRNOO$=o&*^gpQc4o;e8)E~FH;9=scDRC)$X+eU^aDKx|3q0A* zNc<$&KYDI0B|1xVcWR~ZG>Nk;?F^uG;qIoe;g9XRnO_1fzs9FX! zW9AzD) zI1)QpD@=OYoyb@xqHWA@Y*slE*vN6yaG^m?)Oa9r|5ADgVA^eWRh1BJ&cP|cd&{g$ z=MGn=o+-mD1OVCtBIvYvj}xd*Kvaj9vkTf6N5{`f$x<@)DzU86*&(PrhI8CAjc%Hu zRhl`54YFpHcJzDyB*_G@eTfD=(mKi3$hhmRtwp8SH)mUAdKOjn=YAR$Q9njr1jhB) z`AnuLzXF-wxw^y4v&?rMZ>R^k z1QMFw9^Ab%*r1=x6i!<-LSxWE&Ju-~AzyAd0*)MW z_qsqBJGAWL?=1gHKUv%OYo@VVr-nCr>^-w}!J^VgD>~>JSK0cI*{rxJXj@W?mc#tO z|B*64hl~e0-TgT>nh_N^FqT@~!gcNdb%6hTdsH8N;A|oEmV684Z&x1WRzl|~@;qhT z2Nuxd2H zzXM#hLZl_V%L&bw#`!tOBQb|uxYxkj z;5{dcbLu{$Agz=LV-6W3#IzO>xVDnr-PA#{$2|_$UHS&OfDQjt|BRs;9i>JvRk|;T z5z-dqJobVrI%{uVg{ivOygHa?;gZLAb)wI`QscYwFVm`-OfZcXL)hzXgdf%rCGWNb zVmrb}#lgVdiLv?D0#)>g00Gb&%S7eIWmzV3y<>?c3DB`wnFh;YN!SuyR@6HW`o2Vw zzw8l;XHf!JQj+eVLS2_rs`wDASn5NmB`l(%cRIOjK@>p}(`=&bfFu`Pao*9w|6u`4 zC{4N)E8dKzDmuJtPeeQ2kz@rUya}rxHCKVk65ZS-k7$p;$$XYU$=85W)GbzZx!AFo1bE^P0Q zQxSrOmjmYsg@ERlrb7JPa53)`^0sbUbekc$i0W_9h0}R+U&!WJio4Okh}D|1!9vRX zd7)!6Ug3#Gk6|WXkkX>`W!074Bi!-tkAqfDMmWT&1Y1h)U@AXthIqctrV$J9S(%Sd zEDcu}p5#Vq34clxOp}1a4+6$z*6uOh*e)UKY|V!lkcQtCj8^>m_RAyskpa&HuF>0dv7GR46g=#Q@odAlWym9I$v!5C{|RIs3~)#X1+Pe9 zMjfA>IMZ|1FCt%`;0ajjctQ6(;0w4fWANoR7FQ6v#g+;L(0R6MO95Ot_vTaBZA=F+ zxs1vI%7z)U>8d=N<0@b3z@NM6z!Q9_LhykVFz@A7v!rl;BZzUR?V+b&Q`T&d{ORi2 zVFB>6bb?~(li}MYe`}^oD4JOYARVb02LW^yo3aTEZf;4ozN7Q7Mk5yW{7KYsn2eIGZD$=O-bp3S78qRQhK99-@No^o)PNrUww%iOz zX>RlOH1YRmGx|c!{ZUqux<%nnRqo|h6rD|=B9nQOQg_C8&g6X){1_u%)zaW$!QNF^ zP*K!E1a7IpTgMun17B6mE&pLXnlJCAfZA4htS&m(&FsBJ$pGMvVm3b&bMr-xRXOK+ zWe4(5BrZY2HOgQ<(v#XjFo88)MPrGZX&yaZ-LfhBE#goaq4cu(um0m1aI~k=>!92V zpE|`hfqBM*{>RQq?A&ZvX4E~SXh=>8sfP*e!PF{SE|GXDUstYDo+s#bcqsR4b{Q6} z!dHL2T@Wx#{*eL;pv2i$Hl}tRm(6IZ^1TF^4Dohu>!a{KYsRbQO6Qn8Lbyy00%Wc= z;4HY?qdxlP-7kE(YY3o=+{FV4*0Q$l`@G%jLgaQ|-8F~8i&Ec`k5hX+-wz6mJ?riD z|Ar!LQG|?P=n5>5{RuJnZ%BE^-|$xVWq}r|&a*qZn!0m;It_*eLy0NkRbdIcL^UM< z(9!sFWIy47G`L;&z3;_s@9qK1Xb(RbE~Tq|Rfea!wj6W&iX*q|HR+ zjXH4E5I_HyBqU4}}n8k!-GQE5B01+ehzrSX-j|Xji-bCJcTk9&;-^91*JmP;nh<)?ydfLyl z6XM|SbuD1YnBIvKfnu~sm$d|P{D2a|*gFmke0FomP5k}mvi@U)^kV3>%D;4aT6uxi z4kg?P7bV(6-B?Amw|Gu+l}yfweM>uE?I0~g*W%M^5D22NTd z`t(bEfaV`qQx(Ojxgaj7by!h4MfQd+G!ymj21(YiXNW0)aODoTF4YfWVp;}M`+sOe zSq(u5MgX&t)7y|A^Sl|7w~a;>6RZtm6(cq`#ojCJF?9_jR}QVnCU7`|jHa=rzHAAq z66Ajhh$brq<8!yRgq6EcF?u^mbGyM{j*3c4gRFgkGPHtzZhZx=wEPdZC#w?fCYPmt z3x0ro=pDMeHZD`y6n%fO87-3t^IS@=TV)0P@89K`j8!=e3>21Xs%Bb_m;ilYGLqAR z*;zh+)e*!B84ni+l)(!BQaZcT*amDB>23S=eYR?-fow*TTG}tl{q52T(Pvy-=e=%^ zH5MbV)+-J={p zN?V2KMTHVC1OAa)t@s6#oB;Onx!Y1tkyn~P+)sJ&_vfTxXJ;Zk-hqybA#FNp$frEd zK86ZB29(a?HX|%o%Ee_hC~U0&cinSLf$6gl(&EMPhUOkHdP;f`JN130hL0~Oi60$r z@L_=SWZ(DL^>bBn*^%_i&WSxVumg(n9_;F-3$v+b{_+0t)^_IYQqp#Cyk2ow@SKeR z4#ngpJtcMdq{R;Ir;!iHp>I5lV%^S=VxVWv7fErdL2Wzusx{S6aH4;V$MpX0%t$6P zq@Xx}XvGHeC}i%H=7q+dA}lZ?_JI%*2iWFt`)RTx%ZLj{E`!-m0|8jx5P~DkWLGGAqUSb{f^|2WdNWC!K(UpCO(E7kx z{ZS^GRQ}+_crmMmH$<_cx0Mt;owT-^(!TxVEGfN$;#jqwSA~Gw;gP`Ra+r)?*b$(G4>z z=$-JejW5yg5iC-G09aT{M~`R`C4^l2_AdG^jz6#4B<{n0pTzZ+e+UV&zwBPj++W$j zs@F6wNo(-RMoxxVQ4zh|fA-oQCV*U!qJyP%h9-XpK+a)AEWkkb=1AqLepT1gwyz?M zPxc8Ff&FLyq+bt9oaQzU=W(_l0WfaotD4atCoGZEDP!7MKcB?Wg@CYp?3|EY_{sG^ znD*)}?)chy*p&#%jl%(?dM{9{gMQ|n^W^dVQ(*ISECB(53)y#T>nIqo3h7WBDedwa z^@aF zSrpBg5Y0Ak$9Z89-(|Gyuf}I*OY6~baOHz5f)N1P^Z#j zUv)%@8RT^^>R0#Jn z|8k+9{U_i^W^`D`*y9M0bL5XzkGT5Kkk2jor8CK<+aq|nUaBhCB2dB~UIK2f(N2{G zG(T-KCj%$yFCUTiWb^ZHQQp*3RI$cSwfx@$OrWP*shg~qJmNo?-N+eQTCnc_{8%+4 zhAgvTfh|I>h9FEICxOQ=-e|`vcgI}EX$MsNE8|hLEx#dM*cx!(mY_1nRaGu;;QUl4 ze5Kd#U(Qc6e)lgq35PKd7ce<$#<2D%isjEe9O+ZdEzWY;=uLMj(%6y`IOdXe;WXPR zlxSO?D>L>rHMBd7|HjA@arO8c>pGbZz$z%rJ`5B>UUd3MVOll3`RPGnOV`lv?IT)O zKx#!Ivs_Xc&vg+QaM(@F^M0M$wc>T*8=kp|Dd2S;jE&P<>t!JDP;gdz+SrB&j*TA~ zB}E5H6BxUg%tF9pCid-DpBspTwSbZ>Pea zj+hl-<6;uapFuug^FXV9wg%~EkaQ-E1S=^3<&mvNZ}v~i5K7MC!^Y;T83Bm6{_xgv z#tFj5I-oTzKIw8?VIRYE`$594*131WxMw{-nbn1|kX>6<8K=w*G>EhLvF?0fxv6>e zjXSS#L8Kvb@C~B9nXlMjhPRGA-zBE#zsxkpX5LQL{b#Ibai5RiId~FHoCRC2cg!^E ztA5_Nf2X0gMYRMXg(vh>s)So7tylAtA-7q$*({rdN!fx6R;pk3jIEzGcVID8+ghg7 z1nUN_7v?kOb~QiEj{upXnmWuxK87tJLrzg!&n;r_AZfWzK<4!5K<1}cr1d9?ZeVc} z9@#9@`xp8{PI}AZeA!kBkJ)XK=N)I|K)G&TAI6zA*5~w7?3Qmaec=S%LYIf+(+AC` z-oE3)f{x<^$TPNmkrX7aqi1zPQ>UY;qnE=0p1X)-}nv zZ}ST+!WQkrN@;N6Elzt3r!kano84lxS}bf`H>oiU}!}>xtNY;0#cPWY4FtuXe-B#6;{xmawl@tRUf1T{Ble?w1 zjr`R#3`uaAy3qe#Z>ZL6TaGs1&YO_n0*&)FXwPuti3X<X7)>n?yym|gad$H1uLDeC+%ftS z_l8%6Rh1Zzd$#VM{w*6tWZ(r!0imr~n(iGJx!FXH4?6`g)i$01{!7R%3n?WaR`>$! zzc6mWyuV-)b<9&FvB}6zCF_{r9q^B7lao@xKC=c(uZs<+_-LYBPQm*bX`idc$gNv! z+@5XPhy{F>mIaCp6io}DQq7Ek^h8hwMC!9Gi-p+xDH`%(byZN|T5U8|vd4uHiO5lu z$QnU3ME5pkZnH&7L`b{AP3$YBk)<=GO~2u zTd1XV|EtJcdQ@93qb(GexK*%(%6G2(=Ng>bGr>Mmx@o~6>TkjO`Rh+ zvq3DRN%|Xb9fJPBf7H3bg&D{z1NHT8@Bb=&en0$vd&3f4(_5|mp{^;$W79d!H#z~6 zWS3p*4D>k5B^eyD|C^FLV6$`l%XR~KvAF=cmYvt&z6f?>qL1uBk?4w z(kSu7#bEpo0avq(zu7bQspu?Aq#~{TQ3PqhQ!?f3KiQR2vFgnm2+h_jlYE;;eWObe%iJd`{EDnSBkJ;l?H;Q zjrzJah@`fkc8!$^nQw=Kd-i(E|JynCKLZY(Hp*!4L1ATGDPi}Z>oKOMsiRAJm<}6D z${?xD&-(|N)eC{Ow_PT7Wp%w0C`Z1h6faAzzJi$jWlu3~MbX!}*GhK8L6`nOtaCNT zyEyB+1b#}0^$!O08|awYpKB{?DvOv}pF=GKKcIXAFsoP-MhahP2=%LNP7(dl*k$%l zUp2qY?)culhnb(+M#uG5e$v)dH`2afY#@$HDiBGsT>=6}wtM*HfQ4*!!PAB5^1zR) zr14Gn8d*BYZ9b4NkH;vC7tP zCtwL09}B{wo|qbTZn&<$te+^bcc050d=-I#?0@$&nGE0n%ouzQ1XoV@hoEI|g3v|8 z^T=t^cBegLgKt>;BD9m^{Fb^40@AwUx*7ypjOvwtUU=-fUF~Bar}HMix@~&8CO{ch zEgV;^x)9l%<$3%X-zIO8{sVOR$R8R z+@@98Py(08K)R4E$QYWfs+VGJ^t9U4Q|V}$p_(LHC_p$Fpy6<98N;ZnP8I>|b0yxO z=@r*`V?7-5v~u2=x-$y^1%8A31Mt3O{L-O$(g0;`Nm^SVMbY?y5q}GqfOn+)hbF(6 zFd_}xcVIIUs=U%nl3l#a249@UmllL}r`+ky*v$^Uh}kCLyA6)&f8f4AtbBHfh=x*zVc&N<>8!I5 zLv>+^(v0mY5ad|uTd8Y%2?mMkSz(Gb(n^EK>*{9FZUx2=pt}3bv4^1&ok;uF;w8>l z;ne{;aAXztED%T*LGG=9yOwRUgeYXNaid;xVY`pD!3(JPOZfER2GDKjyGHi6_cU%? zES!Jdm?y`02SDGG%YWE8K0}1rKy-~Knlq`4u zMdm7!VaCO6!WFjJ)!(|x|x@3Hm;$1RB21|Z8tG4X-gT6PM4@xUeR3b&8o6I zJ1Ov6Gk2!KO7u%+Z7JJXg)hXwjeEoo65l{jd8Wj?(#m#tasrQaJ|D-OmX)}%FTg<= zn|VkVeqmz6oXD0se5G7zbFaz%re9O?(kk@wufDzZ=b##|p>KBHSv%aQ~Gc9hJ5Y+r|(bKS9vQJ{r~MPD{txaR{a?&%#mYxlN9w@6V&puban zl5>|gCfRWv#87XM^HJ2*Y5T^{M+jMuzPkCB?mFhQXM4vCoVC@%e|`(_`0kU}QI+j7 zwg#`8WTdf=44s%v3>Y0QnshEU(Xx}Jl%c)8Y0{_7eI;4bg9Y2w8~XfbNF$K{I-EHE zpE|d{u1UKrC@c*rl?PJqXc*4oa)Zy~8_{y24p933n{1rk_z?7UE0r1=-d-vz2e{Y< zN50_7dg1ICAy;cuU&J-^^lOcRHR+N;g}%okvKmjGDKcT?p-Xljy<45nwC@9?_BCoD zZrN$Qm8GU8cu?O`@qGKtnOKr&d)Fx5qB`D99vQty4DskE3!7k;V}52j@7J&6Ytj() zn=u{V7ZX5Dsm4*gjD)G)6%Q|& zn^R4PJm}jpDQGYN09y$^N6PEyuE~R|R?>A|HIGCV>CM-d_@g!PN^E=WGb+xd)Ag?O z%O!+aGT9@(`dYFI(_O9GmIb1KF^0J7W8VrIm6u+LvIP}i1XpcxJ8#aazrEi0my)TA zoI-B7xg5pxkg1tZ|iJ^WTG0~C-mADUE*D!CQW7~)){NM8=S|q zVEY%g27g1gcU8YXFV{B*|Mhebe^$UTbw)d$Ev%1cP97~9D>OL&paZz-9n0%U%G9+P>kmX zao$f2HD~A%)Suvu_F);VebTnOj~4oqKi{~aZq2wLVS}9k()1SvwX~Hpo^Z%883`$L z*QWUsJ9l)9RW~(g`WogZFU$gfMeJ@=Bhk?422p_Aq`y>_&|s`wS|~TsSr-QOVTJq} z*XPq(U4QDi*;!fLJ&g|yp6CQ9LRt_eQQTHeynRDR^1PC&K}CvGSrZ+Zby|yPC5II^ zjN{R#Zcd#Q3dF%MV%bP2CNkuv4nWd0UJ+ZCq9>@n9+9>W7y43egWm#xpKqE7ITgs`pU+TnJ2E*cLuvd<-_0l9dMqBokRD|F$X3%(yBU9~d+nIM4Po~dc<+ASo3u8GP@T5fF(ICW)3+#jZc z-b!WF7o)YxJ%bA8uk~YP8XvuffPl97n`d~iOkGCbv=NVgk@#OGEwl{9qi^VuBsGr+ zNg1dpC{(Mm0V*<=6!5?SQ2 zQxt6f8}5{R-*r0_C*P$o9tz1Web9)ifV-MAB^@NYSf5^_R{q;iyyxAUHxCAsy7A&d zB)ARVHfD%}O|#^GOLJqrNK&Fn-m|y``%eVVb~W}E_G2J970ANYy-mJL`rPMb^!t=X z>J=+b68IWci^l?@>7t|NxX_czQd*h(Gizqpm`94iFZD z0@n@Ws;;T-M17aNF@rZlNNI~^UeYhi;_Qd=K}>l7W8Xbz zmYn*n^CMw}Tj$r*w^#pbT&pQH4ms2gt~8_5izoR&tKa(5!B3X>LsB(hEyos%0eSgnCG?BMtxwVNnY@~qES?a0 z_)(VCM959kM5evF>G!+G2}9sh#fz(w+mUz~(};DiEB*Vvp8b~O(Bwmpk{VUV4eog2 zxF$;Oiq=ZDVM==X(W;cSl~q+|Ckg0Al?|G}@r7ZKyL=HU1De-#A7vBsu!On6u)l77 zwsQpK3>l+{E9gxm1d0bbZ)%NKcDLE`Td{svoda?HWodT%FC${{#CaiMESHq zvhm;8fXWzInPKtSBChV-TcSm!+cSI({Z?UJ2-yO!GIs8u0_H|l2>68TnbzoS6g4(1 z{Z*{61s|%ykV0<&!##EKxt1H|Ri}j~7Du_ib+Yq+vGrC#ZE$V4c7j83DOS9=ySo&p z!QG{}yO#pNTU?41cPS8DiWYYZTHM`r=l%ZqXZFFK$>cD@0rSjS>$$J{($`3~Py)l< zcHfpd`hT<|sExY>AEsuYZgFTmd?s@te_TUglib4N$T!Wp@#+W8|s!XPn5KoVdQ)p3$p=#*P)-*XZFz z;}9RiBB3vkY%93mN08^Mt(R_BB>SbWZk%0Na$Cfbw{hPfCEV0n!QUS9j^5A;hd&|D zn--ERfkT{nR*jrT*wT)Zxbt>)r55l>YYcc6ix|ewzC#QwvDL#A~ zN_Scinyw0~z0IzAnSb}4LqKfPP4~M}!w6iuCP8m)nOvnA>eNE2cENg*+(S=$=z9VA zdEU8)AO#Rl+LZl122;uV8;nrZKbbYW9z&uhgQ;($Y$;#<yj}M3^+yt6pJ(UwO7x&IudECQ1)oixtCA;fM|Xqv6;~z;h)Z$4n)4C5A%z7$vt@(UGqPi;P`+Ak7iU%5$SL=UsdRM zyCJ=N5{ld;yxQYS$uu0WsM;k4x8>Y*@_J80q*UTKvO5OJc{Xr}b`AcI50C*sM<8dcIsc0G> z!Vo2C1CSA{b6fn(ty2Sg{HSjv7jSfpRNb1MjY^eCn-hI$u6pfyv-V}ySwxpmpD;~l zu%r@p3+NGhe&T%cnQ%qFb&I`0^FJK2d-{V_QT3Y|Q74m=e9~f^R^rEHk9j?%ZhSw^ zM<5@U*vilRK$8H0X$!tJr6}2{#A2(@E)GKIS@`I?t}E38pUiKc_|>3iZys>2_Tp3$@t++(4i-mQQF<4s-r)gI^4PHREo(>!8 zB?X#C&op6*<^Di+vSv9lfonmWX-ta`C*e206TW=OlFvH%k)5z;ksx}C9&sjwof6=D z;hERC&i;8=T;NGaOQxgVW@2%wVDQ*ImLt@QtT{=gdqBf-f=dQMvGl<4Z-OF15Hgy| zX5h3GLRQ9M-0)XLR_F`vl-6pAoY^xtQ);JskM0Z@~WD^V2Lj;`5LsKNE7dsn+scyby(3X? z`lTK@qf0+19;Ui{t1#pqg{guqCr>XB+o#Qy#^S znjn5c;S+uTZxmoICO4-t$2XK8Baj-d<=>2!N+eR+7)sHmrnN19>sP#I`aUKuCjm%o zKX6)e982S*Q%^A>1LTG696q996V#39n0p;xv7tY!3NP#1?fH#J*oj~lt^EFe;sNz> zH2Z7pPitB8nzf|%>Yw{^r*;R|xwkz1h_u|<0nPENh8wUH3ycuq5PwL;HP~)9OpEtk z%qY3n8qlLR-{V4jwx#Ai%+>GBq`%y~WkK$+RQ1`rk3X`1Qsm~YWXSrGKwRJK zI-zgxT|(9`%b$g0U;whms$_@Q1k2aP49=#7`ASK+%Z!fPb9nhbP~N>qEK1M$X+4_v zDSVlqpZ5Av+Ut7J^$CA|FBE3G`};4fo#kK`QKc~k`w`mJZY}P2@(B}+o6b7r)=_w{ zzuz!ZGI5?2cAIv$UQhE$eD9v1aHn}+bV4a-uc|f=yPJ5yVxVj#xADEkY|DWw`B)7( zcsQ&~M=xAJe3YT?M@KQNUG|;Kh)BX3)W8`i(*Yx4TVQm+%f6HT5&5tFnxw1Zz}Fx@ zVTt7NowKo^?0{F;<+TPW;D78C>>G+Hn&HymiytTujg#ggx`ieOUhsH6^}F$#2bH+rLsB3 zC6W5xh|_09sq-=J>BUw5i53VGf7#T`KkkVk+XFua2EKUh9{YOyP=%hZQa}gW#Cx;~ zKDh3=`6t(|O^Dt7WHo@GL(l+9ul_K+~XH`6w_#I|nXWo&xKJ_Pg89BTVs z`ns=cOu4y(!YfRehT`NmhpVa_i9Vxb=88v(4J&v=RZk)hk{y|%4qPYFDjCXjq%f0K zLEbNYue%hF}KDESR_TqL-QFZ+(_{;nR?YS(!Y|)@;AB@TALzw z%d~QQ*<)7_w(IdTdyMVQXjFTCLcjMipu&W$F1XI$8uc!Ifc@46<%I_L zPB92aAP;}rp)PUQc&HUmX zt04Ciz`&WmE%wROFCO8utK<9Mp{J!7x5XO}e)Mi3%j|t8PY6{ilrwJsF8v0#%EgXu zx!C-mR@yY~M=C&MPBV{Q>nk9DQ<+U>jJbTeD%KPDl7K07jHBZBE{Hc5=-X+O(iUV60=u0-50elk7-ZG zgk5Xzz!}cWsc7KxIwLim#Z1qK>SyzI@I(IZyYAn|2k{_?*^wP-Eu=!ms2vyRk<|z} zsx6F=Ye8T$;)~z#6%4E!B{2_qj;hSMG4GaTKy zg5Z3bq}r6tP1=K4p>xun#0~X}(xJ+Ss$d|^A*{xucXa~nwlif}?$#ptOT9i&n)hDu z+G?SrS2{o_$3!5_K2L0ysAVWySkxx?iPAdvgsdKq&>z4W38bE~QKT0#<|DDLMQ!sz zbuTW-?G(4y;^5R-u-P=ual|?qZBUe0yL1Z`$!zj4>O$aU)7c(!y*|f&RO>%cQTSBW zp|5Y?`mPKlng0pWkU zE}n@l?~PMCfGL0K_kj6|iaw!zMA|!lU-Y(QySz=40gStRH8`+T;i2Nl*bqGUD{9#j z`&>G@Ovlx{;M11BjiV(Rs503PEwi`fL~fz|X}5ovR+s!*OS0U7)A~J6^3w}OaAF19 zLyWaxP7TF$mVKZ^pX;$I@{2|`9-VJL*_A0yN`qOA~dj# z!68N4#%9e~1c{4<*xD`EZMGb~5GY6wMMmWoL-*}LX+HQgALA!VVqbg_j@H$+s{L~p zyMdX7=y621md(U#`iUTi-4kYZQ!o9*()6&D!P4h1YN8+~_72U^S6NsB3e_2thLXU7 zpQL9aoE8U@zK)r9y5r&>*KVAT=ps@~aVTjV$74Nt=VFa7OT@^W1bek)VC_d$lX|?u z-cNE4XG5q;G22Ul7@m-mPAUIu)cP?4P7>^3?co6}Dti8eNH5}Ve>Q7iVZo>M?Nzpm(d^(k0X&J2x z!FN?#_vh3P7Oi@DK3RB$MpVB%ec%KPXcjYbERde(7qs-?!#9GzqS%-?EF*^Ko;^6hh?Qm)%xLrJlj-Ji=N>88>H z_0iiv9-Bza!DDruT%&`trb?dt4XfLw7kg&M!Fd81cjktj3YriQa2*LDU2Fl1XzmS> zl1Ws0vq)0aQq{sY@e}%z07HdygN`kx*@+;{tf;-2w^@8vj9KY`+f>t^kKrw|{(+d3 zc9;NHu*B_h4u73ui$73EzR}Bhqhq^r`fiPh9|%K+xlGZgPz8mgY7AT?ti8HVl6^xnm`5n zz4{tT(2C`Z=%NerrJkOxoftWt!|i0T^S2eY)U_f}M*ABvNhA}2n3TA%Z}yrdpjl_x zR2))No-+~z>j+@z=ZFe(M)nBPTsYO>EQ#5wQ@rZmorA&8MAtW43qxA@f#l%(Pq1sI z#)5&**tR{Z)4CDw##5N{n?&Wa{TCTdBcZr4XCPQ{TN11FqW|nF_blZGMzmw-Ppf@= zj5@=HmHs3J#NMvPk$~P^9ba`ezee!pAv2Hi9*d>V~gu|v4Cg8 z-|lJbOVM^~A8BqMx3{Lj<+A%)`oz+sk{am-C}}aiuJG7Jq=ZOwaFk3wE4f`|v{|H` znWB*rxh-kX#ahEFl;u^PZqogrCrh>5mz^20MV2K+Foqt&k>_>|oxLj^0()6)DcblTR0lnZ0wRqE=~;)cVuS85uB@Ijy=h=K$TLu> zFKvn%BVgCMvZ`ZDHCHe^X4v*y&;(%3s3E93?KL!rUf)<Kp6-OK4N84Uk!wWhGEnk>_XryV5c^c&=C;Hr_I7QRaAPDGmydO{!8a1?*)D3xM zWQTPhP%<@lzP5_>s0Omv4*OT4>k{q|=ghZ=RNP zM@LsemWis8MiA}PSWmKFstoXs`b{W1sDSjk;_&_{OkSj1oXu=;`Pz}laI7{`zXSl_ zGBuN%Og(I5BXTx{@}U*u7dRvavkeXXju@t{sQ##K1|m7`*0k3piEw<6^l?BBo2?&Yz?i9G(9z*;Cp0qteYIXMpj_`Crv!wPNSzqsfCzV2yL*^gXy6z~5=ir{)HnT- zgCfyzm5bXBRYLtnJ`@aBs#&42qGU z**%)YdXXdEljUPP<$ZdOZMoGM!LwY;gfVXj5xqA}JxW-LW#*UJOw)4W(JnfpJ7+{p zYsc61nU0x$m&j=Ny9Ap?JlcQNz`4Wr>Gs5`^UP)ANuw=?3$a4C&8bR>_+TZH@lF8V z%G9)boa650B2GMi`SI5g^CA2HP=p(qP8LR1V1S}4wAu{|J){)ytrZ76j0i4wlhEX% zu}f?zIv8#+vV%F3)NGD#yipc8!lV76>W4oS9K6up?s%LCEHJh6v42YBq#8LLhSScTmzOOevSFvMMZw*7wP#t{fAM_fR@ z>BcrWo$IXM&)hS(C#?>QJhy*ySK$llnG%}->*F)u@m{YQ!BBS5zkzs^Of4n>-uC~V zvfXch3s{?uZ&nhTLfZ9f&sbg_1~WF1lMzB@KOjf%ZO>EzphjVeTCEx}c9OQPmuRbwKC{L6>X+A0&`x=$2Uw74s1hF9vYL&V*dV0e(Z%%2FffBE$A z?6n+!_oOHlkxWeko8^-2b4Dj0`bo_$M46b8<>B{-=M*lvQUA^;T(|Qb5h*m$B6@nQ zM^pRn3f7Yek6r%eKv6I=WT2iVie8rpjBl9Fe`;LsT(UWtxrF`QE;25tjgb;*p`nsb zE_d`OQ$gnRY9D&F&eB;2X`P?ou@>PA9hV`3gbk)2#wTWi4A~5y?7w6aJy{xByavO_ zUUEENh4Bp)i04n9uEM1JVr)v<)uOr!PMJR8W1`WJtwA-)mB1gLj|sn~(Q!a8uP(_L z8m-4j(EE`cPoSOvAA->Df_~CvGKopcu{^_4IHANdvr!V!rl_$m4}3Y~YV`*fn(=$y z9<4Ylmybf`^B%6FVqz|VLe z`(&EJ1on{)E=ROIHm~z|sK9VpNE#0ABPf88@DosryRJK&1yMp?NRYcu)6fteTXrdJ zk{@kje|t1viJ+d!(5elJ@ynUWP{mx{2sxQcI)A+N6I~_VozxhjtgY;}D1{ecetC-? zB#1Xt^+-xPJVH}NRGGS)6#Su9xf#iqfRYDDH^0Pd+jZYh`?TboS?S*j9WbBU2I|lv zm-oX8G2#KC4_`j7cJY`WX@{F7lQne=Cg=r%`sQIOurT3r*FXAZarV)I9Uc+ee8|#K zawz$B`HhIRv}sj~9)GPTyGag_W6g6~rbVpAY%<*0)W=VO_GkSVZq_}al;)e3@L=s^ zYnpF4&i3=$`n`!9TS8xtwtu?k;>(vIEjZ8_v2m$2!Tz5~#F<uzoUB}2m+aXFRr2}YF_J2=qdbdnuZK6J0!yBK!|o4w5&mUaXToT z8WhBy3Q1AZ2Nj_!?m-uOH%vS8g^=B6+dIZkaKpo|$zf{^ntDL2dbL zUCc3%y9lL%wL}KJ`M_)hPII-NRfbwN8iac{ewjJv8+n0e^ESTn@{pmCn$q3B*Vw z*JSux1j6>-d#g1QV8v6yJ2}UIH^qOk_)Y@)M^rmXp$uz%mzIt%Cq`aDcfhvRv(h4? zqdJd}GE@Xzdis*e$Eg#@bBc}8Z2M>HRwE~@CFfTGv*1UUKK<5Z$J(y3Nra|2`!RCg z<^l3xkBk(ZqHge4x=?!+9+?L6kWv>Sj_Af%)EB(yt;<95y*X7bE_uw-X`9~zpPaw; z-MM&dl;Z`=3%jjE-!F&CjWxzI`tMDM!h#_<*{3o3X4V;16=QWaIq^&5pY|%zAW~Mu z15L3K;#f?~KS$|<*J|ovohR`(TWlb@1*FHX?t?W&4A!|6lF3;Od-ZCDiIhz|5~p2n zLH?If^i!{T$OW_`h|%YJvkxzVPP}q>gXJO(Pj5)rJ6EZHW4MB1`YD*R;b;TB^cjhi z;0hxmBd4@l_NT+&5t_;wxqxo<4GhRAY3U?*kunTP7Ap1ZF));>sv+ZO(U(!pX?r2~ zw)x)*a67egQCG-P__IwS3Jt#G5>rbum90@T5`C|AK4+qNoKFr6asxC?P_=p3LfPPu zZenk7^=bxDP$I{bqj@z6|BROZwo;0zgs^4ryO?+XrBy;Fl3>)ub>eA#4LQQ`1ra@N z9C8`Je9w&{lO5`f_ukIK3(Nsn* z;0QDI`74W&)|8=}3166BJKO{F?wpNQN-+5eMeRxj%iWXYS}FGiksPP2jj;#`!Z$1d zgp}OY!+7U}olaf~_;^TujkyC}@Odc5xOx~v{OTcvV!PKn<>fTsyWV8D{gH`;{3x0T z`~?MM9%S_AgNfziuHaRt1$s0`2Q(lP@dR8x&*E+=9)@!4r6J&t=bV|r8a5=U_DF0{ ztpb?mB27agAVywm zq;TNhl#?Nyxmi?xM>2HP%b+%d-izZF#;1|>$m22iFnsQ1x1J?%s(Wroc!?0vhqzyV zB4XA?^L7eV7getjy+w4*nHTc;A@6bgLdNopcK5JCKbt?c5>^j*!9$ zYCZ1Hsr>h{y&c3icVJC@Y^a8hf3RS?4Gq+8+^yKFzeX)ZMg3ymFm7PaXq$8az<Ok^@xmm_ngFmV$Kj>dwP8_h6bl~Gu5QliZrXzdTn-eX%|V@A?u|GybmdfW0UpS8wD zGrS)8BJ_X7H5Pa}VCTCf2&|RSsXplc6;m^G$H$vn@ElWuO*d7?fCN~FBlf&|8#+Pb z3#|L!4Rs@G2?>xt9^}!je@k9>J+C^lQE!oao^15kN2C1&RZ6XI2Np2)z`sTaxX)Mj(?pH+@8nl%Ye<~QNU6LbkRSEfw7w%+(={%!Kay$;#UL7 zvFNOpVn0?ek)?*vGfX(RvYle*^(~{je{cS4p`d9>xGrfLIHvC+tLI*5!TixSPY`*$ zG|0i^HQSV`Q0FY zCHQ68#Fg-|0s|9MV7@=%=IEq|(Bvy|xkRM7Z1BgC?jJCpsCmkrc1~(=3F_qHsh2tODF$uB4U&t*ME-&y?t+RSVw9eLdkU|hG7(2Ptt8YXjlU{LCx-$GHO7kh+k`ed8?N2K)* zgVI*D{6~O%v{JtXp@#1v7(kHWr+yo!S$?WV^hRllUtTU-Ju~xk5$Z0esmnS|*~0E* zI--|c$yPeT5ho&kE`bFW+L^K*(;~y46P>lJ5FuYn{YK{ErHp`%}71K2*4t$a_e*rvUw1Ipao=+paRV{7S{VC5mh)^R9|n(za` zr-LN@9!hy5eZ_45w4vZ&7ytYE^J!ROtf4q(&YEA;*F~~9DPV-sWw2Ci)*hHZ`$*0X z_$e|@gTXfT=h>VIt$+g~jsL4n-p=eCZ_LPY^2_auEr9;3A>c25Hysn8a4e+geLsOG z?%ncf9WX10tUgjZc`=n&7UH{H=@{fP?{*+O#RC*_>T|(}3j>H~Q{W^YjciodqI6BDJP#W!E=RvWl{eOM!q?^A5Y!yfmSe<_Q~ z>7*^!^VUd2krubJf%UiN5Lk35Z}^m6fyPcdgohTxP~jz@BQN3eJARfDzxOLYW2AN?F!9$L^{=@ho_zC&&l?S%fXpH9*9CS3=gUz6EV8-C$En2617Wtd;D$1R^^@6xya+#^}1RMBXG;%L(|Km z%$7T+9iHaDJ1*;+V>wkdm{UiO0b~@8bt{v>-K8xKx_Hf$rE0CQ3<-WNcQIZ}{1@yG zg?qExG;r98&h1v;_rDN-)T`v?Y#x-~x;+)vLFr zWHM;`g}Y@iia9FGMeU82OW{3T^DwxRh(5ljE#5wrm$*vLk3k^gNX4HU`U+fRg}((- z&OV)WITNxQc_>rZl6Bl~#?%gzyE?ZM5UV;81N0<|;U-7LpV!l;!Yy7^fuNx~%-pc; zz^H(}uIqKym9yY1U5y`b`3)b3N5$qc0F1PupWzB%Mmhz{4vl%wj(6~Q*zg6apqo@y zBkKwsc=;dY6%~ff9xWa6gbE8f>7Jp+phb8$E7#pNA!22U8z6li=DW|Q1-4%@4~UM9 z8Zxopi3?cd(&z^Mo8}c>n2oPkOTXE8<>R9T(62^MyE|Apq8_J7h16Uh!;{ zS?eX^`5H*50Q>`vpCUw%vBmi-kt|b(z4|zG=?m32l-RjK%kw3YX7g4YqF<;6ts0n6xeVjItbj8rghF5*hf=5JfOM+?)UpAYa11=ciJ25T_wa37wfTAX8SI zOW{i|u#n-#8|YPlx2o{5wVIr#8M-NC=$N!GkD;gbR(sP6J8fOy(8dP* zg1NxZCGYL1UFSEv(tnUOdavb%{vfW0tf8jMbLh^>H@~zl!BYK25-&_2q5m!~zt8D} zAI~nq3U)mRU@^}lZEJuG0lbXX@*(dx67&d$Dx6qW)PaiJz6*@bNDzPI?RTEteBe8l zk73y!56>aIMnoaBDe>`o)kdu=HlI|DYAa6Q8!V{0hMGk38+NR=r}?QN0klqj7>wE` zxpqYapph`av>e7fkHjEx40)zvd_iDr^hX%&)-@V@lbN?y`$PAc97_fRAmiE4h%BLL zWb^@?FI^__F0|BV$@4e%R!DrRKutBlXq`e^VwWoPCBgC0_iEmT>L*~V5aCkV|6Pds z>>!6@o`3cedmcXzfjCl`|G@4(gI{<^L0L#(fwcSWxB=DEOdHDj+uLzRBy3n`?mPgo z*8H)s^X`lbKSt-vM5}8lXw4nU4TUp z19zKW#`l4Ik47$(wT7{~QrMjRc&7jzz2iCm!=e&#GLn^)k(MyVqt7N{6)OXkmHIiG zMpuFNc_S?HFaA>Uw%z`(jGdI2>`(78yU}7Tr>P*phKzKeiMMwGnQ+i_Jh`ybU_7~; z$sq@Yk5^mm)l&BOHv_;kdSJ@Y#D2+aiD)K{7N9v+*Y^WB^OyJ+d#sRB@AVGrV7bb6 z&*sr$4M2YW?9ty+f?Z{(y+IEER0aw2e)Ix@uHV7(xdli2{H_CC{4YWm#6rcc;XSY# z@N{mqH%JW@lfS1>LO)m?Qd&`%0P6ac5J+xByf->ipTq2a1M<*>g<#7p6srl< z)SRB1)w%c?_TmbD!&tGO3b-d-*p%fB?W4bIy{BCCVqu2TvGiT5Us$v=?f7)5W$mSk zCQDZUY|oe7!N0pj2$&M%<>m}K96Z)s;0PD+gtit}+GArU4;i7t{VhWD`C7r! z4R0RmXdFhoD74bIkf)=GM9)Eir32O~G3O&xE(HoF!YVy3qPhMMXeh-TmM$s|XA`%( zGd8Tk|7{^{9MRD~UI`~f!J^rWLvEQOitXw_H&D-T%Hr>NUWz3qs>~7rlt%w1QtoGv zzz_R;7|o6OEvg8$qnm9fTsfAfOgooSltEOZ`+Gu60#>9^;7s7`v_?jrTlbv1(N>4( zVJDn_2_2vh1uu!C0dRu^DDcCHI6FlzK$Ls+R830Yo`(v@`OY?DY`L;fh~^}UT&KEe zRr|~_kI0R7A&^x|344i|=Nd)pp8YMAZJt+87b#JY$QFpCw@Qh8#ov%3*H7@Nm<0Gy0=Yf<&cD?r)MKGyV246bu9)e zhe2;&asw<6JHN!!pSAZfc$lI;#*lMJyDWO@^8;p4L|}ZYdOO1S;Y+_IV^FrTF~Rlx zXA0b3NmvC>betCqXXUOTD_14c$Il1YYsPKIi;b$J-SCz?Rl{he6YqZnee8C$^9pJ2 zTc(lecTo1cJ5{X{^&d;EVv*~uTtT~ZFSQWK^(uSq1A;(M9_wG`m=T8hn%1?A$%8Ch zP5<4KPYSTa5hMm?@8>bZR*oBNyhUO%_TNFC`UyYaX}|cG1b1Z%`vZ;YXMDz=P^K;u zTg&nQ7(>cL((Gg}C%0`FZALRjdKnUEXCjZwviSKf0li{x)legeYC_JA- zV}e$MUpr10qFR1gbmra*NhF`{tZxNn`@Hp^oH=9OKW?ny@N^9#<;y3MCUCun-Ji+3 z0$@!fgA*0V)z<{D*olItKvedBxR?9xf!;)lAX&1|f9J*n#$|S;D0Y90KCRm*2~8Ai z>9D!4`P9s8%$^d-4MuR3hv_rm;r&i$z2+#j9VG>(>hj^+33!m9oldpdV(@cU>q%EY zfXNlGslAnv7vKj;h7Mq)pzv|0B7%PlU>DWYjq_mLP8Se9((*s#P|VsXQg#1jm*=lX z?IxJfe;4+GuWWDLY?=_fBZ#cAeHB*kwYl=0tm~ZxoshYIQ!(^PnA>p=qQ5N3K}U#| zNrNB)|AyU#dHPz~)jDkSfCzuk;zl{sclZNb+bN|mK@;Y(J4!6vE3)%*MzTQ#0 zrv$TMDYQ)&Y@{tWInmsb*XCCncSIwNkjYfGWqXU-I_>Q3Ebp=!{G_bqX)3Hx$2>1@ zpWVjU(^po`7~a%lMcDX}KUC2-njz6T)XZ!|w;>`74m*qvBK2j+d!&qcl^65W+`KvCl|at5o?B@IfWe zLRoiFUaFte)LL( zYPo?N?@uvLdlL=`P=bWIw%#;I7JE}}PoX>Ju**geH7`kQdO`0)I$~*wx%uIQ(VU-A z|4z-N+iPbM-u?x8AK*Rk_G91Ld)Y-1ho)1x%C@F;A>apk8#+@5l_j3a0aU08D$aUs z``V!$^NCPwIrr-J>MYn{+lO*rMPKr~{VzhM1{`8cC4kS+OmY_Os=%wHW8De9mOu5I zWA88#R9qIeMgycC3g0u@rh$D(P_eNIb~g-@6tfFY6m%E>-6>2ja=ZQq`{+fH=be1n z@$Ys13h943Ipmdr)~Eor-!FH}8-^%~SjS_!cPLBSRFRnGK^po<(yW)GJ*nCeBhD$) zBf15<4J1bqf52<84UYl9(~wl;qp)~{!1Qzv0BCz*;|0jm0yoo+PB9taiLDA4bTmZ#oIPhBI z%{{c73-mJ)mBAX)QAIpIlWK;H)wt*%X;2whI2lpUjyD<0lDoUooA0EE#a{ z@f$T>%KZAJWvN(Y4&o(hd^G%SDyYD@_QDRno8pEDg+e~}D;lw~34V%}VUBn=KDUiUrf1CEDFysPuVw!7qepcHQpnfnD z+FOr{k!8I!k$L6ogtkU zILnUczG?oYKtg;1#;2By++~YF)*z_@GNU3Zr)(cC0p7cX zv@lGRkm-+{(FbxuPEA&FuJ9UhFjY#y-BnBA^~K=4TFywU!(6$RD)Zq^nh8XTCm!t` z=R#gALW5vL6dm5Si8)2J&8TR?-?A}r1xlt1y{KisY7=tLmE1QW`#CfIf@@;(t|+9{ z4lrQE%2mm|ezn7YB12%U%^T~gRMO^E7ZyM7%_GsCm81K<%(2=V7pNkbsowtu$EqL+ z;Y3D&?nVbHfV=56=jOCl)iZb1sEq(eX@{#lf&UAu#?Pn<@WGqzr2ZJEn4kSEGm zD70`oYHt0Ddp&5Zufchnr}<{?R`W9~A&$v4!dt)yDZJJg}7-^zv)%Tv~+V3sjx1 z_VO5cvPH}Ru^;X;$4)_2|IZ=f2^Y_Zk8(qJzIj^;32mh-DUpXdU-KFm7#tO2c)I%_ z)VJG3@t*)d+GkPTjITqq5(4_5RkAPl-HC_$A0j>Z%sO6Bde_gxS|9MOvj{al*3%W|oX z4zs0f(5om%nP|aeX8F0%q{u&%Ifc#BC zqMv`21@0Su_68724)lDZf_}2`C-v!J*?dUf)zWTRKhg=J%6K%ZMc_Bf#RzW+-=kj$ z@0)R75DmqkAPlZ3+!KgnSfiKthH&wKAY+zEFQ*wWrMAK>WADvU>I@fEY%?&W*^}%= zxiEn24s#Dl3cGoQKt_bCcrEdgO{gkc;X*QFv5jxk2OLbzXHV7Qmv&n@4LbZ*AmSR4 z#?xr_b}YY4RJWw#LrOyqn6MS8WCo&*_L->a+>a#y=b%M@TynyY*R-x@;u4bJI`z)Q zr>8JX`)qN^L?{=Cv zOhZN~`<&E23{R;zItTz~7KwV@Zmbj##+8aUE>XNrN81{As>oFg2|)jAn*4qJbUxU% z@bdUepnv2=Y`2;9E|XK1Y>!OmumSJt5@(zJZ;A1=`M1o$v_9{~^;`SkvCYS)Z1_&G z04vJq_^CPMfkK!mVUT?bb~d`WIt*nFl!dYK>SU_sCI2xAKOg?pB#r39|EIo-G^sYB zMeM|6L6CWP!sjGr4}+fZ65DKK)G+c7C+rx>t-X zWl1u;yU~A15W8cq9nApr+bCozk7DKWwD_dsz;5(1ve-qKhtKfq|#wNCmobih7Dkh!vH%BSoUA`+b2o3$96)8g7 zcXrgCj#`*e5$I=wR){|$>1tZd*PBelQCcASwagSh!4T)VVDh^ic@yN6bbfjQoxiiv z{>yJi`vrl|UvA33vl_kst$1jPN~wkJ>VlX-5@i)~L1s2xXVVieNpq4W1^t|3!NHk= zfNia>nw_4po0i_X+Coq_Gf3m5etLj2-noQG9dXy@03FHkRJmQbrQM^J7=j9@-N({2Wrw7rVl1MD>jnO7@Tcq* zy9NqXvX+Dv_WmR#MGy&>S%O9cVW5`@Hx-1$fb0*BrQRLVh0KCgK2D?3lu1GvZUi!0mwIe zz{5(Z7`}52VPNw&MJ?J+vJcUBHMPVS&7ZgS@Hqu$dgj?6PR>s$V24Cy+bq0j14cM1 z+eKu?VjQ$o%BuQ$*B%|I44#zBwWubI^`Zp4`~bU%-|-Z-QGu2UWSZn{y7KH%twZt3 z{YYC9v&SsPYDX^QK!|JE~*3m?f53n5B2?rzuDq zgSt!0kI9)C5C6T?_1&JCU^N?A&!zZHAUc9JawQmO3a8b;wnWMJR?AQ5V-5pY|M)%FITt^%9?8)=;h48K`S8(Gf3@V(xvc;J{ zEBPBns7s0kq;$a!KsrNJ-|YW4cZNL;gSrR){O>UeD>&P5{xEMA#LAT)bZ_<4%y{le zi33)DxVyP+QAi#4r(}9pcd1Foh6xtB|J4`})Ti#>hLWuuknvoM59`*njO%)BvEt*) zJHu_fBBVbKj>Nf%lnztAHKnq&TynnKS!NH;aUS7-FK5Kkb7BLi9ioJ}C=GuxsjXUE&i?b8+6eY^2hyJs{Y|-!meRvN*Z*LMgmm-EDRg z`n|(q_PiG7M)^9y1V!%um(Z|#UTO-M9k)Cy* z&It3{XxWu$`q9qzHoS-y;BZb?L!*P2)lr7UkCA#)$&@ao7o9~z%UvSbKm7@h{pP+< zgu#7IFGHd3d@wYO!%Z&299-P13ioCI8`T_?%a;F?Z`rfE?nxm2m<-Wnc&ur7n!2K5 zTuMMVZqH`vG9?_K?wej`?iCU7!<~Ae!5vS=Y+g-7Dc3oUJtqfG#y22* zJ&F>`(OG;?=dU#rM6l3;y-iII5$S;Evn7md{phM?)Zz#gaWu#!>s7`MDNr;Seh@X) z;^8a8Z=rpkqRWNnNtu%8L_2@GL9&yQSu261bp`;V9Trw&N}UVW{X$4VfNK2QMz)*7 zlm`ia_Fwo&Vrc92{%;6}OwjOiT^qMt4&0_kf-drLQ*|e!u6oNnKbYYjLFxh}i}WQ4 zRlr?h_IZ09xIJ2;f%AT^%L?22?*j3+(p*RI5;v*3;}hh=a%Vl@s+ooEVETqCC&U0` z`+}_${vb=qMVw77%5qwv(YJb|xnfYJ3Pe%T5?OJ+IOEGU@4d4cE`wmQsC{vc6Zl?L zR5f_o=t+r5T0f=0VE1KZ$lbsf$J64Wkkv@g>Zb9F{4W|UBqA+Cr-)}F7BNMnS!Lf+ zB0ow+%4FnxOC|^<_Kx{L?tQ*nA?4TpqR=rJ%j_$*z~^j(XHR$JoDI1iixndZztl%H z0L3t4$U2y;xVF5)9Y*=RW%ywLwE=Cl6VxFfI1UZ!hN3Ukp4aN+K2yTi2k9`cH+a<{ z_qQu3Xb3+l&E{W}8wqsn<0;cjC1I)tdnFVNFe;e?~Ad#3-w33I%ux0fNJ@JiKiUZ(uY z6K%J9;=MVKBPJjGCGUJ}CzNh=oI4LfJnO`0U8+0fDFh3FjkUJqlx2Y50yIpUA*CFq znu}|}B@}8w0FbEOyr8T>Gzu8az<55n1LD=^<(ONS%|5%xjetBk!ZY!L_fhrHP*#ym zWIDHblu&VVs;|fI{C;!I5cB@7)np?3oYb;o059R4%z;hR7E%`s$brNhoq5Avn_#|y zK;a$ORx)rb;P$`QCCAx+AH9TN5wwX6idUhQO5TWo50t|RYq&@KSmOLaKVh>&{VOk= zgY6Ff4^eL!)Mnd8YX>Rr?oiy_onpmZ3dM`NySqby65QS0-Q8V_ThQY6<#}g+d;iHy zekGI1ea&^AYpr7;yK?h`b8367?#Ib6nks>z?jEcJ@7?-<=f7u{n&!$0as- zi0{JC4BqxdljUiHYE}q}Xyi#Sq9ez$UJI*)qxRFiD6J%nCdJFqXv~NiAz?ho$WM%a zjh4BY%MD&`BW%=RR=MqB;<59*;umTe=c`%1=F~K&8dNtgovX5HkaNS;OW7pr$~68+ z(h1Qat)mqdev;#aS*dH2gu0YQZg-W%bbODX>M#6Wnap86Q-JQesz@XfXSXObnL?dO z3yL#GE7_`pswyR(4pGhC*|bl(yt+D`&_nl{7fs$f&q-MZm{AQSPsRket8Unw@_i><<_hP%)D;uEHPz&6OCNj*c}q}tzu(in_VX~shu*6 zuEz$p({quw-rIOUfeP*hTI%a64z6l6dpEhc_exLX7@XW(FslHvr3K;Ol}2U(=QhFy zA(J4)R(6grN#^rW?D?8%33d}_2sW>O_~l_3Y!3-MRWYslV=Zg`p5RsQ=fSW=x|srMFc=nIzkxCqc`e z0w)-l;r;eG6nfxq>1Zc%Z~1-V$7&k{CBEw*3mtS0mGwXxLhKR}#;wBzs4KBtUa(QL z!`@vS5w99FUR`dBowtfuP^b)^RK|#YSUP?w;d)FCXqUIw;6*qsq@no5lDNVmj7g3< z5AYJ#gyK*jfm}GLFe4VXiGuGC^tH+--eiT`MUUIfigo3;#9k#sW74ox?klqcv`?52 z>XYzN8wPaK{T9!y{GN1M(S#qivPCOunxogTbUOLK&re_F&KUjzfe0JWm3Q5}lzhK& zJM5)9r*1x>Wu8wF3Qw91bR zZ4aB%F1mFwx1*HDeWXHYDPhN533uJF9c-0uSU}^6MlU3oW5A0Zu7jc@$$QB@&2?0` zdFS}JQzuWgqyCNGZBowKICe#5>TFyb3fQ9;^E+JmbQk37S@Yh}^X%Si`^r56OnGi5 zGAtFrTF{Ky_$8%IB2Qle3yVj!3oHeEn`=Jd5dO^F5vJO-nW;Y?IH?S^lnbZ^*WT3B z5Y-E96x-a%-8Wk*3EfNHGow)6HG>NWNGjcT2DANPUtIS%T;#93LM3BM2QxiiT6}$# z*D8Aa7-LI49>H<+m$Q2lbnvU^k>6j2a<{kU9LA@nY49y=Jha68#uTJlC>#}cHi4%S zvluk-ZnJkf7FQxbWk*J$lIq?C7h>hyopxAfwkg_L-;6Vx$2gshP7Y(;>%!D5a4B8t zj?;i08(Thba{&g&3P!kD=XJ=IhR6Z)!h`S0nxrjm=bE~I1DEBe8`ySWBOtJz22|Hk zGbsRVJR%t7U}IA-$Crq+75scv^az`&XmgwKT{_C4q!=&h6Pc)a=V-c$f40t9)R}R3 z)bvZV1HI;+?dMdOG;lNkMO=A{`>J$XE|#Y8at9c|mZG(0aNOR*7_#HZcc8EciFwU@;XI8{^#U5$R6sR(yWV%t3TAvv{j1MG1 z4ux7?1)w#3-N^QZsR^>aHCm6^Z#4wp{JqJdj*D(=a#|uy%c#$AQ)#Ri>HSe&oT9Ft zC$wJ$qe-3CMp!s0+?;iFoV|d;;$Etdj^x||U!s4pZ%K`)+Msc(xRcs&^pk zX0EO&uP4_FId92+mY5^#*X(={x?n&#V~_JAO3+6O8`F-deSgGn*sh|9Km8|+$apHr zuLbxj?B_+KdAIZu-`z(uCsdsYReK*%8NoJKt^kPJs!Qeft2ObkqI~Ymvy^;Gd zVfP4X&^B8`Mb0%JZ6^YU+n~h$C z^*m~Ab%5E|`v>Cot-JUIY+dcPiAElxO!~1Zh*$J#A&OK2xY>t?SzD?8D&^fstXA~u z_WV%E6(3?VGY_*-SKODq5v_ZsRSXO%*nv={#@$t+Moyo#avH8QX4brD8ycA$SteEb z*Y+YyD|W3 z>_($w(~iB_u=&fwX)1@nGweMTRej{FHbhh;dAeX#cTCrn=EZJk-csT6Vbw=U0JFUd zFf}%QMm5Z+BiL@S>s%#dQ1{~CnGnt_{BLJ6yAkx$I9=oIo{w%FIp(rln5{N(J+g-~ z17qM-vh;gzv5izN5i3BpFJ zq|zajF^iiH>dTc+&@LIbnJmDM6mi)=UH)O#^d{wa+=}s6G!uTs0A4WFIT&r%0gHN` zQFH^kvL+8*+kkZ%h3KToUF4*x`NoGZ2VUMPPr#9f{BW-lDNqGQfG%n~7AoIx@awn< z3!_5A@to0mHy83ul%?j1D7h#V^!&vBCgZy)fujs6d@kZ%W;$eU0)5g@W!oDLUJ(h+ zhbXMXkm|^f3j2J&))zo6F>*izCuf~mG2B8KHy8R>GMp`R@nrrlOu3e4wE1^a!Q40` zR599;irCqo$-yZP;N``>0M>+!-oQ152a-p$F>3KfM(^`PmQ3-1YKyF1* zj(OVB@`|pcqy|8O@{f7Kv+xUZnOLO5Nunul>QC-HIn}zCft_)FHldF|_#2gtxp0^k zx8o)KL85}0;}%(SX~JH%_Mj3am(`J+pH0y%G?g@_ZK2}Ge4+uqIm6a4Z-F+$xS3K5^t9 z`hP6s5bq|ZrCFZO`Oc5PdMZ{`)HwG(g$HPmqBG}vyZ_yj965Re6Df}-pO(q(^!3yf zy!ImFO6bziQ*v_TvWDN(uejzh1FKfzg9H2~4Mlufri6WJmh4;)H>x7(33ztt9w(Ak zI$gyZQ|P??w3w(Po3sh%vkg((wF>1DVe@}V@5=4|b^Vqm=y0ntLfU#V(#7$pA8#&x z+kI9$>}fE>snp`sqecf z2Lj;rZ=GKf@3j-oeXBF^UrBhYJhNtLs}`p*18J8K0|i1^ZDfHi<^@;DK_~SAr5oV< zbQM5_L(ewEZDMNLJ@1I-6(ZlybpMOo#d;QN(5U#svAgcYV38jKb7kH7Z-UpUjUNv@ zJ!6e~kmN&!Y$0iKFpD3Y+9>JOUqq7uqzX9i7)a)kMIxe|t~P!-jvdkVKEk7X3XFqM zs`Stjr#eEx`$+L$BYR4rSXyCNs-RYs;pt&F3lb8%_S3 zQF0vU#Zy!{fP7%C#E`K=@I4uhO+EC@+>W8#2#Nk1Uyt8Y)Dt=aH7)T&n@1+g0mX@A zmWY4fw*RNEfa7gpQzK``*cgl7hqL$oJx?Z0SBl5NL_a2wn)C9p9rf@OHhIkUV*@h( ztz)o;H0{!UH>6@FfJ?_mxb+*k0SyhcEyk6jvBXxdz+cl4e-?x8khV>|k+}J`urQd; zs6G^(uHi4BmF1=WIC_X*k~C5TR@K7FEP4a;!Hf0kVaB>}M5=5Ezv0fRp`=~m=gy=! z%A*}ljZ3nG7i^|%1NvK|Ni#*Ih!V(<@YD<-l4_~9nyV-3s?MFOioZ_L1Mr<{f5U&Z z!;(b}plzZHPmu&x~kozL$M&1h>*cCqr~d3J|y$?Q4NU4NNxjc6)mk4jCl7J+am@7A;R zhSp42pLpijdbok*0mO`43@ZmChgFOr{A&Z)h0*e)=|s^Lx+|ERMu4{F>}M__`pYYt zO&MgFXsjol*oT%i!q8L?-pEUPyr5t_5#c1-CSt76^g2*Ij=TM@eO(6Di4v5xbj@c( zJ~Kh9Z3Ag2D~rqP$GiGZ%DweBO=g5%GdX5-=U2bC4Nov;lb+qBUu`!) zPCkIS@s(sEG+^oBE`j^!=%vZKfT+i37LLG^V#C%YbK^!57bWVQ%Pk#^_3%SAVeedD zAqXa9{hm>g<0RM^m|Gr+=%v|1W6KHh{d-%=e_Oh5;L$+3GS>F!CAc>Bdf6o{1m;-# zW!~>GK&Xt9uW$B@akBWKu1vj0)Pw7TU(!QC0*qjTK^kH02rBq0B@7M~-a{Qu1sI`6 zc=3+ydcC;tE`=}S?ZArp>OwM4TD#^n$+2a`6hrk%fQYO0zeW4k^O;;HmJZ^&=T zM5pwr3vy1ZY+A~hV_+kx7Hw0K(N`btkzW)`MHOv0`*V)ny-N7mA><9Rj=9;ZbYBc_ zhRCj*0r7|t`h1Pisf&D;K!Y*Iw}!*U0ZGqt=x!%{W;Q+Gi0_$#Mvhk9;Jl-eFo!*zg z4}~>R62?Zj$%M3dG_o9Ozx0bSA}OS@yW{DN*bE-pM^R|~;shth9x(OaC3qRScPA=k zT7n(#1pYwGAeO9ISsBL5jls0!ti^QOlTQq|Ihd`#(7irM|47Qehy%|Q@x}%XH zgdvI?rT$~Fuu3$727FEXu42ZVz>Hxg=R{rA{cDo|E!N(GzOjAXrlOaz9)rb|%au+u zlt%$VyZ1Zm;4Fz+7-qPOC^%Bfo9BXnhjfa6Gt^|h!cz9;S-pphhD~LMLc4oYj+x&3 zij-EIIb22|9wFuKu0-)m2-$+qI*)rA(9>wL9dv zQVzduiDLF}%v&X*ai860YoA*_^3(0MZv?QWA&ExOX-Y=m-}A8ryr0>h!0(}Q8EU+ zp-jBwT;Ghz#_N!O7HL?$A7m@QTtT2o&T|6eN;C{g0_XMuu@UJtnr3yb8>&&{a`owP62&0+xt2v z=b-WCvlr^6@|xJ$=1*}#L*;c;AgYyS zc+d;lna^Z5eY^s%zOEPW(+8B5)y-*E>4O>zn(elOU?$jCzj*@cYmHi^JV61pXNFF( z${o@DQh7KkpL+pNvah$9Trv2Qy}q4iu2PlQYPlKUZ0E%gv%J)+Em5r@aLmEPi0`7` zNwraru97vx@^{LY{aG4 zG!1qbTEa0#oLK}C1_+2D^WPkz2jJ-K&u(Rey`m(@(5r@K)~u;$B@`Apxw`dEs0VqWWdk7) z4C6`=Ck%jqNvKVT-Li@NPPH2yT*#0lY*N#y10k-g#ot$=#;;j zCpDWh69gKSVMb?|B|Z@a!b{f1zL#HtMK%pi2DP8O86oo%G;sBME*e+6NAWJkl=YB+n%SgDAuIrWG_J~LPXHk{)=oc zy=fu4{1c3kUc&?AM&zcFV*I^cNhddfr> zD=rNvsbKA4PC-;c7>&1K8jBsR>-7-(k=ReC+EPZ(pP8KE_ zI5lpX<8vGNzAy4Y0d?p1`r7m9?fqJ_ry-jXUr5d ztle4IjTE6elB~_*XY>59SeVLvdIqrl4rPa|3N2Cg_C=}Y zuG6GKeTO%`Fv)g!L4QvhA4|a&!D^igmM$b*u?J*k)uD>Kj4I~gQvoPxXf{4xYWz)m z$QO;v6KAw8Ij53SrU)X2UvJxJoOg+Q#w7jN^lHMgZTQ ztC;O+U*!tsy^`y9uCSny5U}NX{wytsju&#);nQ!ho!|UodW&rmng&k(JKGF-l--L? zdXA-r>Doz^skWzO`qE0tSBq@33C&PIf*MngHe;M)Mp{-v5q_ok=0JES2OyBd*zTq> z5f~c>)a#hH)nakg_10nz+9`r7$c5szRiW)Hjp^g+1Iv`8p-x%WM z7pTEN)qm1-iLVJoUW~A6&4TlqNVD2%`ld~XRGL~@#@g(EiO7aR&vdj^@2_zxjNd9}mPX`e35`LmdztK=a6$(uI><@utGRB#cFRn0QtIWUHQbDr+YOMfWXk zU^Zl5(k4a0|BI#uFr!=Ai=88esnfieEd;3C7acApVlXhs*QuUK*zPB5@F=X`9`e<` zAhfLjO#suoRdv- z9eD%Zbr`YH?OnEL1^sgS&l)GMu`5{8>xp%jH{xt3KxtWYC){)pvY7#Dw;GdTXZ7cV zOUy1&xlSuRm&}5HT_1SS&T>AV{dsFVsCbLCdyKle?jJU$p_Qn$An`x`jfkv~e%{Al zx))IuDN>x__B@4h%&7HH)|C6DLFEHu_@&hS+^$t3PAY^#PLqnw=F~Eg*Ai#=L9~B2 zQ+xzAbu8=Ba^oBR(QRn#M2}tL^3`h;67Qqym;YU=HvZI9 z`hn~VaHX#2;rLtrpLNPEcc|ALJRSZ`1??C2u0SBW2%#;3@qzriVUdlW-(Wh5upif04kxikn`8MIL&gn)S!K+N6_e)(Lni#*BrCo9bbc%pH;J^ zZ&{W84gQ@XH)6AMX5F?Jut{c4+ZLsloF#|Ju#O-fSGdGuJ+T%rmr zj()ex8l`asDpW8lA(r3k#?E@rC#Xky)$0rSkOokQ{l{)gROZ#h@!mJeZUr*g83mt` z$)SD1)oah@*(%?z$79GV>%NeMy4yV(329uiqOq*aQiE29zUeHHaLY+P>H>C?jr=VB}&cTZdI&E){%d_5v9}}~+3-)88q;$BBprA?@U7g_8hiaFNW+)?D=n89s zd5F9)c<}(`@8sr)5x?DltGIx#i<(8gL{+x%J}q0~NT2%g$cFvg{F-JwcG4FoZGIi| z9A-ZxDv1IMw>HKvLWxbAy~N?RDA(y2bI0&EX9p0*C*<}K83Lj{APgh2C>?aOdkcLj zcOh*gQUV^PSHFQcjOO&6FlX7CKAstZ1?BRPU;O$$r9>BzX4LLhI7+A~+zuSV5l3dQ z*3Eg0B>pnZ<)7TaMaY`xye&*E?OV(_tU0kVJ#6 z4D%CZs)EX-*$LDt)X)VD$|aaAFR8lnV>mYST~@Vci1G+JE4*YvW=_NI|1C2Gt4ubn zGrEJ;HB_#|Egs--N}hSzuep}&leIe z6audV!l1*DDO(tQz{YNP8frJYd&#z-ECpCee!xT)#ovpF;n-8*W0O{Yk8EwbpKkg9 z{t-d<27pV)NPEb${1h=~+kOzNZ})kD^stQ!*6^jk)#{c1r;^7)$Kf`7tU~O=vabDF zx7Gt6Or_w-``zc0`77z?d(WLdq1(Mg&{5CJQcY&0zTa1`xVF2=a6Yo~(q6u{QI^qq z&NO>S`mlko>ke>9N&u(+=LKK4hhL=Bk!^0*vSm~9QDc%ug$nCO_4*sFK9l-eTA*(@ z@v{}u@?u&%i*-XkT>HFF&_i35JsGS?Tz?+p;HE-#$6uch+RU*nQG`lLsT)rVc5QT% zJTU{HI0;>wHdwX%E|Umw;)7L0Fa9PvqE@uCGD06jT$Hm=#I$G?H$M1Mr%W{?QY@0prl40)%n(Em{A;5GC zb|T|h!oBl4YHNa?4v6Q?e`@F}eS^?G5NJiZ?f)#v^BkQ7>jYujekhI$vS@RD4HpQ? zxJbBv;0WyCHp%JcF&c@BZHx39IjIG0WZHQ@u(s`}nq{nLvCR$Yl2F4cY7K)+XjfZz z+}1e=PKFB7@N_>r2b-ovTw>#`_CjxLQ#8=>r!@^A*WE9-C3_!o!8jLlx5sTgTz$W1 zs*Ts%2>|(q?LM_AIsm;+oU_bTZjXbv(CL#};qG_R?>9vm;m^Vc->rv7x$Vc1rU%dS zmUkU81w1k_&#n2*AXcAfy&ga0yVUc8cjA%c-*(^h?MUwPH`56Si78}t7#Xyxe;FHu zS1U8g=S@Dpfp>;`Q4#HhK zs)0LVMTohNh#7mvl1*2IR0@%Hh})KN2&)9ic^*F#c~?eBe*xMM5F@iF0Pq@Wj!Y2l zTA`_G@t*bSfB{5D0m-xqh@sG2>sOfdNLwEIkj`_a>Z`Cro6DO4e{a<{YPr4yngGh3 z z%`2kL)Amg~px+L%iODnDep*VWGk~wM8F(Pvld*3B%8-RbN#O>ORa6T?qD@YKrn7!{ z1{T6l4Q?wvRzsM%u{vcgz_-Z5fxXGT%vLho$NP{ME9id0`YN33ntI`1DYZr8vi(5m zxvK#BFJ>}ggl^AbQgi3OmHOD&qlET$$G=yyk4K9-ZE`WIh_Ubcr^p_P;q_t+kMmw# z#sOWM2MsS2v~^b^wrsPTD_RynPNb7K+J@-;w?RKDs^B(m!^pv=sLL~HDMg-p+~JKg z1ZxY%qc-+q=vhSL!EX8CWF>ld)6_Hi`|rJ3QKHee*Uyz7eX(Uc_DZ_c*lWHraiX#9BXfJ&(nkkerWIo_B$1 zupdTzL=f%9HIQ~o>7LCI$?RDDX%#vd5yGRy$ik(i= z9Pj)}KL)pN%J8*!Ss9#<}@DE^p2*1ZCk^vy{Fggk~Xe@46x3|0syogh*y} zHQ`oAGxHJCQZ6q2dQ;0`T)KE+z{P>U^UOK^5o}`TY;kl3Y2uIDWDcI$q zdHtb@@8OMuui05QRHy}+n6dLuD0>O8#|opgHFB&!^{)lB=O{2U@?f8_{Vb26=OC0R zSD6tpMFB3U@wQ`b?fsWZo^{J90Jkc*Yh;WzfWC2{WDfsj0lC3W%_YB50)%IOcN3ozwg%A|I zYEA>tRtyEbR2g-w35&k=FHUX&Wt`7|OUDv6pLYrmw}=YOWTPZff$W~ zAO~U-AhoG?RefCmA9U2^LXf{st_~19j&RPj!D4?3n5lpIw#NeAl)QO26x$Zc ztB_mi_K~BFe+iUd%z(>1da_vcYA*)$2I_l1z6*COXc@X+yPbA&oblIPk$3eGIKH)S z+PqG&$X$SXhJIpPYaabh`+;Y@chAlhi=;}L$A8Ms0La5=0D-@}V(Z&zBE`dLo)R&K z8?quMx9#SEORl~c>Gf_Ol-qTeJ7~U0&O@v7a5C)k`187F^}m>1Z)ZfjoF6(IHb4a& zuXg=o01UOI{C#P{3w+$asrB`MobySHHZ?{tY@zn;T~3MLuofw+ zUD20R~Pgsul55=axd5aN0O8I^t(GBTs#ME-y?kDkjXwSzK(WH zV35|fzIRPQr1%;?BSu)!ggj|e@WEP2V6)jJ76zRAVW@(=1XRC1viAQwR{+{v|QGU=lb3We44 z@Kke9paTpNk&n#A>5=**)H>+e@n;{Z!Wv%ENs}Cb?a(~c!>|%NC^n}r;v0Z>l2(fv zz&@d-%o$vIc8WldfOsLJ-wjR)hfKy}D4e*6AV;999I}YheVAT{$T$8p#L8`(kNcRe zQ-YJGzW5g_;8yosU1bnN=nkEilcZ}!{ctbm#KtH33CZHmUZ%P|c9$)A<5SpH1e^bl zmkIIE_w8D|f zB%egETtS6YDL?fHbB>|aI<>g!D;%Y|MEp2Oy%R&G9HmLsy4m^SiJOUt;){+(Zqp`nQ9nT-Sf7_=OCF zFbSiwaxKP_`Q->~(UsiRqBYh(Ot`Ik$9}s2WG89*Xz=c!kfMd8UQQVxDR@OasPC9j z4x)jaCxR`58-0@FR5gxUBFSPfR}FM7Eko_ zU)F4-_$<6YA>N=!{bFA)SYk2G6!qi#?!N1kTZzm}?w=Cg-sp3m!~*8FcVSK&_0>do zk1l6;w&-NCL&R8Z+e+oIVrP0eV{Mw+ica|s|4z`oQO%MY&!gCKYM>;%_G5W|@;Zmb zW0)%rr1RS!v;1`Mo!hX_qi8aZ2dAc-s6G1hz4 z=Ij4#r~!f`+*iXF`!nPZu-i#OkoiPl*dd|Qh^_B^3}{Eou;zkA8!rMf0a@_)xrC)w zu@n(C(|7R(mifi;>d8IBfaWMHu53o@sRf|&u?1R*oYCI=_&Dr^at-_tKm1I=Q|X-G zx_r~ozgsl(4*@-R!%95M)+!e$2p>QCYUrQvd~7D^znZ@`_4qpxfiE>a)8LV7%(RNF zfWM4|W9p7r&S~rE@A0TwCgiy0p+L)^0a`bT1$oJTl&5^8pI9W)6jno*Ld{N(a(|kA zQl^$!>P+N){62Rs*N;nHfLLsYeU&Cl^Dw&I#*y#845<1B3*5A7c??5JiGyJR9gaCyQ7oC+g+`11{Lisy6d@Ph zCz;zKI}ut2S=p77Kff}Ckw#-wkFa64y=S%uGV*#8{{H>yjqbkXf3Ib4oZo^ChNUWK z?y2mN+`xiMJ`^BT#@;1vKY}9P!%(J+yaQiF92B4Pe>A)*$&@n<-p4^|>Ogn>QAu4{ zsWE85q)}RZc0NXD={BmWs$xZ$*PA`4&FhBPDn7Qo>h5Z`S#ts>wRuNKjI%~xGYlYy zWr$V}a!uNH5%jIGQ=_3`vha*II2Isw9WY^bQYISQ_LobyEW7QivcvV_->``02&Kt<4la? z-Oa<${aKndQilF%tUVlM1jsc3jrz_mNF%ggx3H|cI81O^8aIaIY?t|xZHY14OXv|F z$>D5hC#Dhc{Tn+$%N!I?Fg}26!3G1`#Y!b=$>I5zSu?xM!iz)`sca_;7s~)kXxYFCJ zUuuB0=!61stfM?r-nudry{U3he-pEQ%X>FkRixhelwzS+hGZ0H#nKTRY4{@Qb6>)r zFMB46X*;~X%dGfRFc8%yD{~{K@1jVv#s7TJ(ycVjT!=pO+MiaLi0vg({QCsIx3q%C z97M2pnB#-h6fEt)9$+q>svL0fZM8HlfL|Q0e@1H9#?y~*T4?>^xTdPv;LRphL-SC_ zPWX)n=!AY*;$OB%b6D9CejD?krz!tk*C{fy=G;6~6>Q6X#+cFnz zWozqf=4n2i?WQjxCnpD5danT^m)!Rcor9~i+kBXLuC~BdZAnQnTdrH6lIWI00h&aCpf2@H1E-?t{kH3;waZ@WJ*{?`SSpUl~%{?==BiCh7x zIg)VQ|M2Cof#N1p)WDh1m_{>5RVW2h*twK1!F zp%q?Vx0@pM`$Zfczv^Kgt>DtQ9+mpACi`u@-jrKS*FKyjZq5H=h6mK3)@8?b8iL;}84ysYYLKi2Pq$80Hd2k^Q?oY*gSfa-KButKgpDs~H-3tyfFmYdHnxJQ!Y_ z;_mo?wd7l?xDM#V8%l7 zWOxuT-w$L0NDQ%>^xlyy$nk``xKr!27kK%-8(7T!4Oe`&V7`Vj(ELcgBpGgc9E7&P zTfYc|f+a#*T3;TQC>-LpUk5YvKm%2eDAc5cSsx>t-lIDba|Kf(mSpsG_F$@$Nz$XQ zdUvd=6UmD?H8^NoC_H_Ldzf#HQ3IB_9QA(*2nZ01{~eActWC081qrldNmpc(bXMgp zXJjOu162rlY(uh|ajv2(3|SUuYs^%_X9=A}EAVg{77YT6#i$apWevxJYMaQ*c}IVt zB{7zmLU(*8Sva7p>axYK_oD#Fm_*^hyz0Pi-083JB8Uc|qnihHs*U;bp&cTuZmCg+qybbg8-U6Rk3Tf%cJ&mB zy1GS(S&}_QtV3eMWVY}$HG_REm&04y1zOmaIyPno1sB>oII8?D2#V2nrw1ALKv58$ z8CkYP5h6V5rayc&ikB9D^>R)a?n(FPU`gpROwpG+v-&sUty z)EVs?Y%lTEEB;W+%~!1opvoGPDP9Ry(?|hQExQNZJ#w1Be!n;Jjh{Y3cNNo8@aE0^Y%|E>7^RCgAvW&Yt2WS!7E+G@H zaW}O$SbTXgLhK@KMitI%(%oXkM#sgyVmub(H!xmQkZkarcKP*^?&`b?4)@n1JJ6D_4OY4;!CRkH

5g$5o)AzvWfgf@R*9v=+U2>nW_h0VLrOkCYVYi@*0wf45D^Pk*zjZlWx{Qg za+GBcSxMdyKvW(aLb$~(NW(2If|VGqUI4e*xR#1LCLco_xm2m7(@Eo4hK6xFdukNdn<48W zie%s5FnuM1lxewGl;i;f)GRbxvczzU%%V*e&~`J3Iyq^ty-(t}C)06-bCJ_6gi{2WJHq@bu_Pe}y~s#{SH`G=BS_ zuZNx$e|P^OT;8q*D5*}5##aLaxaUbgL6nyn-V#1br; ziWyTBjW9xcbRQ|W|4faL5y|m#W3aa{(lNa^8XFs}5sRYt-+$kBL8g5XU|z1y3dr#E z(@)!j4?gH3v*j1$yR!MQdiLHyYvJ*Ll~aH^xYG6Y+xMRRo=eJ8WqGBuczWW=Cv4sN zb9w)58XHXTl=&quS%B#lu`vKP0?Vw_eA8hiXNa-7>tb-T+h{>0g)d)d)EeokHp(=yv~0YKuP!VZPc&B z_fKqpc_pCspyd1f6#*r2C~08TqW-58?|+vAl)m|Qe`gL*ijO;=>)gKY`nB$R3oHph z=^B;j2Oz)pr)%H{4;~3X$xG(eS5)a|uO!aGJY4foDa-3w6a0!-@a zMA3>b;!r9s4FDzoUeJ4H3{u^L`zG!1{wX_hyweVy?1XH&)27EdZ0m+%`^&$K9_#-%TxfRG&|qNEPrCaZY!U(yEhwvQkJdbi~rJPa#aBEF^rd!NRlH-`P?CxgiGOZZY!F2aYLt&v-a;;Jwy9_(r>p&kYq-d86HrQm(duX(Zz%D z*=L{GkAM7Qd*zi^oN^%rQM`FHRbhc)r$iAAw7AEtSIKuz&28 z)-!$jN++;i=lJn`7>#RiV9)UY%J{-fR5z3oNm159S_B$Q6Iwn--NuL#G&)K+_ffuN zM{`KIxKv_glnWs{pwbX{X8Xk$mOW8Badr|Hs2)Pi_gecfmMSA~ccAnY!K+hKUS!J` zSJ~1sx(?T`jw|^^y(Q=| z!CvC#aXnT_xJ1cCWddL%J+pw6kHsE9YCjfyA57S;*T(J0$u4W^J`bogj3q(7RTdOL zNM8g1OB6+vWLa2s5eof6YbT_c5o>EN#q}%OE(}e=DFpfURF`FARa2H%gk@5ZErDNY z*;1^P<^jv)iMTt(7S=@||5f{;q)HL4OTnB&W;1S)vW_JcJU>&i3Ib4yMn?f?N3FdL z8Mn&it<)COEyU%Gx(P((i$9}m&svfM%Kgj!i(13T7(uB3)RJW_0ZDwk?j4{s9Rid}^6Y>At5g7`RKTPGfXzWbDfnZa zOCdbHn7^}ZNny+$eW2IwyMNS{E@G@A3Y`EYg|$}!)!rEbu%ZztF}qySUL;T_fVf2B z2&k^Tkv=|q_xP6X8D9MDHNII{);DF%<6Sm2 z)@3UzqqY`awr$%=?VkIpta@QKV=%3H22fIs1XZQFbuwhfWyS2|8ywL`lfM2wd+*)% zuyA`Bm%PugFlu#V+<*Eff9m*@M1EaaSvfQQ`g-?u!(-ipj~e89-^6v8x%Y z(eM2rYX1Z|{Y>ejxR6fuU=^BdYpV<4q{_3$A4|uD8$d~5F;-VD3aAF4_yFQ$Iok}w zS-kwV7xax>bNM^{(d_kg?APIfYo7-c5`a=zGPnM=>ONfmR|S;R-;`X3jc@bY>;59; zb{tB4Z2acmeam+4+zE)yyo>qboBI69$8*g{oK|)8TM+n89lV(pnnq-gfguAAYQ0+vI65m8RA;SgW=w4dF zfRfw6ABj#!ot)fnCTCuV{C4?t$JL2~^JSSKmj!*_5<(20Q4Gm*K*6#o$ z1z_#aPe~!LGdA z0R#ToPJUP@#pEIe?~o$RO-)4!wuf~VE{74U1LPhVgS%sLFxiF%;MM7gSz8D0Zzo6W z?CB9}xHxR}t>ksM50c~_>JHNN{A^nQQS-Nan`tG5**1?gP9X@Y3+F|x zunbqBR9_O6Ks-yxpY|#4ml%LfYvl0uG zSAS*#;7Fia*|U2<}o2?H927p=c%+Pd0Et;!#u(#27t zxJ}vFrYY;7&9-7qmy#Iuy&c&@yK zlC0Qdp@hrZKLRNIJr+uBZDRmyXsBPQK#Vif2?Hh29QYG@?o{K??dN;)w%FG*KsO0i#JoNlc0a7M9~+rAI!+ zrEOo#K0b8XK017gu>ng)J`^mhCbuBx)_ z_btJdw-5`*WJmI@oWyG?aCw_4L(q3zcJ(KyT(?r&6_=8CBmHF0UVHP+w{8Fa{dVfq z3EDL8xvy-uySCls$hnsqrD4WqrJw!$XZEw7{mgyv(>#3D zs#W&r5s`af^~08 zbJV{3!%6!e0CxC^Q)W_B?&5>svq`q9G{?5wmT6yqD#PyI4)995c2WA&5tI-2pFeu$ zrIqjYUGYzFNnFNPJS%Y^BmrN?ejPd#Y$8*AsOs+N2B>djd>yu;qGD2!8|&qMAB@BP zEvPE=6*0RV-uJm@BzAo1B%t=7)O5enFJ&(ly3gI z{aguV=LEBd804kn=#N$&P-+*45=mfE3X=~3N+nn*rDfvsrfWD?%F^(_w7vD_I0V=e z*4)xf$anZi0FzRaI&Jf&BKy-nTMgGv6_bBBdeDHod#6Z~_UsQj?VoJ@D0On_pRC)ui0qG@|?{)H3s9&7qKm2bA1J z{E_H5?BA{-8m)Cn%FgQ5t1L5%I(Bl1 zTahBP)_1YL|i|P?+AIRVJSk{1e23!P}dXiVl|w>Lgj4KjzR)|^kmddH#gYH zwi870qs?)@tlV^4yR6*St}3^?)>hhG>nbg`6i@{KAO%2Ed5|p(>K^qdwKZ^*6eAF7 zXew{{^2Q~XEWU$B5sogyWZ`@*3#6&<2oj!PE*o4((Ja#4zv(n7+5=V0BzBUE^|c%@(R)4!Pm{)8J`i$e#q z6PKsp(rHNCryY2#yz+07eoh-09mE~78y6?~_MwAOJAk|GS=@_GHaA)?7GL6RNrnrl zGOrek#4;O&=zRn}t4M9Y}Cy0f8l(!|g5&k1CZ~uUWQgbuWty-q-rB{3H zUw_?cEqxIz;!15zRm2_wP}=sDVYs_0AcYSAB?m^whXd)+5&mfH7mWi-8Wfx|CNPP1 zPvPTBAkEN@V1N9c{;aF6XYLh0D}Jr|e7N8HG34I`P@0>k&lNzNS^=OGSSI;i7FfNx zz8D9TIMFR~n~l-u1uUgNz#RkN=)90@9W6=r#yg+c>+c>R7z2E8xJ{Pkm)q?tme}Hj zgZN>VvoS;()D zEuR^-wCH^CJ1NqmKzO;I9Xj-xz5n6IxL<#4d-r~XD`%erf!5qcu!>EaToON_QY6Bd z=i3JNbK^3<1?~?G4LO(1R|)Q*be3`V!i5V~Q&VFPKeB^JZ+GE-xx#8{Yn^3~YiGI# z*K6_Xa2s&@X`p(JAJ_A+a+1}QfF*rs5%@aFxOI`h7T^8Rxcz@GB6F;kOz&gKpAQ2H z0J$(P%{H${v;X)^hCQ+)&3!;hV!sv#ERheF2j7| z^Ri(j%O8b_znq1V1C&A>O49p>2r2vuZago)J`S+ZZ5L5Q)2x$_=mDVg%-2`h`a7^t z0#J$qDD`wl9jNr|_gn0re%|5~Zp$jQdm&hUd`HCYB+6S=S+bQ9tto=5QUsSJElh#< z%S06=Q-s3IX59Y3{mvxYdS8;Q zTvke&hnoSt!XpPuxin>a4s1C9I^_eI?hI@}BM<5`ad11JT&d+PQkjx*MBt%WC5b zIzS56F8abPrDVm56#yeE_+15|dl`|A3IQjwQMPcUppC^)3K5MfpW2d(My4`T55X63 zlopgZ$pJbJ>mlM+Pj}4DH^Hq0z;X(b=9Bg9)`+!1OIMGL!T(cH1krVQmaVR>vX!I- zbyzMf&ZZ10@Td@LE))4hG^q+?tG@!1RHreK+M*0PVqKIw8U#l!UG!T?)e*0f_z9|| zK+&AW@+yYqPZX=GC{}f;G)xh#kB?(%FdDV`GktdO(>6PNWC&NjEIWA-0%;*fm|3i; z$+2~-bFj3^v9-77STSVVvcj9d)d$)j>L-dKIRtU~FjiZgSkZK1xs;8C4s|q@VL9YE z7x&Vf{3OdOh*%jGOJ!JZ)h-^hnx*5&Aq`iVEG!Td32h2_K#na}GXyNxOu5pCjK8C! z!-`5uA-cxp4cD3!K-}a|e-ON?);|lwNeq&tq!TFMYPnkG%F4^o9}BLNg_nSZ!1jwk z#vBg5cDfz_AUjR{ObS$jV1EG1wWfN=x*KB#Z10s%>};~Z7>-SP_#heCkyf(RJ#7^ z9F1)$@Owodqdr&PXvdD8Z~+8PvgUi_(nh_CyyKjssC9sBj?WPwZ*7D}I!$}PV`?Lo=U_ihAG zasV}bP(fRi5`Ypz8fLSJVd*N}#t%S#?N6Pnz$5@AFPWQvJ-4nkm(zfAEkMc5>L|XS zsNDRLxCKk#Cu6>7R~Y?V8{n8XQP-q+E{9S9JTEhV68F`u1Og27#o!njw_m-Cdk9K> zTX(PJr*v9*R)=lAqsX4zx!Trl3;{}j0=+$a?fgLlf!TXR002M$Nkl>!g7XZ%f?~NMLT~5tHl0ZmoduL+6~KS#{=wv5?bl7h zneU=+y#H>WednLsY!_Tg6DZBuME1F3O^U7Cl!66SnccaujF8bN%iPlG!A@2ZoOVbt z4HhZ2QfC4Mhi9-`YO|7G=89K}LC`;fyGU8@?Cdl}d6V11&wu`N$1@~XhX){O{rcCx z?!rkImzKbV0dEaAR`T`ZpQH5`>36zcxZnE;hD_hZp`%OWG-1;NVUIkdbn;Z23~VZS@*lPHwl_+Bz!(SW*Nb zmj^0NuVkr{PM%Ua;@fc;O$DWHgS}CZ6>-%J04nw426yVz1iW1n_Sw-cJ9O;4HFULe z^^m2fOj&hdwN({W^W0*)eO-wyUXliBHnH-9NT79Z)fpgp`6l8h-$0J^9h1iRH(ySgR;;l_~JB+6mT_Ix&F7qMIz9O`$Z z+VilY*nE3|-FtU27G7CaTa%2HSTa^b@Noewb+k|6k`}d=mJXNBoXNqptAuE1fT$yo zsZWmBl%9vyTai_4^RkOh z68l~M{bK@@LgJshsh%Sx%Q@8OMs!pkNqA{%2y;w7v(K* zbrzsBj$3*wfYQJGVBG$nUtb1L!a}SfJJU8UO0y@wngUsU3Kmz4wOB{Wl1%b&<>Do+ z5k3HvX5|{n&gVD%X_sdE^XDb@%t*l3v0u*|U_<+SohLYy!jif5w^jGy`oB>?$y+ET z0HvUrUM;(RLZ)-BFe&r( zuj#Ss{)&JSk;&5FdSK4(ZpAlBM>zZ|zFPkBC89%Nz0wNMP!#E8g4tnP0F=H4pmh6& z08pCb!nTW1qE}7XkAK!+-}zMoYGS?> zVew&nZDyM9Cd(?$44_1w+}vLp9203BQ@K9<1m1}s_t?81^;kzg?pzRnuc}SL5-8ao z*uKzqY_Gvm1F$3&6Bt0NU{T4K+{;2DxDof36_f{*r2HydQW$3iJXgGK@=RWW*))a_ zDD47m+KAru!VAA9{f6-Dke_#TVVQLYt_zRY#*G_o$zqpgcxg=|r^UW9R3@#W) z4j-};CyoM|bvgd6BBCr6<1VMjM$4D2aQsSjb#=~SNdTn?WCaE~S0O}Cwp<+wK+@NL zD%>SE0Y;3{OOzB@&?z~s)3}1g;3gWt4XzVQ6i%EFB>+mJ`UYib^{`j%m=toQ;*S_Ti$n&p6DYf^2^#wn{? zgw;_lTwfV!L_eFNo~En^g8Lq#KQ%UF!E03j$TW=w)1dYAjanPldF_tRURHfrZRK>p zvD9wW+;@IeIg#P8+^WSA5F&56u}0G155rY&8jGFIt`6E{JEY#!-O?(eQRPrCv~*u! z*X9G|P+(F3D5-=>k_N6ju4njCBifK$To;Z14$jb30&I0&@GsaC05XAm<&wu(fNPZc z|1>UV>^)hO&ygp(-eQCs62UD$E|Unl@;WLf1~v9<(;V&!N6N~Gc8 zQ3uW+I&{e1*!70(*}DfTrAENxL3`l-2V7da4i{lkRu-Xmdw0O0w8g%1FI;>Z);Yc@wMAb?TKjExd)E%#liawk@%3|n z5|&DG*-HXYnqa(bWvuVwpj1$hLX=7M0Le%Fj!l;j zdWNjc+>Rg*SN-donHTX@Pfi?^1cGrUkVSagA5(p+?Ow0TTX3h@KJVL-U;E>U^_N=$ zY70tkK1Cb2DxjpIsL#dwpT<=WC`tcU^vZ_HR|nt;0Ht)4Pcfe8zov__Q2G@XO4kCErkTKxV>Z#) z2nP)5S1&Z$k6vjc`dcA{#MO4soq2q*6^9ZNdk9-HAZHe@N|2|VHfp;+?zUrC1~qhD;CV*KWwV`+ue4{LTxmt6Ot8`w z1uNk3aHJ68r9mO^WUz9lOLkwRy^WG`L7pUtD=co>>@=O=9LZU-Rru#O-+IU1A{{+? z1fu4{wgeJuDFsTKNwu}LDENGxrw|b=Wu!R#zLuH#mH=7&1VcO>1APNd0n)a3aHf>wJG6*OO=hysV zEWC1&6Z}(C<0zRBfRj4g({V}32AoWWtebmWoPq#8YG)vM~KigIy>o5KAv>RcLoaci7co@=#rrMN1lVXc8>MzRX8MdcP~ z2~bJ*R8+vE zST2foj0BL-3VCqTGz7wvxCKr?*d4V)O-XhD10(|oK-ihLE_AK>yzlqg z?eaiAu9rh8Jpc38YyJCK$eU#0spE2rr_}rbQg>d8e54} z2so_%#n5ScKbf+(-pGQJY@5l(U=_6s?T-MHU%hUP_^mK zYE2&!jvqhn+?+qcW$nn(&*-lgZQZ(cwr=e@+kXFcEL0zW%P-g8#j9 zV~hn*`u4M9_J95Aa)45j&4-6@XB62es3ynvdOsJ($8dhmPBRfJ*alC%JOYI z$ja6K`u052Ag+FT;wa*c*R7Yu+~2M}Fh}}b043iZb?@-De^z4s<&}Wifg4k(d-eNk z0!pEx=-nnuNkxMdu$=&uX#WY9w@?eY%;wyICwxkH@JIkkVaePY+cR~q_dbJ70#Ld& z>h*d`;p<)#R`qjnC|%Cw%>hbqC`H}m@G^iB);4WDomLp>#zLtZ3#Ae)ly0*%>#Lnz z!3cBF)8`=3JvT`x$io3hExVyW%OK^(2YjAgW zJ$e2!?|aUt%p~_@CYjtj`?vR6*IL|njZt1V_bH)Y@dXxMU;5L4U(AC$>R&>&Mz3_2*zQD|DzR-~We zQ4<%Q3&pgy#0CTGXD7q{oG!o6P*lF0_M)#hqw~9=i*Kts^oglZ)r@ZQb7DObAwMgCG-7T@z)3< zCtj)X@o`ZWX!!s-sVZW8rly>bT>UGth6n`Fu=ggXBSm;x2F>;%q#GonW<@Cn+C62c zqTWJLzqn2-Pdc>uYUp@CVuD_cy3SQW<;D*S%f;eNZgrDUd|Y*pg%ac6QJ@#Z-cJNljXnJI$su8! z%pr|vBO6E9EEP#LUKS_K&-XrlT{e&Do1DE!m|jw%j&$@iePqz# z4Nt>zw8n*VLzHXq&Z$lmPK&7Lu$tFIpB) z+yh}!-mcGZPJ%Z*&)S{ZZtmGUZ!Oj9SMe{UO0AL6?NdVHg9`+&UzQfOJ))lp4`3X2 z{?Y-ZS_NSb5(qW_1^gF`WhJSkTH4{DfFy&;JR6e$@-ym~ z2o{EhD1q?FD&4M;siu>kx?NCQ>utat#lum$hc&gO3Zp?;C$*l*5TP4m^A0>p6=i)m z-;N8WWnRD>ND08LFQLiY8P+$US*@7O+r?dAgQ zu~A@6j{o)IzahW9Wd&2I?Ks$N8PcU`<=a#j<8;2WtElO@;z`-PIc>G>CVSBn!gvhr z$@oR?Pb;SV!;?D8WN7KoY4|tCUp_?8=Uq9LwFDYat*-o+2!BpkAt?(*oym{isAD?^ z4!>Z(4D1@RkiTuVWq_o!#_!W7kfmYVpg8=)E>O3ak%biSno2LJN%{50DAVE6ocHGM zKSE$tcx+tY@0*w9d_jx4VDHa@h~??8Ql566jcZ*-oeUM}O*113IL@&&;Wt2iaxM~B z?!gY2y9kQTI$AEVfxRJbLRYR?{=&_RQ!ORW1i56__h)02@+_l4*~|Ioza8(-miNz= z)!eWWNP%P@UU%iu+s{osVhf|>f0>|MlP8FR-`;!{8>?OGj-FqQfrShUj!Yb55L_D=1>VngIyQLcJ6YRMUq#bNBnC%C%-E6=bXL$*ox*r z=qqjk`Jm?Mrnw+P3vXSm7cJdTW8hwl%+7=gmq50J8CR28>DCHtNeTf_9*ROzNK%T- z@Y5X;eO(`^BGG0bfYL@RtHgKDpRyB4Fi?N-bmGyr5y@ZRdz`8Uj+ngE&X1g#OJ-4U zrKnoYVRur0_L;wZl?WWVt>Mbx?xXJeNK$A zG(A(zlP@?mrMFijDIt6hl5HREBD^i3Z#3r$VlyJSng6)W!>)|eLSkoYtp=uPAKm{rSAP6sDh6vRjeh23b;hJViQWq#BLZ03bN{q1vvulP^3j4mkb3 zbL-x|GrF%|!`Rj9tV_mf7*1x+Vh5G1=@e)v!zJS+787A;L07@6a8u1ASoA`^$Ul+T z1HS$v#2-WW<6Tufd3u?w`{8k3h(#El#W%b0bT$}w0-N9ztxrF@Pzaf3Fg}&cFy-hppBA zj$P|?s1-Y$EM0BDOrFh`@%C%aRLxknaAv1*c~DbbDyn2x)nNzL@EgR(oXN>VD@~@_ z3nC_)EiT;gHfrv%o0UFaZjr^edVI?fltb@*03RcxX1~OUSLVd=jGa`$MbKn! zpLXVj!{7a)2pQm$J&Q1Ot{pyYS$}{R-2+69&{afyQx3`)sGpucT;UV6pH78~HM2HOs$N?)otJEw1TuP+-k%QN z-+dnH^cpP^`EI8~ChjVmsun;Qk~A?V>GgkO47bjYY#-aIy*tV=j&C4m=hb*+oVcnx zz3JWyc<-KM=lB^!0PB@EbzNp$Oa4#spFpLW2pUHJThPpTyCdt7tlGp#m=t~v$R8Y>8RU5AaOYe)Qvj9hcBa-NNq>LX;Bn$nlrqyI8vYn?hu;5m{ zTK(X+s;0dzLANS@7#ZgLg50w8NuHg%eME^_Dp$N;xRJWlFxJnzP{ly@F*d)rMM7vn zO0&X|2yEnH3!>Mlfx_@QMr4v<&EH)X`3?uM;j$#&`L@g^@cdA(uhb^uvdzn}MJ6X- z(rX$dlI9b4S9C1Ht!7uWwHgdp@hY+0-8kIGpde<;Uu26%8!&iUQ(79nu6@sT{+7Wo zT|`(n``=muVpVUOXLvwzPm#3Gmy2us3u2Y>2k1-A zE(4HK-BpeqWtRi2VTDYE^&xhR;^`Wa5OH942Fjl__G&=C+)idX{Tt^uczm~$Sn(e*p0mpI_56~ z$Hv|8Qw~8CP+_U~R%NjA0SPbuFY!daiu?tuP(iTot@pyFU#U3Z(xiMex6gh&#y)zo zBR+E9pIm~rni2s2cf4=gwzOX{q;fsipv-B4!!kHIY_QH_I?XHXIK}ikx4?5<`0WRf zdfc4C(f5C%T>B1`R~X?z80sU~(wfDMw{zDuwK!Yv6RoD3)XYoykRQr_o36xAhd9YT z94-fa^elZpHWuIBL(W+ti_E8KiXBbAIJgwMwnuWTWd=3n4Y-1sGTCaR|EgTQ`@1yF z`AKG7_Im~R{SJSv1z+d~AG1}sG?f+QZc#cXF8J+XL33@}knqc3WR>l|`>nW!kFSVT z>F9`H?F61lJe9>IwHkSk=TfK6hLN>j9|duFW){6nRoV6Aa~nGAcRW5>@Cj44siHd+ zfA;?UpcoQI}Q7gi}PY5Nk}6 zjS~y&ytWXQ(=DKDfv53R47eMWl!0Gu0*8Fq?_GWl6cE%cw!?(n46fe4&e5d~jwcP4 zXHkX}OwxfG9JcFLuB-0wBV)7=WYLB}XNI!osvc&zSr7abX&*U!>*5~3pFI--hf(~>(|Hals zab9{bR?tHKX2Yj>SGlom5J#8#82ao{e6|V_$`TlI1fT7ehA&K~TaZsnp=2U4(D50% zk7ZgMxGuk@$!aO`Y~aQ3Gezikuvu$x)s6TMh7k_d0Mfo$fmVric)E#XlB}wt?z||e z!rk__uMyB-1|e}LKJ17ZKg=sV|4{XCitz*@mmHx~c>)N6qnwtqL>LzQ8dcyKt;s^G z=|(6twSufWkvH$MP}0@X;7U30#4bg}>?G5R&SdjMWq(mX(;COjEDt!N!Pa2U9Ls8- zcz6VTy(VrjaSNKrlCDd-PeG0TwNx_J9%7T6kYy2gw49WjWjwlHyfQ+Gsg3&wV>8e$ za=!aWxe??1>xyBkHVYATUYxmtEyh0HE!rYu24J;^?j3QWDB7MKWS5eOqo6?!YdDt) zLzf%T8n%!+H+IWxPGJ+;6F3*VOYty_0FWDntxwh?YUW%gs*OjT^F_v!8dj$&91=!^ zQB13I%oP!YN~jqC_}5fd{c5f}nW?~+uGZ}yR*F;rd;82d2u&@j6|W>Umfjy4WjMOh z;?e!8lVr37j%=-zwuXFVuYAM0#b=MpIbVC9vTrUmx>9^O*?-SizTl*A>iTcPurJ6{2!&RCz8;sQrlm((}Ay-=DC>PP|01Ni^MbXa!Sp?qg>d=q~fB z3A8rze>+?tepHx(iJXOG{-yCfgdfyE@g32N986X>nY!>p#AB~Di7E+ghZ!EG)JJ@W z8-x(0?aRxH51RZ4vIK}o4oBngJge#A!)dJZh3*IVIljX6FOV~gKtDpXOTvVHLt7@H znF!N!lMa)v`d8C6ZEVRPkh0NYH_yjQMAfa6&-03QHgvBH0(gVi4&oap7u})cksxNN z4b`>aldeXw1Q`4^b@K9`{!@WsVqSBjCL4viw(p)FWf4**ePpTHz}BhFAG^c#11iZZGru8vMeF~I*9%A%5bWUG%&OPP)PEA znfF$m-CzjBs#g_8sV>hNV5b^xvKni)PNyZso(RT}OI-Nk)tw!-mXiYZY z&(t`p+Jo(eIUdh>qY9FPlekgBYrD-n**k}+71OXr z(QnU`2aF@68&x`GzN^sgIToo>%wgWKU{v;(eT-#cqT+SGwj;JjS0uB4wNH*EjFVjA|5R*h+i|SX+ zN}}00?_tm7f9pYyd)HYJeB?5{dXuo!Aylq?N76;YlT=^8(k%CJmdg>rIuE^q&CKj9 zEH-2ieeAqnpzu66`wu#r?c#p-^CS&ijpFi zVWGvROQxcyo`r+!uLa=epFGwM1*6Ahc;LFg@Ixvu>K@~UV2K=jaC+@+`d7DJFRcds zENfr8xc4AJ>K?KgTxK#>RM|qORmb_0Mz>t0dMMsItyD6u6GcJNVXdT8B;Cs`c#;-- zyUFzqb@_AW9;74&9TN!g!PUq|Mh0~U<=&T#jK)E#Rkdr6kzsM$b;Etp=LNj6;{OL8 z5S-4?^>xFA|E{5}(?%f^;v<~SAf?97>8tOjE94!EcpBjdC!7Rb>;VcTq`D6Z{LAs9 zTC-mrR()Q#QyN_;jP}I1#H!d(Kb4bVW7@ELImube?T{<>Sy;sBY(g?e6@XQ|T3)}N z(*X$?hacnb|LeB?K+tUeZ&A{7{H}m)rkjeGC`SC%!5=ySL82F9Uz}ZX9~mh18M*P% z`SPUb1M(JC3V}X=YY2H#S9FUKNF7*c?`S(&X~`MG+|z=WvkM;#vfkNG8Xyrm@73Xg zoIyD@6NsLlRTvVs{o>euuZxJ%r`M6ZLi%=YxPcIAc9WC+;-w~3ui8H0qY2bR##aXt zUY5#Cqx&B5JH||2R_nnDIV~}JP^E6`)H%c)8XG)IN{oiXWvq0gOxfJhKH*M2{#1HX zpif<@W3hzQHFAi6SzROlbQkUk0RhTsIEo`CDfc(kdE{0Cm0Ld`1MNc=Kq0I;TMshn zo@jTZZbO~w%%aH=;(1nUv$P^gqW|dcfQ}xr`PlkI{IgBvVNE7eF~Qlz+n^x0Z#Q>d zwLZz!6V*^Yw_FYjiF9h*ar2(%Ab7O`VLCFbF<-ql|6r|q^imUoG$Fj+QUwo~m*Hg_)1efsImiA(2q zHsk8zw_A|1j*9iXoj-k<7KHE3(AX*#UXj#_Swm5-rok$CfX@`-$$y8bPJP%s!u8^2 zET(Ggwy^~zj>8E^Kt6!4ywYZxY=fW|f~fFtUibJzoEC4ONcg&eADir0Yr54qiVgqBgbhDf=_;8!ncjKR^!^1ts{ z$O?8Gdd$+u#g$DieHO>xtbH_URg&>F6jC)vakQ4X(h|Pq{~q*&6;pgGH7@S<_|j| z^qcvy7=diI%S+w*$EAe-UuHManx;D{p34}028+?mfRAg)iPP3tPO%acXiVFs5;c=p zcRSiCi81%h24%}Y&q9z!JE`W7T3lP(rqcQ@pZc!)N~`Or$gew|LW4o9b|$^)*^$Nb zE>Y4G->(++;WTMo_3_rud%QQV_{SuzRQ;#&pQlzL>CR|^UfC1)FRQ;Q)WxlK_A$$~ z)GeGF3zM_}C4Y^{*LoSCBw^%{hT37|4Xa5m<}ug?M$XQ@7;V-<2>HF9 z$~E7QH&JfyFh5wjN`N0VG-n-wV5nJufH9G&k} zuvDd7jb~I968q9jK)W{x z9B3y1J^^XVZggO8+?9tZ@xQ@3OBtX^@yGyRVTIwCJQijTT zL5!IZqBfb4AX~)5h|n}!=(L3LYCUB6>yaFK7Y{_Gb6{Z;f5n%Yc8%t*Yv*mO@MwjK z;FeA#>{qWrbjR9Ert-FEuqO#o^Xwgg%d;VOn0aBP77IyL5)}AK5Kf_RyWXj;$h>v7 zawy-?Q_-iob_hvSsx7RHEtGJYnbGzj-Q$VYYlZ*mv7Lw)vv%j;DU93Jzp_G8A6+2D zI+`!jMy1gUn1uDOfG&}#57Qghg$n`Z;DVrnz4z`&DivwM31p!3oUeo-9N&6gW%IAY zwXJ&mf5~a5%k|XoGynqRvsiIrdy4X~prY!Dx)_DEkfC|++M*0bI{k&$@-B~1Z@^{F^>KX&&X8*_EdBu+VaxJzt+5nW{~R) z;X@7*#-+!HvxB`L482-*%Y`2{g~pV0wjOsQOC`6 zTvVC9FphRMC3l>54d|XodW5xy;YfxSh=ySTfEZi{LMcFIu7fGQckkloTectoVq6}K zuu^wwSyfdPH^{>G?#z~iD~fRL$%Y5KVoV-S)M8K9o3QwK7O(OPP**cA-5e`d~7iAGP429v-6{TiwogiQ^n=ASkGnMN(MAx_u84_=WMmDg8k(pSxM+&K z*Hl7aOQZOUnr~S3&&H&5458|nRzP;a0Ephtd$sG zUS3(UyB3CU{*w1N4Ya=i1I9Rn^Pn&kY;9#~Gux;PM5C6sc66E!{z14yZ?eIb)1j** zEQx|^f9dUg!tdi-83cIx7Zww9auZDDpagAwz8dyoD{(}`W}~&Fkm3sxjN5-RQV(k2 zp(+N==P@0rX?~Fy)|7E_6ewat`e_&5AKjJyoWT?>kTv^KTh=I`YFXHZC!eN+mPl2~ zxb|&u>=cWct}11PQGH-A$UW7MAMZtRy2`dA*234DZkB(A2J^h!%;To;N|A+0ZRoB6)%pA7I7;vP?zeEatJNuT}*Q zuZVuu3)W(1uSJRn{PB9IMLnM<+x7%3pv;X`zh(k3%yN;3CC>yARZ6c8~ zx7SBRaGPuOe*&?Ei$RV6yA>B*ek*X(IIPQ(pdCCqb*UVj-^?!osav9b^6}Yhs02G- z%$x+M67EQF1)y-zj^wSEXU8Qs(7hoZ6JDQk;WvP~aNLlZz)w-|8C#Z+44sC#bstdZ zcJTUHt<(CA`$=(y6C#OQ9O~#gd-2zMxtD`WXdl%=WSWDa9@m9jxy=4AV*o58(C_;U z2Js<6_qg)vQNBZlpIOieUNT-ci}helbpA9u$fdSE;PpC~D|oF39WRbsZ$T3s{ondy zdA_VXBk7_bR(<-A#+?^Q+YLxsVIn{ZeLdL{B4X{6FRPkp2Ch!5=u>yRO>lX>bRe7c z{zW_^ZhHDFvtCn&CRjQ}>_feVNB_&-#-c8KR-dO}#7>RhID-=Zun3)1Z>UDu!4Yq8 z=*%3-;C!OWfX#{94dbH0b%Uht0UhP)9+Y8sy?6h3@8o$Oh=X#YtW98tEi66&YGFZx zSwGZ%chH2FOuY`3X@1O)6BzUzRih0))*L=F-oV%zGu9uXc00)I;=Ve@Ye>L3GCf(S zY%)H7F)xowJV zW23XGrm|t-t&rNc<)4O0C5n=aT2;?$_@Ua5C02&})XwCJ4ED$SVi6nK(9#PE14uhLImXoFG>3_?S8Ev^bO< zG=9qwfgoFK=wpzb|EIeQ6lw#9>2SN^d}^sB9Y)CqGlU|=o5Yk%IAw14I~aE#6WP$8?;h|KRG5IL5C_{>_dpu5$`e1XYVw-8|A|QuT@gQ?*>$bOKCC& zOMjRf^lglP_vt4{97K4Tdm%BC+j9B~v7%P5w$j@P)|{!nk`hXaL|hEbT0`!*(mxyJ z{6C!Tx8+WjoUf!oMhW6^5DbIGsI%1cXTr~)S08VT_@6SWK5BZaA-1Nn`%6dIq~PX{0B?s!sGXAT=X}@&b$LT% zIw?df%z-uQ6#TE`E``=}D_5A-^q(8j%7Eb3(&;8En}!vS`k7 z@mScl<2Tl;6`yLu-=VyO0wrRP8e$<-Ooh^qO;lgK`;*;MvuxWNt{_E+@zpkP_A&ez z$uYDZg8cSgj4rJYje?EL3@i2>pVG7=BqWQi@WRdK3|($@Xq#srK&i*N@p^aKv=5q- z;efo%*=2pv0Mm)SN|Te|mNw{i?4P^Kp1><&PT)6_bm#8!F@RN^tE`qjneLS*;~cq6 zqSw|Za!YBs4{R(Hum~>?y=|=OIp0wH4JMYT4|>Ll(6-V3lAYSGvLa`p3=*HZJ|b=|8tuJLPp)3}eLwn)5)UO@jK4Jd5O@ln zlmm~jFC*k7ZA)jJ$kIZ~pb&;ezldoGUAqqN@)UM%ZFwwg`;3z;M^#nrSXz(zrEgc> zr9xm75=Y)I_gi`O;8xGpQ2K@$0)nvBnY*(8aIO2)>)Ps=D4a^ky>g7Sq!P!)>`Lsjn0Hhl?4e1&dfO9A`y&o z{kxNdMG;CuebU5KfFXCQC^vHsyT(GdE)Iq-}HzN&Q4YUM?4CL*KXQ`*^Nr789M;wM1B zOp`a`751+sH`Dl|bP=iB;r{DlTF@{%fKEzNnqiUWjJC9mVb+5i`RwN?bq*NS^88ax z6U%CQ5kPxdjYjbD2l;o=-;D+-L4^x`quXiopeA#zK0Jn=zKP$jP&WO7#s$u7z#Vf# zDNGzH0|CH5AaADk;As4^ojC3eZ*e}DSN*|~ig zEvwC?}=9XNzyKSJGPgYpo-ET3FP0!v3hat3tT_?MtT*v9tJa%Hz0E<{c8(eZR z?r5>~a#>7eK?WUOvAXJeig6qiC-w6d+h*Q#05%dj(yq35oDdv3@iYmRkz_>SE@NI3 zs6S(SV(14VQXUBm>z`-0>pYQw-q)Y6TAZNi!PQsRJ@q(OqMQV63~Q=H8Op`&#T7*o zB?#ln31wiN+HoR*@I?u`vwE9M~|glR=#y#qm3!T9|a;&)$qw4ydZq%(pWB zv&dPxesP^|4Cvwyx@)V`;}lS-EHINs-W>b}b_3P*_Dv|4#z~jDYetZV9_fM{`XS?C z@|QQdE>pCQzj(8TT8$2g-Y+22GmW@Um8~Y%-(P&TdIBNI*RAa-g*ut>_vfCZ+5;jk z$4If7V1qBmmC@YzW9^WN14{a+1^X~wo$Rjuui`+SF*#p5TYeKfs|MXh0V#u8jHtZ{ z1c&7Wt{NvtPu&mG)nEQAIt^*IRzykdd~H{-)Z=3AFBv1RaNe1#3u$I-TL|*4E@x?; z)WegLu9$$`lkCJyT;75{s*q*x9YW<(P{n{{cXJo9?tIoTqwTY-48wwixp`=~&CVL@ z?N2?wnMsVj_aomXP0x+5E7*UUs(?W=3tzxadZE_pT3c)h1627TA5kmi)!H>`x^4PI z(CwrINZ`6ODXp$D|K_?tmyagp@@nZGF&RIRvAVilFltV3FQ`HPw;VN-W}ARdF#msC zvSGlS>#Y&+(~R9G=$y}A!ZcYieSPlgIbJTR8y#gs@l03t`*-{_M4D{8(SEw4rm?}I z-OBS7Y;x~nEk1O|O@@vJkH&Vj-otpl5qHU+I`5bawAkHA2R1P;+%9P3&D(a~6@^Er z>gb&1W%Iq=&bD;%iRt|Qq33#_+KV`^IuYpCh_?~t%Kh!_YNT%9^#Ca4A%d%oO|BNy zXG$N++lNfd>8f*gnEc#vD|lz zxb^O8R+c@{akL0m+qq#sY-sUK81R)?j%3bO?zy1JTsD!V^$OgxQAj=pzPoh?e&RO*)GLt=J7oj)LAK}nh(dEvR%Twsvm9tzJuHWN$Ha%}rq z*T>3Y{pbL!&hl!Y3J1%f31nz5;qX-vT_oDJsNW>qWQ93khDX4rY0We3>@k!L>gVNLE^}erb{cQ&m=A3C{WFwTc_F zhCu~k@o=sG0W&(v|fu{Q+^71E+M_%`p9DnswsNGvfAj1@tCuIMEqb ziRF=&AD1Xl3TbYKiq3jU!1eDI;cF`_J>M=_;wEYfW8$K?f0NDiMqUQ^zck zOaxPhZ!$*HEeERKqHQg8sNKQ7_tyOI)ZS+@_KVtIK_n$_>|$@^fI?A{Th5lYqM%N< zpODkrWNH1b>;a*!<=WpkThXlC0?rYE=jrI23zucz*FoPUWTwu|b^78_s&1xM{O2~G z8EF5HXWP2_gOBu#)9f3H(56N0-oHD5LOcLv*5v`9(6deMvFQQ5ZP+gk`nOw5BD0f* zhWY08w{(e7dco3sTLhsE18^%dDrcP)St7(ViyH!`whJT{Wzh^mboLtXc?h26U`{je zHfl$OlhG-7tU+{#27~^&7=^S@`9eYY-(vJ@UY;b}WyhGjAiIF2 zg{^Z|_+MCemN@%LTHu7YXME`UQ8oCKStx*^k2|`pE7+=cK-+V(2X=wE>(g1J!fL=b z24RZw1Sb?p;@w0ioykw~HZ~k?jR*JP9}BFB+8yvzwGgNS=e`RjP+}`5nuO>4ujavc zy0~a*@mXnc7Mv(%jN<7nvlA`>p21NQ0P9d&s#7=4(Z1aKdA+&q7-DIy2T+bf5Bn)z zKM6Q$9W20VZ&!0PmJqWX4=RLZb+=epT8mS+W+K=PPXFNkeK1L$6@?t-SLkHM7#I?F zGXBPqx6Ys^B>F=UZu2j)R;8oS)Zc9gaPTf*RGw0sYRScVuL=739w!#O`#g^fF*u4* zw8WFU-1gOE@^e~KRRvYLk{QA>D_$Esc$epps$+iY+os~J|<|JA<(G02#XbVc#0s&vg$Xp;pK% zvVP$AkCAaHe9J3@4#GLW0oo*hn`Bg&Tam1{>S|OtWAIS{?{qV9yzhG%2diApkqK@v z)C2yPi3Ttu!I(-AzLPx-U3ni8^6@90BW+IB9tcIfUN|z*R7XL@rAgyA+ zgvqcDz2nq~w4&A3KU#o73W>8xB5DgFZn3&OO%B%dOa|Q-=$?6?uL}EdG}HoAk?Nek z0aS-gBaC01x*F7V03{A_{x36X`|mks&&o)QLJ9!NymoiNVcN&Ig0M)``tb|$$4ap} zq8#OP{5mQUG_X-LBn`l-`W3WX6`7NpsMudSlQcCv2%Pq)ptfF0QpV9VQrX{sHU0ls z0RGm?aZurr*NK54vLORef|T%VW!X2Zv~FpyGB;X{HdFunWGBX>pIry-EL8puz|pDE zXtv1>pZi0}=tTB+%|31C|7zO_=YjVPXnZega<++5VOesN7Bu(4$|-p7{qBjD`nF7T z>->?b!%>C5D~qqXYyvISBG+qZl)_W%k@!Pr6F$u#IW72XrqST#rkwo#mins3HJI?S>nw|#}!mmYh(1E*XEL#*01p*7aY^IK?o zqE>*X-L67RGzR5e?mq3uleU-}g#d5szV*T^we;wTL2c&}wyG>+IF!^@e)*R5O zKk>gh$GoxiYVcm)h4}R5=oeQV>S=lg*2Iqd_9d{nbt*_ws?hpNw5KS&M8uED>#l9caBRLRi_jA2_YH~85TtT02LL*9Hw^Xdm zgVNCXB(<}nF#0Q57Zv@PR}daD>U(PoCP3OmVKL_K`~i?8*=Y-q0cjZ6T*)pC3=+LwbxF1eFfXvJ2MveAls{lgJvT1uI-cZikya7fPy4!@y1^t(Kqb#i*D3<} za(0gc0-jk;`Kk7d?@d1v1=gdVAPu&K>s=@lEHx+`cA%=9fmU$9swO=$2dLv6-5mvj zC#7osW4myYw#tumRS6yhvw8_@@WE3NI5)-n`X?l3nsd=j{Ep*zTp3=;^UtN zp3j;#Cb}~#U0a=9J85;05&ZzpmeH|vcRXdvOJ8=0-+za*P=df@SYMK3*v{jx?X2t;iHvx zMZilc{2I(4gTV$JO75NcBE&YQ#&Jf@X7G|7oS=2l9ojEVo{GXP#J&_mBh{EJlgLC| zRW&86JrzilK$M1x7~WViJsk~P2^}Ef4{AaZ2dbbHfdSW*$a|;?^&3Q#5J9H=G`(;6 zv+>9x>ODoa^X{5<2^)##ANYslPe*PWZUY`Svl%pEV%P$!`ae`FmDb-$f<6Oc0hFM2 zu8nTqi0xmi@V!kr%vKxT->fEmIU~%jxn7oSC!xP381gW6Q%{Jv5%Q982zQwoj+|Bk24eA)|KZBI zqibfOMp0&0*?8&Aykg&y``}b3=*!Mb3w4EGm?R#4aI1cBg=BRTz~I{5w~T5Vtw{jutCcqeTY2#tMj*VZEhB=L_36# z{vpJg;C{?i(fSB!ReE}IWMm-)i%^E1r;EBQ4gP)mWjoc`QQ(d{Dru&VLU^&d9WLjV z7G)lJVZjGF$D{BK?EAzCexGu|zfxjy#9>hCy78OYoXWX-xaav<{z=NvwMaM_$Ma^{ z)ZU#u@fxZmf;tr{=I)C)U8{@Jn>3M#=k`N3~0|X@!cFA<7}g&d48RL z21!bMLk1XOe2OroCtEN)*o1zqXaZIA8^oZ|=iLhl`@w{zJ_?LD&y~ftQZ;H_UEPir zuqw*6wVzt8+WjoCy12s=FJK97e)7o~D^*jy9W+V{XT6)i9;~4aiq8+&4G6>g-7|`rz|HGi(CRKR!M{ zLJiLsiCO=of1?7n&DkGKsK8m^2@zq9tu|~jg@9?B{+eUfS4*D&3?m+rqO-gm|{af>w z%id_K4XW&=<$6=*Z658pY}6CZAF<~z7hTyQrb0Mq1kpmBEx#QoDfYgCs^VPQ#+Th6 zp8RSg{r!F5O&S{5AVbeP`_mkLOxI3|g_aql@_J&K-V~f>_#F z+G_U3%5n*ZO;~Wb&}eqE|8lTyCXENxLRnAa94jqmlCK=?Y6eyhC5F-_22W=KQ;4`- zM$oQ@%vHIg5v&T71=E#b>R?+~^5*QfKmD}B z4P|}k_4ssnR@>RhFIdQbT)%4Zc^`Ui?~@Bt_jCg)CaMiaW#M|K!focyib`0%WJ?1c zPfVBPK)h950!}|(%q6L(qZWx?M(OcS&?!WXtzqAj@faiqAt?iwta%Ht%pM`KrZfMb z)TIsDgAK@o>?jqHHsjrb?dS6~r0zm1W!yXlo)75D zgYdzXg-lj|$P==A{|J;JBg%@=!~gM8PzdX|v>M9tB>l^=D*19XN>yQ7H{(#Bq~!zG zZ4CES1cme=%hJrgXGUV&AWArf*K|oL)JHAiN>BU8q$=Y$IjwptgARSJ?^0xl%iup~ z#wQ?#up`|Ur4SQ81U1n&%rRD_b#uY*B92nw`r)Y;u+fJ_P$%4R_X+*@N&Z_hdo?-lP7r)gNkpVK~#&W=ubrnDfD=Gu?o^c9oP z_i5Dg{-Ak%@a?=Nlgl$BnUi^)!*^_^&kO@MCCFVz( zf;_!~g3@5dBfLF@a8I}BNy*UUm(#`OdLZR8(Tx2kT<0!M3-O#Y60W~=W4ZPB?^pE; z@(Bjz__#L!fl1b`T#kN&m)-a`*$k~5MI$5f+!OpIY&l+ojpqgIPha{0I$@$zLWTqq&6DG&AReyz z`kPBghH9%z%woZ7nXr0+BOAj?dQ^^%Cy=8GYvlzZ_NcMH2T$jV6Is>~jZ^x2x56|0 zscpFGjFcU6nLox=-H^8hae)9hf1w5s6=$}qHrFrVHzS~#zMP2Y%@iT1rfU~JYSIJ5 z0@|jD>&ufdP2k!=cJ@OP>^jXwgv<^I!5qT3C3UyFbi+d;8K9*F8`@g2(eIU2q$mjF zq{j$=0Cho!yO2MUP(l=6#~Wd&OV4#Wm2nd|yXoSO#Ry!H1(6lXpdP=DwIFM$oisQ% z%7M4ylQGb2@}feto!zr^1|yZ{dbnFJTwwY*ZQvd?3x-0E=E8fJVOudozS0D<{oadTpy3?5&g*FrS zR3VotE3MJ_fnD!dY}Dj9N$F`zwQ0q9K5i~u$qetJv)q8Y3(eRZvApb(rzD$4$i}6Q zJd)q!q7gz}qf>v- zb<@uGu+={z9l%m0$a)!dw)_X6Dry!Y+&jKwe{XDdCV zuB`v}ba~BP_N6#~Qkn}pDP(|4tQHgYGxHdHdmfjMLeo*uu7Jg~*FN~&7+qK60;e5~ z!{@$$h#v-IH`W&UmeCCHkgPw<1F?d+t2zB8Q}i?&ardA2Mc{g+Fyie*yu)XX+W5O( z-|U|8W_MW_xD2*3;nTewkIWbm6cd5cHDA9&Z0GaPYi>?>=IUt`n z)x4_ImX-VfFPr$s9^`^O@^L|fKWTYyG9{e~G9A{o^0wCsBu3J0K*jvau~b$FoXXKQ zg}l*8Xp47mIJ|xmc`aWV5vQS}!(#0)gHt;{AK!M8Zft>{KrbE;VJ9s2;JmxvcKlqa z)-*Ufvx*X+DS^6fHAtqO8-vFYh?1UR+8d!tTg`7KyYP4h$#ptuIX$0Tock4HX9iJH z?oRDZ%hJnpw%n*T07E~ycIZqblXzln0~^MV=E?LrYJ0JwtWJfyRYGmP|Ld6U)-=xB z#SW?!MAybEVeUl$6zjd4nKX2|F}S`J6LEV#bVo^ZMNXqHe&Hij$enE_6bHI!t}!zC z?4Va@rA^SRC|=yy{A>bXls)p)u}C>M0Q!&S#+WG& z0rY^wQuBb?HeyVV(iI8sEKe`&1yHXZRwTR1}5oaGJl6NUr2&GOd+5$El5Jv)W(Wc zi}Ik8ig9Iy_d-%98!@Nu)xT^ln__by1+*tgG?DxF`B-mFA*BSqHND;?o1L`=f9DyW zHnC(q)LVu>s{W-bZ|;h@izgJCxM9V_d4u=JF))nl9~at`li}xj2g1Eyt?BU1YOkSE zZ(Bb(7?`ssaaHbA&M>mjr+n8?ynuBhGKmaSAG9I-S$O0&K9FUj@od#~t>zywAB`QDWmJhTiF@f5BGuh`vlLJ{Q?0`A$W3vqafeXDE> zboJa7w^d<=InKALG#loFl%F>5J!(9?)#qFROD2*}UoNfvF5%l($_%zu02MHo8qDvXn18!!HrVP$RKoy?f1S>KEC z!4FIF65DY)Pt*(VwY_!<%kRoa?P}+@5j3SDV?2%1{aynb)DD0%UT7^uPN_BSw$$S= z^Gf6&vd2T`qiofg9I7mDXgG!yOaFMi=(?`A$E{SWDP;Yst975c&Y8c$XNe8YhV456>l!w!T* zKU}Xb@whY)TRjj(Q}+Z0L`!$ub^dn(wBv@I09UDNqv(9DGGIQo$#s!and}iJa_$tq z-=m{C4;Mn1rG6zfukePNuEuM;v*R-}v2qYik@GsS?Q}S7P@g)Qt9#}S(7i$&4Zvd& zfs9-OuYPQxFZOTX-+CmuQ8zjz2TfTOaak`RUy6(O^RLVJ)t3{WP^-Fn zWa^4$dFoxT3;Qt1yQu-0(m7)~F!3>CX+M@C8wt)-nedJt!ZO z8mf`!w2cqHbho5c!5oarD^+#*ja%J5aMFUw6)L5XA?YixM&n?Ha4GA_lvM3et^@(O zP*)lnNQC(>YR^56@dNhCd9$aqQ-lJU?i}FvL;KtqY`pKf&9J}(lWI==z4${f)|q&( zihuvcD7D`iw~g_rddAlB(eitH*3`-A*`L?V)4er!$DJ!yZ4wbb22$Em)7ofMkrk|Dy|UO!jW#esA-(H{;yJ{RULZjQPAm?y&(^}*2hN@CuhY0fY|_!71mjPBeqz7*!51Nr}+(5KLJJr zGCQZu*oB#igVEx`>P{*%lt87_u{Q?=fGPcsMBpzL8{-a1OawO-iAb$k6P76>0RiF4 zk1R4+m)&sOV1z~mkPp`-Ig3Y?Eac1Jp(}tafjd`mqBi+REmxS=_RxZzpWjnUuYFM@ z34Wk>T24V5VZ;hzL!=MJ?RC?6XK0Um!VafT1{J0iy>k3kMM*m*$kE?FlC~J~ z8O89W-si>kH!zr&jT(@;bIzFnr^6O^1xZre4(6XC6ra1bhB}*iyls=Wq`lXigW?w~ zY;0K9OnM`Mj&lMp{Oi4NEo#R=9mQNw2(JzsHbd`8bUM)?rJ2g%UNYal*m;smM?!?r@daZ z_S9Sa0TjRsx#U{RLDdkF0%%Ikx1`cQjsGjp8 zgW6eMSKl5Qj+cHC&xvgvm?5Yu-Vlpc4HEZE2jv-UZSZeDhpgrY!+;94o$cmW>Q6gh znBg}-HTMzgaOv&O3VsBD;n8JU*5{i4X3}(PVKd7i<9}veuk1~Yi`{9Y+E<^&w1z@x z4@?$|87(*7r1?@n%`<6qPLh~Ee7?~t{DtJAURNf-DBSOCh^g{C=y5CEa+_FK_v;OD zt*P|*-g?68Z)|yBK1_|L#MWC$R@3cg=_A>*Fu;CchM?j?5QEVYKd!s%NE(~>szC63 zyaeSpD0ibj%J3e**$lv?&&te3&JB}WVI4_kbds}|>Y0kz^}Oz)8hf-6J@KNSj)CU` zz9s2|zDbXgkv(R*$Myqg5FTzk%wK)DqO=%mKP1EFCmYp?!)~P!Ea?yo3C1Y*Q%SX$ z91{rBGcd)_#oD&-Rq06q+i~pxBh2%3$$-1oIUn}!oUBfp=`AsvC|5Nq?f4)yiJymk zx58J;KEo-=b?~ z7XRg5b908XFSimQy%-N!8LcFxoufc*I~TeT&Kwt3cDK(ff&gMxu^3T9d5@TJL_ek> zzeHcyA!3f>K@&;YfPbh}<7vJwEFWRf+It4dMFLGiWp7g;fYe$f^lt

PjFR6S zR^WNQ&v3rKqG&RDSa#ST1uW251YM5f+!|F$rQ0=m+m`HYv1GGtn6%zq0|o|a*1A`3 z76fAcJ7s;9>b-myIv?&VZchB}t^3!;vX^%U?!J+(u{6Ysm&{qa{~u4uQIpNIDzVWk z7vLr74jcGCFG<4NCn<@nu^_aWV4By6(nFP6^v=MvI2IVQ|F74k>WbYFDj5nEwg-eAO$x3$+Z zVr1^?=a5iVh%~DY47XF66y7ax3ROpm_5xG&T<$oQ4~LX*ZG(V}c-D9jrhU%0#lZRQkjCDk@CRO2{lr(_uetAA@F%aH9 z-5UIR*~~2qJ1t|vC=`O@lRM78ls#v_GAk&L=Ao1`@-jWgoFKFete1;;a5Aw)g_KNk z*(?T0#vydb=a5r-$OSEub_HDY)qzCRK~Z0MuM(uVESyui*LzNtVr}{HY86tacn;hh zA60FDtv4_f4Z%3;vFD0-A+4XyfSe3G{D~e4tp4ZSFIQu@Rd_~W%-RDC)4bxxx+?PF znQj4#0-t~fzoyYfeOY@mO4N=geMz-#L(7zW07~c_K*w%Mw8MZb*u^v)d07m0mj97}0ZJ@`OZT|`WZv0XrGm5T=4 zrFmgU2mpJLk)cefERR&-RKEt4OB=VZ??_q)>7}Tx#D7n3J&&rzA50FV>`~OBw_e%c z+(j#h1U}ne8?pK;FUJcKoTj|3W#3GEC_dE)6$q(EtW7#wfKkjN{gjxq0s&=iwP$-n35s=|Iob`rP+O>bwVu$!Pmtw#l23zmL zgi5%cavmm4HfO|d@WIu(NQ8~Or0iSE2R)inOXz2T@XQmn-LE`DZ%UkISwzK`DDKqR z<2D3HXEcBxCkrf!S)HHd6k>Fqp=yhau3uiTdFn*2J*|8REE`y~8r59Br5Xy}1RN^# zC~F7YbJ2vv8Fu;&^t9#c@X(@!9{db}4*s1estT!S?>yix%55qVq!6ig)aRNpO`VD@ zX9<4!Iw+Y4FcC2+GkqJ|Sd_F3vA;KZrT^MiJyikLm0aAq`YstBIVLr)SSJd@JX|_R z7g034$20gFSnYlY;3e;KlN^+uUaA2=oFz1E3H`?{UUZ5U2mdw}>Ev_(LMd^by%y@>a5%H_~5aqdkAC@&!3!r47!PC-Id#b z2-RV}#IElWzN8y!Fkvi1H5DM=Ak-uFFu^tB1W)tj8P^a9mf2Dvfb znyvEo!sTqAP04%EwS^F=ET?GDRwKx>1;4+ZkwpKRxug6w0kHS~Xnb&(r!ZE>Kd!1@ zd_gMsgn5(#r?@XBUgv3!3rW8K6Vz{~!yOh{_pufu-r^_Wp^mOaDJ>W};aP){;qP!RAZe4A<+I)b6_EvvQvQ4+Q48F-sA>eLBhg!g$$J#uef<(pDO zS7d^X_`q*Fc^M{?D`|m(d<9sX7|#)seG2l6u`z0~gTl@N$FaNXim!#(KLy6FnZ{L( zi_sgGZKH^wHLh7OhJzn7uHS{G$?f&RCKTR$d@ZsJtP)8brCivYP-8$|Uv@~r!r5ky z)Vuc&d8T627b{O>qqO&1G`1dAZ; z;P`;a8QJA9R~d>LA=P)K3FtV$#WI{r@@${T=~=iB|7b!-u{;LB0TJ%lQ}8j2^!Y+S zc|=b$*L8<#A7ii|2s&$;f?t@~d zB~4~xsFT_oxpkzBeJ1HxHVoqA91$|rInS_{Y=hk!bC`NII^9gXz4HVBHue@D`ByL< zcV>=}wZCjCE24|IkeoEU04pigK{rvUKVgu_RLmtKAq@1I`pM1b;6V8 zP=7#K!t}{r4O!7L*&YE2xEF~z%an#X9NFF>j!L&b?& z8gw}o3dM}Wdi^}uUnUl*MCLiNPO7-LKaVD~0M(?pQzi1K9ib@{yV^o8zY>B)DrhCM zljcoGV3;~y1$1Trhbi%^OSCL(AUg_bEWu;2ein0#wFI2ggS@45e>!+Y=>avxM~#7E zlQFr#{{bI-9fwin2|r!6WiUPWL|o3wP{aRoHv;P(APh+1b~&x_{P1?|S>fb3hw|tM z>_>@%i2+3Q0Q##m(LM6gZ&Wp*vDLcsX<1{}soBwkb6fep@E}W0ivNQLjZ;j+n_K?p zf^_-guiM4$qBfbxpeQ*V+^5NCm2{?C;8VZKe_)8Yekk{{DBNc&X)H71lV?^5Ctx z2V#Ew2SiUhv~@0b!h`Y)@%&(YaSpp4(U+=A>plJcsMJe>IarH8jNY0z-2ZR7b?)VV`ve8Mb7pt<|YplWP%2e zJ8%*(va6GGp1_%6-9fmccXob6j?*jD_a$`zU#F38lzfphIT8+xdVROa7NjoskB7W!kP z7%oz=qfut#8-CgJWWwOOH$9Y#VB)mCRr9d-@mlZuGpl7N*K6{F7U?gr@V5-!SJ9W6 z5}Fc*C7V(mM!(58U7_7?5~0(8+Vbi4T}G&=XNP|Bgb_K!n+ zUXr7XAAWzK!XGLTwnS_+K|aIok8L5bR}bgVKhG+)E@xbIlysNP<;}hEl*350;4R4KVuamJfM25 zvjgttINjNnmzFThJ+rUW?oWA3F9HGQ)K%}R63?Q=!fgGdVn8Jb$i1Hw$*=pXY!Cv6 zE@O#?%BFLa`dgJTL+Jj?m8+Rxvt&6$Rr#<$hiOpRxL2PLYfHg2D_0wT`G#J$B6e>w^UT8clVja! zJkxDO^31C zp8a?Ku&Ib{bocy*IDHX^sP*Bth*_szX{J<*HigH!cGS7NY3BaQQ73qNv4qa5|gA3tB!Enl`#V&37+?#%;>w8KvbM_Dt+;mL}yzgz1O3OHS2Lp1hE z$-R$T_`cST9@ z(=sftsNYyC0%sa&nGMH6uX&d&6>9fr+z{GjGu=n(;Q)$>@{j5Rt&el!5BY9*j0H}w z$Nd%SHh?87pH->JV)(N#NhV-f{O>_A3ncPze|!q5BLOcDaQRr43s9M2#^ZoY+Gqc@ z8cD*+J7pte<9+p|I9!FZF*KjZ*XT|e_&?2NKCMAf{Shb5C>}r5##3bSo8>I$ z$(>=~NL%GDdUWr(&A{)t7Y%GGR*BlW%%1!(BBJ1s^JmA{a#}=#A7I9~*RaQlj zi|VJCTi*DOHr9ce8D)RRV3Fz-0UYmPBr2^(V;4q_HMc>iKS#3H!wG)bdO3mgteW|4O? zXLb<{x74_cXo3d7U(rl!bDFm?XxG^q?v{`_Yz93vx+9YD1T{)wUt0r5Ys*g*@*k3c zl3$`b4it$|cf?!k@vQEdej_5>jc$w9MfEZ4+?&q^Aqb-gg}<9P7qS!qhQkL6_P*dX zwdMJGvE}-NzkhEj-Hb-bWZ=g!6u^rf2EHxI0e4ghX*uV0du-TUyG2}`LuIzip(S(= z&aJ`M_@G;+24Onqv(BhgO-0nrX|1aGy>Ti&F?c`#wbRfp37d(P2&N1F2pXLi=!fC0 zcuJJOsHlJ%_PhQIQITojga0eFft_yG?xA2em*%ZoY2UErUrtN+MCMdpaR}epVnu4k$fd=Q^!?pA}D{OE)ouK^od+8eS!LsTZ6;&JFQ%^{D(^6oK_#h_H8L~RL;%9{H^^<#YJvhe${;Wcwn;lbeFr4ByPJ0 z8qG~AM^@UZZvq>GIy#Y?`!4&t!xFbQq7sd}&$r!6$Mol%`v%LJty)`5@xV%Y$@;@K zOZ^jy($=Emu5Qo9FGL=CAIB2?$j$+peLx>rrwuc<8;F2?P$QN4Lj@!2?2IlUot)t? zM{Wysg456Yk#K?Yh*;Eu7%q3mOq))DE|2Qay9@bHpLu`m0y`k_r##0xQmv}iL1N4S zSiynfZP)KLS6|bO^mJ!H$ha)~c4Vf0s*BI}1g)avA?{d*=CI{`E;9c7^w;Sk5It7C zMn;hbSLM5eFbAi z(q4zX@J?<^!FgPItU@Oiw5lNWMWmXD912nF(x265$fO7Q&rjW#C*@*8i17l8SPSJN|B!haF0t;Vm>vGk8AQfh0xj%<7doax@9WmLn@|xUYkWbp|+UKa8ex$FF5hT{(f%^nRGQN531hpX)QYQ7)YHbg z()5z_Fl1bLp)exNX(*HvuP0LAS?T~*ryW~-1hB@rgFK!(=t2+(h$!s-vJ4)vLWgj! zMGIs1qm$2*B3V(1NHHOWWB!W@e{~hGA7~>Sb?q8p6Qpbk9<`P z!fioHQ(#URn4&`?tl7e&ECQ|qY?`j5FJDqQUAa>Gz}cpxCg?X3lgh2Dc|KWpzfcso zI1Klu^!&F*!(S+9nbu^d;O-=eqrXyTyI9I4S+}?`IJ&>vPVLs{R05Tz{vC^oAeh-F z*$=S}_8#~JrJBCPO&phq8}HS0d^uxRwGz;84Af-wc494Id2E6EMJ_`B$p8n4iyh*D zqI#jqy5^559j@GgQ}lQ)*Z3iv`EIXY`XH?qYbV+2Rl)WPVlmx$*hz*e0{Sn53xf2B+5kp!_?N&8niUKr@YZ$S_S2 zf*CEaCO+N%ck|#O|5B73d+>g6^-GV57OeNOxNSoqu@iEtXDVrLZX_Vo?&XrqGkZ5$ z#HT$kvp}bl%eu>ow}eYnFy2j7KMpzWYFQR-_kfcRc7)jSy>^NdKaE(#uF|q-RFvATYro%#-9{k!G0E&6ztcgS=WV}U znwYyz>AmMCpk(gL9H*`bw>N;SSkvR&mH=r`3kbK#Z)>^KIgU5uTthb10hrn3DId*% zp|$zmNPUel?yX|?M5M%T?ai>o6TV1T!*vJWU8vwKad^~t@M}EO)5p;jkMe$da*GZQ zO7Ata4pdYhIwbrR)PUSq5$bQ4zUS&5udK*Stw@`B54$w2#@wYkr!VgAZPmn}i6aHj zBI6>7p>}xq{i7CQ-&x`Plf}@K*O=dw@1EDhfKkwYP+Z(M6w=pMT*pb9$$$ReQbeS;T zC>tMkT&4MSHeufNR;jVrpOcOC(@uS9923_xOt7$0$~BSOHgDK5XDa$c>A+;K3mIs_7%v;t{+f@lna7Gjxd0y>wzO%} z?yC<)fRar*6FknxduO-T&VD$+C%7}Xaehv%6M8cv@lCp;PV$s)kV^cyqq!{=`mmKF zM*{hjFqHN#Y*()Pd&oPIS+&3@%)VH+!x3#}SxrhEX>F+tP!Qwr3l6P?bs;FxDFlWF zny`xfNouq(6;6o)-X+|tkS5p(*TNWtJ)hg4EHtl`Q^o;jHCmj_Lx*>vXFo9XwH~k79_swSs`(1>w&1(ep)_78{h1&fsyu9shPZ?4vsleWr;jsby6-LR z@iE=^o7nn|xF{#F6Bf6=b}G}3IHW-{^m8>!^&TSG|EI9`!vcr zx5xQW2k^UOEm5N-;n*laTlq@%b;QpOueMLw5BI-B^Ezc^j9p6IBN*UgxcuT@F@ zdD3$4o&EtT6_~e1T*&35$e`a`HFklx*1i^R`5#f2=vsoF^mQ`I)?4f5f20Hlt3D}#H)XZ zgsbAYO*ZV4Czg-b7wUU%T{|SYG;i+)SsgruL?%0>AUMoS0h39)Qs|z50 z=OvaV@Mg~?tmbUM)YXEd^PGzn$sImWnua`9<=yG7MS|>J{~@?3oX2REClVDF5UD(y zl@}=Vr^3WLlUeh{`{2PSa~+*WoBd5!%hBHDs$GYd5s|smtIQsK`Gg21kWx3ib37j2 zxAsnk*S+<9tEvg-8+H0vYc=+9N4Ow;_yEnAn@`X0{!aVTb@AZoZ6pzi5!WM*B=r1a z+BF*=qgB2P2Kq2HH4eA9fi8W=EuVeaU_m8nBxbejwv`H!v6JT*dDog`_fDA@?UJ}G z4lviMqa`mz9;>GJP1wr`vaV%#0{3OsT}aOaF%FN&JlAZ*brzSYd9AWXNQ4o86bI^k z6HUg8`zsB0jFY%qC3l93;=R3oVd%ne0lk+b<}vly}u@ zKU-d?F{YAFuJoSMuyXUdJR_i2hz^w};ONg_-HSram2ePNLk|AZ={V`lpvk@cYOk_2 z!+M6}&8^))+if%}GT3ll`n`PV%NZK7LSx{4QXqV$fStkbb=kL0i{1i+#N|uBEpxWx z+2{%qUf}pI*WDiC7im@PFP+nnyg&+G#MEnYmmk%?-yrS)I${zBArGUFGSpMC2vkQN z+$y>O>Es*)T-$a~+qNZ8AwFZQiW5U2t=AAfhRfGcH4=}?i`@aUEWL2jc<$q%+UH5L zWe>i7*R5`TzDMqSBN${N=4Xq$)aRQxn!(R#Ye)6{oorqv-J)H9P#ilfM1I1qda@kJ~nrX?7kUd-3-A?>9q@!2c;vS=k zb_0JC2K_Qo0WH_$yigN|zZsz3(5$S{z&0r4Fgp)-HF)Mp7d}aR8~O){ach(@!4wN}%=acYeI)#mPb-fCXwUxo; z&tjZh@4$JgmR#@WSo~4v zPo(|&Yd>C16vBIs4@JJD^LHfiTw^`w1D zcs=ddx}*tm3k#V(F(kr2CKoz5Ge$@4y~Hkn5@^1>3_1uJ1&uvJ0b8qx|3w>B6ln^M z0@axe245L(p4>Sce4DdXqAFTzs}XSAka;6B`qo`_>w&4cOy^g(ypajKx}tI?)LrXB z4eY$rcLz=Mlx(Z8w6$OBS3bCd4EpsSGzj;wbqUesex)uI0ox|Cn;_=e5tD) zBS8|AH|zV$O)_V?-&nHZ+faK2NQ7}rYLvuEC8x*;3C=j?f2CFR$<0)&vVYQ5xmd-o z&I)IW+s}e^%t(vq8BB9g%v@lG<+9>qu%WUqrH!)XN_&IlOD~um>3g$VyG6&5u6iuv zbJE({=a35LhO%%=-lr>q#-|zu!z_QKMk7Jn!%*^c4#19w9;|oA+vF2BP=M z5BuqB*&ytsz3>~L;Agx&ZA2i{dB`*RLyS;$0bMGBeR}}EpZ9=%0}R@8RtGjBJg zR#gEgs-=oW2{>RhXX8i4daNTCi26MlT?Os#ATOddtrKPjO%a)62E_MJASSPQ8R-3i z(gVhE*_#dQ$cpkSDwNGG?3g0qIOP3@Vx2jUXGOY+=i|Yi6G2JN5M1@y+fnmXzhsbC zQAO^Ztfo?=4Y&~n_RnbIuizD-K`n3;bd;_8sK7?LJ^Ub(=yXP8Egk7;RnCL28a zNm!*>e7;7mFV>zkD%x|6nYScen<&5ZkK%|e{p4JCKl10u=9rDgKk^+xMfCGT1ayHk-0gvt*trzWnBz_K zhUIS;NjIs%9f%7RNQKLsntu;PAq4JquW%v=C$tUS*>V18;X2B zTq1mIl5>9+evo?b3bIKjcA)Xz^r~8?qg$RNn8cqT80S}F%NMp)H@wBtsDfWX-oHsS zrJ_L%8hD~v!oMiRq3i2DDn#AolW>E^6Jf%?Gg+18{Zuw7)K0bj=8I!G7|h~vEz=n} z3uGp^m5H0!x1rk}Kufsi<+PR;Xrosa)m^3%TfHElBdZT2lxJh_2fDHH;&U6lzeWyz z|BMIV+*7?^ns*iKnYX*L^lljpYM(iS!)XeBaKI*ipvV?opMRo<_lhPr;iR_36rrY5 zwN2d^Io!gS()KTa-1hs=osqHFNsq^?5Awd0-mf?^%#eI3<l6mfSmt9ulT~^$r z>TQ1MF997k191i}gxqboIam`Z+Wy;GHP`3rQ5Lq(EMVmV|AOCB>u|B1;P&KdKVC;Y z(g6)VI6}6NtER8&35kx^pGHZ|M63NC8ikllYvizpq8K2XTbLXQVLQd;_L_~{uh|R^ z>YHNR^yGv!7_Cv=_ud}?Q)+jGUGW>Ed%C~`xA<+k6R~JLJdPvZ5ii5TALq)9o1j#97n0F zBP|NhftKm}I=PXC&54IywVIu3WNh?`5?H8G+e{!NPOD6R6nuWf6d4OF-P~8-WjHv&SEB&kxhPfwGCT#Cmfl zR0ts1<;D?t@r_(GJ#41Tegj>D$t@!|sGr|&p6$v>eKZh**wO8kAQxw>zVM!F5^4dU z&MeH{iCQCD=gG@q@t+)YyT0Wh=i&j5*Y6%5P9IAdK+8|5!S_|WLo<;vi)9xfz?)y- zHvQ+zll;qRLC(w-{U0AHfq-T1rcl~AYI*Qyro`lm;%B)dsbE?{*3HX9ZSDjQ8n5?I zL0~X#)vgA~@_yX6eT)Sp1Q_Nz%vdc``#!-hc=?MlG-v!tf_#sN(fsWtXjLws~4Tbc3T(Nyta}DSA1B9V|lJg@M&wj2+$Grsk z`3gli8WhN%HiWGrJcfUE==YqsI!5wia@}2j%!_QIy~Nm)2-nQ}U?nc*AC>b@L^c7n zx-(OLk_7yF`o}XaS8P?%{NZwmG}_+{OOf6S7Nc0KW+Sn?sB2#0gXn%GSIPi=`X1vOX^p36Va%eL8O9l((n48v}LZ*Xcq8NfGdGb ztgXl*y;0BAulCLgL3^+%-hj!L2ga->>rY}eo3-w$+7@&!4US1Px_@4zqDcMEtW_@d zwiLx~^Sis!10ui0(-17noxS{$ugdwoigV5!&TvJe*^=lWz2|hq4#wQnx-HuFV0Ieg zuumpFG;%JV9Fk@CeUDQV94Jkkc#8SV;wI9T%+hY-g*DjvK25N0I~zwNrmox}h4WlU-HN;Hiszxc?&iG)g5?@AkYfzQu)itmvL#D%v2l7wc z4W4AC+8sU%8gv6&wYn3q1Xb@j?^ znc|=dqs`v$r%W1tLX&HJm%t(-zCV`1vVHTYbpIo(d)tSc;i`P>+UMYT;y?q5Qj^g4 zt>c?ucmyU(Bn?1#ZYL`$<{P;!yZ`f_@_9gYH0A7lp6&%NJX)%ebv|Bs`@?kfsR96v z!g18qD#+V&B1)>9x0+ul<;=Oea7{ANur&B=Oy1UUiSKXT@TRtb>$6(+=sL3AYd+oD z4-G-gQfle^lS!Ak$GH*PUPb=#3^J<+1ii#zRqVG`OQ%+sVF_XvL14QZ(+`(=FSLF| zE}NNG()Wq$-n_2e@;c(YV{+V{N>UXlHNJbz=^7$*)5zaQ?&R-DJIR4W6=D3lCfnPQ zk05yQPZMaNBJyt`#%mu9dncsLe@!J?P!Cvbv5vEBPqV+@B}5#*K>Hk;^&+^@rfma*XvDc-*S#{`|Bm7)Hbr(|Ws( zgA5z`Wr)*ec;SOgSC*E|vh03GalPj&zQcqgKaS1)9ENl@)y{Hm^dO`qiLMTM#C@0F zY0onX)Q33@u%tPtlskI9LQ6FeXLr3tpWLY@N>R0YJOOkwEr^Xee-HK^YO-@AiyEjH z#Tjh`+t+KMhw|nDjemS=e>u|5=m;5OVyb0j!&d1DiXeH#syCV_gFW8CnOM=$O+6A2 zE>2Qngf$Zi`mtj%KsSLRwpy_YO7#Lak1aKF*hHc25#k10^_anIE5$}_&+Gb-zw8i_ zCwYUmhoL>@>|f{w5_(QN8j%&lx%i2n=JJ_LGJU(o7) zR}OPMiRL2U61%~F?4ym^!+7n)=x#ij*d|;j(!M%Qya{hw{$b+D?lG)GlE`Un$f2oT zqbrsl^DcEdG&9fsdZ6*SwNhc;9;a@3k?v19X+6y^@{-?W+nyg_B!=ie?g*H|JhL|a zD5$&(1gltnw~7)mYa+Fo)p{#^C;y-c^1pxcnp_MgLr7AhtrgyqY?N*#mDlv$jGV+g zpO{911myJQRsQUkEN8ZJrJ(da8Jx{u@v^=0M=qVab3Mu06`QX&<|181Uay|{<6Sro z;tNSEAnS*tPjmG7=3<}J6cyyk#M2C=h~WmeI!`v_U#Xg)*>r8Exl3?ywmh$pLjtX%o#UK-DmKcXWvKJI$#xo&qHZI%5v`SR+*Nx@#`1c-UI)(n3HUJ-4w&JK^If> z;#JqUQ%u5^$ylk5g|b5bo`z1K1>^?WuhjdYFU$xj^3{I&E)TscZr>x~^dV!jgX(dM z;e29{OGFD-{=9_j1S+SyGU#39@!xxe(KbD@aSeu>b$>nI(|Ad=HO}&pN z_La#Ar~2}L6Cs*b9~9t_N~-Vz$$Wk!)vU8_s}n1ZR>7s3wP2BJUledB)$3Bh9~@-p zJwB9ah>M++MvvK8Md3n0$9=%OBO1j4^~d*CZg_66OPbfED+EE-HrA7Vxg5|58;Y8A zfLtEx7gA+CwOyPeG+N7A-1a;<_O4My`+O)(o49wMUOga- z>u<;_0sE?sNk}FIM&jaL!~5$=T=~-ttYSRazxjMN3_{(-y|Z^L+*~p+Dus%hzY=YI zO2|3Kj>*XvOVwsj8zoqAWk#ViA_r*;`3^-sE8gM!YrB0p=zq3_g;Uo$ zwrZ}QW9U@D7Zg4ji@zK%w|Al7&o9 z>>CSvVP+O=B}JGTzhN`hmp_HQf>jfy!< zgrDMfr5t|cFe=Waoc)4w1iA$Ro&hrDwrYZ-mg+xQune0Nvgnv`evZ}_&i-lLdZBX2 z<*qeHwWB@6nIZFCJSl2scz}G4p~%)SQ1OIm)94>%(3L6L<<4bFFz-B=1oM%Q2CfBk0cB6#&t z41TnuIISaIF4}WP(Rv+%ufDQ_kXuB(J}&8EONR4ep}mNDFr65$(y9TlomL z@~NH*c?zV7Jl2Gha+B^ddacinM9W0)irw;jE|G>c z+SI1o?t2LG*5K)AcmUv~e=2$rIG7h}9wrq67iRiD6n&u{Odg4{Vqc^R2-n+J0}oQh zKfn9XguO`wdx@=-!9}}yi}8VZ;S>B!b6%#fhiW-UnS}_th z?^oWEZ%T?Iu;qyD?Ir1bue|}uqs9jO6!Bu63jCJT@@#zaBL~S*`Qk;}9@m_f7WK<; zBQm(W0rWfy9y%*9`P_4Mdz|E*Nu`qBp;5*!6n7LdV}z%{&BDvv{x`)^)SL^_Z;1kq zqq_9wx!P&PSZ)3vuHG^($~Wp7B?Ke~5y7Dm5s_w)9vDOkX;6@EhVGD|r4*5r5*WG! z>F$t57`nTLuA#&C_WwNRyuWk4&zITvb?s~Kwbx$jZ_mdlE$tKTpSiM?izFtqqcaD! zD0Ch=#>2S%`Mf2~HNC7*T5XXzil&0Aw4~!BIgjBz#1&?bg)~vWk$CoJiD8SB;r+AS zd6qoo)UhJM?SVkM&}`C(n4XQBdy%#_Y?D!!UMZHX%=U037o%jmn;#l-aIfT`ypFL{jJWrrmt|w*ex6HPpD2=5%div z$+?DfzMT4tiTwLK;V1{Nw>(8XLx`!<2@s4+w@d=M2_kP*L;FSxd4No z#He0V8D3g@s5#MUnTK>xv8$Oe9Vtmvf?Mqp=JsoH#)0yaS^|L~r%7H)R_1IWE;_?h zIKM3su|cmoIH9B>5zqZ>KpQM%pAya}X<+xs zhj07C44p}SrE&wWevK;o2Ty0F%~;Av+yH1OSEwWA4MS=*IL{U~^mDwhs)V_9E*y9* z3DQ&PMPaZf#7PDv(SE$&!&T)pe)Ke%+-2XDOFEx^H|J}Lm@{3p3{l^S&Y075XtJve z(~kUYIs1WW%8lc_*4Xk&&e!tuRcPXHg~EixhY~g^hQYz~QF|Py>x>UUgR`RrKAe3= z@g0tA;&ki^eLqoi%(|$cvnS&(+16If2U^MO{a}81l{arjv-A%xAmL+T)BF?n1{uAI zeK=Po>^x4fua}?7>8~IcWP(^-_=gn~`gt{epdpIzq3I^Qv?`3fWo3Chw$LdnwGWA5 zF?uqC3<59_u2&N9*2eDhW#YuDy9-26hXoD4ohYLfp?Gy#gOsuS@7b1tynL zH#ny6h6$&ShJB{XJ^a1h+?Yf&WzvZQB8M-$`x{0n%tva+xTl0vRKy!UruDcC5QEb(W<)19) zapvW6r0Gh=Ewt-V5l3ta3Jp|xhqBb5_<*Z|04g~`Yw(;R5m%seTF^@Z*`r?|mx>V_ z%ornOl-s5lYERe0Rq%^l$->y!Q@yHoZC3Wnpe?VTwd+4hj#Q*qnNP{jl3*aM`?g(Y z+kb(hs9yZ^U{5}2KoAWhct>v~Rt^d5`Z^FkfSU3?<`k{fZxZ~4* z71g0?D(Q(n;6I206QD35z8Ey0i1V5p7Dn;++4hI_9J1s~oXyCE?f~KW&|(f$VD;OB zi#%my%xIo+@9!`FjT^BLSOY(sUQl(f^t~?vjQ7In9POIUu$RLhNklzBx7m)27fu?T zcY9t{A$`Et_vh^)yV4hpTcDHDjulSV(VSEEGyi9few0V`O^I&?vK8gUZnFj(NzMDD z7(8~fig(+Oe*tzI+q)%k9JuMB&A5-yV9|F8&Mp%UTo!mv;xMCVf9JMaKkj4azSQWG zy6oNyUi&rm2-~3(hW@B~se{MtXFg+XwnW#DU0Q$jpB}bZ4K1jcoe<1YqA$@|cFs3b zYFrQ8q;9Q9=m68?o3O^?K8~xGzR$ZFyyaDCR}QbQCRp`Z?T@2e`?d0*KHy9bvT5=l|qwStx6Hoa#vM=X`j zF$Yh6P3EYa@PT!F)EMl3JRQwdj2TxM@BabcDWl}QM^G5$K&r*)h)>>Xy?;t}td69Kk&J8#@!Z4If-mme6wPOG3FI-!9m-*&q*_IK%slN<$HLimc4WD~ zX%e%{NeP^6#l5?rtG3JpzPn>?+SIKDN{P+4e}Q%Sop5B@?QToodGq;C-#SxxacCA( zA64nItq3vGP}^7e{!yZMTlw~Q3M)EeZOg-1=$j=6^P8ZfJ(!A4wJeAb=(L9xY;Iz&LFf{rv6)3Mpw-`{$?8ry#GEDJgeruuw9fx=By zOAmGR3X_elcWeJLP~*bhvi?ZP<_OvwI`FdpI%1o^HOTbUsn8dmy_EL@AZ0IJF(?_@ z_Fpp~b2(RmDjYE%JqpaLZ_!&t^G@o_6 zF)v46{a!tZ4fF}iwO-WA{#=s+^t&YfCe3G(I$x<3#6z4Ny*%3D_kY-gDZ1KryqyMb zw51KRoHn`yI@!PZb!f~0+7H*SgNb~}u{R#mc6-0ucRQbN&zt!pOPvLUO=R2J zh93z-Hi)S_7=%A32?C2>vCq;+-YF*UBPa}K04=s69^-q?7oCC1-xHwCiXNvNpHP|UEjaYe-6L(pHW^vy>;giH3^FKo{} z@Be5t9!k&HSX+B^x6k?6OYr@|AOm;DwWi@j^kgoiJ2EY5^>7$+&rr47SaWizOJ+Xl z>*)IJu$YKZeY@)Hy&1;YBA;8Po(>+ShiuC4t~=(H)fH+6$Q$eg2?c59pIUm-;5qqU z8P!YS1mi&U>T@a}hbzdEKjsLpu6D9Gd7X1nGjf@aso|T7L4SV=UDS32_A?V9hfQIT zn_l9J{k#*qgwnW({ZJUFjUjcoA_v$VBMg6!mJD1~(f5r=s0t>g>T3`FYPJ=V^Ei)t zJTh%Rvmsw7-L6g#O40{|Pd52j(4V}|w&0>Wp-V)0y)l=sh3anl-D{Ren0#3?VhyfV(UCV} z%gl*(pCD~CC0xjs_odICEBN!m(+LKtPaUn89R7^H3bohbo_F>LRxXgRaW;W|$^S{h zD<|qpH<*acfDZ#%U_Pejy?ZmowayPML(T9KEbCGAl`t}(x2V*<>pdGI93`e2#D%i5 zWsW?Lnl;RN{ZmLE4{>P1=pXpe^F+4Ov2~ZQ!!@1Fv9&2dp@tGYO}05dyG947-bzq5 z{3d&x-i$;aSW!rPJoaAs!nSs~nKsFDoI?8AhwqBJqf*6%CCrunPxtMf0X6&e2s7}( zo$z)p?z+@o%!wJ{Ki3yelwKCJwHiFZ6bN3L8CH1TU6P8pUlgSXdlDL{_=)&cw9MIc zDVX)^gH?rKG}k2YzKO-7)Ca;Hvx+HGfq*T8>J8+^dg?R*qu$h%6jVs7mPeV#z)9~exgX76@4&K znhzV|`k0>!-v*3@`s%B8N{QRZQhlV2LQ{3LlW2Tl#${EJWk_@PyyqGOb8A}Jzs|_Dr>eF)fw8*pdeHV zC*mlLK6Ost>3p_ajsc}pyaP@4bOHrAC`!XyHnmO7q!s~!iM6C|%UI#MQo6`Uydo?G0nnlG8+H35}Rj2f&Rl9+c# z4&Af{B~U?k$R}1CiT!%DxT|`5AJ&*1AWM#xuVPZ5TpuQaKXR_uyKaV%Y)QUipc7RN zA)$MYd#!0Y{;G;oN1dZ$V~nX-2Orel8iEC~0OMD9Mp@};udbA9KIu>@)D4-Hs28UD zJcG5-E)4vwA&2Afiyig6CP;F(03I&%?Oe{>?Ib{j!;Z(!9X|7y$G|%Zlrh6D=q2V| z3CCASomKXFf^8+#7)oU}bxaMv#ek(J;Dq3I9)^ue04oTjCl$_#n=LhLbbKJg_aWip zWp#Xm^SX5@p6D^Hm^&wuF^jom9M|)H@#|^pPgNJ+VcPawjq_F@C~9=@>wZ1I$PtG) zsLvmlV{oGk3J>(zrkfI=JzYRAru%VP&BI>8}Z}EkAFr~^^feWe>Rd@;Jj3b z2#^sH2}7zQ>C%-G4Gz^Lv)EMd&*Imjt4k28IM4*{9orRsF^~TGQ^&4G-_+Nse4reN zMY!jbic`NWeT`9g2Z}MS1G|EaL_a-`0S1yZayE_T0(v}B*ia}VFwrj74_xe>=6_Hz z5J?ApGWYVG5ObS4*8bdC>VdcH#y}E_t48ZLRymDZ=>YSyOyjw)chwi!?azJAYrIn5 z`LZgonSl7?A>-XAO`&Nn%N2wWL@lY{+=cQgp;jF?O2S(eRh*&1j zR<1u%F}S~qEC~ts{^>hSap@%w+}bp9e@82gk^$LB!}@jS+(Vm5WWzhlgMkgcZ@^U! zT+vG|R~MNsb0Rl$GRx1#W`GM2^DaDPqg>>T13>8h>ax4~r59BwyG1)VM9u3xSfrVHMnyYIHY=`s|L{bbn zv=QGRRQ*jE!H!QdTUNU`oSeuA{j}-GJ|st~18bvtk5&Va&pn8)_hwuYKG`@Vb>Tvb z+Z;>2+3-^Rt``%E|A;ljF=aB;6$G~8bLjLP5qtCSsr+hDf^d51tg7J4V3WrA%%vq^v=?UhHK#7MF15t#&0l)|&Hil?=T88k%$@}wFSn4Xe6_5#;jPGa<`aI;?X5hsnMx~Bne2Tv z_^0!aArJ7lC_=L?Yk?BziMgSUnSQ*-Oad(m*N9Dg=~w89*CB^@qK3E5@_=F9B@;CB zVBu$+myiwL=njWSP=!+~6F4~aODO1oEihD5Uh-m9ZFol(aI8}0u~a#pqip^4^-)v? zEu$8|s6Y4g)2Ae>73})ciifD(iQfsY>p0u~SUOpyouDmZ0AG3O3BNJ@@yVYdKEN(N zbXKigp+>Lk2R0!`4_Vo0-wL=?5LRS0Z}RxHblzVp)~rxy`*0iHp$!Y8^f@ifpxb@}uZFXaZVgd1m0}Ld^fRv_0gV_R?!lzT5Jbs$4 zcj6e%yb{6k>Ai<>gf~|zKd}1h{5vr}b8YpD#X8pB=V@&a#?1WvK@+$P`zOS65DgY| zO{^pb6eZX`f;%|$?;n?fD(>pf`Rn+t?f>VyRP<@UhR(3i%j#cW+90FeOqqWbTNMx( z>j$82v%Q(BD{+q>`ei1;H)sdnrwUX&WJ#3GORHKhEox6#;6m-F4}SgOQ?cF8X6P@u9t3G~e~KEuV7&Z%XYv{*fNj8RjQanI*Q zV%reoBNU%g(cIR0&kJj%7a%@dNO1y^W;`3^jiMSzed0eXapdaIM74LRHj1Br@PeSGnk5aL%+y`En!EB zKf}d}r^%n#a@#F_@Jph8XPIx`4gYRW9v2$kzU4M({7fplzvaFoc{OavvD9&-=(j6u zL(u(FP*?ku;*x6T^UQPL#nCUi=?}60ZE(oS#(=Jie6h?@vyeA;f8x*s>;C(GSb-I7 zdh(kTQJ=S0=XODUNVTbqUugoZjFH^aI4CW=*4kfOSP1g3%nDHD8uACJjt}?)BCwE8msF!7Uh*4=o|*+23kJf zt@GUk!U z(0et%1n7rjBfn^HplFh>ZL1V!-+0so$%6KTh%lw5V>!C9Ke98LGg4nwHq|U{&Afjw z<26Y%CYF{<&zHOithi0XL)_^(f=#xJ1Ry1`Y7zHZSZ=gZkAQDeg77SwrU<#jf^x){ zL=|W-M$6_(a5}V{RySU5ByU%29JKODibPpbciWW> zR=QdA9C1bPZ>I;;*vSa* zAkjj`%&RjnlXNIa0ygfoNymMd=;7r%mfPs!$jWj?Tv7?Vl3ZoKPanI}tPpjd46&bo zuflPPygYIh*Q#fosDi|25Fo-I_6B#svn*S(s!dNEA@eZ^_hH3lQ)8`sQM$Y}+$;`ii?UnS5E@-H;IlJ@juebZ&?`6J!`-9%X z!jLHaK?8v)LSP1aN=Y03OHoQ#o*!SJO!xR^Hey$P46B48^EAi_EM*54ywdZSs5I}S zAJC?YYTQSShL`N?u*0I>hlIF)s~&jgY*NmACilZR+^Ymezg)R;sl9`VU@@Vr2> zDnmuuyGOVN>alTOBKwOzX-l+`Fyva=5L=uJgRGA=@`m~fG~hXYExyOCxE+*eE3`D* z0BPdU=<{*A4=d)kkI~7WagzLtMSY*`E#3F0_YXukGQD#AyuMxeq>bflGSWEw;XH$m zSWOh3V*tb8#*sozJvUWCOSVPJbhTcx7C8`x?)GBp8YZG%TqvguvN}6G2JV%wn%gzq z7Nt1|G?ah}z4+3Ju+`dS8o{I9_vuX4r7iNq?40K-5;>$~-eaOq)+RZRQSS3A?$y<< z{kYK1xHsBrpjjjVqVKKs8xGDrxt}Mwv3m3MPkZba7ksuU-B!E4Z3|`L^SlRKpJQ1S zsQS0ZZOj&KJlovsrug`$q4Pz0q%f4>FX%Y?)SfxQ-mx96x>ZV^9aZVQMb- zqNF_QVHt?Ne@Ftql}vd(?Fk={F`Dl!k&WS*ez;k~1KD>Q1cN2V&)0jRHJmX$@?d_~ zD8)ox3SYMC4tnhP-S;o$+;*6-pttIgN4G?GiMSL!ve>LBD}uNSqOPP@ZgL%siB`PC zpFKv%&f$8CenY z6|D8ysr*>Sa-G2Pf=|Q!hBD+ zMWoABg4r8p17V;-7X%I@6T-np%TLGP}~D^)`&sMr=2q3t=E^Dr8#*lM2U2 z8#OG1PN9Rm?jJi5*QFpjaYsFwaNF;p3?YyW=D=2fFJ*;`8XYnGsdG(})Ea6Cd zdG8SoN%(?o*}nLK^K=EgHbg>*Ib^BSc(6$!v~v1Wu0HqjQc_#Q$PV@DnR@`zcDC?* zyZT35A-w~QA6F%%TJmN9!)iFK%(u^8CGSdB`{-!u)v*!z;r1- zvTdIer{H5qz$5$N(|{w^_x?v0dQ%ZVKORudmHxJpW#Y^E+6WgFG^;6M$BQW6CNJ_L zz)Sq=|DM_9uPwwF)rEa|8A1;UH^>lz#x(Y?&VzH#67*GCK%GS5`*a|3x zHo%&17~Je$joH_qS6b|v-p>yrB*eg!tq6Rb&8c&bo-d4O;_0gS$PQ@`sPxIFd}G1y zN$h1YXYxnR{A~7zV@*}Iry1G!h_Oo`@iACND+5d(93E~{wh+VzG90LPzI5B{R+s*p zpX3R@yB~$(7N?fcIpZM`C3L+65fWw)((iMxR^`Vwh99^r3?}}%{b2dKL4B(}jj4FBeVH_<0*qMuI~&PR~?yb`+@D;k0S~^ zR?>51jbZ@|9_i+jRPN-m`4#jlu@UHHY}t`<`EY}OC?!ywbcC+H;m&kWmP}PU`|`g1 z;WimrBJ{u5UJu%({*i_c=n?gelG#_>4bC3)45o^eHJuR(8x+Uk5hwIyb}9h+AUVPb zOzas*>px#tRmEb)@&+xBeBo9_dXFB+>;^0gS-B}F1iCxmzEgM&3(cc1ZDQyAJgis$ z{#%l;@DQU!@JS_xc0naXk?z?o0VuwH8=L5?vT9;UD#d+i8dVg;zwEv@H`AmqbZ_v7 z+jb;0OEfzv*TlL0@b-a+?CkYd0mn{@#U>s0Z99YQl1u+)uzBT&%21> zd};UDZ7q8?6&AU%*@$jv@l16O5>2Mk3TK3hFFluuqsRa+w`?ml!$81-OgIBAQ+TZZFfXUMn4y8kScYJR`=o-!%BN2z^1OV$hX4ILOF`z?Kb6-yTO=?LLGk{{ zZlnN|vFp*ziKF0PQU}{QX89q%5gG=@W`yF>(&l6or;WWc6;#o^QB3(R?%K_@zrAkp z`f3laQrq~4n}nZU%%%9|sCyD{0{KiB(0s~Isk@Gn#`FPjhynd&)wAK-mj>N>r(x&N z5N>#S9{!GzK5hS|)6WMM_k)+C`A4oe&LxL8iF0DTBA^NCJ46Q7^t~G4PLJWRNRO^L zmvZ*4ln%k&0Ax(OdJSd7S-b5s$gX|5?1`&E4FAlID*Wr<_w;LagrIqX)W1`RhXtkk zJbO)LZg=cn(jOtz+-gO~>($OnoxVA-r(5of=g(l9svHI99&9c1s@lIN?+2w7vit7g zcUcSopql_!lOVgGK;FP}{gLP8dV)FZFZM`_fE5DS-ApC zw>(-~k59E{C`Gdxlj9U)T*KLBo05g)8NndI{VlNVF}Ym5<1%)GsXhW3`rb($ZRQVUg^NmrDlJ zaXe6%9xc;ahTH4>W)Kqqo?!fW``G(SNr93nB}g-+Tt>_ZgrN)_GFN#ya-iWbFsb}r zDQ>WGssUcIJ5#3%EU<9w2o-6ham?|14QIaL_iOWZO698^p*quea1dfCf^gggWe3`pD(?nc?e$QX)RO(GkmXvlo z;ll4b_aTYbH>DXGa!ze2uUbncn{0bY_HW zVSHMMJe_;%3HBh$x~*8Zd#z{Ll>ejSl1KT2T?~}6Lza)!(F>Jf+ z?p@fEgCBH2n8$1}#H$yI+m#*`Cy4;!;Us=wbZ?a+&PcCvE+eBKjNUTya?^OBkzVY~ z#4f7OCCi7@GLT}>kqu%%v*RalL|IIQ{NHzjy`hR8%fZRu4I2e+nk|r^Ns*w^dZuC27zCwFm@6|jytaCkz5fBpU zkI9MbH%U3!{1bzBVxeHT+ZW7v>IyDe%~I{2yLeTsr1C35Cb@EM=ar?_4a8bn&nzfV zvt|Mx2MsZG#P(!H_?-?%E|N6Y3nEA1NJ%V59i*l zIh3KFsn_;BGXWmfi3wb2Z~xqdO~$%WbySPz5H7R}EF^%t))m*`_Ae+vqZ^1QqzH&- z*HBNjP(8{?yz9h#eLG&eVn z?^6I{b>HAZZ3_VB6&J2gyvoh{sV)I>;96lxbBt`RQi5!*azY+bk4r_e4qx||kO}9z zQEbODzVzVWV-yl@=~gK`;#xxdCu=3mWlxSEDkzHVNpx2$O$5BxCITKwCqfZ!#TGsZ z)=xQouR)sE=Q^`XV!Nlkp0hs5ToNR#&sk6Ss3fNM18rrL+bK-tm_i6>{6$a;Nq<(G z03?ROly-aBeJzzQFWZ_rnwL^_5T-IF3+fFBc@Z7_nIA7~E&hBc8@-n5BqW|LZkqQQ zKhKaGC_;cT+o5EE^wslj&i1xQpw3qN*qe~#{@RXE?m9=e_oU{@^BH1|58!{Xc^70E zTO0%&AbNj>f%d5uKgkphhXlLXEi=!;xe$nj{jb3s-R&&+zFt9b!NfF;Xt5NwN~$=k z9?d^r=f19QwC0P=KF6(}9{?Q)%UVuCGY8KqUBKe$DQTOFagOZ`+*oVdTHvt`Jy(S5 z{7&)OXmZ-i)(~kOGV4Esk5P~y2;!Nds%l9yHz2|E`ayhfS6`L({!0y6#xJTpmvD7g z=Rp*k0NK9~9o6ALn}5+zi-EqiP|ZAC%Q%WYufKpj7|4Z>HEb<$ za_Fh$TAZ=avx$&UGR2*qi17b;1}R^OSUe&_0ElZuyF&B8zq-sToz3%3^Im7q*O={a z0>q0~mGWBcKuPQEk6e%BNx&nfLZ59HIO*nl0K2ePV^#oK5P5S}(-I3R4KA7fsbz47 zY&>q#`iJE6lT;*%JnZRH)qkJbBRul)xAT#}Rd`Lgj-{1Pq9nohlBl|4ii|;YK&n#! z(g_OymCrQkf%=NZ{uh!pP1TQtS21VcO!0*p8MXXyFEdA4b}Fv@wM)sr!9rGcad-*S>?;gFmQ*;{o~n{D2jOBD1OppA5k@sdN#pc-f^N( z^HxorRWrAg9!SZ**G6zV`Mhj0n#8r$YMYK0n!HXquKsaBs~UAS22%mv1ZO-zl0hqI zpWIqlHTxO1WNVqeXqsVRiIPUoY=sYXokB%WgJNG8Yr88r+x@nQuW1+-z%Jtb2%CQh z18|xeQx5(<_5F9-E|<@?z4^Lr?)`n94zzUiZUf%HTofB~qbXRl$VAPf{~b^s?t7>L zluA}fP@53NG>P|cugcaM&`Ak4DobIaAnzml)^_xl5SxzrAF?Hgg-3+lB_T7a``%xI zzAYy`LNj;pPupcVWbg@TAR5wa5-C&lPENMI;}(B&(vIOknGTs*54kUf?j5Xkxva{6 z_t3{dw7dTn&vfN#F$n=?WZxUWBo+lYP)=W!=gQyhIxl{a^6Zj}FdfepQU~@wl7rZG zFrW)y(;M2XGvs1c(iiHlOS{SbC3=MCR53;0{eM>p|t+hEN zBQu~Y#D9TJ#Wl&hLs{(>`zG(B^-bXx*i|rA3UwcVx0EVf^8>S|2P2B<1Y27jIU#~v z**QTChis!C_}Q=YpX+!^Y)?JH^E_IN80~m0Q0U65}z=lVf+pvzaWrWH!b7ZiG2kU3N4;!-X@K>z#{Z48gFv>Ik;*C|DYErv9 zPyc;Bj+0M3yQ7|pbvVVajIBn+iLHgQscc&?Ev&Iwx9YqE&*-kFA* z;iQ~8TQH{;YWfo}``j@ppHjIJL5uYEPpIG-UPFeP-Pm|u7x&kce1Coms6~HHV)Mbc zeyH!nB)z67(^dR|j%Htc4LSOqN!K$LQAf+z76K^k_tm*D{W~4=pWiJS+<)wzI2_vvaJ=pR z1hZHm&nS!)~{w+dl%Pk?6D6XdtT~o&{RLK+X3b z?$!ZLKZr#^W5YJgufNBJcZJ>uUW>${x}qv9TnP-8`4rlgp6-0%FHER=k=_Mf!C;w`J~kWXEt%h5{b@c?9~U2BMQcR+wa*9p|Y8%s)4@#(&iX$bHX zzSRW~kQrrQcV9$1^7DM(kLsx8=9cF{Hu}C@Reaohl3CsBGW?TCAOGCV>{W;jpzFM~ zeUE2UKIP~pDvh^--w&VloN3_L_25EtIn=PVy`Mkbfe~UTsuC;1k8)^iKEYvFL zb@08VO=*dHm>1E16w3z8r$*hro&k!OJvYH8=D;&1n)`0NlW{xon?{@*(oavnN>qnV zzHZVp=B!tm?75+|_7OcZz`dL{-p*p9J%4vGP2qZkJm9JCX>Dh$5wv7x2U^C#n;qLN zs?lpf1#UA*;NjBQetsZ&fyPFi06MWB;M&e?uaQ=vRjIrJS8DZELzG*g!1XFiBFQCW zPobE7pB_4`wj@s|#xB|wqE1w0{M$85Fbn>?nucD|H-&^oKrWAKN5{iPFX!C@!}$Gm z*i=05MmE{|$7 zJ2X6fW|$72avX>FcoMs049r6$To`qg=}=CDM7Hk0#1P_x!CG66pTfh2+NJO<;M@|@ zJU3jc_AY&2Z8!abaqmh_V&*a$SiX2`Aufn3hQl5G-bS;((rR>!M>cg2Lle(_CB>(; z@WZD(>a@aU#IeLBXKOUa1?JWb9{pLw<1uSH%`k90odfHS9-T_ zw4SB+vp46W)(5s*6Mz~tE_{F)butfBSUy*nElM;W5Vqd&rx2j{dF^S6+uY+n)%<;p z6qD~NjTeRrx6to7K&t+D)u-J98CD){_63+f4bO zLTDe;qFHex^mQn@pgsnhb%3)0r}1S3TlU%V+-chmjyng-YQSf@T1 z49>NA<|4FPM|71E3tUf`}E5hE&L#d)z10^n>NuP2wNW6D-VO&9*@E*b1P zR>)7Vkzl62stJU1HJ*x<2|WzQh=PX{6aLn6Q=*q);&|k5fKHI%H+5@wJTZaol7oAv zKT-z^S~rO1(^rKLcqbXbv)z9x{lKQ1Z}0+%Ii^nP*ZTgwUhD;QPsD)HjKdgc$TSiP z*h^g(0piqhz;nUEA``Bfx?0XNvTkKQ5SmxOzkFHSvEMy^;#B98S|&ITNoJU z!B>~s_}%9|SlQbC=C(gA$k9EcbCHjgZp=^QOzJqN?maBSdhyJKSiT(>ipN_XE30?M zUvO(7R#DwmtEf=JKZsT{G2VdAMT8Mxf=)TUrbA4>ToYl^S^fxTZC)P^cX08zSxZ{m z2}olX9t%(A!t~cw)LrX!B22_f#Bmv`BG%Y0Lq{zzBy9p(Ev|)+Q+Ql{7|(vif!_1F zk5T*~E>A;4gA>S5Enlsbc*uu3lYe(xGWkEJ&14&Q~2G2F-fqTxFm$<5<+T){rLBDmVLgVKT z!XsMJl5p49LF+lDE)n$5T-Xp3mbhtGxMq5&>Gv6$-E1m}hdJBp57y<(Zw2dgduG;& zFdyf8^r?XyITO2<(Jz}kY)Z?gzYk7!H?H^MYGrjOA{P&e0m{HOjw8?dAbZ>P|udp`+8pW?24RF z8tK&?J0(eaRL|sY|8&O^YlS~~n~K|@q@qt>-L06g2ebs6Fd9SpBXlB_5$IMaf&r?7 z|B`GZ2T_GCQJkEcQ>3D*KfiG^cWia-d^OSc4|SOMAJhTm3&%kiATC*N9p~D>5Jr+k z?Qb$F!2p;na`1TJo$KRnDMpot)qC}Br`zL3lfUe70F1xb$)iNWyf}*Ze*+53${@KJ z`9<`=vFzuA>S>@sd}}Y;Y2qS+$|1Gt=uaH1^vB*JK`)Pdy(Fe$M^!j?uJTj!s0BnK z;~lj+&k_n0Plfcim8wM_^7K8E00L+*PK$XdetbL}NbP>6mWyj|IT;@c>QBH8(9f`I zQ|Is(ujHxYobMCP3Uv>=3i(@I6q?Sw1$cC0iyU@h4?LM=^1E4OTo-irNfoyuYDJ11 zkHxCAYI4P3;GsCo6@6sf7%07U#ARrKmfsl!;C;J zT!dUey+vqm`>U_##_Nu)Yj(^w@j&CGcX(x-(nI%e5b}L3^(gXuCEosat!lEgNfZDr ze;GtV{>=$xr(i_7C2erg34;aY1ednIh>7}{Yw-Fs&1*6+{2FSi!}Xz%a?uD4XMF^xqE?sc|Wpo)3?!w-+= z_M%&WW+HqqgP9v2HL5+4I`8qQtfF%LqaiKRMaehP46;T5(u&C3UEmK55u`_ubw@xM4+08zeO|^F~ z=O`?*zfO+j&5&`;`oZfhbAf+>l1)2lAzp)7dH`1l=Ta*pQaiZ{^>dnpDWO>U-xv#^ z+>cfONcYF>#0iR!42OybA-`{cD&A7Q2N-!AtdnA*$n6l8li%!B0Hn0H)$L)uQWh6b zDRv5(52(hKf71j91=7=(25BS%w3hNmR_B!BbmDIK7}XYGrVX_MyL_+52K9BSUH1?_ zk`HW{FFRBFYj&A>PLB2?%||zs%CQw#tg&(aq>6!HLnhiyh;IYQl03kVP2rfwse`XZ zd5Fan4h}pZ1h0~f>(m{Hun`xXaYJf@?lHOlKl}f>s%7rnFV=eO>@N_UTlI5zq@M{!D5wWtos-40kptJJiAc!9F5;$uH6+Q8T8IlI6rs2B~{(iTu__Sfu-9of#H*0>zw%o<> zc+BR=uXkzEO)jn~Rwe{oGn}8q^?W;RkcJGxOpLgR&z7W(u69a>`hf?u7Xt|Mwg%dS*+9kLHKKYe<8ADiFE3XB<3Zvg^YyN zT8t3)Z~-#wcP)&f*Oad+H#up&7XGC-b4S=7maPKj5Q500+q!bF(WRn!Q_W>#*!XYI ztH>HM@nCdnh2tv$qF$xvUkvPQ?*pxcPb1GxN_(4z1PrueBhys0vrnAX1>8O04G^`p zN{);~Rt}Wk@XnX>DyaJvvI&#Vko5mR#0sHSeK3!K1T^MEXq^wFpk5Cd&@G01PJS9k z_I%8sjSxc5chZc+^1gqSBI#kEoGQx7XnO}+@I0r##8jx5_e5pz+usOZo)Po(edTEc zXf&jqB8qUvA7r{BO3!5`eH)B_DjH{B&o;TI9ZlA`_?ItbG`g<&QZfxiv&fnqMll1m zpRjF-gxsy~n2}~Ybalg|ycE^6S<;_|J1l7PvK*jk)^8=)gSG0Zbgs)$`DJ$6*DF9n z`WXI#FPm>;`cZml4R5cs%Dv9*Zx4Iy zeA0Y2v^_VrfK?Ia*nc(Tty@$Ga?Cu%9ffaREhQHV# zx?q#vRM&U2CsO1GC+9#3rG#67%RfpsM+xyisYER+2?Why^b5qt+t1F~s}8GW!SSCO zA$LaxQZUe$VN7+hAg48!`kfca;xC&O7xN`NF~Ni)rrqdy!<bF7_>tz(8gtjoj1IPUX+I z#RvWLl8DEMO3+>p9@DpqVx&yv2cL}8RaSrnZ@hdc;d-<}xKE_MR=gW4) z?ci_DQ9fcw&dCwz56Y{uF zHUAJ8$Zp8zV!O`c9O-@B%XT<^0@rVMTSGsnL+rh{IVt*Gha=Is@zb!Z+2Vy@Oh~TZ0y)H9CX|W8#x138GqVp;}vSuAqW$Hh7FUU;~6t!=G7ZD5jsb6 zAms-ze1a+|VR^7AQBb3g5YY|XkAY%>tyg-L<-m;)&8*hka)tt$G|q6@^T+o^?}4YV z;d=FPEU1p%e1TlpnV13}|AO-)KGRJ8<_uC$qn1H1zmX}x*#Z++iG?wcrHi9R=?A#? z#4V+9((}N0cB6Zd6{4p2D2U$z4jw|Y_z4Ok#Fiear|K0KKp$sc2zl4wohhAcjF-zv zjExW`-*kEAu-5<^^QHA+jOQUJO8xIB;vin7e)gplXoAeII{4a-fg&DX^CHt*0ks}r z>!sPW;h(rEpkvKd;aL2kj84qyS5#XdfdaiddG>;~h<-$}LA_IBL{|eq>_xlWdDzpX zbAEizW2g9a@t)^LGH_Uq?rOK`7L^5NX*K5$dKqFh#E%o2Am1AL_QvM8I?By809gSa zA_Af(4$K7gaQ^}Stp6n`+4RtZzjGO<--H&T`cv&n?1M;_%1|o}d;pIbK9I{tM#?WX z-57vWt^N7>4S6NI34Hu{_cegd8SGf5KKTfgY0lp*gyNIxKLKbhHY4KNkSqfI8yH6C zktx&wl1W9dp|D5&rMQ!v^S!w_b*%1_zr1$=)e5hMf%>L9pj_~tKA-A$mw*5x6jQpQ zxqqo0xqTn=R6aeFu{_@+o}e!OGKi6$@InuOb;%e-ImJBozXPh}=l^-9016k5%HP?L zA6QhNm)YTT(6?=$M1>PPwxTr!#eRDw?Zd-L^yJwLA+a{rIWQY0!%rUfc0)*lhjIw< zF=N>1HcmIXq_qw6n8xt8!I@iO!JG;ITK|auT7NZNO9+Ap2N8C-p9W$BP6oI}7>h(I zJ_pKm*)u3m+1X#9*8Q6RGh#|2jH6yh0PE@CIFtZgRz`oa zT=e=Au3nehNtY6y7x1XE9WN5jFEh;fPlW7jz zRz{J!)aNtD6{x1}o&Oi^*jL@f8hh?h#TQj4mIbGSHM9ZXCs@1cLpdBl)%~}&cA)NB zZ2dR(_#?`xSMl?B2;t;zp84(i*ZOxcKW;5%ooBUxv^7)BKoug{Aa)2G4>~y80A$x6 zGKjvE@W!K)OV_I~J*Q2}q}OhvWhY zK`bjj%|GGuiL|J?A>-eA%D&-q*!kzd7a@&$!1k-1hQeeY}jx zZmZ|i9P}#{;@BM$CHzpK_PcgtSOD&pwLvXZa72*r?X+sDm@|d<1_hdy7z$yAL_{5c z1A*i}_0`%U%d6?rP*s;&W?#3^el~d85yW$&6 zv%tGE8^O2@5-ADAi!T~9J5O^SbT$K*E3#wb?_+U`tUdNx&ZPko1n*0aCnfBWpp@1d z&@8h})Y~KOR{zQe&ab-3M8=hbprsFKt-UN~sQyEns-!Ke@&hJHzxJ#FK(Fp?_smFy{L zNW>g-xNi80y4&c1Q3j}tgO8v5(KKb?z(813JjcgB;req$uMh^cU2fAx?L_V zOCw84UJ>Jp@^d|Lt;zd=VF`DsA?RbgX59XjncwGa`CIKV!XY5?NoHf0g%hTJl4b|{&S`{ zzEXMF9HXbM6@%6Jz3a83lJU#eo5D~cpn+o%QQ(+CGzJI3`t|$icQI=h#01@N3g!zV zT|zSSI_rb4Y+oq1jZXluma%@zhmNh|qk4wpthyVLML@9oYYcEcLf|qVkuTdsy-fw& zJLO?ykg6p=6sKgXbyruYC97HS(=vE&v69k`-eN(W{7=;bkOheF&^v-T+sJ51*Uu?` zL%`GQ6}9~s6sbM3`_Xw3p>F_nfnBR2PCOsm8k`koi;NYw$>-#7jy@e9{~*-upwagC zzwd+#+linEB*m;x5wGg76TbOpwmlHJ!W|BCY1o!zrwX5wcOL2i z^p{ff7L#0mShg^{d;h^4t5NR|5f!tz?G5pVRSUcVspE@yHa+eO<+A_zbK)a@AbSe_ z3wy4Q1EHCq+(CuLA;%`toxH?m29J_Kup46)2fdqIs+Qco>5A71In1C{z*5|{2Qr`h zWsAtCJ0+ZCYkO2hH(*%4>14Vm>aesjOXKV?IhEh$P3bAK)!)2de2;1$_C}I3W?mxb zcg5DXfBsrp2S3rQPgB z-GKZWA+EnTv_-D>cKl8dvnvkCtcLzi!{ceMt(GmN;D4On|Nc_^@HL+$Wn*u)&=mDC zbjYV#SPhP>t?&QD;9C{SIAXZA-ZC9fho%dO*>ySMn=dGSqhS{X`k&&>qN4p}YR6Upfv)~HmI3K_-Vhoa>~-1Z#&Zejm-win;#f8JlDMrqBcE@ngn z=8e!G%a*|Fmm;|TR%$_#2d)P%h&-%}wqU?(PV}nGlieTA94l(X*Bx&9m&^ zZ7t=dzS5vW-&-5K7JThNtDYqKT+IDCjB9niDzMGCJ;1x-FmEu(v;=^QXk6y_il zdwiVlz6YAt)|Jw$?E&?R97*BlSq#hKhg*)MzKP*Z_aA zb{!T7MAv6K5VoxGVTk~HkbP`_E@@GgzyHy@P2O&f8a;5TjAkM}*&N1%Pwd$uJ(D}3 zY}w#PKbuVV%-MR_Q1cuP+>O>=Lc9N=Ky}OGrb=}!lN&zpx!wX${^<#u1SrdQO2o!N zjjQcf;v=#DvhxQEG4)LWBwyQ_@UJ<)&DLU*yPS)02R-F-klF8uj;#A>aL^9`lVa|( zHaDyW4W8dr(=mt&fsgec=vqI zW{0mWe0MK90VHq0X9)pGKDA_UG(%PkewBTo1pR1@|vZ; zh5nf$+WxpQ8}?w3R>&W9ae!j#^yk5cNH=FsAT5-BRD!b$ z0%f6Cd%ZJ^I^PWT+98gu`WTEH=x+~~EV$ApNr46&2*Eo|ZCCGKc131Ai5XmMuJsbq zC@M5+_9y|OW<>zYoM$HRPQj}smejnbN*rg(rzU`>0sC+s=}?awfuA=%d~LGNiQ=Sf zbS@lcm*-J6Y4p0(uV|xx?k;mRm@RJ3lbo}?mb#+^dp}Os<2Byk&S;%Z$pt}xzA;1x zUwK7nJB&Ph)U~drD3$K-}n>M8-V|dz35R(p$i3=az%r>!>ZE)a%i~U z%Hp0<(Zj;l(bIf_Z%}FsGJ@b4;aL}D7db*4 z#4Gw^ZBA;iyh-(PeXF}Br>nxEWOQ@eMkzhK)}Yo62F<2)(uPg2E$pS&1wxYSa7 zDctEYB|JI!EuOjBYPX;@hRHbSI!0;$5U40F%<* z{HX5bN%k$ry(XN|;bw|OOv5oMaT8evlH=#98FY_$9K%o^G#WEQuC7;k1~bRjoL^I& zw~!XY)*|fzfpV6)4=WrMHAr{j@N~Hx#9ImOUyv=;;acc5ADasJ{Q6DWTdcOM2 z(op3id^fy1k|Vjt5}%XxKh)_QJWIv0vX5ZcP^fy&{r3jsgwg)IGLOwpas^vy;?pl? z0)9X;Z-weZRFVpVz5q_^12T0PSlx{qFT<@ zIFpFwZ#CPYqcQY53CiEgu}=`ys!aqvSdqVbp6U&V3$*c2v*I9fP3N#Vyk$T;B;~`) zB&q$h#N2YurcLi%WLND;erAo!zSw=90k#Ee{FCJZMlW+~e9rR%kmf09w&c4ys)Fw0 zrmM6o?l2ABze5@e!o<#?%6%yk9P)E9a9sfHTM5fA+z3L)ZPG&^sl8L$SHn1I2}Zk z@*`45>T(+-05N~uq&GGr?LneVC7CS#y766$7ho8SU7o$o{4_Im3j@vQurC;Ug`er4CtGQdk1`c8{xFnfVrh>(EJ8-B(cWsFT>KD-Ng|$ve3-zx2$)3 zg@5=MMZw1Q@1q%}VblrSa0!1juy*e!pMWsvlavvq;+|!MWrNq2XaE#Q_mkTm2sl0Y zq==$?3=Jo@#9gbz-Qo$K(*+OtS*M%Gb-6RM9vU~({)ca^>{HaXs_E=-Idw!Wy~>cc zzP?|^u^^wHkzzC$o1qkT@x0$f*A^IyKS#V)`5{ScpoK^hih{hp=#@%JHiartTnQlT zM;+`M1PG!66I|x`UtR%;k|0tIw=hkY{FBI0H`Fi>3cMMTqGrcdfR|Y^fT{*Y1JC&V zfQYOey(a+4UX`IgnOo6#@F7~1)q?q@0>18>ARR3A;u4N9f@oT)ik8P9$zyt6rNyc~ zdj@D^Hni<#5BR-ezEY}M(c-e<=zpTN{MMNLE~CDKuoSg~>27E1fZtILl?1Zzy#yD$n`}#0WWT6AwTyheUsgW=DfU`A z=+!Y55A~aiyIFtY!|%}?X1pH7>x?6{OT zAs((N{%3SDowkkZY}u&YxDY1Pg%#?|Bg%~X;A2MjLdUz2!;*usHkgbaOvbC=?K#+~ zsRMp4_8avnt_(j^2x3N>JNK<7%{9iq=BX=O{B?`}yiIkSt{`xsYejL++he<6xQqLbIlv{suj>TJL%w48ZqJem3fj zD&(1t9)C3?It<%r@20efz=u7k-=#;f4CQR?^jX!@7+SgKG01B_kZgjSQu*!M+WWvC zwPc#?=x{_zN1WseIT?C`iA^>~fQ#t2q;_MJUT^egprD#WAMc#HOZtLQA~#vw8bU*G z<{lg-M)Ar&_7dAGof=0@V?wyC)5Z9H1!JbT&w&478?#Y^)7PXEPLIP|h@baTZH@YV z%y6o>!sbZ2W9Z|dByZx%^a=qyA7|L3P3?rkwDSty&A*R8+T^YtAo+_)OZ40Y(ye2S zkMwQJ`N^j}AeyMr_jMEq0uRh*vlX9sYrp{N`N)1DSyG_K?uB4Co?w1)Jj>faoqkL) zlYHe(@tqnA6xw zdUQt+1xo6h6Y+!1iz4Y?f>Yj2G%DoiTrp}^624z(v3NW^Y~-;&FDO2mC0e?mlbs+Z z=5L!lvJO^nL@v&3@Dh9ZFzo3}>Y;WqjY=@8WE(Jm=PGgTt&Ph5k)dD7f{xTUH_|S7 z>5+SN`E#!&xBZyoSQPQw$>KL?kabkrXZ!ijUMQOAL4H;knO$Gv&%vC*8i^JKFe1nd zr1_+|TART%K}V}$n4lJa*>j#BWz;4+&+Yxz6))YCmfWT27&{ipA#2R)v1w@(+shh0 zFLxJ&DeQ`r3rCA}w7wAt@8Gd&ZG>d~*eYjV_C;`*9mTtB>&}xya8w5ys0&t|H68)) zi#QRnm^lR4h}l zV+(-f7In)FE5zM~U*{+^ z@=m8x%tD{4Fdml!p(~~pnkJ9tVl?Qe)%viZ%ln%%H!(^uimS^qjI&rhyM|msA%;rO z|M^zh=v*1iUc-ltxe^t50$Td+)3S1EdO>AdNr;>c-W9kd&^-*=5K;x`aok@#Ne>fo}hUYBYg3lA7=?Bar zHqtnW^~>W!wU1>2QjQ$$FXoHFNV|DU}?lG(=F zI@5w)A0B@LMdRv8$}y8Q0gI8#<)6qbyP0x8wLN&yLRmo28u1NOT)0$;yz0Xx>b6KL zkV&N)V-Eb3wH?KOqHgQ{csI3Q+1k~f-~{DzB_!+3hGObZe3LQIItihI{&RJa9z`*z zn?;3g4p$pc0mDbyC$=8gbVirD9wwRP1h8Lb`oHtlpB!w5=w)L^FA1q&J zTvuLrvhZrR?<=DR=(>seuH@Vg^KvzskUnkwnd~zw_^q@wzDFsFFR(Sx84OW;TItDV;T~=iH%5y`L6OQoH6!tr`w|FMq#(OE|rSlNZZxJAnk4;PJ zdt|c6AEdb5J2CJTwjmM{J&?YjE!u)N~5rxhSi2f(O^72gFLmVF2RP1eGO1o zX@ue+Lik_QIFDvTh2PPg%H)(j2OSc~mRgIJ+ZXd3r5muPi`=80kv zIphWii{{(YX;YH#Ep35@q@92yt#H~n!xQFkQA(l z+%V7|N28QTX$#eE@zpAXX-XBD7OAG@ZCO!1h;e?(OzcG3YiV-Kr!#87r|iQ;@mgv? z%zrzQH~xuc!<_rh)!&&yPSgbFtX~;pmRcSt=*om%G{H1G62U{D=RCL-bY+}ol(zqK z#0Vr`8cyUhV2vE1@yfrfvsjE+A1E3^G;pu!AX1kRv?OX zzT@do`a16vLZciG{o$`6t{i;KR7l(xecWBEqtbYLJ1p$w?}Z7iD?6KcWGyQ8{*B|> zbYHn58PN9_eQjVZNe!|5&0_vi3it#Gau*4=ClxLumH(yHQTYnN%hNf6c?6p2*csJOU({i@b(w zX{ic*WBfe6HO`rj$jVD>av@)oV{@|d+O3g++|UT87SBCJs|LTx&SS9Or~oQmpW{p} z=#U_BxgL*q#u=N+pAFjHZY_(`MbfX*xk?fFD)s+%v??h0e@6N^KmX9xV>e*M-!zX)Po%xjqKfHD(?Jp7CF`lKTqZ>H~ zPa{m$lDG`m?#CIK3}-kEU@v+i$t~$qxIAKi@IdxyaOv)l7=6HZ60O&=H#*TmxwNzt z@EH&-?k}24&~O6(oQOCUDm5nCuxM!PKHs&Qyhhz_(#X}jlXBo#=%;qIt3aROU8QbA ztxO@oIZ%lW9sih_x||7K{gPU5?`uxc)0R)wQ`PPM+`ymH3qP+y zv#~Z+O?tPu#E3dc4?J3{#wI4~M0k2yp@s8^)MO8NjfzEGs7Yq21m0@4bKQpz-e`

-(cE)^-7_^m?eEr`$+MOE;(o$GXjio>dGI|Dv=sGy#Lqto7xo1H-GOKD7>Q2n= z{mSQIlFu&a{3BIDf1VEa#%<<4LbJ<%P}pGwePp(m|9ILH-)wrWU2uQ8k ziJK^4^bSBf6p*e89*d=hu$w)13MaiObF=FoVDoLe-zxX}3ZMt%{~|yq5=&3C^&MNm zc;m0jAwG#;KfH?&%OO0BzS9u!Ix8z5UKJ$@!eepuf&McTWoZ1%%JfBXS+qJ~l_ zr^G~wED1po0FmPz@G`Y4c4;~0?{b#6AiOpPHknjxW~OCR``e(#BW=81b=hC_e0J+~ zxnZkiRxH;R_B9*Qw^^?+d!H7i65;K=I2Ua^o<@;>xuy&(ZS$rXS|fctFI?Ceuf82$ zd1mp-jV`zyK2BmTw!!ePu(f=RNGX0hhw61b@@lc;M^0S;4#QC{Y8~4E;C*ekTa75l zE`&EeCUGjPOM5Gf;ETTgbqG|zkTT0Zv#L9TF)N@0dh_3vc-Ub3DvJ5CS3n)DjaIY*c$6A)aMEO!*w!aWzGyr!t5r~dnj~OsQqxiTQdqgg<5Its2 zyKpu~rrSUnVwRj&mTXn=C)_Zo&nt)v7=`HGGdnJm9YAYZ9rwb0;r3=KV_l?uib95( zrLL5_iz^%CZ-5(-FTHElcJTh5#trSbURB-+h73>pHSb(hwXikWL_sswu-X6}P>!_W zxC%tL1o=(2s>+r(2!ay1fAL&B{IGs)bp01vX&=SgM=l#|s}V_}W{DC5B|0XE_LMFQ z=wEjX=ws|$N!h@d^fk?odErU&x(#8Bf;1dFSxmOlvfq!?P%P6wb2<%^gcwa0*O@mg zE;Ri;F)avWcPUJ3^nUCopRRrKYOccLmKbwie6rzk7e^3uxT*7=p-$J`Biz=XQ zs+X6KynG4yF{yWfDmc7u-fQynMS~eWp!E5rLZ^gtLEXmdTO5*y1I#f*0n(k_z{DmE zX@As<$MUp3sA+#n4=1e4!ZIQ?{NG`y^&F;Lu~l~b6orv&*uF$qyQs` z`Ef#7Arj*Nzj5g<8ti{@%dim}zyo4FC#(^Ik&DGLHNd>ESF}bwdg4v3#ND0*(F5c=DSk z#(dPv%7;Al{dAST!`KOp+)$!Eigtgdb`~|g+Ri!ir}IaZfR8{KrjAJAn0DXhJT-X| zY4Hf#%(vYB`N!vU_z^ckmhp#eN6S?3smukZ%h86_#n{YJ!#ms1S2hwbw!rE5RLAE> z#iI&M5z8|OG9RxqqPh#bf07*+s6$o#9N3%K?kVIPO)1k7NwR9wPi=LCXDKZ|lih4F z(d1ya+<#oJJiZ%P9@urSZCHZoSU(CZO#!ILS)r?v)PL@iGOy8;@H4?G>6l8kJzOj= zHT%92$PdlKi?sdcMoT?(m1>SO+R-hRXXA7ty|S6YR~} zRL%P>({r+#Xkw@8bh{`+Q&_7l~$VNs+@Ss=cM9epBT8|D-EdWFf?7C_zE30xKLWl{is*Wm-1E^9|Uzr5Dip_IU zm;uXN$j1dwd-Apip$VWNihfa)x@!mu!^mjqwwo1(?=!cXU}-N2gU_Dzp?6t-OMCCZf|!yz#m=fp^KlEW3PV5TJ9= zE?g|IGuQHM7!#!F$gEZ8M{VU&gY^}%ts7upt;w)L=HCUd2L+5c#-k?Ha}bi+q!OZb zt>cecRLlLfL6Z{9A;t(Rw*(+az$MWE0bVgC$YWz+JAU|%9Y1!*PMoW?4{p{07SR4R zc^0A)|9u|u%b~C6n`yV$bh|C7s==hO)?V8ewV(fT5?weZ2<{8M|<8+U|5u+tBo^jiZxQlsasA>BH7gU1JS3 z08wb*F@G42%dJp)_UOv1%;vv&S$ zn2#9kcIeCa{8oYaYhtC6!DBm)6Fp$d1s_#(3eG=?$~=D z%-H|)4yL?)iXb{>F!>sD?%S&Baadjz_Ug+OR)S7i3CRw@hz!KaNyDO8dA#(#nN{-p zEpcDl{(Zj)M13>)|9!oy%099D1w<(bh!P`8UNpZkAWE5%*oA&yGwBJ&>xThE#S6w& zj9}F1vOxQZ%eOIL_s{g}#OG^UaY&5EA`q3FLqGiexw6+7i;>SF5cR_^(}z-^@nZ5q zcjL=m(;T&P0a3lZy@Wo@bWYkPTlDPQj^Eqf+xv+X@Ldh4!rojq^emoM2!Pp6Ib zb}j%!4cLGDhw}hZ0;14ZDap5=zOojbiZ#}>G~JpoL&#*p9e}t zUU9~cJI5r}O=@&XXWccycJNm~RFKf%5*Za}a_T3sI;R;Lqx`u=zX+~Y`mtuP?#{5? zy*+O4e{jhTestOHtuIG0F zc$7I43}5bkVERn~QU2ZG*K?^!%A2|4-{gj`H%af=g&z4(e3LIqj6e5P`-y}jPOD{X zYz#9wxkv7BLc%w0-ej^z*)ZADS4Fu=FRv&=kEPa@HZ{VA*lEuYa&x7dmgNSAnuf}> z%j=g3ijAuz@rfu6)0D}e(a;wlpT1o4Ga+Hae zH~}aDFrjuiORlN)hz*w5COP%MqIT@taB#xu=Qtoq{g!fHj3_xK2nsnc0Za#=jnOXJ z?e>j!d*_1+`~A@hgp-&!EB|z9yc`8Y7?Kn z0Z=Xowb0njpU~Q64RM{Jt`bH@VgRHuyM|}IW5)rbE>BoX=ZLipjRKs&_5_$K%|<^a zr_Aa~X7R2EaJD?d)~+j}Omp!bnhJO!5EP?Q%>P1}vp7_gX(3uis+X)?42Xx~9z?)J zEM7|Uk$WJX^M}9w7LR)p_goN&QYi?afej_kg%Na=q?MM2nWDk~VDNoBTOK-!Zr`WZ z?dpv*Ya3q52aWRopS|~RkMlauyq_5idIyL?6cPXduoqEmYLp_&vL)G4WLvIDyiT(5 zb$$QNx4T~w+u4nGQ#P)#Y|HAEk|=hH4Xhy1d+)%^_q)$K2N(=NiK0k}r0@b~-hO&{ z&wZZfeuDI<9nZn?9UZd#%zRssm2Z#2-}WR%JQ}6e3SNcqTmUKpOh-VaQXrLA&N+NB zp0FOq>GS6=I2FBDUVYUL1AMP6D+hpD2_IR5)z#Gl7@xp^#hXaL^kKjv$2M%*Xy5t% z_w6fBeANL_=}1JKqkodog%zb`@E{s-obZnr;B(R z1~#OEUj&bwjNBw|pIRbH9)7{v?i~k2sf>K1PVPATbv<*dHXo+nCx@drB*tSIh)T|( zJO6yX?D;5AN98!8BoW0Vc3Cy=&M#k=0)6l$e)MTz!1=P*1WxVT0a5S`bt4fa4vc9g zwboef2nl9SVne*0m=CpM&xgP83wDI0fYxvS*w)U|vTS{$>O;wab^xcbU z-Z40$P|ZW7Z{>_VzLX>a!P7&wKHu7oD0|dq+E*L=E=LGtbz=dmm<^vBs*as$JVw z`xc0$Nshpip}`@?JtF=QS#_(dth7>8GUd0PO&$vtMJRsa%g^6i@|};(1poFe*k5P< zer(7-4N3l~9Z5n?JT8)u5;%Akck<*3XG;At++8ZC8FYJApbDcre(<3OvBvlS(raZ_ zv9cU4K2+&wGZCZ}WL{bI((wR+IK+@tiG?84=9;FZPHM_c?1Blt19W5Q07rnQtx-S_ zBwh}++lPnS>{9EfT?UEj9x=!5G#iq-Sh-cg4Y7CEwB7f>G?U&m%0A6jR?b;X?KIM` z04IPn0$`>mP+ptNL=uE4DxBJ<;EOtSY|f6I9k3(ky8$q!Yz(VyMZ|q8(o~x_>pk#0*F#r6riFJFUK_6P&Sfg6VV=+vfGA>%no=wV7aXuv3dDA@I)|L7OOwFDIlu{o-!OVWxNS_-Tl%f# z3i*Dq5FVcb8=so8@#!hlAhAM3-#R`Acr`O_@PS(+Tucq9=-snDY+H5!^1w@1Pz1?! zMhX@>0Xa}{j-&{fApIOm%1mKOea~;|KHX$P`-RKgPO7MSflKN(FP@vTci)+@W5*_t z<{PxO&JpXPinYNj6-AX zipm5OLRtweax}szcgi0yYEjM+f#IQH0M1UNA5npS?KLMEC6zt7jT<)G#*JI7rR6f^ zdW6NrPG`-tZp|9|s~`Or`}&_hV_8T-WaG}lYuD6t)=Ffcps^9Fjsl`kAH>RERF?A) zJ&es|Q}?ssLz}X8BVV$BXqdY3L;vJ)px*x|#6 z-MRW&twvT50vmsOY64x*q^8F@PQU>!fhNkGtEWa7NA9;p4sb?%_^5d2!M%c7*{~ zGORqez-mhK?17!B)Hzva74sHB}hs4x;I0T>nBOaXjR zt8)#3T>wG_z?Pnfq8c_sTqgjQy8xoPI(qDvzbycWLPc&8sV1rBC00cIKvoFLX1%D- z_1QhO#kL6`>i#`3d+3pAD=8Nr+^hqlLYBv~08tLaRV=1(Qf1ZAe~WeQyYfq~1}arY42~zz74$(G}ULR$2@(ID%UZHDRm6 zRaNG&5Rh+$sKh}r1*Zq#L>izJV3hhi=agtRoe~-6v@vpg-qyx7wYSL415$_{<$BQrlk8HbL!GcTKu+=RxVz!Z;I zf(Ho?a34sKY=jGq@k3(>hfZRu`SLJUGzV<|duFe_nPdCg0drC1hSZCENwHi&s9}MK zxHScRwq;ExoPGd(JF8ecD1yK~ge5bLlYo8HwRj76@laBy05ruv*FxX&{(JA)!4D2N z$)>Y#)NR|c4T;2ioH}qT_q8C=)!k)f0NsE2mw#nXKl8Mcj4diGL~8S_oohM=8GR{| zZuOR*DphTwtNceu}f z@r!e||5z`RqYOBr^6dNH+-To@ZX>*7vcwlmE@PM~FXC_IKF3 zAB63-lPOl5k!u@E3+?{hnf9fxr`YE05!7oUmYFKal*QQ_4{3hqVnuj~v2!=Cx-kDr zaKJlPZT_A3Jy(WgoYJl`eD}Tmw(s5j_TIbuaPJUi%+@xpMg421J@w>MSpU0!9*7cO zRC-4GG7xoDCV$L@q%zRcDhKtM+Dp<*{0jp6W^n@p15Og^@Zlr&^2;yVk)ubPy38Qz zlOD8s=)p&9??aEkv9#VA8tSc_iD5qNCMydoR`{ohJ?uVA>c-h?f-I-Wou8so52X@? zg{zQM$Rw)5tsYcqdXbE3I@gMt&;>hn25F|V<#u);(?<+texsMT?YkN4TW_dD#skx4rYXxlQtR11nZ$En}AAPar$>PT%%WaY zkk)5A>Q~s7#uCV#L$>FE87nRm5QT&YaSd5Mj{cDRO(9RrsY;Hz_&azEATTrsS_GdI zk#fM@Sl=A{T2VWGCJG-DJUgv(0AxsB_Kw+=!G3E+dd?N6qTwWFqPD3rWZO_{T-Q(t zFi`?nnZ>HL0G|}c&6J)__<&JhiLTu%DnTTC1}bgp-#;2m>FbF>P>)(EQK&%OPC(Z? zZ_U~}@619>JzyQ3)Lqn*JEt-MQo=}%MXd<6!K!M&sM<8!3?Q|+0qcJNQY8RV8CmqC z8N^FmRj44UthEJwtW?Yv7989S{pb<(;o4Nke6a*qKK9pPn;-ksbv%$1?$SWifyfJ0T9TF&o8lUbc(}M6wJ6bV0d?E?QmY zX}fnzrhWObO{mINAvqkVKB^y)N~^L(GQTdX;!)699}<=y9zAYH4jy6w;#GU~)mNRB z)U8{$I$(Tsc+>$=7cO0JYQf+C?)U9$Sk_w!_g6U}_=Pw})C$yvYmu1ELn11Ly6%7| z0APd*Nm3>uWmsP~Qny___Mg8G+s}TPVa>frLpdO7(sIIAtg5izzVcwLJ^oOw35b$Q zMP)N4i;%8R7l0_2)k*p7k`=E83%NX>*sCrrUs#+2?z@IdexG<(*KP!e^50Z`FFzBH z6T?_OzCCk5WuI97%RtnvEvGvgh`O~|v$XHN!}9y&r;?WaHesr$J8 z@sEFO-~84$10q}|HS?PW6hEjeHQ>xY_$dy&|DVE(FY>F4%AGP=2BPlb+K}7^X*()^ zUk4lz1<#E*!la%ViJ%&U6A)R*%4teRpUoURX#*dgLb~HL95@#&Is!Kg&I3^csTFp4 zB-h?Q+7HK4lbtx*OQp)N(xN>3n;)#RAO6KUxMC3F=i@Zw*@gu~NtJ_r&|mN&?<6J? z8n*|b{G~VuWoJr&(`08#E!UjE>sNJ9k#(E7;N7k3Kz5n`noNsoh_xGsC+{d9Z& zIDlL@-PYu$+iq5^zw-4oR<2X6025Pr5DfE@bFROP$H8T{kFTPp_f6tK+rIqxm&yMO2SBBu_MsK`TOkppq$)p>$B>(o z5jU8T3FUEvJ}mi~F9TP%c*36xgqoRwZD$%u6C@ZqIyxwuvvwNQ))OZ`q^!;WNDWwj z-vB^EwN;@uxu$N7)z{Zs{hB&>UTU4hlokZCF*B(No#BFTlo(YA4@T)&V3g`3ll|b9 zjllyn#-zBvf7p8ZA=ADDFVM*>M^@e1*==o1WCt*dHx8+GMLue{NYFLbXWClG#_Jn% ztiCQEDJdq-`G62PLOX(O7XG+dRFK*`$FbNoiVD!Qy}K`F$D3yC3PuekrzdQ6AzV}C zbGCb1neEw8hB{ZORjfArLZSz$kQCZ+3>Bc5Q_&T)1cMS_he(oDZ@}MNKOqn*5r|UK z0;ja=2tZjV{T zfrhq@S=1O~wz33C9sFsz60<9piEHN=>R51%T{Js)DaAVaCTwJU5I(Re_(ZaZLniel z;@leQOhW?(5-K8A2B3vtET9xr)}jz{`J^0DoaBN{SJaiuLYy}D8}G;5h3oureq86X zpX9Nt#-XcT77(Spl~dgis0v(!o1v*rlc!CmqW1P1vv%O%gq^(9Z>Rc3EjjBawreL=8`npysz#D~!Ir|9n8KK;Kb5kpYlJt7Ds}V4X4>>A z``zz;XTN*?cc}PQ04i2EFkIYq{R92*m9+sX7uYjje}*yOairPS*ed#%79=%WE?%^v z60GLc)i@w3LY<}+!c9h*&`!dr?1mZtdH|w&9S{|naXO-cnjjif{uLml7@k_Wt3LWx5sw2f&(_Sh@$=GuQ8$w4iNi6JZedzc_R^|dV9 zxhIWP>xdN>GvU-g@1(NufmxRe^;QhNi<1+i)Q1yKrc}Y?o`3#%``3T{R|k4XGDrMS zKlw>X+}vM4(H6DSAI{l{<3o1z!^?ohSo-US|79H1 z0QJ}~0MVNKSzBE>ZCf{BR(?kXoHGShR+(Z&NNM;jn1b`Gs!tfFj?dXEFU(-MamY@f z|97#coqz#%AU@u`ajiYLW3An@E7P{^4#T;Gai>4v>oe zDBzUxAzr;lMvK-eIT3+#B3M=db1uood5)+qc%r)O|NgSr{?Tzn$sgLhDx%bZ^$MIg z79$?9F3Yt}`?Kw}ws%jhZM`>So9@AiT(KmgknDgX$^%jIMVmOApo=2kosV3JmjQi` z%6mTl6{P0uq^rLVwMM|GHaMADTRM)~y7f%%?vM zIVZKa>hiGV2teXEEZ#krHoZ;1VN$-SB{YFl+nw&DoizUc1zF+1f{kZ3d1pC;0{tk%9{M z-ueQ&_nrdkN}8=h5^g16R8AqZ?%7i96sRb+uOPd9+5{klH9__lbblcu6Rv*r;pYcL zxynQ2f{C7DIY-?Um>MPzBc!<#_0>}+X6@jC5qtHGc6+mF5DKjl1m;#CVW#>=rI@~g zx+dgJyk!6O zZ~tch{_p>eBr_aSsQvoAtg80*_oCieXpcSinC;#Bh&627X!W>GRQI~zt}BEqt`ZA= zdHGqECP_9znPtq2qOPt*DfuNJsv98ccYjC)h|0E$y@=y!0~}Ao%HryRN&C{C5_|Z8 z6}EP5s;ys_%7TY1%Ps>^K}Ox$-}$jfA2&&x?z!i!O3{T!CKC^s$d**=3-Mc`tnm&o|dy$pv`Yq*%^3~AqZ_g~c>9P7k0#Uwm zxRKmcMbzf^$$ljJy$nPp=g^&bzGQjpLz+QK(lFPfnx~W}*N;0hH@>*BRz2`_L1mu^ zM5%0bO&=;Etrie9b>O3cs7vG3cHm->9XiD%_t<%B#cEVWD&)r{+4k2zY_K2xsDUqa zCVh*5D1D4;g6pLlt|1X6P)XgDo3(H-4@BvL-q+sUWUr0*F9k&Ls_XT%XO%gIKY_#r z&%5`-s36De0=zmG&NF#tYZ@n4F4Q57xr2oHsi| z+y4Nw^+!&&V<|4(h9)wss<^}&SC-iJdopYX6YM%9CCXPskf@Q`-4t#b>8L>UZw{%W zS!Xgns3@*U#ep8*&Lu%ZFM*@a00@!9MF2zz5D>s3AS#`99CqVb4`bTD{W9PF#|z?! z!ZVjw`0pg5grvoRs8E*`M>_4xfKXq0u+G+P0+d@ni%KE>YcfrL;(@53e*}cW8*mol zp$rc;-E&ny;kf+gN0^(WKq-fj;W-=ZpJhLVp@4B4=$}CfDP(Q%HMPOR(*dLW$Vi3_ zk7YmrZ#F)Ir9HTpO7qjKATMGWNK57AhOM?LWHq=FEbf)!@*z0S&5a^G2OCc&>Xc49 zPyu@~cO9b!Efq5LnM7x3WWqYThTznia|;GVg%DE{c?S`WM2TM%Fa-d!*{~)$N}WZj z?#j5e^y>L57%L<&}gl%EU>Mc^X-u@ z<=W2svMnnUFb@}IoC*U(`w*klMY-u|)IQ;g>gw#WKmG9q=X&6S>gnksHk35|#4J*o zBcmgz#TVFp_uXf^ci(4QcJ71}e+O#2E!NxKiX;>OXL$u+1V9wkL(*5D4v304ASz9& zc>u-An`MqDvf&nPeq8eV#GrId-zRc63Pj02wavu6J6Zm@ZF4~7?(2gu|79TR))rSN zI;$bzi?jJoAu+}Cl`h_4_;deE;yeDH-}`6$KJi&yyRCpIO4@xqe4$F*m&`5LGrp*! z`XoTqEr`Xkm!EMC__nXIPXwZTG>S3ns!6c}qEOBID2b?ZgVpx#nL<0#G-@Z#G+Pgn zIl1X6wyG@CzWalE``%yFgCAj$M`Wm)Y)B%?afYxeyp+{E9|=CVWinfv`*kx9rb+^% z<~RJ%i$DN9v_xDx-QS#rX#qa0i?F0X; z_R1rdQJ+3QpO*QyLtXayuf6Ap^5OZt1E!>U<*ZxHIneOJg$pKk;J^XrIOmy?&xgfSq@Ry_;CRviec1+NC}OLas}TYQhO7U5&D z4M~{(p()g|W^CW9QQP-s%=#hL?iq#CYHHN_riU#Dp1A5ltZ7x`+1B-D8`pbYN2QB?YG+O_{B0i+f&Z07Oog1tsbgRXCj*J|jqrL61P1QxU`3 zP#Lqv)n==!N+A$0#fn`j4s|{x*JN=|(ntj2!j}r9NTXwbP;x+eUcw8jy~vUI`#YoHDXfER#4Xca;6IL^vDhf4RJJ^_C-7tlZare&bkeLhr@1 zci|Qu`bT}<&)@t62LbQk!V8Lz^6$DfBBnpDsy7P=Jxc|anx6Q=I@+e}wO2drt+)H_ z=!F71(G8+2UPL$kVU^IvEHgZTI{XwsUW)zs*GlY5j}>CI7XB?H-U2B;)o(?LF^asK zCJZ@+H9Rzm)Y`kY|J`@(=#fKqD7A4(L0`aB!{c=K7~8+r%L5 zw&UdSXsLYCH4j958X!t}r|^=)yxa2hZc2}@55D|A4dNiN5p}J&C#Plk{9|%J^@cCMWgzNf z^64(S?c0ya{+d8kdAWt!`fTW(qtmh{$QodLM$o_FX0>Z@>Mv;|M9I9P8KA+qa(kmVN76-vR)LIF*ZA$r0t_z9>yg zrNKXVEBEny`ZPf#renVCsNTf$U({AQe7wvdO8uPM$jH ztm`#jZg%Q6Di;yTORZAnws!4$+&cJQ%5f{5IzZ( ztg@BW5VaQp+hoF-0}qZkt-=tor$EpwX*5S7O*9-pMLb-76U)SU;Q~?J;LjBjdjS-Z zWKo)=@)Slg3ynNff@hIb8=|caS$}tq4RmK)dl%AcfQ4PXM*=w=~h++w^Rx7&oMv-ax_I&@o<12p>Qg3R6fN3q6RQL z(MI_AS6*d>D@p=@129UGUQ}gE<0lm`aR|YkE0?3F^~^E`U;*&b1aa%MmQKLak+5}* z15iftAbiia%HoKvT0LX6HCRlnDX?1VOj%Wmm7ubh0nm{Sp}C0EXJ`Y;FBOIQ$N;#Z z%n>z{Wk5BfAYZjt9nf>`KPW#=9ayI8Y(DRUvrq8rB9QdFYd0>$q#KE+!Ha&ZacZKd zs;QmNQGrPbd6g@eL@5(p9rT@f{QQp3 z+$9q5#Zk>;>~o(sS`|zfC)GK)4`5|Z!u2Kc%3bmm)bEo!7w2C>#qknR%Vg!(%F#RL zx-awj80&+NPU?DrC|_6R-(Nns<8nZCz}Ewn{k4Fo@|EQ_)66RUO9!m=z%e*(&M|pu zwmeqBbHkHX``u@(?t9PLfu?eM{*^2{g~|B-fh#tNY4R+rXH~)x^@HzKAQ4r`XE_r( z)Lh(T{SyFDi-8C5F%OC!iAKDLp_(LQnvQXp6MmmGZ?cfmVKvD@BacX3h zm6h&U$9Ke}DtRmj0$=>Q)H6OluAV82lm|ZUi(kL>X9;Z-(tcTc=&k5!Qse?E0R&l z9~WhEPAYV+O({`=q9lc+bg{YT;6b7v3MR#YMAh`H2+PI%#v45Izy3aIKlwS_Z%7`I zNkO~O&3Pbd-15>#tTK1lzW;2weeXNvmcJs^qN%hgM4qG;C7z>H5-Lt4#X@x(7{NIg zj(*~0tD~Uq$HVgJaeI}&9#wnQfu0dbJ6!4$A`S;Q0MwbDNU_V!a}dkV+NH~oz_-s> zdk-ZX%bTn+^eZ#IOj5los4kT^-ZbbfLqV&UX^e z0?N7229fp}nHh)iYXr-1gSN7eKC-UHHa1jR)EcD!`rpVOF|n*(5p zl;vOi&EMD$e)QKiNj;hz9>UULhGoDopNUFmX6h{Ugb)NoNljK(ZE^ibILrO^cWL$y zzsLoMQpFSbnF!cXEzBRby}MW21NW^$dJ=1jEYvuOC_r4r+N=@ZrR??R7sx&@AnNwYnOhf| z+ZKpQ?ido!gAc}F5L4ECTmyGiN)-#|hz!|l#M8MfAUQ%ZJPn5KkIrl#55MdJa(##~VL&yH3Gd{EE^GPIerw%- z)H<%5Vo+ZpFEIR#Ta8&plgg z-~47VoGS3aI5iG>C;?GSGDFVFR4}m%QbfGmBp{wXeS|KODB{9R0iy8NheQ3>C%v1a z#?!7|`SmxZ?DaRN?7*ROcJTNKCIC#PR@K@)8!POwz4>ik{-+CjB0W zk`Mk1S^?-h*xb>=>B3|Ffsfn!cfI#X&x@dTY<$e#fB${^#ee+5_U+r}RKCPj^xSjL zIagI(#iXPPwHyeN2L>GoH99(a(}5^o$6OSN_w|fTNy)jbPks8-h8As<4K;ajdi4m` zHTj;e8eCFY$z8d8+0Fw%odJ+Kg@nV!ix(XjCEhQAgR+LzP~TvU4UJY)Q-iA9Dpavn z!10p9BoehN>fnNvG==W#q>otuL`fwm%Ace*Mh7rAKPZcfJ%roCifKC15Bb*B!|G|@ zl=X~^0ZIW>&O+RsRc!gV`?i|x#;RQXnk=hZEuvdWH4XJF)a=51hfGeU*wGK7cH}_R zj-70=!)ID;XgmVQkptM1Z;eRFY+RphJ9ehn=4}w67ho8nfY~<2140lpD^E4ib^sJW zh`^|z-o$|@O~rLzeHatn1&JtVmYK0n&!z(GM5xQC1rnd1{kLiR`+u6Y)oGl5csi&LdW)xYEkL++Gq}e! zU3bq3u;4EMq}(IHbF=u0>x9(&O6#1pcfi#I4_8OmI3QmS3r0iM-J5A$gPArAPg6fU zO+{%jD@FCKtRxfZqkOACDr!~L92WPCI+BT+S0?J75SybS7e@Ll3b-~pGH88W9Zov0 zysQ$^>Jp@FkhB3*3`?>OC&?`-R=K2*-;&-M8&0ud)CRA#_2UNYLQ}q-KU;tVm-wTG ztarTMCT4oEHX60Yk}|8SM3s46$hm5yqgJiT#R?BAe(d5Tij2(Wd{e@f+OBnd zsb{~S*Zer-_len{Yc~ssN}LlWhOvBn`{jVj-PZ?S{>wnrtu3e94v6vIPj|F%$|IcI3?NE%UIFss=87D6VF^tx zHTit+y=mL`-juz+|AOs1aLW3S9xBMpwM}bE>>E$j+T)K_S~2`5E3jTg&x}8ipSww$ zR*U7kBCb9CyxVga-*k1+wkVB@?tJ1CNiwNCMOOZYKm5UQMxDQK9%+gJd+4Eu?7;^f zwB37l+pgWa01Tt>(+oHuY7F9AsSDkxM3f@x$BX1hQ`>?(xGLevPu_y_o0zxPik(aM z$E7VE58v**Un(oPF@V5fCX+2!S^$QcAUQtc)b<2OX)-A*e3EJ_V{+fPw$V0hKwWQL zJ;yaxT3$l_YNo2Xr&+slT&ghwqkIPF9;#W?QC*pXqX(fFB;t%oW}gk>W~Z|(I#Y;5 zUBphEowak9;F9VYw~oO{8|V9DoNtfD6*IQFV%jz}7Bk^o39t~c6=g^j6-5CTGHE=3 zS)E8)b(p<>pv~U$w%VTi-YU|9L{vN&0Y^@ij_)f0Tfxf#2&KM4Ug;Ud zCMeq=|8*shn^KrM)5bFnMBsw^C!ujkw%|Ue(RAXOhJ+NL&zLy9pkqhqs~-z@ZIFex zT$u!41ybaDi17$E>0x20z$pq~L0-vNqLma1{cw|NshugW-JZ-3vQl84D*zYYy5YV%{Sh%lSo#cZ90vW z#y;0?sDDwu6k#FnuYUL=`>VhDA?;)mNoW9OK&XiATAth> zV}!i#8a&# zlX|4Fo}}V}9~~rYl<$(;wXQGu@E7xWqQ4-P}#fkSJ~6P^`Y9? zfr=17lqXy+EEHjC$vhC%b>N5%wVkoC-pd$Z;zKkYbKOrq?c5t@itJxsPO*ciA9M`% zTQ-snTN^Y{EwD!)OtU|G5Ve+6fGEHynUasGj{=Aa$7IPVSoOYE+~@15dw_oHMt~@# zR~@F`T)Kl3spJJfiiahCshH1C4&+!g)!OiBgUd$vt!4PGpRgjm#;LtYi^teY^bTJVM4#wHf>pl zirYG?t*b%er4XK%JV$075z9BVQWIfne%xyTP?FMMPkV4c6ntodxakS%_C!DGw0V}B zU4pTJbUSf6YE6JqmoHBvnKNnag9COM)G7^CxU`f>+f=>6wydkPwe=}hS3hbis|*0A z07CUV+BE6Ymj_D9$QtKPHip(xd(0AK6pR2KNe6NfkmX3u1`?O=o-5TCuQq;Vf!< z=jW`uZ_qmX2d$%T#@Yt3U^q#*js$!b>6S?=%Z}OR^_B2)RT@|mQgsIC5VjHkpt;#m z>+k6ypXY2bE|~%!eljEFY;SjOW>!+B$1!sI_{4$2A)OsH)Pe zv?v=jVd7&$gn?8hiyRUBjaUxx$srD??8VDWbwYXV>Vz_%dhCURR8Bz-`}!W_;G(t} zT)K{5^4)uUji;}ch!UviK`8A5vTgyw+NP#LsN812v6YV6>J@wQ&C7OqAk&6s0RUr| z%>%$Scoc1}9kusC+7~K~YpU$A$1?0ok7rn30VyQSVaC=_SfEz`L`kht0Avc%V}}kL zvV$KSVt>F6f_im!w7YM2spknu6lwW)zx`eN&bPl~A-LJX@Eewth<9!keTV8C?I|jw z3V^z(=S48T7=ct@K$IkB|M)`0{^i%1w!e)r8$LywrBY5`K|QbEzH;Acd-%~B+kruX z9b3}?wx*~z9*D}Kbe4fAR}pT(j~`R~J~;@r0e$03-Fq2`O3t0T_gwWsZW)OBY|8ky z0is+-K>w^kQU8e@!@{v2D1&F*v&tv`of3T2xSZ2F-nk15j{a?Kxq(>s^`RuEn>u$L zj~lcJV~I`AX!Cm=>z%}Ne@%M|%Mdhq&$RPD`5>etc@%8G?&w(#? z3RM2S4yf#BSy7c4=x)f9eP2?5z4jHTYfQie()!{D)^*^x4YpshaYP-`GSV%Qk!EY2 zc--or__DotyukkHk16)v#R)8F^;sTjI(s&(u$|iqZSVc5_V5EpKSdz^O<}_2OifV$ z??4d0=a60q35b#|ArdwPW&pb#a#c z-SCOhh7(uRrHhxCkQ}t%{`R+yGpekt3`>Y*_QaD<*pp8_>7?FLnQTa%&s%I0sjZ&T z!iU^aWpb^!`Dgw9TF)&m(`!9-dtSd*+LEtpq@Ew!mq^Nd9#B^9U6mV~#@UhK5$i*m zp&hGcmoHxdkUEMx=7`Mu;A#<3xh9oW)fHCH#J-`S-WnPk0Hgp>3LuTfsTMOuo&P2v z5bCIaC`k@6k3{T9QgBlJ8`4A*m!F3eWLXuH)@ea&-*M z26eao{&c{A414E|4qUsPLbC064*<|i8t)3U6!14ff~Kq@JKxIl3hb$`=Gqfa2ZZ!e zVRa($~L@rM_3~!o>@2fnfsiI@PBUdQ7be_2BeZTo*AErO|_qEqOFA?>|8*kW8fBI85$@%e* ze{A3U);HZpaXJ&z`Ay#YAQq3+^N)P$1MmN*_UMb}!Bu5U8L6Hu15sa`x}ZAX>w(H% zeN$Igx2psCz}I9TpO4_;q7?xU^^$<7697?dHs05Z3Qjue9T`^p_`_EB#KZQ7!@2hV zJs+}nF0lfNWJPX9)E?PdYWM9dw)^))?Ec;KO@L5Z$qgo5^mYQGP(hJNbvJQ{_Z7Y` z@}=S98JyGbZvcqWyNmttzR&yW<`q)U(*#pdX>Z4p74FEP0nB6f*om_P*3>m(B{^yK zmrvK**Pf`h%2g>=v6@K}k^_<$(0jpTQ~t&iH1DIX1y|kNIyk-gzdeZ_q>9xq}1$=1pKvZHKx!y=7mR;g;^7|iE7Rk@v zj^{pYJ{>yu*L-{v@A+$qd!N5*fAjD9D#L>+lZkOa8zf8ifAGF@l9D>xbPhEih=|eG z65+f+!!`AFwrkIJ+qQiR7SuGctU#I}6JPtQb|?Rkby6_~g=FWX&yRJ%9^sZ8LV_csF&a+s<4xJJ!NIktp#kQ<6Pln`?$_ zU1ORxti{S-Lp2;lDZ~Tv+$09vWK+fZ>sbBHOvO z(6(YNY};-TTBlf+ID(MYkhG4tiu@+d9ZlF_I>PXQG7G5-2Sy3}0c3MP6dY0P13*JS z)Ho7R08vPOxkNc2N>Z45pNT*3S7$=FT-agHeG4G!dv)->q2fo{^h64}#QK&J5aqxR zu4!8uh*CU!eD%c^^b5d#?z#Y`Kr+MwS}OY>P4aVL<6Xj+w7dRdB9JCB>RSXbIdwhC zrlV)hI=iFRf|S&iD_B3gGG>=s2jFX(w$bq{>jwaujptc9DsmO+v(^9*wXPAXhy{{X z=_9|RSZ6Co%@gwbGz>6MX0u2@Ar}J(HIAz0DCx!*q?A%9FIe$-FPm72B0|t6*Qr-Z zVvO#+w>xGRFCevbe#Fk5X|?m`dhH69051*Z*x($JR=A3c0jn$Og)gkoHmqB3jqA#+ z773}!H6m3{#mVv^>ZsGRF3i+4Nw}$ewHQX30GJ76bXo1Qn^@_d`{rH9NRFtdS8Y7_ zNw?%zlDt)E>n|uMEox9Vk?_)9n*gKf*$e=_3_I{nuYDkQbk_Er4%y%si9iy`)lVft zwF>}Fz~6Tt%Co1Q&c{eWy49`18e$$GV;FzMx2Q_tNK$6LGn{TE&xh=ZowfGxgSED6N1Ah)*~=19F4I4QA3xUk zePWQV&1j6leOj{e`Ee>SfaT-cG6z)d&d~#TEMOUky0u01xdBnGk-O1vA%U9IX%H27 zqt!;OI?95@FcvC;^Kn-FGTrJ#K>?FJNP)Fdkp<{NekE?n=ZW|HvEE$`?A!P3^sn7e^jsEKffvAu2TC3TTXp*`EQyljEX_6W7G|e17YiCi(h~m_R41rR^e8FP8wJE@EBp0>tL6 z*4oI%da@&DqfpqjtG{!Y=oX z0gMdTii{pxQHX?7*=iHtPzyt;dJ=N>e$2v8 zr`!61Osg%+vTZvcIo_RW)vJ**ECcSyivo&ZNesgXLLAgg0+qE4T9Y6dZTi?IK`vjF zXG$NyI{T}EC{Pl<%`|bh5DRA_tCK1neNtU+r!|yy+B4s%wr9Up&14_zasq-RZ9-WH zXpvf;z$m}z$i;!MgJM+-eIKBvx^J*YUeh@Z0??+Um>;i`HlV}0Z zq`^CcB%^SD+z^5(!{l*i*A!An<4Cd1SXX<5GDRwF4A20frkR;Rz{f#bkrjnM3ROAC zq$A-8D?tr$)7mPC@XM^I1oC)z?{afvmXi;mI9AjmDcE!qClS(5szWK{U09M)F7K5` zZ~*~e$ch~Bp-qgXAYDhey~Lqo2oQ7B&Yn$0qAp@x{Ug>jFbv4iZ>ga^E6mBXiWQYe zL={@yx|pqQpzKQuaQT2H#32u0Doy!L{UtMEv>nql$`hDT6_1T_t%x};wQPp7W~TJ1&JsDQL3j%JI;z*E8Q-hA4hU& z%nlu#vwa`Ltf>uav!lH8bfR|e_8i-OPXT;zltU^c;VH5} zi+Vd{5e66xg|ev&6G*v@JL%Uyz3?YHeB`iQymZkm9LvM3tSsBUZ9D#Kx79VPoxy|J zHFZ|Errt?MMWd3WV;oc^(-vkvg390++;w9tYP|V+iar0wbUS=*#?B7|ZcRbFHj9Jg z{K=hFNIq8vK-9gc<_UKSRTPlv$z8EYP=FkwQ7ExjK4XbhWPnX zJ2ir3AZn?cxwEg$mwmkcE(1|_c6ol1*!!~AWJ3Leq$508x#OWh!m=Q@5Q|m^pwC;*~{dU~xNNsGa7mfipKL(aW&6jI>lN9_FzSnmONFE2>5Z$7o!9)GOD)}RJb zx0;V-fGB4*k4c@A3=lx$$b&hL_i-Pe2KumD0z|R8?LrjUs*U-u@nY z@zr+Qe{kH6o+E~_EPH%gneE+GZ1^3;)+2?mVf_Y2SbqNl_gfK!wOZ(i zFyYgc@G&(0tzS!rdt#9@8RHf@R_4OwCL;qr3eh@+o5du9lg zp>})sy>UC%lx-*aGA)bi1xUB-+K^$}cBMnCo#MEo%FAW}Bc_nJ280n;k@~6-1~I$)rsZ>}lj*B1e=!D58FKTXt{gN98FHL~-}9l_vOdagSBnS4l*PSX%EX zed6_k--ii(G&bQD3{(!$7(7j}97|KY)St3&K!R;x5DqD+QeK+1i)UkY3CW}@vc8Ap zRBKZ!34%M+<)Wv$ORa`Zwa2s4i zp$Jy~va{er3Ryi;bsHO3+J*+cjcZeERgF~9G(G_Az;hHug*Zk%Gp<=WWl#NdkDNO^j&IkDh^*F-mApDN$$1Q58Hl=8PTidAp9>JBsJn{e2PpQcEFyjt;G{xtzSPW0W*e)HbmUW$PDFMD zfJ)DaC{~hCl8DkOw8%$mYipg#i#Q;h-wY}vtVRq%5-Rf9vn_>ZoAYy~G>0-`h!T^C1`{QjsBIxzw_^Z4@! z^Jd2XGxkd$gexc2TL!6RAnG$NfX^{FwR_he5C@h0k`hsIAZqSntM$LO&w2o&I@-FK z_zu}{xWGmt1-9$!yKVQ=yX@s7WZvL$HOXwWh<;JC zfN0gJB}c#)cN7lI^S zmCT#ncj?Y%b;Hls|IHrm%+Wb9T_jPa419!oRPot|tiwaql!ChTQWx{>cocaDZ z{)EmYT`g6a5MW7&$ze|~3tK&qhBvn$RdLyxn=d;O^Nx-VCn+tiFO_ZiN~HCeUqlC=Z*15$Rc0ZTlg+|h7A_O%t`yY#klw)`tKKR%79&LfeUO%ykJP_PeBh(8K(fsRpphz_f?1#-3(ynEak0*Sb@WVH@9+#j)|^rG2p`_Ts%opLL_(_p9;y0C;*-v|ErjNo zfKo`uMNm_W(ce0BOk;@41(MGtSuVA(KsZy!VJJD0ZPOK5w~fn!;&XcQz+~))SPQdu@grl7{%yBP45(76d++_ zBT=m5l^`A2k!D+!-E4bymf4>@vc@)S%AtH_tgwi&R8ndrJd9O3fl)37Nb#LLdls`>5Su^Q+ZX9w^bEYwrTT5+q`9yt>3T#j<5|@$Q(iis+b2rsOrD!SqkN- zdB!aM#q8x*%?=zLwquvO0IS7kMco77`r5Wq+k0P$?cAAaJ9h^XQQ~iN_5ON*DCOru z7V7MyH~*|J6aTcXCtuS&|GYa~I8onw)#fiPJa*M1OI>h%c+!m}{ZD%4W}Uk5<8e+L zV^v2!2@s|D_<5n<`#2__`|Ef6-k0sIE>Bl(zW&8C^+v;-uLJm}@?Qp`Zf!07+<+)0 zONH$#j|y8K{w*yncH!IwRwIr(04X~si#esCb#7zDs)|)>h=f_i9v_>)>@7eMK-bo- zTkOFHA7r&-t@|Jqp{d*GoR;dOe5c~}s{BiJyj-7}oN|P=O9D}Rq&kkMq{b5je3O5D z{F1}+*Kcxgce8h{&MM!?OV!(t1EPH0@O9>H&YL?mZSw=qbtJ$)tFm8`BPyrBNkoM& zUAD}|8$L%5$&KC4M#!^acJf+O;{rWcB@$@!(@nF<`@*9AtO9S*3{noHD)&BN} zYwg)@)Ifq7a!#BtsaVVt=Zc#YFllAhN}m&N%&LbvjGr!@1S;%J2BLy|V3LO!_<;Oa z6F>gu_^^kx`SeM+JPrXw?Vq)G59HXHfh;F+TE8OQ{>yXlMg1V%(z8$+63H?v*dd61 zfw3IUrb%W%$c`$D5*Pemoy42jepkqAHtP7_2;t_S*uoI2g*%Pn^9+&MdS>J*dNqt?{altAn5`a5W=lPRc}q@YFocH z)7Ed4b-l2yM$%?{k_qi=(*V5VcJk~MJA3(xmE`AHWpSQWR}@-xWg(JXS@yu*2w;>{ zzLZOP6xO^&QFWBhgO+kdzO#!v!L*Vop^KfK9-R07Ed0S%9=@0FVCOC{p<`)H~jhjb^LISD5kK%kqT3i)~As#2BXy8E-Uzh3t2R03%`80&)y~IT%>*p@c*lE(#YgIjFZ z&Jxt?A^^!_@f;8yK?o1^LrJK-;}{iZF(m0Uh+HsUgGs+ zf0CYY?a*K2*+u=d_s8G&=gEHRJoy=au3O1%UC-l}dOZDqk}WyD-fzWQW5V@HMENim zrI(Az=l;1{x&J)Eyed7(<&aQ*S3P^PE+mI}1OEE@pt4t8S_YzSAQL~qE1x?MrA}Lg ztwuA9#TylPtH7v>7u|7DaUm-h1;NMt9NZ%SQ3F_^Xl-q^i##Kd*~cDx%z;Q+!K|#R zbRgB-%$y?}Jb3URtJn1F%$Pa}jm5SQh8r!^iv)#MnUZ)2{ z3)m(A06+jqL_t*UIzbwaDrI8FtyU8cSq9V!d_uzFNnISDoAq&%;JMN^M|;*d(Sxb> z-~9U5SkU`5YFJVc?_(u=J&PZE+EE>Wi>lru3d>FROR^LwqWwaqPdoj7p< zpy3Q4gLuHYQMcrq16Na1WA%J1tO0D)H^WN6sBHT8bR?#uEMU#ydhw@^`jN+Ew2W_$ z9B2Yk0lp#xrc|ieMFGSFPHNU4qt5`tLJAADuZweb_Big`xSen7vrC<*`VGPlG%^Dp zQMMJrOS7sX)oLO3Z*0i2b!+n&TQcA?LS3wVitn0kJKfZ6Lx2@S^78Oq8+wR+342P(eyXy*DCjWU4@#9*aAOwj}_BtQDtIz!4SnVIs8t*+2ByKm1dV zoyNkP76LUXwnz!-0EkjWL}mE?)xAh=^#ICN*<)X-vW%=0C%r;rMtzM(gme&=!tvWx zK$M~+m#~Q*A(q&L91z6?RfGAu;Om928@#jVCFQ?+A?`E40N{hHrUjesiKkBSQ@ZUUd#Y{F*Xss6PO-TZ zR6^-Hah<3Owh@Q6!^~;^JP|sZC~CZOMqODjxv=Ljq`}v<7mmvO1Fm z)>QhZkPACR`GP_E6car0hkV|R5sHqxqXJkc7y&i{qZHTRsv@rPbqQdvE%7+G^6|f_ zmHLyvdSA!>R|f*3#+(ZS(20nDXgI?L`m*f!hvFe@g41cjE_K&g?^G2psD|ODn{a1r zLuILL+R$LTcNW+~4;YKhXvAR@1a5cAnS948UqtGWxG_ZIM$pVSf>hK?a0Bk&zaLtU zX8MaRM_4YPdB={OwiCB?+g2o_Hd_gE2dSPaCj{sUj8Z*xa)Fegcn%L8irE`)Mp0Am zvxBFv0BpbyrFN8_V^3@ z`;{0TPbvQXJI?`8EJ#Ufr-;5@E+-f3iEs>Ryh$AI-I(N}5l_@oX}dZWH}%R5<-<*l z!JX}ytGm>PWgzOaDaYFbh@!Jrfr~J30I4WRMoFbks}Ln6D;$4=Du({l5r`c2z<~qy zJk~8VNqFRuN9=(IA8?a`b?eswFbQOucEp1(yzqjPgpxX+q@nii-D~&UbC3H-)raca zZ@=xNr37vXG}7Smjclf^#ue~OPjF5Sv2{)lTpmSNQAxD}>& z`AIBS{=WIJ#DL3X(<_?Hz0f?d=ECW%uWochC zQm!ny>-X1uFyV%t^&co71w_qWY_^`)Ubmiu$E~YX{o0gemok~frLNnKyVu@6K4iar z?Fy;|NO>}0-MlK>{^sxM?U`>^SsEX=>5}LGq|pbs<|XQ30w78}AM{14w{pq#S@BJ* z(^_@cD!afazcESE1a#p+`L56D#25X;3wuBLS3U@Ql3HG%nx}~i{zu`F!3_+d64j4d z-ho+r;f0vJcYMOyM!PK%8?qmKHOHR)bBLmAik(ZBW(r~#fq#ml;=%;lB()I_d#NQbWL zHx#+#mjVxOy0^)}e9q^-7#0eh2rXQ^zSxmTLEY4}Huw`TB2-A=q9mmx4LuA~wZ0#k zo15K&)G;QX$57#yrL57h5i7`t;JCEZflwPaZiEj8>8Qp=tUaza_@15X0L##(p$czWyO#_R5u~OSZcIt=MEBbc^V@=bEt$RTFv`kKN+&0{nHRY z)QF8tg31VlNQnbcYUhwXKioKAJGb@QgAY~0#ZzVJNc>2RN*4P*2@vJm%zWRH3`D8? zMEp&b1`|DBDJWlcjJiR}J{pMP3Hm>#jXdobK^he#=1(FB`Xlg|HH&_-d*OY~6a?x@+AKv|7q+i>(Ct zD_>D=yY5M|$G<$y_diAo3Nx{AndTOWwNRYF^BIuI$0&?B#@#dL&a-&@Hk@ql+wr4^ zk)CXVfIiJ+7-{FuU8rX7LMrNB=gLsYc0d&MP~U(8qZ|z7R0NfZkR3i8WBf3CA0X<$ zsVmm)fGEaEfT%||me?M6q8@x8%^rFv4fWPZ+M(K;q^xpy`x5|BF5f=lXK|4(6y-;} za@DP%z!qOtv1{{t9Vdq6uP0thJl69cwfXn;j6YuLeSa^}uce;z_v80m|KqR4_qwLO zMRQYUH4mO)4@7C9Vksa>&ntfJJsp3Z+vgno=b7}64Ev+%L;S`0@rbfld0w|f6n;Bk zl72wgfad!k~k`01u|G=<^z(IW)Yg}{=Rqi*+2jDKf4b|Su)bVu=O6uMj;#>2dq+u z@yg3D+b@6hE2kPK-UmrL?cDYMv-ckEbzSF~?}vllL4aTf39uJQ6h-weTb3Qii5=ON zCypH_xnp^r)O-Jydo!6hPMpa+lbNv{cUdlKR+mVMlGqyx0TR6sy&Rl#fA6=>Iye9U zHdRYpTHSm;*t zA`m6(2?Cf7J`wku%&*0;W8U;N@1=NhBh z`ujC#easqosEH;1=F;LS2JJXV`GiBg%c54t*#JaI!EF_7HkTtxZRLHd-zAEA{qfQi zSZoopROsBW8VfE3L`?%k^*r^g^&EK9`p)&Cg9OFM8xiGd+-!*z!9V-Ns`Lv|cJ zF$sW}-Hqk;=igj!fB5A!=#&M9(MhXLfwc+Ctn36pCD?RkfvA|-h3z@FO)mvRNyJai z#~*Fat`3OOZcQQ%@==r{jUrqrYo6qgeVk3)fj5#I8qC-WuV1h;y=U3f_1PcZTL}k6 zrR}+4mEC;PD%YW6QuHcd3*97IgwJh!G9~x&^{Ze18viS-v=*W(YNhSE;Rd_wj=S0L??wz~y^D2+HWDJf+J3JM*>$%x1sp(F z`t`+cGUOCMq3vO$Zju8cal6Sdia6XlJ3D<1aD;kpJ1hNBt-j8X7**hwZbH;;E8(qB!qp=i1A12|kvRHs zawY+HR34lyv*>?H+KIQ}wmCXuXL~xVwXeg*wZ0&ZHRzq&3`f?EO^Dv@PQay=4?vm^ zV3uz$zcyqq?jOXeS`z(5SOTW|ZCq^tP$h^X)!Ocxs<0TAZ}o_X1q+-4jsqYQ2qr+f z03f`Gc3%YW4OB+E|L(WP?AzbPa$E1PjZR^1UZQ+iAd1cnDDcp>A-nU|3wF=lYwhlP z)-C{|0(TVwNygC@PfmB4^?gX5O7T9!HTIXV#tN_fZw5#dm>7mCI;Vr^yybzu3vp!D zli?%&ss`pdc<5iAkUv*@pu5v9!ax7ohgwELK9iz&y;Zv6jv5_K(>79e{1}SO+oxzh zSak-7>gi2bPah(5V>8w>4(AzGO%Xh{at=T%;1a9F8tMvJM_hqb#LXr6Vymjdu*LFx z4DAH5xdJSxnF)YEOxg7@0YVj`Ukjg4+sS7R$dhhB+RO;m(Sz7v2YESjGKJo;X*+Ya z$C}Ya*gt}PEA&fAqf;3g(%02g+U5<*QMO%WTelZtl@U;EZNgU49#G!}r<}?O_=Ocj z0a2odmzkEQa!2P}bmCCW(sMqT8Nx|yPjwT&^6K#)A>PdMxhnCXIl(iZ&OK4RCRzK7 z%dsF|77J(iEzY|l4gsf7ERXX4gH!hFXN&FGV>EuaoV;xy%9jVATaLBXvXV;MyLrYw z_0WLbetQ~a?yE5{P|M->DEos^D+atOPO#nwtt}`mxAu-sxR~B_T~W_J|EwLvScRP0 z((UL6yyK2Lk({{I_U^sKRxuAqA-}l)l-B@6Nk<*^MONg&xY=g_MC}`}m)~xKJDLg< zU`Bcm>{?}a>|JH|14KP=Uok+`1hZfSqAE%83V^6Na%BiS|B{_oa>9AP$f<|;MK)}F zkb8~a$7_6-i6{2o`1qo@a=**Hj~^^`&CO@deQw`g>QjHNv~s@7KI6v6jm$OXKR(m% z%K=f^A8NdcPT~DKRs41LzEMDJ?V8)eT=fwPKjLqyQ1v+vh+;gJn0{S7x+CF`bQi<( zLu*I1hid|&6q(}6iBFF{>h6OBqNrd2IbvJ)fjf7W;(k_@$+b`xSMUO$rm_AZFi5|} zGW&1;{oh=H8?JC=Uab8ipDrgNrvbo!BYQJc|ui zzx~9ONmJo8O$V@Q)VU_ zpKutYy1Tkvx0xoSsQi8*5EY|RySVN?92D^WOIG6bN^|AmsYZbm8Vi;Z&6@+F4gf@* zvytI3Tej;KtJ;Y#E_eUr+ZFb&ub10F#C1v$jktMJq5aukthPURwBAbKhAL)^(&j)M z261+p2ShEEX*ILlrgkYHiZ&VAB_HH)NG;V?=hKV6K>nQLL>m{D&?!K&)NCQwusJ;V zR?>d_(<%GyD?@hbT$>G!cH4a@j=gPfC5!LXSPWVXaLZ`P218&JqbONt1DTfo4mK9* zoASBk;pe;M=9ecdBpiq$(R>yidM~a=`5*k?2lo9ReBTvZgEP3r)d%i-fX&Sv&XL>L z)W{+voQk_BCG*u)Im#L4ldBkzt}21w(ZFh>Y5>>L21HXfh1wWWl}=xurvZ7yIW5b1 zV_2+|HQnA`#N80(KX&Y>n{RJvZS@6ZCD!li5W#6!zX8Cp5ivQeXW_Lumle5X=!jae zW(7Lkr2LqtG>$?*WPwp}6P+?Pm}#uIC8=S$Oacy!{DN}0JqoefHj7wZ%6i)I9Vy#? zpw0FjJZtCrr>$#3AVh_&DqC)AYs+nOL)sb}0TR~1akI9{&H_T5Z3e)?wEdAb4&lIY zt1-6HP+wxV>?#F_Dz#lV=EK34kJT_#bt9G}F)W#gS6>rIltxT1nZ#lnK$Pp%BJcn7 zj}!L){mX=%>4RHynvJtW`3jcvEu0)_K$H9ldvN=R-F55mB0!YZZc`*rU&|iR~J@a2M3`o7>9`{oj*H^@_5E7tO-gD1WQiVon~j+l6D&3-G@jo9I&I( z7YB$`0#|EY;jGmHI;}&GSHoH?H3ANaWr;O56rmJ5VYl9aIA^uQ1!)%r0!=i23xwDDhToa-n1>k`>oWdU9tBLzfs7JE zb0Es2;!gcmbR|@Fvrd^J`4v-!%(~6E@I-%uQ+@=HWw?T=zZCT@KQauLTF)dP@(eni z^6Y7>>Gh0_+svdy+msF-fJt(AH`K$qx2Ku0I>lb$20*zc`aVWNCb3*dzNOEtq@)7z z(rW5+7>=_RIIRxY&!6}?k`vGSI53l(;rqJ)qwcc3NKM?bXEz5DtN5?pjD5Nz6MBNJzRe2Ra)Eto_ zsr;%OWL?f}_F3)?B+9xa!e--J;=O<@Jj=qTsgET0v`nxon;np~ZseKOR40 zd%40ox@MxpbQHlArj^?svh7>n=d_1d{}G7N8bX+afT-n2Yl$l^x2x&%*d7E#$zK&m zR3?307RKw(KB9jGX%QxS0i`@+0Z7&;!Ubs|#fmq)6zV|(6umAejzm8bmeJDOJXQJoSgAJa* zD6!^CL7_maAAJ7@4kU7IM;!RpKkS3oA);MW^K0^_u4l zQd;yr``okk5C8QaI63RFZ#@o2)R(^Gr|M$&Rk>9rg8Mg~-W7JHd3n2*AGsa)TE72X z{^lCX?sd&5;gb#(-QCs2DQUacbxqAOSDL>l5cPi5>F;u#yq|f$hWgLeJv~+ZRvb|d zQZR;y%b}3PWhEB2s;g^lvbn{2pN1m}J$3!(+TdUqwW?b_VbyydvSkwe!T;jOa{Km? z_4ejeiB)kTeha77-}pwIeeMg(Tr5v!!V&m@D)J%2?;Q}u!dQ;onA-MIPBfV3w6XKe zofc!_Tt&P=TwBCZK>s*=7>=kXC+)YdVu9;SE4o!WF?(KYo12R4_aE6{pZoL%TZS^< zM4`raaYL~Q(k4tm6jr3kf2`WG)HL85vQ*F_c_@3{`bGfywi+T zt!_4vtL#plj^DD^Ic=MontaZZo+v3()*-{yIB#FfhYOv`AF4$4!m`Qp95TMJu5#-q z_g(HcKGWn>@lxL?A9L^2F7)KR%frI_&Nai(CUf5_Cs*oJrvZ#|>iMQPST_u!dRk}1 zg`@OE9Y21|4j(y;4w^$QmZ5ZHNq0FiajRCYf)j2R^}PddYL)xd>(G%@ZEydm*ojycVO=5N4M!ZQb0YuF;qTE!&y%Nh!(6h?AO^@k@ z0#BrJA&Ad~Pc9&G+}R~vV<{}s6(X`l-HgI51;^CsQ_}ebcU$Y2wW7bN>%x=`0#psd zRhdBat_Uz?MP-fEA`+79fSw0#GrtfPO>I!F6#Xd150bTx#puv!j2 z*VY!8CS}Z~niE)Qjk^CrsYUi2Aj)Y9x0VA@e2{Sh zp|U^}v=i16`>bf`q*mh)opW5Qg7CEP!OI}PttfQA0n7SWO4-LwfW4fJ^kxh zd-0_yYwhf@(|tXJK};{PjBCi>iqdn4zQ1j^?4Ggv9=Hp!x?QZhM<}njkAf>IVt)Yl z)a1mp_4oBNcO6DI;E(O;r=NCpAyOG~^UZtNXY7UB@K(DM35#{>*22|R>ejqfLLb9* zrPn*R8DJDcim?o^7hfK*r(bEu`XNA+8dz~5hcX-N&OPe^p#Y-pUjRgrACg*oHY|gW6`s7sqFLK1IIb5Q7XE6++0}F}eWkvIr0-}g0wtKI< ziz5CQJXlE2E2yJuqDm$m)n&GhuOO{#SQ7Pi5EJ*N;D3DWr}baw`A+v5!=&a%dVuEv zQOZLm&Fer^B;=J}KR6(YJcb3oCYMl)KH>ZE6WgvF07`81;$D&$E4{4di6iPKKmG~I z8@rr)=}r{KZriqvQ;uyYA??7_?KuaR{sYlGS=M{}@yG35)esVbOLw$|g6sIp-`n)i%RwKIB>1&bT<}L{Lp_QeMIJjjZPV z*T4U-F2?ovw;s1g0lQ>XN1$6&sHzhgeWbX&lVlpUCy{%fN%M*>IeAlW4q6-dyP|l zy?p@MeO3-Rz(<~cA0a4<7 zICUD)kh*AV2boPm5xO@o^> zw|2*z+}Ef6+>7YdS-^x=8z%N%P6MnY0i@+yTZZjS>jgk=IHlNApFtPU+s7uY zt$&PoN35i9${JU|p|xr`B7zlg(^Rl=Mge-q6jt5LT1N_P2=19RC0K2%N!zVAj@q8x zW43cw4VD0_vCPGm-htmx?*cfI08Ij<1Rm#;|9|=C8TMCpR3=RJ;es1)3p`UC za%vjUdH#5weaFkep>gz%4#G);9;W3rR*k~qc>Q@c}NTqD!#$~o)T?HI=N$Lu5 zG{VEw11+Wj`ZTr(prUlt*X&d&ZKjw_GC(GbK+<8=+B{49nSeWM+}b*(t&Kc&V{uUf zas^=1o(*}nbF-2EN~^C!nK?@F*R6v)3l6QiYlC+0Wz^}1L3hE58O#x5zku*S< zESn05(sj-S5YLH7a!%4n*GO3X&ODp@ZsA?%r`e}oNnz&A{dgL>k4+_6gU#B}gK0bR z)}+08wAtP~cE&DDZ?NI?2BMJ8s61P4ZGf};t#QL7dxkq%)iiF6iQSWF|LGkMA zcrhJ?c{kFE?IG5u44Vj7P~62FNJ$s)qM~`!y$o$=O{IgatJV>v0;nlnrq3wYN6CGl zKvY;9Ufh8N=E(fD04Q-nNzYOd+HB>|gG{z?8ZEP`QZzn}g7Z&(>S2`p-3Qxz1EyKm z`Q*{s(t_2CU)zs<^kXLVjrO;H`?vPVPkxd)lv8SabW&0-QNE|1dfHDu#F2IHz4yB1 zJelTJoZcusn>2T>YMkam0AteWWR%@kwmk0<^KGW!30?NN}2M6~#8n!gb);7p(t{H?9BtSRsxO4!tGHo|4{ZMTF6lrMtnctZJ^ZLV5=`8YG(Q0Wg zAW9q2_O_JmLr>I!gBR?Lw_5DTnGVMEVb(oLD_e#YsUm==v_Lm) z2oQ5}D^2_)p7+c7n9ag+j{YQ1LF5l`ti6BVeoo$BvKL-_!2ydB#49AaRbOB4Ahh%W zN&nEbIOp0C2!_)^h05(f5zq8H0#O1`qEkIB3>)7myxzrl<9rmp5fCL{OX8F{o3YGX zq{Wcl#cvend!2`c`Hg8_Yg>$TSn8_sX|breyA+m?(vnhNKzhGM)~c_+&qeogzgHfk z;^NzH&nPaw?KazkY5<**Y89#GDlkWVK!2gebOWVKxue2S5d!rvC1CE6!F!`2W!5XT>wv-pyC+|zyeUGF8=JIU?07gkE zaZ3D;rYmkJ_5aAt;`65BC$W48qBON(PXNFHe=)pCVY=EJ@A+PF%+e2~P&<*Y!$`P_ z0CB`gW>`2|I1dxud`AKymHCh7ekli{(WPB%dtQ$OmDtv~bKR(lNCFzIvicQu(2P1{ zY)vAuID_x+O|pP2xR=(m&S25cA$a5G7`a1wQtr4AiNsDLQuguM)l zqBXr(Nu0I4yH{fAjkUzGNyPQ0To*~X^pPa69%pDq$3TSB7CIzS)Cb(7DvC-oNShhL zpFEL5w_OrZJ;e1+j@qgIaT}F&Ke*YJmFC&Xa=@_aWme0kdfUcA+qqr3#|p3*T?E%0 z?K3fil|g~9S}#io53x;&XVO;FR8XGM&Hy(AxN?`Nmu&ql{H>TSs=ExpNQ-Iq-P>ZF_OwAryk|w6>{TWWB^{Axt`n72ApZR$mDhAN}=?+jpUO zJl}4=H30GgPs6^0`IdfL0H<3IRy3uL_NA9!21we6$m{_uAPR(DX*#g}qd)p17tby( z4F}vYUlG99_$q&#x_ILtK-8;4a76W3%Xx7a(okU5x_j$-yM5PsyZ^y_d*GAk3`0j$ zGDZ7fe$Pvn2Oug_w^{>uC99${74Ek&;dl9(t)r`rcdN4XCSi1N;x>9k&P zS_Jvxgk>35KQZL0AQ}iJu{1=wCla5<&-D{0a zO|}{Zqz;C$=$wkw&~0!_&_2>AmRTp}Y6mK-Z)O;%RL_1w7UQ~p{RmP( zqQhu@;TT$gcm*4&N<6D~`gX!5TU%^w->Wuy@)+%-A1hcW9lq}iw)+0h+xdfVZQ`Fl zx6FQiVXbu|La-7gse3k-Vok2l?tdu3W^;lK3rfuMCfMXKrbtYKeSpBD)Un#&{BaG~^Zf6|mV& zBvjz{**RTQR{1y{`fX5X4JXt-HYKmV`kM9j^^(s5L|Td*e3tl@4o+sJQ05w3953~0 z*uh_{6x+{~;d&R@izoudAK~K;C%c4d`CF(UsQk;$DkW zbt8cU`Jg#;PXHpiDga9!ik9oET zYSs@^_QsptY-op2bUbN2Lo-&0_+0@2#PT{e+A9Rw0$$IQ*af(ux)AYepHgKI5unBP zs&3o3vIj6~4c7P8*@|^3Teg}p3*Bs`g)$M(I5s_C)3Xba6!KK5#^ZHcuIsaC2>5 z5zKcfz(9G$;rUXfE#W*26-ibY5fH%}9f$Mj0^*bgV6)P>BZ`Zru&9QC9qLf^hz@MP z5phqY7$auj+)rCua}i3gd3K@K{qXck>z!S}bRiHDu}MT7YfHv$RZR*jiRHF#O|ezf z4qHXt2ujY^*cyCQ)s&T1UVsFX%nfR%WJ>dZxMvXIOW=n`ifwqf7~N5%eQwsyoktmd zN4}lwnXx_&T?fe6G~#_zva*Oyq-yjPu3erYy=hy!y2RG5twj<*%IycOrk;WTjLPSw z#sIy>n0`o86(QR3kDDbZx7cI#>o7(v?Caro_$G#lG3XtYva&fz zzBLDy0q9EYd~n{TGxL%^nV)PX)Z&*&w|HGVRCpTeX0A?R4pa?u_lw7MaUCyA%VWri zXW{#cepBZ;wSI9sxafncdl1W^v0WAr^;^wM^{Rbe*y|1Y0aGblu|EDY2Z%ey!}=hl zG&5xv#GZ*G#(i};x*qz&K!H$)X~t6-r5L6y0Las4z5Zzj>f3U;eZuE=Cj2DKDFUO! zH1oqB{?PG?Z$AD_mxj`J#rk%xD~005Mjo%>=|}$W2LeQ8J0_K&jvmDDl3W8ArHzc7 zDpwmBd7Vs1DX=(;Bt|CyXV1}(}#W+iO&6uuo93cOJo0d!-HOP| zh?<##lO=iib{6}5?7R9M+wYZ7JZ|>%T`nl0wy#+< z^nq|yym6e+xF;~S1W>lOuLAS*HFos)lpQ{H!cMfb+0Yagy4XB?=8jGFxle4iH4TGS zwY-h_VALkZ8H*^J#!!v5@3)IIqsZCv#XK}OBc8#b!<(2vdIL*Jy@+vLcOMT5sBH^$ z6j-Hog1oq`<;6X{WeXNDIT%yFNWfN9Ac-KFub5DmDB z!@VRKBOSK+uB-25f92^W1DB_WVW$MJ_oA>yTZ5u`fUm- z*>IOJb`;q#eP~GHKdA|;E$Fn>C7mcRhiklky{+3cW$U&Mvc5szMd@-lpy0q7J&hi! z4h*yuARbg;KmElT`~FjF>})@YOu~f&I6MbL6${yN1i2f=1ZuN4jtf{AL0PbTF zVMwC%nN2jnNGjP&o`!rwtxfepC%Os@lBK!iWH}%mda8;MK`faQ3)9%+x;fP;ap4<{ zHv&Qyck0Iin?iq{A7&Q1$SYmn=wBk9eCk|W>vD=~5_6zq5IzZzQ(CdYN-AosvU~(R zOQYmR`kUYw0vt*usZ#)VaYv2}m!M0s!Me`ZTKBoL*3G)HeQ>p%7++&kvs8RiTu##l zwr4f8nVRCXRhA{Kyk@}4YWrgB>X)D*TAu5^xBtg+WYs<90Pfb~V5#o#Z zvGEG@CRN%jO72sW;ub2m-r+i9`E2J9FY3UuUfV#4^^T!`FQG2duZzgcQc5Z^0}h5LZ`E?yNk4c^m;&z8C>K8WFY zk73>k9bz2unoASy*<=wnwn+!3Sc51%F&U^{9@=xzB^kz{u+CLUVm}G(Ih0NPKJ@<}B_(UiPd)vNhkg88-wHrf2G{T}!gf1+ z9Huul_m7o(UxBDFpv=*ip(Rtv;RI5&_mc$%D7knlsnY=|4m}LubN>8!S1v9KHd0W& zb?X)uQ}xabrHzl+-6BVnMDu>~lR446haY}808xNR(MeIcd=TUNk+VR5_OqYmwBt?} z^Q#All4TuP?F)kvlbR3CIxQKu0Zy32vU&X2G3R=kfHOkqc^IUS-_J})?Ql!I_4eDu zUul2w7k^=&|NQ4!c&U+Vfi*Wl_+S=Wp$L+B7fxJqS}gA(J-rj;ydpw>=g%{sQY^2> zm;Et!69-VH20Bc5uDqy6g!t!9qx9RKW%3p#l(}zIuQAN;M7*&ap}?UanZJ?7@haj- zuU7)V$<1@q7DiD*Jv@wMAxqh{GEOa zXyr0CGLG(maoRbc@awPG@adD62cin9ZDUo5?b%vnzxQdB3*TdK zD2xGOa|#VdLq407LbwEqirCSzA)KA$Bo1p^aZ#kED^GUa6Np}@g)yh(;)>v<^foEK z`D}b8ej}CO^8SJLbL#Jkhl}@bMaDP$;;LRvzZM6Tf5T(G@$_^W&krdS)_#s98)*r+ z7iU8u{i6&njw%$kP67CzwwDi_wIMc1$*HtGuzRcBf7e!Y*G${i9fMX;6*!_&Zh~9= zN8As}f^zj9JC$8T3=|0Is_gv zCl_((pGSX*V$7v4s;l72&HGUHOXTVOeHG|^5goh{ygxa~P1{qX8eD%PKLYnQHKP82 z*Cw>0 zCp}I1=me53Au~kbQq`^)yRUB)5#T9wWahapqPEsiEIEzY`GFa09g=mq%uWEf1r&g7(XSPg)PEJ{EU*^zA&r zD3Ma%X^l6^fup$As;XBoW>o{YW1X&al=2F+%7mrPrE5qVlgSCVlm=JW1ptW=6kd-E z4WXu?lJTUluVg4PymfOlz^;T65cUI*vaFDcC-`VV)UbX%oZCn>zbxmO2~rw;u$SMOh*O8BGtm5=={ zzVf+@HYQzFv#Cn@RS|UT!gnJ^z1&`Zqn@%30s3{qflK@aC@(JnEY7dA6>vP=yYmEw zCQevm6X4s%2I`Q0mzW|gD%uO6z6(dpIEN^Q*n=RE5xL$4K=0VG!>UkNtvMj6GUzMj zTY;P@`dvv0;4qxd9bIL1y0z3^-+$pEAZqXWIyjN~_seEOb${)|u#@MtWEjw@hM#$eib5;>0I4}*IX_RsmaL++SCOHm5W_X40}z+N$od%ALsRw zDZg@>rGf6VDbC%zqx^<`FfZcV_{evzi+k!=H`#Z&-zbwgpIx42ACEk!{zVHZsh55* zwHe_6+S|!erq+ELFWKAMu;_9f(qAP{qm% zq>%_i?6exNRI#djJ(K<=2Z~S}`pmP>z;*PDPXcRTjorCxCwiQ2wWg*XHo9o>>KDKGg?;b;{2y4Kt6c6| zdZN~@TZ{aEJ&OsQVg_ZVQ5T0gttK9wgp2`5U0`7`0?V`OjLL@PRLsjbi+uThSlxf% z6U=}4%fGZQfB8$9g_$O57AzXbVy5Di=USYqrTgH|pdOtMetIWbs#&2ae%AL;N8Pck#E6;F%aN_l<&GF3blUuO_%OwDd)8rdaW!b{J7{JyW}N zt~#|NwO39``w{Q#>gsgmmSV-$LZyO5xlYWlyALk~RF`qAiDOWlcw(K$FtHRdTw48( zHlXEdUw6OzvSK(15NWAmv0cSRV*J=~>-^1g)_dsaWr3(MbcF0)RcyEIF0#-4UJ-ig z3J{-|;k2C1tB(w6+S&vr;m2G*RC=n40SM7Gy0^N%h61h2Xp*!`?#UVI5?P=lBBSjZ z?RbVwpf+!u;UU(;TYf7<9vibTerUX*K&w*UR_&Gy7^+R=eC=^MIRx9_mMH*H66O_AMq zKd1ex$pD*10a4mi%%b-u0$ec<@6~mwF%{}ScjgzobGA-TT1Q6*3V~a^@9RK9!1Ma` z8*I($H9p4(gwy6k+^}UF+`QHG1F8?IKdIhh{e?=GC>TH#QBN~) zsJ|*m0&q&3-~2pS`DaV;63^48DmC*A95&*pnm}(<5`;w}f0F>+`}cRT+3vP|Z%){Y z$0tCylw$!{wN_c&K)lPWUz-y0T}ofA!z&G1rZp_@u?Yig>2BXP*e zYi0Jn9MGr2p7>GPSU=m*mT5aR09TX-JMt0-oy~~#J^r;K`}6-S5j=6Fu->6iam}K7 z^m0%>jTHel%5BHgGr1ACozEDPhnJ|ZgWn>KcNUcim!NRaNNXFDVsPj%MGy=Pl189) z5#tT|(`|dYZ=S)i$*Eun2%Ql=toMyVU`34o0`a{4JFx7CynK?HMgei&|8CuOAlDz_>7H0 zQ{X?^B08d=(fSohYiuyPdG`ubU(}<_JdGF{cqJgIXgfVM zol5hRAgQ7fxLWWpy_9ml|KJ(hf9ME@9{@U~Tgl%V;t(6*wB6tMhTV4KLAz=19@~wt zs}m4M#_9jl6RJaklP5VDFpva=tlvuVVfE_O&J9_Po|qZd{Myfi^#Of=!x&m28`g67 z&1Vbj$gzaI{Mx{LAgZ|1?%G&qcVGeY{s+@`|0ig(W#fzwfVTpq;gm*rHd9!YUHyVg z#V46Q;)mHhQ~C>?uVu7AxC-avmvaHKHl__baH#J!CNaQieV{e7;`aWhMF(lm3rlbv z*e)JcMNwI3Ct7Q0(9F2(T3l%<9WS=(gya>L=L^de_CSgwvzE`HgT7IoFZxE~2Jh6a zG_I(O0->}Al~{Bvo7VXwNV&)`mY590;Z|Ou^*x?-zV>*^b99TxV%lesiK zK9z+sDBn&rC6=i#EfTYI&1B+w9s(hjqJ!F*+JZ0z^?MycimrMl-B2~vH7=T|@lVoR z(K#p$W)Ss8zxL{@_P_r9fBTqmNgYwK>t?R89Vs6lb@w3vqBMAGKw}D_BWWN|J;+q{ z@X&D3$-yZ^Yg?OpXNkS>1{cR`YHGsjN4-x^sw)Qw*Z|0iS!ZXbJ^AF5fIr{2dcyq4 zSHEia-~WKsF0b{I>sYa^t;7p(_3Sgx+An_bge#o=A{OoLx%VCy%aaux7a63XX)u$Q zQzHqeIg>FBQEZ#Cl%z#i9Kf^?)4c{NS62Sr?;_4OWPkP7e{GL_MJ@r03&*V1~^T(h~XG(e%7s%|JJ!rPjsSZT{ z?4S_ot+oI$RmWPONN1S_pc0hbYLcqvlvLO2?!!v~UqGotc>RYuj?ZG9$KSCOdhQcF z-wBA)f~6aC(LMM|fl&BzK$>zkUL!}2S;v#lTF=`@9EeJBg0|^Xe~AABd;R%td+miD z+t*cRFHJPKc*owYC3eTH#aQ<&vRhE1I?dvGim^jVf8DciE=Wu|5M?tgPE+DI@U;ec zQX3BU-pAPmu#9FA%jOfWkwcJ{MhwpT{F&aO`Ht117MEJY6NdsQ9wJuR6{jmT=dql& zAcV$4FUsi8B(kFoq&A!Q6#A^v+BA|rp@@Tx8QdAC*=YUX`)&5buR5%&XWV+RKDA}_ z2HUow(LV8@6tov|DlO}%N*mA&5K6jp9Eh45`aI3|;?KM>RYX)BD_#B+Ko5!M%w!fA z{cu8Qo{_N&ZAx@P*3{I5^5S)2G&v|<002M$Nklp*)Mm;g4=E zc7a}u-Fl_;`R8L({KzA?_`47DlQ?!>NglI6l((Dtbnx$;Fjo@OwTJP(?>!~Np?=^S z89IY3BFdVU4xi*lI3*W{%PMrnY}~xXsxVYR)AhL_)Smhrn+C7Hz{BGp1#^x1thf{v zq6qGv0>ps?L?r>D)Bx1>m}R`}2!Bapl}-IoKtPgpM)T<*lwboSyg7vx$4NWiHEG?0 zQ#Q`nke{fh4_4a@ph6mPu@b%$U&RdI_B7zZ>e4=2Ro7{o(MfmX&PLm|quLs`PTJ}X zj1n>ufPdo0N&DH)X6(r62|Ls?0eC|sk^^+MqJ%Y6<=fwUqu9RrUobDPGUEj*X>>@a zTna7{IzXa(jTd3e2%SJc6ruGEfQ7=l(-p7&n00_zc><%@g!={n;HX91o!LhAGPzn z=o-bkT~}Kk<4W3k`Zvt0)+=hLy!g1Jv2Zja7*26=3ZS z5zE?AtHD>-Ou?lG2vP_~D)pa-$fL&5*%`)r@;`y7S?75y`{7$ojau`m5o4PuZ)lowgTVIc#UUiftsl!=~~CM3Eu5^tM&)vyH3w*`P>vrn{%xr7$*ZSnpC4KE{zf&mo;O zg)X=>pl^Wy#DWq#(~^h9ShE*j>9b!y(}Lw#iRPhvo&%_RsmD8RT5bF}z8L1mzm#D*uGD?>}es$VpgZr zid@bgt3IhKDqLWQ@}jzvyJT4M?qM@!@v!7yW4@>7F@!ig-i3LHVflXHdVR_K5@*~y z#r$TH@$zNUb@~B|d;g_f@>|}=e$tact9A~b#^H>SF`_ECpQWh00#HhM4d72U=1|VL zpBLRNncs!<_4>|yPCn-4H)nj*bCuKEfhLw%pNfy?Du?nJXddGG*yTa(Y_Yb(vxV)~ z`!kOPI>`%!?C$J#`U<0{gbT8^t`=25WnTAQ|Cwsix=*0AfGDjOU&64>fB)Bibv?oY zqW%a&WzsQqk+SkwXYopW%7^!vOxz#U%LfKTiJ%VBWIC}17Ihd^vMO%~OH|TS|J2h@ zyKHvNvN|k?AV-Z-^1JT39h2GX;5;c~vSpz~WyuN1lD{x?!7Kfjzx<_r@B81QAr;yu z9(u@?ns43`EaCYF{E@idVNOe4fBiLk<&{@F-Yc7=^e8lD*gN4AU=bn4c{^1|~!9_X#+JUIA_~tLhr-4Joi1DiNsei=Z`oYhv z^AcyueepX*L{L7^SJ|*0!Tfl#5q`{XREHNi(JS*f_kEbqyw?4FA4s`GMz!hG2}xCD zm5XasV%GV(`|wgA+Y_kcg?;)`xeh>-#v2y*j9&sIG)dKR+Fpk*Vtpu)kf9^T=K)c( zu<18`?oX`ovwv(a{Nk8B|HM%{(!bo^p50_C5jDPlZz=5gCARnWLfg6vc5qHvCuvhf z05iq-AX3LTsg09c)M3$%^Kn8qxlP!2bsC5CKD-FqVLc-byf%Tp5mYDz41Y3LsKc{3 z#OQ5sS*r0fb`Ay9TmFz%nvF?X8xA&p+Jr+X9v9i!wh8;$FWT*?XU^O4(W5oqYKm!i7QpGG{0S_PnOAT*x zf_4=rn*9oJ|#Mbc<0&odQH+ zII#rT_xEHE#LljL}83gNC7L8OMhXg(zdL;!q$}mEj ze2dF9Gu$Xep@hUw(h5sNx);cGfdkU6u5RZ08C$(-6^EfHs0S$1xaVT~S|bAZ&FWxM zoG}3NAqvEH^8_q7ya+f%H~_fGsicih!T~jk0SAoK^#TaBv?Ku;XBj7F>~Px*q9Kek zljw#@jWZ8SFekwMRZ?JeHO026q0}}tRsbZ{TGQq_Ygn7dIus-{FZ)qwtsj_NC+&(jXn7I>DOhcfR(Yk9AK=qeh?U+h>ztKRXU zBq1&RBG$m1t2k-#-nZb&l?ZHqUm+Z;h4%8R&GyW5NA2h_=AeP?Hke!$l1PtRY4SCz zPP}H1eDY2tChoKyJ1YQZg*{H%U_VOTVO`WZuDk;7b^&StSZ!xp5s7VcKw=&HkSg96 zvBwaIAp&^IL##4Q9;7c!9F5H_X{YatFZbA!PdD4iHk6eoU}Gz;w)=L}*`0gp?16iW z?1B3W5pxwcg_M=6*=2N&spO)ew|%uU06YLckxS|6kFQI)23mVo^d`K|{PhQm{qacV zzfe3O?u9Q^m&B{b{wJgvLR}(kCJz_Kt6H3Mx$$^df50DIMFS<9iEHkwOdfK>#+TV| z^q~g`Z#>aVS#t8G6uj+vdY+_nKDVOVa&&Ce0mxeRq7~G8Wu<^9jT5oGhkPjC^9mL7 zl5@S74)J9sPq8fVv97T!x#h^bUoyUH`G(A^2qBpqn*A>3A!a|)L3JIUEkQfgzkI|L zI?r|b9!~_(p`);YIxOU7@qwHOV|$2)md`)`ynW}NzQcIbXO{$`lo#b|LEbW1{77Fu z5FknvRj1L0E>^e}7y6y#BuS^tr%s$i@6vJCtMnF%VRuL|Ieyp99d^U6?I;#p=AA@? zhQJ&(n227AbzU4*Pe1dt{rJZ}c5V0TH*A2Nc^l$m zu9hw6och8SzF@cRz177n)aZOr$>ce<2IYI+a}8=fu!RuHmzaYIFzVa1-s0?tXhNs5sS2aRD)gbVGx>%O?GtCcOT9=`@Pkz*o1E@N|bBEbr=ZF#z zHS5YLHApSvlvE}@uiB~puek3!M|3Aj1*G zF)F9mQ#Nq;n05a8S?l8{)RoGXbF%#TKedgY|GNF=$H(odpB%U2{S|h6c9m^fv)n%O zP>tPlPZ?lLzBO#rCN)Jo=vraXDUZ|z3sY@llu>?=<;D7K?%3qz@OG`%t1`-~?aC`A zc@Mx_4SLe2AEIbxzrDU&P?VOTD)LjZxcwVuaJ; zVp~>NY+v|9t^LV2mScU4MSnT^)u5%sIDD6qO;h=r%dh7$Hy@dBp`7uf%Ul=ve%=>K z#1jfnqp0;bnxaS186e$oLmYg_LZD8^S0S$9?sD;lP*?x=y^42!u84` z3GG>n;2feak+J5Qfn0Y{4{<>eZTFjoj==#&YpU7 z>TGf#N}s8p3ItF&=76Z!?*vG(F5u@3fU<_3Ld0700ZCGDugu~dgaZ7S>yM#Fh0KKK z-h0Vk_c_3DxLb}L8)maRWG&6pcD_4d{p@w8$@3I|&1AC7#!^_|%ZwYwCOkhqV(ZEi zfKe5!jo`+-s{rw&d|Qd$p%rxn7=@X(U;k#x-a0a1M_PIfrYH)=oaTC>u($>g_5b{7 zkpodGuSiwII8`DbN;y~e>_K8wzDc&(x0PhX9~E&-b`E)|xdd z;Sj2Gm_#X2bn1~QKpasLL4*6u;Eqvx`B(v!z8}F*K8lMg2d}cIZKdG8kz)Iip)}kV zDXcKh+Nm>ujAy2O6Vs1)$O!tW#?V=M0i8Adljsj5!6rEV*RNV`>)>2k+gN3d>llmH z71**GxTGoy;o5*pw*tNzm}tFSkT%MKA#PFf^nNtAvP)+WNL|W(hoAU z50qCGgt~BWiNZU*p)ZtRxW^MD^GT-u^rfI&^&8c)ev8jn*5m>;L(M^Nz$i-Q*Qv>3 zL?MeYEYW2zzS?GQ97x!k$Jbcv2s)xf2tdNbuu$B%dK!WR{_$E zPO^44SFs><3k4|Jm;SHj)@FdEGqnFIEa8GB8OX+o3 zTN%hXZI(W$TW`A!iykOVr1MK|Q>QMPh}}996G2o~t~j;$d*$U<>{q|~RaS}kauCc1 z9(d4h*|P_;%wukv`Q?{hv6o+Z*#{k+e8>vMr$7B^Eb{I0ENYN)pvxz&nCnYiHE_j| zlzZun(kZ&E^8L5}_TO@VC`9wTY%D}sgviVJWWqJhFaGdd{^JAXB5^MDe376Zt4DDH z@wQ4escosge2}7D2#C@kB|QPs7a+FHD*~cEW`oU#uF>SsKTbSXl1Fa`1k?nj$)=;D z3*Tw0;Lu!+Xy();Iz&d%yK(4{^*-}kyMU!QaZcq|)!4Q#{IPBM!hf=#|Fp+`{^Uu*Y1P;CtjDO&-aq0@euaF!R3l{R|?Z0PhWF6MQ6WsX*?qvx

z6-p)(?qe>ZBOppvQnd+bSl@tB-<9N%|8XF{C>oDw!P7;4Dh@^TLAsoBs60!R>2g^N z-|73yh19$Um6w|QVm&X2M)jg^oL=vMZn^O&&+~tWabEy~MDb_Pi6h?$H`IB!qUu>& zG;M5xdjgIq{bKXeSH%rg$e1Ya zKvb+J4OpQFnJ1Klg1ZN?5KYvlMRDEhiPO;U;~(A#th=1+7>EjhqQ?6q zhX~$|NMBrR`5L=(z(sLliL+G+D;G2rH%JE~6^3xkMiHSKfMZF%qrJ!4v6^_U6a92u z{O(3nsHfA=Z*CQ3Tdkr5@owZVi_22BZh4-qU6HW$>&k5dz|^{iVq3Q!Ze5-uK;WXC z`J^qM2K%Rr%JLlS z+Oeb9wrwr6O`8zaY=9e%=OtL|2tZVzt~dil_rN7ZSp_^&X4k_bdaHflX^MFM=$WdO zK%v(tw$Nw95ho9VLjY~$GB6iyLjV-eu73kD0rraBx3-Sku~WlHJS6Qm&*s~kT_||x z@I&JBlM~0$1$DxIfGDl+gGEI2>E-O-l$O^^j4PA4+QfDDyFmf(ztoqmTH{|8 z5JfdRqXOf<44g@);f7rqj` zQ`>CMEqm;aJMOT?#zw-UY?8DDc45qEux##TL-~P5Y z#=rWjzqH35d&~hgouq3ZQ#$Xp%gx)uwDj&$?-z#uIQ@>3NbUd?2PrKydU|>QqRz80 zMTbLq=^PNnrsR@t;b61y_a#5R{_@?VK&;yuvk@OIc~8wxFCq9o%;#& z$aUf8+%p%|Ai&5NC;jJ=aJx>~lRv*;KY2#tJ_GEe2kiImtGB=ST7%tkbB)z4W0Sz? zy5+OWf}0?^Jj9mrQj!D7WQdE?A_mA@RX^A2miji1jhd_EN3kL%5paP}(h;R`d|ksj zpGUM$x?DV0lE0cIQQSS>qP=B?t&Ls$m zkrqo|uHu3S{{+bdr)@3al@D)Ugd(Um@xHMq&@5IcWr^}U98yP*O4Mq=4!(8V4xc)2 zgOd%`KMN40N?^TV=zy}kj1EIArde^??p#-BH*GDlyKgJ7yKXN)lxY?P%d>XitqyzT zP>Xeql9vQPtE`R{6j?oDVSfil)VCf-4-V-UK)V9^hLov0hZMgfUA+wAgi#Uv9~*V8 zdz2psp;YbwSn$ND5KHdgX38!KhW4c3qLYfm7sMs8sXTx@IRPC4GEy!wrx@kb27?d3 z2^R;DY+?!s92Mp`A@nrvRe*+zZfXZBJWk#}FJ-=-TT|+wjyD>rJf# z!~)pICra{dEu3x}*H+jjbUQU|EJl}9fvtv9s-`9Yh}C7-Rs>KAE|gi+oQ6wk46(iD z=9E4CLdsr#17NCu5DR~UHZ)yqeKV}Ty|A;k0WPSUHWi}m9>1%E^>ZoAe5#kRf&8Sh>|EPVvph?RQ<~%08bp63t|~) z7g+rZV3g`l!2qhzqu4)~vhLnld;QfZ4u2->07f&^4%Cllru*Sq7_jOh05-s+2k$Mk z-~XdR+rF!UJq2I`7Vq*9pOnQ&jr(ett!)5N_&R{74RFK>h|1$zDIbgND_j93IYigo z&~bj&PQt19>MK1QjyK!B6T>!{lJ!0;Zr0VHE3w8t^NAUIZB|zeQgc8Q98rK0S&k?~ zM=z@*YT;nB@b|}x*dJ_RV?T@6OXWsk)L*nn5g6V92-yMa?y8b1_Y*^dHrR9CdX65l zuGe3&@s?(+R-v<_vd${+|B6-K`(=Ca`9XXBg#kO!GhnAi2W{{68vE0)Z9!QnpnBZ| ztiOnJWPm6Gd`YLIK$yjSE)aF8OfLG429`VNd3(!!z(?262D3Ed+wAAMA!^9vTL%kJD+X21VPo!!27nQhyI`EV=` z4;lm@O5<^+fbqI$d9UtaEJwWNejUfhxG)v?B*PO@T&#PEg=c{%l^vfOPy9YN&JXK- z%=c2)tIfCKiE&--+fc7pSE=3?GY#TO(^)JZ**eP9oo{C|SqWv3>Ht6}fl)a?l)xx) zYBx4+aQ%Rx-2=vONFgo?tu@pj)GWfCHj~;^>xrBai6B(C53o$Q*S0&j5Qmo$nuc_U zlO6pm9Zbr^XQ%Q|Mh!O&Mz?x;Chc@fznwWVWXDhB+0j#+?9*0z#z#nbIjk}3hyy@M z8~yyWtp=CcSeIwJw-nf}?FDdkqDN>njcC{fJ9KKmT85_)No3;>r-&6-V0o|H{_j66 zvH$W-taq}ea_eUT6wqgPy)0MI-Z^Ae{kA5X4 zZ_ngEC98DPj4=~{-xI7K^Q?EE0M2^2-}+E8jtJk;6IFKfY_XkZ98HdPfe2Ekg{4+s z3Md5AO?@pQ<10&S-P$sfE~$-;<+ib*z?$%m<4{Hi!${Mu5hAuX1bA~6!0YVU6x=-H zSoWJh7a3`tMHRvH6bHdmfJ{@irefL}>I-dKW4&$JxC|?d1-6y8Q;jn7swz07N`Qi(cWc5^*B(8#)SjQX6wG zTF5DEbi7xX>uw$ea>s$}*q;gE{TDDo^S##jR|-VMc;YoCsQ6-f3*W^s*RLNA3e2mk zO#NSxXkMnvy(>VJNRiuxKOCfa&vNmh0HR`N??ai_nbW7?hEpTW*4q)cy9M1(JJ5Bo9RL6&omCYMSgA6bn_KNwIHSaAb@a#~ z%x<6YI26y09ejh|wR5KfQR0jeh^2QC>CPQE;(Z)c;x*P#d>^kuL?v=4j;QZ^=Q|EW zxw3NSh+=}%LX}ByArKY6Ul@N(=W4HtFUA?KR~yI2F1+S%pYSu+3<2V4$wDB?m6fB^ zQf;yZ&OC|eUD7QaXcqpyAm+SCMk*ONGwwm)k=V4Q>o(rehH_wlsPa0S-SZXqZ@!M6qyxRy%$Rp-w9jtaRbzktjqLzY%V|5K zR#_nhx2)b-a3@lXW$6ljYjdYXCy%eCtt?!NE*8gP&n`pgNH2Aj+SZje#sUQR0r0iEjZ>D^{)uG~n|Xm+}$6zm`0G5Z@^8 zG5_&;t@+4}>ssTu)OX$&-^~WGpdH7w#S!HolygLhnqMho|?ueRj^qB7fae;>Y!-y;6cfteJj&&~iOOe229nxYgC zfweG1Ao0uVP zth7Y1W^(xw^T9t-eq!n*7t(@}5 zr+TT1facy#kliDDc!d=lrOM%+_ds^s3W$^O0-Da!0Ca#O&a4i~@aFy*d;PT@ z`|WE7ZQsdutX|zr8{cgsQ&{PqnY7(2Mr`+u7tj$~0$1QF4ybFa1bu~WJcFz#FD)%C z=zIc*szK-DS^-ft4n*ZK2ME(u0X0_WpG3CB5!HPR8@7k15w#w&1s?HdQ0Z`sh3Q-_fA8e|`)3hZLH&~Nk`wvtM0Ytn+HUJ z4ajohMLMD~UG6#%bv2X@VLwnH%CnFeJk@E&5SJ4dQ)gEvr+8;v0M9@$ze|1KSSsRF zD6qR}QjwxQDG8oNm|l9J)~s5?3HoX{32I@dt>XkHC<1d%E8^7&RtI_a2sH4{T z_5mAfZ?$3;r-el|Hht5d*vw6TjGm-Ed-Lr+J9h!D&B;N`H`myoePgRV@L(;Q*)bN! z+I)m%w?L?Tymo26FlEeq&s^^M^$HWo(k%0>51G36u{~@&lA73gln>2DE~M?JKbf*0 z0YsfV+ib_rHQPE)(05`={=Pd`*k>QvU^m=Q!)BJ#?Lz7OkOEpnGty-Ma#%0QobJwL zb?(j+T{PdhVHOQ=MGqqoCGaV7L`i|EM8VgtTkG5rDyZg;To=dQ+-D!w`&gg4#`|}Y z*LN$PrSjl?(L2UcA+GYds&0Puc?9Bc5J%K3Ue>h4dM~rib3hb2qWthdU;-^sKond- z0zVX?{%Lcndu_JEzwk?2YyFE!Yir3C$U_Gp%Cq2q6fW2Krir=|@RX7W5ib(}8q!lV z23RpXJPU9#XfL0^o&nN90k0x!jrNe!C89K7oud$MPID!G?iZN5I zamx^yli1)4UW_C8g_Is(VeX&GuAB!S;5X4KIM)lOe(!ysYqq|*r>_aGP?uA`(<|v> zQdE+3lauZtdC@;?=JlR}@XSAE6v`EeA3S4Gl&>n z3tUU>9awPeykOmkdY{G0UR(Q&4WMXhbb8cg;9x5(uD43S!}^LMTV91Rj1^i3Q+p%ihLz=^dHZogc z6@^#}MzUZ<-6*1pBerFIt!>*-Yg={{+14BLZ5eR~aZS~@LtS%MX|oq%7-_(pERLf3 z@oey&>d61;iKwOu!+8*DCJ{NJ^jyHF4wGed4%$+l3j>Ha0;(N;tJj`>_APsP-&q?< z?y&Re?H*GRZEJ05kFBcju$y<4+5>kt0ZOqqScOO<;H=t-K(FSORt~oj&4b;nal=Xu z9s!~f^d0m`1yC&0&M0RhA(8q5>+YVlvxud?@@hLk)FFHAFr2ihO?12USs?0DpG+f~ zmqy&P7|u#rj?K*Xv5b^cZC3^M`9;6Ub9OwSoZil)Y%5DZea!QZ84z`~^VY)o`C5S} zr?%<=ztF`zE%t6<*z3RFJqn2Kk@i;;tG-zXMCqBBR0KrTuV75gWj63}h@tGdXx`P3 z*~7l?K$KFAjUq1U=jA$6nPEg#;P6%#d7reyqws@=0Wbonq5-5>jj5xHdq9oI8`2_! zLX6j=B2rn))DaaFu`B-zIig~G z@AR5G=*9bZeW!7MT)vNWt!u7V+gcQes?6btx_CaCBiq8Zwea^`$m@6S69r;jFO^*G z`=x-Wv7T-lINM^qCjg=jziFdb)k>f%4sGQ&vFlIqU$?`D`t8kQeQXvk*y!wt-Lt30 zzVVGscHjNW;GCLZ12=aH&Y3css7l7Z%)(olyHvYcD)U$J{2JO|E=@cM*2>x##=%Owh+>7pKN+1DXGiG3v0nt>DfAO{9f<-3AWD!-ZgwbZ>{vOui^GAk zEdXj-DhR~Zf)j0u;LOmv=D@xV+qb{N4jjN@@S6#1=|_|=$=8VgT7DfKy)_wET9L9X z^|LmN((Kj?#0962yTUwctWMarH7Wb!2Z!t{4_~m}eMhYK^&^&QSZj&BH(FIw1Drwv z)y2uFL%n>P9HS?Xr>uyiiV)dS-}Uw-KniXwb=@>vEUs4x-A;M=j*x{krB_HSPufsN z#3++bSAxyGIGIv-sd>mFj~i$FrBNp#TC+LkL9RdhAU=ggZGqG`(ndcX_D}@p) zG&IOzDO|8A){Gk(8v&wLI|wE5$XpkHQLIZky;oWRh$7!SaKFe`YA@2OBMu$hV* zPRVL|>F-WkU$?>i)@QH3(rX>P!`8=OJ2F#YlPIenO~L&(379won^U^mDy@ror;)L? z5xuF!*0c$Q=CyFs6(vx7j)xmgqIH^g^miOUa(ocoV~6``Lm1jPjs>}n<<>q_j{c|_ z8%q-J^f~u8tlMC>ZrWh?Jy>S<{~lt?>t*>BfQzz;Ye|$;e-Ox)nk|BU=>JoF5J0n> zbHqggE<%Tk9!YdB14PAld9%_fh=;I>H%Z%28*Dk%Z%;n)wmtW3JH|qqtaYr3i3w3g zSv5?bB`?S91`b6&bI&fj1Mb|7I}^5MqiCQOfc~sAZSHI9E39$T3M>->L^-#vENqi$ zytgy1@M5{o0#UED+0TD*&|W`8y`;C1ZsQyf^>DsD{CijBLOM=VXESx{yDG;UP7RGs*EL?y69#9~* zgLu8tBx3l5K$PYhF{ucMT8T*ZJoPK;qquhjL}lXe{vM+HSp5A!fT%2GwWiRFo9i+a zp@tx@ir1i^a51D`l-IkJ6D7$CV~U4<8$b zznS|pFRr=A+4SQ3#et~zk0WX!eY5n)$@BHwOH&}$rLMXDIuLbfy8SM`jdgvgyvHz? z1){K)*Y(yB8*lHhA_3$D)z-K1G3#ymvK>9yZ-<-vYu8+&;Me(-GBdb z7N8SwPt5^Q7{<{pX0n%_{l-L8et+ucI@g}?b?s_ZYbiSZe@dl14w*$`!w?{-=b1vtH zg6Cw#!)SBxF1cJF$~mG0L}5WsixY7~>6FY5Mkr72*qeL*E@kCCizc@3c=d!J;e0C2 z|8=R%D4uz7T`KT3ynEN@w8e_1@>7mW0#QvFAWEDQG|8wZDU@BjIDr#Htu?j>B_*HP za{7HpUK`)Q5fxT7YW3ltNF?460ZsDxfGhdhd=lQx+LL|?Jyt0PSQJ{{!O_8{xa%B> zwmW2*IAtg4cCBqw*4{m4=K-Y7Pt@7eEI?H3%UEG+z?A$2hN9tdaxFv|POAdAnHo@r zy{T@-9=)lB#1tets}RI{24^!1XyIsjIjp8XoJeACnB)x#?d|b(s-lnsqcyQ7js1M ziQY@Ji5sOIoPa3LNqpdW3O`7RxS~_-3G@*VB}<7qyj%*1Qhpqe=3@uOa^i{c#j9Sa zJvb1>kFajlvlwFTs+?;q4RtR-Du7Ybh|x_Vt~Z5mZyUAtmNDz;pRn!$d`}_VOI6l2 zP;3LE;*>({JJ}ED*Kb?dOsz-Z_NrCWj9tUF8ZNhWYwP%3X|?DJt47b0#%w8}rQ117`Fx!=Q}qS+0LB>=x!}x<5mhd zS%flk#`?O@jtUV4O~S>OgwspKRlSK8f?>U$=ZZde7wIxri4aSfL-(sJtwJMFNmf?# zP*(1Jjb1ldJanC zAjuY~L{btnh(Hh-jn27m=)Pe--(9!5Z(lSBGzfqo*#%Ued+OAwuxnSHv%hEWUF>+s zPK3WWYv1|a^Y-+M>p;{#oc9kWDMc?A&VA7@0(hJ4)hP7Gl^X=IG+>t$SzW9~NtM5zpw*IZ^Sd;56%C~%|v5T4mA zDZ&C+lcH&!(r>9oRAk+FynUp4OKVD0%X)m@p0HtJ#x*e>V=Fj!=Al_qb(ZOicF5Bf zutBvq-VobNx<9-E!-#1Ve9?_rDccz<9(7&!)bp~sdx*>z+ZpfCMWw~-I&b`~^BCg2 z@q9BN>PCG;HJ2UhXg)T!t@)m7oi~?tE6y9+cPq-jS!G6A#rEph7;gm-73;cLeb_E% zYZQoMezm*e`0KjXkIhW;)-m4*!mw8To>pI5%y_FHTvZ zGR5*UZ6EzmpZ$kFy5BzXkzurkih$wx_oxTg1VS4~-&bR}A#5eChp`YH;dt7+cj^%TeO+3XWr6!Ex+S;*&o;X8-!LV>Y+Q%QYq*AAQdb`~82f-2;a$ zht@?~2REtRbXePrE3y;^;Z7I4{jAN(f#?`=kD8%r);Dos~Nf)nJ;Z zj~YQB*0U*$*&1!$ToZ2T-Hp7zp}mmQ$?ShZ6M`t;knjdAQ&}6zdxN|;a!KuOZ2OIr z@rL)Pn?&{D`hcj&qv4&z`|qz=Voahlu$Wj(8)@haymqd+jwtO{CDuwT*E^8@(F{Nr z%-rOjfcK*ennQ|mXvAxBy|LQtKpGsOhE+hEGTKHiuXF#@7`y9TsM*O=^Y-HLaXWqr zKTwzY?X`KdX4E9Lm!h(OMk_1uFy>%>A%h>OmZ}Y4zPA_i;m_?pW>4%pW{cBfwlp%f_Moy@G@wm^=j z)pH5}P^d}6g%!lf=B)vE1Gu`Dk0=4*PF?jY{$PPh_#&mm>kHmq+BS=6-ldBd{k?QE zAW9|H0EWQNy}pEeFF`)9dXuV@F8XMtP~SYV&UimJxyf71A3+@z#;F7#whAC6r`lhuNfdDXrQIFW_|kbk(M2SJ@n5#byfgHb+dQ*qtreiEpqe>ukAb2llnw z!w(+8-|DdK+L;763cjPVXcTpI24G5jAhBUoj?!PL*s)_cGDpkkwX-;J2hcnXmLp(M z%r=Ol@?E)<9p2r+rb2yo?|mJ1`2K|LKP)pqKC$4VY6VLK`CC)DZbk>g$hVT*a9k1U z^dYOygSG2=ASNlp0nNH8cU>EaM9-!0pAAEv9IzigGiZzX1;EyM zHphd%(2N>s1&~84=>gjL$v(Wh-j1{KoGpz_ z*z}q6Hu>sln|Se*6)#O%PW~QRdhK}EXY5$d6L#+MjGdmCMwpmo*B&&YKGZ_}*_Wr}e_Pd`yXdnIvU+VW|Y?+x7&`@Dsl8=u1)+8aqK`mL3#wNQm$o2VPg+CqD_lJ#2ib}MCh z-sWy0%*jX8W~Py&_=T+McK1cW|L$1 z7P^$TbE9*10wC&zqaF6E^R2eXj(|)w6sQ0K6wAy(*G8f|v`#Dyz<_h>JuOB1M9<6i zv4NMYy`voBJ$GCCdmgb?9C&BjTCJrmLzFfN?H1@Hyg`ahfHUexcrTL%7baT%Zl>1K z-z28E)TOzu*a$??i9iPsCfAChT<@yrDME6pX|Iw5)_9uJJfw$fT;azRV3h8UQRGu0 z^`NpeCP5<#APOH*R|BGi0jj?$OBzw$=2%eE(W_(3=obBQ_NeoS5}GpCPenTg@qqwI zy(6dbdzuFHP@8qzGG=HC3uxl7)}DTyUGUCVY!WbJd=lSIGkKes%li(Cg`&(em-r~M zV1r$)c3}62?b*?3BLh_%Msul`wBD{3H?P~fFNK3|)^WyfX|aY+D(!+=A}#{XpNMPsbjE|24HcI=|{V0OA| za0snG%uln}me*;oxh}KADnMM4F%hUXhiU87RN0<>=AwQ3JFnW)?A$k6+CzJH*hnY4 z81{A8r#?}!Pdy+2IHN3nNl$4)^I)tE6qof1=75x5UOcmI2=~OrMfba-a6LG@ z;E*Q{zNf`|b!-T+?s$xKH=f5d-4->X8i6QjM1A8M-|!a{2`aI#4b`kMUo5xr+MD^U zwl%hILs@l_ZAiNnC-pJE6-D2QGUFKN*cfjG5Opiszg_0dqW~$USU8X8=so7(HU(Yy=a~7OZNDq zy=-7`*dBeXAI&MW0ni8t(v`F!ZXytM^GLB)Qk);_38K;38L|R`rku2}zDU53W7O@+L%p6N!9)@si+fanxa#^>FXD|3@!6u?^0cwWqIS*0G%tfj)b71|Fh3dg zjWi+=u?`_r5N6P3!2CHVQ?kNi@ZkUFywq_Y1T&e0bDRotKFfa~;zye@z3- zsNwI21_h)>#1ht^tQ4wpX_lLhiLSEnQ<`?WQ_${r?th47NG4`gv_{+tkODS0s!3NsPc3?-3?c3R7_dlGn2Oddbu7~d^;VuFbX{_ofmC821P`0BlR_rKR zQm0N|LPKiQF3<7NA>RVsGB`BHe7U>L?mN_L_Z;rFyAGi#bufhqr&(`b&3#g3*}+eI zF0j=5!EnppQX*LhQ3E3aq1ohvR40<=XJRc)lz}H)D@&smsKxB%*NXF5WtE)=7h3H2 zi%C2AQo?@tvy=7@&z`XP${;Eahv{6{O>$pn(VqCgj6MFrylaWweb0!^%unFJeH`CV zoi^Mz$PSh4=E?_UAAnFZ-$wwVQhYR#Ru;^+xKy!O=p%E$?|=KWJ^ibBJG0Q^rm#I7 zeYUr|&%W@9W&7Oca3H@o$Hq%N_~(-I^U(a}HFd+9TL+><7AJ=TccIUu(0x&d_Pq;2 zSPL5Zew98q(=(pO>`_*9g$2e|bN<4)3zlaCfd2k|c(#uXW!gPnO@3=GGnT!5ynPh7 zUVexz(wN1$rQ=%-M8$T!(~oa05allr0rB%mtA(^4!pjJ2sNNFYdQT9_eM{DuAf01To(5d4<2@fhea&!=$bY5h9U-z6@9EU$axZl*h4EK*=6s4q~AXAsTOI?lz^zk1|VwBZocvl zyC5BbsHhQj{WaXAoHyFVhGB%TVZBq6d=Nt0nx9K?eT*${eEx-NZ`7Fe3RT6%$J3Sf zg_%dXF0J3XHl!}N#fH?6f@HQ5n#+iQjx?gGu9dfHC7d&t0D=TWDGuQq?7%?*Q5^sn zf-4BD55d3_cA|*W~y%Ig{$3IFI)$8G4hINr*66y z7#F-8nQ8G~+Hi$sOfvCRq_H2Ls^UWmaB6%WAZo$RT*}y~%k6e~K4}Z3iWTvGo~;(x zCS%q1_O{!u{&qWzCE1aCYBn^G#dNF<@F;Cv1DMw_w!$kJ4!d+-JJaFN`|KFnQR8;< zbj?nj$4Au?yZrI2>|ovA)0@K~cg_y&&e{RAfA;JF#NVBeOBUeqjX$6r~ST|8|b zzyE_*?YloZY8MwrY&mf+)!-|Q(3Q>G2ltNI!}reHaTHBnFR4fSpWFz6_Kc;p0@;zzh@Q?$D2HflX@QI zd#8u^j()X%uC23Vh|jLZG~M@RfGCyKT;A2%vYmeGDR3=*Xly|ow|LJs5Ywhzj&i|5KJ zUzRUk_P7HRl$~e*tOHT6*~}|1TWMkuvy}r@Ydvhgs(!$pvG=p>^@3em!Z~bL!S?Sh z+6N!)vd?^ck3H~U_uCMNstbFfi3bSR@Zzg4(-lNGt*;S?ic9R@{{0#I+rK|;ufK+= z-gpK9wUaHt`|RNdy6x*r zsR=c8K!dh`4DbnTjYq|Xv1t;m)pBKbZ5W;V#d;12H%jA=Kqb*)1yz(45UElDK&n`V z7ulkI2@|{$&ZVJ^jGLr@s2k3}kBJieyMp8Dg?z=%P4?TF zB?NGQG@o!nHH2np^07l3(3iC(^40|aB~T^_FxP8~)?*9S!xr{EJw4Vr*l8V@V0H9n z*-;3eLh>sFP|<~RbA9(y#7Y^zM0KA-D4s~(PN3{02j(rTpILn41j+zFs0l>x1hfl$ zA({w)3cG1KJ%C@TD=EfCD3bb3WZtJ-6H^}`84K15H|qrj(++p)rsolj2yyc~d`^dM z<5R1ONuz^R^i_S1K-9Q9D+h?$xAzJlDvqfa+VID_(R3c)$8=5obW=n>Q9?uJ#-FhQ zjy`XAPu9_Cr7;t2qzxoU%8&E`5U+xXWdZFdJVm%hY96iB#o3}Q&6e!c>t?T>NZGlI zfRxh}o1U-O3?St^U~4;Ol5J?e_2x>Lqm^v`NRJ)fGh}=AV~TztVSOVB%dxv&8!-a| zYj?a!O#h~)mhHt~SL_#0;}rjV(dL%f*kPq$Wv%1Te6YR41_5sGK9sY&?(VPy2QoM{ zPub95;Eh%QDS?!RU$R6J$5Y99adhaYgHXYIFOY^095nzTYgwQ3t`Q|5DukdBg|?rM zB)kGWrYAFK24?IBKRRar{4cNCne!v|`r_Tpu^u0bzQmICrqA2%fm!>?7Y^8$i3_E1 zkDZv*4fF#y>Eny|FPLW+F?U_YB=E)OXYB|7YZRK~?bvvyP3JoS z-f()3nO`Fi)e8{S!o<){j|v)F50n{F!e4*RHY_BbPisibA8uM-XzInhlMnHk9gpg3 zoM+Abj(Hld>$iZY3JZkZ@fELEBPx~?kInUMpWl88#4(OXwcuLgqr8gSK-BFSueTJ4 zQWqn0tT9G?0rhm&+IanX$PvqkN53a7$Z_4)6T2Q_KCgp(@w~p$$7~ypu|4s);UXt0 zBbK8)5s3QnkAG}``lo;D3z~dHef=9>_Xn34-31r5tD(QKjOOyUa=uv^o26}~%y(nn zIMzBgMva|bJ|-q6(2BX_{%hKCX4%D#G5%7{R^C^AnG_+{Suv2c`TX5T>^rH?aqWn0 z^7&a`lQdSm^lO{+3jk3UE{xeuUYvIUMy&%;$8GkN7i@KE0h@BZvbNu6KP^0BPnO6B!Ap{{cp1qYv z=7cw<&b+?9N_bl*p8HloD9|gkz7Qu72z|NZCHu*z#_eC88nahkEZM8a@o7@Z@Flq2 z9=a=MfAGz2`}`MW>cp2|icj%nJc(20HGd#dqliFMy?U2Z8p)xyc~fErF6za-p?!_n zn}5f-AJZFwsQJ1107NZo*SwVN+O@uGUYy&vZM|J5cW7!ucVpYH>$ssDjTit#eckgx zP$9~5t@3p}mIb{X5YoL(A&e#U2*;01^o_WY$-x510pRh zR}lPZ&jfy>(0s|@(@Ew{GK;McOK1uei6~(b0ixK!>)d4=S1-+D9yDor`jW4W(4v9Z zJo;Q>EJ|qpuoh{%F@T>PY@*PK?+2K&>N1F*{EjExDru_DLmT+;B!#7qO>KAkuw zIrm`$ypnG%0d9&KMwO=BGRIsastgddj~(WAP&VZOZqkLR=qoO??&+ zrK2-o^9>|>P$e;_-2$R$T+o2x+`%W&Cq&hhtjVlVsE&7)Yd*8BgvnS5Us7k!vWw!$ zDvr3(mKwu+58qE0$MOF(TehVYc6ci!cF)ccc8qJWkpmSQ+G*C052*pb z$KAUDRr~cb6+3eppHyfDkF&Gh#kpm>xD1G>HlfAz&`5{fb+E&Z z9B9K-ugx{2Ms_5vw?ApEJWpHMIW^g`$a8Vg=Yi&cGz}Fap@3fLWsV4=sgF*hpo18C ztiR9$5Y+)G2qu%ld_K$kX#p5IWl#U&6lR43_R5)qHde}6C;8LWCHj5Idb11mjZf_d zjM`_3)(On)(TM87gs!jOeMHGD)`2L-Onjm-(RwAVF2y3ChJfo=US6;t|6t0Ve!5^U zoo%(t3$2*u=g^4C0Yoj^=Rd!UiFXc-C`|LPfApn?zC@nzXRSYPRf!@MdgM33^FHpo%A zqJXGB`?EiDAnH&4VfwvFXy3-8Zso z?|n}d)4Xo`$ZzblyN&=vA?#`Ua=l+7LHNscc)_k~{*WBsMb(VAHb4t+j4xmfYb!!R zT+3;oL`BgoXfa_LBVRS8svSMP%&tpI_KTk{*i%1eH>$ak3!V?*)bN3ncktPv zb)A11cI(Qt3W%!rSU{9C9fGr$&B>s)NnU9VK7h@M*FKLx)cUS@OPDv|BMQ(VXhaRV z5E2+9l=rq>gOP$O`#rhdxe9Cpl=c)br{BZ=euJe!D{3acP%q4#Fi_8IXC{h2zAp__Pk2vhA=MNNG;w9 z|Krsu+gfmwJWR#pP`d*9qqu@lDM#S~qU5Z6cx1>99+qid&P}!?geKsL1U5@z!7yJ{ zYQ1DNk25u2z|soZDXYv0VLsqknEuHJl)xsgajrCJ?C5&22ndE&ONo2H#PCyAwZ(ZH zN8^BbbYcnfJHQqEt<_eOfJ{Xz(C#uq|4JoGxpLMF7*)VTi*i=VoM3|GjY-NJsbj6* zW|u9O7^RLpAWz9M035?OlkUY-E=QSZK;Q}6WoMGRpe4W;U_c6xDxCqI!kKw%w$<9m z-QYBes%j1z+VQ>+f#0Va&dI05H0`(W(KEYGFYF2uOWeQQY~0YPH%s zA6No3ad7_n8GtE#hs`XOY-Xuw7iLy$bdeiUSsP|RdfPFz>sYY<-kR+j8o(KOj~zIY zvIB?tbi#PG10oe+t;Km9QKBxulT0@SdL}?prM*~S-8gx?WKaJj zkJIvk{qk7J&Oz&*jxO8N(`8@yWW_%FxvK5mjkEIJHh`$Gc4)jJPpkn^8bhUP0a5h+ zg?wRM3rX+BziVs#RXX2DAD=tqYfRH^+opL}A>P|C`C9xCyVS@7@t$oUDpKdx9`7h1 zN)O-248B14V#}X;*l>-s&CX+5yys>gvA)Lhn5Md;kEkb~eA0m^eNFq;x4vax z{n}U8fG9m^^aVwsu^dl$6Mq`p@g|CS*WVh)M90Rs4Me^BSi{F(K$Liaulo{4FI^Rg zI)Q24i%M4S~HVOS|Ry4!#JNWrWOC zgi1we!;X(nGVTLznwQJv0F9KFdK}R}yNBYOWNK2qpOGG_PGHkAnkjkaL=k|fSire7 zT24!t+~GGI;0S;UAgT)JB-c$?g>qeh6kwIk5%gu2=h`MSbCd&CP|4xgAJ7C1mYR?T zG?qN7ud$End<;?n0wl7ed`yMVT7A{}?I?iD0;XI=0420kP;Kf(;O+y#XhncOQ@hWO zChx`64ndsjg=!w~3o|OwJ^>n`K$_u)3OFI8F~5_f?LhN!2&d+QosGjZ;tnDdZf>4n}aW!WQt9}9dI$e0-|)8?9vW`I{c@jnyac8 z&_saf@`85PtJ-TPq$yRiF--NwaddwCY{j0#(Rp6TDD%O}Fdomb1oV1vaHk#KH3Wc^ zutWDG@FSHbX4qLOW&HyHF=$AQu_49z(>ODK0Zpl+MLPx!UmiWjd=mP)$~r$_{cSt! zz(}{@8{=kGlLQ9U>-PupicpSFGQ_W=CeDic+8Pwm%#@wfV*#e|BSB|}2YQqR}W zQQiJ73SlmYHcq&!_B=k1W4?GEZ+Npnl*(x?GnT!5ynPgi;~S6HsyU9C@+)owQP-l_ z&AI-T15sCWqrQeZcDmh>W!9#hZ{A89E+geU0ZaP1Rj55alliO^at^IX9u{ z+eO?U1>)H1*ci8gs2e2c+w!)s7=`hdV9v`9Z?JM0EFV#qHr0qajkEG&R-0ME@5LTV z<__3*C*Eg&v+zE{?e(}>^mKZ zl2D^J<9dU&nCWG?9;DMHAWBg|f_(wOy8sZix*~_~3H)YE*d zFFbL;e)HqIY{w8z;EAp66*M8_w?QxD2u?D~lLKQpEZ;16b7)7Xc0&&C-f;d#CvpBO z&((n_c7$>uYNL-RzsDuZH>%+Vuf;B`le%6I^pQ6k_o;QYvPA(AW)tG9-J*h{s@0X#)^NKF$L}$Gr7pJT&l&lDv3Y7+5MCl_t22+t;!bJBOe@ zj~Uc5DAE#MrI(ghY%yQrJOQwjbZw~`T1dhG@++7Vt!5D5X$!(_i5_DN95h!zNtiYCi+NJ-4?n!0Yx5M)XMYY&mz)Io5Zd$4SbO1F0I&r&JI{2s zSjVnzG@a6x83*8+#dIru#70wxt+%Jwqd~Vapi>DUyhK}8SRYr)X*Ua8SkBuleXAg( zOHl7fX(zQ7Ys+Q;Au!ovr?zAkN9Y;$Si@0M1^}S5tp#(xELu^3Q26wZOg7U~3sn0|jJ*6>l2EH`108z^HkX!Y5KfCR|mG zCF?OXOz>eqKoePPVSdR0NP(Su_TVFG7?VaVe~Oglyer0CTMt9Ep02Cpb9NW2X;`@I zTpZ7ZP=&;BV0LboQ z=e;leR>nU2*^C`Jl!R_*m7xKsbyQ;~UuJpqXUuW4QByD5PV3sdfjl2tB-dhjR`D!~?G4FUL^;33E8fU6OO< zRZMTROH#`I@!K=@-~a2ly?BzH=n#DSIx_a55AL@QJc{3}yHa-lUA&m*%GO3qVj3iE zv4n&SwscQOE2=r@;qDO;p#Bmc&BNTBp*jCG&f^+zB@nfMMijydU%od3q8gtC*QjD^ zmm6PRbZ2~l@lyCApC~d4b+luXlA#{|F#Yf`+a$w{Cee;7fhc(5YG7fkCkk5ia|w$Y zFPERC87Q!*{x51m#aq{g+KE6e=4cgwMjA{>%v=*`=98RGs|^B~B*0R>pQ|1hXaTKs zoqRPw;A#@5_yC;=d@Uul6CIjDGCxz_ssN|UfIfLl+ZNdkOtBZI+iVzz!)5?iG=)ll zP;&q^^Kz^? zAH!V5AP?<}5A8_X5j2isXqo(xWygPHiB%d*Nbl&h?0o|W&H!JpqIq?8#irZ#+f4g@ zcKX_D+Cfe)=?X>6nzXyvVjh25#XegowAqF6b9Q0kJkHgFS)l_0XJ=T(dZp1Rcqd>%E%+%)Q7ahFW zxdXp&1JZ(o3!Pc(HAKL#o~E(ZPxU#$`sa#ldqNS`0JE+={0+8{1yCs0pg^303e6#A^7UZ{t+AAiJQ!VBZHZnR)N*Fu}lpQC>#%79Um z_QQWUYe&!K(asy;8Pad_q6Kw5x@+0qbMF$S^nLbQAKhU)_vC!)`F9aYl{qLY1T_G< zt^#J3X$M+S@=wMFyY|9MHGBHmvi8sspVimX)|j`MW;Y5%#d6~DdfKp^=hjjn zj`8)@qWl_vJ)!0IZ5xQXUdr8gzB?9(QkS;EK(}k+$2P@dthezzrl}9xK$NKP_6~7u zb!?2=K-AlNT({PG#-5i!efD-9;O1)qQM1R-+v2Nd&>UE1Tk1ipw(qjPop{9lpN03@ z;tJ*~tMm5x4|Ll%zcOr(Jk*Xr!wYs72e~`Do`|AaJ{*`gNJaYj*QDt8C_u9kn*<~O8V28&{OBo+gtL|J_4uxHy zE+aTOz(Bzyd5A}y2;d0ShHL!YDi9UtzY2JJ08xN24n!f;uLZqUtusylbFKwMNpNix zWY-G2`VXHX4Z@Me!iDjMwC1~&M{~=0iR|_35**z$udX%{(xqD2cVV!tL7F~i7RMIl>urrXVL(e zZ3z1r2dWk^$1AMlaU7mUOHdA<@w$ZIDHF9Ue4ND`Nii7(;)E)TsR- z5J7;O041p6gn z-k!k^l{BJ)GiYBA0HK7T^mk=#5dTws-I(ynVLIl09qioKj$f%n8n7aj2h7%3wbB0+ zJN^On%OQ4_2#r%{KP3gy3CO^=k{nzcX#&v8m{HEpE!xD`gbOQscB2tBGz_l+8i-&0 z`GD>xyrWGSwD<(9AaJkumcD8r#dEqQY{8YFe5^EPiuxape!?vwgmTu`B%KE^Ddq_I zxmWkE#duX|s$NdJ1#5=J#PvY!U5m^I0U>4iD#K^lELwXr#LGA`zbuF5msf0Tw1k6v zcF3DsunFeF*c?0V!TZUUHtS~BHx!%j1y->GyK;8#p*}mX7cE=TrjW5X|vt#_^d*OQc52dd)vyY09>H?H0Dn75f`+d$N{Y4>)?5y$v? z+pGLBO2*p;qOO;6H=gf~2BL1fTet4c$kg!|7qG_jn5I^215vkbEN)lHacp&LjN3re z?HYkQp&rIw!txe?sDnX`ZQ(H{Gw zZw}i-547Xl6~PRL+?xVXnA!xP;trric>Aq4M6dG_s^3^6N)ohvV=sBRT_O~Q7^vBCrT)kCL zoNcs(JGi^MyGw8xg1dWgcL;&t?(XjHF2OBGa0xcJ1PBrw20!!fU1y)Fb33>5)vEQb ze!AOaH6*A?1bRUTv;6W7JDJx2S>g&eh-%mT7W1Y^e^+W#WDc(y_Y%4g#b5VJpAWRV zqF1VcUgpx7HyoRMk;$d2t*(H}d54D7g_kr?=ju|b+MZz5s}VLR2**e-)J4v)F}YQ* z2z2?u)i~1TOeEn=PUUBhIzDv(a&ul}k5hgUKnXgrJ!}4#5CGZ^dB89oHDB;Ynwi@* zLAt2KwmZ0mBa!xP2>PW0x0G*Ck}mdWAeepo;JpPsCk3^LC##3!>7l)VsYQlZ(B>Qc zz{=f*5}r1Lr`dn7MGft-o^NX>vW!s@g1#70V`?MqI7%@S9850U!eJqc&fvsA4}{VB zw5HKyl+JZFo4Ao3d*JE$ZBye(UlHHN>Db8kV$k=pxj|G|t@pG8&vDQCIMXS>d_~7Z z$hnrIpvk@)Wt}3m%NHGVH3A{MA(`$=+sHXe;j}?8*w4S$%9ImT*Ul{qXH@TD8p;=b zex-(~DRzQhOP*Wh^sim-f=E)nSUwyo8+rloYO%qkq7~r-V)mPCw1SYH< zUpU=Q=k^9FVdiNF2CJOEM;M#cXFsehF1oO-2W+&%?1=kn@^KCpI2_tZkHnOZKG9;T z@<#F#k=DB^IZZEDTnw+b+REc3wzzsS+}Q9Bx@Tec@t4M^LS!j7fFMLA4Lt6 zbs~7$V%0v-N)zXq)~JLkV<)0#5ug$mwyT_*Ucc64dbwwG_*#$dSK?j1Mew~S$J1+E zVxy;ZDdPLg`b2^V`a8m!o9m#^Ua(5r273vX*UfNDANccjz|(X{pGbm#(PVKPA25&o zm3OPvCW`FA)ixl^t%t=70iEt*-q?>BEvn%BCxdHzL$oONRpzU(VAFXiLpNgHq7U}i zl(KBLFk6sXOiloZaQA-I=Hjo3ahr)~Zl{Upj?0|!KVYmA(X`LH0pQ6{-*Dg#9Q5|m zcmd%`PutMJ46!u+&W}dSEFv2$%Uzs})eB_zl|qi^kfsW;7@6N3x)*_ORi*Y>6>Xb)L73+MEdMYhnU!z!y-gKQaa_L`Q2AQ48w;iAR>W{bJOFHCQ|Gz0z0y!PA zVS~}9$;Wm6=TyBF9O^NZ^K;DwUdoJ{#}kRIV1bLoEHig+C5|nx-|;|p4zwBVt|Q<- zn-V*fwTY%zZc+I*khyL1u{!-J*zvRzdw(-tRE;$iCK}kKKgp|?v<;ZD# zrBYeu=abml+x(-IU?0yQ-vas^b-Q!)6y^3(SfcIM{4n{=}6SeP@7)d5He z`()G>M(LO`Y1TmGzlv8t(yMvnKM73t#6SdC%({E>pG6Uz@#oQeuto4+P1RL~xw=v$ zUF~`W?kaA&RMQM)a_z{Aeeo-2mNd2V&Kf~~qKQ1Ka<4n=bvy83M|F-|;I=1AB{Uct zOau5`!bLU)8cl~4^K3FF1RLmz!v~vIloDQ^uakf8^^CMbZ3b-=2^M>Pqs084q*}xx zq*_+aMUkSj%8foVYfbDx`Mpy8}hbTNtyca6SD`$H3-iK4H5G^y!KiXSO;zTEVRE8qQa8d0PcpJ{syiqe%1p$TgF_w9rA(^~OYyv1C*kCG>` zD#waMa*$kb(@fMKS@_^&3!x_l#Hyhw8FnnK;Fa*bQQVOVF*4a_*27U00UGkc?tG){ zzTW#SGwelzKiXiM5I8y>4LJhFe0(#muC+V1dLp2pBb^X=6r>{-@xks`oTt;xBEsi? zF1Uk^39D+A%yc>9H$zo3_WDVCQ83}Md`{GA$;8$o8XHjit7~j!uj7KgEK*_SyBgSjP7s=x45*B`GSyfSniAg`VQSI1h<*>@sJJ*L^vJ}C?$i#VdX10(O%FppDX#bqNNiejr+6|HmG+u_)ZoY#M z<#Pn9^aZ2Pr^>$Ys6lUuY|cVThEl zINP&@17_L9#}m96R5ymhV|9jL>w6r2PS*RLQylMD?68a2F7*O#&DQ%LlJQ?gTsrn& zsHZZ`JST@lXd%I&Rc^_89OKwhxcY{${hO2Xujm`Br9aQECt^K|BKsd?hh!*&rG^<{ z>rnKl5dMPX71do9e%>}#UK}pOy}c4-K54whko5@I(b$@hZm!#yJZ*}-EFM4V3tJO9 zY2ZpET%BTNZ2BqKI9ycY$Q~;^lm^(IJLkEcmWBWsN9j7)b8RZi!^7bWKhJl!1~FdS zbM|4$5e9v3@6QH!Q2*7C#021abKDq>{9y_3seYEk&E|cM_vl*s7UpT7J)rvq)4ROj zaCMZUxUcxVsIRC8_H#Y7l-3o(QBfSM@-Y{YSM}&K$(Z3d;pvD@BN4-1kigdz6QHCW z5fNtGh&4TD?g*260dKht;STE`MIas!QiE{8P{YTzR2I&?u@0dGE4+DZg)#uxmLLnn z{J+G5xB+=tAky+|Dsm2L(@u~=JQ~8)S(q-(k$0}g5hsen88q$bco^z{tnk`!0O2jy z^r27-lA)dgRw|!-J`TVXB?~U&&=(mZK{QN;_LySXpio;7IaS{9dIYQdQdKpKyf`7V zj%;)m4sz{v2;&xJSqYB*J%MTZJMQ@W+u`B#E{rU< zpiLJ2vh$H_J<&qPPqNw2ILAU`wh6RGgo)Xhf`BRH9pN>5G-uMHZ*G2EWOXTMN){S#y@=3=h4W9OfD2z}|%(qC=bCd@;^0Q46A-RE6Q5;AN(}APjKW`Zvhh zD7u{RS8oj7cYV)^(MGbz=gQ>wKMyS;-690aSi!Tu|7acz91tjw*OpbuFKgDMJxfH} zKh#LXLJU@l5~zjAGNPbAx5SlZoM{&j-RNdeS1|F1N4pVMo}=d6_8i4bV7~I!JDkJr zN*x!OI7plgnETD)c8+_uXZ+0(ANIjNE>4&U{`#g*bEW&IaTV)0&8uiS5@08*Jd+Ux zM$P3NG-%6ZPrr`Tl2NoLM_VPz9c)}d&S?t4Y87b9RBbWx7j~5Wh`J!Q9$(16DpR_M zI3dHU<36Tmn0#OsOH;{X0d+NdlN7?O?QLt-n7;r79v?c_-$ji)cQMgt65BSm9%(Oj zp`7f4tLfB0+f<*jQ z*0+j_da(X?jY%U_(Awt_uKLT}*>*So1*HrNy{ z4wBUUSSXljN8DJyq9J)gMh4ZK5D;{ADdIw;GXokj;WT3Zsc%9Svd`@#b3Ol!G|w5OEx!i1 zDmN_9e|y@lFsCo61sTZ!#O;TGzEW?m@mBjFLm6`cIqby8_sk_p@RH&lCl22$1 z^I+A09CJ`%_I@M1aQRN`0Y>kL>7PuFwT0i8PzDAW`*v%$6fy&1jT1vLDffWX@i+2@ z2)DG8x_LyZ8*8Je0fI6YjqeXuO88^-o$WaFRmLyF;}~l;;@*JBc6pNR&}e9i_K`fT zu04uyC)9h-ZpS@`ue~-F9cQAk4nQ7Ex*5h%VYH~Pds9PXQr}lI=7B2+?jwW|3n;79 zY@_azxDsmdHmJpM;7;R`od!28yhVEbTE&5~Y@p!^{00x4$`$WiDaljtJpB(U+lYxs z?J8k_`uQncDnklwW>+@y>Yvx{sNQJ2SO+2Pc@5T97DG6^N@Db0|5fH17#IMrC4aZK z=P@=R+z+UXpRaJgp*r>8fqF7DH1U*~5jM1+x%;kdbgWmK@Pdl9Ju4)IV??}pc{Aqy zs=Jv{hB<%dUbm!r%W%^^St{NkCC#h#X`_^#XjCgA&|5Zta~^ zYm{LJok&*VmxZ1zxzJ(VyvFVB2Z+y#+J>KL%7FQx`bJvH+7$b)Kp z{*;iDrPsWt1$=wvQ;RP_js#fZwCq)EaFbkVzAELpIY~u$j_D9v$H5S5?sILr zb{&C8b2NE)z|1*Wol^(5=(HtKBPyW+8gr_}@d@tVuL`sWQ>ZDep#}`5z+}u{ac!*Z zbkPSH5x_g4JJpb&dk2JFMihb1XLRwcf8*HpqKr+cavaF?9Y$BvJWr>Fm-4}Ipmq#p zis_dxPth%9eZv%fdPuLK{YmKT#e8vm*#tzS2bJr1oPU660!r$|=xG3M+xkNciB?xg zb^<{ceBufZb1TA3FXl?1x4PTE@mjZ*MfQ5U;=Cjt%V;YevB|TiGyWGy+#!gPm;*-P zsJwbSOJ36+wV#Zk|6M3Yn!(LhESQPmsK$Mo>PuxamGokFOTNhMSH49}X&U4t+?h5k z&-jar&!K2zb#-MIH{T{*$*f8N>ZJ!Ld>BQaMx0Zees7FYbIvb2j|c-wAyEsVwsc$m z1S+QsKhH=^`NzeMX;^G?_6WId|hHacy!w}D;jr#hrAFFfoTyu z39h7{@?S2kDP!*1r=Q=@F|PIfMYrPqTh89LA=j)(AD2Xt|CTd@tx~UzV8%}xID#tw z>Up1?^8VY=_IIT#62^Z7eS%np@%sL6OY8W*EiHGw3>(m7IZYDCRL+VJrfV=`l^ON|8$I;OqI%%DqhL2DpWZ<2gJ{?)=EWOM~C2<7%Jx7ST`RHo3i*kx5^vq@Gu3693kHXj~1-qZr!SZPX7cxdo+> zD<84_5Mjq?@VAYpCzNLIpl`Uyky9(=Ti~pQ`C&kxdZs(XyXdIVqpORu8SAar6&9^e zj7FfWq0|nUPm6-)CL|jxodi$}lYVpvU{@6?J*IT5v@Ap zlO&D`Z`nau1fCx4!xcI^d$R(1v^pl(Coa!z66p)OocfDn-Av492?J)!G;cNhdUB<) zi0V#^V&7v#m5J})yFBLxfh5r0W6zN|q)>)c1EE6g)%oVg?gMF_@KPhRP*obEX|5i` zJi|}DY}x?4T~r#j*x17qZn4RQs6|Hfqnc5EBr$_V~th)gLFnX&g{x z=h05zyRIZ;-gZ4<9~i*?2nm>P0Qw>aeRzBNEOiZz5$(6N?UYHw71lKXG?+>xbUw!_ z8|Vm5gSk0P&_D{QbaiY^buI59S&lzh-;IauB zA3lMQUo?ly^;a;dV zCGj{DA7K3-yT>JZ79fKopY9`Vf7TUt^?)~g6O7YkL8H@5QcFvxWSU22i!w6GPdd=$ zH-MhZ@k!6W!!_}V^`PIdMSJBjeV#+-yuE!<*&E#MESY)Il1}(d94M5zBVB^M8}Udc z-)Fmheb+?U5t^#D2)NdTjXGB6)bQyGc&1(Io$JAbq!K-s|N4-6d;>ub6oVL`ck&JY zChMLDiwtH@X%^Kpuk}?49iiz>4bGHqNXjx4W*SrFdl@|->6m`O^jUk+_}ODL;HH-7 zWoUuOuwm~5^@3hjYA;iDGry_PpUE!KKPsOLDpBol^c)9LMR{CH`UaD7Cm^O%3!~1W z3s5f%sB$cPt8eLhOjhxex^Eeh&v~LXPLr=3la;C@4IV^xu)tCA_W~b0z0#Jw?A)vH z(f0EM@`*JzE{|mKPq*K1LO9Q}Hm{zK7|0zg;DmgX4Mu&s716xm29Wyt@mo`Mz3^?l z@cKNv`QvUp(9z_5QrC;zQp6{>flqfw+T9Z}&XB*S@N;{JjKS6Yrx2dh1Js*Qw^sEc zW;;g=WrGFS|97m_lcX9NyWfrsnJ{>BJ3>pv8|OgB<#bSqEwdcWeQCK{%d~}Z5tQ6+tYcOm&JTvkkVt}4Y+t%JPRcL_0z>fkz|pU(2=sd zkk8VVk!AKR>+S*4|80I*y`(UViYRjuVOwIdsP$Ey-Pi%rH>nH6J!M#&zbbM=;o7YJ znKg!@hg%}rc$&nijJ_&Wn@vH)jwb+wt$F zm7H_BD!m}pYF7!c%H3v)FZzRiv$ihH+HHt^4#TvLl6;)WDWSER?fd-O=H4SfhR^ z!Y8!?(h|=_b|G~jXCSNh4N8U%z=5g6b?})e!W*@5i7R_ED1B{{+L{7Dvvg3K#hdPw zLH1<50G~7R(+H} zH+znJ(6k}gMd;aQ>VUdq9HXqqn33Sm4MV{GyfrT~T#QwP^rRPis90O^E#$Tj9t~3k zXtc}FAYY2)#E=cUg4@jB0QI>DJH+A^KTURm!!^?U&t-*@Qpt6;5{wi|6m*!onC1om z9=6-PwKCef*H~LI`D;c!B_#uRzgQ_n;kSMYU&8cr85u%W=WsKCvps6%Hz{x%HfWo+ zBM#^Mf!^l!W=ngb^^Ah(w)R|OBEc3qyvD0$Hq=%AmNiklfO*gYdtB`TQqJKCnyR?I zA4!udzDR-7Iz2i0T2z*_U(!-U8yAwNbcf-NT4MErmS`xfB;jgdDb3TY^^U(p}C$}SwlB}w?IPWKUNQdKk zRCk|#UcO_f`u!!vrW#i~%KYyle5$9u24u-dC3#;~uwEyfo{~hUn z5#m{7$tH|=(vz8QgK>G;I)dVoHft$^1mG}|_1Q#8p@3_-u##$;aduPygJglq72YflWV|H-0bd*x5DR^ZObefE7s#K0 z5Hs&p(|yr09gfM&r~02U#VXfoqG|!8-;XhtXQjCX|KBWtgY;3|3fml`k?vAlg-vmU6UM2UAo^|?CCHyA!c@FX1%lj zp6%sywg1$_>gS0Mw2!wB_KGAcO@Rx=ju7(C=9OkH2$Jfum9=@3Lt+dGOZHJ;mXd}g zph#kjufp5@InE`VMR|mOTxS7g!g4&fad%c(AEX+*9Gl4&zO7BKPy!S5%Hf8H5i!$E5qeF;+!x+Y8;zR^-(OplIXs%)d@Hwl zY~~Y4Nt;ytyH~~D*2T`oNJB^@)jei%TuU-t1DtFr7zzm8c}*HCO&H#`#ele_)Pt4V z97sG~eXj4ygCoTGIZG;sF;cNKM6g!s71^x&GF!!WuF5$y=eY2TYBH(P2h~Min4VUX znvOw;5*zZmpGcwUdr@cTa@zNIp@ODKiB)Xt(*S9M2!M=vbZ9v}Sj(zk99X+@NUZ|F z7$8BeSYGk*jB6ZlYBtQ^FBt11vMfDof)0@t3%FOF=Fp-b)O}#3+SiASo{e$pX?lL>9lmO`P+u`l&p(s0wSK* zgPj>5c$2Ci0_iZi<6>I!Q||OHdUlHjUIo$-C?0DWlvt!`7bqb) zRx<^eC#O2Nt_-}hS*tpn)SiFatnWw6w#KF*k?_&x2q4|X!P7IB_MsuqQ&r)j{0eXE ze$DKf+>~GZa|ZL2wn@9moH?%%{pifid~}38+Dd>wUWP?-5E<}24?7N$Bh49tc);C! zo4+x?4g5nJq${_D6m}gpkKYy#i;L)|*`^h>D5Zorp+STm6D53?`-G;90|1J7$Ukgh zEc=0_ALVIgF9^Gia&&&P3~JJw>-*`46FPf^la#0L4fX9>^FLY)_5=|a1v zxVuRs6_ku%2d$J()p|ygZC2Qz@I@cZaMK4&tp%?9CI{0FWlfo=A`iBpQFj7!znR0i z!fXkvRnC%{3Ifb@RngG|$IvKSU???uN+wCUG0Bs#8Lsnx_KWdW4Sss&nmdOZoc_b> za#H#|<+WRyO6f;?p;%zna!%mg%F+nM^~1B?nMFisLV+$NyaiGbvecx@7^R9_Bcsk( zdBn2-%7tw=X)B|?IuMeIu~ipH$NOe!&$OhUt;Y`NHnt|0(>#6E8)E-Lf0HK?_zrFD z3xPA0%A$X-lo(<7I;~PB+`J&{ihE%O*hlhjc*|sP>9au5o0P@r&a!X7O}~Q{TF#(R zNymzxOm%0`DV#eczq^S*3wRLpNbZLsmv>w>%f41fPZ%Nv{w*BX`Ngn=Oo^AH^;;XR z$T(-JssH!6jYw+17(&VcL*)6oy4Ln)UE0$+pUdTzsM)1|lRd<1T-o;lBe}9v&{06T z>zU8+>BFi*@K*%_g9?1aWnLmq>Lq?}F#P^)fT-()K-)1FzIa5A(e*vwxm+-vVkGH7$y|eg0|TPPTE}nF;My_rK`Y1zF^V zLGHl9rxiluI*2tVBbb@PZ^9mt)z50&&iQ%YPSJQ!;%U^K&wnp3-OV}K3gr}6MHSC_ z;p*vO(&oGoNA(A0`cL_*%LAN!3_uBauWSGpXMXY(RiIFe169odKX1)mrA?1MM#C9X zCsSh0cHMJUz@JY@10~U(o~hoj!wej+NUxo}H_)?_1CPuqQ{(6Nihl9N!%R*lofoA4 zS~vpj*7{$U&B8vxe)f+cnBNCk)C9}?9RPI{`wJxp^-v|>lAwHN$81lYT+~SQ!h5+0 zfw%(zC{+aVFQxRsa7k2IhjyeP@C7H~YsVJMGucIN)IRcB7zgF8m`Sf#o6G=QmULEG zD5T<*-5&%%$=x6pN+clS0i}tMeX~GujI~k#IT|jY+&vSID;XxqAXy%-=(qGMUo zXjuhdXC?TN(0W38N_%mxrJpuHznC#!W&n?BSi)w-`=t&#QG1LEMy04qS98h@YYmEM zNfQ5W6O23P3(I?M($t0ln(L!;{Yvc(7sKbW9;R4PD!}4n93@c z@=44wuad%8%9rX7ZTlDegQ3-=3c_QE8Dt!gzAY2e1!U^X^D<#+0s`zvg{xI(h2ypi zBo0eE?{AgS_a%>PKNA;R<-hbUxR9!_fcuz7+H1@O_Z8cK3v$sCG2ig|Xu|hDx3{^^` z6)B^Ojn)7_UtqNV<`mk#7Bf{<*a= z#78Xj^|X3EiUl_U?UJ5e;a*wad}fWIH`#RdT;ju(*7q)apM{-v{-OI`ju5>JTG)|J zwF*-QHS;dD;R_f&m0EuNK5QiPqXLL~Lu4$FDAVHU(NK&@yLB&UkHY6(?U&!* zA#|iH4Q6^%5tg>?Via=Df?3AUYF#5p@UlkYZBgXU4=P@aUlFmFc{taNpGAya=5qcA zi?7~3;%@9@+jxRhT2WK{JZM))u&8*A=_HGax#cBqT;BaYaqmQF9}7bSap~l`5YWh4 zuY9tTG)k07E7*#+;>%e0GXC&%Q4S;}_}@Fe@AzKF%E~MCapP)ES+A`y#R*AUN8rk= zA-GciQ2GJaFuPF5Op#!2ZSh2(C2q#R1G}CgkBo&?tLL0TN8BPX)5jbw>Ul)fBIgm| zydMTLJ^d(n5Dy6pU8))j8`lfX=@nUF5)XQ4#>drY!A1LFOhVg5$6smSCPzv-j4z1M zBWzsMNQQGP`ie*}?CsAF(U)mRZBgt4wV^kKDNDK0Tj)bO$M+50fdwZ~M~4eb?08Ij ztJ_29^f2cBuRJ0S5*&XVG`=V$`o|qRbmazs32x)d>%R0Hl{*puhvu&^ zS%-zFiUq|`euu@6)-BWuifY^_m^D-fv8d2VjTZIL4MtsRg?h=^y@m$jU{0Ks^9+$P zgdkC=dOgTZNt;`N2^7$+q<1B37M1j*r=(T-{`i?#dm*R%MV^Y|b|c2&5!}hZu^^B1 zW3p69yY7JnYE-xHdG)~IFt-(8s#IEMINAHGEB{6Pkl;4Sl^C(ZYN{-G05GQk>0-3j zqWKhr4VZ3JHTQetf{aE`RdZPEJ%~+Yjo4zrG6t3#;9b-�W+;8QnEvI;6nMR+DI zWx-i3P8|;6%KQDwidu#l6?Xw`_@ES-*w;=Z)P;w8IM^k>0#97bAg)8;Kb{v83AKt^ ze$RdCVMAhMOwv>;zSqQy7?#VFNu11ZRrdXIpm3>{WBW}>!bvmxns~sY$JvckdO)4QA1pCf5+|39VWh#&VoRlrjB)MQFL`r-VTEi#0y6?8ht)?g%f%?>OpSer8-V zgw_i!*i|&d+D-**FGt8(swD~S!vgrWwVvszM_Mc$-v!~3!pXsP+gj*?K}^AgH_^O7 z55EBwdH((&GrW1~SaIeg{Oo^Sx4vNQK}8b3Dn?~yJFQ<#J}9$uJhpx1OdN0m1VW`M z%YP4fP3v*7^1qhwqpvK8AO{=U+Wufg`1pF)m|a*=$2;Mab(ynTVg=L8>zu_NleiKR z@Vx8#I}0jFn+%}+_8Q46a) zN~N9g#wVf&leH0fahA|;ymQ@5a=SzgxLboopC-_8wZ_OoGY~LTI0%fH5$B9NhshI- z;&~bg(v3u~aQp}ky8xm5KpotSrO#2?E7$IdftQ3W`B^Z`Z|2Qgx+^_sCTLj*I47ns zYzcgIUg`h9AQBGm*z`kc>y5c>2IXDImR?vSUbOFcIYx@!0msM#03R+_spg6#Vx@$u zcD%zX1r3g{C8X*~pvud+4IB!6W0(>jt{If~NnTkgop~0>%ngulXhYeE78(n z?S!Pu2zAW4aQvTbXG0jhvz@Q+$qCVeN;U-7FX((I)&WqGvEFaM^)bnkA^zNg$6nB~ z4<<4!(BtKEX~DBp3YQM5`fsZ3xByDt4{+EX>c#C_U!Y1XndlZc!A^UBdf4-xSZoib z`jH)+3kR}KhjUS9{us-;)%diYT0Ez(5(iiLzzHxlG}o@c_PeR%8@8Lg`E2(;=DR-} zWL8|gHE%rJop-qSl`r={xVV~6p$s4dtH}?tLa8JAU>nn&OoXw(2Qq!XCs>4It>)^k zBP1c@;V0*ZD*m=^1wYw?9rd|%D7Z=jG)RbTG@MCU`f^uEbt1Z+`}uiH(JX#FuLKRw z5nP?}lS7DE?n_!nHm@n|6Q4q4cY{zUC-X(reUXiBeh00>`8P;jFU#s2C@EQHC2<_vtnCeFz!XQtZdIV)8)(^vSe_T@X6G#|=%#=~4xvQVOiM zMj9PH6njup;ifWWH!|7&h_U6s#kAbGO8y;_NSm$khqEy`BDH3|cU8rJ1?(8(-v5Kw zNt!pidjUiO;({((F=tSzD|u^kY#i(vS5?}e4XCDH*Kh6sK?y8Gs~JlDFovxIBpH^H z9HiN`()2v8CBONe`-9_rDH5I@FVPIR7rjzs5&#{n!VO&`j>Lt@p~XJ)RXtDTw;^rY zZPxO(R!&erdATT$A%mbqIVR)Uox1mC08+1ds?H&d?KM^ zXP;~7*+(Vz69_;kyK`och%NK?Y#*#Z&G>6EzKlHhx7VX%YO@yOs&!*XHCX%RQw1ZY zc7@*vjIG9AqrhXs6yRC`=Jvydfym|QxaP@dNc-wbY zT_J{A7jTIEz#pjIH1JL#E$rjAVr*#Hmr_GU6)yCLCM#Lo?|Y-@b#$Hob1KnsDfMgE zaJh%6iZBcql0k?^S@UHz$~^u7c@dzl`0(=pqW7nHzT;rhF-HJL?j$B@B8B8n307Mm zgQjH0`sX^Z8jaz9=1_aEh|5Om1j4mfA6fJhgik#yU(229{7*~_NS65DvsQd8s6$4J zCwx2L_@JOgcZ`@`it9i0BZ>}|a)Z;Ucni%JG2osGchPnFAaAn^)u2aunA;P;vS z*J}KiqXCE39*kSi6c~Y00XoN6%mM~;IOkKz?>Da}>sw`3U5_uaYWKOHs47gno!luW zF(Dtqd`$J4JID0K2l&$FLRdVv2`Y?xw9&6(y#Ef*Q!)h!x5cnSdpFGZ&|4p}PNC@f z6*o3(`=a_V9e){ii9 z$jQIe=R?9k0XS1J(tKKf7roROLR@K~M37mroAAo8@WRB^ z4f7L1(o7->Q@)C@?N~G$-BUEd}`AQfnlV<#&yN28sMe`1q(;Z@+WTz|OCoE5+ z1`1}IH%JIyBHfsOo}e0dxbHX^k?&cyWBAebqCKLF!5SpROd*E&w%DCqq4wPb4`Kh4 z(pSrjk(Ga0M|TP|$U{aTNf4W|yK-ClN+>Vs(z#x>(bl1efv_{(6_Pf~0g6KJC@mYz zuF^>9QWkbXL1CNXF~fX^-JgDEa0uJ6TZCvtVR0;YfGF2|n}EQnCTs=v4)&U8V_c8lp%BtBL(E zM|`E~pO1W0}yo7wr{Zl20BWNaZdA#_iX@j!9rJ-?&@8ExYRa!E*)_l_Kw%8|eJ8kr5M|z%#$7>42`bk<&Kr0AOX%F&Cy6ND zJy@BUStpR8OUAWwgf-}j@+dFP1d!C8!h1Lj-rn6q^Yn&U+RGaGP6YB#)8G4E62?(> zkNlnlP}Jeyl_WNWziI>I!(_MQhW&Ae^-uw(4-+KG{^(B0cd4DHSbz+s<%g+PsO=kg!ffU$plsH}el5LL+c3vOvIi4rU+kp27FUF-8vB!K`kr3aT3|SE+v46b zKL7_{Y~#2JFpBM+XYnaU;zklfHc7B}_BvFXME8ZA7XIn$NqYd;fhD%vS0-fgvEgO! zvQChDDO%B!Umtk2n0bFHJbjovYkhD5cNmyv$~eS!m3roV{wFM8Z}R>c;eQ=VVyl~Q zgYF;+qhxE>5(F-SL?G5ABr?+HtDUn2F~%PYRE%mG5Q{5Fn4BQBb0S${&1`W`%w(G% zVH|TcEL@g(Y=B2Y2iP!|4Y%{>7w2APzwSDZg)+{&U!q`oEGfRt-W(XS)?-L*nKjzF zGXJ#5bM5})+yvUE{1vke*eqYq&1AV{uR^QkF-e->JZ3o zhQJPsISt(qcq!QP&}ZYc_l##~VA%9JR&?P&)+`bBTfuwfh#Bog=Yr@(>)R0QS3496f_)oa11YvNLPa|QG^vwpWdhHsC`SZ*p?dA!~*So|aCSrA_ zC&JH|X@ieby0H%fuZ_nS;(;VKm*6i%)B*Rm20=xgh(f^7zznZ)Ty!H2;}8Kl%b z*vbw`Uqg}(?xNn;BIKehO`){7<_k{^-~w0u>E^-{kT-FfXtVW)yQe=XK%45Ua!wuo zFoyauQS8)8Ve)y&x&IF_-2|#J+UO5K4aN)nKyCTYQnX|4-Con#ZAKvi7;(Tr5L0u5bf*_hp(=K_6=;Z%`ZHEC05jblN(xKVSB_3JK?K%K%T>W~$awhIE$Hi{ z&ceSQ=6X0!^3=-;tFW=rKZ4WK4OEUx7=N)Q6~Z*qVTQPaLALRRcqVcV=NcXQ`cRG~ zm*JjXn4(7h#gX4Ilp)z?F!S^|D`3~i_fua&u=G#2Eah5yWJYKSz0E=bC8Yl}y`Vg_sv4%;$)X{s2k z^2jCHu^4~6=u91l@XqV#HZ;)b?L?(?5#TXV*S$!-m;fMp-~3YRn&9 zVzkw|xS;Gs z@Fj?U)H(W~fSgp*f_m~Y_~j_XG`OSRf%Gya?;l6QveUmYXnNyV&p$rfvljch=^eyM zc0!U>o8vU`9%8^!Li&2A0bgu2uZ0^fSJ?>y65F;S%9~zFV4S?ejrgyjV{C991 z*;*!_Ux39n5-eCP*|qSSr-z;bCgwbZz!-9r1Y8~8rl`?#acT}3qWtPe$70**#L5&ZUzJ-;Pm z8OhT>fez3rea^>?X3&Mj65%gUfe&6EMVu#F>G-OknduYz`&2S z%The>4_ePp=geh#MjfA&8;0|fi6Z~M)o?H8m(v?Cj}#q=`J$*-@kfLlV)9j^Qj(r!n#PRpth{WuxjSVSAM@twghkA zKlMFuCFX+HKNPv2*SDq7e~R^|GT+7R`yxx(F{{ZXB>zhs);on!FFyPJ#*d!h6&G6e zD1`sRfl@)7)s6DTm6bnZNxVOhG|Io$;`=#_`lU%>@8hSXM`%Pn!qZR7XEjE*Z93^6 zNz5jLjs72zFIPZX7C0|q?FfJHFjwKn~)Skn8 zMQ>%{gacRs>ezyPXB`5 zz@eNSYjHVejHd>aG8(Spmm~ZgcYUSMmQTE*fRZtIsN}DF+^9ui8RPGv2OS>(Yekr> z1vK7hfC}OP6Rb?{9Z>kf)sym}B~}OhwLIuS3yMk<20FdM1mdG@V_%PxJI zx!7vm5RcyntM$cmI#mJ@xHI}ehHNGRRoK+Z)js}ds|(H$D$8)hMh(rWm)B3OG@XvE zfiy^wYCz&myCaz)LEG{2kg-BL6`YpS1S2ab&KWgFGTmUi!RaRFRiHOf2uO&oSSwYo z!o`3?40FSjiI}xOq@jz;08GOUens)ZLTr!D$P~`hB~aH#N01?-RFEDu|8We8Xa+Zw zUZ#xsVqHrHtDU;Xf2O!g!;)p^sKowz0FbdmPfv9f_lcFv?b{26u~bvN)+!6Xr9IQ( zD`!Fsivi+Ve0hyN5EsJRM?s9FOS-yonh3++-hHohRI~_VtfCFew7&KfMrrh?pO?4?D#9G-`%|`q{*pt& zP|dcv&o9)Rs7Y616o&p@CeX<-fpECJk7?|eNm)u!t6 zj|iMbX0hcOaA3`F?kCR8TY^Q;cXN2aC3pWS`^NbqY(-L}V|9+Cdp)Wvqfg{XD^xD2 z?b->D?8+_)4HbS*GxSN7R~?GJXur6v>H)0-aH`<>D)(!4n;!}jQd5k`BL?hMA7nj- zxorG#eh@Lf9AnbgZPxg<0dL^u?)hGSHox4lGp%gkhJ)rcNnytRvbnDBd($lFd-`|j z;a8AT608X^42X%DVTjIFke-JSg%IM*?b;oW zhkYBs`xkl0*)sZ+XdiWUzttvwbdlcq4E*i<<8f#L=f$h@H*=t$j6rG2ZG%Zq0!NR7 zu@w2Iziw@$l{VH{4o}SqRNl&$KC8WlPgg3DpQU9l*W#A_vl9FvE-7Cg^!fh=;)@W3 zX6sL^61Kb&%@Td6PuOaPtbw8V_YKKXJHnjB((Za6NXYZLOW3ATT|b=p1HhVzT4I>f)!BdaT=EXiQHBIhi(zK9RT^r#gQbp;mHO33Y36=*Pj$kGlGsS}1F zTCpq4_|RF_Oue}dL#t>bx+eMURt;^5;Bv8jK6Rf16+fa2{Pk~g>F5OhsoT4rXxGM>NHcTpIamy&k&XtAn{31p2#c`yJgAPhtLPWJql8+0j2AaDt zaOC`$)|?5bE%$?dY(If@c7^Kg>Sv7v3yKp2Irc zE1mXM-rRhFfrPL9^33elb9zS3btqkf5O?Zl8(<;J=C21#v25hODVKvnK@~@G#X%PC zc6i)JUM>*;o7Q#jv5j8kCb$Fe`&%2-F?jq+H2iOk(sKl$_SMMJXK_vK4qf^G0r)@% zzkUOqr_>z)PH6BDc<1w{UyGj_hY1fk)9B^RCJKNFLA=*968@V40b2mUE&RyIhnjc? zfWBTHv|?olb6*_Cm#X$}ucqzApXcq|g>|%yW^oh`-!uD&6I6))3O=o}_T8V2+Jz-)95TV8vH0Y^dHdM$dHdp*AFwa{-h(zZga10f^2Ozf zy>V^{A5ok3cmFhIKYpE$COZI84?YGEH61m3op2FM6Z}`e&-F)FGLH>oTa98yBYW(T zPR5VWNnEe*rpYmHx6G#VFc$f}2ZT^uSy{0wm#*;pSi!t|3O{X=Xxk2XbYFY^V+i+? zIV>J`Lqk8$yUT&t$GfeiSH^qKfG82DSAFYs-z~`>_JGaw4(fP}6HfPaOjFT) zAnFbod=F-ieXC=4{H=hfohF-|((XZid^AbYVlVtkgulK7^o8^K8eqgKfXR1 z>LshOIIfn5F}pa)VtUL5S_t|`B;Toi!oF*tu#caeu+MyA!an_U!9MdT%mwxfjFIp| z@Wo8`Qc^;l-?=AQ9~QwklNR{2)9d-NAPV?-}-vWE?hyty@BanksaLDR}-H$2y}AF48F91|Cgdo zTA5=LK!VjdQM*K;;t`19D?k3a*pq%32j4?^eB1ycWpVCJGJpz#F^hN!wfOM`Xd1?M z-UtqmwPP3BKWIW7I)v5+rbF5R%Yi6>m^5IN2K}=x!H-#DDBu=KMFwdF9 zKNZ8l4(yfL9lmLfV=i?9UeF%#NV}3{;F}z))2uM`)Y;xbh~p^1GxWM(kq|U`A{UgZ ze_^bKQ4;Qj=k-J=QF&qsu!r#>Fv{OO-W_Q~Nn0!6*`D$cT%6&iv*4TmbPP7)Vw-@ySn`{8i~$y~mgU3JjJnCB4@p zfL1bh4W@`RQrd3b&tXhQ9{TJ_TSb#hAlpp1-hDixRP}>^z9xVVEhdfkI3+D60`pZ9 zA50CjUBUR!QZ)PZYi;|*FU;P;q516W96NK?(MXzR$Gj0+EG_cey9g~Hz-bU*A<;75 z_8%%HCe62AE``-EfgN3DC(1*1Wb%+b_OXmT@nqdjpUSgaB|8~T;hPK1sT?u*WJ>`^ zEZF6X_=N*}&Z7DF>aPau@BU@Le)1NbSHtwUxnf6#*X-zc(LVF}`|ZNS1QD%$BJ`lAV?tL)w#6I3FwZ3*_t)p4V zHK^}UBT93aKG5j*LGiigp0jU!;~Tg$ShoN9KmJGi_kZyh%%OZt)0ZcO?iVz9*ZpM= zcRvz;`#{uPbaVH>?mkyhE)4k!DHPlXqV9sh_t+z`k9F*hcML?uNv6AfJEe8s@1Nfz z9H8%gb*G;vg|P6`7u@wV%(IBIKSCqw$3MLZh-$PZ0Yhq5M!xw$>9GBvcEtYhv&S&W zJH{?P1$-Xilz2h{kldfEWC_dqY8)1yzP#)mC*40@BB%Gh((Weomb;5GBAvZiWBN{{ z1un)rT0Bcj0Uk)Z0?Lk%ua{y25)@#Rv<0-2TNZ&Q&kdQEcyOXr2UqlmzGljIhfC1P;sUEcD1;RM zQXP7PB|m+l3_9X?xC$VFSz5VV0kpt*G{Vlzz6pR9v>-68X%kZjXr`zlJjhRzeDz2h zK!O@KTsTTH#C$p?tPw7ukFEaIm1L1!2PCNxQNqJ)1wT#fMmNuv^Gl03@+}rI1*#&T z;shM6o$AJt#|madW#qdS;8dQm)xw0Vh*?VsXUX-3ww=ce4Su;=IrZu5e+!NlnI80`l&Pns9 z09cd9L@rC8iYm5 z(r+yO~!Epl91UbCg* zvMsD)8nrfpV`;Qo;E~2w1^_gL4=XuHPZLj~;duH!g!%mg_@~L+G-gmU_@J3&r?UXW zA;eQH7?lHO0@_^52tN7|`USEn1c*Xs5a=PKZ@c z`0Q57_Oq=vcG8pi*{_poI<+Od4SZ6n&#D|_$`*foV(^x#HKHQ`Q*MSx{)M?Ed+Uvh zfS{WIQAYrx_LE2NG*JwKDSF2>F1k$`m8$pMhp|pWRzM{HD2A+jQ0ZOQ@GWD?r(NI# zOi80^vx4*UYRy4t0Vx%*;8h&vFV5qyY~I{K{v2D5&MnSEmo~@15Y_<~c$)%vMNhV!akQxFfHF1tkD2wdo?=DSLE2)!6ThzW3FSEwHxU2WT*Hlm^^J1sZ z=U#zOfJYuQJ}4Lf&H*pVSzN$e_C}W9i3amumGg#OzLvMk*X76Vnq8T{W+nVHnjNM> zjYyTHzEnR^vzV`b1vK)QW5Qwwk^3hqyvu8tT;jL!*giXUeAEt~LZk7pfb$G|$l8^Q zSMAcJYnc6_^@wxw*M3v5zxxNX=l`{0H&!8_GSBZ)(peQBBN&>!_7)@}=7<8-K8mtQO81wZ`LVX}Aa^{13jC~xB zK1tF4I{{I{n4XM|jqbc_UKlc4jOe}Iy3;?q=QzO6QV$TN<(;i4cP=nWPGu#q zNZ^t$7n#ur@EBnGw2Xi#Y4uRPPu={H=9SBs$R;kUXa%o@h-*V34f;({t6p)#7eCi^ zm95#!JYLh&Yfr7{T%Afrp82pAC%ld!2MQ%}hD za|w41Vx2`z1MkW5gHq$>2HH)Vr6#*}wLQ))Ac)QaMkPR0QRXX{)0OMQjRh-L=dA*G zQb#aN;Y@r4Q=S2i>~1zb43pFhqAd5Mh}9d^T!EqDN0PNS%Wbd2_zGF# z^ExW{y=}+tl#nBspDC}13j}tT(_5CFQcy{~fhM{(RD8zoZ@cJyVvEL`@7yjW&W=KU zZe2lunL;_DH{`rIzwW7|kUyL`V8Mvg9YznwKRXm zxHgN4?I81#0C}_s>COhAa}|F{75r6|0nbVxT>^y!a;-Bjl!%THIpVFFxdsf%U}823 zm@-(H!HM?_8mSpOh(mqf$q`WX2cIk4#zW3dxz3|gjezVTobAcJ#m@`^p!G?N9zBZ!^e{;gV_tKzUs_;btO{w2`jNSIW zIAWiCB4p`ab5@Q8J$5o%o27MpPe&y0dZ72cqtbU!B}>qKn6P zqkBSAnt-T{jSYMD*=HRUU0q$ZuYdjP_SLU_wS%_$@1a&CS_34Zx15;XKfd=I=X}3Dc`LcEb^Xl1VzFNUC z?Txm*`R0cGKmYZd{qNs=6M=si?U^C_^rL(2OTTl#9(!a26NB;+x*%gNlXBZxA0 z%I3@MzLZH~mVj7|e*u0DM{(Wh5M{b4D4#kq2(UqmO=dkUY8gvOo9^wLAWAi7>KzSq-<(f*G`8YD(Wrl0W3&4i(GX)ykNpvOr~36G|Dr{^g zN8lxPdtJu~`YIZh^Oyl@lZ61zYywtSY!I!f2D|muFg2XW*KGtR;Dub1IYJ<{p~;IT z6~NO_7JoVTMH`+Pw&BTPKw4=#0!pJfC9_+Z@C}1y=lNOF+E&1m{4dD_aDew}fH@-o zqTO?E-~)r3F_Zw!fy03HXbbUsTB`vl%cNFwCR$=efaMiF46R@;e-8gkiVF)x2Y*&@ z6hB`p*apB{=xB(*mzSj>A_jH|%+clvXc`+T04UdN|MWFGd}z%+@%TymG{b$;JR)a^KVZ{O?g=iN}M{P7tF z&F=z;(mbk77y71oyWzOzrzTwQhdbs#9H{Xa3+SEDqDEA-6TKx6rLR$4p|_l_Tm94b zm;=3i-2EdZ)y;VprrJ?KK-4I^D2$Gd+W5ryjyo!BBYk_9Z@bmMxYszK#jrX|%RvPR z8vs$#h)RH{S+t>U{OBjv#Fs~AWrM}>pe@y>ZK*bD3-yfMVA1?K!trbP0{N?Fo&bn? zJOQHW?35)zJP1|6dxE0p? z+ivV|;oH&U7sMCMd`WHq9F(w{xOTZ_|HuD%-u~17_ZFYehq2BWvWHGgu~46}PvA@A zsi*RG;y6HwJe&hSHCsg@UzlUybFs9248bLZK;}-W!^djUxJE_AcicmpYJ2Eqgn%dn zUR0Rm%(%2(XXmRLLZ18q0JN|*+n&h@fByp*L_TQ=xPngNs92gcs3FMwO~JJi5C-c2 zNlQy@ghYf&Ozl<>EEmysnrD}~CC1S@A1~Hc*_{qwREub0Z8*XLAf%seXBf1pjQ}or zOmK$K+~GSqHJ}m37?n2I*a*93O`r`mJc2Me;Tl}k+A3gF6?2>kBJ&jv!$;9*8bLrD zK`=aVENzcIf)jT9IC-G1Hl{j8Y$6CZ0lwttC?_Ej@TCb~L{1LyFH4Le&CXjX{L%#f zK!OG$Xrw;V6B0gy$xtv2qpw`#QW?6xQ&0{}j)*PlmAO$14Jqw**Ti8oQ?dKQ+AOnk z8L?7kJRzK4yWF-*2#psm;^*h`RlCd%X!GTQ&9g%wTU)}i4FJ3S2*Sr zlMLkQ%uPJ6yxl=%DBg6VJJVgAYj)K55kMhox5nF6aeB`b1^H;+7JUMXcFNoRl*XuX z>Tid8ex}kE7Z&Z}TLFkVcKjqetsP=~Q#Mh27d6f^{&@SH0iZ`N zoNipXW;f>Rc71Ko=9mXIxZl!82>Fr9%urtBxoRX`g)%2uYl&|Zzp*1Dv-XwGJ#1h8 z{KIHfEn|JX%sW3~Cr;vH3oTuy9Cp!LwZHkVZ`e2gg&nralYrkih|A(IJu_*aJCn8F z`-<5kkEiVTaXDXa+kgAJhJE|{Rl9WK3OguXw$FX?I6%}1fT$sU-}ta0jVNAVnFBX9 z&oC17VWnec4u!61CYC_5LKxxjQEfdO5SjBm29dN2#-($tpeVF!e#HY{#PL5weOX`<6m;K9U9<#4~?Qwem)4aon z*>2l`CB@JJ&H=d8XS_NC=Lw2;&qy{CtJuj6f{#~9P%(HF<@!t;U9xlNnQU@{2v z87nQN?Z%~s{q5hMx4-?T3$_IIGE26P9o%n^o;_-xerm$L@TI(+xgWtq@1-0CmzS(j zS?ZLW!jU$%R4gXQ1280Wl~iJb=Ae}CbVj-eN`mSKVj+zcekbT0O(Qf26xWcm6m{TEB~( zJjsK~7or|WLTnpJ9RXSSV`VYlZI9xF=1Vbp=ZD3y_z%jxG#%slPQ{B#%|JS;tHNjv z*Rcf)XwqH41WVeGCr+Khf6(DhQM`tLy!=sh$pi7ZKtU%fCqhtq@2XuPE&L5*zVnpk zFQ-by^AG0AF}piw=bhBJD+7d0dAOF>zEtPU2Eg;y=}|OCFbij%$J*X@p8tl z-Kg0zrt^!-Wm_m8Wf#z+Fq5&QuLhb|1nT=hr+@gcVa>}noLRE72WRZW(HTsPie^f&0J1g&S>ZX%E5Ootvc9)<5sSuCx zson{#4@5=Id~lDkkK<84QaaZpwJRVh{_ywyHpTQ0E^9tAl>0)^g@)K^EP`1Sb^}pM zKX}fTzWys$iCpO>FQ)HwPeNXIF~Qf5z^EX>*Q*Fk z^Ejiu+_HcEmkajK-@9PvFsFKbrE15fj@Tn7&e-pKcG~{vnY=ytD1rl(Xs5d7(wsGx zaQYJij-ylf`@m6Dk|Kdc$VmV*0%W3lTNDX|O3T5oz^I;3#^Zbmpho zwaCHx41R&6O>_<4E!S`)yowX?RWuP+07RC_w}9X?zp`XYAX8YvxVfJDt>XOF0U9zO zM3~0JkWH0sj95SmX%L||hu8C_^0v;n=^G9yd^8$h|{j##0w9q;I<@#p>JgE91X_zBeA5dA)hK2L_5p=5zh zfQ0U(81p{A#kFgfNpctKJ3;*~0g(4g8f(&ikOySi88oTnM=EHAh#~=1n=rGANshq0 zDnp2k3~dEx_j6ZT_R`Pm_TnpbySTPwmr4MX+H%l?sHJRt;Ed!;IBMRou?*U*#DfRq zoY?Hx(MdaTe6Pt*%!$)kz&v;c@FSq91OQnsHf_1IfCk$<_a^WuvmfmaByOa~PV-@n zp3$(De<+%iFfvfl`&a(4oR7)}Z^ZYs3gdqVa}v;@`;t<-#tv7`dmVQhRF?}*J3OF! zsw$MLjQm%B5!`t`b<3nsV1X1!G#BdJwSz)7=R?fv59&`>+q5}>XH`YXGo5_5J<)UO z%P?Q;lvQ*~UrM1@IQPUI{wTMgAF(w8sydJ5=n)5^-nfX6QODHkK09>eNZ<$U&%zJw z7OA#$#(*B$A*i`@_Z-(SwO(@!20Q8!#1KcQTAn5&a&7wf3S4X}9%=V@MY^Ry4riS(;Cc$V<9Z1>!BWc&b zJO}_j!NvzEOaQfurc8zPO`*UvC_qa9xI&f_nMLaugSSVm(mO}hb%3cF7uVQ@@bzEI z+u{Von$p|v1s7Wv_vv_D%-zcrYywO_af&ytzDqpebLdCxF*#q{c z&z!V}9z;80n$ZFYH`s;rjW?S1U;d_LfAhRXlYZ0j#)pR3X@I3qK9ohPD$6DYY5Vz0 z4g1B*6?^U68}{avHvpo}+LwO!e)}Yvz8`-CpL=MM>75V#L^0b!=r<7=W{fb9^jDnd z9#%T3mYvHFKray6w9*?_iTd&;q+X7Llx3|pQ($dfO&T$})gLvF+$uWN~5G51Y zEKV+^5w#C9efb0Kgyfy-15q80?E0h+MD3bY+cU<28jtaA@8r`5q9SKLxX0MX@z@8V zKDd2(x0Jg8;Hx?P+9j9#oM%4P%8&+Lfu}Xc?s=52EWK$iDsF%@*dKI4%fA!~& z*gt+NN*i6eJ9d; z7t30#JJ29AD};v9GG-L7Z`hUJlmWbU+&%YFq#G2c4y!XwnT5@ zKWb~scZsb4CTL4(H>*0}MiGqwnNzF-KnR4;SN5f)b++WKqFF<|fD=On`DIC?L9l6S zI5DqQh5<*0G0_CHKzl+yp4K+lWe?giEeH zY~#yGexPz`#BH=5+GtO-0qNS%?q)Fo(}S+i$r6;Ku-xf(PPT+>rG`8HS5lKS&orD7 zcm-T|Uj0E*6BwmI?b=W}p>U1!@BlsIfCSG;btuvPkkqNi<%`Q>1C2SNOpxU3X5mK3 zW-qU?dsdykfdBHXRiqErYIgNn$}Y_#oC8v>6Z2?u$z(}NaeCKAhgt}}H9L5)ZTpaX z_wAWrk%^CU;^ZWLanK->-={s(^5YghK*;Q_wu1i$eC;e$S8SoOg3vgIX2f2!I{=Uc zqB)EqW>OJ?a9bZQ01jK!pRkKI`>dkIcY;{q>~KD496Ga<)$fEuQihn)C8g?~-}juI zlAL!M%PpdI*pk4kvEC#)rQ(Hma(Jfmq)$4cQTYXQ@T?QZF{#M=j zTq}6nsFN}vCxq^2oC7hzYbQ_4nB@2Cw+Eu)(=^dbjZfd|81mCs{0nn&0ByQ!Uzl68 zb8iTUYS^hWXK+@2lz!j|G6{onjVLPUex|oRwN3>2vG?X}uVa4%8p8k(tr`d_5UowX zR&8p~mSZ}io5JBFF2jd2Y2FF!4DA%z%(s9mO?>DzTbM-Gf%kaNP~2pG1JK1hy2|_| zfU3s)wMndi_Eu_}wz`r9XdlMJZ@}lj4Kz1b@L{*iODRxHW2=gG;tHE9)UjQIGH9ee z>X*szAimWG0jA~Hoaqo#y`T*>F%~vS&`z70*s}Qn8)p-UJ&No?DU&ss?kN=HhiWWi zBZJJHXmaNC?LhAs^PAeK{%|at{L%))suDA}3O=J2Y-wTLF1;0JXKK3yjyaO_=VTwJsP_>tT^@jZlFzWLkzu&(2IRR0_?3|ak zDFNSVB-P$LmbOyV`|*mb4n%3ZcL$|!3-N(%i68unxJHl1-L|M#ZtDY4yXD-yoiC1q zc-$?uF@G-*rS!f=)NZ-B`+R*MYWKX_mNO32c#JoDC$u{SqEuciBOYVf{p0(?f!N3K z*axECpMH2hYt_0f2+V%wr0D(Z)`*HeqAC~XtagJP)z}@cnmJ^}_MVQ9sMj{w4UYKN zXhZ!E|I=f3`os|1yvuQ`1c@e#NG){b<3}JxSb%B~83jMD`2GIVv#O1B_L3FTb?gmV zC~q$&7{oNO_o{;sEdeh4`UQ5U`o*HHU#nR8M#Wy3t=jVdQDdV=?fCw)_|%xPKmAj- zx_(SMzQH$kv8uiDYpeb8*S3!BNeQ88=)|<``Pd;V9NcH=aeRRcjt0mJ!BN6h1yhub z3J!ho(v~UAoPAmAOFIy3zw4ENH zY(Sl62|1=@_0&FuBBHB{fSAaZP3Is!1E4|U1wf+=Kp9#%nE~2>xk>@p65~Efk%ISx+&jF?U1%V}~-=WHp?*LFE3mH@0V>3l^HlQZxPAdWyTOCwOF z5fIZjg~w+T_Bcpn_+2SCtO-cfVrMxCcZ&K74|d|^xUUxI*xpx8nvc)u(<$a~C+7I# zGJK+?5HLZ!$SmnlQKiI^#O&nSlhj_(hPD#|s>CS)0TTQav^D%D{k4fxV!G8T_`q32 z^K22Vw6}geZ*TmPE!8hq(L}@XI2vn}2Jas}pBn65rMM@{R_lOtWAa@ir^%{_<1StfQ#LmF$ut#kdm?iBFdW5Kc6)!a>2!v4D z4#A63Ug`4$-YKbBmvd+N;h{aWsfl`4-PN~tqEt+xDkEQxlv4df}^ei zMYo}Z9Jdd#o=E5R-0^N~|Mt6q2ck`g=Q|mkTNJ3HXkZ}pgn59dH($TxK-B3oXYI(b zV<88RXt?UB+XeA48P>PUwu^fjKlGCC9x2V65S%w|8wx=I1*Ad|N9+krK>r5gv(YMW z9A=CI3~4;j%T30IqCn#|`C5RHZTZxrOlbzJ;@9r#MZlCB@@2=nxCTIvHq{auRAH#}_nBbbUc>{p$!a0EIb7}j{ zn+^NTTXnRi*dc2%ZOiZez4O$aDiz$@kGd;X3f#SE4C+RA2;_99d??Q2 z8a*C&+o)bys}Dr&mUH)ZzBmrzaktdQ{JlVwp3lEWKB6KGy<>B?ZTKMN>jP1D*;{dt z#A7U`chCrk>hGEtx%0t1#y*b6J`nZ6?8o1RYOUKM5Ea&NEOwD5x`C*<=YMST#Ffj- zwvP7B#>OB!4$WYqH-^bV-fj@zYUJ!Sb~O7R|Kelz*Z=*4cIx<`P2(4%Fd%_T&YmT1 zvQ_*?4u}GP2c!vK=P`Mj+pyofv}))6b;*ivU9q+ESM7zxy!~J;2Z(dP4ow`kPd+$h zzyIYCd-$ONc4`BRVHdd4&tA6j&tJiBPo165&>Xt&s7*e0#s&}UxAe$38|M{lP39*E zA!}^=y^2X!35}+8v}fe-S2$4{M}2j}Q%;xLZY6=zU!+DqJjAP9>?2(1dk2#p7i zrQF&0%rt(qrbhua@tY;Ej{b5-_V7%mqplSJ?|hIj76jtWtrTr;dCkV~!L|R$6xwF; z?ItlEDcBw62$VuFm*xqQV_Ri<&H5uC!Dp6EN<0bRj2N#Rnj4f7QYnl}(m8lnCl9H= z9N^GIMU{PCr7KSu zuUn;Wm8~;98QQ2e1KVxC%~eMuY6Fd^vuEtc(PJG-MRBD1rU#P*zyEfbdLHi19=V}3 z?<2G)rA-<`;D>k;S{wRNe2Py7UWgOgS=8rTev_I2w$fzE(_{hIq0e;`KU9A3$rf8! z=KWg+pkD@rTIc;#jJtk%T@Y9Xm|Eq25ua@9Wi*kBRr2Gj4S#JF`I%yU+@jtVKv<2r z0|hF^C3Ue|Wevc$1zo^N_^%tay&ya@%z@LGKxZ+j6-|SKP3F-SyA|V$ig~qwy5k^o z>fjJ_s(ewgd*{SN#(}Ca`J&SA1VxG)a`L{4*|dDgEnq^u$oz8cD&X2>9MUh>&}=Oe znQt}2*5Tbhvao! zzIynJ!z0>cyk0{mGJ2rRQh7VG{J`i=6y%h&)JjP-)Xu1bZ)QEca z*=Ow=-}nZOQdjNkU;ny&^=n_{HwoK*c`Xd<0v459zYg7H#IpOx_lEFn*F$g8bcZ7YYw z8?~zw905uMN`#>`zNDXfb<-~Va@B79;zhgui zcH0OJdeitD$soMpQUI+J9zsG;4{O`kWJ4j(t2WTZT8%2#a z{SIV7neYjmS2>g(qCXyh#;uX4jH*EDfy+4;8s z=sbUE*+v1PW=;Y`jmp1_gg<%^phsqUGKW*YhOwju$KZ_emdBKM>}F3)(^35)j6mJh zTb`B@5j4ay3tG2IQFrS)t8ql!q7ksgx3h=NY=iZPz;Nwa2xG!P=NQ07PDmFhp|Po; z@(4G*+5}P*ZrG=(z?@?H+pXhB?&lE4C!i{0AJCmy7a7S z(S7AtTjWzImb%3wk_e(z<>|OH5VeR#)LU-`A5o|95hc?+l@g;D^A7*<_mDE3p9#yA zrW9!>b@zj=M12^A;Y$2a>qGF-$$bqH@e{L6J)_&ar_M14Qv;s^KiF`9-y~ohGKq(9 zl*tUNA5%UeMQO}Qa}mp90y!v4;J)I*Qo}A?so^NRf{(3bb{;J9e&fpupL@;59^xbp z*4a%CZK)0B;U*svw5h`lc~-{^5L;s+bwgZE?1>hNK9@Iw=64* z)!o3?+?DGYyRwKu9`qDNOXMRjn>0ehhlh1Qu9i)VO_%`fN6%*MVNCFT{KASo`_i&q zW4FFq6MJ7~D77I=-4g)hIRLdACF~&C4fV|4x;=8LVW0W<9{b$WGj@!RRD*nYK#>!^ zhraVZR|kdH$6C+p&Pbgngi zlL0OHOmPJp)hm~-@FA*VQ&UrzZBOE0f5>C-ffxEm^~JK{akn(|^S$#Nh~pq0cUwcu zzY`FZl|~dm)LuC&@B4__ElY2kuMb4smOZz=83$@S#+;gbx+kDJ0isk!EU&waSa$#T z{%|1niE7t*ABcK?`r-YoRm%)5=5*8|UqQ?CHj9$U_4wfz0(?b?+!fQ}~M z#VBgL2hgV&w|Pvz<}p{AWmmHs1LO9!KRIE4{_juPu_Krbu}e^%MX472T5`&)#~1ub zeOg@JYYWG%WtWqjaD?-&;5_46N3}sAKId%;N#QR7eo9}$$)T_El~M}7KYXD+U$LwI z`m$Yq<(KyC#VPyN+%$y^vn$h(on~jVj~ySgBL~ndLc?Vc)2ZUQ*FDM%PUa+qBS&rM z^jXWu^DUu@S>)_$nyt#ywgkwr#8>>qb+l{BeBqX4FFOaBVq~!2>Np68YWEX@)D;6l z5C&qBitNY`AOt(n$xKc=9Zk@mlVg}XffmR*P4bh>p%MuX&=G$jm}N{NWQ<`NHtwdG z(2x0u&->C;aZUwp!H#VVlrSGOR+x)KF1OPRPRSw~MH;8bS&SLo=?X5ea_zrS+ta&c zS%DnBi(68!%I$Pud@PX0d`Loa?zhOR{4rTVvgj8Wqr5Eoodp3-;wja8 zj8BX2!Ne}4i{HH=jjBdQ>KaLK-%)7(i2)8mb%3Y<=ui?lsm!DI6z4k>oRoL-0UmgM zJrhQ50C{vB%L(a8kMtA~>ki2QtP0>s%ou=@Eg&kCALh~oR-tBHi;_@Ys4(R z+Qhu^Zlrc`ehEk37r{qrcH-1&oRuH;v7wT072>n;e(!Zm4>WS63|*Pjw>}S$7Wm1v zznEP2baZ@F<2Q_90dwldSfGyLS2xepW@-NEUUz>80tvv}7C;%ttd8NlLqe>=%b_Q@ z);ETgHM48HyYma|!iNT7ah2UB(R8e$o!SPVX%Wk8P_Zt*ZfA$;EzqmZ3$CqY`Ar9S!VG(E*6jS7DZ6k9Fb!?4D`jbw2F);W zSMKnv#cx4<6;?3D@}q26Fl?VXW%kJZnCM+#gN;jNn_U~i9B~|G@M9omF>e_fo2K1F zh1{`@IJu{2_a80Vr=I|bdg`E^Jc&8+6h7^S=_jFnOp+;m)lk$p1_Tob)zpNY^n=a> z6UMRV@08z;P*##tB#`&R81z2$z7ucP&iF3H<8KQ@#d6-R-v0e}p96O@9^&}9EfBS@ zziZw*)q8y)>Ml7M2WmXVVl)B8Nl5p0Yntc3+p&=T@t)#9cOUCqQ9o3gr24z&-BVrl zt`Vd4wS-kI)VBjsn0T!gS-7HA^MfDSGV%JQ1$+vX(bkx@+}HzFOYgP$^$lCZlw)OR z!d40s_Gf=~!v5^fPv9gO5Cx%FJD*87@X*#mljti&UrN5eKvdU?RaAC|-s|3b@qR2q z*S%@}jCNIP0rUuvVh(K}bW|{B5HNA&!jfG%zhwXI`)T{nFH#cb8X26}?#Btp%pjUX zXc*gC{ zoe6*Ab*QVWMBPY&N{bcfsjgg3KTfS zl^^Qb;_ns!7|U`xxDd$N8FPMO>tIS6=Ozi8;JSO+lskX|gIlvgR8;#Ldhm1|J3+KM!O@JfH zAx{;zCP1@%@sqP|ZM1XmF^aOQ-fU0D0irge?=NR+(@k8(@uGiyHP3p{f zJ?)Em;{ABMTOcYvACEoN^)KHC4#Yl=N0D&5{)zc?>;kE$yctaMM&uAK2EAN_ z{;qj}4|npn4@BJwx4QCn57w?^AK-D2D^DMY>gLV|^E~!-q+UN#eIP1w`bCt%TF+x#F5F$sfkVL2FJP zv}gX^A^UfKa@h9bQ$m_BIlj(@g};sxT7^D{w~5e{{KzTgJr8l^O2v_kc)T4g$`kWN zkxADQZ#sblr3r*eCqR_$>6u9Fi$Q70 z7j2ox&49E_;UxFqRMYm(w9txbv&$MF6Eev#!cPlqIz(O&i{T2|If@dd>Xa*TvIt-TN>on++VYeKMk7KgMLBe~ z#d)f95Jo^uZxE>Jy*ZQHhO+qP}nPRDk~>DX3xY@2`fH^#X;m+O9wdS=b4Srrb4WQPsMYRcOF7wh=r zq%RiFB%+#xqRIUNG`_69sMu^(AM>A-2C#2ka-I!$ZUgy`OWao0?Es zK7aBMwr|ihIZA6LAH1A@Pu;M(g>1P$74c8Y=-N}E6C!}%O;YZ{xae6ySoxYSZSVQ> zhmxs7OiNg+z0`N}gloo$hv#4D#^8U-oNeD4kyU?WMnvS<*YO;l9H@Kkxe&$tMxkDi zO0fEBz$nt$97LxqJ`lWagUyEp(tC8>-CgO+tPtT$h_X+cB3M0AQp!D7yRrSy($;oo z$>Z+tZ%mQ6=r>{)Mx^sjbV7SAvf(RXy7J3J95jp2kV+=_nGT9HGbS9fu_~~|m4>Kz zE3kw;z{FlqwnxakfYcniDtd~AnL-(Hz~U&a_^CkQ^wRvg0n4bXpr7&At(CC@L6mZ~ zfpS^6GjmQic}6oZ*m*=5M_H^VQg{$YI2U`T-48+CsJGug@*}wwd0NaJM;JmiXyir> z`h2$bzwMz66dp75S1rR5WdPO3pIWs!*IHo|y1)rP?!QVC)U`$@X)DE+!kd&Z zb0WN)L*^jwfD-tIcQT&Zcm>#(c;6gbQztBoqgDEUII-Kx$3<0bSrDo?j5S@al|?gY zZOJWWB=xD_)$+NbirXAa<}%B)vkOtm$H;%juF(Y)|7kS>rRU{owyQ*}T;58MU!o}B zHmOJ~u(K(*6xq&Wm$6l^H4J3=sb>yM@d}(Mfv32EXG$;o5+h3Ecu3kTbn8u%>KUR| zh0go zzMuoab5NyEeZr1i^aBowk<=KZsFYM$nBdRf==93NNligNYcMu`8coMmZpZbQIL%gZ z;cPaZu33Z6`xH9H;P186_mGA(6*jkE*v@Le=?)4F1*|QlT=eC0sJlZVbl@66De7J^ z;&QlLQ(h^cL>MFI{0*&JI?pM6PSaS*9vs@wtu3G_yoPhE{dA;b_g>*pxAFasTTq!3 zD8=QTo$^v)_hbDmv&i(xx#&8w44wMe6E--mo}0(@j8Pn3k=8xu8VOwulCBf0?FTK} zC9YKAbtY)BM2)LR(#3O0#D=%z0Fq({%6#!I7ZP>?j#I71-J$`K4P_?|bgIqPwghF3 zf+z0>_B+NGJeMvu*D+W}+L`kZo)gp*C6PVKS@2ax#gea@IM9Y~Y=)FL!M|Y*m<^eHsmQb}p zn9mr340le11A~IP`$rbr5Trd!Zt!6<{5Vlqs}4~cs;KQ+pf?VpjO9YW#Dyb9Oh5r| z(!|UP{1Oqh&o7I2=p*Cb(GpU~IxpU_GdZKeVoALW)O;{o4!@6M%>O-(_ks{t$JQYB z)yC4Bb9YNxOOJ}An-V8;jl(V*YTmNjaD+=Ratw>DL9OM7?9ZW^v;xYJKxQiPGDL7C zW4MESkXFYnweK|6%=rXvwL(>J1#_UH*w(HiL7A{oVzG?jtuM4{pNvKC@Twsv1;x2~ z|Dy_aDB*A8j1q?^ZjjsdlN;;GJIIv8TJX|Qafx)B^-(YWA%{iLTewJxpayE-X_zX2 z=iMDeZjo!tevEFqdp6BT9l`jJ1rwR(Kbu~^;)iXB8FAvY;f0w>11RXs@Phl z;lP}9_(#cZxt9=u>LXH}!|Ie+wd0VtY7mGMA~ zZ=1|ej`ot>2rAb4HpUM?u*~&D^^=BTR9_MYW9w}XlywuN43cvDW6f^;@no;vsobu{ zo=0hHPNyNmP2X%4)Kd9Ci&MpHV4c`R6gJhHac8Lk90H|fF25DpkKG8+^U|-J{|JwR zORov6>hZmA)wblXEm4aZa`qdZBS&`=tkfoPh?&wclcV;Q@@pXXT@0FrA7yfJL(Ff| zDAdVec#)y^2GuQEwzBjXb+oQAt$5D3od0o6MvcX9{2Q0UvC(h2ID-3yp7Bp%8=m*B z@G{`VBvF}g&m+2;BU5!mX0>g3&1kD*)MD_jy_cvIbYsNOa>RN4(e@6Tj|WWqEy*j> znY_x*6I_0@l=TVw(Iq8JH{m~cl| zK)pHyO2~guy9(mWo)WGZAiUo@-X*FXvY)@6rhU}9>rXX%$!vJ)*{6xc1yj+fq9=Dh zqH2Bb$J+XwLoW9;_@9T&-e+dhsQ^WU5eO8e`ftBpRf-=hV-I!X~%bA$Ey^t*;%DJ-m zJe1Luh=O7dg*L^I54^wuq*63ooyV$+N=0N+`r9gnVpkH<=GbeAEs@ECq&F}3L>ezN z@|C%zv`|cU5@Z{_yKV-9i{KhBbjh>S&oWKpGjeRdq<+aLxn5|toejIfMfACGjXnNp zcgcqf$0bD?wsGD;g@%j`IRzRmJ;MrZ2fh?eOxdA#8-_iTvnoDw{W{0mpaRN$rii%tgANFE)tb7U zGsmpoiGCj~i*NT;Z*Yt3Dq5Jct${uc!?R)L9TUga#;@)UB_5+R~aFm+W}e$oN^V2=W4FqUL8P7q~wo zOP0dHdx^Dy)uNTon4$2lp>nyZ|5XcLd2=CX*XZvD4f~$3^AVxAO z8v079BzW@>YLXJ+dw6HE9;+(nmGgl;HVgNxcu~k9)VCVG=6wEF+Ogvn6ph)znIZ*4KvT;6O;_CaT{vq?=M*WUpMllTFD zT_&1HVkvxQ(8TSW9YdLz1Otxj;y-dMshAK6Wn9Yq8FD2#Kyu5!Cpq;D_QBjLC0#Q8 zQMPtd0x6gJK*h=ay-2Rh%cWlqu=rdSMZ~WM6`|qi2dpog9|H|Bazsc~{C=V0`FyQ# zGQkY2gd0^$Bape}pM^;=QHH`+>OoP(sElIseMxYt#ZPFrc1mqF?(@XE_o%NOkvPfm&lX$;uEy|j+^`)MBfS*=`hKFw_XOfMeeV^=}jesw{(5Y5q7|9$`UIcdE5 zLetv*kLaA?pH+G!q1J}!ZHAHvDCwg#p>U2)3#wXK0igil8n##1QN1&Dhc4b3)ake3 z(DMF%soHI4@I8CJ2pUs<`io+v>Z8R={3#`A9CmgHei>C))>#ds_V($sr?3jW8Wv_> z+|iz=OP4~%8m@Y)fEZc4a)8{1q>^OxP{tjIc@Bx>pl`XBb8P+e>&K1Qx;p9p^-~{;4lXnGU1Fqw&_@l5-5lzHL12IrjvoGk{Xi= z5lQaGm6w3%*odM^;0nv-YDePNhQy$*5YGo%xK|G|4$NXVD1NQhvr$jfo1YN6nYJL? zI!dxy^yM?yx8X%bN|WY2hXY2do+FB@rwx`DdQ@yWOJaqc8Z@wCRrA!Rce;fE#!Lfe zl_BB!wc=Ll`=mC^ibNpl8rTwZLpZ2XrxDKhTV6-nmuajZinX|<(ixI`Zt)ZZVxn@T zRXCYH8I+`pOp}WL%GMT)2y5vYMCYp**pcM^M?J1~&y!gkjeUc=R}kwW_{Va- zL8EiH^(A}V!>Ye@^OCa%32uiWS>{7rq!UBSD2X5>lPqze`dwwW7w|WK13g%IqcGxP zUTl1U&@}a?fmO9def~x1W*en*Mp-<)&xVoT?5%_;Hw0or&0S{WiYyowbfF zl+~5@OxIR*K<;dh%SsolP(~1VHI-y8Oota|0szG>ITnI% zcUVFPXF7#8&?>zza^MyOPAmT!-dmhM#2Jy;g#7gyIc&kSSWyjDE*9%>zXQquGmE_+ zjK4nbcT-JuDu-QfWG9Bpx zyQ+U8H<;%F{HsljP&cplyY~kA_4!F5&3(Ej4Wr67%_T8>9bKh=q}Q+w8rq~9dDdbT z9`@pnfNQkL%hWOzs}CqH_@omv%t4T6z;DZdwag&i)GAD>YuvPxY@w}+t#tis(gM%x zovP%iH$f$lLkU3bMsCL|NdRqJG3zyx!%896G1G5J>y2m18$M; zBig22C+mFgZd~2*p+#4?8B37MR}_F~kw4A!Z27Uw_GLH+X<~~B>K-zxAsEKKJR5DD zGMexkagRLd8|rZOvKtTX)90EV!kFN?4gD~I>FN8?X7zGo`6qpJm(`&?cgycb zGjH|Lx0_t&>DX^2FT9efL=d$z*@Ur*9ev+fv5z{EFNS24datA5q0&KTp3b4Ui>f zuIL=zoiqFE8ULDoBk;5KB_FNw(+ye|EZu=wMW0cNDYUb_&R>1=KP#*1FU$!?D|Er3 z?Bl#_AG~nIK&pljeR1aV)zfZ{ENz7CN`LH#K{GxoZP)6lQQ`I!zf|7fKMBM$Oxsg%7v0m_J+X~4<@dbuXK$ATv(|ZU>m^P zZ7%O=Z3&k(PP3Dw1sX^T}%pc|l)8Yb8E zENmc8%VkAZ*B8wekj&7T2*{)!6>`mrDG z#Ha_wc1iF&Vo0XEi-z6+)vX~{F!t0-LjJRow5LVx@dC|W7M`&YpBSC_r+^x12Y`9 znTgT^QWT5wm^XFwjgPy*?C61OZzLyVf8B^VVbN82wKy~$4b9?jgAr4x)&&$Kp zZ{SA~;AJ(TbaGq{ObM(tHcqlTU&O{0^vs&$_s*6RbSA7u?c(g5g70^b6GG=(iGau1 zrPXxMDIQ9YJ=Fc&@?T}P>zJ#2U9o-T0hAhZJ$v-FfA9qEe|W-vsPWBm9`+2y*z})u z(8nX=KdBmT7ndn6!5zU>PH;O#ksvZ!_w6r!_q#^z$yd_P{RP36e=o{}mH@?Fm%1yF z`3p65TqPNQD|D>(=MzlZTP=pIiPZ?UBnXYAsNU?hg@%raduNO3xo_|HMTUS)0a1Pr zg9$|>*p!!Mg*WWs=qm~BXx^yiVIJa#{m~_Ht%!k!-y0A@6Ln~eJ6*q4WqZ<0DHjQ% zbhbh^g$^XkAPu&hYv4_HW80v-6bH5YRc-j^0|wUnhz(Vaj%NF>NwOU4x^+$_0Y+0T zcLHA44tom-`ZZJUb!r?g&`=>9F5gJcIpr+{IC)KQD&`nR(jdjbqR??}Y-KkqL&bXE zRY{(SLx<39R&9Ch(RQSTvRM*4y54ImD`}wIQa}abagAzP$`-V%2GilXt4j93ywoIy zcujQ4mNnKT6{%p5e2opSBxhn`nGKME+eW^~BGn{(Ae=1hIj67`k(N}qh<|=IuP3296mMl|=tPPOdjHnmjHX@X!O z%j&m(@PJ+DN)f7qqru=~fY8bluSOAPB%lGlB5a{{R(Md5z+aZYoPWQ`#QX;97Lr*} z;4nMH@i9QSkQrfI9i14|OP0<8Nl_Zar>j+%NMduInG?uNl!exM4?Aybd|Ud` zylBEyl**9EcKKL(etci_zNX-fyY2eeU;A(bj>ZpgV>)vViItKjCzH*m_edh$5pNjr zd~~CIm3(llAvri{&LUk$`71O@Iu-aaW)2wcdhcdzUf*+RdA%1y^s@>^W5e=v->a*s z*HJV#-T9v9rT}avxTpwL!DE$)C3MWmb;`HYgvo)5#UpzqUtwZX_&*F$Eb^R+5A@tt z7H>aHCALZ_*o)sij){q5}Q91^eg8$vf1KU z>{U`dt}Gp*KqQl4npGr@#V=IHx!AYJirci&c`TRY=SVJ@eg4_({<2Dlu4%gC63eVw z@Fz66isnk~Xj&Ns?46316{lxyw4Sy>4|eRogV%@dlHXSm(51#N93e+xnyh7-&wi0vla^>$MYYS^$YHCADg_x?IM;^;16f5gm8xQ z-!=|O>_3ut?CFesv(p#&V~SwtNB_IGFuoWbf0)st~w{9#u z4n_O9)EywIHlcVCO#T0|0D3yc{!24S<^~k&Z~6PBXLnDzT~an@(D3T3Ghf?Xuyo`- z!x}Da8GOjmevCYq@Uh^~u~T*Qa-m(@7R2CeMrd9Pg2%&;W_;an?8yW?;5fY=_I3Co zmCX4z`ny(X9w*ezmH)A*y566b8zQ}CtOqisZ_*n0BXT#=eOQHC7XWIxF zRiy)M3-FlZ=}0N3i6bEylVYFjl!4FNWD4ev_H}s%s~X$tJ{It7*zS`&&YYuT6bt0C z*sEbSYG$Q(bWLI#l}WzX<7#9L4}F2;k09+xo{|ID#8M(zOj(rYERuX?4J(oD&|^yo zFHBRdJ=5H)8_OG)&=Ry}G+u?K;w~aLB#lIMI+EOfIH_L?r%TvKL0E5STugxNmSP3F zfyO9_iJJzWujhX%I69o{*zJ9%u8a^O_P5KZGQFvdhdjxF=SZ;HSVv(zOAk2bmTjbscrA}5+{i=smGLV7(F5%(b`MPYB9yuAmvr)8PWYxx-B_ad+JkZ< zUo_CZZQoXSr<*{!ut4cvPNx`RTE5457L&R4FGqqifj8k!G?;<@n>b-H%<&f)Nc8mv z6tw|3+t-U=r4R$%FTF06hx9FRvr2^=CVhiZF!ds=)X~&hE6_K$5J1G?Nv0dc*MbcZ zttde6{?2Ith*tq6+LB9;5ApN)W($B9du5d~{veYo4tpGvaW&8{zh+JNj(p)SfvafrqB-+5pA z%cnUP%yHwTyT}qZ5Aqkn^_;{8n_{wk%W}L-`SsYUAGbF1*tRNnHhuDd7KX+rCEp#h z5FTGaFUJYr(U{6m1+_=9Z@7M?W5AGU?(2Vz>-m z17WPmAjSNHRio4G_#%xyI-{W6KY8(YyE?GHUs}&^H-7z^_c*nD=q*+Hfa(`2{cggX zy!}+3n6A)LT()ljT7fJ0h`jB_Q+w&@>OFs~Xl)+7JX(+4?Hv^W6z7W%%zpK5jLj;m zES_BY2`2wrrqt0aI?+SxUiB9_=om^VSIA~ z>OMUV@|lj;@rH+vuH%TIBef(f&e*7WjaVrhNtE?TT%{ZczDRiD2(nKYh1xfHl3 zDR*gCY|X>Gt$XMI2Y9wHHgbiSVh3&$!Iqa4NxjPynC3h!%^F#(cn1}=^%t;G^mB>h zv)QGuAFq!+AoyMRz3VoN4`(4ryhm3;A#<-xxm>?TZ>}HTJuj2FY?o$esky1B@d8x| zVV?V2H_M0HM0P>$m^aF;uaLcmNt@zSuBPZ-nT`j}P}=odCbp;E{VUou{&J;-!RD+B z$_7+(V4e5F2CBW~UA8_*7qupJ(THDhL`5ti{B8Ja!?YzJ>8)LuZLz{Wu6p)aI+2xn zTpLzP(JiHIKE`_69LL`hdfZFyn`2?E7l@%<^|j)VdxpHF6pXZ%{&b{bZ=oc}zk=)H z!FARv(%D+a=Ee2a3G%KHg-wD2{%7+HXl?L*Nd<4PG7-5PN|@3w6FEwbJ{+bMB->Io zC)BH?R4G4Bs5te4J!XaB)`&@FmvP9W)+01jNmgrFPuhEInjJ%M$lpEcf3&a7A zcnSC+)BC&+z+HQ2v-oR9NV;JC>d|g60C5~L$`orfO-KDXX_F)LwTW!W{xvXbg{(GN+kP3HiXsn z;jK_cbwN^t!T>_6d^cW6HBRE@H~~K@W40h}*S{7m;3f{@HjII}E+Ii|mS|%UAEJHF zGQ}1eg69`*76V^Uyw{YET&a9uQ0eAo8}dizi{IAAb7}Z;$2M<{Q}^l%gy2$2<+E|< zD!+gFMz(ms4_3e|=L`G?BDpO-8-K6zmwxc#nDoYia($=o%3lf(pj1#4|He}jeJ(Cw z%#H{H!=~PY!(@A$t5~c4=__jBliKG)V1QWd=Cr9S{X*1+@u^<*mkZ#mRqke3<`zP{jCnOZqP;A#S z_AzdFRi17nW47_voCd-e#&0L)cwDn@R`gq)4b!eWds_b+p_;ASsMbvur#l;i=*8U^ zWmtS3>|T`!#?z3{5lZneu+onuxWGlHxy^e01?`=&l21FHrmCmz=NtDpe=8%dBXf*K zov=3?N-=@RxuR2%i#hhJTV|%%Nb&4xk$M`9BfBfT8JS7Ky?h=d<> zSOg;9t57|!YsMEFbc*1HW-ob7!>gh$ z7$ORixU*4tatBeqEPs}TRz#xi3rVVG?}G^WpzARaP1^w_joR-(dZ_zUzH1!$Q$P&X zUQVjJK-oNb<4itXSOK8f@tUwcBNdYFB2q0IxIS~vG~KrTQzG$hkpl1bp}snrzB2<( z-2#x=mRGcOf%zqcS-N3(A0g*1j2A3O61W=QjaEv$i0S!6M}VkZk~($eCdt=`fp@IU zG=!L1h%Eo^2}wSRY+^>qVXYb2`b6qwQcv&Z8@K#Wk6_-mf==>J+D~Oes&JfhyY3eq z*$dM%%b!TSB$bJA{s*G@7+@AhXIc(0Mojoy+zuUD4r9-E>>Oj=m<$7MEQ7ZNj6Dv2 z6Gs2@92loBX6jAtNeh-(!Rdeq1RbbCZN0Oc0Mmcj!_@~pJKONUYF4%M`>txO;Q{*b zKS5*)HX3o8)6HI2*ake#z(_w(u}Jx{{#)byMax=y=l9Qd^V|hSl+Sj?5 z4~5}^`oNNIYp*YWiQLeGxM;g@>A_sHJ2>8-8hPChq~!YjV*`I&_i;LB@Xz)??F(;B z!d%Bp_@!g9Kd~aI3lyo1wG$QaZSl?db?Na<8J~9*b;{xkBz{)H>>tMFLZro+VH!{Q z%+l`oF|4_R_vf%iR8oAU)pO(O2IkY-w&Acfnbgj*sToYr~9ADh}VZqV((~srzuNdEOUNObGuQN*6~p`-tq9(h{?wa4Z?zW9}*IwZb+UG z`!FKI5I2_9yzjJ!SxD2rIBZl}KsdXE8n`4%W4gCE#|Wz?T}DWxj2@`G`(_T3bF_JN z1_PqCvGY)(6ri+9WLK28p4Pd$0f<#B2!&)EZsGimCIfJ4zRzK5Za|W#h}gSWSK0_& zitkSrm6)gqK~2`c5<2SF-9uy5NTW|+6;TwQ5^NY~Gd~}f_&Z)$E(285A>k=q!%7%J zm72XMo;ozVz^nwuZ4I7970VIZ?KCa2DGgHdhWgqK*s@xZnvVR1_|hLKLzqedw73xbQnpGsALZ04PhG7A$rAjV)(Rdeh zFOBvZxj+KfnQt-LUmS&UOj6|V6P5LLaSugCG2O(YV=Xu)!{qVPurP>2CPCRp@N$0rh?<;NRTnypk|5ZVFnq`E;QjzS4 zYrHq{0g1k6e6sJ0z^d}te~_`*8=N$VU+v>UGx(OziIb}o;ofMZLu3Qu9Lz1W4K!j^~;C6~a9d;9-DL7X+i%KvzY&EiSGA+nPC z0z@l+&8+e%2Iv2#iaZSn555)K+~KbO;G$ajXoTAHs|&CPF%$IKAtS!mN@5u|CTO6ya%9oXB#)+c@@J1$|~yn#v%am z`>H!2QE*9#loH&K5gPH(umSZLfs0odikTH7{daX^Q^E4-PFKU)qr+-a6pU$b6CCY9 zI}**>Eek(THQV;@#i1EbzT4)4pQXk7Yg&h!31p7U;w_+m|K9?v6UP3_ns=_C+j$xc z!`LJS{YaULt%ILAJ$ylS?0Cu;qi8%E&YNKl|C*Lw{Pb&Qrr)vjRPVh|L*LjCr9Lmd zguVa@NuUy+%A%wgP+%2t(Z4l{js+4&XsOpwSj*^MQ%xtCdl@DU76ea{p%6HPz)BK{ zgfURFlhSZ$R=yUECqsxM(J#>|NU0QSRZ(S{;f7?7B;|(GZF@$F-UWn~=4cMYWvsAi=N9(4=c?WQsLVkRb~^Q z8|r0dteV>+m>U-c*)*>dEW&z;S%nGVKuBw&c|5{tRwTSY;04SEQ-rf9Mik#A)>Y_PtXqD6^)?kq923tqEX z7kS@?=v>w^d~~;J7V?*{Mir_cIL=@5J>R=nS#oEMYb}p*iVi8RrNpK3!Yq;+TUwA2 zlzzJ(_Y6I}A1ry!z?!F(9%p|1#^|7p&Y^l7nXhx9W(_zFwUrqCI8ZPqI1=GCfLST& z&d=g_o^*Mz^sayw!kCDt`P%Avm}9Yr^KHyK(KJw&oS3Azzt_lsE|-8-XmursuJPO95v^WF1{%xaWfe*D4Zd6SRAUwhwrYx`MN zYW`>Kkr?^LO6}iv{U2M=KJuMld6*JJomB&4;&?SC{{HU0_G9?E5BQpul%E|A__!BH z5O}}x(0Xo0ityg<>P09eM_=0=M5(b~ePm~nYjHHQo!RNbarAxtYywZv{5-&AzP~c+ z*wg6GyrV@B^GmZ{f1v5%_q)b!e89cMZuGvSs2ZX4N?nsr7=GIPjvgnu$^9?Fm7R>e z{Rv;wt%*cz!Z2x>iOwnKpg@uK%HPE^q9_b`n->LP_z!(+bZ8dqrsA4Baf9;TJWs z5`lh9D-TR#d;xC&X}tfTDp2ugg5he$_6;j-&ZwD;c0hNIo?!4Go07{FG`?pogT0eK z(-HnmbI2C)8H0@E)5FNTNd=Hzym_|_G$!2w^=`?$ITqdJ=buDtL_Hi9?9Q1kmtE&W znaAx%qXQ;H&?3M+sv4pB0`KWe=ag=Buq12|2msMN)S8G*F{qMVHZyRE9d><1oB`SA zhVLFnY$1wn0YiP`_ICNQ|F>Jy$Z zp)3U7@@$|TF7BqOU8l}fECL7Q{C3x96|0y(HXg4n2#|{h&4KMDVRe%2GB%6e2pMRz zC;{9vtmMD?TuQi@YMX_e(v7#gw?SPfJ!p^Seb~OSS;$@r)0UOeq^MtWw4Cj{J;GV@ zkI8=Py-nm<;GS;J^(?k%N2d8kPjV~$ygFeWKF9EYF?C!4s5w4AQlBY(6=Rv}8IP4k z+HI_srDjyZ%*yK`mI)LCdx0{`Gx?1>gTQcYuZaeb6z}}(C;@eKjs11=hzNTQ<#82e zZ3(g|=30|jq@#v^8$O-gRF~B3-_q>l^XAdk$rg*k(N!pi&>zY)ox;LHYHoF_^fG0r9W=TRM4sR9uRDds`~|XM zok5`r(cnvHTIZ((v(L&tHu(LPMB=Y6tb-pOUu*KZ-0Sh{fyg$~J<%eMFox{YVu9F0A_RTi2e4RuQIth*W>TH~U#sHRV&oeX0H+`+fy&DZGi?+wvdyoY`Oh(`|VEKf28aEgRiE;%u^VL{H|kT}|%s*$>d5OJ{Wa z$CVaoRh9eM^tkK`T+Q&3 z-FD>R`0-xRzr+8tc)5g$yes=Yu`Xgg`(acs@7Jvc_Hdf<{J^4z7!nvKm5kE>|0&&G z^yly0_WiH#XZHs}J?3F{TMtDzPZu$($|AuzQuYR=hx)IF^V`|)kyVsPZvS!!lXhmB zBYg-c5HWiu2w5!FX>I3rAq8xXZIcTrCwG_i-7K%G>F1;#BY9AvCb*g@qlR{+ytP4x z68na*0mSx+_)DWwN#Z*FyaXDJ^!+>!?c1wvNin|MsBRV(0ENv3Wjhi@eC+6<%-H_k zdXgs;;Tdeq^AMv?gaU5De2`e1w1H?TxXOg&-bF*}Ps<;WXQqr1;tKxM@Y~S(ny`jR zj>17mgoMe#f$2j6h<=i|Qf}L*y%}guxf@44;t1jZq)%9%6#VGg+a9{obWYAlJQ_07 zFUjuL<@c9c7D-9m5HDcaf#5Ubss3u@hw?K+NJIP+EWwiwMF-@sENSszhSH&4j7F=nu>%ht&2n6E1{cA71-8fFq zN5tKK>BgvEYX+Qly1V1%Jp+YL%IWG4AImg#Bb0*Kvaxd_PsgJ;1F#deEA&bGL3iVE z@dY343FD1DKN!zEqy@%(;r2iOR=}}(V5@@7I*}%13!+ls$G|b29=P9QGqC6O5!pB9 zDW5qg5DtNf;o3aK?YQ(DNQ?01{t3fMjEpf`2nZ(|gUvhahuv52ik0sGsY1b6QKo|X z+8EZ*9?Aol8T$aFHUYuSEHskCwR7LWN%u^C51P4Nr@FDR#*^Z6iR=eHLwl*BAe3s* zqHdBx(fU1f$c5ATCD7Oft6qAeff`|_kD7i!#XURcO-$<_wh8Ucy|{J+eRA8N06b^u zyi?N`GD(E~0;8totr49uWt?k_*`i6Uy?s3ujD;KxDYJMJ>K(Zn*4W9v{yTiX`ZXas5P z8m()_{;<$@wvcu*3!)jQa;rmfo!;iXbjk^n>U)4k>vr&p`Xc-sG+ws_s@>BhnkC~) z)?|^awQEK(DFm-{JwqgHyVNcEU2{n3GJ{F&a-L(;7^`7sKb(M#yIR%3Q;nZ@VU!Z~ z#TlD7P}MjO+QeGQALZTXejTnzrMfrA1!AH=Ca?j*^Yx}U}3-W!R>34&u;~T@oxQtO@kQcjez>6gDg6MKG2&OuT z(0B^U zWfQptJ}9qiKxB2Qms5hz&y@pNs{`T0kq0_B9G(9(c@BmL=#6vH-8QlkFu1g6>nrU0 zP2BU|K+g3@-fu4w`+)DblM(unKPOckzuE8|NKWsG40s5-?h#@?1m5>o_Y1zpZJhR0 zY2ryP7X|(jCJHTfYMLr-GRAE)j4I&q_>85me=?7*lKk2tpOv^vGeSa46lT`xy)bW0 z^hYU&6=H0wB#4y*bZ%C9`F%rp>_-S>$FV92PcKZV3ffbfFtY zflthv{CTr#Sb%m{rKd9{fmZ7u8S#R}01+kHa6LP~ zTAGgs>Z{@gZV0~2(hn5RT17Ptt~xKv2Uf7cUGq<$A3F94L8hyB)usBqBq)wjFGRs? z-3+oA-_2;n1FjfJ$_GV(k6ZB$HKSnm!(wf4W6dlE;GoFWf+*@IJJm* z1Lc&LyYJl;;l;L?SbElA9Cf#h@Gh`H{YTv0}=qjZi=ys&Up)#!*)bT zf^tyxd}Dqmd#himFG#G+2+X!rK%{=1J3y#^YzCP(oh6T`|)BHaHFr0|7x%@xW-Gg1+NWHe(x)QjNhgRAL6X&Vhz2l*pB+dkxI_C+dgCM^$ECM$zFq&tQ+jOsEUHP~myLrph2(~D z03@T4O;;SyCq%uzFxAx}+c*l5MAa4a3 zuJ=*T{kXN{KrRQSNbj%_s*1XbOMXmhvZ`$*_wp%YY8|(|{i#J!;G$XnzolWx$IkQo znK8v~F*;J&UPl$E_v%AUz(uHZR6yBAI(3!k03`vG4dN#BrtKK^LvZ(js_2T=1+XbL@)$N%uNtLh8TaQ0T3tW>wm(z$Dp%E>AEO<`fqJ z*T;x<xZgj9SFi?+#ZS&9gBi)lOiFs*y7?d_c<0~u zWA$g7EJ_%0SD64K9?&=v)mCaK^J9Un0dFL-H5g(>3{vuL95csvm9oetvC<{8hr#=Y zU86ZBonro-6ky_5)vm0282;?;J+(Lnl0|Q@3gN4J_jp$_a;o6yUwm!N%rS`a5{2DJ zZ3f8;uOdw^F!r{FG&Ex+2g(eW(0IA~9RgSC1nZnIkQz6fwYVl@T=1w*3Ira}ZkWz) z0yssu6nLDtWZN9Sj>i&$3@+;2=R6%ym?>kQd#Y&Hu&I|s*|hN$<|4MqxRs`0#maIS z?}2&(&ak3nDAPX(#UhydRkC0iF4u#4PT1$9mL+XC8O^R1^i2oL4g^m|)@E+8vcSMF zO_at2qvDM@bb&c05hh+JXU|;ghb!c-UJW z&~i~!c92wc_%>5VlKECBGcq_8&HPI!z^vm?6$%|ngH3UV%*`D7`|g;>Jd!+znm?~> z1aY8ec!emcOQ5oZ9S{L2hz}@g9N3V(5#54hJsv=OfX3>x23hGTLU8i)9iT+uAE`Pk zuIv2@Y&dLnqHft9pLY4kR+>lo3xRQPC5oV8!;pRJO(@_a9$8P?)=Ya`6hB@izD;G8 z!IXr+vhsQQ@B07_u)t1*Sn9sk{#`1;J(2Y!diCD*;0g5L;Y2BN_)VC;|@NxpP`;zr5E-IXKWr*M)>@6iLD& z;fRA9YJ3!%H7%1XU{m49z-RH>^U8WUnmj1EDs|zx>N|VR_GBLh%cSJ;bAaOc1C>sI zBFB`N01nTLlM)_DH{j~~ zZIRREqN4oF|6}SMqvQI&_wS^!8a7rNHMZF#jcwbWu(561wylN}Cyi};V&^}f@4A0$ z-4Eu;%&hb1oPGBD+Sm2kxL4AFcVuK_5}sdyZx|1dIH~EVp^B0@VazI*m_b&nX(%}R zgR}<+hlFQtcEhXDsK%EAw1CgC*LvnoEb)@KyKI4PbNcOAp}jATcQv)YQGIq^n$x;p zd?vPfh-qztew^rcI8evvcMw)D=|yfb?m)sf_U0{cJZqattzmE;!5oF0)8|61o~DgP z0Gd9E(_RNR+aV16__={ga+E&)-KTE*S|5*Ymq5jj%HZU`e;5Z6s zO!d}{FZMj>kPXxSvlZdw={teCOLI)CyQr>5QyGplt`3ED5ip;jZC{%d4Ld-sSHrSz z=ki-oE4f{xUp&dxUgZoRTz*{IJpjF~ENr5Uk9L;hpEkBS(Y8L`k@`Yq&m-$Z34_vS zEE@54P1rq{C&ujcUK6FqYB=_(1$BQ>C{YdV$(d-el-6W2aXQj$)Tk6{6zpX@(fSU;Aw=!Q^Kj_jtUfmKGhOjy9W zHD}9RiMJ`vkiEyxe?nd$_H(3c6OeBilirPz>6#n4zX69zb^W3wLvet|&pBfr?SWKp zFPBSXN=$OH!bTJ+#d2bGqAxTCS}SQ7gVlq6d|Li?M-)DIfkQ}6Oyo$?=aj7yK3+tE zE3imA~TC)4gw&mr=qbC@$Ee_SFP#-inK)F^ft!|yv z5-_qqyX~5VZ#keNKYUOt16;Ws07Ma8l_(101^*H`qYD8-lrkMqVD7Kul;t)lI{z~B z&p>dT5nL-1n*E%Wv)`~4`O1DW<$Dq%Pm(Ap9WM4+#0GE4Tl3vEp^CQ)(=eAxR>0^- zv0iM+_}T->V=@b%Y+~ZaBy%Sotu*Q^2|o`WV>WjTKW|hHO3iaHP!a3=QVMf%rcZZN6?l|U%gH2|wlZx9qw4S3BWL$o$faV{! z->2L{@~#>D57KgPm9}?yOcBrz?H0q<`6BJ+ozcdfDAQ+E_KEe+ z?$ciQ5H&I*lkcTO6IvbT>8Cj<`=G}>YF||1%P)#JjCxUXV8C(4OJz-KKCXpYvSwCz zMJU2>slnRw_)(z%4mTBAJ>UQ;$Vt%Un?zx@!0pQ^G?vE*uztJC%sUIJLd$#@bFHD9 zCvo*-)f7*H>4XSOv#@72Ama2c%coEXVoQKXHXau5B4HAf6tCP#W09V|Dj0jcOr|HN zP2K$%@O)ZHYu_>}gfhlzZCi&zi;?A_2yu{kmZ1G!IGA*CnE=n=vX1}ww^%A0jERCj5Tp)m98L5n90EU_F=bLot_&5nl|+!5&%%obKJd$(SosJ;IRirosM^}T;@yZ=~Y_Pion{K^Y>Myeee8rKgS zFpn)k-3;VSeDZAk*W=1c+;gj@<9jP!4|oLMgxSLH&n8VipO1xbf?-KlXe}?$SBt4I zKc2CfRbCWGIdbER5|f1s=v8S6v^0U!<&|g29_#k3-jtmikZ23C(KwG?;AU&xUfK$5 zmA2}|dL7yYyOE|PdwCSj>dof(^WA+&(f_C8cfKw=bu(6g4b(Vg@|{a~ooD-{Y}@}N zf(>l$KSd4FE{yK2u*~|N__YsxSIBR2&vaWhBWqp;F zW+VccL}sWILQzd?xTMjwprW{CBYJ&}%~(bMD)}j;{j6hJ^81o4OMsJ|G_*uGGE}!| zHh;(Vfi#cb;I57@-Nb|Or)Bi-SI4gRVKuMMS~msYT2y+l8K6#1O$#^?C=Rm z!gx_(cOg#$ACJtLcagyGiMbRRI``NDB-a4OPyBBr;>C6t#=GK*jl40r0{)`&<^QW@-CW&1XwT%XV}E;TPp9OI4fyw z8G3^#PTr`i%uSK3&nE^)ddp~kv$@bTk2Pd^wMRD!`kSP^nw!_7v$tZ5k0X_5xZVBi zJj~{f7fPCFL4Mz~I!J4TG*jzdacxJmFj*1sG)XX&&0@JvTK)M!ZLK*f8AX=}nnWj_ICPLB!zYSIr;JK zlff~A^GDUO6=XRR7B1fLczvEGUZG48CeG!Z>?EqrUSupKDv36mZeDMGgsi56%2BLU zLBKM-qC-pVV0ur;Kn+NpHlrr9S8z2yPY(#HEbFe`A%P&==xmMFrI_DIk`N}hOeA7i zYx+exb{CUD$SvzDh5g>|CBNRjfW*%ckDMLJT~u(G+6tSm!R>VTqS&1IQ_yXk z{K}TDxRqJQ<$}t7$kX?}Fs;)Q31OodHxoa+aoL;4WydRuI3p~+9HFQTvMB@t^gL3} zIu6XBRo^{~^}&c-vM&hXLK87gWCnF^MU8GfQzqyHG6!u5?^>ZO{3faY1u-B1QKw5f zrstS+t@q3xA68KRtaIVrg6x~I#>@FuAT+=EmZSF2*WIg)nB z%bR-WVIHXAWmHg#l_J2Ic~AP7tWK=0=LgrfzScTJmgtI2HY9oMN|?oZ=-#X=xGZkyTB zoSPj4SKYmMBwq6*oY*E33J1agC$x+ggS55hgRQ=2f4p9`y;O77w`uRcMEP}AM+3J> zAC#eu%VPEO@97%bXO&YJts*hh0Yo2M?X9fcg(t2+tGJ@Syj7WA-_ z_}+Le$}o;TNf_%g4|lX6%ZBg^!eNzSCjo@R?365Hl(X~+^s73L7Be|V6EMk2tDvbl zVZJB0%wI{Z88V@TPqJKNQ1zs;G+I5fEN5=wGyV+ujp9SWH`hA*t)-OMgo6{fy9X_3Y-zwF zbx{{_R9Pa@>&LaOxOO2ID39bQR(Q9A95K(1g6FR)RdSGGxmQw$%=UtI?^RJ?%+*F@ zjv;+mpWwKK{m?yU`#$9COT04tO(?FJo1EcSjV;S_4JrNLV@kIO3&$dC95PXO^8Kd9 z_Yal?X(#HOBb|S3UTNf62@QF=FGQ?R`BsJ&G468V?TT+)v*Lvl{33qTfo1Gp3lDkN zy)meZMV8Ame|1>GHg8+zG+O%MwhG!0aV1F4g(?<91^pVq9Jp>`EbjV4MtZ*=nvbxzk0oB>qoL~z2S5G427HsiEsNNq(gIi zgGLkj9{A9S;_htnjg%(xY5ntDw^p#akKOKI#cCZ4^D!7arz6195m8Mz+8c={13Xs2DH5NMdJUwmCMr2DU3Vd3fAUHqjKd!G_0 zraw?=wfWfd*d3^QOB1hGXM8cPb#a+G54Ize-#qhRqgC|aX$Uq7$>cKrT*~n2GrdU1 zP>lVesEr$E_b4~C@u1Sx%l!?h(0q3}m=P$Q$~e^O+lcbiK;-R}y?`WIo^qs5J>y2$5s1- zUgEk3g4j%aolL#a(DNQ$fxRy~j$Y10E?u4DfJCCjjyJp3@Oq<|-6l&YL&fottulyr;>>j{B0qR-**PEkd$q(N-4LSb$-89&7sPcl9F zcfn#BY)iB;o62gzB#vt_Oxt=;xt193@4#-SMr&rl&YY+nME!ojk3aOAy#fC~u}gc0 zM6P`zsy669YAK-j#(p4n{$z5-Eb}EM7N141EEU0oD$9y89Jk_{>RBf-pK81%@}QfO z5Rd*&4*_dIVW5`J*_n8cV)u_qicgW7rl=@Iz?QMEZd3#AG{MF1us~7~kzY;=oAjS+ zYJI%p7z;d2SCjpIwrIgIZ*I^gTDXm8kE z{||%te}zmV=JLRwt|m!g3EZPE2`$8lxH=}>#VgsKlcr*qRV2u4%z8X2m|ye0a`zyQ zo6m-26W%l}19s;DF^tZxq8D4H@soqb0=>9ss>1_`(pMF}nAGE2iGM#v;0nba+iRTB z;#SrSJ!jn*WbM~vw2>;@`$v#A;V(@zvyNPpAH2y61iE0+lEKG%v}8P%SkikkG??YY zKaG~?moolX5Pbg8CDM*IiU*}!t56L!S6s#U%RvT2P{#;dwU_vhdd6}yagPt!6%Bvf zT-Sn#ImniZvkX8w)Jdwl#CF_Z+@*E4Er z8Z=WJrlF$w#Fj)AUMxQv2u$ZmfzYRC8)reB;yLALd?pFYGF$TMmKFB7mdq*$#U;o~ z0#d6aN#*dLiNf}s^XXHcME~j^#MVEbT-SX*@$Xk7{tYZA3n#ms5ANXdv;59Z+O6Ql zPT_g(s$S0wZ%4Ho?6;lwWv*%-%Hr`pu_0{#^Yw&^yy$v0bX7EY*5h78(2dF^1{~ca z9TCvUzP;^U_}1$g4Gv&Ymce>|-EQM_u8};a6>~#_Sf}nfr(9V!q)~ zA_dCI)-@JJYwLaC_i?Vp+~9VOB%Uc(aTSHkrO zS_yt#chqmVDpr5*m&JS_?}6=qvAJDyhZ7B@MB}75{u_1zgnDPb>Pe*5e%#L-L(+Cbceqsqlx^7dS%+!yl?J7=HbH?jF{;#*V0H zrfniKp1&~yo#xr^JLS+KI9Q+9o2n9%XVp(t5DzA)-pEBhgFL4(-@@IASzh>(Hp#_l zf3K})xIgR+q2^hj|kEt)BBdhjnHXo9hCy$|+tz#d-03)kF@T`oy&y>!r? zk3`(TrP^S-6t8|B7M=2gqOHj%*{#E>J( zZ)aumqXZ%bHq8w#T?8g#cza>^A77@>f$fa~(<5}JZN;v($|$U2@?53vQD+g1!@^!o zhzSoLQ_wzUA_mPeZ#7C(80v1Qqq=+pBZgd&bfzzNs1n8LDOOsO^+@eqVzO;<8(l(K z5bvp%eTtj8Z59d)PwD%bM62yBUGp=O-;@qipZI#0J7&q97@-&oB}IXS!RY1@Pvqzk zum0%z_49^-au|E@0z;L<1O>32K2s7 z3J>_t!5xtM?%5pss6FR}bEMPHH-Gn83mw)FV4AUNuPVq1`mdTCkNt-n+vHDQumL-j zrNVI@mp6bdyWoiy;MKA9aOz2SDp@C$)@H|!a4A)ozk=pi_fJQrY^E-={rk0Ui-`{> zu@RinA<%y4uNd#}KWh))TZOmS1x%2^uJGFfXAgew^ZhvJRQ+XFTK`v2&$HC{DTgXB zp`6OMawmZer-g71UE@?4iqBPj*<7bFdgKwQ7U9laUR!iae_Q-oN1) zrX5AOK+)Q5ZZ>oCl|=!6d}ABw4KYK%vCRGLE&BP--Xu&>e#-7-Yiitt;(-B{n9;XR zLN|zCS`tCJuwgs|IE>A^{V<4rCvzISuT&sKO&7G*l+r`|Yav?64`JuN4GP%LKEjN-E_czYdcrjquy^w=w-7tZBIaV*#X><}3@~31DLmcv*@!7+~dB4B)Qv2MNN! zySyx$WVJ8jnCsaY23EppD|9n|g-CYx=Lq(%@19Qz6q=`OF>2CZ;H?`ok}<2U_>Cxv z@PmEOA269cdJ55Uk&a3>^z$h@scIRfAYzPS7HxF(8)ZdQB@0Jp*5nE1WxQwHef*jH zpihfm)={R<<(<|^$Ha*4CtV$cq6F;(A2hTEbeNV5>FN6OZJAXR#os)S92aSMp4eI5 zTZi~eV>$d}&q?^v9)s)G?Qdp_K`hDH9&sf<@JxR4RaQ|V(B*TrpCgJgGmsccSqmIi zUb%W+wl^BbzOUVxFZz2`HmSPJQsu4*kO;je>K40&f7eaZxy$BBM!XWZYKA0^F2W4k z`WDJIEsPU8Sjex51FX0M{9Z{GvS3 zr_Hw&py|O(-o01swC`o-LuI#Vb;OV+Jwbr9Ul=qme5vI|^6dxT^fim^YJqH*-L(Xz zq6F%mG1wQ)&W8pkzK{bcUME|+enJ^sp5qE%Uc_8P{hFsJXgeU_>apb+AjHPKXF2T| zl*=rX3=k> zz3aJE;Hzy2=)yNwXvt!l2A#sMTm?MsyHh2wGIOQ;*vtKNe_L_u9na8MFj^97yM*f! zXt~!g^1Ac|S0VHBU7oTtkmTrD5EzlcA1=%&_q5p~08t>Y=e@*Vue~5IbJ}G@tXali z!yilO_?~7hy_E1Lv6FNQoXUPJY@OZu{MQM%0$$xLxTAHVi|=0C|9cWVgx%d441X%^ zeOv><_1=2un5nmo*Y?dTi&vh!C=iIxd#lsou&OCm#nU$D z%v%9dBRq9>RE@EqkP<8??(OMKzbPhs&1MwDV9H6lg z2IWy44AP&x7t<*-xrK4984sMgfSKWTczc?x=Hrs2a8OfiSXweTV6wFz7b=I>>EB+d z?Ua6yS+iz(kLY0FL+e$pr}ba@E-KwUj_bTFi<|W;S~F5sa=_%sVxK{S)BG^ay>TQ! zl@<$RSHHo>gLB^Bl${{YDPR^_Y<=-`JS?o!>B4v^pyQu^9$S1bkTwyWrn?ap{(*8{ z-d6qWG0|wf_cQ{{`;Z;ZTFR8;SrDpQz$7f7`v$MSA-+vYrO-=YPSuYN@zX70j6F_u zZA}i=HG7KU9l0E7gz+Op3yD<^ak8)k?2N$dMG511reVzA z4U>>_mvqy~fXwEwZcxtSs{3Yr?%v2&Nmb1cgdsDTio?mgRklc;(=P^CG$InB*}T0- zqQ!%W^>{Mb97`AS>Ty$TJdv6g$RyiYak0EcuM`*U8&#-SvAq^6kIiz_$ir- zt(1fZJt>#)hCGwvh3Fr_$E8;KC9Wd+WL9UvsfVQxA1|*)`T-y-5s=tV8mRw+Ig649 z#UXPyT5X-La$GDP@l^(4c*!dZCwW-ehz{YG&qTN5=Y&3fnjLj^fga9da*@glt4A`d z$wXw(Hq18CcWHN2^TXX$V5^af3t3F#{mEUt<#`R{9>nrQUJl>*R5ID}DL319gZ>&b zuQW6p44E$k5uuH^2tcv92`E?nF8#khiA{y73bb0qdMYJWs_O^*W@T0b*Pz*?g=oWz z4FN(_yNsak21F&Le=>frqaefC+SNi8%s9f+o{06`!^Op|+o6cG_u-1&IK%gjk?NC0 zD{+goB*%Wec;Mm4Snk?B{=UkAE=~zqOI4=>v~#*Nix}4VqI6&!VUWO)edh-VeE$dZ zGVX*q#4@|-$xE~{uGp}IiYTx3a_}33nb}>A`VAD0fs6U#4lBa{k#UAh8+4u1y$3p} z`L5G5G&zm+;#J9cbZEk7v7Nh({qPIp`J?+ zxoJBZ^6@Qapyi z570s%Hd-WOJDp>4nnQ~HfFFYBGiYJHJz%=oZPb@Qw+EK`^Z}|4bUs09J%>4P&3guKoIIRA%dn?n$9v2|sA(KKRe))J0q9JmxwP z=wSUA)A@)Y+J10U1lO%p<~ExrYH)4^6Yy}ZqQf;uaC8lfX`a=_$^3y?CYjPOm;L?e zjS-2_GFjyz1;-sLNkyiJ=|=JsnKQ;2IKYe@Qt1?U%^&o*NEQ{p^z=5GspnO}8hNQC zz~09yHe$|F$w2YYls_t+XNEMak7kv#0gr=yh#BQUh^Cr;Y+f~-a~xxRL~tf@_RQ!S z2yf0O6Wy2qgRY( z+8<{@Gp}d3a_PPYh6`@tl{h>RFWDqLz#w*rc@shiGpeD6PmnE$3DPTvU>Z|{rapPu z*_9zLF~N<3DyM_8>WgBLcy+b-tM!DFhv)~BMRc`5u5!Yq-$N5bftJMYd#1kDdDY2= zjQXjCZqG=-LEtNMZ=HVx9){2|0v>c2ZeI4I`5MT;jv$#uWg!hQNmF~kF7t1Mk zmN+>5B2dX(;t$_vtZ|_&0^Gf%?l~a}vh{>84-dophH!z}^rLyAU(Hg}_C}Fj6#^wV zWl01>1Tjiu>IM!CT^CI@b4)}6(Or`U)VOZ>8ac%MDII84rvA(^Q8mYp)b|n@ubfTF zC;yy~wmN6_wJ<)ZM;>*ml}?L~pfxVbN~LOw@-;6=Xb68w6KR(h;cZ`12|4Lr)ULP^ z5=T|nb5zPfx||zEt<@R&FIF0igtM&aoZv!gtkdD9%6EiT!y1cxL>0OB^&3Xe>|vLD zXb<^DF(d`&1%xoA%h#Se(16XPghWW_gdbPXCc%RGI?54bag8=8)BD%RAb4~e{ zAK80=M~aimKmM}=wtxVn==U~vr!o#3n7WVTEu7&0dWe1Tg)MY@EMMRS_cDRmcQUGu z-;X04KBtyPFaKhVhIMqz!-fdWXJ38tUA}Ec|G92N-4*cht6kcI8UPKSioT^jkEZ1c zkbFMK`_g_q<#rJ>W}AmLAVE+teWUKbveGpv(;Uz$>>&4Ua%E7CtQ?^DxB;OW462blkZZ$E5V!i1<5bfviS~m}iXC9p9r83L&Z~LXWH(XT6lN zcVs^`lxbf*xOVls>k+*r>Tt!;10YaR@9W~&z}VyA&e8*ViGS*^+ygw^NDvCL`%T7i z@b3K*Bqw%F^7#7;Vb!l2d7cDuPF;9Mh`ZjWrIsnN6WO8|xCz5?p9-jIZKsib>;};l zj`Lr-s;5l^38d5ZtE;C%6kr>O;TU0u{~VCd;fa8hM$TiCD`{?Tz2a_zMt4-vC<1<$~P`s@0+QiH{SMUrHp4w^9v^&_<4z2 zp`SW+J{au8i*PLay_iYBetL!l>u#ndX zA>}x}fvFsVUOyNA;5`*VNX^(iZPRc~2sorS_~9q5C(z3~ubumtWk-zncDgZe&!nDRntl^}+-d#MLk{%q9csJ*Sz|oTP`F1&PdK828RQZZ^xfIe>IkMPw{BXM#K-cwtyTt`i2tbmCwr+{zi ze}Q@{L$@wF;wdl{(5o*DJRHgq9h&y}<0g1j+A>^gnFG{tSDais4BR{Px7zf9m&*eC zVRC~i{+&Wp1G_ObP&j)Y!6J=R`+urTX-mN?1sK|Y|Kov{F@qt*RFK}``KL6QQ(ZV> zCerwK>}z_zGHu`Y#7~EEe%1ePg9UH9bqrw=T2uYp6?4) z?GR{=AMhpoTXaf=_$A>^s!D9lH(i}qZN5-oTZaN?3bHX|!7^n>Va8EGviuF$^Sn)o zGtZ=qz01Ox+F^&3qa8RP@vnn}#^}OjHlJrP^d&`!jYYBIPuiI2jc`Sh4Uj-EH}dMe zwi7gv%P^R%UES6_qKmWpwDfG{1CkjOd>YPwn!1t!4y8g$Dtsdl6*dq*WGT)wm{*D} zVZvSgX$dJxQD|ja><>`3l~+Z$NE->l7qp%R)UvK?omMs;W@D!cHEx|fFl=_#u<{5J zH=6h?LKLK^MTkzE6IQr0p#$Zz%(Rb;)16BExl!IQDtM42;wBqzH|S>NTQ6${J+HQ6 zA2&0@Q3aR7-Rz)LnsL4(vckl8K9H#rz$j%*O?>YhagLyRd zU_`3ROBV(4QkLyZn|uyXuYlxpNq%>`!xox$RbX^8Q!$ceFXoTQU;Ylbh`|3X(>IiU zG0x#SMM%aT*9c@5ARl>)vKV6V4}Um1PcWBh=#9$McufuK7g$L>mosp7TfQ#{K*-wT9gD#_HNZ=dgr6AvVW3>fuTuz(5k>S?c;Mt#QqSWQquKv-1} zZ)G>8qhPgrRwKQ2Dp|O4IcVoV^)F*Voe^WPrE_b1NY;Rl`vDKsh$gMI%=G-GA_w=ADUHR<`pSo8~3p~4+pQ|o7uxkP5~U4<+@ zfuIfsUgIAW+yPQ|@UEF5Ws!{+f6;DPtbzoVG-3RySF=ykA-rPzh=)@vR-VsaLB)H} z{1^7!Q~xxN?lBr(ts!G`JIA{&m&+NXCy}VthJ&qka>b$XfTHRe zN6z+xgd|OYM()TgjC*FpY<-qzW689jkJl?GQKE1p90t;Fz?$0gJ5q!C)@?c68}|l! zfoT()5CMo2l+cg~;7PmY6XI#SagkcWb(T77Js#iYMYnFEpuocsgEJV~Zi!L_KBdrCR)~-s51{}isX>j;=jx~+$8|^&-HF_CYX29 zj)#1c4H-VJGh9!8#*#@m0j=JBQB>{!=|o9}(*V6Up=dnMOK&S}DIOfmq`znEnZ$)# zl=2;*E9-@`KVB9~2U*nhif#2r& zyiksCsdaTsjDwL&vuz=G)MOlxi}G6dYB!9eF=RqwxT7$47AdJI#%5-)s@bpQTCD8u zkmW^*2#w`Zjm)v98#?mqZS?{10P;LD4r6pm7duPZLo;SkfzBA&^lXUK{^aTfs@Il1 zG}77mCj}YVPSt0LEZ&8PIV#0y?x>)F@5kZUDP*DAHs5u+)?CMh*3?%JE3!C(k~Fr7 z$bI)Gg~jFaS4Z1CbIIA#L*L=3-<+>gkxOdZn+SLm&9l97 z3nX0mVDO0$-lRw!e1c$B=IK#}rjbPJjdzF_x)jM5y*NkQR(md+`#!7^m@rh!L|F<$ z{=xla!b*ad=Srr=P>dobw#mJykTNG3Z(K#}&NF7_yIiIm^eyslz@o9@hsj42FzUfB z8ppV;>VlJQ$BW}uCms6*OJ=LvY?wT4BbhVNbT3`9cC^;tsD=TrpL15?LJ<%1r*^NQ zq^OZ_ikqe{Sl9an!gyoZtl~uV*8(NFs}ZC>`&YSS3Cb`Cy=0$own*H!MaGHm@?%a2 zHR4-#^`rfWt|>F|P-$B$bQp?@oaxF!<>~EeI-PSkk1NGBrNQJFPREp|Ed=L(s2ys9 z=3KQUe;%sB1+bUU)6*P!F_vAvSE1d{w#?UYJbNhmyOv7%<^78X;SxI*hWeZ{-;*6I z$Bcq(4{>bH>R;E7HS{k@IpGy#k>;$&<>P97^J4j4;?4T8=a-8Dznn30{E~q zlALNUd}CiuPr+$CdO=#%AGl4xg`ETuTHlN}F6X1H6&JWP^(7aWBB$yl)exuhJMeLX zEm@i0rkh5uJX3~aG(pz2KZ~HBQ^iBLSW3H7)gg8VZRE;P_#A%>8HjH?}AeIwtOGmAPagH zVMMDz{aWTZ5Pm0kyJ_nXrkb2yngFv6lN~yJzj8kr1Oii?75u)ku@?lXlVk-UceJbB zZaQcFGp(^iD{gSG+cGYTzCv4>shZ5xhfH(Ix+?ir>;kYU(h^QD!F2KE4H25nXLGpm@H6p05AM(+N;pMuYWNOpK_v}+G^|$ zAiLc19Z}m{QXI7$;OhCZ_lIK<;>RK$Nu(PY_Eqz;tOG;O=j|(~k5D^bJ1N0Zf{)y3 z35#cy7we@ku#6*SD^i&erEz>i8UVV9|8uWoufr4SfeZ^2UjfC)4ZOyzT#(QtPpKgg zVk3NY^QN9qj>)uX4G$CDOysakO#IqElx?%&zjj=T}zX(b5TfEca=7^czJ!V9uBiX-auDXcmFxAa}wN zC-C%-3oP0(^{jC4;-OL=WWKV^z;l&?FN)(@>5xz_cfu6NfW_;fHT;ohj;GZG+8)3B zi=wOvL<3Rot=zkevemyqi_;UQ16F;%4PEL|7F4fYZaWO~=BIy6<$2TiG_|ev_P}cG zU@@^X^(17pf3y}#2!B-& zQifJx$fclTIvK3>&8C&xiEVhrNOPju$=FdSB%djY2Z8N7r2DIQyh(TPBlefv*p9+u zZEt*in$oX2>U&Gf3c|S$ugf3>{PxVM@1hl5oR6m+U1Al}_nX&U_8zl%rNfotSL%WL z8~^DIM}|_R26D+^1^k|8CjAVl?}m79#U?6C-J<@P?hVSltL^NYrThAY?;XU}z6*Ok zCo}nOiQ70Z1ruiWIj_~@zq<5^VNSWqfbWModsi?8Z`(_ucZEXp0FIx4)R`FToJsI= zD-!RW3)V4TDOJNY;4JtT_g!Y0b*`E}z^QC34?t{l?HTBQW8H@NEb}{M|DRhlFAY-Q z6y$03FuVEY6VO0>Qi`vzufJMqy77F)eBNDhW3eb^E8^ImlthG zfn9q=CnkLJp3C2A#jVffO5u8N_q@Y^X*Bor(xDQGKcAsraZ-h(}T#ij}4DHKH3PW)<21>uy`H{NQs{KBo!bXFRP z0;5@vlWrsoXETG9F3aK#y_G**>}sE{x;IhOt;~22nbd0Zb#x|lZ(|IXpU(GnfzHbtxNX~tjn8;+EQo1-@O+DT~YrQXzvk@ngmX2)HIrjO4VR{*s=3i!} zHH1o8=!Fdgc{4=*i$)*_OIieyx1vDk>~sv<-F6tG)02ULcGAQfy1ec{?2`erJk`Te zz9RRink1R~r0AXQHAOt~%|kJo0NRWAZwR{+5pf@7j&+XQHLY7H!52|{7#Vzm0fVP` zp(s!lD(U_5v>D3e2Nbg(zknO{g)!AcPLAmmWV86Nk%bAar_A5YZ9U^vpTHyVzHFjC z)F0;+&dQ9p6&H>^36fImRtl8GZV^f3PCuEInx~li-YV4FMjoElSM7Y}2-JqFmo}Mv zf64GBiF%NoIM&qcEyyxw70Zx)|mDe2BCM>wm8WNxJD{>DcTBSrx0q@&AM$AdWdTkY{&BWcC%LH5vNhG_ z(~4SG@aJeO@o=m!3ufyf?B3<@pNWCG=2dBcj|r8}ne`s%-acyB-ltly2eja$B2xDh zq&`FzeWK)Fr5hj^+)mw0Ln?2+vq3jVzqWd{npnY65W%L@tsg@X>-f>OC5#~2YS31M z;azbWcPfiQBqf;Yp($U?%CsMNAZvCSj0u3Sm8V z|2sJ4t)xB1EOnWxG9@i85bp2O_b+oD+}X&5FQ6;?6`~gN}i2ur;BB`pzh4NuU}C?wE(pfg4)j)JFn$ zqC4#+KxkfwgjS%fq;tzRQTKN9^gLrJP>+klV9$y$x;HA-_+o+Bb@k9i=lR$Bz?`R@SS=8!xwy^4n0Xu& zIWs6BPq<6_**^CUTBwa3w$>+#i7boN^V8EJ;l#C>O-(FXuV4yi zT*8Wu@Xasg%P^5;Pi~d~fOOIK7(&fhW@Ok$lxR{A6Bbp>eP7YT5CX-4-2EU|R3!~3 zzSN?mwA-fCE93HAM2Zq7*$E7#33VgI+n*%3d8)u^#Y0sw^+yC!8s+`!(vNv}MzVBO z$4uD-#442pbH%r$AGsO!n@tV!j`HpIMdZB}e{8M!FDIvu7$^$NU<$y?!;`|akSPiT z5JZ1@EkY29d!9P2A*?wm8E4W>voCHn{xjKIejKe4N`m%4j!$Bm<;6@3*US5rTfh{9 zf0g<+#@e1K51!lMz^l>M2^1cr6B&5jfBd(d$W2E)<;V@QowWXn^p^t^wG>UclqbFJ z94r4^X{r3PxM$489_UGZT7SVe)cer6v$Rr2l|hn1HQ7}W=@EuE4#IKz?#OfR_n`;| zIb_5SNEcW2uhYA{HW)ElE8pm-Bj}crLBE2WHhfV27Ge1O zlhQsm`toC;LdfczMw5#ED&Mk2*Ib<&azCCXT0M_uRjR2s@L~2vEM6ZPm&f<;JY=7BN4oMi#uFVh( z{#;-MaHtSw9|q!ZB`_$m#DSHG-a9FIlb6n~LCZLokZQ@>{G9H*%5ybd^>G;@9gECmg9YTPTPah7fSk|VI+;9@2Fou z9K4RF?z7IVn@-+;6?mRXcF6PHcvIkhr)6bJFFdy2e)~bcXw5bAyI>sk@ZFS#^(#Vr zk1nsHA|^_JBX=OR=8(Xr(WJn$$=b*DN8I~3aNtSKGB19n&S~JAc2@Or@ok{1spYC( z7mFEVS5{+W>H!~4X{RW{*xlhg2wo=m>41I}=}9UcEs-XU2U!PRNTnZLszQjT;$*o5 zT1t0~(LfSutT|sNVS!!i|IzhM!Il19u<(v;PHfw@?MyVWC)UI})s_*J|vG;91y;iSYtK-)Zk$nwRJdEX*uVCYpZq@n<%g979v$7Y*GE>=$zzVfihIyx1KRXhZ^&j&`c0s zQ%D*w2U(=M-|*QSxCK`N?;FBaKVhyWa@Z{oI+IZ^d)$0jSOSD>)x*lZGdGNnhr9oqq8LY>KUrW$2<}FV?+IX=jWEyy?>Ga|2aPY(ByynW*F~>lobDb4^+}9{ zdJ&m;pu4`5t@xqUg-n|)zh)>_uB9YwuHkzbdJEx{s%IHBiPB^Q6>{hFPw?+*iP-9C z-=T2T64~Ftb7F+&OUgKhshm5@*H-ZG6xZaPF*^}xG?UW^b=3+pL5vQ6pTW`rN5|7s z0yPIvMgLemAsj0nZ80*#KzW{9%NWroUB1=P~2lTGmbB|6%Pbh zfFCPRm?NBcEbSLD!7O$3NsFjPThBkGNvi-~xbKU{5@Q->afySlAsXy7ENb^|Om#*{ zs@XQILejhxPgJm3#1qPQ4s2*23{!Cf-UmaRd7bSi{HgFh3ss&_KK{I@Zh0_1HxaRu z=cz>Q64u6sLob64&UFakDr-wiHR+2E&X<=h2`|UT)*Pf^g7770Q1tT-t>b+&)69>q zyr_$!3Mi{y4F0I7NeNPzB6IB-Nsqn~gvo`m42v*%M8jDy%!6M@hLJx?503@&RY83f znG+@8)A2lRS#bISy3Xw*paE8Uo4FT7U)KCcT#q#vAVC@)H$R0U7VOT;_5t5@GsFym zd%vyieyOZo35Hte=y8?d%k>g!&fI0<|M`e>R{c31sA$u~ZlZTU$jCwX)I5n;0HisA zx}|o=yTy=%RIOs(p{WXX!J5@}x!JE!7omA3hX)UaWOPPFrIgu6NS)l)*X)bC#G*y{ zM?6R67i;$5{H{AJ)Vp@JtGsw#R~>dX`pUD+h2BLbj#v{BW9i>kD{3p9_0~(e;%@7ZJ)7?+*ptp9z$G3ky zVXl@iXW$#H8u|?8*s%tS@3RP5`>?9lNb{#PnBmQTLy$)2qnxH99rN9?Vi+zTGX%;mm@omw+uB6yAKm$twggqMi=ZfPX8~qQkG*PShYu;3Ez}9Jdg)(7|j!lSM*8 zrz2j4TgZorMYP@48ZUQRJ)a0&AQExKTtOI}4R1sKr}BVQeli?>GSc9U-p;O8{lI

NA(cN1-bRwX9+%BN4K1d5g%eB+g04utr!=`V6 zwkANT^n3BED4yKKk=`RaD$AO9HuQtA-(g|ozmKL0lO+dgsVR+ zwKG{tiq#kDx7c(jIos|=o*zb+QUXBBlm~HgX%7)EI-$Udb4(xMz*3VpmeQ;of@KirvW=1SH5p7=D|M z1@an)ePdOg??+W^&&vP$^e4W=>bk}6Oob}fSHlPj^qYbyg6Bd?U02<>2v!~iqbj_s z-C3_+UBaMoAcoRT9CbZaQ>feyDL%#3lebuFLL4sVa%4tSe8@LZ{X@e` z=D6BurStuvauxP3k_IQ5*fkxU+qr7YJ=m_Q_~pA0|4Q498QW#EN=NMDOa0u?bAF(| zpF4a>z0eS4#qej0(3wlBd;JK1>VdDt z)pX(E75>Y5C#e|We06bH+n>xrYkzz4j$kF^Wn%DD&G_u9p7+HNzbSDADzS6Qzy<&D zl}Pr7EQt%I22*X#!L(wf$m3vn&&i)6yPv{g`7lZwTJ$c@|%Br5qaLIQ6XoK+{TxYhd#w~LjX_p zkU8rxt(uS;%tW6*%rA9`%ZAMkjCKtt(m1qrZs_&9Z?hrs$&HPZ9f%7gd|pIgF25`G zST&ZL(VZoG-gt;00#SgACEjB8bALU#`WYVNlVr0HfHgnoQi-ghN8Z@N+z`W|r9HRz zeNldmnI7=B+*VUhZ`tCFzp*x|k;Lc^z@C=);yh_xS{-8OZN-wKJQS8pQZB;FT??NF zwc4^}5xRm7X8-Q6ZHsb}hSz*35^Gao4el8Yp9~uiYd*mx0QrvtJ*H!O4rQs;mKezx zM^J28^@6h_@Lu|K8g61J0;uBr!gwz3==MbWVU^4YNE2~(0B5iSYlUBngc>{Ifoj*5 z9z*e2`@Z>ib@7tdvBTAKV?{RVNp_9Ovga?Ue+hV&GimoC4= zmi36vbBZ8%y?~JEwd3+uA?szDl5!*SgXhH3jD3jh`L5wek|(CStE?>N2=xlH;YuRJ zE2h3bo-#AoqPsPtb?+=J-u2>r@5fi*?~wP8U7rDsxlr$Y(N@#6UxG!-@Dc+rtiClv zeiL;EA{o1>WuMaH$_&NzIN>w5eA%f7P5G z2FaEte2suQFeLCm_4siGCo)&u_%N-hN6Mv&FOpH)P%H2Lem7b1G*kZ2^!ZW${$^Rn z#Stm{5BHuhT<&A!4Jd`_>MHBRH`fITi$f;kR;3D=BU=gybN;6|#}H0(rdh1}#>Ie` zB6K}_uAKwZ4BKT_Yq|5qeNpJW+1mfZWkKj2uS+_8)JmvgdCaI!35omcX2#Qd`^M9I zw?WkV^&BjiIamy`Eil8lrRJMgk&aiCnBqT#`r!g{AZ=EZ2%U}~G)^+$%Z|{zNkfS` z@(E(zmL^FD7OM=8lFC3~V8A`Ho-NYEkvLR}2AlPpq*C3A+x^g%^ftv%ELL={)3Z2z zH1956mxJhOHukto^L^e2t~ZBuceEj1)d#pk-|cMaivYV1Y3J&w<24SchkhFS4Pq-t zuYe0>)epSz=;G|c_8=TOs`(^m);S7f^)bkpB9g!avoP`IH6p6Dqj_5X>aOMG!zZxm zKETosGrQ}Y zL^kYWHb_Z*j#7B<#2`c81N)Q$jfQ`|9a(tzyKfAKWFi(z?gzgu`j(i{^b4NI936mi zVuUcfS9)$BY9<`d9;ej){x#Yr&*mT&S5zdnq zmcuGEDj3@-Sms1G9O@KFsKh1P~SU=MRCR>3ZkRn7_6X}CvXQNG(UO9&T@LK zF7<0KawfH+?g|QoP}OZ0?D3RHVyeasfq3)k49>ZyCYOn3zAHt-4^%GUX^IDZKg`iM z75x2@Q%=o3>6zyg5%6{iP))VWJk0W#6*$i*!EYqa;)mh8MDX8&arU~rlrdvS@2uJt zLdD{By_w}1Vx9j&weJ+Hrq(qWNn~%2^c)Z9+(mSmgey+K>s3VK|ABXNswrOiPzWJT z%>>rhFMCtNir$BI%%i@%O+3SPsGi`9h2#f&EMq0lDJfs(IS) zq5c7E?{vyWv13e-V8_ISaX9rM;NK~?Ern6tZgnx(+o{?**PBp;TcL2xfz0ggrk1b) z_26cjjfOv#>K1=&G(<6H)fVF5u!s+@w9G07i(11?(GzbPBp^|<919N^;$*}H=dGaZ zJ#(9sh3{2frFgHPKEF7XN>O_yvo$tyRB|xw(?DVr!YX<41{Z_XOPjv`z~!k zOZ7hT_1>+>^Gk5;ar-2$yP=dvgvHeQfIF(+DIy2G4Z~jDxd=l((e+VGI$$!dR%;7!EYM zi=8u}CNWWX5iKl1ba+Yma6kO;)!@(M6Z)vh6F1Gp8V(lh=dXS{0o!wvDatx=Unv$l z%sfwWtAZf*oq>8!IF276!I+4?M~bEN(CQ3=JD}CmZ9Nha$Lpj8oF=-rWAR~zCmVO} zXYk!I=5iuQQ?ws0=lOw0V;XO8KH352z7Ay>w83RmEP@EyPT2ueyeQQ<4cex>vbNIj zu71MP!C88}p>+Lr9H2&4*7a_kCu~q0TX{K0_|oBmjk(8NCFcso0+^Rm&t$kYpq0)@ zo_|fb?a8G~qwIpa3h|#FsXO?i6>@Y9nQeU>vFoRTcnds8(G8#WH=6V|+DmZ0a|t0; z(1oJviY)nCgC{Pry(v&8--;m`C>8zNqe34&3j&Jc-2-My$rcveu z2=$CnVa#SHbY5(S9loo>7$rXPBZ6SJZfobRkf9WgJgu{XaR(O7ij`#-dElhwR=mRc zUK2g^dUb1qx%awFy4W!+79@lN!cG0uHk``Kwav_{@*6gVb^%GQNVjZ1!Ug zOvKCRD|vcX>XrMUAfMt;uMmS+#M*LcY`$R}V=>6QB9>*VV*MSU?-O z-}1gM{K)sAT%S+*@Yum808RQHZGJUtQoL#*6M;gMZ!Q=s$CVyAN(>$60P6j-ks zLV$v5pn|9_GOXDs@!LT1=M#?J>nu#;%QlRbDZ-7E#hSZ?pV?{3M|AZ2-q6EhS4Pv~ zX6oNFqs;JbaNKQp;j_*6oLCxI6&P7mM%Q&-1P$sy`W8_USh32IXt9uB>Bn=@O2~Kd z^1SG}&6?e$l^P!@@tK1C8(Fn?F~V zN9)`l;LHAzGX{^8?W2}pfx`|k*|Sk2d?Qu-6sy@3hf{w?0}*(1uAw~yZV^Zw_9j^L zETd)>Dr%H~U|Z2c1BJ1#MRZl;`Sp!`swDGT$dct1SC`A$O!pMuW-2Nh&n7C1)>{qg z(mk}#p;gr?_q9@?nF*r@BRhLk`V#LCZ|Ju4RsVpWp#)u(Vi-;;Vq1MqM>BB@c>ZcHqS z>5|gOo*q(nP1|xi1*z4N<^Ca5iZ~oOudKm;)?*3&O&}3+kqbgeg`F}$xsfzLV#Weo zqc`G#>9hkZ8e--FZDD|>V7$IAU}K#Mxi>)TR}o!+Z|1+$|%R`@s=b z3BN>H6OgFOw&^@CiH9a?!$GExXW$Mg67ec&facg|#{O@Ye1L4_3&9+@`xNcrOec^$+3V{L@eZdDNYd;w(AnP{_%2_NFia}Hz5DbXo{v0A>W5pb-7;G{?` zbQP9y6A}R*j?++i^~t8%xeGyECkIaEL=|odE;}M*h6%SEsBRZ)yy<(-hGrdy!H#7= z8T=K(?!~F-JGD(-YH9}`r5SK0O`q?$KN0|{HpNZjOYXwH?gZht__IUz1cwUyUj#h2 z%k$t`^%zh>e#6Rilv?Jc-_Cb2ehHzvGct^P%sVeL!(94RnBN>M2tPcRDEKpZv1Z-jP&jobsY}blK--q@2z1?Kp)JZEg zy2CDBt^Cs*IW>o=DKgU;MKSE&Hzz>W zm0T8K71u6NHtmGEn;G{Iw@}mbb0k2f+hSy!;|IgmDC{I+w^XtEyK7KMd_>CS2rQ7| zb_y>RocCm~i(5CmyNpO@7ZuK8-xf6VJ7rlM!&>>EzQXjGdzJDciD#(59)-jPpS@>% z9bMNqbk%N?jv{P$+{PPawy+YPkfU1h-u0r>z9l^W9eoe=JKr2UHh9VKcJ48=#LYNdsFzUXUwk`I8|0xSB*?5S- z3HxwU#W;Mb$=7WspSOH|zjk#lzu+*GYZYEt>^HI!**YoY$ijH?tL`QnDaTQx zOHDn42IkM~&6Rook4!9cw9Bh-!+$=`4Mc>-@w}>)KAe)(*5L^@~AM zzEOQs%4jn-UBC$qGL&>uU6x zy!$-}+}aLN2tFt+Fh;t0_p?#G? z!D0nvXhY9apPiXme`~1>(fQOrL|go6A4g2JF3o>7(j2X`*2wW^YG!rN*bfdU%lcx6 zZ{`OBM!#=U$|U`)zq)|zW+g6*Q3j6N&=FEiy|Prw-5iGBsQ;s(k_~y{#0#0m>g{(L z>o*`sdh#%Aoye}cDH`JH4+?eVF`23Pxr;+I7|XaKn4Ge*@d@@qxqBMER05nNbv@a% zLLMAfO`X6J*v$7N({{z%H~m*7dhCL9EmlLS;)1J;h0?*#D|jB?mX6^ztuIy~(y zGaVx=^?CvFJb?0O5BNF1QgMbDX1k4bul8^Wmk*qu1t(HFf0{A=>wf(*L+2-ycg z2HhN|cfH3-q?O%(&@#W@+kY3XASxd=s5=f(G>%;71!YEDMZZ_tM~{|Xb700iia(~U z*ijH2%aXzDdtsmQ)Vt!c&Gn){hetwa(KXVZq<*PkTYap^VV=^GH>S%^eo@cI4sZDY z)!NL|!H1XQ+ubjjtxqlI2IMa&NV)l?mi0Mb43B=jLkjZ)Kt(Qf zHwj>T<8D!8b%>4Nel0e^#E7&~7-dRON54k!5eN8DfL4?`tbwLA4H?)e!HgJRcHLKK_N3tvoL{ z2D|*x5iIpDrd|wn&I15_u~Eui1+9zVre`U%kSyQm?2o|6ITl;OoN9ua%_$xNx-1I; zj~Wl;Q&d(0lgOP89vr0L2aB29DupxlLJiQHh&{Aq=L+MRBk{|Ngk8GH)nrNm%WGtL z)C+2)YJ<)CoAzytc{+Rqt>L^q*u;;b3l-c5U4$(3Fg!X~OfqSzopzp&R1w>Pg^-*c z+CT|dGG(vdW4vFsv<;-Gbh;-LV;NS(55O)K?*?X<|Bguz%5dLzA_||9h1Ja-(fH=T zv>qB+u7utZD)gM{Q2!!kny6y1?gO3%IB2&7(gvUg2=CC}<)iH~%%Xf9c`2F2h5V@| zt%wk&Ca&us#0_Amzx1VaA*G(ELWA1+#*xQkiFDvZmYs0P`ioh_`ur=#Qc}O|&OB=>P+ z>+^!uUzA+tD&q__@z-|UOwtU9MsE4zu;!6UQO^hq-ri!G(X|ql^$Uhk-{!@YQaJc?i5Mbc9cw|D?-*Uq{ z@8wjyDhtM0w7;DLT2NHp*Wh0lzcfe^a6c_Lh3-YaxngY!b?CtV>80XgIgfyVFgL%V zo~I#w?Cuso@OP#%RNv3EFY`A!K>?lugz7r>O!R3px4V2Oc_mRmNN1#gre7I;rhDL| z>fvwa;|sNC>I)X+@788%F%e%)_peEdU)4l0gWnsyH^aQXQ2tec^ZX!MRC9_!kiefRHgR}{>RL3Ejn`86TNJwYQw@{*#9w=ns53HeIv8Z})ovRoBuvzJ1p^)a6-z#PlUWTE34r zu%;y-yBG@yY)i$ZV{&P44RD9=eP4g&Z0k_#i$%s$nfYFxg0{CjjIg5jwEu0`($49x zdGYj5z9trPOB^aYdm+oZ;_FL}WJ>UM#r$W;D-APk5m9NT3Tm;YAd4$A81|A%MgWs! zBMF8|<1cqKj7r{vqPFq_z-~g#!gkOvOsO5|_3ZCd#%c^yKgjBBtN43x0(B{`$m3bB z+VqYbMKA-~t1Fa71!0^93auh3Nn~7QZ!l@Tg-76^nL$ZKSTSlruEKVPpzpOnYZPdo zHVux5y$^*L-Qx##D_QfGM&+Ot@{=l};7pa-j!GzpJV4!8YwEgxQTS10tq`hH|{xytZo8oanNM&P+bzn(%rCIHvR_xbx*Ntmq^6q!VZ!a31zn+Q2l z_qt?@%)$NZ_40S1btC9)fvQ#E&2@Y_!BHFp5u|bXDNlrV6EQo30cI}C1)fL5XN(?PBvA4Fd< zvpWT4mt4C}wQ3^;Qo|YYC~iWKa?>7$5Wnx*%@`J+`wp}{rmVO{mq3QMI>sB^POx0Q z9NG$MX>78F3LMI|zX=u?keoP0+hVpdV|fQIBxfSpB>`>EEGZ7Zz zC77^f{)bOxv$qEx#H8A@k4JWo!A_5-?aZVhcM~sMychFML*#y5AvxxT}_%e+qO z4b^6kyTAWwX#!DEy2qj@>CHel#aa{z!uXz{nqL{WGP*C6^Dud2+A*GZ!VIM9*_-H= zv$>D2I>h%Nk4|a*$Cekz+$`H;Rmzxdewu@&dpEtJNDZh%i%q+_!-RtO< z?d{fencIy+{67tUo)mZ0r!Y&Clp&G?YGD#uP-uWlApKL20PIdeoi}}4=2|>O4;H>CkQ^#8p>J;<{~8-KQi*ZCrN1#9&#qFg9}wU^O#KJ!Tq_< zyj&vO2qu}_GY4Y zv*Ecv1(t1dBMorT%gdq(*;dL2(ZV#(=lO$mB7w;O<$nGd?4Z1D*}D38I1fz%PwLQ zRtrFKeiIDWu|tNDl~lV83@U!yLe{Ao!;r`A(nHCScIVj^ll!)lur(cg*p@fs)g0 zt=P28o;*=__r5r625HdR)&fHu5>M$9B}uek(C+s~tyYXQhSpdSFZ|>Zg!A1s!;iQf zhDgbPA>FU3-1P;&s~YXz@gp;s-YF(lto(%L;cNfW@qBpn>m|RraEjt%GQtshx;gry zU$ZM#h7JD1|EEzdSi9mOkrN4oRR4tDmo8lh0MhW@jGqAt^xLfU41G;6Km5BIzDCsi z{Obe_A%i8H<$AE?qYJHft^1$npJ-p9O}FkJ0!i1rvs8iYBzmLND1hGzs|8+rq$dQF z;JSZK-(A*Z4Ysz%gp<*nuifT;+8GnEA2{8+FI?#N{oXpM^1T@dHFz(wZ@N@i>KIq0 z&yTJNb6?bpvh%)=T*i06K0Eh_Y;@#`TK=Yswvq&|2xa~Gk3mLt4l42w6GrP?*O$oe zGdV;sqG%ye8E8Yc4^GwWj=~mKud#+Gckijh_kFt~{O}Apw5H2_^QSphmvW?4+|Nqb zV6pJc16*Rk&ecpG=iK=E*(KvgX7_g6yi%zQadtDWUo#V1uJ32da0;i9sT;Z1{V^W- zbru+@1X;YAH6c2U>q-PU$}9l771P5 zL_EX@V(;;%1bg`*))PLgdU+D=vN6_lUG6JG3sarE+0tx#j1Fo)BBon}$@Dd6BojDd z`SdfMCInQC_3?kL*yja}=_A9g$lCI$2~bm#D{*`&!c@<0bgxQoN9;Scc6JEGk7t9; z+RKgWCtUB_!pOkza|A%k3E+p@*j{~5W<8BL6Lnp$h%=$xKRSzIMa6gxam2|Z`b7#+f3btvNUk~citJLtBI;&1ktk~IcxNkVB?O>RC>p2SNr?c9}?yuOR(BrVfiGYpEducSx(a=X1no?8W-BT1faIzPX zxqO~qZ`A|5LhyxU`CrX(Om71<^Xk|8uWg9&q#1b6qW(3m`oH-6;$K{)88jJZQVKsa zs{5Jjee^d2esI9x=d*MPB%3ufV5Y?0dg#P(y{3}6>+j>nYe&c9$0b;<)ES3}Mx|Qs z^%bZAEHCuqKzQ|R@?+#j=O2jh9dS(&Oc6MDr+-J_^pFz660q0*4E=l{80Mcis;S45ql!AHX}n{A*1YfT2sTX?^s8zMH8#eDr0ON`vwgN z!?T{^=Amwp{b7P1B6ZjNd;|+}-a1PMHjAm0GBAxJ4+L;l1-j&tZ)Y9_QvTRbM<$I` zc-}_~$ADsqjt+&A3vZ!ItS3dnyw+_Cv!;JpHy~inU#^cJ&b;3T(=(V@8s9HlZ#Nw1 zM^!IT6sdQHPAEoH$|`RJ%TpQTbz#*W%2p>Fr}hy>nm@-B%056todAes3ZkHLa{sdj zLU2uRT@AqX^}||@WGJH(LIe}}Tk!Wu`Xi~K6=W(!gPegd@%CV<{FFeN`aH8d>h9qH z8jid>pE&0HCu9{uLT>|@ybR8dTOeE}dz`$9dM`Z~?nE8MHCcR^4K}F5QyQ_imYZmF zh$~@?MSBBm{KSN2OZ=YQ(3&8`Da?kJto`>d2_gY>ntd918r+*_q;3O}sl{k^GFn#^ zG9xPJ7bGmnwd0HNw9URot0rqsLv zhujkpS)&Q+b@cqK7Vc?)7Z}vqv03m8zm{n*wI+Ooycpi9&=<-Jl$x_vxUK)_>yYqV zZ?fUMA>B4tmY>|xXvblMXB9kR*dx5>u8NDJYIyW;nWKu;_GE+`+`W~<%ibm=v9Va; z-1%~K7PkC{x`8*h#kbwz2y+#hSSZ9C78?ov&T#9bG-}?hf8~M0c}*@>0}W+p)lT+78lb8?XG{z%zkMD(&!*; z0LMzQfhcOAyyXOmAG)y=I7}>uKd%RZ3fMUl^JPOWT8!*>OX8c?D;sw97 zT7yVQcf@y+g2Z_jU!2!6^assVwn=&@5*sI{>4SpBbb7ST>IXEI-A2V*FxojQM*p}mIXwa1bu;fpY6C%@>%MGYH z`lO;KIa&oLqc817mw?nZWG!}xhKx@jm6RVquLeqlKKwz19uR zJtkj81%r#0<<&%J zAASW@@@2Gt%$Cm>-rT>m3A_6rd8?H!QWmCD47JyV;S|nMCodh^kHXQfL@mCu<%fA!u|EE znEoF7S(o{B$oX$#UEPy)Ev&?FPqV^poUS>D8hytrgin&+Mtu z)~C)unnhgWuxe-8%j@0Pi&bi3##LhBu_Xs#+7-L{u)*n05MBLG`vUV@9umLpLRs(a z0XXmTaRv)d9+JVeAqWMhbExR`=bY@E`K?KI3Im+L0mDPq#Y~TkCr=&>;sN%C6G>6| z6{{u=JgWo%pXQW8DHz>9Cl^l`MU1htg=8=YmVwuk)jwYuq679D12EdY!OlVMIF-d% z%hI)an=0-ov!$YBAOoO{=@XETQ?-8du;`3zYvuU%8^2_RMTT>uK%~VmtgbS6PDVEB zo(szH%-syK6?!Tb4=2I;%v0>3h;x0L=pMP24WUQELKbG>zSINrxGr zI?=5{KBsEBlZ{ZajD8rm%7PFrC-fyR*iw>e{Yw#T;`lQ9AkJu#ZPG($^;F7$8KE z*p+x$U~+*;Jg2f;iU%pRNheR4tr>Ne>H0vPi#3H(Wo1OBE3i%*{ar(S4S3dEy)=zmr$94m#R*26Ch$JXL?5pV4cDHJ}ibULir}x@SzXhW%sIa9E3p7J` zb`i*Vf3x9}IXNZmmCMb%y8B9$$qMahS7K)-Z^I2N`quvpf^}sP+yE_-6D3E!-z@CX8FplNeLi{^jNIsc$29QyctR#G)QSX_% z8a({p`T6--tfJD$gi=QumuYxWIiJfvf8Gkeh8PG;#&{K@o$CT*X2P9^eS1NzD~n5IylG}4KgbyXVysQCAmCTKcCG0_Ps6LMmg#9eHjpJb8j*+v@>B# zBy21^*3sh=v|!f9t0|1KLNTCO*%`PfrNc@6^LzA<(RBq}|o!?w@tlgDPA>* zpalrRfT`wuH~4a}mWenbmyA>JAx&U*5Q{~0QxF!5m0Wz&4MTS{kVheHLQ370llkK$ zD$l`HsTg1dpKEY{R0LxrN|JC;DW5U|rvfXws3CO-PU>3K3eqM(k9QB+MC(-J;5v6b zuq!?~PezhP<}+4;u?Ukw*Hxf=)%6Gcs+%Z@3mgywNMV=MT-ljE{#)$DdpsEAZ*GT5;4DUh1{x=ASa&;riXE26i>82+q1% zuE`ogY2(4WzDb@xXT$`_h6F~3gfVn|UQj}K8hZ7Lxv#0HjUy6_$APfR>s-kXr>*mN z+J9?8BE;@v-+CAJs&!lBZ+y|~V;c;j9Jjr5!lst97FdY?kgVg6)DnX zTD#n;Pd;FQ^t3p>z7z(}t%&ljn;j)t{Pm6{lu4c1;*TS9@gwLwN-@39>`$8hUKSPA zRm;(~;CVKU_4Q^5Q2^D>4I0v&M=(_~K15y9nJ!DhjIJrHr?)#V6w_^O=2>D#8UIgf zWWw-PuXzg#i?f}9C@xms?Mo?`ysZ1YH?Z4x*)VMLn*6y--;FQQjQy&Gl)EN%sNWq0 zcpR7RQ5Qv8eKt8Rm&c6%W6A7YdD@~{uS>ERl>Gm>o}FhmT9mp9zPixibZuXHDH1so zJIl8x!Qfaj^IU;Eg) zY}M`N7+o)$c6h|9mN+h{cBF_V9|>rvSV0_lW*g*{q@Ur1+CnB0hJd_YnCL3br4V_& zK6=C)Csk>gO~{|E{!R9mpMz)bn`ypI?^(XCkDW<)XL&G4IK{$g_c8F|7}zp+(GRsjcgI?y~M4Tv1tbIL*MU00wWtEf-P#udE8-EY>$4dsqh zCHvvR;PiX0>&J)15mTEc+JB(~Ti-7JEw|LS)CX;b`IoK^WpkZ<8Ht70M{1IM=e3#& z?Ed7(=A9ekxmh|OC6y|^d|k>YutHa07vpEi0-9c@U~swp~&h zCZHyubrwgS1`k}PpN4S6_G{vrj9&Y}zNtl1=VQ68D^WH-qX^-%Y@ikQF&^M|q(~w+ zbvN1ddV%MkQZoRk*XFS*gG3rhZPAr!OLQNzaF{~@Gp?`1N=w&l#%zS=`w*X|HkmeU zMBoLfIkeE0He7T*UXc_1*k{M9qMmrVwKs&zSY>48uCHH$cd33_@0s&RSrU>Do88nT zs-nVoEI`?qZi$n+MO}gssIRfE&3bj8@q%>$=X3<}0{kOzst46A2BhvC2Ft>!Vm1No zYhYP3oJek`n}?XOBaH24h1h6E&}E >vAmW_74!zN8rM28mn1g7}LAYKnt)mXG5s zbSb2&x8r+NUSUXeDY~wXOPvnCKhq)qxOJG~c=eko7L=56J~zkjI=6*F0Np1}Ynar1 zx2#!~5*%OjO@~n~4>cGrHcy5?L33|eF%&Q4B3{hm&OLzXl&?dbkFYf}bUD&ZJZ-6J zR$2>?*U#VZ%|%=XCNCAmU~0&_d7|ZmdYxvn+5_9aq+INx-_VxIlV#|#^m`ywifbxI zvi_3)0_}STL4TWxqR1TgB0vEwkBKo&!I>Xqfp-QWlK5|0koe%koAd%L`o))K!-g%( zb>QLM%F)DJmA9K1NXRT2HVjjI#OB6JxVM zmE6MAw9o!WR|M^27DSx0hVWQ&UZgQZ@2gHF|4Z zLggD}%(LOJ6z>B{!c)u*^Yz@4sUKar|I@om_rBSI*cl4z^L-0t>?~EUgyRen0ocnH zm7b4fYoBvfTWm@7723THPB>_EHzC|^tx%Q~7__q!yIC`A_#VskKC#N>L3i5w6Z&xQ zo6khE2-T+CMZX@p1L_H-V*`Z(If-|dfOs$0%|C9~b#S-(wiJdaEiJl->ml2RWopVc zcemcoclQ~4JEqmeLi2Ryv*on3vJO|L-VLAq_Kvri#LSMlzah7bV_~Rq(sNBONS)q0 z7xpLWcnT--tgwwhPBwX0P2^yMG-cAe)@Kx-#5npZsTEx$j?#smxSHgh{f=?p+6eYb zcwNR+jqR|*2g2@fZ+*+h&iPE$vC4;^5bRQWZX(p@zoA72qx`|o6L2Ot&fn6wsFbZ7 z6m#D><{PKs#t@6cSlaOGrl%QJXc@n9fH_pJa>=D9rkI6!;eR_CPCb9%%E1OZN7HmE z5t*V*k&(#V?lqW5nu{7j=GEJ7JUkRt$JSZ0j`v9?vJg~~Qj70H@Y>K=GZP5?5`{9A z=IF(9tz@)LETyw0?^{9rw>U_k?%ZV|W~*Kl5ZS3T{~LlWxAQ>m+>0LlNbpzg9?!#a z0t`w4*1Xk70s2*ZUvV;$$z<(wX=1?SswrMEdsJ&@id8VRW)d{nXlkmm`r!|cD zyY~MO^;J=Ab>X%N?k+7-g1Z!Vf|TO!UMTMF5TLjecXuh);_mKV+$rvEC;z?U-jk>O zl0C9_)>@y;`OV2$oR)#B90O zDz&rb% zHND5X$IASu$6qKv(*RPi^^b;V^upX2h<~%!I_CJrC33sdq+lHLNesh?dKZ~00--T( zTWeuOHAC;83uU|je7yB#o3rRgh2|0x92ey_Dg20I?%^wAh9|V32bNMr@SH2Oj0@w( z!%B)m94M5$8KWa~zXf02(BB;uJO;ohrysjadE%*bJ{>VGMx|cihtW2En$A z_ddxlo{)*iV)S`N9)5d{aV8#xR}!&*>%oxTb7NVV6|S+QfOA)cA%9{BqNfAB|Ozic9d>zNjywK$B4@p zKQz;?tm^|9J8Hn(9u zNO4`U$+Sh=Pc*6cE-{YC8k9>KtgxrKr2b3h<<4xjqkX#W=bO)<@WYPli%^mcE_%FB z-7h5y2i&&bSukq6!DD(T*jxHWQ)-TLW;FX#e(5!xezf)?zLe&Xyq<<#of;oI)HgS< zh-geqER=vK07h{24}@r7w>DTOewI@9flZBFa#Bj>D@evON(L8u=Eq0B^9qWCX9%6! z*a{9-KVG(w`+&muB+Q&BHtH{qL1|*E=Pgl}*)T9%c&o}N?03gaWoN}fZ9puEK(V$e zkqqxH!fFK%96!M0g7A^aD3sF<4icsSPsS+1AMLzHh;doaVwD>azOPXRY+9=EZd`FY z$M8&DPNXn|laC#R04)b;_lz?CPPt%30JKaBfMYXE zmUeFU3y;SS2#}+e!Lmb7ISy7p$jF#RNBM^xaWP2#whyDa+Emh~acb=HC2es*pcZC_ zu&;`^{Cn_w$NupBw#-i9eR6Q;mhb+bOe-qi(r1Ag$(5Eu;h8TOjxXRv%(-b*`ARq4 zvp|=!9^ultM-E{ZhHn?kN9DfW79g1yRFWw*!Jp*3_IUyq4~L&^H=M5yxt>>bBQ`wa zVm&^c7qMUk4?oY~5GmsddQXQz$8_UNCz+$6LKD3>I0xLxP!3TXF0DZHF{n6{RGw)A zDr7TSd#+LSA2Gq-F<{^(_o$^9G2_23QJ6R_BkP2#{W4;{!h)crm3IK$Ug+cv2u(UQ z;W3UxyR{0~qcs&KBO&EGS8cC-now59g9TGEY@10_!E?J&YCZbIq&rz) zTQ~n(m#6%0JmrMt{>!lNyVF`nM}VcOZJ!%auNz8$ryIY$$lEleJ(%)}krnUsWjl3z zVz-hlVs`J_ivS-MH7V{`vS4{iRV<$H$Ph3Jn>FzX7=^0{2T?0T4yq=5e2p8Pe?p*< zq2@Ge05WRmxVhI`HlF=jsb7JP^okl5gm~hk=LRSBvM%gSmCECNwXtGAl?s)fWm{GN zz?u|%aU&q^C!CAbHyHWbkE#s@aux#ctj5BZV?&0GfT#43G$5oEv>6_HfvTbp#`!Dp z`lDHXLP)mYG~^7e^m}PF_e{~tIwm1$*s^#+NuQmk?#V(!GgOzxdiUfJ9zrK~ovZxj zghqRb!Tt1oaG~yLM)Wa)K0tj?$0XNV<(UwP+7^!oJ$kcfjI5caQfNK}Yu9>i(t`C+ z;g+iu3v(ae^Cv-z09#oqmDBzV8$bdaqz@DkA^^AK?Fe zyGLhy5kNGW+H3l`mjviBr;}vjUnO3um-HDY*=#MOCV-ff$%tR4?&SiD$O(P{*RF5x zg7{Ahxliyg5AFk-kEo`!coFtsLzf2}ujN5YAecTgbQVouQ5nwQIA`H6$a*#_0v0d4 z#M@gp%9jIPVjLjB46WL5$@QZ!PZ=#2T>~+E4YrSP{z)9XAlOpH;SVg8?O2N@ah42| zP~V%*s5KF=dZr5+wgKjSUdy!Nx1vK)F0=Nvg+#Irzziam9SI38D|{mV!0pA}el>EN ze^}>s^Rs=Qtxl~s+1iDdM%~A;t8XT`@~iX*MYP6QSoGnj3@?gZ$8!>D3otri5&I^6 zd&BlR7V*k)T5{ZYgozfmuRqMsev)lzzY&TPj=7J6(Dlbi;+4AoCuMQ*`03fpe4LEB zuQ}SagAr?f#lWU9N7x%faM%kgsr+6KQd+>gWHA2vW5ROT9nPqDv5tIG8D7QKUY=_)i;Ter|Oj zx^7J|KN%VQbHXr?d~1;(RU5QHSFC2j8=Smje)^AglRlJ#Y{L|tNblFqSAU4)xAAV; z>566?Eb3`tgq&#!tl2i&`gWV$7RmBb=l;2We5l>$ueih0~d$^58qf(KLWlEuIme4f3C?$$a~&Lr#pY^3T7C( z(T)g}1y85#i&Z$X2P*vsT=9|}Sl?g-hsLya)6%Ue}HH^-D{R# zqOQbMvsY8c7gfGK{TLW*P6fYPT?T)(7bp3Bl(t(Bmj-4nC!s4#l$bmwFM=~-{NL_H zVKnAenBVtB$pP+@p8ml0ryahR3n^zsCWv?x{Z~SC2n7?~+Dm0v4pV@XCqRY|mu$DK zt3^4bLm_^SP^w4aphU`8xaeVLdQzM;?8d)pEm3q7c?y>|?U58>?)1AO3nrfim=7g5 z2N+pq19K4^VzPm3QKB>@hy7(-v+((W%@xa-7~3Y5;)NIpQY*5~iW@{hV8$7&KEx~+ z_U+*F%qKPB;-tZQl1H?0=_N#oQ%Zr41sk%pH-BWm5_v7kL?*6ni%T^C;^F3cs`Dmeu!<>NqPYU|v zXlSA+Opk@X5^iZzog*yr9}N!$zP#W;E}--wR$)f!zB8mAD%TeCo1dPT@T;6RVfYn( zQuTir=Fp~zmLN2~r6c6qt+fREC(`&?OWOMQw4GBPeV8zzl1^qGs{Q1Z{knTtkmV1P zVNC7>FEM-{`zB3aRNrPde=l5Hi78y`-ucqA-uV6F6atYzIy4x;JrYRZ z##FU=*?IoKq^3}4UeY(dArMw~Gd)O#QU&XP)2s_*rrSA!Os!6lh{Ct#7|Om?exvr1 zt!W+u>Y{cXd1qIMadU43<^w1f8i&OwQOK09?a~o*>OJ7t+#sb(Is1Hf`Qm%Cx%qFj z#ac7P${SY2Atp|i%=2vC3ETR76P_A zYTnkU(Of

UZpC2Zt=_*7xvoKqigS0|7BBpQwKQrddzi(C@Bt6vq%&*JWJy6)_th z=6bCeQ_gfiCQ>C3jCXY4yt`+`4F{syknI(BrBJxca(4>Dv_?qBh{4z{ECVy;SE)(h zTjI$#V{a?fMrf!Y`{m=iTjJy?5-D3Cvr9S3{jvpGaq-PQ4ME#Lz??cWLHPGLSoec^ zj{?5k&Pl}L>VUAB*To@5&tj8tOozsvl$sCEZ}&R(Fdpmv_7vaFF^Q zhi&uh;*Se2)~u2EGb1Ee`mz0A)>QIanMoXhh6R8km`H@d0(1x#xH(|dOMw%kr|P}# zeTBUlRoof0j~?Vqq}U;+hHbyZP$zdR=79L3Q<-AUUW$7?v;58fY#|Y>f6a20iAkhv zd31k|HPB;GhcT1zyL0K@0YP5K$BQ@V>$$-WiopJ9Ms5L*%b1l!c0Xr4;r=AakN>ht z#zEH8tj18~R2D*LT6y|^(n=Be$?I>D1y{8SiI>^of39}x#~F)pCBB|7pXj{+NpGOI zzk-=w?&ni|s?UbwM>_u>iY#fj^pP6=I#-#|c;SiTBLSUXF&7N~`hv0GEG*d#gHmSR znPXWsOLhulwW{1K+(AzcD!)3TZMb|hzgst76wL1K9H$T%$rAQoP-u7QA24{2L(j)g z(&Y~t$E=TKt*^*%n>>mit8)1`1s}lu3C<1fnxuwpvfaDg)V-?y#PDq+Z9#p!m6yxrXiXC>11ZTZp7CpLd&>R)FfVE^la-D|&`3bHpRBbHVni$ur; zfyrZ8uGW~U;E=R>603e#7H0;}GB5MmwmO@yRBfz&Kj5Ac3DjdAzEKdEo1Zc$N9_`; zkdEnNJb`GL#xOwC@Ht&a(0%OUItPDS*G$ztMF0fg^WBE6jfAzoSeH!~ax8Fqfh8&j zGruzJJFxuZGp!9r*285kq&W71Q3`J+U4x6==q14eSbEL$;e4r7|14f?*B|(z@0iJ} zor2kbR@>z@g!>0j1bZWbM90U@@<(95Y1}uEKKqZ%F^q`zLNY?!n`1cryiUqY5^F|N zY@UAC?+jTCqlrO} zR;XXD`%R4Zwf_wV3WZA=}++BOwS33_2%kc^FA`p*MgPFpB=7?x1fUxqci zj;J-J`B7hh6RXJWaRVy-0HxTC2Ha#0m=tx)eh8d=eZIe336jK1hutxmIaA8)(u{rM z$2k2qEcnn)aGi60q2PA@_UgbXDN{|ZAp7g%><}6L@`UYlOa#aU$Zw%3yJpk zGT)2C#Xfr*qU!?b?O<7`Iq^^b@3_^kLkI@`{RkJNi8e|Hf$rIay7zy+(m3V9VkCol zDf+mN`7(vgZEXvVE*E${w%*=C+Ml~gpUpG}7{C4dM!H&cm>Gh%Mbq0wv?!6nbA`2@Vd5 zFFm<{Ik%t1V*uC`51f#Ah!7pjOLzWwH~FMEZW+erVqt9l$VmAlR~jJBMZP1;?b{`b zLYJ(-N0Aizwe~&IR$s-Ah|;c?5t}NNFW$&gW#RJrvdeN(DVm|DRddjM_{~iXshPdP=iJroe9@NcS>eGlB7>o3S0Ue-JI* z^dq1)3arbF6;Q!zJ1I2}bwcIj!g!)`E}Yo*azN**^j|0gN;(ENs{`}v7CspA{9`Fm z#T+^KB;!%+xgexgIm$!;Lcuz^8&_YrX_FQ(lLIHp*%v@2@&=?}J6yy@JZIckOLvV@ z7Ud&I5~W&|Z^+1hoJTC3V>1X>{hJ>0(6h$ud=rX&yO_Y}*cLQD(}ZGz`^BEJva&zn z@+I!>2cCn5edJgQrg{(QgZ-nyYB$(i90mHTHgk9;%FKf6sFcr3(TiNY}lPl z#1!l|e1BTJ!|X02%>92_0Ph!=56b$D@7JAgn$J0Jv;I!Z4wix5Qk^T?1$@Pdf=3DJ z&_YkB+oy=o?Ww7eUMLC!RigiVWXa%NbYXOS$MMs_*D_RPq>uOKYmFH^_7q_5OG36o zVb}rMfeXi3#QctXZEu*os7ZLc#)}*OrE3E=37w^c+W344OG`q|6duwrhW7Vb->XO3 zzMqxBiPiF*1|D0#UmtGCR>qF2`LUAt{FildxowR<9SY>w4DN|VEW4BuvjuYP#S{Wb zxEIpzQhqL;6eup7u8)(qdOI&wv1*uwKymMnSYqk$CEvY;8ohZI| z=k#VUPvE5?>j{p@6m7jjxsUPq<&X0WFDY&2P9nO?mn$AZLn((ujsGwo@ZlduHy>Wp z*84phJqYdIG_C5IFI5m*wAqK(ThBbP;XKj+1y53yYHn#2P>l@tw5Gs;MJ6I;!d1={u4)_*!xUbN zgILzYO|#^`f*ZN>QB)dJ47rv)%r+mTV!QGZY_HZc+lG6u6At~eZ>Gk7Q;U!L+77Z2 zKu1qpkkXhxPL>ju1g)^nGmpsPyb7>~GY?tXWyPNm)BO$?c1P^dsTEOP~`u% z92O^qh56Q3qA1NpE@p@1Q%Gje_evy*hs^7*KYL-6k65b`dT-WPuWfi8QlX%Kz{tRd zfT02l3FNRDGW_EQrP8aIhjDv9=w|xFF%Au)pV7RQ_L^!;mUW>s)xucwqiG5L*?v-o zqOR}jLamNF#RZ!QxTsPv0qHozLq)?oAqSkS4sB zscn{bT1_t7E5)D*I|B+@Ipt>ZMX$@f*{Ge5DpUx`V{-lZBD<0W zbESR!n;R)CSajafuI@Xb!dh*LA^YjX_PVi;fpgr`0gNfI-B{g*$2@(2|# zH`>GrE1ZUiI|BmJJ#o-vF)3HapwXS@Z(UupSuP=KJUO;6Z)nqidMtXo5z3P=or7>h zgj21ziqm$O-P#$qQ;s-ww0pS))b|V8zD1T4L)8Xn6t;f&yvZTFtEFy4n}l#h{awRS znEkwRq<;mZLHR>|Y4~yr?rxZh8e4fvcSGH**dj3>jS#E#QQ0w=>)8*5Jan`DLWV zSI^)984QE$q0Ti3%W&Xfs9ac?+)+d74*tGTG$|Im#A$42X#3hHqd68UdEy)GMMEw4 zAC@%`No`0hjgB@=<*yH!>Mv5V^clI{5U#5g&J6uO;V%rEabQrTcJ%nW_o<+@159A3 zXjr;l;;jAn+F`Kt)$bGI&=A69SJ@PfG1|=;khNy(i)Zmc zxUZQ#wG+MVxGMSzi0IIk_U7K>w99AG8qqeuj~O94kc=|8NQwLPzLX4DU5G-p_4+HB zt68}F`w;~>J%PeZCy}9+Y@R~XfzZzu9F_0s+Vq-w#2Q4k&dwaX8l6~g4**rpY=9AU z+f_$=4BwsV>j`XEJU=Eall<=V&-U2@%@s|kMnKlz6+8R1L4C!>B;m8ll#V-+pKF|x z0j1^odNWm?*kMOF)H7KxCj22RMH^dE*Q)}H8+pw;DqMcEgPb!(2NC&Ty8gd^wRLrL zeh&}7Re8pJ6-iWcu0HU2F>xjfd&(O-*%{1h{&^`472ysj9lUO8>r)%FVb0`2=m@K@x7V0ZH}hj0WZQzsibdKZx#vQ;UfzE# z)eBT$=>4kw^Y?HXS-{(Cz@R0*R?~3h4`X4;LCML@>IdOGgo~mCAiy%8JZJ(H#x9#~ zyqYGR1pU;5M#+-L#9brZEyd$ma@fvbrFOiMecu#ccf)3B#A}xO@+(zkrV}ig_*|$2 z@dz4rs4aqOWm=gnI6~A%X#9`rQfd|yM1Sidi}g5~5&vCJ(Y= z`mac)kL9%HTPjvlUOA~Soh}}*OjaA64CkajH>AB^X&(M$l;A7 z%WATDm9PP&KZ*-`f~3Wsf(T<`6I|Yxh!hK|2i=^UP%MO?!1pHv!W6b~Sx6~cV?gbj zx7Mee%qix_-kBE(92C+M6$KHpWZJlDM7Qq_fF)KSX{qEt%OCYFSw&X5Hws4RaP}(=Zt8!g)w|(pPbi#*q zz+Y?$jghy6tKL>2<J9+&^v;#N-Rzub7Mw$^=q|j0_9q%^d&$?vj7R- zn?f2JqY-)R*cSm$B`dfk?TeGAcx#^fsNsq963xVi};YXbj2xAOxS7S@pnVhO+_ zw;;{KrUt-+`bcTSOJ1Bum&DjAU-%9~g zY_VjGaWAFv+ep56&MnH_|Dg9MX=Hd`-IS?#=LDXhD;jzB!gNj8VTJMcW^ zKa@6$MjtovsssaWWN7;&ZOf)(-oU&=CJ(W^0o#-2lY= z{D%>Ce@%D2A;W#q#zCY;bej)snIu=`Bz=N)j3AqMg!HImUx|1V`5H01XCVypY_NZiKdssM-EPZ8uUcEI$QVkzuWobD~Ku9RyTm^JnP(8OG8$4gX zQuJESX{6oDT#Vds{~R4{X#iEBQ`;TF>Jt;GtAQaMtF@Dz7Aq<4Q!d?jRS=r7=Enws zN58{nVF;75 z{-X1p3nQHfQ`s!2w=c7HV)aF6(g2k-~$Ssj2Bghr8yjP9?!I zb?kRIc1jHA2?+cUDh!(Q0Ee(}@&})ot)Cw=K1(rOnNMEcNB=}blM;&pGTZ2YaR@BV z>swk{%B?q2em(hh5}$WO`82C7q-)Q!mQ(DsYuT@A8MJM*I>LfgLKb7?tRQn*LJbZJ zi#s>t`>u3PlEkoTBma_lA@cI*fQ-_Oh&>Q1{N|LM#XW*enk=l`PI3#H)>>elg;*UW z6V+Z5ef*1y7Wqn;2c-^z;H;Ur7DcQVyHX8?Oxv+)VhBa9MTnDd(Yi}`6Yo*xsK*KH zzM`Q>=3-G)zw=gMoP>bG;3GX!|0syzy5XQIGQiMHdi|fGL-)vR7jjh_Dq$jOS9=jU z#n%8jTI_jPAzQe79hh)B8e^EwSkQUbWlPHwoqb(YZtly!M|Vlp4*NZKe7w9g+s4ch z`trxr4_wO)CMG6McPH9X{4Aqosu@tpfR2#Q0lSdO>#^JBp2vO{iGJN{p9zv*)(x*3 z5IUy--@;8kmzpK#Tsc%H4!t(;yo29>wiHtT}%Hq`mX9r(9UDRa@<`c$QP zy0C1Nb$i22=dih+DH`^YVDi`fTMN&c<&O|r$fr5W4ik8{h0|;_>5Hgs`U`|hBh44~ zG&?&OCSP7M+g=vbGo?adfF7JYx6+2rIji29l4s34%sgx9iNtnN;AM=G+yLG{6i%N2 z>e6XIJ6}rZZ*~_xRMQ=6c9eFBl#qqJmu4o&40SUvFS9vq?WEi-8jxE%sH3D_+dao7 zIr}C(^C-R7t&?8}zxduEbk)s7#jY9Ks|?_C`-##>OsQ9!9q~Oc?~U458`k0gBJed= z6%E65BQ}hJ^_BD6HU*&%oWt=d1s)r-=p*H=J~dEMR7%baP{Ry(%@d}H8RZ0gnBhXt zwM1ALWA8}@FA4%mKB~EAjx2Uxf4eZ1!w*qqDF1YtkjMv-Nf>g_!DjiM3I8PVsWQmi z?8pHiN;*Xfulb9l0{cw68&AP$M?+$Dp&*VQ1YAtci}#WVWfq;Gi?ofL!bfP=CXH5d z!pKElDx8A_TlM%-7RFzP*nM&2-Z2yXreG=SkVDO?njw>-&p|$Bur}U*K4aAb|G3dLnL+3lz9O;^LK-Y?7%Va2 zZ?}zS2x=RQzJp_{=HOye5c72fow?3Y{FzvtBdJX~{&&^>#WV>oE$7~k0Vwm^?`nz% z)3{`B33iwD!{$=~pwdl=h!W&vo0L;qE-GiuuLy_j$7a%P?*vj3x7*zzmG){4zfejz z*j+3YSkNbo84Xm{{b(ue+l8p@J6uH(1_xa2tPxTjR}KrDu5Z8YC9e?e?yt<23le!L z*OH>LVaAr4N?m}}(E%T|GV6GLG8-RE%8RvFsZ=Sjh&SRjgvl=s->AtH=YhOYP-+iq zvVN#&-TK`HQusN2Y%?oQ|VgBj`zk-tILIP36z1yj;E84r*;{ON5NXuO7=a?mi zsd!#t5T+j&ZJQ~Of@QW-0B}5IWteSr%zKGNt<2%Ef<1RU%UmY`g=7g&2s7hLW=L4b zZWtvm%u0s14qZi$a4uZkm>S2?4o61$zc28Q{-*1zWdz^+C30b|R1qOiK+`j*R3()^ zgA>R!{@TA4>yW-fAo8zsdx1C5TkS(CjY9d<5S(N?B3SjH9|Y=Ao;1UJ}) z`Y%+Bzw|ZU4IotsNYc@1Qjh6Mm?fS^6XxOSJqiy{daC5b->soTp9gFrx6J0*>$$Sc z7uXWljMf%$0oh{XEdd{aO3KJyL@bKAl;^`N^Oj#AQY)Zb)?D1YumUF~h(FRB8~jm3 zi>NO!BV2$j4$&jjTW4Qf78EhbA|rd5zSl(YfNBwGp`qRDQCB7Be!9W&xw~BcLxQn! zvRNwis8R|BYanr?NmWjaA9cR=P3f`MZ^ocW;7U5wyICil92=kMdx0ljYh!(AbN_aq zUwt>wdhtV8dGy^9GlNYQp{s3F$Mab$1O7bh#p7Jr!(7{%RjAeeXv5EdQmY2=?MQ=X zwjG+psl0$1dKd%$u!*BZf)L@DA4w~X?uWs~hSI_YFNIGn!QzTa+kpc9@FN$2f)CuH z31st+Ne}ftQ4f?QX}<%&z2|#7sd^(~Tvf z1~hum(wC)=Hq1MgHakn}?vMFHQ~j!^OsTC7L@oT@WyqP|IopeqIac`GA5ts>9|a1lpk1fvAU5YdIG-X8si(MNEg=<)&3_2sm8&SX(=#5WvDLPHcC4NOHplUE1)vO%%mPU zJFgr72kh$psp6_8sW8l*e({lbwW8#WjuzEk+&*PJ$#^>7&&_^I-GvcEo%#Hc@RkYc zWSS+BXg7{Z6VE1}RvtIVxt|%{t*r$ZKS4YdiM*A#535@;r#?@10o%vc#9?U16iOWa(ch zSf*$(DwPS~8oD`NtqaGGl>@B}!(u^LhMhlpisIR_1Z$dho+kDNl~T&~@ppUKt}z3h z@0EKZR&`0om~p<0R(}ZlosthKsEO%kk9jTc34pF|vPfv-sV*45r2ve_fnH4P+v@HS zFhPAhbtA_%GS2-`yA|hOm=|)%KD_RAaqX!c(aM=!TbZHX`Gm=g>k7Sg`$r=+!)h47 zoMB(3lX#8&%Ux94EF|Afp(P__4=zzQhc`Pu!~Qfb!|p7O^XC2g z%u+nUaBf-}SLR#;6QxNc`{!CDB{O(}h>5SN?4Oh4yW=XHzTGf@Q~AKyk-T3jKb4e< z9(u?Ix!isS3RCY&DTdzMiy^9+N7lL4%OC*Yl8ng$cV}Ho;%9OydQwc)0=u7DHDBwrGJ{{kV7OtcbfPXU0HKR=T|ikh{XnzD0( z#J+++qf01_ZSim*c+-9Bip_hNtHR%RUPA5mj-P?ybT+LS(&hR+1T9}|@^%{9s1pS+ zElZG(>{TS-iT-L9PsssdakT%*%ZT@sV&}>Vb%AFFRpCf~Er3A?+2d(6nGcI_!v$1K zh3No1SJ4A?;)Y%>F-_GLY{P+zw#^1G#~B`gF(`WPP}@)kO&jJopE zE{-8&zNTd+=+c1bfWW>{4d7WQXIgBiZ9TgE!8Z?i&w7xLV7W3a_ zN76!wtvxr2#B?W+;uQMPqP>^0wzh^=&Zrh{D%yObe}oU6L{dA|Ve_N9zoe09;~fR^ z^!T6BX^H9z>w)$QOEdjRJLsGl!?Sw&m|ohNAPYVZe?J|%j)wQ=rBq!|!Xq}yeKoP$ z%sOE6Edt{aHgYB#HviTidvLGjGqS}^jugg){#>4Nr&>xd9^GO?|A)D6Lu4I!xKv%# zl?iXPs@J(oUf*Ss4TeOx>{_ED zHpT(rT{W@svf8(Ekc(>;15n0cA=(4d_RLCQ>lDsS6Jp_ZG|iwjbX2cE9dF%&8&bPi z)$_8HfLRB}r}eH&I|!vxEcz&Bb7I~WcdZ$KI`IsdF-A7s74mYNYM(+E4kum2RG2YD zV;8Qg)z`oS`C^vrvH~hf%#G5gPLDN9Zpi?P+_C(|_@k=5S`G6n9X9m`a}es1a1-Rz zkrB14Q*!!KBtWW3pC#zj$#v;XgErDS+JW5o2eW&iDx5y-R`!e*mE`@ad~a5=T8s2k zdb)bEyR3Ckpa}igU?EOZY7cv~QbK>F9ciq}(GOb)6;V+af9}6lGKjt+CYb&gM> zp{@|PqnySPXVGD+y-N#?#`Ug9na4?$FhC_mj5lx*R^cjyzEnj3`7ZiLORBS z)OpAKry-52pR;oah%Uc^5=*VGb+kbd>PSzbwsSPa#*8FJD}&%U4c^B0*_zXF0@(Z` z#~QSNQt?o)yufen&^u0!k60;jfktR2X*^hBreRk#b(yaCuzwko1?aS0PRSd8QT(js zx3y5c+IRYMhGe?qI`uk-)-E31C5z!+ zDdj);+rQ#usGo;HL-5&+TCDQU#&t1*c%>;-F4SR~ zIp9%wO%aCk^)d`34?ZpU`>Yi=AZ-CO-S_7pULIh@&JfndPS@ca2!MCYOsvK$o9uXntc=XPUNW(5t33{5!(Mmw5^%ITdPnQ}s1^}srS?4VRH)r^CVxD=$ zF&jRU-uvtpebgin1B&sb2gO1VJP1ByAqM3a1R!4iExJX2=sx}s7SZt3-D%!BO8`** z8q?xx#ETb+mKrpf4XY|ndR!_$SMSM;kdGm!n(_;2#jgSy>P-!yRp0Me-dq~Kt_B`m zg0P-+-$v?ut9a2?u$nrw_UonbtW<64>P>NLTl;0)I)IaS#KO$76%21U>L_>D(<9g+ zI7x3Y_rn&CnYnW5Z7PHio^G9*4c^)?mM_2o*b(O3b`WRhgfrs(b?^e-k7x$gBcmrU zk5tEBU|HazXSyIcH(9q#fW@9Oe0Tah{$KU^q#y%)J}2qFeB!LW7s2*?6c(QRW>7b` zVAO=|_uBUar*`C4T>gAxzvO=y(_Fs0d+ty{+!~h{(e+%tZ8*59=5ZT8I|R@eo&h+| z8%afKw3qVtOAqnymyy=r4xVBJA)g1Oa-wLT9D4LBpki!v<0XnRcTX#(9}JZY9!^>J zk`_0TWe@BU|Mc>JcId%)vr7aEG0i76nZh#+?s_?KCcg9lHaI7Z-L*)~-IHMKj~Q4W zdt?3to6@ZrSOY+ll@3a57!HMqxt-|1s zeF(_I04pLql@K{*ZENuRfTTqI@fG_D>NJRS+BiyOiJmHE=!?H`h>l4C$<#1aJv225 zHgySfcaMN#*e3sGM+;4^6CtX`GA61e$8Eh+&l(88aK z77{e(z*3UpCY3^jiG;BKyRQ4- z{+Wlce3ETF#Py=*?zrd*=a*5IM>{suqJgpW*X7WvlQh$$lOwZ2v(E<&mY>lxXA%#R zE_Nv$(N~T9HpL|S($KR%3xz6w(;n8E!;^@#R#$+erUTctQhyXi`OALqa+$WAbP@E} zwT4{*nQ7a7Oz78uo9Etqn$5?8hsFdG102%Yn+jvbnes8426w z0z|Q_J{dmI($L_6(=*fiMkf=a6r;X*kMMRV@NB^ss6PF?5f3<*K0H0`N5#Xtf(iRg z7>Q3((B~sr9W!!~^sSjaiZb~d^!w@z5%DTnSy@)q0=`*OS9Qeu34NnV)Cq`|tY$v` z`{JO8$OZFkPsxtQaeJ%wx1;Je8R6@{lbi5}y5tYs{ajHpR(#oP8!{Gj8gCl2_@fn> zISUD>*Q>{h&HoTNqRwqR-QxM%ZvSf-?ix`dUzSo@p)`h5u;U9waEuE-L%Q zY3&qYV>skp%rC=4wl13^GbMhG5CE+nvgssMP*SoBx*+pM47f0A6WqH3@{SBTLE(qg z0cH+q03D~2SYIY4)hVn5)(&|AU4_nP^iM~m(N!8ySRL4uhLs`YT4 zk%D!Ci4gi#_RjIlI*c@h6h^dS)sO&T$lkcDW-M1jaix+Kg6FnND}oe?>jIA~5BQ-# zA6+R59a4-NFA%$V7!-fv_m6=e<*>vAmiM$O3H%l25J>TjadmgDJW6kPBnkT;QJ@{Q zjkKfz^C*UMq=KY%>5+)zt1GYl0S4!}c-<2DI|PD+@0 zYp0vSg@2q0=7$c9Rj?;>-ZdSNV9XIxe1t2D0yj@R8*3Igheeffq(wOPtQISuOAmWd z@^K_FeP$ex2}1soB_FG`UFJLGB+;=sl7yA;u3ml#G_i1)FYct(zSYWl}HUW&}zd}fR-o2*f)V}#>@tniV^XFbpVq6H6Yeid!}hK>CFw(905 zbYIPUcJ@q;)U|A8D$x_(`?qALMa^lK(jYTZD$rz2=pE;2-R<(_3zFoR$*3RCg1i3G?~Na`4&?RG?mXW99Q#^^ zpBGy z$4`9|os7(7N{DxT&%JZn&L{4NrwhK;9$aG?gs_8X7X?np`wVguPy*+wCBB9a7!IuC z2P(tmcf8$Jr@-gG)M*&ZRjb+G&q2+P<@iqWUK8gz&gM3Nle8fws%dThJh&$wE)t{z#M z$6m`$Nl#DC<`AFpbA)@Ib;u{N;da$pnDLG8N4EK^78zyMvMc9YjV3l??sN28Zen6| zuE*BN^VaRKpQDu2NCu@#jvd)_*|lQni7T`jK0X%^UAmj0yI7nX6n3o(yWhZR5NJuy ztcEC^*RY>R5>Th;uc)$|J6Vbjl0&^Aab!%Bc?6{9;Z34|6XAEcKF0-%U8_T`QJqZj zP`c@p;J)l2OHq>(5a{#9RmOnEBaX6kg0If!_c*(nIJ;;xaC31JlUT({@dQrcniBm4 zb5&fx94wfHr*`>HH)a5{)D&R(oN9TgFzWCxSIhp6Zb>P-`O9A5zLgBfu{H&vGBxJX zD71q{ik(ZmCvs)?NYxc^U_m|)&lVo9FNN|6(1E-hH7+IlQk+&YSNpcfTvHwVtA>xl*G84 z@#t>q!j{y#^5H4p4 z^V=LFB$p zs=kvuj7MRh>WKKrb``xA(I=;4Ru!B0P^DuIYU6d23L+=2)P)1zj9 zC{FTOY~kQ`yy4+tdF7Q?<@MKJ#~1u@e90e|-~H|lwe4-~a_rbK`OxowNdEAT{}@2h zdv$H>wp2he3Q|o3254V=@kM#=x#wgA(hHP6Vj1q#Ae_1cDJ5>*yZf%YUJUYZ;bwT5j# zU7o#w}&dGO==_ z3}tVWLju8E-uLE+!)XuC{Lmx7y>{`lKAohl%^A)Q!7A{Mu0}#Vu#&z zk^$h-*MZaSU^@@3O7|gz1!isrKo%5(V`s7hwV;=2Vj`hR&xa>wmWO zE(NrRTijCcZ^Wr_os?9mx(0etGG*EEfcN||!`@*;^a?cHDV?Al~*}*yo z_v-Im>vM--93{)hw5Va717?Qv7yLFfR)!z3l5~Fj-M)^}Ncy6F9u3M%@*{XA`#==e zD?L3uvJ*fQiwt=kDc{xt46h`Pmpt#XSXxG~{CQm}4#Ucsa(P&oxy+|rIpxAOqQS~2 zmq)2EOBKqWpZz(O+p;Df%l-zn|jmH1EpQJzAE3Po5V5QBde>3UqP?Kor3T8XJ@5`hFTA{;7EmaJ-wX z2#AXGIpP@X4-|Ug`@adHC=m6~L-MHyKcxaMX&$K@HI|pT(eML$Uv(f#`5G+nRy~O* zPWG1u2X%qZtq{*Y|AM>#i!K5MVJ!+Cee#nJ$nCe^5sF1N0Ab|*&6i((Szi9tujQ?` z-qK@M`IYk4TW`g7z9U-PGW1Wq^X^%Modq%p9VC!0xcA-<%18gxM-}8MXzPH!aB|{8 zkbiLX?F0!F756$Y^I-5Ywh2-qil}Jb*1XSrMju?NWF4K(I==tV^XYK@e(%g*jM~H( zbu|yr;TzI!baU}ts!XO~nC0o`!RydJlD{tKqkfjyuY&ni%Z<=juC7X=PrIdsd-?KZ zIe+fFPCnf7$*p;9?QM8S;RT*)ily`Y7zKQe%@#Od?Xan&;I;BQNK7ZtAH;!?+ZsjS zW?aU{#^vpw|6G3eqkogpp&?nqf-{A!zlSHLqQ>c3>3q+(2in~+wi;y%LlIEt%L0ZrP-A&M?jV*ZuS|G^;Kx}TY zOJG~T7iBhCl|oqsK;Rr$eA{Yds-?F zr%BeW;i0;Md304;q4XO&oS~m713)$d$*d$4hl5uDosz(GQrL>fQ|i*N#MxBrU2{R+ z$c}i3ZqEZ*lxU(MX$?qE2`@=N@(Nr0bW0s2xyXqmCAq){AXL<~gjnI!#%p&+TFEs& zJ-A?8buRk=Zr5=t-x{pye}c4CA_0AaLINmK2E(G697c1&{o=x+>cpCxBN#QUV9udK z{it_$SiVcK$G@(cVWHu)f(yO2aB~^cm}V~h7|wcwbp`W0<1ySf!96)#5a!3*2iIYJ zJz8~sCO^<2d2K)x=Y9jCPM$oOClSTu8$MIKGI&|C>=N;|`rIg14vW|cUn>7n^l=Ty7m9P|&S7o0ET>MLk|Rg4u4K0l23x5-eHto>-7r&jd-Voe4zIu0qc%ReSK={~O=Rk&EiY*=*TFx*UezicdPx;kA5Wo_HX|N>8MG3kzSQsZ@E?OzyITK zZ_`HSvD9hk6=?v<_~heH$P+ZU~MdUHd*co)%pb%I3M%D5n&`4yW0qJDPo(`v<;pSc#- z!s(iyxqeu|wJi>6_yKKo_3IX`hs6o&9I*fL5P_(3+7GF}j6f8X;p_fk*4gT9e6WlI zf6Ldr=@#?z!{h7iaDZS0EgOVy+FWGfUeN}E7SyXmH-W8qV`?uy^Nd`2;z=3DHs5JT z`cSg616%D{07#e_uj`lb`XdmuaiTt#rB{Bpep-g>I-w70PL*p9&)pznD>t}4fjk`8 zLBNCMMNH6N+5p@f#;IaPQEb2R6fgxFCXEVc(?ADnbGEy&G>$FbE9+vu>RFw@j2P2B2-@=0M5qCvo>RJsY# z)le@Jx571nK1w>_R9k6-t}41M*k0ERNiYIY1ezT16bzai71|1RYoS5aF%Af%;p-B% z1!AKjT5U?!al+pE3M7`;UN|K$S&!|D$p%PI1tM0KnY!dFP%j;X*6w)`0REx9*8(7m z6(SG?o7X16Sk;suj*`0zl!}6=J}u|*ZoHUq+*j2Yo#qC_kdHd2kOef6aP`wRa$$_G zj~9K$X{h_LhT)y%5x6#Ind_z67nk9@4r;?|)))2D7uCR@^)n!92*5NgbyW@w4CI}n zQ;ZK`zMJ4kG#|?&>c5FBHLB&a*>szYzuR=~cK)m{dBt*Q3xFtm;IuG{TZ~7>Z*w({ zKc0#uvN47*tEZ*6`(nusvY*vItfTSJ+%TZbg~wNo#WBuF55`=U!)t<%ba_upAc~e_ z{<`a~(?gRqVUX6+n_ukiEeE#3f9q3zTl1N2Z9XJTPt2okmL+VTqw-IljQ7K*eke~p^^|Uv$wF#?5>6lg z#3$tT+iusy?C|U~oIL*dpZ{6@_y7056)fuO>y!7s_q}r8hwqacZn!~ThA5$ATm63i zv!BY(e)gPv;GPdCSasWNx8b<&4lUDIrGts|1z?ks8$6VBTLV1UaTOWmlGS_2Ib_sz zM(T(nvi^lHP+{4FpqJZC_@b11_}KtZ&%B@feD#?N8hm4e-dsP-zsBQK`E7nB%jClu zf2Hy(>>8EA#iSNtIr6HLE8UqzhlEl}sIsg)8E@paU5OyxnAWM+2 z8DH&#KByaTHeN6EB`u?G)yc@>buybhg`!Xnwu7m`ycZh1h8PpK#U%i&&_e1bQ@<)1 ze3_#ziZx16W$R@gQTWi4?3|?5&Pr$E45WuL_+pcRPo6hW&q-J!L}

&htbRe43 z7xgxA`<*Hi2WZ8U_cGAcL;xy9{Y;d8QjiY`$aYp2a~DP%E}Y?1W|lrK#Qkzy@k0aT zkdOwzA9xETT)1Z=IEg48GC|!=jAbU52iue(fwf330=#j-wqT_wRRx!|bumrU zBYfCQo_<}+rQ0(;pe_nToj<4Te-b)^`uqEpG}5pUUpERbS4ZtikukW{dY3Jyh679X zhX`LPszPpPy67ePDS51I8%&1Wt#RhvGYUkVK7HB&Q9=3FT6?pq8-bTVg1T) zYxAQ!4j_s;q6kEFbrniPMd$i*WnC*_+nVdD%_PnZ9MiCD{~@gVhb~>l8j~M{)4JoO z6JR9q2_5s^Tw*(?D7eDydCxratUUVYqq?O#2BL~LZ0!J10e$OuVPV4>GR*~k9bOEc zc!E++Pv|0GWqDO@yX{u_&0W=dQ2#NLgqe+`L=xf+uv46sEb=Ns;M9QXe2B8lMDUC@c2Gl1HExLs zko9@)+2`buM;_5KAA0C7$_HzA_`CX^hFt*2#bB_;FAM*vjZ4A7__`LYab&09SN z37_LA6XPCII1ufD<#sazqj0|l#ZK$kI+qCaGp%F$-#Yy2h$zv|NiaF!gfy>8Uuq0G zr^Xd{ytD$1+izV?8qU{rIlhkv}B z@I?tg6hNrQzyG*ylOYgwD}bm69{7X;N0bua3*-W}NN~HvV}Jkm^4MdK3BjjNKx&F7 z;~hV7T%}c5Z%QdmO-;!(PQLn=fB6@+M~@zp4}9PrfL3=Z$ff)K116D{@C^lij<$6b zz2g^gp2)|=$>hW&wvafnJigo!Kx14=dcF3W*W`&OpU|&pfBxrxE`Ruk4_Hm{3=38+ zp%Y%@!U9@ir*=3%Ad;2}tw*5{pQ{lrN{EuHzA`Azr(yTW>p;8>Ob9UAgUkYAw=xa{ zLnSYAl$T}WATm)2DglQ}poa1=>D6_~KM+Va@{xnnt{< zkdU0jmN7GD+gjut?9~stZpkz$6MpL81v- zqEu@(=>#2hiDhZT>2;ZO6Qq$E6+WT_QyqY)B$S0GAeNK>K*aflb4Lnk+L{1FHH~9i zT(`7!_DFkMO4_kijzCl+cHdFY60xoX&>`YV5FUkem9r+T)Rl|Q{rC1nhl>{wG_?cOwkQUgfLPf-|VDNnaKPVp?7ja|+J{aJ` z0VKOjt zlfaL8Fdf1Q0ZCK@{+f*|RDUT|ONHgsH%Reoeh6s=0N4xwuTJ}s^$V607?KiPYAAjT z{Gvb8(O8(?cxg0DX|Y_i20=9E=W@uEqiHlo&aYUUAWG=u(cmcZ!bo+FhA@B^U{r~a zylAz4qw{jWDD77uSp7&i{JFp+7&Qh7XFmHoAr04eq#xTbCXVM_Fe7Huc_D?{fz2k8w6QA>3bMxJ<5dak5^V0m9tA>3gykdvY-3qH% z8~)-KzmR|Y$A1LoFdd(o7jP@;)D#e9gPt!8lx*UCeIPZo5fH_ZHv!a|$87%N|N39{ zw=n7e06+jqL_t*A@H`FgPyh5!b!#5?bKB9%To_Uh743Jv^RKYq2D;fPH{EoTN>AN$ z&--QI)Ii89-2;lR_^RV1SZHwKu>}c5Hh=rtZ}lq)PvWDkholoFo>&$aEL3Rv_FHc& zQ1M^>?9b%m_umgi!q`I!g_oKoesmg97uWRE|KK{LCcdZ@4zP_Vv9}1xh`ISWorpLw zrLa#ai8p;+oan=h6cH-b5kU6#_jVT~DRM{Jw(ifU8Wy`3++Q<>VQb3s3&p zbHSpxxseeFAW@=}AR8si02)zG6fN&*xz&#MIu03!^EmFgjnCrXo__00uW6V!rNW^iQRvo~>c7T8_kcvxUnnr=Oc+ygV2s$eUS)>6kV!mL|yBeATr%E6NWS$L*9pReJ zSf(%5ZUySL4CDkR}RbFgR<+=96cpQ@ zcmWN^I@_PRqI5@7P!M4sV>RINK)zn4s_0~N$32UoSmAKGn0@Kdi_=DdG$r9zd9l~kWNMcfV>82 zrL(DwG@|?_^n}~9q)W^rU&{YMQ96QL1esVkMYZUn?Rdi8 zI=4mA4~SWUz!U4td-f;9!4H`R3;%!?c&g!+%sEKlE>Twy=J6yHXLWRRsj_MX76~d9 z7-ZrZ##n=d+8X*>QbE65TPU3xm(Ky02rSoj3+vBX(KCn_Tx{C0{F%_QGuLItGIC|H z%wo?Z7Z<}&ebOO8zw)v;LeQ~*HK(D>uW4an*?bvPViD?W1jKCc1E0CF|HzRNCowAeJ7w# ziDSvUcSPiP&QI&p2t-D8jt~1OSZ_G9SYsIy`qdY`k-pH`+d}I90`2{}OcCJt2 zGS67su}rqPy_E8Wltle0&GIHZh$6oGMBQS2Q z8&@CKA2`O7SW|M$bIxZN+q9t}g|XkLeS!7SG)UsWC_H1)Z}@({3_X&szWS;>j>FT~ zcOL%27v#aud|J|YPb3)S_Zj7jvB%t6XVwnUR~tZ7Fos+Qa1Ut$I9xOlgyQ0^5+I7= zbF`2B{bTajV~@!PKlnlUZ~yhb>1lagIDM}f(h7Voae|qhp+ppbsPBJI(aH=&>W`l| zsS;85-S_))J%A|vvWb^9O19`W7;ca8fGBoOmd8`mxNrQz#f!QKT6Hh>RMUL{abR5P^0vM?WKvGxFJ3vu*pfu0p<#J&K zis;86%?KS)|Ng2hz5Jpi$3~ zVcI3J+%3uJK51AvB;Ebc-*g0EQ9I@%*!ncL*#WSjVsV^4muZAj^2|IGe=mckRsc89 z)r34Vut`Wl>3qQV5>^QyMiyHG*8r3x>Si%F%_5Bhy4W|9w8)#v#r0hV@i{+mj^V)z zDv^nYrS@y`0rf`}lpiW=g#Maca~}j&q1%a;<#P%or;v@#RlH|>Gn{(X0C<5#u#Wf0 zM&}px16@itw>5I!!F?rjkIs3ZU*{^Mp;>30NDL*Am>nugtJ|YUphgRbvpJEKa12Bm z#$mYQEv3NJAm89Z>#W!2g`4^LC7GRD)P)B5$%ScqJ5JHTHVyKf{LdNhI>_G9r6eO7 z!h?BSV|vkV^Gg84)NDIdrL1g>|6>&TuEdjmYiTVX~Ek~bUhVoc*-a$TS;YzL2 z$8{gKpPbE+IE$1 z%0KoU@CbjUjJBB1Xtqo6XKCCz+l>`%t+4GZ2HS-FlI6K)=OjK%(eg!-05qlG2}-c7 zeB+O6-#@;tEe>egYEQyC5Q`vKf?e2*Hu=9-QbAPB{=O)1FfX`I>&f6f_f|8^V=O_%Ys zn!2`j>+vks(Cv=2S>@Wb-pgAb}SRT`4C1qSR=V{So&gXvLq zAj*G`=r#K-8q|QOBwp~?5uU`+=|mOBu8!-8H9R%%lb`&!(-DQYCl2<>@kuNYCgq#o z`i35tNQtQb3hAS}?z&rg4t>+@{c+^`eH>NZB*#t+U>n~Z z@*gM>b=`mhNCd6iVi91G0!Db)@QDRFxjln`7Ii}nW6KVYdbgt+ZGlOIlrMe%{@TCG z51#yihX3VX2Fl76ZN;8sJiwT@y(F?z^UXjXn)tG=56DRW<6!2Zl627MB!FuLqjX`D zn-IxYpU*Bu{%`aFogbQiS4n>PDfa(eIH7{a1fn=W=?gU8{3fX*YIH;=9*XsHa%x3i z&1* z*4{p8J=7<486rhaawtPEDuZ$}0F)Y*Fdq;&Z`Lh)$UdA0_>#kyQo4LzazUPj!t*sM zJ%{nfI#2naiX^%k#(4vYIKM6fFy{-kTNqIHQ@vzx;vT>FaXw`dZjt63==v`f{+OF} zenMvK|7tux=iz>J0T!&ynGQJyb19^Nm@lm6fo%N6n&t23#cQ48m=6iFH9zh_9RJnm zm_)e6r6;MhaE(;NPiqp*myzM;(`M=C7XU=fE! zS~pymn7u2u9g5CCTuwoZW3;sUsG&laRZW+6Dpc0(M# z`>Ha11NBf=XcU-Zo6{n42@_CKBJ|*Rvk$W&d9p91;q;{x^M4mk&^dbKD8?^N)Wla% zzOc}+?{JGg$Ck2B+mYNN<2fz~oCb}pVMyfhU-|CGMSj+Yv;glXjH~6k0b+gxqF9y! zQOM8AWqnHJ=ViU^OIFDNE^Z;OfD8MS&X(j;KE1joLT5IfZH54=Gt)%#-3}it-$_Wx z@}yjTY&de{i1haK=Ey@+>bMS?G#3zDm22Z7^co)u^0`JmtUp*=&@E+(%}MOy8;kOfhhQLexAn( z$y8X*^-??Zz;b<`hBO=%S8t|I?oaMiMs;+&=@<>xXO-np8?m$=TpQu99`AV+C}G?4 zvfAaM@~-ml{2hl?hPy{52;d+MpD6v*KNU=c3?R7C#qPu#EipQt>H3g%{} zXP|(5R=)YouLFqsx=KP(N7UVS-vvdYM-;&%8~9>1JvF0X)DM2}q&)e9Cm=1=DyL3e zC%4~myWDfn@5#xNCj$ET!UP&&xuDcj^6>Z~jTGPHgvBqQbC{?W7Z=oDU$C$m;UZM) zhPc1@#V_R_{^9>o1?gY>;um$FsGgb!x*5-p>zc}~WOPwer0qCJwD$*LEQf}U3v>5D zu=BH<5-z!4snIejjeJ1jIUZx_qV2^m%%~VFw}f84d|4+Rf=`^J+MvkNCMm1_wa7E8 zdo8;Bo=TuN0Uc4vI_hfUVg!px=zxNkB=IsoibryfLX@;wF1eeY`RY}t;gif+i#Kg-Fk~; zda!`)?Ltx5qJ~l_ja8o_7(~ge70ff-5(bb8wCMa0A}?GRAwKff{zvdY|0qGqoZOx9 z+vb+s*hV<&OiM6om0Qtts-OfFUYIc-B~cg6o0$Z0HCJ76IX}%mjD$guKiz0Be^@>Z z%TpR~>(6x>?xJWs7dN~Nvt{;L1oEM=d{y~)5XKPt^Ocq@>B@v(5DrK4;Jx{28t)z% zFq%_p4p&dsqf1X1OY3w-EMWU3bOK^)E}sisU7gSq)u!_UKO;m9^Ds*q{TP}*ezbT5 z_+gfhR^8$-20mQwWUJfZY&w*2z>vbzo0|U~JwWV)#%=sRX>%wx%(`$2GB%5pUHadnjVgfju7sVfI3~;>7jX&p? zmn6L5n5DIoG6_Z;I(%4K@$SHnH+*4@&Hm(o^%DZu>>~;~VtvG^f_;RCTM>Nbv!38% zM+c>0pf&;0QJd|P`;$YJQEhy**c>mBA!tE0?P@(hI-lEY|0{UL)3R?+3XWr+AD`?U z&*Ho4;tp$N?x-Rd_0#8mD&P9nw-n5ZfvDomUUeXf1D=f*F5I|aLkBP*iVD4GfB3_v z6pR|Za#a;Y-gMK=a=!vmcj#A0f;#i~LOqA$H3>w0{p*k5^t;>SkN)V7CeF2{}^Q;u;U5pZIs;ub-c!-1s( z3^CYA-NVc=*dK`Ow08gFAN^SV=70Q+cILnS>%Ued>IQ5TZ<^S5zi@yP)ZoQI?I)a| zcyeAl9#k!@E&HVk*Cd?;p`5G_Kqy(ndp+-{PYB{i1f=j~Y+-&9in=G|;*&p;Gyn7* znLc+>)*ykof`#WS=7UAd2VBN-tea`XT+za>A$S3u#6xQyTY^`6dZe-ch}?Jg2jxH9 z`2nf#YEhfT{ILwci+{f4lFQ9bn1dukHn+${5&$2Zdsw1dI9b_F!T=LgXc&pqxg0}p zy&x2axSYd+zbHVWsqy3HJLc=>%}j#49Wk0~K@{g(_*;Y|Eg@2bf=Y#{wMLeOQD*e> zp6QhSAgyI#Kh~nac`W|RVAGg*K zj8a`reAu9qDcvRB6p$o%NpxRNS)U*O_{Z|MfAhB}cSHz8eeUz0(=R9rY-vd>%v~^V z-$d{IuyWTvK<39Q_cL z#X$8iZWdu79hBvE5P&-XzagFkAZi+mk12Wg|2`wH|I6bt0U!z@Lps3Od;}#L@f9tN zeqd%D^UFHsi^&G)jcRFTKfuicgRRCfjgIQpDQi-Ib z<`+;1dZ-I2G`M82E7J21BQTwBT%2f37mJb^%nLn|*7eLVG3)2jDP$G;+eMgXv`C9k z#MQn}|1hzOWLcPNNqxY`{1}JHEeqb$8oj*UNgxW@sbT)KdQv7psA+7?p29Y7>ZR)M zKO{Z9_}BqM`LECzaqwj`DkpKFyWW&wL|_02W-2N>&(#c#*)j@EL4fn#v0vox zxBNBx?64*wKX9!;BqX7Sp&ydcusoIb zFx#8!d>iNSydLoF065w=&@Tu=T^bxx44?prvc3}ZAL|d?p3m)_&ph*tJo3mR*v@-3 z2BJ#ziJAbSNE;iE`bbuB(h*%6b^-&UzW4p_LaF$_%EZ_tK%sR2M(>qB{?s2S5XE@f zVS*09M*rH^zNQlfPre_)WE=iZlRz8UUn>^oZtWc_toBU#~si)1z_vF@0BCR zj_6CH5`jDkToH^S*hQ-yjgt>7jk)fc5?*dWLNQOR6UzGufT;iZmH#PMv9<6^U;1nL z{O3Qf(p8kQQWMbb=jHOtmE$5-{u}b8ND}3jKk@o;T(x{3cU>xeVa$W+V-roVRg<75 zZ8;!{{YD>BML42uP{cp>+5-;wzzzVYbx1_v7&lp8#@vJdx=e#4VCMit&CSoq8&CgK zUit11WsE=+47cC40{CtR;M59my3NxMF^BO!13T21mJ40&G7F%*Yj#2Ukl*|N^nQ8& zXYZGWWUDmPwa5}Ao#s}s71>RBx~;1Ld8IJV?3K~2ekx(bB@{b(ZlIHjjVRIWai!*r z5|xPdeVzVt#pb0VYZ%U8(xP$U(pVDnV>tbI&vd-@1lT;L6C&!N+mcGN?C>IiJVW~*Kf;eZ8D*cXuD=2g4ZGxxk!H@eh*Krgg^ACY2 zRs#7Dm$Ew0XU_}@b|mPp78`B1J)@<{1%=Oa%=hHV0;J(+M@F2;eh-1D0S82pRJNBs z%fULj(dW8V$M|Wk`NwYUalqP<>LCb3QD4mI)2HS5@#A^zYi((5ZujQaUd>{Pd=6N< z`7X!2JEW#gL8y1%eOFa|96fqefv8M6qk5t=O>VmMvyHE7m;*XCIceL2mh*N1E-{P} zQRmN}S0IX#Fx;NU9S__Ap@Irn@9F9ZacQDsJ$kQ^cKFBo>kenTt?c%q-rFLuL}KHm zz2gxt7=+~H$hb0XX892wLvlq)w^tefN9v z-S2)kJlW(u?|F}WyU=JS3dQrPpR&y z7AT$N(Twa^)CXizExfnR7SbJnQN~{9Z(qjTUgK4iM~SGf{Owl)AnHr<`TqcE0@n=T!3vPLB<;M2*1y#S5JicowaS4go_EoWY&zgJ0vK-ulC+F|vCO^U@M9ktZpz5p z9W62r9d=ES)a-#|)Q3O*A7MWtNj$*nVOQ5P&@-0?PC;Ez1R>mMccxst6!(mL8!5zKUTg)NwClH1B=sH4N3ZFXQL4yo}OBIrGo_qJJ z^n(Dpu~80i&gb(v2SkmigiKFw4}hqXnEzWtcGtHj&Hd}Ty^crZE-WmBAk$MnfQ~3wo=!J6KL>qIH_9hI@o`8-K}QshPvvPf z+_Otj$(LSyNnU*MMS0=*7vzN(UXZ@NK6&7Q2jutO|9dLwL?!4hzaOgT98t@Ue)OaA zxzBx0uDk9!)f+?dsI->|D9u&|71QWGQ2=VXH4i`(7cpP{@|Q!2C_dcsjNb`48S0Ff z|8U!g78^u9-34ii@IQ}^_@*QWl)r2z@Q@P~fhbN?oOt+!gw}LKl>(xyJ@vt!!nK@J%X)yy;y{BJ2&_Y z(J2B=OhZGUiE{_t(D3nsImAqY05_T?4|rljT4P$oy>LO60%bY!_M+69EJNpftq8ydShDi3TkQo=GJ88W1^G;)}FRCub4y>+tJ$6 z+S%^SjoDe-9I$pHm3B>+AQabo8v#+ZUAvgNq8zYioVl38O94^g);vf=alY3N4jvHY z=kJes|JskU6W7*HnU`JfW_de7b1ml)@(|;lW4^48sL0xk{eeIfafM9*QI=2OhBSC< zhg#;@c4(^(5M_fsLOB`F2Asyio~M#rx^xN3U}x3-=GEWGtFV)k6Ecs}>3D4JU3cE8 zz!6{ksloon8*Y>vZoEN7C@-A9peNNm1F<*)1gB452OS=Ls%VVGzVr4wDqc-pP_*~l zbB}!Z!ylHz0IevAMOp|%=`qLN;vzzF*;`HoDxwzvQIv>sKolgRur-e_FL@GC%*{Gu zkh6A1uVYp^xiFo@H8+pg5^azdC%!4lfv`=$!x)Gv%A(r##CXE+aAOS@*cgYKCEUa1 z9ytO9(C?JMmb#_oIayqpm!a3+lnXDvDzlKtq)7p2=vZ2lrUjgwIXf>|Y`t5=+%*rB zp&7taM{ASJwKvMejwTszY|!n*=~PO@CLm9eJ%v^YMPGWf*)jOBEdRNAxC=f;I z)*}F-s4K_;QGvuH_wmuNpP`ZpLh(Yq@k3X?MF8O7ErS9uDzDKrlRf?+J*1EJ8aF!U zlOI@=@_Iuc3jER+6vU18b+S_PgKJ^tGAuT=$pN+*tq(*|N7OMWtfpaDv34{+b8EA9 zF;&I^8=JhhYq~KIWgI$yu07+-<+GaOnGZiapM4!sx-}2V%DMZYQXpzC#=hTI*+P3! z<^k*pS|#HppZC=QqDYAL!5E0zrEX?}T{(>(-os|0PiFA`7Kv^=@w{`>EjkNv^NbdfkeKQF)f^(*q+Pk*L>)A-n^ z%+5?}!}5V*k}H&`qCIu$lqxr;R28@Gu><%ZlnrWgt)rIX5aaUnKLT4kHSa55@wVns zSvj^7ZU%@dS5~PoqqiX3Z-aus*rOZ=wC(YrVxNtHsB)aDjW8Rl;aE_~6wrn-&Sq3) z<+2PHKomXTZ{kT=094t;vMgfmSeTxa)fE6%Fp0SpsT-UV8J@$uG7Eh{vnol+4`Z!8 zZPMA_DaqazS%l=%QYHoE#wZJVfqJ@|rKhV|5?O#ywDnDrNW%h%q8_15AwWt=?uVpr zG_3RDL?Y|+4i8?-gmEh|3Z7IFu}mD6bs&JKLja<93L-#B_94y>+Ml$7e3A8-VEktk zFrU^3qO?887e9@cd@nAQ2BUK?3arsGbPfR@*q*$u2#8|Cm1sMEP73Fx8m)Uwmg4~1 zjFvzYw`MItS-mPN4|GIXn=-cFrgm*^%+K29fVE@Pje)4zZntewXU{luId9YQ9#&7y zyMR;kuv3R8tnaH9Kj4FFRqPGvB}xtb=G9l_x3B#c3c?2E;>C->7B?sj#{!=~5g!T-Dd=7SAVtM- zl#rrC(|z~dhqgp(q7%Jy=B&K-+utb=b@BW;8M}H_rK317`uqFU-gMJVsuzkVHz$@9 zq#*c3TRS0N41%`-x^_+St+VpFn6bD7p_Xx!`;UM8Bl$ZjD+dilm6cm2?1-Mxaw2|S z@P?O0M?pm6e?dU(u@MKtHUSSgNo{3o9?OXKsg25w!?(tPg0UJ*_HJ0=cb!_DaB`kX zMg@T?rUGp}bdJ&(tfx@dXD!< zV-L37wPj=-dh3>65t%LAhJWO%X=zaYKG zPvGbHqtz|=@sn}7&ATs%y|IUuwcSiME@sOyls?uIG}3bG_zd(zQDHf4zC;vs1mL3z zPtxQ3K>qM~L}Pt1IxjmQ3VE{(7d7Om-Ufb}$sYdbWv^JF?Z&o8d-8fiAPVi} z)**!yS|4CYv>z14j(w`l0c#_+8!gwTJ`hETC=2sxwRGnCVexfsalqQh#-_QX(yn75 zsscKt_8} z?;RksAPe%6md|_IJq4mjO<{K`pz$DiR1b(UF518+@6qrCffg4RAqqLBQczs*(^|*i z;!ZmVW(PhP_yRyB zMdwhA&VjRz{SzQXjSVEqjw3&LWLvK-KMU>5)nIZ15?h$>r99JnnGSl^G1n{fDs7Zj1=oIyZ}+w^$Nt#SAC#)08!hy$X`3l>8>(Oy|Y8ot5lS6U_pcLQu!#M}}^M0>QP-HpDq$pK-pPLT1M=>(nFsltC zY>$NUsZqGjsQ{vIjPumglu$<$w~zC%jBsln`UXFkxVXktN4WJ#mcwhmZz|teM0p~> zqzz+iltbm=hKg05;^4*v+cyP7h4TxV%)5><$nO);u=u_R*bM&H9s%v@sC1Si`c>f(j#~kuqUBh5mE6B%@%* zvr96OU6!`47CCgdOPU&6AXf#YyzfP z&@k_^6!?K4VlQ~1?XedH`E{$|>!9t~UL_@>AXTjfZ1daIzpmjL#-tVDfSZpUXv}ux z8t&Y=bGo)07#PqGpvBtP#<;n~;uI+^_NoF0tc_T-wUfCJOl`jTF5rhhXD9j7|tZ2sXPv*B*uJzk$(y&)`-HmdLe{^FYYBxAsm}kub zQGkuYiGbJPAh)ru!8TL4iZM=Z@a4kv3Y{wFgZU=gl$1(^+ zQNqiBDDE}hE)bQgqm`8J8f^u2^rIOceZTm+A`U2j*$0=E!Sam?jbGs4-5xm{(!{PQ56%CfXlq@e!^oAJ<1EFS~Pkro-_c~|p>Y%%IEMlm3YhfW+ldQ?x% z+pI*?E|MK*y+a((_7B>g*D(;aLyWEAY;4T)8BNQ3T2)*Oy`==Ajzdv-3`Es%BW{5- zYj<-kix`M9P8>kj7CGidsyI10DMN!p`Yr%jL8iXPZFxQr#l@WIh^mG4y!G2!pe4e_ zn!h#Pnai~vZLA||cbl&IK-BKmZ%esbCp4FtLZcy9a-hoq9x*!q7ZF%m`vT>+Rc_7LwHB9DF7y9kQMX|DcaK32xP87V) z@(BA5+Z_uNe`}uUh&p<#av*A-RX-+|90=N;ePOdeRM>xFPVPGn@L593Hl!sGb>YGV z1)_Lbb15K7yG-y5@t;TZkNZPybpyYBtZmFSN@F0(IB@`7Tj-b@siF@=`4Ul$O^q1L zwF5-?eb(>Ok?O>^B{*RGGdBjJN-%1Ny<;G%2t%zCnpbet zV!{o>qDWHdf8u4t>mH4JYIAr8Eg3iuYHpjHtqT%eSkm6FQ;} zNn-|!6q=x~=yfpe=!K+34WszOQ{xtmxjoNlIhtDunzmQc{!bnD9WX5lL{U!^bwm+} zI&|oep76Snj;Q_5k!!F9LEE!0YzBx5`_47UvV%}%K1XQTjyYP>NI4^^dksw4Gugs=Dp7lcihRTAPOpE`Q2EzsuqDL*3If= zu2+@#vJ3~TUzi&MQDvC5gF!J6Rf3t;5laNCcdEWq-Tc_FSt3FD5Y%Rom@pi;Yra)~DX$(vR0nW9jI}>nIR)6(H2r zQ79`9URXK+M0NLcOD3HO(`vrxFEPkNF788PNFdt~)(4_YBI?+208x;HBM4(MUoBbq6eSp`o*?$~}J`18i6qS{iGuHm*THLrl7$>UhmTH%1`_wuR6{WYD zT#fRynzU3@wyn?1jUV8KhaQqoJ@_f1+KzN4UC2dSBA8nk<3RevK-3nS)jF!VmJKIhn}iuw9EkdoeE##F zQ)S20Es|#<9Z>U!U$mUOG(~QV26Kx;vqTvfgKsP6< ztpHJF+odcqabTq!i1L{2R_QomTH0tD-baBbQ&vtef?$-tHBV`^{!{Dyyi&$qi}Cz6 zL^~P~H8n*bYRUmoC*28J{?2tvw6e zsd?x1CFA&UH|EP_VC~O1{&hSTl;hgog_UZPX#11}qVQtL11qW}@f@Xf@3>dGB%iOP zW7SZItoxZ?WT6OJ(C-Bt#;TJ6@ zFHMP?C@m$TRn=R!E!8{{mCqv5ycHm-*h9hh+e#bfQ?|W3(sIygsI-2i+J))23`DVc ziY#)%#cQ#!?KNrTscqgVM+4)O3$MJi;xWt7uvcXpWzl;2v?0s~q6kJ2ggikYs=u#b zYo6biEc@8qha5n=Zx)DREi0XK_8~{E36eQ}?b*n-bU+kO&0Cfekb?f2#8{p?OCx$)%WT2ulK01fq&EV~;(p z4;0jGkLf5^oKKt4TQ2@~!?s#R#XyvedGwbUh}wK>#X!{Nd8R3>W1DN)aDe%PtRxWi zpFgiJFLlW}OX^(f(7eNS2zu}qi=fSzC@q^wyBBe-K0d$pqTKD4VRZAQoD-Fkh#HjD z)vUC%v`A}Pt3Ie&T3f=G(qeUt`i1#!m%uHiCp`z5hRxQk7(dq6aUvSNcChV}_yWp2 z%SuEQ8?wRTMw=-b?uYs97>(zL?ew+Lu$N^<>re|cL}+4LbG);zPm$mEk#vbzaJE>Usb8w`@(&GR9d>FNhA}h_qD8!D73xBXa2mV zjU}QgsfFtHk;;vbv$z|0}lLf@M8j7T3k{T-9I%?C88C;}V>ss&cM+jwzf9uz{9F-lR#9MZx!lgZE`Kpz&aMI zr}4mCHbXS7ONYUUan7;3h6m7yzKo7YJ#|FEnvN&}Q2_ci59aCT>o>9a7o*8&@Z;~s zwb5XCm!ieOcf+kF4I7nh{NQ-!ygfHNFEdj!0HG#jVqy$m%@UA^8c-mL0F=d#!KmHn zDb>g`cpzgO^F@Wvb(4r97{yaExlOCJ1s@;S=s|S$gJ|EX2K8~7TjzkaAKQ}FmxyAU zA3l6IH{QKsESw7hD%PA`__p!Msb9TYg==QTN=I4iR_S)x_pLVCq@$=rwb(GGn z(8o0V<9gnJD1uR(0~#9}^&PJh?|6+(jd{Wbq*v1-{p#v!3`AAffH4qNA)}(vHtO6q zk?Gbvpy)sO$xr0#U;nx;V!rsrFUn^>`&mihD++C%2^O&G=U?YVif^jP0h?${I^yc+ zRk?imvPwiXHa6j9q($00+l5>6$~~kkpK8|SS}nWO_>Dfq$RCUAyNs6vAd$s3y~~$} zWq5d4QmK?Qz*Y)GF~4YeRz|UQDHm2Oex-g<8Z6yzm1p_;ZZ&DxOxaN&YI2HO^PEJK z>5Iu`vu^vQH-DqMz}U*xuX%i3`y6lp1ly18PqVn_B%;Etc|AS)Qc567o0-wP_V=$# z^*7Bp{;63G@Wq7xJ`hET7y?l={(R}Tv43rqE9Pfmv0FV3SR0y4O6=OU=AAuzR?eO| z3#HW^at!Uy50CZ9dVNXt<5!~=Mr$?7wleo^-^QFx+VkiS9@&)wQO1L6xV6ys)u{Jw zlu2ItK-A@-%X0bBWqtk=eBy2w?s_38wFZ?es;-0Ug83bRs!m@@4jn$Efb=S) zBh8Sf##i%;-TlJ>f9!G0V=4$w!@YX-s*H|~N_Tg+ZqsRPZ58U3@Y`GG|KK_9`|lqP z#FQ$yh&E(jFd&K&&;~@&-};H)#&%7&Sa{6Y+T(z=Q`Dto1n2+r=g!Hwv*+|h^cZwR zam?328p_QL!9cG6kSlH_4`_)senj$MCr6Pj>g>xh~i1Pu{k&#V87*`Nkk3v zWAo6kj{i(!Ce#Dmm}!(O-U0aWF_FOh5CTza>gRx{=j72xAC6Q0qVC%JO-UD{F7sA)hYRHQ$GKd(kg^9{3daWm}v|c9yq_jn9QD7bkOb zb22sQl$B3RjN>IFfm8ENs^VhK4GKgBZ64C-DiF;wzOQu-aNL7Nj>0;Od9D^0xit^Z zb^=kf)Ejc-$WfJoO#-aa7n)#U$`2QOQDHxbyFjfsc4_)_Iz(UKhbPYWD=W)FAmY#= zY|X>p8p7}@5^3Y;J@YT-SGwFdWN$g(o_qHE3r0Q$e;vm!#~Oe>04Nq@-AV>Z83ly$|CO4GoT5~&-E%E~DX zH9j`3Km-@C0|QP+6hWvJEI@Q&5-e)@IEc;uibU&L#f6!I<{(Tni&(_;Hs%<`=n3#}DmoDMdycGaZM={?Y(z%jP zdCrVFUzaIX!?iDzi4+G_l>^q+BqD4tv>C6@yn99!miPAd%IVXmRav>k@zYhc0yR>2 zu{A`Ekd{Y=(Mb?WfhbP;u#|M+hvzA5!53i&jm{{27XBkG}tZ9#*yl}l4xEVNJ$)Ig|> z%W75KwNrck7Dsf4uWOu_!;IFmu;fDcKtPCyIo9dZr^5;Dl3vzg13?sN2%!*28S$@E zh+7jY^d}b5(}XkvjbOuMbMX5^ z<|C?2YiYGUzCBvRE@+hUqg3!uuXtOp2KR}->* z4!}(7m^PO>YloDDX$ScTjQWU#QNlg=|4Ga%8%$9*HA+wqEze$AT?jyTAUj1xCq?fM znbu?9e*J7`+@FEtD`B`Id8*sitbFw#U^8Dl59aWtAIvqockK?lcked57ZenjnU3Q; znwzTk?xs}Q;L!*^D4O#nNH&_SL2MmBhaQV=Gnd2Tv*`rg@1j!@JIntod_HRc%6j>F z`&6|z3F{I(4Ej~Ber7jv=_b4jWjJi(91W`2v z@iZZ_#gXI|_=rLyYRTdyCKctV@BjSI{|pa5^00Mi@|BpxXiu$m#3ZSzp%1@8HO0fS z_}3MRG_c3TFmpU{d^h+uHC}0loI7_moIZ8Nh!My5GC8%;B!x7+xO4;iEN@O(eXTCh z)ezd?@Tf@a465?Nq?|Z@(oR*ek*xlJllpFQR^O&=#H3WD$};l+o4Uk>H>50_@VvI$ zQ`Wna@AW*%G;e!N#9n{8F1-($jg||$T}4Gj;fPGL=m-7#Yf&n*OlX782R09+>&WgK z2L$rDz3WUY)K5Y6UjLmvI% zs4Yqu?_IlftrUPF>}P$TQb4Qo%*C8r4qq|KA~T%><_mJbzyY=x%?<8+G^5Vj-mqR+ z49SMou6(UA9zQWOZ5|ixMg#WLsnfQp(6LiTvxG4IpN%Hryg`1W_r=8b)ZW@MA2dC! z7&^JJUgV4gBxj?Ob}H=i1UR_z>UXHLz-VcGrz z`|ZTMTW-0<7BsmDjDiV*<^)kRQ0b8wkmV&0i7>g0>O5sEEnOzc$Xl|jh9H0)@z0Wk zU%YtH@C;tia3f&8g9>MLuIiD{>byBCTNVULPBqbv8G>d)H12}!c65;MfL5&|ZAY&w zUDngfi*tPdI*?rr1_H)pNZak)xpSfD)F~4}~cdJc{~ohpmV=qB;3M47n#UM_lOf32T+ddd2tZ}w*;>Px(* zWSOSh2FCoUqEpgx`_X)bV4_pes|4&aTv(sAepQN=HHcXhGxaj}1oXe51Rv?pZmMi6;4VR>}tFbm*8nrAOHS zfh2t)cO~+B8gum8wQIv$^WO^RFPsm5`r{wNgAYC^WrawaF45Jz2qdT3U6~-NhEQ&d ze_R*85ke6zUbtv}q85F!DE#+-|94oweto#=s;k1Nk)tAw8YJrR1q1t&COs}w5mk)J zAN9HPy;uz}@>xV~(ztM#3*n>=(xNiaX)UBB+h_%{Kh=VOIir&~UgQHrzJPQA{|FD! z2?|l7{jK<)W=M!C4x9#%Gclnvrcl?0QE{~4BL-oljbU48CJNB})NPqx6j#VQ{9l=Q zvj=qx0dS*WG&^=g4ReC<(P^~PY-emE`tGz^{sa=fw!BP4KZ2mg0g-w?l0-Ug4V4fO<2lcq7A;Rym0I|@G>6r-28|s z!Eu~>rnb^Qay|x~xQKR;ju`;$U?apYZ?ARDxX<`A`*zhye%|F*)`kcYm4O5F9v_it z#kqNo!?PlBhKmSFjR6iCfHt1dc=gMCgi1q(KI0pXY&x2wV$YPtjSd3L4MqoqSHHk( ztCp>do-^(dK65e0Hm1wIE&jg7)b9FdtMS?z_emU^2E5Gjn0qn3r%%A^wKShl`CDmx zgyv{Y)!w*iW9ZqVr&&Wi`pBb^!h*_!7yg&H8dujU(e$d`WP+%wLM~Mf#*@oq2pXO% zVN{v8zWDr$@VCGJEv#9y#yVuzuHB45Wzot-emZV6;khtFCLmhm_#%Y7+>_5HLEZB# z5?)0M6|aXp&HzVwqI%+H+B>s9)q?=I`biVhDQQGtqQgClQJ7P9$oUQI3CYX)MlvDw zJDorEIJ>Q92!KBV;|pAY`=V1tx$y?>@f8D;YPd|G|4O*e_i5CT^@)6tshhMUL*jTx z3z8jD=sUC)!DCnXj=*^-egt4zVPcb7k>Jo5G)|lS3#h~Cx-HO{KXg%sbmFqgkk1xE zaT)F-+7!(JSsQ8&4vr6VL@EK)X_;wpf+E^b-F0#v0x570&KzGJgO}tL^`%H_)&x!} z<5yG$`VsXD-pl3v&jeALdw7pulp&pqdCALg@5jrNpJ#q$ZHORIJ{(#aE*%$Wz+sNb z7z5{ByL2r9Ylm%FafXWsGK~Qaj3G|Ob>A@b6HZCypbF?}I~`8aHr9|~zRz7M$A~p5 zo}kOQ=gstoExa4*x3gq3A%8UY(#%%z1_N{b3At4{rxeI?`!gp8VNW83;sp05^WM zL@F-kW7DS1VfE_O5;&d@ef##cBisiK(rG$!Udy5cyJEkg*~c7qtwc4qqx?hA$$+C+8n;ssltVhF6JyLq0t$}HbYF<*a!H!)#jf;> ze3h-QDrIPg_epOXaaF&mF}1c;06>1>uD6j8lg%SX_eYW%Jcvoiyt8P@Q_3 zV_BGsG;wb$0@Y5!hs8@4hk5hn=@hLqVZ?|LVf5(HVf^^G#_9-S#&O3xF{@Iv`{A{cDBn91O=t}vs=d}v~=qB_TZAW~9?A*CCZ2b1yux;CRJ3*;)r_Sbt@`f93Fbx^BCj9iY zG;>kAEzN4LX$Uy&XH2@5>!CvjZ9e~W@#665;!ne@nX>{a_XPz7MiZFdU4T*3?aAt^ zTL?HUb{g>Y*I$P>=e-$DND%qZuO13F&%N1bgA1Z;j;PxvW^bz{2sqA(5kjN+`r7NS zg;!sDReau?n*;o+8+~3?UXklX*7s;^>&fU5JLBtzxyb<oNuhA);7~ARu<`fsf#k0*-kx_8xXeT}7DRbkbMJqZ`+gThwa~ckWCxLa z@WBUR!TSp|{(m8XQg2)1O_?%13>+}X6cE6FSr;3Z2s69rWL<<&I63!z=5eyDj}yn8 z-zW1lwcnW_s)`u(PD1hI@3QVMNHc=tzHwOQ0w;fUvNM`WV15~wXRlVAZfmtFYet3h z!ObP)gi#A^((0s%YtmJdq#ZHCPEf;t49B=e_?85#q8B?Q{L|t$yXqeTjDLb1M4$!9 zu3ZvDZQLkr$W3AMrY)us_0U5Pg}FD+H9-W73Apo6|6h=`psEmX+7B)n_srjD#2q<& z#F*0s3l;Q!HflH?WUw-*zc;z3jm?q@ok3SynyyH&o zQ6-qRn07b3ugF?dSqM1JDd*$=`RAVx&p!KXm^x*u4jy_$T2W&H4(kz8`$d1q(SU5z zu~E@NAM4=Kg^#OOtq%YE=Rd=qJ$u5eYp)B_r3pEB@Sre60scOzSU~x@zO0|B&!soL zNYAdyLxAxM7F)}DiE;hzJMV^f6tIBl-@k7dqjlc2Y16~tAwz|Gxn~fMU)BZB0N;pE zlg(?C7w9A2Pdui4^0(KQFU_Adl{gbbRS}auz&-YA()XTDXKK;1xbt~>7B_wfeE7kK z;UBO3L#q1c!=y?b-W1la`zEYeyUxrsfBpEc!|iw6-grMMYk7qrz{2C`4@WJq zOaA)nuZOvF=Z0tg?U^uk+}H}$k!5PU5cquA=i%Aso()Hj91TxB^;Ed;zWX9Agt}jU zHeMh$;+FsA&wmMo>#n;l{OM1BvW+K9vs=qwPM15yIZ zw7|*lJ-+fA8gGtF5LHFoxxmTeWHtHHcy1l4B0V-)SuOvL+FF-V^JvtjCHJ-bnKf3u z?{xhnqS8{5?q5hd;=}hp2(P^SifKemm@vTvQE0`C95pf`Jn|O;?(r8;(W^NSA7D|| zSg9zS>N+3z=RY$KI~_P7L=gGWhaZ_%3_BjvrcDdi-*~Q{5Ow>JMO%r%45E~Z)z^|APs|tMjtSH zU`%6XfB4YhFn|7h3pdTZ$plej#*C4FsK|LK!`kM#Xv#}}nmvV%Se`sjv!sRt0mdKN z>iCITwrp8={<-JE(W6JhAD{YTxc~n9H6>_~p#Uz`Me1wkaIV0Y@=$uu4!{-7c_xx$O>u`m|*r3lALj8JJm zYQ8U3q)k=N)0o=p^A2q$Ac%VLg%`~XpG}8rue~-589GE7F@qybNznznz*l)gvFhM! zbS0y)K(p%;AeEoUSHcI%zgI)0yk*o2X(g4XDnW1g^^xEV00!sv!r7jp9CFaAorRABRO4X4i)Gh=PbP}9{%WYe?g|%zeNf5Q(9MyM}X~u7U z`x_HPRb|YV^#RR|7UY9NL!l3hNBn+ahH+s30SoWGi^~2xW|H~zGf#`=k2X^c-}Pj~ zQ!d~5=35)}T$m48O)$;JAag#4Qy_?XLFQSj?6VqyB1zx*Zq*MI$&EkvJq;)yVM@?<+PwSD_`me&@s z@cK2tS3BJ>?5e&TErF)c$4Ymz^1i0to>^mq?yV;P#i{EOup^Dmfh$T@T7 zm>>!tumyz$(Z-VY9qcBuP(aX;`USzI3wh;RG_@| z^EHIu_0dKr4h`Y^E87O(1!MA)1W_F2-crm7LI?y=XV0DqW|}8K6uV@Y<{^Z_lmn@J zB#bi2L%FYQ4uq#%0MygNii`#F5a`2b#+*KL+BBl*1MTIgyn{~8n?8L?xbcST>~xKb z7quu=fBA(9loUi2Gm_DG@Q)^)-%&rw`hvry{^F=#M0hvNHZi7Kr4hAGzM(ix2SHSa z4jqFFqN+0H%lf(u|7Ag@Zquy~Fy^)6iNK+>AnIlbq9TnbPRV4Yz%zi^@!p1*nC0|^?&~N|A{oB5Jbr*WcO~}O%P>5D>u`s*`}1Lt)}}@sTb5> zf{!7iqcvD>Syhz>n{*rU<&AiJ@ok#x2`g5t2rs?xk`5`^Wd~EtoGEP>7etBH|NLVl zb@aN@?3cd+ z;oP}%VZ?|LCV;|M$k2kJB2Y5plOW19qAKz^^r2)wsz{l}oX5YlKEL5gW3|-tcu{&r z!pEgcmWI!keiqv3G>kUw+J}j zvUeBLc*Ze|>Fzzd!`97P!u!j`RD?RegM@4YA7aN`X&-Wm5Ue6A?`9OvHG{Jx^) zn`*xLhJ)h+_?nL>EllwbMZipJ>C&Yd?=!-Kzxt*8h76S!?4@Yo8gD+N@sj+WJ{e;p<{{D|JOOAc;Vu38n|c>RrV;>3yY=%bH?+itzpG@=k#_&lF0 zr;5t@T~qj~NIl6m__uk?vx?N=`I~B-hJ)RsiKO`(_?XG1Xg_Wk{{HvBn+paU)x+y` z?%df%i zR!*?~krF;8-%;}I*V)~MEHS4BeGYoUbe=YA_4RuothYF#KrVM zbAClH?`xhveSf8Nf8G@0Ob}HASj3S@T+!C#!*zLO z%gbNZyUR*1?>)`oSq_h}*Lj02i&N$REl$ynS-xU<7&K^5m@;{)j&tvC+EBP^C=UscNK(uQYIV>huWyX4WD02L#;o#|%_220{ z<<*-#D+z%l48gH!HzACO));1zc}d#M2Q=4j+PEoP5dP7O7&dHJt|IF2dOXqZJ@#~B z$Cp3zdykWOYx1|hk2?K#ZNIZ7+g}@X0S90};J4Fy@J|}1nauI~_U#LM_wAK~@@`>( zgixJ3caiUy$bVFAw5u`I>3u2P=Cab$`D)_6I{i4=&SXC*I(5o4U>WmWx^%Hq65C7r zy`3D?lg|Ya-u~*e!Rx4OoNPN~y$$K~%GO(*{N9G@)KQtTWqoVq+JPVnq7T0pX}}-S zrsKhbhs4|cXj)O7)dx^C=+voGw8m2(sLVw>y{)v(e^W>DcV+5q%y~0GR4rjIU&qgv zR!gtXs;vbGIDsgENAancL|sySAZ?V!L7*<>ix2D^XYcfPDG# zCd)OI-+X^Q7}Ur2l?8LsS(x~h%m-t7`t<2=`qXJ-QejqcSdOZGn>MY5$4Dc_zthX6 zW3M|IlZVhy;FD}yWBpwgJRKi=*OlN+U%*!kPRY@NJb&T5@D#+Lb~UHvj%&KimFh~u z(c9p0zGum_=J2~R@T&+slJ%wGT;8)}-Hv~>-VjC+I5D$BhYnhhwiM1IynFrWI9XTn zx93ZyC4X16eaSM}?<+&V;huyqrAS8@;pwIkBW<|j$4{6r>XJ5|(2PI}+Ak{uG0^4p zCVwZ>yk4Fsf9Ja=t-2TQ_V*;)k^EiVcQm&04v&28Hn@OF8_znRMsq#k%-OSnjfl2w z+J;WrY(f)?ycLC`=gaqQf0k}fGH+RV(q$UTy|>rn+H6-6PG!9(oriXLTB$ZhLpd;Ono*pnXE}?P2W7sptnW{zCx4e&Q4@TS38Lxwr<&l5$O>`#Y*$MyB0<-t7ntRxyEW+TQmc_K#j za&BTG4d;c#-dFtlNF$VYCG*rbe9CKQV|nKAPQ%jEliyKR9?Y_A_fx1dN7SHDLD;m| z>uB+F3p;fsy;JJX^Tpl{k3CQN-qV{)oW@0Uznl7isl(Ol_n7+qnZL{L$>aGvCXfI2 z*vkH{`UHlY3biycSZ81%VzgwL%`wb@b#RIH`4j%_Xr+~ii*q^Tt{g@vmo)y z^KkF=ren`b?C2Cox{*0LU9g`i?ev;o9Xudr+ zK~*tbNY|6Rr%s1CWxam#czQB_@;7-skHk#y&!l=s(JXI{a%>#kTz|G;BER(D< zhYJR;F7ClK+EJ7#HRcmcir4AyNY?AW^F8x4k3DY|R}BJ=2TD6k8O!!R9%rO`NWaC) zd(3nHP3(bmRm0yBG=P+Rm$${Ad7XZrj??+m&$Ihtyf`e9FiXQX-!o{sr(1sElY7Sd zh4UB81Q!jsmePtK-SZ~j=jrKZ>K3^^NB(qsypFQc{dq;=QtyrnCDW6?D^h1;%u^mL zlh1$!_nv0Foj%yoMDIDIhI##GZAzGbm;^6pa7^H~6kOvzWblLR=sjGe@>y#6f4rUL z=V~}ltMZLiX?+rR$@2N$Pu^TQc+;hkY_a3UV@pi^N#elk@%$cBglEaTUQIHOr&Trf z_ovJIyVL2leb2Wgzpt$J)pk2#bVjde0}z+Dnh{V=ETHf(piWa!)k&E z38G}KLpqu;E`;#>Myrg5>5r~ldKKH%REjx#>+^fO4f$}AON-_jn{y2J9NQ}VbCL!- zC4QM^lol&NS}`q^j(MKf?|I6Ld7lUJQP#`n+EQKx*|QQ50Co;HVuxiilRx(~&y!BK zG3@<7nK92pLjp4``T_V(kA3P&x53|&j7z;Men@&*&ywY{-<5g= ziu=otqVv#uAM?4g@tCDP54n1rek6DSZ;Q9X^Ll-LU)k8}^Elso{8?q|ZjAZU-|zPh zXJFy*0Iyu81;P9d+eQF?3dQrh@;JX23ooP1sA%3PG4@r?>$i8SKEGG3Rl58es#LfR z3sv_!E7DYlg~#bK={8ut7$^1&{Kgm0Ja`(h*Woc~{yx(Dx5qrE4|sl0Psik|&gJ!| z>ma?XXX(5(eed5`)Ad%kJ|Az2ef%cdmd6tBsdN)c3%kyfG~|kADa=~E~(k(wUyM0h={xQlU#Wl_%UOuf{tg8 zt*-c;UN3PPw_a~9k9RB*qF3i0Wj`tj0f%J_$5OB^QJu!G{ZpdygD12enGpC#S>pjj z1N^J;rCwq%5$qZBe!88|rz;wOQQIsb8vC|!9Nk-0{xilK zeBNbkI@)HF)_){3zI~kMG^gS|Wp(8Flg3s0K2MP*os$@Y#w3=vVR!7w!03OmIT9iuL&1NlWHnkFtF~MLV z;uj|3DjNwRE=PHlpUH?FQtu~Zw*?CmSIn&V4ysp0?D?a2#!q;i^GtD47S#*{9Ou-= z?|hfxLO3woBypd}Z1o7YjC+_JUwC*QimGPEEz*o({BxDSbDn$46sM>2`m-#qJOm8a z;8g#h*%AI?p@KFR(qq#E&@3p)k2$W5;V8eq9p7P>g?q+64s7u$VON4&SUpBh^dx_G z^Xf{*UPoohl&m4UOF}^Kv_25S)A4C(%ID)VqS-&@@J+uk?N{N}=K&kz>Jy$fdfw9B zMtw#%z&ZcpIM)>3pTeoP!Skf=Jv|xc%af)Te(!nxo_dnMll3<0-#%viBOK0gx{qTP zl;F;&f$#$?9RCI@D&*ARA7iIoWaJ&ncU(Cx=_r!)0S1vn}-j@JyZX0F)!IrJLz) zL=UWx<4UpD@3B4CpY*+_Un%zXrSti>rPG_uy~Z2!vuUqtoZ5I6FBZW$LWuEf8qY1^ z+ZpSO(c~553nA2{%azT?vFdg-8AYm_OjNcgkyex~Qgsh;LPN@l6!m5VscJZ>sZx$x z@M^z>UUN!qxZy1^Q<2;)VFscbC=Vy)F+tg`2z@~l4}HQI0G0K6o%ywb@l2P*z2&E@ zf?dhUkoRR*jY1$djzMHOm*c}?#|gN%4iFWjA8@p2)D&On; zJ?Uqpm-Q^2H@m+w1bn=^FoAmu!WXf@Tln+KU?1b1F^mQUcqXWTl_9SzaU=Sk6hwI? z#NK!K>0{iVm)8ZoTzPrCo-D2q1kz*I`v8R*yYvn4%NQoF&>UaP1qzsB3x`p^;d$J5 z;;~O=o^fgPT5Ngr%jXHmhXs2Y{qZu1q+C78wB+w}nRMSu-{;DzS>Co>T2uJp|+qpC_Im3dQ{yk%C>v>ucg6LEiVoJX`<8qC7A`}^WI!Exfa2YFtX;VA|a zX&!t$bMJG4DvRrnc!3;r9ao8Zy?)P=zW4Mi#mV+1^ZK_X)0)k1$Gs5g8->oF8=Rrh z;7S0=@$9;{gd~t+d{IZF5ryzNLZ+2tPEaAQ+hCroByNXS8NJc(vN#h&WqlxnKqVl+ z1eIe%U{GQv#U}xXTSVYu<_9{be-|%a43~8J0zxQ`{$%GgyXqeThAW$eQf*=4(ZAgM z5i=IKT=B%@eE|luGi3sv_cp8a_z8`;VXN02?G=mEDJlc_$pjrYeb8s#`fOHGwi7#)jk9WWK*z+ahg8dKFRvpVTfQp%@%E*Q=GvHk&>Zd!0s2tI zz?ooJ@pKw z014hZbm(Bg7PLy|^2smBFj$&TmSoB%E}&2&7r5g8<)0!m+6dQ?y0vRHp~-}A2ZY81 zaMwm5S~SFJ-9jI@^*~?Z_hpUsOQt1-Sk) zbqF}TUE}ex@N`k*6dKMk&CqXWFnv6OxAyJZ8x0V5Df%A?7EHJxT4826#KJx5|J2EQ ze9Tj}eTVic6fwir`WC`_yofQp(+!HdLjDhQdT^zD`Aav;RL6IDAMbgH?Vn=igA1C| znb&=>YC=ZQ@m3NlfZLW@$f6yG*3@P2uW;`CIV(e5Xg@+X+O=&fA%tj0jPINvibkby z>22W=`TgEw($iP+nf0YOLs`Fb<-I@U5}Mc#!4`bl760ZQJYBeOAsY9ZLQAJ7XiadrIiKgT zME=B0&fQ<>M`iP0slF!o9Gz8IlwBKzX&AbsyHUEkLy#1d&LL)`rKP(=x?8a5p}Rx6 zyB)eg8vghD4>;q5>tetA+0VMyS}VZ7JllA6N1^U<`?>7l(WU||z@hK3Znn|ko6DaC zR8NnfX0o*zdB0e1qz-R;mey`jaK2cE^k-7*Z4a-kYssV!?P7YLTUih3fdO>LSN+@* zU?}Q&{ox~v&L6jlMY2nOS;CzM%6f+S*(qW%9hP7?4zGNd4I+uwYuuGNi@PGPkv13b*RmeZ&trYu-*5Z{HGB(Btlk#V?MrTvCzjw|D zy4q}Fey?Fc1O)PkTrKX0G-7T?=CPJC98_X%TIc6ly1G`ZzqBj< zt1<^AZon~@`HobGS9uG zZ@);`%j24Yv|X~2dVCJ}Tg^(6YL``kSJk-4HR_H5ZyBowl^*_>M&5h2DX;V@*`SQ- z^){b|iH3leiE=yPyP!yt6xm>=lw}b?g8nOD(^a_FtCE_41eJn6{NlI_oJ8lu++)R% z=*u+>;Ipl#Scg^qmeLy19IY9^KdVkfdD|}F!{r-HNy@=fMtisU7M96mVcFogDtAL8 zDcADvcmxGG3!8@gGS;>K;cJg__hwH-In9WFb0qxcWOaGC-fo@?-?uQiWZ$}81?Qdg zrPS6w&4Vz!nAEiYa>vroHMw=`+^T9)_~L28cjS|PERFOR0jh*uTR4O=xm)t?E}{zK z(fwpb6q`(h?&^41nD8yVRy_ADsUO?9Fl;W9z1EXb^i+mZ4o~>Y!mnK zn)u|))!q-$mYCamE+M?zcN;g~u^tI8K40gf!JEJO*pC=U5n!hxa>nfn6q zyQrD3S$2K7!ms7vkX zhf*CwTU01~vbwm$iwW3Bf92`ab?pni;c5#V0RanjcIlvE4d`dEOE;HD=&!0O9&Bo{ z8InR1fgjb0bt;JPphS~vTtpN?R%Qv2!Z0SRDWU<*(BgskXjxH;W2;ZLR%ZoW77JCI z_1|R%2f5O3(1rhsl(##FKUX=K&CtTwf`+UwilhTyzA`F@6EG@~=`2^v54>e#SL&)H zRFil4Jf}w`GaE^5#*@T@7XkAU@!fM4`KdU>yZO-SA-Fgz#J?0nB{wnE&l!VB!ibD^ zg-0#!j+rawS(B@C0RCO;tQd(Z8MrCxydiV@{DABc@G+Q+B=0I6V1UA9L(ns|ihxx< z%gT;xMQ={Z9?|UWGu(K_Zur|jQB z1kbN4ycPjkfnTWd)NX@RYec82rRU2hiXn@LwnvQmB1MY*KsqmJ`|^1%%2z{uHf&BZ zitq$7$6zbxNQ8r&{zvHMOBF;i_!qEuHE3jNE_hvsaZG~tef{cmeLR#L@D)af<`^E` zrrIZzdFPyF-Vg-9tJ8;+xm#m**$Dt8@gSP?p39i8D<79qcF*x39ovg~A19R|L~`GA=!U(!hc|lv2(UBFtqkx;anOC9aJrS;`-i9OU*(;}`zM3@ zwU~9b{03yAK-MBr2L&Ce=WC>QdpZo*-oz;|C2F<|!u3q!a^C9o`ol`=ku5z;130Rr;k^_7l>D=c3bYJCu zSPz*tkf5Y+K?!2_JkLH~E_FDZ_@Ohv^BLvw{;h+Io3Jl~mmES}z`B2rs6ZfZEQve! zB<9{jr|gpb$3RV#(+Pr}@&m_@UW2mN!_s`RGpQCSe+TLC36jWgr7Qqwk@0Aun$do_ zULD2JPUPEAd7Q_j#rtu)hFDHl0dq8LGJF;jL3Xt)0d~4x=V>k!?V%wCWLHTUnMS!{ zhxPWhdT@>HjcK-3yedW*59THc#rx?}4IH3?hnI%7T~=!2w@z>vdY&FFov z<8_=)nMO2k+-RM^X5pH+@2zu~1;A$VTErp|y-L>k5?tdmo7qB`Y|X{_plyM{GiJYn zS=vb=+q)!a#~B#Vt;siQH(8_jo6}WWjs;r27aT+->|snM?r2XYVO52iq0SW=dlXxX z5k$UP-iIR)wBcp#f>hhhfM%$ruTR#WK#@T`}b&V4Zm*wUfwrfF*PD^ zd)=9#^t=&P@K41V_8Iz zlyvxXQseMH6&OC6t;R^AF6Pm{Dy&w5DoPitZGaR*LBcVYMxx6E7Zw8jcucou9uATD zLUq@66M->6CBmToDz0amkcmItX|YxG_wyI`TYz)xNu-x|;D;{3pce3v%&+0K&i%pv zHiAwCJ&#CFgpE3>9*Wdz)kQdu4b__QW$*yl+Sq;eLwEoQ8wOK3r}tiS1Mic`9VBq~ zI)kstKlMAE+2RV=@10I_AS#wWiV}*@%Y>NRSqK`_w)@=$cQ?f*2|Y1ld#nttxqXe7 z71hn*yl~(Rh=}#=vTTetR6K_eaF$tYH&B)b9IcO+_K^38!t(m;(LsgF4X5}lKdF4p zq(Kam@m+4LQ_(KH%H5D9eM@i+pUC;oEJ8xNJtKSL-YNy3sJPNxagQZ^YvfEEHX%9! zwQ8u9O>K8TA$$*DISm4B<-hkDkA_uIJUT5@(fhV+8i7P{vz?J-8MDTX?cJ(Dh;6ij zUvztg-_q@KkypU(tWtF^5)xbz+Pwag4BW8CUKxY0JD*Q`NX;N4F}w0a@uQ6VUAE70 z+bk=Cx30I*^KsBA30N<65ebb&r7!*fo(+kowC0gh^z z>S4V-BWv<{3`P5!OcJvdJ{utOB@Z~+I)5xTByTrtnj)L0UO&dCJ=fWrE=%W?R8FYs z`D}=U1=V6(@qakRY=|P?w{8KeD3^_XE@A_1-M36j^x~p-D_~(Hh5n)KEufP87jpa= zoab`6lHF4o@Z<#uxi!Zgd@8(m1%luwS*$sL3T5Ch_~*UAc-+{7j<>)-vJzr8Qg$`T>8BkXES^*z zI!Fi1sWL41!nDzuJx7%Dl|AS?zL0v3h>C?}2A}ok3<>ud5Ro~Hh3aJJy(!j|`{5jg zYxBEqwouBA_F|N@TRJ(N_~&5nH6C8}THA4;d8T7&q=9Es^&~}1a$qt;PgQ)BkyQ%!I`^oFEKjjkwfoZFd)#n6}(h8{WWW!f-rC8QQ>3sQREi zy6$_auHWKeve4)PUTB0CLkF+-R|hgJ?5VDuhqn`#C zOau6W50boHY63fl5$lOYYVPf(ZDPL->t6d-g#95U1STfIB_SO6ST5yB<2EkQYx=0( z5+Vzfm`SI0gG%Zfr_V?@D61G8d#(`qA`6!u9O2MkmF-KRgcvNtl$Un}S|m7UPUn0( z@BXtMn8qYuszss4U7|H2dF}~aW!}}Pw+PuNeQ>*QTLAtp{i==CDyw}$A~u;9pX-xX zUv3T@f{P#)>(UjbP@8#mTx zEe_xA{t8+j#rtW7tr+@SGRnA~gb_JNdRE;> zQwnz-L0h##07{1^)OZ~44A%+2}CKPIR$6M-If^SSwp z`ihcQ`A5zc&Lv!^UX3wY0B~#l+on5sb`NL6iY1Y8K;~`Z&&twb?3rt9#83rv+@tiY zf3iK~{!;i-LA#JLADs-wu1RphlbBi(Pf@o0vjKoqq&)}G#e^Lbs=K{Q^JNJysT--h zUqYEF)1);TOhSL<4C9$-Z$7SHCUz8__46fI(15lwXB`p^ReV)9pFLpScNvj8Kb$o) zGT-dt@`{K*W>gn`>W`S1EFQ3bJV`2G7@k(enq2Oo_FS|0xm1#A5I^#;K>u*@=T%xq zga94S-+j)NZK7zCTd<`g@O)-19MD)61Z(>o*Ue`Q;U2uy>%3m-7NUv$%CEfNXea~e z52JnoYq%h4? z=@3skErLdFc(y||WfuHomiQ*nNXjOQ-0U-Ad5kD2=7c~@N$CkUR!gb=yAS7gKzr#FxkT}_WnN(v$)WSdjr)M3^ag&3{3yY)0O7B3K`2+k@AC~j^PcWk7n<)`Cym^V zIJI3vpVwEK5XPmIvdY$NMQ?WbQ{J#Z72Nr{+pl?YRzCW_tEv9K^AtfAr?-dbFT>ln z%1vY_u#j09XCvRREx1sz+R}ZH`pdq(6uZ%PZ!@C1(*HVf*pIvGFQS7$MLNmTJRwIN zMp#%_P+gAQdzzFe>Gtk;h(qM!ZY()}tR9t=Z{y#ffT}l?mEW38St4JfCUMY*$nc`j zz3pFMi&DXyT|2E0ur=h5N$0?gA>|edb~~=CjcuY5xB1NiAX?Mmi~TX&?GTHx98usW z+uqjU@zw=C6W<`Pt5QTZeEon`j;{7gYuu(QkUbBS&Xjn+6*JCk|0rSXd3?vvh&6wiX$dYhJdlNp*12#^e)+J2dQvw*3FyN@|btZKwCyI zrc0ijQ~M>628#(bPQTi$ET6U#t!eYP8Xs4TH`;`UCf2HH9kcF>#!FUYa*ur)it{mp zU{)F*CB1y_V@EAITBaG5qZ+PYa^ty}bKq=*%r~ z+osk1DJ^fB6SyligvS?(P z8~(g~k;DHm*Jp#6rN-TQ7994DlzTb6N07e~bR+GR4J&nLyd+CI|Ib-Da zJW=1Gr4cmK*+Ha@7Y?;5XZl_BXV?2BoUQJ$!?g6#Sp5b{UWL@Y@kcOiB;~{iM%uv} zAj_x}kCE^KZ?H&%@MdF{hehbKSY#{P)45cugh5$@*{G7aAH6JYw=TKurOc5pK05F) zLb_>*{ktZ9FVbwXyV=$fm-@$wS@8DgFi2kFl9CET* z=$#H`cGB;V;_z~krGv})JXN%u;(D(6rF#W(cTbH=;VswO;xRHA2b0Pygl-{9 z{AGbEIHj3iY$uR}CrI6k7<;a|Z=Mg(3O6GJ48iL_+1U?Xf_rI?fF7jU&DipXP74VM zpMSaT<7;s{4)eK+Cnc=$YfQUtU=OQ?5LVg?blO;F%@54DW3Zy9+CzqLk-bqz53NWYz|DMgMULT$^6&06;>%;!qchVC9{*t2-xKU@)>vU$ zxvwg4ROr|$+Iu9Rs4`{n6Keg#_}Ha8z#k1GAgs*i<+CJ#wCt)L`)xem3=vJItC;m+uAaZ>FX7 zUCSJt@kLmt5@xHPp#-Pn>_NtpA_L%R#O#;J*6jwk=_?~^MS{Z8+)tVTAj z|LkgiD+C46MdL&!NIkw~G5p1t+`85lT3c9HP$gqnEf!hgZs&mQE{Mn^hkUuu-fG_M zZqQw}Yv#oz0R+{|;gxFU(v+H&^MIREck41fDNA(Cvs}rX@w&n}IE`sxaX@wLbYQ$* zmpz0&_H`dROGi%!t65F~^&O4y9qjW4il4F_c_E)Kl`GGs7>pK21a2xo!ySdLz_wxl zULTOodI#apq*LYXxH(!Sg13o|3*~OST552zh0h5a2ZTUn7*h~l(B1Keg_m+Hw_QfF z1pDz;T*uqK*zOEwB`=cIhGtP@nkqVU?wswZhEaOmcR(l>VX(N~J&tOShwwh509dM-%+-P<`Wz={18PiIPz zSu$_qx?89FyqkQ>_K|(QwKh z#sn!#)}k)04KI>ZEiz4yK8&A=AD*qShsqn)Xu^jPUt`hEbQ}*yCWo|YfWc^?)cIA7 z5ns)P?EuDDZ7{GPXcfmfw(2X`donywmid&BQ+G1FJLPZ>Z=lj0uHKpDU zzy9F|bUD5xR(&q!?fPzC{K~!f5%(*eMM|Bb_dA{h@{?bocHAgqPZ#S#YeZNXOly+d z;#(O^#d-m*B30%T9KDJy_B?`qF~%S zn;}wkkFDqZls()5*YEyPJ7Q_U5j;-V(bwK>tWhTSeFzTRrp&mY6pJ;W$o1`_BN_TNv7EW9i|Z8gcr?sozKc~6kt~CddHCcf85=uP}Tf& zp2H@<4hTG*e?vPZFV1@4{J58rFlf`n&$R|tF$}~tr>=)nyRI*(P}$o38ReyeJ<&32v-?52*Q96=aeD+RX`z>kSS@A`)nh z!4|^gj{Jy6B{B#jdH7?T7g#kEragfrkVhb;Grl)jJfp1C=igasx1#JX-$n0-iNgVp zOOSqE5GdIl9^cET26qFGU3ITbFpa|BGZUQO-qbWcANGATop7rYSS^L8FHddOtn;KQ zMDNb%4WuJ!TF>E>r35}bar4=87oi}cx+Veo*2kOlzLz%pZdF(|Pi=>~RKP$SC25>N zTo-MCjpH4=#DnyB_{-hl%R=~!;Jh)|a4G{V4~}hcI@z8jNQ?v?07ztukfU z(htPFWO^VPDM6y&-!>zCpYh=<0^$;ndp#`I9^C`o;eD7{#2mUYZo!7ylc41fZM!Ev z>TfON-l#j0yQs>yot)s9jSaG)Io;yjE5)G8?VzibdJ}Tdn+JZi8W=&*Cgj=R-;jrj zSM@|Up~W7%8>X!JovsoJ;STYp@$^IVS|9$kY_@r>#gJKl`l{On_bLy%?4{NnM7gulvS~2szf@6jEPeaTcv;hE1YIDD}6BFui^y zF8NPRWyMvF;RYg>F`@0>I*|y*Hk;9hGyUc-8`r1Rulw@qSD5p<-%Xf-n5aX8Z{P-c zDDs<+uSaI1vO3a-;K0KRR?q~gw3{!?oefjM_P1uMHS&L5LCSgempcH;k_mW)@^tR` zWK+Q3;b7Xs-mgyIEoEmaOj<_f|Bz%Fo2Q{$D1mWmb1S!XE+^7Dzn%lbW*PNK%P1Ar zs4~jC3>(X-n-Tu;P@oBPsb3VlI&gM#L0$vhwwcb@DG?fRqe(kMs>MYi%?OaO^VJ@9 zDt^b#v-9qqHM`5<`cYIW=jmSxqY+R3`OmU{1Uns8EI;{}W?^Hbd7dmVA2)m}CFoNk z+@`wxLnHZxEJ2z2EBRmZWgeM_x(3|BrtiocTu}R$V<+ygbmBc$O;vFc9b;#ZW~Yb} z1|qfWZO}jLm}Qr#f<_&RWQdIG=ht2@2HA81cj}N* zt_fcx!A3nV*`;cGj)GYU?+fDT=uP4HVOKAry>sqpx&y|$uRT_zo2V2Mkdf`%r2z?j z)wExjbFHldLt+=-nDd3N*JEw*p37GlLoK(R#%Ugr9I@V{RVD_WgU^v{>%Kk)j&M5F ztD_6in9hYGXMd%3BV<`p*C|u4!(kTUAUoY4j6v%^zZ{pQ%}XB=^6z(c!#m-9vD%)j zux}Nk`0N5)S3wL9Uu6pfQ1ImxDYOX{q9zKG5(0u0v7~v|xfL(yKW`sVb|ZJRuCr7^ zWD&V%x=Bipn*F$ZF63)CSqltYU!HC#wdI&8Eg@KAu_CEx{?y-gSlD^F;L>kLSYils z=4!GP5u7^ij-6t^hDO;}>U_@F5S9I#+wd0|Uhe7OnN59SSD9_y!W;r?QF=k_*brrf z-ET0uTE%Qw&iyvnbX+WSO)>0DoYHbwjhe{>v;M&;NtZ7 zv6RY|V}ap%g&fSq+tiu9>^^TosT5Da9ycUdD%j-h>PFTFEPw1Nc*88;cZr@_NPzPc zU+&(s&}R!fRri6qZGkIGr{#LjX2gLdQq}TDy?-%5U;k7>(ds0F)m`*o7W4k2nq;+7 zH0b=7{#d(i^Gq9#$6NWyXFS2*g35>7@DB|`kMVIBRMVDUE`cTSvIW!2IqeGp##aLe zCN=mCy(otbSC<Y2QqN!>V<>&*$u{x3bd~ji55hx( z1C0)JstX}XKQkxa^}O=OA@UB5$llS)5har)HsnT8yNQn>;ej^H7ZGuy`O0kGOpcT> zFL+(o1%w4W9hyzqiY%0g9e@i#>Hpr@} zTrdv&NR2euB$k6#m~!*Z=u(iD*!cV%zwFE_*%WKY82;d!$fVkCMM9-lP|xEOvTRDG z$mW+WOIczCwC-^^o3NuP(GL;16Ouk2*)rR*cai1;uezy>ypTNu3xEZ%kZGFmjsSSA9ZX za0I#cJmwJeJXGh9Z5<_jMmgxq$B%yx+@Y&QYv(78yT`FcC?Jlv^#Kj50;^}7h|l`p zS3F<*mN;9?p8dthk%OK0pHQ*vd82D}G{%}9@>>4xTvV*=bEL@Q_wk-WdJ9$PSF!Jk z_pGFB9b2wFT$5Jo+cc&prJeAQeh^|?DKY+>k)_Hr74fW8#44rSwQ?MdZ?fymk?>Zv znJwF?`WT}NDk7WDSTm32)mhT&fn~=#M{O@RI3?sPxH1ry8XToH)BTK7yPPPA8u8W3 z&M&|@K;|j+Tysy)glq^0PiOvjCzW|v4v6xyP+&0eA2|gzUyABP-*hNyL`@cLpp?23+H5>vZBD)1n|-Bw{izKQv#H|DNa}ByEJuo| zN4JR0-rtf_a_I0-QMDlS+=cICXg+gc@jW{X?e2fxf3R9B{YUAAk1t2(CJ=G8q|nNy zt{gg+1E~WKXygXhjZblzB%y)Tj5Hx&kV7fs#dWYVVZQdfnP=PGrTjF`i}vMumQ#er ziogvEs3>o)+pTpIzl$*f@67aZtn=mRaP}=k(DD|;C{`n7qNqT|#=_pJcj@0*;Kz@V z1*^=?e}hvm5@$wsQO(m@?d4TKv9c&3Ip*rO`Mb{)&%28qSyc#B#3aPw-Q9A~wyUIq zn$%EGdbd!VwVE&ivB%+@3G7QWwEg;cc>r=X=di5CACB|$@Y@~kOLz+!lB>kipfIce z3xk1_`&qZ_hw9!+Wq#(?_*aD5VgU>F+ux5HEhuBjv^rhucL#6(eLI*l>#`9TwBLWG zC;7wG&%XJlNlpK1$WoMIor9?D)P2i6|15j`X>Jd8M>;KrH>&3xbw=2sHL`i@zjX!@ zqM9t~C#I!1Upk~RzxWA%rj_>`WrU1wj^xF$1~g1(qk*cvKy-mmKYD>}rM(2cvrW(t zYB-`rH*1aHi`67+y=(ZA)6V6#Z1zk}Cl9DQwsWuI@zXcnUutUKZ(c6a@uC;0nY)ms zg4_%-FCjxsuycg(Q7{2vgQ#>XPw-3o6N%Per8=7Mkg(Dpo2;nXOOk>SSD&>8HADv< zP2ZG*js`3wxKwiU!|<}+U!kLDqmak~kudS%n$bVdcQFtebD-cAOOM*^7HW&*<~pIV z^Xtxiw&`#0$M^M<%QWV?i|f<`xia{dfQ?M&qg35Y@T=V`YfzE78_%|aSJ)|?$K+&{ zx%Tkn#X1f_*I6(3tF1PKQ#=U{G+m%SZx&?L#7 zE4qe-YL}tBA zs=cwS(D*>bZv)G%m^XN~1Q3+Cf_h!%ji5i^e!`fVI7&wKdO-9HHQ^iYd4wBgs@3Rs z-Yjb#klM>}c-^$=8`BPzTlZTHbv*qwZ>f~(m2m)4*> zz6N+!r7Zr%%?|}{-A`yQc|dG~ZSHX>vgXjs!-rqa+fQ9;!hNAbyXsF3H#jdE>rBoT z=eGHrSXd>qW6&SJhm^2sS!hmZ_{-j57U3&3(G6>;sACoBl32_bIYGf+o+ZvBNSU3F zs94lfk_E-)$%ggo3eMiKm7)0#GZoz+$9jWmMr z+gXy$_ZAj~yb1XJk*fxaxs0I<8$0;oRwxu5NyUaaR7HqE^`QjcVtG?L)lLogVdqXrWJ3YO6#TaIlsIKdy-ql|!LU7%BvEr!i}q)f2_z3& z?9C@aDpnVZPgne7GG*R$Ss@-a?ax=X@8n>iUF-iOyx9W;^!UA@DNa2uDw>MpiO%Ko z#cNU`W_6{H+*)v63w!-iK2;){U79=7#d}jyS=FK>t9F{=t|xR)9H6i9AWeNl{} z)q92bIB;}(BA%O3%b1fEKEp2hTDmxF2kQHfD?t#SFT%3ofrC-hpO6iC3U04RE2^VEa`8Z6{H}1h!M3D9s+td z&|;)6zJc1)^$ux?%Tvuinlsa164sbKy1Wq}1CF`910WxWb|>=4BqD09yA0xz)-4*0 z2qtg>El!u$FEAn-F|r%jv;dl zNRT})#6o<;r9ZdU$OMRlHmN|YS2!zf2024VLQe2qJ5}QNSNyFXWqCcmP4Ru!XKVuyo{pl!|NTb`6d^W76l1jg6F0prmh1F?3v-1>E&>Ogc(&Cqyi)4()hFtzMV&3Jld`0`3N zJj)%K1lL|7aQZurG&$`#kXeA@+v9$^s4O*jf1nj(aDZMrLY4ijk}r^@t1e5te)zNw zo@$)B(f)LKd-%j~SH}`LMHQHQ0ai|k&@A~8?Sq4&Q>+xnqw~k$;zdZ7CDRth?rvz9 zf|0W5++Rs%(~MEXGfpW2DFEdxvPpEJ{ zw#klg#ed3d6rqnZq0C^zin_6pJ_I3cty*Z|(TY)t#9!0aVC|Oh!*V7ff!Ri&=m_@e zuVU?xuL6_-$i9mo6|H|oOD7^JB&)kTCp5V^LuElca-x`tGLp1TpeCrFsMSs^e_&pa zV5N6WN9P-L`lj77<6aIeU(4s_MDRHE!v(3cR*Wvyg5_?4(#$M>g;3eI47e77+U`9L z-{`}JWvQYh;LSvEI;{QFFjXZdGTY`OEY6#t$R0dgZ-_68 zo+E4RNo|;9B8ZHb@!ocrvDsgAF6(xv|1p!_QtTT+5C{+Jy#R|wbpPqXc`g)2SCS)i ze88jnERWAaCG9^#HC~zCPlS#uagGkS39|-<45?7#JCO|K%(fs9m<7JV#sUdv<0QBr z1;&AIKAqm`x7MF^cK|ne_l15dCh=y?$UH*nXzE7;hwh{ewcr;R=ldYCrFe0VqpA(} z4ZKiq%Htnnxy>0$cJJ}8VJO<^+(Rq!F@z*t4wvmU22?^zd(SQfEX^_F!q7UWc~6VlWHv-ydB7CO zk8za3pM2|uX=RI*;)T{_F$zgI^zrd6=^`n(rzJx1g#uzsT|Xc2=H~gRE$KRSJk<*@ zttHKkR^`xPn#lqH;aDLfp#l>t3!<>Q5m)1{b;aTGc3z1q7bJ~E3Ah}>kYtv6C@FI& z12HydqRo{3v{xpVw6r`kzRhD-GVg8=x^ws1z~@4QinBXW4Z|u7`g2-E>KNt{o3*@h z^*tb6HsJjgGYa7q=TZm@6NNUF*L25=%y~!%(_r4W>+U*2g*rW{I-SNIZmYlej`?~A z2{-3E$eNcTcfWtU{FB<`1!Ibkaa{RS=A>-%p(aCtUvlwitZ2_wJdG zqLG=x%0xK#Yrp;3`Tm$lwkF>nyTOQwLq@6(U>X#P26bfvhIvYbJf0uh{fJQ-_0{QB0hz& zH;mJw{oGkxrvX)+RHSAS0R|dx#h1HK@g#0#nCxe^(9lv>`40LF?pQb-oByZ?1`iud zMHc(dJWoc3s06bMdGuwL>iX0!|CH?{e{W7T>F%pwoHmz4f*UM)rc6in_hCq5A-Ek7 z;wYwr&4qmd46(4Fpff{5?F&9%x$zI3OW5|^4sG7d5APmVDIjE}$mH&hk6OR_2x~cZ zq0I--*A#njZ5pyezfKUYjr%|;>05r{Ar3SQXdnZsV$j_sJbOsOi@7|4YLbC?N7(Qc z1_MZA{+zOJay7@lx55hx%Ikc;l-K6tW(k<+^7HO=8hy2&RJz&re6l?pMqpU^{1Amr zyLh6k&L@+pilfQeh_%I4l97%47*C=ky^5!yUd-pQ*$*|tm}!p2i`W`S#R0Xlu(1Br z1WtDZQiakEY-tyiM~|Y+X7?DFUL6!>D)6xN?Xv$tJxjpAMkv|UpK;Rp%X^JDQ58~k z$Rz=jNG*?Iqqjn~0UZ3EC6B|@MPIGMA}GctY

&(BUU`JKuAs%%eFq7W z#UGFuDT5MkpVB*QD#qkDBNZD@+<6_4(-ItvTmn-Lqxum@KhG!*zpV+FrTzFD&Zzj) zh1B8Ahp0b48J%8!4r5Umke{N{JS^Cru;RqQM=>+tg~k&d>w#xyjCk3nl~Na=aI~EB z@GZP@>F=5_qI{vZzLH@7a9mzsjTpHX1HrxqZ$bSxpYOOG6kxLy=8-GjYMAq8;yQ-z zJ-`T0?#D)?kcybWAsT{!9|-A6;hX25%t`j1jplaNZIN3ddQkg0wofj?YSWO?hu#9l z4}e)O5coWld+Lg9kxb+@A996$M6H(*j6LAVHRny8arWavqy??EN`C?6> z&5WWgb{!g%d`9w)=k7-ib!DERB1up#d*jI#O5UqBlPoZc_w+q9$~ z`a0%k^|8TuQx1zmwGb~ScG|G9H-hXELHuXFZ#4Uj<@Fl}p`P@0r zwjz~_&-=GFTIbne>@iqsP809Noi_qG->WExl*f_a*^9Vz0B(}1cZMVWvc;3pa))t> z%*ySIklT;Xp?O{xpdM)~wS)6Gw8wb!XggU$A$wbJHvl=PgMUMxpV>z5~19 z$(xYM+ZIYPp@VOtP3IL2$U0{UnM_&bjRv=68q&zm$)V^PlHic9=OefB8&v1c1NOCN zlA8e&=Afb!ry`i)LTKkVB-SF?Y2|lB(L}ms>e*b!8BmYmA}8lgdB?9j$;os03hKFH zqg2M4NgG&Q3PzLvh1frs^gkEK>~#v~UhQ>4F?w(D#3b9;>-cj` z&#K_&V3tWnx@n3@Gm^#$#{BRK`Ksdhb#|jrs}Y6VEy49aor19_&y4yq8`3+Y z!i>w#upBjf<}L+cbp^+)0d@&9-{-KI%Jg^J7U`VE6V97n9*=?53+A%J3Xwe{w)uWS z5;sS#r3PV%$Pt-3WtxKd1WiJdq&3fp$jWg~Z~1S|C1Y^=&p&TE?@w9Vl=hqm#vVix zFxsQXRwu}?`xP#=+0;F%KzFJ7iAqVQjgZ8501VOpOc~~T_gQ?5yh9G7K|iIlS5DeI ziGe;+pTdj@aC_pMd|K!42cdyEDLCWptSvf&dr=~~8_aHF?snh22yiw5%zjoNA(|UZ zt!c#*rEFjF`F0y_Rs{HblxXqoH_f&HTMcX@hIp^%SZu^R(svA2Vg|id6;Ej@_U;}2XxYRXNY>TiV8^DT%}K zQ|?+ii^(jqJu(--j4pL;Do&c9XqA_I%PX$z#%ioSCz;ltj-1+>5iAlK-dz_zZDnpP zCpvx>bvu|)ltMbi@O&HixD~^9{+=yS^vVA2A*)EIT4~rGFIoMd&1+w7p)`!MYd{M3 zfOk6tUQGQi|KiW`-y0G=G_z5^JZJrHn+0wVE<+6P8BkM8INgO>pO+3Ts?{!eekpzLvrt6w3J~|x^uvv~ z6_I>dUVmnZ%N|#wjF$@Bh)$F!K=7SMIp+R_JN4(w$D(n;RLWDl{ZnnRU;wG!nBG|C zO^3^X&cbBw3YBRvb;{HP{o~q^{m{xzTQBP;Lv$3&6f_OPT((&kh88eNmLlim&3qm2 zI$lm+a02cEo-JMbB;RY9*Am1v`4fJe7t7TQaAj-)qRrz_v<>(V(UEur@tL?tijO=t zFD-WCP5J{X^s84qR0!CrD91olK$=s1?kkcX83?UUbIXXkksb$W8Y^-LlkY};a?9~; z=}I?_wh87nF0kA31wp%vLpnjCM_NAPUtW29P z{Khu(-><>_aZzKe?;ltTR6YP+r0(6!_lKv&eTiso*UF*VS3iz^N@7%r$IpdiZvg3# z;HWtCy&w?1BIQJ+7;Av}pTEo2O|blZycF3tNI00zk(%tV9}|uyEYt7qQQBqt?Sg{u zUe$c77ke#_sZuE6$Gd`lg?J# zk<|${;sd{KCPWmcQ$v{d(66GBDJ~D^0~pKG6*oJdkuCJQcqaF?H!0!_ZV_@4Ttz@~ zWl~$)6DdJ2@z< z)!!alC03T73c*r#QAO#M*-ZQD;|Ux7NG zAyDEy)l~-~UjTWm3uM7{RNexI-4#}NZ+BYs{_1dM8}3^#M4zKSiPqsnR~m29F|}BExLPo zw1fI~3S^O8V^BynLco;>y zWUPD6uCx4Nlm*2Ne(OunIXEHpm8^xYRXoLxYiyIY)EMh6F2e?sjv92iAvsESK%;ah zSO_Zyhvb(?`D%kxJ}2AatWu;4fFPi1s2;4D2*|kQCA*2tkt@-|$16Hp~W<2Dq=v3+`#IbFZe zdvu>7#G*l(D|C6(a@sP`FMKPv3|-5<9JRHAnM0w^&+xG}#o&<`LOB}jL#w4a1=drG z`xu^(=dOL<`E}>qIL{^7^`SWL`~)g&UiGu(*8}@sei>^cbL~}a8NH(WAzJj)O!4A0 zgy(LetH&mOsFdirJsgkL2Aq8t(9r+JM$B%0Sj~v?UAiFLsqI>bh$&Mj##b^^w89HX zh{DA*F3`K41RPUTxKV+{9wge8d$(dK}{q5F;2gAD#}KuNEw_ zX>`uaGq#I1qv@hXQ3TROLrcIB@gCj#q-Gpg`ENET&u*)eFLnjqtWZB(f@>4wVsH-U zmyMtQrq5ia?ui9|7p*_x<^z+4E0^ImCk|Io0S8UlvRs87OHsB<2Zz-f!x$ z?XElVg1ZL>UJVPT4qTz*Vu}44RTLr=bu0LAmfPZMF(V=0rSPE1NkceTn_oL&rSJzaYN@QrB*9f|L#ARBp2y zAI-Y+#K@V}*JmJ^<~7nc4$aHpKz;`XGN~qm-)~BE#di6TwJG zDgb;o3gErei#`UfMK>!aO4^=#R#iM1|g$o_EQbC6~+vE-rMARAsv& zeZ&i$;<%F&eaX51ki6ZF)Mc&g@u6IL=Hv~fZhA3o!L^sH$hL5nX3qCPG$bTj-%g8j zAQt??rl|vuMOMU+yPiOL$~yP(XCxLoq|gj|j!q)yV45rBI zr`z3ydsK>(pQ9KwBuQB-`|cNsUoMKeOxgD2IoKzqMVmHkbH!XgW9FG>wh5y|j{&Lp z+D!Es_vj0J0W5#lanx2py>cpdEMG>r^E^GeTS81+Y6Ph_3$yiV!=~Q?{AI9no_y^%-$A2w(vL9^vV7#A=ZUFW$mQB6iZJ%fx-{? zlhWNW2Tk?u{9z_M^uRo>^n0-)>~3wh8{bABT`--XtT3kT*nLV6 z3^UNuXo(?gRE|~YZ6l;FwhrOuQ1IVAit4?SUR)_kPDtS??F4vErjPWr?eV_$gN6o} z|7@pBAU3A+w-_c5m%4)AQO=FfcCTrTxGP*PCIS%lSgnZ{V5da+4uv8S{Z^e6w07>0 zDo4%_rv8HuM_+_>^(rnEMnm}mN|QOTQx4UupB&TE3ABWz42D9@gq7gWGCpS}1H$QWxrIgH*ir>Bb20l<&7a)8x~M1>jX?mgk4ObaAPmW%&ZpV?l#CVLaQW9{M?(?z~?H5`kk=mm5aLliB{%_bY#` z-vlKzhuM}q#MX$|a7EY*;2-5)nDL)I>5BSZXA;#?^rp=Qq)b(qe~6g79NV)%WGP^r z&{LI;G(3{37Za`)Kc$N$Qc}dg17DGfdA?)3?WSrl>?_T4t?C@bB9A?W;ew2o|%*4qkxNc?J_F zv#1SWA&e#pDJl)s2V&B4p$O*KP^mSNchzKO^~`-c=?{v6gAa^@p4VY(>HXjGQR7}=ZhUQW43X1-`>xUT0%~`|ufy~`6Iw6O$-;D; zRrz7t=Qu{~yopnBUR4VtFSRBvYz;IrlDBs8Z2$9?L($&a7*sf-sch1m(B9fK8xFU{ zMK-^ue3D3icHNx4!Lk6oCw6cRKe8h(f2I(iU6@S1F0q&&bUZ#Ar+innPxgFw(dQ#t zIvjy*;&HU&!%pj4rQW7316CcfzrSYOv&U0H#PxdW?W9`P`E{XrsRw}707$ipBBN< z;B2u*UOIv9GM|gL-@RGF=m>P80(pGX&8U)h+?ZSk^B@oUI%xyCB#uxKm|ENRK{9vY z!w%!aJG=m6t)oS&v%a#q9;$8bTS${wijSVIA#SPAfEM`qmV^GosrD-u5~@W+rl=sc!qBTU@&iX)hD6 z*r(|(Vtgz;AM9%?fEe_Y-9jca1(h9WZ?5xksSGm_G>*)NctMl#nR^SAQbAqb8#7`0pbw`6U_}TA zF{A?>H+ZxY6aI?l_()(qZj07rDW`2n@A-K=+ixfLm|I;qgbnd;3o?!c{}lUxkC?&? zhH{%3E(3yq<|l(23CtwOBCWM_X|k=UeWu*9<%ob`GrHMh_TD9@Ldzx;bRB_-I~+3r zC4G=2UYyU3MV+~!Pm1!azKY%so))W-yVvho)ZQI@=1LMfKtUf*xCT7lxU&fA1N{tV z6jDXX+UjPGJ%GukCeK8xFMmQS#E~qk*7syQ*I;F3k|&fgX!2eBi=H6#k9~NvpP^G! z!L=02gd7>w?gJvAVe?$!c!LP%*+w%3bUtAbxK-5;Da#*>e1a#4DQ?g9ciXh3=9u9R zP+`0(+d3+KDhSMcx$#zM)G_%7D-;1|>d!(c(PB=@vY@99slhdcSqau`z{d-pdtg!< zvWrdD(Dy0kyTjw#MX@U686gps+M&+$V-P8|v2bhdhCR{oZEY)z%#AU@bjm~^>LqJ} zEk%k1-E)$P!E65o7MPpU zaF5k$j4;d8Y@9vXUx_|>9xtWQYdk*x?HNK*#c8M|z$SBDpzLN#(4>k`%omq3%O2QZ zd_82@JqdP`hoNi__#tqmZQc8&+{A@h0)yKe3j6TDZ*!u=8lq9}thOdeV{m-kMRm?M zuh#?Hqq$=^RZ?m!8aOcQ$Aijx`e?ILM1;%hh7p%hv*z50w`pPVcExPgmP~B$`ptme zqB!}^`O5lKTobE_Q)bZ@ZDrAt{;wvpXvJQysuM&!5@{+T6F+9x zxL`yyyf}ooTgI~^!SvB$Eu^hb)SPVYmibL5thF6z{IsdMr5sa@eLP*yTP~#n;35ld zoTj<#T6t8y_jENfT}#tV*L{Ak8Gp1F%GbvL9f2afgn`~Jxvhq=gdvi%pSLn7M8C{d zz55jZRO-9Za({4LG17M4yg&Aljbe9|$2W|!)cXMvB~4FbE%s|v(qGe`y-b}4wZ3p; z>P6TiacMGVo^QWNhIM|`Mu_tKp%0iE_bwx(+Stu-li;(60z6M7rzyhaTMecZc4eo& z@-F#}LbP&cTR%8nXV|2;;bD1(YiaGRPf2U{dYsq-34=lR&fP?RZxw|rHw%_BH>Tcv zvxeyn9b-eU8Xx3I`;>J1S6&aei51F(2$d>}i< z_rmO56d%3#fG{DjX0sTh>t`r-J5b}j0eE^va!d!B+z%OrI{7|42&{3GSN48gtk=&t z+oxdmtlMj6+4s?YU?IHQ&!Gsj#f zwbzmXbEr|eTE5U?o!X&d-6Y0cnx4B5hphB@GO})dXcl$f;+<-0d$(ViQr1}fI2a$q zdvG=NGtoYBe|3vF0h+yrY^%h(Cs%-h%k&1!LALD~Jx0{CoQn*p1r8lY^LwFL{05 zog`lOyQ!o%G@(L9PF>I5wCxApuO2dcekHBrB5Or=vHoCuN!e^0jZhs26)CsrfjAwt zlOe`(s}_t(SyuXU`|-gB8AQI`ld%MOe8c9z=sOgWD!koxrQ%tg<4MBc`&tmMxUF&t zZ(`%>12yUc^`h(aaZ>X92QMqsh52Iu3>L%ybdVe+DpF+lE7wUJ$c(rsGu5ZU5wEL8 zeRg@6bu6`J08P4i{DVuDHZxVxh?;`^B-^}fdV4~ybOf@Suw5S56au) zl}POR6;xBDz@Mca{^I|5BBgx=Vai}=dMX0=6+9Lw60GF2&NcntqW&dVofs95aqgU= z->={>3k9C7OyueOPaXf(C`O-w(pj&zKc`saKMn9-Fp_=+v8Fw~WcE)+#o(!Qk1hZrB*Ic!1>Jm3KsEE;PFV4QpSI~<8NvHwo2}mVb&(G oNVcqB!T)#ZUsn0Qa_KqU6Ao799HYU_3zX}jrosIhb-UPq0Z{ijl>h($ literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner.rst b/docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner.rst new file mode 100644 index 0000000000..97e083389e --- /dev/null +++ b/docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner.rst @@ -0,0 +1,71 @@ +Visibility Road-Map planner +--------------------------- + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/VisibilityRoadMap/animation.gif + +`[Code] `_ + +This visibility road-map planner uses Dijkstra method for graph search. + +In the animation, the black lines are polygon obstacles, + +red crosses are visibility nodes, and blue lines area collision free visibility graphs. + +The red line is the final path searched by dijkstra algorithm frm the visibility graphs. + +Algorithms +~~~~~~~~~~ + +In this chapter, how does the visibility road map planner search a path. + +We assume this planner can be provided these information in the below figure. + +- 1. Start point (Red point) +- 2. Goal point (Blue point) +- 3. Obstacle polygons (Black lines) + +.. image:: visibility_road_map_planner/step0.png + :width: 400px + + +Step1: Generate visibility nodes based on polygon obstacles +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +The nodes are generated by expanded these polygons vertexes like the below figure: + +.. image:: visibility_road_map_planner/step1.png + :width: 400px + +Each polygon vertex is expanded outward from the vector of adjacent vertices. + +The start and goal point are included as nodes as well. + +Step2: Generate visibility graphs connecting the nodes. +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +When connecting the nodes, the arc between two nodes is checked to collided or not to each obstacles. + +If the arc is collided, the graph is removed. + +The blue lines are generated visibility graphs in the figure: + +.. image:: visibility_road_map_planner/step2.png + :width: 400px + + +Step3: Search the shortest path in the graphs using Dijkstra algorithm +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +The red line is searched path in the figure: + +.. image:: visibility_road_map_planner/step3.png + :width: 400px + +You can find the details of Dijkstra algorithm in :ref:`dijkstra`. + +References +^^^^^^^^^^ + +- `Visibility graph - Wikipedia `_ + + From d5aca66e1b61692e239e95c928884ede6f2c94cd Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 Dec 2021 07:23:13 +0900 Subject: [PATCH 433/940] Bump ipython from 7.30.0 to 7.30.1 (#594) Bumps [ipython](https://github.com/ipython/ipython) from 7.30.0 to 7.30.1. - [Release notes](https://github.com/ipython/ipython/releases) - [Commits](https://github.com/ipython/ipython/compare/7.30.0...7.30.1) --- updated-dependencies: - dependency-name: ipython dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 2a0135cf44..09bd9f50ad 100644 --- a/requirements.txt +++ b/requirements.txt @@ -7,4 +7,4 @@ pytest == 6.2.5 # For unit test pytest-xdist == 2.4.0 # For unit test sphinx < 4.0 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 7.30.0 # For sphinx documentation +IPython == 7.30.1 # For sphinx documentation From bf4e68245f4af09af65a579a9a8c7c3df0f644c9 Mon Sep 17 00:00:00 2001 From: Muhammad-Yazdian <93126501+Muhammad-Yazdian@users.noreply.github.com> Date: Sun, 12 Dec 2021 13:32:59 +0100 Subject: [PATCH 434/940] Add speed limitation of the robot (#595) * Added speed limitation of the robot * Removed leading underscores for global vars * Added unit test for robot speed limitation * Modified x/abs(x) to np.sign(x); fixed code style * Removed 'random' from test func header comment --- Control/move_to_pose/move_to_pose.py | 10 ++++++++++ tests/test_move_to_pose.py | 11 +++++++++++ 2 files changed, 21 insertions(+) diff --git a/Control/move_to_pose/move_to_pose.py b/Control/move_to_pose/move_to_pose.py index 2ae0090dda..4548a6bb8a 100644 --- a/Control/move_to_pose/move_to_pose.py +++ b/Control/move_to_pose/move_to_pose.py @@ -19,6 +19,10 @@ Kp_beta = -3 dt = 0.01 +# Robot specifications +MAX_LINEAR_SPEED = 15 +MAX_ANGULAR_SPEED = 7 + show_animation = True @@ -63,6 +67,12 @@ def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal): if alpha > np.pi / 2 or alpha < -np.pi / 2: v = -v + if abs(v) > MAX_LINEAR_SPEED: + v = np.sign(v) * MAX_LINEAR_SPEED + + if abs(w) > MAX_ANGULAR_SPEED: + w = np.sign(w) * MAX_ANGULAR_SPEED + theta = theta + w * dt x = x + v * np.cos(theta) * dt y = y + v * np.sin(theta) * dt diff --git a/tests/test_move_to_pose.py b/tests/test_move_to_pose.py index 05cfa269d7..8bc11a8d24 100644 --- a/tests/test_move_to_pose.py +++ b/tests/test_move_to_pose.py @@ -7,5 +7,16 @@ def test_1(): m.main() +def test_2(): + """ + This unit test tests the move_to_pose.py program for a MAX_LINEAR_SPEED and + MAX_ANGULAR_SPEED + """ + m.show_animation = False + m.MAX_LINEAR_SPEED = 11 + m.MAX_ANGULAR_SPEED = 5 + m.main() + + if __name__ == '__main__': conftest.run_this_test(__file__) From 6e4d43962a12913ffb2be5ceb35bee58f58178bc Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 14 Dec 2021 07:35:03 +0900 Subject: [PATCH 435/940] Bump pytest-xdist from 2.4.0 to 2.5.0 (#597) Bumps [pytest-xdist](https://github.com/pytest-dev/pytest-xdist) from 2.4.0 to 2.5.0. - [Release notes](https://github.com/pytest-dev/pytest-xdist/releases) - [Changelog](https://github.com/pytest-dev/pytest-xdist/blob/master/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest-xdist/compare/v2.4.0...v2.5.0) --- updated-dependencies: - dependency-name: pytest-xdist dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 09bd9f50ad..4763ee4253 100644 --- a/requirements.txt +++ b/requirements.txt @@ -4,7 +4,7 @@ pandas == 1.3.4 matplotlib == 3.5.0 cvxpy == 1.1.17 pytest == 6.2.5 # For unit test -pytest-xdist == 2.4.0 # For unit test +pytest-xdist == 2.5.0 # For unit test sphinx < 4.0 # For sphinx documentation sphinx_rtd_theme == 1.0.0 IPython == 7.30.1 # For sphinx documentation From 528050ec373ebcfb9c64419b46f4139202e983ad Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 14 Dec 2021 08:06:05 +0900 Subject: [PATCH 436/940] Bump pandas from 1.3.4 to 1.3.5 (#598) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.3.4 to 1.3.5. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/master/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.3.4...v1.3.5) --- updated-dependencies: - dependency-name: pandas dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 4763ee4253..7069c53c93 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.21.4 scipy == 1.7.3 -pandas == 1.3.4 +pandas == 1.3.5 matplotlib == 3.5.0 cvxpy == 1.1.17 pytest == 6.2.5 # For unit test From 54be632f716f9913a89a166b7d8a722e156da7d0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 14 Dec 2021 08:49:57 +0900 Subject: [PATCH 437/940] Bump matplotlib from 3.5.0 to 3.5.1 (#599) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.5.0 to 3.5.1. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.5.0...v3.5.1) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 7069c53c93..407f161b60 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.21.4 scipy == 1.7.3 pandas == 1.3.5 -matplotlib == 3.5.0 +matplotlib == 3.5.1 cvxpy == 1.1.17 pytest == 6.2.5 # For unit test pytest-xdist == 2.5.0 # For unit test From 196c756706bb4fa2610e70808fdaf59df36e1bb4 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 25 Dec 2021 13:53:27 +0900 Subject: [PATCH 438/940] try fix appveyor CI (#605) --- appveyor.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/appveyor.yml b/appveyor.yml index 16a5d7751d..e9535e4e3c 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -1,4 +1,4 @@ -os: Visual Studio 2019 +os: Visual Studio 2022 environment: global: From 4e1f644007b8da56e8926d77242c4ad479d0b701 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sat, 25 Dec 2021 14:14:41 +0900 Subject: [PATCH 439/940] Bump numpy from 1.21.4 to 1.21.5 (#602) Bumps [numpy](https://github.com/numpy/numpy) from 1.21.4 to 1.21.5. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/HOWTO_RELEASE.rst.txt) - [Commits](https://github.com/numpy/numpy/compare/v1.21.4...v1.21.5) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 407f161b60..966b566000 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.21.4 +numpy == 1.21.5 scipy == 1.7.3 pandas == 1.3.5 matplotlib == 3.5.1 From 680ecdafb21a798eb47649175e0eba4e72ef356d Mon Sep 17 00:00:00 2001 From: Muhammad-Yazdian <93126501+Muhammad-Yazdian@users.noreply.github.com> Date: Sat, 25 Dec 2021 13:42:32 +0100 Subject: [PATCH 440/940] Add a Robot class for Move to Pose Algorithm (#596) * Added speed limitation of the robot * Removed leading underscores for global vars * Added unit test for robot speed limitation * Modified x/abs(x) to np.sign(x); fixed code style * Removed 'random' from test func header comment * Added Robot class for move to pose * Revert * Added Robot class for move to pose * Added a type annotation for Robot class * Fixed the annotaion comment * Moved instance varaible outside of the Robot class * Fixed code style Python 3.9 CI * Removed whitespaces from the last line * Applied PR #596 change requests * Fixed typos * Update Control/move_to_pose/move_to_pose_robot_class.py Co-authored-by: Atsushi Sakai * Moved PathFinderController class to move_to_pose * Fixed issue #600 * Added update_command() to PathFinderController * Removed trailing whitespaces * Updated move to pose doc * Added code and doc comments * Updated unit test * Removed trailing whitespaces * Removed more trailing whitespaces Co-authored-by: Atsushi Sakai --- Control/move_to_pose/move_to_pose.py | 105 ++++++-- Control/move_to_pose/move_to_pose_robot.py | 240 ++++++++++++++++++ .../move_to_a_pose_control.rst | 95 ++++++- tests/test_move_to_pose_robot.py | 14 + 4 files changed, 424 insertions(+), 30 deletions(-) create mode 100644 Control/move_to_pose/move_to_pose_robot.py create mode 100644 tests/test_move_to_pose_robot.py diff --git a/Control/move_to_pose/move_to_pose.py b/Control/move_to_pose/move_to_pose.py index 4548a6bb8a..73604ccd7f 100644 --- a/Control/move_to_pose/move_to_pose.py +++ b/Control/move_to_pose/move_to_pose.py @@ -3,7 +3,8 @@ Move to specified pose Author: Daniel Ingram (daniel-s-ingram) - Atsushi Sakai(@Atsushi_twi) + Atsushi Sakai (@Atsushi_twi) + Seied Muhammad Yazdian (@Muhammad-Yazdian) P. I. Corke, "Robotics, Vision & Control", Springer 2017, ISBN 978-3-319-54413-7 @@ -13,10 +14,77 @@ import numpy as np from random import random + +class PathFinderController: + """ + Constructs an instantiate of the PathFinderController for navigating a + 3-DOF wheeled robot on a 2D plane + + Parameters + ---------- + Kp_rho : The linear velocity gain to translate the robot along a line + towards the goal + Kp_alpha : The angular velocity gain to rotate the robot towards the goal + Kp_beta : The offset angular velocity gain accounting for smooth merging to + the goal angle (i.e., it helps the robot heading to be parallel + to the target angle.) + """ + + def __init__(self, Kp_rho, Kp_alpha, Kp_beta): + self.Kp_rho = Kp_rho + self.Kp_alpha = Kp_alpha + self.Kp_beta = Kp_beta + + def calc_control_command(self, x_diff, y_diff, theta, theta_goal): + """ + Returns the control command for the linear and angular velocities as + well as the distance to goal + + Parameters + ---------- + x_diff : The position of target with respect to current robot position + in x direction + y_diff : The position of target with respect to current robot position + in y direction + theta : The current heading angle of robot with respect to x axis + theta_goal: The target angle of robot with respect to x axis + + Returns + ------- + rho : The distance between the robot and the goal position + v : Command linear velocity + w : Command angular velocity + """ + + # Description of local variables: + # - alpha is the angle to the goal relative to the heading of the robot + # - beta is the angle between the robot's position and the goal + # position plus the goal angle + # - Kp_rho*rho and Kp_alpha*alpha drive the robot along a line towards + # the goal + # - Kp_beta*beta rotates the line so that it is parallel to the goal + # angle + # + # Note: + # we restrict alpha and beta (angle differences) to the range + # [-pi, pi] to prevent unstable behavior e.g. difference going + # from 0 rad to 2*pi rad with slight turn + + rho = np.hypot(x_diff, y_diff) + alpha = (np.arctan2(y_diff, x_diff) + - theta + np.pi) % (2 * np.pi) - np.pi + beta = (theta_goal - theta - alpha + np.pi) % (2 * np.pi) - np.pi + v = self.Kp_rho * rho + w = self.Kp_alpha * alpha - controller.Kp_beta * beta + + if alpha > np.pi / 2 or alpha < -np.pi / 2: + v = -v + + return rho, v, w + + # simulation parameters -Kp_rho = 9 -Kp_alpha = 15 -Kp_beta = -3 +controller = PathFinderController(9, 15, 3) dt = 0.01 # Robot specifications @@ -27,14 +95,6 @@ def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal): - """ - rho is the distance between the robot and the goal position - alpha is the angle to the goal relative to the heading of the robot - beta is the angle between the robot's position and the goal position plus the goal angle - - Kp_rho*rho and Kp_alpha*alpha drive the robot along a line towards the goal - Kp_beta*beta rotates the line so that it is parallel to the goal angle - """ x = x_start y = y_start theta = theta_start @@ -52,20 +112,8 @@ def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal): x_diff = x_goal - x y_diff = y_goal - y - # Restrict alpha and beta (angle differences) to the range - # [-pi, pi] to prevent unstable behavior e.g. difference going - # from 0 rad to 2*pi rad with slight turn - - rho = np.hypot(x_diff, y_diff) - alpha = (np.arctan2(y_diff, x_diff) - - theta + np.pi) % (2 * np.pi) - np.pi - beta = (theta_goal - theta - alpha + np.pi) % (2 * np.pi) - np.pi - - v = Kp_rho * rho - w = Kp_alpha * alpha + Kp_beta * beta - - if alpha > np.pi / 2 or alpha < -np.pi / 2: - v = -v + rho, v, w = controller.calc_control_command( + x_diff, y_diff, theta, theta_goal) if abs(v) > MAX_LINEAR_SPEED: v = np.sign(v) * MAX_LINEAR_SPEED @@ -104,8 +152,9 @@ def plot_vehicle(x, y, theta, x_traj, y_traj): # pragma: no cover plt.plot(x_traj, y_traj, 'b--') # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.xlim(0, 20) plt.ylim(0, 20) diff --git a/Control/move_to_pose/move_to_pose_robot.py b/Control/move_to_pose/move_to_pose_robot.py new file mode 100644 index 0000000000..d5c51caa12 --- /dev/null +++ b/Control/move_to_pose/move_to_pose_robot.py @@ -0,0 +1,240 @@ +""" + +Move to specified pose (with Robot class) + +Author: Daniel Ingram (daniel-s-ingram) + Atsushi Sakai (@Atsushi_twi) + Seied Muhammad Yazdian (@Muhammad-Yazdian) + +P.I. Corke, "Robotics, Vision & Control", Springer 2017, ISBN 978-3-319-54413-7 + +""" + +import matplotlib.pyplot as plt +import numpy as np +import copy +from move_to_pose import PathFinderController + +# Simulation parameters +TIME_DURATION = 1000 +TIME_STEP = 0.01 +AT_TARGET_ACCEPTANCE_THRESHOLD = 0.01 +SHOW_ANIMATION = True +PLOT_WINDOW_SIZE_X = 20 +PLOT_WINDOW_SIZE_Y = 20 +PLOT_FONT_SIZE = 8 + +simulation_running = True +all_robots_are_at_target = False + + +class Pose: + """2D pose""" + + def __init__(self, x, y, theta): + self.x = x + self.y = y + self.theta = theta + + +class Robot: + """ + Constructs an instantiate of the 3-DOF wheeled Robot navigating on a + 2D plane + + Parameters + ---------- + name : (string) + The name of the robot + color : (string) + The color of the robot + max_linear_speed : (float) + The maximum linear speed that the robot can go + max_angular_speed : (float) + The maximum angular speed that the robot can rotate about its vertical + axis + path_finder_controller : (PathFinderController) + A configurable controller to finds the path and calculates command + linear and angular velocities. + """ + + def __init__(self, name, color, max_linear_speed, max_angular_speed, + path_finder_controller): + self.name = name + self.color = color + self.MAX_LINEAR_SPEED = max_linear_speed + self.MAX_ANGULAR_SPEED = max_angular_speed + self.path_finder_controller = path_finder_controller + self.x_traj = [] + self.y_traj = [] + self.pose = Pose(0, 0, 0) + self.pose_start = Pose(0, 0, 0) + self.pose_target = Pose(0, 0, 0) + self.is_at_target = False + + def set_start_target_poses(self, pose_start, pose_target): + """ + Sets the start and target positions of the robot + + Parameters + ---------- + pose_start : (Pose) + Start postion of the robot (see the Pose class) + pose_target : (Pose) + Target postion of the robot (see the Pose class) + """ + self.pose_start = copy.copy(pose_start) + self.pose_target = pose_target + self.pose = pose_start + + def move(self, dt): + """ + Moves the robot for one time step increment + + Parameters + ---------- + dt : (float) + time step + """ + self.x_traj.append(self.pose.x) + self.y_traj.append(self.pose.y) + + rho, linear_velocity, angular_velocity = \ + self.path_finder_controller.calc_control_command( + self.pose_target.x - self.pose.x, + self.pose_target.y - self.pose.y, + self.pose.theta, self.pose_target.theta) + + if rho < AT_TARGET_ACCEPTANCE_THRESHOLD: + self.is_at_target = True + + if abs(linear_velocity) > self.MAX_LINEAR_SPEED: + linear_velocity = (np.sign(linear_velocity) + * self.MAX_LINEAR_SPEED) + + if abs(angular_velocity) > self.MAX_ANGULAR_SPEED: + angular_velocity = (np.sign(angular_velocity) + * self.MAX_ANGULAR_SPEED) + + self.pose.theta = self.pose.theta + angular_velocity * dt + self.pose.x = self.pose.x + linear_velocity * \ + np.cos(self.pose.theta) * dt + self.pose.y = self.pose.y + linear_velocity * \ + np.sin(self.pose.theta) * dt + + +def run_simulation(robots): + """Simulates all robots simultaneously""" + global all_robots_are_at_target + global simulation_running + + robot_names = [] + for instance in robots: + robot_names.append(instance.name) + + time = 0 + while simulation_running and time < TIME_DURATION: + time += TIME_STEP + robots_are_at_target = [] + + for instance in robots: + if not instance.is_at_target: + instance.move(TIME_STEP) + robots_are_at_target.append(instance.is_at_target) + + if all(robots_are_at_target): + simulation_running = False + + if SHOW_ANIMATION: + plt.cla() + plt.xlim(0, PLOT_WINDOW_SIZE_X) + plt.ylim(0, PLOT_WINDOW_SIZE_Y) + + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + + plt.text(0.3, PLOT_WINDOW_SIZE_Y - 1, + 'Time: {:.2f}'.format(time), + fontsize=PLOT_FONT_SIZE) + + plt.text(0.3, PLOT_WINDOW_SIZE_Y - 2, + 'Reached target: {} = '.format(robot_names) + + str(robots_are_at_target), + fontsize=PLOT_FONT_SIZE) + + for instance in robots: + plt.arrow(instance.pose_start.x, + instance.pose_start.y, + np.cos(instance.pose_start.theta), + np.sin(instance.pose_start.theta), + color='r', + width=0.1) + plt.arrow(instance.pose_target.x, + instance.pose_target.y, + np.cos(instance.pose_target.theta), + np.sin(instance.pose_target.theta), + color='g', + width=0.1) + plot_vehicle(instance.pose.x, + instance.pose.y, + instance.pose.theta, + instance.x_traj, + instance.y_traj, instance.color) + + plt.pause(TIME_STEP) + + +def plot_vehicle(x, y, theta, x_traj, y_traj, color): + # Corners of triangular vehicle when pointing to the right (0 radians) + p1_i = np.array([0.5, 0, 1]).T + p2_i = np.array([-0.5, 0.25, 1]).T + p3_i = np.array([-0.5, -0.25, 1]).T + + T = transformation_matrix(x, y, theta) + p1 = T @ p1_i + p2 = T @ p2_i + p3 = T @ p3_i + + plt.plot([p1[0], p2[0]], [p1[1], p2[1]], color+'-') + plt.plot([p2[0], p3[0]], [p2[1], p3[1]], color+'-') + plt.plot([p3[0], p1[0]], [p3[1], p1[1]], color+'-') + + plt.plot(x_traj, y_traj, color+'--') + + +def transformation_matrix(x, y, theta): + return np.array([ + [np.cos(theta), -np.sin(theta), x], + [np.sin(theta), np.cos(theta), y], + [0, 0, 1] + ]) + + +def main(): + pose_target = Pose(15, 15, -1) + + pose_start_1 = Pose(5, 2, 0) + pose_start_2 = Pose(5, 2, 0) + pose_start_3 = Pose(5, 2, 0) + + controller_1 = PathFinderController(5, 8, 2) + controller_2 = PathFinderController(5, 16, 4) + controller_3 = PathFinderController(10, 25, 6) + + robot_1 = Robot("Yellow Robot", "y", 12, 5, controller_1) + robot_2 = Robot("Black Robot", "k", 16, 5, controller_2) + robot_3 = Robot("Blue Robot", "b", 20, 5, controller_3) + + robot_1.set_start_target_poses(pose_start_1, pose_target) + robot_2.set_start_target_poses(pose_start_2, pose_target) + robot_3.set_start_target_poses(pose_start_3, pose_target) + + robots: list[Robot] = [robot_1, robot_2, robot_3] + + run_simulation(robots) + + +if __name__ == '__main__': + main() diff --git a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst index c5bf15d970..81c64f5485 100644 --- a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst +++ b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst @@ -1,11 +1,102 @@ Move to a pose control ---------------------- -This is a simulation of moving to a pose control +This is a simulation of moving to a pose control. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif -Ref: +PathFinderController class +~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Constructor +~~~~~~~~~~~ + +.. code-block:: ipython3 + PathFinderController(Kp_rho, Kp_alpha, Kp_beta) + +Constructs an instantiate of the PathFinderController for navigating a 3-DOF wheeled robot on a 2D plane. + +Parameters: +- Kp_rho: The linear velocity gain to translate the robot along a line towards the goal +- Kp_alpha: The angular velocity gain to rotate the robot towards the goal +- Kp_beta: The offset angular velocity gain accounting for smooth merging to the goal angle (i.e., it helps the robot heading to be parallel to the target angle.) + + +Member function(s) +~~~~~~~~~~~~~~~~~~ + +.. code-block:: ipython3 + calc_control_command(x_diff, y_diff, theta, theta_goal) + +Returns the control command for the linear and angular velocities as well as the distance to goal + +Parameters: +- x_diff : The position of target with respect to current robot position in x direction +- y_diff : The position of target with respect to current robot position in y direction +- theta : The current heading angle of robot with respect to x axis +- theta_goal : The target angle of robot with respect to x axis + +Returns: +- rho : The distance between the robot and the goal position +- v : Command linear velocity +- w : Command angular velocity + +Move to a Pose Robot (Class) +---------------------------- +This program (move_to_pose_robot.py) provides a Robot class to define different robots with different specifications. +Using this class, you can simulate different robots simultaneously and compare the effect of your parameter settings. + +.. image:: https://user-images.githubusercontent.com/93126501/145834505-a8df8311-5445-413f-a96f-00460d47991c.png + +Note: A gif animation will be added soon. + +Note: The robot Class is based on PathFinderController class in 'the move_to_pose.py'. + +Robot Class +~~~~~~~~~~~ + +Constructor +~~~~~~~~~~~ + +.. code-block:: ipython3 + Robot(name, color, max_linear_speed, max_angular_speed, path_finder_controller) + +Constructs an instantiate of the 3-DOF wheeled Robot navigating on a 2D plane + +Parameters: +- name : (string) The name of the robot +- color : (string) The color of the robot +- max_linear_speed : (float) The maximum linear speed that the robot can go +- max_angular_speed : (float) The maximum angular speed that the robot can rotate about its vertical axis +- path_finder_controller : (PathFinderController) A configurable controller to finds the path and calculates command linear and angular velocities. + +Member function(s) +~~~~~~~~~~~~~~~~~~ + +.. code-block:: ipython3 + set_start_target_poses(pose_start, pose_target) + +Sets the start and target positions of the robot. + +Parameters: +- pose_start : (Pose) Start postion of the robot (see the Pose class) +- pose_target : (Pose) Target postion of the robot (see the Pose class) + +.. code-block:: ipython3 + move(dt) + +Move the robot for one time step increment + +Parameters: +- dt: time increment + +See Also +-------- +- PathFinderController class + + +Ref: +---- - `P. I. Corke, "Robotics, Vision and Control" \| SpringerLink p102 `__ diff --git a/tests/test_move_to_pose_robot.py b/tests/test_move_to_pose_robot.py new file mode 100644 index 0000000000..a93b44d198 --- /dev/null +++ b/tests/test_move_to_pose_robot.py @@ -0,0 +1,14 @@ +import conftest # Add root path to sys.path +from Control.move_to_pose import move_to_pose as m + + +def test_1(): + """ + This unit test tests the move_to_pose_robot.py program + """ + m.show_animation = False + m.main() + + +if __name__ == '__main__': + conftest.run_this_test(__file__) From 7034d5ff9eb19eff561f84c806ec591b2d0c8e26 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 25 Dec 2021 23:06:37 +0900 Subject: [PATCH 441/940] Add rng provide function for PRM planner (#607) * Add rng provide function * fix CI error * remove unused import --- .../probabilistic_road_map.py | 60 ++++++++++++------- tests/test_probabilistic_road_map.py | 3 +- 2 files changed, 41 insertions(+), 22 deletions(-) diff --git a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py index 8681420e2d..7eac40a886 100644 --- a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py +++ b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py @@ -6,11 +6,10 @@ """ -import random import math import numpy as np import matplotlib.pyplot as plt -from scipy.spatial import cKDTree +from scipy.spatial import KDTree # parameter N_SAMPLE = 500 # number of sample_points @@ -36,19 +35,35 @@ def __str__(self): str(self.cost) + "," + str(self.parent_index) -def prm_planning(sx, sy, gx, gy, ox, oy, rr): - - obstacle_kd_tree = cKDTree(np.vstack((ox, oy)).T) +def prm_planning(start_x, start_y, goal_x, goal_y, + obstacle_x_list, obstacle_y_list, robot_radius, *, rng=None): + """ + Run probabilistic road map planning + + :param start_x: + :param start_y: + :param goal_x: + :param goal_y: + :param obstacle_x_list: + :param obstacle_y_list: + :param robot_radius: + :param rng: + :return: + """ + obstacle_kd_tree = KDTree(np.vstack((obstacle_x_list, obstacle_y_list)).T) - sample_x, sample_y = sample_points(sx, sy, gx, gy, - rr, ox, oy, obstacle_kd_tree) + sample_x, sample_y = sample_points(start_x, start_y, goal_x, goal_y, + robot_radius, + obstacle_x_list, obstacle_y_list, + obstacle_kd_tree, rng) if show_animation: plt.plot(sample_x, sample_y, ".b") - road_map = generate_road_map(sample_x, sample_y, rr, obstacle_kd_tree) + road_map = generate_road_map(sample_x, sample_y, + robot_radius, obstacle_kd_tree) rx, ry = dijkstra_planning( - sx, sy, gx, gy, road_map, sample_x, sample_y) + start_x, start_y, goal_x, goal_y, road_map, sample_x, sample_y) return rx, ry @@ -88,13 +103,13 @@ def generate_road_map(sample_x, sample_y, rr, obstacle_kd_tree): sample_x: [m] x positions of sampled points sample_y: [m] y positions of sampled points - rr: Robot Radius[m] + robot_radius: Robot Radius[m] obstacle_kd_tree: KDTree object of obstacles """ road_map = [] n_sample = len(sample_x) - sample_kd_tree = cKDTree(np.vstack((sample_x, sample_y)).T) + sample_kd_tree = KDTree(np.vstack((sample_x, sample_y)).T) for (i, ix, iy) in zip(range(n_sample), sample_x, sample_y): @@ -122,11 +137,11 @@ def dijkstra_planning(sx, sy, gx, gy, road_map, sample_x, sample_y): """ s_x: start x position [m] s_y: start y position [m] - gx: goal x position [m] - gy: goal y position [m] - ox: x position list of Obstacles [m] - oy: y position list of Obstacles [m] - rr: robot radius [m] + goal_x: goal x position [m] + goal_y: goal y position [m] + obstacle_x_list: x position list of Obstacles [m] + obstacle_y_list: y position list of Obstacles [m] + robot_radius: robot radius [m] road_map: ??? [m] sample_x: ??? [m] sample_y: ??? [m] @@ -215,7 +230,7 @@ def plot_road_map(road_map, sample_x, sample_y): # pragma: no cover [sample_y[i], sample_y[ind]], "-k") -def sample_points(sx, sy, gx, gy, rr, ox, oy, obstacle_kd_tree): +def sample_points(sx, sy, gx, gy, rr, ox, oy, obstacle_kd_tree, rng): max_x = max(ox) max_y = max(oy) min_x = min(ox) @@ -223,9 +238,12 @@ def sample_points(sx, sy, gx, gy, rr, ox, oy, obstacle_kd_tree): sample_x, sample_y = [], [] + if rng is None: + rng = np.random.default_rng() + while len(sample_x) <= N_SAMPLE: - tx = (random.random() * (max_x - min_x)) + min_x - ty = (random.random() * (max_y - min_y)) + min_y + tx = (rng.random() * (max_x - min_x)) + min_x + ty = (rng.random() * (max_y - min_y)) + min_y dist, index = obstacle_kd_tree.query([tx, ty]) @@ -241,7 +259,7 @@ def sample_points(sx, sy, gx, gy, rr, ox, oy, obstacle_kd_tree): return sample_x, sample_y -def main(): +def main(rng=None): print(__file__ + " start!!") # start and goal position @@ -280,7 +298,7 @@ def main(): plt.grid(True) plt.axis("equal") - rx, ry = prm_planning(sx, sy, gx, gy, ox, oy, robot_size) + rx, ry = prm_planning(sx, sy, gx, gy, ox, oy, robot_size, rng=rng) assert rx, 'Cannot found path' diff --git a/tests/test_probabilistic_road_map.py b/tests/test_probabilistic_road_map.py index aa58e28bce..a830cc5e0c 100644 --- a/tests/test_probabilistic_road_map.py +++ b/tests/test_probabilistic_road_map.py @@ -1,10 +1,11 @@ import conftest # Add root path to sys.path +import numpy as np from PathPlanning.ProbabilisticRoadMap import probabilistic_road_map def test1(): probabilistic_road_map.show_animation = False - probabilistic_road_map.main() + probabilistic_road_map.main(rng=np.random.default_rng(1234)) if __name__ == '__main__': From 88671e4ba10072efc2099f24fdbdc4cf937479d8 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 26 Dec 2021 10:55:21 +0900 Subject: [PATCH 442/940] add doc policy (#609) --- docs/how_to_contribute_main.rst | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/docs/how_to_contribute_main.rst b/docs/how_to_contribute_main.rst index a4ac3c819b..703143f6e2 100644 --- a/docs/how_to_contribute_main.rst +++ b/docs/how_to_contribute_main.rst @@ -65,6 +65,10 @@ Please check other documents for details. You can build the doc locally based on `doc README`_. +Note that the `reStructuredText`_ based doc should only focus on the mathematics and the algorithm of the example. + +Documentations related codes should be in the python script as the header comments of the script or docstrings of each function. + .. _`submit a pull request`: From ea7a52a835612961251770bae3990174a8a59615 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 26 Dec 2021 11:10:33 +0900 Subject: [PATCH 443/940] add requirements.txt under docs dir. (#611) --- docs/requirements.txt | 3 +++ 1 file changed, 3 insertions(+) create mode 100644 docs/requirements.txt diff --git a/docs/requirements.txt b/docs/requirements.txt new file mode 100644 index 0000000000..5006af8a8e --- /dev/null +++ b/docs/requirements.txt @@ -0,0 +1,3 @@ +sphinx < 4.0 # For sphinx documentation +sphinx_rtd_theme == 1.0.0 +IPython == 7.30.1 # For sphinx documentation From d08a044f75808d0c8eca5f76697e4d11359bd346 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 28 Dec 2021 08:00:15 +0900 Subject: [PATCH 444/940] Update sphinx requirement from <4.0 to <5.0 (#612) Updates the requirements on [sphinx](https://github.com/sphinx-doc/sphinx) to permit the latest version. - [Release notes](https://github.com/sphinx-doc/sphinx/releases) - [Changelog](https://github.com/sphinx-doc/sphinx/blob/4.x/CHANGES) - [Commits](https://github.com/sphinx-doc/sphinx/compare/v0.1.61611...v4.3.2) --- updated-dependencies: - dependency-name: sphinx dependency-type: direct:production ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- docs/requirements.txt | 2 +- requirements.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/requirements.txt b/docs/requirements.txt index 5006af8a8e..3d564ac8d9 100644 --- a/docs/requirements.txt +++ b/docs/requirements.txt @@ -1,3 +1,3 @@ -sphinx < 4.0 # For sphinx documentation +sphinx < 5.0 # For sphinx documentation sphinx_rtd_theme == 1.0.0 IPython == 7.30.1 # For sphinx documentation diff --git a/requirements.txt b/requirements.txt index 966b566000..8a2591dc4a 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,6 +5,6 @@ matplotlib == 3.5.1 cvxpy == 1.1.17 pytest == 6.2.5 # For unit test pytest-xdist == 2.5.0 # For unit test -sphinx < 4.0 # For sphinx documentation +sphinx < 5.0 # For sphinx documentation sphinx_rtd_theme == 1.0.0 IPython == 7.30.1 # For sphinx documentation From 29bb0197f9d6c40eb3d1da791da00163ec0cff1c Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 28 Dec 2021 08:29:45 +0900 Subject: [PATCH 445/940] Update requirements.txt (#613) --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 8a2591dc4a..debc39ea17 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,6 +5,6 @@ matplotlib == 3.5.1 cvxpy == 1.1.17 pytest == 6.2.5 # For unit test pytest-xdist == 2.5.0 # For unit test -sphinx < 5.0 # For sphinx documentation +sphinx == 4.3.1 # For sphinx documentation sphinx_rtd_theme == 1.0.0 IPython == 7.30.1 # For sphinx documentation From a67ecab1eef7fc858823433727e58798b9f012f4 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 4 Jan 2022 06:51:32 +0900 Subject: [PATCH 446/940] Bump sphinx from 4.3.1 to 4.3.2 (#614) Bumps [sphinx](https://github.com/sphinx-doc/sphinx) from 4.3.1 to 4.3.2. - [Release notes](https://github.com/sphinx-doc/sphinx/releases) - [Changelog](https://github.com/sphinx-doc/sphinx/blob/4.x/CHANGES) - [Commits](https://github.com/sphinx-doc/sphinx/compare/v4.3.1...v4.3.2) --- updated-dependencies: - dependency-name: sphinx dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index debc39ea17..2636263e6c 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,6 +5,6 @@ matplotlib == 3.5.1 cvxpy == 1.1.17 pytest == 6.2.5 # For unit test pytest-xdist == 2.5.0 # For unit test -sphinx == 4.3.1 # For sphinx documentation +sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 IPython == 7.30.1 # For sphinx documentation From d24ae2ac1abe2d8bd70e1c8ffa6a6b05a960356e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 4 Jan 2022 06:53:44 +0900 Subject: [PATCH 447/940] Bump numpy from 1.21.5 to 1.22.0 (#616) Bumps [numpy](https://github.com/numpy/numpy) from 1.21.5 to 1.22.0. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/HOWTO_RELEASE.rst.txt) - [Commits](https://github.com/numpy/numpy/compare/v1.21.5...v1.22.0) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 2636263e6c..3387ce5a61 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.21.5 +numpy == 1.22.0 scipy == 1.7.3 pandas == 1.3.5 matplotlib == 3.5.1 From 79f7107cd1543ff354049a8da311e718b430ff2e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 4 Jan 2022 08:41:50 +0900 Subject: [PATCH 448/940] Bump cvxpy from 1.1.17 to 1.1.18 (#615) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.1.17 to 1.1.18. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Changelog](https://github.com/cvxpy/cvxpy/blob/master/CHANGELOG.md) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.1.17...v1.1.18) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 3387ce5a61..396a80e9a3 100644 --- a/requirements.txt +++ b/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.22.0 scipy == 1.7.3 pandas == 1.3.5 matplotlib == 3.5.1 -cvxpy == 1.1.17 +cvxpy == 1.1.18 pytest == 6.2.5 # For unit test pytest-xdist == 2.5.0 # For unit test sphinx == 4.3.2 # For sphinx documentation From 0dfa274be3eaddb270b2bcee197f7d34acbc1363 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 6 Jan 2022 20:26:24 +0900 Subject: [PATCH 449/940] add diff style check test (#617) * add diff style check test * add diff style check test * add diff style check test * add diff style check test * add license * add license --- .github/workflows/Linux_CI.yml | 6 -- .github/workflows/MacOS_CI.yml | 13 +--- docs/how_to_contribute_main.rst | 3 + requirements.txt | 1 + tests/test_diff_codestyle.py | 115 ++++++++++++++++++++++++++++++++ 5 files changed, 120 insertions(+), 18 deletions(-) create mode 100644 tests/test_diff_codestyle.py diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index ef773ff71a..d8cad21172 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -32,10 +32,6 @@ jobs: run: pip install coverage - name: install mypy run: pip install mypy - - name: install pycodestyle - run: pip install pycodestyle - - name: install pytest-xdist - run: pip install pytest-xdist - name: mypy check run: | mypy -p AerialNavigation @@ -47,8 +43,6 @@ jobs: mypy -p PathPlanning mypy -p PathTracking mypy -p SLAM - - name: do diff style check - run: bash rundiffstylecheck.sh - name: do all unit tests run: bash runtests.sh diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index f01d85e62b..1921799157 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -39,10 +39,6 @@ jobs: run: pip install coverage - name: install mypy run: pip install mypy - - name: install pycodestyle - run: pip install pycodestyle - - name: install pytest-xdist - run: pip install pytest-xdist - name: mypy check run: | mypy -p AerialNavigation @@ -54,12 +50,5 @@ jobs: mypy -p PathPlanning mypy -p PathTracking mypy -p SLAM - - name: do diff style check - run: bash rundiffstylecheck.sh - - name: do all unit tests - run: bash runtests.sh - - - - + run: bash runtests.sh \ No newline at end of file diff --git a/docs/how_to_contribute_main.rst b/docs/how_to_contribute_main.rst index 703143f6e2..4b39089e7b 100644 --- a/docs/how_to_contribute_main.rst +++ b/docs/how_to_contribute_main.rst @@ -50,6 +50,8 @@ At the least, try to run the example code without animation in the unit test. If you want to run the test suites locally, you can use the `runtests.sh` script by just executing it. +The `test_diff_codestyle.py`_ check code style for your PR's codes. + .. _`how to write doc`: @@ -153,6 +155,7 @@ Sponsors .. _`reStructuredText`: https://www.sphinx-doc.org/en/master/usage/restructuredtext/basics.html .. _`doc modules dir`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/docs/modules .. _`doc README`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/docs/README.md +.. _`test_diff_codestyle.py`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/tests/test_diff_codestyle.py .. _`JetBrains`: https://www.jetbrains.com/ .. _`Sponsor @AtsushiSakai on GitHub Sponsors`: https://github.com/sponsors/AtsushiSakai .. _`Become a backer or sponsor on Patreon`: https://www.patreon.com/myenigma diff --git a/requirements.txt b/requirements.txt index 396a80e9a3..c0de8f226a 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,6 +5,7 @@ matplotlib == 3.5.1 cvxpy == 1.1.18 pytest == 6.2.5 # For unit test pytest-xdist == 2.5.0 # For unit test +flake8 == 4.0.1 # For unit test sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 IPython == 7.30.1 # For sphinx documentation diff --git a/tests/test_diff_codestyle.py b/tests/test_diff_codestyle.py new file mode 100644 index 0000000000..3dbe11a11a --- /dev/null +++ b/tests/test_diff_codestyle.py @@ -0,0 +1,115 @@ +""" +Diff based code style checker with flake8 + +This code come from: +https://github.com/scipy/scipy/blob/main/tools/lint_diff.py + +Scipy's licence: https://github.com/scipy/scipy/blob/main/LICENSE.txt +Copyright (c) 2001-2002 Enthought, Inc. 2003-2022, SciPy Developers. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions +are met: + +1. Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above + copyright notice, this list of conditions and the following + disclaimer in the documentation and/or other materials provided + with the distribution. + +3. Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived + from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +""" +import conftest +import subprocess + + +def rev_list(branch, num_commits): + """List commits in reverse chronological order. + Only the first `num_commits` are shown. + """ + res = subprocess.run( + [ + 'git', + 'rev-list', + '--max-count', + f'{num_commits}', + '--first-parent', + branch + ], + stdout=subprocess.PIPE, + encoding='utf-8', + ) + res.check_returncode() + return res.stdout.rstrip('\n').split('\n') + + +def find_branch_point(branch): + """Find when the current branch split off from the given branch. + It is based off of this Stackoverflow post: + https://stackoverflow.com/questions/1527234/finding-a-branch-point-with-git#4991675 + """ + branch_commits = rev_list('HEAD', 1000) + main_commits = set(rev_list(branch, 1000)) + for branch_commit in branch_commits: + if branch_commit in main_commits: + return branch_commit + + # If a branch split off over 1000 commits ago we will fail to find + # the ancestor. + raise RuntimeError( + 'Failed to find a common ancestor in the last 1000 commits') + + +def find_diff(sha): + """Find the diff since the given sha.""" + files = ['*.py'] + res = subprocess.run( + ['git', 'diff', '--unified=0', sha, '--'] + files, + stdout=subprocess.PIPE, + encoding='utf-8' + ) + res.check_returncode() + return res.stdout + + +def run_flake8(diff): + """Run flake8 on the given diff.""" + res = subprocess.run( + ['flake8', '--diff'], + input=diff, + stdout=subprocess.PIPE, + encoding='utf-8', + ) + return res.returncode, res.stdout + + +def test(): + branch_commit = find_branch_point("origin/master") + diff = find_diff(branch_commit) + rc, errors = run_flake8(diff) + if errors: + print(errors) + else: + print("No lint errors found.") + assert rc == 0 + + +if __name__ == '__main__': + conftest.run_this_test(__file__) From c05a4fdada59fd97332417c4b99515118bfef45c Mon Sep 17 00:00:00 2001 From: Trung Kien Date: Sat, 8 Jan 2022 06:44:42 +0700 Subject: [PATCH 450/940] Fix ModuleNotFoundError when executing test in the tests folder and little improve MPC controller (#619) * Fix ModuleNotFoundError when executing test in the tests folder Signed-off-by: Trung Kien * Improve model_predictive_speed_and_steer_control - Fix typo - Using @ for matrix multiplication instead of * with have been deprecated in CVXPY1.1 - Fix missing conftest module in test file Signed-off-by: Trung Kien --- .../Eta3SplineTrajectory/eta3_spline_trajectory.py | 3 ++- .../lqr_speed_steer_control.py | 4 +++- PathTracking/lqr_steer_control/lqr_steer_control.py | 5 ++++- .../model_predictive_speed_and_steer_control.py | 11 +++++++---- PathTracking/stanley_controller/stanley_controller.py | 5 ++++- .../test_model_predictive_speed_and_steer_control.py | 1 + 6 files changed, 21 insertions(+), 8 deletions(-) diff --git a/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py b/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py index 01a687679f..bd211046c7 100644 --- a/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py +++ b/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py @@ -17,7 +17,8 @@ from matplotlib.collections import LineCollection import sys import os -sys.path.append(os.path.relpath("../Eta3SplinePath")) +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../Eta3SplinePath") try: from eta3_spline_path import Eta3Path, Eta3PathSegment diff --git a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py index bd2e54bf91..db5a755008 100644 --- a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py +++ b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py @@ -7,12 +7,14 @@ """ import math import sys +import os import matplotlib.pyplot as plt import numpy as np import scipy.linalg as la -sys.path.append("../../PathPlanning/CubicSpline/") +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../PathPlanning/CubicSpline/") try: import cubic_spline_planner diff --git a/PathTracking/lqr_steer_control/lqr_steer_control.py b/PathTracking/lqr_steer_control/lqr_steer_control.py index 6f01e5a840..5596ea0fdf 100644 --- a/PathTracking/lqr_steer_control/lqr_steer_control.py +++ b/PathTracking/lqr_steer_control/lqr_steer_control.py @@ -10,7 +10,10 @@ import math import numpy as np import sys -sys.path.append("../../PathPlanning/CubicSpline/") +import os + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../PathPlanning/CubicSpline/") try: import cubic_spline_planner diff --git a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py index 26e8e74f8b..ac8b883bd9 100644 --- a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py +++ b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py @@ -10,7 +10,10 @@ import math import numpy as np import sys -sys.path.append("../../PathPlanning/CubicSpline/") +import os + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../PathPlanning/CubicSpline/") try: import cubic_spline_planner @@ -175,9 +178,9 @@ def update_state(state, a, delta): state.yaw = state.yaw + state.v / WB * math.tan(delta) * DT state.v = state.v + a * DT - if state. v > MAX_SPEED: + if state.v > MAX_SPEED: state.v = MAX_SPEED - elif state. v < MIN_SPEED: + elif state.v < MIN_SPEED: state.v = MIN_SPEED return state @@ -272,7 +275,7 @@ def linear_mpc_control(xref, xbar, x0, dref): A, B, C = get_linear_model_matrix( xbar[2, t], xbar[3, t], dref[0, t]) - constraints += [x[:, t + 1] == A * x[:, t] + B * u[:, t] + C] + constraints += [x[:, t + 1] == A @ x[:, t] + B @ u[:, t] + C] if t < (T - 1): cost += cvxpy.quad_form(u[:, t + 1] - u[:, t], Rd) diff --git a/PathTracking/stanley_controller/stanley_controller.py b/PathTracking/stanley_controller/stanley_controller.py index 2af3989fcc..3a67d6268e 100644 --- a/PathTracking/stanley_controller/stanley_controller.py +++ b/PathTracking/stanley_controller/stanley_controller.py @@ -12,7 +12,10 @@ import numpy as np import matplotlib.pyplot as plt import sys -sys.path.append("../../PathPlanning/CubicSpline/") +import os + +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + + "/../../PathPlanning/CubicSpline/") try: import cubic_spline_planner diff --git a/tests/test_model_predictive_speed_and_steer_control.py b/tests/test_model_predictive_speed_and_steer_control.py index 9a50e48044..904cd2920e 100644 --- a/tests/test_model_predictive_speed_and_steer_control.py +++ b/tests/test_model_predictive_speed_and_steer_control.py @@ -1,4 +1,5 @@ import sys +import conftest if 'cvxpy' in sys.modules: # pragma: no cover From a13ef29dc4a28e48e31dd9d6c65cee40ac4de960 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 8 Jan 2022 17:06:29 +0900 Subject: [PATCH 451/940] enable MPC test (#620) * enable_mpc_test * enable_mpc_test * enable_mpc_test * enable_mpc_test * enable_mpc_test * enable_mpc_test * enable_mpc_test * enable_mpc_test --- .../rocket_powered_landing.py | 51 ++++++++++--------- .../probabilistic_road_map.py | 16 +++--- ...odel_predictive_speed_and_steer_control.py | 19 +++---- tests/test_probabilistic_road_map.py | 2 +- tests/test_rocket_powered_landing.py | 17 +++++-- 5 files changed, 58 insertions(+), 47 deletions(-) diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py index eb9d7ba4a7..37dca15b98 100644 --- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py +++ b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py @@ -43,7 +43,7 @@ class Rocket_Model_6DoF: A 6 degree of freedom rocket landing problem. """ - def __init__(self): + def __init__(self, rng): """ A large r_scale for a small scale problem will ead to numerical problems as parameters become excessively small @@ -92,7 +92,7 @@ def __init__(self): # Vector from thrust point to CoM self.r_T_B = np.array([-1e-2, 0., 0.]) - self.set_random_initial_state() + self.set_random_initial_state(rng) self.x_init = np.concatenate( ((self.m_wet,), self.r_I_init, self.v_I_init, self.q_B_I_init, self.w_B_init)) @@ -102,29 +102,32 @@ def __init__(self): self.r_scale = np.linalg.norm(self.r_I_init) self.m_scale = self.m_wet - def set_random_initial_state(self): + def set_random_initial_state(self, rng): + if rng is None: + rng = np.random.default_rng() + self.r_I_init = np.array((0., 0., 0.)) - self.r_I_init[0] = np.random.uniform(3, 4) - self.r_I_init[1:3] = np.random.uniform(-2, 2, size=2) + self.r_I_init[0] = rng.uniform(3, 4) + self.r_I_init[1:3] = rng.uniform(-2, 2, size=2) self.v_I_init = np.array((0., 0., 0.)) - self.v_I_init[0] = np.random.uniform(-1, -0.5) - self.v_I_init[1:3] = np.random.uniform( - -0.5, -0.2, size=2) * self.r_I_init[1:3] + self.v_I_init[0] = rng.uniform(-1, -0.5) + self.v_I_init[1:3] = rng.uniform(-0.5, -0.2, + size=2) * self.r_I_init[1:3] self.q_B_I_init = self.euler_to_quat((0, - np.random.uniform(-30, 30), - np.random.uniform(-30, 30))) + rng.uniform(-30, 30), + rng.uniform(-30, 30))) self.w_B_init = np.deg2rad((0, - np.random.uniform(-20, 20), - np.random.uniform(-20, 20))) + rng.uniform(-20, 20), + rng.uniform(-20, 20))) def f_func(self, x, u): m, rx, ry, rz, vx, vy, vz, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[ 2], x[3], x[4], x[5], x[6], x[7], x[8], x[9], x[10], x[11], x[12], x[13] ux, uy, uz = u[0], u[1], u[2] - return np.matrix([ + return np.array([ [-0.01 * np.sqrt(ux**2 + uy**2 + uz**2)], [vx], [vy], @@ -149,7 +152,7 @@ def A_func(self, x, u): 2], x[3], x[4], x[5], x[6], x[7], x[8], x[9], x[10], x[11], x[12], x[13] ux, uy, uz = u[0], u[1], u[2] - return np.matrix([ + return np.array([ [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], [0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0], [0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0], @@ -177,7 +180,7 @@ def B_func(self, x, u): 2], x[3], x[4], x[5], x[6], x[7], x[8], x[9], x[10], x[11], x[12], x[13] ux, uy, uz = u[0], u[1], u[2] - return np.matrix([ + return np.array([ [-0.01 * ux / np.sqrt(ux**2 + uy**2 + uz**2), -0.01 * uy / np.sqrt(ux ** 2 + uy**2 + uz**2), -0.01 * uz / np.sqrt(ux**2 + uy**2 + uz**2)], @@ -219,14 +222,14 @@ def euler_to_quat(self, a): return q def skew(self, v): - return np.matrix([ + return np.array([ [0, -v[2], v[1]], [v[2], 0, -v[0]], [-v[1], v[0], 0] ]) def dir_cosine(self, q): - return np.matrix([ + return np.array([ [1 - 2 * (q[2] ** 2 + q[3] ** 2), 2 * (q[1] * q[2] + q[0] * q[3]), 2 * (q[1] * q[3] - q[0] * q[2])], [2 * (q[1] * q[2] - q[0] * q[3]), 1 - 2 @@ -236,7 +239,7 @@ def dir_cosine(self, q): ]) def omega(self, w): - return np.matrix([ + return np.array([ [0, -w[0], -w[1], -w[2]], [w[0], 0, w[2], -w[1]], [w[1], -w[2], 0, w[0]], @@ -304,7 +307,7 @@ def get_constraints(self, X_v, U_v, X_last_p, U_last_p): ] # linearized lower thrust constraint - rhs = [U_last_p[:, k] / cvxpy.norm(U_last_p[:, k]) * U_v[:, k] + rhs = [U_last_p[:, k] / cvxpy.norm(U_last_p[:, k]) @ U_v[:, k] for k in range(X_v.shape[1])] constraints += [ self.T_min <= cvxpy.vstack(rhs) @@ -460,11 +463,11 @@ def __init__(self, m, K): # x_t+1 = A_*x_t+B_*U_t+C_*U_T+1*S_*sigma+zbar+nu constraints += [ self.var['X'][:, k + 1] == - cvxpy.reshape(self.par['A_bar'][:, k], (m.n_x, m.n_x)) * + cvxpy.reshape(self.par['A_bar'][:, k], (m.n_x, m.n_x)) @ self.var['X'][:, k] + - cvxpy.reshape(self.par['B_bar'][:, k], (m.n_x, m.n_u)) * + cvxpy.reshape(self.par['B_bar'][:, k], (m.n_x, m.n_u)) @ self.var['U'][:, k] + - cvxpy.reshape(self.par['C_bar'][:, k], (m.n_x, m.n_u)) * + cvxpy.reshape(self.par['C_bar'][:, k], (m.n_x, m.n_u)) @ self.var['U'][:, k + 1] + self.par['S_bar'][:, k] * self.var['sigma'] + self.par['z_bar'][:, k] + @@ -606,9 +609,9 @@ def plot_animation(X, U): # pragma: no cover plt.pause(0.5) -def main(): +def main(rng=None): print("start!!") - m = Rocket_Model_6DoF() + m = Rocket_Model_6DoF(rng) # state and input list X = np.empty(shape=[m.n_x, K]) diff --git a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py index 7eac40a886..294c389023 100644 --- a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py +++ b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py @@ -40,14 +40,14 @@ def prm_planning(start_x, start_y, goal_x, goal_y, """ Run probabilistic road map planning - :param start_x: - :param start_y: - :param goal_x: - :param goal_y: - :param obstacle_x_list: - :param obstacle_y_list: - :param robot_radius: - :param rng: + :param start_x: start x position + :param start_y: start y position + :param goal_x: goal x position + :param goal_y: goal y position + :param obstacle_x_list: obstacle x positions + :param obstacle_y_list: obstacle y positions + :param robot_radius: robot radius + :param rng: (Optional) Random generator :return: """ obstacle_kd_tree = KDTree(np.vstack((obstacle_x_list, obstacle_y_list)).T) diff --git a/tests/test_model_predictive_speed_and_steer_control.py b/tests/test_model_predictive_speed_and_steer_control.py index 904cd2920e..0ed520dcbe 100644 --- a/tests/test_model_predictive_speed_and_steer_control.py +++ b/tests/test_model_predictive_speed_and_steer_control.py @@ -1,18 +1,19 @@ import sys import conftest -if 'cvxpy' in sys.modules: # pragma: no cover +from PathTracking.model_predictive_speed_and_steer_control \ + import model_predictive_speed_and_steer_control as m - from PathTracking.model_predictive_speed_and_steer_control \ - import model_predictive_speed_and_steer_control as m - def test_1(): - m.show_animation = False - m.main() +def test_1(): + m.show_animation = False + m.main() + + +def test_2(): + m.show_animation = False + m.main2() - def test_2(): - m.show_animation = False - m.main2() if __name__ == '__main__': conftest.run_this_test(__file__) diff --git a/tests/test_probabilistic_road_map.py b/tests/test_probabilistic_road_map.py index a830cc5e0c..6c5eb540b1 100644 --- a/tests/test_probabilistic_road_map.py +++ b/tests/test_probabilistic_road_map.py @@ -5,7 +5,7 @@ def test1(): probabilistic_road_map.show_animation = False - probabilistic_road_map.main(rng=np.random.default_rng(1234)) + probabilistic_road_map.main(rng=np.random.default_rng(1233)) if __name__ == '__main__': diff --git a/tests/test_rocket_powered_landing.py b/tests/test_rocket_powered_landing.py index 7cf69567e1..52b812eeda 100644 --- a/tests/test_rocket_powered_landing.py +++ b/tests/test_rocket_powered_landing.py @@ -1,13 +1,20 @@ import conftest # Add root path to sys.path import sys +import numpy as np +from numpy.testing import suppress_warnings -if 'cvxpy' in sys.modules: # pragma: no cover +from AerialNavigation.rocket_powered_landing import rocket_powered_landing as m - from AerialNavigation.rocket_powered_landing import rocket_powered_landing as m - def test1(): - m.show_animation = False - m.main() +def test1(): + m.show_animation = False + with suppress_warnings() as sup: + sup.filter(UserWarning, + "You are solving a parameterized problem that is not DPP" + ) + sup.filter(UserWarning, + "Solution may be inaccurate") + m.main(rng=np.random.default_rng(1234)) if __name__ == '__main__': From 82d97cef940679d9739ab81ed3eedeec9d73ab1b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 9 Jan 2022 00:01:29 +0900 Subject: [PATCH 452/940] add mypy unit test (#621) * add mypy unit test * add mypy unit test * add mypy unit test --- .github/workflows/Linux_CI.yml | 15 -------- .github/workflows/MacOS_CI.yml | 15 -------- PathPlanning/DStarLite/d_star_lite.py | 14 ++++---- requirements.txt | 1 + tests/test_mypy_type_check.py | 50 +++++++++++++++++++++++++++ 5 files changed, 58 insertions(+), 37 deletions(-) create mode 100644 tests/test_mypy_type_check.py diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index d8cad21172..d0cdd2996c 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -28,21 +28,6 @@ jobs: run: | python -m pip install --upgrade pip python -m pip install -r requirements.txt - - name: install coverage - run: pip install coverage - - name: install mypy - run: pip install mypy - - name: mypy check - run: | - mypy -p AerialNavigation - mypy -p ArmNavigation - mypy -p Bipedal - mypy -p Control - mypy -p Localization - mypy -p Mapping - mypy -p PathPlanning - mypy -p PathTracking - mypy -p SLAM - name: do all unit tests run: bash runtests.sh diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index 1921799157..7fc1854386 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -35,20 +35,5 @@ jobs: python -m pip install --upgrade pip pip install numpy # cvxpy install workaround pip install -r requirements.txt - - name: install coverage - run: pip install coverage - - name: install mypy - run: pip install mypy - - name: mypy check - run: | - mypy -p AerialNavigation - mypy -p ArmNavigation - mypy -p Bipedal - mypy -p Control - mypy -p Localization - mypy -p Mapping - mypy -p PathPlanning - mypy -p PathTracking - mypy -p SLAM - name: do all unit tests run: bash runtests.sh \ No newline at end of file diff --git a/PathPlanning/DStarLite/d_star_lite.py b/PathPlanning/DStarLite/d_star_lite.py index 603c053dab..c250e38f91 100644 --- a/PathPlanning/DStarLite/d_star_lite.py +++ b/PathPlanning/DStarLite/d_star_lite.py @@ -64,15 +64,15 @@ def __init__(self, ox: list, oy: list): for x, y in zip(ox, oy)] self.start = Node(0, 0) self.goal = Node(0, 0) - self.U = list() + self.U = list() # type: ignore self.km = 0.0 self.kold = 0.0 - self.rhs = list() - self.g = list() - self.detected_obstacles = list() + self.rhs = list() # type: ignore + self.g = list() # type: ignore + self.detected_obstacles = list() # type: ignore if show_animation: - self.detected_obstacles_for_plotting_x = list() - self.detected_obstacles_for_plotting_y = list() + self.detected_obstacles_for_plotting_x = list() # type: ignore + self.detected_obstacles_for_plotting_y = list() # type: ignore def create_grid(self, val: float): grid = list() @@ -248,7 +248,7 @@ def compare_paths(self, path1: list, path2: list): return False return True - def display_path(self, path: list, colour: str, alpha: int = 1): + def display_path(self, path: list, colour: str, alpha: float = 1.0): px = [(node.x + self.x_min_world) for node in path] py = [(node.y + self.y_min_world) for node in path] drawing = plt.plot(px, py, colour, alpha=alpha) diff --git a/requirements.txt b/requirements.txt index c0de8f226a..8b6a5ecbfe 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,6 +5,7 @@ matplotlib == 3.5.1 cvxpy == 1.1.18 pytest == 6.2.5 # For unit test pytest-xdist == 2.5.0 # For unit test +mypy == 0.931 # For unit test flake8 == 4.0.1 # For unit test sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 diff --git a/tests/test_mypy_type_check.py b/tests/test_mypy_type_check.py new file mode 100644 index 0000000000..07afb40afd --- /dev/null +++ b/tests/test_mypy_type_check.py @@ -0,0 +1,50 @@ +import os +import subprocess + +import conftest + +SUBPACKAGE_LIST = [ + "AerialNavigation", + "ArmNavigation", + "Bipedal", + "Control", + "Localization", + "Mapping", + "PathPlanning", + "PathTracking", + "SLAM", +] + + +def run_mypy(dir_name, project_path, config_path): + res = subprocess.run( + ['mypy', + '--config-file', + config_path, + '-p', + dir_name], + cwd=project_path, + stdout=subprocess.PIPE, + encoding='utf-8') + return res.returncode, res.stdout + + +def test(): + project_dir_path = os.path.dirname( + os.path.dirname(os.path.abspath(__file__))) + print(f"{project_dir_path=}") + + config_path = os.path.join(project_dir_path, "mypy.ini") + print(f"{config_path=}") + + for sub_package_name in SUBPACKAGE_LIST: + rc, errors = run_mypy(sub_package_name, project_dir_path, config_path) + if errors: + print(errors) + else: + print("No lint errors found.") + assert rc == 0 + + +if __name__ == '__main__': + conftest.run_this_test(__file__) From e24e2b781d270c37a71ae49ff62e3a25b8d69af6 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 11 Jan 2022 07:20:58 +0900 Subject: [PATCH 453/940] Bump ipython from 7.30.1 to 7.31.0 (#624) Bumps [ipython](https://github.com/ipython/ipython) from 7.30.1 to 7.31.0. - [Release notes](https://github.com/ipython/ipython/releases) - [Commits](https://github.com/ipython/ipython/compare/7.30.1...7.31.0) --- updated-dependencies: - dependency-name: ipython dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- docs/requirements.txt | 2 +- requirements.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/requirements.txt b/docs/requirements.txt index 3d564ac8d9..9d921cb0fc 100644 --- a/docs/requirements.txt +++ b/docs/requirements.txt @@ -1,3 +1,3 @@ sphinx < 5.0 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 7.30.1 # For sphinx documentation +IPython == 7.31.0 # For sphinx documentation diff --git a/requirements.txt b/requirements.txt index 8b6a5ecbfe..87d71b96a7 100644 --- a/requirements.txt +++ b/requirements.txt @@ -9,4 +9,4 @@ mypy == 0.931 # For unit test flake8 == 4.0.1 # For unit test sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 7.30.1 # For sphinx documentation +IPython == 7.31.0 # For sphinx documentation From 727354c5397f3af857fd33ad6f333724a6892e5d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Jan 2022 12:48:04 +0900 Subject: [PATCH 454/940] Bump numpy from 1.22.0 to 1.22.1 (#626) Bumps [numpy](https://github.com/numpy/numpy) from 1.22.0 to 1.22.1. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/HOWTO_RELEASE.rst.txt) - [Commits](https://github.com/numpy/numpy/compare/v1.22.0...v1.22.1) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 87d71b96a7..e44291157d 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.22.0 +numpy == 1.22.1 scipy == 1.7.3 pandas == 1.3.5 matplotlib == 3.5.1 From cc30a6bbe928c1c4043a157cfd54da953a7ec6ac Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Jan 2022 19:34:13 +0900 Subject: [PATCH 455/940] Bump ipython from 7.31.0 to 8.0.0 (#627) Bumps [ipython](https://github.com/ipython/ipython) from 7.31.0 to 8.0.0. - [Release notes](https://github.com/ipython/ipython/releases) - [Commits](https://github.com/ipython/ipython/compare/7.31.0...8.0.0) --- updated-dependencies: - dependency-name: ipython dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- docs/requirements.txt | 2 +- requirements.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/requirements.txt b/docs/requirements.txt index 9d921cb0fc..f38287f015 100644 --- a/docs/requirements.txt +++ b/docs/requirements.txt @@ -1,3 +1,3 @@ sphinx < 5.0 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 7.31.0 # For sphinx documentation +IPython == 8.0.0 # For sphinx documentation diff --git a/requirements.txt b/requirements.txt index e44291157d..dbd81424ac 100644 --- a/requirements.txt +++ b/requirements.txt @@ -9,4 +9,4 @@ mypy == 0.931 # For unit test flake8 == 4.0.1 # For unit test sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 7.31.0 # For sphinx documentation +IPython == 8.0.0 # For sphinx documentation From 30dae5691f5639ca5ab0ad953d53e68d2d733f32 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Jan 2022 19:34:27 +0900 Subject: [PATCH 456/940] Bump sphinx from 4.3.2 to 4.4.0 (#625) Bumps [sphinx](https://github.com/sphinx-doc/sphinx) from 4.3.2 to 4.4.0. - [Release notes](https://github.com/sphinx-doc/sphinx/releases) - [Changelog](https://github.com/sphinx-doc/sphinx/blob/4.x/CHANGES) - [Commits](https://github.com/sphinx-doc/sphinx/compare/v4.3.2...v4.4.0) --- updated-dependencies: - dependency-name: sphinx dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index dbd81424ac..306ac1e1c1 100644 --- a/requirements.txt +++ b/requirements.txt @@ -7,6 +7,6 @@ pytest == 6.2.5 # For unit test pytest-xdist == 2.5.0 # For unit test mypy == 0.931 # For unit test flake8 == 4.0.1 # For unit test -sphinx == 4.3.2 # For sphinx documentation +sphinx == 4.4.0 # For sphinx documentation sphinx_rtd_theme == 1.0.0 IPython == 8.0.0 # For sphinx documentation From 88c7447d292685ec849a09b717db510807e7f19e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 18 Jan 2022 21:28:07 +0900 Subject: [PATCH 457/940] Update requirements.txt --- docs/requirements.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/requirements.txt b/docs/requirements.txt index f38287f015..b093728994 100644 --- a/docs/requirements.txt +++ b/docs/requirements.txt @@ -1,3 +1,3 @@ -sphinx < 5.0 # For sphinx documentation +sphinx = 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 8.0.0 # For sphinx documentation +IPython == 7.30.1 # For sphinx documentation From d2645da2c7ff6ecbb4b62b7c6612712380ba91e1 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 18 Jan 2022 21:31:10 +0900 Subject: [PATCH 458/940] Update requirements.txt --- docs/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/requirements.txt b/docs/requirements.txt index b093728994..6614e6b8db 100644 --- a/docs/requirements.txt +++ b/docs/requirements.txt @@ -1,3 +1,3 @@ -sphinx = 4.3.2 # For sphinx documentation +sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 IPython == 7.30.1 # For sphinx documentation From 87a535ae752a50674e26db0aadd5005bbcef7f45 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 18 Jan 2022 21:39:47 +0900 Subject: [PATCH 459/940] Rename requirements.txt to doc_requirements.txt --- docs/{requirements.txt => doc_requirements.txt} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename docs/{requirements.txt => doc_requirements.txt} (100%) diff --git a/docs/requirements.txt b/docs/doc_requirements.txt similarity index 100% rename from docs/requirements.txt rename to docs/doc_requirements.txt From 7c3dbb01e0d1fd64f6eb9c37799161930b9d664d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sat, 22 Jan 2022 07:36:51 +0900 Subject: [PATCH 460/940] Bump ipython from 7.30.1 to 7.31.1 in /docs (#628) Bumps [ipython](https://github.com/ipython/ipython) from 7.30.1 to 7.31.1. - [Release notes](https://github.com/ipython/ipython/releases) - [Commits](https://github.com/ipython/ipython/compare/7.30.1...7.31.1) --- updated-dependencies: - dependency-name: ipython dependency-type: direct:production ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- docs/doc_requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/doc_requirements.txt b/docs/doc_requirements.txt index 6614e6b8db..65670d346e 100644 --- a/docs/doc_requirements.txt +++ b/docs/doc_requirements.txt @@ -1,3 +1,3 @@ sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 7.30.1 # For sphinx documentation +IPython == 7.31.1 # For sphinx documentation From 1280ace8e03cf68b28cc551af15cd4f0ed518459 Mon Sep 17 00:00:00 2001 From: Muhammad-Yazdian <93126501+Muhammad-Yazdian@users.noreply.github.com> Date: Sat, 22 Jan 2022 00:12:59 +0100 Subject: [PATCH 461/940] Fix format to show contents properly (#608) * Fix format to show contents properly Lots of contents were not displayed correctly. I empty lines and :math: labels and fixed it. * Rewrote one subscript as _{rho} This is just a try to see if subscript renders properly. * Added a gif animation for move to pose robot * Added gif; Removed png * Added the into * Changed Param. Def. style to bold text * Added algorithm logic and math * Update docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst Co-authored-by: Atsushi Sakai * Update docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst Co-authored-by: Atsushi Sakai * Changed Eqs 1 and 2 color to black * Added cross-reference labels for Equations 1 and 2 Co-authored-by: Atsushi Sakai --- .../move_to_a_pose_control.rst | 108 ++++++++++++++---- 1 file changed, 84 insertions(+), 24 deletions(-) diff --git a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst index 81c64f5485..c8d844d053 100644 --- a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst +++ b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst @@ -1,11 +1,23 @@ -Move to a pose control +Position Control of non-Holonomic Systems +----------------------------------------- + +This section explains the logic of a position controller for systems with constraint (non-Holonomic system). + +The position control of a 1-DOF (Degree of Freedom) system is quite straightforward. We only need to compute a position error and multiply it with a proportional gain to create a command. The actuator of the system takes this command and drive the system to the target position. This controller can be easily extended to higher dimensions (e.g., using Kp_x and Kp_y gains for a 2D position control). In these systems, the number of control commands is equal to the number of degrees of freedom (Holonomic system). + +To describe the configuration of a car on a 2D plane, we need three DOFs (i.e., x, y, and theta). But to drive a car we only need two control commands (theta_engine and theta_steering_wheel). This difference is because of a constraint between the x and y DOFs. The relationship between the delta_x and delta_y is governed by the theta_steering_wheel. + +Note that a car is normally a non-Holonomic system but if the road is slippery, the car turns into a Holonomic system and thus it needs three independent commands to be controlled. + +Move to a Pose Control ---------------------- -This is a simulation of moving to a pose control. +In this section, we present the logic of PathFinderController that drives a car from a start pose (x, y, theta) to a goal pose. A simulation of moving to a pose control is presented below. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif + PathFinderController class ~~~~~~~~~~~~~~~~~~~~~~~~~~ @@ -13,45 +25,87 @@ Constructor ~~~~~~~~~~~ .. code-block:: ipython3 + PathFinderController(Kp_rho, Kp_alpha, Kp_beta) Constructs an instantiate of the PathFinderController for navigating a 3-DOF wheeled robot on a 2D plane. Parameters: -- Kp_rho: The linear velocity gain to translate the robot along a line towards the goal -- Kp_alpha: The angular velocity gain to rotate the robot towards the goal -- Kp_beta: The offset angular velocity gain accounting for smooth merging to the goal angle (i.e., it helps the robot heading to be parallel to the target angle.) + +- | **Kp_rho** : The linear velocity gain to translate the robot along a line towards the goal +- | **Kp_alpha** : The angular velocity gain to rotate the robot towards the goal +- | **Kp_beta** : The offset angular velocity gain accounting for smooth merging to the goal angle (i.e., it helps the robot heading to be parallel to the target angle.) Member function(s) ~~~~~~~~~~~~~~~~~~ .. code-block:: ipython3 + calc_control_command(x_diff, y_diff, theta, theta_goal) Returns the control command for the linear and angular velocities as well as the distance to goal Parameters: -- x_diff : The position of target with respect to current robot position in x direction -- y_diff : The position of target with respect to current robot position in y direction -- theta : The current heading angle of robot with respect to x axis -- theta_goal : The target angle of robot with respect to x axis + +- | **x_diff** : The position of target with respect to current robot position in x direction +- | **y_diff** : The position of target with respect to current robot position in y direction +- | **theta** : The current heading angle of robot with respect to x axis +- | **theta_goal** : The target angle of robot with respect to x axis Returns: -- rho : The distance between the robot and the goal position -- v : Command linear velocity -- w : Command angular velocity + +- | **rho** : The distance between the robot and the goal position +- | **v** : Command linear velocity +- | **w** : Command angular velocity + +How does the Algorithm Work +~~~~~~~~~~~~~~~~~~~~~~~~~~~ +The distance between the robot and the goal position, :math:`\rho`, is computed as + +.. math:: + \rho = \sqrt{(x_{robot} - x_{target})^2 + (y_{robot} - y_{target})^2}. + +The distance :math:`\rho` is used to determine the robot speed. The idea is to slow down the robot as it gets closer to the target. + +.. math:: + v = K_P{_\rho} \times \rho\qquad + :label: eq1 + +Note that for your applications, you need to tune the speed gain, :math:`K_P{_\rho}` to a proper value. + +To turn the robot and align its heading, :math:`\theta`, toward the target position (not orientation), :math:`\rho \vec{u}`, we need to compute the angle difference :math:`\alpha`. + +.. math:: + \alpha = (\arctan2(y_{diff}, x_{diff}) - \theta + \pi) mod (2\pi) - \pi + +The term :math:`mod(2\pi)` is used to map the angle to :math:`[-\pi, \pi)` range. + +Lastly to correct the orientation of the robot, we need to compute the orientation error, :math:`\beta`, of the robot. + +.. math:: + \beta = (\theta_{goal} - \theta - \alpha + \pi) mod (2\pi) - \pi + +Note that to cancel out the effect of :math:`\alpha` when the robot is at the vicinity of the target, the term + +:math:`-\alpha` is included. + +The final angular speed command is given by + +.. math:: + \omega = K_P{_\alpha} \alpha - K_P{_\beta} \beta\qquad + :label: eq2 + +The linear and angular speeds (Equations :eq:`eq1` and :eq:`eq2`) are the output of the algorithm. Move to a Pose Robot (Class) ---------------------------- This program (move_to_pose_robot.py) provides a Robot class to define different robots with different specifications. Using this class, you can simulate different robots simultaneously and compare the effect of your parameter settings. -.. image:: https://user-images.githubusercontent.com/93126501/145834505-a8df8311-5445-413f-a96f-00460d47991c.png - -Note: A gif animation will be added soon. +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/move_to_pos_robot_class/animation.gif -Note: The robot Class is based on PathFinderController class in 'the move_to_pose.py'. +Note: The robot class is based on PathFinderController class in 'the move_to_pose.py'. Robot Class ~~~~~~~~~~~ @@ -60,36 +114,42 @@ Constructor ~~~~~~~~~~~ .. code-block:: ipython3 + Robot(name, color, max_linear_speed, max_angular_speed, path_finder_controller) Constructs an instantiate of the 3-DOF wheeled Robot navigating on a 2D plane Parameters: -- name : (string) The name of the robot -- color : (string) The color of the robot -- max_linear_speed : (float) The maximum linear speed that the robot can go -- max_angular_speed : (float) The maximum angular speed that the robot can rotate about its vertical axis -- path_finder_controller : (PathFinderController) A configurable controller to finds the path and calculates command linear and angular velocities. + +- | **name** : (string) The name of the robot +- | **color** : (string) The color of the robot +- | **max_linear_speed** : (float) The maximum linear speed that the robot can go +- | **max_angular_speed** : (float) The maximum angular speed that the robot can rotate about its vertical axis +- | **path_finder_controller** : (PathFinderController) A configurable controller to finds the path and calculates command linear and angular velocities. Member function(s) ~~~~~~~~~~~~~~~~~~ .. code-block:: ipython3 + set_start_target_poses(pose_start, pose_target) Sets the start and target positions of the robot. Parameters: -- pose_start : (Pose) Start postion of the robot (see the Pose class) -- pose_target : (Pose) Target postion of the robot (see the Pose class) + +- | **pose_start** : (Pose) Start postion of the robot (see the Pose class) +- | **pose_target** : (Pose) Target postion of the robot (see the Pose class) .. code-block:: ipython3 + move(dt) Move the robot for one time step increment Parameters: -- dt: time increment + +- | **dt** : time increment See Also -------- From 2878c4a84cdac66b0f0c471758809a385b83546c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sat, 22 Jan 2022 18:57:04 +0900 Subject: [PATCH 462/940] Bump ipython from 8.0.0 to 8.0.1 (#629) Bumps [ipython](https://github.com/ipython/ipython) from 8.0.0 to 8.0.1. - [Release notes](https://github.com/ipython/ipython/releases) - [Commits](https://github.com/ipython/ipython/compare/8.0.0...8.0.1) --- updated-dependencies: - dependency-name: ipython dependency-type: direct:production ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- docs/doc_requirements.txt | 2 +- requirements.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/doc_requirements.txt b/docs/doc_requirements.txt index 65670d346e..9319f7729f 100644 --- a/docs/doc_requirements.txt +++ b/docs/doc_requirements.txt @@ -1,3 +1,3 @@ sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 7.31.1 # For sphinx documentation +IPython == 8.0.1 # For sphinx documentation diff --git a/requirements.txt b/requirements.txt index 306ac1e1c1..557aab4368 100644 --- a/requirements.txt +++ b/requirements.txt @@ -9,4 +9,4 @@ mypy == 0.931 # For unit test flake8 == 4.0.1 # For unit test sphinx == 4.4.0 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 8.0.0 # For sphinx documentation +IPython == 8.0.1 # For sphinx documentation From 058addd2ba90a16e2697333ba5be2f430944f417 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 22 Jan 2022 22:18:22 +0900 Subject: [PATCH 463/940] add requirements dir (#630) * add requirements dir * add requirements dir * add requirements dir --- .circleci/config.yml | 2 +- .github/dependabot.yml | 2 +- .github/workflows/Linux_CI.yml | 2 +- .github/workflows/MacOS_CI.yml | 4 +- README.md | 4 +- appveyor.yml | 2 +- docs/doc_requirements.txt | 2 +- docs/getting_started_main.rst | 4 +- .../move_to_a_pose_control.rst | 39 +++++++++---------- .../environment.yml | 0 .../requirements.txt | 3 -- rundiffstylecheck.sh | 15 ------- ...odel_predictive_speed_and_steer_control.py | 3 +- tests/test_rocket_powered_landing.py | 1 - 14 files changed, 30 insertions(+), 53 deletions(-) rename environment.yml => requirements/environment.yml (100%) rename requirements.txt => requirements/requirements.txt (65%) delete mode 100755 rundiffstylecheck.sh diff --git a/.circleci/config.yml b/.circleci/config.yml index 4866240bd4..0a1962ad0b 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -14,7 +14,7 @@ jobs: command: | python -m venv venv . venv/bin/activate - pip install -r requirements.txt + pip install -r docs/doc_requirements.txt cd docs;make html - store_artifacts: path: docs/_build/html/ diff --git a/.github/dependabot.yml b/.github/dependabot.yml index 9117f1216c..07f1bc80e0 100644 --- a/.github/dependabot.yml +++ b/.github/dependabot.yml @@ -1,7 +1,7 @@ version: 2 updates: - package-ecosystem: pip - directory: "/" + directory: "/requirements" schedule: interval: weekly time: "20:00" diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index d0cdd2996c..c706a50ed6 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -27,7 +27,7 @@ jobs: - name: Install dependencies run: | python -m pip install --upgrade pip - python -m pip install -r requirements.txt + python -m pip install -r requirements/requirements.txt - name: do all unit tests run: bash runtests.sh diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index 7fc1854386..4088c4900f 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -33,7 +33,7 @@ jobs: - name: Install dependencies run: | python -m pip install --upgrade pip - pip install numpy # cvxpy install workaround - pip install -r requirements.txt + #pip install numpy # cvxpy install workaround + pip install -r requirements/requirements.txt - name: do all unit tests run: bash runtests.sh \ No newline at end of file diff --git a/README.md b/README.md index f297b6fc12..9aff69ab72 100644 --- a/README.md +++ b/README.md @@ -141,11 +141,11 @@ All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation using conda : -> conda env create -f environment.yml +> conda env create -f requirements/environment.yml using pip : -> pip install -r requirements.txt +> pip install -r requirements/requirements.txt 3. Execute python script in each directory. diff --git a/appveyor.yml b/appveyor.yml index e9535e4e3c..c35e76ae4a 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -37,7 +37,7 @@ install: - SET PATH=%PYTHON%;%PYTHON%\Scripts;%PYTHON%\Library\bin;%PATH% - SET PATH=%PATH%;C:\Program Files (x86)\Microsoft Visual Studio 14.0\VC\bin - "python -m pip install --upgrade pip" - - "python -m pip install -r requirements.txt" + - "python -m pip install -r requirements/requirements.txt" - "python -m pip install pytest-xdist" # Check that we have the expected version and architecture for Python diff --git a/docs/doc_requirements.txt b/docs/doc_requirements.txt index 9319f7729f..65670d346e 100644 --- a/docs/doc_requirements.txt +++ b/docs/doc_requirements.txt @@ -1,3 +1,3 @@ sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 8.0.1 # For sphinx documentation +IPython == 7.31.1 # For sphinx documentation diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index d907ab8669..a7b9ff3607 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -67,13 +67,13 @@ using conda : .. code-block:: - >$ conda env create -f environment.yml + >$ conda env create -f requirements/environment.yml using pip : .. code-block:: - >$ pip install -r requirements.txt + >$ pip install -r requirements/requirements.txt 3. Execute python script in each directory. diff --git a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst index c8d844d053..8bb40f2201 100644 --- a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst +++ b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst @@ -1,5 +1,12 @@ +Move to a Pose Control +---------------------- + +In this section, we present the logic of PathFinderController that drives a car from a start pose (x, y, theta) to a goal pose. A simulation of moving to a pose control is presented below. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif + Position Control of non-Holonomic Systems ------------------------------------------ +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ This section explains the logic of a position controller for systems with constraint (non-Holonomic system). @@ -9,20 +16,11 @@ To describe the configuration of a car on a 2D plane, we need three DOFs (i.e., Note that a car is normally a non-Holonomic system but if the road is slippery, the car turns into a Holonomic system and thus it needs three independent commands to be controlled. -Move to a Pose Control ----------------------- - -In this section, we present the logic of PathFinderController that drives a car from a start pose (x, y, theta) to a goal pose. A simulation of moving to a pose control is presented below. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif - - - PathFinderController class ~~~~~~~~~~~~~~~~~~~~~~~~~~ Constructor -~~~~~~~~~~~ +^^^^^^^^^^^ .. code-block:: ipython3 @@ -38,7 +36,7 @@ Parameters: Member function(s) -~~~~~~~~~~~~~~~~~~ +^^^^^^^^^^^^^^^^^^ .. code-block:: ipython3 @@ -99,7 +97,8 @@ The final angular speed command is given by The linear and angular speeds (Equations :eq:`eq1` and :eq:`eq2`) are the output of the algorithm. Move to a Pose Robot (Class) ----------------------------- +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + This program (move_to_pose_robot.py) provides a Robot class to define different robots with different specifications. Using this class, you can simulate different robots simultaneously and compare the effect of your parameter settings. @@ -108,10 +107,10 @@ Using this class, you can simulate different robots simultaneously and compare t Note: The robot class is based on PathFinderController class in 'the move_to_pose.py'. Robot Class -~~~~~~~~~~~ +^^^^^^^^^^^^ Constructor -~~~~~~~~~~~ +^^^^^^^^^^^^ .. code-block:: ipython3 @@ -128,7 +127,7 @@ Parameters: - | **path_finder_controller** : (PathFinderController) A configurable controller to finds the path and calculates command linear and angular velocities. Member function(s) -~~~~~~~~~~~~~~~~~~ +^^^^^^^^^^^^^^^^^^^ .. code-block:: ipython3 @@ -151,12 +150,10 @@ Parameters: - | **dt** : time increment -See Also --------- -- PathFinderController class -Ref: ----- +References +~~~~~~~~~~~~ +- PathFinderController class - `P. I. Corke, "Robotics, Vision and Control" \| SpringerLink p102 `__ diff --git a/environment.yml b/requirements/environment.yml similarity index 100% rename from environment.yml rename to requirements/environment.yml diff --git a/requirements.txt b/requirements/requirements.txt similarity index 65% rename from requirements.txt rename to requirements/requirements.txt index 557aab4368..f052ea51fc 100644 --- a/requirements.txt +++ b/requirements/requirements.txt @@ -7,6 +7,3 @@ pytest == 6.2.5 # For unit test pytest-xdist == 2.5.0 # For unit test mypy == 0.931 # For unit test flake8 == 4.0.1 # For unit test -sphinx == 4.4.0 # For sphinx documentation -sphinx_rtd_theme == 1.0.0 -IPython == 8.0.1 # For sphinx documentation diff --git a/rundiffstylecheck.sh b/rundiffstylecheck.sh deleted file mode 100755 index 8a19842c6e..0000000000 --- a/rundiffstylecheck.sh +++ /dev/null @@ -1,15 +0,0 @@ -#!/bin/bash -echo "$(basename $0) start!" -VERSION=v0.1.6 -wget https://github.com/AtsushiSakai/DiffSentinel/archive/${VERSION}.zip -unzip ${VERSION}.zip -./DiffSentinel*/starter.sh HEAD origin/master -check_result=$? -rm -rf ${VERSION}.zip DiffSentinel* -if [[ ${check_result} -ne 0 ]]; -then - echo "Error: Your changes contain pycodestyle errors." - exit 1 -fi -echo "$(basename $0) done!" -exit 0 diff --git a/tests/test_model_predictive_speed_and_steer_control.py b/tests/test_model_predictive_speed_and_steer_control.py index 0ed520dcbe..9bc8ccf31c 100644 --- a/tests/test_model_predictive_speed_and_steer_control.py +++ b/tests/test_model_predictive_speed_and_steer_control.py @@ -1,5 +1,4 @@ -import sys -import conftest +import conftest # Add root path to sys.path from PathTracking.model_predictive_speed_and_steer_control \ import model_predictive_speed_and_steer_control as m diff --git a/tests/test_rocket_powered_landing.py b/tests/test_rocket_powered_landing.py index 52b812eeda..2f294c74cf 100644 --- a/tests/test_rocket_powered_landing.py +++ b/tests/test_rocket_powered_landing.py @@ -1,5 +1,4 @@ import conftest # Add root path to sys.path -import sys import numpy as np from numpy.testing import suppress_warnings From c066a9420e9373e85bc2214cbb44e3a2fd5cc593 Mon Sep 17 00:00:00 2001 From: Trung Kien Date: Sun, 23 Jan 2022 17:35:54 +0700 Subject: [PATCH 464/940] InvertedPendulumMPCControl: fixed deprecated waring about using * for matrix multiplication (#631) --- .../InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Control/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py b/Control/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py index e7b3077740..3764f29558 100644 --- a/Control/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py +++ b/Control/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py @@ -77,7 +77,7 @@ def mpc_control(x0): for t in range(T): cost += cvxpy.quad_form(x[:, t + 1], Q) cost += cvxpy.quad_form(u[:, t], R) - constr += [x[:, t + 1] == A * x[:, t] + B * u[:, t]] + constr += [x[:, t + 1] == A @ x[:, t] + B @ u[:, t]] constr += [x[:, 0] == x0[:, 0]] prob = cvxpy.Problem(cvxpy.Minimize(cost), constr) From 550baa1e4929aa98e69d4da97205809943cce213 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 23 Jan 2022 20:07:34 +0900 Subject: [PATCH 465/940] fix duplicated math lables (#633) --- .../move_to_a_pose_control.rst | 6 ++-- .../quintic_polynomials_planner.rst | 34 +++++++++---------- 2 files changed, 20 insertions(+), 20 deletions(-) diff --git a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst index 8bb40f2201..77ec682a30 100644 --- a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst +++ b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst @@ -68,7 +68,7 @@ The distance :math:`\rho` is used to determine the robot speed. The idea is to s .. math:: v = K_P{_\rho} \times \rho\qquad - :label: eq1 + :label: move_to_a_pose_eq1 Note that for your applications, you need to tune the speed gain, :math:`K_P{_\rho}` to a proper value. @@ -92,9 +92,9 @@ The final angular speed command is given by .. math:: \omega = K_P{_\alpha} \alpha - K_P{_\beta} \beta\qquad - :label: eq2 + :label: move_to_a_pose_eq2 -The linear and angular speeds (Equations :eq:`eq1` and :eq:`eq2`) are the output of the algorithm. +The linear and angular speeds (Equations :eq:`move_to_a_pose_eq1` and :eq:`move_to_a_pose_eq2`) are the output of the algorithm. Move to a Pose Robot (Class) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ diff --git a/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner.rst b/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner.rst index 2bced07034..feec345bae 100644 --- a/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner.rst +++ b/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner.rst @@ -18,7 +18,7 @@ We assume a one-dimensional robot motion :math:`x(t)` at time :math:`t` is formulated as a quintic polynomials based on time as follows: .. math:: x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5 - :label: eq1 + :label: quintic_eq1 :math:`a_0, a_1. a_2, a_3, a_4, a_5` are parameters of the quintic polynomial. @@ -31,44 +31,44 @@ End position, velocity, and acceleration are :math:`x_e, v_e, a_e` respectively. So, when time is 0. .. math:: x(0) = a_0 = x_s - :label: eq2 + :label: quintic_eq2 -Then, differentiating the equation :eq:`eq1` with t, +Then, differentiating the equation :eq:`quintic_eq1` with t, .. math:: x'(t) = a_1+2a_2t+3a_3t^2+4a_4t^3+5a_5t^4 - :label: eq3 + :label: quintic_eq3 So, when time is 0, .. math:: x'(0) = a_1 = v_s - :label: eq4 + :label: quintic_eq4 -Then, differentiating the equation :eq:`eq3` with t again, +Then, differentiating the equation :eq:`quintic_eq3` with t again, .. math:: x''(t) = 2a_2+6a_3t+12a_4t^2 - :label: eq5 + :label: quintic_eq5 So, when time is 0, .. math:: x''(0) = 2a_2 = a_s - :label: eq6 + :label: quintic_eq6 -so, we can calculate :math:`a_0, a_1, a_2` with eq. :eq:`eq2`, :eq:`eq4`, :eq:`eq6` and boundary conditions. +so, we can calculate :math:`a_0, a_1, a_2` with eq. :eq:`quintic_eq2`, :eq:`quintic_eq4`, :eq:`quintic_eq6` and boundary conditions. -:math:`a_3, a_4, a_5` are still unknown in eq :eq:`eq1`. +:math:`a_3, a_4, a_5` are still unknown in eq :eq:`quintic_eq1`. -We assume that the end time for a maneuver is :math:`T`, we can get these equations from eq :eq:`eq1`, :eq:`eq3`, :eq:`eq5`: +We assume that the end time for a maneuver is :math:`T`, we can get these equations from eq :eq:`quintic_eq1`, :eq:`quintic_eq3`, :eq:`quintic_eq5`: .. math:: x(T)=a_0+a_1T+a_2T^2+a_3T^3+a_4T^4+a_5T^5=x_e - :label: eq7 + :label: quintic_eq7 .. math:: x'(T)=a_1+2a_2T+3a_3T^2+4a_4T^3+5a_5T^4=v_e - :label: eq8 + :label: quintic_eq8 .. math:: x''(T)=2a_2+6a_3T+12a_4T^2+20a_5T^3=a_e - :label: eq9 + :label: quintic_eq9 -From eq :eq:`eq7`, :eq:`eq8`, :eq:`eq9`, we can calculate :math:`a_3, a_4, a_5` to solve the linear equations: :math:`Ax=b` +From eq :eq:`quintic_eq7`, :eq:`quintic_eq8`, :eq:`quintic_eq9`, we can calculate :math:`a_3, a_4, a_5` to solve the linear equations: :math:`Ax=b` .. math:: \begin{bmatrix} T^3 & T^4 & T^5 \\ 3T^2 & 4T^3 & 5T^4 \\ 6T & 12T^2 & 20T^3 \end{bmatrix}\begin{bmatrix} a_3\\ a_4\\ a_5\end{bmatrix}=\begin{bmatrix} x_e-x_s-v_sT-0.5a_sT^2\\ v_e-v_s-a_sT\\ a_e-a_s\end{bmatrix} @@ -80,10 +80,10 @@ Quintic polynomials for two dimensional robot motion (x-y) If you use two quintic polynomials along x axis and y axis, you can plan for two dimensional robot motion in x-y plane. .. math:: x(t) = a_0+a_1t+a_2t^2+a_3t^3+a_4t^4+a_5t^5 - :label: eq10 + :label: quintic_eq10 .. math:: y(t) = b_0+b_1t+b_2t^2+b_3t^3+b_4t^4+b_5t^5 - :label: eq11 + :label: quintic_eq11 It is assumed that terminal states (start and end) are known as boundary conditions. From 702551748cdfa64c2baa3debc6c84e05181e3416 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 25 Jan 2022 07:26:33 +0900 Subject: [PATCH 466/940] Bump pandas from 1.3.5 to 1.4.0 in /requirements (#634) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.3.5 to 1.4.0. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/main/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.3.5...v1.4.0) --- updated-dependencies: - dependency-name: pandas dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f052ea51fc..90e98e4f5b 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.22.1 scipy == 1.7.3 -pandas == 1.3.5 +pandas == 1.4.0 matplotlib == 3.5.1 cvxpy == 1.1.18 pytest == 6.2.5 # For unit test From 2c245d9d81ecd9efeb53f567401c15731e34f359 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 27 Jan 2022 21:37:19 +0900 Subject: [PATCH 467/940] enhance histogram filter doc (#623) * enhance histogram filter doc * enhance histogram filter doc * enhance histogram filter doc * enhance histogram filter doc * enhance histogram filter doc * enhance histogram filter doc * Update docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst * Update docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst * fix duplicated math lables * fix duplicated math lables * fix duplicated math lables * update doc * update doc * update doc * update doc * update doc * update doc --- .../histogram_filter/histogram_filter.py | 15 +-- .../extended_kalman_filter_localization.rst | 4 +- .../histogram_filter_localization/1.png | Bin 0 -> 57183 bytes .../histogram_filter_localization/2.png | Bin 0 -> 198077 bytes .../histogram_filter_localization/3.png | Bin 0 -> 98927 bytes .../histogram_filter_localization/4.png | Bin 0 -> 51007 bytes .../histogram_filter_localization.rst | 102 +++++++++++++++++- .../gaussian_grid_map/gaussian_grid_map.rst | 2 + 8 files changed, 110 insertions(+), 13 deletions(-) create mode 100644 docs/modules/localization/histogram_filter_localization/1.png create mode 100644 docs/modules/localization/histogram_filter_localization/2.png create mode 100644 docs/modules/localization/histogram_filter_localization/3.png create mode 100644 docs/modules/localization/histogram_filter_localization/4.png diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index 7f453d69dd..a4aeb419cf 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -71,7 +71,7 @@ def calc_gaussian_observation_pdf(grid_map, z, iz, ix, iy, std): d = math.hypot(x - z[iz, 1], y - z[iz, 2]) # likelihood - pdf = (1.0 - norm.cdf(abs(d - z[iz, 0]), 0.0, std)) + pdf = norm.pdf(d - z[iz, 0], 0.0, std) return pdf @@ -88,7 +88,7 @@ def observation_update(grid_map, z, std): return grid_map -def calc_input(): +def calc_control_input(): v = 1.0 # [m/s] yaw_rate = 0.1 # [rad/s] u = np.array([v, yaw_rate]).reshape(2, 1) @@ -113,6 +113,7 @@ def motion_model(x, u): def draw_heat_map(data, mx, my): max_value = max([max(i_data) for i_data in data]) + plt.grid(False) plt.pcolor(mx, my, data, vmax=max_value, cmap=plt.cm.get_cmap("Blues")) plt.axis("equal") @@ -197,6 +198,7 @@ def motion_update(grid_map, u, yaw): grid_map.dx -= x_shift * grid_map.xy_resolution grid_map.dy -= y_shift * grid_map.xy_resolution + # Add motion noise grid_map.data = gaussian_filter(grid_map.data, sigma=MOTION_STD) return grid_map @@ -230,9 +232,9 @@ def main(): while SIM_TIME >= time: time += DT - print("Time:", time) + print(f"{time=:.1f}") - u = calc_input() + u = calc_control_input() yaw = xTrue[2, 0] # Orientation is known xTrue, z, ud = observation(xTrue, u, RF_ID) @@ -249,8 +251,9 @@ def main(): plt.plot(xTrue[0, :], xTrue[1, :], "xr") plt.plot(RF_ID[:, 0], RF_ID[:, 1], ".k") for i in range(z.shape[0]): - plt.plot([xTrue[0, :], z[i, 1]], [ - xTrue[1, :], z[i, 2]], "-k") + plt.plot([xTrue[0, 0], z[i, 1]], + [xTrue[1, 0], z[i, 2]], + "-k") plt.title("Time[s]:" + str(time)[0: 4]) plt.pause(0.1) diff --git a/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst b/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst index 9777258e3e..d2cd52cf12 100644 --- a/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst +++ b/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst @@ -120,10 +120,10 @@ Its Jacobian matrix is :math:`\begin{equation*}  = \begin{bmatrix} 1& 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ \end{bmatrix} \end{equation*}` -Extented Kalman Filter +Extended Kalman Filter ~~~~~~~~~~~~~~~~~~~~~~ -Localization process using Extendted Kalman Filter:EKF is +Localization process using Extended Kalman Filter:EKF is === Predict === diff --git a/docs/modules/localization/histogram_filter_localization/1.png b/docs/modules/localization/histogram_filter_localization/1.png new file mode 100644 index 0000000000000000000000000000000000000000..5e3137cc1a5cd6d84068463b5a12842a1c3c32e4 GIT binary patch literal 57183 zcmeFYWmFtWvnV6aN<@TM(b>V=%GL}3kc>#tK+sgtz~lEIBO!SMLW99E0t=a<;*eAVVVU8vN#2k} zf57}0jz_OnD=+$vQu}?KWfQEjs%TXMRqG*@wNlyd0xU75dxh7Q#{xMoJ~^i=9IN-E zk1;;-CwzcCq_d()URCTsU#TEE66Rz!F8XXSZzME9fUF@hl9z8=G650Mt30ID7ls-K zK?f=gy=2`N{Fj;nFxv1vfLMiO^xfe7Jz5KFpu>)g89V?j#r<#|UYT4Ut}Y0P0_YTi zVNr3ePd=);iIt+D42!Tq3$Rr3;?-gYTy>0((rj6X5I*>XFO$L6!2z2Xcv&9%yjCHyh1DTfr%{u`y{yD~+ zp#-Ysl2|Eul|(mZ>L))f$-f9M(GEq&sNCRgz|;vYdjJ$8CDBtVZzSaIol%a6e0KnD zm}lP$NZ3O-g%h#y3hOM)BS5Waz0)7DA`n}p(C~yhWvNgVe&5-q{gNI3A&ggVir?Jt zA4{pyr`F$IGbm?nb7v44tcxrl4#pxc7M2Z~`=XeIfyhK)tl?#E+}Lm7TNjSWa|BW$ zqq=Mf;uNBaKvKIj3DK$#hl>f&>h^8bx9yPp88f{m0$)%>|bA-PcCkvgd}0QkK}{V8)5W=${20}o#Wf5 zGXU>veUZHO&F{ zp#~qt<5+A^e1*RacAE2Kj6Q;|!k1eauCDD~d)9%^U6L@^jG;+g0Y z*G%qu?i4uCWs!LJg@bd?%)i@kg1E-_AfsT5>BX6%T6hts+w*@o# zsZ(?%|AVv`vLefG6oROS0$WyGIpLE0`8~SE4|=~uwo1{1M!Slh&!sJFA>%euSC7I>mSy9pi zsYc3&uU((Tf0B%nR}lA?mQbgE+d( zrvghYm5e`ZEd9PX$2rtF?Lt~dXHj}l!6&g<(fZtw_{hXcHU+9_UU#BH;03pL#C_#{l5L}!>aMc5)b{;GJdI5c>!I6 zydKqnl4t5C38ZMFUu%qa(d5y3(JaySuL^>?U}lL2@|M_N?6&A2T`AWtr3M>ZiA&rA{qBO~4f17mkP%;XXxCTOXKa7;?|Lmh6*H`Lnn* zNV1g8i#Mp4ckRetqFv%&zP;Ss;lo0TB1Wte3+a0kwW<|L$4(ok*2n$ppn0y&1nigl4_oTQZiD$KI;VA>*7wEf5zC_XhqJo7&{;v9%jy_UNgua1Klb7Gw z&3UTVtk3P;+@0y2?M>Uh%^Kcm$M@STqHo~e4*3RAt2zM=FR(8n&jGJn;kI5MA$oGJ z_;)%&s?XzKt6;r?cwjp|Y6{^9Eq-eMNdL*}8{0QjkxCIbk`9raT7r45qo%-4n1P{3yIVyj!wnuq~lVDY$g6lue1F&0Lqi zC3TVGo5gp?o07t^iHM2J0-}D-zCq&*$^uMESzV5E`%1e?vSucfA5NPyealfTak=kb zHpw=M?xd!Z2q~jwKBqadCnRu!oD4P&i^hx8q&yM{65kKmQFBwPs93A46onR7%N=L% zx?ezsu%~1ve^|-w7hNS^E$=_6d@rfYo#dOgvEKiUH+590R}E{-L)&wKK0-c^G~4+~cS; zRjCi&yZp%f0d_8MZr<)3iWyl>;z>@+@E|sz6#%`IiW(%+a`8?1nos;hDQjp{U0@pt zn0e6htGArD=OWFeaG+rfB)U#}hZ0%y4)yJ)w-ty8<|RM*b&E8}sM}cwtVS=m6e2;9 zJ=sxX+hcZ_7F-VJod}onmmYM2Sf&h?I+k6I``=H*5~6MxzR->8L0lqqh87ZgQi~X@ z^sSp+CnhBf#QfDXq`@gED-iCrL%WePvkkN35x!Ih-RC-4Mfd!rs?K`I)7$4r#MS7> zF9(_VDO$9P8eTOE?HR4w^$-0SYivHV2UYa?kCw|n+>qZ_M%G96%#3LUbWb)oFTNgr z-4|M2{<-{13_G5NgKv*i<#o`nFPUi${taTa#V$63GY@v=i^DBliwrCNHWFL0 zp|~9x!`VNwLwJZzrRUvlbXFZ~JTi|MR-cUGOciEVg1bs={H$$m(@%8N!e*!syl)hi z1GYPAPcshm4m|J;38@5tC^RU~&wl;494KN$);vc(t`kR zlNsEx@|+7Z_~X7?60=0NjhfA>L@d0`2b|k?lba%xkqTEW(mFm0=DEJV*$a* zL&)qWhvC=J2sho=em*yP2OX538dj55H2fSP;}E8Y&EUY~&^izR4}$@C1+BqA z{{S$!0QkS^0Dv?M-hbDXVW|EY0}B9zSpnew8KVs?|9s-1UnulH<*UR{00Q(E2J{=8 z2m4>6VFUAC{Z}340@?=K&SqxzE|w0i`xo(&(1tgTl3FeR02cY5FN~Bj z*%{PaC`ER{xyOd zTL04wCMEuBh^q}BsivGFv514S88JHpBLgET|65{WVqRxcb8cl(@qfUfzxYTkU0ofy z!C(&$4+akw1_x&gFcTLS7nqS5%*;#=9YOEnW$$X_NpJ50`WwlA;Sn`+F>$tXbhUD@ zC;o%i$k@Tnm5-G452645{5?-IPpkh>vUmAsSeEKO7;>L!~aef zi6Mt?Y`pOyy8Cq)={wZtln+i4fb2^$*-TKl^gX9Tix$VzqP z{io?qPiP>fpabyVZLA+)-O34b#r_YbzY4)mBx`WB-)NSi4*yLCitN?D z!Tukzf9=lyJ$u&34foe6C4c-HOTZH;KlA&ysgo4uSd_eOf4Ee(%mgT%u!#axsJP&J zukPB%kjKG~20yi%_IH-fMi-4U)nQZR|1F)|?1;ypY#?Z24p4{IO?2kHRuO6$8y zV+GsL*1DV)o9!lNXE{vaWx8d=Z7}_hkB^znhTlcWKt@O9t*or5(`dv-_74v=vRmGA zv)Mdnm#gUL=$!9AJ{FgB=saA97s^5?HeSDeZF)FkSKgcF>gFb8b9e^&T)VQOpCrJ^ zY1zuo!GY($hr>ibFEBh^^*{nzC9yd8UB>o}&j7o}9S%Rpm6#E7B^AbB9Ri(d(FYjG z*P>8tRTtow3$XJT-|b*D4h!7HOIS7*J> zyT>iVVK0!e?Qs!QHm<>5G3TTJIn67X{!QN1^r9@@?*+1>k7_-Sgm+DlM-GMrLUPHe zFLFt@JugqrOHKng-$+py($n55qHYD(uJYdH`Mx}^rllG9Yc*TluU?+q4u+h1-OAqw ze-3#O#t(QpB;G7en;BYtK3*L@)W7A9lI>RDKM!7Ve>}dJGl?5|xIRQ4xxd67M3=xP zDamrKKk9xwfxjfBH(RcCD%ADfe;ItbeUff=ShaVY8?3N@_y%9sR2_d_*RjO{!M?1A_YpoX(94qG2Kf*MuzhgEDad37pVsq&Yx0RI+Uw`nzJNZkN(LYXAKMA58kLSB`Amv;AK z?rOs6^K1Z#{IhU`BhqH8`7*cHMg-;iF{}EQ=f_O)Ga>TqG~Elf`>=pJg!``u{KQdM z^!1G)&sVOugRf9|sWfz*LVVYWx`{hZnk%$kk!-M7j5ZqNyPo_}j4=^`m|y!VJ-|&M zMGV-4HP^lIU7ghjb-bAnq?=n*NgbOgLBQ%&KgV#}ZY~(fWCLh1=dsYpFmG|%_45I1 zTM&&z;K#Q}PR=~5WLG9p{IG}!l|cb5fN6XV5z3^9cWkR5T!3VP(U1-Y1ksqtU~f9({J(Im6VZRcbD8+j-{wqm1&I zzTPc42k$~;vlZ{ds*Ab81A!(L6whBaTa8olN%xn#s9Iy6HSYEbvj;3{WnY|Cb~>9P&W?;aI@4i`SM%Pf|=ds>{jF&vcN4 z%|l@<_i$(%NpL(>Xq*!dfMhow^Nj;pHJng0aq-^mCnAX8%5}Aeb$a`DyG;#y1;~k1 zYRPR@FT`N-xPFAe+^Ww3DuyCXNlu}oO;kLMgb&`2cAA+aUasrAMGio60Vk-2z=ujf z7d7<86dVGIUSPxlKL*b+NmLUP#k1}-`<=MtvM9sD{Gf5~81?FaT#VRhrsj{K=rLaO zy!fQ)y8LRYx4x#)s<}K)?P-;EUp8xA@>un|=mYynb>DWK4sq>fnTTWzc0HbSY#$oD zwDUe)O&Q7OV&op$w+h+c4ar^1_uMxciuEGzF|sklH#x@I|Fr0QII!8WF?h`A6o0eh z|9D*TaFfw}d`!TOKf*h(M>?S*M1lB%ZQ!d!+)!0z=X}$)JN(hhC2Vk^T&-g3VuT@S z`F2TV#q)x?{%F)kR#ipC9#4I)jQi@l62<5%^Eg^Ufix8bF0mW6t^%JPk5{`*j=!IAj-#;~7uE@~I3`Ys6HizH6aAd%8L z2Qkc-jjd()S=zWD1c~|k66+E}#}Q2cWB_{}?U0!~GT^Z#H%Y||H6DSaBX^{)=up?6V~C=(=8B{|;G&zAx(D$Ta@q%T(rFQ)#Qr-W)z>*Q&=q%Y78 z5CWlR9#nX8q|0HMLaxYvr&j4S4>xJ((Ia9pB*yt2nV4srk{{F7bQ%XodBsX$M=Ur7 ziOuXo_$Ehldo)+>zHmfP!H^MMecaM_xt_kretD=qD!U{hvTB?CA?Byb)I?FBLj2KV z*)0vKuL;b#e08xyS!tCZ!NyMUsU~y?)tcg~Uh5sMAH2#t+s!(bTuz@Z?#BXFTptG| z_>E1mo=o&jhAtT;zM>DZLm8?;uScI-BF`EqI%2@wD`-_KyU)u??rVgYy#4_R`Lx@# ztn>IdfGmv2zcrz^x!IlE2w|v(sMTPU=aiRAU*kYn(|y?u+w0iIfY#vdJ9cyyNl3mL z79V7>=P9#_-FyTGU!)AJA2r~v*LgkUG_@}ZTc$#Lz%e0kA>>)eJq*RbLD>dW;lkmd zZyQDb*&)p}fwd20B)v%Y_VQK0MN)2XN{95bBU;q}QGjmub(O+TwEY@RAk+s4<#c5ac2l)dBfDx(>d(tPvo|KF;q0H4dxnT1g9TN9;hBKPq&MNo)bigx6qqcYpz_4 zHs(yQ@*`fo+QRk~&eV2Szy<&P%k!qd7AW9eiEBT2b31&Nkim!Ai2I@xWCp$9StmI^ zvRb7(LloQ>?OO8lcXTQ0-H){iw7VB}FzO9oe+(6?t)V=cnw^>|(V4uG^2r>Xi2BIN zM4ODtbHqqL=B`y|oTBTs{r=(^wbP)w36&t`N5>-sB7B7!PBdX(1FKJtr&GRvdgUiV>tNvq<5VIjVWK>o=%rwqj&RerGwrwcfFmQV7w8GeXZ5M-sO1I58tId7D9Ku@^5@R@ zS56;4)Hw!w1=Ffm#v82o)cBs9KFjkzapWq|ZsZQF_#BH}De3(V17?Ys&x6l$U+!~% zU3g5%am&f*KX9r4(KE`cskH9OJ|5T z;s=ScryGz3O9@Ph^I;tf8)GH$UOh@om(PjB^FTS>5$?yEJPufBjS39=sTYeK8XZLY z+T9J);Ev41%4cP7uT+3BD6Je}^d?~xUg*BJ1r2Wr&vo^ihn{CX#t?gwMa~1l#w=IU z$c0e_F8)0-7kMhD`VCVEFq}OEKWKS~10OozE^p7dhYgd@%`sBs@6LcHaN8C#0B)5|m z)trQK*T+fg`oVKq20WA_lXlYRCMUZq0bPQnEL;|V-Mq`Ej3B6`1PTlzm(RS)l3_-CU+`e1qE1TGOmPZO_xO!<7sfQGAjD|9og% z-3%Y(48%R=5LMg@3tTsGV|ql`(9Fgk8T&GMTb`2G7K?<#a_e-w;8uTBXLit%iOkb5 z80^WhzRmWt zfdFyt(~*T)&C(gzinyiMDs0SP{0ZTHYdOnHW-HBO)e0{DKGNs7iPhXnqB$!)brF;R zj;iH^m++bkJA>Y{99-MUn0Bi|-FlEgP#jgA4#?nsSYs;~Q~m?#tU^V|h3~TMBhs%V zdUN7HI`8|f5{6WA?ySz+92qy2LwzsZ9=eOcr=HX}zYB-0UlyJ7>^-kn$)q^oA#r~U zXM9-tcCoL!c-6o44gYXIB5VRgi0bodvtX6JZBC~qw%Z!%#D{SsqrpWI1R_&B+6GHl zMC|p-XTFO;P#Ak$=m%j^RIWY4<=Ios^n^v4*IrOpsijJ`w!TlHO{hQ<^3`Ip7Lq`S zh`-pAm50cEv*P2>#N2%7+aa)r#VnBQ(YXn`%&@aYVuQ>5b4D(AKG8f3MeX#%(JZ|Y z)*zQfZbeVSAKk~uXQDM{n<1C2FbmE(qc_SlD2?L!JaF5uqR^Z&Jat_`DV0VR=bLR( zhBELG)9forha7!u6gIe?%O6d+GSJrJa^<#LW0Z3fNsq3Sl_SN z_k(&F_KHIWnWOKQUIL%CmrtKe+SanM57fDnds_mT^8VT@$t3>I-&?~!t^aX{zmlP? zDZx4!X>y>bQS=G@yhA4(dPf%T+Dq#y@)i<-*CHC>{B|hZh)J%K0`+Qbw#0kc^-^Iw zt6?;`=lL+|+J>}b_!|O|Z4tU(!P3@dt=5xP7e0YbIU`3rI0KT+fObCsekt_bX~<=| zF9HSV`fC|Kc#?rPcG8e>M7%9c2i@wCnD`_%KC+pKyzE^teGO=Q2)Bal{p}W@!f^Z} z{vfnU&2JcLlAdHHL$zdHL$}~}>XPEJ5)ff4VA$ZVX+JnEvB$MfJu@}FbV&*aJHwR_ z@?V$KQ zV#2iim&%DG4m5k~%$y-JibEEQED)V&&Z<>-pUIn&;;MvAXG3>ms063Zyz`R@GR#O5 z{Bv?4cm0aVE_r~^-}n4ezWr80P6**dOtD5ZX52leXh7_sRJ$*q@tozo)&Z5sq4Cv1 zc;esd42QZu;+1aT2GDpQ@SRL$|0fD+3sz_L93)f^ID8n1ycr-TOr;yL=kveAIjT58 z>o}uoqjL?=dky9<-TzlniVWKgECQSik>tRBJK6qo$bSc(a3qKiRd}-iSe9S4YOY|# z+`<0=vLuG8+8wo<3^to!qK>dxP3ZvXrUreSE(@J{P2w>6B~?L{4i9}XKShQ_ z;S!qHcB4DIdZWvNF;lF&Oa|$}7@2c`CZV^QDOPIU9`8qfvE87h*Y3Vr7QLa!&YdT> z_c0E>z1{rDVw_n33hR`ouj~#hbQaleslE?Wxy=epY@{$-E2pz@xUyR~d8;0bWSQi? z$Rsd_;Zx&EhiRA@3q@M5ue~&M2EOX68uXI|ZYE z6?GKJzBv^6x`Gu&cOAQ=Q{ivjXep5q(J$dyXQeoFl@TZ}Mw^=-9;$*;VO&>yhgsG` zw{7$;FSuEUuGuhUhPU)q+(n%Tv(jOXG%nlt5MP$kS)lI@pEg0FB2i#?c`)`gf#rR) z+-AeUpG{`he%xr`eiP{*VVN$l{jJYJj#3!Ff*OfE4wWtZpw~hG<@r)9!SW9>2KlGf z7F7?~fLP^1DHVqc-{igdi zeS>uBsRMWs0J4t{Cies5 zUX^nR6TKU~5vqB^#1Eoh-pMw`ZkD91pU5Bb`zun9wgbWQ*{ z7cNt-5V_B%y63&{ei$QCH*7KFrldWl(TU3s2zjE8)SBdpkNccJS-91R=F895qLXrD z_Q_*Tq}!5TE-#Ou*8iUs)g>||e-)v+7o@(T= z(8U@1V^cDR1dhS{RCQA?VMGhYHz<`4&4~hy=K=5hX7b*j_PN8A2SVeF6#(a%dP(i) zdi7@Ov;lhFY4OhPi_5gChjQ@j40iR?ISbKw76b_9k=(kpA zdBsW8B-L0%drc`WRvt`y0&c;fRtannt4F7%icEbe`}a9RP%_hd4@vLj@QU$@Dkb%y z#IfBfcbW1Uh%d0U`(UKW4bJv?TkutUVP%SwVRV&Srxq#*@a9UYzt=O_yC3xZjbYgy zn>aUAzl-y6xKej*+U*_OexF5$MN8FQs);XtX2!VE)?z*^E!UfV2aU}z!l$g!{G~m| zErCTbWalYq&Rn8$>iCF1e&T8~6zj%<;==+_VRm6Q(*9AgDH3`3WM#VA!i~|kDOT2E zQkUMBZ!xc_lcc>SpC-}KoM88={@T#Ezy#zcmWfy#S|oznv0|D4%ydh=WP?ve5$so4 z%wN=^^3RM!A(iN8XC!OlrQ6XdPJ4EICfgSqs%Sx$>*F2;c2-eR>y|Ng0YJkz}}QTWi4=C?8K`zhyMts!ojmg=MwiCuPegtTdP zwS$pS)AO6F>#(nyw-Qe&{cQ4luv*@GSl;8t*`{npsl!^fh2>l2ebU1W&AwXU8g#LZ zo2Gd3IkSi;on)~$1(IHGyE><3=5-aIdj;igI)q4uLMk}Vy;PTqkOJl^XR@7yhTIQZ zwG+DJVKNDPTC#@;Kax9;-|I+7eN5&Bx9~S5YV2)SskeJ}#|l=VIl^kvZs9Q+5VmhG z**3wDT#=@Q3pVNV*9$Y-Wr*3Em{Q7+vvVu#0E_TpC-D!NPXqTpNSl9LM;HmidZ;pRtOt5~OAv#A zf{fZv5%CKP!GktH-w(fZA1Emi!B!7wyJX|R!f*#F@A@XBdO2Xa6&Iyj z5)$^f1J8^F38wg$it%82u&49{w8lr@7-CsZjKpifNgu;W%cW@%cNvBXmVsZR>Jr9==^ zP72tU9?6L^SF5t#=VOt`;|1QKIeIy|QsamPmMPn_4Own`*BxNNoD4NCrCCiB+S5+G zufc(}hpEK5n*YTqqu#*k#(KSET>qQmppB5G*r$o!xjVdAnQh-0?+uh`5){PMlf(5ShQ?dn5Vr5s}*UA5Vq%2wBY@y=Sagui@2M9sNi*Q+lHi;bx zz@l_fjR$|C2=RUX8@;{PRwn)eDJ$~0BxawMUdJe=TpRR9Ac5Y?P#qAZ45a`nl(Z>E zuvHRS}rDa`5-djrcw*tR{-d>E_|-2mcEl>Mr0N&DzzBT(4DX3W8b`|2l%QuxZ0b zD>jEv;m=~Es#KL3?OysgLd4`_VbOW}eN^aB^yIL+Lx1tvATzAya8^mQK`*8s7hsCD zlemDRy|vE=!aZt@LWLaR~fb3u(KqfuU&+iquqa`Gi-h zU9PR#0#JW%KSnnKoO?AbN1;`149)~G!UlQ!F@5-euk`NLk`bzL=M3MU^i?6jvR5Vr zAy`i)YT*>=mP0uNs@DW@p~CYyRNIjt6wUC%dkki!-5+KJ;V~FQ5Sg+-r5|lA|BT~C zhmITdw$iMM_DvQR%xX<8{>4bL6c#!RTa1`a2J0k$OxEY=47Dadz(W^W2-sX{5&~Q( z4VO2HlQL*Eji(gq4pN0>SvUDlwP>eLEAd~e$GO2(RU813pqWcY;9F?acQOt@V1h*t zN{)KMq&!4ZQn>qEZANu#>QrI=U_7X&Zm>ty!6QLT|7YtPe+M6~1K$M&x<%vYTFJIO zj3_ebBxt?n5>pk^Dq!7k9(s0}f?P-<*$NL;BVh zBb)AcG50QNbTp3kAi7<~r;F=;v26u1jQ#;JsGT_Q)vH&NQ&S+nr>A-mgL7i9V*&!^ zVv}Kcb-~Jj<>lqc#l;FTv#`eI=HcIED#hs$>?gw?1!p8>n+6TEzAB{0E7yWzF2a9z zC=X*Hs)0?Z4|IMeJnF~T{L#C_BEX^yzy-U6#rf5g!U!_Q5|sk~eX#9Zt&sVz3~~t~ zpRBC&9TwA}#J&gf1=C=M`zWw=C*Ibx!7}Ayi+#!`6h6^Wo)=%Py|1rgkjzV0I;qTr ziEVmVCW2FPPN^>-A~ei@(s?%=e?S;}A$?iq*5?$o2>Mh%%C89NTJ69F0Pc zo92^XyPQcI42kCgvo=IXG<^R>Zt$o2@m{4?Y$kovhWq>t0z6%H3UDCdOG>-m0n zdp(RW5&L?(T!H@ZBvK?V!?cVu=71LKj>)1q2VZ1MmcVfr_!|+ntQjC)(Q6b&Kx6Pc ziEX;l*~VVfVKqgue{i4-d-n>O5@InM&El$e-j;6LvPl~p;D3J8wpZ{ceL7{fKUsW% z(gf(fwsS}eLBy8cO{RuFB;V;(bm9ennBXG_!X;IV$rsZP)}Fqq*E+4sbm$hV?z*v_ zFIB(wy4)S&0ehxp`7YpHtz?#~Fg1FJlX%1mhM<*lU?3Y*ab(k~x-m4%qe-&CM1L5~ zfv9qXzUo~hCULDLA4iCysGTd|xQK(9+2hg1nde^Gh< zeX@OB#(v^rM~j!l6NICfHKp$FFck(@eIJaq zy1e_)UXQ)3Yt8$O@oletLUp>}2#(Bs_X*J3)~L6FSAUQNF>5k!(5Z&ax@T74g%4vaqddhcH}sqZCW_%GgXVO zE5|J2&#eKi9t#T#uDJbA7fVFX#E-`|= za{`3v_lRzf0Pka?@AGADnx6Z-m_9VPy??x7{rIl-f@6QLwf0C1BONJ|%jJt9`I1Gh zUnK}My7McO-k&)qHw`sNxk^*B+;N*iP{`WuWv1Tt{`wmmSfny%z=+(z#)gR0Tg4Su zOvNQ?Md1UCAFwr*K8(8*TSK9J$3%PBUE-b@vVblLg5_x_X0LA<&vS|7bm^B~I@ z?`F0RTruo`vXm~twFjm+J+j%R|2NpV)maCy@H^wAZZzbrFWS1U6Fz3EPd8~d&FU@B za;>2wnE>IGP-8HA=#K^{x~nfNYO6VB%)0-zeMJHvD) zzfjp+{$=T8TLd(5miXi;d^LG3H&uk{a*(1u+>!dlW7$%zxwwA$8^gwDXbzz#aSWP1 ztsmIvyBHVgnSOJi@WudP-mYc&ce_XZG3uake9yz4#P%UH#Ru+z)H7=A&-OgW_^u-w zB=@2U{M=y^^GYw{152u*2i}=pYYmT|R_HX3Ece`nK&H}qOm!%_cDn*-D6?Ga?H`%N zPFoIy^c)_0)KGE8%Fxk2AIYSyD#XlLN7A~KzsZYb(V|YJ(;_u^m`uC6bU6OL)0i+g zLBi4!m%q5rjc`_FkwxNiMN6W=UA+~C*W$j`q7)P!wwRn^PpxA)Ut{Q3}|yCqc}-og8SSuK+~$cd#bgY#w1H6Uz-?3=X0g> zSV`)?oBblswOQqmgpw^X@-B+5Tha)ba10$``R3=QT`Sr*g}*h*l(LKOO0K$|-Fxz7^=O^{}C=ZFwr1pE>AoS(i~uBeKC zV2U!v&XG5pue1FRT80(mbRBh~+H0M3-*b^IXbK}$#?8fT2_Cy!0$ZU=ZB8}&VR&QQ zq3Iwhwk1{6x-m9@SJ@`j{>9RvDPt)3B43_lkCP`3`u4mu3kk4g2;Nz~2`k2>M_9kC)%LzK3$-yyt2AwP8UC(EHb;7p#V)Z|hp}kKVpinzNgAhAnb{dO%d>W;5!Sq3 zr1eeAhZLJ5le{72paL>=k zTaAEgC$1+XcHff^O}&*^C{4B6)1+g@=S9fobp%*C&&r$U__%h{;4MeqL#?uVZ)j?K z<&QJ%z_#nl2yJWT$Jxu zt6CGfmwBup0Z8$YGJxRIZaEKZAxYlUemOrn(WG`bq>o9P z#h0nEakU7^?Ld0UYzTGOJ&>6;RS^EKpsjdq@{ulHO09XjN&{UL*q*WI@PlChr4hi<(VL=V4ecAa$>M?NZu(%}vd zb?Z)FtTc8;F_cNT!cE3N^DwTn3L;h(!6Q7A`P{jTb&59}c^y~$7lXa+>zCUX-x0xs z5(3XsT-(2=Odp~daIU(PLu;>-7DyPiU^Pa}Wmj&pXwdl|6Qz-TmRY+@(}4Muv>;eE z+ekCIkf>oe*c-=RqEf>uK<*4<9-d~`d>5@A|1Mp>?G)z`g#elXe4oxNm(e!vs}9kJ zM;eZ+%p+9_o=y$IE!{{^yfPex6fvbv`B38N(9Y@pR7ju$Tz2(CsgB)7=V#+LGRs)3 zA(0}_cMB2<3LhT2#CM<9`S0>khm69A?2UNuXtyuSG#D$S-+$ZYhE)>^^Z~v2mr3`x z$wKaR%;!8n&@%EqP2XDjd0ygK8HIlf4evoNccwa_OYr?05w3+s|EuCJ zy|H3g(}nMY0Cpt_IZk4N8%h*G(36!4oGq1_;{BOs@i|NJeVrF`5luVfa4$C%B+~Qr z^r`-6LSnn8=T=XvW1ajS`huvu!e1dJouzlY=JY--bpdy#w{lmE{WobLGU6@EUs4+> z3gzSkL9fOu5Wu5%L22;4iJR3-%`gRzu00BnM3m8v0p+P$uS1>TWxd$>cI-59w(ADy zwHtCedNl69!%@S{JsUV~+n?m~&WEZnTLAs5yanjL7-M6A4_ zwy`CQ`%}aEv>WW)nOq(dfJ$_0FaB&d%w}T#qVh{j?4>$^vD~8E$8Mx2`_&bCftOXD zZG_e5<}wKOpL<|$?UM(M2%QX8EM{HSvFeHx8Vm@X=gnnQIKX3A^c<(Vqab;hK(1#v z!eb~_a2d3=`1QBndvBP25y1D~C0~TPgJIG?ZO$_`=itHoF1(=LCjusZVDBTcDL5BG z-sGn5Epyttg}$RqI`!SvsV}qWfNUH1%gXy~;@R$TROI^fI;%%cmE%n_^X7CaU*ap+ zV}19s%K-8(xlFrGkJeTlP39!l{&*MzXd@jdOgx zgqkV%s3fR0G_Yt*#zX3Lk?>KU{izELh7#V+hBSz0X)Xoz)gXT?K@`kjt8CMv53t5T zN)=o-)au3IXGql)>Zzr0#ve&hmLF!yYv(<`Gr2fjg|u&r{Q!Tc+j<~ zV5*-qXJ>qDBXx@d*trydi`@+NUW1`ad+h+QqU}y7IiFK`BR!DP$-74EVhZzSvq&dm zeGP@+t@;eYd((9ZMq9(6O|Ur`uJq1d(5K=Wc;O zDl`^QaT4?!i*{^t`ZY{OYSPyQ!_&6d7(r@qv5Cypcq2%0MW6n-*zE}y17;ADtU5)l zd*QKp0b zFZ5Mif>wjYP_F-)$VJ90)W+$N>G9qOnL0LhZ{EtWh0djE5?C#V7fe6us$Lq`l*>P% zON4NP88EDC<-KV5VbOJ*3%60YVPi(q;RYIz*hswDbF!i`haXNDqjv*6sRrh1RUAKs zS9~75N%(%Cb_jps+KJ%dX{Sfe*m&iB)MF%b%rokT!;`xAI)W(&;!H)Q$3~KsiIr65 z40nB+s68As03wcdW@pH(oS=_H?#TUxJ5RQ(s%c&l@3UaEHU?j0)t*`amb>6eM)Ddm zRWYbaoc+T*azBtXSaFQRExsoetIP1SW?`N1hqfPxMRAQm&@|w7l)!ycV)c)Cwn4-7 zfv6FUK{bH~Xl97e=l2Bn)uVnohrcNX&`hmGeFO= zW?0}^t=%xCSeubHmY3xztlr11y2)8A_(Qi2Z^JScAOFV6QQJn^r%euG3t291M;Oqc4-;)Z*ml1H)evtcxaW#xfAoxMut@@=pybNxs* z`!QV9gGZV@T)nCUFQ)Tp_WtYTCL2jOXFUy()MZ3H5;)JpJ`7dFFtKPN^)8{NVWzDC z#wx8tV*B!BzGRnOtS^L`@OD5gqB+fTVtWXX5_uPYGu~l|Yys98p4_h%?KSE}5K8I> z)hm&nk+dGFS$)4I-m|ZM&KpjY!#*o62`EpasPm~5?eE-pe{lkT*Z;y+j!DC?Yu`!S z4cRcCjd2TgtE&!TX07aKU(w|G zk&qGe=%keb!ihrtTjtaFyDw^9=sLjjA}g2Ow?p5;2(67UQ?yk3-$%k-S?z_>s`6sW z_|&*(5>@aX8Av_$l8=2-Xnvk-wlukyci{6Y8@au&rgQMC?0vs}HF46ZnaMc0$u-qv+qOH| zwryLJZQHh8lWjNQIiK(E_52I_oW1YsT5G-6jh5AUIuL|*&F&jyXSdBn z0+H*NkYpH*CD`7Q#cHxd;nk3-j|L>H%C+G3(l=r_@n4Ky&@X9`O?g9?5rr(JT1ex= z6X*OxxMn3^x16F2KhBvFa%i?MXT(oAO6ZRe7RVnhx-o-|cz8EWpJGwnDRSBQlwyB6 zT091W*;BR%W8?CYEBsOb%#d7^WA8 z3J5~A;H!aH8>z?^f`i6_sN6IK;>O18te1qL zJhr~I|Ca;B^9%dWTQP8TI~ND?nP{WHxlu8@_yvKhO31nUn*V5dzURwwBlJUw^L61o z@1;}|f@mwA7hAmtfL6ruC%N7tY|0`z)`@U8h!}i_ox-$4p2CTEt2j3<-T$)Qo_xHP z(KEd+-I`9D9Zna3e<=Bd_mli6W!{+N!gK<`Z(MG!Gz9^ppnhTIb;;k=WL`b_a2nYJ zX=nq~q{%tAQlUgeW!h+}vHT#XpkslsM2b$YJ+aQ9r0YMS9uYCdRNVuYM zE(|ny6OrjQ&l7lduGec#OhOZdwL3?d4XHeCq}mSF$4?yKE$8USW$dK5Tb<7JsNM3a z8>GdH3Qq}wIh(w(gFZ!rT&w3M9xLeBCNzR#>Nfzd4lVZeI?SQC17B~yhY>_@STh72O`?^X~7tXycuMo35)3w^LX2>tQH)ze7;(F>pgEV)H!rGq*|JDRmA2WL~c~B zw;fcqd(-L8=5Dt-9F4agb@m5)N6aqnu|Xa1`C?Lfgi(bsq%aae@BT6r2pbBElyZsg zG5v2$K*oNO<%W{uATe{^Kfo4%KfxuiZ+!8_LE#S^AsfYWctGE%I=-!2y_?DQ8DoeW zby~r-Rg+qn7RyKH;wdy19K(UR#lb&eQ6q4B)^7!)LFrFHSKiH;Rokx@$H$?wRL%wc zCeNc;Bn%r=;{ic9jahQZa1trI@QL`4IbYPA#kBQW0mrIC1Fr}b?s3P$y9HaVZeAxc|PizBR3BOYD65~uldtgymfnt6IHt(tuB2=Nb<_m3<5 z=Jm4e$3tiKt2e~`ntol}dxo&2cSEBRON`QZ8CrQ=kr~B8^~XfstmOel*_scf*@2@N6Q6dwaPgfRe}eA34e--|bLE|46};{%c_htBAzn z*xIM(O#!Lha`9&CE>l1OJWG@_n0}M6yQ8@Ep*1BePJ6n12&V6US==qBxO)WJBmIJ7 zDi)pmN#RaGluYkqA5En9thGS$8pAfkjI#<~JZclq`Yv{Mnnb-Hj9Zn$30A&keD1LA zAK8yiw|pW*Ln(*8XrGQ^JG0EBonoD7=VmiFYUBHPLYq739-QqgpNRgUqwxh>2nk@I zPo_Kiy2Em-L)~~HmFU0R+C&cTwiuCj_sgUW=;3q`Oe~rNLZGu*EYYx^6eNHi&sPP# zPpZ+E8N&D)YV@-Ls8{4YuEpA}1A2tdw3)29WbKhcwd3KLGNm-&AqV(iALfDkO1{!@ zsQh?ocW`F=cu?t?x}m9AnWJ@~WiFwz#?{uVeY^>!sNKD9hz||5@1n50bUhC|)Wo)(gL%IE4)PFQvwgogAam!WLzcG1H z{Da0!NN9s6N!3V1R6|Q!_FdyHm=Dvy)Zh@}fjH$3zXAOh3)XVHpJ|`V)!XRgJpW#U z67{!$JCAacFR;lNhiDp5iVWuB=lUid5atFW6=*V9oFj;1Ha>T;TF$En=Fz7~-5>WR z`wR0jNzp$QgTG<81?yC>gdNZ@sZZw1!X~v2bpUqk;qVSleY& zn&)*kW^@qqv(fvPQ}+G+y{XAIO~K$`h-;MXqa}qOAKq?I$LcSQGfs^+pfXoWE5U^N zRXRic0p7F&hjp-y9iEiVwA+x8%!6AYnVRF$;?d^N zB2@X=2$CiK+v9omP-&_h`oM~X-0d@`#jEM7HpQ*C!)7p4kwxo4yD3P!;^~lj1&Nx{ z%Y?rt%dPP-L@6WfUo!4F{5wrO?BldNqmf6$Xsy9a&?%j;8GSjIWtNBf%Cx)%iXqT9 z^0RQm%o}@@?MMj>tR80O`J(7#lijQ@$qrw z_TcOQoQ`H5|2vWP>pu*T5m7%<Bu22YqTR-8MW{me|3LMu*yeaED4q=_q2hR6V(pmUlGQ&X}6#;C!=%`t{?CuOU zv2QamEnZa1G~w=>vrBoo={l-JPvtz||1}k_V#Fg0Z`T|s+o!jEAMn0JUmk9EobD)2 z6aV4O!w5|r{Zi^$Ta$uVNgN7bk^WJk(WpZ3dSP>5=C#$}(y)I0)*FIHJYOt}D-X5` z$L+E#eGX!OCxdDDaSQj}`Op7QMslHuI$y=m%R;aD| zWAF~BE5eA%-=EMqc+en8SC)&3Wt~f4MQ3yTvo{R08VGA2qDwb2r>23d!r022_|p|g zKSqj-@4_aa^0R|n9`zRI9P{PG`>LhENv+w(8`U2%$@jQzd;-vu!Ky-_J6 zNg*FMchQm<_E_Mf0;kHwgbV_GumIhfIbKw=HxDjwLE6#lRiFoNuTo;H*>aOgv)MZC z^3wXQ{VBWs;OaA{J3`**^Bpy@+Up(Heyp_E_>x^-x{e*XB(?R-ag>cU9BoW!CkXYRy;?Q*bsrLuW#)KF?L$CAA|C!uD%<>GSkof8Zv9g=X zZ3a}c6Jv{~u}~ycYHdRZG zZGW`zg*1aI+}00AlgruWO5VO%`Rc)HZoM*4mbbmx%A?uR-6^7@!?_S;w0Z$85c6Qw zBquq9z>|;Fas#Aba&i~Qk;7`$#`Usqcw4Ufu7KimVPQ0dhmrh4uCLSF-*>TjDMVFV z`tOs}*>}G-QeQB!zH}lI&*1gy$PRX;19EsOo;GcGz4)f%bhlk{xGHj%Ire7+L&UVD z1ifx%y3gyz|FeqFKn9Q<{}G?{Iq#NPDkiTBMF}*8^{9anQ<=gzNW;ORoLN5St~X&> zJl>vu`IRu}KY|U2bPw5r_nnU=rP2{WsP-XF@CH~FidMN1yrPsR2l`XQ@_OO!)x39Pf2Nkr`Y zULVA&ozjOjHt$*3)su^ZYHOmIcY6b`tQ|z|IFJ%Dl};{C83!nt%`P^-B?%n-bioL` zdb4vS$_dq|hkk3vb>AIF#lJu<@I!dnEv&3meq8g=T{S$}sxuh;ny_3h(cILezM<+g z3@KJ1_UeKGk?&d^NohL7)v|1+qE1EsAetNAqRpg|p_6G&B-acLh#<&p|ZA*w->y5?B2$vKR9hU;@A1sQ8 z6WJu~$KT^y9bD!s3o*tzU=Rxgb>Zo|&qM52QRx@m&E&_KoJi}Yw>&gGr%IQ1k^^Mh zGI3(8#>$m_+LWl8AG#6~Ev};-Wb8h>fm=bmJ{QWDGn3koSE^#f0-X>aLki^5J-@ZGo7@P;O#tsc zF#eh!-#bXpjv$Prb=7>PhtcYax50pMxCVELg$}~6_0P8#!Na90Z4%Yb$=9L-hbXOsA>(*O28}D=%(!+L1xl&h_q(js z2Jz-Ilr0UzTsrTmGUjO}t*9UVw)zVb$zejrim%FYKNO&hRx}{z5c#2UUHe+jvvZ$6 zh#uK)IxT}&0(A%HxRi$a&cpQbgC4L-=>@UMhJ%S9%)?Y0;13$Qdt>v~)`kWeWBsjx zmZy+|&)6>fPGmi80FvvsZR-tpo|6-3>{-?Et{6wg5bU~JFXrWd)F$d9O!`?T9D?-H zRP$0!ztom|h(A|J{iV%eU+zNgby^|SXmtb=K?$OuCzBwx{I`R7d)#k$P^QUbv zP3wzD>&eg=?W^$BKi`hSo`3+E^k{n^wFb7htf+98d92d#h5$`iZ<|=t`zhvL0#CgD zIPgj~uK)Yv$Ls-L!gVP+2V#AY>4eTjDtK@6XY*MO`1Cocjmo@wSwuajMM) zuR@gGDz%%u3Rk<_`(g;^K*>6%gd{P!A3W^j>}5|!G(#9KUMl4n&rpd z863D1*Nwwv{w?PYFRr(Sfi!++v)}-QcLZY>_%rZ?)$`F%EsX{tfGK^xg`-ohnkC8| zOMDVWKcU}V6v7Oc{77q<^wLuG+Ibp2zF^)c@Nv3_InFptP@Q~47lj#0@EYginA_op zC1610Zb{uAS10OkcGHOT9JLrslyG1lq!T-$iEMHzz%B2MCo;!lZ=WSC4dv$HPTenl67NgE4; zh%xFPBypd3UVG~^mN-RZzg(ok?G5PsqdOD9n)Fut;xZ>pv%bEbcu!j!btH(b{x>0V zmF?(n^%byft&78`%GrDIXVMYa*Zp7Sv)*JfIfAZDY-(v|qrk9=5Rq@?{3Sy7&EJXH zQSNzfxJK6Eb~H!o{HRm}=m^nk2}1m(ry~(OaT;V`H1H)>yA z=YE1;PgIN`gY1dA)lfskMK(wMwr0*|wN7~HG~Bbobz)RASFpL<@%Rzuyf zq75_V?C%hU>2U3)I5Kkg_p#AT=MPF3jqkSVr}o$59FTO|ceN-9noRejmHdW2^@m`R z>R;#Xp2c(U*ic4=JfK;sU7L{*t}ARFjicqxzZ>i`7Bb6AE5kZ#zvW;M!^KB#wPhwQ z9IioV(Ad!9z=1$M;Bx*L2m+q=dOyP%e6MuI6Atm#P4c+x5VmeVfQ|Zj3%0t|P-b#< z=k%>C7c+?*DFLH7!VA2u6(I-ZIVbtU_!7Yg!^kH9I*R+>ImhxS`zVAVgFkbAArj=M zoge-F6EO3-Ua?+M^K1~MaR+oCPdct#T70ljt*mQpz;%?JO3|U>Dt6}8uIzR^QE05Y zD8=9+^WdOI&HL^00hPvBNe$p??5h>ved9_H!|60o ztyI|+Sh81O@ird_{^$ZW?>NgrZmtZNU!UNd(FnC<7F&^)gc{()2tadU*<=2qai}-M2mu>td>KssMRxFeqFVljs}D+9=oIe}ND0-V zhxOc55#OrX-W140%MVBh-xKi)F?ve1wVP@nsGa`S@(W}x!^e^Oct77vhZ162&>aU7 z(3*1>fKR9$9Ivm9PjCPH*OwT`ld*dH>xTWo%|^x&>ww;~ zSQKr?S;j&^4$eNqFs5A9TUE38lB zl9)JNj(=L(v4CLj(SRH@>DvH=Qy+Njw$n)Ae>9ncioKo((0!tK=xaR;Xe<*o@-|we z9>)Sg(SacrZ#1n_{kSvwM)>He_QPXlhYEGr9J+Jr?HGB@T2GUjl^H74v(k&In(C}) zA1;BspKlKQa$DO0j#U@l#hr{3Y4b#vn@&M@)^|taQeb>BsOR-ZEtQvOk(&9PL!V(Y zxi2!$SK_iKu=4a|JVX!y#vj%l_5C&4*O=o9kBF+Fep_B7sWyQp^vMdF51BH+esL>3AyW4oC9){y$C-#OmV>VdQn6YRhY!vY; zbxYMk(-LKl1v*LbD>JGX2nRIDO2g9>j0>=jMFLK0%&SpXC7{uSs%OOG6Xdbw!r>Fsb-C1yW1avce)#a7)jSi>mbp9W0g=)UY?>BgL(l#4@czVJZ__266+{ z&X&p!tQ%3dtK}uPBsoM;!r{!HkdBXGL5?6;5ciN088m>SdNC!KatSson-2jk-v6c6ZR!9 z1I~=r{s=-PO~NQ0U}(#4bZHheFAIyG&C=w~$+JODGBIzA0_I54%I99`0a*+M;rePA z-h8pg6jt6@DAfjD{j2h_QQbe&3K83DI$o{=qGG(^c=5xqLm5zU`|E0bK>4Bp6P!=^jpK|2bK# zgY#2t-A9%b;Bw;wt+2vM61d%ow-*_cg(qtI064uL#hJX)fAPj#MC;5Uj}zI)cBItq zV)ts&XRunuKj0?r|3vV-9W}z?HRtf;x@LhJ0rx3Uw_nv3)2LTymeOd@I5=m}|7rs| zaR`-zdvxU8O;V;bGs^^rF=bnzSa!t}jzXOp#?GC|uD zUF*ScN|<-D$dvaJ9Oz~Xji4w^=)w zExlc;)U+T47g(t}&JM!j*KO)y3^~zPCYj{8snB|yvBYF;p0l@~q)^MGaHrJGIfrT7 zIX749NoDX%R=5H>WHw`LhZ;(mq`ULxix3$od1K|s@r3s~0HY*$TF=V!!kbiaCS*pc z0=g+D@R1?D%_lbi^9@@tHmCViO3MyHI@D@x~T$0g|@2iWudvE}-km&Blh8zB!n z+`*3Aq#Iwvcd79J=Z172k;sp6AFpJ`u=MtTDmV;cElD1#ilQIgC?<%z#I845oC{d+ zUnVct_2j>7dHsiD7op|)m(f16D76TYHnH(iC^2{>`!Zv>x_^?Dx&4D|oi!+TjW*-= zDZ?c>nGCu8Cd#W{?>{L>Q9YvvJY*B}rLMZ~I+N2&h=dl(@>Uh;3@*F65$JK%Q;23c!f zQ$3=EfdFx!V2`oac%gpD_d1gTX%a@uGOti=+=$Vv;H!z?T;(Ru-uRKBX>rUE)Y}lR zFE5DDjw_g3qS>wbrjxaW9vSCd=P67MdKp{|d!BCA&4afC^w#l4-Je-_`5tSXk`!O2 zG+#0;&$p_Ue!X|BzD7yh>#$004k6?HmautJS?zMFpPKeiAKlha?=&yu>N?pBse{DKtKEkrb4m;_5}S7C88t|o(;{>hUCm*(IB8>tTKzAG>3qhjOcnsT8PYvp=W#d% zV$!tr%)qhtQjPSXu)JRgslW$Z3lC$z?67G(+t$3yU#0H!_I(o~FH&3^_-X%Q@^Z?e zh?L>fwezUnJ{G>5Mc%&Ql7)9&ezxEBvwd{(w-%X$BbL)=k+++*MGV(S@W`^ZHH^g%IJIyPep{Rh|Gj$8>qIjPP^jn2IH!Bq05ue;?OZGrWo2rBgMLuNznM@ z2=%3jr5i=t4JrFCXh@FRK6+7+cZ9JI2G1S_4~>Hn^_DT1y%tm&oi)f*h;3_8Zl*Hh zXj(Bl@iI~O)w=sfCPz$13)IQ>QcLn{_ zW-Zn`9iLV=c;50g>%B87Hd`j=*0VjRP>IJVrrq7Y?BOWEWSeSI`K&ysoxCmjjFU|B z(Es9e+zG5|ag{i_*qq^}#Le;0xmU!Nx4c}Tf+M`)NNcyPJ#Phtp{&y_$zn{^vb$A$?so}u>J4QY zut(<|7y2}PbUHEp-9i1`9j$bkY0*fyWex_-mfDeDZKGb`zd!(>hR)dp`Y$4TRh22USqhlmx-yaFfl@9f%*Yz4& z0H0V=+?Pqi$zZEGgG~%F<%uQ56vYnBJ?qUi3hCEG0wqKpMac{ri!Az>-;?wB`40{z z0hM*)w29P3lSyuEJqFvGsIg{u7^9H?XyUXVeg$XE8=uHorC1d+IjteBddzyNbNN(N zwl%^KrK57l&Q51JonX;9;Ct8?aVas_7wfCQE+$xfpux)g6=82NzWExsI+jTNTiDFC zc*R$jo8wgB6H~e?O6s~xAtp%rSc?5C+M`h7M5g@}n4K;Q0{`abL>DjLqxf=7fFQVL z!4O?=#D{w%K28A9uL5SAP~I&T=chs*NLhSwn9YAdX4pc+F#CbFInp#@#c}pO_wAJ6gHhD0?&?y=?&pFN0}`IIQpcQ_9+GJ z2WOH>?t=`_$AnB;*?M^m;UA3PPvcp{EWSL;baq5J<`oVf>X>YbtnkKLU&sOF+*ykx z{TH;<$jz3c1;d_ZJI3qyVob=(^;*2AU)CM2M9H5{&_g0U2!B_eT}_d}TnDVUe-Gop z=&zU~gZO?dqDTUqYV}o(`YMA)qS@RKQ>+jC^8Ofk2gL9wyuYF!oUmVR0&H_7<@lWZ zOIaGlbgx+1-S!;pEfcC%xSyk#3{O7lj@pV3LYD|yZOn_gx=n4&j@Fwv8rJjvy&_+; zppN-%x%WNv{JGRFNvS-=etQW2bS;ZuTgepbB$vq~3`?>J#j;QXdilY_eKJ5tZ`rE5 zJVZfQ5rdr}DlwG`WA&e+@=1qrcz#s>mB5ATEnBF}hBL=anba8>b@OV~B*U1o7G&K0 z(grG=p2sRq9m1#U0(~%Y2Y6o&tmYA1@$p~rH+43jTd$Pa^*68fqo^;FFOyN+o_m_b zw)I2CA*qu`8Bw)phqrth(dWF?8>jWx%%&BP{ToR2^9=)LW^12LU=A42O?~|5k|jR> z4$`A@PF?(RDv)0dBYkz_6eIp9@KdwL$kYT7ql3B0Q&h<2w?*BoLUqI6NCmCV3V9hf zA^IrtER{8f{L!|6oEqZaTEj11T8!sm%F(TUnS%DNassd+A)$h8Z`~>tLaQ}Z{1tty zOzh=&%ZxtSejWLR%Erz%@tsRNlqSy<@7GG$9*OYIsA1so98_+^AW3{m+||0C3Qe^=NgHp z2j=Rjk&x9{QDvPvZ!;{U<-8Y!&tiA6@}jz&M$S+-2<~l z`_!xImTMcdxH?-@04clygxw}(-sUFx?#JHn%@oI-p=zVwX=|IriYisf(qnB+Ow1J# z0ey7m(ND?w0WE-T?8_@+ujtmJSu>~uL`oQa>P%lznB8Rd7 znABvauB$16hG$q*tqccBtN@i14S&{7XDM5YJGq%9xLw&ByX^sZe*W;LF#rU)-fJpX z*m7l{sNcxoi&Zar@K^KuI`}v(GS0evHzFq@*-;qupxyKH;=sCURoEt*CM!e7uxga? z$Fm1kGxJ5{j5NYf4yqKA^`=xw08iD=2sB}%2DRtgR%}v~U6TxUI6n~pwg9>PTLC_Q z;`)d}v>I`W{w^Q7)2AS`nHuRJQI%QJDX$dgAJ2!&Q%IY1cwQH9Z3@Af;DP)#-kd-9 zq-a67s!=wm&BhxNCz*nh4GB-O?0tsTLI4 zM?l9=VBLi2!nz<_#mu|EG%ju1PoHw zF~pF*i;Bm5^rdB+LL=$Nmg~_j+^dZ-L-ps2Br0gA-4+FQPplC z2Bv?C7S-H^sO??;%X)&zs4e9kI_hFj$^pF6f9rEn{}NdWB%~M+Rap$hI<)6!TK}mD zMq_3Wavognp6R}rTda<_Drb(SB4Qqspk%&%Dh1d*$#6UaFk!In!&)zpW|^DK$M~im z(4p7r&Cctu&}M*YJR-cwgr4xvx6EIzX6W7Tt+8WORZN4~cVX2*W_4x6)6*GrxXmZ3 zd_a2~8I#%KHu}shI>q8(D?LhF@yYnr4#6U)hM>E^EwA@}M4jM~ob-P)_;uoFlq3fs za%*qABzdE)zWe)N*o6zK;cmmq!ipzbmFMX6sK+ZhLQ$ztx$X0iK>0*vuCbgFtg%pk ztwyB(4P{vrsT_N?QKyisZ$2V}TOd11NLnJxiy*o@UnUfeoJJ&!6oJFfWM3duMZeM) zNmKfO1oeZHhQy0~@S?Tqb`K4``O94vJDH9h*AIb}bt_WTa-d*0K=2U>bOU?$B!+7w zI8}4bzYol3bKK8l+L`{M;bmn+k0`j3!Vs%DVi3Kbm-f*tOcst@r7K=3pno!(*}}NZ zP%s6R09Z!9DK2Ve$sym=d7{Q9Z^W-E{a1;IQ3BL8#ZPP zZ#L+<#)NSrQw$+8&m9Gua&@qj0>3=%>B#^&*7!W1Jzu`5|1xZ2Y>m6tdt*e=U3!f4@_CB+x@1s`^GefiMW-qUbL z5c2YrV*AJfK_w2nTvn_jhtvO&C*K3WJZJ>}=w1P=pO^qpfPwIUYfLJU(hL=Tr}sk0 z`g)FV=@-0m^<%8pTOvc+L!=&ZvuoKR)*{c0}RNiYn2u1J|YPdiY2; z-@c{>-hA%Y;qc}Smmokb$a13yE}9vi~Hhv_<-smi&@!bmYazFcIdQu zG4}4FLtDwTisb7cz;~c*2ECXshh|B+_je)yJMv$RhkD!he!O0WbKH^gAkzlZRwTxN zNEMPyq;DZfeR0r&;Teq^&jI=)h%i0W9#=lhkf)hM!y*n1wX=Bi60;gS8hB6Dvd}oK zlglPig`yS|z9*%K%OE6ZAosn^(kQm70(B}u{vMwH?>@8X<;7KuiU6FAT*7nTSpMMT z%Q>=knMK+5lW)wASxD8^>r9&NiFmaa5_s-GG?i&glxNE}v$;!JZ>eGj1`lUm4@N7Q zW2zRo-@da<{$b*7@-s6(Q^rpv!Ey`?wcgyKz-=yTWLS2%8)d}^aXgW`{fm^8|4Gz( zEJ3yF)KFWO`qn>V{fk<3A_$d8@H($!CtpMkGLB8-p463}kNgA5NT?wD>p&j9WAmXR zh+Xu)J)v4q5TdzMpJ@Hf;+Q8}v8lvGBI3CNCgz_g4!9RAn&g5TqAf+rBg z+_NbdTS<`spGN%r_Y94qQ#&S?m9XU{f<$K8JO^m){wI}UShCLEbG)d@@^`azCgrCO z+{b3VA1#8a5c3}EkMyUlf+7A!A?RXce(!AtLHZ`^up)$u`!R(!7Sq0$FeNJNWUg%R zG%DQ}UTyAdDfFb#4)BKc$wV60a+vH~Z?zB%Z~$Ul4}Y-_Dcj4KmpJ%h0g|F#5?mkT zCOqc{CF0ZC_z9M#V)woREN!AGz2CF9cDO5E322fx;F@owCIX6o;Qf2T8^5?M@DXA; z zNdj8d;TfoeSr$OvaH_Rqx-8z;;J8&@SJh~bLB%>N#kpc<{;UM7P=a0Tc#-NYo=u>} zbgfWXJZmH_hATq>?jaX3;zMZhD#ieRKom%Wi*5ls`8DKCJY_gbko406enzBn4YEc6 z<>it*8sfrrL4-G%O**B;a5(%#Kbp_@KSX`CtTM*`27<8sDxyD`5oK9F^;axKV>z}@ z#7>X|a<3nsJ;)+)zfm2HNQND9WLYx8kmA(lCZ7-+pie2-S@Y>ij+b*d64#eolDRMZ z3%v~3P_7)ucYk7vm}7&uk7Qv8%)txD&YjqY#SkQxXBGmE;1x6qk5Wg7g#Ipw7-Dfd z%}60lscR5q8Bs7xPs$z>6FC{>HiAK;Y`j?WVsQMWB*%|=@!w@0Qizv$e(6LETVL>Y zVF$x*`ka6~mTrBpQ!_Y+eS^w9oIl8i-D_s}oAmfy^;tm2DaaX`=f9<54Z8U{jwAWZ zC8Ui{l4OG%xXGs{e__&RhCIv5e8jPPtKDIJu;dk|?S)8HxC6AtwyJ&D?4$PRdGGsR z6!7}MmD0m~(yETrNoaUVsp|6mW=x|6Q_}YZqy_YhEq4yfE#L~Zg!V-oOlW$yLx3%! z-eDQ@I*dQw4ba$|0FfN%rT^oK0ecO>Piq*zL>9gmkqL{#nOh+89_~aS8yVYzbW&nk zFr7Rq@)P6Te?;k_-y`(9X&XL=7U!S4x0NiMx=|N@BF7ax7C6bCB$37jBwnY66HKXv zTg!QKR;%uHuP0cnz7V`;E$73>!JPT*&=pYvH#t=6tC~LB5 zm8ri$&-$DMXWrern1?`)plt z`$UOl*5`0RhZeRH<2dQl;U|@m z9Rcw}p>nMH@Vg;BbsDWcrJ5(&gaTvbWrLM*tCw+U7nMB5|CMT~AVG$LL43TUHtKK= z*sw3T28=~@c6PdfB4tj9iM;r zFXieQ8tMQ8QGHetxR33Fd}$6^63|FP0pAM!exu7{ALKma6kagmDIA zp;D1RHB7oYZv<@6t2gk(sM0^^xa=iO_YaE#?-qT+0D6)Zp&yR*^;v<~TM7_lJ26pEIbiq^T zj0=E!lD&%i{`(9_zDvH z*W4l%QHO=%z-=2QIo?26C{dx^Z>xRxk(9CJ1Z1h_ z<)V}zBuOC3XJs3DD!n(~4E*pagJru0k-qk<;`^6e#0d5Yj$*%90Wp+0b_H0Bu=^6N zx1uINk~r-BT}+y|!^&4vE@@1suU+m|6lIDiUvB#ut7o-u;3F4NB2wm38O;L14s+B2 z=UWSNcAsF)cJ4o&zF}D|{J#8vD{YnoK+q7_c$!Ln_W@KnKZCOq(4{d`>t6#J;S90k zyXo=@4zv-g%nJs(>Y$ptkIXY?iD88qV(J+u9hBcOpIhSmeuZ8p?(poH z4t^1G?sK%`Y#-)`0#Ix$kC|-Fzuz_(Y2=$|Z~%MQ&JC8q(FZ!?QE;CilVpguxe)U% z=BRF@ES)(iGos0ygo&p#_^@!KB&mxUH^ae*kt3KJs1Eyc}=V{!4%D5n(qGhFRB6%t7H#fr%Z6P=fR{n*C#O8blAM zIx1H&QRKbgVXE*(n9P*3Be;25W{5;@b9LXJBa>dhE zTpn+%UN~0 zL8h(!U@hLHMW(ueSl9bK!yvr((65#eD@3M893Hwa0Qwdp0YcojqsN0Ba$bj0=D7!J zR{}vVwD*V0hSh2^NV1Ns{2xZ=LpA%^2D@nSRN60-$BFJjkD`mZrS5fJiOx{}}RS+D?DQ@2`rxZ$NS@t`Qtlk(0QO$8dAK8MeXWqnU<4An0)hK6AlCXWk2|bcZ&y{sjheI?9V}tODpczFwrx zun*yT67w{4grXjqD)E;U9T!ci@gtdh*yib=!OZpQZtQ#&tavV$EHXC|N*$pKVasPm z3mFcyjng?6E-&qq+>h-NCMbmLo&_|$E`I*VHc{ysv;H0Djk9(zXv>~?W`X%ON((h& z0|=DibboG~+Y6#;UibAB+re)Z3{| znf(b2pR~lrKtUh}8%J+%wwo=`$rh+{X*+&N0@Y~+$2~Q(*jfW?y~d$%A+@ty;X9UN z9D}qj5J5Ra$*SjPWp@42`0T}%#m*(%tsH6d(rIdLsELEL{ zgO~{8oE+kVvnqs8Vl3fX?2#w`5bic8_nty}R!e+GgYZ^T`@6rS*uMIgBH1yZcxU@7 zKW}2W%qXFKAc*+QUK}};Zw)>cqA1EVY)^1FtlOHSs9^`nEv=&9t9_5(J+j%)Wo->h zEHzAsb@}GIdKfgI`>|C1)q{wiv1w}Q3a|zpP7FAL7Ho0zv&pPY7%_7zx`WTei`8YQ z28|NB|CfWizw+=aTm0yk6EqO|zgIt@K4}FN)-rGYg`%?%cOq3Gp*U~Q4K_g;KvVKp z`XHP(<3QB&hVXz&bzC-wCRv5(GUjbxvpUBPKmOEu9PhK@&G{ZlY-woK@hiB=z2qAj z5NeYIfCMQ7hv#w=J$~h~JN$l|$^!*tmtmWW>Fmc!%Jf}nsaMF~%l<18i%L2gE#k}< z$>&KP3J4aklG%_kio}R}U4}5`UJ$eDH;(G>D}keTc%FgdSr0Y{_b~pU^r>RWLWg@; z`3=e8kvI?5jD#uVOh2nSFRJ)wh9S3gNTOy|vv_Fw=6ud6?e%5m-YX8|T$=|z; z$UuEX(|40(egKfnh4S}bW|_mks47wijx845Kv!q&mrJ^1oDr-pZp*H`05tAcp~!O; zwLID$tXW33m~E(IRDUJ^G?=-oj7FI~0+ky+png_h#~~Hm0DcsK=m5BIK2%?Cp1uUexO8HAf*avPcgenjc~o(t5LP@k2yJ z#F6;pdm67#msAF8Wjg-x1gq5=sb-U9EeaUxE@hH^m%^{|+{!&opfD1EIDi7dLx1(b zdL2M3m_9r>LGzA8`pIy8)?bL$7;X%AdSObP`qlN?#^Z6YCy;R9Y=0U@_Z{-3o-M0m zuutg8BE&|&vcA=w(Z}1|UckE@a`mBrPG``<;104qF5~{= zRJQ(YJ&l3W<*KCq7#@)+?x(2Ra}!=oFmEcqfmdKm ziv~dyaDXDp)?pT~@5iJVM{s>PdidvqMnf3e0*gqBm${zURchMd z&fpO(fZxH#l%=j7rrgfsIujAuCvs^$fn|Jkf}R2Wv5t<4Qs)hL4Y^%FO>u4@cj1LL z$_x^K(AK!z1YZsc0t2)53-Y3);QP=hmUVqP!O-j~2OoU5^`<+x!sJuC>t@mhY|*`Z zb^H8$%UQFF8Gp%nD|p*M^)W3aSMJp=_gW2&@MnW?8XHv#_l{m9L z$i4mUJxN@=mM<@ig&2LE#AZ8CQ$D#lkMl$O3{Yi_9U$}nnEL9dsH3gznPG&XXXs{V zq`SLA2|>C;3F!vu?(Pl=NdYM->6DTZ6zNhLr2T&0``)#_KUtiCGw1BHdp{3K;BA|o zPqWZGeiZpp=&IQx@+g$AZ(V}Ti;)Shw#^1*cMsCB#E+-F`{SPECMJLq%_uu3ssoSX zh_ik-iS(Mu1wE8O`MrjD^OC{x#EYi{$~B%-p}>~{x>Nv$J^)Ks$Fb+P!1Bdcg<8w? zwDPh`2HYjBh&OOpAEeFu)WT=J+Ju2*q3djnb$eEo^P{<0Zs)%{UfJAWlc4{Mj z1i4G@bPrg|J(fsD?=}_EIj}V>&F@o)SX1cH2Upmfd60(Vbr=iAUo{~0<|cB850NaI z{V~9!YeFJT(nl{A?ixmd2ZF`=rm&13>{&xE3j}|1pqzwB!VQw-Dg5#6jp!)Y!t_S% zGbEHuqX#^OG`&VXbbzuSx(|~VE#>1oV|10;r8-#Ug?Jy5rU>c$UfB-e%jEZBt^vTZ zTkl!xlIjD0%lKT+L|Wfoke+oknJ~TXd8Al&tA96R!Bwm3E{C*&h9HBo4$<&nf^Iv{ znovdb`;)%+C)TB)9km-4xNS69N2f?mAjF*iZl86g7I3z%x>o-iR#gBU^4ht(f8D|E z>w}?HuLCWl7qJ*K0@Rm}KHr5QHY1kWmF7}n>V6w;rC~YA6ihEJr?|h89|I%WKl&GC z8>p%C1RtisyJ{Mq2ekNssDa)R?^U0bAA0#ngUsh;v*mY1Ub2TF?T}8+3Og+FQ%8ez zv%4p#`qC%ARy{ouMpmt!UC*S=1jipxC%^|<1~r$ZWs)=W>G&I-ggd*-6+MA4E9ifc zF54F=37~n1q&9g9z=i%zH@#n+s*&vFI>BBvW<{fRtt2H`QWUZfi-?ngL*by%yxn_j;P{;SCb`KcfX2B)x%=_5e!RBz zhuwnwz~8yTM{Nn<(I`^x)k%9-$UCfA=AKM6L6nF!Ur?Eqe}M z4?P*@QGvB}^ZokjBa7hX)KAL&ULL`6Q}_pS(=LU31UMc>(N`pv_?~vAQ~J8nqZh+m zYU8KI5O*T{5#cF!2rW>5$y$tW|CN~T-N9m%C4)+;*&;oQy3ZaIY!$jKeW5n348KJO zfk{wxByXcuy^g>0*k8TjW$ry`@SSJTzd4a@A#pic6;>cX(TJqQ3oeI2WkEBa+d~I& zpl}?b><=>t(uH+%J&fKn<2g`;iIu+U&z?|c{ zbNBdCd9~r9o$39llzBwjTV3{t;HLeFvast_(VnKEVvVB38&JhH=7D1MSxJ+!48w}l zCUV3TBRtTexfw#;Sa#t)S2fF?Yll_|^F=mtMeLBz@ZL7YrpsEaEgVN1z+GBsZ?ryV zB>y5GnSc?8<2asC%VWCswVaQ1_B)_Ho&+AjJ-5fwT^EhLUPhNmZgLmGNCe-*%joe! zNInlHszFNEXPFmVD0!cZ9(-NyLtNs{!m6n@cs6vSAq#X^qXuWbxZ8vT*iblLacD4w zg2W}+`Z`*!$lU_>BgG;zQg)2zgMXaAI}Somjx3SN#m-81^ABIiz@_vk1()D`D$gy3 zNk;mW77qxshU0+XV5V{V?(l7o+xA?ci0ML&z5`jI?}2Rx{M6?AOAFtRI7B2E?{y&1 z5c(jlnbJr(>wEzZy{lEXsv3hXgGcAZ@2*S0$f($7%9YmfE|o1Di3^SF;+?x!I4*6n zXrw(?cVa}uU^v^BXu@@9s3uk!hBa8W%1oV^F+UTV!JN7DN_->AIan-YU>&#rGtw=2 zo|7fePD~4xwvz?)(J4ELPk0g7e#E-hxh>ZVJMF9 zz{a1Jl8OP6EEpC^FcOAj{OP#bHbWFxW7w+ZY1php<#+G0a);aB=C`+&UGLXrbl=&RDpC9@>F;g*-xSq=d%E^5%HyQ(&1Zf5@0;U~0C<5kH1I_McO;KF{j`3H1TUw@ zqlNS@g2E(T)dB^CFI!2`K0?}}u9qGemO9I9Ei zeaAUR*yFc6GJCN<=fUh|}2V3f?1wtRc zR!A^J?nO*z^?Qvytr#gR_~UqU7kH0$votKp!Q0&U!)N#VS@zUh1pu4V+wfRCJd>37R?6!p#tPR9>92Zat_o|ZFOI224lRlovJyawe3-0mw} zYoK$#iF|kMchp{CruH+s*U zLzR8n7^12KH@W~qdZ{+4N$07k0$*oI?{b2fg6uyeK`zYFQZCrHQN5bpW(mdnHo<5x z8l@je67l!Cu&N)iJDobv_Y_D>t3HzmYp-57m$P?s4+G7lXUU3~?4to?jBX9p{G|lS zCG6vDyyRxrK&KrDNvygguco#%>?fMnvKgFDTPEZhlkwq(G%l zSlYarnC=!2caiC~;byHvqUfL>s(5!Lia;ofJ{Lt5xot>i(1iCkydZJ?9YpAgIE&bu zo!E4AQR4j#|4=a@heQXot`t+C#;j=5w>qDVZg6ovH6>yX9SlcfS8$Avjnbuj+FYQb zr5U&v#&!H2kg^y3BldBH?k@}a7HB;V zX71kHMx)EtI{+cXEVxn6X5$?ZpUR|{%0#cGzqX=8CDPwfUZ~{lVnYD2KAuB4As?in zvHe}`vd`+l>uTSZmNlqXH2P>}+J7QHPoE?uOE4rn7P&%;SF6^gSZM8{E#GU3qj zqJacLAH>b&tpfFx1`SNqh9IpajO_i+YzMB461@eiF&1#tSDP>&KJ#ApclOyJ6q~0} zpgadLC4-b5Q%#=FBvvU96H)%&&jv*y5V}BN>!6Wovz(>evkD8V~h$pb;rR)FV49lhj;ql$^M zSyk`vETfVRJK0WB7Lf?&8%l#6q^^q6k-Xe?<#gPKLS2;YKFi&(tB7;R4)OMkC5`{~ zpa;K6MEGBjf}e$AcAbN&`g=xIMx+knE~-pO9z8bDX3-)`Czt2OnT@RYdyORZ?i*?` zPo}@$Tiq!&qaka8=J{#KOsI3248`NlL3s!)W<^~gs7*dLt7^8X`L=FP*)~OQ0L{3! zr~)XKw8KMON=K89vR%U+pA>r}ctX3K|mvauhy&7Su{vx1; zDms~AQ%%AU_+eBy>m1EB^0mUF6zsBnI8ohc{dqwhz^k?G@270%kNlJz?&FhOm7bsr zJQxB}FkUb1uA^Cp$DDF5_)Q;dA-SAHW`3}#{nwjZhc!rJq@++Q7r;85bT5oon;3-a zBl*qR$Cki84c{PwO#GR1qE8lx57jmbH1^71yU`rdsV@W-LThl=C##crD8P&=eq~@V z`;?kcEl17DKjDc_fmMz)-G_#KuL-4<5zOOl5SZye7|wu?&|uUQ*pHGDgiS-1unjI& zbfL2cWp^xAUue+~A}X)HwSc zD@EnW1=zi8i>~B~^nm0Y5v!!ue8g5gcV6$i)adhg*>gtSM{s|s#>b6fkr*w_1 z{tnTcT_othz(mpG+vu0weY#%Zpnc0RAa)1U07%+uOsUdISX1sLs^Ua=ZC`1u!%*aU z4-5-fS3w`1TFy3uGPoD3co8EANOSoWC$G)vK6MMt&_oB3Mct+PE4b%1M(jP(wXl6NEtIRvpU_V>lRjaDEF;bQq;*7oy?J59 zl8*!(X5m+<-AC@Bl`hcW*Yj*?Ms3INEYeD0nz2)L9`Hhb;@eQjIm$3Q7Fr zQkHrsTO3lOx@>83L7)tZE$By?#-*og#sMbOnoxp1Rnv2K=D9}+qgPG6XWMFb?-I|Qa{;ArQgtl6Z1yY4G(y#{=ZJ>K4zEh`$%3Q6ffIfiv)#%RN7=~x) zQaobhi^2g}XEKUV8M&ZIg{XFg>}V+*I7w@E(8rLty$CN$(u*i1+S>g{q`HS#i%wOZ zDL9grgJ@Lv7o$mX8@1_s8D^LLF(pVAM?qXXYzreeK;R%AmW7M^ha5`oul5v?RH4vO zM&Lg@bCII!lhk7=kG6%7{n(pT#|^RV*5+3W_BxLM5eILvD>CCEln`LvA#0oRkr+@p zOp{}T`eIb1es+K>tZnwKElhgN(Rxc&t~DzBxbRqZeRo}oZ*S0m8y>8h!z|k6%p<|+ z^HN)t^hc0sqMIa#BZXWVwdcoICyTi z{}gk1q9g84sS$lNud=>MiduGm8-L?C%L=cRb=40x!LgU+-d!k!Cu#P@-*)6q~*IS%>Q| zK|sISgiB4!_FfYZw&X7X2y#Ylll=d11IGXWFpqbOYInKfel2+(3;K=2RDMeyQHI*h zV`38HXpmn)XUVuOPo*ZfX9|cCg;*ZMsRX$0UTNlz(;$$M}$cFOqiG>#B{mKXv?5?sU{lpxCH z=eGMLT`=!l;buBgg8pB2=-1K*Sw{5&HmwRZey8R~VFNL|;0-#Eg+$QI$VBiHbhhx4 zY`PWw5VhVLyd_eTi*!yXhBOGgzqgmQ>ak0`6~kJW#-K_xet+{1RTC#uKGxGdwoMO$duDflD2-?^IUJrV1fGVz3D^!Ve&1D#rfm+@0nCro-!Gky2jBwYq19R>LvEK;XOVFv}ZdW}=Gwqdi$87`G; z{Toak?##n3rHuIj8|&(^|B91b&@nAJ8R4VC?kBkB8hd}#`j!Q5>?>ae4~Jy?Z(|B zRqMg!`jqciKfc4vN{Kjp$74*Ir0!QkNM3nfDcbSTS|7Rp?xGnc+4GBwvt7s(PQ2AR z8^>oI6MEE0h}p@576(Wv-lrAUNjZ^-x4r1JVGt4b4`B?#>2LV5mRo!d3IwRxMpM-# zstkMBQV0PKxp8;%5riVO^&Pll?bh-ua>?m|&O{f^Ec#hWHm0XjpsbWn&&xGA2*tK9$fc224_kxV>pKSUB{-ZvryMDkV ze+(zYC6~g*#T^G=L#%9UDnIOWu5d%-ktAJwM+?FV3L6RBrNj3$K|Dd3r0`%zW6tf0 zmFBZONvnshN4o_@Eq1c4Ku&AA#2fkSC@Cfw^f}1*b8+!#$nhg!^%Y>=n+dJ!s1AXp z$WC2p!S>_Rr%cjUID&LYezq!3=5}0DKd%AVAq`GYLPB-N?mHrtk>2(~8 zPqqliw2$%UeA*@Ido^|*APj&BZ<@GYj7^_< zec|=*m&+BaUrRn$2heJeK$IF6r!4x~#-pU_DSOCv;(t3+&C2bA8DB+HabbSd=Mf-o zj3b(iUfny+#ufL|hTRc9EJVwg`lQJ5obzqCP zVMz9e;Oo7h4+^$kDjIyw`7tuDjH#*SWP?_E z%Ob6xTBv-@vZ)_UXd)OaomOFFxeHea8~f*|@&Ha6&8`WuG4%e!ITn2rGvj|VIB5_t z4mguGw~8J?f(6Oq9rkex{ajFm2L?QU0~)})#-Nm-g9Iak28DfAITL071`{A-l%Y{l z`|zJ|=l#aczZjne(J&SE8l`(9mfWHQx5kR~qItuuMY-LvmgpcRR}JrpS!dUmh7^QO z1W6&yAjbaqVgn>xCNdF~FOjH;sG;SpRdti$tITsRC4$cT2EX-E>54Ac%$ z^rV3Z*W_K06kLb8xrBymp5Tmbo>?VtIYQQ1*FCqTIr)D$+^1u##J1 zGN*u725@832W^k+cH5z|LfFx7@>S>SCw8swhDJh`z`33Y*B@o0rT}kdj|o`!AeZTq zi3)bV?G_ExPg7fQU8$C5<81S?%T^`t>D*Hn2L2!n1@PXu&Z1xJPyh={pVlu-wvScC zEMf<9U}!!glu}TD{(Ibbz$y-KsTUwhvx-IJkoe*`wFter%oJ|VP${(1pWo#KoqOcx zUjGbw5flt~)Iuk0MIgZ9yN7}z)P#4N$p=t3y&A7L%9jwq=Wt3_#SBpBW+1Kzr3-udeQl!}GfU`ub-#4G?gy6$-Caf0{<%L1hb`~4_4fAAz{*D+8r6$LkXZTgjWnZ03(q+w z0HLGXn`z;_hNOEpg#s@(?xsqq6*$V-{Q@fc}Q! zsS^fY3frf8sZ_e*U!(Z{wZCizyM5yidjNMEtG(HSNpwu5 za_gh$^LOcJwWNI)g{-wJ%Y~t$@ql8<8@Nr)0LOG3YwnVP z#&3pJ%&t$DYw}+&RG>VHK!SibQY;9{D%)$FkJaa6Jvz?(!9J0)M#*|`6kVIjgpH=3 zOjhnz+U07w zEU`qK8NyAk4=Gq`v4J)QoZym4-NRkOK*`OzaUzo|bnuROVbG+0v-dvD&A5K~mPVco zqIbSpcigM{oU;9TgL*6{J#h>?C8T5$_=S8su=BtjplJ=a+g?_t75XVNf>YT;nsmjL zq8htc5it1M_GBp#`X;=EQS0k`8*_y%Y1hGB?Cs&>E|C@z@*t1A_6KP`T`%xGc-sCC z54rm98K>*j;Z$IS|otNs1)1guWkN(kkETmWo_yY3VC5lG!0l2NFsIGX^C51E>zD z_ICg2Iv%wJcwFm!E~~8o`11@D96d&$_oT_lb1>a?AX#xt!tb~%mT(%~N|T3g$~P#> znM0?*EvgX_+<;JWQyJcwG~6nVq)MBwUL5IcciZYkxyro3BswT~_Ic%b-xn*DLNZAB z(@_ABJH5KDLnT3chXml25Ja(w{_$C6ikjbDJp;WbbV4=A+zA8 z5XfgkkiW|?&?dtsNwh~!7DYi(z;4v6x3EXP3J?=J{MnFfil?P0+;0N-eu#q|)t;OtMvuEA4apXV#=Z{-_EpI(2WA9xqji_b!Up#@-mq zwP{8MPyHPj-Wn-Q$oT$esr1-?ASve+QZYI5aBhTiXoegTZYJVQPEOvBqherw;nX)) zwjka`<>M<#mEF%d5xk9n9zE+S)gN-3g{PuI7*riZm-;|oodi0lidP@?4#xtT zQ#f)3#2I3Vk4^k7-OkW@04VPI&O_tl6v3XG$(NYO9fUw5QJq75S&y7wpcC2jEwtTd(&OxfN%VK*yp@Ato!PMat4Mb*o(aC2KQ zi8#`1=gKeh^WI56$^`B!fAHph&-iag#`XV#{un~mEr88Eon3?)P9#2o*?IiKZ@aQI zfs42M?s9YXohr~pBE@*zwu#ezSobLoe(O&a4fMfRB#c?J%zemA_>kEUI@CtZsiRz5 z_0S9PNsY`Dy#UK%Oa!A*(gWmoqTBU<5BlwH3>{c{jy#-_N)se>%GC=wHg6d><`Qp% z70Fy6b4jMYv%Nts%?d?aP&ni5oVw`q$McQYZ6GC*`kKPE!N}|T<=KPNWA59>K1}P= z6b1yIH+zh*wzn6F!jPDh2<G|5XWtSgF$p?moJ(BL_&lB$Fg3YzMB)O zk0$Q8MgIWLvvE%8*<+AJk%jTV<)BCogRA;SNpg8%XF8syNyRZ4}>$%swyVC@2flVF7UybCt8E%K%p)d#Nb0LR=57!Ts%uA zK$(Lm-AzRHOBPxG-dhH`rG3B;J_CX*y>2n;${~*xE*xzlMm6YdJSc*GlU4ODrGTfm zWP#PsbW7FJGzOcF0Whj;DA_bg%CEDs1@;-X$dAg2EjP0oRVrK#Zo2K4whRZ#XU%=3 z)|6k(ePyD$K#^@B#lJp_gO$Yt{^++T9tqkcP;gBgh5ox#P)IN;HzwKV{inE5=ISTh zT!;}0Fb8Cm!j(}8xSSC?4t<^duXe;kFR9pU%#rg(VkVXbi#=k1T3u`Y|>)Pas zkJYHXozJ@K5iCDr9Z%(kjmpe_OLtjas+6&dtwikbtA7|pQD#JUD3G`I?-LHPp1k3> z-7{I&iZz7Jj2)1XcPPo7<|)zX^AKu|>k+1?vq-i7d_#;-c`3 zF8%z^8UW^K1QWO-pHcL&8D2;h?!uw7&Xmko`5<%RlwJ`H?|*T#7IevkFFXSG#lJ$F zwG=5OB8o1^JhM!8c8qc#_zN~cQpty?rex$+LQa=YfCK369aD;ya)K>63)sJQLh`tq zBS>aDG=V(40(VL`ACW+Rm7Xd5CvDRI7Mcn9y};4Ixhj7miy!=m>RXI7M*%fHHWay{ zEm+n^?qL!u+uvX!9|qzi*6Pd<3SzVvAjXqYfo)xPNitxQKIee;g<`h-M*;#F``M!S2Po|7T+B9nN`TAYk%0@DjJTJ6fl--$Hx-& zp6&SWe+O2S7U!=Dc_C^qHu zOXxf+5b*2I3l-awxYY9>iooc_;31=yfL!!5F;k9lo{%p~Ctr9p%hM@>!P~lf1H8gN zv9ficLeRX$ywPloSRIAg>39kLi)^$A0CD~rM)h}srR0fDR4O~V1NLd+`5kg7>WC7xWUh(YH zB$eUAwkJiS9rtO*v!bNB5wLeuyX5jJicnhMbgh*4SRq;0tCP+Srs3vWfOe*r=_TTF z=l)HrNef2X_!=L?TR%_&RMmvet3>{#g^IMGLgK|*WqoI8XBZ*sx)Q*5H|iFf(%z)S zwk=7P6CE|Ld=?AG9|uF^-w!_o@oou#9mq!gB~|1fH|fC>fmE6@|9uZgh`%(*G@+Q4 z>0gBVx;sS|o!F)D!fQT{5^q51~UA?#BP<6YKxfyqu3TO12$+p1xH!38}s1arWG(N!W zE!h`eGLwYBoN-=g3yhznK>8qpN{_F3_S6wdm0j0ZcoWQ`H{{H~*TCW1Y{XkxTWV6l z-Cs(I_(P!2XjIfZJH%xxEY((Kex60ywWmc-k+Opg8}F_CXuv4^CWjA=v`*+OJyNzHuPfGbhPX(g5ticGX*OQ($PtY-eb6;~SX6kx=HKlflDN`v(3~B53*Ngf@>HG7PoO=5F)jxXBiJ zJPty|r>S?VmaU{F?jx&)@Y{q;iljxJx3ip)Ct77t;CdKA@zOv(8x|(@!f&3N>c^l|hz^|jYYl~V zZ~iUWj^Yl_{~h|jd}>s09gJWMVsoD5@A;A1Yd+h{R}Pdq#Jy_n7U>%o`x&^e|GS}I z|9m3~YHH&9=P`($;^N|82zKe1hk`>$2)b*udx{VN_}R#g)i3%zZY*;Cr5XzZe7wouV*n%T9`b}0dCGw5V>oVEGZspGkj9`SR zyUwUIeh#2R`Co&#k!?uzyt0MiwQ>F^`JO+|>?4@~PG0<9xmsXf#&t^AYrQMYL{A}4 zWQl$X&FdaYk;{O0mOk02B$PoxuFIU_VmF?*AXO%1s&dm|lNFYcc?ZLEO`R)Do}pYi zXh;i4BmwCYN$J_vxf92`HL=*O^J=QV_#@<&%b97RNA2D_M@#|czT!;?ZVeFZ{mlkZ z>M4ZQuAL5#OZ8mXM4B5#loY zPKJ^IDhmz7pLvr(?n4sGZgDMbGP~8xSo({0h9Fkmx-@d9PECO~OBx?WeA43*8osjY zHAofQt?quy>jBaQ{*7kqjyw+E8pN)9L(iQ4Uj5y=KcC7B#SznpjKsBv-Da>G{^JCE z34y5}F4P{5LH1toKP&n?>G&WR)fe$3Pl-RKex^(3v@KAwV=ekHnm3RLTkYoz| zzw$etqr9@Lqp$65sVwKlaB3s}rGZ{s(l3?`2(aS|k&hA+>M zMoeEeuPjTsCJS!-Db~qGe+JM}#|IkTWP3-*BjR7!P`qaHV%l*0_367?nB8v0j9bs{ z@KBYam)B(|TjY017DX4i)p~03!PwU>ktZ&HPtV&V^Zb^)b1nl?Oj=c1_49uBSMU!TMJ(vu$)3zCEUZ+m_A<10uc6W>0+A1dS*jXb_?ik^<2+6c(a7sOe<=ZKR! z+Sm=Kw;5i=>y0ND9Q(Lv!s_+Irvgho{}rLj?sX+zG);ERLWhH4>zH{YHAm#(TCmDl zf@FX^zf;E1he)9MZ`|#>9)6Z&fPyP=ZAOk!=UbUa;k#E%w7^SN=8B7bchZlmtBfqT zacdP?80OWqIw<7pK3WJY)!T3xnELKi>h}o1{05$u@`KXJh4zZto@KZ^*px899NGS$ z9_GNPwRv~S$GDXxWS{vrSv_$j5r3WOOOCjf5v`}auiABDAwT9yRbli={D;_KUY8&F zNBHY@Q;f59UDQ4QyD#szm%G^aHZ&Akt6uDpM}i_P!$k{$X^m^unf>)E;$DH@sZs}4 zXyZ04)el>i4s_n{JZ{%hY;X|oHg_E?gUpW68SJ*ma3wr|){mNLI4xY)@dOX)}3ngQE4@p|m`!y(lcuHcgsEmz8kICJ=gxKPP9rZP2Nkdb{*)d&O!b&if!rNo9tyZhoti7xg6&^UzV-kaqc`!X7ef%9kpn**m}c7 zSF63+hrs>a#a9wjTq(6q7-^S+g`HY{}zvHD5D) z@;%&FozH0v^;$+QqLS72)4VC2OJ;sr{SpH;8+< z`XcXIzkBAczIVe^7yZpgmtkEAtvs3bFU9$6>btz{dLQ$8Od5^y4W&8OV@Ac~x0~oY zA^Y!`&#r5q+ie8g3E9aW`SK$c>!upG_F_~6>B$A1GI^)o);^;w_(q8OX=v$Mjg^!v zQYpZTwsv8O<}bCT{dIlasCeqFmFn(5tlw&+8Gn>(gC7*=NUH{ha_deqa{=*Hl?xuv(aQ2O3E75W(C*bSQG zwX~ru$VZbZX2(?(v;vNwkd7!aGYNdSbiJI{9dCTd7)@KZbzSrSGcpx$rFC-+%*c!b zB_QIL{Fc%p>cZOu!T=lElU*g0C+qL4>;99JmH5*>HG1^v*fG6CV%Bbbnv2Z*(xr5$ z@u2mDWAxOFk4}w*jbcVw`bQ|V86*gM@M_{ z(TV+j>7Y~-Sl{`GOX|w^bpXqs?>&(oJ^U_Tzss!>i4nC9FCRqNP>knXUqaUJecWH& znt1b?O9>M9=anq;fKn{Y=p^XpYDikmCOLp6!RYB)!3mo^u4|g6E zpA`OVh|twAR7(ap`o2WDRo-sDtEM>RBQhPon%Za`;7elM*k9r%s(+og=G9Y>acEf2 zR8p6SZ!Tsmxlu4onktSF_nL#Qlcq1mt>^NO1;8y<+HI*xUoP)Yzwp>@LzPe672sVM zawino-*hc}H284CpFoBCWs~D*?aOHcUVWr(x`LQk$k67AJq04uQ0&7(Q6+~SWH0-7 zMjwswrQb(`hooZFj3b)kd3hR6jlM>!QM_@{KWiLxA1p`$U3M4GcP8=g(?_M(@uoA`k&EFX9MDl$+Hn6+36sYiK;`O&YaRMEoPW_TzMtD(P*iu9eTB18h^qMd^MJPC=4 z_QM@*&&%};PMtaGEjRS^I>?47&nUL-jCKnbwj^g=bu%M|w-vp4pRt--(Ab|LIjEgo z1F6*c6Jp*Tt!@4}6v`k{5WnWV_RvkNHy!SmdOcBEJ7Y{I_4Ww2QHRp1I<;#DcyYMq zn=S*}Za0Y6U4?czGyTzxVfJku-pK+-?N~%!gN18Ns`tGw?|sFl$pe*$6`R>>jk-FC z-aQJ*yu4v08FX>Rva^zdx`bt4cKtmTz$B4+uN}nylfUKiF$^b*VjIABuKT!VOtewrV;v@p^Ho({z2s2 zaAu`$p7WqP(1hTRkt61@`3dODX|1RNZmH?Wi%H_LcedUg9FlK!F5h3*D+>}y-UEW< z_NiWS-kZhTd5!zx!l=B>6tli@yaqm-X_1y4Wh~)5UAKzIdTDp+2z!pkCAZVp(%C+ z6KwM)u_Ju`%w=QK<@N*PK^7I!>j#g)rpQZ6F`QIZB90@b07r9{$M+rA9&B$Z>U{$X z93T9Tza>$znR(BItuXi}B0X#VXvKe$_WpCID5rHvy;zJFc&WcF5)d`4>9)p6kvsNr zkWjUhvGd0to*-h|UkTIiAF9!-PX#|+-39PzTJW@03N4HSql&;T&*zk;_P_x&M%x;~ z-(Fs9o(_1dxlM_aA5ew=;O`N`ksK;195L)74WyEc4D6{ZNAy?TvUze+q3#}$-Fy_X zG(Vg>;i5wO7VtIrz#rR?I`Zza^se^L?jQ2o{>dz(qhUu~j*WHl{Kbmb=9VtLS-$zz zwr!@8I#Q1k*a2T`P9S0T#gf8YL99d#M4cp~Dqqe3#|I3BldmLG& zil=X^-ppEg4j4OpIJl>f{>yZqlQOrrmv?~7Mj?5cN>ogt6Y#IkF86j7Yd(x3hf z2A@%9NH&8jQ8NB|OX|(0+qdsdTSzpga;|Uikwdh-_cG zzSVMmq+SwpU$5GQaz9l8N3}H2I^6I<8jQy{G@iuy1~BP4%I1J?}S2+9U0u zNqy7dLC2z`E*II=lLT{{Vc!R%z&*{sY;}gKruPz4=ZQcj`DThvMd|;`L23W%>w1!x zb=UN=NBEZ;k_*=gs1Nb@-(KVhnopzx4sz4v|10l0qng;hJyn_lauHBUK+zz@03t|{ zP^9QZ$`wJRgD8T6(j$=2bCnJvC{ltVC@n~b&;;rAN^hYBqO=fNLfRYr|JPlv^*+B( zZ$8di=j@p?XU)vszq0>mo954U9kuN8{YdCQ-m2c_pe>+*M$IvP6RJN9>oV26ONUSS z8latW=gN>=IL^j$cJ3bL6Q3l^rYo}|7xDbEB}#4BeYt7j=j@7XZ5_s&)`l^)fZTdSCtq|#^_%w z^Iol48~<4CVbfB5cOo!gf8A!Kz~UWh7NEONYg9VBZ-vaMJ=J~VZh24+b;rDm`WXBM zcb@ri3WZcT6R$QW1Fa=-_>5;ElKRb_q=dd!NEL1-84$muH}+LW>!OS}!Ux-Fod_zD zdVpZmc)iv%%Ra!YcCR@EzAim8>v(HbMDpY5+q|BF;^1Xy)9dZotq^N38g0w%HC%S>gD^&Cj&KMxQ5{bB zqqp2>eD4J~8;xn&pYn|7*VMgAS+4-p00ydCYB+;6LDr0f~VY{k* z2Gxa+N?^komGFH+-{rx|bg|`gQi;XcNal$%9nd z!)2gNIv+fm08kJrx27Hh!}D%&ob12@csx>V=4m8ccJDmEhY{Xv*$bs|rT|H@hp00$;YfMTbTs*Bc zj3pytjxfU7f%H|_P`~57E0K>uuz>*rf|Nhy%)y6|?Tsr}%7zV{k)aRCMZ)lgg(1Ee z+G~iT7lqBGO#b+3r$U**cwO+JKK&@mF0SQ+5(}G7LC@;H#cmSBtiq4_zN9kg!s}L^OZ9f*}YSK>O#=5&~2m-bFXSsd~ARCf(|#Km~+7Y zTRH?zD{_1kiZIsRt3h~TTjww~$OxnC*INh%2asJZ;cNyqP@J+`d8|YMSiPN*mib2| z!I#e^4qqiaH)!n3Gl2rxRNAW6s``HabQyxSHi|Nfn*7*~2Sdp()&pDUKBf1*4PA12 z^)Pa5PwrBKo{>SqsOnQ2w2oa$Dls&6)Y7LndBwq{_)iY?#B$jxb55o02x@UfvqUt;`G1c0h zR7T9n!_2!EUoMp+?=?AXUPq{q-1(ij;#MktOgphI#?>BCizW-63$0DhGf(MYjBo4= z8;Or5DRyj&jlh7VR=ul5sPSJ@{hm*+V!qGU#sFsr<>8&%HCMMp^8`pI$v!?T>xl>7(`w)i%2G~(lZiC;Mc9&7g(<;t) zvcSvAY}5ZSQkSaUL%Vh`qX3p+ejc+TMLdO&Y{DK6H1|gGUAudig;PLFRpTs{JXV7P zTF@t}Yjmy=&LxcefE08!d7Q|xL-!92kF}<-a}ak%ZkwHE-t}n?*mz#IS3SLayy|(R zOgQIz3@C8sGEPny-miGCDdbHI?>H*{0M?7AIGrl-Pxa%Szd-(MdZKpoaP4^6((WI{ zkdbO$T9oS@(HLu(k)&gvG;5_|vUs#;=Ys)NT6^ZLXhKV^lCs97z!_M&U5W4FfcioF z1FmqJklA|wDVfdpJCPr4{Lqo|W8zB(cJ&3tqp-^WnduJ8)$u$%tw_Hyv}b3vCoVh5 zBSpaW@gWcL=C#jbeGl%2vw{4EbcyK*a=H&eiepU+Rps+(KoqmLV!J#@r(PrWof;f@ zB5M)!jLTfR{c7t=|D^?VeC|;Dvkfl&iY8s;a zFZ!<8UC}pI=o{oWQ3&iQ0U9`GmnBs3?eFB-<0Rm7jgR+D za&cs0sUn=EPF)@_r#CX!1LW>igeR5V35kpG;epUJ-VI=W5PyEQD= zYSZIxs1LClqR1n%66TyXgYr-ycR3;~6R5bdzIy`Tzy5y2KakAfO!+i`YrF4NOk(|1 zr16b;oUrrRy78t1otSQo{X02Uv$Mm^uKVfCliSUjh8_3a-v)5M-P+8(yprTBF+Y&i z@2E1vkW6s6ptFcEX`9l!8vqn zj&;%MHh@@QK0MV&ls15dty@spEobUoJ5|4{I~bV{c6J!Ov=EZru(m@~I&U6{gvjTz z4!Bw3G{V`HWx$RA+o)s{db=e2*<&rSM6zM7B^$pDa~@04sbUowbm9Ed)C)#f(rkHX z(VK(eZa^y28HI)5xhEDDy7xOGolUPsbxtc+hn>D1!Gt6!s$dL+O-yo7z4!tXz!t1c z5-yu2s^N@h(Lm)HNjrV{Svpp_jrR>4dYE1!5jS1fd{fJ`Fqb=qc~)w@B709>oCS{3 z`rum-7Re`9o1-h1^;W7`NMY(0a+i0s&Q7BpwcN)wb-y2xw0kmZDcayfsi$;V3iO*1 zl*?{u#pFy%sK4$^OuyzX`MN7tqnf9B#HPMJx!9#NC!NcZ^;P7y(s7#Q&vxk&&`tQm zfef!UhqlANBE2K(Gv6OJ>L9~RHGW7}uzdA+jid&UQ^ekDDBbvII=+$Zw;&wTsKYk9 zF~rV%xjL@r-Mf{d-pSsRSs2@TbDj!0rtr-W&h5Hn>ljQ(*q?UW(P+SJM%f zQ9C*IpIkkyRQ85$AqDJRPWCksv4EEu+FG~P3{?(O)$CKcShE&%!U8*t6@U6;yq3g- z77^6-hd2j&&cIiu#V|OLk}7c zV=9rQ5)xEmP+1b%-310cqf~}ZtxQdP%5-|_kySG(NjQ4};!tu;`*!UnNBmj(gNtK# z5L8VoLA=Ro%`el1Ns)b z@Lh0V_NG5uuhbc)_66_jgI2NQ(T?OVcF(@0MRc4LU(8RpmqkjzKb%NJ$$rDiW)@5^ zz=d6sB_z+)p*mO5ussb1yZHPfd+Za4VqYwa?$>vTK;L4#sv-c21Z7`|Kr6iYN_j|rxenms@<%w{$>7Q4Zuc<<_8tx~H(HB>HI2a2d zb&Evnu0Q=pucE)sC4-xm?@t01{35HBL&Hk@DVu9sl_vAiT$IRbO#xZ*|EQN%2u1=0 z{J#Ag?UgTg2BBD0W5c@cqEd0^&;D#)QzI9B-kBbdwhx*i&4;6-)h7g3f*n3nTEzDv zR=b#ypg9XaDHsu>uMK$G8fuu2gJ6DXRD24k`_Kq9qMnSjnoi8!QGcy8Bx)5rasVKv zeL`1rC0sQH`5AS-4|=ydb0o3!vF0CN6PI?WL9-WdrqgPKd`NH|fcMV0@SNroVMmkL zX~Jlc;ZF*lf;@4@P$h`nVWShGB4#=XTMb)q`xA^%b>iRW{2Fp2iy(a#8!y6pzuTQN z*I=2rq=q@kHr#rl#gQ^K-sj@?BR{>zE#3Y>QM)3DWhYzFk@w>klu~ifHSQ;xgtZH; z@`oq7w{5rb!O>HS`2K+Im6f`+L_;Rg_b!x30H(b$rd?;KeK0vVNxiWi><<`OiJT@K z*-T=iKvmI@%u42?v}t(>M9IMDDa4zqv<)}ujmb$L%gk|!+_D|v4yhXujk5iewWQ?1 z-a&T<${eY#R~XP|bZj>}W0l2LvJ%#-I*ESt9>Dw&pLldbPQi>hM}!O@eCU`+5j#?q zccELLMP`Y~o^>C(@ zz{}G9WwzF~kMxOuegZg0Q_4btTkPhEpyiXuB6?X>I%8*$@j+nTHEsRYop%y~St92U zwB*Ez!nd}6W_}x_kgtbfSxS3_bK01`?*lnznYYHll)2(u(!A5@_Sei4=lFc*hLl{= zscU7;x>nad2Y>q%&DGB2{Q@lj!^`qJmDe3h<{q56dMPz-;BIi%at#^{u$`0{psN!Y(17`nL6ganL#5hCzsh3 z!gL>qMqgn054#DNMaKtV!I>n8>;FzK#vLasZ59WU_Tv8nv+go5cOM( zBr#y@@`RG~Z(N~>>i`w2>+$=c-(naaiOPJ|MNWD9Jy|87{|DI>%F?{^mi)caVKeE(i?5EF3R MFfhGds^=8(KZ62h0RR91 literal 0 HcmV?d00001 diff --git a/docs/modules/localization/histogram_filter_localization/2.png b/docs/modules/localization/histogram_filter_localization/2.png new file mode 100644 index 0000000000000000000000000000000000000000..2f4c2235dfb33319a6c0cb5611dd0954d97facb3 GIT binary patch literal 198077 zcmdS9g_vu1X7q^7z8As#gz001CVQk2yK05Agp0F1jw z5APuZukF4A00j0nGBTPkPlm7t)6E15EC0S4e&C9n{>atHbK0K|quE*4RBU@g}*|f{~@pZ|sJaW0$ml_YP z_rckBKG}!MA}g0;*Rek82a1YW+) zpXeAEuyP4j?zk%oZgHQT*w0D(xJS0Ca0gT#AV^0PzFG(6P10WkJ77qX8M2MNL6E0tXkp^4JqK97_5!{a2AsBzk3CzrlA*uyiCALA zti}dp@sZ#h$pJC?el8BIZ^GWJJ&T~r?R;YTg%~-CjuE(qpwn2;K*RG#?`8@~%XzEy z(+4t6{2Mm>RiN3XqG5DzzAKWa`IXq(nj^-KNS(tnmwF zmpZCC-uH^8#+T ztEPOjpZV+JyUTH!a1ft7`jc!HX8ZV2Z_n>~GmX%sby-4KKpmr?v?N8b;>nuOZBq&_ zkCshi(5$xMmv3p&#ZS6^lxz&t7Cbmo+5sM|(JqI0x`9w1Nw7p23914xKeB(pbq;81 zZ>*-c)ryw|&?f}iF=BI54? zTY4fsy-X%?o-{qWTyr!jMpgx*Q#u;OFyWs}Sd*ZQ3cQ6tFd}t_>+k)t5T5+VyLF2~b(uIVF?1pgn>{G3g&QZKq$2Ld+ zznY33f%yb3NUQSzpAd)aB~V$dv3EVV2yvSAs@yi(DyqjIN|h|cO8GkdAa zVr;@u#lA=Ct{SQEZU*xGw-D`1=@bp_^~ZNC^crN^b4ty6S$gpcK4-dtRo|qVk3vi^U@xYO~tayFr*KYcKnd#9<4~O26Ish{`EG+B;XfCf6 zLv#_R@vdD%7^kUtI}4Cm3V&`M`jMuhjRf8qLbPbp-$mOoL~AU0&_#nCKte*q9w3^4 zJ=x_tYw=irlb@Gn1S?vaixa1`+q(+a4ojlj5J@MBO)ZTtiVMZ0=zi)*w-{JjOasL7 zg9}m0l7xhelRPwy(PeCi5Lk;tF-t3ok_NLf+9*Cuid7_ez)$=>=o5==qS_!)0r@4p zSX8F$7z^E?{W`{EaGUJ%S4w3$LQR2RM0C+td3J)-YOjjF&TYM@qcn)BkS!gjb_LG| zWXtm8%}j8gQq9L>sM463e*S{L5$#kZ`hsq_$9xvEjG(mdW0iLq6=<_mmts1){YRuI zmene^;{%1&AyI~$P@XOwcm}fF6AMb+83pdTM#f`PcYlJbA~_s!lX2%l=0dbyv6+ah zK3XMMR9Om{k!4O)s^hroYX2fX!ZgNK!RWw5&)7gJ5fLA8!%8~zWnC4I^+%#-0j3t0 z4T}wU8@nX=mm2l>+L&BQpJ;!YDnBjEb`En+JyzD!TToum@JVXW^+|M3IhWpdnJ2DW z(K;(pe?#Qej2Xs(+(o!VuzN5_ z#!p70_en2v@5f%VFay;Xn}K!ylP{%T!oP@oIh0R}HH{~Y`vCe5eY5#ZL_RqvB~>`hCUqsBgJ6eMP=;ulDu0@N&F}RXr9YHe;k2~h+ z#^N)s#oKICPyv@(MS+qz`C4tu_6^k&k`vk!yc5KRBsoDeBYw49=nvfJmG@yUgrCR1 z{UJWOQ!7{>Q}agmpvtb1wyvg8x#3y0xUm~7-E`kJ%fi59$#Tic%tT`&wICo5x)#+ti2;Yx7%IzGb7c zr`5Lo*>u+vqr)#@_Nfb5PFD!_nCDb8z=OipWQmpb`I~f{QI;OFuL{Wn_!?FkUpL>u z^b83qBMpsw>b?As=SQEtW_&JCvnX?v-Ffr2Eu7}CwdW#}p_}Iy_WHv;d{6OZXqzLt;wT=o9MdaM0<$$pSDH$CA-E;zWw2MbP&ctmnG7~lt4wwk z-JICo&EDo$hp#o`EMFm_x0#oj)4VTU@Rz+Plhg+T#eB60@4w=uf|yjo>V*q4dIP^ z$T$;};Po+ZkLT2V!?p9&r7xq8$2rfr;ZNI8?C?^u#HZAB4@RTsV3xaYvPMbI#U!VE zEhk2ZN^0xg%nJ?sPhY+FtFfMQ5M$0^hdkpAU^q*CLKIc`gcvUvuM{80vUmifU!cRv z)gm}xGj=Sd5ycYKnH3HD1GCSt5`!GI;hfB!c)XAzH|Mt2vu=0X?m3W4j6UZsdNF2z zc8Sy*nosKdT)=H(__4utVp73K4*FI{nI|P>87&UqwI4=WtXb?2OMZsv-&U(?x_@0P zZ>vGy;N3>yuf$vz?PPpSdH;Mt$E$L_CB5lG%~gLoT*zl;r~IYiwe?b;8{yNksG6wG zX_&5m$7HSZ!o!~re}q+h|MI;kR+vTy;@hcIx9#m_eHJ)cl#vR7*2+~Cy4Vg*U)ftO z{A_Gr;9iE>Dy+waQMac5%<9Vum0&njo^w0bTY=bmWbART+?d3hYs@T%v=`g@eYCwu zJJ5R@KFzh`eXgJ7nDp{RQ%lj-7d>Z0@0wBx?(3Ns8Bb-E327zBU~JEDJ3lL#4(D2>xbWj!Aa z%N*Zd!uk7SB}2s(S=p{FH>#&;E?_yd>&}boy-1h9%@1SOIbiSZi&qG_!)U_PHg3Ah zx!p~c{pEeaR6lMJgQM2TMZOM%rWgoWm!3`@%iwj~FDc)ovHA4+`UL z;-BZ}0!#dMZtDs;@-}}SYC{j9?0&+tdRO7g3>i5Rz`Ipg0+{Da?O+$mO`GIXBp8#S6R(`MoKZ;)$h64EYK3RDTY@`8qFM zDE$`N!x0Mj)oUgz#0)!j)Ny&esuaP?D|q^o0H7rRU@(`F3Dye>1MLM3EkDe4`+P<4 z{RuNr!0zHrp1S1(GcxoWtT^X4>JJ^KfTr5r!i`a8Ya$)A+;Hx`{`hR6t7NIB26%Sg ze*}1dK?=aS?_u0G00uSS!9RTfKpBJPzx!Gkod3qb1OUQq0NDS=`EY;#`%AdL?y3KM z$4UwV;M_lv-d`cPnE!>18IX(hUww?b`!RsDwv3X}{axG4*}}rX#Tw%3Z2pDo9)Rnp z_}&EoAZPn~VJK;_BJT^R8Jjn{uDWWf;${$gZWD8esRg&Ez2o0`06wr(s|lm0 zy`6)LxThrZKN#Zo{l8!yX2yR|Tx}(pb=5Q(WgyNLjKbW!+`P;nJVr)FptHH9xR$K^ zzsc{PB$=&UT^+@Fcsx8jxIF~8A zHIJ-?iz{NKR9FQ2tdxT+6}*V(0ePgl`>e zTtWOmp8p&8e^b5xA2JZ1py0oW{uBDYDRlp@6#ohR-xM0oHurWg`70XeUYmc!`cK%u z@qs*lm;OIo;a`6C5A@#AKzKl&|8`msUh9v$3;;k1pd>5(#uH<&9Vf3!m4OmY$@ek#eC`XuY+a3ZBb(ZW6%Gy!FxR6 zTRpns1a$P2|3^!}k;fDz??HC`XM1qcr3m1e4Iy?3#|it7c8@y!e;^{e{{M=4(1$fJ zFhG{Jd#af;|G?@M^wFCG{F@O(An!np{xVHkcD_%q**Fm~0db}Vv3?YzfWrBS4WjDf z|FUbYCtSHCe&=7t%foS4>5$AieaT!mmY<(LTBwrxYYn0@b1|{FV%F%elrF2^;p_E1 zr$}qRQaC#dr)k?YjpKpX!N4lK8a8Ot}zP1kM6M-GB!aM z%^9g3r-e0VFISFViX2`*4;$xF`_4uVJFc@w5ASXdA=xLHMkGt&(5-L>`irIk`>!`A z;JaG$n+b-SiH**?>rN4#yJMbCul5>E2Co;Xl4?n*2d_(fI`Q#TBewo$V?c zaw#ZPG9izbTO{^}*>aAJFVs{2eMj!{{=_XbwGJc{9IJ3)-z^ z9`e(e!y_IRFnB3>yVmJ_w6V}}vmgRP-*qVTYIyzB7OuRzs;m@0^}oCDuarG&?YwRk z;qjRp{zS`6#sK|U?E7;gAAFTBQhD7{*~(O?r}Fg<0lqam$y&M0nmoY*Be6s(Z+9vy zWJzu-Pn9bRynoyO`n%%X4flJ}vwG8C7YwZ0!Qc>Pr8h$VFe>Yd(*~1%Vz^9Xm;)lH zV4BXy7z{`ZviMS+N(aOJ--c?%!A8gjM!DK$sXooAQ%#p@gU?fZqBjfhK{^%Y5iEhP zG}M2IzQ-a;3~twe9w(;^c1+N;Cz5vQL`;n+>yZt08 z3$6B0gb373nch$Dyb-$FD4cUMm(zZkOMI0(I^a7pU`K!QWq|YY`tRb8Qus|!*wf!^ zDL_D|V6bQJP~raWQh3>n@94}T@F-Ga5qPt$v66czd9lc1z;Ip_Zf|&RbuX2}Y-rs- zx_|yh_YEIi383RgV#n(Q*72_WH%Ykgw?=1g8~e9dq%Vv8uZl+*ZdVz0KJ#)IAmM`1 zdNr&OmB-I2Yc7ZH6&Urunen$*q*ijIze5e|emZ)<;~BWMdN!y4(keEA>%gBJhdS9_ z9o`-sy4rr0jaq;7ev$iZRD(lz>sq|>L_8xLj9#6DwTXJk5UayP`D9ade1GV?$wN_B z9;GKr87?Pu9S8Afg3WZuKqqBvK>tk-sMSd?7~Pu@kLm=yI+x@~l0L0*SUmWlvuFyv z_l~B54Qv5D#BevUvA=w;ULpQ+xJrYX=jS-87i* z#>QXYFTAL?oe_pye%AOrc6erZ_!L)%J!Zqqdtn%tCUWaOm~?Vot~WeyI)B=7)2D$B zN#e8PNZSoGzx?a=!Vrd>6xPQZ!s4fyhR&u#CG^0i6u(F4P5;}?Ffut;Q|_jl>u(B@ z%0s6edV}FedeL62UaZXlEEWtP*hTCG6}@K{5I*%hwcVIQs^h`1s2_yPs0Ve#aOcEk zmvaoh9oV?L&4k4+eD7?zJcry&kFKCcSGHU}vKq2R)^%R^bb6c^tehDr8!!JcSe7%A zy;@wX|B+c{oyir^liB*aWk z4I$xR$nD?++Id}B4ja4~fuTn>XgZH*Qpy~6++dP3DY8d}_@u8$rPPN}?|3+DS572X zYQ1JW{B+nH23PSpSPfv%^IDNZ%C?--0uHrj;*oj19ImY1T^Vgd8FtI}Hq~#eSJH)q z+0VXW#u1g)&iBE}(JR-8gFJNEopr9d6!AY15xEa`;Hp)c&O`LrVVQXydm_9mV__k4 z{Ky`0e_Vlor@n=UR-)v2BYCBQbjfW$K` zBi5tzz5|A+eMKK2RG!4g>b3b+#ItU%+}*6Ccsi{Om{}{5G#CC%Wy(zW8h_@vc6Pt# zsjpPwJU5d(O5`gf8v-G|>Itkvby~S?Twe(d0HA!-cFyf~i{I!blfB4F`t4lK&HL>; zrbGb$Iq@BmSQ(yM3T2vOdH*Mx0eo%-X3t(6+aMQeEUqU0a#~!G?dt+=^u7-rV0}+e zDC^^MtLIACD_7+!A9C3AYs;(Xe*aAfTn+*g0of0?}`Lee75AlW}` zJYJEcFC5;AKh9sT^$6(vx{%{~`Hs8TIP>;3bf*~lUHK#&hr<$(LnfOIk=Bt6A%SH6 z^gFpjPs zGUw!d8KKB2_5<-pTOmohHH5HjirpiV zpQCAbEq*B@JY;p}E0bjEX*`wcJCte%S|tNXE5Q{3l6v>2eN)pvXMNVS$tAMOZznLF zQ;drx(S^=L{lmw#S4$jL{pE;?Aa@ z`vN+C59hyCOi&yVbwUUt7Z6^4tlx7kymE@Qn>Ew-gd*4cwgnTV7vzD9=>PHZS-Y{#k(a}?*uT%2$mAy8cxU4xc>#QUnKm!Vx5zBv*mP+k5Q1h;z zAXfx;$@nMiRRoqo&lFr9{vq0 z6r=ZHrOjFZv`0tZL=1!%*uG3-JYsC#CgaJ*Xp%?3u(?YVl4N>%H_t`65GQuvQyFjp zY(SD51Xc|CQ9?EJv@z(ikdQ+M>B4Ni4D1MnV4S>{1VI!?BMg1r6Rhw%puXhejfGjW z>7Plj0sh+|dax}yt#HWlRe26+aRTH;HnQFO&&~$KwdP`Sl;?Jh$6@)xZ$(Ebw=?0W z@v8`orH!1!E#4EwvQ`^=*Y0(Dl2fU$gnaOrR00A3ocDowmnY5NkWuy5?LxDzOi;+KES~^uJot1GBWWH& zQB?7>V%!#o*xJzx_0NiM&k?-H4-fjgZw^tf6mq^@l5-z-Ar3J zhvIQ$4l1(cfi1c|3FrMuDd$#?y%p4%D9zU}UMJM2q8PSi7DLvl$|7>*E&#hiTt<2< zomHV~hW$Cy{GuB@@o!FPam&fHw!DhgbfAB9c20uP{XAWpc%6UrIxJi~P&<6_UQ45Y z@>P@_o7+dtTtLSxV66sRuQtN_!babdI0hTp!xOlAUv=~XyCO-u%GE(40~DO1uSx6H zDb}obBcW4 zu7+n2JwAd=_N2b*PXvehh!0Odhb*^Km9D(>SB^gicmjY2 zPVvdygFWi#VHG2JT>asVg?6J0H=|<6sVU9P>?jw*O5J&?al+6LlM!o4=LU0O|H9u2 zE%dyr5LN0O^_F6utQYk+uxfh+jIV~QzX`eEtC7*I#4ipxE58UNpm&ki+bE8bG_N;We7pOnGW`1U}}$r2U_t z(cYEO0|pgCW#?}|9794Yum9GO`UJ$Z1_T1(DSvm{MLmwXvgU!Umo0kSOo`%36n9;E z#8)`M=*g;%>_PLUL$!0B`PI)}vroRl@kXqx4ZBloC+?LD#jYLoc5TY7Ma9<_Z2oXv z21I3wEx+2~FxgdMR#@}lmC6S3x}QnI9x%6GK&7s+#`&qTHDCz z!w0GU$;NuIhzsuH9!kpFXOQ}SNBvLpeB^2D`w+>*iz^fQPf7c?to^6qOkz(p zI6xZ@>g!1nhj9~!jhNik;Lyi3d-9rd>oKgH8_+Z{Tr&`)*>1epUR#*A6})KhSK4U* z<5hh6FMOdpAY}`XlAl5OymI?kbDN?{-|7EI@VDm~0CYT{$G(|F31M`Ud!$1y zC8av(P5-Ut8)8T1-ee<$!mBlWJ}0a#XFH5W2YDm3;Lm@maEW68$2R)vF>zRB=d6pu z2)$IEO9~(fC3!suTL$jFhfVSjA_v1Twgaa?ST8yxxO&h|l~`>N0gQnM#?*$VjFw6o(oz;d>@aINSTuQW>G{}(OOQ-I zHyfxaiyhRnTjy*^{jnkRiXQNiHiy4Oe)EaWSru39rRo&4**fvl%2YyJ5Ht$zL8qr$f~gI%|D8M;@O95%*%HQ>cG( zuy-(OA%90_`x&XmPQ}L&gL{GZp-{t=@@5?|tRtc$EMi9YW43TOV>s181dST1T@W#q zG>TejjuoP-iDU6vJ>8j{_}vvPZod&zPlHCjtiE*bZGW8>aZ)Abd9Z1y>i zysg5Hn_*>^k=~Cx6y)`a-2GuM0;?jDQ7=qCGd!MZ$UrgQBl$EK-&QIRpE-#j9mV#*Tj?fxP8>nV6<(=hOMxM-;TD(-!})n z45I5_i8r5NtT!AQ9MR-x_+L$(t>MflU{X?W(NIxX>3_=v&|+fiOCG)m;-gtrl1hl@ zY;W#4Op@o743P&S)|lp41IOi^Oi5m+KYkoODv^MYYty3v7L`Q?Unsc-qUWHG{p6O=LGX}?6^lu6IY}dgmi$8(7&0-;^%CKke)iHHx zmk#<7grAj{rxrZ=Dw2*q+6%1pD(A!_IpigYBE2s0i+6h_`KbsCy|Qv^{-??$m^kl0 z5NDb*#n;o^IlLwY>qkbm`f<65h4~|kViGCG3LdvB0^()vp6f8bjgSql&s`{p$>mUV z{1r(x3J;b15KjHU*LEI1N66>NRYbuHdB=c!<8N-{SHV8d4b}5V%`WI9b9>*R7MZ&v zg-<`Xt2~v2huAB7Vp6o9hU*hZ^R$xV*4EB58Oe$W{$jzx9lKOW+=y1Jo z45+6*abt5-ns6kz;`OE#?Bl*QHkN50UBsq$S;f{=GAWB5e(bW_SAYP_{Vz{)HUOy+u}$!CiZp5 zRFL1$;<(2n{U~tXkq7%Chc+h{kr?X_jtP=Z&+0Wh?~1wPKbax~)1;kvr)w0Qx?l;V zTj>m_0S>WKFzhX+b-1=O!|jWu=uYs=(4UAdyU@oy?m=%KD*srbdrH~*1monLhi_AS z*sQ;+>kPNrDOu}hOiIC2mRVB8UD2B(e?0zoyhl^yzY&BVa99u}tWCYet8Z@m1;Fzn z5_)7D!aUo9MPF#jY&Q8FAH`g|;+m_oCd@2+1YKltzr@g;8`rYgDFSYNpI44kTuz8G3Qk&ES9DQhZY z%1x7xMc3RQCWq~N*?) zIzRci4R1V?eLC%PL0&3WC5izmIPD%ui!SdBo=>n2`gZ>I*|fyoRdc03tz)|wMp+$2 zbzJ2aETSBgOd$A;ZoGc06^8E0CMghu8&;TzL;XXG)%u*~DQv>mNlvP=SQXLUu#%Tu`gtKcd zcA4R}As9wjf#V4X-%fH?P5yMLzM|BksLoiv-6MLETx?l;pyKkzZJhRp(OnV)(E38K zotSDyo}{q72iSYzO}oT9R-VUcddu=U3af?2KD(ap?SmHr$}KJiHSCI%d9`O&%;EYt z?}eL03vDuho@r(8SxA4>G~{JGPQsY&0q+l*KU}1#M$(DEpVL;cq($a;ziRbSV`6}+ zS)^+(0SkGY7dUTb6*CqRGD8gGeQe2~F<9y`NV+@G)l+#t0d7a@rt`kyN$hf)5p9BD z8h0ySMgJvcRLLtnPU9<2)UK+Hcm@MIeN*i6IIiI)mt|_@_+0L7%}~VohC>`9mhR?dctN^% zFvo3?U{|!Q6n}nl5(ulwcINS*5Q)6CUXS!CK+ zS3XP4hdrO|k7p`M!&{6@Kf**3Vu=T(-rNM}J#rTst5uSCUD{M%5eqbB-lc~<%guzF z3fp2P+Pr8z-rv277BD}>AZQaW+=6tp0-ej|b)5MGuupw-GekFKgNbpcQ{0)1c9srRIzIfHH)74rl~BY6B!L2PV{S3MSS-ZO^Vw6KVXG^J96gSd>72468;eTx5`gUrnI1&fkw2GrV z&3I+7VTQvuDB2MU0~ymwdInOh<4iEl%p{uEH|r)Bg6m9qD}xh)q0+S)5^P0*O)|CN zk2+>oj^RplR}V+%MN4l*bs7UUw<+uW=;8Bh@KX-Mo1rDrc;MqS1zOcDz7;P)+s`tC zkE-!p7rr(XM|6?aY~Mh! ziqs1$fs&R}&%wZKR%60rVQLP>VahFLu`F&|R0_WEyNNW<%3Vx*c02)!^{NuX$gHqq z`OIn0WSm|1%pLvMNE4Qp$B|6C(&7rCV#c6c6Mz9_zAJOL4!E2#N9|No{0H!U`O-%}@7|O=at4XD2+z7al-MvAWo|0`9GIX@5HDPM&vNrJY5o)|&M*q2MtB6+wCzuSaoC3SQ^;1&0Oz zw)|=Fg1WJZv%e)}BIw+Ptvfu{l)+1x%JaY3C}VpLtJD5(VC{2Z4>O9 zk6?b1_EF`!kJ$Ei@vflUQ-^J^_$OXS?7AVD25-H`>L2w|%wdArH{qswS-T{*un{#$ju$RuFh%WZ<2u$(>`n-xMozXm3bkfl z>&3?~kW!?g7AgGNxi22Tx)Hu!xi5a7Sj<*g&R}Vq_NluA0&*G=q*ULb`2ra&C9Rb_ zbAYbWF3@|6UwktY!J|`-N#}zJ+3ePZZZky_+ZcEm#4Vc4@imwjzazCO1#Tpvg-bdE zJhqY6g^2ZUYePJ02L&+PvG*q;9g%mK3-2wojZRd4?D{!oVRMiq;2W7E^A6O~78>W* zg+50H3{+st9L4ad6Nl0Svr?Z1dkE2DfbEQb{sOZRp4bCPiIHm2rbl46$Rt=+wQz1Y zLzifPztTsCty-_?oOL$|xlp3Xg6w^HZd`garHhi*YC$q+$3dr!avsC;9WSh+HP2j< z1Sw5CoyN3tj^TOA_4T89iIp=zgsk9K=Nhv@;|L8Ma4R1-dlM5{M}?C^s+i_wx?MoN zh~n`#jMg3xH;4sH%&Y&R6vHBm5zUV1#8s2o+?Oy^z10+2~WsP4ASWa?x6_LKC7A z|GI|i&-0_5SyB)}eKN+DhLi9&54`fhsUc*(S^8kdY}t>>;Zv-i{~vpa?h+aTQCs(O z^kQ7O3QhIGrGnIlm~x%wSgKuqjn4U(^RHx-2Q~=kkLRlVNQ3d`76nWOTgaXzN%mJg zfa8;?3tJEOtIDuuG}z?k5|$v7e=%Riukul#sU7lSk`hhL(IDSU0N$d zTD!U#8ewVA`+Wky9dkGh?Q7!-z5%YoJQML?_#-2ZxKHC>;=EYva><(3o5ZRX-POr=6&$1LS&>4p|CBgzx?zU?l+<*gC@cH$yOgA%MRM4r*Mma zaFnc4*Y{j0@?ZlGIkC4(S1o0Ir_C#c1J?~2_*<2M6bo(AX$_y%!={tEqVOTZZtn+5 zhEtc`5*B>}S2_tRDdxLc;;g zzvZ90?e>4!qCxb(38A8N!Ck#{oVQqguM1CqBa&>HT9c5)^3n{a6WdRtp7PIKK|KAn6y z-9-tv%{V4aZ^I^#YjG*E5Q6IA_-5@f6Bz+kDg5z zA3YniC+9$*0`Ym_)1sShP3>CD)!eC6qfn+AOW5?qGM2ByL(RPx-H^yyr)xgZU)BBm zSeKX@IBe$6O6&+y7`vYvW|AIZ_JMzo#CdWg{9eeL>I!`7d6AK+RFCnry_CB@&6US9 zhN~m2q9GCVVA->_L(<<7(4Q4y4nr^F_{ZxKHyTv1WlaC@v@P^=xc&6-M4h39cnjJEY9 z^x7Hle`OU|2ile58>|NVNmU9g*>esc44_0e%?}G|cd8E-Ub-{&)08sl$j%46Aa%)^ zo?q4*a7yfVxrO6v80Zb+&Q1K%*9^}->jT&Q_GI)ln0OdLmC4xTAY!nZHjxc%@yguzaj$Dn`;hxCn{;+Nfa#9~ch zAnDyRUiv~uli0nd7!o&w&yL{&+sjuIRL!iCF=v{0=_{*739-d}d8ab9eH2f8tuweV zuAPTO?7oHfBxQZ!xKprD;z%mAT_wrspYu=-2?`tinE~`x%)hQowx5A7J!Mxg0{>u#8BQ+M}dsvKsCAdf1 z?5H0-xe*JN-(hi6q{VOz3?d%C>ski2UC?$ZUr zuuBRz_E)|Ek>Rfl8f|zQINXjQu`*OdZ32HVULFY)9%-KcqW^{wC^dceRF8^O|HF&2 zrSB3_;{oBG-IaJ>zHM|#SGj0D-VY*zzre^iOb4l;{20XFweL2OCT<}k_384LciT5I zzPFakZ`2rBa!KBKvHE2YzqV9K$Dm$ZI_dAcM%nYF&8Z2&iX}czE7iO7L@S@E?C{wV zFq}S6#O^M9Nu9(+Le1Ii$f69Hos9x#0lmnCc3zB1zW*7P>xLP`THfnv_F`L+o6ut6`{xjg3)gi;U}{HDqje%1@;b{WAZv{9&8M@zl$1 z^Y5&^a|D;QQ3EsT9a8=4nFC0pT7PjHe2)!JGnytiZ|7;PVdmJZ`p;*?%8hIsoa5cL z4-EDcb}}ED67qmLJR&X$Z6_&P`g*Oy$_?v*S&o8 zS=WTLkFHGuub--37epC<0lFX2%&AK|>ftwG=iwm_vB>w^VyC$%Lxv>CFdpp2<#=ge zz~~CgZk;X)1eiU3P}>s~Xu}*r%fI^rN~_M1@qpk|aF9<=scrQvPiL|)lP6pFs$mF<%gdGV5bgJJvtPpH`{b6xewZQ*? zU3v45$yw1DT@c~3r7g~t6p+q#rErsfv0cNFVn+URonA;<9}`jQ1chkaO7Cxoh(eZE zNt=L|vlb;b@Ec#3d(r4B%?TdYC1t80o>*Bb`Wryei@z9*iOJUSseGaNWX}RqiDquf z9EYu?J3bZUL*2XeQw2(x`Gx&RmI1li%V5g;{k9+*5yO_d84~=x4G*ahG6UUS{?0tp zA*F#;!@fL$t4@bQZ2z3Tbm>LcrnnOgnm&T~tvp!WXQN3_{Aw&6r>+i`J}I*@JznU94FMY#2|&Th0oIU~C<84CyJ> z!W>kZW5(^9+0B-c#%2tr@@&pG2w}~szU_U)oYYYpP{*BY=f*DGS;+(LrQ^w32%a^N?F?tedAn*rQX$aFy zYOPV;-M$^?TG4VXqwGEI4;H<&irkmKf~g13@G)m6E6&qiUrm=UO`addnG?6QLrbo` zbC5DsH=%x>Un{n8d7epg8|>Sn=XS#h=15%-$zU|`%Nu1>-k2`CKa=(h$H^yLR$wR% zGP|*&7|A2Zb7vIXN+1*5NCLP1Opm*V^ z9WT|WuIA(DQ*H~ZzvCZ&>V3%9R3Zc8S{P4Tp@#4li#|qSjdlF}PyT!pDU0tbO-AsM zByXj=od11qrRcAE3|THvTRA{Rh_XDFEBB*-ZCP9QDGJYgDSYb(IHCXey` z%^Jq~HTh{0_cRvznHBB~&|t@8+74t=Dk2~MyXM#p?5A=w9Zt$?*h%GO$K_;9fcE2f z3LUJz%moYQU^gVk3W_|VNAOijpN0|pTXqqCUjCv;?TLZ3dCO)qLU%jT$1FU?_$w6` zb10G#wUMZCV0#ty`qo6oSvnaO9;m`BmDUob(Zi+8uSgY?nL0ywM$gLA(dOvuD(AZ< z6CnAsWWJSol0ijvZ&y6bzHR(1)L}oW_TAw=qNU2!Pe!C;d0($hvZ4|P-A!4kYx*p) z_%aUUDlm@IaU*$Ry>d<{OUkBr8YOZRd+eRTu|Y^5MK}?!p*u4e$g{7nViRrtfUpLI zfB^`HzUDZ>p%qx>&U8*K?xX=eq#++|8h?7`=ih&(|I#3T+CpiJ6lzjxR3I(c7bg{;dpN+}UMZp6Z5Dt`Xy=@Y>4Z=>%|?eWT}^ex#Xp%3TNJ{{4A z3kQBOw)cC|B+>5El4gsHc~~>fkelnrdD`Ze@ra0HJBW6QXEiT)pcFJ)Ci}H^3T2~F zXif9Rl0yer_{ZzcvP zFsf)i7@h}`2K9#%Qt7L^C5(`d!Ju+F$4~vTiIR|)G~Y@f$-Oq(s3jx7pg9=I&n;f= zQ6EjlM5=NM*rD{Dz;R3~w=)Vl-w~4c=#TZ#N{a`XoM=QJ4ch=1-g~%)bj-L#GKe-* zu1T!Q(3k>@7w!H?Kx@EhRsm_pi?%lk;JP-{dlAE~(XGZYc)q~CRP^TEkL~YO{5F^( zw;~-e34=@=S8K63n3-oG#I9lwi5xFteGOUdUHKRnL{FIpW-!jZB&l;qy-#va#VbVp zmLjRqPctM!%57VQcz?>0)o}!#@f+S^gbwJ=%%;x74H*1n7m@ec`1?(v063I`rs@gt z6+p9@WW25U@u_<4gy_BBVDn?L^3fT}lRAQ*QAXE?WZz+btr*{>(sUKb#v<6bQW4w~x?uv>Ni`@F`$(Rup?Y33fF zjp|ty*E}e&mbhyumeVcZrJ$k2FQurwM~sh0_~w1%h=HWC0idbZNdX0DxLPZfhIG4- z+;iV*Ty|<=+SqlPCKS_|qBojQv*w&?c-}l|e{0kK*`Y z#;~0HL|RL+UpwRz$~6RKN=TXHuu6e8^3z!0*-BwuLp~g@rYFc|X_KP!^$8JfLxODq z+zTzRNH+9H>RFt}rP+@mW`xRaCKQnJx#G@yG*G5z&lVuQt8t_GZKlp4(C6!eU^eLN z64vl$fm_#y{msX>dC@hhGB9WzECEM%7mND~P7(ekpcQu(J4+_8YaEBj8aDy^4d$el zqgY61kagQ{xLi9O`5xiq1`j&)8>fVq1j+Q?-VmJ~aW~GzH?|iWX5v5DMBg0loYY@h zxzz9^%4HEkZ9u86Ux_8>Jj)Nyi!w6!GRip(GdHz>?3) zLMxa@bPyAsrZhjIjpc#tf8*`IR2)m+Fmc<2HO)L>V-h_&%LDcpiQv$iafMeK`uMw= zN2^`pvS98V%JofnSppMu#?xMVaC#eg<{A!eC`c{hJ*nnLr=_;7$9g%>nU;`T_$6GL zt49VJPP0K0N2nhUKC-q83kRTHhH)7;NXixvja<8a=2p|KcTp3LFEJx?3^44?H)>+* z$_u};a{0XxYYfAmEyjVCo_s_X5;BsJRR7BG^NTQ24b5tEPF`8!gb#^G*V`y){po!9 zjIeDy-XC)$=HpH`mj-)Mhug5F|IO7IDozgCPb2~G)WSNfKq0}6Pv1X3)74ZnX+v; zl|$stycc@E=P|qqPo36lanF-3E{fZG>5_1BmA<@O z#+xyknyh|O%Kr>}HAnl*NIh*DFlU#v<(ZVdHmUnQUZ`W*&lYHYL|f~)@2c{1Xq?G{8Y+OElxdQmrl$WM%S4O(8dIEqdL(jxxpeL zUWL49aaUxoP?}(Y{_a2tqpgU=2DUDF+c$}lfLnKcmc_8qQ6U|yna7^W8(ozr5m1al z8TmiH<(Y|{~rK>Kz_d) z@^ml%h{^t(AM^%`K71JYpXLp^yxpJHGq+q%IcNC?L0)5#)W~=eEcm3)smK4xFIELq za6BhB^_ZHrb`VnFj^b9E`@%+5bhQrn2<=!~70}J`*=5>CA#xV{$w0xO_`qfbIdL-%ExaR3LWnRyTDY^wBPT67BlsiG{K-k z-9-ApQt=ogQ1LvrrHzDf#`+V1%0u;`>*0_b84cNcvng2n4eLrz0397^5(Jh$=s&KM%bSuY-8-sk>@No z)gHTTFm1E%N9B`nHfsZ*=+_6E8$f{#+VI?=k>xk|zz=HijW?1p%hEcEG1|<7@nlca z10LXUdc?*KJ-h(weuY{}AdH_F$=m*szuU$N5A4arCgjIw0yEuA8q-f@6KdI0e^it( zO8eToTgS#`r3SJ0P#`(-JeUS{OV^^uYl$qa@!Gj$OdXH9QS3w6isJ%2kMwCxME6`b zPT;jU#NqVvLU-m4{qYNPOUVd4xUM*{OfF6L=&vAIqMQG4uws_OMP_K z>)-g4OV?-}rw&i-kkD?BYneal?(~{A|6XrgL6W!x;M#{v8Vc%VxM&W~Zkl5G!g zQD-n(zUa5Hms<`(idDg{2gTQpJ%PB!-8I^YS0Aa`0OCj<4uvIKeQWzL9t%Oeh*tnb zNQ0_dwGq5NX*3NbEE8wuMSt?AHbbv}`eYtIq=tLZuY&njz3VtiR{Q!fZC=qi*|}{> z5YGaYh_r24a}>C2{;3x}pVy0%0ZwJmjr9i}zCnb16mQlWeop9+cq0ZVr{p52tO{SG z@GVUxnhmegk=${M*(c+q6Sg(bbMm4IZ}E9&UD2FCL^Z6`NXUP_o5r7vfn z*pJX~l2-ZF`XnbR;+c%yJ(bdYvJA@&bW1IN*GH zV0;Gfe9!M>9oKTi%AM1h3E_Z>{;ED97~Q*&ksEBNIYHYy7K0c_Bpn&dCK6Q?OxGgn z9=dHV+byxH%9Y_e3DS^5catq*g>MnDRkdG8il{TcC+PrAk7xhUzvRa)pY;N_6O7%z0d-;Ap(D(J|ULQDhw7TCG1)AU<7rGf4`y$U(VOWmni zZ`bo;G<*EQi_gtT7g5Y_@I`0j8+>cl?VS>W2L1XnAGFXnb3=eWrx;(7ksgv}>aeBB zCGk+gj6wxy`Llt{EjV$mr=*FwFeLZ!L$~p7^ zQ$66Ed%!V;Ag~j}%L*U}tpz*!3CL^XxDfsX&kD3_@JT)?$3f5d`~_}Z-A7#0Neq#! z0|FHr%@Qo>qK&$tYl8_w$a_7KUrR=J6w1-$zcN@90&kzsL1moHrou`3;}`j|5#fhT5mgcBAIBg_>OZwZ9=q-^-D)r%Q$(FWs<~U*=yBh2>Wo`mj^UULBwwW4fNg7X!|>2gV8D z`JP`{*FwRfr3%RLtww?v0i0+;h;q;r7C$(H7(=wE#)8f|8cU%`Wq?VOUXsz|Ft!mli#7n`YdH|+w6x@1SxlpF;0Q5;R7 z8=xY1+D7>#+DfoO9=fr)Bb#MM$=uNo4#^vRwhvwChrjv*Pp3c-1QoXix$Wz59E=Xy z=-`uRYU`Sa4o()i?Fg_=&^4q=2l_l8)B)yCDaBFzEFA2-1{nrK7bSWF zwE0yN5-IdUA4)jtge}@hV@WxNuJ~*k%ZhmNhV7HEsds+`7MdH-ih|@((k)8ZGDnwV ze)+P7evyOz7=T1-M2Y{Lf2qzmv~BK;n_?ie$au`pP3qh0gIn{=fu3Fve3Guoi#GE| zA3pb-8YhOgAax|^gFe?$D!zrL2KMIaLHk|sx?mJLrv=fWYArGxIQ4oK|9BH^q0wW4 z0-1*$t=VC8Uz=-q^z+n%{IW>eZQ81f`zX=3*Qt(=`q}e8&4fT8s{%#pWQ7KkpU|iJ3_KDL+kz~wNz0UdZCyc&EbO}!iQgtp z%UJtMKF@^1iJR>XS)nBKBBkLUU1`HlWYFs0*_%jBFqGD%GT zz>6mfP_k0$Pr=d03!p>?aIps`{@d{d1e)kZo03sBU)7_L30v|-4)n0fnecd? zCc>A51keWFkVrnLvQ^_3-EJnESb&-&r4DE`1AXwItU&UHUbPz$^vlOlM|Z!lAWuuV z4g&xHKmbWZK~yH;mB}At@Re_ZSS3t5Sm^37@Kd`r=KL_CMDUz^{7PHtRsYbO}DWhWw3h{GGl)8T$x)(KZcX&Gkuw4h~S0 zMRk-nP>ff))o1;&hu1z}er*?cphJT#HO5so_?PR(_*qNZC7l@Wb>X(}8m{^EB|6pX zq8}gav+03_@O?H78CtJ(K|8b;=B&4i=`PtN`ym*wxSny#r&VTMMKWr`Au4 zPvErfm5-9N2%_ldgszTH^=ib_d6-W!iP>ggeH_r01a-bFVzeQkzwsFp-*(mZy7&Am zuO4@8E}_XlpQl~4jZ3|PHn6rC)&8mn>w=9HZ?n4;ok@Pi9;+H?k0Kk~soRo)kLuVK#Auaof|XbFwgOS5m2QjXhy2nGx}O*k5g8jxo+pt z{u(vDbnSFuuJNk@y@_k3%R|z`x?m=@xjiARR4f6$OM0x3jqWqzfqmEc88Km~d6EY* zfS!c4J7!wT3T7cko7%#=2PpY)viKFtVS`*@+MvPbNr7 ziwr%WIUJgJxsKSh5zQP(hxk@0zw`mn2M=vx;+=B*?lJkXDR?cO>xM*c>iWDRd}Ki; ziSxmfBLO^{^L8q&Yw$23!D!zmUW4Hh zz4;JSxouYg{2FBT(f4E0sp&=l>Y>N?I3H#PAGvh{>hWumX4;*y1yUy^j1zRLK0RM> zQZ}`9=;@?Su~WY?(QQhVTTfrdsC#^$ozvXcXx|uBJI$+?L3^LA&@m2Njo;t}v{6T& zH)%F@Z?a&5hku=0Df=>EG7@y&5$v;bC=L9eaBNd1d z7~~gJXd6#|urSj2S6!l8;4!zC%42SY^SQ+U@R<|)#rU2Bw}o38wi7(dL?7((=@nzT zRUG}`Xgo?1c5G7O7Wmm8x8eiO&xA~!l8z*jHefxS^l@81=~55t0xmeb3{=g>eJ<;D z;l5fjZ-vz~#Mw|!T#ft3&3FsWWR?t?1$!d^^Ae0*~!FHFw0~oTc zca=?$^(I;SNhmDSWgT}NJT{jW3%3HJaoA(ggA*zPL3fF-^`Z2*H;eSQIqa6QBZz8V zL5ww@o&x-9BuYz;>5%Qm+U@y=Kgq4@QwcyFc*fomOZpJmqwU85&E!>qs=%Bd)kTQzzTZC zcaJmKZl8xlHT$KqDJrWQx8PUfQUcgY)%e+)#!K($5N+7OJTM~vM2U~6^8(<>ms?0u zz@^QI1~TVU%-IhN zavh;_g&x0-x!&91eoDrcKz!E*8v%OS4!U4<0!gDB#aZ>hcnr*0ow+;En~V8KKV(l} zJNe>PEFt;@5Ey;Z;GjUT(`}SQnKUx4zxXf>M1??VsQjnCHcXPR2+>`6pu#i8(fn1ik?mmab}Z?eeM!yy^H`Q1 zmgshH*5;-ldL#9(EU-!YuTAzm&x1Ef-yS;0GVzibp_6UI z@91X0PObCSmGZ*}QIS3Ij{fp{Fv`BOwQ9|SzeSvJ$hQF!pe?u49o(Z&!Q znOdo&Z-dYJX^lwYw!fvr#4k@Gr6WF1(EFBd#_SW1*K2=?PR!aHaj3a( z>NcOA|Af#g{4s}S^^a81gu@&!DvkNpzP=95%{G7i*goDp?r5JK55zJWaNa%OAj1W& z#Baf1Z>)6)e8+t1HQ<9sn~h)&(ggVYD|jbjHpa;(8o{EY$bw&kSwolCHNgycl zsxawOIxFv5FDN_JCEiA|k80a|DS;(Dp!0ZQ<%Y+`1|*N%RB401mbfqR@8=YLRo7aF zKXU6_(znESNpEnMfHmSxin@V%)ekwmdT>Afk2`~*KmLFZr-)$ZCQ3qZ6rU9&iLrk4 z(8x_;|cBq8%N0-^UCAxU()vwVNK!+|V5z9V-~2 z55H0Z_4=X>|B6pv1@Oa-6U=t*@}7`J9UV2Zm$oT&f4z!ywbXkJxd$Xl04HamA&jWzLj=uj*P=c_t1km(k(AX zoY2{JBFD*<>0Gi&@&d9>gL%jkCR#Od0uOKk0`K@gf#fuP)Vb41qL^5PFA7Vq&@-x* z;Sw{j3rhDPq~Fx(1JcH; znMu*a{d{X0fDZrox=}rx2M>}h;)Fh@7j^iM)bJTicwJ?2Mg4M|Bj%TI^7@m-@y2?h z&bt#*+RQ-@$aiwb7&vv_kSpC`0EEun^kjc~hqjM#{k2>PG*>K|4%TRpUE^&ZkI&WbJ-2lMBk2h zp-WMpuphVUkTvO&d(I@9je$U2Z)<3?=w(b4wUUC(n`BqQmh`D)EA=(Mpbs{0S-sU* zVc2!Uzu%A?u;CKg8JOva-zU(KmarYeE3BX&xaES zkI!XGK!OFg3c_=z`t@dE;G;TFhsmWc)$WRlE@U!3*@4}NV!iDLVrim6lE z@I`0`&5?YNw=>P2gaNa5*KlGi^`m=DI*fzQk*TurL~g~k+`g2J@HMj@;ea-@lFiT6 zF-uHz1+}lvJ@Glq#F4cq5qk_MB;r z@3u>VSe0Fa=n@VagMw=e_A-p`65FaS*hxr7PwPXSAZ?z|nvQw}@PIz>f-gHNlfX;f zZBUf!ZQeF1Lbz%zZ#q(H?hs_|-b z854XZerp)}_>3rHfOX+p-ufINe@Fx|qS3?S;HF+N5XA81J%5rglRtDJ(T4^G*vz~_ z=cgNJ3}yk=AzRz;jxEF+op7R1{0FG^*C_p_pUB3{UYr;V|XE1yw6n;ytGd^U9-S|8{EE?t0Y*cW*A%-Dn^E|)mN%bQg{4jua12mN?$bD98d1^dN)@Y8LR4i7r|dw?4! z8_-pdoYq%u!;Z-}g+Mr^O*M7d<*l)zAO2oU)B+K-YBLGj60SC|*o2qnyz0ND7mWZm zBQ{z#5y_LxOayF0;t73vGhdRdOeB+r-}U9?M|`kmZ3iWE^dVCleALmwe&yC8n|{u1 z?ufi2N6-BeJ_#!iXU+#S2TMV)5pPyhQl>n{k?Dm-+cXeDS5N7*p@Ke>fVK$G-rpc! z#Lv~~5inty^tXOd$~GwxzUCp^;X~^VuI!69^+ktH;G&W3OsI@+Uh;4F7{5>#li+2a zV>Tyy%nP&}@RIB!%Y5~q?;zzgH~aE>!vK72JW5}OD&ZaL8L_N?K3~e`2;ohlrsq?( z+t`6Rf!0XS?E~a$?FDZjL`x4fx;lNSqes&XUaQceA2bq-vrRRx0yD2Wg^ru=$bvPhl54P$A8q8 z0UwZnfr80iW7eBF;)N}g2AdpPk`gxhQ%c~qf5`PlEQ~><=C1g*32gFYXto7A=uh0Vi!V%&8e#^o#txAaKx3anOM4B_yZ6f)?w$5m z`OFnb4kdto=zzY4UU!Djk@=D@0+HLT^a0F0-^!**4=?bTe|!oa^~7eL`0Zbkd}bbq z_ZVceVy%G-4X;4aF!D(1(S`K@KI8F!D&Yk1pmA)3m*|^hC4(tYGW2`Ot(}y!-fmMS zkGTi`IEH%MYaLwbl}2`Ua?CB%&-g`U4I0lnT=~y4`Cr*`<1B#n7vGwT6;tam?F zWzw9!zz$9ZHF1GVqDNo)F(25BAH7bu>P-PY14zGUgBNu_Fr1S+XnCQh{pQj( z#HtaE`lHTL$rC?T+9uX&($DyFjTm;+)-JtO&WyEPgTJp)^zE-X`Ej0-ZQ{~G7Ox)6 zv-a=WJdgJH)@{a^Ype@+0ZX!H%uzdw9vBJWS)8>~>bwv$PRSuRP68FdV-0GcGme8@ z4RZYD?I3TwL(3X)mx3H}c%20JB*XnSX63&eE-vDiPWLo)fkdmvciM9dhoR%)xK=pC2KUQxXFK^)|aY7T$6VGVgey z&1b`d3q7n6&rxMj|0t#(9LKndN1Zi`tosV!rDV5V3;X!?N!>}hzq<*u=c80qbhtIC`x48rzYNPMpFZ1yQV1`smRn6mRr_k363M-ouGdqe0H3Yjiph zxf%~YzkTzb;KvsmGQqGd=9wpxxvr6mPE{_v{pDueMY4L#gBs_>Wnwn|frGy|dGf;9NUf9Z5Cd(Y=)9IHtM;j}6>yCnOG_j8_16DIqbA`MAAQf`cC_)F7IA*U{W` zwtKP#ugYmj?_MWtbn>#qlfIs&;z?$+p~qt*^`?(5Y$W>; zp<9^IqJ*~26tuhyqAhLr?<-But>ZkITgNtkZS2Q4^|N=zPF-SM-?-jC4Y;CyXk)k%75`b7`Xl zpEU@MHt`_jgeICzE=eJ$J~=0en|;g}$sM;8M(J2 zW#Y4I;Kwif#;FthGig8%bQfQc3qTKh*323xDT6*v;o#Z(-gNd2Uv|iAl4L1HL&)Us zpg-o

_nR}*#+ zCK+_@uY-3v4J_nU_hml@-u-HLke2k?-DrD{#3@{o(Kgk^z#>IMFFRJ4$xjke@krw= z(kq>Er;K^>H!J+eVV4~yNo~>aF?IS!UnjpEpCVemm_zRhVLdJY&ayZHmZqdC{LDn~A>`)Xj|YEjCp(uaj~8c1$Egf@6mdu>I-N^rs!ElpS66H6A>r zUAS#G(9V{HhprR-DVCf06}uUCgPSAUcJ5XaeEwJ8(OFOThR{)c#!%Xt$Mp*G2zv%_ex3;tE*S_B*!MMgtXI=KaMzG;~yq<_EA=!44t|g7^LN~O- zUGYg}5*G>TcFGM&9cyeR0O%)K9D<6~TdaPU#)7_EZNC)nz3roaJ(3+4?g063(l_Jh zD&UeW)4sQR@Q(DE76yzTvTpF%jKEu*0-wzQe64up6yBf4=A7kRuTbUdhl#S5M!jt#qWFj6ImFfyrqu&`BOC zz!$C@dogwS3rHG<&#^A;ZE_lK(iH)h);jTE61mV8Wv%6>Bf=eMZ>nxU^DOTK>C4@X zYZ;Q>mZ5HUi2Q+G9PcLF(>_ObZ!Qe#cr05YQ#@AL5#gId^?ewP zr;?R2o3AB|bW~gP8pljU?{=>q6Cv1e>SRh9>A3{On=eOwXbk!Q!?SJbc4Z%l9~#dC zsaw3o!^2E)^cpLZR8?viI%5^Bn!U9tTzw2}~hpy{OTbk7!^PDb)>z08V}oK&(hOgSoAjJ)2C9FrU0 zy3GHiLJ0&sUNNvx%%amVEP-WN$YOmj#H345wTfkm+k(!+)<+kRSjB{bNm%gAQ<9T( zh!ZX8R{#uf+Afzw1k8`+7=BB)#IG zAM{7Z|D?Uny)B^V*a)Czyq~D=mXP<=jc%L18OnWq@Q(V6O>11(c?qDMzsC5g?-DKC z+sa;TxFmD$XX(h--u^xBB|C;j@@Gt~F`u^E@v{|yTLSpm>d%Ybn7lsBqHWUkNQA{~ zCQ%dfM=$zi&s9zaA_2lvpUf~`bT^hQIE)4&4bR)iiE*#Mkjk8yKERh z_9EBAOy(bkK5JPeK=9zG4?gWCAY#d4Z|xvNfy9qqx?biLFcqRXF@C1HgNzn3@@A=eZ)$=5R(MqrXP2|xX{aE14y z*z+nkl}Y%X<_E#V!PCxVPQ<@TPiVJ5yxuNX^0lrE#}Yhf;egAZ^r?CoF z9{TPBvMxb}M9G(wQgdHYp`AZ7zW4HGObnh*v30z}Q$LE>6}irlGqeYiJ$C_fqm#@!Q&seQ|tS*{cn7u~|IEN4PsQIp60T(tZi> z%orB`RYr}MAXeNZ88_VHkH9SfeEfa*pa&M4egL79KMW@1PWXC(u#A{IEBV{X78ms= zH6vI+(W2_fV?#G%VNK>OgFFi+>XMy;NvmEYt&RRnX4X(VwP*&9ULseJgOU$=XzxcW z*{M92VWsoiyUEzC!98gfp31v} zqtC+g%AX-Al8!qsYfRW>3iFF(N0SUbfBx$5I(DdoN@TXqt|Tb9dZ{y|F=?WTq;~&` zt92{RV)TCG)jfg6QThct`|3wYc)JhFjbn0D`a;NOa>gcdErv5L)RlpQy|a;D_0U?R zCD9d=lqKD4_Ofc{!X#w<13<#vIOCpVaR9!1thG*jbPY%}=iQ;~$8C ziP2}kxm$}}j?lBqAR#a*!fA)EMIbmlCLe8!s9LmV5aI22?=^oj^#q6)%=|`f$qBlS z`C_AT+0*2m6l^$`c8fN3{B=)ZCNMblvBSa`(prRY^!hQRB1hjUbvD3u`8d6 zH!61Vxo`<`n(JdBelHn@`mqn<;OxZJ3xx3nS3buPw6&m)+{l0fb?JUqs~Eb*h7~n_ zLTq<&V<|pm$&Qaju6BI{U;(^rWCwkczp+_tCea)gZTWu$Wgomg)2^(493@+Ij8A+7 z({JB>4!l|$S(PI ziFSDO$0T-xb6k0hyXj+X?B&yHH~b299>hkm@^v5W%2(u}r;`nPzxTAIpp=}qKvgWa zHsg;C6-$Hq0?ZiIB$jmJ8QafdvdO(5<|687OJv^Q@kijc1Niv+@Qpl}^V|unEU}r% zuy*-^n{yhCHg$_1dN_6E;Y+b#WKVsMtw|$D$;dmIog%7jh(r@?Jy=3WDeQ@A7Tw|v zL+j0K8X}7#3AH#DQ>umOqwh^r70}s9F%i~cvn>Q=cYTo-dHKiNSNYg6EG_&leJ9y# z2~GdK;n3BD+>1E8nZHxVjU#m=+S;C?s(Rn^gszh)rTbvQ)zb7yFJ}C!1t6l?UA<@L zu(X^c*01=jsz1Cq7*6sdP6Ie4rR7QR`jAZcfm3`&&)Pav?CAv&W=)3F+071P%U)O8 zuBDAB{i)e`e0NJO%TFX1fE@Dpg07Ou(B;Z^)mv&aj&EaiEt=6Q9+HY4Z<}qL*gz5Q z9_Gnl9*JlqaUM%@?iEjAzwq6i9q%rNhb>xfN-JTe>6VKk?vUMZVpZbKX z6LcSNf*)@KWI5qi9oP8plRY+{#hfkI9X_f-R-b$oOL)X==Hw&c+Z5<6VQ<59qy60& zfeeKkeAXi{lds9MCxK2f)asJdM&L51_DK#b0<|D7i{3s~=1M%kVphpe%6Q>NXSL^R z<_WycK9vk`J^*hKr&GU_jB4q)xtxec`+auR!n5%?xD+>i zDiM*y4e;OPNjr997qdUi&7A5eEr=DvDwEaRWT82J6x4H+NPOQF38Dc~2gnCkD12SstIfjuO(6=tMEsfa{ zR)TlXeb>H_H$Nu4sztw9fLCAaLZcB6?R2iXcjC*Rr3*`zr-sK?^b_CVMekGoJuvIj zovykUt~KA4f1+g5K3wJVDg32#Z~GW>iB_9_=G!H}bDq%Mr8>9yToB&rle?TJj4{3T zX|-&kuGx)d{xAhNcXM%cYg$KJAl9Y`{=8- za4vf~@oRC5#96k?Q5NzuNZlfphevDj(`G@CDBz#Vk7qnn37z$YE@E3}AL*Q(5OO4E zcK_OzUNGUbk>OrIZE*PPTDFWJv)pz1p?nT(4a+f+NUivjdz3#duW87wg)#J=!0iRP z7h^IyNlil_q*sB>)gB&4AN;-=-$y#izaZ^q6>Z3RVdPUQ;rXf7YSFNj*rr;_L69X; zvw%;0*p%u+dvQ37h-1Bxw-7%cmUsj|rb-Yb1jm1H}~_8}LzuIcEhzky6f z(MC?<)9Ohlt@~vNLUsiDP>G(HgIa*QSi7EVpj(pIG3vfTa?}~ytE_J>fEbtFMLDY` z<`-DnFb!p6`*Mk{k|ihpb&|yB+^@YHG2Se^V^cM0U2I?Z$=0-Q$49CdufX0)sDs=! ztz^|7*Agaj^_l*!AH-*z?dyu#+tLYr_vuP^O`owbZGEO0Rk307vHJc(2kiTI=#S%W zk-OTlmdW0Jo2}?7i#?g-wGADYHL^z=1nmZoJ_5G{@X>eS!w#6#Jmg>@G|@P@YZ6bP zPWJ4B*}2oI-9+e8nS~0ir*~&jN70LV(_YeE3pO1lBm%cj$&ElVU*`$lk)WB4<`gvK zPq}t#LMc(fhnDRM64F9kn2g$o_!T4Ei)Z)GPK%>Unx!N7kMnq@gwSP0@v#f|GM7wE z(Cjx^zV`HTXvqSTkkSqB^*Ap>Gx5S>N2Z>#-RRlg(3hCS6nv1I(&%Kbh11brPysK} zFA;ARE_f0;Ha^X(b;Pb?8-L*;Ud7n<@!JcBJy9+B;hW2| z-e<@bG9*EmjSn*HCi+{ccCDrZiZ*z$5EF8^>{7Qf@XU(`ipZB}(i;~m&e~^}l0Icz zV&3W}D5IWHS-Hud*e_)t1%vHSW`& z`xur@5jV1GWL2f(;~d@FOZ}UG_)2EyiRL<=t~vE40&g_G>mzVW0Dsqa(N}Mvr)7UD z@8x^?PA_Su2#ZuFDm~%8^Q4my+Gg>2Zoy97gyLvjsD*tHRqwW$;51n<%}^$~N(_Pn zCOZ?`$X7R^A@7GDaGygZfI;_sn?mTzmK6K%q;3-`EAzkGJCP$_5(XqhlO)k+F}C1X zOeGt$GgZXPSDJdU3q79Ep=iQpf4xVMu9U^py<490{JrnzS>F(_1AR^Elm}Or1%uN! zWY8m4lD|p-gDYK|Eoi(y(IhQlK6(mElCR_Lt#J@*y!LSqbR6wn+B^Oy>an@#^QHZgeleqK55s>49|Zlz65iF< zJ*|4_Ut*GC@t3_jwdB=_o&#I2$tIJ@j*@0^yN^E9XD~KRLZ-3DQ_Jauv5h0Q&cQPY zT_LBaHd`*m7bRbv_t&80w7P2~H~b@uK(CIE%;=lBZy5n+yhS!_&R>axkHt$%XCWc z`0=@?@73|c?UgccX--1;ZnYhgp5WL?-vBxvi^>3c3(3ifj_I8wC6-$F#Me%qxZBmM zv9k#yW$O58k%;3%uO0vRj;&)uXD^r*O^G+Z!1}OC8DH4@zxY`FOksdcfJCvZevQwL zUj0J%`;tsF>!P>~)gYiE7v2PcPrTflU@rlu% zXNV*V<3mijleFONI1Itx8OIaL z;c>haBlMHVX~$Oy)z1Erb4kXu&5?g4Co(2!p0;cJEB;bUY7AUR((s7|oqK>Y?EDs< zc<*V{SKZS-xRF2gX}=vGcLXvdZt$6pKu&&XjtL$}{9Hz~kXexX&!1`QMGL;tqM&M_ z3f_s|>?tguhSMTBEu&{4ySG?L2jQE2E3pZWe3uOY67o%Cv-_fs28D(0_)9p5v55l) zyE>WiD3f!`3ab3{OM9L4`D_QRCRX&tCBbT6$ru_kfWLW*Uee;<`?+rUfy<)ZT;IxK zye0wDZXvn^^z^0BQ=E@<3y3i z71JI{q(+Y2G<|Xj*uEbFZyLi(^4KgEeA~-q2Pyphk+<*EA z+%5tCr|*N`5epvX{f~&;f9+Dq%pmCPPr$XmPh6+ z+S7hIR_m#{l<;io&K4W@sC}GC%Y@voS?P%#J-t2_zexg#G*P+NPtI8PnuXW<-#Urx z7wy&q7}12647+1|R$eDkb-=ocL0Ol@cC*+0^79}|?H;9lcJ$tTN|wv9ud^E$0~W|U zU9+-@6?9_OdP-;Tj?+%L9Y6^?o8M1d++Q~fOwmS;y4_Am{c|x2u9B|MTO2AjiN~{S z39w=OujCf-1%PHITg20%P0jFkM5N6IgQssUHPhU z8KzoD>A6C;N3&^fHyZI~t8q0jw2mtn@AR*;K$fj zv0wPEOYHOTzV=n_h@6DwQtXCilEyco9iBNFlg7g(`4#W@n*R^NYCAiOrfV_0BEa>ka4%kZ)1W0!e0m_D5P?fCd3V2-=N*FXeJFi!T*B@?oMNML{k zvXX$5Eo+qorQ{#H3EK_zjhB4gUHFJ1b3Wu=0t+sgdmy`S_IEjS60xRZWog{8!Iv#5 z)S?0r=wzgQ;V(85;+AF_@G-`J*_&SD~tmf$?VJ@9k|3(+! zTPLb*gGjhP3H}nmKTG!W^hw^1SSx}Bu9I&&lJ3J4diLH2!-KBI0iJv&Ng)H2t!bz} zNxd$a=IGse`p%C4Jo?jkdk8L@WwG@Gp<_mjhh#|Whgdp(WJ{FUT)Tzn>JvLE-VaZo z==g-M#zT&?;67ygCHMA=^vFQVPO)(WrKg8WBR;`5xnfP$LooKPcIiz`Fzj`-0y z=jonc^wp1$&1W(8xevyMH=*6jA$oioKZgeXzAz2F<7(oJ3v%FxZsg8U---peX8S6) zDX)L8zM#6qd&!=4j9r(0Yk3S2cz6bT3|`!9d@us$M~g?@`)3BuncYkGIV%8+Ky$yk z`Dig2nJ|F`cP1WFEW8$LjJgjP`n9Z00z<~yjs{2qU6yw5+FS-Ke7;OLJ}X$fO-`kE zJ8G|_pk(#J+j6teZ~P``iC5Xqe*UE{0aXTb>{@^KzG-yE<5~c!)K9reTG?!&6blK~ zTpAr2AHL*!*Br$WPfh+oOE6{u8M@(}V?0=(SvWD(-eBF9e() z#4$_X)uIz_F{V!+UhJsF0K8(h2R`E;U)aQH$4Pc(eCQ)>RZlw_5?|%=@5C(CBTOUO|GD+s((5!y0J`Bz6_&6hQy9E3=`|Yi)wupIX zpx&#Ov)SV6q|QU1wV)BE{*@#Z7IeEHsrF)*f`#2B)!+N9Uk&2&BIwJ8J&T%0>wZG3 zb}HlnlTDR3IgRU`#Uj|g>S2N`?iPSb;zEzN6RRw?p&OZ4tVb?MSxizad*K1PPFDLU z(eMwBFXV~=CI@g_6jGK9rl}roFq!+PBlTg+##Z{r=9-+-V68>t>EJKF=u5)vCBx-d zmoz_@SklvrS5NG0>iCcJFo072tkV8;q{=uI}# zLsrM7^`o!;&e5MW>{!s&3opCylw3Bmf3evZqq4@=qL}>yc-05TFBN0t8q_(lHI{v} zY;v4(14ON0L8oV>(ar`kB_VuJZ@=#*Xmf6?a+R;qYrA9z9eX_5fjN)Rt+3YlV!W*P z4zBGhU(x1kO}Rn0UzcmoTDwy2?_!{(c=L6k z>4KDdP!Vu8o-zg|spHQj`KzC+5BF%fH9dj|+!DY?&`Dpdi55NgslDeqSHKjaG$;C$ z(bawJq19H4S#a=nMxMWJ{#pPxZV5>*{^*lLZcn4qvj>y*e)1p@za6r&F%xJnES-3| z#8`>UCd?#kck4yyXJW@+sZE5DKMNYX%apSlW|D);|5~&=5+?Od@GQV16AyZeJO3To zwFi@Z<6}cAV&=wp@OAI!0gz|0H3;#<{pGxR#R8`O-n+4HTTLoq2!Yqf*lklUdqRj$ z!tx^VXFFaWNnjo_u6D`L^ORpDaVwkS_c1TX?T2vU$bZc2&hrSBr1905=tYaHai^sFmOl1XoKqIhigVi8Q3+6a(TjCZZD)=Wlx{E0 zrHc;mDsk-{qxKEy`DW!%QXg1lw-R#_TTk0xP^X=(VNIWX}Xmj zdjxI?;A8K>H?ZHl0vt_oYaJfIeUP1&nJk7Dy(BN2f=4j1%v@>msD(8s6PSg5UAT@+ zDd3xXipd2;0mt_@C1XP^vSF||DbpqSsC&qA^fKb6B{=^H*#s-s4rQ3}7R(_>a%!?G z0i86JzUYEiey`$@WF^Ta`Ea!;L>N(2(ZTOZih{^n{VG;tD>~}S?-Z&YTrYO5H`Nlz z6clxNJ19w?7bi=c;b`=)5-B_ZSYK@GzhWU7>e;=zEO>olQRvH?on)>FE)jd+8+&}b zu(;xp`{Bfn5-4 z2=3TE44?3LUCzmY>og~&)jubeYS@O<(RN7o`{YebSD}1Nt9V|LJFy@@T-DduUlP3c z!5FP^N=N>^EsSqR8E-G*IHtySviLsZYPFd@W)AJ!+IypaToKUSH@HQhBCt+)5Sb(D z)5(lU!NPq$jj7Lsvga?M7rxA4CC5aQvIQ6pzmGOxah@k@)g>C5=Dl-pz+}eO;V)#q z+Ab{(c402TBrv5nBo=7!GP{`;>AqJdx`S)WsyX`3?bb$x&mG67RyK3t5k-+%N6%tgF`6M}V>`HWkoH&;si~fiy z9@1*}G_vrMQ=zFZROdj>QBQWc_`wcG36}(i&ceqjaUqk9{R$o$;{iQH=UBVOlCDM< zFFkEL*&!SHb92sWlWalasj#O!;ir!sl(M1ih~Nbz*gk`0yWQ}%mLcS|O$%GgLKPCe zTX;vtk*-wtxujT&auJm!N3#10_{x?pRBimL$~|9Y(`r;?EMhKl@`at^u!l+{_Q-XZj^z;5^5zz&}kB){$nl{~xTT03!qb^)-CJ>uC( zS8NVF7GBU_dJETbs&CWgp26vt5s$Cr@t)X+lD>w%w7qGm{)3+cgU{8LgJS8SsIi;>8=}$m%@6u4uoi1|l6(M;TFk4~ zU*wNjYgy}&eo@7Tp? z+@eVoM%_xUZBKv64t;RR{*g%zAAPRDssFFjj%^cTwoRE_@nOf%?RB9SuayT)*L&B# zed)2f=U3myqik3R_kNDNh2&UVX~k-d!Cudi=~j5O5x6CQkGAXH&hVO0w#mtfJdptl>p5oyd(U5ZDKs_*JvBxiOV(F zk_>hg@IjDvPmos#cPte~^Cc7*Bg3fPO>z+31r=QS}dyRH@ZpX(Jf!jTRkE_2vk+n`_ zPkny;ao^)-u`%%gi>b3Zx4YE>w$3@GvX^;@u}PrrM+@ET(uAufI!8d9iO?Ui@8z}7 z^)(Zs9Wj?OEv6f>bc_wEPUV8u_NAJUnq-{cs{p9$MXtCqHJn1W5 zd~kmyd%yC+6TlL?ylgnh6&C*cRHCLKG~!|x5W#Qdk1}_EB{|KdRS8_Hk%V-gyv~Co z?>xx^CaL?B+)z16%7K{B15xqJv0~_9kLYdhLKu>|?45QGHN4J^RJrn*e#;ZgslWSf zKUh=ojjn={O>V@eZ`+?fvPZ}NdJJqn zq^W?tx)RWZ-qB*szez4VKc&rOe|lFKp7BAOSVxktGpN|<&$~@+Yhv5y+sPIJ`kcJW zH@b%hEgd~()J{O>&<&r~lFgea&{QW5=pzFL&tpwbHfp z^KZQKw|%E&bkq*{Am89v<2(Jn#^nvzip2Qg+}O(oW3L!k!G)mw$BRT2O&!0G}2`g>x zeac*UoS03(^}3iO2(MApO#t6|{S*1zECteB=< z(#NLHzyGxS5&xQaLxauE)#pEWT5*AJ$yxiedd&+yuY1W;z46a0P#o(4nb4vGB`@`w z@cHil=Oq(Xg_MJncvK(1elH1VzrsfXCdraw;00_A`}U3O$w5?zo`zfOV)!Wr3; zMs_p-x(uO=fyfif$d))+C_SzG|FidYueNPzx!+iG%{kZFyGo3O7)!0Ht&#YNSK>tu zq6wsexr)bgB!a|X4*mfKLM}uFZ@e%B1TO@^e?TOHD5#uc&QbA74~a=kE@F-*exX&A zReP_s=3F0ne$U&U-rvz?A7jq7tG4X9_ju>*qkX;Kt@YO4(fY?gBKIy5C?OR+95kst z;{{ge0^mdUsmf4zTquvu1mS> zws{PzoqF^fuG1GI*(G(Tk3Wqgo@FT#3gBZrwU83%Igo&#j_R`tzUPPO`y!2HLcam% zgp33PHxN{T$$SX{!0&u}@DdsL72Ct}E;0`BhBm-3^%xntq<&80Q-5(#W8?=f<*s|$ zNNMjj1|PokGyV$RZN4ka@*xjrb?7pB{cU;Z@NsTOxD7x0gU9*D7puUmKfD=d^+kbx z-1m8SrEkM$D+Tx6+PKB2+ddYA>7&p62! z&}31&Wu`Da3oIy*X3}C3XE|a5rapYb2Ps)_n8aCh(S=C~&b0{WJ%d_Bp{*dVc$#)h zv=!7rBiTBlYIbZW6KF(-yj}$YPm&N0IIs6`SQlhMV}7y)IYFh4MVw#pAcRQ}5ZOhC zPY8%QZ7rDZ=)Ej?ry@+j2MB@*aLz?XmHR+k@FDNp{ z$$^g4^OwuPEO7qy5utNG8-bC#O0-yrT!N13uUG`H_eNf6;9Q7Jqc=i#>RqZ)o5H&}LhQoZDoCo^*@1$BPCXW1Ayi z9zs`AtItx`ZA2|>?>3-o=7!Mpbk-yIdwi$BsMBxdxAfTdBh>XJWs47Wob$Y0Ypc(; zXt19z3i$6f@SNO`y3b#yFJUqJv9Ud6@39A1OHc3t_W%>CCk-zQweV!;kBLBYQ0=M+ zFN$j2t+W>F!y zVK4@Lb2ZP;F2%9sk}&<9iqp6X>{=_4N7P1EqZtqz1W!_ zwpd0PR_(}b2L;MoaHt+v6I`>Hper)CZxSGE!z_H^vT(f{s&eX*(tprapi}`LI>X6< zf>OpJfeXGPuna9hUs+!Iv(Pa<(1#Qq0O;vwTyPgaw);#3=-|Lqyu3TC)cTG9y{uiw zq0bx9S6>bVRGwu=H&SfC4}2d{lHx1mcW|GND*7&SRLALZI(~5Q%`(5J zU(jRLp?FunZt2lwEPRK)^uwY4MfELOc%Z|q3wok2cB0cU*!NUnMiy!BOXR?=_-=Cz z?RM*__C9)mIqw7?a1UhCW0KCKLY{BZoYYJto@nF;FJNlx3kJW3%EX{`-wRss>#}K0 zLYY91xe`p|Gch@@PX{V0*Mi37JT2}*V#f$w>K?7yHSD}S8L1szz++PO0;2}nIKorS z#)B_#p%oW>31pxj)yrZHKL9;B2pE?gMU`LZ((={S^@5KL&$Vp>8M|)WKWMuKA7t6r zqJ=ZTA(JhDeR2?1`hTii%Z+^wOpm>NpMJChFx@m2e%bq`|gD<$p-;?Xmyk=HBRwgDM`^-{NzsyT2arG<1K}KWTm!4=|ZL z(uCk&bQnRO)}Gy^W(X#MOq>KCfG2a+vvhL#mT4xF1ydLcvmZn-ZM7YmjM%k7K9doA ze91$z43a!S(J07gO?XUtC6_i9NN8sOr*toT+R+nUOn@v%SH8cFfU+h;f;mJ!esu2k zcb;51xVuzPNSN|s1ajbAJ-aqTKW%DdOM?n5c>CT8)RknsR$m8Yy&3wr{mPz{YzcyXG+ZE zDQS8K9hpFUiJU%_!U@`-bGvZRFTnx!Mo)E-ajsutp?I<44BeqGI|@Jjj4`it88P}w ztot*UySOJWJB3CHA`AuaS%|A@`7GUPe7h1KTeCu`F$qJ}t4*p1xbL!PXo+Uk_v%lK z+yHja83%w>s;timf-3x+fC66N0Oixldx54CH^BOBG=cnz2AH;fWI{5#tRd}hI8zddv=foi{GWrWyD` zd}wSP3%)y_&Kvp6#WQ4l9P&5#9y5cm`@Hk-e8a2T>HO3oOW!v?cRr{5{qn%+9>Dw6 zU++#^oviFeus`GTnF&m@Dd%u5^)k8A#>C-8MrGQKPe#zEJo95V0guNi1zFHs7$5AI zFv;fO1P6Yj&5N<}u+KM5>Iek9*eYLv(YgQ*(j`f-vs5U9&d{^d<{dfxUfRXQxp{H< zkf0D?_X&FbcwodgZ10ob{X z5c()>WO?|-<>8m2RaFD({N-pUik$F60n1cMb*J}vG5DBduXPnr-doGbp+0V)54V7G zH7wDAF^6?V7{R{M_AIyXMM=Rql3C z<8ED1mt2{0)9~OkCgGcM2>C+C=sBjdxej}}giZtR-WL8njcjzG{}M+J01?&&l5zVHJ8OoiwHSJq2*MBu~3 z#e|iKhG31INfxaRkS35Lzb<&3)~xzwG${@ z+oSetwfUPo!o>Hfb^-lvKm~j+WIKT(!NIx8q(YH>T;{CF9sQa8U9Z`$NB-^-#>@9@~M9-fdNi9)#Td zZf<;rD0rh68#;b~M|BV2t-syN=YGA;*+WfHR)|2P0?biVKv%w#O0~d=j5c~D`?L7Q z_{b9?dc|+5x&h#$lUUow&JVsK6;x12&c0C@UzcQd0}0wohnMmT{E(?+$%Bm!6+lx0 z-^>e7W#mIMgZpt*n&*r#%31K!Y~8T~JyLlfUE6zZ&Ck4H6aI6XTv2^9WOeC%ur4KAKhY4dKGQ309x5>A58N$q;HZEu zJ5Qx60Rh39D5cCoiwR5nz%Y_AEBLx2lBW0%yq+8MQv#Gj{(VR4}kzCh5& zkM!UQe0T`sr4&QA3q@>xXQFx32Xxm`@=Vd8)G-YXQt_Vf@htZ4Wa4$n}{?!?fmu{S^@ogz=Nuc zd*-R=(9rj?H~2R_kNIYg$t{I$=PjsizM<0~LLclI)8}1SEjY(`hVO#hGKc6Iin8@3 z{Vx9Ar#qGIy9Z7I;C=7G1NtwMj3ym|0fMdo69yA3HB3mk_b-7NPhIL2c3xDTD9~Xy zkX@YY?s@k@gyy)i_2Suz5m%`iXhSv=4%7=SZEk3@cTpLiHgM6EAj-RH#cl8#$UPDA zy7NNA&{sSVMeyb;b?_Ww!6z8FoUi_~+dMW1c^PvH&~G?1xi@ zjSp1DZn?+-XK+bT&;A!aW0*06Zf--rp+Eh`>rt=)Nja$RFwk9vUWM5)(5dR-Q9h}5 zYVlj@4h1;K09Wd6Lgx=cbIm6HRwXpdRras!PMNMM?YF45>#zr%@l|w=j-4WQ_qtdW>>K2GtYJg7BAeWnFKpXr$b4eP`iR~%!-{cySHMQbQC(5FD;49h^vD1G)Ib;8 zFl?JSLU)1>h6hdo;0L20_pIRLB@kdDVe(>PAO%R7WY}RkAG5Tq7 zdF+15>^#~tLHBNOA4(7l5OScWv-R(?M*w=<5gbrzrpNERz?ofN>gs)hvPDj?S=b_; z$j4t42>j5S0s&0-`1e9klG&>MsdzU>VUHR1X6dm-+B(zXer z#b-PHvP}g|t6w`l(y_zBTZ3&8>&~A#>w}_q0P_$Y=p1wK65bu}4s1tXl+K+muAJR* zjCaTPP?qo+-@bA0t(tkaUxM($jK5-){~yTzoj3h$yYJ@0g`LkkmAcMLR8(j}jTvFMgX-*nPYxX5GIO`6tDk@D0r*$uKiapomHE?h#}MpD`5P*nup7 zzztsqQlB*STPdQTbr2|o^36?5*moJhux>*SzW8(oe2#A5`xpq|Mi=`~V`}D!FViiw1%H;odCPec`RL8j+BA&AzNYSldmvMYy7za`(goryan1(owIYCX+%I4IX&)+M-G( z111_4LQZPVVFCxr1cdDVF)4BLIu9Fg-yaJZivSO4@RC+;4a-7G3O;-tVvI{T^V|?T zCMb@1A+K2ot!GN;OgM^* znHCB1&;~h|dM(QZzu$}RuJZ|xUWLkP*mzgRQkcH z%qpJr4dX0h9NYLJz~8$C`&@z?xXW7(aEH?f7&w5Rm`d*BoR z-v2(_v|!8`K7+k0p_zi4@wq{tCw|#^U{UdJ%nlAubblKQ2sg0<>_%`8Aa(5g@pP~+ z#j1@-LDPpOh?*RkC>$t?#tRXC=^FyWQ%Rf`@h{5-A8L4fs2KOaUA13eSu)p+`s1)L{(0fI+lp@;ABQ_9ZY zGyNh5GT(Tk-Wm8zzo$$v$Z>ulU&=RE!g;KAKiDy5d3d2-**~n2E<_Lb4cU1G4e|p_ z)&y?^83dwCxa>H+7!L*D3j%id19Sm0u${~K>=^n!K<-ndPIlp?C;ApZ@J`>=?Euwp zG%n>uceUw{dIFF~JngIeQ@%+E@-PtVckIM(4(!E`{^b%dziV85QsblgZC$+JC9>*Y zr93=B|By1?s=fMJL#Kqfc6SV^)DX%YB^eZNz2l`S5pK+YvE`cvHFxIzlsNdZ`13$VXg@?rXfH#md zIQYc+(qR*beDr$Rh0pZA2k3)tGv6S^|0&NYeF1&CbE5|= z-Bz#(?C{HQ+rj|e-B#pm=?=k+yD(`P^!IruK^rb;n1{2BY4|W!ka?TWJ139PF>Yr% z>n7gEY=jqMqWiM*KjrVY2TlRt{qDb8wI`TkqT@9%&-FBGCV{v0bngtbF)3UxGXc97y8?#yM5)$Om^ng`(0J}!;dLl-?aX$?sC1`l^^tyJgJmId) z9b_r^Krcg@RAy3o`|YdUBfZr5xp1C}|3}_@WS!r6=Sl%Wf)Ij1cEuEcVVIb~4!=}p zG0(3XG)Ev%fA)O5||M{vZ%6jBL9_m@k*H}=!Jav?Tt4sbl>2^-BSgQ>?ji4 zaX;bX#}|HzI40RHeK>#--XmR(e<)n^0N{y8`hv^TcCci`72v$1)%4l5F4t=(mj%qG zi3XgHC}6e!RG>_rz}CTr^1K8aStWE{3mFwe%HvWcvMX!V!h>>91?b zZiAjcxa>tEFNW+TnwiBdAK=wuxzQ-B3gSu*!vtKwBT40j=cva|p&^iF5w||3DnIgi zr8C{9$dIg_p`OM5m3QNHS_o?KC)Z)&DIA}Vy|Lx-?NF)JmcH~Mw6rJfNXTGJ9OK{d zxAI$j!MiJOe2Bki9S-Tdr2{Owt-%?yK#H3wbofyJ?+O@`jC;PU^uY3UnEBpo5p4D2 zZG7xM5ppig@H#%6X;0-3h6hdo;0L204_e`cN#{O+mo}|@In8q_H^{4=g)viuYCOsC zdKM-r@G^vq4cEbEET(cyB!czr- zo~$L0-8*o(#K>+Q?X)qW0)C=ad>jy|%)NmRwewY%9z{nWY8_Bm2qJ`!gFaR8dK(8k z(!q|^sQ_y@SKj2#)p1}fiV)urC8K8|Ub@<%&Q=xyk$L-!3RNWvk zUH^b5=cAIN0Nxf*--EL)JihR}kS)DUDlR*(y}rvp=dFMX9O?nfo_M=q`lvpu%J5Af z)#Vdl(f^#cGl17^rF|~XG%4Q|FZey>T%iBq;V(YD@s9b}4391F_|XUF*%shGe9m3m zGfL;(ecAa0CqD0Or~Li*fQIM^J`^6%yz7NmXLKz}EFLv!FeTTtT%I7$q`?Hn#88VX zb+y=08T>t3W{VA|psN}{i5}FD_av!^*#XXh;4|+Ui(fd<)N-q6^E><$6Gbo7jE#m)Wre7 z3mybRRB>4!C_h+Om8o;C(w?W9wTNIQlLxZlLGa@?F~>)^i!o%c(XP7kD+~3yQfD0c zQkfXk7Y#-Qv~Vw=yvo9-X&LQ8kQg83yAg1R2;Wc_D1F646&`N`C+%|@`UG*|MSWyK zLz$pcL)n+hsRNe--$X8fC%DuB&^S;~p8m;5a^uEF_>pb_eU4rM`XRwr>So%U^Gmxj zH*mx^=U(vU6dG{g*L47|Y%Zl|-ZLM{#cQ;PtOr8f#`GbWhiskiM;%;`CbNz+Z|v)O zbY{?EFEI0&X_#9%W-t#8l1|_I3GUc_2%y7fGYWdc=dOK;z9;zLd0=D6eejGtStJi+ zj?j6`g3Ch0aR`_&94Kg#VD}J6-Hlm2Od=!Y11Vy=>;wh`1$o~alN$Bx5(1e3eKWu4 zc_Q~6UH*m7BktGJ?iyuuBhccVY(x<3*fGiZ((lmc#klvc>p&AY9E2Y1K4$WUj}ImI zE`Q4lid6%w0c1_A=uez;rF#VlBr71*C1dFde|9gy;nJ}0{S%M)278l-HxjG{m0h9H zM)1WwZxDgY4if!^?b#iu1sUrKBE#HOiM{a&w1=SZN)vElryG14kq)_O2#j{v;c%|k~ZvbJ>YI?XH@1Dyud7=K$qV2z2D1GMl4A|pPm z+WpVq^jhjX4%JT`kUyr}rP_TtE3vemGWXd7>h2SKC_JDUf(4p?mTdBwM7Hc_daFgc z7Bg_DW70TASd-Z64J(49dg(DzBA1Csn(DCL)g;lSHxnM0eIIk5on|Z+knAcESkX=p zC~a$!bV_OE@51n;3MjCK!YvdlL8)tgAZjc>w-nS!HA5>qM#aC=06Ofu6!n$@8?qmydc1u9vsZDf&;1;}Q+&OtyZXa~TD7l7$Ll#eacryt25 zgQ8!3zUGcmm9AiPT`0pZdhY3io**0m=zL(}i;Zfdk0W zN3AMNH&Spo7(3~ws$2QpAlj%%|8)Ot@rE@1++cI6y2l>SseXbFiwBqEU>{X~h@Wp*-$bwmPWcP-hGQZHbnwHCcEaE);!6jh- zCa}tv{CtVvneHV_FbEz{Y2{rpeGstuQm^Wf?;vi_c2sN&PX~;YJA(53Qb=s#awZck zm!+BT*(Kz%Fg&;%TtQF;cwvM5JQb~M`Cv%d^sOt`#RGlxEQuc^$N~Xx_#zLpdPWX^pAM8+}>?<1x9Pu&s@;uUDXP(IOp%OgMnUn)O$_r2_DBGkPgpx;@JgwmS z+)zEcmV;#Yk)58RXMqn?kXW>JPT{-i3q}J$#SHYN#ZL{?^_`_LltXb!AeRJrP^ zHaMF|E4rFjF4&6*<( z{nT7$)}4lm_>uhFr}Xbu--8PrYb%UnpN!E8=rdN1VV~MQI3CcjI>Cp+1I&RsNNQ1K zDmx5J1cg^AlT+ULmH-H9CZ2Wj$s#<>jzf%bCz0W`20Un3K!C;1u|-BEY06*`=yBmfE=5XK$8g+%beAYrUYT;!$`WX1Rd<~v2 z2M>kOjaSFO(>s1j_3s0p`qGrj0Ce073E-0oWC`53lwEq!HqaM7@TSfiRJ2D1bs|J- z)TtdUa8Y1fdZm$~Xq;6ZTqOoP%fWa+2Yl{~>c9ye)q6pXh7e z2L~m*uEsbt1lH!I4Sie?U-g|_H| zN@FN5WF3F0RL1Ag2LFyj9`nMJ{4xe;YsmOx@ySFNv^`xqu@K7F!K~C{d*C74!B0c! zV>s2wpns0R9^VZ_$hUZRRQqMIVaW)k=ZgY;&@0e=NL|+_I9n-WZyl?JG4tM{JJsEP z51gI?zW;rAs|B8TbcXvLBVlJ3Xqi)lPz&_Ribae`fQi8YgytUyAwuya22&vOlF9@# z>}oA_&ID1rVA_h|H8G9Ed3JsXc96qsQV4=_i4A_d;>DL#H9PWf1p>HN?+age=H0aG zr&kVKcpVGD1@Pkfxt?HD9s>jw+{mUO2U)yck4Y1Z=fdY;7xCo_)v40=18Vh&E?%`@ z20=wcFfKfJkr!cfV8`o)4rIaOrS4n&hc7(cz47LyFJB{_wigPL2n_M-lP9{55%$8r zmOkjgCGA&=?5^u^W6Lm7K7>P1#zK}|Ox{dW!2M*p?=Vm1O3!+&MBQ)n?7DW|kY`;a zkXlR<9u=^RFBL<7 zNHk1VfR0krxz4Xvv10E9M6G%+yU0~7I(ZCtnS0o40bHP|S{387<`RwbTX->C4&fle zeiD!LDeM_r9cEq1_Y;mi$9Y>keJZFhu`=74f0xzs;nC|(`TOgEQvi5>`|i$~Gug1H zKG*xGnC$%e37yF-Vw9O6_IAVu=lzLdom^OS!3Q!KavvL)IiKo*2PTPXTZ19Wyz9@u ztDD)&SS6bWB~YZE;2m`0!vhm;82y`v=T#R4z0#DzO9)j|T@T99{k`5$17CoqPaH>`Z8!-v(!Zq!G$l?{vm z%DzG?Ui4Ev30yDxCSW1Jfwj9=?byshgdZIAsNtCcWN0&fym)}CNQPmr5%xT=YT~avbamk35j^h_0^E2je{8ok&Rm z4;pajLu~ayn=%BxTYx{%5}Uz`pTOk-5bAyJ7XIY;EUD8>A;Z9Z@OrKeL@ zzWlP?Hys;3^yQW=k>Bm4j&sIST?}drX=gyvEr82PJ1Qs{+peeL1ozql|0n@q7OQw_ zYa*L*7=fqp6_0&!Da(%oCeJR#3x9L6XOf8jy(p?4{M6l$o>@W-!FizF6DEzCB&(i9 zlI1l04Not!tc;yjbkH)f`zPJpDjwhuJs1m?#VX3|qXWK7NPgmX(2#H`w+DZb4?UM@ zNquQ`#C;Cn%yKmhc@7f8S2St0kA{2(DP_w*H5Oo*XIhmjD6C7m;GA)JcgTOJEkg7m zz$GwdvE!YAED-E^77qm+nzdVeiv?lI{hyY9Q$z8;?oCXw-LL+_shaZ zdj&X{P<&Zn5)@^u=wi0%xa3)jUM=qAU+7DQ7dX)+7{hM!5x#>=*&H?ki>0559;D~eA&T$ zCl2uL5dC{y&)?SWu`z7#bjcs0ryj6A$}@i8M{Aukif+}G$0;mR&r3NMa%di>HKGU z%Cz?b-R}y043-X60}lrau+rfG%`3g+$sgeEiBWk0HPnvdz8=A^fI)$Ue8pvP0^$mc zxqpz*tAKWn05bg^zOl$qZ=IET!5oV(b*NK)4vrR8E|n_7rD1o&5JG~M_2g?UN-V(9 zoFE2%eNjGFnGl3}E{#S9KW$uIbN}Z-8Sk12Kl%{(u*lHALk%xN*Z_dXZXSH2ha1`l zzDz$0&GK5a{lUTpJ#5SF(xKz^JR5_407U%2M<4U%LjbQU^%wR0jLR1lm+T4>dOdmTJ;qAfqR&t%)l13_ zExI3rt=8Bd{=FPt*vbK5Bl^YW;LIt(3;qkg-cCL3Tae(Uw^7GfYp2@Myv3h$wE}I% zYV{9#GoI6@3j<}gc%(1EqrKbG@yT!b!sB2b2wmugTxb}VfO!)9rJ|}&pC3REyr(;W zOv2aK*ZR4xw{>~znHI7a`d!sGc3<{oU#3f3^~5GV1@H5p|NQQqciz#7!V7`Vjq~{N zW1oBEs_9Z0PFuS57dUPfBnAX^$3LFOw!pFu#KwJ2M z7S=P(QU*u5ls@t?5gdBy@1-VD0wVa~~h<%o4`t3+v^_2Ae=Wqu=tbRTNrba1E!aNrFZw((Pel##)2YomEo zqn*BH2bLg;yC6D%Cyy`qY1?0zZzvQrr^|Vd=mFSZ-ySCox@~3*n3q!MJ5Y4cbtGuW zFZV3L(K619A2x+A{f#{RkGW};Mjhw;A#kvyMtnePw};6`Gl`ZPPqGeJQkPkGXhnbc zCV5S8Jg!j-^s2I|YsW_!7N`ys2`aWAyMJ44TXm=f|A=6kb6K;OcaK2ef9Q|iGuRf@ z`*N=u!3}=L&4PlD{7qd8GR(>2s|uiyUoyhOBAD~&Nji0?c z(=mQ&EAgzpLSQpyGp9vmWwilbVaPQHJGBzWJ z`wQ9K@`!k)Uo#Q?r5IG8R=Z*7#DVSer1D%s;|utahnxL~A_8)!zYbzH*6aspbsW#1iOo<8L)61sWeM*=?drkyf!3EKGAri#Z9 zdF0WC9P&JvQ@bwWsK8HG{0#&r9Ypf3fWBe;@?~HX4pf619eN-jR`um;gDzt>P3Q~{ z=&=<*m*lIA4?|HtF`_;?UFv$;`A~0LRms?<57XZHhn}{XKXhBTq3J2MVGCo_Ux+qr z?fAFlszS>5Awwfm-T`X=uH5(Kg<2ry~>-QWG)?pJ^HS9iboi@&)0j_>%6-GB2h{>AR2 zAN}a=XMW~qcEA7ozpoqOm&X|oYPC)y2T?xU4VggLV z(8icPM*CFjMGuzg4<;_2PIaIm*Z& zKf5*MA8HjSpc7d^>0fo}Hx@fw6x(18WD%i^-0GXc!xk=u+9n|k63JS}A^d1(XT(96 z+B_zeMxTJJ+H?PjJz* z^j-rcGu4L!JmGQ49Nk#d(GQ*LT&uo-Pj-&nrv5Ol@Sx!PM|>IHubbine0^6Sh+^ym z@lTc3Pjo#5$Vxk@`=H^ctG@8)RUch=4Ur$pX)4h- zoR^G&&wcJ6cK_G^`KP=8^?&)dyTAPZ{?fbh-B!-k*U>$;9`bqDn|yTlj%yPXKQ^^Z z$~X!Q74%c|U1(+^Q{Mc55B%`Qf$#Y@iB2`|YY)s{*1x36a+&wrzU|v~pZe6NG;k^y z{M_e0=M$+W)Car2{L8=G{qisW^6vY-@B4N?{KG%I`@|Ye(Se> zYxk|+`mMWf_=ayds#nHu7O11hAHqg_?RU3n)?nGI37`ic-6_-;4o~~Wx6I{C7)%1s zbgjxkkt*2zpe-_>sY{T$l+Tl|`s30+JAl`s<4M=NC>UN98^KeMgm)h=A*Ts(eb_we%4yx8)>7r;Zk)+M%#D%T_C z)l1{5jfet53$ZM^=4`}rJji77S_z=?AAhVD`1iCB@E4jck9%D}m5@t&`Q za;v~t_z9M?C_!kSo1#84UcEa=uoybw(*FQ@j;wV@BcR6A=ttGr$3k9htuaSE`YxAp zrBiU=W8X;%b%1YqMqBAl0gy-bdgaNo-lQ9dfeKzVj!8usus8ZsIqAo+4bXoB9ylqwJ zlU36OjlA zFgq}={O-Wmsm8KHc8TWI^Jk+*JYUwk18s#BR1>KV0=vLV(GVC{0EoXvo0NU<@Lc|Y z&d#(iZL02jJ%^R_wU5P*_xWX-=8`ZIaO`#9qk^n74}w^p8qT8sSigCE=IBZGu$W4m z7aUzmd-RClK=+Xm{91qMW21Em_gwyvFDWDMiGuL@nLNF!M)x4{Di~Gky@;g?I4^Xm zm;MVlD*>?K%f!Xmx!G$|)?)#!3GXsyLf3hqgD>++4?_C#88WzBTS2FF53y2T!j!En zJot%&McVhDLa8#kWd{xV1Zl9zTmTNZ0PV?>Qq56eb0I+&9B2S|6b=RcN56`s`jjt3 z?60uwRDe=~o|)OVQ6X`6Z5wn6Lu7k8fzA$S+*7CrhrdGgNgU;XaC-2M0e z-G95s^|PP(J8f`$a`*M$@E@pNJvZ4BX-2NF9kW7H;n^5n_xZ~o?Q zb|3%v$9G@zHD9wl7()BUKK3!a==TeLIAqJS1b%<`hkv;Hz2Eyi;}ICJ@c+hd{DyZE zw`e}>b-14s*bAVX!8yzhO?}+-POVW)YNBBQZYbRA$3z9sN|m7?V3DUUh|B1g<^DAo zsEu2Hd>^991bGBF=Isx&*!zHMkro2_kV~I4zAPEOG%RT?XjP>=`YGUx&LCDGr&N{f z`a$73+rUeYWv6U-@bJQVd*)--v>+4{ciO#gqcXw;=!784R34x6$`=9}Jn44hl^xLF zGw;F-9v7Di5b+P<^tTW2Kv!y!RjnlKwj#G=*Wy7deEb?5$$<`1(<{S-?!^FED!8nQ zE6FEMkjQQqL7eeKTTchq)4l|S914LDwFv}#A~!$A7V=Rb!QB>7=~oL8o@4h9KG5P* z>@|*3@&RnM{lY~5$bbeQP^@6IzNpNBCp23CUs#|A`Z$;qA|n8;7(W2dYp0JXL)U|0 zo}gw&tZYc0;1=Wxa?47n3*_ECu#OU&`p5=pt=l7Up=_wj?p)pvw5+SJ6B*WNASDo? z4L%$*bUk|hF8pU+8p?*%o>gG#K=61k)aA4Eul~i)4qgVi`6@r_v=C33&;0%0?f#Gd z?N40$@sEFv?%{o+FI(5UfAeqt_3qF9?9X;z`*ok(U0mwH##OzA1A2J(bIVx+%f4JF zV6!s9=e|dAt!kLn2Q%yLo5sp?@yi_Cg(<$Vzc!o`zVJA~{rA8)z2196m<%}x+;R^f zyEp`a?D{==^hlF*sRQ06m(Db*=iQyIX(m|c*iGRGkB;}D&&!XT%b7ozEI9d7W;e;} zS925#8#MUXmlrh&F@X{Qu+WEE&93+2MnR0SD8i0BeF7f>9Aqc>d!a23`k3+!1t1Q9 zBl`3=)!v=6ynzJc#iFWn4PRF$C^Di5$sJ>Ep#Wb8JA+Bc34|Dg3ke zfvdR10b=?VewHu7S|Cdf>JzNlTz!D!hci?KKko0#y@8X+y&^op=an$trLmlWB3*D8 z;_Cze06+jqL_t(PcHK}sC~9>3D7z${*n)Zi+oSplKhd{*ojxJ8ui&R6J?L>OCi^nN zbvp&u0pFs)8pOg6{(Y>%1#K5uYQI!RtnbFSXj~WX`Parc=p?7%a^9II;MCbYm^xWbzi9JHXKU7 zl#i-U4=L0AxYd_@nWlaVdcUUK=M{Y;pF_s^(P97W=`G3&H|H1hC-~rc;62{~jO%Jb z*8N8c^mxq+K)^=u$17sEbW4Ch9k>LE1cAW~pQO-z&-Z-Kj!VV0bHWRCuN+AJ{ont6 z&`v2H&=e|rvS@39gUO1$b0Va}K;A%mpE<6!ryhYYB zuY$Hf?b0p9%Amkd0)Be{ztLU++X&oxfYfO+xqDX=E8#6&xS!8$EB{3nyu^dczXXiN z(`?D^W)VvX(Xy*(P?2$3>+E;#-9(l-n=cbH zzUB2A#$|?wnRKc?DfyPI4}vh76SN^`p!>2WJXp+>h@PYRkRSzDA)j3`?g7jblki00 zYIio`mX!WQPA<(t5`c~%le$9_k!|G0eDNVD;tL3L;R8GPmoDf^sdU07%7s7jGOoUW z)Ody1I-0C#&EUufSlEM)@DFlqpX$+rKm3K<_>?+=Z)DM0x|N?R5G437p<=PL!$Sm{ zKtG{>;WHjK(UwZsAiX>$8_WQm%3qeXU{{^L1hl%)1lM0aXh)X;T}J9iEqREy&Z?tN zj{!D;n=cQ0f*PS^>f~GW5)GoFFa6WuHecB%LpGEj``B0RzWv+3!z}(v_pJxM@B9Aq z-6!ArdSAVYu4!BP1qQ>{X}gi4EU>Spt73x-2R>$>Q)UbTukC7BS&*aCwR#58$4_ullO5@`E6M{nvl(`?|7=$J4_+MDmf3eB`Ju zyjL*5P7^d)1XBN@PdTZX0hSZ`zytsehZY2G^k)iTkt=@^L}pT{X@NG5df{(*IlFy4 z#moI}7Z=?6U-BKS`1y-c#*6l7gSt;jmgx${4XyB~h0_I9GM)frs>yiZa7o#);DBc> zln{i;z_xNJ)G@DDug1^HAxHPP390z-o(^O|Q>s@AhIL@7l|I}Tr}C>8+?y!;g-3|M zDL)c!q4NtpkP@9=o#_jZfst9etsAEQkRDx^71$VyNNs@4WJHu<6CxX zc`)OV>S)ViLOTzX#HUD<8x1VV1SPO1kFnshAON`cQphZ-@S}|;f(88#?JLiF5E&!1 zU7*;~s_X!v9EI@aK2d&Km={4KhT3x)FN=AYxEPJi}@0}|y`hnS?$`6b$DAYOhLM%g(ifhGYs`D0)ow0GNW;rg^d z`3XE`H|jyN-bziYlmH=l+Gm|%GY4DX0X3E?k2%QoU{yYRlNQ#%9cUT5y)F5<&HQ0D zBG{R4{JCYeX@&60w^%3@66?(O{wM$O?&to8|8e)bzx%JWR$c4fzpvl@(;xWfyRZKE z*GdhjI9W&w;ydgfYNTngHx;uVQ-7Cq%jfaOrhQV;zGv_W@C|sB;upTi9vUwuI(>W~ zJn)_efb4p3u**lvE*&p?rp#qu?*HRS-#_?+Kk&mJU-xxi=l2Ej-awup{@SnQ zxW`dG+^ss3S@bd)WYH((tjB)7 z%~<#VEQ;jKPi-vDT-E?;jG$jMQJr|!!c^m@bQQgy!Y$lf8co0#`S5!+p4u&KN)8IX zl28IuF{(=PXh&Hz&~a1%h)o!!sFj(~0iDYFFWqF576MPEw7ud%5gN_XavoefDmh~{ zc&R|`m3GlyvExVZCqF=Q{ZbF72oq8QS_2}Lk537zDL;_P*ZMGRVfu?zJt17Qe(xYN zJ0QmCqv$Owed+3%R;EiyWwBFt6}s^0d+)ZX#`XzESY8wy_>6jVyV60Rf;a+B2Q6x6 zjBu&Zmw#=)!y?;>AiGL5q$nwomNnF%(zrF&6o4v-Lw3d#i&Sv3(@MMP)20;vzIciD z@+W#I$ESIz4f*I?-d7@^&Q(>s@fp`Hf#0Y=SN`Y)_&azMIcA(-Dp5txj~zq&UZ zC(nI?XXgs=FhaoR;!EM5T|RbD>6KGuIY@`}*GhW!NITp01deIo4L$xkdst6B!?VNN zU%1kZ=C#ZCKo2snvJ_2peuBg zYoRBIDw})I1w8;>fGUa{s7qi@@QZ(V5|}*kM`);L*AF1?v823pP_-{{%A3flVAQDQ zPg@7*g=yT>myN}rItMuNz5cBOE#Q={^%CmP&MEu>db@hH=Oz8AM6Zwb0X-Igwg$iSWbaR~QRe}6pio(F(`@fZK^ z?iYUH7xez5U)z21lb`g7^AkVu6T5Hz=5OBp_>cei?)$(0`*%P1gFond{(k$nf7>sF z{`PPG_T5ka^iS`;`@6r}mvrxsJMW>UWAd3bXOi@Uriq4=pUD!`OjOK2UR+hnqy$u5 z<+naV126aknXG9ugTad;U>c=aFp){VWE-WBM%IOeS?L@a4Dh8v76ao90jkf=A2-^) z(r%pLp(CR(ae({a{K6A|F3FPCCFPZ+9R>q-6$P)B7oQItR#n---%ABYsKWh!4h&3z zzq1260#B1fX_F63@>Ngl!XoBN@47^scLuTmJHQbd?ggDPe&pzZcX1*Z#m9??CBvFo zfzy6tN{g=-it1~E8g{XerL4do~=7mjhu;ob$?1n{nW3S86S+wBLe;LPUxN2E?ga#RDLpH%HLm=k?J}JLQw;D3V z;J|13|3IUvk&A!Qe;!w=BbcyU#{UMOBP|{)Q#-uoU<5s|0kDk{oFEDvW}3ph`3bK3 zK*}YJ?l-abYi6CGBX9-6x8qPB9mxY_L(x=Cea>`g%Xu^NKZL*1t#+bfd_@0n^KjpN zqkZN_IeiqKJq^EJH|K*x`Z~V0U)z|P`JT%6(*y5m0LcA(T*m$Rpa1#Y&;8ub?Rki8 z^DqDMFZa#wT;~0;AN#T05B<;&`947I*I$SfS_F+BHY}bG>(tZ?NnxC6KFSM~w#X`Vvyhm2?BXkf*rhZdD!@R0K`uV^NJW>^eb6s=RCna zRz}UVHR+1Cux!iF2^pLtETsH~Fgt?;e!N5)FgMziXSX4{T5jC?C=cOJ0usMKTYko7 z7H0Yok(7BQj~R-j7VSMoE|{A>&>LLqG0>>WyY8?j@e1|o2KTLhNdeMED{XA2{RXa( z;qS#%WgKHa36J|3>kCM6&!t~>&CAE38! z#m9Z3)V%aTdI&goIFDG!?F02a!7hLFUN*taOM2!0KV*QHg&2jAe;YVp5K;o28Gqq7 z8VKm<_PKthn}4r&ZtvwDU{a3{u@=CD$dXC70yyE9^j4w?fic4Po`Wd(y;l&uXa2k* zh`z-q9fD5^;3Lk1u4A2(Yam^i>u0Qi76|PzpBHXXGQJ2TXI)ka+qq->w<%7w_rU}2 zX#mJz`^ZP$)bYuqzF=`9;Nv*KKcWXTCuE_^q!j5aGQKZt>=t-J18K}aUc8tUUIQTI z!38b?LRyQRCOcnhKF)~Ay#ktq97B;~WW%VvMb$Qlmu6?bN`@I%c>*?$Jo)R(#KI*Q zbTB7{9oPw%mqN3<=XV2+py2`c^)ch4r!E_#t9fxxq3tbSxn8`$XZMe>&+gw#9yAfu z1064R=X$4Df>ZOP@rb`!=h*SP(65Z}fC#_?BOF)0cd!B!`qhDh@Q?PM+P!Nh`?%~H zz!qLNbIDFAg#lzyFAEcP66hybDcnX7Lg-k`^zZi!N*0SEzmp8mJ!uQy6u0(hH2AX#fFh<5HeSdr44%6rt zX8;50*b(kqIB7ej@0|yj59WygX-p=W2>Ev1Ck_HCCS%qv@G_^YQ_Ep}S$qK|Y(Q*o z1!E$wBP&n6pJdI9b%+zVrX9lA{R70HtUwO}I(;7kR}W`AP=LdOAbFVNEDwN)$bp~n zbbp||AXexw9O?WhGp;R4DLLB!?XVv|_~+@2rFQwpFKdQQczNI9ZEm7HzU9|bxR)?H zhO}L9AE1Ixc5rD!7Xp%@-jLoB5uxIIxeQ+H0CJG;fG?InM!F{$3=YAm7g7neuHuh> z@Bw2D-=O2A@L~)4G4|B7d&E7C1kNbWaR8u!C;Z@_l=|o6X=%nZ26)j_9(e?2$TGb? zNGV(10a@_SzajQR2jpHpg4YDFS3Cq%&9;dwx>CnM{x*PrWNNU@k;OqA7IhF>CojJ;$?dq4S3MSPV$j4^8knT zjz8m2hQ9AY1}8eFObV|pNIfb1QVuS@gWp`wl(U5o9l`gZw(w=_asJ|O0RDYE&hiTD z^m(5>@Sg4f;uuc$yTD!X?!xPYb4L%TYqlm5sOdGniDrrLI5eWDIJ5D+gx+e3CW>BAD6Ma(`i`?3YQ$ z0S$P@&PN4vDItf&s%|f+OI^~)vS5VFe897w{4P6)y6P1x(oSt0gTlsS>_ygIYTsd# zC73ot(~GB&Sr8qB2p4}Ps6h@poRAWTGtSCpHK_8CTnEHL;XE17_6S?{4}NIE@S#60 z#TTCV&|jnw8fbZN=(EBJ!hQ_nc;;*UMMSpo2gdLwg z^cb9+gscF00+B69K#E^((5NDHq=#%|jIzr}5H`z!W;PgJ=#Afw1xS&-rFXA8ghxGn zkB#|a-Ra1qJ0k%#t&hg#7QY0nGd<-k{A2Z<2ejR1hj?|GQ~rK?;5`oj@3(tCAlhqX zU}E;4W*8+lr6e!V3QXBeWJk{YgvU#wm6!%O z=$XZel)kU0l<~qo&<-c)k&k}xa9}o2>(>zQ-x#abdY?~9@W;~Fn|kDotL>?>Po!DPYWvp>ny z)Z17K0eluKCNdV%$_sPMO=7VCc`r;$&CQG-a1b-_YPYb0P!`+l9%fPO)W}PF>Kzbj zCgy#2z)%UJT*t#4Hqx^-tv0vk&68U46#=1wIB06|Cy>Io1bn<>5W}jDSGw>5X@H=H zF9YjzJFHlll0P>$CepT5xv~~ ztr1k@#a7bfgXZ7~oKzf1Xa0v!@d^Ez0Jh^He_Z8Xs`tGBZRr_ZxAm?*aa%ZHMDLK) zw-kFhFEUnJle4{lsOY+MScij#-EBoc&bXR-OciTRso{DZPIl z7^~9#Q~adyYj{ADL;^V`FeZTj`2=oET)hpPS{TO+KIQ`Bg+WW#siIZ3EbTmndZE`~ zWRgTLCYHM`5i2v6OD>Nt;Mr3W*j-zU7{>BI0d$+&@)r- z@ld_d8x3>-JoSf-;j#LxY%jc~zbe#H_|6-{ALg?bZ6A`nOE6?DWz{Fp#-}V2cJE?z znc^K?={NJX3gTg1hRlw`0$?+T*`Nd$n+<9s=RnUv>Kg17!h%-l!beBk1tCF5jS0%U zSi1Pq99_sC1M?Cyfj z!P5Fa(3gd3rZ4I!%K9wZ2Ln~1V`PI7ep$HT9odCjeCAK^7d_Nyx>47IE%F^Ne2(!3 zXXYQeIqklq&3spLXY?E8Sr6P!ogZwtfxTZ5oA+zi(#(5pS#z-ypQjJjR{E-!DoC3B zc}UJ{xM7)sJnTf6F^qKN^**I8QxJ&ulLRVyv=v;Ji-0;z~0ck-=>_jKj;Bw zAD#Mr0@$0N)WE`Ow8q2%hRQ5PPvmN?@m`RvhqI{0Itp9ZDAWV?5S2 zPlIa_rD6kl&tA1Fx9|-~Qd6s-{{@FS_+<7pPc(g9AP6vH6Z#iO#!BLcKHLHOeA%Vr zrPtgG=Rim)da;`aFa82hMrXGfN0YdA(!A@YcIXJOEy^E7t*S8^nDmP$uleyMAeGtu zOArJF3k|z|i}ay3WkwY(u;J1vc>+KB6$0NYs4{r5w%!R?0V4c?v@ynHv1_cGjG;R@ z9B3JP1eYV91QR(7FdSw4gbhF?mFLp9JZ-z#ee@2;z+?9l7P-VtHRT0RNKkr}kILrZ zb9%lr8(*^SF!M{4ZAK@K*Mab_ zp$w-2bjQ!L4Qby>!No?>@MX8zqiSWnMY>tnZ3*ugk^Ta2%YWcn7xY3WeGudVp{vsV z=T<-2KX>#k^vFRcrV@^0V4pPv#uf4m)?FX30iMrtMFb;qdoaRh2OmNGjdB@4hjHVA?s?-d`Lk-NFSrn18@SkW77h`}F z67doYF>!llRK1Oq?sfB688tKX)4mE2xX%xO1{;S$4#0@0UROczIm9oznYVSaq#GZ` z8~6kybb=>co9YkKWFoF=?I@+g)an2VT0!+6!CCnSp5)mfBnStKdokfhz=OID1f@d) zLo?d?5H4a^h5>Z1djqw=i!*<;Gj;&vf?2`h$RluobNZmlK6f9gQM<1iF|G$Ewudj| z(9|KmgC_}V9eU7x+{C%R5uxP!NHG3elnWP}`TO%}XCWFpGa^)4%0Zdp*fa zjr}fx=Xx(BGVla^eLg7hX9R z!Du(WJ|dzAMKzZY5D&fw)Cess84BFhClejZMH3Zz_&hQzVG!juav>@+(N3tU1&mkO5eX8 zI0b<3-@f@0YPK$nFs-Sy*fY81#HNOm+q)i`A#(YQU?IB|rV@kj@B+qcB1oMJ8y`Fb zkOhSlo&+y-uhl;Fya;ZvtE$LmCU>3%HB+`GDuScHzKBt)N|b@t6C3#Ak$VdlzF~65 z)V!pJ=pB$!?z(KT88r5(bYf8`K2lTd7#hXF4E7Ktq;Ko~y@iea z|4a{wWWivEhRgKeb9A8S8hv=-Q;B;O0o;olLqnc>l^mcbWnseA>M7&o9zbXUzTt_CdMZ=DXRNWw{fxCcB^kDomo{q` z*|@8X=+FT>0qE0&58@ZvC?k{CzySDU>08&-2YQ1Wo?sVlwY!gS-~i;g-&3KKGWEcW zPaVATWshx8tIt`>a=veC(K;;uG3~ z6FxU^6(rGbGt9c=%fpP9a+lNlC++F?l#^25cTA&u+PBgz{>aCtftKClPknC-KK91O zq-i^)_tyjK40(TTIB9;12UxKB6TO)Tvdm>SgEh~K4HGmpS}3_Z8~lz}3uG3j5u|w0 zgtQi*ER;+ruG4JBqUTF*npNRjZ8r_bLmr~M(P&<%NZZT+o~F>Jc6|HsN%t*um+6qD1G_l9f1{$(Kj!uf2!GwgZYdyeHN8joUo7=9>ZJ4Sgq%j zN4{$Hd%jYH4F}}V3oK;(W^mD!p2*2!XF7ejU3m0)$*o`(Cg1?j%m8l2E3UFo-sPxZ zHFV(cs~lXie#{HB$FIu3tHwN-1c`hW6|BM+Jo8qHJ$dgU^+5cMFZhdpVly=f1XBkc zUN{O%^9dyud8it z*)JoX{=g3%V0lb8aIrO_p~r6>j_H4_Ej(gXbfF%b=l%f?`Pke68TiJ&*l+4+&Ubxg zJ3w$>4*uZcn?Tp6`-Jw+H~6RYgX4kIQ@|gbzC36NJ3f5VcHlHle%=bgGQ)1jJhynl z;{A6D{+K49XC~kk1}s$PdL@P)CiTLvR?B6g@HbBpJ7u92t{;N6>~XnKuNN^>QK1ic z0+6dS?LcuE($l_l)ulhb5uX{eLD^7r^$M42&YoH0y(Se?x zzSVnFnk0E=>;mpp-Y7_8T|V|}aClgRpbvkcH?!^yK+6Jx3I~a%vG%63PO^p|?d5|C zu3ktN>dn`z>k=-UsK35?zI*oU`R>u9{Zkt6K?c+gYy~O=dOQfiuY`CpSk?07;AdCb z6}!|gi}1h%fq-=3U4^9VbZNuP!5jgo13B@3p;y^t5hJjndo9}fLRUvUMO@?2Px~^~ zM9*OwWmuFLhxAQ-DXCWnVGBPM_dsUiU0BPOU3?^b z{P0jI=Z-H;ix<0voPp^5#en-)43Mz}w4+P zoo<7zU^{H;=#SShroVhyiF*SZ<7Jf_`2(Q z%=gFm;`8WnS33{cb*g{=dw`kl1RnwqFv$??`F=4LN|l*8m^{e#!|tGY_{D)*%O`MS z5`-sZb_%?piBTr>&=Dl?U<318E!eeKnx!fUL>|9E;G)S#6Rveap#f`-1(ykG%#>+R znH^5#Eo}?2WD(p6*nyMf&X;at055pv9zeIgi;tm`6Zq+fdX^EEu9QpyI_*B{qgn=i znq$Y3hF)B$tDV1+gU_gA0l;@0p@Sd&Lh#26isK`EULv{ot#n`~1<$%)y~t?+avlCH zK9+4=(%PPg1x6tp8LhnFb@tq z;-2uQEit98EuGDYr241L7F4X7nhRk0!RNxmi&Xr~i(HM)v zw`7V)z=FlQ3`uJjj=-tm}JFR4|Tq}paD!9Xs!*+rmHzQblq!av!k-)K^lsDVK5Pxt4f|v3a zlMeG`3qv%el_Rpy(K_65MR2e%SU|t@@ygcycqoVp8nobSK_44i?RN?4;2#;JftssQ z+D?tLcF7(R)yO{vbZ75VaA#e*A3HB-kMY+q-V68`U)_)0*3OqPc!)1!gE7(}e4HI0PMiX&7JdKmnRYR?-rT zZGhQe*U%~H+Af~(pOTNR-?c@ z)|q*%Glnd!w^aVNAnGPX`4N3OM9*HAJo<0Rfk*kj{1Be#3_k$c4Rg(FFes@(j=haU{*38@e5DSRPaWLq|U<;DNI(YoqPGke&O(7hVc0Xj&}`_4+C@v zD9etZ?>%%=+P0m(w9-6mhLr<98qLp^X%Zg+gXmM-w`L0I_V z0_wZ`nLp*o*y2q)5S%qX96Z{n2fE!=Mu(y|!hw(Y5w0AJnOSd0yKg81rfJA6TL`Dm zd+&i$0C?}a@NNdMFd4J}>@PIck_pYJ<0jQ>btlkR7FT8~0XQ`w5je3ESb?6K#Xl1V zJ9%8Pt#7ZAsu`Wha0Yli*9(x>UBGo>13yoh!q*cRQOB@nSY-lO`yNLV35OlG(gs3h zxkQVusvnAYS57##XJNLI4Kb=X4Bp`z%?@^Dk68^FZX(YXXyn>iU10d{*Es;futv8m z?m|sJFo9p{5^(i}`bYs3J6G(|6729h!UXOC?|zAA`j-0Qr3~^0SpMi(63X6@B_+5O zZWb9X*CL_H?EcjyU|4a9kw4_oC%)%QIrj%OuCFpYiQNkq>^ibYQLcbV838;{xpsdg zAKi%DHUK&J1N-AE(2&U`U)tbSc2=+$Jvuwor5-)3I!X!9g99Kf z!E>Duz+s#x-3o-Fqlq>?SgfH39K^~Uqo_2wYQOE%z7oApyW5b}zQv!NDopHp!Dz_J9}Y^r=gFtZl(Lz?XJUU&E%QKL>v3 zw^GJ?`tOimpxe?f__Li`a!z&k(*s|`w#WT6_`|4mPGELoa>>ARiOz5>l{)z~!SEC< zli8SLm~fcn0O<9}hugW=EDN?9g-7{Z_f|c6bwR=R2wJWM);VoP2+S_z8?9$e_gEV@jfb_Tfgwe)FkxFFi1=HuutolhU_%fCcZ7F3GYZ z#Dc}CT=RhzV^*I5?CjNq$$ebw)XK!e!6E|oh48rK=Lty_j$;TUm4B&)k~suE;1+0U z9up8jrguf4S0g(;+_(18k3Qag{`1cqJUxD_fbjBs_f)SnF+RbR7$m@go*k|;?%`9= z*#Y|qzRu1Sh!TiNx!UCeOFVR`_l(&Nh4gP8YT**`%NH#CYU8(C;Vs&F1&&@;y}KHL zw|R+N_%pco>Diz^`=S<$W7~ zNOU0J+Tm$|DqutF+6|6XwIEHTwSp&h*B78{tQ16Cs*-76Kg-1s?F&Ewj=r_9t{_xBB5+2)OvqBu&!G7N9U8Kujv8KXBL)9 zwFql+AfJhcxsLgv7Sh6-MG)wC4gr_EQg{T+OCRja@#_i3RiiJZCT5M*?VBfaB?(gM>Xk8Q`l z(XC{W<3Og9VYX5fFEs)8}zPmP<+8!% z4dGYTqC?fg^BBOBV+*LR+cR#qV$&QrbT^@gOtro@skdve4WE$$B(aC`mM-Wp>jCbp z%V25Tj*soff;0O&3W@KG-}OUo`Gqqt5~ zQvLCtS9$brwajB24lI-cP!|WK8bQX@!{!GsCKbm z^l?87#aKWINNZ2IXFAV0vs?{i=sJ1SJ?H5ZP-B2 z05DYSw<_NHiHscR5}ELT*B0PAjzfSh=oDTvUio~#_BOq-6Mm>f+WT~$Q`vt=cW~*? zJb*-*am?6>52<@y2+z=kKe}>kf$bPR=ga0X@Hjb+a*X`c_CEH&yo$Y#RXwTpMSDOe zF^jU_`K6PdiHviE4-)0+5?>e_fP@SjMdPd@w1?)yLYZ+HLn$^Wfg zJJrbGhuR55m&dQJcK_wozuWy6Z~yPRuY3Oa-8%{hAM&)Y^se8PZ49N!OVhD~M{q{q z%5`)WBWbI&o;apSWega2aIuZU&IA>mJBC6MFb;K0;)=ZS_oaT$?2R{diMvhc1QvUQ zVjxv&F#``C=pz`3(UW&W`+($fL=6OiT&8_Pms^qVhd{*K3$VDb(+t3${zvBo2v)Jg zyPnaJAOJFW0kI`IQb#+7R5xHxUS>^2ABTmpezG`2YtuytZGd{1@(x1I32@OD9SG(+ zK<7R%uL=;Lw|z=|`Fe5u7y~Nvhses6&G1cF2VeZ>x{;5Lr1)V{#kl#f4Wkf$rmd&& zvTY&=4P|VGKmB4n*lXQz067Va!5Rk{tjthNwkn-hq?u(939=wd3xvhfo zxwguYGq=(o3`gdS_-)4NW%%g-AaptSQ05=Shf$}Q86Rpp)c@djpC@3P`BDat^XZU3 zw`fjv_s0XL0Pz0w)fcU4O%(NwlM_3E29rKO9TQ}3s;AD2fhOH!6B>90g~cMpQQx-L ziM`|pcRzi8tsSf{JoAp=mG1px!Xcnx=Hnre8Q3#nmyU&MsIRgDAr!tNydk`QIJ?+= zm3GKJ{p$Z`?_OeV%eK3)@AE!Y_g-JeHrV(g$Cj{y>;?!L$Uz_^9+DgM5(O!eBf7Lf z2#Gc=nlxw;rI8kiyL2of6eNt4G#!GB1KeOR0^~<*SJipu{~KeCz2~>i+TS^KFLu>e z{>C|buQ|sY?>X0;S5(zQCq>pt&&0X-+|TG!5nTjq!GS5+@A%MO_AcY4?`kJ7wETYlQQ!B* z#M^*9XrATrI=-^6>}Azr(}9q7pa0!RRsHsF8oDp~4-BpS`@d~WCq(hB*^0Ja4--C% z|0DnwcnKI;7A7AsNgcgxP;Z_s;S9d?r*RUfP1TJ9d3-j`m1nF@GE@sPn>P6`@<+(Q z-yh|F>)VpPXi*;<=68;rTXU(KAyHfQIZg~aDG6e0R|ndahwe7Nj_CP!+s=|WPTWi3 z_Ek3fx&mxEI3>^2tKF;p?bVsAl1=(o7+(iBF;!=;`!@GHLpw)4&$t=f9Pu8xCgc|7@KchjN*#N-4a__+4nEgkly_ zG*foZnaOky^!puKllG^dyga}APqt7C^f_%5WCxj)iV#b-W#_~cZ~Dxh=>#&ao^%~DI=Ty+CROR*6!5PC`0w`k&aI6EtqrZx?@tm2$HyPw|D<8$%`ZiFCK|s zLFyJiw;m)XPXEWE;Eb1o$f;Ow@pHJuvPpc`0=m)EV!iovp}3S>_N^fp8s%A3=Ny0| zsuIzZJv?ZC@T8 zd;D70Kl!<5H9zx8uoqJ~yAF?}mCf*8$BAtfZs%NE} zM7k2o8JjD?QYNd;EfdTJ;sg(l`iS0rqPDU2cnWXbPH_-(=Fm6thflpV4yKO)cR+~0 z<>!`k*H}fjBgDIxcT>uJ?W+=j`=@}vDn0ogKTMiV>L)qdUuG6C5n1bls^r1TZ!Ly3 zalq9-#|2WsXA%K5aipx;lZd~Rapv7~E`KVeZo%?!#_PNS=8-2Y&rjPn9~$@nJ;~Fm zpXHM8lkEIS2JHNKn$;7(mF!U7+R8e%)k0*^PPw718G{B{M-wHR%Gelej((UYRDb^Y z59T3^2dBUE=|4aH%#-W{p8j2)(0p{SGa`pBk_^)&iPFW4DsQjsEChG4}=>i5__`vfZou zyoh>s*!&zFSMFZM`Q+Y=Ku``O)Ntla3aFM|9CP5YI_H5GMsm%S;2OJcntf};a| zr8DNP!PvC6)8nCNJ}KV@6NB4m=pg4v*YJ&&Il`Ch6%ia)*fl#$?~^<7_ecH7pmbS5 zL{|Jq?n>W%-$|F<-M8BxJ-7L@@~`Ewf9#&)N+aa!tts!*v)Yb!WU}*!m(QNIUSW7v z+?0oMm91^!f_H}4YRmB7AHO;gxK9ATI(>Q76N}r&?yJkuN&Y;OV_n)Z6PRE!6Fi@t zjEpr zO=je5lbXfT?*Xrl{r=#7?%7ADAAS7l^k-lElhY5p{p9p3kDs0X_mBRo(?5Rlt<#T& zzkaDW3E#u$uHXI5@nPzvJFoMoMcH+nw@-u0MD5C4A^FA~P`Z-|nNMWYpqrxJYh*9YEu1%J>n$m3?U-*AKnmjfSE{;{rLDXUVa~ zoYG(YSM*(vh30F#g?Z1j(ynE@VQUf~Nr*Ko$zi!-xV6-fi~(W=*fQ~3 z>9iGX?5A@N&S`%H?s?F`tvtruHQK%0wT@?nz1+2Jr7f3E-`^cQ*5zoGDt>@G)=rM5VM`L`YyAhWyCVN{5GPcC( z9`1ew?i0Yf--qw@zy$PB9<-1E)>D@`x$Cl98a~N;;w;)ubQ6?a8|S_g+!MO9qd^J0 zHGdW`xB>KU-XzI*(3kP%-n443wpxKIfq|Pv-h%i#_y3I^KOslaXyz8(O}Lu5TjiTQ7g>^usTH zEipKqemg0Ihcf=)%ilQt;M435KK?k#UeXbleF0}J*4qOi5A!p2>Xr0a3C*e|$s~WR zj~4)6$}%l?)aQs@=rMN}$DX;?l{V1is@i{$iWgyHI;=@vOu#+8@5j<-q8W zjI+vTv#Q-n-58n0z}R{7Hugj~o$AJmx*f~%m4J;;-7a$_I&}o8L7&LpO5REk4!no2-?i`{Ms-edwiA3p4mo}slnH>wE4Wl%*o>Y7B&Po@anj)KSigOHh^w@E-copPOms+(4S2BXL zP{Y5pB-iE|L74>O;9J{GrK^RL^g6sRKK+f;U;d4McKWFozjXS?kACR%?dLyq`q5AR z?di|F`NfLQ|M>Mkl*IV?>4Bul%m`BEF(}H#alBQVMM+5sioP2S+88kuka~zLlIs#-lum z{V0D}ynXnz>>;mwjI2sxA|z?F(4C=m`cA^bs1(bmvdb80)7LH|t4Kr3Z*8>*R$PrQ zGTQE{Y}(-MR5}7OR-LO|Y|swM_8e8`os!~3Q2VzLR=Y(!g$=|P=g1oTdMsHhVk?)K zW9&iuppeira?bT0ZbNoHqGQj@Dd&b1M#hROJ8E=vT*XXMeng9p|Hj0`ZDi>yIx(_w zh2h}`UdKJnO0R63KlF0^P1ZGg$XV6Z9Izr5!F$@JX*(a<@3yUljO}}WSKbdP*H~uj z&bDiQjm*`S!Oih~yhC??{PIWOJ^}pl_tAH4p`^_mX?Md!n_^9dUb9j+hxh!MNy04A z3vx}Enc~n6D5HO2cG}MG)zO8|x#zFSY<^Xadj{+s{rpP&Bg7r%J=HxIw>^!J|s#Oa?r z`+?J+dHcPm|KXGW>-1+|{nF|2|FMpL002M$Nkl0%f1Y zud&nGdP48gXLx-8b+xDlArXStfB24e4w|b>Nl^mRX)ii=ww#t1r#hVTB9S37=fgQUamO|s+iZFW;HJA~Oy z#gZn~;wD`{S1*0y!=3;j12jnH-$JW}8~Xb9Bj9A_C@w zH>piNwjUfOs=05Zxr(*ETFf4MX;+$suXKjNQ8F->HE&XPt&;_dKqo@%?1j)IJhrne zkh;?7X;k#YZ#XjQ9er7Z{rfESKltgdo__eZzMbUn`%i!Gqn|ka>yLi$^oMeP-v9ma z51sy})PLpSe{uSQzy0l89{%-Q8jcO6rsbTyExFlN+E&n1Q8A}6v+2Qn0AzK7+xq*Gb|)#x zFY6p?Uoppy{2Slx#PSco&3G-D8y?QTjsu#FHn@JEqkU>A?VCRO5NO*!g!1#zl#Sy3 zIYET?Nzy8!`uIIGEB%z&V?GbGoVvR}A+UNn%zE!Hvbc@W3G?>h6f>`)K@7AP{ zYAv9UnnG9$tsxsRR)A;cdnIy_CmR>2J3fHSDef=SWr)ROvLw0Zy6aCx|gCvPaeIu`S{ufP4 z*btAGy9*tqE#OOu*e7^s!-84!pC8%r{Kkor_e&CRdPwx#@umWam!}cEa3V{97=WQ zTk^)Z$*8fEGT9ZN93*WGI7tBg$HRKWoBw@YghF}z!=*fR62zvYg-)!*WW#7)^j7tq zFY-r6#U?vvhAfz4*ZRBkr&zJy8pKAj#>a>&dDX76gQ11Svxg)3dm8oX%P6FCwPk24 zCe?$3=_C2Y!`{vAp%91nLI0s}h3Xdms4abBdgS*i_sDkqS7Fmzhs6d(`fl@!+|jqn z$7ecyANb?n`BObl;jM0?XZz_w_n z>SwVY9aX!$q(3mW=x^(>JZC>dTxfUO*e*cBs2fw$$xqJ zh4}M0?H}b+IyS!N=uy41V&7}Np8^hV~XQkn(Ovzyyc5e>}}uMhasmI zpiwN{D#}~E5@UqH-{dZ``l`RrLUZlaB|}*;i7i_w2YusMZTVVl83JZZ><70V@r=EW zn=2J})=z!qQP%&fP4octiZzDjQc1O3z9ylb-Zs!Yq+{oL9M6n2?+BEOlX-HWV7@Kf%n0~7nj*L zxZaJUI}351&aK5ey!89$9e=Nq0J6D~B&E>W5qz5Co9yVlPP_N@x#X&Dm#-F>Bzbt0 z$Lp}ghPJ0@Bw*!V+h7M1-fLgj=DtPA?$f7F^De*b)iJTJ7McjPSb0z4lO)3xRtiA$ z>Jz`3;vInd%e&ehr|t6a#+j}DAeg7Y*k0i3_*`{q>M<-b#R=oTw$kX`cNnMLF8-u<9oGKij+W^_<8IagL)~%-GboSv0{rae0ru`y`H(k>3*E{nlcMD@B z37QU|V|(FwmxMjBCH9a9*u^!~#x$4l^v3I9(oiq{F8Y=|=7}MDdoQ_V;U>Gtw{q1x z`nB-SuZ7TCJN9(1%EJfGHamfK>f7&}1Dn0{05oU~-`jw$fr?{qFqZFwcUHi*6v?H{_;%6c=)a2j6XwzwO>j zn_*RY$Qc{2#d5D}==bFwrxS{nXL>cU4A3#3-Z{KXd}v(GtoH(@ zEYUL|Jga3PZAINnXI9@<(m9Z9i3x0M7gR5P= zVUi4OvLuXaVCvFv5a$;*Tj}z#JL&Q?`rfHD=}Jhmvsl^KS@^jSineW=oh5~Dk_dNv zn~WX3``0lU=FPmR){&U%*VH;ZolLT0k~ICi0{N0VzwBWwpfh=>+wH6PmQ(x;Cdq>6t~dx;tMpz9}g?Dh_Jh2V_ek*rpt+YExti z-}V4s@rkUKztAmavPB}(eY}@)sUIa>9j}XSwja@vBDrD55tMIR6MM#%z5L-tQ(+jy z=Qz&1g+u3z zY-+f|R$5I+wIb%ATuDU)NFbDpmjN|XITl-eNrWU6lALPZ+B~7@opB~oiO(xHAqHmG zkGK`kf%SMMS@aDLyIck?V@jtYD=cAsV zveKgrh`iJ&JQcCfphDXVt8OJ$l*rA0rCi?br;vLG5B373Cr%8{r6s(CY{1XDuW}GM z_CntHNxYWkb8*h=Ga?1_?wK1P|A*@RuSmQGGI(Ke^u|*7rr~Y8Q!Z!4Knb+d7r~gi4IQrO@ zkQ5lR)`Dxghv)uyHzRPFdGDtE_f~(72sp1zR!(LU(b4Y0Dh^F2KfRFd7nqfH%C&$; zk4e^K*^{1SF8U&{^wu#;T8^_rR%>Nw>V7_k4s1p8US*+le3=~~$p=|&AL%y%W){df zmNCc{@i)1&)yh|fw`_WHnn?O`w3tis-2cabYTJ&L43dqWsQOMdwn}13p2g5Y6<;JH z%I^OIm7Hu$@B_UwDA_Bss4ZDYe8`>h@T|v+qziV%P4x6nSza@$M5Sy=eW7EqN z_%@KVO!7B$dpT$P6moRB>mM+2sY<@q7!A&Gco)&wOGf7$?{hZu>aw}f4Mo0>CnT33lNlz-5$sHbjEwtP5@%Czwmw76fuJwTi zJAf|xN|HS6Afc*Dyb-J<{O$d&g$e$a?!G2FG*_GTElsa4stt^!R0-` z?-%t-7TVlBdHJ%x>^?+2{+#a}kHN1;`rZfQ?>>pc*Zh~Hi7k8h5FL2`A1ie&plu4vk}-7a4>{^xfX$ad_ABXqB^;uO*{(PVeGzmYdF>@+u2%e4FFizAx*O z8H@Y2`}*CE!2KoQyWM{uWWB}bqdW=vY+GzCK9)}t&zrh+ttSd~iJQgSCA?3v_!V8z zTWq#noV@Skv+TmjlP34FD1Z96FUyWml}tpQ$)hI2%-g@c{q}IL32nz~uYgIL#mb`l z{OOar_pg(Jys-J9r*j)Bu}q@%+n>BRef06u+A&0DA?leuJA^OtYMHzkIp!uWi;vkg zd>9?z@n>E|lNl|(nh1dfK@$1;b)LQrQqqO5q50mv^)lj=Rnuevef82)!AY3t3e3~U z=ll86X7^6KOCI*%%3k*YPJ3k0ul^*yd)k+6saAiGtL^zmc?vlFC`LegL8|c2pXDKy zAlL?6HrA)l()LlF9v*VIZtrA7>`Gsdp1M`BP*%cSl-GkO`ijjdP+IAl*QSSG>-TuCSD=L4)yk^nM>3tN}ovx zja`>^EBSA-v+Y~84(PDfCz#b{{(=gB6kaYwM}L0L_idgKulqXDM5(`LBzu)eW(=|s zKEG2FEe#S=G4v0GBWV3Y)wF}Z)S7OsUn`3nX@)*n__3qcr{=Gr8w>V&2EQJ!`CO{>$pKuGTXyKz5TJ3c?`_(PyC!Q-cVE9- z5x7qP?^b_(N7kC)By|?kS_E=7o7kQ7-t%VxG9g=aYGDtpiOxTC7FaYUe`GG(n#AGI z0J}5bvs~Jo$%3v*2tpgudQ}O2?LM_A1^+tjF7?$b8{}=30QDmIR#M|SO`wy8=(4hg zuWZ`xpCX?nIn=jX(D+?DXjy5rnS2!JQcy{gjeSaOp5yy}EhZ2C^UW5121)ZgbPo@+oa`R?%8$6ddk4cr9m?JSaf?eWMz zZ-1^f)-aynYz^1qIDBiLl3#6TKIkW;K~r zJ(EW*sOGSIOwcCE{7*gQO_NCl4^W=JAn|yD60NjDqIvU@R^N+Mi+Fg+9l%>UEDDfY zeJfU*#kF?Q(&j$E7kNLR%fKdL6Q|v?T8xXg<<*nB5nlHVQnEoWK3%8RCttk-Vpd;h zhsV(+TCacUox)D^OpfCAIuD1`eSw?28}3s%;hk{r;?WYT41rzs9Bs2H|_4T&Js)gt&A? z2O&E^A|WykD-m4Usgktz?qA!vG*^*5KBX%d@}jByDT0Hq@*s3{4tV#YJ_lq}i2*He zBa2)w{@#K%O^$5G&KEn7Y~XOrFWcr1g-QOLkM9F&h8`_*$h*M1GKgLMy3k%qF9zdZsqnVINvqMJT_z>QL=OH`LIO!8N4npSb6 ze6yuw?Y=DV{Ob4kiNj4>ihPl2N3YZ@bZof|-f51!dZ1=@zz*1nuLO7mmsxh@ZXl*o zM{O3OzPCuC)ZJybtsr&%1lVjWyoe3n2id!6-R4^|B8hun@=|>sT6%jC>^~MRlDf3U zsBDPr71-Ki;_TqsT(RhQ7|Z&JZ;3~Kq2;j8Hg0NsW_R0zMm1)ZY{HAcUFt>0HgVL+ zd^e=k3zsq+Uz{V(l_CshKZuoTpw7qeOspIG{%>~OOj;PyKoy^lfNeLsYR%`+!h-=6K|5lbB&8QROl~iK6h!2%U=GGu)R%3G<#h2 z=i;|^di_Z)VScASHEQ4a+t`db<71Im{l4)u&GGknOmEF(bo@Sm`B>yV_DdXrI$giS z_T8KIpD6-00c0|9g7>7DORg!*95IO;IyfzJ%3I*=wycvgdN{-mb$?X~7Fe(8sAPcr zd}apR3oqE?8%uWYf|29$Xx(EKV!s3uRJG5g&ymwIvpgj$amln2me9`qKWl<< z*29L(+_j5yHY$p$Y^ftJpEy&AV9IqVc$;PG9=_1brCs*gh3p7-kc!Xh0IoT#>D-n+ zNW#T#m&eQBV!ru>URx(U+B)%=1f-r+zR6Pkf~Qm3Bt6liPe-){guiHJF{vkVH#s$4 zH0C2o$5`}R`_@$aP@yc@#`7+uP2$ijL7btJ zfm)E*$c8c^1R_qiXhssc+Hqoe#S2@E8{OqDR|_9sqexOxJ93PTAoeHBl?>KG zLUum2fO()o=r%fX@s`{mrM9i>q8~5gB(aqW1u+TJ#DVSQLr5i}-itRj^W&1(5+)8| zXu+xBya2xLry|(mLT705@RI&x$q^7sHl2JTfh_oeDx!%$l>`?}(@o6L;`fJ#dmqKL zWR;NCE^gx6`aF%?e^9lqi$a$2sm`zqx+Lwt@RB#bzpGBq*`JM{-aWM5&F-S>KM3}8 z>Jsw#V=BdpCVzd_n5?!O$=Tz^&eB0{aBd-J$h3U?p)( zTV29?yFKB-NJfO|O(lw?Nr<)pu|>iV*_U4=$pa+eu^TBzb8I0jCTB|&6RS!dHrr~! zj2_9Shb*4t_l^~7&e|Cn{wo79A)l>u;018}cL^5~-7LJ_D(N*&i~OCh zwqoN85&89CQu-nP+eUggyFth4lK51;C^I<1zvau(DTSk30;*|Eo*87kcD(F34QP?X z9YJC9#ZTa9+z;@b53~65yT-&qGqjZ`#xLBh{~~8-9LcDdY{=Etm2Pj#+NMm-*gf@0 zis9MrVVmu5yk-v%n(=X!(fu6z!wU~q`Hi{QzNe`!-Nj{UGF|Z?13wd&vI=^KGwOvJg%@CD1SWGpU=-jMc?_o>%lf3@qx4n!x z%zmAt7eUG2qk4S|eJ}iGZ!ISmlO>0Ccg!3Xz|xkoCnbOF;fwmq+9Lccbaq7SD0-*d z*Pi$5O(Zke=(Di-HxsZq-$NnzUw`!E^z36p)W+Lq6fc)T`A z$6<*b`}kc+SZp!bTKFZ3c(ip=x5-GGMF>cYh8HcEq=EhHe4f{`xO9C3()cL8OXey; zsM#8Gcp?V=iC4~~&i?^%kdTR!B(PK#4T`)5CduYU;hQ`et6dDg!0`>QmPvNQ%Fp8e z&`8#w=cAz(njD|SaDFkX{-6+t@aYfs8XtZG7<`sQ_(>9Jbjs46{KiX-r^kLjS<;6& zu!U$V`vWEYn|LRTWt-${T|e=~l3H-t18O{lUNwjMQq~t>`eq|9ySt^Di*M|(*cMNy z{5qeNud*5eWHv>R5^;n_)pXUA#-+sz}7 z@<-t$B`b}1uePkd(ycEBcVtVA*;q0Dk8SI5mA~SZS6ilSwV!;j`Z#p!@yIruhQZpl z${zlqQ%76&CT_bSG~{(|i_4KLIDZg6OuT!XoY~HWvyKexid(yQZoe6Ppzp!_5Y`is;pR8DSmCT3uwkla~VB^#1Ki>U?OPhLGrq9lQ_z@fpf z4CHv7NQ|tW(C8!=odwBGKc-wv>o z-m)^swkfeoT!~DsnO$PzJqdumPbcyrgf)(hGcsz7p z$n;yt$k9<#vauUS8@^R!clYVDqLKU|fwzOs2D|BTwa$alL0;Jq>dmA+Ptssq_Sg*3 zcL3y7!Vtam?7`UAr;|iY`%&^RZF4-!K1fFBjq<32<_o|^Zz{_J|kz2=m}>RP-jj$s%*;!ySyas_J4I1#SEHC;na z$IyuDJ>2~WY|FykcjVrK+aq8hsl_T}lEIoV@?}A*uS@=1};msSh$fxnM zExD+KCiqD%EviKu;&tJ~PL_nvq@Hzwuv#Q*r!P1O+$3t12!$4o9QM^B9<~8>$x99` zOM|k{0^0H0{qvcJLfFX!lOnudA1OUS*sar65CQF1`#<**BA8vh*}jdNHdPAx6o-!&iqoaNj0twyAlX+kHOH1- z^xH?f#h<-O67n|VAZ_J~FR<|qZ}}Ts#XpU0X7eZyT`ipKNxxSrs;v@+PW;w!t32vj z>E*j@S!~+EQhMomFh-karF^$syE%)v2>2Jha8|np|UwU(=uHK99X;8?Gqm@$vzkeTDxX zeK#VooHlpE;Cm~-vj|v7?21_6`#vsKV%OapbySIG%&$;?b) z(f%Y0eeK)?Zz7rn7k_f0n&?Yz+8ndi6iyNVEPlOY(%lQ+{FQq)peXxm7Elj)u){*@ z5^>!F7Mp5w#xfX6aHD=g=1rgsQBAlEyay)oa zJSm&Ri!NuEBykeOuvb}oJD*r)XK)hVk{{dE(avJr53=Zyjw?FGs#iHBNnkk;yVxNn zpk!|4LTq1nFZ^8|oLCWN_Y4>>VvB)Xk}IjH*2`Cohixp`(W2I+Y2%`kt>zsLq0KWi zkvV>3tc14g4^mv|7A`n;(MxWPjU2&@HTvPT`>2!A^(OY+2~hr!NuPm9h(cO02}Aj~ z;kxDWJ+{n|4&^yI&*;Yv@90(svMYd_DCbW5gx1*U{wuoBkhcO^9|HKP8c?3k$ll8; z-5rv%-NTQTofF@|Upt~-6GpOEdxj6)*fTiCH5oMw&vU^_w3YEYKL^UzMVa~$WN1e2 zyDehA+P#sa0GFJP_Va>r;;upU< z4js{6SQC5k$wx9%#9N%u4oneEUj}Z2#|NZltX;0_a z1RUFvzBF9OgD(s8nq-i_Pe{hLVOJmA9H(uLMKhIyqp^Q9R@maRx1+~w3%aIL>rvaD zcg8v$=8P5gc2|7@xe_krPGluH3o^y>!I+4U)vh(>Sk^I0!r05sl~3CW(>BLxQ(tjM zexf}}Fjqb_Y-s<~t^>ZAqgN_1IqK(?=Dz&Zh`{|lfM1P%yxoh;mlioEwnVRY{Q6Jk z%-dTMxGmb-+-fmWoW(J$+oFCted70gBj=MWmL?lF{%e;^nz-nhT`!YN$;r{AlwWzP z$_P_XGtYL9#enq_tx%8Oi~AMjkpzTVM9<26|uS+9^7dHn}Eq3%$!N-XGYq zJIU+hAjHKH`pvLP3@FZj3%j4pt4q_I+YAsP@ge^KWx>xvPzz#o;^#*Wy-S$m#$HJH zSDQ^PPt&j6P9<5ru);KmclS)#)80=uYqMxI&2~5|#!-+4Z6mGXt3HLMx_l!nVXae| zU;bVws{c!1=^;~ldjm8 z2D|@L zeEsnh6ADK5$^+LDnr8j3VMd3s5jwPnWZSw@es|>>ckx{!u)^lrimJE{V$OT@9qW*E zf2TGvI5#YXRnJ-$n2FUwUUQ4FsV}dA`3LXBtB*IS=_;DY8G5+-Y^2J27+;Ut_Ou^T zZ=HSr?Rv>vKOd;SA+lnS`D#F4f}_}!ybEd3-R6UY(by{^w((p{_g{B10{02vo$R*H zXS8JPd3MLVqQf~`i|Y0?>FYdg;WE@LUaMsH3|5l0tx_}bejHwtW8DjwHVb}Ts>{7v zFLNim1r}KJD=A3XJx+c_qJAql^_oNw1?aCy$AXsno7}};DMu=HsXna-64EdeRq*&N zhB(+&3(v;?Q6A`U{}`Vt0YsIG1n|kzJc*flKQxj8-u%<{bW6VYOs>h13}v`lbc28@ z`{PqD@|}QaC_6ZVF70eKX;yL<9g}=Kd+w>+Zh!sSgC0#oIz0Mf-}vc!p6nU^28c<- zJV_G%yk0HCC3Xk7!Ple96WaQMJ(_9^WRdXThyDXGui`D9c3GZ!Ur?IF2mOhMeILwQh*@17s z!l&x9wkd04rv%j)DVf_tFvTC9x{OPHX=$lpsam>Y$TsYp2}U}Y=_tcRy!Kg-zyz?L$}JmjenK3me1!`WZuKw zkHCEbc=!A8y&g#Xo+m*tN!Q{Lj%OZg4OqA(X3poDL~~TG$vg|A#dQ)#ILX>Ko@J*h zAl@}amR}EmfBoo`y!4z-!D&)({rJuwO2^L=Vl>E%X^!M&xl1c^z$Yg_h zsV{7Qi81g?ApouS`;qzL#miulTqT*az)cKrc)I#YC4SvcWLJW;9Y4xzUc8&IL zfy5Y-Bwims>qPQANv8=&{+{QF+S$$F!rb5IXp*)6(Z)uCKeB0Bn-1>}tw2R%;r%yED7YqBu z%KN8p%aRa2OqSx`heD0tkbfSYku6GfALk&h9E~}^D)IAqA53_+VR?gG@>22I&m1HeVq!s52St;k&_6bN229$u943kD#bHYqONjP<1&G9O z7Mw{q$guzyUrEc?rp)B0IAdT#Cz`g=$)QUFMZ+v<S1e8nKz$G?StuIY4a?hv4 zP9L#AA4&QpfY-oIo1Ltu(Sd%T`=Nbf*tGGrI}mZVcl;LS5pr-Wew^flU%#!OX4h9- zeKwa@lIpJ;h*Z$6k|exzi1FyW#BYl=J>rv(eh^oSGQi{f8|IN8(n76$@V*3qU28v+ zPmZ{iO{?K)>*Q}c_t&=YaB|EtHURxoZcKj*tyo?IHfZIWGMMg2^ipeHwu{r$_qz7> zkb}R^f|fmcv;jQE=F2FjAME8e_QSr*?oAF3#p%nv1hn*v^XOh_*e<60o_5D6ue8dm zuOI5eo{nt#YRqkM-|Hz|v0G1+zYD=?!-Bpq-q8qLpRs=z9Wu#X`}{7N@fB9(RPM>j ziErU=L?=o;Av8+6&+O>*0&jvc)v5KwP!mWh>jLF6pJZhE(hOogN1Ok*!>-+q8&od{ z2drt-UWwAKnNIrJ=5B18QpU8wYWuXm%1$6&37z)~V(`GoJT$V(966GUb<(zLR+pFs zD?m0rGHS;uE5cDckn`I|Qqr`2tQf|YwmFpfUwsfBi#z=mqJ5%6KcH`P($k;l+6>pT z+TE{5@8~P$$s5&uWhT2vZ91suv1-Q za%t_j81qMf$C%hB0uxL3myLY<=!TX^egX8xgkcRvzxQpYKwQ?U(2@4Sh?<&WuAph`n7$ zwh!%kJc_$^I!C7S^5|SU+psr!Rd8RvGZFa0cK|>A^wZNX|MD-N{^NiAk6HNovYqG| zd_VSMKX&?|ANrv?6U;BKp^_;lbSDVrL-DP9i!uSbzilG#5+txdIoap3VC@zK@0Jvo z&g$O4OcEv&vR&S@$a{*?CBd54YeMPW2XtURZ?I_vi;Tt6B56k{SFW?=ln+@sY+}v@ zJ9T@Q1jap#79hGUf-|9!QT~g;CKH_(Ex&m2svZ;>nJ(jc5iy(gmqXFOcboX$bY>Pl z$s|zkmpP*?)QvAmRM{?}3auDOw(6XlH(5yF5(Mi8}AIYRfggUOm)`=Hf+YXmR zEX)$P>erM@Pw*?CL#>TocJ;k~q|s4_!>_pofsCRH{|Z9nemQp5PH6R)K97G04IdJT-5*@eS5a_Kt)=y|wcrC(`{sS$+Ue9(!(#V7RmnZJ-j7l_9> zX$U4m<`AyguoAPu_!XnFZEZ~XNOswMOWcScZ|u~M{VOdO;nSyN0lxZjJfhc3CMcUW zzQ)}A7Mmkj`*Up|QmPp$4W(}*jmV-^#Z!<%)g4o)i8!ss2Hx`y zMai%*HYYojs#O{#g|DCE>oro1Y4)r@PUE&73Ovg%7ms@Vm+4&Gxw`v>0|@ zY^^KalpX+^;>y-j7Xr8rUGq(1s>XM5Q0~^|YgyC(EfcO{jy8O?zzV2(KDtVR^&}61 z(0LnZCl5I4cYQ$S;MGCf*u-@ya{kh)*6tJXh90`*k=^pDk8iPw&PnF*^K+6eyyT5t z+V`;1@7vb;UeC0#pKlezoubvQq2C|ze~1mGXG^q?lHI*rbv!$h-XYUF-9!3gsce+{ zB#lhxlreook8L~kHwo7dt9{DgTAa1@80-EtH;m=XzGll_$F+Ez|G=1F5Wj;})~@Nk zdIux$g(ZL!D+{ZgmA~*8{=(^R{EfeH`q3Z#(MtYI(m(ivKUieS_wb!Zz~WMgSWav^ zN`9uxg8gE<+?m%P-w>|NBmrw;wuq>h%nO&gU7A_6(Dt0s?PxZZT5Khe^h+GxxUn9= z1{QR$Sb37IMY`%TV%ZtJp?Mj5pXBG>D8M(naBO+`$bEM$Xc2jOn?>T)>)PW=BP$~- zxVn^^CyXCuk>{g{-OkFx)a%LR;QaRRqkLZH@^AkPTiRZ}s>zh7L&X-4{n?%_0%o0+5qzNlfqdDo_L{jXyOhr1u?PeaxQJ2 z`ysb3d#1@fe4Y;1mjD|&4~R?vd_aT0ze^s($UkNLX!5_~m!sW1?}F^z!2Y?q5=r0& zWlPHVF6H(giQPHAmA|yfgabocmF25j!xMq*+FUIPI(nh(ewvuo6WDcCKd}sD*^(pP ziB(kJ3S=P>Gd#MZAE;?x*e?#%$LZ9j={92~+=?Hw`37`RKQGfdM>FImF_j~JO*X8S9|9aux7u`AyGy2KtU7GiC{N8JK(pscV zFv^w~mvSHFM{iA@d#H&bNV|dNIXgSJ-uT_!AWW7PdZF6mpc4sNlZ;zWIs>x^=V#jGJpn1;64uCV#_AT{fBr4fTqp8uaH26t4U@WzPt?l81XQeM!g6r6F*`LLS;K;4`Qk5mKoVAoddd~6Bn%(rDd34SpJG|L z@wFt9&pd^kI=L?M0PWXyCg6A!|`i*4Uk&}JZ(*$_Bc>t zLQ?%e4v>6qYh@*650Vt|q5tr6&Wck00EjLLsu*L%&mOTmg26ggf*1OjT0lPNV^`>S zkl%WKl;1s`UxR54oyf9B(lv5h!p(2KX{Sg0?P!V*=)UN2*gK(}m}nCtoLq^Ui9hTy z=p(cfvtz0Yw)$KDd?>?(^}Qvwvi(D3Z=rv$Oa$bXk26SA7wF6B$Cn`YdYn7c?~~|H z(hKigH7~4mi>mh)@se@H)c5kgkAQ4;8X->02bq}p{~1?IrzSDP`_YzI;FBO!B9RH^VOIH6E0HjvRDY$ey%Qe``lHhK zD!&tE0)CccgG{|_>gzU&-%fCAt2gX7%SNXCF} zk_=U{6{LDSMT|yUbZM*D1eM-S93<;$3voht26P)+$zoi@otC3TCi8SRDNWZ-2oJ;un`R15ni`z$9!7T}03?jFl{ z)Ej1J@lovL6J9!28kFJ*$e5Qeqk%8nVs{ZPUqg3Wl3}jk3t0oh_dfYU?585y3n-^FSV^oq|k?d{pq@9Uq(*WvBHc{hPQir?5Zy#6?t-R~p% zp>wQ0%9xv2-bU|l+t~#i8GHH~vr7oiV_^B?VsG!rx1TfCXHI|ePyWf%x4-@E)8G7?fAjQ@{?R|m4f)=ib_^27|MZ{!)9F9_hyPGV z<=_0x-^_{eg}ZfZ@E3%wrJ~o1vcO4fVZC-Tn*$_ncJVS@*8(I-sCwjB7-~@poy)p& zPnZSVq@vA(AjHcFcCNxEw1GrXv0A*7$p ze5eU{Tdd$#sQN|+uTE|)dJCT9hpupr`4qi=$Vb0TyG2A?fkXFI)8KI*A|EOg z8=c<7-=NRCQj2#8D+WPzz4h1SXYy)+Z#&3LwG#U3@9>aaF*(a0J)5>P#-y@`FC`;& z`5nDS@H#hE4(++$Lx>mt4C?1fY-4K>v(S!>w4hV>5kIP(J7U3aqXmw5{R_I^`uynF zicz=Ilg-*2x>nOlz*$Di8+RQ)Bw-mkawSAZ@`q+*qbYxa7~I%$+mX-WH#+$HJ{!q@ zAI*_YeK2~~_OX|*GbY#e+sea>Mjwg6`+$$elVu3`@O-FWqjRM{>L=}V4XpHoTaOEA zq4)Gh?K5UqIY+jv?f2!o6M-*m2XH3bZ+`Qer$7Ja|9qX8U;EnEPM>}D+3An}@jrh0 zTYu|so&Lc;_y?yy{D=SW>BoQk$IlTp+?|4-eDcZZAO6FCc>39&{n^v6{_3yh9;hcJ zF*1@AUcul1ezdwlI-%)2`*+501tckwGX>gb`bpqnK|wBX)eoJ z7F{CYR1cb_UDN$0s_YtkYQFa6!8Ce2PVOwxGkKDqREif6!MahQp( zeX)@BPMWq^kl8Zrg*O`?z_o+{>G)TZdg>#g>Ji@K*rIqba*Cxc3?2J0ZzOE;M~YZZ zo4?TQRJ`*`AE7zJC?7=RiC*1T8KvX_YQ~y9OV@i5&w6-vXwFCcK+GlTKwr5mkK9hL z1s&)kzNqm(OJ4CkbiWbXHX}NAMOA!*XXWU%yE#0)Q0u!+tcq#>HS$YGE5c7pdSy>t z^|(=X+BqE`G)M;dYX=jMbNaS@jchx}`47f^Mp3n+N<>bF8qeg6te`7#C~}np7~3?V<4-5o2gDmnx6#4Y;ji;=^97kC zXY5)fp+_rDz=CtXD6S;$l*Rcrc*lNy(L?;q zHa1OMYFuu9x3AZA)O;deWySDr~h730@>?u3B=R{uvgrn)Q zn_+QDnLqmJ{FHd;+a^M~&&3>AnCYl`+8V26E2WXj_Fux^eOY}L5>%Z$ zwXL<#Z+KGh4sdBr?#}oWdeKcXkzHA3G9^Q%3%iN6ux&Q4GN(+oKZ-^jeEng;r+hZn zYUhiQ3tx9faw4Gr=#sTI*fjoPJL=EXmIKlEs5=ya zFFXNUV`Wg*gqd9iAfdYk&z?Q2ox(r%$NpH6;FAct4E*o^{lCA)_IncVB<_!?sX-lF zn}kdPCPvmkO;sBU3dusaL=5QX;i{cxDcU*kHoS~&8;SH zLqi|g!^hTH=wt(ULCM(4b3aqjrh)oeC`wk_g$CY-`*uW2iE_!^gb}{M`~|LMb16Qx zfT@!K1x)UxBVYWrFQiVNc(%M=U|g=OzwC3=CRv?{xP+}=Wnc6V6nWlpD0cqivFqem zaocQJ*`Wr#i8$Bc2e*l=K6nsco=9Id=lo<~UCs}&L|x)8gw8$u0I8l+_bI*k5(zt% z)=4nux-#E8{>BB4hKf~^0D5LTDHm*H-G?1dGC;*+Dvc^TUgrr?iC-Cwf1|HtFmmf& zu?^k*aasI{6I-&uBsmL3`K~@L5RXrM;IwsO*S7{tf&;INw#IpAd&h@_3!pKUNt+k1At)O~T>#a*z6S_{;XG&7k=Rv>hkVS z{^U=de)xxf_-ZuIzqPu_s>^Egr}0&;-+K)v0+Rx;uqj%MEolAZYcJSqWRgncH&TNS zjr;VTENJBMC5^D0|^uCk%2NhR`K3aiCE zg5U;BN@ZUq8c82ADM#ITksN;ZS+H>SWSw2AD0%j{cM-_|+9iOW<&`h3Ch}t&d{HDG zE^TX*&S2BFCM2nDb}L<=l9^OR(E?u+d~~s`h4-QAp<=tIa>b_aMZ3flPI852`phC& zag6Pb;zwI8jw$I2_ZRxjUprK2>?%pRfZzM|&<2v=NuClt;F@ zP>AdF(`wI{5OIl1d`P1|NXQ>3A5wwor-M@nO^-L&M2w#3=zl>4+OC#KHad3981@qA zREu|T>I416ar6YCz2v98X3z3VQdDww?fme$24Y$5i=EeK;n(DdJ|DQ- zbd0=FvGPsZ99Q{+8z0WLPQ!BK;#t0O{5q1={kAY(DUPnaU#sm$@~?3aj~Vh6n;=(vr#!k=Ki?;R)pcLKdlC4;62KbG8P#^{{?6a|JEw2` z@V8Ds@B`m}`i9Ue{K${IH>z{8znAd$D1pht1mO5IiJXP% zMIN@Wi1(IKma`OBsL3b`A+&q*p5$1Ib!LRG=k+l&Nz7tOW{c>>%zNqV4!VC3Op;Pb zVQ5W6l0#99nIDeM2II=JCT$=Clo%yxCs~N07AOldM|kUu3tZ60@3E>2JRVS$!KgDAvN_tk1h@n4EvLPsS^>v|?e2EhJkMe4k+0A+( zSqzz^Kq4T{4C+MB<<^cxJ!BI{i!L1XRBq_-h=Y4FQ>wb;Z)}&$dG{ljMTQ1EbUX>a ziGUCE;&ZQG?dqlu>ym%{A&|#q>lHSTfnssYr~WXA%(vcRUG3u1{V%zy_ZD^o*62yU z=JWP#er=^N{l@{BY;a#E8!IN$fuUM(bbr z#e9ATdt`|nSzPNf`UW;6Aa0{^K$^`}mM^pF10N(Ap_Xun)m*P>(9$=Pk6Z>tOI$##`3;i$`~p|3@4QRsmbi3l^u zuybSrF1pC$S1+Qu6f40h+P2wuB@8K;cnPV)CcjZlJ1WVrK#AKvX1#FsZk3360@{KP zKfpFI_%w+(8_5Cgs{^Xy$DZVdY42C8Xj4W_9y<1UIEQ#K{^TWpy+)@KI`Q2@`MDsi zn_;OWlnIhV??Nm+k*Tk9#s3^9O3!}s??DpjqHdw(YUCIP^@lVb-3SdQpgPvWM3(AH*C`wlYEq9CfxN*)wMKS@&h_2Bw@hD4oGrSV64V z08J+QFE*`|{NM5 z70)cdWEB^itndNzuSu@Nr|xL6XV$ezu^1QH{p78koJt;w*zy`g{ZF5XV#tC;pziel8$^v+NK&b6Gn$31&^=p)J0mEcU98ZfNZ!RYH=A zbC0d;vD@d8|J#fYVde8A%oIPaKM6=kdgc(&r#zJG3@sa9CaZC|TQVZSn8dfK>FDGZ zFBxiNPJAwo;q6aNTvsROfd3pj_ziB8yV^YTbF48Og0VX; z6qL>(+K$zfuOr)!bbN^2I~DiUI~IX2ECHN2NfNvZ@E(2#BaoBcZkn56+>d4F&m!W5 z!**w!{OT4x6NrV$$v+cCO%5?{CW%fKdI3WNZ}FTYLR~`UvZLh8Zcb43o5O@wk`_KM zjkXZ3J0u?-g)%e~pG(ABQe+k9g{GAFG?$5M=OYc}U)tD;#^MZT7wR^!LuL_M*VWRq zvDt~Ut3w}ol>|qJn5KHJoBUbJHgxV+1Z34QUo)9Y3W3YunCz+|ldRIyZG9glGb9`0 zye7?;Ty7q@`lpjXHiSRIsO0;a;M-Ny|IODA z>zIcoDJzqbu+|?3p<@%dHC83rh3jN9=p^sG09T(zVf`@>e2w$X<&u#vu~zOK>>e{^ zOYrq?b9Ul5UeB0V@yd8s--iC^XbPD7LRUFQw1cbo>5GhQ{;?gb$xdUge~TTyif=~B z$T;Gde(xAZK^i{&_#r<7S32_bKL4GvdwbORHGR2y zGJo*w`x4I@lN&r4E5`Q7E85HpVd>jL79a6t=obBv?MHE0b+LQx|F!MDe0L*oG`Ie) zdsB;XM%a4%T{q&ZtS~2UUFymV;b~qAv&G3JKNFwD&qOj{GV+1(aq`bj20l2G=zw;8 zXM&g=5d3K1%-ypyR6MEEC)ucpr}}=RefTkA&N9mSAbN*Jq7onDC-v+|wQQu9y|td? z$UZ#pgJBuEh^ZKnL%w!6K&B}5q@I@2-Sp41vsSxni_h4Y;3Fv!lajUBCFbQr=ps6c zPn%yhq|KsX5fI~j^2eSzuawUarFL{BehjR{F?I2ovC{UZnQabfcRV|~;tJi#Sjf&X z?VaWt{oS;H)F%v5`No;`ne5#Hv3Z{Sg)4Or)Cz`i@ zZKiG@kfg`P;M%6=${5`ua(;uIQXD?%X(GUB0?rDwVp{f2l8~}T+uA>*9 z+n~?)3q?+uL!N8?8f!-h)J5W@#FVjTbiZx5AZr2+U&Q4;ww{b%WS0+pEw0-P<5DJGNm}iuY!c6ML$7?8 zxC9ThkuAXhlF5ePqsM)Lk}!1cv9deoSP73{fGDvzjc<)S{Ax)INKe6r$wx134z%uod8_dnMxvyZYgfPA(*O$)S=Eb)8=oXFIwn zu+2`}{#+t+KCPv{(X-uU`|6v>yCi|FzY?d=NqXv@#L$S}(}>_R8Kp0HIzWmY^V+@i zWcBOwy_(fnQD}a#*@O7jZgu2TtSQ<79ehrAmi~%`OVx?lkUO$%P5$ul1#}{aCJ)Et z!ImB?ZPCy<4%9-PIuu?%lP8rgnS)0v(v=<}FP8jR8KR7ve(JGp#9%g+^z zFYTaqbi%jaHR{&u-}uLtIv;MTxWULhzO!TIfg1!{W&Aj58$SLRDP#W;?TRa3SH!L? z-eiva8LvCC8&&k=>L(zHl6*N8@d3I%6v)=I^_|1#;Vq`^Yp=0w(H|>Smy32| zm>ul4<6YX%gAs>`^XK8ar~PtAU{=j9x0UzSeRmPa++~6C*WXNl1WNwYEjCYc@16-` z58CWN`IrPup5`=^+6Ja>F*2ysB~3%Ju@&B5-SRawKET2-<-v?16Y@%HVfT;i@bw@` zOi`CWxpXRF!q=Bk^D3GsoC&z-@TR>N)Ly*LdV(jn>dN_$Yf-=8P)wV0FOd8svuq5y z?3kiupO1+0ibNl~wd|&MlE|QomLI)~+X<%FSMpT6EyKN+I-z5R zb8POiBv!0ku4miC)@5KiCC&V)LF+sQ2)KOXWg#6AOj%l{x- zHWkxMuMdEm*uhL68cX!GPLvlI`nJFQmc03FVjEeJ-ijOhY9kb#bO3EG^OD>BEY?Y; zD^_UJR^N?JvGk2EbWfZe$2aG|fW>{r>);$$yOhVrmBx8|_HS)i%94VTe^J@Hm`>gW z^v&3@>Rw0^7jsFUk1Kx4!&l>G(WjlAW$zF##~taJc1Vl?V{YU-UgMc~oX6V;$#M7x zrCxMPg2ncUwP9d9gR}iz9T9b8%WBVF5289RwwQ|}pGIa0Irw6Saf9|Y;Dgiu2u8hNww*4?BKu68bn{a}K*l6!=GFG0kKzUT z`%+LR2jG`X*+t{a%eQ_yO_I>ISJa}1EQy4Ky7)eB8E}#}wmeBP#$RiU{&KG*JNsRJ zq)JBGest;<(cZypf5tX^@U=r4r1d~t=>gNG_WCU=+fPULC$?SfpFVsRy<$toBtId| zLenb^dU)XY)B_;O@Hw)Z$N1}yio&9WZ_uxJ=>rbr7Nl=0!QSw2EAQ0DKXFKiil&e3 zL-j6{o_y&`x@%nJIQ_21^*E#hbP| ze?4VdWGLGlqHh2>+UlH7yz9I>NCZ}X`Y~) zyh>PBhEX=hP0v)X(Hmn%+qBOS-;oU~{m9<4#BWFE|%bu?Lys5|% zF-Nkl!TZ|riD!+2D?-SaakAPyV;q}P&Ut(7vhfws_vkwmf%^pT4t3UdYO2ZjQ6+9Y z*_v8vamqyLeSqrPO~ifAR%^;1^)(rpOwi%+;0Q2*)BhzwXg}(a8#F{5J7>tqQ(3xkLsB$gjnpS?D(Wmf0o7t%-O1LO&$<(f1;#7G2Rp z^27!X4<<5NYYO5}|6#lT;XGV2i{A4UN9V}Ys#)|9mg&rL^ zCsDhml^0zl%{fQ*`0Z3Eym7+UW8I|O?5Dk~rfB;`zH|=q;3)pUd`i~DrpDjdmS$Xa z-6(6`7>iHrQeSCW!u|JMjlg{ZcvpMwbJ|@yPTNFKf9;2VPUgqS^h_A;sk6Y${d9BR zTg|08>s=-`A4r5IX<&w(KM#^v`D)n?O-)icnm9}t5nH(Z%IknjcQZ{@ljA@#zBZv~_z8Deu!918IhYr1f@#Fk-auDH^qJ!CnqQV+_Z z@#j$K3r{6=(Wx&h_QBDiT_T~<{BZKiQz9)` zy_BpIBit-(W>FN#uv8KdoCRulNm`-s=!;GQaY+s&B9)}B3@Hx}G<|!Bi0JP{jjfUa zIEJ0+&xLC6)osC(FR^Kx`A=3!D7y6v+LP6N`Ol?nyN~uTB~oOTz>D6|LkJ?lVvA2e z;^5&Jy4#M$<|aAsJQe%KDAt|m^z=R=+4Wg=ZzYv{n1rxiDMQDmvl5(?$pBjTW*j)4 z`?wlgSH&mfIQ$WCzElJOza6m*RI(A9w3WR&K7hac(Lmt_O6X?SvC3O~;Mlc}M{L+z zR(NAbCyATDTMl^eN?LrF!o0Cn8WOpl7yU}E2!VJ`SZ%pA1GJlQueMqcJ5=c+O(GU zwCU!Ip_Sqye@~0*UHX;xW?5fNf9+#=9QEswEk}Ot zeHfYd$GaPW8$~nkB;`Glj+0B3GAv zBSbRMQ;Ef~7f91nN=08u5*}>~%2$e2w@90OCb8Mui?=4Y9ES$Z4%Z6gmh25VQ=2)C zd`JEPyPoWqS{Ue+WR!d|+I~DVvl+lEPg1ehS40P25;t~B`f8_*;6T(TDLi1PHoBrS zr1XN0LYK9X;;Cu)(ZN)8RAVUU8>QEcCCq_JcE>h#3>&Q!;V{Wmgxg zT#59y%~bsx<@5t`YX>;x>btFlydHN-7eMbm!fSw?#@oJ;U_&8F5%>4&&;u zxsat}J4J^6+%chm8}_#2rmRWu2V4C<41-*bGmk*=;+XV;-OFD@ZE;yK#!JWTCbnzF z;5G!$&4$sn_#F9rW;`f}=q8Eky`7dYI3^DboXMva>y+!& zF5&Mv%RO=To3^?b^ap zxTBSZ_jv1mq42qRU!6MhaZsVKtI_wW@ub?*2F^R2bh0a#L~SN7#XYp`TeqfK;3!rPU9vC!PE<5c zOcA2#q_Ehk->Ns~U54oMnPeiO7+Er0fOd)a)ti1u$yluzWy~4JV&y@DkkZJ7PEf zj1fuqH9)I%#_G_O`c#;(!Zms{YeGY2_v%i-B8)6BI#$`;(tePjFZO^>{D2{~-!&Tf zSg+Z$+C1`G?$jGhAyN%LTT?81@{vG;DRO_I#~!C0^>U{Uvu( z)eT-1y2)5$H!)#%$=_rQ?K?sa5ayI-+n5h%_Nb9RwixR=o`mVQqqrcuhp$Ei?i0YT zMnB%_g%jEY;k>nr;skcjl@s5wCfA(tPIe2J`_fRG5G+)7&PRG_TKO1)-9{^Tl?2J zWmQqJO1;sfEfuv9Q=L*2JKaJ^K*3xDg+RzfNI`BwAPC-wmz`^`LQG%88%JMxf0_~x==D>~+) z^haOt2m_yFapu2kJNE{mC9b~zhrgDu7y{8>^>S{IRX;QcS&U&P-E8P2133v{gY}}N+n>MHs;x~g?tC^jow{h@=DTe0ob*I1%LHo-Yl2dgJt@)W zn_e%tJYn0sI zHpnXjMM=E@EhjW0(BYNo2rD=Mxzy99M5b*+tVPzM%XbWi2-{Z)PQ`$yo$1d;$f=YL zpM3hq_``@SfCBBD?r}OuysU>#0sbTB!8j>p%&^OTs^2z>A#Gv_Po3Tt9$e@snM-b4 zLtW+tDE&55aoCd!a4Ud5ACLEb z#ti%E@3N^Qcf|vL;+Q!>GK;Jvn6n+2Z9i0^3z%)PEyP)Yz02SBEh%@u)?7HhKW)?S z{Va~MgTC~mMX0mnuhY|S`I-Uo4;(Q22_G?EC3P!WVmr%>+&RwRv6+cD!VJnd?r-E| zjNCE$j^y8U{AWAr5TWL7^jypP8G(8Iy`NrOt-crmFB+m?(_#GpYLl$*Rq>^CHoaO@ zibCs{SC%Xu^kuLd9ujFM!bY^kzN7DZ07p)L2BKTc+I zss#>OKNZYwth!Gfl$g@b$A8Gj78u#ttl{Gh~N{+ZoZ>&Gem_o6=JvOz&-IXdN$ z3NNV8un}_d1eo8o{ZgECg7anXRL$Q-6eEc#z3AdJ4~gDf)rTH{Yk4y4lkV7N0$rS- z41YPv!)6$348^UwHx|+In}q1+A9SjUR&{JqohCqu9{Meg(mjxueZxfavEi_p6K}r6 zXjuqBhlF5@zGYzDlqA@XbYhDvXd)X%*Z@lAlK<2lMhJtBzL~;qW_9z#u6-AYA)Xf?J(Osk1ez_P56VyCnxnyHuh%i41G$kE4n{3 zFN5!8WCu6L68uaP+G}~gBfvg)g?Bsx`3RJSJU2JXFB?uiHauUBMW=;~r(2=tDN;5` z|MdzsXyI6h-q&yR@jWftoNoAMW3;I99jELAm1tIgy>PkXyg!Lx{+d7*D{Mk``1mM- zk60hSda7iwRzOail3=ls!jsLLlRtji2K?X47vy*im)}LH7+{(%EO5}Vfk{nmWOV9f znW~U%^o<)<`gmOeeDH%DgAhH~#>tcAtDuY5Q~3q`nNT_gI2pB#l{l5XmBJtwfwi$z z(gqvoE#bqtfbhy6?K{4ui#TBeS zSOm)EYN^}(+c>GMLrt;OTx6U{5Sd?u2zl`<8~QG}WFB3aOL-7Q?s?8&zkNlvz%o^* zKZzzW!VY5U*oZDaNDj_%Q^}hZY%5puriJ;%Jhb@jf*$Uty8v{K`9y3R)psO?d#cBJ zV)wkhqX{#sePm4V{Y_xAeKMYV4PWcEcOKDq-I#L89%9j^VP`$8GfwmUzar-Tn`Ou5 z6@75CpTSe27a81xvuyg0BA+>Z$?nKT&I;~g`-<<1d;256@_mJOJpy_M$j-n5&mz`= zO$=b6U}N&81-TdAT6Ai2Vsq3&0}YF(UN1z%M|8+UiZ?RLqrbjWSerSrS-8Y3KnCpq zXeTWyVXqg;pg?i~_*c^T^yL$E@!hsc%CH69Y|KCs7d{TPZ7NARu#$}&JNSUtAE%-N zz4}M;LbLp92~2`x$f`;UlUB}m|yFZqxh z=}BOSEn`U=`-mk#9ihm@F2Ht-e(MyPCLAPs5Er))sy`ZEH-Hbi8q4CbKFKYcM0^V% z12dA$F$XK2%;RFlc4*Lr9n_(tO&#F$9Diwot8t*N80y8Qu9n82`uI)3@X`a!?ZU3F zzCRaPE;jidUb7jC9>;Y-124XH!1hiLKc`!fQ@#}k`U9OVxJ%_`dy@gZ??Vz-zxK`} z`dLS}srTU%HU{En><)e|YhBpwnENlaV{>$L{o&)gu~{R7OPTdK?YZ3K&K+tyAsxYB zZZn1*BAdAMF%3;@Py1TFI}x~k1pMxdfE`xJr}|0g?Xeb3~Gu zY~Y+$B>~7rxzQGv7n)}}abqFz=C768r4-g?D8T|w?fCeZrz6?8`AM3GAJA}}|N5aR0835P(c`?2Rh_BdCr*hJ#HYai<5B#+a zl7kP_#&=FZ%bwcMleCb0aGJwMu>4>%FDE9_Wf~NVW(8pLeKTU6L~5%Kwr#5!@dN$d z_%m@nJyaVS?8Hav_`ai!ck1`xu{d;Usd&^z zLE?{Y(H6UToZJbaXemAwIoqV>3OhYNO~gA+-<-OuU)lBb(XEpl<<8p#wh$}@n~b@aO#qA;eHH+H|?>sZE>XEazikc;kO^d zo{(&P?hN*3*~jK)?-g?&BXCUs@8hU_NSj$;9`o6nVVvfG6pX@k?>s_#BN~eaiy8|C z8y(4yTD3T;Ml*jZ4ng#Kb4RG?UDuMxLRFhml`L~Cz*smz8k!JHf+j+2|0 ztiobolU7c!*^z#UF(A*Ubt*Z5adIJj;CO7 z8^bReWg}x0NRmbyy|m$B1AM9qdf5d0fQ&@sWD!~bT8y%vB%Z35{gt5A)3m1KVtJIz z3kHEr%~f4|GN(2lEsEQCv?PWwGvBaBW{R%b@Ov%|n~*<)^$jF4(Etx|f*+fWSDn8m z!`J|O(hUcCbvEiJuuDeCB2LJG1~Ra(5AlN}&U0pnLsBK^g})?umFRSObU+hR%YW|E zq6&WIp}p!`(RKOspT%CGVUE>T3yOQD?=lJHOiz5m(`9$Qxjx(8+r7@*VjL5X$iWU` z#kgDoWYt}BPStf_dw}`O%=6mN@agX*-PpkQYLiTNxt(^dAJNTtiTAyb`Ik7)@~-Xs z8-Z&Acz?(4&X#jtqP5I7Gs_JNSZ#4E$f~pO2r0BTLrVS*>?36o#tT86#Kw!Caz}pu zt=@(500$caNfJLVQ=6zz{yVKK%52(v_sb6p&>=v+5LH({iwxh(LOwQf5=fgx4qUxN zCndpW!J@=^J%ns{Jbq)Y^dfBs9(aDPpMl{YNk)3x+sakahb!@i1t*~=J%V@R?gvC;D4-zy&921rtkLq9#>WR94{F8+FQ z7+jw8CSwG<4SMQ&{k@GA_h{I(mt5m#HX}co95&^w?t^jY$?eJ;caH4u0JgxMfy< zBR8@r1F_rj8pz)7*a?rn9hj#8c0J%8Z!)Xr!(C^2-6kY&iL&b0FyAw?-TV$F_eW00 zI)9fzQw2Cn2m*1NIs`waK#( zvRP&U@$byFg#n&dlED+X$VVKT$zw7OJrT@;LlUyu%%Yc{^kXq+fpW=4sXE{1d(8H% zCMZsyyePZQrd10ki=ncfn^Si4u!|u;4lyIi z@))VT;Y9;r133B_hx(2rD)mn|0J}(fD2XwK&{I`Cqm45H?CB+S5>>ElHm0{+>5)># z5*F)`2tr>oQ4E?NmoHi-s{mSyWBIP^b%QOOf0Uwj{o)y!6m5?#Q9SI?DT@R6l{{8+||2H%&>Ky+v3X;@{aKcMt)ufTGL4qK2hg|?AX+0r(Q9rI0c8z@ZAN9 zmT|iab}4EIFiT!e*3$BJ1SkZ=_*e3 zU_>Qo*a0cF;4AUtgbg44P=Pv;S@u?vg-(C0teu0C&8QOEn*p{_#}{Z#pb|RdZgWL# zCsQiH5jS*W13Ce?q5%vtxKM&0WLqq&T}iY_Md-MN3FH9$jV+s?bW&o|P~cN)$3<^a z&}_Nl7a8(B??&A4giSSZfYxG$tgZq<_yR;`wQgS7c%hl0A~$2t+f0#c-02~S-uxd( zOe8LWRt@T`MCM)O!h~#eBD3CPoQZOSHK6;rvU}#j|JXU(Khx5-&5JmO*771yNUAj_ zLorHq5I=mn3+z@FHF4%XZ>rqUG0dY5_{XaQ@#6O|v2^a6$A|tdv(Ev<&h*g}9?DGz z3@ck+mEPxQt7_e_s?Xs{n0=&e^R zsw|9!r>#x__O5`_JAAJPUy6?;Q2Bv`7N7D#0~-K9Oh6&K5+{>NhxkoVe5oTJA82n(hF221 zY@DU5Y{4Gv=7l}jV0!UUXFPopj35D5^kWYv$818CuvVgp9Q42o(1sRBe5r3f&}e`? zeNLqdn@ZxaS8c?C!)0EUDGVP)gU1BMntFZYE?)S=m{MIEBrYH<9YX3=xZW?wA8r~A z9ply^!!gr#n(7;GI2yZUW4xebSABI|$uEAzBNMzaVi%_J^#$Lvj#48S)s@^(#kaI6 zbH7k8-r)d<0V}@r^%Arg`%^-@8YlSB)kD?kihta9l7Vfx zpRB)K7{b}^)_qn*Zy+|H_XxTjop(+ap}T9Gk91w}Z*K&y3E5dDfW=|8 zK}IRGNkY7ts|}9LtuGj%PieWjQ0l8%N|-8PL)YJb@Ispir+WKh6+SRd7zV=YnJ#<` z3GY)q=E>d9ww<% zBea9&XKwuG*wjG3lMnHg-jW4hk{nL?`~U>9m03m~-wEW;^@XmIj@rDCi|vl9>d*DD zDW`|}zsH$4@{*L#7p80br9pw*tXPQ|?_~x?iJ2vCeJNMH@_I4`W2*A&J(~bTP zkqIUAUCop@$CrcxBi9P#H90f+2A9ea)xeu@56&R zj$2%?cO`5Hz<>CUTuLl69$DWK!*0i2>ya7y*gnT1{gmP9W$#a&u;r^D7u*i{wY+B$ zxPAxlo(>iu8iFM(j zTo!j|EKfH32~_DA&wmstyi#E`s#qtssaIVtA*B9^kva7~Y<|=P^0$+rB{@v;=I_S| zNkaEhc#^#Oo4B=MIx&+_lDch^u})&mZ|-3qa$`~XA`%1RsXVjdDH39aABnLO%z=B* zY$YBgfCocH90r|b$krs}9vj)m=EhUWwo}YbXiAE#h!G=pY9i-_zPqVE3|MvX0GdE$ zzh_(-PgqDioxp0mRMi-lKyR|*$7_IgrIn?(u-1y0LlE0GSC|i(v&f@OT&2b`=zGBv z;^>mC#FaNN{@c>bA?$%iFXRHf4u3w{r!TracA}>bAK?iQ58`}V0+7=;<`r^L-^5s4 z^hI_`$5M^V$>5>)7~$&>mITgYA%Y}+N3tX9wi5Aq)zqtd1ikSM8MB@v+o4_Y!OyIS zuU&qZO&x=<={A6txR^)8nL|f>8PmiRx~{wP5nuX-Ilb$we#9T5RsYHk=vTCnGnaCk ziDRC5uFSO8_Wg^%H37VTWA@q>vzYVrXPq3e(Xz>D@oTG}6FVWHtt3x0qI;o@8ZzkN zt4**N`G~AGQnl4jQbFPc4fIYp=u(3ujbsG8H@uQMe6a>6Mj&43XGgT=Y=G@f>Pn5| z^TWV&7at39_k|vw6trH^a3WP7GZqg0_GctkEW+@Ue2|3luaX{YPn=3u=|lrin|C%M zep-c%T<)Jp26q_pME~$P376ubPWYZExy3e4I7#;WAcu^B{{?ZB82{d!aLDCUu>&8s zc6h8inlT|J*dFjWnSc1II^$GhRSC~y;;Mfb$LXfWNhfTK8$blyuM&Cuc(?V?DL^0J zVdN*HtNq~g3Cp2RenU|I?W<#Mp0dM9ml!k8EJPRB0Cd_44@DtKsz4j1Ue`;#>-Jl{ z=qG`+-J4c^ovPvhaY;Wsu>slWcd}qxu(8GspYRWw z`kT;$c9SpC3s91Z02wmFdcp#Vu|zj^cSus#anzy9-0kw|tAw-!MRsWEe_aSKdWe0E z*i9+34=dZTXZDf!dcGdWjt_}X=s9`54MGbYb0f)R_~zIpX->aP^PJvdFxk&|zTyq~ zfi2kX?-I-D)f)xoF7rF`qj$Cg{B5>`cP{%}nftEo`x}940(gJN?zJpu5%DIdMWzy< z+JN@NuQn)c>sqX|NGtJUljGqFf4r!Aew&X4kcBA83bIN5c*2z@bo~^pRvLJp@g%1# z&8AhGY%Qd_15gM?K|+KA>?Pqq7dlD~_1fryk8Ego#~PpTlYc&CQr$MP39||c>aURu z+2~@GQKawS!Rzy-2PUmnH){hpFPk`L_mOEe@< z=;J>!W2^QD`%RmZL7O`GtYTa?SzEjO!ncwoevCxEh#4z>8!;O%@skSMAMWki?@r@*35rEL%$ac1sOR$nxjx`?R?=m+ed8s-xY zdr_IB4_UN}9wrT_VV7OC(N6)WIv71{NKo*}eG)+3KlP)|A;NwA z!qoTto)W`)b2WUzx6Y(GzByS^$$gnbXCgan=H9^188+E-$5*LMEHeLYvwNdee7dO_ z@0Cg6=`_8*;^{d4noe}FB6W!DOLh~}{AARM-s9GVwtDD2w`k~|>0`w7%6iz?4y(7> z0%PXvCA$t4Ts!Vn1X!=G@O2P@EL+)N;xdZ|iy=UQz)jEQ>{`N8udDPKk+oZe49=SlpAKTRsZDLCqdUQpm&^}e+jRp0L zvBw#og-i_QP04davPim+S8q-7B&6!b=oew%ftunr}zR-)bbt# zz7Emdaoqc{J9yZTdmF%)wFB9)d8Nm+!=8Jr)Qy@xrSEJUA}AgxWSM)AE-m9{GD>BsH&I>Noi;6JA(EbO^{U z&HH8xaq&_^S3Z8}8yixw$qONbjfbQFwY;FAti-8sCKs~kkOb^H!EcF@dO~3`DD9s% zcb%B}?*yYC{`qe_(I}`f1z|NhF$35qh80I21*Ut!11vjhNzFT zcR7RbtYAasV|BoZI=hI#o4#$X2!QR9@Cm!|>A}lq>TEx>CR)s56G1k<6D<5lY|HGj z-Le@B`1C^NXxdL`O;5=``bEbK>5wsXsXk;CZ@p2V?)lW1A|sN@K5e9mAwCA+Wxk<5 z0BxYEylG-?$#->;h~mdKRw9PqCxz5@_J}cUd`CNV=#n5onEpQRBY;@q8}I!)6(?tqC_-HVpbYUDv-6jf!ap0de8}y$u)-=3e4* zNj|dZ?_(eNPKp-l`uKF&_|)5xb3~v1Ue2~eUdm2OeTDC1TM7Nng)OVNblW4d+Z_q; zg1^H3kHGaK;QK#@ujK(Z_W7pFh9%_KoKi<9H~CB}GH<94{nr@i4}Wd+c>WtcKq0fFX$&80son`VT9F<4#!e;5+pvBCNxjC zO%(oGSiw8tvtf*b5W~Lc#UJ~s3beEV5*GWU(tL|(Sd;QUerJr0qLK;{T@s+$98lST zwo&LE0%UDX5)q=_UlDMhWXL8Scu7plr;XW^vO?TZ4Xv*vkndPvJsG;(|R`Y1@RrW^AAB&qF*O4`t>4{$hz8*E$U& zzD`Ia10BdlFE45FtNf!q`l?#A^1o>5gkB(q&Qr+!T2z&IMHlL@13x+-ry_%|_46+9 zc&t=XcM>M1$SR(S3F0!Nh#wCq0qB8`p9X@Dwl_=73utQGiiZ9fN>_Doo$ZDm+{|kq z$7bDSI@K^`Y*xoi8=hXq@7b@&g%;am^O=q& z2;X>hIHCx;%yocb=lBg3LY{$Ju(1%!Z)DXLVV+I^}g8^nJh_^9agq% z{kSsdDQDWbz42Wu_bvk06To{nWN&6Li%ca>Y=~pUS%_lcftH)R7H^V)J^5I$_}wz= z1#hoi5;h!HmGkC@m_`q|WLp@u*YZz!?d zHX3w^$jO7Osnb1-tYidV9?Nt3`7W3W%jYR&PCWV1WhczV;@_JiAww^A-~)fz#5#sj zb*r;NMFm>hE!sMf)l<)k55LTZ6_52)b=4~odG=D@&lC^eS>v<{qmX~L;SBw@VW^6a z8?9)zx@gMgiamb%R7A+|Sxl+3`HT~8Xu6aSYVoh0;HIy3bH{Aha8w|R=>RQYozg9| zargm1r=u8M1|i4+rX6*9Jr5+ovA1QRWITsl;WNi;j__SS;*H<@d`|&>af4unp8c^M z3@0(;1-M?-?F!BIMr*_FmCnCotA_W{4~9B^74)9M%z7MmF?2l1ME_g7k+v#Vw7GA( zOnB$Eam~c4HpHY5xr})d_o@4=+2iim%f~s+*u&`=^CjaGA*;B|_A@^K&$p_2>}MPM z7|r8Mc|qMzFXtD^oGTN zg@=#N_}13GEfqQaEFN65ASD@KQK-IJ1XvvMvmjfCd12Q!rxl7MgoiF7BZ~_QNr&pM z1jc&OKL|IwwED0a(+!T5>Xq7TviUgA_#ynE^gDrb8{S%ooj3`{2JOUZBpCS2sn|K} z4_Q2#y5iS4eYJ8!Rr1Nth>(m`BF75KIIxaBQF6d<>Jgh4!g;e%2e$GZ8|=~kV<48$ zp|_&IVqB}S7ku?GCMwETC3t)ytzTiZ4E*M=si>&aD$za?F>S{cr2qmb^y0gT*{qU0 zxl8plk%j4AUBh-s8q8N55k zMQUvGHbH7seyh(T_1rA&5qz_odqk43mt@ z*F$$yhBoqNI*+SV%yhFIGvC~Z|eP>!G5j`HS z8-q<0&TNfcTbI3K?^=_`;|k4U1Cj%;8@hMV4bNhKG2SB~V0lOPsEAR8;R)amo;yZEk-Z4@K+usP>N+x}2F zfZ>W04NhoS5z)!UN2^Y4N+$UD-o@o(pmSVplpWXW$g&#`u-(}7~VkZ`0I*Yj<>n%;<*N;%$>heX4RV^@YXot zPD4v_!6x5&igt9}C`97K+ihaCWZQTN86x=;O78m|Gw2S~w#)E`{gz&N$& z=fy)9ksBg$ZJwf$*9LqvIv$K*Qy^C8bsR*L(=1L^o zOeUd#M3^`LnUATL+$72-89pJq+LS(7RVDoK2a@>R=S#-ZGI)Y{_=-Mo*v)(+##UIW zEDJp5=3byHWbjiDpc~)#%}0PfCm7WX*^SM*Y}mSsk2vqBt;XE3OkwQL*0WcL_XxL< z@sSBYEIL5jeMn!~er|!~41$tb4J1Y^W#UcmY)f$@HoN?Kiaou1i66-55M99$58^Td zTwQLrtJ_ap_N`ti1eCgBC$HRCHy7tPOS~I0%ujJOJTMd?B0<%WBaZ!exUkY_`zu zU>Ah&hB0J5)6M{%Bnf$0Jj09r@I}_VDJD@shSVG8GD#A?+F$I{3)w8s{9KGTDe;p? z5d%&^y|Bs##sxsPYeP?LraN|0k~haE_!y%kL=`vm){A}sy8<4YtwA}0$Ur_k zlu?e&o89&i-Lglgf6oCgebDoPKhO}zM2O`mH5+wHuFC^C})6fB{y_; z?YqtIBRR~mB#O`^=Ge-8xPqQs5|{XStb_aDT+$J3sOX<*Xrn9m*q*Tr?-uVMR9fC> zTh0&?S&h{9B@Ab$wm5o)cRB*s1n`|6-g2%sx7sN9-8b%Q{vrW*pNgquQ6LfAH_B>* zPco8?^-{>7=UudQj?EGrfNZKPXigwhu9sVrZx{I3wcxE2usR7$B14%vOxTH^EM}OH z1wMV*n5EwR*vA7AckvGyn1e0&fNf=7mDR7h{tfqS8@kW|J--(Spf4vyPNu{_tYZg0 z(MEpZtIQ@vvIswY_*8aOeDR45(z2|rE)r!MXyF4N`BDNe^|3JzivWIOAbw=~p#}+m z-hSAdI`(0A#?$gpJODg4f+FdI{(XIakna%ky+-^n zrMT3+SXS#6y3My*P{j3k%y19}9W|QJu|(I%PJV2q1y!`xU$_ zLL>$+NN+$aAPW(jKbrw*~dh%p>R+e>NWe1~6nM)rFE+!%w^!!+>ehm`Y^Qj}FF+ z7j@5VOi?Fe3{bauDvJg>PWIF(-BipsXcGy`HqpMhV=JgFb|`3o9_x^GgHcx)oh;ceNdQX#IE6wSLWG5qT;5_`gY9B8M{b{b(#_ z`Ewf?m*xun0D8F5F3s7Zyk75n1g;6-eILO)*v}&Eds;VjHpN=}i@CPvwvvkO47PSr zdS?>>GU)Q6BEepmbs^zkVe~1V+TiQtZfr8GcdL@s? zaEE!IDxs+avwqG6q+SB|tE5RXfZwq*n<0XU0~-XgoXBCPKE8CU@Qb$kNMiWcfmZaS zL>4~*!^e!saB`&Ym_5hK9NffWHsPwW)N z@j?&!eVQzK;!iC3sU747pyT6W$C*L61)$gevkkWryAeP2VGC2M#=Y!7@{`A}PES90 zTBm-T{8h$me^INMyUhXg%rN6L#HRN~DPmX{v(9QMy0BUE^yDRQ97O`pUFeTwp}+2H zjmuEUn67|+=1}NXGB-u z`_6gq*FY0LZq2_kiaDxA2nDS>nH(s%|{`3Wr_#g5GkBs@SRFo&;aywo0U|Y6&W?1G1_*J4K7tUZM6N31O9g$1S z`zc-LUD0<%ofaFhkKZR`z5?`v@Ab|TKSLk7l*G|*7*%#Y3)CgJ=m?$?*`nCu9oo<^ z2Z|yXc&JyrF}uelRI{AmDSIC_rM>bqb8t1Dvn*`kcSsqJBl>Q~wSK=Ma7_U3*Lb~| zwY3hO@n(TILrx8DepV7TJ11ve*w`%Vl#4}@M3PO3e{38qE}ZrOEOPW~?;JF>Fx5$1 zZPN9js>V7$pNzI(sciZ>vF3O`wT-5{x$6E*y3IlocUA zE7QYItdJx;&?W>9{zrAhRWZ;`gWtD-7hLlb^YVF1Ooh*egCy(0UThx$!AIIo9wQ8S zVyGlrcB$b9P-G=0@#shWWe^g={iD^$W&9pJdTe_<*5Zec7d9{-YzumZOjOffKibXa ztj;%pE+6)sv^fz{Cw}2`N=6Y~wF#=FtlWR1jRahD^{RLw8w9b-oCFm>M>ah+Qe>j1 z$J&YSupxYxO7!<6t>)Gxj_S*%-ru-&F64%$o^@j8t1%kN7IO0jVCKs`)<3T8G%G*p&s^?f6dUJ~Hx9R*V$VF+_Wg*! z8!pTD!?~-KA1(q~!?(?jO>bK`jIX{Vf7ZmpLbjm);Jt{d?&Pr0P70t+k_a)23$j_P zDA^!Xv`q#H1#CRnk`e}ZfFz35y8G3-L~b7`^#W)ARSu)5Edf7YzN$Zs=D!mx`|w{o zh=uqEiQ~YKP;sjUH{p3V8whwmR%nw4ElG*0~F z07(;Mbg?;boEbU%ULHQsb^;xn~ml!rip%%;wf0&VEfkA}4Xhw&6xOyag>jvi=f9|1`*_5#oyCFAKgVY^(ipLxtU zt@LBk>a;MTS8}m4>(982Lw;DUbRQC5JMK*ct|x%^W~e?MLu;ediopt?m4n5DDnH+n zQxj;sfsjOy^JrCph7Ev)h7+gfBQaqAtdk{+6HWQW*Rn|Jkg1;GY$bZ}oP};rN(vi( z^k4@N8;j!n>O?^V(U4x+USvUxex#uf$VTbL;=;o*>?z{%1D*~ZGa;=L8~E3hU>oB_;!@_;sh=rD=a`DYV=7vYmlRZ) zQ?U|gQ`LtJ=!2J@=;NdjIkW#F*&sF~`C=pi@bIA*3<;WhbfJ%!c+RL^^8&qcO4cZX zqOJLYJip=4bAQ^2SK=7F<*TtuRD*jZ|L+QCc8cwYGqP`!OUyFHXS8RskF->B?Rj@h zGUj_llB?&on9h7TQ-0paxO%)jC+7Zh<)QCXN8zKeJ% z24yn|?Lx^Fb?+m<(sPA(JpyBs`mk-w%x5nZ(iwh0t6oCCI>^S?lS;y7($2@{Fb2(64ecauaEQ?%ffEGRANXNw$4E- z{@BRrA0~QpRX5`{k(-GGWlmDql-Z1;k}~rH6Y!x@yONKf`eo7jsO773s>M>dVVx{gg)s9JzVpLl#KGkED^5ocoupaRE>jW>%hx}wj78dhVeH=4NOt)u`U_N0Z5#vq9Z@VorKI|Q)H&4N^D%p6Wb#3PRRYy zRLL>1F6DP6Rp{VUZI$4}7WkkuE%BEw{^4;?6zz*>=?AdAHqQDR$dSkCUd`D`Oqn~` z5aAr`mO&yM+t8oi?JN1R$y7D>cl`r771)XlzUEyCPUiiuzsCGEyJH&e~MR0;&6$o0^+E8`es+*CG*Q z!|gQiv2i*XXq%`{e3YE=Q62rfDtTkG=5PA$^0trjBp6#*kXd}Jci?OvwyF&tel`#A z{+L-keCLk8FU!Kq_Yae(_ESl*ZeU&sj7)b(9w&Ebc&ZhiK0h#lR{4X>B&&R!%_dNZ z(7?0k>mN8?Bt7^<9XlL<_~ayYY{g&t>*S*3Y&J{2<7Z!M!$2T10kLr{xuf0tkW+ti z7@g8FI?)HvB!Sa|yJ!b zmFr^Nj#n_n4_##Cdx}zLppTg4yQAm>NS2={py;WMDr3tjBXVmjpUNNRqW|=uaM-L^K-%kU*DMdSaSuHWNDdJHx%VB zytO#vn{|tTdg#?XY!a7NU`|<(@sM((lNBHZ_FHu)9h6eU-#fN^(Lbk0yx33fNpitr z4?FT?+3<%XclY0RDn9VWU&qTlm{wz38>tGUFm`^w9IP~{ygZFWXd$q z;rN)}-~f0L++`aFTF4&9Rm?2|Ig;IJ!Ow6ccc!D=$A~uft?w(v!6swdH2%;58|~z4 z^}hKPy+?jJwh9q%qAX4VQG^Py**Sk(j+&^_%Hl{z=J z+d{G6Ki2Nf&Cg=yQh4gXC~nk^c#R8-3cv=wZ~T>Pp@YN-jdhx*nirw6fknx-nZGu7 zHf#8xz`Mv-^CHw{uVjmjQcNs#-Z;^re^2xU9oi%iESl9<#-k%2nQrl^UBNmZ>$d4O&g!;?C6yub&ts1q~B zo7m>Zwn+lfhrevrq21%7e*Z4x*myDM0(8AcWTm5Q?=;wk9iAUj10CbTNga0bn|z+H zYCFM`E4axCC3vB?1d2By*iug=XZb5%q3Ov&HrgOxv+Qci6_JBUOjD`>>iXus}D*d=hnS-lGWUR=vVI9|7I8tWx~*Vx+Qfh(4tf zg%ibE&s>K#iz7Eab;>sZ^zmXL+!CaLLmnF#rxQHbfeJNEPoMP;T-4JKu(>7~EX?g! z^s~7JSnTjU{>MiWk!*&X-f;>Bz+VYhSpy#iKX|A=^PwMtW+6=y7rDh*eliZ|AW_3N z;tahXAdxKp&E3f+;#09JNmbuZq&!XuN|d#d*jId|n+;m}^4ouG`q)g8g-1y+^W9B! zv*;JTd~Tw*Dn8kc4Rc(v9vB3cFCC7HEa0z=U=Om`botx885{hl@9JePSFDq`~VZl;{O%y ze*~@{0pI^Iyw!tR6m|29^5x4Hem#2pp4VsJ^tzj&;am_JZgOv^y2<$!cz}XL@l9`h z%a?E`OUOf;WU?4rwk|9%wQrO?(FLC5#T$8S8@3p){?OXk3m5dW2zrwk_Q1Q@q5hnr zfe$@#!VY+Cy~_9kj^yPTzo-n8P61!O#IHSR;%~JgBM%yoD9ox`5;qkJqHvsyNGRvbkxw5968$Iu{1Jn@M?3+L}dmRiS(Cre2P zk?D_0OYGSd*O?JfNgYJSKfC;iZEJ2in0wqzSGe~PnBE`Wdw;GDEF!>0 zLQ=uz?`@F3P$A%kW<&Ibt~%{XaCqliceqd+(Ep~81p~Q!H%0%g8!f!Bqh6I@Q1?PD z+u=z+IfK6U@1#IzHOg*iBP)yP%GUTypI8i*LrtAoTxo)LA|WL#%*Ks((c!_i{WOsH zRt#MeKW&l^BFATT9@gof1?>j?|OHcC?gIiLYL!*0RmyFqN`DA;uHD+ z^Qo+dVMJp+oO)GU`-3gW#^?DI3OwU<1jw{l5oG*BoAI?db^$q55m<^wC9t1kVp3sC=N6k3U;RGMI%Vb#KDj zLW2KVSjYm%a>d?KNrV<>*#e&Zj(5D204H(O`B<0*%B9-iNPzgB7kFNNm_n--e$KzM zCGs=ycUXjB@*}5Ss%tgH4uFLjxh%>ovH;&F^KTETe*UA>dlCpgj-13Dd7js*aB@hz0>q6O_Wl!mK?bKT6&vKi*T~(6KLGts_G0G{ z3O+zs66fGj9wkQ1f#?YBs+?uVo~Hhc4Y~LO9X@58L*y}4$8hg_3_>)Ok=K2mNF1Z1 ze(=1|-GO^2c62=T(4TV@6>($yR?uz8{SrFITsps+fc<^$Y<3TSV^2!vN#;s$DQCOD zr;l=u-_hLaaxw?Hjp-+bURRzj5ahTe&mO85*a{Pf${RFL0o;iFd+ky!ckO?612L$8X8gDSDj$(VeM9Q5QA zlRuLN5AM*kbhj%U7i}YV6s>^YLF}+p3)>$Qg%E%mM7C zukProGgckwpA!lCi5>BTdbX#=<+7i%P22+jCtZP=hP5WvLC<((Ea92yBPTI^)P8m* zeZB1b$oJft;sHH#D08~=QztIW`TlWwzdsk^HoLq2$enR3`Otby6`jP-aZ0d;u*6}W zThT>{zIwxRa}L^e5zIDq{%if+h`==gd^g7Nq8BVC01JaRceS~>Nj6vnl02~{*P_mf zQppQ^&_ct8X@HkHWYDQ@KDAk(0C*s9L3Kc(+3bU10p9EI(+nT>ZZN7&@CFhTwy;pg zK6J+plc{YVwb(<4OrC5Fu)TqUFBW^_F^+|>tYIUB4qw3(4|QU-^P{WcC?csrQ~1Pg z*tKKp@BuyUD18#6pTW@vtfUTkbh%rX=th|9wqk4${4|a5&%q5^=%~{Z8^Eo=bR?2U ziQd74T;fb0^~8%9nNL`3^_ivIzz5R4R97OsBixnh=| zcPZNXjYaz>9yo7+jo-0$NwMNL0;yLj&*@mj8@V0kws~|(;*?l)9_mGRp2Txtru>pY4cD>{the zvRiEt9Xy_|%`Vt|LaNT_UnQ=52a``5##d2Wv`g+VZ>ijXy9aF;T^9}T};0xIxM!xViQH27YWg@(W8%kfWD!w5Q{4tz-=@e z+mO2{PzUxqec@wFWC_Q2AOZS-BqezV@6E)N*e*K%D?73w!E5_1Aqhh^=Q{0jm-vY< zs^E2kpnAm}*&{v}Ch!x+#tyzhZ`ZPz#DEBgW>0dkozs~r>*HL+ku2rsP_PA`O2Q`E z32~1#G7|sHi%?@n|1Mx;!Ox3+-V7vRa}3aFnMJ+DP&jxDDxtjzSX=-pytJ{g>ZL2J z$U_%#$_dF}cTx5fKXV;fmWz#=9-R2_GeBUGbr(nsphYKqb*gmEy%HDtbIP(Q_WRGe z-NBx2N94`&iBl4R(A=dYPQ304D_hWue&$y0C*-YY!H1rBc6#$Tn7X(GvqR|7#r?J< z+Q~g$$S?Z6!}n4x89TD+Ll22xCrP|lPO>sKz>EP$RP5@cdukf{t0E++%3X4bT6>}vqFMM94m5@KBRW{T{%i>Rx z15UTU%1R`v%@sQS!Dcd$f|6aB)Zy>IkPmf3NAJD8ZhLr8pv@i2lO9xY5=BztQx&yI z{7A@rVyJfXZ)OSMcSRBcU1EX#S&YkGweeYvIys7jk(jAj2}doNBqkMuva4j2fAr09 zp(px^s;=SVdwW1+`lJ0KkyVw%)woHoY>EBYi>?~4NE?i|6nI$Q1uQ=1M3+E6F+sZH zqE3=AgX$HJDG5b@NMaLZ#xk-q4;c&3HPP_fiHs$HpXJ{=W+v*FVNypS%WsHeK>xTA z8q~lNSHfqThb%VZ-VP0Mz{=O%XyJ#CuMFgb@kmG43r*M6d637egZnj=79rWmGHG_q zVeQBk`!cvZY(gYSITF@+pm8h*-#kVu8GbV`5}Y|MEBcP>F$6!iLwkfzKV`SOoC}#s*t5&kxA&hJFqGcN2J}`Zyx+)+B)ZnXEtk(?31^;UE6t z>2Lq`Z%?22#3xSQ`JLZ+`uyiVe|rD@_dkxPt?j&O2R ze^QNpfIc?dN}#H&MTCT^R#r}!@@L)HhynB=BO4bQIDLd;h&Ej=Nn+f)A_(DBLh9s6 zhL+|=AiH?rg^y{V zD4~v*1Xza@TQ>SsM<%kJ2&u%fN0Ln+e1MZm*D8k4R*!7azZwhllr8D!=P{`BAP2yM zBj~~o90AMA^aup4knFJ+PC)+(kYyiq;jgyvUCQ{l(Mu*iS-dWqUWSSxwp2ezPA38T zZ8~C9b1eAyhDp?kH!*zT_?A5SEJLzuEcbD?g2jbo4__Rb(O+|-@STNC7v26YSnrtX zM7TVcJtOIW1lO?9K~aIc-Y?W4$i#LJAxq;szTbxJ0J0H}Kd$SNzq;XmdNp3qLlZly z4_?{L+!Je?;V4Gf8@@}i#BSd71sKB{ zf07PKgJz}=AEoc3LEHW9G`-$!hn`!qnX-{)Zf$RphK_FcMyyJFM^@L-Y3BNh&c3!e zI`h!RZX)eD(+C(-uPGP-!4>Xx1m21S@WqQ4r$73mKRW%=Fa6T#*MI%j9nin|o4+~z z#83Rh=}TYw(&-0(@CUW<-M+Bj>yh{fjAsGy&uHl8eX3P}o7^|EbU)Vb0&=%=!?Rcd zY^?Cqy{?+@;Q>z_N^iU(qP=hE)kY2r4tV4M&;j6i^#u^T`{|=`0T7eK&U)33?Xbl@ z>rp#2By4O*BoxrR(xw`JNU-V@i-nuSZzMFx8$!V$3tj*@d{++$4r(}~13dmXhAPdY zlAm2c7BYvpji%@;KGi3^;xS&Ob*KS9zv1^#ck=`N#1CVLKM*1xUXfTXT-deS3Fb0D zi`@vRHxRM|C4$I7K8lDxRmaUp*(chJ%MfE5z{NHy)v67~eeSdtE|#xc#kNE*=TquInMTv%K+a?Oo#!kE2ym`iLIw&D^9WV5>J>z%RHd&HxRlJnLoUYTi6f3(27RA zd5OG~@F8=y0Umsx!D5`ki~hpW;}hoa{9=RFf=BY*}jKV^5m$Tkr2kI#>93*BmuFHM&ysfLdSA* z8FCa30MCnr4q%gctR%C3nnraIS5I9l@hkn?IEsRQZ65k`Jxmn}d>ClUg8MY0tbwEYZl|I-;cpBBsDm3$Hntf6SV-L*z zvy?draFTGaqazZj=&jM2rS0t`Nd2LJ+kDD+=9KA@ExV?w*;`%Eft`$npZ*<&g5$nn zypHTh{7GK>lfyT34Lv=!a~x-$-VSYkBl9a?`9Nd;!k<$4U_u7Y_QQ`4xWl|$LF}LV z5)am^8R!ENH)b;TPI&lrg_~T(bK5mOFlksX&Q5J_W4`v^%Lsg|31A}j*MI%jr{Da| z-#q=~PyXcT$A0X`PM`n$=TG1BJ>PTsvp@T@)35&OubzJNM}Ksg0D7WxCjhzw_D!x( z*K0+9Mbw*{7F52&#bTi!`S9XeTSRTxELYix;AE3ag2A$a9Ds$tmNu38AH31(K^Jno zc#BVBM8?Oa&y9beKbOWTg&Y#l0-n4c|;wXH#^i|)G}Y#^pN#XPjVAMXlt_~hUhI`j!to2pKUqsCDyxs>|)sY zYQvanGx=FN2@-q&_uC4hBZ<)^n$SW+9cPisv}RtA1feFnp#yTyCb=x^`kF+l%MT?u zkIzA3G)xNlR>C*C|Mckxr~mKI{@>HT`d9z==__CPyVJk(5B|aFyTALpPoMeBzonnG zD%Q?dVXQT76FgNqy=~Ej`L#;^U`<@Gtztto%T~`px6Uu!$FA?3O5>e`vqa9_XLIXD z=M`};BXGXEd`vF<-QWG)>34qTcTV5?z2AHK>}Nk~D?a(jPoBR0+rRxp-(UR2U+8AM zIV+jiEFylX{z$)FM*Rxs5n$sadOjfX=2?p|_=JniHw!+oPP`Le`k`l|r_aflLTy^f zuCX}zBW7=q!trslB$<}8zDJLr=sRkUwa~n*@2F{o`3_azDJrGyHmBU`}t{jNilja z0dZN4=N#)U109@@*Xy$U&e!Xgoytq77`ImqBmrev{`mg79Zh3BE>MZb_$fN|%;t7~Wm%cPt zPw_$Hg;pgryu4x^mI|*Xz3W-b8osC!}BD1V5OF84- zZ6fxW2k>Gun+J7|&IomqyP5||_N3di47}j!*tuyvd-hZt+hcETPR>nBj}l=eJq#go zVC9sGxs(l#d0@QsgUe>ky+2f;&U1~m1YXMCXM*X19TG8Ms|0aYGEdPLo6b5H4dy+v z@vtX!d_?(SVPy+G6PF~R(T^@`JWw0HP7jZDh;xq**mHmfIvy@rxdm_JrbL3{elF_H zEhp?6*!iSz`x=LIdcH6GWh}6_+hY4==$vFScj)t+SDBBc`A+)3_!s}j>3{j3fBE#y z+NYjBdw%+ZKlp>wKmX_dWC|98LOxi{N)n}eB)*vK5?K^1&@T{*-YS+k$$ z$8Wz8lXKLMz#pYcQ097%c^}gw{wx0eMc`vi00~zuuA2FR`2>%}{PAOL9^91!YVm*I zg{p`>FtmTI1>%Hu^Jew_TLfSWV7Cioe z^V%)|r$AW08rBNp&7#u&Acx0;g@hA6`h3cOOuhJS7-bC^3n`m=$@BuPJ~k|9yz!3{ z0Tvi|Sj3VLKwoxZOC=d%vyE(TuUk<|8GNFTbeT)fhGY5o z8$RMiA9ZYdCcXR}V5?{2M9yRjdWgvk!`&I}Hge!0M$o0~#E9(Q0qlK8vXAhccdp;X z7F_PhnlkBzgWS?!R$F-{_>Yk|N38l`SiX2@E_{eDn8+P zT9R&FV|%w{wwZ(!y}*h-QZuhT4g;CFFw3NyhkN{s2qoGav;28JB<4f>jkyy1wY-|1sP5tBu{&~7kX^L4o;YA^Jjy?P6(*iq6i(3 zCtmp(ixt3z%`B2f3;v4lYk|WSUM#Xi8JqZPB;6;+2%-jQvEX}iRy>^0H5#hO;bZnh zf;O8xGN~H|&1h{rPUwcBe!3@%O@qB8U)gjZ_1MV=ix$HAWILtMrhQLC|MJx%<6dc^ zY<9qJ8T4C%`s&mJJobRcPr?C?ibm0N&(w!sH6M$nNK8r9K>uAqq1uwVOB*!uu(&5( zD;<2?1{|F*bsa@{^Gay&leizz+iv;ExZM>XJ(3qOj=dreU4UqEO0?o#(T5M7Ik`w* zY)QM9nH%72#W1DY6nlvgvoUXq`goducf%^e=f-qNpXVV`#miTcKBZ5jfKPq$Q+gxv zczpDGI(_=npHW;Md#oag@sG{iD~Z`r9KuJ5KBjK&dD?Rfdu(Rj-rnkxVS6@2>4{yS z<9A3*uS;x6lI}NhcfYkF?pnTu5%^dWz{KNIpZe743t#xc>5u>TkA1R7Ldd%;zWYal z$VbCY0>qG#cVFN4ec$I-a3qVr|NFmx`tv{k^N7BdL_l}27sT31w~f=Atol;+4b$ts zR)k6-Y7y8L0(Fv1vS4J0uIRod~EFTfimp!7jjaLLa~i8-DQ0cX9YGWW@_Se&p<|;)=DL z5^^%g$K=SseoBw0LO>heRvSxV1^ou96H8*2#h(}nWw5-|2W{yq3U7)Kk@=7DA^9lF zYc3%lsExYm@tcL}vNa( zUBF_^Sn-`V+%6+FfO9P6#~lA5sK7ve{3c*48u?6kJ~sIwEQUUOz2 zkE#2tiAbIZ#zyR5)QCy$t21IX$^=_8cP*3UyV%m*x{cm;HO*M^Py$F+lDM?)J5{@{ zpZnbBPXFYe{*%-H_P_qyr$7FG{&eI2um79>_Vk_K^uAPL`(|M-ue ze*3q7`}D&<{KKa&e({S=27l|fe(UrDKkx&7IAj&zBm~^3ti&XZSGXAgHs@@py?5-> z-b|@G(HfgN?N_W60`1Y}_d+V%2)EJ(77(rloD@OBroqD=KqUdYendhC4~zN+s_;ypG%QrI&c{vu;haajsp`;C` z?W2w?E&}>Wzni{UFaYwEFa64O7P1D^w=Kh z${UA_JADAW5@Dc3TINgMeDL59-)(}o195~uvG09H_0qBTI;KPaj;&ha$=o)dE|eYS zcJIS3+sMiF#E0x8hT*y7hxLcBm66fyKov1WH;LsXfUgqsGLS3dd$hzJ*@2Fg{kznf zAIyiW6)U?s{i=V~Vf)3zck130x=cQC`jLP9@1Oqr|KWc+{mXy(yQilg{Qc=WzT-Pi zKm3pX>FJxl`CD$p1^t0mHHxH^2{YqEPf1^w(QWDY&ht8T&+oy|=L)h{c6I%p1DZou zxc?FOSQEf3+~4#~-*oz^pZY2PC6HhEg zs3(YPBSAhIke@`%C}HzmIArSCPzVb|kR$+OD#fTS6P<=`Tymzu;Jo zp~VKVsnkC;R+|$2f$(^N95y(q3BgqI-LdRR9QYxN1vr1P1bZq)EPtFx31|C6i(h^5 zPV9V=h_GP;Ns>?YFi^Po3<*ABFS_WaO!Dnc^%sB9^07X8Hkm^jG3V!Cu;*q%Av=j5 zeCQd&2oDf@h%feZfPMzXofpY6y~N`^eT0q@z2`8lv!RAIJhN>*QAZDSyn1re>(Btm z0+5aVz)U;K4;}3EWi!RD#3MA6mlCbe*_O%X^c^La=yJS=ADteXW?N`?-0WxgdtBx? zZZypGCa>2W%4X9lerNPUD1NT&j!vnogX$nuu4HHY(XpB@urtR$``OQ({)7MUKRSI; zf0*F89&X|{YTy6FC*7C(6P>pKditD1r)|9pvxH~7PFR?(hDtpX~iE9jkxgAN_l$AJhrp^-sYiQeWFL8!rn4 z-~~iW6Ul+Ud=Em9e(L$ylAi{F-wUYt;c-$TmLwOEM;Tqn09Zi5Q6fL5P1SpTb;2Q{ z(uYm^Ng$L?d?W+goFJ9iqEesu>J2!pvV$arg)d2z7xTeWI4}k1M27y$uNO+(^iifB zM6qumZv#k%>?D^?0EO<{)GG$153wYV5W${A&~^&}F1A5y1VV;T#{u-9#b5aiWPyJ`cozAq!rh{DTW0$|Uees&P5~Ku-U`Y4kf0R0%D1I^iEe*bJE?e9Tr_v0;a(vt?=!f9P+8!N{TXC346J!HopZ z{H2Sebp^=nvFbE6Mnm_orT3@q%2asS{o1H!)lR_Klgm>b{7pIrZrDxzByme*bB*F(0`{xOXOVmh$3jIz9i?xb#u= z+1Q71ls98u(T=Y@Ca$ZyCyd=5?nOe^{kSQAGT_?0w-IZ1+ zJ+FHk-FswsZg>_5FOXUV9DgmCEIypxWz&MzNq{O@XIXM+WYYr=onPwUBR~K?06ajm zc)9AO4i?00>?B~!hmuoC5q!uouUNd8QHqGgijPdqFTK#f3w`yYMaY5AMuQ%q#8C+l zO!ymns~25DN)`(xLdv$n5ifKA@X==&x~L0ndu$8!qS&tR3>D`0sp;q~d9tMGaWboZ zv(s7Ui{P9U;?A0Lq=UnUxV_mU>hcQhYu(x8wM#`pDJ`oQd$tbx8_TKwn*nHUli+Msj7p+Cl8UD#%N^#Rn05q4yJtEaC0^aWaU zbR1OJVx5h#Z<-B#gVyme0l z^OAXHKjFW?i^+4`L(aW>#G80C_A4sv=`lxU#xr>AGltjAN@A8yE`^r!D-pTYcP@jU8T=lUfuXh#|5l`M8jh z1g4gqees0H2@n<0p|cX5TA^rrQ&%sWef~}>qN>kqu9L)&yv>U!{G3Vx^+YkU$`;Fz zUjBp|8VT58qe6I7Ne80C}`o@ROV%8-NBs&_Q2# z+{Z=We)sK5KD4m~UVt)x?SsW09g$B7clfMN9yx&(U+{H;TR*V^4nHfFl|lE5X7U{_lQN!j7NAQ4AG$j1&-IrMu=zZKCCkamqP?iGN! zb{in?h_2#ZNgi@mx^0&%PoMpi(Z2s#OBOb;bl@{_4IlE&yTH>IARIouZ*lB0j^-G$ z_qlZ(7wEdYx!vcYv)#lX<212doA)#VT0-AGsEy(6v+G^5h&8|){a9C6 zh*>ylYpg}iO<|y8QLja?qR`h6#w%k6o>!8UqONNt7Nr4<7q=mo#n(xUm|39tjX~^r zrbj?obkL1lK8p62sKuX!4!P>yk~D0g4>|mkb(=l(**4*D3K{?!fCZi;&ob3THy>$I z^5VDW_-L_gHH(ul5-0itNK3qsMSo~$1Ky;?Q#K8IMMpO{%53B*;bS9;D$@y9JY^$w zY(XFOf+Tj;2hN+XO5zJWFCx)-dD7Miu6}copK_s(kB%uBzde5Yd~zR`0c9Id7A_y_RrOX(TvP7)iCmXW4|;p-eb3;ez&ctogs*%|8K0RqH(=P( zX+wjq_z5m@7~@MY^K}`WuhSv%Xsn6BSyD7&8JoMz)Jcq(dztUShlg^8*h8F>u!39J z71}NXnYYa?-UJ~pKy@WQ{pgutg@b0cJL~n#e{J922)vaEAdBf0zIqYp(M)J5R||!c zEA_Dfv*@wllK^p|M>3X$j{a-_-lVni(DsHdeilk-LytGsrxJUzXwjd3>ox8%fgHdUI6xB2Tl5^voMy;mEgqA;;*D8n;#`FXaGstZ^?~K#LXY4iU*yMi66*7R(zt5dh9|R z?XpEFxB59H4L$xc{%k7H&@XZ`y{8|!eWc%X6l$c(bd)|y@-yTlW+~~TjxAz!T#;!T zG{5YR+Vt_K;pn3do{xC_5*_mae*qr;ARbS7bD+Keyfa|0la|pzJ#uE+-bPiD9q`zL zf0~}2U!hIxI&Jz=+NWU$^fTZ~@F}689=$Wq+(tjp`8!P|jD^`~B%klDG3LSb#LoQh7t$(0LF`Gku(CZ@zX4h=}-Ux6QXBca z0#tiDcuMTuZkyII+l^P;Z!6lywydH*Z-gRuNhsuO`w?Bo6PF}^;4@zm0_H`xyU*P& z2i@>qg4j=ag?A?cW7&Rp9J+e4jsW*93qZaDwxVJoV8Qr?Cv1$h=t7qTf*f# z7N2~eJ3c|4O^gkZ8-vpkXsk-#+j?#AZW$#kUWn=L4N$ zL7z<=*~LdYH8JOkM8!7kcnh^QUBl37b!=_2h^AS5fz~_F|Da)o2NAYAV zN!o}iG=WsHA3p3RA9Bpp31t!rkB|D`>2Ds86*-ZMUC1QC&8F39b_Km==442q3Ll6ZZ7eixeN5uw@FnI99%nXkGbcj;ypvRo4%g> z&$PF-8MoX!kvsDsKl6R=J8Jj1%rxC!-wz8P;lZ}Vqw~!2(vJOip$*TqeETCXZm+lB z(5r=S9)Z3zU%G)=tXODS&}-wV%?CV-6enXW90Bk&>!hZ2gg_;WP;^4?ccCa4fIQ0? zC3PTwXBd7^Xo4589Er%LLvjRHKd~@k(82>PeA-iNZ!Ab+f(&m8l+sC3MH@SiMZ0+Q zu6ulJ`d)S?6bMQ_mi+(ioe8jINm2Jt_slRTyUMCSE8+rzE21#Ce5i=x8irfo7HEWo z81U(bEJi3|xP>7qp%M}jY8Y-IDw~1}0)8NYobifd6UVnY?wUjjCOuEm$q^hjxikdLPz@WzKn=}YNxKq zqf`>|kcC~?LPCav#HUrdEc^6ZwHUcULKZSj{4ifK8~C$nxt%r_=nFpS1U+pzL8HwM zTKXVCTOluv;j<=F&AH7tbn7psNTYJpS+wY)cIqfcx|(d!k&_}n$IOcyU}PHTa>}~U zUgIl%qKrP}m_#2jueDPb$B1K>YonvFqE7NCD`{M7c0v>7Ml6wqjkOf}fu|PyXFll> z>yg9yRtiN`xvwGECNWOJ6M1u~_>Z#Y=V+*}^(T7TA|BEozmexlmLeG7O$ zVBJkCaF)DSmk0mxKHsdfK7HArjz_ z2!O?;&nP~6J<4yYw z<-raUO@QclSQ)*!RZ5T8XS} zz}7-l+Wa_F_!TQZhORtwb?z(}6`QbYDbbFt+W6+^kp~T!ks@6zt1syJ<|Pl`(~h21 zI>)Za#cukDx78$X)12osWilJ7iS#*>`Lix_w2>}e9h{@59|A?$t9g|BuN`B1IT4z+ zF5wd8!&^%;)e}-^q%#eYyN*{u3|F{oDa(yCZm;p_#8PdH85l~o>SGQj1Wm|izC_(c zmvtA8QEsH6%Y4+&?a4T&;NUc5Lg$Xs75kdvU-MnvDp zGS>dXHbyTRjnmRl>@9(gIlI0CbQ#ZtxiUpCR01&YK_9wg6QIq5Dywk&tlqD{+3G^i z!mB{ETz$i-x(tMvq;mC=I-}za$S%F~hfe(Uq%ic&R%8FIsT^CGfRtmdDmcA2l|HFQ zmlCQKoE*oV5DbMkRl>yO+c60m5`5JAn7Kr1OW*KO_A8sVyGDMfrirn@faL^*FcT#k zxb#t-a_BV=r~_*yzsk|ufo`HJHlz8`6aC0ua*Z*4E+x@M8f;@DmyJc&LJ`Z7x8xhOcKEu12|R`(W-%kH{za%43_#ahzCF$>SI;$%|Y*M|<7o#x2T? zyuMataA=@vt}T!aYn!^cK18qaaf~Z{LKkgblIOv{84LYf(wv5tlSW})^jPJhKlLxU zh?gAa3v+Q*LaW(D1lG8vT{NlbTtff{E+fA{>Mfu>Epad@ea!F`Yz{a~1X^)Pdpow6be>~&ofsM)6vx?{XOA_cn8#r(k z)cZ5N;e&)Wcs%Ii*uTJ0bjK$8^kBzUIkL)TS#WiXOb!V-a{5%2TI2WDk}Kd-t_gx% z@5^X?9PL2Q=aFj+dr_6l^ci}rH1}1K9Vy0eWvpe6^5^u1Ni9iV+M-{gTXj&ziZ4ZWg$Bk~4) zDfd#Sb6g}e3tMw6IZkFWm=ox=F3ss4`J(J4^|ZDlFBnV_7+YCiF>oDQN~vICV=yzv zT=!%n{t7>`X+pQC_b|6Gbjet2Mz3KkArADRxTp&Jnq!os4_jnxjXQ%ty9K;6Lv>+_ zvgqfW9nPvO@Y06@F)jWJ>v_tJY;MirOmK)E%+Pry`6gunjuL@WA+?~0fXHsW4H9?Q=(kvUZJaPj_{L$ilu_OI6$hUvz`a}{AId)Jg^#X zGE+^SGv`i&yUDE4l?{5e5!xF4M7SNetx4ZGT{G`eAAWV&0E`$qOx71VGlzYgf}T+x zw0cf0_nVJvm`5922R^LtoX~|P`t|_IgyAEWl4P$T^X^#l*gBy_538%`z0@!CV5a_| z&3-iU)90k$8Tw81h~pUhsFl$#E|UwQ*4_1{0|^$XRh4HQ3qtE~5?jo(F6eA` z3B#C1>am>1XlxmkL?2E};yKSyVE#!vPk@6+Dj#Ow`zI*jZ|()7n#rzm<>7Y#!nEX zFNx5%f04s-=!z~yR(aUm#d?3n+s$3M5=Fcs)J#}L| zpMBWM9fFpctu;BSV@@$T7w#CC@GBB|p+d zIns-qB>HG0Hfs(@??PSwM3gXL-5n-LzJg)+Zbk8=+q*Q)Qp~6|=sbD)fL|v@X{^*vL*@d6flt<@axqM<+OFZif*F zTxoUshBD3Q>157b%KjP^J9hc-(pjGh<^-8#a0+i}ELs&A9?Tje?Zq}|iXfc6`Yk$| zZvCrbA|`#8)65uoRxt*SE;;BpWf+gj7!~*77@~wyk8iv>%O>U6869@0PqA#8(~W*s z3oOusgiQWa2HTt*??3~6K1q=LXik=MnB%gc7i_>oI!IS!)q*zZk^72knKsN}4q`4m zoFp7YcgL^q3|X2>ebpqB?h0UZ9BrjewoaI54(8~iE)f&;8O2e@UmVjpx#IJ7J{A(q zP!zdS!WwIBJmHf58XxiE!;l>lZM8WZX()p^z6F``VVS0OEcv4j<0AqQbL`Ik|1jfP z>$}x$4+1R!+@7&G7EM_2eieq59TJ-=&P2%cK?YxE1-h{2`ITLCpu`+ z&#(SjJs8mi?f7io%SWOf8RhKVWFoXr$e@jHF|XKq!&!R{@tl8&BnC`K)lZ}Ol@=7X zq;G|mz|E_AndK^Cv5jC$fgRylJt3DbuavQw%BpjeTKecqmU*abc#if`qJOGX?im~( zu!{Jo?XWpA^re)zDfvd-UxAfObcw+cHV2g_Wq8!4Tyl<@BL|H1S{mkqWapqR_OJd# zt2P~jCHxnP=Tx5}Q+>yrX`N|v@B%$^B;p-q)XJjIZLBBki;49abx<2)>h-FyTyn{k zgdN8vs0)ofQKa#?)$f$dXSI>jUrx30%rqRsTVZ!n>0RTaU+Dn9=6($m(PcT3A8`>) z#N6kXt)(dEFyktjE#FQA`f0tL$~CPnJ_0OgHqDyjioJ1bv$m;3M?gEyn3NqUjzt?2 zJd|-P{A`(ix{Nxmq|qJ&qZmw-K8#={MF+M?u&BU<%_3igLKeEP8tG0A0UUh#QUzD%xMd91vJY7*W6~9Nm61RC#<6;x5pm2RuW+E2fX`n!W0={0 zlWR9sO%{K7ERjzde)bNAnPlvfgsj@QMIG*J9V6|vvwzXcLCR6*O^X*!6C}x@$;puu zWGIl4yjrecgf?zftP5V$7n=nyww8_P=(5ai0vE2kvpC^sCLYwon!4-k`BURY$+w1dTX)Cek-2E=M%v3PvbLYB??Hm8P4f1zZH5y_S=C5IllB&aEuV7*+a^l=p9A#?SE2K*5a9Q3c+@xIZ_3M1Xvf$P!h zHP*sE&Mn`di|S6o#)!P>_(ksZWdiFf(@z;juB?)dm9s7gUSf(mJD#Sqf>(`eq(4kq z{fZ|Z3!0^Xq4Y0qf^+`L34w5Ad=$WrlmsEu`4iis9e zv(2LOz|~}%X%k!|pL~uN8Nx*J$m96Y9{D8~x>(O~wzDQ1x|a3>fi$J}!>DG(dIWF+ zEOrGO;>gZ|dZ$fS^=fochRVJn;@LuicW&c?-aTQUr|6ptA8V3t0wx1WIZm7*iDMdr$0Fv#cz7hY>ov5wUUbB@j2+ zD&q!)49S6BZR$t4{{o5$C#dDG@W3&>I_LISZHPlTswOsg^(}(3$?0gC=kZ53{)S{_ zAM>GNT0l1aO?Y~etP5AJpsyvSKtByunrm|_%Z_^2=p{7LQO7Z3>-7}{^xMIrlN=_+ z#li(l=5V3kC0hp@D!LE4S^-SBLXJH-;b%BqS#239-G1YBoa{ri=v}+=I&zMs!aE)_ zZ?G+=NLR2aelXL;V~t@Pd*sA1;y5R#sWk*bWcx{7n!B*!pB=wdGlGQG_2ImMVuEAR zJC48X6e}hntEK%!AWgabH1cw{O1`5wuYv}Pn#Il)q_xRtaYS>eIMI4*+z&*Ds5x=a z*LtFE+!pG6QOj0?GgYD(4!t@CB{)}IX@LujNTQL0ALVe%vnT3hXZi4#ps}a(V`@wC zvvVtYZiYeSw~zS3cUh@J)k!MRwnb^x%+kq=S!6x!o&Aj1K-somCb+AT0c)q|a%vrdo3P zDgBi)a*#~jT#|j0cH?u_No5%WjSo#;wp?~h$@?ps)5_rpoirDRN-M;Ekz1Et<|JdJ z1f6fBs@O0`Mx0x0h~s=;#h)%csGev#b_OOjOpCqaKuiMNk=@6tj>~8(I&6wd(Rbtx zU3n4Pp_wE*&Q-BJo{V8Dw$16|@{KvJC1gh#Q8s1GF=VdDb;az%^TbJ={h^QRwB`g? zIF_-AvPR+3g;vo=%4)gSquN$cd`T|&$?t;Ms99Zl4VWyy*jwgeb^Md)O?pi%?QjPW zXaV334AOyHUHn9n&{|a=7%5o&*Wp#^R1r(F-?QzPU@lu&#gF6|6|6>tTJ7P=UWF8y#f7 zfi(F9Y!kYGuDiyr7>LzKdp~i!k+cRGBW#oGC@llQl2xJ78~g| z(?$I>Z>g)<3ICWz{l>Z;%RndHBhC79U3TFc+ax>N8s%quGwmk0AWw6vhKslN>vbZ3 zR5hx!SoXQtzMKefHN(; zW3WS=e2_Z}9R%UNq4dYnBQ(2n&CYpnU?wkLor%0E`_HzaTu81Dov%p*S=@dlxudh3 zpbPtP{OIC8mBg{t%c=UN;9ZV*xR8Ypm!I?;gF*W1#|d?&=6JsZoQZv*w<5!XOp^y6 zA_-Q()UR?ym7Xbo3ohNc`4)8HxdmNU!oZ>r^w%>C3OK4YPCF zP8a@XAIy`b6m89Pu*$BeyJJ$pHQPHUJJUtk>M!fU@#eVHxJzAJqrQd`KFp_lb#l`= zka0mi&%ydyN-DALSc5USK4Hg_->6}dG0b{ro=mTP!E|n%M58>)L|6V|s*MkIi7c`V z<*WmKi@%(N3H4bv)atEfZ`8l=kMtZz*&MgD`v`>PwEM<13+f2qJl1W}(OG5ZRdW{f zsalPmWF ztJ0>&Z`_U>6Yu_`U(=wNKHC-T<=L_^=n@Y&C?T8ILFmdK^)%naUSWdGfmAG$92ycb zdAJ*TUb|7ASu48I=J*+{>~g051HGhMEJqs3wKlpJZ=`pOLPd=?eoHsgi&b+*cB($+ z$mW?x=4UM_xPWe*9PF7*@S6bF$uK5Ys@bPD$9~51*7#O%sVF5};Gau06

h%9SnFFub3qB{#pZJq$IVheR zpH&}Pdcdxwq!YPF1CKDFKFa2p_E3I0VYeSxbO{ z6X8!O6jim7K=d4NtWk!X+peg z^4Ns4$MJ%auH1Qjzlubkb>Nt`LOX7r1t$WB(SG`f-&~}LZ&reD8J8lf))#dO9J$Je zEb4IV#fB2_ftLrPrk7}<&eUoAtvDIa*sm~vcc?dpVpo(nZbn6)LN8sXl;tRIUZN3y z>|1ThH5WM^^ipG=QxCQTgLBF4fX)ciZ={8PE_f*zM(V!Y#-Tz=MwUyhw>V&%QsoMe;qRiRfgZkEBFfOF*jG#r(}qpdgrO& zD4umWGO;a=)jD6t$<`7c$dt{{EhXk{p1YclwXs3AaF~+|CYtM+W=VFYZO6NVKnnnO zXRMB_X>=uXP5@`jB8L`7z#j=ew9XkhVfdKa6r&!8l`Xx=(UW)CU4LT1)u>&14owP|V^)VG&OC^13JSA7UvEd=NTnQOy#s|qZMr}SHOUi^f^*YTp^8e)d+4HFV%T&^~~L~{7hbf zcyjgXByfosO?0(`nr+a`)r((qMi{C-=g6V|n1uCVgEVAKB^5nu_N~)@UAyL>?2P(T zMvthA>t-JwWcA~oc^G>=my6sv9p>u2-`HvB0G^u92qfNL#%igr$lJ=hi9ibgcXQkh zrM3KxHqaU~4yU$Z#Q*@l8UNxU@#EQ<$G!+SblaBtEIZQ1vH}d8QIxOSIIg=n&z$6> zb3Mm6L-0T*denlE8egtcAIfVOW}bYEO%az>JEt5mK%cghBiWVPJg~EICaI65@yz_# zSi8#MLCc1QFX=w$R8fk##dyQNX+mGVJflrbIsC{$?@iKaZl#+r@XJX$qhCzSucZw) zT9Ma9ltWp4kmqzUaAEy`RZh%F$1F8SpKLQ^)Cp(hiG6ZNzw{r|oG*$rwX$QLl#={x zpVog(4)*a}a1u2k6$X>aa8Sl{9I!b(0*e=si*8HuY1ebhkw0P|>nYR!y0yc2`K{%C zo@@Li3!PfpF9ccuxL@NrYYmI}up4L=#`=#h4bAQB&DqItt5J?)lP`2cddb(Badu*o zE4stv1P0(iu#^*W(PL=?$UL>5Y3!fhGDe2mP_YkM^`Wh|W-oJw z`j|u?>vCE6#XQsGW7!E7=%$42{Aq5*HqnqzwH#X_A9Hh#-(~dUK5~~5bEOvi(TY6U z+3>MJi8@`)VIE~1MMv&7$4xh4ZoI|*sqPmOm#9lDv+f88;v)&P)3*l-VVuNgX1fmn zmvwlHXI<`rNW>&C#CcoRQAMdhuj1VLkMl5(sd&j{U#y$x!uSKmLW=YvoAY&QCwCv) z&kNO~H~P{iy2XSaB50&qbJ56G5_01_M;GtQD1{4oOZ$Vs%=WN91~y9y0$R-3InatD ziVJ%#aKV8@r_RQJbB-y?kMy|>KKiA9rAV(ja`7sUZL#c|1zxUCk{|7(Nw(B{G=1Pm z^9C@7i~7nrvK0hK579(BYc{ElJkr)M&$4Yay&LE20}J&VbM-+Tv>6M&j6yw0ePkTH z(LN&XQRk?8jaGHyVV=h1n|iNk)Hl*Ff3D(7GHEV~MtsUuuiSMv8MMn@wUI}@Xs2j^ zDBB5Y;#0fma}FK!B+8S(!H$uADRH6SS};PrUp4OM0LLWsiGf0?9Y1Ba^0B1^j|7k; z1tYP&R*slx9*WMf>A{1pFRIyd@x-|cUE~!5GGrgQY(VEcztkq)C=dBrm#jymmke^r zRUX?^F1%w8(9X$Y_*h4vPPrD;Be&L{>Lg#s(xc_Ojlhh{+-;+p_H_j27H>Xll*5Qp zchH{L`NR`5Fxy(C$IM16MMUe6QATM z&$O|gvIn{ST!A)-73m}g*SRsC5Y8O9KK&eA*O$}wM8XfTHNFxomQHK!HFYqXt2Hr+ z_fq2G_{B~`S^cX@$C~G=C!j;eTGIN@0exH(na{6W*}9`Y^+_J*y6Ts75szrq568KV zHq|Mo4!z?sbvda$>moYZ;~E<2%L$a|lrs%hPtHpq3a|J@pO0gGY^w$JqMggpMJL2r zr#YThzx@cb0C4-q=#p#L?|nl*axU)B`LIM?4t@qYn??ETco5bXIO{YK)r1^U4CrR* z-SHJ?>@?!-&(Nh)kyt(@Kh{;t$PQq*te%i+HY@UoOHEGHtI!sznjX>4$<-xvsW7-s z))o_oL2Yk}b|AMlK1J5@#^ymzKL>Ij6CGUN@m5i6Q@OUGt1af}o=l9*D`nL4=cZO# zHmhKUJHHj!yqD4he{5a=1=`$<^f=FRU)Wt6cjzu9E)%=5QZvWs32vHOu6s7P=hZx? zS#zq`IwRbwp+zrJSx04TYF)Veo)&tFr;M3kg;eA5h7CW2Pg$ddNp@rrS(n%@J>ndY z>_|tM`WSdJH~qK6gPoaY(_>^S6}dX9=S9cjD`F5^r*5^of(Cp>y;{melX`0qcfi~1;?qKe~zB6q=$0kp{JZ$*(|2L$j*u0Qxfl54mvft zY~-_@phK}UQuI#J#v z&C!=lq)6CU_t0U@PMX0=e()m9HVHj*t{2O(0o+A za(Iwg(|JOy5uOFlHwO%6(brCsjLABxfbCHlBN>5Hp(*mj{wbA~+Hur&741$|rE z4+L5OxF6$qC@Wa>G**dP}zPY%;tA>rZ7S0-m+Gw-v8f~UI%CT>Rae$JLIej3j=@f0u zV^pJ8cc?%+X*xdBqe3zLWWEqIWlpFV`?+tjN(wges}r@kD4msyC+15SMY?QBZJy^% zJYyK;tt($BE^#ae-6;$QhM65gS4)g3e>FQrAN!!raSrmS%krx{$rr5~liGM@xjGR+ zhb0@NZj?zmKMR@V&&iGc3L4jA)t%5Zq|Bp+G6!^2a_K?t%Vyf_)~OGKWie z479DV(+JEg>z%f#DW4Fi`4zq>AO{u~KTc*LRv0A98R1-T6mv;mNT{{XU6q>9)?|Af z9Zx8S139&!!U}puOnS$*Nx7H3WE1oSyU}aP;le(nR_JDxVv`LZ2M)gZ5;U6{bI(#q zu4ttM8lZDYQ+<36q|H{8 zH{(RrJQuzAYdN&c;}U?56wW(fSn6x@E5YN0nva9DM3nW1PIGMF356r$5@%~Kge=O# zPF_1gK9^{kYhL$C6~&A1=AIaWTiRA=?@yN0{W*x*dC*Rj$qK$kG zUafN@5+)P+m4hksoE~D6y*gIz^Vbg0m$Xh!p=zJIiolh-s(90Ta|BrI{K-Z5=E6rv zEO@7zRu2@k*8)Rr3Q?SIw*3||7nrzUV=4}&-YL$gmZJXa^se!%P7WQrq<@qRUClo6 zD=)!Nc^P%SA|M*&=v&2P7#vZq=Gj*11|{tE@u8)h=|eXptM=#KPM0rG4D|~I%>ium zTbL$yZj6`%Jg>y~9$4N_he0}8`8*NuLrW^4r&ZA>xbYzRim<=}CO)T<-2ARNvCPq{ zUAaGtrGt>ixgM&$sPS1hCxoHslj?(5$1(xw^L1lfOjKHGaV`$y;TRg;JuMmKIlWNO z=U$RcJ&8WNy&SH54)U$Vet*YQT>h3Z0_N7yy75F8r!gC`2fdh4zP7B4E_12Kw$?zD z$3NmJIgXq0u-?u`W)WDfIY5>A5oYueZy5)+Qgpq8QdTQH=-cJ>_KLUE)n-(oM^|J> zj`&)>UkEInlkAtJm$5Z0cAkYMpG)y~ETJh5qEJ)TH^8zCHn-@!a5$U1R2eyh2TKkn z>yZ0)Jv|^8^~^N+xKNJt1Tr4XRIovG?S-pZ1`ZlK+|kFzR3=dL04DW?j_}G^C$`~` zF^a74;iyR^Fd9gQ0(!;qQG<_@wV``2LQTWiQ?E91%>f8q?sU%?_+7R|4C;eCC+m7~ z>_w063ZNucZRFBVb%nmtp$JkwN1x^9d5)MleZ=dS>A>hianOP~)st&HAyB=DwN`Td zoF3vMk2uEqSk{4R$W|2 zkp{lQ-~zo8e&oP}&7FimM_;kO=#SU>Q}m~kkX&AWOjBwe=5834fg3x)FwR9aM!BkM z`R*dn0>IrJyNxwxA?NpeMQ4Mc>||({1Hh@e^Rm1aEa7^xysTVqFV3{)enwex%22sJ z*^BjhqaO)+>C7;7w-BPH3Y3 z;*~tch`>on7)l4#=e+ctYs+R?dvIrErwh`OZ|dD> zfsUNOu#l5foF>nkkfH;SlOXn}1`Ng{=jF_m50@RBR)u7!!pY!g6nw$v`mAxH(DO%f zKV^#Rn7Zf`IaZpJjjg>nk#?uB72z8s$lPHXt(=B?74?1*`u=i;5q zS#v(-W}9#%&uOxbdS4-Z$YV-}v1ynGwYjy)`o~u2Hc5_)DdW1=jOv9%U25w&+qpFU zx{Z)|*6E9S=t-XOT*uqmw-bR4r|EVo-?Z8c0eofjms-e~o6SBtbK12rXWDpN&M;#S zv9*+a<1!K)d2Qp29K{(HTKZp?kf*>^v;;3_duOFObXf4QB3sFMXP4yr<~0+DW=3#f zgM|OE$;YVDPuxhO%)y!Wl@Sy0G#Z(XX5|Dcbt&uvCNMrI?l^uzpHH$ILF zbV;c=MrsnRj+NJfD9o(QOUJPS!JKUMp`3ZM$@tSxt$)d(ZE4e$KIAbS2A9aUNf{h< zQYm`rp=0HT!CXAbS#!RQ7^Fic>639;yN+hM+GPEoH(a3ev0tOJ`&=8dGS6l@O*Yro z^PHV|{82|==$Ye5-3^CvO=mm@qE^`Lo#$7RQIxL%K|llqq(}>bG(oCFLRXqdQ&D>F zy>|#z1q6b0=}keUcR~rB&_k2nODGAUcL+Dmnmc#a{R`&9^<1`7_+>FWLhzP-bo4yhaC!+$xkDG8D`xXgm>U?cZNS6cI2&1MP1 zqO-OodL)5GizRUUYWFnAs`6z=a1x+J2^uTPbx1{rn9?sW!vff2JAC0K zfVT!O#Fj{_tGuUhn`TqM|8U&v2ZLu+U5%Qo>d42PEv7+{MVWeQM>+38W&KPOLV^ra zp23wkad)-D%B<0Xw@Dzm3!VmXWb%1I;Q+JKq&!?$@Ovuclb>Up73J3s34-u~Cqtp6 z0@}YXsI6WZbV>{-zb<$0QqX5dxxzFu6Z{(ty_L$)f+0e8$HlUH0XS_C307^2Yon@* zSa@;iUWXSkd{^-+nLlYFhgO(j zM#r$vg$%ALdkkCeQ+KIZ4%LfQu9!=G-36FF%0@)bCQn^Pd2r71vI?zqc{!_93&d;Q z@aix@&!0?9y=z@eL55gPSWcErM;l*cqSK`gY68z5*p`RRv?u%ZYGM~xuSUBQxD1M51N5Lin%?KXl;B{&C zIIa}j6zh1|^M`@EeC8?WSpMpLhXRnFE@!jPdOBWS4DtwVp}&*UmcXZ$MjW($Pu{Y^ zO@QcP>u%4m!|{QA8Md$iK(7qtoGdmITB@(0!#OoaF@616dIS0c zM5l0mu9Ox}@4vri7OgIy)&?f^nfVoHdjE4ICDR$TlWE37tMEgW0+ucrpj|kt-Wbu~ zCllnRu4gS#^+dg;uqfP(@JK}Guf}cFZhl$8qQ*%c(;6+^ERYPW{;Zi$KAYbpKnuV~G?;$Y`8} zX9uWS#lQ_n>sZJHi7b%$6Af~QR)vAYXI&4t5|TrP?h8)Gsc-#i6jyqi#8z4ck`mtk z-W0}T_>EdPqW~brq#7SL`?7%D^GQk4GkdP-vs1ENiL&S@ti)Pbsf6&Z#}QK0->w^s84m9g%DdM=96`%^9+fT{2wAuuC|=H zH==*U^B#rn)F29I-lzv{0SPbi%T*9HBoDyqK(F4=xDSbX`uEglNKnRy_h`(y=b}{_ z*VQA*pKxs*7FN{=izwOH5YRbVNCDMrV|%?+2$)f(F0q2MO%6VoYelKxh?bE5TE)HNefW4A zRnI!pdrqmRHQs#oKTD-lMe4V0lx24+_?{&!QW2hzs`iE-Qi^)tsu{rJ@dB)J2o#K?^NU6wu(?F|0?X2LQKz3qm zu136MY4kCwe}A*`-3U#io3NNZBZJN8n=^H{zRTEzo)m_LUpY9_0tmHAxkHFP6;7j> z^?9Gn;w$h}pm*15N+<@EBlc?P+9|=l#-ouV&W2M@^^Iyx{$oL|lBcyIb)QG{9O}l} z7_6@Dl^X0dufeOz6Px3M^!r~LO}t3y-tZ+9C2qQsDCHPMY)tEt8CD0LM?e`avl8ca z>H(proZof<1=0C=#7_zYz0xp3j>$(ErH9r1sS@3!6A6+%PvmMG^MBhtct?==jtjy) z=C1aqPw?4^rW0#-{EYl?`*1JS2Hd}YD;8ST%2FWT?mqG2XxUdK!Jxm7r|5f7ms~2{ z2@7DqNXESLfQ!_Kxitv=gvoe64#E7a&q6BR>h?z9ZM+3j?F@eaWw8l!@b*u?M6akC zdz#(%w+VdN-<4&;Aej@~>WhtU67;koEtFTwJGlua!ZwBtV?X-Ik4g$XW6&APVaD%L zkfvQv`hW04P5YDeC-suzx4lZd+AG&ntE>}wRI|PG@?$go!1m~$^|miYXWY7Fgik=t zer2y^ZsMx~9jyoBzet%q*fuvx5}XlexDA=S(`k$+;!xknp;;QE(W|V628db)uP1^l z%aVO)LIZDXUXHGqRwJVzd%_7!#{Q*q8N z%c_Ox*T-$i*KgRH8)9R0)?R?@#%4TYgEa(G9RSW20P(-Jc?0fQK1xNMG4bnFY4&%9 ztHg+Z5!dS{Fwb6}`e;TDnibRmaay&4@!tRwF8Q@`|8s}q8s%9=@`eeva5|`)#&22o zS~$)Xs|Ha3ap5RGYfM}y>EW-Y*J+6xMI>ZHkGmSP#yI-R`tTA#hKKrz&b{%0e>XC{ zTW1%DZ);&IzyCG`YCYY_-at*;?aJ4P`R#DmgUU}5QF+R@i~>8UnYAnURwag7N&;~q z>oTKDH{TA%%Y$r~B}NmbCf}mpA6u!fb*oaBTmB9bpw9~A@Z2i%M{6(tmMBVV_bAKJ zZfzm?b&5X*J^UG1>&6J_&{cAo9z4{ zh=!DK5p$xXV4{42VgGbi7HnY8E-#AL8PBRyXdkHd&SmENl~NKghDSR?u_Tct;t_}C zW?O&;aC#!B<7*r5aB72@!VNp}PwK)L*a)0Lp5tqQX)MgcqbGvyM9kkIcCgU+8`cIr zhyypUa`8dz(BW0b(I*EsgXUlX#87Fvns4R!R8q2{Jgb*B;Ip=}1*=>9{aS$;-gI%w z&C4%zSt6K6NAsz)fHmP4`k3V|s$v)K3 zRu1gz_fXswGw2TI$}fP3tR*bFXN^2ARG$i7x7%2d%OwhF64s#qVP$wul2Gt%WVSF5 z2o(a|?|U!M_#IJO3ANcI$T^PE@Q2V{{!(@F2vy=8d%x-4Y0cKCpS{b&q?833xAvRv zDQ2_RY53-#4V51bJeX$jw(1^^rD|3@eI61m@=*y`A9r|eN*|iI9vL*w46XG^7^S=! zg(cO@xQVdoR}6-(CfxTAA!fSnGKUVl{DAH}(H)`991%o>tM9JA(eKd}p>I4PzwT}L zJ{-~Qj>k=#g67vbhto86N$4S<&j1B`V-mBr8jo@%pfQJH-W^8pcQezy053xU)%$PrwJ$gss^{>WXs+%BkAzE zQ;}tU3uh^#%}3RfP6@~D)`Crao78I$HuJUuW%QY#$XDw3#SgP=WRNy$7YPCGxKUgdK%Nx6hZN>GJ{5mQ?J2(6 z$ptdn&c{~C$GIyqp+5BVK*=ro4m!$VeW^fuAYKJ+9Q{)OYUI}p{wEI$1$u~|)gBeZ z{!gDkM)tc8509Yi)+l8L%W8Xfj-lC8x%*C&21CE7C*GY{#{9}eQ9?-=)~7z5ykGM@ z{b(gUZP@Sdde`G-Oom=OrA`ESrwK<0Ag&qIdI zAC-B=$7$9^bB0%A67Sny=cqO)7_B;u9U3`P}S+~SqZ!pFB-a9QwUtIt=3E!`FVaO>z*9aZksj{2FJWg$kRU@4t6 zFF0(U5Em8WRrjc}T*8MqXL+Q$_@EL>-pwMfT5Ruf$F(Kp_O+L}s{QCRo3ygsB6~-_ z&6dt%@V!_aB(<#jPUnfU!K6W~jE<)%2p3`ZjLV?+;OFt!Oabd zQojRx#UGz#ByIY9xRWHq@-(+T^I!5&=s)8uucXU9fzU<7pfi62NOeXiHNJ)TOM++D zZIw4Oe+@`9(O{xHOly9ST_&b@x-t3BlxeB|HvU3}lCAi7_*);&*Yz?}) zFM4Q1r+%KzCPXm5$HgZoJv|x}OuoTIv8Uw&3U4{>)ErQ+J&LzJ^i&tBs@pXFSz$d% zH&Axg84-hQCJ1LS-wk^3-=y}+Y?DWO%J8R7SN2-DSYk_%XU-E3p=p;nI zlY0!YdqixBa zZn?UJt!*zB~s)tv=Y!F-PyDy!p$=6D_WPIbav&XRDz3 zJALC7uxNl;bApITfxaCbQw3w zMWOjMsqGtomF`0%e!~X&SV|GJa%|fp4Gf6P*kiT1JhyH2KSNBG36QX8L|+t|s)-Tn zA?_^VQ_w8#vw2)rYK4xGfQvZ&NRKl}H+YxI@6tUbjCU?^q*YWhXr?itXkZryd_zCX z8C_mXqVg*KH!N4F$M6tJ)+588=59HWYheHz`_m2rxk<4+pIZrG!xCHe&*+HyMw#iXXT>aOJ(@( z<_i>F|2L>s7^}^Y_|t|@I_`gN+FbD2>}!8(RL+uKOl0QeY4peZ%E{cA!_mB?OvwA!R%?nq z69nbh)uDeLWg<@foXs!;^-vy|KgQ*MfY=Z-Qs85b=LPdzNu@`;M9V|UV1A5j${pR` zfgRoc6U`E=hT5$QL+6xhqHJ#kLx_TfNj-K*o{IBwY#b0$0wTz#s65a{)i6N!k!R|W6Am~5rghA6G_?KoY~=ydm+nM==sKaDKLsk9fB`D5^} z;KKXd#CN>om--n~Kd?|Nq`PK*%>xaGzM^HMnJbKV$F;$_kSz@hE>(*FNpd$dWU9uf z3JJ}={Ub;u@FgZ{!$m}M%9GP@5)u9m2we909(1foUwaamhl&hBPBx%FS$?FqN7+?O zC7b+=lF-yaz2?hoS9^IdEm6kn%4;{o7U{^9IxJHkke5-i9Xas9bIj(0=bK50_q|XW zN<7UuwU)UB%p~~sEI9b=#N_s5q14%{7=xavUP#t4o>@39eBmXuiOXH5yLW)A-Wrfj zJvumtXX@S`wx5rc71fo)8KykUltUujm!;0DAyW{Z`Ft8*Cv>CIP2VHqjd}!s zv;`6Loxq7$k!p*D1@uVI7{xuiG3aF5yd^LtB?qpUvW1h8VQ)1 z@+qRPLzD4HZVSGwgdNX4-nkNg_rAQCQn%~hTCeJQl)Tn!{S?84%0TY+gvW-tv7~;> z3>%Z^fy0B%#st=l+C$7^Q>~3v?#w=};GK(wy&xZWa+^-e&c}sflban3%bsrpaR_0k zyIOuMC?oK?Y4t1LwfI<#`^<;U%#eMv6^DZ+`3hmfd-JZI?j8FVA77B7Jo;4scIHW@ z$S@|y40gJeC5Ax#kM-TV;&TjoICVel+Os+tIf>1YSNu{3Ba0($?S|gEz){ z3KL7EG7x80CwQ)iuZ2<6SO6@9Q!~rzshGsM6la3aUP(OmG76b|tKDjuqvK zWZH#?YfB_OQI>DSk1}k!@}*{lTxblR7anh0kXaxkw+1SwMn$;R13GoZcuTACPb10T zqma(!{2YQzo(B}G%|9jjt=|khtmoa|$X{!*#;~i}ecJ^elc#jMJSlcL_!eOF@FCNc z2ypO1LAU)qduE*pzHvl=9hPgo87Gt2N{L6n|K>svNwO|&ckMk&ZF#$_g z-hhjEfSzLFCeaf1wBE-h=qRHJRo=R|vEaKFyWn7QHH!h(L)DXuK59^znyr0*?Z|bB zw7!4MuAaxAQwb9v6AsIb{WQ20*}T}R)W2#t5-MxlnfK&kJ(5fv^DQ?u(ASdKYHv}7 z%WIoK0>}`#3ESmn$>oG%Q*5AmE{>3>pk=cHPPdq&*y*>Fv7gN!>WmdOvQ-n_<@~ia zEsXYx4BOUhw7H0fRCx-v?!48vDvCN?zcJNe;Lp+WO8nx6o+*Y8mTGxRF1--b(v?7L zGi|Oili!RgWyVN_wS5xQ%ydt7gF03g86}q^GZ0qr$*Dzaq z-|tJ};Zo<_C-B6I)#3VgG>S)nskN$S7xL!M%y*PIATn~-EvOrK!EQ!KsRB*rh-^ay&Jfra+++!yj2Xpb3 z#jeRN8hH$f2`J-pG$+YkuTc63`j198a?4)yEesf+R$=Js8$J&-pUyfo!DUV><(I-K z^vQ*7&?E5@KLgdIy`GFJrcbA!{_3m<C`7}2LyxwfFY+`bKG)-5fM_Z8!ljM&^ z%<7le>#BMJZL5`Li7&K`(*z5-DbG^HfWvMxjPUW~e1x%c&u2~^>CdWqOz$xMhIfrS z7dA^ywt+Lmb>{U10o$)yr|Fy&O%AlYpGT)*6UQ}Qo}OGXX`s{OC~-iJI9;%^jeNO8S6Z_)Vx3j#?hzB z+Wb?HkIKg5asH}zC^lSeWCZo`NbvaAZ*laGZQO<7K?MP0iP;k^M_GG@_+e~&H+#6V zZA)2pHs@;1048+>-!;Z!yvhSEKDH`Ltx^R^ei!^=2tN56&V0#s5V%Yqd_eE>?+R+W z=;h`!_5F*QBI%)4sg7OKgsrPPh%cf1gg-TM7%f@K3!;u|-AkfHEI{L1x_&=~Hb9IK zzfCtF^Vv60>enS-+alCL4$e;g4@)7YP6_v zf^Q;p>Q+Uot#15WexPLcSFEp&h3l?J>3WAOk+{SHe1aeL>3wASNs? zRE0!)Nlw!>D%Z!5g|2T$e>6Eg&M(m5V!e5Wxf)h}}i96VP_#NiP5N%mSdV>!|Qgs`L zX0{5&%zBlEl4XCRl%b>hMqfzj_IKqPZSiwsaCu#ne!cQv+R$7tpi#lU!`WhSfsU{9 zu$G%$mpzknwk-~x4`DfM`?#G52Xnr?S;G2%XTbXk!P}$oX$Zgl4Ji&IOq#!ooD|Y| zv@NK#Ii@9*Di5iau>ll0{mqsIC&$7;bKl%@PCT&_w8*Vk>~abC3s3jtacFJUVE{j- zZiiswL#Jj+Wqf?Mv2|YrF=ugW;Q;UFJXpWQeySa zLVD74Enw$>o^D%a`NZzbJM{5^|a)e~o)vm(Ww^mUP zGqQTF*Wbu)e4S1}Fie;S8C8@s{YZv-Ejq&E&iw&%A6~hX+VyDJN%;Ks5p-c#mVcy` z(G*jZoPrd{{uE8>&dV4PyZ=oDjPYnYmUaS;?v-&ma?`DNd3OPxtW=WK8P?#v?KvD= zl-~10VE$nRTE6x&$enAY-Bld)Kg)r&wSSZ%kcBb4T2>BeNFoF#QW_Jem&w5nlgs%N zXD=1G!_*eVdY9gD?IcjlEh^zfCUUVgbeFn}8#!exd+qu8__VBS4BK_%^^_34N4i~F z*+q{7hmVNssHX3F_G>(IV~9|9t-$XL_&gw9Lb$auS!g*tfQ51hM_3opBd`67G^8_H zoJ`J5IlmS;j?PYOIfJ7!4Boo_9I8J%kLv&QK;p`SyWiUEXZ!Z55Y+=ukQF3pKb(zl z^WGQ2StR?sL3W)CskmTD#vMgZdE*&{nV9w-bggMrEE*j9vu~mv-OfKbc>gaK_d+z&Bi0l{~~AZZ3=WCv+5DrKeZCk81jPKjoyYu*x_DEoq%pm z*^8sO=ORWF6#hnzPNr+y%c$j+zopJIZf0w^_Z_zjDh#0At74y@N~4qj`(r=NDL5wu z5*fQCuNX}pKV7`>y-Ww*R~PK5eo|r)cnMWa^Onyo*au=n6uzLpC)dp z1Gr>%>-x^fa9J}MGqdrF;}RR`>VP$-#p#)9zvf3Wgql4NeX9J@w`dsQ)Y^+9UA}JU6#E30~?1EJ|Y{f*Yw+?PLYak8x$OL6w`{$_tN3Ds;4Bh9aBYb- z&D&SYpTDaCI{q|N&IzJ2DS&hi{tjre?d+b=LlLHBAY!9`w|n;yguAN-G#yJgJM|kf z+-$j>wW{B&kk$fwKQ3~y#A&4(L3f#iLGgHR?>#tolMHQ*&LR;Jd)#+aO?vN@pm*!s zQ_B06qN%$U@4+QahW*POeJ|BARx5dpl3JXsN~w;=RH(go!=04dC05(z7xZ8B$FX~) z`mwXlKn9#3wiMqy&YsQ!1|AiGWhXg=JLE24b1jsoS+;mQc(oNs$j9J`OupFp$=P*i zSHWrJNg!d@DVkA77piD{WqmR^=Suo;-C)xPI$-n#>IMY~&J55FH7%Z$VF!1|3WG_% zm^LY#`f!V9Y`Re`3eLW_30kv0^^Pb%Y!ZVg$Bl1%B6s*)+wPw5~HMVaEW*L}GYAsLEYxZ!C9l{_0qsPKOa%8d$G+{t1IbjtCZBla20*`wgi3 zz*@W-uLwIsi_4l$n>&8CMaz9(%7@`B%Rs&1=t$ny+|K#sftRUkjQC`wH2qQ>1F1d7 z>3;^O5~(+5Xw9zb_KbEFww-;h2yc~KyGTm}QWfxCj~pEUZVwV^-~-)QNA4?91jd8< zrV?;f*;##-R>tDOO>k;2nlT!XE%a`Q1jd}@%WP~^w)E5Gsp5^Gw_e=cEk~^Rz!In5 zJb^X%Ie&k(`jAabb^XN%RWwpwnV&~Ys?ZlbHflwMhZzfbZp1`D9{NR2KKJp+16vY9 zd&0WaM{TNhmb(O-^B>ztON~fp>gSkguI?W*QlwckWDGo{M4Pl*QdTnbfF5e2F?04u zTot?O!gImU=~Dc`(_*Z9`{Oy2>Hr$Xl{(Z#*W~&gZl}HxM(3y>EZGkTcJD2d;x9Ei zkvu14{J%f!`kn-RLMxYTx2l*NXq6-Sa9H8|6$xc2vO0k&7TF27{3eT#V=|#wHt0;l z{J6XG>WYXg=qV*X&k>ub>|WCD8n;s$|0L?ANk#Mt{hx7_!*Kbo@B`%BDoEI+?T&u` z^@p*)K*7@+rj6+V!^o)0smAHEO+vqq)a9XOrKZK`#ncM`yjHu%8EwO=km2Y3-K%O3 z@nFD2gwnSs_GB1FwTV+5HZQX5u0joM_e-ymDzto;U$ozm)T2pfnh-Txp6z)vZW}vbH3eP-+VE&5RNXz zQsSh~`QN0JhxM&Dy9@s|JZ~H>FL!{i29Cc; z7}<69X;Nr0iD10_*OmR8_3NVGOKw@Jwin;dH=?ISmcQ z4VbsowCsMk=>gkS-|HaR%;SG_*9DiGNtX-%b`v2Jk`%u=!mImB>2%IlVFNPLl|J~n z%nTZtDp!4+2flWTRrM}RLMYT4zTzgW=hMt0P$Qqf5S|Lz1hi%XHQ4^&3 zZa7|AwX|_TL3M)>1y+b5AdPJLjcKQ5?gEy=XJ5po_Ki5qMr!TR!g%)SbJ@q|AFjL@ zH68|Srv~-8J$|tM=NB^b+#57CO?{5Vv1`rFekn`;xjNRoJvJ{|>EYszSxv(V%rSf2 zep?`7JHMI9xzRhL%sKPRnWDOXgKJiUpbRr9vqd{q3D@=QW?cV6Bc9W?xnPklr^`8s z_Qp}2np_x<4(?^Ze*6y{98uPz>0U&v5plWm`RH1y8HtbsH-GJWYWpWH0Ef>4xAAy|yk#qkezD^SP$y z^*#h>BfMYa_qm7S8je`YB^S0WnhX|pQm~SpgrL?_hgPJGr_FHY0bh{e%F5UY2kSv3 z24~Iaob|kbjj{k*-^IifTt8W;BL~@-69!(dvub3D*3I4>E`4p0Osxk@Eo!C;H?HiqC|dxHM@|m= z#xSu*HlO}9%MB;~=)bpcnH92kS+;jbV_8Nm^Ut)Ci=^SaE%mx%tMe|QrQ|aLi$3A8O_fs4i<0J!Ff9i7Jw^V+4zt% znKNh{@h8NJ8-CLpSJf-d_;JZ9D(9H^na-Xw%G-U)g?}88OHwMqDC86+N#@LhZyz&c zO=||CB#8;na7@OfT_#q1nO3?^+N^&z;XVLH91gCLhA^!SRF@n6UA-sX&gO$(ku|qG zJHdf~CHXnWF2~6VwV5RFg^~vy|Jx>;0GD|Hcatc}QBs-{DQg9}8cObnY40A56qR`u z_GymSlTmmlnL;$ouyszsgH297(Pelab?d{iF>m$?5By~_=JJTIb-F71!Y`q_@R=Fq z6NJE9xSlMcPUyGF`n?AYuev(-@1)D&R%|t^eyc-(-}&W}7BO*|qmj>o7Yl-% zn(Zi2cV1+3=a zw5iERPkI57@iOh%Gv>P-j+4(YI?b!Jtc0r*(AjocbB&}=D=Fy#Pijf<{D!04xJNk6 zxYveL0S#fWIB%PZimWDXLJ296!#anhMI)O!+4FXjMesmzxP_qGBaM%m7;b0!g1+r!jhj-NpdfF=vv<_>L7=A2 z6}#{!49id164PDo(%g46Sbg-YVj16RJIl*5&%HZQc44&(h^;VS*r6jLOXtfo#B8E* zfen+pxw{8(!PnX{lu<162`lYR$k*hQwiOx0P#d(Pwg!{_Y}-?=9an2Y>HLpZ>Q2th zIElEX_!EFp=)+tcQmSG&aK*Cd3#ETJJ}PX^vjw!r*!;3{`+uE3pGfI(=R24RT1h$AMD>1bOsxKZ%c1!O<-skosGg59 zT za`wogyCX}to+^LlSPivY*irDZO(|P-Ytr!?p~kEH4yElCO_)2Eda~B-kHxt^z96m&oy-!GKzxutST-K(Fa)mIZrrXm(@aoMKc)~~}Gj{D;njjTm8zEr| zc5BMOi<3o?i|@nz&1Bq^C?^eBzB0TS7TBC7rT8I^iIGK-1)L2bp$C_^k+(HLnZ7a? zc<|8URj-p-_Q`Bd6T8Q$;cIDzu3QM{m5|3|7#qQ3WQ41E_DEsw{;SIcZDYr1UsG9~ z^M=2C%;GA`1Fz<(tzr9$BEeiDrnRM~MjHORT@-~X-GpmiPYB%((Bb$Ni8kz2Y^3iS z9#ZCn$-=U_^+@U~hNo%Sp6O>YKw<|@C*obPnFp|L0>E(4j8OfvZPdv>0o({`! zc3&cZ(97U5%gf}E?Dx~8Q!hhk*Bc%lhLG#Jqxf3s1rD<;A7%Lgx0Qp|m8C}3bZwS9 zK3SlxC^kgj?c_!KF0ZF42hx1222(#5mqGTl4CR4qh!pQJXpCXiFR{J>E#gL)cm*v6s~N9l@^S%nCv!g!YHJ{3xxH|>$1h72EBVyjcw z1?C*bKX1{&O@a=z>tV53B=eIR4;Lj%%E`7ZQhoK9^ihNO8j<_tnYxuGLdyHa=PK8C z=>exAX(pyJ3Q`rK2ztm&fUaf<%f(ttmt{okY!u$xbLx@(MhXIIqUY}O`J=)#-%Ao>8h(6P?$7Bchf3^spg1d#TRgO5HZl|2~E1$G~ zs_kS9i^~*icSxRI7oVFta;w?ZG9O>{0yJYHrVL$wCML>H;^{osCBCxuaJm-XZl|v( zBMEeFSn0vE8sC1wEbV3-P&Od3o##`&XL%YycsX(*+)MD;Hd%ME=-PIfcKUT)8Z>}e z)TZGx#!hpR7`3R$902Ice$5j6L<2Id^IdSnEq}1OpoD2L?P>5z*RF-bgX!OR4<-Ve zDiwb^aZ6gT96i%;*14XJyZOEZGrhA(N56D#_0l6cx?0?w)qc||ncs48^SE)UW!U7) zwK@)xwvl0IAZnD$fm?&1cbk`iU5;*Cj4A zJn!qAFxUDIXNt0^E9lzgBPFv-iTkLD1qQrMTh>N&uZ%Pp;ZqEfx@UW=*^AbvK<#@! zPPJlNZ>KV^Z&9o#t$+=kuV2+({r2K`%cFTHx|Ua)ssqt#%Wj(`XxN4CXKr&nRb_#Ygiy`+W2)RL*qB)y6!^AqU?eus39PoV1Nxqr5)FAvPMZtnAC*uC= z_JGX+4a)Lo=PhsQd>2>^YKUb|v}C)7(ZO|gEYo_u?X*RjSCuXE9u;%2ZSVbwBAJu6 z;SUsOz0^AyUBss+*gIqt6#Tl(Ti%syQjYSn6((*B`ws-_n|7TjvkziySetR)k0eeS z!fv;*&Pof}c;gwL4vTL3^=oCj<0&Q7MvLcGAKR!oiAq-RN%8qgEvFMRH}5M7N>oe{ zf?8VcB9|iox94{PfQQS&z!zmuB$imyufLqt@aoiuH7TvG*me*#G<&gu^SAC?O`e6e z5M$cH^6y-6#@r$MN-@|6n7%87XkL3ZNQG={A;Gr69(b8@-z7f1%n0X}If%kgK9BI8 zAJjXs%E>y1%63sse;mCN(A^g*En@*&eMEfPU9E=&+nVmSo_7m^e3x(im%j#AykKX( z{wE`Z8tool?Ei~yO_5?JjA=bh%LhTGH)#2U;D4z^zWX=`HvEimm#KeuK#usd7(|Q+ zSUjRY4}=rbJ-C!{C=Ukto_7L*Ov^u1wQRIdM6B=L0bZGR^4_m(pKt2gC37}#>j{ez zNfdq1FEuf!SHk21muhOCTUuGOf1pFqaIbJv#+!xB*}`ojuKES1YnzO5(vbYpl*z3b zJcjRQ9o6}abUmnn@hB zRyRlJZg=BKTy?PP3LS+ljkhIT&tG9?&o2-)$6a6Lr1H zL^HQ#dw}Cw38HVqh&Qj%;G@Gw=Vf@_ojWpK^w2 z>w{^OmR}fMLY@5vV+X@Xq_)#~rS#;UIn>&uM!s%%^tbdO+Fj2Z33{B7-;)2430EU` za`nD!CJ;1TdQd#mx@RFU*XMAm6$~|fuq)Wqd+ezxt{}1h_;)GuF5ITZW7tOfS*@h= z?sMqZLG2H9d?5zH_tm5ROTzgltiU7W{61eCoJ{%K|97EfO4wl#&OlfO9W^1lQ{ zQ?h?I0n*)nrIq&|n&y8#Xmk5lrT#y=_4#eTD)2q0H}QKs+($)GL!s=IY1sb(SF$}S literal 0 HcmV?d00001 diff --git a/docs/modules/localization/histogram_filter_localization/3.png b/docs/modules/localization/histogram_filter_localization/3.png new file mode 100644 index 0000000000000000000000000000000000000000..e7927366a8771f5a8c707681762915bcc34ba901 GIT binary patch literal 98927 zcmZ_!1yo#3vo;K)L4yZ^y95sqbZ~cf5AH4l3=-TexCMf{yM^EoG&qC1yURDpbHC@g z*ZI#sv-aA(dv|qp*RHOvuDZgN6eQmw6CguDLA{lh5>tVKg7Jr3@Q809H6qn=QczH+ zc2=UIO46dDWJ=Bs=2o_5P*76gNty^+s+xoX9#rJyNR$}R_{J>4rs(+O<%lqB@Ob1% zR8jA-zl0GosaGqA;n3>5tFdf=QBf1CsH1B>q_b8o`JIO=u6(cf#`0J&`_()9bcJj6 ze(W*YTj7KsY7g}+e+r<6=kFsOz(~&a^%D+gQc~D&sH?Bc zRSrT9bej5K^-#NyYQnJj zjwn^B=q{TAxP|G$QPnR^g0*YI;G+GsJAIlBY}=$pqi5Dc;q&t8-2AGieX{BOv{2l| z>5OU7FA=vBO+sui5r6i~G?*v`Cv1tm9rv#%;}GV@E0Vh0`1I18#LA*#)%0av)gZMv zEwTuwyRT$tpe`T&T>1cTzCpAS{NO@>n7rQaeNAZs-)>YsyEipaN}OO&v28N zTt5QOpa5?SM8CCeb~dj%66ZW2#Uc?0g$5l4G4~wfZ(uFpX)D0##|er|M~;qr2P_FI zumEt-gO1|xEjDPn;ctVS<~>=Xj^HbZS6vc~@)t7wbw{+=%~t9Q(VNsH3Rn6{ec2+LhA zTvB7sp>*aG5tDF|BJ&pJDM&U;Cg~9vr&XIUIpsa`x01I0C^j-`jC};xX z&F3gBvc@p>jhH(MVJU8`Kq@jTsW%DHQW)@T=-OYtQrg7J52EGc-jnb|WQvVZ5)ayK zK~Dv?i>>6oml1!f#QqzNIPxLSmV-cEq$qb`kFox}enh2M*#v>B;G%!F7)##VB=Z&i zVl1>Ap~>guRFs`ar)q9S;*lQHd6;t4vR>cDPjk(ql*HM>c!9jCk z6!Fsav=7}KsS=~)W7L&o_T(gFjaYnPv0=|tSVO5>a>!JD@t*lGDj%#UtpxYsN)ms| z6HH9a)=oIjMNG)dC0Hg|s#_mV^H$E3T#MPnmCH6#KPGMt!dwtt&|fe+v){9|WB{Zl zzt5|}e31T1H2hiST|u^Uh;zz?jIQpI%#xyaLZg;EMU5mwsSywELyBD04q@bEh*j_7{dG{s(GXRu zrgc(n+eB1f+a%LSU&CwUHlF_Z*e1(N-xzETwlFbfpES>w&-%sEXsTTE3TJ@}OWn!l>C>CYy9ocuMy zG;Wu&l;!lWNfX6@KLG+111gJV(z*ySetc zwG))N4%{!9_nEV-jErpMjOF}#f&d;L)w^fJvaqAD*04^gs==1{3gw{Uz2Z;GTrK8$ z0!_(FTt6&&o{);ZmrRCFX5^9fbN3B?PN&Vorj^sLf! z_qs{7k$)#WlSo1vC7YV!$Qd8cP3dH~ahN}muP*J8K%DSy$nFF02US&T)s_5^f=c=0 zbb$NC(-7XY+*GfX{C@t`*DLV;vuaOKdCnC7jE(jFZ^G%LqIdFqf?!jxl`9i=SMxJ- zqA@bleDk9b&+*93nX?D>mb47^$2+2zH!tkMVc$e1C{b}L-w6yMkLqMxbMUcx>$}I& zX{miUc<0ia(aYkT=iIp6J`_CyPUQQVlI}rf$RJ4hS}bOmz`(;l?PESUidIrrueSJU z#BcUN8&qq#V9!I5L*qct>Q8!|f`b-Og@cY9h+Kw(U|uvTpqH;n^`Vtxz-sJ*M=^pj zqAM$Me0$t3!-B`*ydB|k;nIUq2-lR^QrEJ>alhw8JU;ScW5!8D>-P3tc|>hQ*X+2KU*}Yv^U|B) zH+>u4nAGd_4{6Kme&El3Nun1eCx!k3tVglXCLg$mxh}->f;x(9K-M<5X(zhsp|c+jylxc1 ze%o!;r|Ad!2OdO5By@s^X!K|=FQEQgE;MmcYrZ4z<`;w|QchB1q7ODg1Unp8pCTYk zrqX$16u1{>i6(ruB$MuyNZA362i)6tQ=6i+5sFt$GP>T1<~csUIlmu|l?)YC zW@Wp!KFeLDxd@6sxgIb+9)-IE?COj?<_LQIxE0wHKaG5w(#}kLzi_xqdAxG`HU-4Y zrGMTwwfwPj)6>Fncc{!*)33F^!~NXr=sJdQh|3&cZHH-?S!VX1hDk>VN8xkUL^krz}%{RB?2h>s=3IMz9ty-Rf z`6R_zaPfFi&dl95F&(>-{Oi)QVP;!Av2TUJ0_6OWY^Eh`E-w#74=E!;!9!y~!9q&V zkUtbO0Tle-G8B{yG~xf0RiNqqX#)cV6>0?q_fH!g$o*BZwE8|?p-|8Rj4Ruz?&hTK(6oXyPaT`V13hclsMAQecCQra$1P`K28E@){L zsx!#pY2Hdr%T-HWj@QJ&j@j7M;jJS(#ZW1dz$d$N(++6u7DE=_|pWlDRY36D5UrzQe|4a)qL6$#nSUxhdvix6Uu2$y%f5`s4 z`48FOdHshS;7@0~N>-j`wpwCVb`ViRh9>awBNr>+FQ5OPSN|R9e@N9`%$!9X>>!k` z0{{J3{}BKC<^Lx9%TxQmJb5@c|IPAWZ~jI3XAZn7W-bo4ZhvH`Zg1r(zy@IXzpDQ? zmG*zh1U_B4^$ z?Qbna(*%$KEdQgm0?6$QA(T*1LQv9T!fKw-M;%DN%_P-t_4y0=vhvy8Xvs~#j3QC_ z#|a0q641c+o*_rD70dnzNHNaMsoaLL>4<GdC1YX&}z{9QfGwt9wx+}{GS`^ zdpHgB!a@yY(QXV@I8^9=ZsOgD-`wE-UH2x$AG15)Q?vTqzuQsz&m#N}5v2M1_b?Jr z2(xP%`v0blg3=-VSLdQe5a!TCT7kN5Z~q^|Kh0q*LH`~^KmfTBoTJfO`QB?QE zMePzq#&@18V~Y(o;Khc+D<3f-o$3Ip&8F{ScS&G#_=z4;FBCX~7M!`Uhi zo4N8dgup^3=}xmBWLuP2gxz!uG+PBv{N6Wvqyr?I4eT9dgGb5Ew^E%HX4W*1AODEJ z=nX`=7EmUWA>DaoQ1M3lXB&|$?tb?ve)~6I4?}A50IB#lLz}V9#C-0}1A;F|Ckx}g zjcw~8hu|WC>kqeyg7=A7x1LP~QrNO@{vLBq>Ww_uN)#|^x$J?4%p z6_3~FTLw--PFqJw5@0^x<53;hg!ECX&omp$wt2rWV>zYk$?Wzg>B|JzX@IzNS2@<} ztM_bO_BNW}lOuJ?pDdm3Hm$+0<`{xs#6)%`8ecNcr%!@5t7<3HtB9$JbUlCkVz3H+~Bc!>9lzo^e~MV5yR4Aco&?~W&zl=icqb8G9uJH>e`54SRQ{G9k;xi{Tb`p zw0iJS@OIfH2})x79LvD>e*5Iu!7udjLbLNI`>vO^_4;tO?Y83-WIa;#`cTDpQ8BdE z5p~c2`m2_C5P?MH89#<}!%$#^;gJ+^b?nRQhz^pi&}on2e7@d2F=O#g<2x*``&v%s zABwcmv^^mTJ|7@Gy;*YT`nZq$poU51h*P*h&Fo9G)x(L=)U3xHgGHb0GlyaYnv68q z%D%ZOYGVo|V!LUFM-dUYveE111O#K0s4DP?OOwH2po)AecM6MBMr2$MEc=I^Eo%ZC&ntk9GIE*7V!H5nO}vcm>_I zL9|m)Sxy>-{P%6LuD#RiUF_@L%Z`J<*2?3`Z7c1|eC)o;^<1ZW_G8EDBmb?3->t_< zSSbG}@#~;uNO|L5D?!EuSt2f?=J==qz7+mkv0WH9M+*!qLViBQ82m3VNWvlBvz0A7 z1h?Q*-?=Q`hy9ay5$Bo&E@0@@u)M|HNS(t!Q^#N}|>?7frrO9g#Svlf?* zxGKuv>P)YL5*hkQ;z3f`^4Ckj*G>D5V~yL1Ky;)Jy1R|G3#Hq33$^0JQ5bw-Q_Sc2 zcDN#q>Kkq!yu=opt4ASVRpOxB2awF%U8$V-t8xJ zaCHEV=q@uDoXgy1?g9q*<*F%_a!!4A`A%YA_F|XW{hkJ*q3G#vOd!Tz9FrAB3x{XK z0`UqbK-=$3XT)4c#E`hJPme=gtpE+*_u@#gy2vg*F(ek+fh*%Y>YS{(Ap8cX6 z&I0f0LirdouO7Q5FlT41D&^6@UptctSyrP+so{h$kzb(TOs^02i;Ol+8I~>jv1}2S z1wEIY23q_cZ~Z(3S!4$sUIJG&$LB2sF0F1?Ji6vU&s|;2vR@^eQ`)zvYp;M&2|t>; zjupX@!Fx4o5nS;I^e@+juQMG7>Q&Byw=ROTV#n$S`>oG6d|SDRimjSm4>K}726sJp z^pooXyl;o|Xi(9{DbYjQ53^2P9YBY=VBkd@+=>VwcB#?M1%Y_01N6haF-}6{tH1D` z@3yAFCUe_W#>t`KYwJ#A;rG);QoYlYmPZng$74ZP!+7d7RZik9gQsE5=#KPK*A;XU z*&jr5_umx)M&Edo_?!t(`n6gA*hH8mH$o4}a9r)U}q4w=2fa77d zz1^-eAW&)3>7mz-Or|V94(Zv2-Y+&T_j`~fiOXn>j2v)2ka|PtN&{s<23eTaDq|}* z<f z9gq#cT}imrl4g7L^AR3s<`a$lSuqgTN9YhXq}v}eEa4kBDn^VDR8rVrO?7w8e40h( zdJO-K*0nk2kSHZBB6$x(-?ML=U{8NEp(*|i26&ZOwmgXMv{lxS`2C3O4cd>=d`SYyJ_H$c8xKlKCtvBYhJXdD)9cO&{;eYxXVS~2SsD(4O)Kv3Qxf` z8@>)hfgV?`-}IxxaB)*(NR)a~2t*g!?aVqK;(rn<0Y{KPte=d|_RogE0ND`gD9oHg zx}h);gF>o|>HL0pzq`~EkB#5uCP;zPy@NquQQ2AHZx4?985heWw%3cTsDy9>5Y_Hm_m-1nyL#KU*jW9t)>_p-xFzXM{+Wj?*NY_To}vz6dH z&Ix$ae(*b~Z$6)Pwx{oH+e!&~U9~F;IZCax7nSmNZF<8x-)O$OMucSnzUSvKDkJn> z9>Dd;p;7;>fDErG20Cp3ZR5|WI*Iw%zg{{I#9pUjvto0>;UWb9gW$(?JrRY65-@N? z&ibj>zdZoP@oBN~u7adU9M=lQ&RVdy;74dP9iOxu&HxFa+ndKr9&!L1Oz>VGb9=aF z@0Z=ETU?R;7kLu4`^xsu=5v)P zE2ZaVoFw}D^NS>QxY&jjavGjF(zCM9x@%f?l5*KUt`-RYkAY|-ChTx2_J{z~Nx#eDYiwJ6 z2Curc6YN(1M7!iY`g`mQ`0~g5N6a*1hkJ;Dl8tOn-Ua~Yzi1Zs!sf%G6II##*zEln zbOZp-t*pL2uO61^p4|oeBSfCgT;%_Jd6bvJLyrJx3KWFIux||+!+4!}37ad#7kN5# z-kT55&Ylg|z>SE$i(@?rM+r*YR=p7C_rR#Z>$>YZIjS3PrN9walB}d)!)bk=ty4&WPV=;LdtLN}X3f zyb=6_lO@KnRE9l3z)vWqwgzWEm*~k2_^#l`Q}o@_9-sVPiXgkKV5Mo&_6i%hg4D=f zZTsKQ07rQDm25*g|L%N!*nYE(fk_!l9gffSIkbv#X0k^2cvVD(s0&QD z4N@!xBb=h_2~SV{JUV96F29 zlZ=G$Y2O@t05Ym+@jY?4S9LQ!-wCIF*4Ud^k)KAeQ9Gzf(#0|fPd}a9aeok?U|V@> z7DM@&kHI$nDvmZE-g}T>D$n}2K-ug21pmqRU6`Ebcm5XL4)nz3k_4YX<)EoI=XYU) zo?LrGlD+O((W0I3g=j_zIoI*z!;Z(m(jc!uLUu3-qO_;dJ z{q-p;NcsKYzSJW^8?KX$YqSn6 z@&AT_aM7VxxVs5q?=*NE2(_*zq+vWEfq}N$uGi<2yh!FL3B;UOovVJSvK)ctLB+GI zA~Q06!0~(^Kz$*nAV%9!HgQM??K(ZwLv_3N{MTo{cfg5wjR8*{vx_(nl9lt?^q$-j z=UStbzT|Q?E3NMq*>bba#hU5a^;e9%Q>Id}A&fVY+dq8?n1z{JD|p5McX{Th#yL$W zXH9O08n=++%xsp=@Q2NP7v;lMX_&#?1m>14EYSGe{e}E!Z52rCYyVQm=rc}xkBC4x zbrQ0Ps4L+CuL3P>EfO&7w&dvkTkB_Fp4CyTTP)VjHWKhBuC@pr*Svz>XPwbx4*aVi zR^ItvU2F>3?ierQ?O{t#8Z~4+KHxl$Gp@4Uc?*mYl%y- z=^?g$(HjsD>wElAV^l<1V-6}3Fz&66lmVthvs`|AP?HH3;f1vi>c}_2J+#_&&rC^* zJnkUZPkcm!oJ66I33_(zcy%T6Hh3-KNzFi@Z)P=Vrmqxg2h70n{% ze%ls0xlT5ze{rZ_?3YnfhAGpyPQnUZDaG30`eNGzRHq>A#yhpwvc9sT-egO!c}4or zdP{A3Y__PW4G{TO+E>CMj0>Zdr=n=YL9Dz7&67ufG9%~&vp0d1f6`}9&iea1w(mYR z+aLVrS-;bV+=ymeC`^`BwhnjP|8j7zigN%Wl;hz?DqsmEgPghqu1geW9FojI3x^b3 zIBrWFjD{SDlmlPXlZ7p#Q6)A&Iobm=6qLKgy0~eRdJQn}t{8FB$X^3VjPlF#C#ZE3 zj_SBYq2Ll8ykMqkMCvfTEH4FIl*Sm_|f;P5s#2`JCCw22Yfp{d1i+ zpKcqQI)2&BR|_+senia&VPfu4LH}l0P>wYf#OTfsLDUqwB(TUHZLj}^jsGQ+g#aR3 ztMj{N9}ZByb#SMpk1HwnmY(_!*3|(y(ide8=5&YI7e-ycrwE(N>;Y+>$>k&L4WLi? z>)Q)sLitNp9S1H zPRu51rf};Yzx|?c|J-lD6nbaH7nar-oGShP(=io=lY`FgmGWR5QCUd>M@?+1c5S@p zN82j3>{cMK@g=My>Bnvsf2xG*09&F+Y7tmg?p47iQy@J#lL%NswcxqDrF9q-;Tf7$ zoYX;f+QhK*DPPen-TNDlNLNGv_QN)nS6)uX%;#8AP0B)XnT)Al0U_Zr7}yW?+$^F# zYCbdcA7tS)WNA$V7ZZr?+dU0wW+kpIW0Vxp%!6u}ggGg=+E&Gb`rB3{UI{5ge@JsG zOldUQaQLaLOfFF3C+;-H@pWc>l^U)uaMJcWGNZX!XHN#IV>Q?%$P<>OGdr~QTI&2x z$bYt6)@nH#jffo{T^vvF$VRnVN2aZZUL`?)tQ*$a zij<4CK0okaD8{Xg-&^=otY}#30XZIOg>JK%h(CL4m-Q>LsZVke+fbwD{x<~O_>8UW zBlsbuvEi@rlCEZEBD0h3ycW)F3L|nK;;1g*bidCk42fGqOCygPQt}gsF3KaVM-(p2kcU>npbNJxzfJZ z>`yeAGN0aOI8NJ}^O;IE0nkdDP!F|gB8NEl@UUxik4XX6_RR|2EO{texiDR-#$zG(%Cr!qCuA~*$kBY(H@W@Nltcdfmfx0SF4aslXA_^6 zk1%BR{UyO?4ceXj9Tr8puad|UK0suw1y-%?QBKcunkA`6MQl)5XL_Ak{5YRfyyW56 zB1YR0E4>oVVQt)9zqY4#T$l;otB=gA_wKE_jkL-Q>KLPtmXbS=%Mqq6QT3 zpxdgM1sMP}3(Cp)89!c6o`kIJt9^9ik-4b%OTMIw?Nor)3;6iEqtd;!yM39y)N+L0 zb&GSE?Ft#1(!ax+nVk~}dQfdOIlWG9PuflYs=1Y>g3SxKR~+-AZq`-c>!qx$im=by zGG#VN5LGU0W{skZw^(aiTI~zjL{C zB;sEPPn(oM;x{8}A^2- zG(D~*EEwryPww2YDuL+&KD2#Jwn!NMf|5F}V}GR5@hjOJLrV-@D_KCHX`mhZ3d3<<`tp-? zVGK4rb0NW}+K?VCBz&U=8=)yR&S-xoXs&2a$>G4eJ&+)AO%W428G}(g7tXJgrc8lB z_H%aV5EPiRURbtB?y-n*70uz?b~fJHuO@8pnBM{@XmOsujkaI``am|PoeR3v4NSV@ ze`G#R$QpYumuW2YD=`+@XYkfP0DoRvN`ee68mq_C)Oq%)W)}DUqYa(p6nE~fygn#5 z*Q?+iwjVem8qX?B+e`D03$3Y>2hI0B)J-TxFPBTn_B0YP)ht+kyI@u>%nqI=mn}O5 z;6BhnECXj<>Ydek`MX87cD+5ONfghP(R+QqkGEhw-J?D1;IL;Nvti%{j}ZD2irM{9 zVJ7BB{gFSQz>y5WDA|HS1zl)l-bmEYK@K_5XawV?$kWQk?({{geIj{>m?h81adCDg zd0hnJgdC$2LYB}^`&XyqM}d9!p%*sn?q*?`ldF4G7tl+PI^i=$m1RoT)W<4@rhqws z_o71CB?WQ$Aw`ParujA=B=u+XahW$MlA*0OcRZ2V&BCbeM};lRo`mn997(JVSNV;` z)ib~vOLk22tX2svpd4dXnt5cV+qo$iqIQjORmFP5VhomjjRHV5OjLVCl>7h&Yk^!d zV=Y9-v0v7=%$|N_meHmCNx()r@{)anN#HiKiVpU1y_Bc6ej#Rcs8Heg9vCyw@|_9Y zh!hCTF0~4s>NhHZ=54!0`DqS88GfO}%sAg}#Es};DpbIc$TtVP3R#lJ!}lI!;(D3e zeF*?hs>k|Ffhv|AD}+R18kn6fEr0ha6O0OETmUs{c_cw;clJ<@G{Xm0q&e{yI_JqH zT2CvB?hH6!VKe{#m7fugbSMo$U#zMUb^EUg{B)xt#k zHv@gab^IFVn<*$1HuNn^=n>JhEMy7xpwgfjhHH@h7yzy?qf-I)3x^&KXkZa%)%M26#kgxFl90zA*;omm(p7hIiTGTH6(m#Yaz` zm_5<9UkHyy@fX`Jqd9*H?cA3hyuYf4pQFfeVNb70-fML#*Y#uimO3>?X(Zd7<&gLE zMg%I-_f1s0DQy%jubFQ}KSz?7}P+zyj&WkJ19D7_{7 zT~Z2+MWLx}W!}kokD3FZwr8{TsB)rLuk^qY7FFn!!k5})a#2v$Li&JGJz8ITm7C-=E5yJVITRH*zn6r$s~~Rzde#u2c?Fw{}fM%pn0(w{b8lShmc& zaY$w5snT{KvOxvIjxx@%AkYZe7R_-<>JIp9j?xPTHr@vCVpMxW9SXS_@m{YqHrjuV zF#a{|9K_f=BWwOzA!>0mRYZNcn72ZeHZ*lnP@t$A|5|MSe9uImEh?=e`2afC86C$* z990SNGLJttd8|tQ7~GiMpeBee{3{W<4am#*3!@kXVkz9nZM<}a{gDbs-+41ga4FGI zfz`>={F5K@!x{AbxCj$;sG|ER$Um9Sf zRo6DrHRm4~MKNvwiJqUj?z;F?|CV8BQA|L~@X$NLX?wI&>$YCIDwIpW^{%hL5t$lT z!@#DY%i5%Y9sv|T70MaQ<)K2_T_@p_16!0Eg9)k(S`g5JjAMSYaIU5f0oF1H;lBA; zznh3qr0&p{d(X)*+suos)y})4_45E@W-H06`{PWoBKIrq9Zoq4@AMKhTojc1H_V9i zI9GLjHO;L1VYC-Jg-)lXOCy66uv11vJ#jWlw!N*%esfrd=t$r|CTD40#rJvjil$0| zm|t!OF`rf3yAC+%Z4`H&`gPbv8;ZX`R#3eeKH%rfK80HRQ1x)N<=s|)p|y|;VH}gF zCe0k@(Zmvsb!z_MR7Qokd?_l7dX#SF!&Lx5t43O>_6jZp=P?hnCy!G?d-o-C-A%63 z7^@sRkHXyq57srl9r*Ardotd002k?LcB}e<*%x(Oq z{vBb;Pe zU`(Ib@r(ut+n_I_pg5tNb0Uo{N*^-vqlW6<>~L!gnk7Z=9&dikccr`Co|$Y)SR|rV zRL@z-JKdp9khV+LlvL@c?fs;#fUBFH9I!X~kZJHvjNSp1ut@QNxoV~7!qprl@J}S_ zTZUlA#pRpHtK}gqY3$Fn`Lv><4AB)KpQ^TnY44N8b;F~k zV!{A2e{h)Hd751t!IAf2zRkcX1W|c=}9GYv}jJ76R10|I1drR zfw;yod6VCtfw1a{GnSh&{J&#sE!Ml&5TOU#dcO#OgqRU>Gt5M*>q_lZx3_9i9@G6x zD}1|yxa&xx7TGEU=2yjSr;jSx^p{v>cX!tls7Mx~ z#@^bZ0mC3jC^1NC<-PdN8yCunop0O@MkbDOIu;qS??inzFh_y^M88LpzCR5VNSvbe8jvS+py*1}+hU?;wFXXH! zkm+OxNA=wjK)>mtqDbMiylI_+k7fxBS72irW0PS+o^4ZHAlvt>f5b@`>uNmGd|IS$ zFK~|bZ-VoQjrasJ|GmF-SZxP0St=A`!%e?e81u7IAwM2wBKehF+4sMpQZvYE(t6X8 zy-kb_PmT(@q`?Vk-F5pVbM$69JD5+Ti~YdHMCYphhLGQnrTWL*tp>+q8ARWVX2RUH zNLN_HU`E`5q%nJr4Lj+xyR9KNpZQo^3u5NelB&nbVhiLcC#dDxOh-6m+~Htm1!mDN zAlV64bRGT_vl0io-l|`PUrdYQ8yRobYm~+nao4}FIgRHo3JgF(C-w97?aB+SH*H3u zGj1j-=*>3IrOafZoyAN%weN8Cdv6#~C1fP3ty@7Va_eH|tcI-2+E+W^O;8CCI@J&&lR6J2H9(qi3ov;$pn@4}=y z#QkzO4zNI^|5DtcQB{Dp|ExvlPu==3$i+&Uu-faK9Vt>|^N*{X>@r>d*vQ zQL@$%6&{)y=3wCQG&NsYZNaYxXUvI)n<`|@X%j?$A#<2!u5~%BPn&Go1EXP2j6619 zE)atlw(i6X3|zQ4>Up4DVWI2ttl-{v;qJrtuZ0%jX|`r5ev4=F*T!RksnvE+2@&Fj zNkcLs!5YwF@3f)@ze%JE@bB#TF7^V@w$fZFYOqW+!9^|Rve&p~H5)QwW59qCtwhd7!-p#e_>)_X)7q8#_xWntJRs^ znXS;>otJ>!Z}T|S0B%SdcKLRk2^Rz_D=$?c1{BgT=ydK2*HDDXlvzd8GhR?l;Di)F zY#Y4KK7Q(t<0VPuk9w8_BZX>W6i;!hD{UNa{jUApbR_aWpym4xf%_Mhw zGR9n~o#HeP%Fn#(JskmRzX#P0GkxCBi@3?sN3H9@^nP(sqeT$ccXy8!x0J_0$=5Nk z&j>nLS(130n%) zVwM~)BcwkIPqV*W=Cr5Fl@zq1aTi)A(*N0lZ<9f*!Q8b=G&?yAn zvg!>1_&9W&G@MYg0K=C&RzcwXqO2X?8wR+d-8-#IfV8rdMXmr$l)<}K~*o}5NPlx}qqLCB1WHJyL+pP!l z{$z;{0uuzYXTMy1;2^n79cUilKXE$gd^~aC^Eh@z7ib3SyZmxH>D`QR`jbBYga0d% z?c2@r$o5`GG2H9Cu5f52eV%jy*9?&G88Azb8wdjM$Q{SYoOa%#hPir-_^Z!}sb7-@Cri{{z2SeYt4@U(Xp< zp+j&Xq!9Fs$9W&#VMn0wN+Vd*pTYQzu$0jpY-8m?cm=R}%V)U;6#Dp*q)B(rw-FZF zLd@r}2lTjq)mvwV;GUN8V+B+l1_r<5Y4^!BN|2aS4t%IC2HCh*gl6>wOW~dx8hkwh zj6|jmrHGTUL!$;o!&J3jJf8eX%z|fsqPfKSJ#B(Rq6xuc#7)fzjo`zZcmxp$0&;ww znWi{8;br0`>%sMm+qnK`AcZD!{L}KTz^?nratR!E?AkA`)piVnNKeqC*C^FMH{M&2 zrzhq760L6FFYU(qk&BCjxb9>6G3+}&k0Zy!xr({XERi?ivesQ3&jHKbXOUZq(}o^i z)qX3zG98HLoyR8AemvBRN4nOXPdE*N9U<7^Y}pEZ+T9Uv$+5Q^HSuB07E9PD<&;_e zn6je5)!VMqmkZFVqVy8s%GsOSJxM_whT+5?fbBM2L~w08GYx@f@Tg9UxA#ox5Ie0g z@LmY0wDkpr+3^o-b*3&1;S7QTodp^2nUIshxXJzA+bSrQ<@6f2i{h=$(fvlncJ8p; zT*Y^gY68v;wReLcOWX9gE8-(d_&5$f4)FI7E1i)DQ7hziH662nIPKVQFe?m+NwVr2 z%P6uM*Q@LwKfp5L!$idWVg!Ep9%g@G{Jv3}ZcZU&wffHlV6`7#ZmXP6f#cp_%}(c< zNAT*sok#Za>HvcgVg~0i1RV%IU~W5N^EmCeZ4E>h(Ap$-@)%O>{gcuK;M6K_<_X40 z*sH|8ks^~Fz`Y>v7Sh@}zP5s83A~6KTDA0*wu>sCFIvyiQ4;fytZTSXX@TGs`<`D& zI~PEEfquvKUC$aItCkufo-+rc!q zhUH5LKDT2Ww9B{Z)OGp#+~{2kFdkIxloNUqK2wPEcQTE7$I0MI0!-xyXpn}B1bS4A1`Z9y1lMgYo^jvGRRLdA)S@gSP z+Ib8;Ln2Trb2``hycAE4n^sD1pNJV&1UL5a)+y{`?or~!bTQAuJ`Ue0i+|_6oK|mJ zgbQ;Yc7CB+NKHm>ugi8(&&iR#(a9vAcn7zGB^34^dqAEGy!EmHK6T20>`TkzuTLz9 zEquSho}1BLu`7l08LkNdsM(G^NGJH?PfoY%=zjARnByxF=V*UWi?xhyp`H}JVwdn) zPEauCkpoLk&xowrF?Sx%!RmS<*oJCSmj+uUSln~xAmy=~Um56*ML92YO|DZzUN05# zOUw_8l|a_$;gH79L-Ac4&KSRzdS6nFuI@5zV2bER{PoOkePWSAmDCX|VTJ!FbcMbL7sB4QZ9{by?E;&KoYj zY5v27ah226*Ly*~d_&YU)gYR;eX{W(qVM)GC}}bnbH}O3t&A)-93FyyXgi{@X`dH9 zUo=wgPIzfwKu~$e)MyToP05{;4d38?4jPu24|y9XY0bJYSJ{?CXqk(CGlSdlf(o=7 z7~*^GeA;F?w9)BNv6C_h-)999r22Ekc|1eRqw<3|49N@knm_DSmjB~vS660G->E3_ z_5vp%jC3!Z?wGGM_1mM-N9l9@GJL9cd=^Yhi5k7S^VhAS6KTDHO_i1I`}An~4GfBW z`PX1T>%}lGKg&h3$pr-UPRW`A^(K}`@c;t4Zb_^5hs*Z47z(cyHvF6?o-E>zlob9+ zt~8Q$2nU`@7QB?+ogd!Iw<}HRE~2p;%;=Vu(iLg-8;E&0BVK+vk28kEOwwXuPa-`& z<#G8nOOtcO@5^x=bK%9oX`YV?@vgoc^^ix6fw`(T;wZKMkMia@mfqMVHWk*I;5aIW zEtYSp)10tr#U)z?rA&MQeMlY}7%=xAbbV(pTIuj|+S@Ems>7vmRN`lL+Anf5nQcXL zOc{%E#@cxI2_}&nJ)j3#ZKX;#+udanszx}cmlWaHFuU8gn5ujPa}See0<_eO-)SZV zwFd(7!^(k|R>p5%)r=`&ZR3^17tWm{u~euTFL0cGl=l8A-fp(^EAL5dx69NN_$9GO z>v=tGI#MY4Xa?TOJ*c6u_9j5PDxx14DO{v0iMd?-AT98gP?i)IhOJ$T6|Pj&KcK^M zVmm4?jc{zByNwmrHk{Mu{Y`)5_vlMVZ0zEaUae94%7?zpG&_KLinVN1OF7T7L#l!x zneCx-3^r_3_z0IZiXtJEzO7#S)uU}QQ zFh>k$i`2|#XPnFt1trV!q)itKMUtf*6i6#GU>|cKeysv4CgoH-;T7D_^HL_(0rQyW z)id4uu9&zzg09l6yI4jMpODdk>rcEQ+FgsA;emBfNXtAvnT8-A{k?hstl?&ucPIT8 zQw3Ny8G-P?@LE%PPf*?9|KsT_xZ>!-B#Z@jg4+!45E2OP?l!nP1P@MdcNsLeySuv+ z+zAfB-64=2zTLBbU{3d$+qZ95)l+Yenxk-#ymDUp{Jn?6=M^NFE$ybxQ9--x-1a@% zX>`}AWIu$p+dB}S91N4~GQnqJ3wYygiO3ta(bF=8LN=rs$uf#f(ZSl|m%}nk4C*%5 zS;f1DGW4<*znm${?p``>1ZLF#qlq|p48DhwQH6FZblWiykK}w?*?NFVJ(;xf%tloj57vMVb zlpXjr(#+<@H5l(f=lORO&`{f9a>l(Pm2yrD+hsf8cK~pj8t#;=how;h!6sbcmPfzw zi>3HkSicAnW0+&wR%;M|*(q$P-9`^cc7y1q^=fvbv4T-QpLG3mNK|70zhg7`3_<)l zb~pkit^PKN&$?W|{wC43E<^|$qKSf)YPrPypv%j@&*p(UXxa^zXp0zLj27EC*SqUh z7fib~6YC3)CNdZp=Jjn3ILq`(ljN7AI3y~QESC|}`1E2* zdbCWfQ@OFVgO-XG4UptuD}z~)1t-jG_8Ew%e%p$&uEd$sDIz;Ubg|cQ}FjdY-JAKcD!;=#i=_o$`pE7szGI`4iwXHI9mLyG}Km|;b^BuWri!6=bmlO;bD71W)ds^(bVaLI1bEeS@cX&YyM{r|tC zMFH3YNE<9)Xqxe+QilF4CAvwIUvyQ3ai2>b!uhN147N7FeQrY()!Q-~*fdTtzk;|$ z(U7;0i-Y*($YYz->@OO(&`?OrgqBPCSNVd-<*7mGc@sS`N%ET>kC$ly?}0^|WLz}Z zUQ7aPn47NHi6qxF`xnmeT`~ykzElilROy72^zyq5Jr`qs-=$Q?7mKguYcmVQ`Yk@F zZn68gE4A@=htus9&l+ttKTWqL;<6|pav@7S{Uh8Tv?95Har&qB1YLxu(ssMHf!~h( zqU0r!mPE@+1F8Ah)VJ)aXnfG!=<2Epk<5z@+N)^<+boa?l?Wmhk~!btm-E3|lIjO( zEe3^uQ*Rr5K!CO#k4Y~F+fPVzXj%oDsdSYP&EA!x&y2u70Ifjr*?i_-`Stf|nHka- zeH>TX&PCM{7VA?wBx`G5-vDu(MR&zC=0|-LJv|d}d<9BwE;n+npq(yl36i%qq9H2g zMX0#cFH>5pwC$D*yVO8UGj+JrvPFCtxpsh5<}(=ek2rH!`RNKrsSs-B}nu zb@^duMp^THh8?9h)IMU8Dd0I>SGtIF=4$c~HQ>|pIBB%J?iix;5nf4lbDpVbe7;5T zCn`?!f&K*d?Sux;#W3}Y=902Piu19lnxCI(r6_>g>e~C1)yicofsEEy>%}lyK6%gv zJQ@adfbV-1hlz_{dh5R7Hp<96l1K>i8S+Nvf=v~VGB=hbdR#60h8KWET5+ZO$#N1! z%XxC#fTnT`pK4fI3akAORtnQ|`=UXFp^`Y+vmstb8Qr*Zq9ni;wWOUHB0tQmy4>-O zDihoK)?(EZ`{B2H7h4x=w8$I$QP5)Zjxz&fCHVI!lxsSQ-4$I|#Fem$jGqy7nN7@e zn0=f_aLNCY?9q)6HTwb<0>?l~)vyl!p+kAH9=a&yBOg?nY= zzr9l-P@{6;fn;yf8AUJsEX{}V?4PzXLn-sf=|Xmp&E`*t%_nv?u6d4LJaNSIV{}_N z-FljJ8k!mbMVR_9?G+ytTpF`8y0s;4y+ctwRC&XE1JKbjTAdz|szs)t-YKiODlg=$ zX@l^vC>xxZ_{s!I3go-dTrF;x6%v({Jm?pjODD)l2c(53l>^vInUB7E2&^QTO5mod z8A&GCdhA>p&xV$vn@#2W$*a78Y`-ntayTluRZf~K`eM~A_1rd}6){=V*ghMlh9|O@ zYbuCh1U1MZZl+e6s4$smq!=_Ayle?&^?|*tS%yQobzPHbj66QhBfL-xM%k`JIwOMz3K@eU5ZYLq_m{mKAzjJ ztTD#r01+C)eh%KtND=x)aoM?{Uv>g4qA#@Oe3>RB0J7PUe~K<<5XOU=rjC>j*bkJamEjS_ zc}d`GM#vO&+{%hNX;Gb$Yy-~U5Xx3wTR~IlOMeJ?5Ue48wykW>U}mR^}CnNGxS zMi7-^f_#Sl)~{09f4qc!m~m`;C1>I<0K~c9L@Fc1yvkqFYmDYt^wH!?WzD z%t22$NVJEEiX}1%dea^*F-{6Mf#z@30;bkS< z#A^N~n=eMV1gYo{3;mD`CJk|m>}jA+6oY^7yz@c7*<=`f_(~Xow7~bPz++DP z%_Q&o{n^@ZV-RMQLH7o!&*Qe;?ojlu`x<>H6!@D?M@}@W$VXum<358-IBP80`ws7K z$)WylT5bkMuy41*r=}}2eKv4yv&nk3CY&nC#)xW=h>sT((B&QHhUo1ZJNox^DXm}y zo>A||esWic=>D*rFwWZjyYml6wWCFbV+iklqU!Ah1mtzK|FKKF4v|nRoa&RqhGlGM zabSLw*H4U#e8!#q4osFjrUJ;FelwIs!E3O;E70GX3R>S663h@!Xt!|#H_e3TS&kb@ zf?b;HQ2jZvQcs|RYPJV;w6#^HHX)+;Neu5f7qv4)ZdO$^Wb-+g%sdAEEi`zhe#pb` z9I;((7(LtQ)ZzDahvIMu`GurQHI3MOGF=w6&fnqpY>4->XPQYCtR8t{*dKyscd}S{{JI7K<&!2VH!a8| ziGWGJb3X@DH6f{MjAco5b%3mJtTwRwgnkYyJj3h%DzhE^=0*0jOdm&kg1oXdQ`x7Z z2H($T+mwfmCRwmOWlP`u`$uH^#fI1K-cYjR7_J>e!u*K!2$2^h{kc6xWUDmS=;P6L z^2vjar|Xg8Ml&)!Gt=@0la9Zv_+!uJt2Nwec=@WX)6J$u_acz|Sb zRUS9N*Uw#*37V+5qR&vf)7EJo7cIN44{3_NtKK^}*$xoTLw=}Qbp6KQQsiO6;;n`E zG6#0ybE-u~X`Oe({Q~D&qvZ$=H2=iO|bczw3-SS0-yX2M}Go71kdi0687jgg`R zFP5-xg3>PnIH8Jc#w>QqPG+3buB!~E_*F%5#C3J$qqhAkDkZxp{mRVBYQ_78c+47h**Iy=MJa$NQ4;eH|;5{14|D zua=L$Sl*4Dmde}1zsHW3Azxp4`15t5;n$#lf2aPPW}$ykW`0jHQQx+t|ZY6H`crogJdYe zl?y-E-=nnI4EPx@?dkSy()H_*P4C<>)+>N_djRa5WX#$VbR|o5-GEWIJolw3QT8<= zgeF{DnOOA(n$MToL5i6&UnoletXvpQ2op^a7Y-$I=#Gm@74ve_q8RH2d(A+ANFs(Y zJM;;|_wxGS#f7wwZe+GCvL57k+_wQs>WW*SJhZQO`<&PF zut2&3faly(-dViThyXHSeGD84iiPa_?)Yl7igpL!oU5DFp6-~^Xw&J4ConS?nZ_8g zMGnrPIj*~We7p2<(x$Gwi1LfThOdl>hK?h^x6;k;ldsC11pJyqWz5$R3@j|t7>tM4)I&{jhZ9dIhWZ>$kl5hZbg6H*n4}fej8h-&FaKa z;Of1~8G@9;IJzBM6}R`J3-;M2h6-Lny}fS!>+Epd7IrK6{o{4Qg0G+dWo0UPKNZ|~ zT^d+*f3C1IFP%RtrI9crG_lE)r|#@`^jwe{B)-9QIb=J3Fv_8rIrl6>rl+jskgM0Qkbc zt|vqQIMAj5?^$rx9vOs5tY}GzMc{W={<5w11gGmRFQ>Um&3vNscxRenRytTMl!JIA zGv2=?n<|d!eaz+y8)^xgPJ<+7xn9tv5=<)XDVpYDvqs~aq55~>N$;4>&a7*BCitcs zb#&A#W;Xlj+ipfoQ`#9Zj4c4NLU&r%S{wu4etm|p?8l+OK9ox4muGIj<|^%R(%JPh zZ-1JB<2+QlSG4Eb6Dt!3!2y>HM`ywdtEao59`Mpz5vxR5N&XQ;NPoYH0=Dz1biyD2 zJ2%y60n5vznl+Lwg&(a@byP9=hTU9&a7uKj@do`e99I;SUQK>@o4RsHrYI=KlII=X zWclylB*qdcr-%Egb02F9*D4ORDq@9w8w0{(mE4S|hwH8FvCbEUk&3=D;T|aVL`Kqg zwA>_HtR3s*+J?4~GM$SOZiTMaex7e%=gt32U`g={h#5vsEkRrThsm;->X^qq937^g zN>~bfr*cm$ZdfvI@Zl3(c-6=~Fni8~MAAf?{3T#T7Y!zj z-*4fgg?3w%(51SXS-z)_DU!z*1UwbuuqD0#bty+GRqaj}3i8q7QHl8&X_L$*RWeu} zuKmt`^w!@pUp&~#=VF>%inrsE^@CqMS(3SdwvrNWHkdwFW)*p44p;0o4wvZDdQd44VZ8UMp*%u5yO z&#kyY0p>9)S*kf?Qo+mkd4u2kX_Sf$8OL0uZE#;S=bL^5-{Ju`ZN6vuaintQDL(f_ zu`?T@CczgN+;!zomZ-cs9`F@S(uV0TQuM2? z^!ky-!Cmi9r7@MnR`96UkXsM5xqk!wY-N=(teXc2T$+#8m#}YH;3$5s)CnRe)Jm2R zqpv@@A1v}PWvNt^MfN8B6u}g>Vq|Yj1dvJ=h`N&1L{;s+U0v0)V3+xPQs^T+UF}q8RD3HauBbkwAB|_9~ZqYo5E~B*9fU#q7Dyx`}UlWBqKpSWn0u z%}iBI1^oq`#B<@DKf{S~5i|G{ zB6TI0z7T1M6Nk2a_PM>&MRz$oZmM%-VDojx#i=iU?_7)AUR=`!;k0WB2_0&x^r=dx z@%T>?It0j>1+FpmtL&_?2o84W)8bPryMMo=+SdxHXv@~=9@)HG9jG|IpE7tk|FfmL zlfmFA;M#0%uB8uW8qs8ks1^$a%ZB5JK2ZCrRk-5!1tsms9p3)!8LvSw2tB_4aXQ7x zl%5H>!kxhj(SDmpBMHkG+7*u{25Q&I|E6ZQk^Kf40HKp$aQ@;?k7aF)4~hgez65L2fKEvf9)&U z#4I6zmO}J3qAxbSODaVvC}j^uqu<$RY=d2%_KExmz}2H15z=iSXE7$0zia+*;;ZUX zA1DXeKPKS7Nd7`I{tdswhu$sSn}H+uqk+Rf8D9sbNn#M>bZrS;CnR z2Yb5EK{jY}LIxY|U^^9%#mG=btTG$a%#h-bW#oNfyw@_hPRCL|CR{WIzr>E>nxl15 zpoW8ToB_H34(}#S+*~SsEZ4IAm}F(V$%6P($RpKkncuJ9=3zkl^K{K~k~2BRm2|e1 zjGCHg!DRSyC=fTeZA5hjiB`7pcs{f6hbce+)Fis-bTDexOC34U!MeB zAK@}|*0k#bWV6>j*N~rBg;4fnJynfTk@sxEu4iOfPzVM6RY9;sXLk5c<+NuMYn8JL zCacU~cq=sg4ZZd)B2!T&!@^&%Eq>8$VIcM?DL3s#c|`{|B~2UImgNAb#eHf6o7=ht zg)P0S29Kr;8Z$(-KtB(t^4^&SXE^8$(ZvI|_)k}hMuPh7Jh#cVu2K>+Qx{3h?H5lc z$BbKjAMjZno0Z66GGd#`l*zk_xJe=V))B#-Lf$WXhbA=j8GEYYmGybUN*sH%2fu~F zuV~E;w>;E9AH0^e+2HElGpi^v z{9q$P!ef3)Ic=BuOn;(v`JjsXgDa?oU|C#u(@OiSx@$wQq$jFgB5Q?Iub?OM%cU59(KpnLC(y>giw;k0Vy^RSxiF%--n z=u;s|=LIP^?}V1!T5?qycGRqP5w03X4|}WHc3MS#%pAx0gK{QZ z{pN_82|rctLL?@0$Imt@D`9V)-e)_V5uH|VVThCGZB>fCHoD*n&cdQs5M6d9_^F>h z1gDK_l>GtDmf(!{)U8pkH_w{y_`2&?A1_(;1IjQZBTv;1Ol1kZ{Ox*+t<0aotxn26 zT9UruDQT`12dWy1C0}-#JKuH7Mf9s3{GP|zJ%T_D|ItGE3lVT75w(8e&^LucdjakJ~m&omn38+<257d;a$nna+8>!@VAL4S$rh9i#1 zA$#A;l6e}l-SOUmO!LH?!wj;EW6e~62_$(yJ3yyydtuQ_{YxT)T3Jz3-J}1Vi0a&?}JiW9RaLHr8e_D=l2ib!c8Xu&{<=a9W(FoXBbxq{iwql^(lWL zWI&rO^;6g+SbAdFn2ME2|2*}VmczuiuV*QZdTr19(R7aAYR3~$e%R-YMjYSHYJ0+$e0SK&a4|_HGK8{ zo}1y3+^nt-JvgUlE*|sNI`>s5c3Q;%dI&@feqmpan9pd0PE>S>{v~UrSOYDnNTBcb zGFxj%w0uuA%nK1>hb$(!p~9QmZHCsHke~kHh+obY=A?Dale->>X=IM;5|{K6mXYz& zLZI}EDrCbvOy|Zb88f^3@z3*IRA6Y{nmcD(S1-fFrbdO}^BrA`j6Bi&IiK5eH=yBC zrS2l3Noxk>O30x}h~>T48l^T9&JSNGdB4Mq|6%5``lIU)xCa-Vv2OzjtFt7J4`$f0mggnQ=EueJ;W zK_Ku}Zw&RIi8kIz^Y9FD4}t`I@$VV?ToA5O8KnSV`^I(}BN*7KcPuSf$G|_W14xA z(Wx@Yc_)R+Sh_R7^2*<7MAi_+2zA*1uQ1=rf#SY|N8F98XWoc_5jnkmcB8A4f&d)M&z>@azsIo+eVl5HMh=Cqn{ zt*Cu0QN_@T$!&?RbL<;E zf%5DnybOAhN%@9wl9jow#xPz~ogreud%%Dm>W;?a3nqsdD=ZDHJONWW!&iL;;{B85 z)m-Q%2GnVAu{OJXS%(7GRmjn$WBPqS^$rO%4`vC4Yp?i7Y(2f~2xGRmMFE4>fX0YW zapGTbl@gqRNOyg) zmxVLS!|2>u{$5UnK31wP{4qiJZBZ6_tw-lKg|;G!uF`pL_*xyhyv|^PH_!0JwsPN<3nQ+ejp}xN{o`jIov%S8PUvQUf7~E z!6^b-i^nO4Ag(`zW`(xFd4*2-rBt$eVVYt0A-ZaLMrQvTQ{w1nj8COAiDRIC3>aXE zu1D-gk&3@hpS6gh6F9@v=GzZOvuL&Fu2if(N*i(+YFu39V@T6d*pWNJs$>b&0IP&n z0or&$cFnF_S3RR|`d2-{UKb;@p=Hag`_Jst<@=*TL0vW7OwsL2HSL`gm79c zG#G+R-51HsyM&x)>QmV=)_RM`rDE{BT&y)5WKxuIf|%2E5(3pzUr~lzCLKtYhCdZn zBIO_muc4#Ae>Z)*wo`NeqTXyLr*UdY8itH^iL0$Vtj$H{)3=x*RcW&xy2gT?sE9=gh5Ag#3jRy4)1 zDY)1^UW|4@(mf?}Ma%if2alDR=Wm4hucgn@8No*Hgeru! zo^4!$Zfd|&t&u_;At`teWLC+1*2d3}2Tk3`sKa4)Vkk5{JHQUt@FM~B#>q%;)L32v z%rp?kAZhP4O5bS_MCFnGPTzuR9KF5J%bH+QWsF&X%8U?+zpWIIyscnF2KHIhLuO0@ zqbx|IhPj{~V-)3HMN)2oHY6p5zZBe-FL@#@4(d(>>RgJbBjuZl#RzWLmpqQ(sUW@q zquG}=_{?O5HcoDamy0={cGQM^Lc$^E>koDhG?Vs(I?jIjh6EPs(Y=ttP3hfoD|%Bp z*sHh;#0-l*M~)vzh@h3jLMl=b5{8yOU)EOQ?DQqq!L)|i1F71Rlar=}1Qx6G4%A1< z2jadcCYU~{nfBGO^3>3$wrZcZQqr}~@c$FlHw`bAAOVN&3dvCJ6uQn-W0aMcWt9Y9 zE6b(*4K~{ln(UB|`>dF;R2Bb0vleG(7_Zvw(m};yrxZ=+HhxH85WY^*BLQ?06*_lv zL+~M8gt&bDBa1)R?e<^;n++s_=YA4oO;##{}dW?4?q8D5gr)Su)kNw zAx!?lEldrI0`>9gKP;doe#3iAMvz0+Tg6R;uQYS#VEt?tY zk)SsVN90bFoI)oWG&CTtB66dQH}HWSVSoBnNQ8=v+Z4d)ewuh`X+9D+)lXp#(CeBX zwWqVFPV8p#e3aD6`s?lq>#0PAj#<-JYt=mpz#)sMK zH3?-tZtUlJ(qYZw+xQx0fte@ShHaHY^ub||ZHv%Z5=mc8eNB==P2pOF)06)xM9CAI z=z7^T6;Z5hnGL!|+Y1hW>)!Jdot>uCtw^fXC*X>^yoOxo88aeof&I=n3ucogxT+cV z9%M!NIEM}jDe=CUB;U&mTJ-7|NQLtX_&RZr=KdSNY3dhOgW8Sef1k9${9YOK9$*$DsZ9nWdJLT zJYI2~QsEeI73C`&QCD(nJq8uKP+zR5=su{>`T#}BCE)G-W8F293=!b#z8_cY^D$RJ zMK0{aDuP~2aWTEY@yM(fAmoQROPri?v1dFuPuyC>%G)vWG1jLJ|HQ-nr(goCFzPJc zs~Qv?Z!(~ov9CL#=r}N15MFm>5;=}%!QU^;F^HuOYMZP#D92I8p*2P61L*|})urqw zF)t?;N2iLxGBkYzE-b*HVLr6*lW1sDsEu?ks{W>^5;h&z3uSa&wm%T!K!zyb4btj* zi0#&miQg>yd`3J>1&Dvjq542NM+J-m+E|3qm^HU>BeIPI{9`&D{kbUceLfc4*N?Ru zhRSVTrtzeTDm(adwRKaTkDni}DPfMMR7gi>nH<7h~yr^kXs+ zv>JG-r7XxZ604)il%#+BO5;Bg3CGi+8c{!pFp0$Emw^Qnj;zn@k(QH4FPX0~z;zW7 z{`e?nl9KTweMx5vOl{4OgRxdCKbl5CQhY&}8vJ6- z`1zP9uD!edA#4hq@q@N%8WhQm; z*=NR2q8%{@iIixmjc93_sa#B7BB8u{6)$hbZ40~yFgp~U^#yCcNyh{td<$(kp^`yF z{1_GbRpOP)xQT^Vg0a6#ZCWyZ6D+dOA78*cK3h0R=u|=0j0M;}nn&XPnemmey|kDI zC}2ZBJS95tI15yEAISqQA1F>(A|J#yd!3CCOIpVbOWc)73vUD*b&$x9h0e>6n)zj6 zj)zydPx{5vB}0|oJe43l^&<0rtg0d82#!^HI}P>)kY%5(}PayjQHMus2Pz6t{& zt_}+`b8Gu~+xWWkoc#Hl?b`3z^Y!!h()nSM?@?p#R_6;LBs~0G0*dlNi(Q-Qp)~pN?n& z;X7%XV}H^tk`QLIn}d_WJFtn|b<5Z!-Nh`!lp*LRIZ`4{@)FQ_KA6ipLUTO9sk3BN zel0KENlkq=3O)vkXv>@hx`1*<`9FU2d7-)u!~0P5d{&m#MMKXe=>=jPdOt*VKSrL1 zQN}1O$32Y=;^{brc^+_ zc3~dt1)BI_npD{^$>L*4MAp256G6x}7N2IO3t}rH_Heh4E3p1@0XHCgH7$w}{xh&QfBLK>l2D0#HM zOWhw9NwW{*iAuWp`5CWbPVD$|uDx)|4>JWMj+Jj_X0Y-n1ZgHj@wj63ccaF2NZFk_O zN*J{i9*v{IDD3iv>&PMvTQ{uqBsO{<91PV%KKBBEC(|qZ)aK+&vF)P&L(9$&Wmp-w z-duI}Au5-7Xwi0uk!;UXQ(43p_s5a5a8#!(2NC$E1ccGIH^FQ7y4@-25pdb{mGS2w z$5^~E)f(*x{2aJbkrxKR#!~)#FgugS24p_S`7^ohZdLa^QLC9lCGVdW$>WGc2zoaS z;Hd@O7t9^$Qpwy$5UWSdeoP`F4;(?n>)zK4dI%d=vZbYb61R1?UdpGN`I&|)pj5=t z6o|5q!z@@HR8fg*hN)3u(vhqE15J!v3JdmcAUBzYf!U@)ho$y{6jec@fNtV$GwZWyHqv>aNxQMxyva!0JE$P2Ye}zlxnc z29P%Xbx0MkxErLHw>3Y8M}}Ab3;D|KaK~RT7i9pYgIAN0(haPVWB-vC&m*peGM5F` zOFEUZT%H`4IHItTlJ-Pcb3x-ITmFXDvjzSs`hYA_px=m7o#z$+TBVs^%axPeyjOAK)##NZYwtwaGCqBVa3L{mP04}Ygi zccaK-aJHilh2(gl0LX_!VQjT=+%ZULuRH%{_dfgX**uhKbT9H>Nh{(y zwQfxD8ew7<#+lYJh9;3OEuEm_Ov>CAEXPHGx&Cxz5J(+VuTvqvcL=MHBpYupPg`CZ8z1ZU6w^B!_aTB$RO z^qNSsI83APj{>%~X{l$PexEX$CdX=CkD<(g%|lh7loT=g zMrca-w-2DMsXQ6g>vKoRCgaL>oAww^DJq(M0!6q}Ej??{Kzv=*yafpos-eslju%i; z2>oa%N2t!!PaT&g2m?65nI`$sZ(nl94}!T0r3zmar*UWRG!p>6hqR9d>kH(kN(s2K zeo!LlPolB30XRU?&k{VKYMQ6pHM{l&?{n2`rE9n8-cW|mFZWBV@h!ft!`bd-ynn+& zPg+C?^R(|SVh%;Jc?bu!r58gjYQQ`tq482kTQM<8UrTfV2?YpXC3$Wl$%0eXtAV;h*5G-zw&Uy;7P@Wt(6c_V7j-AUN?k^g@AE@@ZhChC=4o~Q zX~8ufHM+<^0a)TR0KYKC^Q$;Zqy3_?KMYS20P`3ZTn+UJab= zAM6CG|Ab3?F}R)2kq2_dRbo=fgd^%~kV_eAxuRis3c=vOxF+HOU`Z>t(@1I`ASUQrciT8WPj0n5F~U$i zfH!6Mt%`4|Zc`g;E#>YE}5x^{alGSrnX&OtddB~_m6_~BqiG2@@(XN`;*%za+ z>5ca5Qm(c36QS}5$GBne2q4*5l!gak3Esxv^K!i>Gq~9O|6)xEC?fCT&f9;D2{u!T zLzn+~akvY2mO`k1V`A4Dj~b6|k>YDh-evMG2*3A7zI0~DYIux53QD~g z7a_UCx&on(kQdnEikXPf!3g!L1_>MzQ3c#zoA!b6O_SnkKt24p+gTk{bs>DcV1X5X zs<9vb`Xg9tTHXPCZMw|tGI>;+?yaDRLU+@7vYEl!W=(dvV5Cp0ZgX#SB8}NacFQSV zZy8>f{x2MMoANJK+%VA-;)m#F?!=8n*Sm8+TFZodjFmhIXZl|~-o61gR0;JFL^FG1 zE0JS44~s}DRZG%s(gXv)evy&Wg4q~v$6Tt?ARdV=c9gE_^Ct6+Qec*CS|%FFCDA5e zg9%33g3QYrhD9Im$K=j}8=8}poKs+;Wg71<_~i)|M7pX8~ z_LP~$>cPhZpe80|GMdYgk^>5~2u!$4->R5nNR*=m?Oe*R=6aMR?IKKr#cF5o4%Fy=j zd-~nJ|0ZaE>oxy_Sxx9AJc}ieCM_7LC z*y0_P6k~K6_TwoYBZ>{O&BrsJ;f+|)W#Mgu9e{q!W@Sr?h$RU&#{l0l4bHY$n5a57 zOE@PSA$}}4c0o<|Q-J&XsI8Y!-^WzQlrQ32{q6-3Ot*;0S0azu;}J^oKYwx5M>P@j zY-Y&sSZEGvmfNu69L0u1J#g%>h$U`h;wzH&dq4L9Mz%H%wh*q*7ogh9Le%d-l?~>H z$2R1XiXw;oM!$7w;Q~^4M8obGzGFE7LxkWKh0%K)CO(NJU#ZWIl8=1!1V&tw1Qa>S zA)XP9WG~tmjH4Xd?_gw&m`Uld{SXrX2;`Slj3A^TiG6g;B$t@|Npr7Es%XitrP?Tl z{Ux?}ZD}gJ*dFY4JvZqV+V#+XzFJ=WvHFm~?UYi{*&^#ovvtbbppvrgH$#BlZkE|jdc#3P<`iff72p8^1i z2~hOcBXq*^mNGOOV2MslfSye*s_CeS(K4bbg3QZ`#r#~ zz+DlXF<|M?c=vntr}nq|O)xnH&-ku0_}vX)!=l zz7dSnM+U4?=I!+SpyVViN%;=;++G5kl3eR>j+}3E?I+g710pD5A`!K7cI6a#$Xd4 z%$AqURXvCUuh@3qcE+1BTpbIHc|o$W55rc(cv0cFd9+wMH)B>zp%qW{JqfBj#fE7C z-^n2P{Ki-e6ZqswTcAA06%wY*IFj`MFy_Cb*7%5Xoa;6wZQfzjOT$n8b>zog>i2d3 z*toTrfe=WafwSzlrBzax# zs!Ldq3P?nd1vG2l??t_?-gcp)$a%nKFo|;pnsu;Zu8+J7zjV+#rtoP7@UbTU0nv>A zzM;ipS~*WdK#-=Sb0kb^)Vsiv#J~4U2+bV0vEw!E#1$Z?zU09%r8T0WRQAVICAjyv z4wML(f>j?sxnBsCJpW-?99Ntvb4hcp&$H*(QZ@6?^!RtcgcUBPJ3Lxsq<~Jpu0uVA z$dY_hVT=AB$0_9iDh#RtC35BR=r^t8r;J)L?624<{Io$%^P1SNOjQSh5MPEmecFF&4Ss9XDZNtMJgS1RNp)q=~)Xc zO7K_|8OF@nq(cIa`uxy|5@X2qhq^R~NqYbSYLEn3+%NEVD+L@r9s5yyLUPI}Fl<0W zqHGkg4uX=I(o0y1HxvbsB>s9ra-6@?jXC1MoZs@#Ct0B6NhFef8t_nu?NwEEk^RyJ zbn)B(b0N<-0S&00*gN?1tv@)fL_qzcSB$z=n?K1$^mt7yl>JQ+N`{!2%=)tX^2aor z%VWJEG1|D{5QEqHD-{czE$j|x=`hSD!Hr_Dc1h$FhWoZG(2g%dU$Bk;j{vhfTzK&- z;$dXSA<(mdFWi({k3Sx}mMSR2Q=5SEomB}zdl`|u(kZp`0+iEJ z^|dE1VfQ3Ma^8(dxC!2hg?~*I5))uXbErg`e&jJ@(j+^;wi=QsAnS+55%Vk4v|uTs z(-FE?u8zaP_m*=p7~m!-S0q52X0Foea|3a=T|WKzU~-T^Yirs6fPggHEFuM59s!TW z#gXpFQ$0FeQK{UIu*qNTKXaiDyd2&{B@7ei5l)G;H9KYSHNr{|1T#(Yp!U3V8qXCt z*J4S~hj%z}lSzdSmszM^D|Hw6xsK@tCJ;UnAzmG=N!0w9a3d(=o+rVmHO?|hvx!Prn?>$;#aN>HU&i~fd`PjmTd<(DW`V4-kFQjW z=3AL!k=P6?`7KHa-K?@>EvWxP(_8pO)xOc*GYlo+&|L!3CEcNPcb5W^LrB*!JV*%0 z&><<^CEX)Isd}m`*UAwuX|nV`<`m~>D?hD3G`-bHj@6Jy!Q@tf88_D zcV41{Hy?AS&k?WmpAS-An#+>@z;37`GijV+7T9EM!2X+?foHB?Jx#~So_cK|_E8nS z%GgxD8n3}60_?u~$1y9vuD|Ml8lrHk|D~Wk6X&PlZj9YVKfdUH!zEzzp9ku@K7z8@r=jrYuL|tney6d zIHOCKhS=v%1irEdeZu}NPf-^rfeDwKx4Vtel~be5CVBNd5GC3bwHi1^M%!-$*aD{2m$e;4lC zq^;_ z-^{(`5EW`s#nSdsqMF!(i%kzlJyoflwKtVW9B9O2DR$E1(vmn!0kCKcwm|l0v?hbm z@*Dl#7hFn>IPQBHYPgyl%8>dwxfO+EipoC!pHwJU4>i-@E@|t|g{kNFUSjvM{hZ+P zAHx;s5wgd>3g0pmsw&O}!H6jnXlY}e7WfIP{^zVm0N!Gy2A6O!idslDRC5}2ju)#M z@UdQ4tlD@P#qfVeU-;49B#-V7VC)lp*11i1S7S6T{87`(F44CUUHJs(9eT)ZPd~jX z(jWeScab;!?e+q;qRcHvGYD3dD~cq3-D-M{kLV$1*zY}RBn&(iTky)WoNAVtzhkLo z$4XbpJVwkRk#2s5qrInAY6>)FzQ#?DZh!PV@Rjv5Wv18neZ6`A-sg&SgNeEoryC+d z4@VxDEP%c@eL0-$T?yLXZjEGgpCfSqTfvBhlD0af*`?psQvA4<)`;`}g|1EojKvbS zWPDo^AB(^9dCT2oYQfb*ldQ z_h8yve!4oI9U6CE0`pxLk8Sz%Zo9W)7=oo`UlGBxHO;qf=W6}C5$(i24OIGoHPGSX z)6J-gd(ME$7c%=1cF#r9!+cMmgmJFe;)H(;)F;WGPd6{!dU;DCw|&V~McgN;wVpZP z?&K46A!Ha^+fWPp;(mC##=aV(^e;L{ta$fmrR5-Od~^7id^Jq<2g6UMFa4?cLo$+{ zV!lakz_>K{?uc{=20{MNR55}g9)P0|gat4PEcpjFK~rEsGa6E6J#YK$VRTrGRjMdk zYm3m`;yL|;oyO8p*FIS{IcS=B1I{95)x_=Ck)S-#Sj|ebRWB_6vd0;&DEI9>x%RFg zZL+=p03&IOTlkE|E}sj!({>VVd)1bbh%)!UEUYy5!5+ciWB=hBvOO+*&ujv8*H5Qa z0Uva^0-Eiq^$4t7WrGjl|1nK*Z10CuD-l}u@e4$;t8{+^kApVJ{K6n+3r|3B!{>&I zWr2zOL%SLGJyhBJ$EVb7q~gKz5rC z=_LWlEY944=+{N{`TlXJ7_cTJG@(9B0?~d~Yjb28{z6Hq6BN{!hg{>w2s*P1I~kV= z+6Quy37^2ol%}Qv043p%$fGcEp!S8D*0fH7`=@Iiu)P*eTkVh`d=&?FM_e_OK>o5Fq$#l&-%r$(G1 z*nxxty^H*U9B{Z!4OdlXakHcvAlMU+x+UD<=rbQIFn%^PJ345(D+o5{?Va+g%N@F9 z%l%#qF?sRwNw#eT>T0;BHb?g0bWRqk&uYp{xlUcN3l%* z(c+!l`Bs|Q{dWk;5*=z zN;{FLpG4@po80y+g`UdFEoWymvd#`Q8-J~IA1069MaDs(p|dOq5GoO8DZX3N!sUt7 z@|N4Tq-XVp{Y+@wvXePAS22+L?i2Gj`6K-sEOqO5eR`a5d(Mt?3WNESE~mGqI;5&v zh>HJEsnLdxfpFVN&USHxuYVbysu)BSAhWWZib7-7c9uAg4P@4Dd${qszBqG-;h+7f z8vPjM^hK_kC4eqP2FqaI-ZwSwyB4%Adt~avZ&cAc;jUh43$-rbk}xgN3(4e)L>}Ky zU^2#>-JJA@C%y~iD4_f@uEUJ=dtAm6SGXS9c>-aV6~yg~d^O_9XZ1AVIX#y8=MMgD zuhSpy+rOO-296kWs-p#JW}ei}J}D&X#QrO+PyH*Zx?e$^*eAtpxq%ALN}d`xbu|)L z;=Xmw56|_Px^)|x^Tva>pz{tS0JXfFQ*+8mj3e10`5+pLv&BK`DH_SDmNJUiNx&lQ z!yct@5mkVKQ^{NL3x^T+are9JCWqESQ%JMytjSaw<~g`|S5kdpiW5%-gl-JW=<5PE z0690MUi1urO>x1v$*{cZjc6ohlOTvf=>+B0uY8bXmC3-m#)f9UR{byFe>w55JKLWF zLx6y1R9KE#fNRYIZI&|OmUKE`SPYXF3H3G8thJPRV1+8r{_pL@+4Mm~1$^c?p>*Qi zW~vidFO(TASNaA6nX!F^nfkE?`Sr<*gvKY$1L&oOR5<05me5(3{V%Cj(d_$pZFDV~ z!A*uCsn)awFo6avpp5a;P}HtTGGm&_?0lU)lcYHV?3sG)t6ZJuL}HC3%EF3iNS|HUhTU;*y+Hwf5cG$ z?Zo8XxLZfNqKm{t(c0;8;@^4#x2RheDt0lq*{}ZpuR3)8RL{|U+1ZsbGw0Gn#e#2+yg zzeI`RSma%3NYbawI%Q0W{M)X~{_8=2KMmtyB29LDEZN~W00;TV5)XlmS9wF**3q&k z7j8S!Zdng+M+K7@@piq1G^F=G0(lHXgKP>uiREy>WXL+00RI_K`rEiq-1j+VA$x^%Vr@E@mv@6#PB z8JF3u0~TVMq(Q8-f*Ab8Get=D=LUg|6cAPRgPVs!AX`9TefE!{PF@~z5$wBZexDkxFs)PxB3Pp$z1#zauQ5cj`lQOHwL=uFc9b} zX;>G#?J6lWu{>==if zl-}wmp$=xl?LeD5KOtU>Y#Q4xzxAGq={kzq9p&3LhQL@RkGi0I1HO{~(_(;kdK z-Jr?^RwD)Ds9=u`+h^&ml59Qe3P@J|a|=MvX~|q`VcgiuuA2y7>|~quu#GC2HZ?Wt zuRhZX=z{80aSUVQ3y6zA^w=-_NFUhw_PbbeercNF&+YL?+D_I7%Qm%0XXEGti*JyS zJa4EfGQ?Kd%_xy6sJ@;fCary~+L_l{pO;Z}&eIQSd~w7sir?h03spQ3AS5CzL4};v z`Y7jt*1$kf_i*X(hxL?0uTbGuC8d4M+pNyfQIQ`HVj0J~@)b`=e&_WM!Vp7IMNNi{ zLv*H{Xy_c10L1k6%e~j0(qEA(I*viUX()|7?%2l&G$OzqpaLimHN2Xu=LsW^0Pcv# zT4yf#T3ZaY+UN5}b*``QorGgIg`3H4p`VdTfP*Sl71f?=UBv1H&bY@!sA1#dAEQ64 z>A8)pQERkYoQ<2SIZg>URVVxgMR)~pvZO0StW9U*iQ+TkC-7LkQ7_E7Vgx=ZEasfh zWEJM)|0WWRk&x#-oF+IXyP-yrJZAWUIMMsDq$3X0k)63WWzR)de?yaPAyMWNi=K%> zlXL7)-HN$%aj~t@A0v}jteF?PaM7o242hP4`0D;-`iuJ5sdz`0 zhtEp1B!o1_A_JC#Z>}7}UnOP6aaH+0(So+{y7+Ru8e*hyGAM)k0}|uAU*})TzF3!M zy$Ip`*X456tzu04U_w3II|6Ck`REVc0$^D9l+j3D9FVs5(}JAX(GgjrYOVfC;3bxl zqKP|pneApMnll;k*(F5x?+6-1)XhNW3DQ9blf=u2<~<5H-*CQG=`fVREm)BsuC=>+ zeY~)e`7aHO^Ze-+=DsL8(I{(nEFV#ko6FW5-Xx%$X&;NsK;{=i=hs<#bg zbskt0Mmj!&@sQ@9S3kH`r}FfkUor-;f}r3<)TV-FTtuAYEuXz$%${oX6@eqIkH&xXuT+EZo$p185F2MXvPsw^2$`p{l&# zj%noNUbbZ!^LFA=76+VhWd<=}n3DtYEj0x?E{`KN0VEZ%sn9;!c%WLoM|07 z(-SzH?=sel>;F96gC>QcQ$T%T`p~b{o;s@q_r0Y=i1ogUljmxiy+@{_67aziNk7Q3 zT7|ke!od1IWx23-MAh_eu|t^XqkhAOj0B#_C@IhKDL@*{4Dt+vdT+;^W{|7c<}{u~ zrAH6a7Cq@q{}}~;7I=uc|@K^<`^fJw+lyDCFk_UMNd>M>1@(C4(K86_W=* zj>);QWgzSO3ViQoms4g?6Y6i#RHyn)yzmIy$u?6sdlC0-%6&1vtOB*IQd52wBUfP? zK%URaXvcva-@pH|VgV=EayOo3R(s!|im)9;+5(RFO{>wC!(9CaOP73b_rYP46+%^Q zIw;rRH78-fd6A6St~mj5L&)N zRj3M922M|PzTc|tbLke#P2Bu+0ekHFcsmBVU(Rd;ul~|)nxDoNBAOoFk1`8}Em=9{ zcB9qjTX5KhN&Q7zo_V?QZFrmQ0SjCYC5v{I0)Q+ksoa}Yx2n)G?ai^aq_ARy?k)5O ziOuXkj6DjpL|MDeG>+iXbho*zG!AQdv5m{_BV2M0dGiLc`Q_`G#Fef^_LerxfByuYUr ztCR+uD%3xAHiLJloNxCy7W@VViEWWO_826V;cB)`z6E^F>D>;qj7>JpoUF68t&fk{ z9%*@R?#N2)JHtZ+$VZS!FA6%B+%<92>m@_Wl;ug|C6x6slT@JeasI)2UzO2llI=-5 zzGMhY44ogXwV2xVPnC?~&44^s7HR~EOQ#zCHdPX(iQMpB+O+6Dod~`nzY}&gLm?0KNZ-;M=@E&o};G+b^5P zcyIGwd|x>9ed~TUCYh$?w|$G7vATS`{F`8+oXwHo*9r!Znw_=6cS{XRBr4X)EC(Su zC-oiaZ+d{d-Kx;SKyg`kOZDq_C)G5+Ebr5`^lD1KDZVHUmbI?{3_^m(p0&pIaI9c> znM1F7$M<|oKp;Akbha5~Kj{0`E-N9gzE8DqHI@dBc|jfwQA!J6q&bDCY*IYQ{Ckqym$uuZy5Vd?4N)x_soD1Ti3_y8N3%6ycTas4ypVn zpS6SJ((W@Nx=HvQ784gaF&N}p|G94$v+lekAay=$(ohAs&6+buMq?`WRz}_+@)zs@ zMSHB>vmdhm@X%3pe9@Q;g`ELk%IwZI_kVT3P(dfagOX9+he_tl^yf4KxpmlVG3)(G zr+vbKb*5OEohgd>56O2i4VpT#I|kJNNh`@%<}t$`Mpl1U%%(dWG0pR+eCa0W#1On( z-Wr`53zVY^?#qC8XWt+0C2^})Sn?Jr3~(Fm2FJ)ubyVDcXr72Gy2WARW0KpcwQ*Hd zxC5H&%Dw;iyeL!*{B?8*D{@YiiTkW3!(#8w9fj(td752J2jwvPZVTy)|H|4LHCnBpUXZPmqI2RDBoH3ZSD{@DilgLMkk0x)pHz zc_BE%>eBi+P7lWBogbp4f&5?V061l+Vz{KlES8hoF!y7)bq{-WiOE8o+dXunjGv)Q z+`OUE*wW6aU179=3bDT{V1T2w#z|@kXb)GF1+QFtZ@C(7wdJUloG6@r^YZ#Xv-dI; zK;*~(-bVc*IWzNQwwLIe)!Sg-#t)>S=7m2^%MKf;*-Iv#x(Eh&n}}5P&v2q{b#Ert zwuY|aI)4ZJaWeBcWv?WR-n-|)9@yn<7c2D#rN^QQYM)Pcjvwf)QV`jQVo5Zb;+%P0 zUviq3LZ7eK?F1$Z+^S`+2DML!nL#Iew)SMnE$B8^8Oz;B3Cx%izzG1W+ucPaOs-!= zoQY133>yCN*pd|qL!*j*QpnrfeO8xKftZPf!wjyg1{$*a{a3hR5nCP%Xy6wWbvwYP z@d)5tgA@nM?H5MHUB}yt&=OIi$cFOhclOR5PS(jm?Fj0CSP8&Glp3w_6QLM15>~^3 zazJfci1tLfR}U(Sj3BEI5wqH9pMrm z+nnBCF^kYOje#!y=Xj}GJ2e+=hFIY=*&41!I~8uE0;U!n22>ucQ|ruhlIk8UDO&lF zu*}ISQO8o@IjA~TsD4gDYV{K>wxx7uMu;Wyd@ zRd;yD3Pr0~bSp<%X%_kHDi!(VmV`0Zal@(eNK87GVanoueDdFMy_oI=D`AF~M~&7z z*4i2cQ6!^pxCAE}s9NZ)IeA-G?OOXxbPsvk|lON+jG3dcrrZLIqk^E-jXl zc~;yvah=U%rLWgaoafUOcP`w=qv~RCZRtxoel=q7vd?0~Pp(_=Z(&v@PJD~|4ze&T z8SwP=vKO2dNJcsYV(8*Jng?;1H^7i+EMcNB6cRRMNq)lU^tekP){GUSfhxl0(&l!} zlS3@qxaTmXt*BhsY&4F=L1bqdt2It(mm$9`?E%Tnn%AquYYRRkygIiqI*6kGml4+V z;G>~X549=xkk-YDuRv26mohcvQwZTS!`kEgaggK^o`iL#H!J;+ql+h(q|#ObkDrxU z@+b;Cl-0URpn6_ta|}4$PU+cn6aB|0qP%w{7F5XpVSlV@D`ZfYCdLN7>$dv+7vwnr za{S(CR_+w$IdDhLofwe+VJpPWk7SyprjKPY=Jgr-Jn1FsUqzx>o$kmShtSzrh@olUIs%9t<>$*%SFeouiT-|iM+fin*Pw!h|K+Ok>o{xHGFeyK=!rMFJ z$!fq~njlV=vwEr~5MI~jB&&L0DyksrmLY+ZS?70j#xg(Ehxo7efH%=$RrWlsa}Oc$ z8{teU#2$fBBpv1Fr3+(fw}29>_NLf*ep!w9Yi$dAPW6vrC{}WpPFL>p52E59+|#lw z$89e4|1S1nGo@?m(nm-xBI%#gk*gj!sn6Ewp#0(d>eIToM=a-UrFJ)G=3SEy+Zk`G zY4XWEexDn9;Z$6#^k}(NWH^#CL$B52H1&pQgMRR}ysVnt3>$;dcP{dpQo7B7UKCeS zLWFYOKaJeC+EU0@k}7$*j!L~GDW8K%a2qHvuw=2S)SI4)tbQ`ydqPq7ao2WJm!-*C zQQ8|T-v&EOmOKu7%-yXbM>rf6#>5}wiua&p#zLNskp<*L$!-eA1Imj^2OjXaCJ_7(O{8K-0Bm`cyZGnu^&5_Z?mk{`mW(`?>lP?nTN$7 zQU3gbWbPvf+>wO>7ZJK9QCHuctOZ6lt=0ztR+}lci4dqC_7E*$j&$FHSaTK2F0E;l z8_VURNxglsQi|+U@y1;f%&8i{zT+Xy&BomQ$bbI;8X|WY&1iF63~k%UYf`Z_xR_)N zJ%GC`6I3c?6q#{5Ox)g^`E53BxC5#ndoonM8M_hc(<&}uW+6_YUBYm2NlnTTxo7t2 z)or>F!@W*lb8pnMKr^J1-dOo!9v-wdece!-SObGUTB{;bnw5}6HN2< z!&0)BOS1r@2sRAC_%>J#;+6Z}4C-IAFldI?|5p7NVg<-_Y7w>uj68qS&6SQTYHQ6 ziJQj*V|yTre9xI%y1*uuK6olB6xY?y{6NbRF8jtP@Ee4gNjyOWAyHTc^YLl(VQ|+q zxGUTG3Z@L&JAW#a;GNnwZie(g6z|Oqv$_S2a

{<|jDdpA(hU9bzsBL!gM8f9I(+!m4gBZp*!a~{*%<@q-b6=IbhKe}q3x4E z`be??{OP(sQ^z`!Nx@LhcWml;UZk6JYCh+pX@C!yv(zi+U*@WV^#SizhGANV!Heqw z6x!$tUVi+5)-Hg{V`S=e#(dOvrNV@quk6LA71z(pjE7BXoxs21(>@8{$y^h+>b1H? zTk$Jz^g_1%*j7zN8TE7Kf%ytLXNC=PPUisv5wV6%#c?%*(J~)`Mf_LrtbxXX*i;H; z2Lv&M6MSoeLLefbQ6dYOhX7avIR!f2P60LeBG2U27noD=%zh2uoq_-^kj;c1zslboUp_E$4gH9) z*!Z>iYXcAdF^FE!@i{*H#AgA~fo(h!!c-!8w!|d5k}eRT7cN!S7=!R=vZ91PFZz5s zsFOhC$4kiqeuzfaqq6`wi~-`auztOcjwLL=`MQ7>e2|mOD0p1Uaa^eGYf?f^+~SRX z*fDndR{VrpJmC3u{M?=DiKzF+uJmA6Fo!lyB#(m@KI)y20|TCM>y@NKa)gmK;!~iJ zO+K<;%|>#Bmw&JzHcweeLXv}NXz_VJXc)uS(ktp-GtBv|__?}EaWcx9FdmAa3;3dg zSpdA8{AEw{1wXy^BzxneA|2}pZ=#o)? zQZfahrqUdqI>BAD$~%+>7Sg{3f87==nmZvQIbO0;^aa0DX=?U1dcd}#yY*K+1{m81 z)y8QvY6R#@Lb0avBHyY+LrDE*UE~jKIEk=8vdFscgfAN);BRyCM?|%mQPv5+{j1F_ zIw;xfypiPzP9|^g(uN$RPQk(fh{(@*;jNShUiu|Z@G|jE**pk2lfICZ>5LLj(ZpMb z7c|wSkNX&K5?AfmG76lA1djD!_R&uEnF$PoIsN9x5c1qMKBYGD#`9L3;IX9ThjP0# zx&lI$k~uhU>&$Z&`S}NU;akf=Y9^RXA-FVIVj?ZG<`YIv{>+1K?~<}ZLp^VwVoA&y z`V{)qDtUPhXu->g4)%Jkuf*vmy2&v~CjA*t{GbcRL6d(Z&8J2W z_q@B)agH?v|9#NMfNlTHl+_n=?@F!76is#90y@Liq3VlG=%Sbrb{I~jhlxgcCOlB4 z`Aq0Ll)M8E)ObX2;sWo%I0S({xEWW$qBRuoh$MTU;wvs&NJogq~@xePpk6tJ97kwCy{m81& z>r%&-^yuj;zUyqd?75lrZ7(QqNGuyCHEiSpP~(*eZ$A6Y>lR&NJJ+Pb8N`DXT4NEO?Z1Mig#A9!=t-i5B+uAq31ky@eZ6dI@S!f>Dup^L5KW! z^?EFzZgrXGR_AD(8xM3L{@mC#3@IKU<|%+i0H{e>LD@}qVz35_jBCrAobZBog>26F zv^x}`6JTz}Z*VfYG_H{tSPI6K!of{UPk2L4y-m8Lzc%`g55cu2LDfGUs(hC|%Msf~ zX}w+cw0&DazjZ=mUOnDYTRJoO0aZ3_k{H&*5+v@@$lODbg}2C3zeS`i+_3RG5N!eBu1xG z!N~4`Ms(tp{JcL)RtTfy1t1%6TXnS?LezcIS?TnQK5oATeO+tD)g%V3#+!^uh}#w> z|D|4ZrGKI_sSwu3V{7;&9&|9d>LFmpZv@R4k|ZNDVs?}y^IVJA&pZO4Q-eQs{74UV zAd~xeED!#UF}|n*kf6<9@<1Q^jCo65Fogz|uxl(QTy&YPbq@v}zxxXlum9kX^AX+P z^OBHg8<0WwI^^wa+tuSC!%*u}-wFI#*Rs_Ftwf$r(d&?}1N9-giLbJE{>Tk9UDsaR zjUl`SoIekYX+3{)x?>SR!|{v{b#u`h_64+z85uPkWR~y=jJzrkYY9rm_eo8~p$-{1 zO9_{8lm9GW<~jdGKPL^Q+AU|g+;rfJo^bYNwM(_#)7x6<;BPT$v*6|{;X+$HvPIS8ST8)$?4R*&4GE3e*J-kpGjX-f-aw{#;s*!bNdhZ zBtH5Vgy;vJ+EFLL32k&cS*L`JPhMjh1VKP+dPN1^);}@w-8i%|87dcOLBwSA;bow1 zJ@6sC040w)@ry5oMBDu+QR$sn+Mm@9-O?X0ls=3HPwFI+;)5R1W^=h7i->WO zb;guf!8E`LCjFCLQ9(}5Dam>82}XMGb99;y9?C>5(nMs(Kh{dFmyCDls4q%M8ak$4 zYKDv$)=PFZ96hoodRhDEQ~@~ss$>#bnqh**#vP~p7>RTuPyFX+8rOmALQU+NBq3Z^7c4eDMTqMY70aWv~nWoCvZul!%~AfN}L1vuLvs!vlZ^b;&}>0NPYpTOm?>-Cs-U zpfs{bqAtg8?ed(yQl!2T&Lv-?gcczFrSP?B1ZS z_}#GdGhfB61%04NJL38%ajxez+Gp1T<1sL2ckT|>Tz@r2pzDD^yL4eYu;hp4GYEi7 zXsq}I5C?n3k9c$NwycWpKK`mFg!?fjOE|`@rGwGZV_F!?gef0oQ|VkkL=Jpx1N;c0 z_=8P{eu8v*!d&OF*DF{lf}7urIs25p%HKH9Ea|JD9fR>Clr6CR%=Hr87V-%VHpNTa z9xc9r1bdK=4BG^54?W$r_-QR|ZcS&M>I9OW<;O`~F!pAR6g{>jI_3WmgkRZKk%_Os z&)b7pvRT8L{=|vRFBH3dd@CORa!s2i$%U*@y^_wp_8028hucVap-fdQ&-apHxN?`c;z^_z6QB9eET-*Fp`zfAI8Qv zUvQ~QX7NXKiJ`C6iD$uq26^(O_)rgo#*CuU!P1GM>J7L0rP_=RibJ7wJ{VeBg*EWy zw^Q<))}g4zSsTz}DoD^GAN~Lz8{o5khy|G2e5?#7$@wkd8^ITBbcc-fQ~`eg@_&@r z4j$`6Ycu*x3!XuKSxJZ-1Nfr_01ci^l**;+6C40M)MSpqL&GKfyzWwe5q58mU3O59 zi5&B_&akL@(5`s22b?btj1$1~HJ^*t^cO!!zR;Hl2)w)if>9qhO+(AE!l%?0{T)yGBJ;e`PV+z8LPG`0EaMqVLOfMa!F5*aqG$( z7JXGVa@^j_zZ0Nf9fVa+c;g#3N&H~G^jDz2W4F+e6yR3f>BaB(q%Dm^?B1cPw&gI1 z%M3atiXJvvHeCZ%w!G+`Y#{N|zt)!tN^aJ&Io@PfjAK7*K>G1Glt}*A+~McM23g|Y zO8n(E{LmoRac;g&3a-U-1n~!RCH%&dKI9u*m%R8A#t}(q>#X|P4(OB^g>3j%TwjCo ze0(l2<&sRNjkNJKe8ELb)rUH^;14G|){_#ojn6ozoIu*I>Z#t4&kJ7WONp%{Z`@*6 zI~2mzRVU{7DyN^&qXW9bELz}EV*p-&p9KjH3124BjX1_3rC;)bq>)V}JT&(R41g~+ zC4aHTDd9ms{@VvqvqQj@yc7ePjEd6J%=RL4PR=ULY3hz$JY%u_O>+==>amNOUfS&+ zJ!jhkBLO_y^LIzu6MXsvVvP~OXx@m{up($huw!E~SVkY{;N`!rjay464;h^6$o@LA zPfGsa0RM$}Eaq$yhuCUOWFyB}E0CK&`o#V)DssFjxvwux)BBL%zN9DaU*pS0#A8-C zIWfT38=d=HqMJ8c_Z?E2&hrQjCwk}xpdbEc!)G0^;Q*$Sj%9+_{GBLxldOKBk8yPM zh7P&-Hs0`0DJlPYoE(vmpcA++ckO6%EgmFD`om||;CCYiDJ|2!z>fg@VmRf79E&nO zCtCdE+NJo$EH*RlYYtw}_JBT1^NKWhk)qfa(88kPTOYH&9Tz1JtxkVu!c%2}$903w zSHu2macmWu}DiI%v4X4!&tP ziDiw#pE&|@EO0|H>e-DoAvc(8$Dx!-Kd|Kcl*b%pvW)huS;+~x@qZQIYkw>u5f|$T zn{j#?^x}00K+Ee8sDGp%gdg+L$5GixBH0+YJcQrCd1!lJB!Ca?`MF=TBhJ)~10nkB zysQQ`ItQ5p10g)Z~K(HKcy;yHZ30~+#3BW)8Pf+co6Fxo7 zgxpnZW7jSDP82-WI(5o2Tt-M#T4e3yWyY1G6~K|MARHp?X%#@Vdz1hna`@J*hX z0FcZe0{P50b)PVLQ^y<<4Ffp5_~Hii{Of`F<+h^N5*Q>8nXqI+K=MFh0j_^f*a-#v zlo-c~_Qsr#iy=vwb+O#qV>`qv5F(EdV51XC>HzB$TY8XvF{X8_@z|8(A;%8Sj$-0ujJP?;w*sC%-#T7?U<|nt;J3O>iL?*1(*cPJU-I z;`3`x0?~nu#G9>kGAG)-o%Hnq+W57Uo_1InfS=_kh&CMe8Ffhpdp!EqB+&SGQernc zgh^p%&MSP-1^M&={f5DK@0Y|}ey?_d(c5Y&e1=>~5&+g6OHT70om!L8!3hk>AY(nG z?%9j4NCv9Dl^=3w!)wM#{ARkw7-#K~D6;v33pk;HOPy+l;mtV74*2-mNhHZmJ&A%B zzOFu1y~$x5{=DFoCzMgqc*u^E#G3GdgYCNzb9(c-m|W%&FY!WAW7g}!x?nH5YF>gN zb}ivsmhBBR*^AEbaz8Rq&HOFXer3$_4NvG2;23m~>>kIhbL@qdwT17X2be3szET1o zUHCpzO!E`k)*H3~By-fcm8>-gEkYU?&uz+n{^$eGF^l#-0N3k#GPw~f@m}Kvt$Y|Z zX#F+4EB~d~(qE&MKQS7ARzQY*QuU>;wkyr3pDho>5*l#cJ>ct_3*5oj7q>$mF+@S5 zIfL6TkCpfZ^CX?^L~S-kP6@3OCrNxsz;c{4qPK5@OSeD( zhgW{{H)&XQPQXwHI%L?t=xQH83!q02;25Zvrs~J>xxvlt{0X)#Ts_R0WGFXk(Kce_ zA>R-)nF%DG;d6EEvvrK~lW_X=kEokJ^i>b@5x$X1Cw_p&{;#z3+vkv?ugVx8K}$(V z;h)!YGH73-F9N_~J@7{ni4*fln@9NZP-*b<*JGH6NDL$C#tqEpK46~pv4kl3M*<2B zy!HWh@T#Cb__Thl*%db6AbY|Md2&fG6rYYaV~)91rt8osW;eRZU;K<1C2z>woW!f+;0)Dn7Jde?Nx0M-K1iVo2Bw)JgJ0MG+qzgP;2Im%e#(6%2uw##?> zFX`S6_J+N_YmArpR(~s?hh7TI%?|5SOZb3eTkBY@bEu-tq;@XUb%LRlv^|KOK<~%i zRwWPGhLD#VVp8Ti`ttd^$xl&p;#Kin&m=5tjDN1Po_JvoK!F}kH1G#&7@!YoT1sf5 z!X^zr{sVa?2p`iVy%QFA=Lr3Ym$F3O{NI>m*Va4hj~DD^IiK1$!-knQfn&|LSg4;K zY~{2Np+1p=0(MeA`u!-IZ4TQl+=9lpWM3N3w)Y$?10Y z)Jj?DpQ&?H&b$Zi*T=wIzkYr5{O3P^^MV(=VDplfyd)Ob?ajj<{_xF{p7f;66QB6R z&BGq{FkR$a%y-{?_vU%ed!BG#_Oh349{I>eZl3a#r)-|^gePpST)AJ>JoA%yk^ymT zYl9)E@T@gLHyb${@M(a*!~vB@aGgOLK=5ab5ykp>c&o;ksR=9upCFxpz?lJO>QY6x zQA79Rh-3ufxKlLoa*~6MJOhq^xn`quY)WL&8rvdMZoGR`dUZJZyjnPy09!YJ4sGH! zb6dh#?(2hgo~DHFLSou!4QG1$aZ-LB+Nv2($p;1&V9hYM_9L6J>jiD9_Imbh_(?*% zk!0aB&l^nG#FcfZs{ckd0lk?H0eh5vNCb zWK0UhPR8cjiZi9vieUk`^a(dAd56+i6Oxh_VjcDYN~qefk{s&oE1SLT4NZ0mErcT< zybv$>|37>85^G(y-G%*B)vdbNIN;dEHrR-31Hn-&OoFfi4TO+wMF~-`5C}m71wkjY z5hf9x(1;W%5-$mm5Y5=Zv_K#_B$f~~?9jn!I6+`+VvL0pzrpv`EC1hrtg-hxyY~6& zyVovLU-^u4_Fi+1Io@-wF~^>3KO6_9VM9yniVsipzn(9MX7kyW<>WIwK(nAFZ$N3! z$3?dH;7RA&O+?2AJq8fm&ReIVX8g}MG`)_(GyJnNMV?>pU=wRwO{+S4}bKJ{?Uiu`8$7SasT$;{@aIt@DKjM!(aT1e=!BhyANOS6<_i2 ze|`V=xBrj-@ju>z@zo9S$HQ`YXdf(+*c4E^pl%U>W)dQ*0kj_H1aNLI-M!<={b16W z>`1P}dX|^d+Hg-EIq$@1>6z`PympWL5pHd1a!;~fAoGLvN%n(3+qOK9j+{8)!)VFe zm@kiGW1QoMCE?}ag8{AGcbJT=h1}wJr+dZpXi@vQfA_hEpZLk2?2D~m@hg5sZaw9G zTcWGDJQo5lvR&bmy898lC>|5Gk*}zq_jb+uzE%wXEQE0bMrp^(!5HU)&K7hmF%&9-F5xSjGg%J^NAuxb}X~ANsaPTw0`L zsKvKvgA+HmaVf#Kai#MN{VBM-%9}CsTfdPLfh=?lCGb)vNe({Vi}4 z7kOx$Q_qWu#!?=~L*9$#G|KAEvEz6)N?-K9h@bx+XxMXx}Q6m< z-Pe8H!`FZP*FXI7U;fKi?4#p(aXPmj5&aTBk=<6`ZVWc^A67BnPFnBlm4wO zwez5z9jCKI?b%&h|89Fr5hZrMe((o>4$Inrf+)qrd+pn z;f>wBqVFt^{as{Z)H!}zSAmo-~3SMK4k1Yy|OtZEts|DidQ80ilE~cNhc}y`eGY2L7%00gyR_uMb z^I>eL1}ZO2c02_ii1R8qF|2)1XPIly?nIU)1oDC1Q)9kyn`^TaL&hj3dkXBey~j5a z`}cF9>F;=nY5vG|T$g%`PQU+KKZ9u8&<8)Z0Hr`$zfIopRVH4@yq1Y@-Yullu;4@Q z8p;2CAZW2)z~S1|$~NddS? z!|mSR|NDRcF)3%Ne%Y6O*~9n$lYjE?zkkp7Jp9B@{KUgof7Mq#{L6p&FCYHy-~GD} z-}#;2`S8uZ?YBLA$(MY|!>|06zw+UqgzkI4_y2tO)^Gi`hj0AG|KtPl-9)t=b}d%- z;+~IEfJ8k<4T)Gn^=lGMn(0@>xWFawOM*Fq*Tv>oaqh)eifO{RWh6IBZqW)gILT5{ z-NmB`opr$%mm^!j$Y-wtadER)l%O<|5%I8z$>#;*bMaAfwSenWNP@MmKZ#@oIG{U) zY{+Bv>(YK1Sh;lZRqXB+i(SAXbahnzK_6{Z)g8Z=QF_okMgQ2Q*B*ZI$A9ACyZ^WE zeE1*!`|r3&|Ayc68z26s|M`D;_?B<|FYdnmqB3IEhM@~%7T(T{BRFV|=0)x{*3YFe zUfzRc7qBaE4y60tYU6Dd0CDo&aSHpLx9}ay(33N9o^fW6qLA$B3XQRU?bz)@J4N2u zzVooVPU+hh8W($0QkYltfYC+&@Nc1^Z)4-gZu)lt-MGB|DZf&39d}Zf507gU)b{Nt z=K7=$oQt_L{o>imY$Ela9hsGj2KFr$1!>v>|T1&qPkLN*>p<3)FWo#XIM z{QT{Uo^*Fy$`gFQmZtLNI_-NJL!-a3MjzQeMGoMNwE}Oh=_$ar;OkB!o*;}dTRnDe zxmI=;@ZIDq_Uc3PG7#0Z0j(S&=C{0P?p^=zfDfR2d77Vxs_ysPm=Ur!2dTpeqZxze$B&IeEF9@ zxc&Qs|KeZdy@6lS_XR5cz?XjMmp=U3U;Aqx{?R}BM-Tt{U;pT(05n-$GjG5B_QMbV z@DD%y=#Tzrii~&W;>z&{e&7clzC3cD;TnNmWV&;at9z2*6njf0Ir-Um7r#W}=m9JW znxB&#b6mW>Eodqm;sodbT z-^8~v*r7|FvpHda6KM!>=~haH{YMv-{d7T6-DRGAzu-PYH+9G zGD0gi${a_>&?z$O^HG4jz==`h>*P&QD#?FJ5+)zh$tVxF$%r(5FE!xB@*y*3KXpF<@tsCZ! z^R5TMi3^Z>nhUBU=Uxo7i+|?Z*vSGcy0%Eehs}EgFOYM#@o8@N8`pV}@m_G~M|1jP z6FT$81D!WO05o*oLiy9_h=&bqJQrYR9yagwzr6Yje4Y7$E!mGC7@ApT7PId411 z-93{R&LDv;979ui*6B$k8Lkk>=W}~$lHMfDNxGdOVP*mRr`QypCc;`aGT=6e`~EIi z^cI}8tM*3sB=Sy`+F=pnD?9ot58>IbeR%YWI#SQDNt-;fmzKVq-i7V!qLrO7F?yLK zdM=^}CTACaNY|zH3;JVjA|w;@!Ll?I(Zo#~(iT+0Vi}{B*8Q*AV#WpZ>{* zpZ%GidPoJ>^YfG9?~y&HPWr`piC_hEAb5@Nb<$DJ4( zdt#^$4c#;D`6B2DBa2<|p+0<=xic~|H_g0v-wyNqG6>3&YXqhU8Xe@&%U?88bh&m? z{Y^bjt5H0YX+mM;#y2jRt0lFoJ=SyP~WMhLbII`)O7lLMn z>of@er9E^Uis8hSyv`@*hm0HodCp{TozHbU{l0R@_@kkB=9g>QSN%+Uu>$7<%3rg{dV z4Vi=rB$Yi*Do(NqYILS2w|5nH#t*68AhPk>k&xUZyX`+0f0dhl^j_uDRXcJ{mL%An zp%7{}fw!HL6QB*tBanO-@YdeoZt2jlu{N~efVuKIds!gc0&&aTof&;6o5=hyyOzc- zD!HG^&x`%4ul%ZqFYAu^`+c7+T&~8vIQ#1C!hac-55TJ{JjO3&nwD%7hlhQ)e)*nKg)oawE9?g z36H0>U!2KyF2=y|GT-PO^yzuxh8*9-Tj4Odygml+_^HH{yy`n-r>k*yJoCIAqc_%c zu07^R??gmSZ!en%A<$39_->9UHpfhTGltHucyq?wGfveNI=OCl3<)Ko1!DO^cNBl; z!j0|cIX_zOKR-n)_LQCFo+Ugb-#nA+&Tx;mFQo2_9zHRn-!~_aH#pCa<+kJb=@S)! zkGueM0V)3e_TT>74}bp8|M`dC^Lu{J!yo!Xf9T<>fAz0!Am7XfL;l0OFYw3zzw88N z2LiZQC8D4G*`MvFgm-7KoyU_~%WhAdZ&A4|{Hr7PU;V3pbtZjoCjt_kSFV!zBsmMr z+$u9hE_}(U*L)C?X>(HAlW=EDjLkhjk9}Vq<3YOQQmMpm;oV~Mb8HHa1S}boU3$ku zmU$p~byqM7wpf+(*sC9$?Hcas;}@Bz`g$V;=5Um&dbAeMN`{i+A$q$m$I476y4z%{ zVC^D0>)(av3vFC&9SLrYZA{KG*)5Le-MKBErvMo0+J5-+f8>w+w-5i% zKmBJ9|K{KPSc(3t|LVVd_}08Y`_g;}1Z+&!*B8a645z21^(DUe%@gq1wDWauJr^o- z091Ub>?qFoMNHd|pez@@{tiUd#LP z-ta}lfhkmCbI(E;W6WRkLZRcWsHM3bq|neo1KJi)X|orYH@y~g9-wP|UEIARUcN4; zYgV606+jqL_t)*QC^x|z3ZI9?iwMFTyo&(hg<#% zIiAdw_2-O#s!gwfeX6iqzI_q2=f9XoKF>Axi>dWl*T*3OA6WsIIn@hD@%Oj>*57*g zD}Uv$Jbe4NfBVB9{DXh+;WMB4Onr9&e@Q;w`*p|p_vfo$e#3A04ZWS~y@LND?+yIS zXTI*?tG{}R#d`s3643FQi!3)`%;snKKm?lP6Pqox5F}*D%99W;Ngzq~tz&0)XlIdz zk{}gh=Lkz&z+ypO7qXmJc8I2i1PS?iUrJe58Y{FZ$vydHApYn{R*kjsMX%JpAwv{a`-@{F}bvKYsZ2 zU;pc4x7F(!lb#&s+V={~rP(80K)j6L-c}TksK4&iroAsnP||En#R2T?yq+9S(=~I$ zejR$?V64xJI9+il8{ zxY!i~)-HHr#qm<;p6o^^)^w0a9yy-aJL5aP1{?GgxW3m-NWf?8hE_C5*POe(_QTYhZl% z)16T4_6A&C&5Phs}2awo~}oBPw-M21fBIPxp1 z`YN`*u=CjUao&O~IzoV^$(=uA#>EG|klmd$g=0?EZnV3wp!+ab+32>=eJ{S**&=s} z#1W+Jy68?<^fVTsc|VFipzG+rr@v$5R?V!*k4Vn;bPNIKv?n?bp}Cp0YL@>&#BcN{aW z{iJUg-}aS>Ig%;v{#u;31y6cFfBQCO2T!`hN@SO`;}?4RGVSUc`^*cw%Kia*ydMT~ zO7rGHD^@#SZh7|wAQ~{&=ykpic5GUij<>)z<04k)_R2+nVGH}l`&Q2Fd5hNsV6Q*@ z^@p(h)AbCmegr;}0&v6P!yRt>`ml!Exo*w+#IBvXZ~Vq@eE5C8@AvgP$K1C4V}IQ}?Seap9eONzu_wj!U8KhFqAdXl9Jcox8`K)B?;T=dgt zcLQ!=(~n)8<<&0{FGvy+@TXNof$r8FiNq_^(#zxru%*fNay|(Qom_LJ90K&qPM25r zO@MjRviA*n#gDhe&LLxUP2!rxi!Jys3kRam^9%py3t|#+hwiKFm38FJV+ZV-SSL!4 zwN*|~o7m62v-q7c_uG71p!-G84?biC`jRjC4`y*aGl%i1MPqmKZe{b?qIzCDmPX%< zYi{?ZP%ceYU&V?dWaEWi+pgfXjrZ}37JYOrO&j46*Xl{v*g3Mhm}aDmdq?bu4Lms{ z?R(MCjAXdsL9>O`w8u`moC{t1FPwasxuK7byO3|uRo}yF9GGMG+L7+Hb7T(xRo=|A zkQL7JWo45CmVeIXIVvw!l39Na8^oYC95ibW?Cg+D9QOLL8(v*`y2L1I^pEcL!c2_F zX>h$boVjw|QAXWZk(zwux(4%=E>l2m%vaxjJyZ$vv^!$tYAeuozSZ}`HuJk*eG^@e z@>b>%I$-P;n8Gizbk|N}%%BsTc~0my#bo_PH>{8OmuJO3C666TL+&lzqx1VJYRmE} z{uLiYf^O&4;g%NcBZGWbEJ4a4pds6@QIb4m0bsy zFvoO%0O0B~hXS`G?B+M0eS&{tF=DvVm<8_^DPHo}qHjDJ+{A7AjE-~uu$5-E18su( z+A(sxh(p(yrwbqXpmL(6yMVzHafEklNN~wD{#fV|A+i-r3O@K2extrLo3{=nJ={JG z`SqDx`VTR;rSwD|fp3+#8=6vX75tuMXt zUh3!LCp7{eNddSQsqggry}$SOzEte|(udo`9?$U6M8HL#|4ACj9A3HJ0vfQ1<(8re zDE&>$((ohtBUuO6_uV9c@2g{EO~U7-5@hw{sdMI#MSpKWSO7x5wlH_;&$iDi@hLi! z@4NVP@h0!2Z*38Ub$#V22)_^@-YfsJJr=~*lidBWzl&809X@(*(=2M&ByLb{wU1qo zEqausPhB0?2)IrDNS;~%PV8M|wm{nPJolg5#(&2I{wetuF0|k@1U>IKq@_?6n-+Q* z5DWbBc)NiyB%fb=pF-d^QWbeTk#>ez{9(j=@=|u3LbPKe^6cw;iT>UKq&Il>7zce| zc*YyJN$2*Le^+#S;;vXp;@5pn-pUZf;IoMyF!Z^kj?JgPp%UNr%3P024-*Pr#%n7$r|dfgs=b(iii z&it4nZS1a$@Z>ecRd#5N=fP5ad~6&r1af+z(PvKjS-_<$(eVUlKtG#13g+ASdOp)> zPpq%l7hQJ|S$+3t?%}RdhtKtJE&|E>LV=GS_w=4|8`FDwdi}c|>)1VtXWXk4flRND z79^FOw0orS++GXd`Z#ztA#MNj@#hzT+r)L2CgC*+9>^J=W0X!EE90_wNt_EI*YEve z{iLzXAMnc!l8Qt|A~cb^c$BD5CmTwSdKOO$>KW)^!`@;hZ)KyKq^W=y8!o(vPN16| z<{EhmxA9o~2aaL6a!qe#=IMj}jo*7qO46m$!gvbt2UJ`TbRCZiE)7YU3~)~5&ewbL z?QYzL!(xnPZNUT3-_jmEb2vY*k~1#tUBu6_$#nkNw`ZaCqF{==iK4j675kn|)T}ioU1&5$Hn}rj_H7bN+HqiK z<;>b}jP-)Sl^H?3{@rPS`m+u3|R8``$yVjkv zk+-(6N5Qx8!S6*@V|EfYF3xo%Haqs@Db&JJzxfW=-M=uw>+gBmeA#?KymLH`A?tC+ zb9B!2tFQEP=p5t2TgOhjoMcX=zPrdmYCh~OfAsRk2Xe+C(}A9i^$Gn8)~x(Y%Z)=c zc1}>>I+=Kk4KK2z*L7?)ANU1?Xr+-Oj(h!=;H937)x_bY$e)Qm))ANt_z{}u;y$j; z%aOXpomI~SHMxez@fm*p5jaOtau(Kp8Z7N2H+(>eTS= zc4jOigB*ai`g43tKU_nEZnd28n6vYIym-2qdP5jB#P+0%RHoQL6$0l9sqRX) zk5~Mf@nQ9v;^=|@ic8EgU(Cxl66^WE%kf^}5Rt#*%dYj=+c^}5k*`z)KJo(am5RnE)L4n=x}Z$4BB8(S zQ+TKB)TDJ}t!>{XMF|ql;_9cJJh}vg56_wYB)SQBll4QVam z`C)NE4dyqLL!Ya5~=do5A?A3`-$@* zX$;QBp)*Egd$5yC?O9Y=5;+R`+BWgQH#B3L^Ie1wRqfyS!!3U1V#W4}KC(S_e3pLk z2)9kw%7t4ncm2W$5BMZbj-ZF?7#v&2@39}%S!dgg!CY4rk|$UH#)=!>%N2L1Cbmz|6eq%Nq zU+fms{|v8w1fC1PSAPsY)B_1}lE-9^O~#V``5K3x6gf%sHnDzC(In3%@O0kNSKg7Z z@NPna+V&ZL+jb7RK(Z~2E3?PxzTl42By_F$`MR@B7XJlFzjhz?X`gAA4$tlo=--_t z$#CVdOB=2-a?a*FH~9*(zFFGF_l@)FdD)|4N%AFMBA(l2;{=t8!K(fcfiI%1t+97u zY4^N-pZd{@A2<$6dO6<1ubq6sZA>iE{BxUJEG>BO_<8wG`uDc$#(WB!QN<4Pn#|#! z*evbpBvT^YxFBCqeG)J~^sfIK{4 z=ZE&hZ{`mp(ZB(8n#XBzANF*pc#`bgU%$ts+Gtvd`;OgN2wKJLQ*f61BuzT*(cR+2 z%i|2UH0M5TJHi{^?Gv}nFCWIgJkQ6EcLZKA1wY<~KU??m5pW?lCm+dG67}Z;2~z38 z;++rA^hu!mJ{f(JMECaWBv_RA(Qd+(%kt+H%&TJ-c_yF)`b?8O9bS zId&{FEyc~^nJAUX0=7R9c$%_}?S9~BrJF^ z7oYwuNM;W5cgK3h)Qf}VcQi%-e*2)-Z~U&AJ@TE;E$q`krysuZ^28oA#YOhgj7@W{ z-QqU7-1eV7@0WeAyJBRW`L42Ou3qd(hdw&t)DY%0{dO09pkn8=V)tCs@z*>LNp-Cb zF>EYUXX%qy(D?)ALC^)hn``be*x>~}qyhNPF7%3(!A{JTjpmCN5&GGSmfVdcdv4(# z4m}_40s57ve~Y7gw70m<-BhT>3 zj=)@1pKKq0$$KZ2T+?b2a?)il?k2`b`V!LOC1gC3GQ2d<^WfzKypp)&l{9=Tw!;rU z56i^?M;?(_MZ^qY+Eb-{=pxcol?3)5Nd$hy+aVmP|X-}eb# z{UUGV!es%g=VQ}6kAM1@${sSuuHn7%Pv7`EixPVj1{Ts=+aEb{bFx0)pg*ruYv?X4 zFJctGjp0*tJC^5uV`dQ)3;h!>?PGBavH4<*Oe*%wdl(fxih=o>j-3OYc<6&C(?k0V zJwN)+c(jdskj4kw%9-|1zvj2b`}@Z;9{P4XQSbwfZ4uc%*NO8T6a9*xna4Q^T)b!7 z^{jpS#2#{hc{Z)>&G80--XGX5M>6#7+%CcK)L6#`wy~ehz+w3gRPpDc6`st-FB;$W zHD1GAe_i2<|I!%mgBH>9J@)<39a)WE<^dhBQ>e{tTXKNIH20j28OP?Hv|At^a>{gi zGR?ebV9Ut4cFx?GxyT1rxSq}Xb3B}rV;*>%0iF1scc9PxFKXi@yD`gka0dDwT}O}A zUP#&9Jal8%tq&K5qp^11`m=QS#Y5bl;gcPKkK}7$KG`9A^}KUAZ&J0R)ufzj+hXDs zyhJhyc@no*&XR=pj>`ekz?<1E{G9g;9*Mz%WtRp>fK3^B^3DD7QNQIsLg*!XZu^wH zw35pfoNbqOc7EuS6Q`IvYzR_fqKnP_`MBUVM@=#fU-~Bj#uz&2CNKbh(UtSICDHs< zXXqWtWHTU7lN^RCT0R{g`R>6#^Z<=V7uyqldc!^rdY0bqYFl(KR#LjCRVHY<&Q7oV_x4|bcnMX6OCQew6@5wc!{BL0HV)_ z7}d6c>n3&j$Y_yt#JUW5!h5hU>LSk=BEO7zPP7dJo+*xI%=sf8bO7fo+YuP+`i3@b z*U8L*8IrliydYw~;`WWuPciMfz#G=`9%?$zjCKFg7ZWZvvcK~%`25ej%27Dk&aVDO zcFx(`t22cCr4ceQ1<>xd9KrP$Hx51Rk90OPHtC=CHEwu>K);8d&2tWKR}s7w|7t^! z;s`HBjcJbj?pNTXy|F;=dKN=s&=87`9y_5R%_F8GZ|6234RlO%G{=fcAO2hD zZrwpQeesEK)Mp2+bDvI{F)&exq7JjDb5qJBcf?e-@r$rp$GKMDG7 zzqopdGn9eJor`-ueljEQTmXJD$Mum{lGiMTvrFOP-lQlI=##)V;Z7o-gg;4i5{>0l zqLr9h_(V$+V{lUhN@kM`%a?w#=vsZfr5c=DR4rh#`0VXvi!WOwVRE`?J^elO0L>@o1ufI7u3yApW^J^t(PEw6ML6zR|Vt@E8 z$aq3t8`q{69lL0uKa6rOx77kzL7L@ zM4O&1+_;8b?4qTG(8g3O#Xvv#B<=W@HvP_b@ux)_DZJss=az7<(a7mFmj3nC@S!c} zPs3^Z58j|tTukBjsSNy*qt&-Be)Q!u@_08g+{Uf^AQbj};n}$qg1{ElGuPNYKJ6?g zf5v0%L{Bz9(4PINz&zo(2jgctPyO{Zc8ME3>l^-a`&OQ~nH#q>UMv!?-@M%qT%2X! z^4!Y4?e9D=_8EhPTN>9|>F(IHJdXIx=d(TV?A3WISKl*yvLf(Y0DiK@^R71%c=At^ zB!VW)BQx#-Yth*vU|v;P#C@4>ZP0}I_twIRj%D7QPn33gv@o=ggs|zWPcVySYBd z!WQF)jx2QiV~fR(Ez@@h%wfm<*3aq)-_A#)u`zK3;xMJjF@8Zz0l|>y%=-dgcY8Ry zUCU$4$?oDyzyWY{Z49*i@dvPPWXy*s=6!GCgl2r_>)1QC;hhqyA};n$aVS<-xXK@1 z#BAj%nW#O349$EOUXJ>VtvKlC2RlH=JZ17!_fEa&8vd> z@J4WK@gk*1c_l)|zVSc9TU{e(bxs};2eyTz^MIUv!P*$<2u$2Z&R`xtpXZDBKRf3q zTNc;^=XeWS(8-UtaE~62n3cIa_h|Kv{Ode|W7+Eo&f2tdQQuP#^B?W*847lsi^k<$ zxqI&TlznGgD)1V%Gy8M<6^ej-@C={u2=v00$paF|Bm+rKdy>CoXi?vb-*F2kJh->d z`882jY|gVlw6d_MWnnnk<+)2SwhEVX>e@`+lgjmlQ;IU zpX6DrYIiz{3z9A9;NN-sbC);&<6pbzVImpmEx71G`3X4MO|0otm{>!cU+f&RK4TZJ zTiE2ga*5u!p&hke&5v$4g^(>!_Ra!c$}GsUaInJ%OvDzfj#b}Xs_A<4jE_u<#O}nf z82|Dv13Wv}rO()pt#c&D4n%`}FjZFY(5nm2z5v;RpZ-~3am-r^EcR$e?u?)F#wzk| z0qPRR1b5HHdFK}-c^=^Xd|k?W@4h|b7s9-DsQuGBd^=8JIC5sp$rAtC9(h=SnMi); zcChBr_%C)0h>H3_6)xJ)xP~US=sd)ksUBeUFAl#pI(-Dtr`Qw=D1cqNBsr-a?O8nE z^2z1stVLxQy)a~Y%*K3F0=KR?fW6kaAj9hbwELP22I^I@Md*DZ}h*nO{ zw*c119=_=t{o{kadw_;MDn0PiGB#W}#BiZ;2p`n)ZQq9-&o=SGLKj9SgUjGsd@Twe0s$de3B4rY+goDI+b>&2H;d~)! zu8XMt*)7n2T_ma%edJhRW(Vi6H^^P|>9)8?x-DqZ-XbN-d<1y^R*H(W#KjH(zZI$V z03RV)oj(;?*ahe=syXf#F!Q1K_~Qt~MbmBwf9zsf5ZTD~+RB%}EI?zgb29KY=0}Xy zH{mq~^*uy%Gy8qJX;E4o2eax-NQ;5M9r2i0PZ9bDq!k8^d`aFtJ=# z@~fk^%^c9THg*?^FQMCAz{Y{8d0cj(dwMMR1O#Rt4bC}#7c_UCz4y*Lxdob=`3cI^ z<|TH_Bl`Qv**D%gXr_p14E1&F*g11m;p!4_?hhDmE%uYzc8+Je^a11Q?FC@yA~%hF z%fXc{xX_NCk&E}xRGky!%vp4iX8s>)!aF{bSNo2RJzqi+!yd*+&YWs9v~YV3x463) zHolX&`m|~Gr>!{lTi|S}+B`Y-I*0~*z=4na@(JT>u{SZPx6woSQQ|8kX)5zXk z#%<&4brV{#0&qvOKC)$AfJ{G2t0xSVyXcoWuHev~non}B{Fv03tQ}2D;gVC>jjjTZ zxIHQGAZva&3?Q37V)6w8z1Uwu{}-&|nei7T0&>?ge9|M33w4SZg@IEV@JD2ID!B?9Yde@L0J@n z_g*l4d|4UwAxQm;DBf6$_qe;a=oG>V*M;%zi0^^ay|?rxf)fL3y0dezi@C*y47MnmJ?Qb6-L(1e578~C z!oznly!c+d*FwIh`xH47??udU?G|r#DTa**JWOMg4(IQuK=Nr|T?%ECXMo~IZOTby zgtzax454wMqhAx`JOs{Rd&@WSTt8%c=r?yC!J(3kiWmLp7Vu+Xi`cIY6dpSd^p9_& z0G+=DBE`P)^&DNx?;QQ=CPm+#@0Vbcm#AI(YEOvCu8vqME-Qa6n4K%~C;!0rZ2+M^ z>tQk)z*ch!h##At0NxeTQ9-ImdSP^Ish90Xx?QcE2o; z`;^SHjC1@KZyuj6??pd4)}}jt%?x}*`h4;VN8ot}@D(1s&&TvF-tf4HC3uU>y(GDE zEy8=j%fpkXW)Z8D@He?x&?|R#ZzLTH)aJ9)Fb|(i)#4m|cN&|ZhhkohMn+FZrY4)w z!(VqWYRTBL{b)mEVX$jq_e4RnHqYWRiw#){r%izLOxuDyHcTR>dx|fTS{#QKOo17B zQ6Lf9vEna<>ivqgQtVGAsr(vE@ z)&4ZZi4L}VSR6YC%AbOvQq0>RE)vNLPo$jnpa9huh4f@!sq=z8o?52kANtkRF$m4RC?TdXj~t%} z*54PK#ZRH9U#x*P`6GMq)0JyAbHccc_jFG@%6R8#^d=5+PUP-I!IpbJx@@ zn5So`%pi9D@a?ty1motEGwr=L`&Xths9%Q-IeF5KTlr@@u$yix_nuz3r+n0BUak9$ z_XbGk0XtqX`x!m~5t!@$6X3|R3r|NtVr{Z;fv4RIJy-fB_1@Y&`mRZ3l6z^A7U1Or z=Y7vxQuRBjtn7fu1)F3g4i6xi_&S)M%ZEbndIhh`1O4cSw~H{c;Z|1@>p`~*Je&vN zj_@9XkHVF6;OLcLgYMVZ{M_5SM2$Ym#^%|{2-(GcJ2#4`ej#vVupg}?DA8)WwaXlf z8(_aSzC!&T*=zyzF%~)11`gW&OWV1}>@cx0rBFl~KYA@9RA{rsEw(M22U(==CcT zU1TCKF4ku{rofs4L2Su7>$Z>@ADY(3(i}u&&R3SqI8LN%#>iS>tMeEiddVT5?1i2m zHjF-n%3L$(XTHXVj?;`CobmElS$sA|)sg02pJLap;--BWk8t1<>pfoj4#8pyyl_(V zjlFoTvKYbby%zaVo#7*|vO`o~YENvBERwen5J%$((39aoE^sZ#7ha^;-DQ@apjm0Xg;=KH(9VSKdbkYD$}hL*jAKTOQKtpHS>Vu)ikYe2R*6hG&xId?_q`i@;7K z-_-B>0%!4xj&u*FH{Tnan$U^P8dM)Q2=C8CFQJydB)cDMib%prN1Ll4A#yu0ucBVi31$ zPyI_9p3IH;*gNO!_Gn?3BhV(}oSav-e)Rh3vYTN?t^9bSi+sAknXiaE>0**TR7(qK zEH-ZFw~by@`iChGe46z$N9X29W02j@U7+ddEn~#dFn?!1XTB&T$s$9sTRX$s4;IlJ z1Uty1>tc6sXgw4{9uqs%kLiLq(ayYC-umMN&4~|&&1<`BjV(Z-s;xj;3Uc;0X^jVa z!Sd{NuznDw?KtB{fBYsl1MR!@>U(JPlfN?e8kqu3{AcXRTKVWbz|6hrTb;K@l<1bf zjCmRvGe#Z55TM)Qh`nHaUjDJMU5AhJBETF5!Xu`ubMnX7P=e!$c;j;UPP`!ccgR6T zH-X}XeqWHT|7h5?MSrgwJU7tm&&73ueT&8kRaxY%OnvnB?!;sEGux%Te2xnn2j>b# z@c`s*(O<;rX>EWy%Q}&?NfvP<_qKP=E9-vOGximX!1FEOS8&iiUz4SXP0$jq1))V@ z5(~VfB7Hgx-7K_C+UajmBb`PNn%Ql7vt~%LxY0_eZkweB?4s@!dvA~Ch_5?0q1A7Z zSi81(oCR!?)RBxr)dDsA68GK;W+!`gr_C)@=Va1F)-I||{K3!e1&Z-iEZ)f{Ki>=Q z>z{h7ex$SgP5vpK`n#uLajtM38!Sk4O!2omz3;Jc4c{z+lBo!Vwo)g)Xn=!+yZp02 z&$&VgG&ZqMiJJ1IJmXh1gyh^t59b!RUqJ9TyFVk7BK`D;l{V-cIJ|E=O8FKy0z+#T zhE2QUYgb6|@#!In-zaByR9xvGpMB2xY}_f{1-7?)6M(maGdAcqHc0nN$}hzq9TywK z9u>XwB$mJnmxYLaB-bLhw(a8SYc{~rZvWbXj%{37@b-{tnJRm7yjCv8hQ`uE{{^=n(;$Xi=3?ZXZSeIVquVP);HzGb07 zwK&J}y_VNNuYan(jP0zNTi3fd=d=s8a|^QX!9$}sTv!`cN9_!~bABk6mWHL;Y_LF* zC$?~oTWI7oW0Uy3^SQ>196*+ZQ$OGKw~Cz?4jF7E57>ph>c7TJ-xiy!Mb9mZHt>v( z?7EwyG1cLVefRy9ia&G;{_-8hIA^!h79?qi-r9xs;5hhtIO09A(~mbU)CPW8;K}tB zF$7%3bJ#Dk*7ilOug=B!9P6ds=KPcd=_&F5^&L!QnmYhNpjlUUBk=uJS?ykhL#(JnR8zG-uZGdE?_ad?<<8;+5?< z+?HK^guLJRd6i2K`8z*2F!cDx_th_69jDN^=CS;3;b0uk^9ToBx4@RQ{k9MPEf2XJr(5EeI2RMK+80-67IsWLK3M#n z&BiM(XE^uMVcZ>WZ9nrow_lwIJnsO$I%D;PTbc_t*LJVk+Xd__RFYUgE*W)!NMhLw z-f=!5`g&iDTP$XAwy+OK>}2i20$bU6QV2HDgy!78y66MD7-*m6N!a?97rk?fmH*{u zFuN)@+J|R~Cdn7w^yd@GcAp~mvRgua6j_XKf!_Dti9hoNTw$2UR~{ z6>RK@C#BtDYj-?qS2*fhGV*J$Wp^?*E?DfmoF`&pGf5eJzdj`R@>a)ik-av-jQ*84 z^t(W+?`FWpm&P_I;`%du{CA#5F;|yX0MfdV(FRi}D@8I?QfWA7$ z3x(oifMP^@d>eXtsw@2+qsU<=d&&H)7eE32m`A=+Mgcqe2Csj|pDc9sr#kha*m0k8 zbd7J7<4J$Cp6BA(A0nzhn#rag>%QRWoC*=1i=QEg*@f2=3-5hZ{QD3RAL*( zz;QwH%>O~3WO{UBZSg};a2AIJD0K4*{h&MbZ*oJAtI02|CBaLcbM5m2RD5_W3>JX= zm)4P7fQD^kcfrchg6Mqh9LnLLr;qg8NgG}Zz{F&E(p??hT}a<0;bL|kBlzxQj@m_B zj*36zd}3Ssvp9Y#pBi*p|3ZKUpqN-*ZL#F(7B}>fMC#=ge{b_1_Mnr<$*z1nhjGsN z`nCm@q7%@GR}8$(e+sc7SXwq(3`(=e&^OlUG)A>8bW~EoPCFZJ&sl^vwksdq$|SP8 zp^AveOIKj$#uPO0{oqaUV{c=MlEMIeyVGRM&@bQW<;%np2Y=_>(SxiV8($gZ`vdts z<2b%GW-BLswHb44tDHt)@L8D?{OshGt}4@>w-{_pjMI$0VuhRmF zbCPCX5bZdS573YS#)pZ&*tpI!WxL}}-^7UQ`NLbm<({X~q`!SV9`iQs?JM^o4;`C) zP~}C?VT^(3*=}Bg=Cm>YN%p08#E;i}0Q_A4;a2YS&N;p_uw}39#gqH8fc9+nE${le zcCTDt-E?cq_B|h8tq3GFKEo$H0-G@R0(bGAi>JklLl?0eB_VVY)6%1pU$!7>@swn^ zw42n)p>qpAdCOy7QR*GoogH%5M*3DKJ!DH#-gmTpxY5_1@J?ZMT`=gfP$(GDond9r zt;b>mR>o4FZAY@Y__#D=&0;$X_t<@1bjZcW1dAg-Xnp;SH?w0gh02&W3DwTW$eYAY zkB4Fgo_yfg#0{JFJO-~{%#eD_B2LPHqG88=aby|GS!A_`Pi!nOw8P@Op)&hcyI zEtw-b_PZm+!+aFUnNu*!JM#v;K0iZvrZ-L<>&&5hfTuFkDQ>{g9Nu;td2&6-b+@qe z%inAGBx~_w$I)>JIn%Cu6w7m~>qY0{wgu)b|H{U{^3klH@S78~pW)Sxz@2IOYCH67 z{Rbo9;&stVzFTxjur6#57yTyH#ku&;iT_;O!AsU2_|SS3*9=cC`J+S9mDF-5-PuAs zQgOr-&=BfCkECCbL97gf=<(q%v2#oTMF$Fgdssvi7Q2|#?od<}h6CWcu%(0T&gq=w zzs1JH%bU@?2aXUlz+r4YVo}@Ivss85i|(<_0?g*Ra2U@!h5 z!(+_&NcSv^BgZby+E9u-k&mv6W7^%d$vGeShR!1HKKK@3Jw1G44?FskY-yJ^M~l4> z%=yfRuvA|ccp~!4B0kKi(C=4TPH}->v-By*#6L zXxV4im;(ONyYjcVHwQe*AHRFO#UA4;%<$K_HD1rylRm(Pm3_u()3@_>#%(Cz$3a&P z6X%)`d$6?d+O^}b=}hmsB#MpqfVhse)N%sy&ak=k7EiXmGhX|K{UYj22YEghqdhm5 zCKp^-KfDp8=h&Zj^v<%+f>s~g5!!S2bNdyI!1H?mU(td4e9V@7B(El$T*;U7_FL%grf&PX9`30%%419Nxga(p)@ z$kqln@1kQdl(2yW*yQa5abUh0Way#rqM2Ki)Jy^;0zVjkG=d9Kf}C5S0(|LWlT-bh#5d0DQOJnp77}7qy4*hA_W(BbvBdI6CVsJV zVRskjc&}i!9=hq*ENz~&mv`P+KkX=M0MoO=EoYAqz?E*1tuQHhFBLaOGDA9!%woJbDj(7rjS!`LzS)!OYS1 zt3oP&d`n!9*dIOhcOp6duw&vow!wDJ9s23vKLb0bLNJ_q($0zN$c`2=bCJBdc@SzF zCGQh8R`0qsP0po%=*1C=9DeUO=5%a`AqNZ8U7*L%O*|iy==(63c`|F&+50+|L(PRY=ljXu)xSrJq(z@B3jj&8*bjxa2V1t_n#KB%AYN^j zxhf zwm|0Z`mIg(n|)8$c!XodX%;ncYJqe3fJ$6Ooq}U@z>)iq!tc#D-)zCP@rUlX)GqWh zUgY{KCPbI93!=9yORt}=Q>fLJauiEa`^4hhXFO0;M|jPtdt-oVY#7fjGMu(=UU*Zrs4;;*v9 zU)~wG`-}&6B5@^gjjfEc%}enjxhsq9JC|41@;jbwMz=9rnw-2Zw&T)2~uDUGp68kwhuFaKwsMUX{qV57`n-_V$J+inxvW3Vd(i~52P5V%SZeex6 zy_?;p?k=7T)@%_I!TahREkAZQj7|%m*wHx!(kz(pTVU+sh`+KzPX_+kdCjfI2zWo^ zgLdRx$Js6z=kNmy;l78ivI+8d0>WCEy3LibKSJX70z1&HZ|D@Rd;-omy+7#Zb`?8{hHZq9?l|3-FQwOvb~hbY0j zu@71CE5AF72Y(GodteG5?dp!m+3~){T_HAp53ch+bm&{~@sYe3C63xowZ-ggmlz#p zANpdql|J&^)_%Poa6vOKNM7?r-F+c4#T&fwVZ&IHbGkA{<1@`OzqVjuJ1|bQGwqF2 zi>tDTAF7E*UmP98o#T4a-^XP}q90is=g~fR@;qjg1~($F^J}mld=?`QV9YhyN{_fc z1wy(0-qNsb?Q8o5w0O@p*kLVmRExVg`Z8c#z?yvAh`6w>Jr~4n0|A{mdOYRZE!*?? zs}})N>={1c5!ht933Kv@WS^ySv&2mdnnIrFLux^o#CpqkKS`Yv+fpq5EWVSL+%}cK zZdF^vd|_)Bk+ip9y3ziTo{HmO(sZes6KP3;Hh3=q#T6ULEKq zel!acD>Qm7#0mxRnwSm$EV_0O$?{%B5^xwd#f76=XCr!c>ga&ae`(3o-?2^~8NT~) z7jpEsF!~4E0xr6*enc)i^H-ZgW*5i;dWIQm`o^z~Rb?N+Q6z3$#K?zgEL62!QRMtM zPBBFHj>8l>bXInbD{Fj@-@%FBVTH!vqQ760lXLQ>K$y0-Jk-}PcZZO^gOB|7<=l4w zDn7&2;==Jlb2S)zrfw}rLvD$0Bcslwe=((YsHrafi>x%#W zMuzc9gmb1SHy;MyI3&jC&`f@ru?VWRp2xODRp{p$pZMaLd4i$;SR;_c@h#29dOD`P zxQ!LcEricHm*?J5EH|FF{hNb$x9wXR=NqGyBZk}7Z@Tik&^{akOMA}_xJEtKC|{ql zfi!Z?P`M|BskTMj$U1f2G|#le&gc%&%f|Ia2@5t(F@ z%Q_9Wz;=oXgAn=(lJWAp45uD&hGsux2*87i(LbJ{y5 zZi)B(m_yp@0-Kn1UPhChEVlaa&&U}W+SiA%nZ;V9_~j|ZBuKVz46G3`6X zHL~=3kUr6q{z^>e2&if7*cGuY*WxyqcP zpzi^T(~3;}J3raz6S5NzJ()X^X|V%--b+D7p1Hj5En{~V#L%!~-eWd?)P~^LCcbp- z7k$&`VT{N`yK&{pK17=}06k#G*&u6*J?=hiTBLCT3cQ&AQow(H?Bk`FPDFH?ky}(c=Zkofc?<1tydL+6 zp}rRZdEK?YBlkso&wU^72z)dZz{lI?UwYOZiD55tiCTi)pFaDA3`i5jz3g*RGD%y} zlMEc_;&mjZCVvU+wAiB2?ZF3+s(3*%Lc57=kL28grM=hp6mFBO`~TJYz{G==c>D zbfY?O6gO#+N!{!!&kGSuJf7l`&+}OOE0^Fv3)l!i3&>$>Ir6l2@|R3(uD?>}iT=?& z_(N=EdD@><+k)Y>?ApEND`(PYQC0vL-?_D%=$!;?aaViTa&$VHx=t&%+7i=Tl6E>f z$H*^Th-&9`UXK5xNbEXiL%Z@0amT!y!mmD;cCLfQA`JN1x3+l!lhfKq4w;JF!CiI0 z1AH^i^I~#rnZA3^Ez&0S)YtPh%$Aph^Sq}2^Wmif55M<%ep$V%XU6IXLYT#)*VKVp zx|LgcmG%vsd2YHcr(}I0K3)VoH$IjTcrE}xmc#N3Ym~$wNp`0#qW5;oCi&Zhxyd{! zCDf+{WphW4Xr^zGSDVRQDA{qcau+9|oQo6ZzARSp;g*iYYkBMlws7r2Kf72Kuv=KW z7Ef1kPtXqiP+w@5`8b|wxHgOURp9!A9QN9C2zcVqV(^BTPg?}jwYwE)ozrD3XNjD1 zczkO=ksfb+>do-ach5P;x4u}6J67H3+|eyg3*_wQ zQbzvBR>a|If9U;0nAkG`|HRB&5GEeAUtf6GgxB~{y>iij{mp0R{Oa!k=lEvd?LUPV zyWh)7z2oHg?%SV>4JqaiAN(w!wivoz=&P*gV5ePCg&||;8LQYh@ek_Jcd(Mdqi)n z_*?(NM<2e0Q*%*wkF}A~4*|B(d4_w}^7%#0nReSPM8!3>E6!dP_!H}lcl|HswX4wBOg8K_nl?d zI>{T*@1u#%`FmZo(2gDYkgYwwR*x~|B_y48$v(#M6E>dm+me|_{0bOJK22` zi^@Fy8EEi(f)vH=q-Kug@ZHo?I4mD9A4HyrEg2 z^t)c(-&YR@9X+>DxCddgmm`tI4KPl%R(k7%{c6Sm*N zQ?hR9p3h&M2pk#X)iLi|%k8y~lBE zm<4(4xb>5wmAQVgg3PgL3Zc<)B=i`gkDu(STd~Qv>Pz@vDBx`pjuUH>bMn{U8JVjR zc>QeG9-GGkW6T$ew{hRw?r0S{%R9&6CwXK|B(=#$BLy2G9R78&UB=YtJL{d+NltsV>H zRd49at0Oox=B-7sU!fBm*jTcM4#f-FeKBM#Tg(Q(aifl%EpkGvEgp`2-(3jormuWbgRPBs9D3I; zn>a=R+sHIe{K*&juZ*2ja6mk#*-bt?&@SmI_Ob6v&)Qe4$5}$Ln;2Ii@gJ{ zrRY+a1N<9P=VEAlYE6W#8IGNUkIlkzfn37%8G_seW4Chn@3C-dE~;a_^pH!$))1%(K3Y*N(@stG=AN$ZxLObHO)BARCCEXK1qL0GW2 z$f2vUBdZHg=mFL9lSNYeW7u=NY}g$ax@%h+7SGB{KRj4J*T3T0ljK9H14)O~*@Ydqy$gdX53EJwmST8Wc13MWCZ}uqk06U#4 zT-YI|aOn3qbm564lGk@Mih>qW;URxs42;Z`yY`Sz=ExiQb5>0K(Lx9Cqwj<6ppAiE zzE{6U5E6} zwJ1N_yTrP7XA2v>Yk>SY@^U3#uZa;S4igKv^uy7(kX?VvX-=RX``&%u$;f;yEBX5h z#Pk_I(D{KPeec>WOgY95P+c+5*z;W>AQmkQNBqPj?YXA+g@v6d@i>Uck4U~c0$t?N z0ySRg8CZG+aXS5%zXf95#nE&tkf+rQ^TySC9^b|eoQ(CA~s%3HqMWA&Wqw}0h3C*yqF_8Grp zX+?Z80;pRd+~g zZz#y7!?JnnXQ(PnY*sD=I!h)SNC4Y^DL!iV=&=iC0mawFKTKoW@Gj5x!Ah>@bGSpK zX7wrJ(9AKnCbPm>*zD|8m&M@VOC3@h@Pdi!_^d6~VrDJ?HUsjZ_^A!viC(mBr@4(< z{!qR9_S-2Maw9Ya#poR$EV5(g?8Y2oD$A4Kl4Y;Cuzh^RJ*CFE}w@X*n>UU1DanlrI0_g+n(3+TqAZOxXPV@yrP)P0E zMa09WGd6hg-*X(~n+Mybv+_b@H?Qx}JbqUgc^B>oWl!T7y2G5>|3+x(BB$=Ba|(jl zNvs}n(jX(PJYqqZ;NClS*4O|N>H5Df5@x}l7|eB)X9epxQoXJV{BBd5i}M0*cbKCj zqIYi5QUB>ae79SglJ)*v|`=@vY;S z=E#_N7O_2_*xk zUtV!*Z1X-Bd}sNO819^$W29~T&bT`)&!|@{0=XQX;g?bbE*ElAfi&6Vnv2`9i*t^X zJO=5a2c?sSbG|tA0EJ}hv*}1a#4B)X~ohMvxTcw*m{T3FB30W2Z=Xd}`owVT8Xwjtcyx`=;alYeDfZ)A8izd{3k*TE ze88J?^4`zR(iQ~x05;9lZ;@5VZH$KIamT1K+#3 z?fP17*V4P*)3)=N*+QAkVuB{BTOhNSx(6m^Mtes~;1tK#t`bb+%58rU6w*_|TE*jfl*SWBo z+4Y#lS?TWaU!oumPjJVs*_lrN9T_i@-@eG5BG=i=0pG=Q&AVs+6qb+W880s^&Tx*; z8UNgVbtCY+1NiEW-REU_FX&{!S)?ZcPhy;ftN2Kim(cD)q}`;RqvSFDlVr~ZNadvs z5xGt9M*<;R0``H8c#l`Lzk>y2L&=^_bMGt*^0qFT4u0007x=V29$wI4; z!Ml9BBYBuzyRg!dI`y)Mz1}yek8b^Bq&M_eoYvSdi*{|iNTfTD6lB$fpUt0|l)(r6 z6YD8HHmW|@(6I>%It93b7~lcN>6`=yO%Fb%vqkLCEe_ExN{W0jdBcuKi0xAHg$#ht zLs4WLp!LC#4bJrXX3kINK~g&M&E0cbEo5u~~u~ zdtIfE!hOL;?rq$wtNO=oA{0nG=-NL!p5kIzgJOyX^bNfsmQz~O$IGp>=?X~Y# z&h7c~pzqknz#Ff82-w^ALPoM;$#*pJYrX_ z(x4mpPd&G8pyUp)qwz@JYljb`dwkqDV5OT)8(;-VBOe(%Mr`#r<15)usUhKyt~qa< z4tvPlSfCq!X92C=$a5Q(>g8LT#nNK6cH-B!=ZA{R0e^Lbz;DzpJvpGoO#1AeT#BOL zrvOW#p;+ihPe94jy6jN1ha5#qBQawc)FYrrjP?`q=LL5c*17fVdhiL=&h{2D9T`dw zn>$|lzCNerU0-0>=S4){&o>3(>$$BiKIy8AV*|7H!O_QdJ{>pTb31fmEH2&>(D4eb zSc@Tf1a?O*2JxrzgJz#Ou{*95AqP925NHbYMz%ABU1g`u+=Xq|-XoUmU7h-OOx!jH ztFtG^6WMzCf$YkkQRYLrytqocFHoMCTaiPb7cpdzD+g>rcTqm3oK1MtUK`J3WO}6xuC#$Zv6>5!fVZpi)i_$E*_}F!uM0YV_>m;Jt@gWX}h3+w&iq&*2Kbo`M%fr@{psn!S z!UxUym2rItZekSO2d5nm3ENL}*)Dt|+0+h*WZ(EE*{{qNDiLsw)y0-Wo>*{8Q4OlE z#l~1VvdGqJ94E9pR!!{D&7V@Ffu?eT*aE5X)K{u`zV`8Ga8oRlDB2=){*PU~;jjOZ zwS``Fg>Dw{!;pv=i6iU!JeoE}V$ODt+MTD`5N2N?#O= zVI!|aK~7ixtsQ&Lj!@+>_B1y19AJD6(V;q6alZC%tmcIWTiJ&ybp2kxlyaf38r)O` z$RMV%i-X!Cgio|rN2Aucr#}$>jUAoj`O;{`zuRD2)zv8eJ#9a*_9XP$L^Ptvo?8e zwy+nn>o*teB%Jxc zf&|=8m?k5>F2SZB**%ShO*1a-maQ`p^d%W7h~H zmn_T*(0nmW`t1wOiz9t4kTv2DF1D5sR1o%<+T_y=dMv(<|^aC_Zd?YfA&G~``#%Ud=0 zXO1Zd`Sz6E%Y2s0?tLLGKPdFiKA=6HuM9YO?H)u-;N<6xfZa7-JMPJN#=RO5crE~6 zjdA*US?T(1fzmW*k>3R*3q`JW7xE^GIZhH8{9{_Onjd1(<^^;Mi*vpSseNonW9%sA z@>H1-BAHs`!G$iJS34+Y&m>Cpqi=np0Z9xhUy^eY;`)eI7aV{Gi`PEKW@Cou;&f@Q zym<7rFnJ^2y_Tf=jO{e5p_4k>(!FZVpr zIP&MZ5ntzE=h5ng)2H|PGi$MpO?kRrb0{y-PGRAlk9n{s{C@Jzuy~Nwd6M?(j+HIS z+t>c9&-A=ABaIfbiO$T{Fv9^Aw&FN}`73U`LH z+{M4hj-`1%elj9p-Fb#jcmyn1UM0HNC3D%kJ7+n16*}iRB%5r(WY^9DDVYxKBr!>U zli9Q<`3NEWEDBS2QT00c0ZDM=jNDy($;SisQ^PA`?2Qa|gvQQ;zDcOZd5rg=koCa}*CIif??K$@gAQG?zW4}*~zS;ep_gdlG z#h{CKOkj%`@NFOXB4!r9v|EIQa6ggBG%?v2vV|Ov7Xg{GcnlT#J#T?<_@$Q)_I@f0 zt~s;k=oGbu9MCw^->>LMo7{PS9DHusB0BJG98U_B`6Y}&um!Kjf|yfhXK8J0T!TyG z^Ea`en+;p2E&rY`FL}hT-%ICsm|4`hy)?#-R{uNJFwkPcMtps&9zn+y{Mz8wzP88s zI-c}7I5K@d-y5HLtL@=i+KP)0=EFR;zww*y@R5>diUY>OSgu~Y3Q|Q~-)|c-w8o0b zzwFKNhi^o9u+=%5-ASEm()i3ZNSD5y!+84PuEUnOu24M&^1=MV%E%DoE&eu7$Yo@& zJ$TlqiFEoQ19aa5Iff)(AKg=cj2?Q&hbc&%qpL0Yj`P7qP%yRUz_Wu)xKCwwhOB`s#%xIk+$LP{^|!Vi z#4SKJ<||?Q9BBqysC1ly?LshJeZGvR_+D%|5uBPayRljnA8KEYEgoVB`-MBMR98da zeq3qfVezTo1O%q=P?8vvDN1J1Cu4rw*%-0)9;^*}RPfP*zTe`fj+Lzd#l7RMe`%Kgv3;YTE-}aF(fA*6 z3PpSv9gfCicB}*lP%Fi}c_WXwJb{IPFNi$W{#EXRkJ!6oz6n8pc+fe!)cH zI6I?aIriz}9~tHc+bdMZ0ge4Qv8c;&cDP4|LVAHNu-8vtWCVr8JQ<%IM_q5J#_sl? z!A;Y@j!f5zXo(S2AUe9QBE{%S~F+7<)H9b*k!|s(Zn&>)_ZpHdl$SEz$BLR!q_`5g^es5>9B-N`od5L~@VN zpo5eUVWkfehz>0T$N?<(EDJ?4N-!8>MDR;O7;JoRomW-(A zfkO-YO=?>BkFIp6XbVEgt{ifI7H*OrM^NAS;)4X%Q5z9#x7$~;V|&;O`rUuM!`7JQ zYg^l{Dc4`lhyd!UPh&eBl1d3>4U`Dszuk9QohRdG*%kVh%BOfZl~B`DP83bYI?q5? z(&;ikUqVsws<@@xcH~DF8?=XD;z6JAkIzn3W#{`tpkL=zJ}WKx1LhNTKD1@s0w)F! zLH}TSnC_AsI{17|k1^tW7n3~{&xU5ZIIVKvj7hlF-&M|i@>jZB`Ef>In;ssg@i(jA zECO}%=S((xfpFpV}wp@YS~%0{(IY8&r!f z?Q6V>=q=~Jk{2Ew_h39SkOM^BaNgY4C z-tnxMMhJ7z`>t|`{1}>8c0AkWwyeMTG`YWIk&O9sYvCcv9peAa_7nmDCx(TFKqWb8esfGBxz2|4#OrH%YPczZhB$ z`KqO>cwjoFUFvU%)Y!G+`EwskyW^CHeqSHFyx3=8Pq*6QJU7Q(1AeXiD?R)g<5h;X zaZPzWpTuFEw^qKjEat`!dvEaBi@nZwSvKIx1f( z#CDS~PP}}Fo=aysrC&#*5Bpa=IYT`@7VGjgI_9|gS-PS_+pJHuAVjKNtd=bh7126K zLB^)(2QvM`!?uC3sdU1JuB4^xW!qw0uLH?Zl5q{hlUyQ77JJtY+88Acp61nmbq`x< zi`x7%W=jV9!|&aKY?-eSr;VND)3-v8ixd7B%OrAQXyjESQXz-`GZx6vCgBn5deL(E z-3h7PF7}Z_(kXTrwS^}~cGfOkp_BMkTlf;cygD6oCF90YC0=aU_(x`)zmdaU;7_jA zZdc__xZ!ttJIjM5m#R^WJ^*9iOQ=CUHSryOH zw<(>*9JR&xtH3V(dTsu?%D8J_yLt59F`M{|kH>KmIr>jO^L;=(S6Jz*X=@+*D+W8B zy$p49i<(j)X~k-1bbuc{R}JQN{H#RamH>WMdh#AWEXYo16T}KLDa=vZT3%_VZ8xv% zNow+tteM1WVKGrJRD1dA=zGD)#1mRNEDFG4=tZtB!;#~or5Edzq6ZHDDM_?YTBgnc zC9H*_WaWs?uFNb>&8IcV*oKE|eJ#(VIXrY6C+kfi`Xg*lk;2r=gSUmP78-I9Mqpgz zO6+OhwU;d$-ZidDO3LuiY>PQ|v@_{zHd#;ns}D-<_+W9Vi?+2}h<=6D^tH@qdKg$X zM*qaj(IVj$9TFHaX|U@Ds-AW>?=J_E#a5#Aed*bF+6Vshr(Sj(Y4Fo06{FFy**10s zeFUc1IX=CBxDyMbsp!*=hCPxU$wrFZw_95YgDm}M!^^l0IzbU1Hg>zF_77e6Gn{eQ zqB>r1pl~9VK2#w`ObWJoy&5G5G4J-+5gy~Pc9gecYY5@S&rjolJg=Ey7jWRW-M1P? zkg4OZeo5odlxe9nXY(Q_)3~GGQ@r@>MAoIr#H0C8ZvHH>Yr9T%kllJyh+Mka{hFLW z-|A7t`kI|AmD8?ix8o&WY}hz(DbdlUPgfY(JM>C&r%VQ2d!92}40dnU4y<&ASrJ8X z{x!{FM5b{7;Ol&7v5mavd*ZSBSTZ)AmVY;P_lUeTJ+cVQ5Bo=E_RZY4jzG_yZ_W0$ z3^M`MW!vL2alaG`ko)g@Rp27$AhDO0dGp-%%<-3 z%i#!xKi19*_qDB*N)<1a#V61;=~j!ZWtieQzoOvMLeC(N5X;J8iA2 zNYB2G3D<_LOXSP_Z=`$ooTHu^TUS22Px{XosQdOpYe$bAm9(VIkE1@%#I|=ynND8G z&XEj>B7N20!5#mFNjpD$#*Rsn)En3G=r3Nx4*>ng^O>C&=u65Xi|ueOySK(>nz(DT z3z=T2zCRn2g*|C$f0}>3S1X7?Qyd#x@dVF~47W2_dDjL!`e=ob?Z+Hhcc5^m2D{z(E|a4V2>lGZIdl9l|Pa_>fxZ(NK`Eq|}!9x=D3M;8HS)eUYD_^Kk%6U9tg zJyDrNOh#`rA=RR`@mPS&L?2f&a5ArCrfre{EmQUvILwmAdM3?vlJ@fEna(CrJxT5o z{E`1?!*Dgt*q}DF-E#ho-3PFvd@5Wc%LX%Uz@j-&3ur192+1!H&z5nT^tHgZh{#79 zIS%Y1e>z|ijuPgp#U86y3vFIC(=&+y1o2>Y6f4M&Oc72d{zqftk z2YkKyX%Veh^qY>+O}6nN(W}0QK1o*H2dQnN--$Y_qD3ceDVE*h(c|TebhF`vD?7?Z ziO4<#!DTE+(94Y2vxiHG)X-FnW78h+@Easl^{Gm})&%pCYJ7dIBXHmO zYtnd=iQ_D6nJrAH$h-KDM$3fpJD+VXuF!HF_*vX>~O7iE;n)uw<7#N-rphBrS&}AsV7KH0te1IL zUOu=C&dB^Puwc%jkDGnHxJFNDZ+{Tei?5Qul-W1CVcqWidKXrEjbMyvGb>q{F)Pm9 zA05}R%dTPj)#HR1dVN+P2hXU`)-v*$0u3sm3%(PMQ~#4S_Ky$MFX7dOTbz4bm#7V!@-Q^|&NrT-iI7gLyE6euw zP36b%OxwuT{tz4!sfCcP?t#1VjX|*+xa6DWm2UbI5Blkok+B}f_7!)jJag}*wj1v8 zMc|eIKE6JCYl~+>n)$<|Ta)}w(zN#kI9xlTT@_DFzWI`XNCd1RC2Nj5o_&?3`ec@> zUA)vSCKkAYS|luKE!R<7E!gOqDho(b2KocO*#kE)iIKKVa?##tVYwi%8+Y?x!&^WM|Lv!~CFNy=)cvVM^0h*94= z7DRwf3+7zT6tAL>{PB}7^xg+9z83wK72q*kDuGHv>5Xo?k3cdt$>_S6(%+Y$s1 z7h$Una8$iVX&NNP;)Z4tndx&v;PDKIEBf)(C4L|tfHrM-VA$wVakn98Ix@`qwzF?PP9YThYfdpXw8gBOB+(+U&j`iMN9APao{t;I*&7N3vJA zIH$x%{7A*-J{Y?%(G2fu3;OQw%Ys*VYk4n!VpB%$8*lYT7lGSDAdjxg-rnGv)H18i z;$y)u0l6d!H_(&29fI8q76O>EH=S&ms~o?FizOcmWD09kwezl(#>rnI+tg) zO%mI-3ROv~@9x94XXKA=^5}Q801C4NWBRY;CgyA)Qys1G@bY!*uyew{pisv+CPPqAcBzyv4J1NDLeKUZ=WR26N4kZ=n%Fa zN7=+~0GH+?3~$NbTG-2!qFssMT71O`g|P-E`Ks83TP&4H;>X8%cc;X${ErMcFg_^P z*x2cVUx96VfYPs}CqcYGve}*aV6&%wcx-~|oZJiD>ipfyyM!z9%`aoB;}E+Hifa&h z55^d8Q+24Yn9g}`qJ@fW*Q#x>p>{_#fOmHHi;Bs^P4-|W+}S0nNq3_$Zw2jPKtgdEe3- z+GgYEnm^+QJ$_8v9Elm<;XJK9fKU9yp=eT{grJk=@#RUq+s*Eez5x0QPgtuT>Tmd_ zjUD8Y2_#hYbZ{E%uo)rx0L}Da+>5^%>m{${)_6dde;zO(&Sgg0U%e8~{&fHM3z=QM z)wdq5kjT`lQOMqO^@9psXWJ!U|0J1DDv9j=DoY}##uFpTk{%2C79TkJo%*x;$QZB`t z^5FZ4WwkWFpJkjuvT;qaj!9c5G7hNf(c4!ZnxkV#Bw;*ZaatNHV25<>Wgplm1|p^qZ< z@}1KG$z_e@l-a>A#}(+2XgRM3T5kIYCq8iemVo$_ynKzk8G|EZe{4OAl8vDI;zTXE zql;W_l-wNoQS(bk^<^c^DI2$Q4v&qFZww3VoD<9Gb`*0-X3Y(;_idngTB$CcglS~3 zVd6Wu^>~R#`$M*fCtcHD&ToFQ#Brbetvauj^%Z;XgI+IogYG_tTic_I!0*To;4J*t zBJ@!EHNG4E%_875wy4xepY#5y#W6^edriV=H&LoP*5urUT0~4=kdPkt%j)41UjwN+w~GA(d`tnwl9OuCY#ce9Q9{Kf0T``L`B~H?Z2Cd{6nAz?KulB5|eNxQ2cB(=~Y$ zPd4A+vk`$$JppvN?Zt~1S)g8J()}ox?4BOpfB*fQ@O5?+?)mfQhnFv3RzyuyCjNJG zO$yz6?|tefel~jY9xrNf%sK14b@I;SS-TF->J3Z`m!MAgnsn1=IaZ>!(OQg~YwNe* zS21*%E-InW<-559ExR1)p9LNryWzB{TO@KQ8w?*yS|v;=7hRg**=r&_OLRBc*n6o` zi0#3f6ia@N7Abn6%APdTG4j}$kmgms%6KvfToga+pLuT5qW%BGJR|r z`^T=aA*5%3_Z`W1c<3kFvEO|cdr(6L>O4~z(5S_t>D zr~ZDDZR6Arof@|q%3dCAeI38pTmGex;xTqqI0vqQ7)?K*^n(R`C0rYu^2nzH=s$|| zzrKGOyku^G%|i=E2m2+IHJ)={pTB@p<1g)-xca-s?R!h2w{J!1G5pZ@YOal5I6nd)L(bK@%D65)coWVf!Xc%(m9 zkHu+4RCSBlk!PzfDlQh8IB~~&gU26%Pc^%e^!>sw{KDZUfAS{}KlgJ#cldYz?%y50 z|NFoH@FPF+BZn`3@rxC`U-^|^IsDDP`8N;$|N6t9`7?j! z@Pj}2gEdLdWb*h!{yXo1iNXC`&RLVRSa$Ld#C9T^&`iJ<;dKEp(R(2+NU>m&7ZnSr z1-ImG!b}u(`4ew+`}c9~DKXKOh{*(I%){nE41JM70gJ#>)D7P5fEL0P+B`Vx?B123(o7#1kHK^sHk^WZ2Fw=Ws(3ysQGw1Gezn+(2>RN=G@d(YNo5JEa3(#W)Sl53%4oU^kfa zQLOk><8K?o+QomB3%3HEu-$fDl zR1?70xlZ%Tzx>OGfA-J*+2OZ->$eVn_wWAQO7Q;JANym+5d6pg_#Y2H^;17}__bgA zwZo78=#L)0Y+$n~tuFW?MP0Nl zpG_7XHr7PiB=zl~hH(Oo1#vDX_O4SFy5OEjem4DXm3uE+5>(+S^HS!z_0oa}XL0Zk z_~sY=j^bLj;K`@_+S*ETaOm(2&_AF^_rwam?9byB=p-Z-ev7pDNdQdtMK9=^?2$P~ zat12lO+!uQ7T`39&CpJg#9n0qA)h}FLHAr!A;(jfIPud28UOM>ViT(r=%~xG!S$Hv zcq8tFrISig6HhTNF%dQWK61n=B$4Ss8?<&=)jRo1Q}I+EL6a5vyMUJY_#HZlu2mJ5L^9(UJ?t?46m`} zwhiPVDPSYjD~#L~H)U-#UKggNIAq6T(dUZ|=zdBgduSZ~CThI(+-LfBWH2{i#27_>S)YmOyF0_>M{d z;q3(8;H!&(iTOo#t)9DvP^;ze@d3D0bxdWHQ;% zvacU9X?g6bScH)5_mUhriUWvi3p5TwY(C!XF8fZwTIf$j&G~->k|Z#ti@vl@vMQF| zFIPUKEJ-VffP|<3A7HHUrut{wnGjbA=Wzi;G{((wLw&sY)w1X~ z9R9<9_|06g`1Ql@`8}UMeDgPdQ~K?_v+>WCP851R&w*z<6}`C z{T1Xo#MX3j)3#yEa^Bg2?6Hi&SmKvbeB5kT8!&D_oiAxGIont)JJVjb4us#W3j!lN zK7bASg`CkVwto1OeN9%jZ>p+a2q5421Nf_0FVil0#$oqUC$_^q0`EVv;ZhQ_ayh?1 z+Zm-B?D>i=&HP*e-!(lWdt`}g_r*@gDsU@{FyFi1?h??ug7G`heb8fLaQov*uWj{< z?0ux~vz?#(n)zYXHNM{wxDwsUk0t`2Y62*Mli2yV9PG00Z~Vq@oCU`uFDd*N|KeX9 z{>I<<8;5WG)^Dwyzwi6L?>qed-~ap1X!n&_AmB|lH@F;un$)%#!L(whOSqJ4mn{S) zZfilsF%4p?eHIuAnxqI6Z;FnhJ`1RclP>sK96QiR!F$my6(v7~ z+%?)pZc6JC5`CKh&!EnTUopP-51pe_1j4vFOHX~Hp!kai%+ zc@>}7j8DNqf$@PHyAb^EOO@e^4eI(G3{O?I zFHIHe6eQhGKFSZfO?L4_4Vq4xnn}Al7wIxaUxn9i826)9|L0H2J$v>vGMko++R>d` z4I)?EeFkcbM_%~}pHIYzQ~^6*?8PzV7S3?(l>E%^y1a z&=394;hS?s!Wbj7lDizMTygKjk?o~7U;RX~KFq(2PnYLw9ENYkPROfI*{`kN{nm*S zde)V^w0o711Q;#;HoB9;mb;DXwDF~!3lV-k@|*pBd_+p{=t@b+BoB@c?H{`C8+H;o zzL5`y-WWumDMCnVtU1TEi#e#VoH~IeHGFRhOT&tP%KB6F@=b6Hg(kGNvl$E5)$Z zB2e_*RP~Ll7T|dg99%69l&zC2{jtgJ%>Z4{ zJfgOiI=qF;7sIN&wMCXTpvewZ4#CBy2r{%_kQ6K4(yM;56aO6u9X^XA=modSZ}QD9 z3+GElFeWaGai5+QRmj(BoN@m|ZCWVOE-ixr^%|2gBezJa>nIo6~*Ps@W2(sWG z8LkoU@N}1v!B-q|++1o|X+Oq!YtxVHW-Z@TYD}eU96Q(9L^k|LL|XcSah${zeZ>bs zv={H@h&I0e(!crt4u9pZ{O^aq_SgPeXd1rsrSCrcZ~w<%J^bN6{NLA@5F)&E&aMuT zmdx5{FPoy<_({2Bhrk$}B((V0T#htNjXCxPOVQU0FIM^#R`4@LbeEG*TLeD&rCxm zz5#O+9x#1eGJ>0g&eO8Wo9g4vQLiXjG_uw4QD#ScWY9Si&nEiFTYiLwJr*wu*XSRc zUT5cz?DnLSy2_z~D?c(3w~pax+ovW%E-Qn2Wlh=M3nX3Ri`b3LMVznkk=<+C*dkJF zxDU{f)3(Ou)VDmL?4EWqW}ywoDP}GQ7ZL0Uy3aK9N~ew`ABlm8p(oddtb##(5BVa>z}vHl!g8X&9A^EkyX@++weec6?xans3W`^kYCr=dMFy(C5iIh#Hxww35sS^gi5 z-*_Bm4ja@en>cYB;OmoZcNlIG(P_W$Sbp(0M5Ci@PTd$@_3UjT7wr~4)q?Ud_%ZQK z?Aga>S!T@}v4OyMSVa8}0aKbFlonCSU~Jj*mJ5zhepD3{Uq3+65eN zS@;Kj;0LzBXeb^I-}Y_acKE0N^q*ET_ecK7AE`ue=x0&&YMGz?*`Gc9t-tlR4*&Mw z{@c1=(18AjxpedA|NNiNU>=Rb`L%mAfqOkiN4HP*InkZu@RO8?TGsbkBx>T@>iz-+ zKwFDz1c)*IS`^aKi>?X0%e`<|u`Cw&!xIK{o!mgBY!QJQzAYg^Kd(`cM7rcSP~uXV zer7A2%d4RLsk%kB>BgTT*uKVZm!ZvmYzCF&rQEUUq=+s$B%#gMF$i0YUu|ti3W2hx zCfE=J#lNx_!xb1=lN{h1nYD;jEO*RhSC;i;tL*B3=QMbMICIKq_}Df7z}P*fWi3YS zLeY_FLElj22XSR%upP4YZGK?1-~-3lwZ*yLye}6!g{LwW<3j zfo#eov~!6wd}t+Y#w>bqjmiSNUwQTN@Z~(L23}@*M|s$xWm)Wcmg?QA>}*Dmu~idf(gQs6)SNa3YD0sy%Ux#&FbUQVlOSSV zO^9y5AK7?YfAgblo$c4?8GFg3M-1s0-jsUs-uy>5fX-)r9*KF!1y_UiyAa!Q9rxWN zfb>+Cpc~@gIyQ-8R*yz+3$xgTVcIJZj<%`muURNY?{N(A?`Two>P4aMu;~B5ANXR;OV#I5z_z+HpL-f5UhJoLk|#+X z-SD8t2mh*8I6ip#867b0B#ja#PwFcBuv>q?m)yvZ%t^4gLr%w!U7eiHJ)*Ru^CYve zFL@9f36W&fi<-Sm9bFF5p_OluLoeFM=NG3vP*zD~l0vSrsrn=Jq9H!O&3dpaL>=<( z-)el|YaMUYvS<>`Ju97)NKF#cG+R({Gd{m$Ksf8+Ytf#IRJpxN63cZ0_tfloaFG-3Kk&Me&S1ypvl zh}y~f@|V9{ldqRVyNvsbzxa!}?DF&VK*-l+hwu{Mb;;OgfLzI=SI^wwJOVu#&BWE0 z_$>VI<~o&=yOO35%_KgFOixZdffk+q3|}p1_##sO&Q9HErEi{;gd2HQv&>;#&yhuB zndBzv@b`epJOg@A)1QMWR?=hXYSQf(ndB8W+Kf5($u;yMUHqXV#o{#y5S@||H^#FC zorR|o&d3}o#TUBvJMl|H@{X#L+PYE2&wSAl%_UPDsvdb_okQF2n16L|WaNpvg;!iG z)MIPYmjMID}1YwgM+?9UYEjEkf&q2H_g^$YLwhaADTtdm!yWBH6wnWCQ*7r?{!Iep zN#k5|IO7{#WVNY14&F%u{iQE`&*9JgFF$tpKY#qM9)9Ilekl|m9sZ~P`Oh8x(0}{i z)f~kRW1@KRr!?nGs`V5(U;V2=airARvBa&tb|Wh(Bdu*ISyk1Kp-;OQ8Un|pGI)uy zWS*`Jql!t5r^wxM+>*&x{rcqHrnT6^;p^Q?cj$LE~8Ym>atcZrG|ahW9Qk_@=fr+?@Cfgigk2G&z6T`IJCFpaYH4y$srYdY%UM$`|+i{lriF#Nm6s=X>(Hg>SC<-}`%i@9?+( z_TN7I^}qht>j~of!a0e832h!UxsU#9vCX|iUaMlE$W&Jg=EULSy1vs>iOKe(%;cFL zaWNvnnm}g3s)WX3b4oa>oWE~tAu-XAuZ(XN ze3MquMIQMdy?lOn@o`?yk!zWy&yp1<(OdK^uwm!%nVpp|Y;Ch@e3aF27PWe{O85qP zxhG<@^df2^eVv_2_j`FioWyk!VfyW6`o-RfVrUXszP-%#zi0jajZ!hOnixt*EoW1I zkvbXf*Q;?}@ew~%9sfzh_>M23>Pvz}&@tqn5Bb%X*>cKeLh16_oc1n0WgzqeE}M=B zB%e$$3zoikFZ|+T7-<$0Z*OYRdilW*@s#JSNTc{<&btEdQfPS@_Yv;&+bi+sC;l`5O;E`ak@ShwuM^|N8K& zzw*n6Z}|G(d-yN^t1lh?v)mJ?54tZ8hY!-{oj9)rCiD`SaNa!uT zVk(yCJdhDo(X!9Zobd}Muw(?SxWUA;G2#x;&`k%~>hy>YU>^AsH#oMFGUr@aE7p8v ze_dKe7_c*0iD=4r=y06zm*O2DFXkU@K)~J_%jMu5mXb%mG5#jt6;hYz`EM+4?q3uo z{%p}F;v}&K#@WQs@gXoyXHL6BTed`wBY23usV;xBSr3d|`t@3(3lDm?ea7U&{uI;p zb)Wo|?pA(W5%|;-Ko4sCuYch$9RAMV`8&tR{QbZG_v^mDAN#Q%t5?1JgMaW34uAPC z|K<8iAYT0<8I=6}(Lee}a~bA?Bj2UMOt{+C@+I1@Rh(13F8yU5n1y0u(UVb62K5AJ z5c4ZnTfMR*6U{n>nsl}~#cFdlx#HO`Fr=GYO+z(FSGgDBnFLMJY^y{fM`e@g^GZhg zuRgf^WD;{JFjvNs6iEI`>d6MO%g@uISGKcjoX&A3d9=n&*&QiT5%yn#j$PtYi*YX& zNM9sz?R$&bM?O`O650F(WWLNh3oE%}a=`o1ES%_z%;J!Lbt$?@>YD@~3oje6qh~vL z`CnxXaMeGdt5|Ps7IHR>J><1iv2Oik!-g$OvVDnOeDuWtdU_baV|+msUC{@(zQU94 zvL!6a1BxxCjr60V7OPZ~N|z2c7e~G%s}g+r*hD8l<0GkQA7fhi-}-7imrMy`{?>)TugMTpnn6&-f(=^F&B0^_`bAVhi(6*Ob=WghQzsA57zmD_2P7ahU zQB(~e^`*mK{EL6_AlaLR&B^C-uZKN6W%rl<(qF2} zz;^IFBmyT9^nl0>etRNNmnmxsxGT?zZ6Y^Om?V5wn8iked-*brtj%X-6O-K@QxkdQ z!p)?$ty`tU!yo7>`3sF-`zD>R)sBz0T42&@^F=_lG-!4`?@l0TVe6n1g zrMni5N@%P3?5k}H3M-}!*5pl61Gq4k4l7w(7@A_E39a|)S?Jw>wur61us}~tPI^Xy z9THEdp2zOJ_{>*!R$`QL`3}Li{BM2m;@z<%)h?CEWr zW@iw_Gh5ifM)&kNebABP7*XXHITBHIA8qV&U!GXbUo@%nDsuUU&i=Rd@+ z=i8i1c<3LxIgaf6j^YPI2A{sX#D57_jKjCdS#eYDrjt+OXC+e`(IxqC=37VpU4l7( z_N~bMAl%DECw}^JjoDtdxQOdJ`K9GFEL#>~OL5P7t3T2Re5whc$?*$c_@?^Y7oYV$ zzWeBIZJ#^>v)EjcFq6E=!30oG+-3%F!p|aa;;Kuk7iIxGCK)?gn#q&syvmAY;xo~j zfC}cQvXw2808J$I9hg;skfEvH4=LRa>M zr^~&75e4ALuQv6<_Sa0hOeR;ocJoq~xY;S{g=8l0;3J@7mUfe?%f8~_5-Sj=m+p7W zKM9I}Xy1cdDbPwV#|JdZ6|eB%L&GjHDSI~>K22NmZE;HA%g0^vhXzDc`0|nHZQ}us zFZzPrfIcpDO|sIjNP(C9$ou+-Ly?zU)W#&c*v^+852>IJZw|{(jV+l8etaV>)ztal zJA(C&!_?u~Gd|2BKbJ-+(T+~iRbwbP_5kOCCv?e1v!Sca7rBtAr_E*MPQrT(p(8I+ zLO%)FiGKJxA<20cMEMd94~I-l*+NgnIf}TLF-?-D&a^I*i5-{`K{vX?zN z9Iv&N{)+rceO^X0W9mLx=UlhiV~)V5ngI47x_fe*1dRO>!F6L)N|V3;^dLB>?;?!^M<3^Nn)G0_Xp zluyUOg$H9`c-dabN^rAKX`h5JSA$Ehcny#td9%oP3RSGc_-UeSp|l`~sbAh?&rbR9 z*Le_U*2G6!+dIih`Y-ng&Z0cDWp^Hy@p_JED3Rjge#D9odkcI1Ws!w1IkD}yUMMy%^vFq|F(W!dAR-f92Zegi5a^VNyUVBAK z8PKvv2Ac9Ojhct6;vYF;gActpPdh$+E0V^X#10L;#&?RxI;r}0USp$8e*-*|jLujo zUE!&I4GsE=VdC2MKtx6=5-Id0Gxg%#jO-+|>57jdX~X9qkG-F8051aVd@6qzhc%;F zV~dyUix7Ht<7>$$DyFPZ)eVOS6z@t@xJFRPmUTQ1>F5(;wn?D((Br0UTie=>&5*U> zo^r?SL~u>^P_V~2ehoJFt9fE^jrKTZ79aUMiT5gtjD7u*-23dmPxd8QH{9chz^9%7 znoJ&qH=%h@$c^B>2&@w_I{jjzG>Ofk;7QiHteHj2Jyf;(mt8!ILS3%Zm7%G{ApA3_ zsC(Md1X9zRdL|}+lI_VyN#^o*RI@zy!m=4jj|B%fm>2Ez`Be??9YWjZCw;|{ zc9$nDCI&EiytBC0CDq{V`pn`>4?xqgC`%ie?^^V7B$GWprB5N&D}y;!JA7~wATr<2 z7SO!9=4oB4cFC`IMV}--ugGl=>WJ1(nm9w#L@~cb;8l_rPcZY3p6Z8+4~tF^ROrL= zajtddNmj8RJ5gC9B=jq=ynGGv(mC4iQ$(``9$h|?e7mg{V9B~Tz|-f`aiOo}p5lGd zkLDp*?H?WN1;!aDIZ41KKE|Ok=rPI)p4z=u_9H|hy78xuj$AU0VJcShYD@=N>}jww zCeL+0+>21_6PIWmt6cq~H`>_tpXQE7m--uh+p^KdE`2Ai{V+@K&Kdij4j1zpr_sO0 zhpzF7Ou$7ulIT2%KI2a4kkk*T5Y?_DeVYs;kLg>8+R*KLF3;0-seOo9kWdyl4d@$t z=Qysrzt%_@{x`2W>OK)bLd1?oW>Tu_>BIQz7y?}{nLgwr~Mg-;lMsY zBcEM+d(e?}{A>cowvo3#Rv!e}Beq*x24P*_+kT&)I9B`BSDVY8d_80rz8gHA2z=@Z z;NuC!XV+2-O7f87q}?a+DPhaJRC9(TCTm6rEp$>aJe@Gv$*{xY@44242Wd37q5*XD z!eugxoHTw^37{uLd$-T*VbZjKnxni&?aB7^sfmmZw!O-VS34)~^t=Bga-eo4b3_YO zleltlc0Jf$30M#&$W8#8H%$fa#4ebSm+iHv#U6*>RERNqogm86EmbXvCB9dY4_ie3_M-y=71iGmFtA_>!z6j$A*c+RB(}yL zKOWerZvYzoBl#+RUvCIV*_|>yW#2(K|<$avzC8^qsW8i1#6=2JZf*6 zb{oEtk0-Lj-!eMZsOhQrMDDW?mfqmm$kU>!@AEG)Hr{7w(S>^W&#AB1Dk%yh*Y+@p z5MAW%WyAXza{&F68`IzB7NEbyau0mCvEEV4@fjOt zeC%bM*|2Y1>inInIfH(PcRPKD{C4~dMBtVHeg-=6As3w3Cd5fJBmm%aLia)pE%5@q zfOG<;E@^p@EW*TruIAyHjSv)6Yqd+98uD((7|^eq3185)tCA(8?z_s&#var@^K>p= z3!m4lj3hV<(Y%%dKDW>vVJ5Jlce&M~;o$<74KR&H3#tTAY@UXu7Qzq?KYB?jJiS>5 zY89#kYLnR>YiNIzz(?6Rog|SiI^8455W7)TMwd3bN(1ceB#Pwt-;u7eURg%ovwa(NjNyQWm@F9zH~dy7PbxyvCMt z$07Lqt9w~Pm;V8A>al1vw{`Gj<&*Q4JhIgNSgRL2Z!(*b?&t_NTeefZn&_p+hwJ2% zvqC*cvyGRwX>C1~6UO+`_0t^FGP^HMv`Ve7lWm@{aS!ZiuY0cIXFqwrqeK|cZ>xWe z?eDQ|aC}*5_x9^oV((ft67C-Nw5yI){@#|mk{UB{(Qjl|-|Ura%;cBVdHuddll{tZ4G5x6CQpN)Qe(2Gi1?o0@$#IF~CQ@!SfNX2KOFd3MdkBh=_CON5| zg?TW&=;c1Y%oq|KEE36C$h=dG?Ap27bh-D>v@}o?{Z=vG`DnK&ldnFox~Hx5gt~S$ zH=>d;wnq@#YElgj|17$dlthR2QKG#r&(bY145M4ABm}F?RMGDz8gU$!Gm1MJ=d^gbWCWSs)P?fO;X6ug_+)$6I~ z2(UOwNVQ84j2p2WSWGVz*VI# z8=v6Tal6uV!qYN~e$Chx!Z%H*7M8POC420zUrpV#+CA}L!+nshI`;8OhrjwY@>d!6 z$tBB=3DD!^oOhM4On&{~TWs9RUt>uAabDjGD|s!mJ&FwxHu5fz-%yVz0zF4PB7<+H z{`N({N!*iBFM`SgO5K*pFtfu-J2dwlEtV$pNeU~G%9Lp0G1*j-kjzBcJVoE7MCxc$ z3@}*nfs$RN%U>p`5AsT(XI>SvkVrsFABR%Vh8D2ZWy(47o5AX>^<+DG3&Znl-;IxO zd*}o+F=Ti2^n(H;ZBN~G=8R1+WnP+_L(`rr5Joy`Y&`gJ<|gI|=Cl)GQ69a<$(Y#Csa zSn0c-6QpVTciG+F#*-*>2O{?vVWD2is);0ukz9D%@~_UoBrL) zpSIiaaYZ1*>jq!z5tvEc0_Mb4H*>8E@Y}=)9~myImaH&)7-AO9TF9cnq9^$nnoBw? zpytXaky*#cHIZ%W<0Y1hxJfQFl2f0^?1lHV+O;ihdke}E8f6K`MOY_Q1f^%A)RzAR z^z}{jDGaik?tJTmNfwZnoKTT5AjZ=_gS&L3{*v`%CHw_^W_LfBv-Eq>w4Rc)U4q

f&NP;aaYHuk3cN-@0crzR6aYwru7wkF2M()Zn3*9Ip z;{9|UJEyLm#StalS{5J?ODi1BX)UCM!q-@+l*jI~S;=?0)AIgM!d3WihL&5tqOmxF zS6#y~!)CSzf@J)cS1UYYB*^R}D^B!t+7w)Axe{ql~A($Wx+?)T$`vZ`;{VT3j#e9N%(n zbzuvGnYoCR_wb|djck^Hgmmu6wC2v9RQU3CQOD70G8-|%n*^hI`&aHCS3085gnU~xzx@ARzGufw>bUx!7 zFL_~S!_2Z2gM?;zkaX^PPcUu8!e=2HT`V`B2#rn^O3>)nnJ6b*t!{p}RSu#Y zTa1FG8{Xjb+ZOMO*5MU}*c`1pZq63J!p!|&p-H1@vuLQym@_4)PLPVMe(Dp=W%%5- zN-DhP`^KQZVapL}N`k5Jq8vH={zfIVn$|iQrueHM!j)jJhM0 z(Yt~svq*e2!JQ8BEbPY3?m`HsD8DV!WbTDkV=U~m;>?@bihIY~AA_&6&a|vgf4z10 z&MvrN>%Nsq{;_rsU0u#McI~8yyP{EIYRCzEINsyu+ff%l?WH*5FCiQQr2H&Yua9v`f-|lh~g~Rj@6dFsM(%Q*=4tMswFm= zRjl5Nh@}C{KusmJ5-I2tg3u9{?V?WfD1@*@!1!?8FptJBxXw2ub^Ypw5W@zOVYaTi z3HUOIKYyx3Xsq692oO$bczw>vWR!j1M5*W7%hoiH4R2Svn%tZ-D}4TqV?WLdf} zh?_;^;Mq=>2e&RN#ku|>*PB_I*#am6tb7z-w3C>M!GD`6dI?Q3P`dPl@`~zBoCpo# zVlvZI-Ye+|W>KO(tKTIC@)3%5tN7$|No2nTST7$Of74&zpU-%^n26eGW{SYxahTH5oGIHQ+(+ry|l@*y6I z@Ns7F1C9oNxZfb-0~GvpL1DsdgiHB^zS{8{HT>^j((TMavn;`l3v8=qBDS{QHID6^ z`U{iv>KWgUN>MJinUi>ZlPZFo>&yuwCp;671rwSZvDW2y0G?$of4tSFIJ7%5>Uhvv z2-RbbruPaYE{aqV3Cu@;%+{#|@KN|Xj-|)r6(=!qgVuAM?7!o7$Id>>IQ3HtZPp*I z$epKv#HAK9eG@}!|4=Q6$OH{x#t7<&Hg;VeX-C|kA*gA-Of0yatglVF+KFjI2MUk~?s??4o1V)Kwir3bS)c;~<6gl2ZXKu$nV<6Y@(VJokwd=F zVien4u9;3}`M$T|7o2A+CUrwGujt*-vc!bUp-&m61CO_obwe!v&*KjdV0Mb*&$m6A z_iqnx;GAur?#B=0lzI{{((ECv?)~Ijx0M+Tz(@FP`-_6^XnHuq{lp{1_h~$65Gake zgV!YQa|*=95DOm2WQG0rrnw!-7Jop~h5H7RlW*JOi|eA8n}?h9#z!II;b6vC!fplc z0@`TWFq+d!n~p-b=zC#b0*=z}8fOf{M(`durc6;Nf^qqycXoE(o1ZSi)-MM4S4(Qj zIm-ycC(J`LwbKnfZ)S)uV%T1B>P0!&rT$_sQdud_6yiAmTfWEU>S^lZxL2~Pes?<~ z<>~N_3smdjhS>_ROSNpi@vh$Z;vOha|$RPm< zc}}I)`$z1}6A!zF&OWH~90y*fZ9nkHDP17~Oq-269U&xd7t;yyf8kJBOUDc7HcQOT z=h8RA0#wl4-20Ct&90(yhPjsuuMpKXin zg~9Z+Tep77euYkoM5R#DA}%W=9B_|~+EU){cDsnF9%{)`VkNmM>aPfy*zda)om^+{ zU*;vU!7&j(*}(J%H{4hs31jIj(DoqmeuX97{5J?6K-?5e#u7_UsPDtKF);itv*ioz zG6KAi3m^ds_Jma{#ya}vgfVvR@|`@}MY28vd@MB)hHLoz($+3(|1_nw_mN)F>r^Ww zGCaxlf6>gZ;FT0Xr*wNatgI(E)RlL7jf(S%DxqA znwB6v0iQ{D^9YBS;ODu{4B<0`OJc%-C`BzP437XIF6(7C49nHK4n1}AH6^q^{wYv< zS9}Fjz-sWk=wX#yac@(iY=u@9fn!(*5&JKGIm0&&nlxXS{u0z?nz z^9$)VT{3v{DURJYdPdKl=4kh@^%_V5sqZ18kHD#IP>oFI-}p z84t7o?|eR3V3KTG0Fh)Z69EV_sZ20IxghGCDHha8WSUSLrhv~DiK85((PYB$W2T?U zL6X9R$xetjR$QY2t+a#s85AWv)Rry);`{OR(@z`7;6BPVfU!nTL|-qs-~zu`#y@8i z09mkLfu*g*S;rY`jsKqNk@cDkoO7J?ux;zstrnIeYA|EQj8Jz6aHDcK#)UQ6St~Bg z01IEFj+zrxF~=$Ab5p2FRen2Wo80=Fyq|2OQf># z#^vuBr7RWzVY@ibb2W3lShOoLJE0Gt4hVD<8$>a5+2Er#}l^9tP!B7XoM z8j!!P)&xdlp|XHA7_ci4up)v-M1p>Q;HZ8kuD|QK)s~)kt3U^iBLa7f<)}%+n6Z7v zgNPCXOq~?khvf;VQ2T_)2msEaBU%@LP2`J+%SHiAmKmge{6-NFA3cn0A+bjfKr*TN z^#26_l4(M1e&bARVfX-TQC$-|yAPkGn8-ytO9GQH^_lT{%(ayL;%gBppeSL7W#$NE z6aeAE0BXkJ4XcI)KTI?Y?V-uwlp~rz)o}WQFe^;shfnTpjL>qTLVea_To74#9Rdz9 zQIB}xX_h6_n@VxLWX6E366j6hfrGZTMWu2mIyl7u4^qn_zJ;1HULXReZ(!Ye)3_iQ z18}uwIA_pm+A?ONpHqF1_e8@o0lH{bIPIglHR_LA4yrINy$SnF^<3w;r2;^pIllSk zo7RPR03_HyGytTRT`w@TLs6g_0h7)eO9a|v!Xn~8Rw*b(%+8bji)9!koNSzBeC^7* zW_R?!u5y}tx=SYYcaOij#m!NsC5{d2Gq#LNH#yCuh3z3~5LMA}q|qi!mSzS(0*whU z;4?QZ+q_!apIyYIQ@Ws+S?)5FrZc~jib_t}AnF|A$P@IvBUfq?&Yh!hmD^pgl-kn8# zQXjLl-K{n1xBd<7neYDn+>vgK>cx=#ZDUol``5PaP6@tjT-iUT9%ITFedhzC6%DFV z)~#I@Z37^1juDXpJOTi_X$%Whlx4e)Tb&{)ery0EK?7u>MIrhEh~#Ucci!@~UBJhM z0zHW4Q?X1;>&o?=i8CUXVQc(S8S_-v;kv@{!ZHnjkS&t?3IPI`-F2Bal%5go~bcfWsO;ewf@aaID)SWX=p3 zSrM3JraF1pHgo1o+XdpfL@KBsc*DQ} z2?$1v7?JdD9(hManUqF%?T%WjOzvlH$yCMc@JP+7PsrWss&?-(FwhnNNwxv#B3_%n zL^p&D%G?y8yr9h?>X9fwjJMBp01$oyZ2_R?MPGYH*`25d0>uaMw2zMP8i6zwzX5d^ z-$4}u06>KT_(3sZX1{mWPVVMYhFJzMXh0M`gi^IY(Glu#Ak_wJ4C_^BI)r%}D$U^r zgg|AY&y||Z$6>}9KXqhJ_vV^iM)|6jqYu!bJvibuirS#RI7umZ|KsAZ@rE(x=Wnem zcaJDd?Hkfj$R9TV0;t4s=NU)++Np!wjnjtN`VXt-%gjY(Mz0#8`X!wOQn;Q$$J$=g zjx=IuWlRtCx~>xsQ$pIA|1DK(;HZ$o==idRM+j;(YBK z+7whSC|N`(02x$=FB8BRuL6feI@Ss_K@|jSaE|xYm_zfbMcp6Apt7;eqXf#w_A9i) zmWcl&S+KGVWRi&BYXV5IqJD8UyWhu|3_!SUhMnbbzrhUo4fkOpR#>KGiX!DY_Z1A# zm<;XJRyxcde5!oz;bd)UZv%jEA0@FZm55xdsssoEJbrYqTD2FhrY3+2@@dYGB~#CvrhXpbiKL zJDV6|#~AJxooJ|WSvyv`tcr~i4%BO^TXdJsJzYz0&2o3`zu$;G^mZhR6@~MrNHC6b zhml5?ndDJQqdTEfnX4+_X&23Orp?0vWsJ}rdE>&&Uo@r7f1k`V$Blg?OTh}>fD-{A zKY4z&WdcL5L7~2gE~82HQB|)J(6ay@`J(cW{fg1XVFgs2D9YNE(n45f zu)Q4xSWr{t?%8WqJh0Ay1cGP)3xK9cH#4>}K$-`R9e)V8ag6Cd6f29k=zX&yAYDb> z%FoR)$`Vlw9B{N1KfYWkjYa=T)ZQ*FmyTzHdu>g*^@nx>YyegO0aDUZa1uc_zikBI z54^p}#tG0hP|*U~x?W=j#ffu`&o`?;Vx-1Mq$R=+63HtXqUgx6y&6UDl4!l4MSqd+ zS1G;lGaItqW<^$DR&`ePuNL)FGJiLqi-4fO41)7Aft;Z#9trSTxqXj;Ikv#qLto?A za6Doe$Eb${{vT0fq_nC6HlJ;&w$Nt)B1TqSM zaN=^|3)9+DlR-a7U+ZUE03fYJ71GgfG$1&oh`^vn#WHT1T%@49Vd!B9)h06|-(K0o z5P30^LKd`9BT8J>#ga$#E_D%F@zFUR&p0u6fugDihty`Zh-y ztlm>PT&PgYTK8AgX!HX(trVskp$Nzbx7mbb0E2V^5I_^@mkIZKOLrzT4?uj>Fi}tw z1R#mb0DkK!(d|U*A<97%!`o7&CoYtOJ3tOTbf|fvQc;N=0D;rrw`;zf;cABW{g%&#AOCe`upUt4b)2P(>w0v6E1wn;b3>^s^C_Co>yA2H!LBKofvH46Yzq-DG0 z9=ullqr-UvzXoOFR(VZ@kxlpIaYZ=+=m02B;#61CWTMq>a#^juM@Wx+oN1 zM8`r_uMGkmEDwhXs-91=OL0d)nMH}@@mqZqff}M2Y#aJoXHlSLjS3Wj)`CBJO7Lht6quq}`x(n% zfU~bFx^c$n-jNSNctqF2H9nIH+i^c3f{c!!Jv4tlx$UCKplMK>5K?33o_lUu zX1;A>aUPz3{&@p&Q>IKgAe}4Oe-N271{kz39DB3~i8`--w`biei>3x+TmgdI5YkQiOBH}5%Ymjs zIu*^SDKS!@4PXGpXN6|fhbql3KyI{XJ5EIZNrQ@%F{{5tGJ>nEQid^#>Fp3uSiikeK%v^4?q-3}2HgOS0w(txs#Z5e zMT$k~>M0=d5moaBj1ZA%%f9s2#qKSMJ*V3gx#bRW_x@_WQ6mRh(mr;t=3Vrqf?>V ztm24J-v%qH(of4}DVrC?4a*h&pdFE@jD+Rdsdlr^v{_3-+(n>8@*4@{-v=PT7naq> z_KdFOJLe8@r;YAwsfXL5XrE)iu_8Xt5hoGTYdzmrVlDv9Q#WzkFp zAeo#gDqb4$w44x!!A6+);vNs9Azc${$#jbeP?!tIO}}wzTwc)lIo_3R_&i>?+rzahuC(Qt`LG z;}iku>zc=ZP+nkXb54nbco8wP&NzKjhILnlrk(~!xnLhG0HK}CJ`q`x|KxJIbazKj zPzb!P%Az5MO9UhcK!%P#&b_dz+!1vkWi7=Pk5|?zUVD34^rEL0l(|)M@~L5gjs_hB zLUF*yx#RkpApNoVTU0Nl%5FSFK!{@CD3flMB80b|QM?aakcv2xp~>$h^2|+(b)Z;L zeH^e8&sY|U)7p(&+&|{6bsK7O+?M*ij=c6w^kJaX;AD3K)BrlrgdC;pU1TsrP~DoI zf%MD&^V$a0$B59VNHHu7A|ZNSj*IBI$zzQG*9Sl(is95ZSwnAYW zqDTXg4s4fF^^(4rs19JEk0M6wgN$tySOg;FDVoFnC>qGPGvkE19&xk?h%nyz zZ^rhzNqnx&S=3}`VY7Q@+xt-vzz4?SycR}tSE^X!)V`4oK*NNl8t*R=nkL&1T5AA= zNY=OhvD}UmV+ZAp=oQ+OFP%NYO&!)FxT(YDHB=X($&6E&*TMGga4=I8{i1*SnP{-N ztDkpSnh?TTx(#xTBhJ$Gws6124#zi43UXh;aE`-fCA9Y#kQN$0$JbA5@BIT_J^KRR zCzE~`?LC%<`~ErrNRmgWy)_x|AbruJv(7pzA$>)XUD|JPibrt)Ak`%tP%gGO#mxF( zPz3-U6uUc^3vYX+GoCkZp4+}@ojWFbxf_@-I#cyFx2<5LTU9|(HJrhSAeouw?((9> zXK!%XjkT_M@D$fFkiTQB-^?^qmxBygI5mjR{VYBEU?#J;xY)9H*a}HJ0QiV3p)Zmj z=$2OGxZSzETz+9>w!c$zo$I}4lN-@Hb=?uO+)$wCr+3_OY5|nVQm`tks@>Cb-f*vO z&2nq&l{#1AZD#FpS^)~w=^#?zYdxTO_+N>|mrL_O8xVKn9746C#>S1)hT3TTa?Uz) zj44`IjR;!aI`pR@ijvS~t3AO0$pC6;w{|ft3C=nor&MjB&6WX5yFrIRB;+XdakOf{+;aMGYm47j@R|BC-}~1}10V>! zX{T1VZIp;IMRqS}OAoxYNhylAM+E5VD^x%FK;i>>+fASWV1Sd&xG}C|{92DNTw_V^ zS%-dN6m6s!Bmg8!5j2eD89H^#+5ydsV`h33@v_MF1yC}In3iKmX)k&mjw#WTMFNLp zDbtY3c%XHPoalEnKz`$ygA~>2yEmF>-^71lA|)O;;d1~=^!3F95GF^02{IU~ul{|h zMcK$WMihv?(n9EWfVg|FnPj@4_$@j#-()HPAzJPu_rX-PSyfwH-kZO6ofbXfvg#}M z8}yd^BG)kCN>_ivEv}{Ofc?HZoZdi-=9nTfOW)E$Gi46^}RaeEt+uF$_Q7!1(C zJ1jFtpaXy;d0a{9>QnHwhbDvBW}i)ji(S|`#}RsR^FY(Vg#e)7?O@Zs`t9)S(;1V| zDa`CI^XJcZdse;bMii90LCqUoZGL|@ud0>K8}5D7RTbkX`Q7 z!JXXo7oT~+{#*M1;PKMR9d52f(KxFZ#r$TB?PC^5eQVurH)r`a_xiGpZoN{% zHfwB%*5I(xR-!|Iis@r|yBkj)y3dKE9d9Z#6xpG6E22PTVu~udpH$MrX69)ZqVEUg zj1x`4iNw*3P?vCWTP&R|lqvjPQutC6WXjMYclogcS=|h3`Z6xly;puvX?t+ zZ0~*Ti7Xv?^Z=weC(k`s-p8nRl>$ISAUH>e6hzLFNIwBJUFE=2pXBUueXKvFqKf6p z*+{HzfJQ|cT)+#}$ba`rse4ILqICis)ItFyVgL>RFZvE> zXw2;6U}L^-yk>0sNz6Y~G%*aS8|z|dS_XFSEZ|UU^*uOFY@Z7AJ5+0hbAqT2&+H2T z!g zAce#g7#ZN0A@u+SI^9$ID!<;kpg$V=B#ZT?662JHB!{Uia2Y&zbmD)?0 zVnG1nQ`KgdEpnY7`>4x?{@RK)i~3r7`JY^KzX`1@b?Clg5|V2^=jin5(+^!kLfSLn z3XoM&QeuB0?I!MKiN5%Zm4Kl`Q4BF|<2t@b>j-2N0Kq}Rkqgs^1iZSp2oY&=*bj(~)hBwh`@Lr$ zI1+@c6HQwPMFHxC*V8cL+il` z^oHNVqe}0(RB42%QjOz}1B{R!iqzFp2V3SNjx)=)buPcEnkX-*nBYb^p>LP&5{(KC zKt$63^#^a?Q(tiSKO=_^M>iRx9b{Z$radAU&$s9aS`dm8_7U*FcujOy` zM|lQPel=%}s9rTDET^Czv?+ikv?IVmERnPaAb|V%je`v+tx(EfA_R!Nak4RCR9OUM zK_TledRARSiybGNb*qD+aV0|XZ>JXU(gmbB0pTAfjCD9}zIDZ^30LsE$S?=K_wQhq7F6#7&oQDF%z9+PabLGJsCfm6X-KInN ze$yuXK1D_4I!NuMOtBzM69AIGr_2>TaFNTd*`81rn{~~tx$Y^~Qj}WFn1ptc;zC3R zxaM=cqhQ^hNRzN^;adEqMkKY7!KrntA)bQ%C%p8FZ0FvZ!ZEsBmbSP+17%Bg_ zQH5pPG~ir%od*|K((2+^``N~H?VF1XT+?*x8lv0BKC%}+;s$l9bbUKFy9I8v&6H9Q zj~QcTdNCYCgsTWvCl^(?&UHJDhSfY$V)UX&I5@K8fsgEi{vg_Gt8fzzHnn89uzG+; zzI7revsRY7S2Yt(jS(n1WPxJ&g&S0-qN36j7iGJzUpdWcTpZYn13y_QNA#h0Ho6rO zc9UHS&_N-*Iyu7QhUv zVt-ckMu?5oG^Of@R_`^woP4-k+80uf$r*we|qx2KO=s1&m0(pN;B{YXo3 zzyUKvQy9MnMMrSHIe+|bgV)qGAv0RB_C;M1G%t~JtHmM+WZ;4-^=W}KwuPbD`1aE) ztVrWV0RnTP^*NCWqDd@ABnTafMTfL++5$yvx{@HgzP8+e#BN2+fJ>(3kfRTlAcbx} zML>uKkdX_pKtaGCUp~S8eAXI`ZIvCrs&HuA11( zef0Q&23i0wfS5yVnF>InGv#%A_6x4llD{Q2+zsO|cY7|pJE?WrV_|0Kx#lxT$2~dI z4B8XFH4@Bl?{9BgD}AVsdXTK9xVX5zo6xbpb{c^W0FvZDb76hyrI&2288c>tUImpI zK{8We%p^fsO1B|0=SNRn4_;$LJ;;Q`3}YBZ#DG~Owm*IP^e}c|+oWiuTkxm=NQLWH zAgx9AIJa4|#zX`L2yA$|3x(F;{r8oFcwAAr%WtS~%>$2BHmvhR!f&0A%sv1WEuPe&1R1Wvi%H9P39$U3_w<|5%?MC&;a<_l*BsZp& zOi;GM-Uqh#mI~o5+En32$mu0h5)AOXa*h`P!Rh_un;YHh zs%e3)0VlVnu0b>@9KMLIfpoe=EC3GZ6v$fj<#R?F$O*P7-s?S@egEG#HY&5z9!oWg z<^~!QnVq0RF~bjlfG&gqGKdh6W*3LOKx0L^WTFhr(v$L*XaMaZk^%UdIH;Rtogx!g z&;TIMy}8gmw^<1Zy7Vxb(Kc-#3fA6|yszQCo{;38INb~lNvSm?Jk!VDfmIHJU{Q%4{Hh?XQVCg+Tf$afOPgiXX z+WDG_De^ggL{C<4tB9o3RaURgopN=oh*hag0yM`ddBSI>ml&9#TKl%jdTS>D2k;Wl zv}^P5BUgy`m*Qgp;7!u=kISV{wpS8IDh%gP&dN^l*;N__pKLqxpftY=p*gl z+f?;90!oS$I2&2i;yym+{nq;kil=!+Q@+{*pm5zF>s^;FT^z+M z?cIcq{k78wbO4Yf2RcZJ!f_7ELHEsKmi)Qrp0l@z`KY;(PJ`=-Q_Kwm!*Sv!PYATQ zxY#}m;{ojhJX#zHfLvI{%y#|ar`?de3O6WgyW7@zgj-Rm%Fc3haoorX#LPQ?{RK$+ z$dQ_uy-FT!57*Lbgft+k!kV|g!y4UIn>`n$4B_0wi4&v0w(+E3V=#*t%QD8nY(THB z+To}gK3{1>i%9({eE{uRys6wZ@2PeJRXFbZA2~hYS?0gIwZXkD&Be-XRqmJ}-S^G> zlTH|CcGBP?_u;7n-C$9P;zdAk{2zRKqY22#P_;{ulstK&^*S$w4LD)6?)%QS-kP(I zqkHvn1KlV^18|g?!EeoGF5c##crBAq9V!r1F^&%r1*lZ4j#Cch3WJh`vkcfk%nop2 z7T;5Y07Lu%2mm8E>?f%h9*#dci=Y8Oell~BG%Y!9dz0vCa{O_&sR&-Xci(IY*VY4) z;QGPWwnsg%Z=yG(&>f}z^SeT00S$@>$jQ=)d@RaYC#v(3qB!&oFno*v3g^OH)kh(E zLF58j9w244-m~qY()0Z2GJ$H*qULH@qBbn|^lJ+okpZ#_)hS5;Kn9S&`cxx_mWBcF zpkmEaotxRqcbWj-LlEB=mW%E;V2fjFAWh#h#>eP<`ol*fNgG%v-A0B!jERxxnnRDj zyT#r4&lRQ};(X-zS^Kp-kfUdQmK!0w_t8-ix*^+X%eXdqaN?hXASE7PZ)>~3?=uyE z;K1U@V&@dCc7=1kZLgDk*mLH0T*H(blU*&;<$c67(~3v>L8I;%6Rl96ycpbn*B;N@ zPkrVqqD`$8L~f7vbnGL%5$FIQNseuMQle-Y5s7D>dB$3aNHJYH474)LG@!-6Y{s^@ z*s6w;`HG8ANlA%)7sdk@ak!>9;AHm-%K%r~SI%`~ve&zzxjRfWy`W*JoWZ6@u{k+l zIJ@07yG?r2ql#)=QFW!s*!Kru#|0HmErtUFO{-6z z19c_LeE<5zH5Q#&t(3LsDKM3nbKP62+|aJ7wQ&78_E{ni&n_u*uSkIYt{m7titOOL zL&2if2978N@X%>U`Vtp_JR?fey!934+%iMXO!^*;S)-n59tG?0^yH5kKwvESM^)`U zi29{pKs#{xu>3* znDr;}LEivunEZF!AI>@r>{*yAadAV77)084;4A|qt*f`-+Wedp=rida=y zgaVxfzf;Ua_G$B08| zaMS@AebKO+5$*Cu6Nu_y&=vuL93PJL6Q4fbFP8S_)&K|q`Xl$vcgv;S;h57#s9}s3 zT|kS3?&Z4U2U(WCcr-7r?>-9LRtLCtd0^t7g8(Iwl<8c5xegQAKH-ED+S=t2^F0(E zs65#DEwfzy{QpU*?ezj5bpj!WlVxh=GC#&7*&$lb1lgg8KHwKHxr+g0!(e^b#ycJk z`3Q6XkR%TQj=R4RhDC`AHi;YSzy9?v`-l*IF#Tk3xkO*HJ$T22{k>qH*+iUTqASdP z5EUW(8fFSU!r0_e=O#^kldue-cj>yd?x>cf;=^lZdz-Wus(QYrd7#@~ixVAjwxGt8 zs7^>xO{qNB-mazhD3^%-gLd0KN=q$mG3kpjoEZ44(AxYy63HS4ICy;iCUdCC=!8Qr zd9|zEwbh+5DBE3fLE->pdsUsg_ocNqt6jSD{fg>1@8eak<0#R*DAL!O2>qUy*4b=3 zv-3D~v}vaV;Ja%hS-Z0InXiR`GYTb3Lurm54s1S-uP8q!sOa7masXo)DR+PT{A#yK z;&Ui8R4vCCw|Axe=(Ts&AHYNkUvu!a?PYQ{y#YX=f1yfMn-)HUNa<3Sc1X7Y?ikR%mGeB(`nshkZrPpvV?kmZ%L* zFhGYfgC<5)2MQJugYlxLT{5ws`{1P3seNqmXD_S~0NibWW4M3|B6Y@@B90_Y0O0)i z^6>`9A}xqK`joX)4e!yj=ic$4b@2@#_<>))Wz;M{1xwRUeSAP40UT6nr#}%&SeDW5 z?z{fj_&YerZ~S$aw4AXfVu<9RYoTrn+8g?VR)+Hj(Dkz`C&UF`zG<9uTo;1?CHR^M zc%lG>Ynulq!DkOr_?`#|0EBDr@yCY;-hBVs>p55}xQ)w^x;g*T;|7%Bs-k*P#w`HwzrYK*;hYjLV!q9hh^pnWE2455OKnWX<<{MVznIr z!i|v`GAe|oYJ^ppttX8j#to222igTcvr5<;jRFER{=zastIUu=V<4MYSjLS4`qPl^ zxo%SD&8h>k-DU3-D9{d@@_V{HSp|wPG`WKMT`sFp0^lxvM7y95HXIW09=v16vu_z^X&t9V_ghc0B7hr&B87F_^u4;>VbnlWc zF|@KH$rHD#<#PUT{76ZQ^U5DJC(tU8b~e`RI}Yp*pIId*yT%0D2%2dpP9!thL=YxO z_i~bGOJumhpk0wY3M!IzVf&{NHc=$n5}EyG7GKmOElU=uA6-7dKDP}79st8X_{So* zu|`Gwn)B7hPDUd`XHud5kOmiFIkY1pLR27UpW4lSjyaoz>eNLA{0JfdY7wI2q;tOU z060Ofa*LuL@c%`)o`|7Cpb$AW}kYuhIe-Yh| zdMp4vg!VzB&(X#b9AhFP|EA*$#Vriu{Pf8<;sFr$%Q?Y#5ed^ON*A1^6vcV&i)W2E zfO^OBoL_ULzXA9jEsfA5{rPJl-$xtmK$jN;CBfGK6raQ+dfn*v{NDHj@DNQw@C#7! z0EN$5YfJR@4yX4)0CHYuY5iXPNlMMDoAxDFfAZ&3S~skfGBt64A1@No;72hj>Gg^J zyY_gd?7&4AU1a_VzbE{Z4$I6D=l~!|9@nraQLQ!O*=L`%n;OEbSk#@?*5x~Hh^tqx zwm)v57@<|b2SUuC0SbH`ZZcqnWq=&O4mVgo+Y!dTi1ZMNpm5@pk$qkE+85=m*1D{! zGM81eO@pJl5-MuYQqWz+uQWTJ-%S8yq-z;A%|1`0O=Pq}#Lqqe8@y(m>03!jiA9oP zIroWdn`I8R_$2~+(&lavoe0N_S@UU1lZy_3bAvz5Yu`p@{&7BWmLFD4jirjpKu4nP zMo-PUuijDZR&LqtdgQgZ<4XFwTW5?Eg=v{)VAyxW;TA|1@cDqKL(rDI5rz2f%oWm9DE+E56M!75h*y%$N$rO& z1&A3SJp`1ePfi$Z%V;ux_oOfF#D*xx4*EAN*ZtUn$?id{-qA-aV>;GcTTKDif zn+!bZv@oM@8V)qV^e42BK5@p!g#^1T( ziYqMRCsaOvUuutickH8mN1y|MBst#P2-8W4N@Vwl(3z!X<}cX`0**dW4>+9|X?zK- z#sf0kG|*?1$Z-asgk{jYpnGBGpMQQ>yD@qL;EQpyimG*$E^FIjm$h@Xz(-V8maYR` zb6@2j?=dW?_IQxPh0@P{l0}TD2hRs<=@=`7=l@z(wHgL*t>IaCrMBRtYD)L6LJp|!=m)BV1hKMQk$r%$|ukPJU01QweMJ#co}ni)-&GL}dU?IgPrQH`L{)+gTEYVD)?H%=wa zG3j?%_9#)Ex=PHCc7oa>6z9V^2VAfW#S*VQZjjr&ZHFsevBa&ZR-wJDezpyO8bAyk z3KSkd2k#jR01ii$iu~R&gZ46;O6t>~L3Upj{TCqZs2Ow^rGOWnxWPm+y)Gi@{@wO;iTgz)K>e5p+ zKL#m6b)1Sm-k@T9UjM@JW~?HSqW#B}egE4-3oX(Efb1$z)m4!f9Q!>A?EpRiS^gRA z$G@LH%Je9{E$My^0uUx*4)%BTy_qXb@K0n9x*UfxU*{>&!Lb4%|0TK>fFum#TJEDJ z(0KsB%<^(==5tStZEN2+_d!q+{rXU*8s?f6tQOw+;j3Kk`q$d((th7J4xQ#|KlJc^ zpB)ZwGF7+Z$Cd~L=O}u{cz%LkHjL+|pMKhX_`@HzL=#Mgb^wqtM)~mAX2t;!F5cX% z!Zc5bg0tHm85-a|)33>sCnp>dWqD@i2^VABtSBtRUu!>TZWNnqf)AFXXE~z`At`!#-+v{Yv7i;+- z03lkG?5rnMu>YhKuhh1{sRbn9R1T3S9lFs+rVcb()t}zlY+0_#`2Ex_oQX z1&|7s&zb747ohE3(Bi&u-gq~lcX#)b=T=(;17{9>01hhYZvhripr8x=Ty-M6101WL zEDNYuxT(_CrDnxs&0e1-`WDXbJc;SipL7$bAcGgh1)o}2=4NXhz>e1=;Pg+@dWhLe z1YZ99&StkjDS8cjXgU57l>yJ-aE|Gn=PGuWyOG^hG5dlOjg~`7U-n0KC-w;dBPs-V zAxjol7_=+&7rGhR3@W=b)2^SIWxkp({R$K@#smEZ1^`*Osmesr%*;a#3L0bZr#Cma zMG~HSBU9U@(uWFx!xmGvrUSZ&D)0D&0CfOBa;QGuoN@gt&i=fz{BU3x#_#(H5G^iZx(Xj*K7L_1*;!vmC9&xz8ExlRxz@szG;fWrH* zQVmB}3(wi`y6gP#)h??gl0>4dv24*bx%R4uT+@)lFEud1fGaq5Cu3<4*3NW`dWm6LWSrS*cXmHv>*&> z*WVQ-q4tS4I;Cn=WMRxu_c0Y`yz9Bu4yTr=kD6l{( zBSku0OgBTDzA!@(*g(CT)&R)MD&9%-jPWB4F=Iw87SaOWHoe%Wc-8?u05Wd*%R)C_ z0F!e}L!(Sz5zq+bj?8LkM(7(6qp&R&0BLKVj72P9;y>eFk?15G00kft52U2({1JJN zt`?rV_)%9d^NVeQkQUXh*>nC+UE_o++8T;O@_lJ(sohh8pz)A2B&41CdOJ*bCaPOZ zXHy<}=plF0O*fe~6*_aO=U_V9)UmB_MxX>em{MFl|;{Fl!2ZjCin4>*G)Fqra9K@An5$c{M zh%Lg4;}a8Mf(z4^Omt#SWY1of;z>xp_LVC5ZEwk3=s zKqfJ8OQV6MDJA_RRxUKn%OZgmqA>jx1tL4y4rwrO-ur5X9MHjbHi(jSlqgoF!BtiJn z-Sq5(*ES0NqOR;8@o<9_;Dxm!}#*KMteXme-}Q6scAA2_O?YTdjK zln|)@QPDu6c^rR?^9dlrpN7fwGS^NWY(Uf&2=M_23yLV22)Uo6!x$^BQQR{;D2aYf z6rlK2!|?!0yz4g9nON1rbELt`fALP2vu#Ptt~T`@@9NI@rfV90TFmbchY!OzW`{$+ zXana(qFSr4+WeO%Pq#%;NBh9OoHiajJTv=^u2_~V$8nF^{6Q3Q(mG0PovY=isx z<(#$dvH6>gM#bkuRiH8HzZroN9PECb1aNAy+=Ris3@FfdYId*>s;DoQF2=HAX*`J{ z^ibUxoN}D{VFCx#^ccFgNMdBmkz$E}klhl;ZI+UtXtT zjJre;QiMd#I#ePIT9uk(4m?E!qxXYmHvmO|6x64aRVRfuVgK{mdZV@hCTTy21x*mz77983zY9hm0EBEsJ)pHAeQ+6d zW3&%IMUH?AAcVRzj33K<52 zl()|1SC-o6EWb<9oYIEw?$u5wxh36BcDoz%3}8T|LZ5QCsDFTAXnHrR&IzEFegQZD zAs%?JLC$~L@`FpqwF_ z(Ln!TwN|N&&F_Ezdw2Wox7*|?41*2;lFBF^8S8WakQ9y+Tx2fZZABzf*mTTQaMW?w zp;1AN3K}#Zq8?oEG3Y-mhcldt@q>?7R4Q$R=+C)PAQC5B zP9eusjpI$aUGyf`M|t zBO>l*Ih&2j1k}ZxRWuXm0EmR(6lzl@C?`WzZnHj+$n6g*b0u$c%Q`@045y1gq0I1M(;H>A%nMP=j1_g=|Q4At6v5eHj zP{3Ad{4pHi6BT73tCz2z;@A6?z|!l|LzK!vhO*^pWE&LuK@1M{>C>kU6J2WmtWJ#i zmlOe^Xd`qc9DWKk(%F{1g(BGpkuQKJ&uqI{>*0K()nP2p9Mi{r?~<|B9Qt{`A_Xt6 z+GRkL4*_|c8-NHvSu6u&-SNaSi)sKeI93=`KF&4LF@N%uVFt9QF~hhJ>G9_Y`W^a9 z#OFNG>&RY)HPw{6U5|Xu71gfS@yc>J^}9{K#qzZ+xo%f;7uV3y;+OLP06+jqL_t)k zo7Q}#Nlyj2ebO4a{J_7BxzYYMB!dR0ff~->UA`&TVvei|X z{bm+?{P^)E4rgI*4v5T|k;nLvQaG@rq~xG}u)e6CuW4Z$58;9FV;r&R)2G`FDumtG zje>DvCTH5TX-V&bn=xq@*#?4hjNIseJfFfC2Lg}-jRFlwx-AGmQi&G5zGkO;L6HfB z%FNqv*N?$>_Oc@7r<;Z4t9?se zzgjlZTj?A0J$(Q~Vm$Jh4zqzW`U5>|w4xw?`uP4cy69j?3P9E`Kv6Gc^P&z4jyho0 z@1N~r=rR8Ll~PNO%udjca2}D_4Dmh@tRG%F-Xb4AeL>E*z$ys~04Eq=m*_;Xjy0g} zy5p54Oo<}$p8uw+Uj2qEtl#ePvLxW?RNxwNx>&R=yQ#+IH;bN^-N}{Z^mp5{`?x#m zZ*)6cM1;<^0XP7~e`<`ji;h>Rs7}7l{VD+w`p>!HqaT0y#N@aD%Nm)+ha=IM<+>5f zp5- ziyb03xRL%MPlhKPV$wJstl?-gyMvP*W_X#K7Lg?Ej5E$K5v09I^8;fAsA4APlv7Sg zYU_X`B0>l%F>Z#8b2ROa@nYN#Hp&vOaY4FTD$ycly8k8`(mWM6#L=Q^IF->Ov(u53 zv@BCAXBUkC{COx-by8|m|AX0goJc4#IKnM9sjXTaVpW}>+58_|e)K-Be!M=U`uV?9 z`0qt!HzG?CQ4IOfCPb&bh?NJb&c|s2KR0VuJ(gon;lRI1h)$*@X8ZBJq2lcI#RJU( zazvs8fP@JuT*x>91OQ>&1o<2a6#`}IMWBZW8UO?R2H=i%LH|kS=2@=&{Kr36n5Z7$ zLpwP}(BG`>Y9UTCS(}PP0lP?16pA~t4$I>Dz-!@e3snAcS>S8!kV#zd+dg;1lW=#|)Yi;4lK%S`0*S z{MZkg8Zw5hkY1=lsh zo*K<$S~`4+WXI>OyY6y#-g&1@7}AzxuA#~9t7G{?I|3a5B!%&h6_H3`GYPLky$poq z(60a@{9(+%BQnP!PS=mr*RXb*(qv(vsbPt2oa77IlSl* zph{I~MtGf~4CoG^=#U+Ys^d^(wo2&BEHw_I{5{Jy)hI_!li}{#sRP_?XGLf`ZS^CS z?-5|*SidCzfzwDvDST-%VS$6FyMeagLOG43gN?SCqF_C@RDxJ#Jp!QAs*VZA7iT!= zj3ZFTNXJS)p&FreU~DLMi2IJ--40g!x+>~{PJ?5|b~v}Z4hAs5G2wGEiUDi@zP*$h`Zz_EZa=fcGA0!~ z`6-vZbCqi@-)Iqz@|MB~h}3#m3OXKaXBCDGn3;GD~u!xLa z19FJA05XXckqL{!oZq@|v{BrG{SWhXrp~5&tsHMn;bwop$jy7guhI2h`07?mP{zxxrB1 z1OphPJ9VvZA}NU%E?j7#Cw(f;Jk%K+FJ9xwpP+gPssnG%>q}_zQ;kP$RUn94k>NH>7~9!JWT;BqA4-K zvVag2F`RoGU{c~T`%Tua$wRuE5I(vgWU_itnUB~nZ6DNKbLASB1**jXy-7_n=Q}T3 z&br1!l^`^uDlLd8U4V_RoU?!5pnpBNV5`*#!C~GkI+AHLG#s9NjSjG0=ag zcurpvH5_~*Hcx3kudUf-eP**b`|JbS5c?(yLNo?VMzlTi{A~B%OSNoEf%=qXqHgpk zWCMeuMQZ?|RJJFzF^>NrMF4($*?6O40esj8VsKIs0|JSx5EbKCAugvKg9NgMDbj&x zo9GOQ2&kkEZ47M*mEqA65kbQ^Zk$U*(x8|@{pusYLCRr_ZA_O2gMI-{ayGu@@?QE+ z10Z`ETHLCpKIHc@(8O3XE^I6EN*SzjcDruP$~@LG*gep6wtG73bOT(Rdw>uCHj$|l zls5T=WjhRzv0si4<4Xh(?TJrG%y(g0rUH=7DzM0;3?LvC?Hw$JATSBO2Ba{7m8iu7 zC?2RJlhlKKGD!z57nT6`hD5@- z;*8=v;_I=Vpor@(9r9h5j&Wm$^*11ZIK8#msuz}RmqT4H@FM`E8E@z>aPx6!KdOr0 zL}OwZ#qa)I!e+n(ek=flb&1O0OylgIGp>)aVU--PI-uk3*=q$7YE7gKfPubMDJP%V zZ#-DGhpqspyt-N847vGzyXK2tG{D_-$}rm|ppBx3uL}?m86vU-kZIJoQ6EH`G-Hf# zav3ii+G7Qb&X+?=lm>kX5r9PP`!iR#C$&$GS%Iq6Lpj5U;t(MrnZQ}<_qQ(`bHFBN z&6@4*U#=9ruF!3(ZnUTkPWTF?#iidg17{mL7lVN4n@Gx0%98f1B1ZHJ^T)GFfE8NR z5G_YPFw>@}<7Djms(=~^0T}N)MI&29SphMvpQ%A+8!37MkE`6iIJRrz} z5olQXOCNKc=HKtKcPw|?Te`a~4P9M>g!POw+rt1B031L>?|hw?HKlHy>+ha!INsgU za@oFP!?{bp8MptuWUTwqbE^%A6KUe`u{GMk?*srsR4r@^lgIPsE67doU8~Ir{n!-Io5rJb;p$Nk+6C{{~~i zF0Aa7t&Q0ociiEA`O9Cri!Z*|J@Ld7tu5N|-4Q+l9RMVS1NhckZ<#KDir4&wVK|-4 zAeEJs?b|$=t*8PVCg&9goG3`T($?;4eAEj<@Dy~!2=#`Q?vEP<`RJL6Lu(St5cm`I z;2GnlNoYOMOk&AKSz@)Jwa>V*&YnHn7D+}g^N6A!3nju{DPVE5GDsCFjVg}u%PV)7 zu-t1EaNu#maQqM&<49h2{2+56?|r${y}53eQDkTU>*GXs&T4QaU7Ov>P;Mw(2zX(8xmh@{e9mmT zX6OYV5TXlVm4METI6c(X7|Y4O>VukAhZ!HFt8BOao}4O$&tT~2*~Nh_I>by z^X1L0ia6C3xlNUg24eW$_aDj;(FdqV6e8r9}dlczF7g40|aP9$}L_MhG zfp{AuiUlwkrE})u ze=gc)$C+gS0=M>f%}px%yCNVfTv#L962f%1g80G;8 z5!Q(lC#G!|L>d3{nN@b~M)X_!R8kqR^exj+ZZR3Oofe937?iH{ENDOl*ob7ohYz<4UOM*|y)B{uVP^!2+@O}F}?sU`pgZB zn{sh+v4P5D!t#kmS%Ujc=5-K&B%_!4(;Mq8E7CeeJgCy`XWz+`L=*()6UVbgGo{d7 z&=lZ&eQ;8Lb2Mq=90|Z*Q7TqA{eTEW(aeBn)z@gYx!LvW+uKz(M8E_y+stq?lYY*) zzWcfexcQ6fd7#5UCxLShH3?6^Iz%WKstNTF)GTCIFLG zF#~^aywq&%GhegSePc#Id?RpD(O1y-c@k< z011GRg5baj(S z88mcIYtvN#HeGFFJN(WN!nX!c{QbAB{oED*IaXrd+@;r<1N>3J^*p%HsE%%5zY#Pgp$B)QB?|ZFTcije3C`e`cO>6mjmD`Lz_UqVXW8 zhF8V$Krjsdo@j(OA_HWSdPFnwRQ<-`hhnsSca0ny(O&X8xq&^D?MMIuXAS^@Zs6+U z2AZfB+7(d)oOhhNaygizH0wP=Q5KwFKnZjlQnZp{7AF?R6Z*|%$Mko3K={^$W6VKkLqDIj#^_&wr_PE(;MCC%4WBu*!JQHu z0C3>MYj_Mq`6vV04je$n=MyTjM?H^dqwdO2o?mU?1C0e4umCc#jBz3x7sUyQS_KUN z0?0pl(lKsjMV8eU0dV11GgbgR`VNqJMgZ&giZUU#2UzK_m?#^7VxFryLLotpyQi?R zFFdrkH9&pxu)s8|U0**4?Cu_x;k!u~JJC^3x>Acd$1AcwXQ zc^Y3>;qGkuFE=`Wmusr6aI0Gex~42Lv_;Yq@7s}HuN4+V$yAf7*b@$3FHkci(;YSz9_DGIInv07weQ6^9nb zHeG;#nHVnCh?%_+?LcF~>HD$f0t=0_UW&_y%%Lwj|xS!v%MbOw*9z67aV$$(U;l&Mw|MBAaz9rMt+a&U@8F9NjS z+#y(=C@K!rC1%wZhyu1jjysMu>q6y0;LXf8&M<}d{0ugfn+P>1+o)h81ys;m0A7ex z;0i($V}=^%6o-<}hRdPHsYh!8MQC`DDt@n><+3-=by=z*;Tlw=Q@Mk;R5iIZyPMtG zntV4eXOdf2c(m$@G#Hr3lcuFxUW@zeITPI3(p3Z<&mTUs$|5ynbHaH=tj|onf(0>6 z%`(THO6k;8nKG}5*?vqFKkbwWd6yATGx7nyjj2G0nGSS9%*G2^H!JRP% z><8MDFYXuo-UAQ{rM33k;+TE)@g<53MF1kv9W*gG==w?^EK)grxSUpwQ%@Z``o2TQ zqfX}skpzG(eWDoUZ~$$T&0fC4C|PxiIHG3(d;l^4o21%ZsHoJR-`-@I#h__%USLr5 z0AY6)JmAjA6P>4OovY31<~F-Nu3A6|Ef4MV);+7*4a(Z#c4YT;Ym}7t*2d2XyhXH2 zL|Ygy))}fck|LO>9!Uf^k8sk73;`U8&Oy=o#`&ZDrbBxU1AtI$agmNEKp9Zacw>M; zu6O*-{&@W{s>u?e!-dhgBOQRWHYQA5abFocc(DCN0~Am3N;K6l03|4tj|MAz*Iqz? ziMjvJ-kHExS)cj-NgxY^1hN1L>j{g1Pyuo3LRADsTdUT#E}v<=Q(LVc>+PcRxn7ss zs+~@C>a@3YZl}&@XKwAS(^}gZ>rz~CU#f_Lf*{IHAZ!6b*s|Q;_j&UVheL9b9L`BF z=7Hp#yyt!Y+xwpP{r#R51uOlQ}$&u2)xHd8NBzrMvy!_Kuzv=p`U2 zoQrf30>C#!hM=~P)dLMYLFVx>5!~?5l938F(|N~3Ks8$Sj%1BWVfk7P!37H~EgCX{ z-ZLS%%AwJL$N|P!OCAsif&37qhU32DZtK?<;Lu;sGQ43S$^xkw8B z>ua{xc|1yFU=1LR>ZHHf_L8%c&bWLX7+ZC$}+dvn07C`f;ws=^C9|MYJ@)e>aw3$9O&1jnWDMVN9MPxEUEk^sqhwxY0%f^hcHCt9aock9`Pzgjaw#7ALG!9E*k?(iMO< zKpN7;dC(Gg@Hi=JvDn1R{f|Ct3%AHsEU#Fa*E}aGb49Gs_Qwn7=+?)U+lQJH#Daz) z8Weft+;EN{J6KG}Oodkc*NUf!<}WJ*`-+5c{%~C*jcsBd^hf1-Vmu&Lv`5x5s=;G1 zdqA-+6jHD2vd=B9vKzC0W&QSSwEP1itht4@W?zBrY*ZEmo&SQYdMnA^ zWdj;_+4iOZR+BT>9`1LcJ=OGAZgs<5jCpX~mTH{1jeY;TW9$wQ%grJ=A*QFVfFRcq zF(G92g3M-GGLcc~n-9F>F;1kK<~zDrP2Tkmz_6rs+}-)Xs5;v$a-CY;1;|IZ%+SmO z`sPk7wJ)D|P$LicyZ7a_9>Bg-z#GBpz!G|fB!O>_oe-cQn-X9RaDz;hYY}7s?ft^F zJKbu4mK=>U^)ql^f`HH#htw%pd#2oi3KS%dP#qiai+d4(kTJivaksm8;f58BBhr3z zJm-*rX%4?C?@621uiC~muC~F-h;$&o)VA9|m8t7%TWWS#{=UtYdtjH;bScR;?I`st zo;->&@_iv^r;jVKi)Re;zvF+s{NZ*5%&+r;hJgGA<}2bCgzg|R?&78Ph^aVE>y5S^ z%{KCqs*(TG=l5IUorBn$u#3)cM$`)W+X^L>56=W^mEMYJ=MsTvtF^SiVf?MVl4|%D&#(6L&NbvNQtEqy zT=SSO)`}mFUv5Jd-EDnU^}Ju>ZmZwF*Xn&eb?$W~*2^txM^=$lHw>^h@@Lwb@t5iN z{knGKLZj;zl1t4Kh!yi7#WLrT}@9GccA+Ye3NIquoFL_~YFNy0y6<={B@* z`~<<$f`uuag%1S3oQT0H6=Z2R#1hbCX;<%DB;3Q}1GdEGXOSl=Vsb5#s@g)8Q%*Cm(73 z5bvO7Tx(1kUNq(9(y||~*VmMZ=S>BW1M08>a4arWw2d!10G4s!DgxOcRVYA_>`DFA z)|j#a*Sh~s>i{^e7NBwqjsQ8}9l8qq)UgCW=O_rh$gZ6o^Wb@`0rBo$tn+stS>~F1tOZz| zaFar`TuvH!Ws{n80uYn?85W}xRomjMNo981V@iX&VT)~(p)WsAq(m_@tUc$LpIgs8 z#>YdOjPsU9m%DWeKpvgnsJb{YKJ*1}CvE_X3;AA*bB+jJ^K|_)()7~Lt>;wQ@_GMiW2+yRg(}-NZLP8F z291|VWarwR?0#0;kYj&rJk6Gr%(V-qmfLwsrZ8XbU!+b3e2-CoR5@o2;st`cNn{0Z zjukH*N{RUPlfBPGN>?m>SO4}Mce&!agc$2GbITH$&%S%kI1&DX)$5auFV)Y8C8Wwb zR%Y(+JxQ<-U@3^jVxEX5Q*#3=v`0|*zIH@fOEnx%QbN)dJO)TxkIQnVJs?^eH}kph z!VA4d*bO(_V7K3XduzM(ZtEc{&`Us4IFYFm0{klpGAGp?!VQ3+@?=Hs*bglkq=i7m zOyA5i?M}pef>4MMGxYT7)16#}?df>s#tl)#IuQhSE38)O1{m>fUT2mv zb{4Q&t@dlBfgY`GWK+To3;>H3c5=l4S!Q;4wQo}5GA?RdQ2Bd;+_(rXCr*Oci>C$t zu|zN)EFexKq(kT1+S?E2uL2nisj22yqZ>l>5}Yrm6=u$GV;#!XQ^ z`q(AHR3$)-kfxX80o(l)YjdVj2CEa#sKq)G$MM-u3{io+2pAJ5@^b|e1MDGd6#t_Q z2nV9!_`@{rlL9FTSYp)Z3{e z<;wQzV|HN2CS5N|=i5|he`%U*FWOWEJr{Yq{~$7rd*RV8JWGfnOLt8PzI(SnvBHUE zSOY9`U;or7J6ma>Gc7!?_#wFn_xGM8Si5XsAC&HSVX!)nA5rEp6lQBTW-0#n=((MKOO+}W{A zVI{+=gG*UD6`yGvbT>BC;|K_5&CX<~NM-E$CsR&7Z+yGJR}ZgG z>#VclKT7F6;O}2wSS6Pf)hUn`eUgg9RjpfX!vD56r^u#^D7MMU)O6vr!(Dh<>yY+t z{LgpY4U0@fSR)4Y%XI<~QtQS<5Ux2rCKsA076+{~wHzP}fMDV-0Qp#E)SSm5^zSRs z*+=PRMLeWrR~$gD17WoKjRK`hL>K_3z)c5~0zmlu6I?z*K>e>3Q}7#sdB_f+nG9W! zlc55(SVR6s>1FZR2Tb9|kCy+zx2oI?h|1;&L;&kTPJOLi+voQ-Hfy~N$l7a*P2VjB zCBgNmNMIJy!VllS!oKx3sX?_Ra!1&P+%fiIzd3gDkS3cm`;3-rggH|egR10^0*{GM zdssmTj)oWjzN0?KNLAqTCEkU=c?9<|YHDx}GzE`W!9v10a1tZ1PvAXqEEgX?%r2c# z;lLZf{ulK-Z)vsM&uRrE%;RSm1ATIxa}3&i<^x%Qd>{mdzrRWDX0n(yX0wfW4v`og z2MFZ{kWYLK=LcaM#DMq!$PBJljG6O>`yA(#K59hx#CiN!KGz|h)W92Q{#7b6iWLmk zFtTdlrbbN5W?4zFqA`A~Wn2po*00YT%rlf)BtQ7U5A5cfZ$8o{yX^RfAAZ<~UkUZZ5<8}31H>d*+)&~%J^k-q0+PZR z?kFK>4Gg0Z!s^kP%HP3_DAU!+S&HCJ#0@1~+WfYbm`pv~6bY;+!2U>u8!8s25LbiQ z89!al7m_Igf~UTP1K@%m{xT5{ z03j9#0Qe?ZGXTKE3Dh5`mxjGjnY0F2PHvvN3USjyn+iG9$`-odW z>azN&5_W|j!dxLBkRzZr1PrSU+WyH+E9^ktAhVJ&_D26R^#HY&)RSo9DV&IAo(k*` zAS@fCGv%B#$?C)Y2&AchZnhIeVhf0Acuf`GImQW?I%Z#hH-`YOd4qMvvy!n!+Q>Lb zk$bb^IYJ;d?UTlsbjGVi1}W^fLu13j0x{4i)JJ2pRj5(vm7{sCtX7Y72_qV3fB&q&~QQH^`jzK zX|XzU|4U~|_wJrQ3Ny69JhP@wo!Z^QNo)Va6aq2?6x+qk?an*zG>Q^_6a=f-%$YMiWiv@_ZoKhEf0lqr ze*4?s+CBH&Rc6yXavVZwxz zT!7FfVL{1sb#lfTg0|D8&8N+_7_T#92?T^2EF|Yh#jOvrfDp7z06Fy{)~s4-Qa)R4pCX$i7c7EgFPd@anz0U4 zKwhZ04Ppmqhs;fY*{Yp;>;r*EwDH&^R4Pxw$x+pAH0Q$y(&~` z2C)|q57POP<)}oKm8sbu$Rts0dkSOrOrO(zJhNua@@wP~k+zo=%>Dd|?cO)!BWV1Y z8m>nDMHu>tyw%FeK^(|5Rhz#|)!c7*Xql(&4b~CxcKmwKQ3S!6#X(^|#)&)D|2T8( z!4Klz5tl>8DB@%wcDP_c{2)4zKfpKcS`?aWPBqYSG=0)v=o=z{TNuak%K0URhpbv} ziQs*p%ve}im>U2em$I$Ru3T7866e&?QS%%6(eRw;#LrX1cG5CBB?eJ)WpQLBqY zCL>3V?CS0_+FxP?`$U2gPgZ!J=w;B>;CSu^Qj+)@+`qsae1A_l12KJg{2T6u^H4jNkurGtYm0y z5N>Yxu7;EO75Z>x|Dnz@BVL1bmb22p1xETN3ER6^g*& zGJURH-9o@+3qU6Tc)Y+NfxA_51p}y3z!3MDdC$FKyXyAZsLC<+N>!5ptK5{f?zNrL z&IjNf#s&}tEJFZhs=mS(<@ZmWkhX+=e)9B(ZgpY2xM2|pjSG;5>_zw1YCGwDy^^`c z+rO#KzMcJmjZtuUQC6M3-3Wk}_Ft31VuO{3c|nAze=uCN7Grzgv&NFKR#!CEo~@4p zWg#G_>F<2=jR%$kl(BMPt)Kv2^sS~wMz*IHhMYy&g$Brts@#4$f0bKKqIi?G zW_fTs>l50{7bz^3wdVe>Om`Qhuow3dvQLp3`K@)kJXV5(G*thA0P-FpK}If!StPXH zx)3|VdEpvCwCtWf87l%7CR}%j5#oGv4dKFt&<}kxzvj2TJ@FTxY1zD8+D6z$pIp<7 zl^-g@Uw`IUkNNSPTKN@EKmaIw&l80$iC2nAxA1o#agy-|Jz(KUS zTd>&T_KE_AXGBkto=iY+4?@9+Hapel*3o*NJ6pj%6l+W*CgJanq#EYg2|(wWjVmG; z3hUVg7hGVMUw*m8Vln@IWa8PKj`P6vKrv}1Lxp!32wyG1mg8^ zmtF#r!WDpTD=`L%)xrVqJW$Z;BLo})hL5zy1z$!k+{FG;7<#*h#DnQfxh#c25LC*I z9GA4tnzH#qa~^om1wU4_Q9Q)sZ&b8TKL~{gGx4R*#G2I#@IA0#y#O{=1y$`{S0$}` zlT935VH1XzD$7rWgSW7jTLsR4{n}bvrK;g;mDPtJVXPb zX3p9Bm>ny(s!68nqG^O}RZR#7%Ywbq?>mWr1VN&v6>PPfecPiC<+w*UOyC+q!vnin+zfR9nF_BiiJlWdBpC$_uix{g>?jy9*f1? zt(q$7JkO5?x#^~xTC#QVTnuC+acp2TLh?Bk>McaI|=fYFYc1yem) zd`U5#{WKY#*XT7oZ$ z)##{j3|5a2>;=(7yU<$2XC4$-T9DbZXM3%Vj`q{h{dVlwkr6j9K-6n;CBcnq+50Oj zH@nf!nlZu7m@-OQWJkU&LnOxIX=S;3RzC6la{4;3qkvzX+CXtlyak$n+_56yoTb>3 z0e14}LVI>emAzBF$Ai2_EA?$(-R#%N;;~#ny13aAa=eJjbo~T38LpAtyX!1A?ihQ0 zbGALWP?fBehBndq!2p{vsJrvf#x6A5o}iYl5T8_IzNU-v6Xc$XadvZLfWhJ=#$iZ{ zAgZMP#nXfS!3E$cECnd{f?IX`IuTQG#T8e?Z|b)9!TpNj&ETha1!(-Ba0N$sf_(3L z-?Q6pyDk3XkLCMb0+PaM$4tqC1K?X(S?TUrA@dd>7^?>tW4a{t*A>;t0rf%CNHz*I z51A6akbrk?^B2 zp0cLK22~Yqy=Wuk z!*PkPg?ZWbgYzcZY*_`~Ucb}seQAxS&1EgZ;q*g)2!x0C;WOWu@GIHpw1u1BgICUQ zi$ubqhx{2&Kv4Q5y0em8;M>1{*K4mZp5co9zy*;?>eK)c@9>~_;*dx^3@I#EJkfQt z$E0ipf%H(h{?T`;b$*-Ajr!)={Dw$&d?JBECKLBZARt(8i7DueK+x$MH$~!+PE+dR zxf2Kbwb+?Qyvb~ppq;RG~ zu|BLDd|?nWE&-&uA$26%Lua}T{gF|E3=x@>u85fk<42Q(#sE_`L?W5+<>g_GMFYVa zglV6+m}J6(;<@LZ^Ih=oZ_Rf++3_9utSi>+si&Uu^wMn=ZT!>Q8|=5QulIDP6mK8} zEfxcSIY5t}JON^a;&~$q8f`|=ZdDLh`j5aK(wv9{j!3akQ5*(Zp0bBoMK)f)M`^Co!R3qA{OLRco^ z1;BfYit#N~s$D=N;r-LqzJR;(M3v^tO)I}ZE^Kl+au6R8H@$Vh zA3rBF=>W{g8lZL4njWK!VAEwmctgb(0f$YxH?S7OuFwY4BmiD~%BprnE<*A14)00h z3y~okSdABtUmVXIt~h0seKI!C z1L+}uq{fXuj{f<(h0yS~HgJ7~ZDD`fQJfPlleb?m zp+n@StuduzI~r`BTj{QEl8&(*X&b~8;`M;*aJtgRAL*FVbv(*FfIdLEJJKhEr}!@L zOnvB~hwS|G&rjFXGSUu;5pWqo{Sw^Ck_os43`6X2NRE?i|DOI?F9GS~8O9t4%jKaF zB$&@3A(;?dyWW2LZP)st#m}U~$4t!5kjqjSKfbgO3p9UdJz5hiOZXF`^*}o7-o_2$ z*=L{iVpLmMeYke#MMz_xc|+MV6&gWEmmg9r>3RSKISS z%}dqvU@1Vej|GMLAU~9g5I_rIj*H~}vQaT0r3$1cwd+4VvCPKrUTBl*mzbhOET>69 z_Zm$@maG+7IabrB#C8rn$zIzZ^FV9jWI)dl1gsWl%mLGky&#wDP+2~X5L6D>Chlao z0{F4k;DUo&*s+TL`24hTyWzjyQ%uTU&m4wzgod#AKvoz(u`IY%`RValM8D{dF#wFQ ztneNp1c?M>#w~l?Q3v0$Mw~N_31g-6&@SycNoZ~;SJo}g4Qt3I(&jP;5)J^|+p=cS z9{V#N{r4b$=1KcZH&}b<8`r;`vP>~o_RY}%87E^TuphUzZ_SFy^{ahFLU>@eMnE(i z`@28C@7cSkw9b0#;bt{jYsS=?KuTgt0X$XN%l>xG7>_~esPc$&c-4O__V_GFBE=xN z_I7AHeUrNQ=5xliJFi8H7PO6roSa|8|y*T5y0T;eHr zll6r~5SL4?9h46rcj+Y{owx$H*ogf=8;9_)A`LI*%1laE76YwSzBiXL4wxsiNQ^g0E&KDv@>tX=|@)JXy1zd2h3)uLVffh-ie=xd1=X zk!Ck4GnTZqu>nG4vRuTJ#l4e}E z+z^CJEI@l?b2?{$x=2$ZV`>DfDCMHP5_#yoT^84B%xi^u{7Lv!h zK>~PXP3fJiT?jAK2En>hClbQvZ3+7x+E%nPpcsn^)**-$WP@=>ZTIytIMLAVoJ-ak z_bo_7Tir1_=1Z)~K+PRX5Y`ebFPwYYA-*EA2JO_j-0$Njb#cf@#Kdwex*V{e)7zRHgCyhFYL(m!TIHU zF=qnp8OwiMKD}M5QY*tr+oqnHUYG?UrjR&OEbt-QV%iq2n;YuxuSIzY-GYTz1)IcHe#XB|U(BIR=F*WbflHy#%BKR{(4rjSfTr2@h%F4$@Ki zy1gMld=@NN;K5CqE)K|pKDaDp%3=`aOF=x6XaI(s%mmKyHu}38L5PCofHXMInY-#o;vkx zX?SNJQ)a)C#iv@91PI4=fiJ)&S;HVvj0NDy8U*V>aP=Za27ruJW`$~9U@bZbQ5n&p z!WNDJa08r6RjhBcTzs(3U@buFO#wjGgn6Tt&eQr~k%5e$Eytoku|l$Bu@70h*v>KZ zP9Mw@VSRlRLixCzL2_`x(yoUI*Qn4*>r|LyH+EhsAaH34j@(?eo#`C}XqSu8>uWQia?2T~TsrDbu;2mRyn zMZwD-T{x))z#raQv<1aTNRH7K0bx&yHsYGZdBHNpS_cbHeA~={xw52;nd;74K~WcH(c>0=S~^wnYR3cHhy8*M$y8(tt~5X z;-S|*xWpDJMK{+L?vLS~$ajG2iFy2=i>I_Cj7U7bEB@}O*}YghVhXX$Q{RL-Cp}5J zJ9dZXby!m@O;|gRX6dzn9NF3FaRdbB+>zYV9a%QoA_El}JwhgikgFQa6~MSFQmJ)i zalo#y7=*QlRPhC_tgLLwfe*<;d&W2rv>{kMQng(0pdfw%;bztu>xm!KfnV`fqgk_3 zi!%YBKe~9M$29;<0nNkm^)9P2?2D>R}GN+Utj0s z1E2KWA|VdMl{pJb0C5LH<*GWSqQnkl=X;P!dLk_W8+#D0Z+%U6i zcN<FR41oMBj*G6B7R5&0HF6wOlq38 z=#Mp_N7ggy|IiVz9bl7nSu6D-jB*7!5My(be86m;MLf{u?g#eSyGLucFX z?${l?2|{KuJS0vy;e^gkp-cDgjR85bsXjZ!5bFRs{XZ>(0zU0FYN3dkY=Caed5<;Fcb9Jmh~Tx?^@ zOGFUz?Lrmw1LQuX3|Na)IBunCfB^U)GguEA_7i8I0BI4A5z@$x8dh$f99w3~Htupu z3-v{&DX1GL3@KQmw7Uf&JA(^zyj?PBt(WEFEx8QwK4`H4kPr=y!^Mb->bN0cRlv$n zs@JWuOq?M1tzdN^o`e1X-jD>+`3{yP0l~Ek%g^wEa&=O?!167791J>;*E|4MwIUbv zD`Sm~D-zfeNda&-Dn0|SDh#L?6yLG4O@5*Dy)Vd0K!&CfvKHZ@#e5(mObb^bvNnD1 zGviz4`nv^H_Keajfb>FRUb%ki>Jr=;;S* z4i*zYJ=f+J8i7DiMNsxBPYLxCix~sk5 zI!7`c@J?3?*1*cjO79kOj+NBv~cgW`!Np78#tBHv!tEZ?z{ zzv2VkQ;9PH1po3Sr5RK_0)T&<+@A33{>$nbtCAZF0JCp{f~@o8;*wuvMFaY|Yu2a6 zl{#=D{qCx*yB!D(5vbp~gDTdlfFZCxN>+wTKRMDSkB@mVLj2vaw2-A~iGsIrgDI01 z6+eAkbf^+NR<%H8PbjrllLRKqvcZZkG|2?Lyj5eNwGl+n%^Dg(nSj$6Z)Y7I*Spk1^FUKoGS>Z z$5!}+MEF=RjezW9F04UxGMqFqKU{)HE9^X0`;)@>+{uGI(E6U2*4XdfSTBoHWSIe& zcU0(c`lupz?`bc^?7zRV*5h-qWJ!7kEFpdr z!~C48mVai#z!m~>>Zzx;+>4Wq{kF%JdwOW%G$6j5cVEW1gL2f-U|n~R1}s_xu#;tt zSP<%yBoog6kDmO%ze{{KXdBBLB;cmA$Eh7L|8@i=4EOg~tm6a(#l%eyy=RN%ZszH> zrDWlISRjij>wL!r6Fs|EJ6&h=<5aVIWpq$!YMhutzW-z-q*g^wlJ2%#RVm>Pibn*6 zB$-8zcImAHlKL6yB_Pdf#|;JdA1?af{)4t0Ae;zVyRudW!^?D?iTKMW-eQm`z#jU0 z^UXIsBSiQcf)`R79*NZ>w8tywm8zo%sqZrJz)0q{25=>Sd(+On4$wyxOY<+#zgSiU z2nS#Sz_>!y$=3@g0pckT2*_U`0s^Q71P{qMU?cn2TVe5FTO+q4NXn#&LK`m-|CEBy z*|)5}GV$!Iu><=LxGU54`aX8bF%>pPnWs*yEb%qq7nQ~zUR33N@@u7`Zj_r9=xL~c z*eGf8XUT1Z^rQ%d4Ifkm?uD|jFgAb|U=D3IV}wW)i+u135NBJY4URxE*`h#`X!OyX zS7{w^Wg_-Mm`NXzVJdRbp$z~uZdznvqAm8tVxnFBhd^$uE$=Gu9Dn-=utO>$3kd`S zpnN#6j@)n5yeTxphRNOQ#KDcWcw4qD+o8HCGCD=a&{NbG@33S9AAdkQ?k%`s0Y0gf z0q6w$ojP`q)^(q)5a4D^ofYN|>10myj-|yxyViofu!7N#Hap46=MAC(;PwO2MgtBn zfuscM32pV0h97IwS*q``Ocpk3i*Sy#yqyxp$Xa~+jF_^0CASW+Ha~w(dHZ#J0ql!J zB(Q8S7YGR!2eO$lR`$91Ps_Y`Bj=tzIG~?na2__J}e+#`m5pgX_1ijg!>C|CvUEm z0!5v8anH&@Nyio6W*{Jym6a`;-}ukldQbMX`(9gbk1yTae9f2__ax~37=6#WTT%(G z@9r^oq<_wLNNO@;#*D+TK}Xs+n)m5$;z$bMVD%s+FyD)#U3x2_r+$Wd35eDX^FF3W z;t>#n%dvQ1`Dm?@d3@HRIdkT8NE_!3r}(QY(!7SDbp>Fj4>CbO_IQs3lW%L;ZNk`6 zeVsRNo*#PRi6>?xV_92nYgjYLP6epMtqK6I|4u4K4C)sJA#47`dSD>{e6tU=E{L&s zUBTagC$!CFefL>Ke!UGDJj9mQG&zWySYBwyiiAA9wAx-;zR3nC=2&*_}GR%uXJ2kbtllixkBAl3Zl=D@F#A1P~)odaB$vPEtx--$x+wp9CV&V&k3y zAkWo)17$JUvuCfY910xACn~$IjS(2EkQSM0=*&g9(#Zp067BLt`TJwxpjh8SiVdJo z++6^gSUn&i#FG&70-y$LvmOf5aAH7gMX@qvQG}4pRhyOVid41$%YdUH9({BS#3deF zv*y0`J}ayrDjHakYnM*Qu|F-_Z69o}x8*x@A7~*V%{ww*9SaG;r41QfL{=*iJ>4Ug zZzI@0>K!*HT*87|41l&XJcPAnoPd1h;Qtu6emMWc6kt7K9$Zh5AdbQHW~E%#_>8X- z>xl5ZibfWZmcbeyA3<`^^0RM^+mZ!%@MI`O(6G|{PInYM}hosO|r%a=Z5hxPIt}o_afn1r!q0rpM2q1x4=Yu zXYMyj7%b{z#*DF8EY|6ca4VzE3}h9H(a|EQ#I_tQV^1~?h<-@xPJBWpTzZrBpXtxK zn>dn%3u1>*fH1^^WP095(mw9-U<>4`tFE%U@4ox6=D2Q%Wd-w~1SJ)3@TfU#=a12b z{|^8F|Nka!1TO#pKmbWZK~(I$2Vk9Nd4~NQ?L918vOFd45hqR@XD4=c0$~LLg(l%I zO<83YQfQ#e_NOiVTLNvNp|lX16w(9|60%M9Ufz4iw!Gw}VeR$b*K_LD&pzu#U3%%ImYSM66vg&h#={Rk?BAVz z_SsfgSlH`vgZZMqzTQ@^UTudDAMQGR%$PBD)>&tDy&viqk38~-u`U)bUTj50MMGV@ zwYIj}vSrJ>+zT$az;beOthu$_{^!+Qw!f~~Hdh_7HvP(I!~VJ!%S=tOBQ0$Hm+!_?LN|KsYyvTZ$hrUZ{Y+hE6RFHzpEQsZQY(4t8Qqq^klO+ z<8y6nPIN7AQk!pmqQbTxYP7xTL#x`MrdoPRvZW+PEF;op^(|_5B+1fJQ*3-*nnm=F zK2+)WmiA8d&8#>#&BkV@+3Az>?c*0ru~c=C?_bz<*tQ;Mw8N@cwmpVy2>y^gJEY_;mfHjSyqRXtNxULS31)nIoV?JaF!EIBV# z-?i(D1*JK5_OwF##068WP3>K_X1D$C3!7}kp@`-w;$>#0m}R6ytg*GzkD>3>Rg&3h zg$$8iS2jefzRfI6bC#LhX$|es^VNKBk52Wr9c@b7Pim%*MOsRdw>dL4*-G=%b&cw@ zBbwyerZ$a5lKPbreXag+?7<@~womITx}G|{4Ov=i5zP@}%h zBvt2Ts*bwmHcQq(Fb}``#F;im^V*j%=KuS~9(#W4VQXdJCF63_?b_4E+oCD?U8mmp z$}YQaTAPrUuJSeb64vMb`WBl$Hq)}zkKG4qtWH0H_M{YVM}AhSRX~>C>kVd*9ZqS!3s(d#=~JfB$|PJGSTF^{_Xrp9(L!=puXOnP)5|CB?B} z=tDT|```b*{pDZ&rN8~=H@|7$`qsC?SO2GM^jYk6b#;Dh zMn;Csn>WuOApJ>WV`JAvXz9|W#<_`<;U+wZ0PKP6ZQ8WSc#ULdXB&iM!h{KS>ZzwD zYzQBF>@g>pXP$XxLM~`+ZEg1W|J z2dz=y2S9h>^did^fT}pyVEY8Z0ncNyqvWzl;0VwSa075#bG>!w=EsN!c04@ zu+5I_t+40!3iLNctj4meBRNV00Npc-b8Mmj{q<*076=up?LoMq@<$(%lau{8E(t#r z`FM8gA=_2mWUT_}!q`qKI`kbtE=kZeB?8b-(qF{#h1gpJ{M$9R&3dMP+4?Kc=K$4d zW3%jrvnGm=981=p-h9ZO);O)Kto368sNGlFY?Z2e;lw;UB(lMnZ8^}OwbSY2(V}tT z%0*iP*+~&lW(*lO{dW0lzc`#$?7}ri_{&y8=uu_O`4|NA|*U)`kd?>ZAP>){@C+8 z#2nx+)eW(jhyZbvI22{22$-ijd81y4Yko$u{34c(U6KvH9H~5SAC*|wzsCi$F(p!-RHMngoyRT8voG; z=R3jbUjNsAx89a(Z9&XRMUpc`mLX`Ytt=4^$knM6bG^Qq#o2b%ym7{Fb-3iU*Iu)l zni>atfWDC;Z@lq_Z!(pamm7a0MYv9e%||xP*lZd}a-!#r`j;$O;zJ5HJ6Xn;c609s z8`9=mZn?$SoaX(ne)TK6?Y7&zPqSvtvR7Yyb;J?Z!TtvR&k+!It2b`kXghcA^fBXx z$Ay2!j2X^e;~7W@&J#~O;fKO}v$7IFq=SJY$BOciwrHmzQTx zZ#rPFZWqaw7Gs_?3jkVn{$JlwZIy=`ZK4RosRGvk?jr(HYqd)|RltWG*g!%kuSVcE zS3q-fMWxj@HQU7EA{$$fYkAEFtTZ`Fo|DotZAWsc)wLyAlQb`YYzP1vmiI0!6*=f# zV|K8v$=2_!wIfZ^ut@tcOCSubz%2r98~4>)jdqSpwJQy%2k-%0g$A8~qzZ(mX?MQ0 zBO($IB?JIR2+AaZLUxv^d#C!la8jOKIHTw-JIl{)Ib=_5I%Lat)i|jN1O?&)07Y|B zA}z{ljSoPQ@t}QZk#aPq^#a8ZfM(Ut*tO{yA_VXkw)8)K<4Jmh7AIX=fE)Y6pJ2zFWKZh-(;XL>wUlkS}-vf<}RJ(N27R=@gq*m}ZBM zG};T=?SEi>jWk?QA||DUptBz0l2AJ1E8w5XxS|z{ex8>Rok!Y%#se@9SYA9e-!78| z;D9tB-*{l7p}lHsZnXj_C?=1~6|qdUjrxpMpcM<}qkXDZJA+V5_m=Wmn&y*!0Nkk; zZOngvbYY+CDwG+|GbH=Vzgg$&1Y*#t%J`R}woX)CtYx%fJ4Dp!Q}LKwCoy|O+Bp|8 zdCL_uq!E1UZuG-z_uJ2&-{D#|G%^`lH#{?+6I3=N^z#>&$J5M&91{o#_n#?KrX-|} z6H#c;>_9&F8z};QV5b|wLVyjSktAU~o+ypnOE0}-mtTIl4{1}AHZ2ltT{4t&cmMtO z+x6F9Z?(0xJr)c3`2FvH?^v_P1O5+w_FV~#5;E3=t1XZmjYx^?T^1g@l{ z#7;l`^xld&?$0rgV$P1YKfN`Cem?r>qy9CjSJu@F(jL6J{jh^(Kq9~zlagn)9Q2)M zfcZJ)g;pSv03l(A7_fbwv?B9LbDcG|ph#AWmTdRriHc;WOh zc98&ItkCaYzPwA?4Urv@ixQ0!0J%y#)({xV8Jm+TO;WAQveX`tAV7JR`ZrF*1dw`A zS_({T9O|n9Xlzu33)me14`~6^13cNy2Z*x!4S1biBp~0h+aBDRWYwLSZrTN5;hKS& zjt=!QRD?`--URHfv630kOlcqf{=IWt8?jb|^M_AXIPs)9$k^eAC~4w-&vLY}-M+-M z3*b+^Xfq~dqv1)ieT^~&%Vvzz?W>ngvD|DCSKX)?>ref9wM^R@tWH`ZbwMO4RlhZv z$?309S`@}YnB7eS(d=kAoU~~PYiyzo;4{WAmE>fRjc z`SydGM6#n~k}+aV(Bc$nef{mbX1_%%7h4AFhBZpxAznNWrLY?cU>T_dZT;uov0)k1?$t0Nc-+Jqy1cAgCozIpq{9C@APEZo`HRwr$%sCpnOVM9EO} zr?0lL*6w-W5v#0^Sjp5GmYZM(frh{EvcGcNYZWQ33RFLUrBbca6 z5YV0^t;h{BmkMS`v2{N8+;d&#f_%=6kMWH4X~75J;kEmm=&)N2SORb^7NIzE>ajNM zs|5I-+IT>OqTcq_Hn|odML@7jfP9QVH6V7={ssZRCg17Dl&V(R21pbj*gD#5LS~0e zFV3~<_B0D7Q?w1Up>sv9&`{t*!cXxO5s+(6DK@|)!kA$e1Np)X>#zXxLHVs5(ylxZ z4__3tD9su(z%%AoXhrxQfQq&Q|B_Of7p>cO#C-x9G^Y4DKvEcEcG2~blMmVeb_A3I zJ^`>a41!UbpJtuS_?(zEMxsET&jJ3llX@_TgBaCG1H`E+-pgQoG3h!>V|>e%Gej2a z?ao(s8{=E3afB@42ZZ?@bCRKUQ*NVxaDSp<^g1~%SIQ6kPq5J2BQq~dz>4Lj_L1ow z>MO@Z?19P@+g2B`J@uIGNeiTUXdeI{GB{m8eSv(3o|e|BP2XeMw@u@kriz$zj)k1f z9WO1A#^|>zw3ak4w3|K`iV)AycYl5LOkdCawZEtDAq>A+vDaSOR_$6d>RUXuK$^Bz zH^XDiG3WAJk=Dvw6NTRfB!Ac82DQ&@LSc^Pw8PgA1O{!@4?Zxj*ET_}?^(XrmTfp7 zO&@C{VrQ2Z*oPNQaG#W(+R0o$u&T;_w`!mJ8*$7yt;r9ZKHe^wJ#=>I0r0UY!~JNa zNZ3iok6nj>W{uMnHypzE1Y~ zMl=E8rUk%d7oOJ$<~}%?ACGFUrycJ^E`*+Z3=&x%=4D)HF^gin1|pC%{5&cuD*QBn z9=l-Nh>}1QF@h-^+7Zm6Fpo-<98Z7ZX%i+dx847o+o$J^E47@g4Ea8!3fMP02xX`C zkap?WRnHWH;&XOi0f>M*d?f&kkd!ikM6@LU#_=+-0RZpbEkL_!Raa9cO`2qL=FI83 zIAh-rkbi7_m6y4vy3xTUfU;C&Owiwj(mb3x@lD6yU%arxwn#IvPUcrd0-q3!BLbv2 zcAqMc3deYIf@T9J^Qcp^cBYeM>ZQ5H_h7=<0(T%@uW`te76r75h5>;*U|SDJ z{MfmZ9pnNCA6d6wCO1vqf5rd@WK5*cNYHM`6MiFTMgYlmB0rN0Gvv@;Z&e!4CU&xQ z9ApCLVRotk`5G=KJ`e;51z?uX`Ck8BqPy5{z6V_MCC?G+RzGD>CiVe|0eB1HOT)w* zYMPuNaV%uQwJ}mvK&(C~=VieA_aEQl#Ot7lXYf72e*$90y1*%awKOG^)tC4Psvb4T z=Vy+#|662AxZ!~Og+xH41hH$&+HGo1r>(D!*wcF>w)d!GJY|ReG8GeKCHjRk(yS;q z(>moR^lDY7ZL5|ewhr81FCQQskFN#9@dIa+`kH)A{!5Ro6G_$F*&rrP&#A>8zb})y2;e{7`n6UXj9vm@LV?C7RU;>3-=Iq(CZQ{gZuw#sq`B3-(019!`MiLPz z$_tKp7;eHtln*YnIELdO9fF;# zJIzWPr^Vv0~3^V|gOS>RS zk)|5kuE<;M$?29M^B;&Nk+3l9DOdmKhm!#v4{&?`!tuV_%x{NXWk|&~nR5}%3Mmi? zDi!e}ve88|#`qYag?Us&<+U9(Zi)q&g1q1hf{9k1%z+qIKrDo(TBc5DmiX-S$+>b| z?{EMM;iLUw4#1m`6WaKuMBhPbFk9kXqau|te*jnB<6IwvoqPT$g>gf>aPh1nyXpKX z(j4ryS47?b?mILuq3#f6iSgKes6p)srS<*{Sf*C`Sg3KwDW3VDYBU>YDrU$;4vth= z-E3PAY5u)`(*CG?#zKd=3D;-lwc9wEFg+upvbi>5hni&`b~IiGb>xajP034kjn0i{ zjJ4u|Y`<=@%R3Z1k&MgzN9UfofN&68fMH;*@Q1k_gc;$O4bpC*37eEJt=yi2^7WBZ zenz&FRGiu|f4ljzX6We z68c6T+29(;y??02;NE-hwHt4|(Qz6k^8`j2m61CFBaVPzezkJtO53$-m(Lo&sJy(~ zci@L|F=O)&F-TNs*VrXD+=K@^OfEv0_{4Kl#6%2pDr_DRG##jLQN4H9dc^h%@&O4+ zbQs>j5~|p?_V)Vaio^Dr{3srMW3%O?blSq{lPr>&E(h)-0*tBJ#m~0u&X^$Z3TTWt zct;b0;Clfms}exQ&qH53u*5v3C|x`BM-JGcF>M|qmm3{xn{h>(gw_D!vrk|NpuSbw z48S~E4D9qX6fT!=rT{If!vXvg7nZx`W$m6?`~IVwovhR~wz!V~Z^0vWhlp;_@Sf$ZSp0r*9W<6v5V@a6r$O(HqA z)&=LNJ1(>VZ4uguG|hKJS`oA^kQSWrXwVst3kVx)g0b4H@u9uc z#v0%|ek=Q>^*}Si8o976*JgC?vNeZgQZ{a?&-)_zOcBnPF^ETg@nWStx_-ZF#31i< z80`xY+}?ZYc>PYJn-lyd|66`ZY!Kw>JN%7MdtpAt?_-KIai3jM_7;Dpc-qkYn2}0A zMryy<&_qjsTzKJy2@i?ieZ3_5{qxU1@0)dO)(+JAVJO;m*IjqnO*h@-xC1MSp~P%M z(Z10#hIRx-909>}C^#LH!-8l_i3sHu9JLb_S*iOphtRl${sXWlQgE`vcZ0F(&n}tW zc{ELoJHnVlT;hoig83C@Se%0~C)N_K~pPnjh9)ogbL z$A12_N%{6pnQKfG5brKHw?4K`-Mkd(5fGw}45^3X%L3+YeY%Mv)ba8RsAzO$ww7 zz}TCa4%&=o<%2+YVl+V^>J>gDXmJROd!aNSIOJop^Y72?5D-*EERhaK3E&zNEPOnO z-~<663Ks3%Ez>i!0FWubG{*+>8h|4Nq<4vahnX2;fCkG6j=(?u8kop2MlLE>|6Ldp zcH(i|U!bUFAC-Ad5Ww@gy><4uv`8;YBT_5v5GGrFwIZAwo;B<$U#3Yi1ETuab7=$b z=_hl{_fEjn@bo0T(dR@cBX$@4!S4a{F9;D1{g4hcMu2_7^FnkOyKz}b(v)<%c~@3a zR8tVz6P{5ZR5eA(5WXn+S<-~X5R~q(Azq)6gZy^QF+d*Ey&!1AXa~aB^IKq?_>8qo z?wQF7e|36Jot-(hQ{gR__PMbU%8h;IxAx`Vu5*nTM4ffb{IbSaJNWtB`hoebiGzHQ zzXSq8TNob%{>fT{ApPlilkIA0O^#Piw8_iyw!gRYM{2*gFG8*mB47@MX0W$0JQ1Jc z-@?6|d;ehlKaZ!~cieG@ed<%6@=as%v&FNqaXj^no_k_PV8js+h7;zDF9PN&-1rh9 zf#e*IqxL}BHPoST`>H!QJhKbZTWCmjh5JjB8ZmtinJ(` z1;%rf+;7j`XdZ`MvgMy!l5JO>F~iQERbrSlKtRxbpar4c*JMHkd13b*fR1SryT+i> zeDX%f9|N$(PV;nWV!m|w427S~wqL(mDXm7e`+%@34-Bi^jPVQfUql$A4@C&;k+j| zDpHsFiOoL#0B8>|gQ1=HcHpxDIl{Id@J;_A8}x-=J^&J-FMUfmAbJ9zo;(rwc|bfU zn@dU5xm#KTp;6Ajft%!s3q>^FuX)DVzPsGJVvmwi?sm{GE;k@Sb1`3u6JOm?>vI%N zrhU{;KM~r&Jn=qiq80sufB|TAFn1ypGQb{_KgJtijUzgB@C;dFywC~|iS19%o#YY1 zFsa0Zkv}w}%eK_n3zbbi&a{HIoKo0n=axiYM_csfBkjUg{?}U~R#DqwRSg|hB2z2c zcDOO>ca)>{F=1%gw#qaQQ#<;CUW9h}@oi0ZUWr2XUbkexzy#B;J2eN89fAXdP}lfp zq3N2YwT<~4W^`!%zVZ8wT|Px`_9VKVAj1Fr{&_vlb?mY6ydJ4QeWdn_kn&uMk)=xq zPK4uG6DRT*LJVWkfSK=5n5z%8FaPtPC_HAw-d|$oPs7 zQ6y0k51|@t-8*E<|L~eBduqjIYY_0ATq5n1oP05Tnk51;bxf9ha8b`hc$aqUm&qh# zRb{o+X}k-p-a+ocW`VKHTsvpRctx-(^qqB_I&sSDjeyk3)aYd;bPFII;GC&lUd%@T zbEnHxg^cKEWd2vCTkH4L$%LvwAge_rMP^<)9!&?wLq-6nXcrbv&XbQwy6w^qGCTN~ z8J(%Ja_VaC|y8Pe}Hy;Ua*O;9ARcb`_`QI#-(V%+c(0C*!md~%!n(u9a$&K&gB(eC&$y*=RP z0x5e&V-UJUsc3*08#T?xgOI=k6JQOZIfy9Zxj2bTL{j`1%!bgCK%^jv%sXwbZzeZ} zk|(xCbE`1MB?=gThT?Ne%eu_oLi;c+BY*%tOwmmAo$fnQkdb5yOVaHf(^8$NKw8*I z<$4hW^Qk9xN9>@IW_m_*eG$H9T-61U5=dT@T%nD^Jc@R@)h1B=Qo`%a;R`% z0}$HHx+Cf5csZ`40YO;%L@8t4U9Uu$?~qo5kiGxUFIV{QCX9Kg3XKee_rXsq3--~x zEaAJsJfCQr`@yt1o^wWOzlh94gfE0dbKy50&zPJH$6zf$&>Q?ePec~-pZw$}o-v&I zN$xjFKu(5LGx#=+5|BZTT_XJodTLUlL&?V0$<2c>x@a`Y%gejIVh5C6iT(Tc`)AmN z6HyGu?!jD$NkRyb$<596ETUZ%4e^UWsA%g@hlB)RJ-oKco_Kkc9nfxWT8_fcW@mZS zC(MwpoL4MUqn;C0V$N~^z$)jRnrQ?>k*u1c4=PdW<^} z#c)`~#{}}SQYKh{xGXskZ&2buvoiml>E*e6(!&WG?EI^H%9@CNz*xK#;Y*S0Vtx$C90}7$r zEaZrvHozFi`>A6x?EGnC>|-)l38qkt*Zr%i-298kSA_LN*p((ZAd#DPa;=u4cmd`aCkPw}M#z(V zcj(Yjacz~}^UUXDnOB5lZ`a`#GTe(C$=vJDFPI=gUD##v6_1@bCUCck2x3-6KQaAd zE=YFCT7oPSMw#eyzmlfpj#nxbKp>j`gX0m_9_O$|Z@zrGM+}R8Gx)~<)Wdaj@Fl&y z&LmP4b3W4g#eI<^i^wIHT=MoB^dV>s0bBUp5&<*Orrtd@_lH0Hp?&@9U-zh(XqsZL zKRq2k`q{}n0;2?Ekn@MC5{I;S9kmBpP1k8bQ*Z$6=BH9b!YFhq`e4^ z)7|S~9PxiyzG;W8J|r;OnPe#wX_H;ld<^Ow^cZtrzLRPvuk*kSVs`p4nJstB+*a>-*%}pgM)k9L(`dy_oVW)%n-S zGzpWQAOQ471jvaH6|@?(3+MMM=8o$!0}IFVOg@$8m1R5tNI)|F7ewj8_XW)ZH_j*l ziaj&l*R&dmqRl`+Fk>q(%Cwy#KV(D)yaW8zT-T0}2oVhvAfMj}=$74ld@k_8xk=;; zvT^%MyF52YEZ~mT*Y_j!0FbE@Vn-GF{}!SCnd7qDuLhD-xmS^%^ixeq%dkVreF3pR z7;m&BlnMEyOv*+$0s;ehMAP*R<@+EySrD`^gr_Ak6@)SP??715M$HmA#SHD8r}XX{ z!5sbR9jiRA3&|3l4X8(IN|(?a+LD(pR#rXa}5dq`1wDR$j&^#7!Als6L1FCF-*(x%^Ys|$AA1s`_6a1;}#K^PLC3h z;hurvt#6co4061KUqN4f5`!$d$J2&W;}ZN0aCRmXAE9**9XjOg!j_vp4~2soq=vHb znZThhQPP`6XDI7q=cvA+$)?SjZxc($dsgh;%I79VUJvZ)k>uzXKmZoevMkP-LJN=kZVS0oq4qzI94`{{50c}d>p&j<19NC|)O0!)@j)u4u zPNR$@UO?#-SazI5}dLbS4dHdDx&=Ek||9I8YHrU6UO+rFRZtnbqY>k z(t0Qo7Nie<9>y8pnLX+Y^U3GnYd|)2@dtUGt=uhV$kgu71hj)JTYo@)6qxVTyM_-E zfgqluI>aaqY zVEy^R3`^}$umSn`#Uos^AS5Kr{N-xp$kCjk0D_ogsjry({nZuIyG#Y2k`Ks_pV{tY zm+?R=$nTQS&#Y;3+CWwy!N)5j6{w$RXXfLbm)_3jKDd1Oa$h@3moDw?u#@t0hzA4& zA-E2{nZqsL``-7AKgJfTk5K|L+%qt|^^FpcL5_DY>q*qEdiQ1xr^Y4t8<3v^u*|L{ zLP%cBve$vgcr~1J$p3fWMrx)v@Sc-Bpf6!!?_9t3^>JyVvn5AiJ(MSTuP@7 z9EUM8quv$DI=^nu5pQd>c3RN0sE97Y@a7Tn>ChX-UfuN_c#ea}@dpV5Ff)#j0e~rj z86C$Xe1a((njgX;(-+3@>iOe56!T~ATJ74J0I>a}n1^WnZ#v9tDqI_ZZiys~D$XSk zoN%hDbTYahYrGLfg7OS?p~;5C~+&iWMIHDv_IJ!`Y`$7rz%a(vUOHJkxzM{mn2w zeCu1^vVZ!gf3hpCxS}i9+Avl>TGcR*z=$Lu+?e9s9UJU;567;0Y}aMPnS)Mp(r+hy+2M|r9DR%s)is0c8 z53!^!h|XMT+^7#ho58#jM1i~}m?t5uoxgo#v*+@_KY}%c=^cWZ9svxlm^;>^r1fTc z$g%(Yhi!_&R^z5zkRUaoOISY$V-Fd|--l(=pZ#*9==!HJHh z)W^~|uCE9L!loJXP9BhvB;Y3QV+i5?#+3G%ks7qz;V$u#%gDUHTyGxYNf(#5)I21FYF~Oq4w> zz7lsl`jTy}sqsD{~D< zymdmvrr=_eq* zH=%sYmB>8bAOH=}1_U!VYQBSTAho)q{zSDnNlNesAjP+$kD|Rw04sfG%rx~!ozv6p z{ON_B+vFLU_q?>d#`{UV5CDKY$EK=X)EiwVfM3k$q9llL$ z>UPId9??U&k0IpciYJ#>Jmn7Lm@j|%%XZssx7oGVUTgQL81W`?TOl-90i@+y(S=VD}w*4#&>}XS75KJ`I=_v72=1rI#k8nwPd6vZr2O zXWRBm^PteSdAWJ+pMm{$iNdE|GJCARAW-f2BxtB&lQ$AG9<2uxRi1c~+<+9s#ue=!q?!Me^&JBjgOw?G&)%8S^X5wcahCfE$&ZkBsHrg@lB+ z3d|DS3Lya^;2nE^z&TFNrTVO102vc3!t~BlP7HR$Nv4Ny3mTC3%je)R`6pnzPd@?w z-7sxe)#5b*`q89{XnU&VsU4iLh5tpu6t?zFrH|Sz;Hyxz!O6a>pg3Ou`U#~=K!H4I zAF4IyBv!1^GX#Ku0BCY(FMVezGB5OjbM@cf1M>CXBS(d*`7XAf0Cz|rJ{;8wv+D#( zW_6(~$W0oK-D&bwDp2CWzwW{aAg1DJ!{>sg7WA$zeD#w0xgydRYnAcF%&b`XN=mYm?dEgy zt+hFt3kCBoz*;=QwXHiT3GX2;Y%GmLQ>BqgK)7cSIE78K^Ups&o+WV79K$-~K8Bog z&N=RzIoyr^+~+=LKmYm9?ZY4bu-$p*ox@%IXnn&x0;2?EkOLmVqL!COqY@3Wn7B_% zlpjNPzXU)4J0F+|4Fv4Q-I16B2`kGuvWs}xWtYW#Gc+&RVJGAFOKZ2v#Hi7xmE>Eo za+a`L3TPsM-$in$hKL-m#O4}d-0<_*v}x1P-Ry|_ow$n4s+%l&ZJEsaO;-}uf0>pkS{PURfI1D{egXFg=mGF?#s!2mwJ7wiqIX#Yz()QFKwH$8f_x4|3Pnry?XO-j!@)LfMni!{ z1I+_k4NS1`O#%Fl71%@g4u@~ddP;Iroex#C39eCF|=zH1`b>fGdw0b@CDeUr7PP{^WBnSl1 z=8J@6$zdLV4B@~Rg3!VMc7$VzKt{XpD`9EynU;(DV_@P&0D*?1rday;Edl}Y#DglQ zRpt~>J~STn8jqB=Iy*0EtzDG5!N#XI`+N}HtFk5Ao@$wEFLunf{mrRPh>NryIqx$| z%6imXF;;)|yA2-j0FA?3{f^wEO^s%5aoWdh>pR!XeoGs}2l#({{r(M}bPxhU7-{B% zKJ&Z9gzI$WKl$2KGyIf5KvvPiG)N7z7zy$>b9(5>In*zw~ z?e`ek@pgU2Cyp^7YU5Cw?w-g#ha6bUQzCO$orpfNo*~2teWQ=VEo4EzL)p-8yzxf+ z#V>v_+|`fPH_Rh2NiGLtf3c1N8#?)%MsMTP(e!(PmB@Yo+7I`>yjgg|1yN zG2c!VI5}0%$17a8(R4sEa8v{^A&@z=9{79!Vjo$%Pk9uG{?zDx8h~9KThW4CHn+G} z62d$YHEbYra-TAAzoCrhPYawAeW*!f1A%-2w8`&*na`;cbM3T=InoA=>lN^@%e-<| zovjnVoS?`=)?6=NfCj5>O}1pQ4I)qpA9sO%VPJQRCbTXj@8joBwr95-mf2RFfMyhY zv-{8cXcq2>Ye3k+uTqve9KLZp#u++K3EvJ1Trz$R=vChWwV9p%4=C*GEcuDlNu%&* zcdl~BW}-Yn^rFz-yWI64Tq&>|eM=NACj#LgsxQSgWRQT`=2qAC9OVdIWyJde z4FnplLd`AhgMc9TV?aP!0olgjCii+e4Y}v^{CM zp2?5o8imsB&5wije)+fSq&aBv_7E`(pv>p%6d?=070kE(PLZN|6Xxizq;)|1011N( zQ3hlL2YCV>kc$N1kMtJ)^shx?R*J|%Y#|)@4%I2_Fd8Oudyw}gkeJ@u^3&(GE2Q-v ztI~R8zF50FV}=Itoi5YAPhB|GE|95WJi<7jA&Dg@v9BR39MhjL9)Q4DQWCT$JfmHC zyAl+fnK5%aQTZhL8{5Htj~OifZ;b!B=bk&*V&0bLu`aQ+K+x_$fQMT?_OXxI-FM$@ zH{EoT{q(0l9q#H!>l@|~7$qQs9Pq)|^#@J^*cYda>CDKwdF>j7=Mt(<`94 z?b#ik2V{@J-IDL&jqM64+tgz9?MWWym2kA|)+6j5V}b>!hv=|F{$6DYe@=NkFt<7) zkj+lNP?&O;$j3yW6O${n8?b{{vyH@6Vhg>toB4F-VzYt!uaA)8loyav_>Xa>ng0Oy57o) z^Q^R_*rWUa2Iq{=m9uJ*z|!%ln%OzR1S_mLcE=!Y-4i*Hxtx%<>!n3tmzkY?K*w5z z%|#P3vp7dN6iR!{AreR-S?4ip=n@f*q#e&$qwrXfCSSW*YF60LPRj(!H+~Z+=VtdSl4?%ITEx5?7m~#g;qjVKq@=k#)t?^ zl?l+RJ8GnPQ5e>v%t~K(kt{Eyj|WxhL@Wx3qgoHl#_;>V)C{nV{{$K2(ej`%Aj()E zAoH{~0p)0DSjRg>)avyN0Yj4o8KFGJ5g_jDNzY_H=ko(~GBfOGu&<`vX(f?EHa%&t z)h6XzQ}zVw6#1aPBvCBRP&nPreIg>Y)=@OeI&&vj^U`k!f%hFH4$}AE%54H6WvnR= zQiTQ!B8lTVgbHHx>5IxdL~r-uBACHXp4sl2Ku9BVL4U@{go|>{kO>xL5eaQ>VZ_$2 zUf~2Im|(F^K6?8KC)jAr(6-Tcv{w}(Acb0Im`~mIk={2^(7^nKd{Kz1#(F)vJiMvQ zAw+qpGTE>fgVE+2jq-1 z&M?f&Mv7nt%jO*sqKFhVk_5ABg6klJ7(NjM_Cp`~kUjL!L-xfle$m76j->G&?aNz7 zV3dHobxh*=q~9IsxJrrtpkVUVJr6{@C2-SX=Y|~|gqsfz?f5Hn2c4*xF~dr<6FO!} zgfm9afOKz%e{q}-FUkr1*%cdY^WIwPOv~2IFkiqf)d3$-axR_IyV+5HRRe&yAu(RT z<{MM1#fumBc=3h|K{mE(=bI#N06>KIjRKYPOY`iS1>-%BL-)FSB!%_+Eos98QLRT! zr9~PJhimZs$+bBM3;DcDpmuQr&Edh+!2<>`1+wBP{G13HsZga6F>oyXxaT zeFKz3t_VUvTLIe>Y=~j}dLfj0>NTZ!2#`Pk{(tR^+m~Uf<)S zk?~>OGVW;S-0w#1gtTR)blUm32dy|ugkb4X4s}5jLvRFg;m|LRjV7cdpG>A*K4+|b zQsz^=$=z@4v0uNo+kLW_E7yGZ+T&fc?yp`k-QLrSX3`Hjj)%ecN^q?Snvy_DVxPlC zNPo>Dl2cE_1k!@}4Vv-62y5d+C$t+(yW=?r%K&`)2qeOFek2Jd#8_G&{Kf`5|AQS9 z)(z3GmMvRmU;XM=Jt5&>%NjlJ!RD02Ly5TH5uNE*PrPoMb{(`l?ZlOqMnM?6 z=;uuv<2&<%=^p?9tppk+gtoJD*;iO*$j~b7`mWqnBa)HsCL@^5Y*GR~c8u8t|KOsD z4y3xbDUiZ0tyD|BC9S#JB1ft$vVW~mu7GFSI6K&x>n2gTNzGQXZ-?@^?6->6eB04c zVlT-XV53cSUxR5fqq^m)*}m&eyIC835fDt)zWdN-nNT(QEQ9jj`j;8t0ilG4_yvrq(vQCFKsA8QJBgSF1XwDPTaV_tA-m2#_cK(>V~L zDLL&{+O);m$IP;h@uynLxnGQ@iyqM731xV{>y6z`jF>loKYb!QJ#ECqkBC&g`A{$q z8{|8JpUm%8Rk=S0c}AFHg!Yyy7(qtc5xaht*`*gR_0M_0eCrzzY;Y|KA)_004&xr3 zcawimj@pyqA$iGRbDGvl*Lu)#zj(3I?pw9j{aMD!568{d7+bZ8Imi48|Bp*WWD+5R zAt3#=0|F9DNVrzTzUTKIk3d3#1|{~H*N~Ukaf~gG^6>#dPE~aK~PBORSN6^=z#g%se06+jqL_t)=g&iJpS3pz}d68wu z1>XsTC|HS7`J%1bu&vTk^T&xG%yQEZ@_-CRxJU*^#1M)T$8a3^F)8aSNWfv4^W493 zujkg-p`CSMGnX9M?awaG^<;48iWK!E-Pc>B@+C{Ee8nQWU$@SbOxxHw*$y`1GZ5YN zPZc5BtkA>B^?PkX`ySicIo@`5me^gLm-r6K)OYm5Ipm+fj{!3)z%%C}fc;P= zAK~ASq*953g%dN!p+&lQ))+VE;vAxM;qSuGh8!PcacACYr8&?APoZ|D>CwMKD#M+@ z1vL3y*j->3B0$2qbdSP>&&=y0jnoIY4sE8cfe7uVy@3!Bkt|2RA59LVYKDMrr}rn~ zehVL#_5)J#*8O593+BrcF7qV;+5Wh#J-(+yUj|HWjHJd_F~7qU0{wCW?fhiMx1Kku*zhUjLSDIAA}0Zim;&+|YKkaFEVq ztu1oVpuHhtULpjb4qzWHXKltM)qK?RO;7d2h?mJ648Y!9098-Ey2jR3R9f+v zF?RKNr&<2`|FOv7ZThRQZRvAt*O3l)0uC9o0X6tTuv0$WDlIe8Y^yq_+mr35*^Z=1 za(ItwTdr3YbdK$hfc!x~?Rhzoua*fJ+J>$Bs_jT))Cs-09W6uDl!>;p8_ys1^YmuE za(7^kg_ekZSL?ieaux>+W3GdV4#eYt%%%YNd@df~We@^42wD}&ggit|m!gE>oU(im zrOY@1M$>gNz#6}ky#nNv3Akiz=V&)RninJDzCbv912_S=sj4{B{c_9!I*BSFXm7|D zWO-$s9IUk~4?$Afz-T%xZf!{D1LH*dAYn!FksyovpPVzvo%1y`hSnuZeSB79y-L~_ z&$}XXDo6r;LkPcb=7MpeZv;~a+5-B6&qzUMwS6u1e{61Yr77c!ZD=p`b2$ex$k-s{ zLBR|Q&C3}XyEX7iMmT1=HC_JqdY$IS^!Kn*WauZ)?2wk`h)mt0j^AFk2qi%Wh*EZi zGzcGD)N@`Cv<>)_+`D3*C%MF#9p`a;NDxe_AnfDP+U%T?h<)`#OZ@Zj0Ezsv{5UE^ zKFQ_5nj*ZkK6V!DYf*h5Hbie+lPv?q}~>TAP>a^e-jS>LNoh&A%3qRfJ}!*J%F?eyS_cfKZO3~KQ85XMz;$}*(xt~++Nru5ylfj2MIw!UYKdqrrE4n zv;4E(9?*n9MA+2^6k~2fVnl#bcY#DaBHxjUUHfdmZVpQn7$(D4yXl2bCtV7z5 zm+MRHus|Dx#2?#d? zq6^V1cCsH_Q{}lkXk}VwvuzjHZD>yxXisxM&Tf92d=rEx-BbwYcKQW4UcKjtYdP?B zAqNC~hiU*0*=2?(K%OuTp?o4ov9ph(Hb5UyxBRnKkp*_|89R2h0jli&;|Bqm$n&tb zZ35@f=vtW4V4j3u1=;~LPK~MyaE!kJnv%{AeXh{7;|j7YEj7iD12_|@jBzD!K&`YP zoKKq}Ob{MSjQSG#()|cwbdiu`&yM~l=S)^|#W#0|(cs+va;5us;FyhX1?>l<1BOcl z%xN?2p-;>Y+7AeurpvWD9G_*4_TAK<+w{mDh2(9uwVhMDnu%rwGdSiIKN84CerB?r z64`3aDfw2NIoUQZ{;ti`crgc%z2}rP@@0jz2H=x>(LNDm z0L>J+IhdC+t?$n*EpzgS&j``K7{j?DRFJ&?l@AEHc?hM;`HU^Ze1^*BeELi1>XP(U zJ8yi%zI@%1uD zPV|~z)yBH!OVy2aat_7I7*x47@oUtc}L&Y#n_hR9Di z!4GU!KuThXN$l%zeeAE9u@3TqoP=jcN+KQP`)gZY-(#B0ANR&YCh6^~4T<`Wu=oVm zVQz3jA8z4(L;ex)%MX6=1N;2vKR?_}7_D!ZM_@z}5H6CzJSI`&Ib0w;v_F98-WO_V^EhysJK^TCZL5z^g!X&`m5ju`vkyw6xd zJn;RAmA;~s0UiPCnEbF4Kcz6MM@RG6@^}qM`PHkH4*FJYud>5+^_DKebHTWJJEvoX zEofU~NkwJ0sy18Eq?+70o6xezhJAHWQzQW}P}q6NG8wc9wyJH4-Pdux1JJAIm)LjS zHRmk^gtfF@Hu;#=KopR%S!q@&fC#9=)TQP~gLXp&p5&J?wWQGP>=!9&5n)&%9FPL+ z?QsUj$(IOLBrpWP1KinprYuZ~7!y9nK|Ba1SvZ?JIXLg+K2Ks@+ zJZ;8T2R{>h64)WfVVw6tyj6P8pn2Inoj_Pxgs9lf8Sg$i!T`WA3a&&JNbZV zHCqnwtx>-f6+(X@L{!Nb(2tNLF?v3ANBu(DMX0`#`oA_eX@`~BZd)z#*=W(Wu3l!bT0B1yiq}k?*hFZ0y7mlJJ`6<8hGhuipN?=f2N8-TBJ4O*u5hr2+l@j! z+AP4Q2YuZo5D=WO(R=_V-M2$f4*vxWt%GWSU9mtf4#}9%5N?=Vb$~7Q{b)%5yO`pj zEm|YZ497OKC_J!$;0%RoKHMbjh{zTo8*oh-?4WZl?`c2tSRu0@$d>-Q&}NV&W8Ph8 z7s6O_F2v@ldE@N!7neuB&|`&2>VLgZDf1lpoG9Ed+3J<2U8Z#c^tw6cXjdNKiv|LR zb;2S;Zqb4Ojwzet(14^Rb=o}3%`$;*<|B?Jv01p88hZPwM4F*Dc&YYTW z?_N-1-+pkDuSc{_)Qiwo&QllM?2Mc=tU0tHjH#OD8ZN@}=BGt$QcA5|K3Up7T`OV* z4ayIn+}5?GRHVl3O`$fbr0r;bFz@=!pDpsaeDkPdU)}n|HrM!IDoDTt1g!|f5lsjh zi-BlD(EQLw{8<=tv@6IyB_w6Nlxj}De)TLnM;f7%UC@FA(^@vLva+(ex)l6RVznlL zobU`G>rWVWuED{atNU|b4)Xn#-QV|^CgX_Cy)}_JvifUBBEAn=e#VwWgu^Xd3m|pi zkDvYQXGT)OQ5o4IFiJoMIlt_Jurr=$kRF;BOuk|r!?{>Pgt#d3<3*-Snc^lu$75s5 z1s0PpoCgzmAp+QkaE+*ZV{cTU-$U`dapOj}+l|*>hg~{IOGwnnSfWWnqtqMdz;>2s zW3ge9F$1|*8N}J~B#Kn9(`Q$=Oi2f^-Cv|U9K8t+>qN|ACw5X+o7LAG_AyG0wAsSi zC+w8u9iB*Vb=wpNZtOe*mf7vC6gURV0rCp1)@CUh66RM#Lwcrjp}=Lj{lD*>D-)P8 z#}E)AR}mR#mw+M;%^}YOAeU^_0I>6?kFnKTcG`XgH<($HYwx(=tzgbgZR8U`wscI+ z0F?k!Rw?FHkO+3a+3f}t0<6(W5Y;NWk{!!;4UKq_@6)1M?jDo**2%LOvYi3_)W-Ux;pmHi2Dp%)j<4Zw5~2S<<2eO$_tJE#Kzd3~Y%{zeY~V8A$QC-j}fgJ;PU=%X_634*5Ke_q{X zPb;h}AeDgt^z(w~OpF;0-Dj5-I)Hse(Xn2Ue+q|Y2pqfUaGbvhtDKkIVxP8O+qjN{ ziiWk*T9Y$vZ)BVuXie9;z>}ua3L;utkppg~wV`v0?XqI~@9Y~bFDt`|Sukg!6;bj; z)U9Z{7*8U%{l_1l>ZV%M&zi^20n@ZH5env&{@kIQA^3;@;voQx7a7m-R{?TjhKDI4 zV+%>a@g7YCWEY>6b0%lo;*5RrT{+e~1akS^hc-DG!|#Xn6gwBRiShRb)yaC9q9|S8 zy=IpG{`ji9u=dH)j)sdM1dwmm9X?952OlUx^TwLabuXj)dvc~Qx0G2V@)5}Tp*s2O zNXZDP{Id(D+WSt6-&D4H9dDQST-V8qgpe&9twlV-+(S@e2}vwb;dQvr^;I65D3Frw z#3X#i4u5ag@xIFCJMP2W7r2)!Sg@eK!%wR3xqorrXPgqb@z~p-Ft?bCV{P!uU;fgr zzyA8(4juh`gp9x_0U6{(29S<}-31q1FvwEkKdrlCI3e@cok!h`kVuf-`R>W@;;-S& zBe}q0hneWUu~QZjR-y8ZO@{bpYmWa_Pvot)QgOsX4b4puLDkN<_IDHQDNHit;dN;f zR#evb&ON{j@Vn!1gFslOn_^wJC>j>Hr}i96K$OM2=8)QvWeu{^KdbH`o1ePhPDz*9 zOWqvYR!d%qHvK7+v=E&GChhdIvp?ImJD6Q-W%gLdVyj6XFA`B?U%G6j2!)c;30MaW z$Z|P80~pa*u=7kvRc;Jh4>UR$J9Sc?T{(B0r8gev)ftl=<2zs3?K}FABG;G*cKR?Y4@WZXV{qsO_@Qy(7>WlxLrz{3h;L|Wc3b?kbj-Or1>)rwqGKQokPpm+T+5*L zpCV#&<=kQ?2ftmh+n(NZ*ol*K1uE}BGQ@81rvOybCJ4yY(ttqb5Zdu8nX3I<8jwI7 z(ZHbbiE3ForQJ%ii)N0ouU|FOUYB<4mjbnz2m$gTQ;Y}N9RPHOT+h>!mG33xu)V+K zUK^hxqS3j>lG|lQ*QqhlUz&VFWYA>|I=Vs;(hgd_{WNl|HKmV}e@B)`Y}6;CP4mxq zK}ONu0P1;KmAxU%x=XT^Y($&`|RJJ z+2I6)HRbDBZLN|9M9a+y$d@mhVM`UI>tq**!t+O?8v+x%4u``QkvF*b;g z5fZVHc(6e`#ivZjv#aEX5yF;sFZYd|)%Lucf0v8Ev@|tZYKzEbigvHlWg3^Y(-w8E zvBhaS6k4|3cBhxyj=E?j@lekGx<<>X-(eZe2W^AQZ+2UW{UPHro2@L{7tI`N*D2=+ z7yVcQ^1?RNsR&CeW!^KhI7`4g3che0uMi+TQwbCSN%^gZx(Eo)nC$G<$ZQA=3 z`h)g{+Rg4U1b~dwQBX>#(=-QQQ73Q_Caq(@CLkQJ&6))C2YL?i?a3Qp`e zBm*cRE#sBI4|6X3A=s^^E`Tva2T+SGKP0GC8ie^1azs?x-L#6`cr+dShKM?q)Ldt^ z+KDdA%~95I%+W}SrzDC3-Q*R?RER7+`A$92sBSuMve*63%eLCX@_#^^1CS2pMU*QX z?Cpq>E16!YKP3X>fN;iu+!zkNHO9Y|8PR672{R`8$+_x+mnY2cWC#L-*5vZJW91Zn z*v;f1w2T$zX5>(D{|fa#xwFm2Whn27rAxz6WgqN#*s=xS(`3e%*C{`TNV@_CB->$y zC}^-uJ75L&U+q`wd5mjc(7-@sA!0$8TL=jA#F*1pa+chD`E)0H^!bU62aV9So-|S? z5}1IH*Q@nA*eJgu%;wOdA>{hN(VjAyX>#-6yTLj^Ab^Y=#18_OuiQ3g7AM)4KX8FP zu)4~_LX$s)?D3d4ax86bVNL59p`pw1#LGQlmA7 zLplWH1E-Id4@~?7gf@Qcj+Ne4)+(e3AzD|Ceq!Sl{NVPFp5blvFHYhI2to+M%XPgc zlhs6Yk82rZBoLDB&)jd~5i}${5fnaSbB^mgzL?=UA5WPl!!aStI~#$C3_jD_STKKB za1fsV-h1!0_q^vly&XFG`3M<-5lKL}5yl&hW3cncMF`Nzu1R;BEan?v~*-5xM!`IXEz4hp2L*|FdD*C@oSZjN)Nl-Q*F zRJ$hm1)HiJ?nspq5wx{GK+-lnR-r-G9#tU03Dt@Y~aKZEtF+qHw)=bI0rp zz`s*T3n>F~QK2YWm@GBQJP1(F=i&-pHlzVK2Ixjh5zfJ0o^#nTM(eO$1PHAOgdi!R z-B6u?Mgid`0RW{e#ujkQd&V5F59mjOaLs~Z``Pn56t1`4!8$+?bC|65Ix7}nZ_ONI z+YYxlK!i|1rU3Z#37?EJLnRI7cEH~I=Gpgo8WiJZ_g)tppm zbo7M=sLdudZL+g$jZKd1li!ClNz#IBvr>DmeZCS@PElF-oJ5HaWl=W56R#*2vOwEd z6PSb%V)<_r$N=pgnvP{kN=O)8d{}4=BoN2%gR(QixDJ0C=9DrSTTI;OH_qySboxd4 zXfYr>IDPZ|4$XUZ5~M0(r_Y?|zB>SUh##babEwbzu4mQ~!e^Lwp>;t!gg`((e!-Mu z{4H=o-=?u=ywNCq^MQ>{gwWF2P9>T zLZSz)NqB~AagRP3g^fox;jnx->#Vbey$jrn2wK2gJow;)cJKhlFM<0FE`-H79$(<4*fxLB( z>P7u%N6;=Ij4PSU%gV~Sz+AlTK^w*eJT^}Y5p`aa6Zz`hH3D-{a}-DgU!s3)hi?Vk-bhtyriUL z>&zNw9XTa-NH+gl3(m2I+;TVdhzFy;k2?tp(lDW)^y)!rF0CmN$DSnpQ5 z3EBFSXLr~EwWZlXyGW0|D@|3nTlIZx(HPra-QuK#G60GsNTf{4SR@V54N9mNLeNs) zZ@*LwRFp*;Enu!ofBW!JI5E82oK2S@tPE-iOIr|&$t$(^jxY5@4D2Okf}1zHT& z2J0V^LHTIcnCHdP>fjH886AMaHLWXn0q-G79#u`x6STHiUw`|q*}i6&Uwock(>w-Yyy+jmJ=QGkVXd)_=`$M# zw_G`Wz}E=MCt}y#Z|rsRF5VX^ME3dPJM6=kj+}&jZ&w1sc=sh}NO~eBfwXX~>`x%> zV1htMf+i)rPo#r%Uz10_Kgma6lz$CWukJx`YT5FG`u{QFgV-MMh1bAilJqp6*M z@B=Q{*+=W3?z={#;vnHn1t0~m0q0Qw3<*)Q1nRJ}$4p1n_>MX^adyKu3XGyD$Ph7M zw;Lz*8u_>YPANM!2M6bJEFgEX#usPwN%FIqJ3ia4k(Oz)d=*}mKh9tLW}TB0Ks-X< z0H>MBIzCH&2GV}*k}Vc~BFq&#;MBuT{#22RFI_gxbDQ|ddSH(KY1uXh#9P%*2ly(Q zv6?EU{e|+Gx#_$qemL{^!zYzEQsYa04@|$31#~e_^Y*AQGeuZ-N%I5fg|Hw1;sQBh zGp@}7@ame672nZ*HP3-Jughf;HBY8}`?NvAIPGppSD=Dy@5gp&p)mbptN_^5d2|>k z>KKWV49X{|Uv$nmfI9dNt-wJ5CSqNrUgokGC=4zdvrHEJr zHb5JOpxt=K{9@N6urA1f@*mIb@G#F1*z&O=w<2DQ8^k0cZ9%7;=Zgz+o`WX&rI%jvD)8;&9(l40 zYXySBb)Jnt?iXmt17X4cgk$;>uCI`iKuo$nd2) zvdb=ur@4bZ=HZ7Q_H(%bv-^<b6srYFfR6JlSm-Q7!Ou@OB4x!eP;7Pf#;}Q zJLQw4?KAfq-vX-$b=10z#XJ+(lF-9EAa1 z07`P1kkK69jVhUTRUVSbn)(t^#_S8^OpRkLyY?&P@Lh;0mB1rWo5&}!PPY1oqz&N~ z?fwON0YFX_D9jVkBjY$Bf7uZSG~$TOj`Qr|94A|=WDFA$K+lm#5$8T@2!dsYb{6(Si82;)E>0O)8o5c zQ#XIS<~aUHzSyV}z&ZNZMTc|=ACbThb2V$Ml_sUr_P3%1A{teS)e210K0tP>G)QW~ zF~azT^3?5UJ5;Bdc#LRT)VCD*HRUQCErAR&JV_JDN1IskP0DlnK41L*ah~{770jyF>s`Yz$u#erJpe z+CNTha`rEGf0l6O9@-+r|(jLw|#)>eLrwN2BtJ0me#<-W#%u<$Rx z{IVZ{e`H@y-F=nwcKi-aH}}U$lO`RLaF+GalY@NFo(#l6K4?q2KSNd$IhNcP`8!cb z7FjoJ;32QP@`~pKc{{Fw(KZd;2#gYtL5?Mv#`%!|TCcd`ib0mr^JyU*UhrdKSAej8 z5E3p*iS{`m3dO6hzM3#{729h}umHh}7ccJG{fPa3C|-w%Wso;^kE5RE8ko*+cA{B(~{rH7b?Yj?d^xPttW1-D}q=1{z9w6*A<1CJ! z2023jo&aXX39UnkOp1Q9e4hwNwX_1!NJk#+O6AC>+yzKUnfR?|sl0R47Qp657R$s< zXdSH=7G*xnF{SD<)-_oZ%br zFHcptDORl-MISN2BESHt##p_SljGt_;}a^tupsUgnQN7HLLkx1_Z4+n~ww=!CW_9;TjvXC9%)p zHESUr;r`WKYZCjux9fL2WuyH-3&KWVPxr8R$~c~5h(K9ZR^~-u-agV2Js!{4jMQ^S z3CJL47By^8Ghcb-l|!O7vo?l+L*xnReZ7YImind)PY9n9-Qg+`8-fZVGr*X(X%76mx1YizRJ z+IenhC!0jX!S)mp4#4jLIUExmY2oCk`O!Zu+iJg;9}711fa$1{w#pDt2f#x%&Qk(5 zB88!OK~jZc0juXvFZ58YKX_uRJM^PDAPFA+8-UgB;Fz{K=v4i;UN_$pyiwk#f4xd3 zST!C7nfGs%D3V8O<3vjB#Ni!n%siP7-FWsS?-OA8Sw)~CbT6+Fv={8aV>*SFf!$Di zPasKvezZsUhJ50JsRGxVr4g#pIYg0?8JflmuzQq?bv29c0MdHW_yW?2N);t;J#db$ z^LW8IoTV-}v49|skx3C_6^KuDgOV@GL`g+P+o8IsFLq3$b$el54;l_H7gH!m^y!-8 zn=hO0T95CDXztb+5Js1J5KO%w01(MruA1TV&*zv}5t zr!4m@Wu3!S7J+Bj zpd(rnA!CP1(1vmU4}_%qGxx}N1bh%nNV>o7%e)JJNbZ#lvqfSe$s zGO|ZtL=q6DEMAr8V5gT|^bl$g4ao5TSpW+m@X&CCNE`s!dGqFVg)kg0zYNABmRwzR z)m4KXqPWg`{PD-V&t!Kew)#*D4w2jpc}CEJp!FDPf0MyxTaUNDAv7|(q}WvtmBdRx z?s-G@{URW5$Se!T@V&}k(AX@eO(!70-KYR!ahT4P7GmKfMfp;+EfV;B?~yHTjsu|d z9eTlJG#~&$G$4eQy+u3JH6kT|V9dDyxcoLS`TCoOHo2({BnIFQ-V6@aVJz7A2Yo|O z$g}cCXO_wYE2`4};PAJ6Q=W3*D6I$IoncGKNDrf>wdQPhV8#S_VEtGG+fl`927?pwnDy$NI#Cj=V2qC;z+m%<+uyv}dRVtz&N)!~3c$ zb@}aNKFp8$7-;giZqP~h9 zvhTPzVxEi;prtR+J7kp(Q$cJ3vO!0}Sxk3_L%0Tl3xYXUcXGmeuH*d)^APJG-`&Iu zGhgmACo0Jz^>c4V(8iRPm-pAD(eF?45f~*PgPcHid7eL-YzaS!!P;g5jB#w^qK0sT zg?M1f6Dz^zgnAO~mqA$C5JqvRv^%kViG58XLT<$5l7Ms#m2lBUYXC6_yGM*2H^fAk z1Ox&SZ?^S;_A?NWq4oiamw=F*kc5f=aCYlkWRst+M0Q8ol@~(cTLFK7Q@}5~-dWmp zA1gb0@>VPn@c!pNY<2LB^DSTxQ!UJX0H4^~&zF|rrt_z`jXk6UL9=kXlI`JuOk^d( z@V2TRv?k1NEP!Tb9*1^x1_0Nw0{oM;t9_w-Q)t_B%BKR*#Hl!dZm*>4A^Iu1=J*2S z$!rO700}rn`9tV4?OGuc!wx;<3BL@^YJ!BQjv(x~Baj(#jnJNKWeuM`HrvgU$YVlQ zZTu4&qzP#gcz{gNYk)Ffnu19HNE_TqUZf6Zc(f|9{iYrS^1*oe*yugul&;V4$Cx7m zf{7QAx)^uJ0qAfhN+u;vo{<@4^Mq6j5?M$66(^f~Vtvf29f(xjKvdI>fkc1GH zBtXKFeAoYe^T6S7lAM#AlfY^2AK@hDyvy@E?|aUa2CLk1N!9fQ&K3M=V?C>e2UowR?Fzd}(Wa-aA?f{2_AgRJ`B?THxvTY|0Oac}+ z86NUvVgwL$JcI2uVnGAy2M z>zz425i;hK=p3L}2?&vgKdMvrf_1g3_@qQ`B{65JmjvLLuG;%l5)~&L&GriA@fPkj zZ!}V*d5Ufzsd`j0E+PtmB&0`{$DzL{8%xvy?=;~3YRP1Z<)!}CQ|n9~gSQ@l>N{N{ zDPmu%B&2f!gxRmZNCU^E@)FW1s%sIwAfiGAsrLlH0mvjL14xgzAYx!%LhUOWV1$Dl zj(jCTlW#yT6xIRYF3fDe8ITKkz;h0m1`IPlKs985=mjJO;NM5UxF9#fA}J6dHiRfZ zkciAcXxO$z1qC2390yPdx!`$-9mmt=1{BzUHD@f0n~G74N2k>>k*ev-PXuH_Nr90j zwITAq(;{S4}Uekmd;p9^8y!ldTIp3H4U`S=Wm-{5|E7b&$*m8 ze&*74Z*a|-eck%T0weL?m0AkBl4C4(=S5>?YZ5at#Fl#>4lbx4A5~2TM>`HW}t+|9h&zqJHK}y&9 z3K-$9$MZYa8*c&m7+%UowG!l3fOoD@vc3>K0ij?33H6CK-yAZML@{T88+{{k1jNWS z0Q|;ku@VrDM@RP`JipPBgK3VKmnM(1pgN^^8(MoZ4C z+PAH>466Zofo`B3*a>h*)Plx#0BQPsys4ZGA_ahMsynslu~DEE>M_38ZfpP*`g{IW3lmQ9)QL)HCV)G zw#d2!f7w&ER{V{GEl-0j)wTB3qBtg!F1-H`q;!!O#)FKAXwGH zdd@&w56MhguWe^4EA^TD=>Xw%2XV80l7*ebQZW-7Pl9j?UAS*Hf8* zAT7f|hx`g)nF_{t0QVwMe6Ahdb|URw@)b{ld^jNqCo25jkxZS$bE>9ctZ}j$6DQ-E z&7M8mEn2k54own2Ijy|6!Fur!5E?LEd+oLQ&TBSB$Tz<64J%Lq{)3o2`skx}4oVb* zow`c;lCc)?9J7~z#Issq+wz9x2EeHF!5gn54BK@a_LI02zb(2MG}4tVp30~yXtfk6^zcZwtcMvxSF2~6a;ATWHva1DsO?Gva6 ztOL5E5t;d`YbE29%%zDk8(zF%OaYw9Yaq!UsZ}&% zmPBPp?uNY3EDz&avIqG$O-(`HpbU8}_cW55(ss`e+qv~WNClA_&H;hpe&U+6F0pOJ zHjEPz!hJ>wWgfZ5rs;QIf;arQ{&(^={^`m0t@jCQPo*?K|GQdW)|~TlA3;JG0F}`o z3ZI`jz^z@q%HG#6>>X^^qgpu}lU1m|M<_^s=elw{hz;wCybTUgB0|IcfKf<+`x}A@ z*$2 z+ofyEeav+t%Eq-i77Y)g~UZc|~0*vMi>V`=Mkz!G4R_t9(t zvs5zj36WoufX;V!DjDCOd{^>4JYm9wqf_$<@}7|RNA6#K_X>`qJGAi&-^t;m1kA+w zAUvT^$Rtc&Ue2-E{#3D_|NQ5U3Y9n?eQ^TjL|#j*1cdKl6foq!K)#5!MdlfO?sK1W z4?OUIEz7Td^(*(uPk!=LS)!=p>?I&km!;z;0ldhEFp`2hDxt`S7Euo#F+2_7KR^WPLBJvkcP5U|C& zkI{$_qgquzkrtoC?7_E}PBDLgG5sen06vwg=mJlag=$D7)zcN7r0Bi-noP2kra2x~ zg(rG$5Rn12(l`>YIYv@5eIfwTROAXb2nb-WIvT`At<%3a$qv z4Xe|`#mI@Ol_@P&<5su>9t zPla{z&ntlx7VY^%~`HKR7YZW$rFFP_q2+a8=0KYduZ4-^u47YC%In2rs>0 zXc+i<`5q&SL_!AZTGAheYe#2$`qTK*#M}q`&h^H)2e*m5jMe>rwVGIdSiNMDVSqPZ z$Rt(*lKsl}6#<#=(v^U|GpE$m90(#dtQ(vS5*L1@3thb%lD5aa-%{#+mwugd6R&aq zeD(NbOy}q^k-p+A;qxNdCF75tw3~iG+mAwk61!xQ8^Iq{DW3GZx; zwpQQ%_P4D_4Bt6Ot{^4l<>l_4d+srrTUl9|<=Rl7#yc9K9p_|xE?xri&_fTon{K+v zrt;nIe%IZ3=ba}^3v32X!XZtrFu3Pbwq63#$*Tw0ec^={Y;VG0u=r?(cK~ootINN@^zBBBMA<%P9rB#}dNdmyDM@q+RNf`1VdU_)~CU&q2Va0KS^?4Uhw>zxv6Qs6+UH!^$xbupKRrby0q< zTUDcoQ-z`+%^7ZQT7j!+jZV;!n)3sQ0LK7Cx@G$YZfgawiGn<>WOhI?kqW>c5tFJq zJl5J*^8wgej|{xxt)Q6q4_&!~{Ei?|e5>R$%n@%ZP3s6OHY%!uBr8`$h;H2+k7yBc zB|37`s1GkOo^U`bxgiibfE&cc^z-^1Ku@zh@*IeskXX&Q0J}Ryu;gq$&H(6ucMGW; z{aw)lK)mJ!3DQ3sKi>8kDhqpqn)3mcF&g>3phkT3SJ@4zXdRQi81Wxx0dNjign-|N zXbt-de9slBp>*-`HKp-TfqOoCv|SrP6?=`bTVlP&$aooSG~NRFv31ff zL>nN3L`~SAd2uh^qAF9Ay^Us7B5#lo$Rkl9qCiB$h=`C6G^!|Q_Qz{fK%-;&C1oOl zP1}qJXAYZWB$n6MhrA;QDx`(`>>^42Zr1r%svphIUfOIVor+h?g|Rb6uIbI{5knO$ z@>0kjVcg7tZPU}zb*x)@k9JB>Z>s6)9H>sPvMW zgrB5`4u}kz?<-UbopqS?(9k+h?}Er#&HweEf%h_y;2#9SshLZ738nGV<`l z567f9>FAirex32g69M`7$3O0V|NGzDu)s8tIL42cHT#eMP(GK8?{MzLQ`LG2NGGox z0FE9O82a64dPP_&Q4c))7$G`5{heui7cPtHOwzjzAjbc~qdR zZArI)d%zfS7!rIT1oYXsXk4)?D@Zedz&(Y%w@*TijC=v?{U$@oN(=f|kZ4Y0x`8>8 z1}Rbjcmwo~64#zscns-m)9t-%XNIe8Oc#j}C>0s7r0c9qcm32s?gP_?i@XG#vFScd zMXe{_+aa(Qcx)j`WH>zo|>M>N&u+wqH``Pc#$y9 zT9eF-^eRYx50b%IKa91(fPtEp$+xn#4o66+Aflpi841yt0Lny0rYH)6*ByBpkM}Lu zeLiGxzqakAU}hb&6+w_Gw&14v-{KO$-OZ!|Rn7QI{i+zbcmL!U0Z$^1;WB z%CNOm7WrU(vNdNUZFthHDWQTqtbMp~4?ub;lg$2%om?3R(@qgRqD&Jt4)Q13GDrtK zINnxeHLf8Y>Kjzn8F?C&urRuv@6|d?&>XKCo9pr$wzwl1Ic`bAAj<(E@?*f;?u&ph zupV?Thje2L->-F#EUz@ei9CsM^FvevqVm8?fsV}Q)jYV`{BBukhsz5o%nqgxe6Op?9`0(TwuAIDKd!O2eu_;FPuuCXw-mc~TSD&6=FciB zSl}MK^~6T0exF1<;_$(njzcJsCBqXjwyqun88qMLNM*X3v)I+KBzpgzC^3u^k?&3_ zV3AWx4g~p*hij$TwGr$RI&UIK!okIJ3M-)PCumO)Y=E7*Vi*MGU&Zo93m zO;7sgdkIJBI1{5sE~1)z*g+l7M7&t@q>Q!;*19L?NV!Hcvp9 zFFM&rB)?iC&pjQZ&r~l42nIkD0)jV}D8Z!@2MGuxXF6=&U=oIhWH-4{%~b}}S+Aj^ z#<;~*X#(Q)$~$N=c@od>P&8uk#yysQ0XfK5P1ok;Bd#zf%?%Ph9Fup@m1GI|wAx-N ziOTEKB;#_fYCjr&Ntm>qf)du9eA?hF$zF0@eRH;ZwNe$SY7V;E{Xw1uQls$Fwp6n^ zYh-^T2wMeCeV1#z?HD;DrG+_`*TGx?!lOhqrVJ~vD8pM@>kNz`MM6Twx&TNAD)D%v zyz7t-WNS!(h-Tnv_a$lZq(g|vqadP!JPdHRWj7^!Au7ir8H`2CYz>^%LY>y%ZPv9TYQlJ#6W5x&kNebolI_C{va?jtLZV6#oU=z*Lc-Gk06+jq zL_t*bH)75<5Yzv7Ws3-Ay#et1-X_EYg$NQZa1V%bBX z*drh~194DeANarr+@JpRr#9!vb@Jtkzxvg$x*z=D2W@V9vcHhB1O$mxd)mW9To?!l zUw$MV`&mN$G@ui3ymZqpmoJa#pv(jA{2>Bt@+47ttkGqQ%&5e#A`?`O zB3A@MnzUSr;sDU%ep&7eMHj5ww+I2A;o_VlZhXsj*U%!(eTfxLRdbCHq>xS3M~X1+do0qsGePKt(tJ@Vf-~k?9Cy z9tF;j5cVKa!Pxj6Yz>H}DimN7GJ|XqKjhmx1-h){wWbSP>jPyC7!mnGR(DpU)uHg7Gr%2R=H*2*_(9dXH?$ zHUj3y#_<>?Ylhqk!a{_HhzwP^$opaKn>3$=>vq|k*dBtbrLgtpd=L*v6a;s&2net9 z{94J{kYrJv>f6^&I7%isZ+rHFq9NoK5&5xXeQiw626Ou086|E?|HJOJcUHTH%ClU9 zKs7l+BSbox1Krn&PLT+Iqa=M5lMOt7<87OPZ&+e{KG- zu4|Ti`2LC3t1H&^Ia#;!6~20^#4ysTPk;K;mITlDX*?43 zlW|Q$q1Xus&P(6?ZE2e(*qaQsg+iG)%llX;R0@8(x^W1aK8Bn0| z0l<@+h<*(iZyplWkQEuY>cV;0wL4`|vB=B1IGv-r;{imfhK`XBzGwy^qF)O63K(lk z!~_j)ENj~x6~q|Zs#U8D*eAp57bznHXp@9agT7UjL32FeL-TGMSk&*Qi!|UF-cYsM zZQZfgjm#5h6TdhuG{ofOL?Oo~Knz&O1$ARQPv z9H7ur9jB#khmz1U-H_p>CfQ;8T^iQ`C7Snz5@!Deg`bMGjp9?#QWBoXY?(+ZYhm7=#;bEC59#CVCD)iW~?4 z{MAdx7)XU!uqGG@=k$G8F5<>m0i2MBLz0^j0b;&nOF&py8>(;-T{xl>r|C6v4v2zy zg9Kna#j`+Bh)01445fqtr~7pbA`INCL@mg}0Q9nt?^W_$b=)T6@Nddlcy-fm$*-u= zbu6mFIU-wxtHB@TU%WD{%p5fn(NAc8@Ksawt& zZdJ+1huI?O7r>h}U@Y&dZwPD06#Em(()dZ}X3bb{qC{Cb4pqjGZ?QIv8xl)YgxsHa zZ0Y7bmIp(5UDlE)3RS4i4Gl0U#*?qFb}v+AxvHitli?8^!MJ{0SEOIFC7Gi$doqk( zG{042Os)^>f z*I1L@kM7WgU+}&{uCPdXSr-l)byvQCiBKR>^X2QpH-tP8^&s?$QDusVQao#$%nD+F zF_M#CU%lDAU%pLW^nKiAGpAYgCA9vDvS>20)gm50e|fV>lmJHnN4)<5ASAI{rEK@_ za|iW>S=>i`Ed-V(j2h|+3-WCrKqMt@w+VP=s{aICqXC%M4w!)qX%dOtzO?Epd5Hm? zIqCq?R9EZv9#Yxbyg+^kXvOeG)5n2c7BnbiOvq|TNWVhf>5m8qK~7dG3bC<9&G97p z8<5@NhW9<;TjE!ZrNwit(;+yd}`d-5m9qX@t-02+gU2v-aAw|eLGJTC$IDerpG z*n#f$3r5=CY>y$w`l)pP9$e5=G?0=!_DYAsk4bbZ8?09FOr6X(77wgBvCqS%etTfRU&K(I58LGTOYf z`EdpTVSl7k9G`=qKf2IzN`Csp8*X!bi`#if5fH5-IUUw$Pn$uIhO2B_nKS^%$>=2nz zqK$j--sgkrT|};s1#&+SrJ(}Y$8=7ry~Sf)A|RZoS!3Axs>@vWw9DAB(oRjT(f0bo zZpq029gAl^o>O3+PXl;dQ~gPrYj*M&5Xnkw>#>(f?fOdQaOR}3R*~qkiGvO7*@?UOU!;r- z;zJ%tg{nYVPYubQsN6%j(R6_`?#m1%sUA3Z$f;_o%kP(GUzoYsSt3jgmh{b#h*X4> zn^7qeGFTOesH6o@Zctg*DkX*E)dpk*B})%mLOZgP4Lj7wqh1NzD#JTwXrXzl-`(Dz z#Nh)*S^zx&RmgzJmxOyb&XuPP($8Q^29I2l^&)aqf_h2a*6D2l;3i@a$ese35srA~ z)2L&kP$HV3Kh4S%g&JwEK?lnhk!ur0OX8?`2*BR64&i=-2Om8 zeoBi3*k_KA)F{xDKdPkZr&TEoLIB_wSF`=t7Gn(jPIE?b8jwOk`j9J4RkVrG1wW28s9(<$xp*)%wyUqdA;`_xl!>TlFWp$a8!oPE->kx?=JwJ;y!A zYkDghsHG49$K)Q-6fLU4SpIg_$fI-7=EoWGB?vpDk7$k0v7jiy^J{7p(K{qU5nOxj z7b;T`0hv8K&AqpBwfjSPwhAWnwZwHIb*wKEIr^f|g!2n?%1nxN+({Gg2NJ~}zPQQW z>ySAjPvk~HM2N(YGxFmPO|~_N^>h^90Q6y08}y(e*8Pv$P7x4`f}~}*mc9es_WkMB z*b%AX6jfP+Bz2cnO23aBm6EE-D9F)W^N4mHfFhr*$X8FLPTkSw68W4@utyHvm7ZLY z$Bp%GDm#(WfP>NZk%@KRShh<9CX1){Mkv%90qN+v^b(McRw&Br08c74;FWJEy&A==p@U~os!=`6v>y9BVxhY`YKIb&7(TIrDuiphBzz_y-3fvk^&=I z^zA?jL)9hTBODjgZk7}edcAB?v3a%0dx*5hS5z69qDKfo7cdKe;@prJJC2@1R)(aB zBy9u40>6NLeuSCz7yxCZuBc*{66*)ZW3S(-)^$XY6!t+zRd+bu)u?h8eLwKxXJ|jb zdD)`` z@2WKIP(?T)|2J?^EVn1q7vEw5f2Crkqx9> z5R1P#JFUK*Fz73jB_j0??jl zLw`q-IbM5jlusjpC=oZfKW5}(cSa>RHzkJ21)&^XGCe&s2qb9{Zvg~^E}-;HVZN+q zSF49H7l;g@b1ac1jOjv7MWy$5G`Jys)FFFkwcPPa;O#raKo|WCZj@IWnMy21*->A` zs#duj!dB+t2E?9GqE6r&R@hr-AdEMg&m?13sJc>(4~(k6+NeOPN^3G#NNWB)z)+E&X)KpKU_ zhlX)PXsC>Y#0(AqDFKKhr6Om;1Ac85L>ROYaxVZZ(UU=W8A^&4SXL8kjt96VL6_)A zjv^ida$4NhhBU1;KlDKfa#HxaNk1sjAP$_nBeScl^Xk?;N{pyJg_j z(Bk$q%R8?`cM|exdPoFf(vW<2URj|@;W(~0*7*%3!SmQhYqoLc0lW5;1Lm4ytSeWO zf&~zX(}!^{W!w9eL~h6u+i*`J^}NVl?VuOWcm}(oHrRwSz}$_WNf!^;X=a|)2B~A zT6iWI=jn-Kq7vxI1p6QU@Q3bO-};tC&B(P$G@b(Fch#tT7OV3&6pB3pf-}Oma_Fss z)zzzX66}wc0sx&T0}xZAnGaTfTtepj-jy!i@r=($CBmz2#j}4r+xq+#%Dp91>q<#E zn(Xn$rYa0y${3Zm2*vt0Wjte#+?L}KI>+YDof}ibugGIW`}>J^t1S9~hkk5fnw18o zlxAAtFauZs{p+TdSXH5D`-eZr{q=`s6%Gl^T9w2FUpW#Zn#u*5or8eT zgb)()wm@A-M5j+nldIlQEziA@rd3($>`_JThMD8t#GwUt8meVcAq&DXLXw{$1wrMo zav~P{o2)tC`DFtX840Rj`LR7E0)p3imCBTo57HoD%p;!XG|85LqckW)b_A)RqA?sm`hxEQ3Tcl)lCB_d_MX#q<)w+%K$c)moe#gB1+Rbt( zq8G&F)e{XO!pdMlL4Y8SBY5Wc|NRk=dm+I>zT^!sPuKXB%Jm^Jn_Lf~SKJc-cIG3F zq_t8Oj3!7Ezrp=-L@b6%!mz@@>^6AzDE15pr_cvv(AU`@#GT zijt{gxi;*p>qo^e3Lr2B)|aYn{_9$!x~hn0vGohQIUVSVbamDN9-Q;Pa?fUfU!Aq<|G_&MLlUZJV}XkiiS{W z&nMP)!)d$a6blwCu+N<{&Nw5f(&TQLOvFigI>Daq-~2$vX#C6AQDHQb zd>}=cG$_aA)@`;XfR|r>xp}kyEXmSZ5rc}FT`sp-iPBoc`oo!S%&;Oie&_)Av9n8$ zk{_ZOPp_;tAV_0EJk5{@z$8uAkmX#bibH+WJsbnrk>7$WhkdIBEb+MGnHT=DGOfs< zh!kXrWav-^fXV%Upiupa-^nKd_@bBZE1)()p!fR%Y7l`)Bcg)`o^q(n8F>#sn@c#g4R0N6_>7N5|g;kN?4 ze^efdUk{GSKCCGOh5QooU?6843ON#Byw8yXZtp=6pR_FH7N}@|)_|N1q6-impzaM zOZhF7Xl89vm4M)=tuT+?$&u_u;=gYiy=e&r15CtJm6KCsR z8v*IdX-dSGNUTltx;kYal|Unz><M6JPjWdP=_w_7CXe!@ zZ@vUZ>Z8l6th6xF8JoVH0xs?90K4|AK>Do~Y!Uo% z?Ad?>FeYBN=lM^65EWr;0SO8A4*rKsh=3@1@v#{t?&If-G~x|Oq}tLS-rVlqQk08M z;T)0qkn00b55Ay-vvVwt575`L8*t}2NF#YVB&>67{`P{AZti&Xhl#=HSpS4%VC0Q( z?dX@nHQJ+lM-RcgbdoGZW*{eka^}wO=Y|SxeB3A83&cx&uEZckX)q!jNSY={zC=WX zD4K5$$?KM@r08F%NXy?$$#v`3y&n?+fwXYHF`j|Czd3FqY@KqV{&m47%jY4Y$6O(M zNX));NtxZF(arZ{!oPdss|EL)r7429y0fIRfjL++-VZnEPM3A*#nJ5M+^ z&Q#hD;0(v{O*+7-Y$=vGh1ETm?s zfR#;~Ho0{hHn}x>(p*hbh8sL&u*uZ`TWID zR3OKJfS|p9dZnT}N>GRV0GR0U0q|`U5#b4dRI^F2_>)Rc>S-acM`AJ!0RgI2>ZT6) zU|T@{RP~sk8V_rNSDc6jq~Z*D4QU|y!Ajt*Hfff|0(u5iLuMcs)w>&PoPBasWl8%0FauNMM*DG2 zhU1^*HAsb)%Z%3;Ej>$EFLEe2H_Zz*eak_qR8qLoH*7n0VoXpshBHuQl0QBsAQh|j zs{F4aS%(yj*|>*lR6zqnlCv9h07?Tx1UVn)%GP9w1aTgY$@BhyA|wF`Ni(lIxgY<0 z^?19-Y_oR$g8<$8!bVpik^oVF;IS@T17t{CSIz?g;aWmC$;&}PMMFf4ZIB6aKLi72 zZ34*{_Y!#`Xxq{;JksmU13g| zNwC6pJEec+vmK`$@>y~SQ^jyX`tK1UJIQR&+Y@WX+?Zoe<+o4)i%M8G-gu*X z_@c$Qkth)x366aa3to%7Q6dhTkUzU4D&Yr;Hw3m#L?V$T`G`h9?C5KO`8*m(4rC`8 zhLp^Q&M&<1Li3^~>O6pY%E!L7q0+5dx6ug5RTrIQRj}w19jgJR4_=SI4NhZvAQ3^O2lOW9X-H#OV70V34wWY5doS zFo2MWY_L5#`iUZ1R7s-YoF^fS0}nq@7xD?hpXW8~kMbxZ*IFTY5XZvP&h|t#hybvD zoR@Xw2N_liziV5L2>>LwhIx@oaG;UWuaFf*TeQfv`+`0Xhjl=}B|pf>sPx78^zZ18 zRqN90oCo2R_=1rZx}HN`7#Gn8h$PZ62!)ox)}NBXDjeksGF5p@L}ZH+;vp$Il$n;w z#;oDnwFgA+Q5Sj6;f?Fa@feqOZMEPWQ#Zu~r0`xlpDTX%pAqCpNd2SFl9U$X~s-&GM9dB{rl^+~b!_C{9X$kZ5Zc z{v0Kh9~U7azlHg+CXjEgZ)yK57s_sM^G3LoA|Q0J<~x)K0g-}KF`Q+K7A>;rklVt& zm`c{u`7QJS0aTxg-Mt~)zR-=oC%*EPuNcmuis-%f-s_*XM=DuHQwwl$g=%7{VBdNsl|pDey-x0SUWEd-h0wE^zG2zw!YC0BWN(GU9uiPQA!$gql7fY6zeXT@ri8@}h6^)?=o)U{N$UJw_6 ze?R52ur8e2UD0)7qgQ#Rn!3a4$&e-Sp?vT zGEq*~IQk!0xCX1O8Sd{Xh=5qI`xg=Jq+oEP(s33Ga4x}0!Z}m!W`R| z`;GgE`x+xIMMUhZkp+s%OtAgzg(&}Zl-SI5|Eh8{kmYfo5oLii65$%4Yli&pTZ;Vn z3R_W5k(8(Ie0+@vRfAny2(Oo_A%)D(Nq6d3?ml~(qMCDNC*}M-aZqH-IPj3tk}Hua z#`lOXWDn=t+(Fle*NoTpHfTv;DZmk+itrp<}tI@vuDqa zx;;eWjyvwK9NcIdKz^Tm^2wxDCyjRAWIUI$1O!0ky}BJO9NUpJhvxF;$u>_4x})kA6)_T(V2=a}ts?zCu$-J6le3Y>0wH1DVf!S!C&ReD zzFX+5S+kN7I*-<=yfbsDmTUQ6b58{_33qo%IHeNnXZ_jVub_&A!NInvVn^ylilP^XlT= zMutN!$l1yPxMs=_OGaL%ie0~4yw&ng0IbiNpg*02`j zY5*!RfaZM*%GFFzy;t-a&|{0qaQLnSN;pML?9-HFtJ*4lAkW zLLSNw(b;5urYCg*Z5*6Py7zL^-y~5|-ZoCxtxt!`%aF|_qWWaK6ZrI}KkXiV_+fYZ z?YEn^Ki>U&a{ELQ5axj+{J#6{Gsh`?bs)R6dbs)Kn{9o_K~4qxt0y1;M=myz1q@IJ zz>h`W=}XAcotv8@*~W(-(V6b3y0t_#!O4H=N`gILiV9b&R;@akXpYp1wW3@tMs039 zW|aC(mbVNtN(C|O{PWLG%7<%Yr*b=47ye`I0Gze8JFO`rUw+;?DO+!x zq00v#Qgx`mA|Y3+OL_mkIR=8CR6YtNfk_IcJ359Ze~7%?c$h2q>~rNc^(Ggh%Qy%Z zSram)BIN)~8=mj3I&HAY$0%R=lyXWcbvytk6_Nm_07E?cc)>59ILO_0-iV_FgY&Ia zV*U~}CB&PK5hWl}LTBgSE!}RpBHMQFHzxsJd2%=K_E(C;Wk~YFpg0d;ne~J$;H95d z+TS7(YeWj@4FZ{><9CpGpk!$62{hGn;Mi;%-A;Ugc@?Uh^Slu)Zsy=)ukTd4#L}8{x3*5_(rvc?P;efIB&3pjk1>ko zum@!0O(j#a9*hGL2LXd{kfc6Bb3-zCj(W;Kn#c#?ybmg8hbmc+AdKtI@x<#aT7*RH z;&DapgCZin3@@bZIT7IvYWRs0qp-Qo%^H#GuAMW}juHMJxmfh-pt>2+kG_h4(Hn)x z)K;xKjRLQjJjmUwF7e%I-+OMo913;HRXSi&Lx?buFi8HOJjuh-4!BQEOp`bC;_e() zQqM*7gU@vGC2^FbicypW#~en!BE&sa3@073Ypkc_Wkfz6fBbRx+0TB~{p@EyOO>VV zoku$>@K;Mf2&dB11J4>pq=Q_JP$+cNOV!T0*-P)d^Ny>mth5rmkb-2JCj|g_NKZ1& zC)g9&DJv_B`&0mCh=(t+o1L9)a<0gdz9gdag+(+ZS$bi-JI_7$oXsIwUF6YdzW(~_ zb`JENT{TD(_a_OR7#m=mNRa?zfd~Z&=Lb|WcZxb=1MFvx zF0%6>C3<1)PL)cf^3f4{PY~T8B7>Ca#Z^`A%}q6Kw*V_%^np5_B|HnDBE2HYKtuz= z@o(}>FH$Z6-e`<-lScrN0i@DLf*g=r!Xh9fF2At0*2XWXZ?Nry`yuFi0>R7HM96)Ce9Retd}X*}qe#wgCRRyYE_F z17*?JKiTHX{&toW#4|p?G@!aO3HGcnQ6=xShjfrj0ttyUq;Gs-(QQ3h6;tqjQ&$`# zbe`xkzZ{qRAxIlWqd+gUuqWdDkH{0`mK+?6FLElaas4sCO1$2;CIS8bQIh)xfnGoz zUV1BatK0|VOrr#($-(&OS;suYtefR+wB~*I9u7ReWNnrEw*_lmgD_QdwzSX!xBz>i z0hAG*I=sLtS0SIeSHKV;hW=l8-YP{=p$oYZ05+sNh`+mFq;dfYZGHf2q(Jn6K&pad z3+WX=l;0Z^kwI=niDDuyY)^E6ZK!-TL}gw9;gA!gO~;^k0L0-1TpzZ_lh4?Rl6V55 zr|mUO)7FJP8W0|m)d9Bw?&n^SaSd==jHGW(kF{^Uj5S;gS9GDVmHyJBbqB?fG`mW;dSv1MNtCc0f;AO zXOU!O%-xQm$*~>ehP9ulF6d{4^{gOC`lWR{-3mn~>KcQn2Ipr?B*^zwxA=YHJ^2de z49!!euF=izSL>9oav;sF{jk1DK-Zc#s)6GUJvU4nPLyQujthn#m3DpWnGLG&R%7`r zta7BW-rPGxj3$bNTrj3c$?v-?H-|_8>vC8`@{mZ#5P|jyrN!=^YmQa&qGa(m|Gd^B zX2{jJM&7u_kRmF>egFE27V-11b;l#`6^ImMo`@ra8)6EHoj5Sdotaams9B~}=j)E~ zbjLYJ$i;EOXL_;#gPa5JmB*_Ln1?`g1~5WmsCk~u3QpnI){}znDEqr~=~AoUK%z50 zu^3(y))&nphRlk{5Y-;qT3^1b_<;l_vuo}%&pcyeB6$#Pa-xlXF#gMlMuF|+4z+b| zzzWg@qC))6F}T)5ySR6$dVzJOlrT9CKV7)NDq9itz~gQa3!&4!0`kT3+T+px<`v@% z?AnRi`H%dd7Z)#;bVq=HM99D{V2`9_%Bmu#p+qi?>}Y7WP2fA+0}j9ih>a@hYds_W z&+L#zCpaZw{V(tCFv$**C6aeBKs%*@AscjL=X?Nt@Fw66GD2j9A3*o^z4WUH&?x6a z{^PgTt`;ews+D%NWAH!m0=;BlojuD$rZ_+33BpEXVW6Z~Q<-~c`f`e{Kf#2pX4 z=T>W6`xFJ^+>D7e<2oYGV{BMyL6)0XoaH_|p^tlheVu!)qRCa%t8t*l454EUAuNM) zTigXDEpDRv)nKH2{AyjM+pMB(Y#Yru$0)5a_bBo_q*IK6YFPZvbNdDUHd9GTbD2_F zWQ28^NG?Y7gGy86EOC7pyH(rLppale7{8|~TeC!Ldct@wuhJS51tgkB{t;!RNA*4A z-jfrH?;+mPsbZ;0K&T4oolMAJy^J^&u3Jw>cX*Fb{RtV^U3cB(?!No(R9M#DIdrfB zDN8_*-2jL&Zf>MffMfq0k{`VCT?wNiF~ZXW!0ryMYiCG72iL#Nm*cJQMHMKb9(<5t zv92%C527HD0?0wKj0gz#0rlI7C?wj5TKMq1Zxk5MIqm;YDFgtb_n)L>;5lkiccpSSIx+|d_amS+bo$u>)JF{9(zByT zavY)(zg=2kJs{pxN#Ag3QE+a}QQ&fd$jW^mo~(R_WBC^33Ou*E#&QkFCm15oj1d8$ z9BhNYGGvC{6LeMwtl|YH+CmNn$=$p4cf9~D<7>sxmal;%2e2$GZsRrCla3W&V?|Lw z{QB3TC-@af)0xUU0gS(|GQyN4CKB}JOGcY)h;c!%81G`0f%Ul&oEL&LjHrYpX*7I< ze7vSe5YjIr5S%B#>GsI^*bmdMc79&xcgO>g5a!J}S~t_U(k)4RhN2puICq4uafN$N zjRV*3P$NhYgM%$3fd_;IV2<>RMuZp-}uW~%iXZXk~)tkY{B@MgVtElF$xiU zN;x_ZFB%K}S~(q7(TdMm$pux=$;t?i%1?8bk5E#*J_nFZi37UdtxtF5^~dC0I?Ztg z<$zgf2^2BIcMe1e@6UhzU#}B+zZoN6ku_2m< ztd0l}6|h)mdg^@rvN09~Iqt+g{0Bujc+Uf5c~7T`@p+D8j_&}fNT!OBe@W?m48oWy ziNMS!oLu!pbcgR|9CtWb@44q5D?iJ)dM&kAAms@NUtACcUxA4advYi!`|1H$XD_i& zpiX85r|_}GOA5mGjraFA-+a^7tgNi8-3niT4009t!ojGb#QM@ZB$oB1S_=Cki$Wfi zEF%e>yb5GqNCOgW0CJz8cMXDN|V{VqiR9>1S3hy zTf2R?z1AoKLR141!kBV3p$Q_I$dZtCy`}qsUMP%*NDKD``6iGd@@mMrp?VXtsF|v4 z_FKt`kiOB75W>d~o$9Bmv-f$rmUOyj4KbWO4f_u$|6`+jV{3yVZJy}yDl2@<`e@Ru zRj8k$SeY%Z{&1SB*rzCr?#;n@!8NIDV1MPJC~7uE=PSy~F%ro8i!S5bA0+q_bpp_A zRs@dIKuYesTqUbDkCVwf0YS>cdpcE&2rjvm6c*_YX>xb1n|Hc!zG$C$-8GJ6oCmqD z&tdF|=nn7KIdkS%^S$qX|NHK1U;A1zrrCSUlWYZ2mVf{@Np1$*@;e6U030VuyV)HH z)ZzC_cb5J26~02DkX6D8ABX=PZ#^D7NFIia3XfMj`3XplAaYb6BSAb_hPD)dPog`X zxkMX)+?QyaJ9n;ouWG;hi;}(pYxT+r5T>(Iu~P*ek(^D)r77HERj@)H1Gpwxngnj7F$Y9|h(zGo21wp@#aIDd^@I| z#fe5B-$J59S=4|%0C_t&e>b!5A+B3+dRUC{MY- zH~BVKOd8}aQbYj4N0q9j8>mC-0&3$Xw3i<_*F0A0~pGYA@TwBd>fU8zL;*=;0vBg6aSTa~*1_8MsnMsWQ9 z5WRdQ(T^=mcNdnZYTcG*MNiV)E^#b~7sKX9e8e6Ht8+Y~XFcc`-=rKAaUs{J2|_@S zVnLFK-h^~df9JXhHeP>L#{Z_uLszJ)BiHB55d{|6@~?NtqtBH~H3GtSE5R*&8wy{J# zY^T=$sFs2>4yh46I+A5HA_T-!>NnB%0b|C4<+m+b0QrEopAJ zqGGQqF*O(oqC53E^#fsChXmAt_vu1;$c;v;-0CIDYxvL^!;X5g{c*w{`NDeWg*V(b zd8tcBjkX8~1cO`zH2d^2S@?dfayhEas}8^hfD>f^99k}gwx3v%?|yjWB6A|ZJDna8hHX1JVa4JVWd6Wh7% zaQd4$e0X|^mDPP-5fJ93!&npyaP6xjaXw7A`KYlS7Q7N1o2p^c1(>T8x!5T(IaQUl zt~-5*J4X=;*6u%-Y;|ilSGaY1Xj-Vj=pez`1SNGLT^tY+NMw%rGe*b=)x*d!K^}Ly z$l;Ga6jb*^X7;RPW|T(eUZ$Ke0H5ZGTpK|C|D8A1@-KoBAN!wq{e1Bji)wLwIWHuO zF&OdD>s(i^@0aG5S%m4O_iL2AU11F(_lPVvA5mp5T@w{Hv-Q=lW~>X*6Y)4nxB}9~ z`av=avbm?z-G?UiGlGF*grACr7Wd%NDkESAMZSneLT-uj+%#k8aYQ9JOLG3NuC6w~ z#rIP(Kl_q1`nHdXLkXt}(&X-_4%zld68j2yekcPly!G*Z*Clo|i9K3RlPd@a7z(HE z0}njlXiC^?slNg#OF(!-(K(z1almmh62`hKf5G2|-C6c`#fla7B|^7y$eTAlgn7+Z zXhJ%L*S@n|VUcd(^&saVnKA_AOURgLj1^f5*w3vik7#H~paVnhA2eC=quolH-EV&n zmGla*hNl@Dp=v^d++KHPu>hbXYxG)as}KUcJ6>8>tNe$9?yc1u%ric*tkexH%C}Oa zXN(9cN3}QhR~3zTTi)K~%AY7yrZAPQD8&m91;7D9g(=M|k2D9l5Hch5_ifqpE4RA^ zZ>@E8@;c`g4bi?qCu~al&XFg+zrek({zDH053V^L;1jq@l_)^`9kWA9BCb;2!hY-H zK!QAEh`tgKBq}7)0Prm3VoVpoS*Dzlhvn&~PYFF0kPlHI%I2bZKm;1)^^YVFybhTm z7XmLiy(@Sm642bZPu}%rSKp%QU=2dKI%YT#2ww;GAE@XB0G)EXuPMK#TG1G;J*FWT z64oJXOyrG_a{<7Hn62F2U~{4){1N@^(|rN>hxBj=JKTpq6kZ~Du@9j3$;^;-lx}`R_v~wHeB+pCimj| zJ58R(y$HFZN*vcdQI@I%1cy?kaxT5%AW`ep)5oFGAu0s!7YIlySx=KIK99(G#Hsnq zU;fg4T1^RiE%jF*WeErp3^bcvNiy%~^85USWXp&AIEd;H+U}0Bzy4h0azHRxPY4%L zB|a?p5GGF{6bjkzevI)xq7^3p0RofEL`)L6N#v$j0G_!-8<7kMF94@$&_wt2szB?H z?1k!5fJ>U@H7HWjKl8Agq(WTt#uZqZ%C^WG!0xf-+k@&)idfX{s20dl^S8ocH?lb2 z8opgF=?gl1avt*3d<{=D-t2JO+0f+vq;jhe0RZIt982<@L+HX}x|9a2Jn)~PJdlsb z6YR_4h98SDQ5yB>celG`Yqq*NVfE0k!SZUSSrsFQ0$>ury=?Pd_a{Xv=o(&GcThl8 zKv*Y(@BlzbK>y<0GD}+j@75|(BoCA53|K}cMzcVAIGm>Eu9cU+LZpMnhUosc>UYWu zLm-HF;K`<%7x^qi0;~rJ-f+#2sWMOfQ#2r`Dy69y>7p!cdVRIaZ8_*(uI=l#>{aiR zFcJ_xfB!p?0suG(_uI6tkU5A$I6ei;^EagK3$62{^ZMJ8BGFut@sLoC1dARf7?q$P ztHG7=XA4LT&#{kBCg*w&)EI6#dziagUFXAX!NNuE$?|5m(-pW)0@GT0BO*wch;X1D zVa+gPY`mud<5Y~Il=A6{s(kjMQP$DDT!iMUkF7Sz8`lTP5|In`L(0Z@ARt^zqBCt7 zQIsd&t2WX?BS(z&p~F0##^FbU%1;i>ql;&Qh+D;zF? z5VB8Cn)62WbJvdVXGJl1Z}LNdjF+}Hxi?k0tzy5%t~KbNB|@gP*&{MCK(!7AN!oSV zfEM>!O@^Xh>c65j@jYg^x4$%Zv@6K#WA|~iamMqUZ_>(l6!Mc)G2j0Q=O50MR52vS zCZa@C5=;2e5lm(DfO#eT485!)0Y<7WIJ8Vayj&;wv<@eUy%0flxtq zkVYi485bpN0U*?+=Zi7X#<4jE1f;Qef_vfp-KxR^$WrN3fuhC(jc%hV6XC5Ns@@56 zCk%GCT{_La%-R|Y9{v~C)~KpcooVt9*KRcc+NWrkY2!-^b1W&B=56$b04M>%NCqyG zlq%eoZQkvc%llp-Nf;4?EsCrl9|DmBIx!8+!22|Teaf`X6S?t5e+BwnKnRfC)Hfb< z)wO%wNF@!QIk8M0^q@)<9`@7Jb77vkPSb0I{t{GX!qdG+M2U0IuL3ZK)C;l$f%?O; z?QXS>jXa9iFxG0R@)?Mxkg$Hvr~#5X?Kg7quGWOX)AxgFM>UE-ki!50p|=R-YU`~} zh_=!k1E?JU-T{5H4R8}NASy+rt$s)9-HZVT-Q(K>0zw`{dj`ilP08F-6_Ht?e3dno zbrw-zNdd#`&8kwVi}fG}fv5%5qllJ31d$_A*$YV$AR6Edz$fz4$_-8!f-t{bBP3Nc zBOI&iJY`rv_xBf!I*xckhIgoe$J>pA+{QhJjIcp$AeoGfTp6EmFFt0ZjMpI-fOyK* z63w80%fBwzWZmWKC0FB`Xb841M3=u$*ZjEO?!0`AJ%7TWTc2Rt-|IRDozx+0%|@EJ zXOTXgt)41v+3Izh+&%L*yIqGQ~QsJBaS^J%#!pRjjtQ*7`GXeUtfJ)f4O0)8vZxAU($@%<#uQ z{?UEpBOmFBW#~O;H?Kf10qMemcb9y~57C$XCA6LF4zvDTNTZNj`KZU3F=O25(WBc1 z&VIbHJmT>{(#02dGQCR3qmW5KocLl)wD~f*c-0#QPIT`o34M(`|3p6MVbG`u1)#D> zg7sPBhq&u!gxn+nxAu&tfyk#I48sKqcW>Whn->oq;nwVIGGN_LUT^>`ARaJ{q=@Q3 z*C<+W{+NNs0m6;y4e^vb(61^feRWlXfGEkv>6V+oIQI$s0#NB>{Wt1Leu*S87-0Fn zh2@sJKyC)0nIzsrWF&pq002M$Nkl8PNt>i9IDF`4^D2~Z>1kW=+)`mk- zEsgVkV&({w)3vo;JkMtc)vD-ILXQvDYK(}>CzPOndTURQw)THz#d`OnMcZ6$Q@WZS zvI+q~CF;brU>uY@rrb046D0O4myR}a8GcNpWXy>O8r9W2X+gGzab%)f6C z_P*M&Kd8=CBx%>}6Y29}n@9bRJg#t3;(zBe0QEo$zmC`NGGoY;kSpJuQmt9(&APfBp4IyhD2reX^`TF9GSomGItsI;eL? zBPqVDh`Mw~*^0(eJmmPo@3NLZUh%w+0nNf3ufQ5F&jTcRzzOzw~gXBt6R zxLOV2cI*|PM1xNSr5rb^q{z*kI9Q43gG@5i-Z&_qO9DAWhR8z8u5IRBPwQVIS&Tt{=G;;P zw4C>Q&#reHRN@puVB-*Q1msawO#SKHC6kA`;`~4ogC`pB_W|V&kn_-%0X{je2V-=; zhNKW-L6U^w;U*#i!JvNy)`SDVBukU+7Wmcyi8L`aDAP+ry| zA$ox_y?|k!PZN;rC!pCcquG`85s^vjW1jDtdUaW6&21#d|Hrri;?pEkBHF^3khghx z8M!4~6H3^gtq2c!6dvgMBSH3%#{KhC>#ck&jR47G=^*f8Yes@Nq`?xnwGRpLM3O!x zl0zl2U%j@~tuL=|yBb?uopM?zBfLvd6+eIG1rdQzu&xj=KsVb>R#AW}6up9A&RV6gJf^2K}cHb9>aFVA%xnN4~a(yVdOHw@Vg>Yj|R3cj^`4-m; zati^Zdp%JTq;cFoMC_3M8DY}_AlIzhh{A05wTp*JMk%RWtE|gQynMCA@bg9fj(o=x z61GSB!e<}S(0HOJk;grm{w7jSg)cs5k?E$2`LfBW*0+W0)6;W69-wl^2UXpOehtWH0AD*45oi>U0^A`x zp(53lrF@KIt14Di%G6694#3qtd z_;hH?JF;JW>%)#AwolSDsi3TOovtUPXt7dSt33Fa%c*qhNgf-J&;^YSGna2 z#uizA!*K@)`{VWU-R|D!HyW`EZ!Q?NNz`8f$dE3Q^O2uTA6ejLO1?BnMC9LJ-eOUt znmQzQ!B`IfJNrRgh=y?A0IDG~$lS=qKpyv*3r4yhy;!bf_I+-BO%NI2JV>^P z_CTiiXdnmVbdlAMt8Wa&1llu74}bgV^>*F4eh^*GP4tfDl@R8Cx@z1BB!=D|l>gmY zTW8lD+Im>`zFl*jkZ~X(B+m*0O>~Y@(qlzHzH!Ca6OP9{@EsBAYK@0t49p8MRjgbZ z@=zeP+e9|_8Kr0t1ebFWnS!jbMn6$yFz&l>GeWEPgC`@AFI(95D=<~Ldq$bf5|16q{?m6JCAl&pqGHO zvp5~S)Lq_tKMqRYk_b+p2pZ}o+K?#m<$+huTe1`E`B0~_2w`m+_$A9|5=agUWg#gS zoMzSzDa#7T1YlmM2ne3w>!%-|^YZ+f9q#3IJ52^dlm%}xkp{fM6XXG> z;oRlwD*@nqMiH2Y-mEnF6yAO#0-9sRp8c*;#7IT8+$bf)pQ-!|A|6P<=4oF*ZKR?7 zU!vY1^hRO493S9^2mESDh={N(Rv(ZZl34LN5fJi5I3|PxppR^+wl$Xok3G2|9EW6o z@>Ke&PA;T@?HTLD!F}B#ofFB8@so%_K`8K`kIPp-5Usw=-+F4Djmsy=6G7rfIKj@%u}M595&uJ)BjZ4B78!By!>1q2Q|bpogo}M3hm42<&A4ZDP!gp$N~3T)Q5YMHJ}d^ikQh< z$KGSdw*tKcB);`JZfg&o@l16GV^3D!5xjRKw^P5}%LpJI=rNPs;{;C`wbl7@z3j5f zj$7YE{;_1q5=UufDs7-OO|*p*5RMJe!23t^C|=UR{zN1I%~q{Sza!aM`ql~o;bu4E zv~ljBq(bCNJfUWXcy;k4d(U*4z#If*tN>zYV4l0>+z}k|s1Xr(d3~+=bkLK63P}RL z+JA@$44u#~lIK28vK)-W^Z!xeFeQZncz}8c4pEsM^0F7G)amq5#qQ$qgH6H$h>Zrg zAqOO21Csf{o2+4&N8Kl#m*`+y1PVzYr?dHHN~~%gKy#`d<%ndk9*{D>KjZ;#I^ZAl zNd5=}1u{jVF})-3W^;a>?gRsP=L=-2MW5@VGQ7>1S#E?PI%V>r6aB#h59zZeee5lk zK<96+Dc*DBVUQ0ZLE6l&1LT0*3c%`>k|$kt+VK^tI1KZ+e_^?MQ-uLYp!brZjz|d6 z52gz6CWix3!T9?s7pO+pl8BKVLx4G$FAW8QJ{S2pS$6-hrX=1Yor0u7q*yQS)n~rn zdg^^6gyh;lEQwk$Mv~--Dsf(j1jnWbf;X=JO=k{0djI(6sa&>TZLLZ9$h{y^gh7BI z&67od5u%s4kvjyDpk!`) z#{CZYp`u$5wd$w2WZ3)eyU%V=yhOA;G4YR{ zti&5Vi55ZW&gco{;z`)%bC#UJRIyae+2Q)2=HUCEdvWH>ncaTLaM&Ti!rpk}jc)0y z*6ow*J>dx}kg^1Xna29TeZs25_yk@aI-@2VJp18L0+&WT0|pFm=bn46f4WPLe958N zWiA-rG;%$tc}~P7k>`pwP`;>^E?sI#?U!GEd9+Ou^4zPhzG{SuvXG%rC?Uu62jM;= zaumLX^c(4Hz6<~xf)JEs4WuuWj;+|R%8i$&{+zRCxMoFGe*5|sfw~%jSxG+x4gpdD zAkVP;gGq{JP@U*TH5H6zfP5rTReSf#bFb=0A^<}R`yRI`ApG~sDy)YHfZHMf+QNXD z%GM52WuR|dGsR6632D!kDv=&<|8iBu0=Uw@0-#JORiro=AP)&mslaiI0QB<$tVqi6 z(Bsu6(u1d)aX^Bocm*KFLk$T4e3BG?!I%L`%0Fzc(fb4ty-Rrv5FQ8zpp}RQ1K@$b zArQ(8QG$1dWJtNTew#!-D6h*o8KW?(#uD`5$kh1(vAhl`2$G>8j@m}Y<2-|v^D|6Q zh97_Ev=bsiTw@aZeMw%fHDsoBDYW;ACLHYgYK{~R0Qf^T0LSzNft5hq7$fICj80BQ zhmmZJ&q$IUnJ?QQxq>W^=kN*T`$R^p9#-daBw}lnEY3Uu`$VOPS|B%LtxHVemS%(x z5(|N$P{3%Bx6i1AFW1f6lke?tYeG~8g47k`-e&%bRR98VhKs>hyP9Hwc$*()-oO9Ydl#iZ75)=P7@|BK^?%r#UbwlDG&gg zz7|A80OXLcjq*|hP$5?UPNFN24l7x!u|Uj-Zs4^i2Ltx;AJ4M%E<`wAy@+l2gHU*5*3z$zk^;MBy97ZXG~nDG?kPBrxJx>JLE{j zZFnTH`8HLEx>6FeaN}A5t|55uZl}C;KxP=DACuo+)3-HX?gK;|XnyD`ks%Qx7l`5m zNXY!YIIa^TD;XlCmTkN`Lyqn_67{cA z1d02gv*rm1<;?la=!_XTRD)F?E%BtpKZbuUwRe1(=p^73*E$tJtUNq4Ow*NJl>i%Ntn0Kg6z9DaaCeT#-6a^@=2IDoP=5p5>eMhWaoBDyc z0O$bBc*S#-3|%^)ua&~Re%dgL7PL2(_6P|3QR0_e5adWyn*v<-5eV+$Tikgw z&$Yal_Rc~6$1BqE6Oka&K`C6o>smEM^!X1Y6EkN#^8hP)Q1Chp6CnXbDiw=&8sJX^ z1<=1m)u+I*`D%r|TXUzYHYA293!TczkzqZzDzW{r0IV?O2?m73XWlPU=h4{uN~(nX z3&6>Hn$oloFGvy9w?N@Uf&kl1T64D3Q)YPInFr$+cd@*j%as#z$Hk%6Esj0BE&0{s zB1q(#0Lqa@1&QrqHj|KPJXF#0Wt$;9|G8v~MKyLw zR>rkEs5u=}(?QmJV7?+$y1qpF=)R7eEE&cc+`p*Y$Olp}#_XeUkS-cy^3z%C4$v1F zJ%N~nla+X*ClHhH2nxSPMo-A;BZ7{jho4k2PZ&FjSe=UV-LhqiL*mW%eKPV(J6aRY zPlZa1JXcEn_gd<&KuQx3ygz)2B+JN=K-z;LABy}SPV{+slR_N$0PJj%7M=#`w0p3O z?hzj62^(D%J0?r^GJR)0Jy>W{h(f5e^;H=4RcXO`F*6y{WUH~5i z1urw6V}SA*iU54oyhN=GUd&`1*AHvmEH+S|WD)64X z{13gk-R1^KLP7+9<=r`6IRT8F26#j~s73@4L5I)t0ic&WQ2P)GBFeE|WQZsXL~W`X z@vT=J7$^l_aqlZ# zQxyyXLY22U;|97LrXNp07$Xv_7nOTNvOKvjnuaB$lYCBNN+KHfzM#rrx(_J*99WCn zqx(**%EQ5V2{|ADN!|~sVE%gbRFoi@Yly=Ui8tzs88c=i z^Hfof4f*kvJt2C@=+zbV#Jx}U=nC`_kS;7gRh6i&gi*l>=~6O{HzxTSfV~SZyfCg) zK{y~U$gVIv_C!5ON=^g`yv~O$M5QZahvRf)B!-h9j*)~ODFNze|5#rqSBD%8q92_t z4apZa(lkQV{0`wn(nYlwzGRw_$aTnc1P>r^h5#BPfKi7X(KGU=4gMN&G103t$8iSW4*AC^~7Te7x-BQ8rx z=mX^0&dA8Lyc#MWu_0>@_-0IyDZKCi`7=ip$SZzCV7kuoM2Ln^VTz>iEQKd196)s{ zh!9no+A@g4`-=3?8J$RiuO_uhV10q221w2@B0>4e)uB(zaDiW%`9bWcELEiHP*sXf zK|II_YH2>~@)RLCTglkthZY)X08m39iq)u+dj)_GiI}9dojJPDa&#a$J`%%PlPf|F z47o0oOY)2Wa2!aFPGylJ@^Of;=#Y9(5HadwB!qdNqiSG9B9z`Z?=!1{UL53=5Lw~6 zLa-rAGeZN^tWf!9ItRxaBXY`hT3@x-(PUDtETlgh*LWd!5@Fvwxn?g-BB3$qG@FSfVF< zCx(-gaA{Yx=!rk~$@qA(U$3sL8Q*LC5VWUaKhFI5^R0>)A#9=|vD*6r zkZ*6@qo2JdPXb7j*Fmy1APsLdAg|!iF4sTfu)FP&(_K!%K#Q7eQhyG>Am9y&4&L)| z0+h&7ZkRqaChucs2nhQuTC~Wf2;pKq0Md{G;dLv=3V{5dWon2gKuoeR0G%=1)!LJ2`;}JEJ19$_%0jR8%^%l`S$dv$# z03oU8_pT+wjW4WJ`IsI z$(XbTc=CCKRFvsh%oS1w393?5!mg3VN=^;yM1(^RMiP+EagBY{h4tflbM16$%i}=; zNQ8pMn?!0TMND552SKh~#-e)>V!<5Abvb`@bh#zO^ubrR zSwxDp=Kf)=hf6;Axr;(>S9OKSO?t}f+?Dl%NJd6aJXyi1#Ooay_k4Kn351028&6o0 z^xY~N%M+wM_^xpcmwmsFJNA`roo5(#)F}vGHJon9s#v!yAR%YS^%0Cjg$vlXsTv zL>{N3zq^aXp-aZIQdU-GQHzeo75+NwPBe)1#6qEvk(fxy9eqI9h7fi<9vpxx(yMm` zSdg+D6dP(=%mX% zYG+(Gz%vmbqCez$a1EIQWtlNX4WZG?_Pcgzy{1{#--GkqeD*N+81jPr0mYsoAE!tpol2+9?YEy{8qJ%7CJ@Ae5k0GRg=gp)Z&BYBLyJwqP% zAYJ7}K)5vAzg!#gby$y5y}$0hX1tz1@qNa9bNAEh?A{{khqMmkdPDkVC^~dmsiIH< zey1VZ+-yW&_PGR)k9x?I1^T>B#1`;SD zJUGs9taZ0hh{pE;<9=z+IojQ0>pfrcR-l)FbYX3IqoDi8h)D3km`sbOYdHB1l!j%D z7*&}_@``ng@sgd+&O4mML8_AV!9!&h)-MzaS*5R7#*1ui_3G7DBc1IT8@V2BMK|b# z&OUg@!V~&CIv28;r&d;*XPJlwunthX2lAol2LSX80hWVR>s@hXqm2QLEFg;nW_|!~ z82Jj*OAAesWl!ioywdtp0E2{;HZ5E>m(l zK$A*ZfYxkDpvEY7f+XSPB0fQts=!N+rU!`@KpCWr42*s!2bC1fb{w-%ofW4H4?5K| zPlz9$_zC}?z4ri&>nzj#Uv{7xF>~eGWvaoO| z`-k1-vcR(3g}_}PKwuXFA%v1bdhbr+6x(qxa+NK~vSdqE|3ANP{CQ8tGnziKh2CU5 zqnSD9eCIo7&Uv5reV+HNDic63C$Oe6S-9aeLtk2}V?l-m5U_A!xucc=J~*EL{`5}w zTz_2P&N|4{;E-OZejEt5F){@-!$U6tC;`M^IMZ9@3^PZRge5BkZ4KbcJY#?%9PZxE zb{kcwDpiH0Ch4@>H@?GI0Dfeh0Ji6eqIHL;MwDYFTg2(1uQ-r`;2w<$*$RLM%Q6Q5 zlH*h8jvW~*K$<_Zw1}h0G0y-z=yfc&=|HF?_k;-{IMlAUGj|l8NjI8i^g!N(@$(Ah`eOehsY{+BJbQ z?s3^Rm?T$Td8GrDFf}qwXV3Qj4R0^<3=C-i!i6lJNK53YiTy4Y(MKPB)O`_6#y~>c z*lUaZ4d1knAE%ENgfE3NNo{%3sTi6HbPAIvPu30Jy9nV+o&0wqVCUqe<9~-6j;Hcu zGK)lt7jY!Q$aqTpLA4^=ULMeFtIhbI&~OZrT9J@Ebc$K8_krzBd}j;hf@-;UMGa)1(j{I!*n&#S1`)eB<;( z!NG~xqMKH?##vBNWu5(bP6Q4;iLr-7-)fL3Y7OIBA_@-CUz}?kb-)!=ptEX6%013; zqH_MOl}3TGwM53_F}hmQO9QSxpa#%GbtPUO6R(KZILuCjt-m`oU`o`Ibz!Uk1)|g2 zL_aE#2)(#S;^I-IZp>tm%H?bV5&%vZ0{q$4r7i;*cLPhMOXF=G*7 zRqidalk{r={P7zD7*PxX-PO%2Yong0x2lR4eQzkFK&Au`!uh{X+9iM;Ao88l^DXc2 zo*@T7s5nT04(>b2h>6J}hXa$~-&}iQ8TZI=P~!hiHhbb}N(A$UTAvCkI#OoX-{)e@ zZ@NF{-g)h{*E$vn*|T8)lI|HkHP<%`KvFm^TqvR4U{s2N2cJoc)%XynnXCtqB@96s z(F}OCiCVV0ymMpmStK~1$&59geFIF8)qxf;Z{ED9ivU=;(eS_kZ~zu=q_F_pV~;)N zbT)8kqlx>YZdf0n3n1!^^Uf`Htf(tED%Hm+9#1{>l)JG90SL|^P7Mw+4j*E4#)%X8 z(1wFfq|N#O4@BretFlr5ma zT)*279N~Oa-r5<)g>ZT^k#;C4TC!Gj8!|ikhKmeS#fnVHJI|2OL-t(0)QbRoy78)9Iu0jE0`XRirEXHzV=g7)XWonMHO{U%|jGx~lRGYH? z4x5;B$d=X)?EL-bi+fx-YlQNQ7vO}rpM63!4t4G?)Oaxw1Nc!Anqvo;p05HAXj*t3 z&AuxN-EUvpAEM3a{NX%-`o_KjimCebzF8{W-Mo9ygul_op6dIl0+4~W&u^6oIe{xr z=kl+4jyHQkmLyzr;sHuD=XbDaN(0SHs-HpChIY+;YoPmMs@sXS{2%}LN4xI2>l|ed z_C}_P(L~$+@cV-^1H%9$g?YzuLwJmxd+xaz7f$)6eK?rG#)sUbNuk0~#kgUU{wCTV z%V~BCMEJ*NTeuKVohnn7tt=7(axSoB4t%}w@O>g`$M-0+i@{%p4;yc03m^rcB05HS z<7CZ8_`;7JX=G&W%P?J#?B8J#CiP*JT&Xsd4l03uu<8d!x*8C&6oNcQP~0L`SzB1c7IzR5}e zBmk7q^IS<`&5u5E`^*cRXTCRDv^GF7*&8wql-;G5NMAqe(D$?-04go6#X?On$vRYv z!nRkvJfP?4P&;72`q(eN8*y*AoCWT5q)%AZk%iv8nwaonNJCzBD*apgFYen#(sGmcTNmq#K(N2p}n=m0I5xbaf*ne;Rfs+_X1D&2eNc-dM? z+lG2aOc6C?lrkJd@An>7*;~vSJPd2uum-eUZXgGmG*?tG1$(H(N?iK0Vi!Ko#J4tO9c4BhC1 zDp|{C$r=vd51*-b;DPLrrp7tgA*WvszsA$9ZL$w&MbLLxd!x-Q?XczZraRzH_T(qe z?Q$TG%)=r%{(u(72{6EcBoa;*Bp%~fp-TXSKo4V1aM(F+ejd)BHroEj%37CcBD3+l zD0v}=J_ML>=Fv-hh%t^7vIlZ{e#ulm3V|T8#=8d+FzI-QgCu_kv z&K}j_07ysSC|h%+%+aC9s33#~c%z?LrN^g#yTO5PO65|DnE?Yh0V4bc04v|UZb3YU zEa~t3RQjEVRq2cKgmV!CbYuJ;0GnUBYNl0oHw{Tm0ll%f4w5-eB@p8#ERFwgoeySD z7^4R!JjatgVK_L)+-E&F34)bq*^@NxMn+aekrimy+#jLNW!rxJ>tEYPKJpQ_edy!E z03_Q-U~slK3_wzxcK`?%wnUrHC9~OJ(>^pH2;!g$v3(o@8tm28)g|OKM;k{F>|Alh z716$y^7}y=+j-}m=Q^>bywV6O-~x-t4qy8HK*32QqkvNiMT_jo74xecRmP7u+2;pTJ{563)ER{5N90fwg@%?hPBb*e zPgN-d;PjrD+PBBrG`E0GGKX}g|K=mx>`he}!&@d2&vJ-~U*B`Y?HdgsuamGD14xi1 z!U+d#5oz}z3g`SqfrMx9k1+l*&nvcz5`T>x?An6ob`IVsq)eQMdl&TM(8)Vsc^2{dvuodjtDgyykT~( zZP~Hg9yus#UXdtu0@h?vv?=G%lNGvF)V=3LKYLiz!#z5F`pAuw^O9>M01E2dfBfa* z6ZAulUApam{(7CO^u_r_0SWe*EcMYYDv;$m9oEl3xWrw%akhq-(bsPPl0%8^wyG(QrGKrhhyDshu&)-Z)$& zs?!k{ZN_QDaDt&^(Lo#M72zv_=9!A{6FJ8@+^l7$jV*PWgDV$=qW2zr@Ei?*ko|Z? z(fijWqK1Nmo@3M2?RK!kZ0dwD)~Sd!^cmkw&{zIJ!$K68%nObvVCekmqnto@{eIE8 z@TO%W6-{3u$Cu1PIt+)M(zpOFO7es$xuN+jbjgl%=Zwt}cD7X8Bzzu+gv6B4(lrbg%1`av^@&CSO zzT4*49^7hg=(qu($X1}|z;Ng_WVerKDn5MfWCxnatl*^4w`R$taupaD<<`mme(TZg zt^fgLqgyqf)BCpDd;1@~FDACJLN1I61j_){$3kUBzSVP*<)!l6SrxnXtm% zH7(bkcyq69>nOH8?Rlaas%*3N9p@gP1lZx+;oSQC-J4t)YbtZGfBN4UKo^bCN6()k zZA|8})gQb44F`|_|I<}ef#Zedhe8wlE~r#@>kVhP&eKB?fRL%>nhI4k(PA8-BX#Qi z%Xv)}9Veaa2W$rqPIv~q#4@f6(ZC6SCE5EHfh6vn`qIP|k%t8#Fd9 zYTWFJ$N|=ZmBP62bF)m9E)cHK@W&`!&rlmUF16DIKw67j-wo&`bEHSWa1vitg(+xE zIN1ON*I`=}A{;TI&Lh=D93Zf4>L@1~XE_f*_`O8C2?A({hLf>qki#qg)f&}TMFpK~ z>C6eXc_!2q8w>C z=r2UV5%tq0JtVB|v)YOrn?0)E^#aK)Dz&NO$EjiCcsscLO#^iEd#dlLaP&4bF9?{4 zwDUmELi8W!7cu`#IlOdbXCD{~;(DB3fC1Sb{N4jcR61AXWT8@pgy&wbqms!27gSS1 zXwGYn+e&3X=zb1WYrFu8@8yEt0bLLCi6N$kS_go^$cC_wRKxm+0KukLUvS5D#@q$g zkvqc85o7qu16!OUtV80!3t5^jT_X=_oMft?!TsR<3*C6B{=_`)(02Jg#|zU-w{M(Z zt7eb2k6$p=HNFHyVL1BXh9=|3qO<{|#vI*d=QRG>%6nUEa{pefOZ`^*MXTyBu%aCG za>K_bdouvI0SRgF{J!1S**Xma;6Pc zQ8U*;GRx>B5-CTXj=9g|ItJ27K;H^h>hj=(_jn|dJ@FZnU=}6Q*%PWnqA{(lt##MH zOwMDZb$|c+-?vYH`qS>-%vjRx&qUhh@Oy(l1H%9$#bc04>D5FwjX;`8PEc?#szpH+ z%9QRT2zH=*MRQCO*@tM~z5o9E-A8AieRfjRr)cX9zE718C~MFih|YP<3^m;WBwX}U zwV+0WNK(3uj1*2X9NjmMmN)@2eM4x3Mr4&pFi}?`>9ggCwyE*lK2fm%4QL*q`H%^j zASdX8>0=yVV2lF+5FCAk(>S;|y$Ij&KB4m*Ik-nr>ptlwrr8yXrZ_qb4fI}D)coLa zk+Lu2I#skFqR*>lj}c8M`MG8vDR1hc?Q(^wN<~E?bON68gyZ+%n~iQh_A2WDHK^j) zKAUYjtfp_jC_|zCA80CyD{E}o^7HKFohl7{xXs;sAK0Cv{cLv*Bwzx^o-Dy0t%qy{ zU=GR{)x;>99HN}{yQYaWAcT5@-h>X~Y@cPZ5_!o)>^lWkSO*R=0(jO1b&71lnc9yZ zJX7xg8_qgZC@4)(!pKmNO#p;IF#>EbJ`5)ukU)vxkDfQhHmrHx9apk_ob%X5Wgl>k zH|ZDxCRh&u21*#`$5>^BmZ&hn*WWeQRS+Ws0svwDx>1>H%s>mkR*}vn_U}Ro@h_S= z+Af_l&TV6$e*h@!b~RbWvtO}}M$sX=cUo&sx$VoTvDThY$9eW4KUdYra+|G2Rj&>g z)mTo&MC)DhA^Yx2?Y8eY00De)ZsFLGWddkWNsI=KzY^VxOdTMYIpcfmC;Ne>i9r&^8jS9dM_lqf3cP$6O2R7 zbv2QOtg+TR*q?iLmv;y)y64%d|nZlnmh|6U@`o+5=t106xSjRFMR zB&cxKUtVpm)VIhf?r;@}i16ZsAwowJa@pJ}=bS>pqM;iU8@T#)qFp8f^dXK3m zLw<`@=83K(I#y9hsntxFYYZ zu0_9@R)JHFFYD&q!9ho_^T}0p5_E^UjQ?Ww9#N~*&{TjD$`ehZwV%scbTd2;#OarQn{dE<96*v;QEuXyI_G36Mo=+M20t zXL7wzuqaQTZk

mK*=%P*gxpw`yb#@bxkKmXT% z{a5?am%ij^*aY%ojW_KB7+&F^%)l@JNpadUDLm!^#6^#aR2UZ+q9<4;duFhH#MJB? zmdOs~tUuE_8s-e=o%zHltIN$1E^k__OG4$IPFuZtwY5kTJahgc%fv<80}y}{V(E2z z=>yT`oMQSb6v@#llyiKpBI&+&NId%&4S*2whYkddi^x4?QK1o0(FkX^{lG3;KDNh} zEDiyX-@dxv(S)dWb20m!#djzT7O=l^%Ygx4C!LZtle_D)ibA{)OL5NDPM1q z15FAR4*Ep~ZG8JTp5WD-TR%c09fUZNnrTaeM!DT$;fC3aK zk&LrX30t%;MCWH{+_hs$-M%m{h~lZ}^z61n4rJha;C^V8j`DS}K-_K5@3I40$8MFj zDK|kU%NzkUqXc5tG zmXptz0d8bY$YxX&tE!Z;T30Wuwx#MV5|0%=|8Lf}_f>1#z24UMO|j;lkj90bq&61k z3iF4vUQ?E5OY^o_PUU24&KYfwlwNC(G>L9_T!bFVGO5X+G!=l*KT}qN%m`h`0nUJC zjsd`iOc~iGjvWmInX^nAR79%B(XoD%K==w(IRhwpBdA1WzM)pub*KUmFVxPaP9i*e z5~OzVI-cwabf$1{68sz8A6W<370|gek-hile6;7Ue)X%y`9c1_i>V06X;;$dBx17#UG@9deRKTsKcD9Y5d$y_rsLZV* z;_0#%UwqN=bh$}*p&%3>s3latLXQBIhti~pSTq1a=~$xQ2+*eqa6mc2$aE0ZEp9(x z3oCn+0Xf4;$}8fU87$}AnspI{|*XW8}%Z?`8lH#^`(7KHh9pg|x{yJmA0MF$Z8(5U1EsL(JS zEscx}Jw$Mhi?!S?l|p7e^cCm0<6JX-dT5Z5Voo|#9SMyInUG1xDOvRSAZrx@JtonA zk?j@epsE*{5i~V3C@-##20*yBJS7U-6RK*4CILzt01C1DxpkFp zdHS<>2LJ~i+7>h?sC?`P+7EOMh`s?n|3euUpB;&HY>OWHjO8|OwU*|Cwz_kwqke_v zFUJ87?UDl_Wdb+M$FdRoDPd(Tg*CRi@@nfES*tR<tHaSZ2Rp3w`Uy(x2%s$ z+%p1koQoLWqx|%rFQ0g#XGpBEX8QA?3P7TrdzqfkOs^jbG{Hc!+XR441>?TvK?%=6 zdY2DY#u_IX67Ii%9Vp2Z4)7V2c(Nz4)*sL3|L_n0VE^(j|6+L=7c~9IFc6^oZeCIo^!8Lu$XiGp}mK$!k z!EU_q#<oBC{3YyXofrlXB%Gq}m3C!;F{@E-e>{Y;|7e;>C{&%XGHI z3;CBUS(3J@Da;jsfCwW7;K0%50!zu{l&nW3KKH(2Ime{O=~UCgqmA;K6p^mqCBDBd z;*)3DxXClDzj&nePgtsrhaC5mwyA~5uy6z9=9kV=iO~SaQ;L=YK*)g5c+cw%sOHls z$F#gly)!C$>}|^z+K7r#Cjk)l7a##0saDjmS#bam97eJY01Yo{CUby;j41pKar-GF z>^pzs%)h2eS2IK{TQZrdR5i}|1SE~yc9+%JUYp#z%Qp2-wmqH24g^5?@sWH$z{E0D ztvayUj`WYPq6zb?JfX&#sQC}_U7TF6xh__fyAb{@QpWbQBS}$2G3>^^wifk2BA@2l0bE3Be zC6-;KFYN;Wf$c+Qid)m89W8#~QtdSmCQ$>^fF|KmX)e2 zvVL2KiYD626<1irq&YTE1tVy7iRhpCTdLz;F0c}A6i(P6-3v4*=Fk-eV1ZM_Hg4SL z0!=u46u}rO#(e`PZ1Lj7?s_{^_G_?(+KJ91$AJ5I5R?SL3fKKuM)o9>Bav<;c z06zcu&pXHas;jQDd+xa>*04^A&%gM^FWOhW@)cdLLf6k|gMwOq=bd-P%q;!zhd;DW zeBu+XfJ3Bp;kVp-@4Z8c);OdA2tP0!(M+1JOaw};t*uRIQ~T6ql}Z~vT2EP6^aRuv z$GD(mqhu}H3U(;Zbhd?*E5M5zRyyj&Qz?pQ6*Mvo@J6ZPZQHgvkvn4dq^-Bxa(2I9 zIUR@06v@r$R_W1#5!RVkYP(crtM6#DRgF?t>T31a7&XoMM~t!lNz3J3sa#ZwMw*;b ziP-`mWIhm}G<*@G*@Hr&s8^@9?1Wqd1 zpN7^h=QI=jzgSh7$V@!FW}Qvk`+$vX-Qc3&>-(oV=ax(Z{YIeR01V3INV6|fyS7?k z#{n}PtC5SYvhM1|_K@gR_p5|1^dmAJIREW(#>p4}D2@l$UG{@0Jed-}2^GD#C!y7# zp&z1j{>JqsYeBUszyg0mAqxRJB-189L)M3efU1zCtPwXizPC*o4;+575LEucsb>37 z#Gv({eei%mUw;b)3(y_>jL)Gdy;9%m`kXKi=sEz4qeW#R+XW2_Fi19GqKXDE9t7zC zI{*Wq1FDw?rK~fWk)>NBP>D`u#pbWu`0jcu=s0NWa%R|mH7TLYF~^xXVSWHPtk)G7 zDBR@$d`o_ny-<0LbyrTc`rc8}v9!3k0L0M{ak0enSE%eU70ON*8>#?=>pABw0i|U6 zDW&!J>H3^2t(x^pOC{=FfB8gRi$jGQ65Y;V3$+s+??B(@_~09PKteVSzk}j79=Hs& zy#I_0iO-gJP~!hiBzr;yEGl8W>s{}%yY9Nnul|&NCL{5qAN|Ntx*7My7hmiGgV5Wk zy7}#If7=BO*$D!Mue|a~)JDtq-FKf|ef8CD?g>Z$$naCBOa?IVbAm4hz)u(O8|(=l z1|TUO0nf`v7z{-!8N=E4CH`2RA8w=?>RdE@$=Xa-jA9Jg%(n1@B1!{aJ(W_p%nu-g z>N310dIKOc-6G^d9)G&%t}QGTih z;S}Sfqd9>tgcDB1C!+T9S>2fENkX~W4~SkfPQVA-yWs_ETKA|`AAZ&L0ssPBU^>vE@E<)! z3IvGg@Sd*>2@6jRL6zMM$nDdpV=*^-3S(_V^7IzsEN)wayAz;sU z$qt|=p^P!(2OL0)LMuVJV=628o*}I0p+}#vwN0wtRZ?ZWxdl$gLRN^-tsu^S$lBbg!U2FB!0V+)@3GmPZ`d5$ zZk-i%w&`fGJ1%_g4KM=5YjSD7O*ppMdiDD`m|JB(?7ZAwZ7s3=$3m66m;+`Fs@4Ma zPvIP(BrxaPU>N)GhICnIYsLx~(VvHXiDqPIp;-`gq5sfOF)Bl1OP4OqSe3?DbCuh) z#qu}&*7CPL?6TAT`~79r)-(HR>z;X)IFX^>g8wYmGY+IL)tzdvG1j)S{rR(D%_BVs z@c<<}i;_t8BpjIdzk^Qn-~7$r*pGkwW4rFU>+F}m{AIRxKdJ3~<};shMRPv>@sGOz zXZT8(qxZl6{dUJ4ceszf{N*p(-~avJhkwlhKl~JY7kasIo`qBV{`#-~+P?R_@401v z@{^y~2S511lh$)OzA+3yQaoy&78B&(jNl=g7XiJ2ImeSLkV3ROrq(4f{^ASPi2KipU^+Bjof{r z$nAW_x_7>4y9*RGKQ_XNfh)C6zyjcbECw0}1p8$@>aWtV)^e-oTlw6Tc5CAT=ZsUb zmhqz(L2GhMV4y=|AqydF8u zOm^8UFH~oH(F_sxcc0kd<`_XZb5Ym7+iuLeTa5_oZCpv8H5AXV28|PeJD*dY7*I7* zjX-AQ?6RD`F6$e=*q+T^^%K$M?06WG4V4*Mo8X$!F*)}SR{rZ*t z$1`JqV`-Oku6^j7Nhjtvd`v`130e##0OHP}#~yRLil#4Zg+9V3FWTQaSqonOxfQ%} ztIi$$X1Y|4S(I6K66^ZgUs$S)b*X;16?SaZKk3|B6m3l>z3(eU4VF;*qyeSzjYOJ9 za*WBAgo6?fR$w#4GW?yt`m4Wk0Y?Iatc%|RKEO|Z`cqe!A$T8(wZ2pJb12jJH0&>B zsqs<54S)jh!Vuzr_OqW2|B7RCOqw*w`8NbBC<#3jY#4x~coaP?Cef%gKVTeUL`xWb zHaM}!01WiQ%XGykKOI537a4<0^&4S(zLFSP7k*@k8c{?tNS-EM>^*UY7Ro+W?gLBRC#H_m~u6^8*7V74_SV%XkbL4US(;~@Rp?Yza*EM@ z@Ltez53IAioljccp4E1=xW-;(ec(Qo#U(|f<6m5?uggP6agG4!P}z0agqT% z02=lUdQ+#eBCHQ%hWu-Kw#-tcuGz|_(Nqsw8-_@oEC~Bg1_Urh1+be|OgWMLp)%K< zPp`M#D$bTySZt*_1^_2O$ZV|>de!QkhaJFTZs~r`oRH~yVS9@Mjq;z}+%n#yqJ;rM zIF@8v$fW%FSrgqdZctJF`I(9a04f7Ryf}F^_GdU zrt6@#TV2p$qk0^uES07_8O&QKPFtivZ) zC6|egvKukqhN}3zCwDr^AQ>gb!kEZN0s20B+4P9u+XE1;`A}_#f^pvD4b$Dj!KuHs5sT9s1ViAu;2E#v|C855IWP}0`NkX0bK$PJm(^PA8_0k$@!(C z7IZG0yQn6OPQki6EVoIZLS>R)?VV;#?LAJv(ktKsXu$O+vwW5OsE=Hfy>4ap(p!+?!#C5Vm$y1fCEl(h?*s)o zXB>~7UK~`*(n|+E_?~cu10hhN$oK%Rm=8c1AeZk@G8Z}=*#a~mfPxR66LN@{t8YBK z&0gNT+nRNGSvaZEMwXRm9(x=RfL2A%lnIqZPS8&|Ub0*4&tYZp0BC?9s%ssSBMp!O z`~i5-XfPLuzG*;+P<erkUmRVor6zeY;V_nNXZvX4v{kHKyyXaSFMdUzg!-(b?UufR?Lx4?%4!&?j z;=eP%=<@a;G+uU4|A)`P7<02@*xxw*SslFU?T(=TvWDg*Ek-*fFS&GS0v90%cA6TP;VK>i*Jd z>l;;P9q;~+xO5>@A*4SRj$bl?vTV&mGTX^k>12NY+_$-B6HMK@b*m8^#G&TdGeIKl z0~wR=e)qePK02k}!zZDHGrtAjNIE!R${z39wac*@2uepYKnh?5gRb_W4}B=wS5KSw zhXF{6hlFHjXY!JwHlBpyH z-HCLj2XUUp5RJOV51h0mlq`f?$yiRqTFU`|NdK{?aGKS(_PM5VG}%Mj003!fRkJ#! z_~%a@XSL=1R^7SN`m5$i1ENUoxYV2sf39)CN+)L=r-7RS56(j}M?Cv;GMGsU&RZ-1 zg40UHtOn>vGWvCpO(5DHZj^;Ziw-eb9q8!T5DtM(BS?XiYpYf%>Gu$)$maS%x-;y$N;n{^e9wqunu?T@AJvPZWb zcFrvslA`0_g4f(Y0T6%pcgPgHp0`}(9Haw2e#O&TlYDg z%%Uk{tf)9d*`k6N{U~a+j`LJC>vym3S4rPvE*rxbaG0UBF>We);kI!ML)#8@P6u=W zc&KVd&yZGSG^q3icmaq*2lK#?riWBB=;-`5R@MM2ADGLthupQ;rqXL9Pt| zzAwLH)=7&G1CW!ZB&9bBpZ>ZPZ2W`ewC%N?0tFDdN*qwvp>RJejtjq4=#AAm0x3Gf z`&25u^Wv{q@08dtFx+TRuM> z{}|E$gdY@6RVEE57zz+6*?~$aqD=q=`^rpIrXlM=S}qYwcg3iIww*1y7mh5Efp{v3 zaZC}Jb5X(oaX8~d5xK!cGg7`}otSUR3MXR#4+lU5L=F{Cv@LB#a^RHl&|M7&kc-Ve z{XIgB4(Cp(wpnEzHnMZS^^adD05V4zkm<>6_QWz&_9AkWE&zfv$ix3mxJWXGyyq=A zr@Rh6o`3#%2LJ)l!QufpWprtOP*k8MId^!nM1|`_pF%JU1;~rV*$&P*LS-VzXiiwZ z@kqCG2w9l#LbY0~Dq8F0yiOMwSuml(RXy_KjP#r%%3S{D`_!vN)H&&P*0vVg=3|xC z*rjr_axhEtdu?35G9^dltmhQlAr%zZIdYk;EnMs(;W*nzIsp%4O#VwyKUvZ7$#UW; z1Iw6wmV{<_MC8ek>{Def=vfGo*&i|_Y!gk#SOJH6(YbbMc``gu$#C*<`ZU0Mk#A>SOBWe?IRfyK3_F^jO&hm z$IE+NFAf}W=u%`)pq?>DfS5(1lHGKMKxO?i>J73*Xh#FiE3&?dN!C00T+y!t*qIR7 zj~;r}9^Twy_3bM7&=)#K88fFU+oV?vRnV?mR^uvS`EkedeCxCIPIm;oj=Av$br2Bv z=}V@&Mu-0W;4_(%Pu=yV1KNNhucraT(J+(wo~?cT$E#-t7jv%(h(M{tLBXjV3dS|W zH?YOw@*2F1@0%Kmj=23@mUC3pJ@sWekULIUR2o}`u4SA>p;w~$>0BOLBuZjeljwcp zt!L^*)_Lha#~dQpJMQ1yr;^nw#@xstePOUGm%aPl?{+N){_gMo&c61wuMN^Hq<^yj z1^Sy{Jpb+A{_R^fLdL@ft^rrK+;YoXJ`er@bB2nZ7=X>wwu0X|-Chp^kQ9#?paLBS zHxWce;YM_M^XAP?1kGneleyX8LAwuS^bX98gHj{nS|&9Lizoo zVf5#!LRPsos?+x2ys@@%^h#^!(lL|a;1bm)Gl2eua=ie}PhMQ-qVK;^<3&W^dj*=< z?_yDdpzc69!gZ^h;@QB6Knb0Is9j27Z$KXqW8)q)}p+`2ieY zY?n^n>^tRV0Y}m7VO0{lLt_XD;@P$?OD;N0 z=7nqs$IP3C?m#w99Ag?wW=5Kukt$&fQ1sazKoq(Ms&pZW2XOq`W7}Q9fIZqzvK4?7 z01TO!k110T>)c*GQRgo5V@6o7{tPbk{U~-<5^#W)C)XtwV z+WzwFNhdAu0SI)Sp}^;62f2=*C%~xGSgK%5HjGSX@!cP@+_rtHK3HJ8x=P(Ond=q5 zKMb(iqkmi$QpdQu|A2HL71lR;nsr?Fo0!AoK82nkJm3;@!BhMT%n<+t8;rsMY@ZUe z09Sfz(3Ef}7}*Zk7Jzbo|fswWutCTSpC^8sC z3jlODx`@&cs70d(g>Q$<0T~2zHY-=I4F5R3zcr4Woljei>dI4!_ejY^+jOK@4x70A zijp@qHM$0CqeoWQirNu2qC?q_F)G13aPgPYR2kkC7fG8s4TsgDdW!55wSaZ>2Yblv-T_u%vsHey|qjXz8Bq|s^Nyv5p0L~S4 z>BbdP>{p8J6WQkhwX9P6)+A>frxQ{47-d7CBmp1*P7AcJo}R=0KEAoxfdKZIGQ&9e z030f1LH_{(P$`Q(Dmcd2C~XH3I!^NYmPRjD0qFViFQ2l5sxFmF6|5X(dqn#J=+I{b z=bFQc{)BSIyv9Xi?#GlBxcvZ7W4y;_00#gW*#_nTY7tbjjoN<-29TLKBrpcu3a6X> zMVA6#y#1xUZeKVTIL{c%dsNbw@5E~ewzt&pv$Y)~t)WL$I)NvsQ_$MTd|amUfpWsZ z^EjS$GyWevD|)8RSB@bioiXN+V*^0qnE$1!Sw%B?<^1?LWt;>&4@k%lriUsB&|+Tx z?$T)ywIpO@$(jx&00M^}O&><_67MiYo4a(qpSxez_CNkl0g%1cn^&x+qoG0-oV#T2 zy!lL@1H#tmdN}ouoMi1c-0Qy*^*I*hH0pw<_y=6i2eWVh*M-Y3zud?$0X_gBr@N8a zqzD6k3)duqxvN&KI%&7?=R6}L7Wm>g`O?Mo9Pv%5Pg?0|^u{m%N%3HDV?;bf1Q`A# z#);y&i~godl$hv#qBqF!;Uz2B4qs0^e`kyCg}4t*2Xho&|C$?`zfm)0G8mNCO|&W( zIvq3=2-V;AwztKz`;osR@R8fFR*GGf2t9hxx{F6!Ltmw}_2k)pU3BcoK@&5@CQIZ? z&3RK9-o6^07rai z5>5X1XLcLH=DqUjiHLLaS7N|9Wl)K@@n0ZuFMS&>Qe>Fzvfkgle$a@LZ&kxRvL*Px zn^Zjs-+_qqI63q+6(LFtLTVZgCSX<4}wPa_1!!Nt*~oG{UF=tbyHzWw-iRgvm&fP;NuKcIWi^_>g=6|6og zpfZrLUaCUXONRlK3$Q}g00;gNWrWaY0K%a0FpmHis9DgL$T0YB@R7Fh@MBNdo6TyN zI6{37as`l-RU$L9P1Ve{s;3JGhm3@V?0^O9V6I1~%(1J?rDLLGiOa;$lLT5B4FV~9 zOqPQT2pKB&!S6rEaV?I#fD~i<;@d-FaOQ;uhGdHXSF=U`0>~s{!HQ86YG=50QBIk; zNyPxT^hDXL@p005kjS~r{Lc}nA+z#c0ltBZtP?$RC_jzvhy5$jT>gbJAB%LpL^6L} zgTBkPZzvcUU^IOg<<7ZYXTx%uw^_;WKWw>26!cNEo!vbG-a7A~!jbXN|L$C;cmu(Z z5e3p%^(q4*y;0wo+1Byi+hY#Xm#QWB;{z@+7dj2TFle;7<8#Ax1LvHKI`k`OSn0HZ z?rrgICz0M8ZEbDN$6$Z3f%a)Q1H#cCqK4y?X$=TzHKM^>kPrxQ@{#r68KVp#)GRMF zN_DEeUV=0*)sQl2L`9(3khRGq=hgR80el2+#5CRGChhBr<9M^*lq^ovh)5vfLZluk z5|POIat^9tUCT~^4FJah)ti^jK}`o64m4QX;T9{e9Aj0}7K%?ZPE81>yDUf|>yP$b z4?rSi+oCPw-{)t}@4r9~2Lm)Lkk^`Vau3CC#$ z{Lp{n{iwweN)>6Xij=bp8N5 zu3c0uz|`Tg8jHcQ7s>0_va&;cpb z5Yz}o8%w(0=YGLG3ZvY4Je3{OvTgPJDEamKEceh3RlquAhw`hett-@91_y^Tm}eIh z(I4ZBx~;Ig#g%yOo^y?Lt@w1zVWhKEZOn~j@e6}RoAbNKc}rzV?r-1v*0+qNgy}S{ z*Qr{(0EF}Z$}6utL23Kcr#@xh_{KM)Zhlw;!qFe1#;y%i)-4^oO;sxd(cI*Dp!Zc=ZzTtSi=ce18rA6wZI9j7UMS!#9o-^Gaq3D<~*%0)Mhh$r@A# zN+z=|(w8ZlB5t{QxXL}$oA2&WF@k;8c=(7_R86tkX)_dAQ&dx>MAK!S?uXzT$1+|E zf)4-M1CMwv&i;6ieZg=lI48ohP%o+(+wWi7FLAS~B8egc4Fw$pQAotPAu)B4UA17G zol`r~rpdVrTD_vtYj(HE`3vbD2$DO&d5xNf=_N4?b8|@N>UzevjxisK^E7 zW`o4oIA}QEMD}q?*hjtxJ!syZIpjGmYQIvYX8}R%)Ayg=sop5*5OpW(Qm7r@C5;B}v2HrGV>q}7$;re}B9^9m z(JT@Gc~)KOzxU)02OOYY(bN%Oh%Q7!a>lrr6aJ*^G0#xQIF^(@W-K2*ce1NiwpxG_ zAv@x9_Mh>QRhg%(!7@4DbWTr~WwK%v=fqD`0vgakmWaqXpc4>5RjnJA4_x3P*?lBX zg|HMoAYeWf{4zwoi>F>V#ZnxSSZ@kfd_`@F#xCsK) zzE{q06|4cL>h$}N6FbuYgo;c&h{|&UVpRUXL5p?5CNrb4^b*OeGukp2CeCq=gpVeQ4}fWZV~bTxnrm~; zdYj9Nq-R5+wcvzN!Z}Fy8)*HU|2#bC;2DSAgO7oh^`Akx!cp?agPt{<50T0p13aGC z+-Og2X?EpV(H!9913qx_iRPazKK+?fD($L;RW3W?$LOCKBjR5iDn!nas5(?#Vn3i# zu$(vE^A-dqP-*T}_G5!6U9N+=mPf1LOSnSOC@<)<_D%`ORpPZ`M3IEUV{DoFT>t^khU8Ji9qaXm6RwLXN$03>uNRKue0gD;KCnAooe-fVPT<(u2PT%`RB z0TsH7?-VdP3>`}jFcEk_&_)4`B02p><Ju6ozt6$vNC1T6 z@cBP%v`tz!nG1}4XRZMuRMvuOMg{{1ocSS&4!CgiIqlyy3#--mu+-7PZk2Wdu{HV_ zGE8VfCTPCUJ=}QS$IXC*a^zmm5sOFNoQH-<=>2JG?9K&aV>a? ze`(ONR>$XsYd8V59Xoc|t+(E4ANj~fPVpH#d3apkZ@A$G`{gfx={}^h`7eI)i--ZS z@TCbr4EF&EpOqo-Hz#%`0SN2IdB(Z*R##W&qFG)nEtkl9L>lQv%5k~$(n}LrH16+ufRJd0BHj%| z(i=rvmO132$b;8BJn#rQ>d}_xeT4gLlk5P?K#v=!dK*sY1M8J(Qe=FK=q&Vzfa)X( zfpgw*Oo@uq#I971{y@gKvEcZjPQALP)nyv^tXedw#p*kOlN`y|XY6@Z)LLENYHx@d zMl_$QP3SJ5R}t+df?t-eYlZ#>B<186IAJrdG3a0bDI)y4<=|083VK$HfCNp>(5w(? zMpO@Ypg|u_x;OUW-yYv#Yj(9d=a6|K%K$xx(yfgDsAxNY54MBD>nry#J}5mHRkrAQ zUab%=`V#*gzn$Q7G-nB#5e)*#*0A2t6bW2uUjZ7Fouykkz^hKZJ`NqvYK)aQoy<#+ zQiOg2-2<5$ZwT_KaOP=a{{2**8+5$>_~LqNXlk+A@nh`jbLYEER4VI?wk(2w&I{%u zQ^3P-n?OrbQlkpIn{p2D1D;aJ5l~b+b%I_$(`d?Jg z&=(^A3niJ~@?iDKh&-y)-yQ5@#&w!f`cxDB+0TAvANarrQs1d8ui>K~{ip*^Y?g{% zcinYY+*I-5PUu-aSlQYfCw8U)2tQgli-@N&oI4u!;Y4TBaH4Uh!}SuG*rwN;#M7T6 zmF;^9mR|=|!ib3Y)TDnum1l1BfHxdzDsE)L5&;OwY@bvzQKIVVYFn~oNyJrf&Icdf zf#>|>5sv{lNQZMnz{oz4g^DMmN7wF`1V9?(s1r@bsfWH(RbFh@FRxKGpv3y#`0>6W z;PLFXW=HL6l9L6O0*VaI|3y;$L)BuxG5_qBeO4W=SMNOR1kxoEpKeuy3>;0g5AyFF z9ZJ5xl?#L*@-8VUcHDnf$JiTGiHh#&l;XwdXE}O1AjqaC2i2r-xK}8iWlJe;}h+f zb(58#LwRHKA!}>zu*$L#RyB5%y?fDkn@}3Q&!th56K&qfnEGaG7hG_Gqr67@Zl>PPZFt>^p7=*sBqT?fY3or|iyt#Uq(IjR z>Gk?*mfEq4z8E+7V621PDfs%C+;L)`zxvg$+Gjue*^_o3f0Jr?^pgXuLB}2nHl(XyaRW;?0C6{5ap8SQSbq|v z(qY@LBcA6VT`AMetFoatp*j^eV&)Yi!p?rBJA=dz*WVbgxZ;XF;pL6^)OeT%nzb*C-zgr3ES#4*PfsxG86fxHlOi zWAKaByIsE!01nlKI9;g9#Cj(vgK)!Hlbm*f{m13{(-2Psxm^|B_sPA-9eEPlBG_~RE$%?hn3m3CD%1B_S34e94j~Ul&3hL0d;J3g1tzCQVwF&RTU@h>a zFMY|r{N*pZ%~N#Y!3Q5qxXl7Z00{D;B_`;Kj~AX1rAguUzV|)1op=TDgEc3KYFKnhdT&BJn)EjUuo9JF<~7n0|m}kxe9J8+ppK| zZI!O1$yJzwLWLNb{oN`@{irBj2!&V89_Px_Mj9JV8C|)bR|e%x367y3^@{4`vJe6? z${D%ERE$^+3Pa5Vd*tzt6YVHh)D60ZLnT8jPW31B0kz6Z%o9MMWG$7S=$|n`K>swn$Ge~wdi{PD~w*Kz_Q&~|wwYs}T>@80N29q$&kuvA$*C|H0? zoo4R5x?%Z5yF|TGGHr-z$uwg$d`)*CDbwSRwtlXOP_QuiJESu^?^Zg9|IpYMW(Br# z<;u7-<>?wSbBp$qC_mW)sz{v<_MPv1$8Ns)W;axd^!(~qzlzBcAh;SSn0McO_c`ho zbAeC!g)e-;3G=x=AY}i|Z+_#pgRYA6aH#yQhBN@-i1`w(?&u}?4;Og&@NoRS(3}$v z)JkMWOCc3DO)vc4i(B!Cd_I0yQkUq3={Zh{!+X7IrUjK6VwdBkH-uE^d1Krm|eL%B-y zCJTKC5p0*7avXV@)x`^b1{x>TwO&v(oD#S6$e>#~M#Uns8_TASwDYHj`g25E50tBa zeqf8LV6_=p6a?3<46mGW4Od`m%EpQw?q!S19nI3QNT*k-Xzbs2L)fl)t{HHlEd; zlHW-e0Ac4S|NGr1cPO*h<1{&B*Z{83`Z!m=bk(f4=yx(TA%pGAW@^8h?tF5h# z_;rBBCqD6ssH`0-g#pl*tD$1U03^nd1i%11=z)MyRuD>xZ$tzb02JUvb3$g?($x(+ zo^hsIZ^DI!G$TzKy^{=xBWgw!h)jvM*;j6izCJx7^h`t$D8bCW1pz`l^BnJYUR}4* zUf;CcMpahY#VeLO>I`$r1LK*ShtGV(vtH8gfI+BN7||CpYmuTf1Fa9r)jCzdB6FbR zf^)2iw4YU5si=S9K#RuwjJ_C;tGX5xD%MGcp+_KVo66v#VW8~oL)-eL`I2nrrI#9e2u(zuG zFuhW!LRG0bquV(~13%uU7fB>xG|d2i@JzjLI*(al@d(>_B*%d#I;nq50P1u#s1^icpkLKSaY_=|x90`Yf2mBLuY$$0fLO{V zj}hR^h7Gneo2h-oIi?IRh9d~$VW=3v3cxV;j+C18COIL@E!8eD<{0hJ>0s#wAnY>? zn{R*n+xEyKkGOy!dRXqqRM?`d@1Ri{Gju?P0muLoi#`GH;dLaGKPBrBEG_6eY^S5a z-2g*5@ewCzD&4S8tSF8bUK|cRAXU8y*$y0CZnzlHb)xKC$TKb8W_y4f-=UW>yqWkR z`;yG*rjogcvxMERZrUjze89@e%dAcg3lZ#vssbf{)`1TXJmQI90RYK(kof?(uq>1- zgl_RH&zyQg1WWTXI&~w;?$-Kn$`NLht++(}DuUIM{BrR=v;RMr1_XM^>k^~GZ6~@9 zU?3y1P!y~WoHaS3a~|AAL+dg7_CxEPsJYb_Zjvz7H9ZvAV0~mT$|dwBlB_=+-3q8c zW=E*mD7j0esxilP9CTLJ|Bfy-ZET67gi$V+^^kD@ggmji*?y~PQAbqfmwETg2&*_f z$#qM|yArkl4Ju*LjT?H`i#wHZ5m;a#9AkjR1)_M(t9ff@ZL|`PZEA7=2@o_%rGR(u zl1{Bf<5h=u?UQ&FT=<&s7G29v71;-`bBQIA`In?^L;0GEwx-Kx@Ldu!#~n zQ#tFV^QXFuNa)?<|7D#2{&c-<(smecVSl&f^$CRJ2;_-U2Kac}tTA?Rpcy0CpQCCn zNhPj$Xlu!jE05fw&^((S!2+*@>T;JI*Y%rqfncCOEZq}En{bIf7kkBJ> z4_KLnAZqx&;2ZcJU(mh*c*FLmF#|&$fB+u2nI&ReYyci)H!z~X01qPc;g4SGH>s_yb#ycTej?AzJ&rEpCXI~&XsCL@1rN)#c$;ky>3>?nT#OWN zq7i<#V2pprevkzrnv>3p=#z^6;{dLRUBi6{pO-DiPx2JYJL7n>dCwD4~(CsKD zWG?8vF;bd}^Xf+1pNZo>kT{!j51{+V`u+CAz8q`q$+e@sp+MCsAbiot{yy7`F zWIw(sTGUR>1@l99dMImqBoc=X2Pimy`e?gyepNiHi}@Wu&M#K))wV>nYdGvEb0Y;V zrjM_5y;lDE!l{n7Mn>lz%`g34Ffvq&1kCA`aw-E60z7045S*gv8wxhq(ezBsA%29v zf1Gp9IgWCjscmI@y=Ynq4ic2h28}#?|9l|^-UkRJ(quP$UBiE$UNbNZK*Ej}rQpai zc9T+q<8Z?q22--m6 z>frZMc@4#g#){agRjb~T#Y$zp!DXSBq0^ug^Vw&g9sDTi*JKr*6lG|$oUwh4D*4=T z*a}4h%qtt?s56s4|tP%9J4iq|nfh?*SMtRqqd<<)I-XRkLQP zpT2mv z*^=q{k(v*#-{0o?xG)Zk{YQvDO<;Jb%Dw*O*^}J+>G+58%lEB2XnPtOt>c&q0Em(> zds3D9$&7c$o-uu2nG$G6G*<-l0)Ww_kcC3yG7vCL#~71chX){N?6}4b1skdWB-kyS zYDe75hKk|yKoPaT^NzF$_SCA4MM(hTeqXkl~mij3&w$ z%|P#nwfRn_`bz}2?VWWrC`*?v4StmN*Ep(VFQ|ls?j;eU?*EI*KU_bbkBgqdh};c|g4y=r;f@YL+7K7+R3m zH10$J2;I8Z$(bdi0-(WB2Gl&dQC+H4fvQoNm4(tS5Y-3#;H*PMnIeqk)D6(87abf&d+m^3n6BoY2br?zMfk zMwC0cq0iBLvdw;_O*S3~6>XSZHNyUE+4vK@e#ZU7=XSe(B|CIt^r-}Cd&e;cXy%R= zT`OM=2BjA6urL z(b%C)8%h9Vu<1ORI#v`w@I_2ktXL5>AepJ{XL7y%8i~G@eap6?|MdO^EP_-@QfGVY z!`n-328IEM<_~9?tOpkvj0inh4;;Bz2In=?Y#gIiBPU^{^(b+TTVJvu4sf8EHjG} z{h%mVyF`Q8E@}>uXS$pp5KuTO$`TrtIig@8c#dUIgXpBrGu^e(TJ(wo)qGUZ?IUum z#o$9fv1IZ{M?b@fMH51Ff0`&o(6GGu^ANfs#(ab~Q#>SU51E^n)ueEr^dTd)Z(60x z65yn}sJb#Fuj&}!+|oIm>;)i+zbSLdGg$?wNO@YAPT~`k)fg*>pR5Suy7ifz4x~X# z!wHARRitI07Lmb$ruNYlQ%_X)y7QI2Zkt=BeZT=H+k-)I>*(rpbT%kk%r*PTcpeuG z>#@yE)}dy7Ep10!Uz3XBT&tTn-rlS4lCeQ!LL)-JhzCG!#rh`*2zVWQ@EyPj#~QKw zW&xqi2adRLvH#2yv@a-G*DagifDKuZU%kA~fja;J*`6{v{(v`*-{qo_`E8Qr`HvTN z3#1)&bBe|XAi+AxLS3(Qu3xv-H7X+*;-jTx!oG6<7Tck7uU)SJs_Yk3F|t#L>j6A~ zjbBT<(ycL&Nh;DD6soH{V2Qb5nZYp1)sm59f7q{~VBAY7%EEP@>+Dc50$Bb&Pbt)( z4)k>2N3V6|8cB91+Xm?HjdcMd=n#kPPh$rDqyY#~Q7AL?@xZuf5+O~b_W@3wkBnrh zyle1O%!ae>x90`#@s`K+6_tqUVPpbu`fzv$GOwLTCv_=&d!*2PBPn>UvBng>d^~@1 z9zl^qV4sc)IS$|ML+$pQN~~^>27;^tl$|b}xAjd&twdFvsx`HXsmj-V%w>7J&Ss$T z0!Y~Z-~&L$-@)o&0FEc+)Z!=~Ztpn`K-4K*PB_#ZPv0SnutrY$UTFcK!2l9)Os9w* zMm7PVFue(4*~1$SDkE`Jds!$w(BGSLPqABk8E?<4?vx-=EXTe z=XcH%XkyUa_%0Q~bXrkUz@0l#w62m~B~^ML`;d$cMF29`dV*w*Lp;kslps-={W;`vH%3tK7Cpe_aXgV%@%AAR&u_ck{W zxa8?JqV3EXV(wH^*~}?(i6j1qG7Ln|U8GkLa2zP2^*Ew9QRhwzl`v!(bT>rnxM6ZJ zCnA}M0Zu#^*{*&IdsUsczO~o7U7rkXSVm{_iE{2%&Km0?{k(_n0nsoS6RKbl;fG#y zmO3!|rhI%anh~|W>(za(v@V$jC`{0+5I6&B05Bpg$!YI%83X_VlqWI`Gv)Z6tww%C zz@dNuK78dm1iqYyK_@!e7=rHu4v5N=b#Rm(?GN-Sz!+mH)ZcU!=NQyUm$6@BaRAbE z0gCsEf<$+AZ$#>U@@&0p5D1M7FhTP{#OwfyE9O->TABYo+xzMBa=7I*1B#ea4B8h! z>&z*YZtkI~J)r^xyPA*MmOV|Pf~l*ydKOL_S7tM(jJNkMpX8`&e!V<%PWflfm*9i< z`8$@OyLeQZ6Tk>3BiWy&%G6w>QoqarYq;f!o$h?yqt5d*Jw%(r{?tn-4t0wrh}WMP zqH2BP;jPL0|UngKghK0T? z{9fqpu4#7JmksJx4`8KN3xJ4YNQZE!b6jD*h*H-HrXfx1i3##f(9adoG};)AUx z$kZfooKA@j?-|%ZPtE0?=z%~6HWPJ~XidHN9ls0)!La>l%)pQbAUI_HrpqDaHCY54 zc?<`c6nJfIZBjR(Y>1oPK#%|9o%M9me1hu_zK%!mPG*5j2{#@L07uq?>_@zo3F=b# zwmA=|t&NdF&qN(}Kp1)h*3CAOG4Bv^p7NS!oNhD=ZE~DCF1#~S5h9`4Gq2_r&{&D#1@qP9EN&>=vr zI&a1}cg)dD;aKC?A$Ep7Goi9bPWoHN7TiYgHDd4w-&9jiMXoE<#E|9T_3v)!a2W_n z$ST;b`RJD;-)*CnMVKOo6DM<`9Lbf^QPe8~#cvx!P#LMF(A4IdZByR ztMPC=gt49TihctMj{}Hun4y|MF*;MgD`@*g@%sI1`yE}0EDI6)d@Xmrv>0azJcS#; z=iWCOT-jfM57a4iFGTs@v9Q{06M(dFZ?mo6)okVY(86-8x3El-59xvg2+k8QT`I5= zuleyBW!V4#KmbWZK~(FcKkxjx$TQ}j{rb?&_+t$i^9JDh-c!45tLB5_1pwhw!5w8L zj;NYfk+L79_KB5s4qW~HJsTZ}0Q8|F@rJe|M6VlR@0xVX(FlV8gzw$E_JAwW09}pk zI@8AJN)JF~TxfhK4^5RWPq(6P4abn|(-*Foaf1F9T0wUH9f|;iYYz7VvW>}J1G6*x ziEV{I<52AI&Ma`>f;LUyj3$fOHs;kgALL$?34La^_i1>0@y)=W6aax5MAn071{Ul^ z5#My3{4IVkz8mJsm6;JY2e+DTnon@u;jd!}-hH&oN1Nep(pWIjib~noCyETvWfdbk zk!;D?@Hq9-ms3(puG za!zsh0iXWivnc!>Ps!ufW8Ka{$Kgi<0Hud)0Te5FzBYACsq3tc6HB>SoLC%NO1{>P zE|NxIopVsxExxH65=4PNWv1EnF0zn^wZpHpWYvY_~QiT8ekF2-X>s1*|j`WoBJQaGV z7LT+*x|lYbq3@DqxMop^mKGdGGOztP>CaJ~Js=6bX5C~azWqeKK*cd-jJh=^0!0D> z0959vPGFKO$X}j4(XHca5ASfSgfCw;GcJl?GV?ajGEjO5VEMub z1AX^&`OFKNhZ+FEcc5qhHkA6Cus>w(3Ebchoq6V&yp>g>yz!M+Ug@rD1T^EhUu1QF z!yC)k4E#v|5S-6o2X1cQP&25u5D!IYpxF?2yWlgd{T+B2iG^yYxFV9TX<)0 zbOwMEFYx7pfoPx7z{yxP_K7h+^w2|Yc<3{@*rwY^W#jzgbo-QYyxYLR^NyT<&AG|B z$|IJsERigZ8Lt6Uy>okAUHkpLW81cE+l_78w(X>8jK+;^tFaq9JK2rh*uPx&_jvwz z-ol#enDfLK<3k8Q0m!mPLHHz-U&GGp3v@Y*W|4cMTs0lGnY%skLkepUw}~$2PwwXM z#kMe^D1{Y9@aeI$Zi20<7uwU zBCnGK58XWYj*qIA((syWcG8IuA0d?dZ4yu=0MXJ(lM`ZXN|%5BTt=nv_S!P>9wOxBEu>QhlYYj%VK{!^7nY$b1TDKv5+X~NJ<& zOrOXB&p{nY=*J=dN{TvUA7uX|ArslPEd&(rbb3wf+qRhnU5Mt&ziDh7vw9`r>&A7Gi*a%IIb#Cx)C$H)?)9Z+} zB}N{$*af!AC-o;WRgAE!{;;VIV^{uLaGx@$P7CYc{CmCOWq+fn{AW3V{k?MYc?jm05K0R9unM70HFMNO;%SuQkFc3~z9X!?Wc%W9>r#RobE<&Ck%v`P1 zq0bKYX^$_t9e_aTsHbQFndLf_H1p1q@faWbG$yct@%s3X4jE8`3j#*=6uh?KS5|^(Q?L*anuQzY7d$4bEU^p8DmUV-wn|%Go z0zF#}KMae@{~%a4Ohcf)C@wE8A+E44bQ#u#+Q7gKl~!Z=>cM3Fos6;z#wZJa738!D ziw*x1`F7cT)%IV?78?_w;iSWx$~P+-XX^i8J_h8YBZG<>xI|a3KQCGfQ*Guf- z=2gn0jcgyuRKKX`F?pOO)=1*sVr?TbUkAYIDJy`%%A042*hHYOe0@ujXj5HB0U*3U zvh#5Ym2Rv`RZ(-R6ksN?0Cy42`TC#UZ@L4VawqSrAlZK<+it~-hQ^s@&Ji3{rAH=P zvVK?@6CI<=#(U1*9s7N&$Dq|Gx{x6%JbD{IEyTFK9_<-!0(v78pLnH@1A^0zkiY{& zzV-C?>TD)Fx=*%4Oh%&v@XmkK-OL6S?-EqKD`vseG0Ybh>49i0H!pi`m0rKHsLqdv z63lT!EM8#|cOIey0b~f`!>sBwTs$2LUj=eG40%77{R;18Kv`!6uTa{`!Qr{{UtWMD z*&<)T4gck!uk0b0D4KP_Hxfzz1;-mgg2R+(7$QOcqv#`_1b6&NEUrhk5K_(#4LWTI zM*^B3vcgMQKE?NYXT=4h`1h>?a%J$CU2w(s3}wk)iLYV1G9X|x)dwDpN3&m1&-#+N zzP`JIL*t7wW>kjSh}Pz2zIp1m*IF$_JZr5g3NK7C!CC*FTS7whrh2}W_R3P`efI$z zH1BUCZM6ISa!cGVA@eMMUpQ#K{bk;36`gbn#ZSm*;TTI_TTvu1kh9#m?e$zkakfCw z5qUvrVbhrWc8L3Y{}X-=QegZ+l;vwVTNkbi9>k+_-TpUN|0D1*68EzqfhXALn(%`k z1NirAjP98|r2vWiCT#iY+aTX%WfvS6jB)2Mfr&e@)UnWLL~l|=LdfHk*PUEy{xh}) z^swpNp6k>#@s;mx$W4vW{{?sAc-uao`LBryK_Sdh$VslTo@_))BFYyr<7G$BG;ou< zE@|nr+M!K8YUSV+gq`V>{k6I8y0zG-cLL(s_?dcHFB*>JA z)YkBpCD-)bE3}tntnwj&L-H_v7e)#mo5d*ayA=aIuc?SGO|lQ;lTfe`WI=fUrbS*^ z5v=I^t=J-!yi%EOMOOV2?^2b&Yrs=27$F@wNASm64N22iH2KVb!VH|Xh`!8eXS%a+ z;vEw`tN)_&P4PJ{)}W(hDWlv%c=Ixi{A|BIYHyUY;$6xy$7ma>CJY1iFGq7dRmL$P z!_8tumVvl$B-sG9KLbVHes9e%qy{#i-nFK4WXn>QVP7Nwm0OO(L8Hfvt>77)<|2Pp zKK@0Ww_KzLWlW-LTji4E(Y5>19OVzNmI}sEK04zaZm)_`d&~4HcOrL_P-Y4M{!4_0 zJTPD)0sah!_NIk7pD)>$)fobB4BQ1BSw#(u#^H9%PFyw$ybHURc3y-usVtAxaFDJ( zH?yQH`E*HXk$C@r-J~ zd0DvRD70@(ID()bA&)Fi2Qdy$gCoSW>s$kzW=`-n!8HhU_Y=7v*&xXVMuF_p}<)%E*_6~#*X;2P4Rc9WEjbh*NH)|W?>*>9l`!758cisXJ zIokAO;TH`Y+&ib7hxg4t)SW_N2jMBjw#wgM4I)2VjS= z!8w)|QvcaaabJBcn)NZpZZ5c7Vl4kU)(SXu?=TC-@ z=+|fERr>nC^sowH^{(If@@v9dpRBxt0>4z~Wp@T?E0Mx02B233XVjWM}JH$^wl`rj3V+!6mkgCU-5 zqVJ%lUNr4K){Bs;EMHZ{V9Az*DIE|^`jN>#j(p&s!ezoW;Ha$at5 z0hER!T7>MyDEV%YsR&0oF&1TDut{7VEO{MM%-xIunTroR_oJPA>UOLcXk*v!*GUSf z0X{&qD_4+DD%kaxUZ6vzPG|1Kgmoh27SmLR1W+3O;1mBG0{(3$P4RMyw1>D@nla#)RFMCcV-Dc12hEahwvW$jan5nTlNB{_R$)g0qYum6?YCteQqksV|nLOzj~M>K=bk zmn7SL8s1N$_-r59Cln{=brjG_`L|`n&wMZk_W|og}3oe0k6Xn##V+v;p-dA$K z>=6yg^U;}+llSiC_7^&Nxy#$H^Ra#VR$#Z8TfP^%EtNe3_)doO7bakOS)q=r zDfeVwcA=Fi=@GB~sP%AkQ6DUfW=kKgMnndILv4KOE-=`L&r0^Y!_gB9jM@fQ}77=#O-S285o|p$_>K zd zHUJAlpfY2IjVRaSmV8EvBQWY{S%exX?-ITR@Un@bL(-0M)qzgl;WD%184X{`IV-(Y zbE8_O7wm4TttfxB{?fH0$UR8x)0;W|r8SbHXX|YHqZ!-FjwxL!v+SWL^I?*L;89lH zOyRJ?)ZTAQ1Fy!>b9tchTrq^t#4;m{DZ);42_DJFxD31Cvz5NzEVc55;IOwf=g-$t zXL~jgS)1QF($3bU@YoQZb=QBC(L4Lf?z*=+uy_IjHi_oKr9J3#{6OcTzOXup%1 zspFH#7?wlD?8=of?Mh$2Sh$!s#5%pI!f@%m@l0{$+~^Jk3daZ*TiGU%dF4jl_~pmj z`|f8i!%jS-idZ*mJV7@tor~F%p=74hizWr(KvOvki3z-{Hub!PT{B|Sx=aRU&fk>oMA#XJMNC#gr0n{yGbB_yxq z$5z+REmf`M&~b2?DhBM^F}=mSVnvuJW3x5c1l|or(wy1#c$WLj%Km!0A8Vgtt`!o0 zM`Pr$*gCx=$-sk8lKqol8GhUUK4PWa&}i)vLXWd&~ME*dCy+wrPo#vY8?GK z((ee07c+TpCfiQFs_HT%Y7OD72?_QcF{-~0QJD44_pSHwelBTqxrlGB#W&FZ)+Y;r z33@d3k)RJ5x;k(7A|AQ@(M7YqOQnQ_W7O2T_d`&3yvbj&4d{0WlOO-ey5d=rJW}?b zOXXjBeZa^BhecJ(y}`Mc#+CLPS_Sxb*wMFGntaqP*m;X0shHFbl*e#XH#vkXls#rh z5Zf1;rgjbX{S1qNSJ19nsp}?&fc6Cd$$%aby3{dj_XNtR3+zET7NvmVjga*x^t@5< z-oyMv10)tE#iQzZMHohS3=C@OnbdzTv{svSTKfZ{&n+n$#ezW%o0=u`q!RxfgN1C0 z1QxdetE!6;EAjlXu}u?c)p8TU0I31KuU&!lSDML0R=|yHYrOAf7@5WbqHg{J6eoFs z8F$50@P|=e!1KH-XV+AW&AtTNKeH9a-k=u4O!(SHT)R$!LY)AkZb;x;lq-^&h{X0Z z^qo5q8Ildjj}!X8=7V(90J5L|-g9cd>|h(mY6D;?dk#k_Vtm$n8l4W$9-Xqa-+~{f zFaUpJlE!p%8~}r621mq?wJXC79xI3wiiRL19jZ0KI7*xvQ~CysJLM`6x1w*tJuInA z4VuYIsx~uS?Dud_6m1Unbuoa0dpV@R(+Y<0kr0W;wGscnerxc&;J;fRNf?DDtp}P_ zRU0Rx<@1kB-K!Syj;01WspkTQhK6-I?nUP5XICO$!N5}@?~5W6NIYAlk6(9tok)F9 zFnF>kR){34?-SF*!vlZO1WOv$;ICa*xR&3r3#d-2K|&$k0em9_4sNA#lIl=oTL3{d zIR6oNWb1QW3E0(N9pK6&!Edf7tJC5gz75YZQq;5nC6d3WO)SUD#M5d>=lIpnz7g||yx-Et6ACirebrs^_8_MLrY^UsJIuSzu7cN^XJ-GEcZ}9k5^?kz4|0N2(y>f znb0uOmNV$+wpRQGBVVnE`S_i9F{q6)>DNllbnc)v??rwIEf2x$71AKz(l(V2uM^zh zmDw!${lebP{U-!tw8u2c!`;N2l^Qk8fyB|QI~%Gh+=$3}gMPl>dqX@L`EOj?B)qFc zyXERtDI~!2o#vFqL+(YAjZTvhbf4lob@QdFJX~V)7cCO!nu!JjDsP~FO~0Yo{7()e zr>?nv7Rd_LWHVLH-*D~5ljef=nt(6rTxPCwpKj1sydu`?!}4po%l}^3K^kfZrjN?< zeEe641mM5plH@Ke<1fY>->(WuQR*@XZ5&u8P3q4V6P4CiRm4xJ6RnI&Uss(fR3}tq z1s%~;6pr>Ru$KIFSeK!z8BJ8OyaA0Z+SJ0aeZPZ|$M8y~a2g@@9zsLNY54N65U0Gq-rsv`0yUKZDBVZb7ZivO-)-nIC5(7irh%rAAWQJ0RRj7_$Avsd>;5i&HFkSt|dlzx$H0<+bVf4@C0W zvDRL{Qy)R00!503D6Ct#W-)JfgE}VHp@61pHEHHDFWYN?OAkK*lC%NsdGZog#p}%}_fM@T|%l zi=NqrM7aA$g3;)7sOc)YT*aa133i=)k2e=}k&fXUL?Ua_4tzpesMo4}m`2Sm8%khU z;o3I<7$)G<(XMk2nbzf=3dkg(ObN|hU^TH5sjsrrM}myn6koXyBM!Mc-_r1Cm~boW zQZ9QxeHED)?67>K3{xA7I4kUN29O?0vG5CAYezG(EF=mC_ zP_2|?$CrF%wx!9(Jj-9A*4EwbJ4`-jskja8(yZv+7>n=~$vZI$nHm`0dv_w(cNAW7iz`&HnTf9FTf%R8JP zcq(zoK+JDgzsPB_6U;{JYrt(>>M_DSW8s%Gc~~=V#zO?bMj9B7$~~`uww9N8tr>Kf zZN0Txtnf_G!vgM0=43f|_Ul!EUYl=o-ZAxP+{yt+vHkx3_&jqsldEhswAVfjcf~<$ zy22RR-3PD@vk(UU&E`p}Sb5KC4ns{-%!7QV+-4H%fz7nwnbc_9x-#x^uZzvV6mf+u zLKK6tH^{ql#|mq&nol78h9(*_;1||mT`4f@Sbg{tGsoQ)Cc7u-<;@63IqcwfXQu6z z7z{vi?A#BEvIi;^GQN?SHf)QR*y;EWcxmj)F#(olDnO*6&*Uv~e{hOLi z?PpTHTlJ(D)%`oCHPVaZkD!v_2u+NA-jV(Gy_=S+L7(^jI7Pzdcn}>lXV%OR)kdkPb z+)1?ZI;dYSl`uX4^AnlV&alX=>LO+aUGOh5U zx8{^K4&w!nF9rKV)sn1e^mZj&%`4ru~`I;*1cej|^AgIL_WO|m0OZ(BoxI>h^qJmuYNC^9>j zSdUi#vSGQL^5x&>cuC{|1V+t?w^8#!&#B)Od#th?ykc*%uNzF^stfYEAdEx`UNYua z9$r(BJjeV;VfZ%|{5JNlwLXw(S-a{=ap8Y;HgyIm^8!8j68>T$u!)Xk5L&E?|9A+2 zMZtE$1hm`XS~A5o_qcZbNBTf7pkAjD5B6`e&4)8>jehp4TheECwLxDae?qV0sF#x# z%BD^;7aSR8(KI6={ zu(`Av;(%eChG$Mdx4Vhz3@e3_>6{xw$anXtADNX`uq$GP@&2S6!H@*7tH@JNX(xKB zfzT%YerITz582OwnMol0nQ1I3u^|P=zn#cdU17U_{{>ig1<{F2K`J@Su^oWVac5(x zr=XZ6IG2IbytNsO&Y0;_=i1|$CuBmr!L3tivg7w*&};|2UNFBd(}+CFJ%4%Y@Q-S% zR+*ds?`Q}8DD7dHV)-%&h?V2@2 zNV}>uiLXg-rMw|QTViJbiaG}YWf&@fg${feGPfDG0=LYjXtQDbZbR&zJYvzimC<~K zlvE4H&jZLJb^=~iT^-~^?ukJ(#cqvF;0AAfvy_&nV&?PW<}Et34TjX}c+V)`5Pj&O zD&(Ftm(z!5MV%6>Fr8m4#^6D0)!{R2omHqLuX*kK6`%XzQ@i_7!W6S7&X65jsh)q! zJ!DI6H^Ii*;23&CpKm1Dr+*vw8^zIsH`^fGWz#iV6S`S%p2A(4RpDPL_Jwh`Ji0PjE%bb1Dl`Q;T24L zot44rDll#bt+ym;>0VFfZHpu-8O7k*51tE_3?{ z(b#vPKLc_G*>z2crj;VrI|crieC1-%EX5)62czb1sT3AHOG&0LgWid6LW%C5Bi?E^ z6t9lLGMKbW;9{;}`!?)o>ttXlchzfgWQTX71kN7WLX|M$szdaev#=UqvXJhH@<`Kg zqxy&!;}R%Bel6P(CwD3mA?^)LtSlqZIc!`mZBd#*N>Xjj`N1Pn~JjU={oTL*UV3qjEOBazZh4_H1qi6g3nr^?I$7 zL~^$_ms~o64FQs5$5;&95Q_AL@ZWG&(MR4Q6|qeS3LO&&*N4|S-e#E8bDt6m4&XBx za0NpzdsPUsh( zq;BwZNh%$|ub>T5jd&HTMhvcI^g?;@joT=$to0cNub$onU==VxPOesb4ko1fR$o|M-uqInon&Z$w4>zgi32DDYmh{8>T(oFXYV zCKI5sH)*bgVt|e6Qer{6Rf5}y$4VA&uiI>u$S{C2hPzK6Vk{iGYh$gB=4je{%OeOu z{Bf9m+WtTshKWsg8w>40`khTCH8!cT@N+8j!A`6fjIXdB6b^qU16@kSNAA8fWjC@k z9YzVt{uVPW^PSQP6snEf0dS84HzUK^6iPY=nESsG4{mJa| zsl_CjrCs>?9r~xpWBm`_s*$$`hm@I;=7Z%vx=TGu*!j!O8vS^J*MqbTA$I4!E`23q z>JsaBV{&-4I59wsOu>8NIiKHF=XtGBr;d_{=a*`Y*nwh>C=R7A7rxK}gE!oM(%4uP z+-QSOmBSEfOmMXyZTLjMeefy&i(WlGdifRQ^n6z?Vp!v(eWeclzwTE7d>Ss;`HjYO z)D`0fJxd{RnlYh_@7q6fj;3F4On>`W$skB8!Osvn+dlQDw4%~!J7U*HEoE@ok3y0S zTJ8XZyW~=aS3bCM##8jBBoMJMJH^PI)_EqyyB3-yH-ae87Il_S6vE`}ED zk=VO>vCxHxXbT{H~laFqc>R;SGgr*`OOzjM}Y4v})K|Aj8gcC78cGYIukqOzw;(22(MXE-FfBEIJR#-XtIWk>UZu7@}b%!TdR6a!i zWyKcz+H_=Y`f?QfVO>OPnoe*1zcE$k=yFt{dJW33<**d%mo5|`Y|j*#`e8WBB<=CR zu!OnmxLAkbNzdf{bh(;h2Js*{+LD1nBHmd#8jiiK&DPaI5O22uH0iunI-UleEmgIK zxP9fEcZ9js{TLa@TzfH?AC%4RCW$`5cA`l!E^3%tV#7*?JR12(XuG(n9z)9|H_9Kc}$M zdwJ}UFxll2D?&sh7E#nOQBgUJ?F~@X#l@u02{gE2(t3g#l-tfPwH_nUj)J1(v6p-8 z@BIO}nU4>h`1DI-9S<#AOz55jeRQ!Bxy#_iP#5@GlMFCX2O;2;vd&jEta%tmt{aRq zE9n7>KOAo<`5Y?~>ORaZQE6&;18D3v>X^%S13a3$c49qHmTmOfv29hf2^Y8_K4L^V zRYJ8JX_s@@U4~wotOX4HeP)sJ)^h%>X2E3|RHJhkvh~5n4)cqL%*3i~Qt}?PVJBR< z|Al%!dJs^H0UZnk$uiZ})iFP&yhn*R6kI3gZSJ-OZJ|sZi@X2;p)My$zZ03&y*ouR za4 z{h3bzkV}%^Ui_rxiq_l|3@}(hV)3doNf4k5b!DNLg|wHAwmQlw z8|1MsJJ&WTKJz`aW$*gN^G}*d50~vGz~sj8b%R+qxI+2?*>2{?p;mS^X(B$g&Ub7N z&Q9DMk*=0AO4Ni7JU+uDE)axKu%c^{Np>QDW|)5<8V|w;qS1>sxHzVL%Ii}tX!hv| zib{?)6spr8@>F~*?zuHEw1b*)<820iV1_S&p?0qPEil6UQ%Ya{i^PnD!w7por&Vi) z4w6(68F&!beNIwIYxtJV0j>!^A2h&-iFwG4TN!4RloKqp*kwgRT(zPYMhbz+T{5?YvykaCBlfgoqv-vTCa5R-N=sI{RiWHaLtgbKm?*zi#9k}-WT%fp>Jqp_L z+f2n$($9usQpw9@+=!#r`6n@?s4Gj{r z=);~%0vq|^9o({d!6+bkOCrVB5>w;$@TFdv>Y%7ew3*#R4B44=SVdwe5O*0#E@v1& z$+C2ueERG**hG&lXc)XYO|QNa&NFt)SjM&3WK>II%|>e=2pig4llmCdEiWEbi5k(S z>^$Jjs4Z77ughdJyho>lBaC$8D0v<^oGLqPu+(3kq=e(62A2lQ{s5IMz^nWL#XY$C z1_URb3otK~@2Q7Z-IcA#i62BFryp5YKv_#!_bx5*jIZRE8g%UWz3csa znlVCZA^wijM)ZAe5X?FdH&u_%b58;5+iA;6l%5tQDbW&6BMD?VizdT7;!MSTk^7O| zwcq8Xil_ajh#W0Ij&PHL;7n`sqffPU2eCT~TiZp2iDRsVBIFldt*4uoSv+N~0M&XW zvkuOiv$jIhd}I5rdK#t}CK%C%I*<0walJbmcgF@=G&q=W<3e7^t@t$3`fqCb#xmgG zupnuIxW&W1?%22J>x{(tj4xI5K*ZyMCES$Pj9K8U0m#Y9({RmMWk&-%MG5}{xv?ID z1ng;C@*`+y z+n1OJ^Y&rcKi%hluP+=a6pNmVS|WN45tQkRl({o-VtR*F%*~1d^2dbj#1AUfE#?cZ zuOlCsVQR+tD0I~{hnhw!3C%^tM$IBY+zpAIyIw?&2^xr+-pZQ7Y7{YWX74s&BTm37 zb2D(^B~eo4iX_u#E?S)Fh;O(PW$42 zNlFMCeA|;!$Bd|8zivswI0NZ4$#I_(tmu*8AF&s6@!s(n@OytD;V0iWmk+)*liN-j z*+qA}kol>a$=2~XmO)so^cf^^)qj4odvI{6@5_k%x4ENbZ3u_~bMwH>11c8{r(a00 z*9KQ7%<<{}Xr4=JTy&Z|(8B9KTWu06N%r5{*^~A?UJm~^bZMmBfW|uhb~TSr4s(p$CD#tfNCe_wTbmUQe=u|LhPJ10p#q?Tr`tzm z+Sq8@=d!g8s%m3sFI!4iSeAZR0wc~g`+ong&KmvwnSY@j8G`XQo~9sRVH^8^ZlEJ; zSci1;ns7V#^WE(?63_qdghgp3x|1G&3-T;X$8lx4?O{d^lCbTtGtzUyuQl@h@hI%n zH@ua&b*e2SA{s4mtp5G=s`p5viL77%)BNjgtL7uZGW%)4&39UUt4o(R=vy|i3)A3& zi$7~>9qSTFZXF-X+r|P}E;GxQGAv-|bG}7_Lav7{c^W z`ExjD>a=j3tK}!}MpgMr4Er~)Ggj0i3fFDS7%r+>ftAk-c=N%CBNR580+coE>i=+c=tu}1qByGV zPGjR0ct(XK>o37Cq+b~-ej}14krIywJfWte&OjXwg;X7fw4&NvP3}AVL@k< z$x=(}ny$o~7tR@BJjzg3rx^g%b&OVn0k`ZO69+P&r;0RMqf2X@z(jnWH|+A+kce4b zv+L~rG5+;$8{F3fMrrc=+pGdo)%|0u=_lWD9N4@yVNM|p!u(ahW5r)VNJO z<;S=e;$NC7ag@d$X;N`UW5P^2eZ-j98SbLC+u z`?6)6D_w}19Wq}o^8|S;F_8R{<#B?qqo0GPtyiY4N{sPDe&->cjh$1`H zl%?pZRBahaotz!;zNM5i0i~-oy^7_-Uxzzz?+*;EGX#zK>9@8UBgK*K-y>m^FAv>? zcd4rj3dR#F>pvU{>gjxr#@9|rG~{JJoG=s4ybE@i1s;htLdxR^djHfsU}p=s=WMyn z_INLGkSVf>z54sZER(B)wzgr13o7QIA`SNrLLed8nutfRQoY=edog?xP-FwXqeJI4 z)HyIgt*&maqHuwF%BP4;fwV9qLHt<~5FASunV^Jo|4JKF)=9tKQTKfPQ#?=4H>Z! z1oXdb2Ub>y|DE&RjAC!txb z`oP#&t}Z;+`;qOXJYpC%rj{;jr0q+#UM~5VBkREof*sep+(ag?3u>!V!7bEFJO~3- z_59mu*Z$yUnJPZkgx)Vb%W~UnC_s^w?hqN*To%~DO=LDeZodQV|1A)_T4<9L63H8v z#CwAkvONU*9jMv<0lZGg_C1goB>{}iTS~J>vHn}aeiA~-ahn zsJKaSL<}o{;9T!!n!<6Kai#HsYa^@ccf4xuofmOaMwch`XN3kRE?jTy*f{=s6#eA* zZzekjlLvTm?8$~n6V$BA``;etFo$#oiGZ6Ij0%TDIwYPAkP`|_jN;3+M?j(PKNuXr zqE=#`g3J-++;v3@b?GQH)g>(}Mh&wa3h)&pG|dox8utp!VrQe!;EvA17$6&>15y%z zi6SOk3kV!#IR-Tw3S7>ekbrkQ_hZCNyk&xGkYRq#Q6q`3dNglx{a#>Wq8~Rv|7;ZH z&}3R9^-$ZkBHtIj^mR(Ms#r)Xwo@Ja2c}B)^92vGG5CB)ia9Cb+|5S9G3mXfM54s} z-xa|F?BMk)CIAg`w*m<9T~Yz^Vt^>&T=yiV^*9{eIHtwF?A1|ROy+2u_(b+jPTf%a z%-Ke4I0;Hk;M2j@wm|Fpt!BGJ;^V%Nsi_&oyBVL)+_b!fyV9lVUFcBltZfR(diuvQ z8YPbG>X=#&NP;OO#-4>oXkOXdAaG0I(( zU{Vm$74|@T>9YTTU+LQGFRUn2z|S@L2WkjHuj!?rPl0O-ivPNfuf@x2b!UpX?IQx@ z=6%)JguwsW$St$p0j9X<^9}p@89ymvKan*gM*{qnhO!_?$`;STxE)>RyfK_08}Fm_%hva6S6?3x*^J*W-5Sn#OsF^5ePQ|FPvO=87a_G;bep*@G5zVB zNBafTC#9Pa9IjgoTkB2{$v=acbo>>r6de(Uzqq9S6?vS&i?Ju5PP|wkt^55;Zu3%a zjkku{do4O@pM+*&ev&p$tjSs=yX99d{d=wnXqVfraZ&BwPdo9|^i=lTb@NH?RLVT5 zBHX}{B6#!s(hNOmW_dz=-mU)VAEl<}E&2>W84dry+FWLi^PPFb7k)DNs0cv@a_(n` zya_EmX!!32l1&A_jgCJUk>p+Dv87+@#^?w<=a+^?NwclZ^H>ESNU|>- z3vL7=R0haa_u8}m#>%ll+wCfPLmCkCt+23M2r|AVJ#??3!F-cmvXtduuuZv4h=5+$ zJ-^6PEO;1}x(nQFb9BN062sQi$k&h@h;QQ)CT^zge-WaWs$2;>QAMMCA}Rccw#vp= zxSAEi+db<7y*aqeRn5qE{=X~$&ajWN=|Gp)m***bj1rR)RgiSeC=_=3>XOuX3!l2d z@-2hX1fr-cRRRGXY1F_4YXqwAwM~J8z#4^wT~Ur&$qn9bnk|^X`P@sr>GJ-JbHYA} zUI@mj?pG=9JI*O##m3E=Rz+Fk=`I@Ph!FRIo!0W1AMq``APZ7a?w&Qqz)q{KoN@CI zU?TL^m(%?x*B%7s09*hW#$alI=n&VrvyZM$U-k*HYVct>uJm5`W-^qxOkllRcRmAo z)qMbvW*P+;&W9jREwfHM^~cD7V$-kjb?tG@U8~;cVu$*j?VDzrh-Ov7|J`WWNaxws z`L5dFA*E(rf-W|AOeM$(xh+Z0r7k0m2*HL1#i;0@(h5e5^$i_aJJV6@(eZe9qiHbn zJUeE!){z=Doea_}c2^ci^F#4r+?v&vM%Z7lH5!qliZEjBQrlKa*;+LB6YcaYxzs;i zt;t_Z2?QK(jU%1z03IU9vC~F(KhKoB#9>D^B3alYS`oApG;&GVXdfNcs#}?prXHMX zy^Gjr75UpSNoy9LeKYk$n02`gwWj^#bB~jEotP}1?p7#f1LGfaF^BWm+Gm#KCmC>z&yPV7B0xm=f3AMYwja!Uop<2x4SQ}+y48V+4 z#GHw@k!%_{TtTfO1b>@WnY%NJ8CM-^e!O??Aaua0;X@`82tp|C>D{-t9p=Z3}$n>D<9usdlXK{YXn zD1rLz?vx<3-RoHLC>HzE+C9bOqKR9#1l3g**1R*pxXUa3_0=ko69K$${7Wy4C&sXn z+`5@;1HVfKm8FNIZ#V>NVO(=V+Kg!t1gu$SCeUcO(tzz(UIcsWfm4vd(zxzk$6rgN zI_SmMPeEq<+&_S5l3HC%q6iPe`f5SgSRv;iOzIFj0vhwjUs{94RH0Dp90$P#zp&&R zobl@#GtlMfTe`+QB&9#Q914UA3njK;u)=M=M7MV8wJVPmnep8l2MY&_%3-?!`N_cd zZ#UkRU&4aoIWJ`&MlBLdVpyQf=fr6y!(eK|_kn_d5VND2K?O{WiYHPi7j&43tk5I$m=^k6XnISq{N%ps$>C-RDuBzP+dnAFTmZVSCr&IYp}W zet1#xtUxp9e4l+d?_bsReJ>U@0B7I=gb6DW54chhIC0Qv=>?SzDw0y3MvNtSrkAec z*Z)9DNig{Tc)H54Cf{(sk)uJnQ@XpPL+S4Bl>b)N^&(>fG1d^hXfM$}kzBMctgcUsDQlo&MXhU#_%+4aB4W*+8 z93tOzN9G<$f?^3d@=BKex&ortX{a8cukFa*hrXx3i{FQz0-l}>1@OD$^4+Ep>syNw zN0rYLwfzBB2ef5jA*~PTBg59~w9>QIEG3R+4AjSd%g5mh0!#^ZKNn`lTiD|q zSQR35;!F$bTy<(d52$v9}BrYeG8olbZ(a<_v&1SX1r5NO~ACQfHpr7K_ zI6nK=ddwR(hbOsDc<#iz%^xFccFCzJsd@j}5cR)n?g+y*)I?J1Ib*#QIIg?u zoAMeUj4T%)`O>t|sv8DD{i$%RLOsV|%%;dO65Ei&hPkdOoLo znPU3bd$L;W5OCEo755)0B-aiXW&ZQ~-jUu|?ig;pIpxE!qeZ~lKBn%nW zG$)0TI?Ld4X~1tK1X|fMn28hzJcT(iQE0+ln2@xS!d;UQ;__WNYOn}isM-%qLSiH9 zd;v`RQB|7#10^Gv@&~1$8)n2P@PzsC-}C2*J#)}m7$3%QlJmWtJOgcwO_blCW{=WC z3OFJIv-=#hZ&zQAbepV|U7RPK4E6;)CHhq79i66ve>Q*pif^6+L#y=?_zqWOHFw^z z*me}5grZD?#2bs`34W#^=EHA{f5Nv(F_;0NH;x)2EWRwyh>!!2Kr`&&$5>@7I`WD+ zO25bxXGr20e+Yg%j_xRZ)8{MZ{~Kf;^5RAu#53Oqey^x@76~B4 zipLnA+vavDO*$59m->fVjThqSaEaP^cXZgBEq&N5b~4O(Ox1?YRk&Qc!c z_l~o9XPy*qk zVtJqNBh0-p?nBitKDa+&Q5+UI6&ld+oqi1*Tr1TQ_JiE&=h2_FRkji)i+=A3cw+~d z4nBJgeIaIW%tAQLICe>9DVry7WKA*DJ@aR@4DTtbs2A))nFy~!mqG#8nip1XL49rR zNrO?K5Nkr3KO~K-?neRG*|&}{9^eJ1Z9^43%ccd3r%+)Lk(}BBvWMIX)4RYEc#ch@ zvs6aDTYzieP3yYX>K&|+Fu}aseN+N`#J1F)l<(psWC7T}{mj#KJ7&OU(*3R=O8=S4 z+Ke}fYEg=+KlyP6$G^tTa=-t6Z-RHKzK-ysu2Hj@i$|#MoW$;>4v&ryJ%%C~PS}S- zy~aw}eOh{-<=B;6L*+K^(oERAUId5GZcu8`dreWgy7o&4yFHdR@Nb!6jn<(~x?1|r zShtSI5&Y))G4h09+S@zQAR^arfIVDMh*fXAbZCr)QV%46Y%aO3iA}Q46T4KM@mmyB zWa0?VC@YSF(ko@&ZLC*gz9Kc+gP>vL?yHEVO&U$m8EmOX7|NDW7sXe=kIJX+dLwM@ z{VVWx#jmpBchc$8J)bgKWh$;wC7>-de8J}=<@lXtt=*UKcukw(QzLI1E5|iT$`fm| zw4%<2o^ad{tx zya$+I78R{VIaB8DNI^;?PCa=$@uB;OtI1OH9F~>6YOV8k zQGS_)Wx=F;0s8R}$63df@i)qJU1aXLXityDPY2<145WO>C^En z4Ho$ptf7uz#8Z-v;I%|z_sfH~OOY$JtvPLyK!$QkT&iO`N4C)=g|`w*uOGGEPfEIs zY5=PK;Ad2#+P08k-#4C4i>qo!P&pCehjE_GDz;tn$^Io&#fAp-1ftW;(`Xy6u!*cz zas`F$1g#1AKQ&DM0*;tM{>g{XiQiAfuM|H&PP`a({43^2aS~_zEk3s{F95qcYC!dR z9ywjI;+fJSrf^5F)4F6IkqrVR#y=67=$T=0zpR8xu4pf~#Zq$;0f9bzQ8o31QonP0 zl{^;TPX*(GZAsr`hOkn)aa$wEvQm-Z=$x+(plUev6iTiuV|OFM14Su)Btnt|fYWg{ z+8-9gcSpLSn>`lkCmxzdZCe5m)@{emvdyl-0a^RWaNnC(iwRIzG393!fadm8h|Y@A zvA=)41@{3*H-4ug?Xk;hgjIt{*Vk1$n)>>TqnZ zO2CSq1L}GP2{>+9r<(kxqguCuZD8kzG(*E^Zcnzh~s zj3bhXO_zCNepCq0B1uF@3a+5}7%geOQ#fPcmqa#pA-d(JbD@cK%I6KrT&4O4!jN;q z3!ji1pSRAM>E61Xn*S|T;2^|FoIsNj?L7@QUGzN)t1h@RY%T98S;BK2r({&3J~tkI zjLs&SQ9NKGtPpjh*^uby?U1Aw))2U1LOIiZ3Er!HTtM*T3?bk}XWYg2e(br9tWjo= zpg~w9D`}-TekHRNW{j4$12}lQLRAMht2M$@B)VZVV^8450I%{1nU^6=(6O*rG3kt# z{7+*GKZp99F;qF7@sCL<4u~J{d2=h{+f<>#>>7rA+C1}I8vD7$z`sT!q`=Prd_BAO zjuQNQ+-AijS(fm<7h|UFj3St1DUy8YvjVdtiFY2~+Y!6C2lO{ zbXOL|Ijp4w2j{zRD}Lw*A2t;*ue<&emA=A8OoObll@&r@^)m~GZw-N3dPeQ1CfP3e zmiqob$aks#6)wtzYS=Qx0%CZU4Nb-P`x)vpNKx+Q#N?FnC{OOd>6D25?<&#JSL3u}gO+bx`zi&yYv(zV#e-Ld+82ZX7 z9sZ?UJgN)B-CZRl3pzx3QmCf@aU%y3ozYbA5VUEnTcZOI5uC-V_Pub9qMsxrAjV$= zWBoKqjoUGpt2#?QY9WN<4oKfG+tiySu|mjtY{z6mzSnbl3n zU-Zya?WrNQeAU59lH?%^2ahU_6=|dsnOhLPw1)G5`@<@xWXX~{EDyFiSPvZq4{D&g zm@iR0#+h!xkBJhGZ?1g}cV?Vh7d>o3OEN?F(sR(ebOA&;9DU|rODyX=V=&Z3QaCzg z>_(Xg%d^WTvj`$;6*+Cwe7+QanZcOa6Myl$>mlq&NJX|K891;_@_B_l2b%l)Mtb8y zk-Oi!5?jp3r_(Tse$i^p$o!Na*A>U~~im}77npK4Q(XjHQwqcWC z1cKWI3|w}5YZJa90A5bDmQJe|vKiMS&L3*n^@h>~_`BR``NyTEL9|wjpFhg;c9kG* zFCvWE1W;gv0;C9jX#*EZ2z_o^($S`wa5*GVS2BK9gh*EqK1o|ygi-zS&@_P(6Jj+(O)ck;XLAk*#w@{X^KCVd~38c!0o zUiYS;w-aLIU0Np_!N|V#Vh3njiAwEjplr8h*O*p^^chcp9KT|{cQSTEhgS()vpyX5 zB?@H8sihOlJ5y_;R(m6LU8ZF`+0LH} zQNakzaG}+UV6Hh^QWK5)0)6YE$g@)UrihJKGdgx$WZB@e_L!uo6p60SZm-@PZfnEN z2mL=<;?BB)h(y40L@ekmglF9@fn(yKMTuVy7w>t2p55Vyn7%t~tg*503r!Ed$NZ4U z($Z}*U<+RmRtz#IR4vCg>H{U0IB!SkEc5%pr*^O3hSYgucljrXOLzl%a6i1ev9q`R%@Y+Q-t1pEDSJV~eZ9aL5#2KQ|I20vDgv+G3`rp0f z7>}JJ6G$VR0{8j!i0l~;;q4jwT5rxIg5NyX1N{Y{uSI^!CU5!bi{EzhJxpvLbO(F! z96pBS6nf$cizODL4XGU|k1~tIlqo;; zE^2p9ED`h*9}@=&d1Bwj!do||Dmn-sRe;lNpS45%uuq{*BHN60n@8DukG9Is`%7`5 ze_hT197e~rC~@BJ(3r0l=3CxLPru`2Uyes_iP8N&UaTQhLsIymrp1QW@%pD5;eg~L zGP@pS;Eiaj)leKHi}esg6u3Y-A0jl>u_k%fy|j8!+tP|N+9?GjlS%xXc5TO&yvQu* z$d+u_9%Ev@6c0eg$X>6g8e$UaUOskW{)G{7s1I;a0B-#L_nE3HBR2f z;YQ{W-G`+M`GH+Zq>Dw{rqlhvFu~^z@HWPx|5~mK^hM3^29YI;hKR0fPG0N+r}?zw zVP)?5+T}$j>VcD(Dcn$tgKOyZZPzL>DgnnVe0&-o=%vsM2#gE^3o$`hR9PV_yQUiG zo2Or>WOuFvQ6}+q=e+pUOq>p4ICOHHq`srXH`MS@K7Nk<^IMVA5D@_ml9u_7l#a_&skm1t|B_UTmc9x!+$yJU%8A)CjEwU5_yOhdL%?2o7wHyT!Q_1@ZgFD zusvoGLmB9EdnHrNm5Q~C-%asJI(wMX7he?8_1-lWrUotJT^6kiO)^5@JNXn)K6h(2 z(Ty*t5UTmnanJ?poE@NgOL<7%Z`vI8v9sNLeE(|&lgN?*8oWw+z%rrGy(8PY6@~fI zn2#^}Nz)eQ-Q7gUN$>^M%Nf>1^F$DPDIfW@$=s=O?(1ld?t$VFIg|yJiv8kQgPAOZ*#)g#=H9^Cq3u%X38+%NDNR-uNz`d(muLkVd*{yU`tA4`w1!}U zMC`_%70?inJhE3VfWXNLQ0q=%yCg;=m#1@+VWZlz)6l196g_Ai^b+DyeV|OkR0-nJ@cKz(S~eE8B-?T z-K3e6w>|&NlvU3=m+zV;_4#APb@hDw$>npIq+28jDiU69;E-J8-L=}lZjZAkc3mJI zVR@B!3A^4waJ^=Q62diZSEsI}X>le|I!U#>-d;3+g> zZu*LopK?o1-x{?9^yUSIP0bSwPzjoo^W3B!MVjEgXbc)Y0lU|9muB^Pu4WIQm#RZ>)lr=`@&^n@MKRXr_Yt5XI=0oTO1*GBT^Od z3i|P75ZHyY>GhYu+vsu`g0Py((y@}9Z9`6zd|P~}7N>{!`M zKW->A0_WF1#VoJwwc3TGG&63Vz*+98^i}8_Q4aj^w;8>l4GBW!zRTb2tOpE_tdrb~ zO8tWgRy5M5(kBoVU|Z@w@$VXpR%b}(W>-WvH|J0~nidfOke)91sa9EkV=!g1K$&{K zQIwe7Fsd&BAvD&S-H^~6ytK~@;mxyqUR1lJo;Rm=<>nUNWu-DukpBI={-MxlFm(<5 zFP1JFd(_|nM(@=ADr~h8QAUUVF1o%TMCNbX^;K{GMolws#5-XFsWAzXJPEs@1-qqHbN9#LQd%gS2rgl{SAHRmj8=$2aa;n+ z#dS~(!H{#XJPf?{BZCTP8g4$1Vl|Y4ICQGqx2N1<;J?tXRI*LMiE_jgCfPz@%CpKN z(dGMaabiyMN4GnfMQi)G=)2pws^FcLz?)T{ky5d%vTQ#CvMufQ-9DnQF90f0@UC3S zM+0B%sh|4C2t=*#tjxjS(p>*x6j{#CO?(<4=qsV>5EVeD^e}xTvizXqMgDRDvo*AO z@L!rBHr)*)+-tM*VTVSn-=>)0h@J(g?A?sr#NI6-xd1-h+==2+uPobqlt+*!ayNo= zDY?cbLp$TfAj*davXTmpdyXaLU6Cg&1x+Y!cCm09EYNix=aoP$`?QZwCYho2d?*;> z6mI>uyI%Z5wW*RB{B61r+g$donN$V$d13|*`~{RliXFgK*OKIe;%=JYLP$$TTRxvO zC^y)=)F6CTyP}?->D>U(k(Rs4PpM=sesG^WV}bB6t=?*0(9n_$w)1zKTX?)A-yFL= zmZ4?tcA1K?Y%&>ha!i0}w^r|mXR&t4p!RTj4NAHhm3-=Amv@9ZSkuX*6Bc93el5>R z1g=uzLB(kEzO1>$(C&SR@c7L)V^D)YF=(b@w zhe;^yFmT2HumUq1pw_}GiS+<8D56cUhfVP^@{y5P-4K3(UpWbiRHr->qFcf7`kv7` zrm;z955f2QrK@a}?bika2%9aGeE6M!Jp#v) zw{oE)k#><>hVXA8;IZ1o{g(6+9Jq)c+S8fFA49Aj^ZZ1xIYoVy#mzHvmMl=#;kqng zK~RgV2Rd{mvsJ(SHD3p4FTPON~hnu z`FPVQiVac2HhCpwA-_e_wl>q5e-sN+p9Xf6Dr{67OqT98Pb|5$fy*?A_5#`SOuZ5C zE;AqN<^i3HQDP)i=E^lEY%ozuEjgEsx=qV4|Mkvwv&)s#qQoeCAj1zMu4hD3OEw#t z+s_poaV0yuZP~00|9X8Q*&|^~1_%b9gzq40I?js%=nN1(pm9A!5);53Bry#{UGjowi#P7fKVa8>ML9VIjY2u=XW`F zPQ^fs-}E^LqKH(N>qru*On_*1$*^^md32kQTusmpU`Z8xp)noO*)##fhHQ~xrCFw$chP*5{j>6*Uv{HpSoz?StHERO%5kI@+d%m|l zkGWslaee1N`)vmkmGrXfUI9@BYJV4syJb#xxnX`6NBeZf6OmHhWZiW}*{E?sQ2N_H*vML%z zTHjB8B+jeRFs|k$GS3cFcOgos& zJ)_Mv5GqDHY9994wGqL$bQAXkjrzrstr(7>Txe~t118d(XiWWcze)5~a6<^X*!b^; z5oyt|_k=v-o)bsRk{v)fiZ;RKVS1p)0eksk|EL)PII&D$?iY3{TTlF#v#W#uR7H_m zKdr&MQ_hccan0ZSavl|i!$*;r{ITWUFO8{>c_o!DG8#TA1IxMc>e$zp?+E4SN*-)M zH1^v`nd$?4x5vupnv|;P26Gkngg&MLvD59?;jot|%PH(6sEsPII}|JKRCtssCw>co z6mCUEA>&JzKom>FTWL_F1z`tYTsLCD%~4`zM^J5haM{r*WtucQ=m|Vms=gXy^HXFV zui~qlT(5~_V_vq~mzZX)HXb99qWg(lbpT}+d1Wkuaq3rqyPEM-aQlA3(E@L6YdmHP zRnXYRZumb!)rHx7G!Yeo|_9vO85Y0YO@v;%s23`!(ADJ|JbW5 z3Z8r1;~C$%CG{<-B4bHi#<}^lUfpnHcQ|^hR&tKYtcRWr&~pbeh+f)_kL^@Xa|dzF zTQys)n<)X;GN!-UW+wd*qkRSwVHtI9;J;jOywLcp`Pu59$NsoCXjeIxd*!B*lAMTe z>LoN=V{dNIJL2~k7m#wI<8H4Pcih?8Z_yFqdCBL$QXO>)$Rt745PJ8!oiy7cf-R@e z-f?1G@V*g*umYB2WmHKt!?;Dx?M?F;>nSz|V-=an+~^~=L``sY!2=ayHy5E=T7_e@ zbkzq8{7F6ntG0#@4Y3nb=&D;OOZR?i!w??2!j_1#v`Y+JPK2fus$Uk{*=Vf>nE)p3-f>e3frmXr^FhJ=14HNzncsc zpjLZ+W`R*t7D)}6TcHj#>+v5{bR{DX{DoZrhqG#KmEWQ14>7bdnkc3F{N4E|YWD99 zWLcYW^2=XKkJ(P2;d0KgvHKkN*qg!GGs}pg+N*@|9HhVS5(K{v=l+R)#i=EzzW;U( zs>OqT>hnD}g4@>DEa#Zd4EZ?W*dlg;UiyZ_kAtwnyXElVbVkKD_APuFSV=ed1!r5` zD&y>(I`2z4wV`e~+e-?XV3;k}jm=o^YAWxt`3+VGE5oMHCFU(u2%3Q$Xm-c(mW#4+ z#r><|0~W{ad}GJk?`svwLQFefRy_AP#p;I&2IG1;*)yV93f)Qu4^7J!CJ2#}{h z#qWCW@(~%72cn`E&78E$3gGYlc7B5>Pni!mnx0mxnmt;iil&~ExTc)_`FAyOl7u>e zUWLHkDb4Co>0N_8>e`Hv?7!a&!yEAT@n`!30m&ZLr(`Vz2fs#HCWxtk2O7U9qY2#o zK1;0*KD?P=p2(?SdKnBn^P|70UwXc`ShY5?WMWt7+?ZM+tfg^e>JVmHm%9D_GK%bB zQtl-0hDEP{xXatra4W(pcz&0jlVzy8a?CM*r5 zqw^Tair2K)CyR_p<{E=j^1iE86~qYYp-1+d|6f6vkN2^Pv?;7GM@!-%{(bS z5wqKdVjYTyGr-viZzQ=5phD>5pad%`btrM8Z%O^s?6%+WlMqjJ4M=Cfh{)d|Au(+k z{0%x`ip~*q_~01F17rJG`jg&M@gT^jZ+nc!FN*I>)z{a{>qf;VFbTAHJB#UZca)%X zhRaT|8C`!VBM5TLN?3e7mt=5Tu5sI2>89#5t(1~zswqm@ldT@Y2Uh@fS8N9p>MZ~< z=wS@TxmfY_U3^P?S*0x${O1GfdIQYZO|8v}7BXzA`z*AO&Iq1HIqQBb`U@Y}SEhx| z!+!Q1X1lhiZ}kVa<6-r5__%T1giBOtlt{Z%^Y-=qNm4Dh2Q*&NVtow$gtZaP0&P?p zmO((~PY^_rdxAz_wHT^p(W>yUWx?B+r%&=N7%%9tU%e7 zG>-_M>=uE<%ZE!PBLbNhKkrR7Y^y_`GBJ63$sBk{_%rS)&fX=Nthm0V*x##(-g2&c zdq;HY+1j>qvAGIOo0jSG0y*WeN?W?ADt3o0)EM9ZN=3Md=3cq`78-lPxzKO`exC}S zRCmNh7*{`H^z%TO8grwY@5G`9?`bZVZU!X8d$+xIZ7~BS<38JX2Axw%)tc#5?5t;rV zVz+g2Z-_=_W3UPOAi(Y<*6icz_p~a8AF+&Gg*A=+ZQ5^e> zUBKXSgH=;XJ;E( z`iGntE4jj*4jjKR>1qd>n&0O+2cq7QN%(HX3J9x#Zu2jMyu^P(ixSi;p7~c_k5$2? zIgw_IB1!Z(c{L;(ZHkyffVT=kRWX>0JU+qYTg?4ma% zgYV~_gx*aI{q9ia_Oj~ajVDh!|IEMdn9gp=r#x*W!cJc3rr0|`x5zD>IHLFtPU*p*BLJC=Hi7Lp;Qn7eZ_*pqv;hSV`g{F^Z?9usRl=2Xiq!C zANUR6nNDT=sG7sshb*zPFf74-s;#qL%4apP+ionK(GH`(OTV7QZeBN6D+8=M9Imw8 zIZ-jndpSNP!>2NLyRUvIqYW!8qT&> zPB-ht7F93&6K`({oS5_b4Z@}sxGpNz_0THDPXVpEXM-eL&6f*lIgvnyj>G)0H>?EN zd(*-5;?RhiPzE@$YMQh}J6tIISG=dksrcY+xJd>cQ|29C-P0h8SD>sg1#m0T1PP)1 zC9@)fEsT!8o5F9#6E1fP04H~X#yH=?Q<}Q~w<7lqNUR{yzVRA7Yt_db{{rlGCvU&a z6VVJNm>KftM=O9d_xb;E5`X;jmk4=z^mwpDjJSfjNdW3S=rQ8acb~_{l8Fb|Y5RN< zV&B@1K^0c*k{flMG zV{T4v`X>V)YppQl*v|pHj%#2fL~0gNEQNu;)IuvQMlH)KNkN(uUWbG8+Gm6JEG41+ zZN2bg$F)Wdfq0I`RIYXMn?KQOTna*&kw+*!EY14Fd)6-y85-6epYJ}}sv88OW=LC9 zufhEHM9fBc&QD*SPscHSrBBFFA6GqlZ^lW$1W)Pj`JJ7qXJAIana-p8j`QVA+ZqMI z4~M2NOI&iB%A3>qJSI(O8HnJ|-T9;KkT}jIB`Mk^e4|RU3$?d)LB{gyk660&aBM;lsAG)_wx?(9z))` z`F^$OSYoT1%b|aG82H}m^8R4%XzF`a*ajD|j_dlA7E2DsmixiruW3^O)V#s$iJBe`3V#Fd42up7nB!oP9hBA&gF_Mnbi)r_^W)%QG%1y6{!S;Y zIn>I0`NN}cnoyh}f8MiZ?9j+U8Q5ib+Pp`BEXQnZT#`|Huq;dRN;9*|=VHNCd(XKq zOK6NYr9ET%Sqkjr0OI!8wFB7n^?eS5f~lH=+Z`zRRQ>3=3#Ry8iP)v+NGO**&0Ou; zhHHL$m2}`=5TjF^^$T*#rKDOAIMYB!Hs856(yTGeea4iqT(zb_Aec|>96vh!@d=`I z40_O4JCl->Ea3nrD&)%x_>4$%oFro`V~&iLd{@%+K-9@IZZC4^CrYW?RZYp7$fX^z zDXB(q5dM45aGKgjjWIj#RpV_|Nk*<_u2w-=w>0Zt03QVpeYWhK{z;!uHg@G6T!-3} ziSHPA&ote75Ymcz)ghPVF>k_uVT`PA`piP;LweHNLO;d~AfqrtysoV`uMNaJ?Y)qX z0rF|l`O7^ck!kXs95F4Q2)3@q-3fu` zZ9BVxX?i(If*a4G)A5%>56DQoPgpmP?oO@+-|+dFah#sCUJyu7RldB{XiIq(O+F6O zvFuGh8(Su`uZitfCG|%BkXSd9FJ5w{08<^K#J%5%Us$;F))27w7U4`ZXP` zhaQE-O@reN>3IX3`jmh}nb=)Be#Lc%8G6$-5xleopbx+WBCu6Z&53Gc-Q(K zsbb)an2RBivD7*)_o^-WKN8E=kyH{eu&=4-k=rKQfGb({&x(jDdM_~d@lX~#IUys1e>$1X#=`uPdD-pyQy)3(rEWwS<%UJ&K zrb{%X=(Cvi16oi#UyU+bIDy?T8LclqT!&s#%&!VA1c>o!(8X}@oE=ttKGniiA!*ys z{?-z@;-d58c2Fe`F4^MfmY!{S2m*(PNYT%CnWnj=3RJsjBkMC+H$yJ1j#dk5?W5^S z^oq7B-==EZ7Tv4Yfe`#UgB@BzRy7HnbWS7`!t#O6a&|q#`s+x8H;yVP(oaRxt60z< zDK_=~W*F4;R{o9=qjnWZJP_XQ-sD9X(4r;B{*(<*+Z-b>j0aEKZJDkIxJ|8KgM_AY z6d8M2TlpkBQSAxe05Cp7-=l38M@Tp-UZ^%XqH!>2Ar~lZg@)^V9i-bJ^^dF}B!XMLBfUPeqVm~kMq+O99(t-LZ%>O5|nv*8`d9li&u5cnABX7f{Vp;4oKVrk$4 z91K}&3Lv1*aYOctu!37RftnXW0Y$AY~c|bEuwV7;*`70bDkOFZzvNp?R@&- zbSTDNb$pt1y(_%0_7c)HSktX8q>Z>-xz9G_dH&AgH-I-qDu&0v1^o8!tfuN*vJ2178sYVDz5%m85+0Gm!Ot>fujw*&O-d6! z)upV18BEne+tS&mT@iLnI<7yo$Obxt^K0OkeZ61QvQfrW+QIeZ#;dh)F5j#)BU?;! zn2Yv;wGxl}6;ILsa#MWf9xl(b7ugL0bYg@jNl8}w+!f~4BC+m%vIQO5z6HA8hUOiA zB~rfbk-DQ=;0xZpwm1!d@qQkFPhTk6*W*+9urNLn5I6LD-d~@$ zLbg);UCX|LdVC*b>T7mJ3+U+oIUWrm_Lo^7>SX{2J6 zOe+~1I{)t$KNWR7t!V1zPfGL z16ddsd+x5PB>P^IAy7;Y9@K2*FZH(qFWe;oBgsG>TQtGR)NKOy1`(mR_3`TJJU(P4 ztiUON;jsMIFU3?2Q+Dy^^LQ3!b*19+G4~_e*J95CG9%@8a#dPDy_WUdPfqi@UbHnf zqa?AZMct9&WO=a$Akg=*u-4S{IGr!7rXyiAr)|8H z;uUvlYFZd;5W7eVS~71Bl$PyNMx&|7PF1vEu(6@ z7&7gzpc+KQ626gx%JJ$nw5Rrbeo|f1T@|!t+=D&9uCkhcQO>=xhf7(2(+YT>qPi6ftM+xC& zWQ@0HLE*7!ZoJm=B|3MaW4;;WHLwJlzQB!e#a8{TP^=SOCYjFYpgJerokWN9y~K1Z zR&GWFSVW;%TJg-af3E40l7z4s0?Y0z+^>+);2^Fj`YMo}LO6q3q=dq-iU9n-ez@bOyCE(ea8 zF@ZPRf6Dj}e9C32=v#=iS>ERui1W@{2F?>ZTrqaEl3qG-ag5?95Pdo7{}3ZW)n{t^ zsB8$3UIZbARn$Ydl6u~*dIcToHsk$KT$mSJgTa2LslM=OcGo)^;&pw6K(Y6z5r$_^ zH|wVk$tf+yZljV{nYbSR-A(qnFCZ3V-vw8(f3>Kuoe@+p_7Hvg`jouj~}=HdMDu5v76MYZ}Ejv*H)@ zo6v~d8IPeMWJ0iZUgOw)xzWWZ1FM<+0l-C>l=E_DIq18EVs;(^h&M7Wd^(i%isOqA zrqtVy?gj=L`EGm?I=)e_FZRzl0DXV8T>BuvE!3gP3dktSe`Vl!Q!4O_!L1L4%67R3 zOEm#K&%y=ag#ReH11Xyfy6tcZso+>~L>UfkdTpFZn_wGQH=zK ze2E_i3@%okt1+oPWp@wrBDDTHpM?7Onz#ZL5P#8e-@3m zDL|`id^a)!>5^`JgwVMEWA%m{m+|(oe3~% zi+Jgi*lPW+Q(bwg;a5-u?(&m)pDgI_>~82_IDVs9+yfdrmD3|2Ov?(|D^79-LKC}X ziy5^bzkL^z3TUlfct6(={f|NlY1e7Sm)6zO9)f*8A@>pX$Lad(vPsWcTShyYcIiu# zf1A-UcmclpMRZQFQ>&Bih=2*dQ4ZX!+RPNVO>rr>`~-1Ya$3Ukq~zVGNvKa{n$d0^ z)m%C5D*oi8i*2dU20w8nLvOmVS;aHndz97C@JRcJ5lXgjsXlxzmkR(Jw(Phw)eeeb z+)`D-Q()ZcwfkRv&yLU-54l>K`mdPs#HnBh9n}o1%>96e+loz^?6ELG1gTjsGe|_V zW9JG*q6gltk9lGyeJao|htEQ*!A#K_Bg}JvkaVL-%?$XKzG++h;e5%j*0Y|?lbR9L zY#tb-X0hiMv8Z&s$;0# z!#q97!?NXJgQz=2?X0+j=G|*%304`HqEQarnKx6Ah%(cTmLFXLnIno;DL0mi&_-2K z5`i687#0LI_e)D`Z@$xl0!SVcW}kI_ypu8_IBl}qhad+}?`;+MO0U7oOt6z*9?Vz} zjP}KvCy`>iVXlXg+nUZ8XYHX=jf+zAQhTO4uHZWJhE17TBB|6?@a4L^?h2sRwlggqOQu6G-5hm6dz8r8!q{c|!)m2iy_8L=F2) zYsG7^@M!lX(sxvq)*jYhf^V`n2~cnK>K(Mx^K?34-#GC<2NB+XcHn22HRgcvF^qfR z5yMxgSlWiZ=;M9#XCpl1y#15etyA*zRH(dOLB_g;enAKF!sgAbFT7`u39WSm!(>(r zusa2T!~+x1b$}z!XIeR7;|y1b5=+)=M+~cV2y!9>2lo=Kt|CPcWbiU(xX)YtPQ8~~ zO+$4q3uE7TqOZ~K|CJ{A;@*$eg`PPd#?U%)exx!QK1T{HimGnPb1yqp8|6ZAc&h6c z`EK9{*@F5k4yv|w-Pc|rsWGLzK@Ud1?V=eq0ReK}1$Z}9_B{&`++zho;n~TB17;(z z#Qr7%`+~O)Fn-diL0_Gz!{F`2BPGQj&w5WLU{Mux*U9B}TiA)_p`g#87|tM(9x9AL zJ<>XIH(aGBXjEC+aUh^QKcAZxUEL?TS!$^QSm08mJqaw6UKF9e)l z$f&t-xsXyQPP>VyJPksbCWx2D)ks__)V~o4mhZ~P3jK0Su)6e2W9OeqPrK)t&jgwq zT7nGh{5O~u89`v>BIEaMA7JLCTOPb?P0IZAb=CApuhU>Xm1@{9Q;ykyX?>+wYz}Y1+`u z=EXY6H>+9oQa*XJ|Lh&6yNeER%M^fLw)j+&&Y2E=sxPo^UFs^jFHO5sz%fh$`kc{S z`92gMv*Cdr&gnr>NJ@Gx#X5n>ma*{`93-q}p;!nZxrhiZ+$W!oI=Gn-noX(G)JTs<-vdOwoJeFg*WDpKakII(-q7HR-RL$~cMiS5$(t2=77! zAy|^o$W^jj2^C2u5SE_d%)f+{&Wt$qr_YZA-51nCdTz+eXjG~JGDE$kIYG1_t6@}z zaGeRb!m8S6$&k%uee5!VtVpVXUW`S>g%XaY>?m@w;;7BMUZ-tm)sgT;N@a%R8{u+Hx?FS5r=Rl}x{%eK z^Is3cSSN>tG0>$mK}cv}FbtSwDR&oG^DR;Y#)QL^)d6-e4j<>#e=CP{a)MqC`ycC9smfA&tsK0H$f$>dmVSL;lkQPb7>@yL}oE8*c0IJe_(UMK7atA{`?w{2k_X#ntaRk`P5!t6)C z_YQF%X9D|?zgKyMwFS3nBmL$qRF~I`WvvjW!+?*Ry{|D!boQ`1`klomZ=VxXye+@` zN0p1zwuA*iYCZ)ex?_?EG6o?eaIWayD~uA5#OXFL6K&dkbuK#Gq{#(fh)f`+szS^P znXS_0J#_1@b}9EQiD0mI7dnCm`meue9#5R>1spK8blPh|^YJ>}XJDWevkcj8%g#S? zqwbLB%e;|SKA5Q=g*vE<13KbMzv9}9;SK|?J}1^NVm`sLLzF3C(QJgv4sB0Glutia zU}+XF;sJX=ep#=l7Zz_zN!)-p7~*_2Z+B}7^s0+2oI)W|66#mxn zY019NZ`5$QEAQU=DLu$rR?Ear{hdf9DthS5%gVm$xKs&h96QOr6m8`Z;St#hm{UiO${kNPdn?gk(*%v**Mm`@Sn>8rjW2pTEmV5~Jc z?H2iR`~KLzH#7NRW-&_d9i9)6m(+Z{mUl0B^$_Y5m6s9>nmL#1r#upq6zz)@Y01A-erX-wT(e0**`DNf+|p)fWx;8H2cy@c@+SUmeb2kBPr1->#tRI zqFhr&LHp;(LsVef@0%vT{cA%7r;8LWDjl-Qxab*4dlk$zN$lz)wCDCcZRe2jauuGm zxT&7Ap^6a_W}$XVqNqRo_7~ZKkbD0?qp!(;<>b7?Nmhmce&v%M@BVjveU#o`PSLP^vVy%w6f{l?uC>J4Hw8vCki%F zXwfhHWd+2PzJJpH)AP!E-UaLki{BR`MpK4Ny~bndV#7AfB9*(yE#-5ca=EkKCV!Z ze#)jOfMW%6YYRK#->%-OdHzA$6csllfA;@d^)CM)tkeFDu7uYhQQ==h&Uy-4aNsE5 z-QUL)e75W^s!atga#rUi>;0e`q6Wcf_t;>#+Pk^j^9xaS-(L9kHH5^XjuQ8M=u?QZ zqtZJ&OsO7RolB)}HADr+MqyY4{*pY+wJNtqT2Rs}y_EI5po(naBb5W!-$%_95b}s2 z^nFX?&;7nBS_lxmD!(A((~iybs{AxDL5-)Ee)eCnd00BUFV#HzjNzs7&haVzBD~#d zyBU6=2S1UWtW-j>nfV-|K?k)Xx5m!W*FU-6*J7y;<0+;kLawp@T^7=R>dd`0a4~4I zyuRdld-$F|_jtPg&7<1p;p~j*t7P1dx<$iT)l)FK^2w*I@28F#d|6P5#r4^li_K0A zmZXcsW8!)HTqGe2M7@N6(!=BaUUw?=T`JtFf5qkFTd(ieeHPjFO^RaB%RH&H)RS{hq9F7E2uW)nSI zG3=YjGyIi?e6gkDpy@Pt-2*XXp|8H?Vs^=NiutOR8?@A?Gxb!`mboY9r0P|YUT(ni zHQ~-cia$-(tRI}rI3KrT^Xk(3Uqjo+Yuljz>f%)sJEKk&xo67D;l1JH{MN59o$I%r zMO#NnHTlOq?Zbj{*RAJY?{~gFT@87Z+{efNN(6Sby7(s|B-jzuIpdi~J^bhPb71qI zX^We_4KtQpd`;aGqYo3$blq$9cp~fUlPDf)hTJQvFQ8bC^ir|XvEmNOgTn>3E)R|@ zRUZ@WrCSAtA!rl+Ga)lK*l>TlgH#sQ6PEj4h?H|#rp`)vwk#aNJ5Im$U@4NA1C!dX z&ta8{<{JK)z*VNoaV z^s&lf9mH}F7D~m`MXZ^r!!IMP@}i;m;uw+9GuA1)UjE)_0XrRjELktevv>sJXdqXL zKV>RcM`yMB?bNa_4<3bd5oQ^rWAVKPxPe_vzCR2MzM8qq6jJmG_4>&^dpZnVDfsg( zqFob_RRytcZ$}?ZXj{00X8RYp_Ef6cK$W;pRMEWWy-QI6;14P^rFiMdb%8<(j`UPg zMEht|cKv8*v{Jfwr_|85%f7e_bwZDj95K(bP$9&S^#g5GU$x;QzMQ2e>c~*IiAF*| z1@61sYJV#tkCj#~ba+zB&p%Sj^g%e|Rm`9{UEdU)i+HB1K{exjz;_OFMP|d{eC@VKdxy2QQFD$+uKNm(r z^Ru*!eg=OQ*ibI+nz_#c%7t5-{P|L>ugZFKt}`_W?=lzd_dbwug=MX`T-$AxZ837u zlIz1+#syXrLfRZH`Y2=6sW7H`6G2Uh)+P;M?KFaxFD{O@R*?xp0+^U3z>WmF_9>l0 zRy_&tbYZYtMlBU|AOUKC3QAirMa z1{|?VonahDPBs542B80{aL4e%A2Po-EuBk!`ENvVPds@v}h>3F&>MijFSv@Bt75!^`p1I0ieHXo;L`lqiHpSPE6=B!j z+IEiMTq#tcPvr_U8VRJ_#oMEZ5{YSp1j8B5soN0>19(FK$B>J~gD{SOh4-ag=?qbD z#JhdR=){PTg}0)P!$Q}Wr^$f{%U#iV0FqFixRTJf+JRT&)i-grzdG`0BcJj-M5!6H z9xg@80;#xQN6-=A<8Y3!B8acjQOZjk4@KQdv*ECtCsfG-G*!T1bc{G3imUogmB>)= zgDF?DO`?5=V|^x$S?0fZ4#N8oFntH)qYBQdB+YGU&ntFwR?j$FbycvO$r&&Cq2sT< z%Qd4*b~LW5q-z{b>n&K}Pum2o+m>At2@J|t_EtDBn`aB~xZv0|}yyq&3>-0EMVxLS~o`-}) z`=kf5S5ueLFRfk3wi9rF?9C~zJ{G3sK^bQ(hJh>6QKV{J2`m zM;2-gNI=(TKdSy48jQHj=iFa?9DaAGdC6;eOJ~9}oVW>g?oVNJoG91)sGa4jqyS8& zxQS|s@vwC~F3zM)&$S4y2w#o#*sIjLT>%9d<*YK4#FB$g*7R6 zLyKdUwoodrn&}RiinHxSj>f0o37bBzXu)BVu zl4Gosb^&T(IslAItVB4(4#6-!vj;a9>$*KO^n7)iv=T=24AoWK0pB}_ zyS?eJzS+uij8a_p8ki6O-urtqJ9B#+g>Ne)uU)* zNnGy8k9oPJd3((UwugcxX)4lO^rZz|YS1DMgGJSc(kSVaI7qT@o)SVKIvL4-^vV4C@8?-}(LN^c1eqqo&i6E!<44JNa}s?re#MFg zQ&%pVicRB&Ch=4uM(EZO51JWkK2Bv&STK>!ZY>ty11nU*f(~-wJ({x7xa@&Z#UKh>;&jcH zIMc1cqE$Qs^3Gc4J^Y{yShzY16B`n%K{wVJ5ojM6_jfy7jm`jJ9L3vhuu(PrYJu%S zz1JSZMdctilx-Ftu-=xv7xA5KCIVrSp3HvmTz#LQ4!9~VUKeN?1IS9DnG;hq%%IVi zB_*lUto@c+4F~55{+TIsMl#cQMUwuERhm)yRmebx22XYc2WM2)VSGTruUFOciLW@O zp<_!eo#4O*=Z2*37Tc(R8S*{c@Dfn;$Mnyjg?Cppq@O`?Hy_immBrsj{NuCtI+qep z)n68aEJ9%nTd8TE>+Fd=?0RTB5od{uD_e0g@)*{0Ym5h3e>F#_7u1F^$zo@`Cg(YKX*y`{Ctn}$R`4drKH&;M_(5q( z#Nk|vx5Z1bLOx`Aelj}^zJ^Oz^R*}%`i+uDPYjSRyPSI#5Pu_6-8H(ybtuP|$Im_L zI|=nz%RlXBP!NU~$W2&g-cr8g5}qfkHg1idvLWcwuK!!ICj4DIE__ObzMdZa{EL)r zN2cP8m56m8aV&fsG%xZF?_mIHSBomQ`Eqz$uKr|bh=%JZ;Zy;oBGkdiM`HZMOqI9W zzsZ{CadP|Om$O6iX8}nRx2FCUPU!u^koV8lW7~A7Y}=C~C?@HSvH0;&0TPm-^0wMC zDerc=ZTpYX3BEu1RK~{xRze!b@*jDVQD-5Ob9{pU51Cp9Bd(1HDJ5W)E$>+P`Lt6Edt&hR~n_8=56|EeH zuGpw-Q{QrwPcBbF)&Y(*n-Tkqv<-!RYUbCeF^UvJ+}bfxmgZajO+J$gE8_bPV&_68 zLhl!yMKsmrdp`6`@fNC_i0$PSsOjf<`grwQM>vS0IE7aD)eLQ`f%6vQ5`mRssxML` zDUkH@m^Uca|K#I=`B4iey)rVm|F(1XKTcet_BqdQ&>F5ql{1~pBVSvYG&oB|+7Og)p`Yk=3`@JEMybVPT&ZtJ(Kalq3{TgExo~j zu)4s=U$juwoJ0)F63@v%OGUx{_h!mNPb_5uL`p!iot^W&k7XR|!ZeQljvmcFn;MZoui}F|jaBXCoJ~J8*;8PnurLiwZ2QA@I>BKM)xpxX%dUNxT4N}U~=vf?j4!(e{L;oq{7U690*&4H4=P$@A`c0Ax`qRo3|a#%zk z%vzF;gO6bZ$zy}5V!{mvvT%iG73Wq1N9$(Ek_sHv< z$H~MLOBj`@ag7QW&#kQhQBM%_`y-_9#0U{C!=>r_rD za}HS+=9}Q_tS15Z2n9<(=6WK7YX(0Ob(<0Uv>1Fza1wa#{iD*r@!zk8)GL+Ep8&c> zy$u|BUbGsL;sb>O_q~q@NTZvYoij3(Y-+;mW4f;wY~p-HE_3GCweH*J$(eW>J#aTp zGE~breVw0d&+u22(#l3a3Ly+wSdMlCx4MqQ2)z2^d)m{S9GH$TB@Oh9 zx&61-TCq%a@31U^(KsI#u9^4xYrZVF5Z-54TgY;sZ*7_QT2mP)dwX@L*YH1GTNnx~ z)$4lUQkaLPm1WRGsZ-Vw#^De~0etEH0YmtYMh=!e96Z8oxuA>YMa_+Xg8`nAwShMy z6BXJPdMR|Z7pHrBXqe{h^mUUeFeQ^KMJ{{mGM#A*h ze!0{g1{v)ua(zGfN}NDEO+;dN4AQ6Zm&e=n zCj4DmVAC>~x5%*1zidfQ-PhJ{T+aX9v^+PG-)c*xv9!`4}v^sRIwQ9VXuBtkT|L&I57=AL=z-nDZdFokO-(mmU{dY3cXv-wWiCr8R$>s23v> z;t2~n)RmmKk0PUAvByVw{JD1SdH*8dUqdt{Hi8a6S zf2xvDuJ_NFS^0_;am3-feb!^?4N}pHPXUxx~}FCVYsTuz&Ix8QOeOE!E+txQqzq;fj7aQtSzj_>9~R-!Y0` zgdf7oWJyo)<*8~e7@O0c#uCN6!VB^2-_FN@PH+VkV3~$EJuJR!|2t&eNiL54o|vXA zPfD&TAQuYOvwfi5%Wx6RzH$#18UeSV`ylk^T((d8TAhh_Q4_|aCEPBv;_D=kCl}QE zXs2;9|3zqM@a^^KmltP3JqQqE-|YBTKaWp9C6M8O>|Oq+|JWh;VzMZ6!&Y;!#ab?T z=;7C4aayjpXmaMiN+gfuf7S@eDKPb2!L&va?VRhN7n^%7Q}0Q z@)Q*@R`z*C)(98K7maIN(y&QlPM7(HPl-C}8 zul>n>MuJu)J|S|&&y{LhWpSpYFTQpVuZfw%b9hJZ!-_2EjM=76ywWnVCLx^onv7zK5TUhcl0NF5>FfKE8=A@*v8$Joo>Ie%K&?Ba7JEXQ< z?raR?xz2~fKLSl+{|=*;)(rFWmU4A@!cW`5D@Cvo<|pgrK^-*c>ciWEx}@v5|q z@e|oKzzIkc?x1KZ&$TXW`wxIX9f9bu-RsO%=P!U8_at~XGGC=xW-$55A$u{2M%3pr z?^J!ndA~HscD~|etZ~^jf@4&71DO7O3I*2BDrX&wGs)jnRB!kes}Xbjh}npYV|Yz7 z9ANX19>a%`KC1j&=ks;UuPp_%7>lL#y}$b(q2ux+6A|Nbu4+d#?UOFpGKoVYM`nNH z^zf?Jktp0+a1dZtGOrFS}iP*Uf08m<`1>7=v>MiEm~fbP#02c7)xoAVxf zTno~j^N*`f#(q*Jf7Jb$?+u}dzjX>B1o77@|e?}~zFQu-;pWY3wk zM(!|2-dXanQ1W<+Zs-sxvo%c}(XH}i$WGJrod0Gwh>P|4!`NmbLVNn+Euo4@Djd1L zOmk)OQlc6|3iF`lB&W^^{R#SP)(&=04kT?NSOC-jvEfhlCtneVEF5MvIxuwtJH`#v zBkp#$7?rxmCOpq+5}|6iF1Kr$YXj3V7U#DR?-Grk=Ln2c=p#}pQCN!7UurK0FtkN@ zMRQ?X(63Jp^J?x)dxSw;dz6$9R@fdejPJr>*n4iq{1jkxPt#Sf-c%1rqkX>4s{K26 z=wAJl=-ct=f#`#+;3C?K4Vt-_eD*5_iGA3fbc;DMkhcl;Y?#RTSMprwN;K0m6>dn&3Ec>dXne1R%Up(51FPW$A9Rp9a1PN)^q5 z`Jk%%kWjRJg_cDTl_hYkL$xr{Sa2G4szfG^rbJ@8^Lm4cx1fcTIKl&Tc;szQ{xLdY zsW$GrE|9(~K|1bIuSZ-8FpQ7FVU03@p+uDs>WXd<$RkZ4@m<;&panLOU{`IrZ^vXg zg8t*FI`3C8J7D+5>%M+}(CPg2pL9C<7~C*Iawg}uIyn=L?Y9xv|Gm@m%{zlV!=~p_ z;yhEZok=9Ok}D1MY=*;xL)^Z^E8>6Po}wg_viz*;HnMF>@k#_S#5(e13c|DsJd(7o z+>OG6aD}NK&ETKZcR|2bCy@Z3J{mE1UpW7fG(Uw$b`tR8Qj~ zPZ4p;Lx!9SL+GciE}U&>#v3M>abg4KJ2yWhDa)JWBfl%XCvjWJ%i_zDAEbX;LD}pnKzo%?XYxXQy$>DgOJtn>lX(Sx;3%ENlq*4WeHtxKDa{qIUkMlI z0cI+dMn+~*yd030z?RrYJ{Z|s9|bZ_aHgbye`5U{J}e{PkQy3dQ7Cf;JAXjaUHlSr zQaSo_EMS>VD|Y2oqBIaI>7q>~pDuJ@RjjraAO`(!;lX~c&=%E{Fi6hYipeWMkm(}M zi$jTcbys|-&GEfY#(K*~miP(Np+|DzTEbefaJXg=OSlK!UPH|cn+2L^2>m`3wFz~9 zDyDq@N?Bg>Sac@IFYt2b%a|$~;Y^H4lVI}_Zr>je#{17Ou{gWeUL%iXT0Q>1>OD)X$2&e z6Fmkjc(h`WGnb12dyi?Oh?20-W$`t@=j?;a;(r{YeP8>(vSo}RB|-8LsEzO; zP8`T`w~+>lV!6F>>QK#koG+u6uP5m{Z%7h_?KgkPzlulxsFN4~r9}$qYS0ETTye|t z3?-o&UJ4qIIjA{fe36pxYu0|?O>5P4mZRaYBie*KP;HtvVylJ!T;9#6huSDRl|#LC z5^N|2bPdcicby0}2jtkJ4JJRhC77F@><*)~7_j&}RwTc8v^ma!)Hs*C?AaE!!QgLr z@$LP{cnd&~;JTL0r)Ot_MBycH*g{F{2aj*ZnWQaB%ganUoa(ZEpGb2RNlW3}WIwF4 zR6wyms;z(wj-d!~Jnc`bX-9L`l*6YA#Qe6zy7_=SrUJJ=83;y3@qSO@=&!BpA&k=IYb{A&&yXavzMHu-QA+>GrB&-)Q zhPxMQD}e4383yvOm-AOAJWaW=Yvu<%|8)uVI@Pgk-11$LoidePqb!IEee z7srv@^-@NLAP@hqa$J6Z&zRLag#$S|ACiE&Dkkp1IgVsm+mnTWy?%9*M(0#g-_?6J zJS>&{@|#I>K;!HW$&1p99JQ*h7J%pgpN3B+r~aThxoX2nL>5xF`*qB*7HYUzGPE9- zzSv|?I^zDBq)aDe@I(;*pMY{V4y8nRH(-V_3!P0)c}5&2h_OZ}peTORsw*xW5_Fp$ zu$-=EG15>VAj&VUu%c8-N{I*HQieXsj}&s5H=`T!Qw{>Db`jcz)WMX6cGU{|DJk8h zG_3b{+W*p$Fbxt7sZqYfrChi08CTsktltEd^8YfDQ=&>j?4Br5X(9uF%{+D4=`Rj3 zPW`>Sr#KCX0)x?apkTajdKhR~3*~OUfif5VP8Hjcip6mhcVaGy)1qFwrzT=;_sl+o zir~R?+e@h9;{<7ajxS~D=jSY-S2N8{etk6S7b-3uw(y%m)@V%*N?dmRX^VpXY+8iEdr;yz|S)KPh=#9gC ztPONexcCCiL-Qh2GmdNekl*5`=onjnQQ}QvDsEfo67k^sC*7q#V})@Ei~-{*(U&D@ zXx}BJMZ%(Ufa_gjy?LNb{$@K&DVM0QxV`yoCBEP^;??HlyX2PjOtYuw_Y&^0kuIMX zAJDEYB+!e_>1>5{&0PK9Gj>~o4<}>zSW7*>Hz)|mlm-eppDl}nX1WEZCqCvG?b@^U z%m_|7@R=KI@qJKIn8klEEn+;>QYKV<-$5a>0u+DDP}~yY(#>JskkrG(B`{+D#$fDc z^{j!$K8cp`0N??=hYr^ae_d9Xb#l<^cVCClLi{)qJAhqh<*3*fZsWxgdjrPQJt0RP6C3B+Q=d*c4W=vC zUy)>hKjVdjDq3ohM_dAK@tX&7$eXfcxtTeiN!|B>C?UK!F-jp@6sorE!sQT%MwVLZ z|D5N;lJXfzwQdB=^63PGA<|URkK{h;5slpI;CTRXiS+DQ!bvq()d~29Ki_z2lDt~~ zIz^Va(Ap&N*G>K9+xztC4%UPLa#wmESxZ5zRDv!_tR8d|f{$3fh zjX$0G^7MF_IwRjB#XgpR>KwVC*AI7VA`sL6JW%OrvgG>8YlCEr5&}Pum-ZS(ODHi3 z<3>(O`UGyZ6nyEp;Rj*G3h&r~8XN|PJvWQH)#|6-SYc8vn8Xd6)o*n|C@ zFjC$$qZAErEwPSF%gp=ddPreGjLqCPr{6?sXc#iQSogoD@{GqZT z>eDZjZJ8HtE%67#6L7?oV0b;2a zPh}#Ag^;5CfwL%miUaQ;afA*N8~$MNKhjuGqTC|>;p4dXDeNyOO*tB_m!dsYHB`qz zo!^Vb8E-mU`7Nn1WUCq|(_B#WTD*ffBVQ zq&$)~sK@w1E;BHV$__caceo^f-jVl{Rh}XSA$t)gOZS3~c2xd0P;%(e*g3!#?7yQE zwlL1VA1BNxj0jHfN60fS3=sE0?*&bXtfV;Ch6G6 zB!u-PY~4@Kr47TtS#=nE09jm?SsXb`RYi_0rrK|7qJn95i!}QxHAmK~{mE+zTSC{l zFn`MC`H`Pz@mgFUBhcy6kA%Z~p?liK5pYg{b57!DvNU$ENdJElP}}dlcs~qW9TW3v z-oA7CezGCdkxNViGEwC? z(|Jak=sc_C*v~FM=4i0AK`=BonrFN5Kd7b#5HpXp`z}Q3$Fg#hLqt?cCLVX-S+uJXVA)>74TTf8?~i%{0WGJ%L!X?7+Per&Fh<98Yby`w%# zH4tsdSL{Hu*Qz-V#Z8~rlSF}kvaL0b{`X?IdaQKE){4EzH)C+X<-!j$O^0%8+9@$x z-ouZ-Ltx36q`vpC_I`67>BRlL3oV&1l1;>k4l6VHd-5*G6hf}bmfD%)khcCEmVb?t zoAl+`dE{w0HurQfWKmJ)jDFC60kzz?V>RG~)#1vh4ea@~Av2oC$%L`8tvK;dc1uLy zH=Jm%JPvZ@DpAX5)MUBQ{`Jt%Y$oe-=V2H$O)@Rzp@EJ)v0!gvfh^J9S8M^iACtV& zM4H5g9Odm#iEhK~d9nGuWF1iq0AJ0=>Ep*|MLrXn4}Uy3 zy7zUzn^Ip4*kDEo+EwPu-1VasY^cCX#jAGroPtR(m1imKtgw}rT`{BT(w1lzU|cSu zY#m>T-RDV78x`G-r+ZZ+>!IAwS!>0|uq@)Vx9!!H-ggfFgj4xPh_8eOY7v z8`9DJFx5{BEjC`rAKoyV*aT5TVOsSk>y9(ckPZHx>Y?asuWqR@5q29Jro4B=Qd{k@ zX$sAedUEIX!00%=hT&gzuN<^WALMx-F$S#n8*(cHJZmqa9u(z8eLOkzB8f5IyYuVa z=?F^I2NnHmUQHUs1^^C4gEp-%UfvDzDoxbPJQ0%q%%~J0L_OyeSoD>vr5_ zXUz_BYUyO4;2Z$Zc}Cl#s#i7H6KZnqyB!F$RR$sSud03z?o4D z>#9p?%?IaWwBR>qf}2g0Eal(2P@?rq*GrGXuxZfJ96!}o8d*}B1j?f#aHRgGOguNL z)9%O@8~Icr0=7xJJR%j|r$WDfsqncID66|+-OmqXO4yX6nq{MeZfbjv4_=a6opjhG zvgtwxKEYW#(f5^paeAyC3<*x76VYNw@;znhloU0^^A22GgAALKf4^&6-!Kh!V2IZ7 zIwKGd_wx}0VT$Uu%j@!;ToI{7PT{snL<(-Mgz$E6(9IXic6zB8lg!*}kRgcD=SG!- zke7P^DgY`|I0sW0sbfQBry_fl;Gv}PkZ=tJ4QZnm`_@PqX@_A-cV*l2hYzVnA^jR!Qov% zgvoUgmSu>uPWZOx9%qnM3dQ6B)1Dwn--zVmFmD07QfF@CtzU@CM4dsIT1!2*QeKLB z{}3?XR6J8i@k92dQe*gx#xr$v;29rM-t<>JdxEb3VC7&r1<>5{cLl@1UFP3hy-9T| z*cfQ|NRT<=QPk-fjCgOtXk2fY%WJ#lOY5Y8x#QK@{`$4o zv~y1ovw?!oZj#{|>f-SmK30ga=m#FdT^C3kF$`Z)mb1;4ec9Zr;iFG3nLQN41@L(Y zUspa^eo~lWPA3Z^!!@TJVt$qwr*VUNy+ld_w@YM4YS>=)n6VFPGTnN%H&z&v1a+ny zi-oi8;p0l;Ju=qV)h?@dUi0llr)e1_qEEHzbT2Q_>P2eK_t7~j@J>v`%}0houZgDZ z2H1LnpNi~~@x|7ccn#3m+Wk0nvaVd?U;LfQO05VD72ecisny~AKGwsV}2IFyH;xE0t z?`&^2@E|S(G(VqeeYiGnEF$Y~3+#(z z&k^e4k74JI-KA66lnlJFdpzJ8{_@{pL0$e+{;BqIC+MR0o5ic&6++(94#0bCgmqNZ(N@@e zP1RuaK7PO51zu_}J+U(q0id^!-1()S;;T#RQ$dNhFlnJLl}dT~R3PCB#!|GizldUO z!&kh9h5MQ{X=2w^s@Oh%0su^d(}n&W&_TC{_OE-Ie?W5?07`Y>zXYj5bXor+jW)(v z1rcN>GZ7IY!w_;REs2*QA9h^rD?XrYVyE%g-kcI};SfC5;#I}jKOd!qu3iWg(ic)j zb{jo8SQBS6-vnZWB1sub^()$0=ibHO%NM7|(Sq#gETh$+SL#K2Qon#}`LNZ^0c}@# zN+V++z3QDo&=wFe@MAY~rtldK;1g7shr zPAO&;seBd!n2d$4~A6G=X5ZeH|nv8?V4SHSJ12+ovg}%Mz<>Lo8;@ORVtj=ek{k;g<=StyN&faH*R?fUFC9$0 zuB5rFoFmtO{F3X*YitcsuEc~J9nI0A6!D2O!5FTcF^@C;q;elu#3Mx;oM}f6jOG=I zGm%r+fjuZ+Svc7d;?t`ivR~xi5zx$|Hv;fy-{rQ)&T{)xsp3V38K2yj zoU0EcCiHGF=8dQ0P%sn>GunNeBEiLkVONQHYIv#VMX)0WuA2-2$k`7iD`c(ot&zq8Ul^qb0R^q&=dXg;4AUVH^7BN@ z1pH?Croo-`c7rYRF?pBiZke0EzP)8UTJL@I7cHulC6QVs=&#NQOu$Xraq&hHSnPlp zssBqK#DF$cQQG3bPdsJG-<03FJXCpOnX%OQmNK)INOFCP-MN*@ACqObHr&0<&&~yq*O>LWoOA!0;Oq# z{Z@r>3Z$Uom6cYs;n<}&bAaJ;3y+DodW$<9MrGA2g?|yG`dBz+%ltMU zMDerqet1SL_Scv3u!zzn`S5Oh-f~i6$obITF0Clnx!`h@)e3p7m%C zvbj$K-$)D8Z;$O{7d#hiob>8rc47&{D)v3hGJhFMFBjO%2ZIRe8xp8^E3k+D7^wpO z8&2`3HQuZX_tW;@>K9oSrb-M=3TGd(6`{O^oj}^>;8BzUqbf?uppBwJg^Ds0beq<1 z>bk6U__*x_vr-MfG{d3XmKZ2I?)U28+X>LQI+kKt*>!!!tjTW?G{6YjK!%k!3hX_v z8LA5QKfb6YrXblnAL1Ni-iv|v38-o++En#j{s%*0>cVlO*+^NIO$I_bH`9q$3M>CM zTX*96$*lG!if$AJ)bhcE6W=_;8Rs(=w*FiD6exsgByXo=Km?^TN^Nj%pBv-J{WL73 z2jxa)>c#o&UEn(Y7%|s_mPM_-oB+-r2^1>sq+b7!5pf!gL|*?u7T`EG@frS}mL~$w zc?7a;D`-km7GETD2sE?_0kb~FCLhr+-Zb$ut3SL6l#Nv`Op9wr56#qcQnYO(P1JB2 zzvEhTWsf7)rrJH9>Ki(0`a)7kyO;y?lO=I;e*2sTVY9`m8g zGNo@}H3`VBaug35`PN5~T zMl)QO!MYy1S^&|O_ohLNR92p|+z9M}c0k!k`2#&{>Kzdo7!-*~oPdf4SBb&A;R!T8 z(lUDLrzG4XLnr~?GVl&uE3o4GCXbAhBORktQ6#*8kv)*xE2-a?snTN7s;^5af0n`@ zl;m;^<4UOKFMI>^4Guv4a6x zmi}8=HmoPJvz7*p&)>sYSUX-y4F?a#&eNbp#H?z`*IU3OJ+ADyY}x|9pA&08yi%01 zhA2G`Z$|JYs^t=FdVoY|CG$2!T}=)RL)tmKte#;&0Lh0d9W1iHfRi* z#d3Vl*a@LiKbIC0<4YD67faJHvu>l1+8L4VxZ8Y zTrA_Z$A^8eDhS!mT9|r@zx*Wzm9oRLXv9$1|5Y8v8MrCHA`1u{3T(NKOiS8vw6Iyj8x}gCbAPezBh&6Rs3}_9xFHN{;fU37r&uHD|sy zpZ9*=91*13Ot&5%jAFv)!zYfR5B5srn4?O?wl330WOXQT>nf1PH2!}t07?Qb-gLrF z3Y>&wP;_-!y%^(LAQF%X27im};Y2q$Uv+*}I=Ci+1un6Co8rn2A~2z%TvndpPTHJA z-Cl788rK95hZrF=AQF#4SYlG@0S=JVa@J)h2H1Fu-#-puDQuuQ#h$GufAzB*)zx?y zdx7}kK0h3agJ+**b^=hLM?B8G7W_AI?noln-Dc7+ehJZLD9AAn+@jUNeFm{Qnh-Eh z#vzV6(uJvU!Iu10-#)W1nRK>#xU!lg;G}wXXi&#yw|^uU0V_r8Eo>v zT%gE!&osxNLahd^|L%hS*bw-NCVlT|)vfs~-xR-0Qx9Vql8r;dcc}tdVep4G^1J7G zL9jiLjas9mo2IH%2>a-3IoP#H`ZTAmaFmdoisk?&8uXU#;S%Ld{04`hrSL_Q<+s=L zsOK|rp2Yy)r=|Ydlx9Jtq!}=5esasD1&I>WliuP4$YPEC-Uhzje}7czI%UTOvd$Y& z-;u*e5?-gtvV{uy-f3dLKiJ*Q_Z}6dwF+!tRA@NRg32xc4JqzF9Vw!PaO*Un>fwOA{jBxVA#507I{0aQ6$v2jAnh^*PRBC`U{i`waiut+pKxg69KuleaUO|iQg zY%r1YlTquQB z9fb99QK%FJ-NAf!*(JyApk`33|8D$t>@2X^*mCRTJF_5{a3tF)chu={bY>QU9R1bG@C3`ae?GFHetkm^~ea-wg^#>xi}YvzIhuhaiAO<2#@uO9#rqdAp~To2ZV$F%q$7#@?S$mOl7j&^JUq zpf`)uoVPDit9E0Gqv$C0Q?Cy(w|C^tfff%!^bC9g~; zR1sFiGdVDji%U159nK-J9-%;&)gE>)T7;0onb|MzZP@r^VSoEiiP z#n`EGcJm12$3x$Fb>Dj!7YpYS@Oq;?=R2VgA04%Ax4&VGavOxuX4JnZOIW5>w(cbT zA#g4@_v!z2@Dd?7ILWQd~xVqP8PXNQmo%Yk>1&c`jEq((RY! zO%7@aGf3h%nO<*}jJ}C|;(a(G`IUYwqOZrI4s>~UM)3wbU|ZE4a1{*H!pHP}oA;79 z1E+0AfH_FPQVM)Nxg5ZYHo`VV3ddar2`Ll?7ODYeg-emZsP`s0$PSr?>KQqa&oDKqm$N`O8iCA4MDdm$V?p@Nvhe2)>3 zN*FGP0Oh^RqRs}K($gt=Uk?c@DxD**kEbmj5^p25L91yLvtY3jLnt2skq+DwTb|vLi(AS`U5WYg^Ugi@V=l(K8UJ^21f{3jb1(*Q#XGtfN-b zvgpej;BiWrCxl*vew8NFl=yjShOIA`);CFeFo3{>E%EcoEUhK9E*7a}e4wZq%P|@u z!cIa=5?8$;oKEaOw*C}a&3jP~9Lzs=a_st>xxw7_`0a+DtB8vg$^ShcZlsXyL$m11 z?xRG}Dcb6(_joHIzVb)UOI1{vC;!g!%CYxW0Cq^fhVvu^Pg1K=dIA=jT#bxIrB1Bp zt3W^Q0W>g||Eul0Cjy5YDk9Gkb?b*0E=@vdJc)keTh+LiS#fz4s^~vPoIl zTiH7$e%J9l-{1H9&+pIQ^GB~ox$kqG`?{~sdcQyK4@OCrCZgyb7D`V8H+#x9F1$Dh z^dWr~HH!<-6Jy~zNZEgrcByd|VrAs4A}jSKLW3B8o^6TgXO`6;1v;PA1R_M*+6ODY zFG(FD68qk{Io3}lVQ*m^EP5sJZ7lowY&m(sDY`W@!BYK%UwOu} zR66SpH=d#ftebcQYhJTx-es9- zX_u3ZDSrWgcWSp_TNdhEsRz^rlu|9dvU&^-FtaE|4asQXq^q1MrGtQ`71wM=bqDlo zB$VeRA(ul4rT?X|V+T0!JeSRPl1aN!9fn*HanO zO_uM%wS9tRCt!%KqmCLxR!)Z0HpkDq46Gs+>hqnW`v}w$w}#S{**C!Y#&YsMvtdObxv=t5OdXPBH4ZXzimC_#_@nccNg`la z#Iz*955bp$ayspM+4zB4Q$X#av$qBg*^9G{x|~5CGg}X2TBe84FLqTCscJ=;eH;c| zk5zRw_2CGe3NoCS+mxwVVeZP#IAf-I;1$f$kVt6_J!L3-9j+buTTM5xaTr?@=Jk8Q z3+*`GBPO@lv2dg@7>K2zj7u5`#7TKYieg@*T$!ToZV^yvl0-+vcM4(o{A!gZ?`Ibx z*vb}ZFceZ(-YRC%v(wxrA0z8lsG-4c^-zX;SiK)-FkcmCXia zFye=zvtX{bH3&L%*4_pY_r3X=J$vyNet=9cgocB7?!8z< z3Rv|gxFvVLz~nV;``8pD#Ts*TTG#3{H|mV8Jv%=vA#En-Bv??6t)U1H!Z=8xpXt zys6J|%qoLCt=nVkhby0B?#qM{y3WYIrm~Wcp`EjCzf_0(3yy?nk^~c3(qeP9tbSB9eAj^^fsel?tpPjwc)lUqcK{k?)b`T^BVyENmk_(z zujm={`_2EH%@?_frL)nYp5%J-S)lp1^L%Yo!7}9)kxqGrjgA#DA8TdxCeXZoUjY$@ zp4(x*d*>V3yf3E@4eA53?$dyHEWb-BMiW9B@ZiozZyddvYNL1$Uo^@kd{8w5g0%1k zHb&LDo;adr7N(}2;6?f>%}o5~;T~!ru2!BFQqD=(AQ(P4nA`K6R6luFB%8j%&=o-# zfRmzKN=3C%DElJCIWU$^0cDQ^n0gtCw|+KVxxb`~C{CbVr&aIyDMF+==5s^~4Ws>CXA%L%IV9wHBU7gB+|TS?n*$lIuP zZn7-K&-mXjGHIsjfKmLd;@Rbnw(OMCP}Dm#d&S&_%0nFnIHQO|4y8^i+u(b2N8UN! zi^b9yEMi4*Hp2t8YX=hQgOx2mIYI?eR?20THs@L!Z}D4(X~iCSEOw382MSYjfHr4yg(({`BLg0iqo&bz3itdUvCX~ zhD$VeJjvq@hsHm)XsRx;llt>jDvhBc*$9Y-nN>72Xd-<#6|Nu4bnt zBd9+cLtcs^8^t`}j(>#?=#3#}!xBRco<_$+H%K%IWR8PfVTN{fEmA}y_FC{<36jANK}cLPf%>$ zz0tgp#Yypf3MdWrZ_Ph3*VPzheVArR>-)>B@c0dWV8H5>Ma(_y8#iAl+ik;M7BZ^i zq8&7LuNMrg+twE%dpEZeUcJ41?~NEq690nqx39z;q}rd+%bZ$(m)iZAVceyn1E z*fyyCzBKKeK;tZVW2fWi6R5U_WLoB8X|!5Xm<>cO(dDBgYAW_90Jp$o$=2!DQS{<@ zjx7HfbHBo@Uqn+3(?NG6MW}?A4$dkdEV?u3wDFpuHp2HC88>2rm-1$Q#voNV=-Z6+ z;J?(Jf_^=PV3%R&v9!(@tbjU0P2`Fiwn%jX=(&B#%RQlJ?pob;^5g4gbg_)*rLZj3 z#WAH^&Nu>z!6X>QVFVn}xg7hF%uTo3U+yajQ}_(XfMG=(-}bX3d0Kii+`d1h=?@5R zwHDaH*Kzv}rsKNYE0im*isGcXInu514HfC@x!iQ6+p^c#{QkO;UxE*oz{-zq(lrSj_hBrhm zZg90V-3@7}j(Fla?PVOq60sEZl40Cp_3yVui}x6kXo)M81|0-Xc%&1dcd>BGetQHS zYU?y07Wq9lDt%8lS#60ALr0Y_arL@`ah)rpe0-zBS5viJI_0GOp{3YhNZKGjUM`}**{E7|-Q2R&QqF%hLPtYam!BV~!?##bPW+~bf2y1jl( zR%W*wPJ&7Y<7gZnl!lfZ#~RYTA~l6g!vlNKBvSY=U57BS37ncC_QDKeJg=&(QxHK; zzRMCK$AK;(x1NSd7f}NjNe{u)P=!;$DfiP%4`ktQN{pb4{OxkR>_&Pzdcu=E)X%ru zn9Flga+(+v14sge5;J8F@VfG$Gu~_11(=msD$oyy?^%4aloVKuNY|KNYdos55%MbA z-)lRH)*{uAu)SYk4+Q|1H4vSMe(;mc9kH&4Cs3hzJ3z^RT~}>fxJ_F*0{IqhD}n=| zhXseZaPvEnWeV{!Bnif?bVg6!lB4cU@-mjo(Sy=k3P@sAA5yBIDd=(G2k5h{(#8fR z4A^lALtnG;YVzx~vD)8By=8Y}4Rv{oQ$T^6`$d&I*V8o zUy}*YXmg}k$~`6m%f17*Rl;E+h`m$^YfVwd%`TD+z{Q~gMYU9ZtBCfQ^7xC!A)y)J zEoPd#)fM_&a-e0IniNwm=LMJ$&rc%S$$SIhJO%BB#(6vxrnQ1phOegVQ$JTSD%R~x zhTDC5CfyXm#>%g6Y(h%%WK{lRk15Jr$5L9v2h4!ZNDj(i;47Aw!1cyiKqV5gY;#8d z3~kASEb@W3Tz&_D8-Csd$Eq>Q6Qq!{zbH@q=4fLuQsVs5gdkh#3m5N7QxrT{{z{SN z=I4|lWrNhWrGW#2UNEuZ8>#1-WPZ|gR{ zj4gQ`z?EvRF8{Q;{slf3yh_|yXR|Ibx!=i@@;jP#@?GeW(x~~xIkIjDgDfd2yCJnJ z4=J67YQ8<6N{MQ?dy`2&EVstP*Q26L=dx(y+3Aj69V{7>qz&mIQIhM;v=nIbNmtc- zq;IO)!Z4I6j*thnX8y>46IndUY8;VmVY&mn7U79^b~n zj`bRu6N?9R+}!iod$o?v_mp1mwO;{^vPAjVea;)m(?5>ZA|Y$&o=CSjSKY>^tG#c) z1H60bXsmnvZOE{g-s&0_$(pVOxs!K)(p7_QbawV%vN1N&b7ZK95sz!DLV0DL2Bw^$ zU?&l~kF6P%No&N+uts8AWqZji7FS{uMR*a2MDv6?$X!agvtiwn&f&v@PDqt0GI>Q)-ye3(FzwG5i&NdTh?0w? zAd?GL6N(7adWQx323k917*pba7iPoqlt+@1l+7%&A0$)SEO$Ove*h(T1LsLv7RlX1 z)v&QJjxv6eJ}y3fuMtA$u8#QuzWJ0QZ1q)K^HCtoLB8nFER<%wqzw@vcW%30hZvzg zD)YxCHO=xCPfa@tRHjz%zrolAB;JNZXltf0IbB?7Ru%tI+XvRcQl6B@FjBoFD&%?wj16`6W1NKBW3?=?>D%DYtWkUkO@k=L zZPNFDp92u^<*wV-%@mX{pKTnI-ZOL4PCF?jGiBQ4yh5#|=9G`nMmvzr^auHj{f$LQ zf{wCD1j6sNv|QUR=q%k5lVucS%2YVx1YdoN(SNir^b!%wL^&+iE-OhY#}psG04g*p zaeKVYtHd@UHj=O!V0E6b>?wUaN%IuVqF)aS*qqcDl(n@#cIm*T{2nd54AteQdPLce zo9k7s`eAJL%f=x8nLIg;tT;W51LE(KI|$pSIH)SlaMqr@(41lWGPKSQr?Dbd5>xD- z*Zwoq&uCtPicC6s0O-P;qjAY2zNVh>o#$tt3GF|&I03HW=N<(<1O{<)kKLw@87 z9!R?#)X!{kWJah;_8=z(1I1tuI#7mQ-w*q9CkphYe6m4VCd8BllN^S;O8ZlMgJ?n- zvx7cIg#M|4Mob?G7J(M>=U@ImIV<<30Jr^Sq8Xc%0{esP!);6k8yuX7Rgc+)CUuzW zN3SqBXFy$E>u0jJ@x>IQGL!A5VTtOr3#YIF!9c}#il&?twA|)j5DK`t%qO+!Ep}$f zHL`;p`2a`i1@m3T8u8GQB%$0ieBgHwvbT<_l)m)7LNXjkde~IAMA|e^S%kNS-|!1a zmK?#ia!BRk;mx(3rR!UlB~<)jtGu(^&4I zh2RzYV~7dl5YdWF)k{@*J7&2c75VOjB&9rMZ`}|ec53+cE6LKM#91SgQ}O1-&DEyg zKbq9F19iAco`N#Rz1>QEuKOL&emn=^i8=&=SwerZ`K9aP_hh?U=e?{=9^)3_J(x7D zwD4a|BVmg1PU!i;k*cf`B1lDmodtR(_GhcIeb+P(#ZA7`CWd|1XxT@sYm2iMRE;%) zD_x`M0Ph7|o4CZ`0ULa3`eU9*yRRl*6WdThRm|{LQezVGu$ivRnLWt;S#Xbegt52hppXe=jawY6s z=A*qIh^~MDPbF()B?23ciz>uoZk~hy}EU)X`^?T=TN78}>V87ZVe%U^zv&SRS^1zq;ts zK!VZQHwI;Rr~>W0$i6KunV~`&pMTB_^+A9l4;%D1)Qf*o@qMswn;50r>OA5nVt>nr zPQw9X9dLD=dpMlEKN5_Dszy>%JVt&i(i7i4Q9Y5$slp3;l1G6*3q&Z!ZyZ=> z!!k?QwO1Kcw?HA)_Q?K1-Q7V{@nsOO<=-$d#cDnHi>UMnq!rg?cB%TI{o#9eJ7xlx ziRC~xOd8%On?RaC0&^)3mi9lCqI-xV7se+jQQxHVt@g76u2up;3CHrA&Pdb-Hc`Ch z4gzqgZ1r4sW@IbXjUjlY{!w(2^EYW8e9INF`^F~Vb-XFm%il4Eu3Iz^0B%1T-x%`s z<@4tY<6m^$ot-9NGFN)${(|N{Uk<`V{*d)?S<&P!$+(K8={V{h-7U1Y4A7B6lE#Ax zPv3?L5#+;ihmNr)YCfprx5zEGy8V$RF_*9(VDMqQ+8pvd(ce~5aZQ3eXD3po) zt^;Ak3Q^pHf-ZCPIHbnr2NP1<(~~!d|KYaGU?6-Iu2tffMx0ykB%VGv`h>*$Bk|d z(&G48n&x&5cX3r|rUEB1-YUsF_dML`S%hR^k&LAGQm?Rsqg^I~ z)Q^kWh~)u$q#hcaTQu`eP??uPpYRs7DA(h{nAoDO)9Ji(aYWM4?ftN_?Jxp=;Q?Tm z7_)n{og|`M&L@j3Gi@>e{ZmV#mz6#ymXB-K@P`V7&zFIMPXZwyO7Yq$u0J)ZeRU8J zCQHR04JBXQe4@3YC(P4Qe}dj8)CDdnmh?N1YDE9EJZ}5&gDv40sI(`5Y9AT_?cC#= zl)A>QiK4un@4w~jfx<|-oYV!Ot!`&FCLmj3!YebTMmzi0xh=niPG=@;SY*b)rF zg`6E)#E7puX1cw#u(@F(c1NEy)>O4jt$}j&#@}-A`X$o)FRBSo0&jeaYM9yORqs8@ zNItz>5DO2(HbB#h7>oCQei;~Qx0_-Y#kwntcp}yXXoAne=#l3+7h+jN)_Jvqbu9Z|eZ$ zmt-%j+DFdCekN{a5qu(+T$ZQ#U^6F3*(SqDzE3U7u!i9tbLnV88AFecefWuH0o|}G z5Gzcu|CQ33z2|rJhxxZp!6`JuV>z7g4)vIJ%^L)B&&_l(lNyF8LYY#Jgqd#~3CzzZ z?fv4e9IHddh%b;chP+yRA*zY?P}jbsBA)5~jJ2bw*q?C(e{!_^! z6sX7#n#uxS7!P_A5IxK{2`KqKK5h+b6`CiGW6QNJ2~4c#%AJslS;3ks1e;bbkFkfF zTk0VSZBGO6L8+-F&W(+y^t>9K%>Y`A<#ASD4y!5x1Q8RG673~3rLDV55=BujJ7KKC zyu(2LXm9;f-eDXNFbW}{w*F{6nj@7flI_u%Vi8%5OC?|(bxXwAvX$g%->h5gW(XtW zXjxkPynCPiQC6J49tF=waUmJ-fG$brxSg2zDIt z#}J{{?qQPr#zDMuIUTj~yft)`AOaZ-YVn#3{;z+Fj<sye6?M~<~S<@YPxen2y$fOFTn z+2$r*Y4p3E>gc7CE4#apv}qr$Z?75!8k6T5nFN=WN0f(Bax$4ArMHN8Y8z5%E73Pa z8bFvb28OXU4C-t(!e8(i{%))TnRPPYT8Q5dfm2!A^r^j47U#jiYB;nO$@MGDbhA4n zBK}%V`9oqtc*3#0y<<4|F*vt;+k0cKaydT`>O_k1>qdLs6^?TW!>UP7+8ez*P91%$9831zsGiCkKHT?Vc#3H)bOYT zCH8w89lx`$&gm>x8ehNu<9I*7GShTo0KIbjJEjHX8zR-p;pwKaeK!(ILj50;4x(Tr zvoQTEAgAG=7VRFPgvs#Rvy`%7dhe?0oM}z7caYZ^BsidSV2rSJgru1Sb4+1R=`GjD zeR4J_Igz|NA9=$zJv}=Bb1~cK3XD&Vi_#aPccV?=7iw^OwR%(=q?vlSEtJ81I%T)h zw)f$Wa>9+ItsBWgI;{_3%XY@PBiDQ7&!|of$@2aEqvot@_{E+w6K>`4cI`;gA0NZV zoK3Amdygc}^S$i>K0LGil`aBVd&i$ywm2MK)PU9bc1CYJ?xC%F{ZEJD-Z*Xny}VOl z*Nx&{VmYbY<~!}hZ?lp>&Czpr)u|NJ%1azg^?gppRfLr4Em`$nK6bXn?LaVp>LDr& zR*2C;*Aqac7mfu)A9P>^L6P^}Z! z;XBt*Ms;k6AnvDAA!QmFf4vE1_94qi=hs{!^q!gaUkD{CR+&dEH|Xway;FVjnUj}2 zQpu>{ah@tr_8bEIXPUGwt;?Vau(xPak$_MXMOd5@F>vZ&-u?Ug1b_Og+gGqZk1T9T z?_bYlb{ZDhNI6*f+$i4rr$B_Bma@gb7Sy-dUmo3`>;esS9yMY~5744zuQNURF`usl z5A-WmF$3g@-v!VMn}_hpx%e8KAMV4i{UG>Icp&n9ltqH1#B$i3L4cF&?V5k|$E@&I z>E%wmzcwzc^Fhj31M(AvCJbR2@M?)*>668Zsh!rLiJ1U$pc1vH_5=XS!*8G7pr^l9 zGbhp5{)Z!S8!3*Cve9quWB5lc^klL$v^03;UeViVegT_dLDkdjKHC;7-{_B^CGvaKnxP?+wufCjrPz zTw{+;HveEPAUaP~Hm_4PvO5e`UR`l*eZrghsk_SySf5p($HioO!6BII2sAmRgI;f{ z>znVci7Ka_@P>i>a*rT8*LF(8wOsv5=eg5yA~)~ z^L!oLq}W&x7u0&v`0qo_L{N%*y%b?e;+qb}r)Y`&&eizl{)%4Gt4Ry806R2+tv>eK zkv3VtEdlG4%fEjLC0NN60fb8Hbpa?f&w+lM`Q=HaU+}KYsk`-^tM8K^$XnVCs8e?` zrk-p9w(5N_dc|eCm|2aok^oQNB&@_p`)Ii<>d0IDW-i^|O@)w#0qLWSk^64as_wK2 zf}P*oW}OsVfbd;9HjxjKBug0Q8%fUzl+AU0_ zi^h|rrj>GBrh_RjTKFW74yKY1=OEH=Ih-}=E=;ttoMXkh|nyJ zce8xQfA{q|&F{u9e>Cvqa%^X%2}p>4D&I=}=T(r#;Qa$a&!iuR=&?Km z=aCx6p!(aRnj!o}?6CLF`s@4iFP4l99h(bEtK{?-ij>1OHooovTSyP~sQb{$?X-PJFJTA*u5{c{sNJOZtpwg&N0 zJMLr6rhMigI3jt~M(v-P;8Z&#^bAHj8VbHY+90Y!BBH_ZlH0)Wxdb>y#F76?S;@&LQz*q zqe~VC0rZ(x-enpyJZ^H0L-Z9rn+pu9!ndhY&OJeUH?3Yp1)vU>n4Ob0D+A~Dd< zB!pi5?1fd|quD~flpEeZit)SX@_fV=Q4Lh}nimGwWK-Rt%&3g|dlPzZ=R~f{7%2MD zDMlkN5Q}&~r*2KFxXHiN_4*QmonRka7&jEe#%)knWGREy&wOjgU#Et=aTeRMv@Kyz z4@i|m-c4KvPkTig-iI_?~3e?$+}W0uvCNuGFXVDM_E-gv=$gO)>% z1|5C2T9kDZ9k0eeY7k8>pVHlZ3x1sQokN@YCD3>>)bbc?n_c)vK-thWKx->uCqt)e zWY0Z7rSq95{$o*h@b=JE?J%LL&&*i2I4lIsI#E*=&#J%n#3qB>UJE@9Nm+=fdwlz< zU-yINcMu1w0EfuQZQLUG)ygvqV3B3sJi~p@8#vK5MIS^JL)O}5cT$&w`vGA5zH7_2 z=n6ZJvY$3`&mc(Uo`yZ|BK+!r_IK!hVhsAG+3B4?S37XTB)P?M^EW$emlJdD< zQ{S&R2KIS!ONirx8dznIQ8KQp;U9_9-`f-g_JG?}{aNQ#p`OIrZ;b&U>7FD3h7U~* zY~@E@qnSAjP(WT60ZR#aRNsnA?f7{9dFf&O3@#R!kF74 z{D;DG=nBjev_4d_-ewv&+AlEz%7FP<^}p@C-%$XJvs_QeOikACE9St^Oa>8BaYOkg z*$d&%OH0!G2e9W9Gt(nZL&RPil0g-mSVR68OBxLs6#^Lcpww$s&@n7b>-9(I%^Zyd zYc#sS$p!xH~>(l%T&M#2t!jEC||rpn@pxVpp00}%smiPU+zry3R8@LadC!2 zullo)dEpfoT5Woh`zDoO(Zx+tYUrJY0hjMe6kUX0&>K053Awmbn!oGk`4JO0Vf%u9 zXV|{fBymA03ZaBbMjd@udK^zU{ulhFDPokrt>Lpenwt`RC$|3PbIu`b^Y;`Lf~=bw zj47HO64Meotj5QfU%&wxhW`2+@Ave-$b|LzTJo8Dvnvaa5eO(}e`_evSg|!zD}V~` zhxFQTkqi?sUAIXFPyutGdSFjAgwPHr0=|#yVHh$AFs?hN-uftKL*t%{B_hAx9o0>t z<4$i7%eamV%(67J=%?E}XSOOG3i?4Lm!kx)YNqZ9k!oqR@{L7TsMa?mubP{I&m7_? zEi*@BgQsxau&wY>59nsOqbH@+o>x&EyzAju>W^v=mCSJuu64ymG251qTBH924 zD8u(Mh4M^b)L0^cz*qy$pbt5XICJn$tR52=@|NXHEW{-Ro zeM!*{Vgr?}vfAiY->b{NGnp%3)DX`?`iXzt4Bf2hd*)q_Elk+%*aG@g1^Tc1qx|#I z!AnRljs-f|6$cy4h#Wr>stmGd%sd*r1R_Z(mmxo2G8MSGgSPORSYn-?T7BZ(El8?~ zJi;~zsgOu`hh~Wkr z^v1VXygAq6D$tOpnjSw5`}6%Gi4G-h1d5Qmh1_z_K&HRmNpX2xD0xeiBI10F*YC%v zQ${AY$z@Xd+9SW;S{56K7iTW$HUTg`yL9gTYhcdxM#5$sS&aq7y^d|&qwGy3J(*%N zUw+8|=@po85rI@;M0!{i)GdWjr-2xzRHo2#<@J3d4^}^kANlcvU{JF0P$j8N9qGB ztHN2)Wd0O{%-lPGCF2;VT52C6Ve?`I$W&`Q0Q_+kA)XKD*fiNb(D5mV*?ECvzko;4 zr4EED1jEX+fHz1oDF4VGg7~r!fjoha!pnY|729Y+@B)zaq;Sm0!0Pyps||{??b49W ze$}7AZWTbl8&NK}YVD0%2x=mwZM;v{e~rd($;;*RLx0`CBHf@DKN=LU%Ayf|Vfv!+ z&+E_$oh_Hopcvnb(gjOYhs2>fPH){2m%ctraoh{~KgS9pNd%KX95)7ZkQ2g`YqdLS z)|5!H*FYZ0gKrT^=j+kB;!x(@*R$Me0ex@&&Lg`ig!{3P#Ah^BU=JW6Id;&Gr9$n% zIC${rKJjt=9K%^wCEd6F7DdYo3h77JzLiBO{OK9)wOb_wDMSL|I+9aFVwicAmN#(V zkD#yYl)S8+VfmJPMPenDNRsJ&*tceJP`CQ#186B}eZ@q|so3xWd4Ac)3cDlvNP0Tn zoMiXfgd)44aF&QdLb+6TGOJ1QdNzc-E5Hg9!7#B+A+x|$JGn3DU@b|<*!A(}88)s4 z`j8_+9uP^aw$~ckSIhkX+aLDewIdpmz`!!V8R*eu0|yisgJA!Mqe6f#+E^VJCW`7e z*4|c@X=r~aPU1DsYP{;{4w3|m0fN@)1@urzA^0}vE9ePvxRu`Km?HNb&)?y6fQTbt zIQg@pCDSRs~S&!(@E!? zPbhiFzG2!r_mAsaV2|q*fU7x8*(ARXyl!K;Nf29ajTodnftTUd#&3wku$>w@vM&=-BsV-=S#24v>ZbJ`LE?zcH#mL~}?D!}>&x>!c=jm|rH|Bnyw z#uOcTA~bDDQfoh5Gb+>mYZ?Fk*TcG}U!~7#zo@lrTAQ<|=D#5=@JGiTyO*+_`+El< zHxTssee9GDy)U|!pmj0lFac`V3!*V_YM61V;8V@?zrSVB#~8#)C+H^slNr5ibc*=E zA9;@q-rSaH^aXaX`e;hO`*k_XS{r7Aw9a%8{bwP&bD#i6Z9dD;*=5hnEAZ;nUS=~P zbEeBP5CA*V>!*&*YveLw;+7kid~P9sg#P@cYv@cCC7MxhK^Gehp!wJcHY$*^k(PI# zcwYawNspyKz}&!!fhh8kb%wOXpZtc z4H$l>u{}$Y(fJ}HQ?m0vd2WRN-4cH`ihrwC`O>BUtXTW0>n45Q1ub53RS)K-McmBr zTu)sWT{w@fCYef%UwKOkFG<%Je%w!tTbiyRWe-d_m+t*LXL1|iirv;;vEaofMYpry zjrRTyyME8Lu>*h)=^cs$nA)brbZD9nExb*Hjf4(NH_>nNs6O%nvXedHh6z|>97nB9 zq2G9~&-u?Na8z7x81bS}1CU!YF6#EC2|MM90PJcYW^532e=iKQc^(->O3!&i>)mm@g) z1CJX&oRr56`PjN#fFW;&2G7dtXYabHC4i#othMB4!$&gbx6J~5(j~tweFi32_q%Bj z!K}D3P~%_YWMQXwv;KAHVg%+ltX&0{|7sEkC(W$m|so_xVvIIjC-&fyivn{UE4&`nFC_yQjcrM_>2wd@QlH|wXOVnt-+ zqbSW9=G+XA0HLwzT&B0s-xmP>RK(w@A0~{}M}+>EC{G6*p{F8Z9PE&1z(=FOnB7x$ zso7H9%3g(3fTR5YN2SUz1Iw0tD{lLtzewRvMpKpa_rw2@2i(hx!4Y2?u@fGiM*u>qqpR5g8|FLeO>_ zz$|g+AR4o?S4`9gQ)A~cD1q#t*)qQ3=d1D7ppr6N`myy?m zv-f+cpbjUxr_lT4XG?gA@$3lQUjpWk|t8U3N1~td;Ug&_Ab~!_tn3= z26erlkS^gUdDXfYh|d@^{tvK3iUUqd#Ms#HjO)|FhDC^}!S~^O=y}@0-(B~Ra5A5` zzxH?R%K$un>G+m5R_Mhh(e=0BM?XyK-eaPFuN#WMFd+i6nNsLEjz>Xs7ddlpnb_&m zu*V4buY->WBnvS9eUN0@GW3xG$=4t>79!#LQ~PUy3WWO&>)!dF&{k&@?qj|O!N z9o8mNc_GhXE+JKf(;y0t5*U85W%guS5~LHeJe{*lbWGcNbMLOtrv^IKW8*IW&s%T$ z`((?;vE|1*LWTp7{Y=MJJ>NKbk=Q8=!y}-5!$uq&`uAcai7)zrb|WBo0mp>Sq}f%q zwt}v!7CBID8O+>H3bGD1-a*xk_N%{pcLL^|2e^%ET8B}zur~mLBn`kq&lSL=Hm1|R z_68Nb;UpLsSj9@RQrdF#Q~~+7;g=%6t{UC1-r>n;-1aA0hE^SbE zvF%`iI`GsNHOrM;J+sr#^m*lO&&okN>`|eX zDocFL-+Pz!{3#TeSP-Zzl)l9u1O0z(FhLmoBE9_a@0s^H4ZF@*^2s9C`hj5|FeTu^UIXBD?d%Xf7=R8|jYD+sazT zf4rP;_^s@Z5#Wa3gf+H%w6_TZ*Db2#JjEz>pV>QOw#*pWXj<6&vUOrENR>!dV_mB+ zKFEq*#{~>ZZxC?(g}^1?7J`_VOs@?Xz&~C841NdlpO3%(8)TY4Mx1;(9DVV>zkwA- zi@x;VzoCDK#87&x6ZW5+W-In literal 0 HcmV?d00001 diff --git a/docs/modules/mapping/point_cloud_sampling/point_cloud_sampling_main.rst b/docs/modules/mapping/point_cloud_sampling/point_cloud_sampling_main.rst new file mode 100644 index 0000000000..cbb5652f56 --- /dev/null +++ b/docs/modules/mapping/point_cloud_sampling/point_cloud_sampling_main.rst @@ -0,0 +1,70 @@ +.. _point_cloud_sampling: + +Point cloud Sampling +---------------------- + +This sections explains point cloud sampling algorithms in PythonRobotics. + +Point clouds are two-dimensional and three-dimensional based data +acquired by external sensors like LIDAR, cameras, etc. +In general, Point Cloud data is very large in number of data. +So, if you process all the data, computation time might become an issue. + +Point cloud sampling is a technique for solving this computational complexity +issue by extracting only representative point data and thinning the point +cloud data without compromising the performance of processing using the point +cloud data. + +Voxel Point Sampling +~~~~~~~~~~~~~~~~~~~~~~~~ +.. figure:: voxel_point_sampling.png + +Voxel grid sampling is a method of reducing point cloud data by using the +`Voxel grids `_ which is regular grids +in three-dimensional space. + +This method determines which each point is in a grid, and replaces the point +clouds that are in the same Voxel with their average to reduce the number of +points. + +API +===== + +.. autofunction:: Mapping.point_cloud_sampling.point_cloud_sampling.voxel_point_sampling + + +Farthest Point Sampling +~~~~~~~~~~~~~~~~~~~~~~~~~ +.. figure:: farthest_point_sampling.png + +Farthest Point Sampling is a point cloud sampling method by a specified +number of points so that the distance between points is as far from as +possible. + +This method is useful for machine learning and other situations where +you want to obtain a specified number of points from point cloud. + +API +===== + +.. autofunction:: Mapping.point_cloud_sampling.point_cloud_sampling.farthest_point_sampling + +Poisson Disk Sampling +~~~~~~~~~~~~~~~~~~~~~~~~~ +.. figure:: poisson_disk_sampling.png + +Poisson disk sample is a point cloud sampling method by a specified +number of points so that the algorithm selects points where the distance +from selected points is greater than a certain distance. + +Although this method does not have good performance comparing the Farthest +distance sample where each point is distributed farther from each other, +this is suitable for real-time processing because of its fast computation time. + +API +===== + +.. autofunction:: Mapping.point_cloud_sampling.point_cloud_sampling.poisson_disk_sampling + + + diff --git a/docs/modules/mapping/point_cloud_sampling/poisson_disk_sampling.png b/docs/modules/mapping/point_cloud_sampling/poisson_disk_sampling.png new file mode 100644 index 0000000000000000000000000000000000000000..6863c9e0469014acbf371a911a67cb50d30da41d GIT binary patch literal 265198 zcmeFZbyQW~`aTK@3L+wnv~-trY`UbSTco=?HlVbKf`EW@N-A9&ln^QDknV;}cig$v z&pGG&JNJ(J=N)&9FJo-?+H0;k*Nk_*@jUM|LRDE7^B(a%BqStEc{!0Xhwq@=36q$H)Pi=&0LojDScTts~0T~+mUg1{T!AxQ~^@WA)|DU_*5 z&m^pn-y7M#q7h?wjB+cSOxGX?Us?*qZmuvq*cRE0HJqVZT1>4Nqnv?Z^M$yE#tdrc z+)m2LOyd*R6~B`y*Pqa9=#Ho>8}>7DL{=b00hnELUXb&V1z^u|~^s6%D(77{8YX{*8_9kn0vK%&7reln!t zfVQ%@B(~%Q-dCSqAGm1P1dq2qe*D-Xd5Y2!DtCW@T4}_x%}<+t$C1Z0hezNeKV#pPx!&$hFt-|x z<;aaU>5YDD98HDo8uimiLf^ZOwXg*$X4>$K88J)~PW#FO`N%|j_i*6-x+{5KvMiE1 zoKNCc=vensmUV*Y_4Vje$+)^Nxnt&Z3Gz|o$0G47K2-Ez_mwcq-;Y0EJhQXD+B$u^ ztNZieE7qjt%C_gTbwmln>A_d6m2+YMLu#s{YkPait2&j`3)9fb7M zC0k<;&UpEG#?*aKwQgjXR;o{6U=$7}Jsz_|o*tYU#0mU#A$TCrn5{G` z8SY{FGf^EgFz#S!X{k;i9ZrdqFM~`8Nji8$Wl1xM`LznCRO%z=VoH+&kr;|g;607N zJN?L^U-5Kq>Cd4V1l`?5zNSQx3dRq_SPyTiV~0`q6#9Qup7z^NpF~9wZPQE!gSdqbxC|w{$solf)7p-gXHUrW9pBi+q)p z$uEZ{pTW~lSAfJ6+Ld`*74s0oji4UIFswe~uBs^aeOL&jmEi-5x{13Eg%R45=X6^b zVPCuF`T6mGhPuv|I6X2zrFcm)r?9J3dw1uh@i$Y3z*zACRXqlEyxZ*(XW3b*Ul=%T z$e1WJBMT))GLzM|3xosIQO)Dt9RktS*jGIyrTQVHIExL{C1=-%c zJNn?r=Rr#9cu{|vrUDaFiw=?fL&HT%m z1tLEx&pa)CY)mIg3w@vaBe}EO+`D|!oY{=Ttijy48++++>4OXNQu*@JW#!K41d@03 zKQ_B7mIU@UmzbCOx@Hq8)H4`#7*3gKnDLlMHET;ba>CVzwGUO77+09In2oeZGcp(i z@d!c`en|<))k!?cdGYCv1}{&Lo|uU8cE%efMkZb65Jq!GO@>tMjqFUTb8cSN2rVfg z`3BhwVHJOJS90h~g17rY{c1FGpSFkQ3iB%S81o4OR4cQ{tAM7^PTN|;J1bI)M+;M< zS7W-!N7~&C;@-6Aw{v-UM!zbm@p9z#Nbs;$k!I2KGZOVN)stt0pWs@}#gHuVA*T_! zeujbC49;Tt0k=^+s{|{fVLy58tS9U8hg?1+{u&BO-TDey?qWrfwi1(KLK;G{4MrCc z57fdkaf{Tmh6xfnG!8a1xtm;Bum*p$n>DBaIV<$x$=FPd{pC{aNCx(sGV$iXE_Z% zGoQJJy`i?VH>^JSu~pX+bZoSzVDM`z6~e-)q*MAr6w`w<7dT3)(5m_cPhdE?m-F`?UI#$o6aXyNjb?~ogj&Jcd#cwyhxD>ou1Zl;dM#>BFr zIz0X?CRZr&0b7M`Le18U%gbfm?y@pf!*`Vnmrv{BKgQ>0aSqH6$YwV?T?%M^{6gfR zXx_t+*goCv-|o5`zZ-g{eEH%!N+*AOVLX#Rzn09ob&qW?caQp3LWaRE-8Uf<;})+h z=)!zkXU=ZUxtX7f+rDmQ7Khq+Le{(3_(57O?B$5_XJpSj^WH@Iw}%a8R4!X9t!tQZ z)YEdlzocC6bNX5E2x*U9kvABn@SDZzu3UPntoJ0W6+$!Uj;O1RyQ-mrV-WbVZv*@=)gyc|BW zr8_v}&VFbFzcN3$@bQL8V#Sg-dVkn+S{MlJ_|S2tvXuTFqUo!5)Gz=)@~`$^y_mjm z6u}5Mwh9#5-H53aZMwe#p%-QM&pgYr_~EiP^?B84wL6#nu5pBs((9$GPrH`Owyk6N zH!fG3qgHKeb0m8yoi!nFjTy24$EzlHmgigRVM|!Ji)R#?5c0FO)8T7@%Y&$h9`;&x zbK~eHUg*Kqu@{%O%d<9Y*F0Hdyeua>79>Zk+hT7}0tX{{uoNs;)~$mqu95T5FX_{g z>hjwO0tMR?qos=pkd!G4V;CL{e0s;whW}Md>se~5fBxzr<2NcO%SB0kK}tdu@};DO z#VP#!Iv-VCGk@sD;s$lG2aQs_#poD#uaV|D@)k-;NKD`w4G9IA7zq_zA%hPDndD#B zGRO=_w}0Qig@hDljfC>|8D;Q|_P5y1R)`Q6XOR zufIS2H21Rp_nRDC{|*ZbkR4IN&dJ8X{;#${Rbj+kK~-xnb30urYkM$f;2jWt0bb$X z&;M7+zu)*DHFf@7laqs!>p!dhN74UTRnyhnMbgn8yweTx@Adjy`9BN)RupDO4E;Z* z;?F$)z6&NAa!;83UyBC0Hy6&2kU&yvDHRRy4Wtb5hx`@%!|>-DTqEx%Vx8k+At8w& z$xDfAcp-14-W?~?O#O}}B1ZfwK>~xO5-F1=6Sr`Vi5D-Pit@R!+Nk@t(Awv+c&Osm z7`&=>wSklmZ75&ONU&$pi=oL=zW?Rjx8M9xXtoFD3is@uIt#d2J>%LQo=p-GfPYeu z`XX@u*26#~6iOsyG%=*VmqBS%pHYIF^1GtiB>uVguVP_j6cP4Y|FZ%p%(#nAx#s)1 zUykd)ijc(ng#NSnKTWNP-$FYlXW@>$|F5S1>4aGS!GnKw=3k{gZ;^tV?qWpKNd8x! z9v(K{{_jzc(*$O~ze!Mc{#Owg0{s6N^ZyRv-|PQp%Kvv2{@D)yD@gxiH~znF=R@8g zSqlH*l7^jn2(E1zta^w?%kGwXzOwsJp3*@?<9-)&YH6Iu?zg)Qu0I7jW+9u!6(36{ zO&UeFGxQocVnmL0PPQGPlk{8qv*!sz?t`WE8%#CbYz?QALh#0lA)Y(GCG>U_QgFcY zc)q$2B$Rt%Na9+75>_1OXy@^Xj!r33nScJ3)l8%J z3dUhdkB|V?Sv61u1ec#%x(2n1)dp3PCV_s zntBv$w{e!@*z_pX|M=IyP6M30r0INPz@?j&@RQ>4FU$0`KIpY8ZBON)7I~BZeuRo& zR&2i4Wc|`&SJf$l-5#-MfFHNnkGEExw26oCyoEP4kE5;+L~owdg8@+GvRg+tibfHz zM$X(^pJ)$OZ4?&CJhA+#c;{DtRe(zR#nfsRYxOu4F~qMHny8^=Tl^*T#?bG4DE-a# zZkVW4S>ygwi`qWOg`L|owP~U zt#|hl9O5t64f6bM_7j_5YdAbj49L%xjd}Axc=ziX7~Zi%3v{I~o#N_pRWzo0HozBd z1P_{7?+ZAt7{FB##uii((XRXDDZ5PFa5CeY%^t89H6TM`ztpX>+_;{XB4d0pF=lgZ z1Y12#uk`!%L};VNbdRabI^n3P=L2WTNvQ6G?gv4<DcEzD>ipc2vrgR?IO{a5~m}&BI#I1v6`6!U~SFK!FjzA3oLD zY$ynA_Gvbum5e6Scc?SBfW+UNz~KIMP)YGoexR?w#{URZjDYw&@W0kDZ<(O#wR|fD z{kyWdxjKn?Ah7gs_O{)LyGF zgB3+;O}w5iHq0Ec&1N5eQt|IPd0RwPLhf6qfP09OWm{TjK})JRM_Y}>KNlzmE7%~@ zESq2|Dt_i1N4o~ETTPRLHJBt1PZp4?gk&G=Ciygse0Xb~nIU?%6nABXd^T1PhULE| zX~cg$*?gt1`7(6SSVhOYJ+bj-A&ULjdhKoa*=dL9&g{F+IC|~%Hg0qgAjvx$sO_1#)JlSMEAHBxFCo&VXHf z2P@*T^?^`NdXeY!lo|SYS-?>dKHmnawg5ByMaDad6uWZy<+_$<5F`Jiksi0umJ0&2klkYt~;mPmqL79RS3`xOM0qaXn^H7V8)?>sp zV8(m(s8haNRwrH?Q%U6sCdGr+_*1zDBV$#sT-J6}py%p(PHN=h6p>$m0y`K8M#Xs6 zI;d)b8I&mZRF8p$cgAaR4ZKG|aBpnmi#q$VCFCG!nDKTQ>{w4TCSS@kxxevnP@#zU zF3rR8523eoMUpmxZuVlJQ?g=KT|sRH&Ld8TS|3nehkQC&di~_*8g6kObNkp2JW{il;j{8WCL5U zu~L7jWwoI+T82|8T%0Baa>aoMRJ`S(hN8mhI51jkXpRjET`F69`NZBaj z6Ec&eT3&^6Q7=2vT@L~R@PdJ|KJm>NHyJ}ishT&)YUUSi8WkdH=l#P>vO$bw<4&|U$|8i zn`Ul9#4%4VsvAs+cj%J8j;fn?b}%}WpN(P)RiwVlBHYgEoNVqwa=g{$pFs3!OcFY* zCacMRy`kOQ6r3dc=>Pm}N0;q3z&-aXaY}5zW*C)-|gQf4-QaO&oQ!=z}hs*Hi z=rZ_eLU59G^FoE|&~M7y%3D-TGwMbRPFXNeVN+wt9@zu9^94jDo$oA6n#u8z zXEl;T;89aH{*ijwJlBh&*V#CEGOu%zWVUn~1+RBJn-yGF;MUXFB&a3<fQOD;nW_vk% zoo@*b<&v2u6R?hk`D}f+zR1#&qQfj$KU!YHZ?56)FV$3caaft%okNTnNHmd5)q* z$Shv>ItHlA`%xl?3PzUG!Bwjp-!du;O93tYDLXP3d5~Fqt7E-O!v(8?y1#5Kz_POs{;k&!0f7e(?L%jmM z*XFa<$!EP6_D1(bPFjXGgq5_Hq;JEyG%>C6L>3d}_$R{y zosq^cRDvL~s z#X&b=o}FeLB;s0TI_g+p#4jB7+junr^^bQeg8$t{yyHOY<5B&M?YV2@6GcvWgr z$k|JZ%M2r@>$t9A|b zYUdxCJ9kmz@brr5|I(crGxRh}&yW=}F?Js7$TClcmI9o|^Ma{Lp z)vE&b75&=C!6UZFyt65veC}LIENum={i}fllT7|%p4q7utHXk{Yo{P-%tzX$iLU}m z$ajjpxDzi$;NB{l_0f)_du_NXikNJ8O%rsbY1T`@?R#?VMGev47ZVeMh%BQ`ou{^S9J! z0M}moVD286B1eAm%(x#o{ilG>cf zLH_fPWuyRM6GXWdghD>A0yW>d_Xy<(Og&|(qiQ0kuHZO0ZVbT)w+>m&2?m|FB{%haMhsvf9Iq;!I)J%-hFxs)LTUZ3D*ad8F}x+x|m7U4?8=k0=3 z-4+f%DE9>A){*vYWg#WW{3<0AewxWayNcF%OE>7s*~- zEE1Ic_rBzOCVKk`ac7+erJ=WU8tyNBaT@5VRHOIa&-EP8VM?_oXkxEw;>(=n5S167 z-Ex$Rh9ry@&#Hd7^M5-dMDAP5?q&8jrz(85 z9r5m!#R|L7Bho`+{v|XOL4GbAe<8f^eP4HT{O3%&Oh^`i<4^%sujd#6G?PO+Nsc=o zb5HpmH;+U}z$EKNyEf+I4QuU}an(4AxTn@pWn|FHJ$$wN0rt*qia2vZHoZ@tl)c3M ze8jBzGN}Gql8Rj0(`%WIAsLRxd^rP8k4riaQdIUAh<_s^gTPV@)j1IY@m51v3Qjob z`D4jY4W{JIvzd8PAM_33(MW;As)Yg4BjAJ5O<1P;Gp%a{u-DE7>&=`C4=v~reWqHK=-nc1ga=crK`;*Hi9e{HeSU-YGw-z>LAEt4ouVRZurSvsWvUUh`SRH(Z-)CIuA0iXw(IIHWH-p?+u3Snzk@~mg~7YFHyU3a)Z`7dc=zhm zj#V>l%r{;xF`Z1{XQX`!Hjesqxw?LIf3cI=LE@z9XKVaWmE3cYhMVgP<}c!gXqIb+OKDF)4VLx^=FKD5qtRZ9t5VDa@6w}uz<6ZcN0J&l(GCL(0= z#vz9b{mj8e*#sL&K6R}j_l2su{F!~$;%l6qDy6xTw0KqnrA^M4_8T%4GX`KslVa^{ z5V~<7YZ7cbZVZ2Ncg5Ms|5$D5Q;P*7*e|RxOgw&zn*EG`pX_~WfXWQ_jyP~Jx?v>#x^Jg;EIu**o(xyeP_hRCm z+F;r!u+iy)nt(9k*sWAz0T;84AB4+eQ)bJC@T|IZ4J_Eb!-DKLg>6N3dq;{w>^g$( zJ?EGs7-4_btv?YUDD1d90MHRpq%7v%XdL})WKT`7Go3n`T{gc6q{1PW>-`2%peMtgkoId(iqkd2bHQECZCKVQ>L9fpWH;XasA6rZfx2C+-XAYWl#mp`p zQ7E&YYl$D@u@vpCXIzWB=u$wjOsYP`sF}kJ1Nycs4C3fraKihM;H`mK$;?Ie)kJIB zxmNhOfa{9c;|*6)Qsj4+O4db!zKL%{j>jPZ+o5?BuO^o|RT2t%sr^_D$Ts8E*R)o> zXGWZ`1#+uK4@pZ>KTp^cY4V#Lt*v$@&PXr*k{724c!GCxwwj*ard2mOoaXdcs;=)G zQ&ZUa)^BjE4s1@>?3TyC@5MkVb}7o1dPlJNbaGJ_mX`Uv-)}VMZPlgCd^yJyh_zUf zMWIb1$FdQ-stiA_(ytHmnfN@^RNj6nFESF+T+?(`esY9l7EKxAb!TiNjL#81}$&49qVYui7^9x z8m5n*Ii;=TDr9D(eU{(9rtWJXzUKpDwox7MLF>FD!b26hdEe?nPDx#^LilX3!KzV+ zaV>r(270*|Ut7^sQ8VqKpW~@xeZPhY$XBlO+#iH)7@&k@yc~ zLx!l|hjL>KB`nh&YL|VKs1d~KW>p9eZLZpFcw*5*l+NdjSg67-NorlN;h{9yMFy*# z+NUL|f&ULAprf)j~Z-K)^*Nr#56(bpF{4UYI7)_TI+yO=5YyTR?uW)HrXZ zbHp@0k;O(@O&*%=QQB25gGOWD@(Nuuew(}5LuKe*Eb}FOYn&KXO&V8oXSUBuTx(mL z2||q15n`OaYOqQ6>K0cLmSNF=jNL&_O`7Wcu$26E{2BF^Ka8*U6Nl}FeW4O6B{)Z- z=L0b=%?dWf{X6Koc_$2vD6Nf~2GJzMC2#Ym4rNp7B#ZYOH2xg zaQ$uzMx2_aA($3ER2WWC2?xFMN1cOd)tC7Jk~pW|=Mj)l7c=2+JJk;eIsb#LT?DxO zHc*quox5Q^l*F&E(I=)-I%UPxCf;H@;%ZQVJ*mQ=0|Cp!VI@WZ+jrULOBR;SfZE_ZDW4S$!%{q{pZMJ@%)mWLPi>xH4`H5Hl;NPypG5^ zI&j)!vNuNTE!vRA{RlV*2n+O87$T!W<8J2eiiTH`r4WRZ2)Y#*ZyVgFy{D;+^RnvL zvhU#f)tO^_fp%kldO$r~ehew-D5M(7jTz@HchIU^=oT4mc9&$O4)!?;#n~)uCBLDef z2(MuyZa4y8zN#3=mc2Oentlaws6+le1-;l}{d^sm#-LGgU~Vw(6 z`?cnhU6iU?w=zGI$pssEUmc|1Y?aon5TEo*V$}irTMK+C!K3dTliue>7qH`rZZfxi z@ut*4ixFuG$?`7`7eb2>&`#za?2x$&(iQW{$|VmM`=BxMCrT@^WU@lx8GK= zU>W3{yk7o~=l_4UKtafgb6~r=v%?N!^=q9neGhv1?sA})KLD~C{q>mw>vDpjhc2Jn znkt{y?(>?ZSOo&sh@88((vX7F2$BDaOwb#g@T?yQ;>`h&dSuawKM=FPE%`ixHo*yy zMIMr&_pQGR1yJ^D0g0+!pmq9324YcGdXg4@JF$}r>@c?xp5OMOUS2FabokUNw15wX zG)e|2n@XI=B7YVu2nScE(d&!vT4orNfPsD0$kgt9YielC3q*0GgxCwCp&$eheA2~S zc4{U+977?RHh&_`NHe&112?}cZyGv8!Taa^l>IWd3Q0vTwkjZ@*wixo=st){6EQV( zIi}t;kp`*_o;c_9TNaJEZ9e~K_f0O?pS<=U%&%EObuRAVCbanI4rc(;q$jU*E&mw zvAl>bZRDo&*e0Z_H&3~A*L^YVxP^KvvZD%*_s(2Pzvw}D-7iDf!0bvnk}91^O_I=z1jIf zZ}F$euYuHJxn5uK1s;WpF{15mGf8tMaN(kzKOCB2FT6;=_ym62;Lc5I zreLWw$byX_a@_VeGls|sya=n7ioW$B11fTpVJ^e>XBM}_jk{jZs{dWM7dRQu40>Fw zEepy057qKn@0nYsx+e&o&b_?yF1kq)bT3TdwNIV|BmaJplUm|8{kb2pK=pybS1D4 zM;O3I*k?J?QM>H@@K*);;DEV!0fE1Y!z~(2M`@;K^Z7{G6fn)(D?d~9pI`$j`HRqY z<IgPn-LPVOd=G;W13ID@viX+$_B1u6Xh<*x?kqeM|uvuEWa1U-#x14Yw za<);@0h}4d;HE0Ga!JX4%Zhn)po#yTapd+IXe-kKX6#g#F2)_#^ox(pTrGN$#m#7f1e7HczSw#om4*w`kRMq3Shw#(LMjst5&$c zq@;YcKq)fmB5|nA^gSBUo{nTLU2~{gCg2OWJiR}51HIsDK8qHb3%q^V{t6v;ip+Cr zK0)V2L~?-F2arSn5oLCb$N+o%@mq;M*#mzJLKxZ<^yW&fkw`y>dNkmcEV;KCp7zb< z>`C*@)fDzl)tC`J6hNG_=ciHHu_t}*?>`AIsv!-WZv>ox{AK=ZP59~&*t z%qm;}&QxGPyJ{Yzqc?Jk>9zh+?)LrWF6L=6Qb1BVNRB~SebNqVdAninI zFF0_Zyqk@rJ&W`FFkh5R1c0!aV~|xKOO}VJa6kG9AV}H3;qYyCHjU`J5Wh=?Hw~yG z|I1f=8_U#gDemMd@w+Sw0?RXdAg}@QB&kk0#>oD0D;eaPQ@sobd_$G-Nx5A^8Iw}2@yNooT>LY$WiCowYly$Kmd8&C|6;NA#|T!QQgaU zwUhgD40@%VeyBGN5UfH+x2K_*o2p-vFDkQJ`nV#L4&oAGSfKM)s{QHC-yf+pvPsY? zV(808TpaX?iXQ5@H(3p2$t{zd%csQ<^DxyPjp`R&{*wNYotDuIZ@Tcymgn+o(0Zvl zSghEqG@<6uGkltHCz#uFUWCVp+s3bfm^So68F+!7k=%R#_#ShKvg1@B0zTJgtFW4!56YprM*0yl z3Y);?B{KBeYai(4ngKCFk@z&8=w%~ev9q0ko|XSfW9)vgSV2m4-rxE1hz#zI8U>}SnPSyr-+f| z&?;4!-=>6n2r^6R;6VhUoXvaRNwPtZDQ$eUp$+?>tv4(wV*35H6xt2+lb?yByJUeN^V_z%=W%iYl7?b&&E+ zrU;1<#v3L%@XPU6a$|+uRb+y{h-7!vcdWD={u>CGw6ONebL7xuTj^C60g#L zk%L_-yrGR$Wj%h@xtuuVr;s>&3&<)EpLKhB8=TBc>CkUy~=qg%s&^D{l*d>!(0feeF5iuy}Dk#S1!?}^~W?qX|#w=?FfLpA%)LuPtKxD|&Rz)AgKW#H~c`T18M=;V6 zIOoX_*b$0vqr0ir!=#fl5A&>f@kE5zYJen#^~W0lX!u`JN?t$o4pQ- zvQzmqE3(_11D~(+(|igyoT-DaEk!SM<7amz4sP(nWNzi?8i|)RGJLe?W@B||=&0$I zb7CO|I(*>itHZzh;;CXrc>Drt8H_yD?bp@7gV`Hx?&CG+X?Cf5bD|PPO%ngrQ5kgF zN$YqPdJ}nrut;6a5tgiU`QGDIEO((MM7`<6rwJ#BV~_{W7&&uJCT>=>ZRAZmXs`v;G>e|ir(CA> z8oyT^m8qzDjB8akzN~Rh+SyTqhX68aTyPsL){S?g@SJjvzp$o{ft*{lZ*z8#sxQ-& zWvJ+fJ-#o8N%5W4zETW~3jdImbUQX939<0b9U8^l0>bU`a!Z8fTY7p@~q-zMy9yWagxA#++1NFcBjK4KBTS+fOy3yh z3t(GSjxeb**76gO*Q8Yo-PE6bx?uGw<7T`AGD?5B6zvmyT{)zz;Pa_|hgRGXeGCt+ zB(E&J4VKr34&Bs+`=65pVca?;z_4`k{-d+GE zCLcd?)T`g)ws2Y@X`?LMZf2ONX6RPr$70t``+L%=;hY-h#WGF zJ1Ow93MY(JswPJaf)o-*|3<*f8oT!L#Cr)=F&I?@8x?hu#4Q!xJkE$>Z>n7=1$;zN z%a|UXO3{{nG7o&V_?`6LPtlvpr$oJMkz>Z<%|8Vp!MA8^i? zBs(RcfEe8n8M$74z*s1m?V}Ibnm z4uE^*niiE*Z^X?+vDFvEYDIXkG9*?y9i7GaEm3!NsO1y1Pnsth`svy7ocE*(@eNwx z=yzwRyjUceKlZYzwP}ky-nOCHu4P5wS#{lsQ-7g?d(uE-zKHNCu_&8ANq$n6UFz%I zU2m3YtKyDZxnV5=g0*Z6wpz+(W!nf(LcVqzz{DU`Y-H?!rHD2yE?^_V8l6+WR>@jp zf~{^TR_>M_=6$_!#S?m!Gz0nc>SqdiCEOzll0;ggfUJ~`*5P=AQws&lLXBxVMr8{e zxiV<=)$yeERHc5uW7F9RB7YV)np{Ni{HzbU)2%*4^agUiX4Rh|4k2TLuMg#i=@x$k z#4SZ>jyp(4dR_S>ct2ZU6_KdRT-0uBb+h%Wg86zYM?KicmVn4}`*ns4V>ItTdTw`@ z4kjrAJHBej_G1=h%BOzAPo)RaME&^}c%avQ-7=-7*v*D@IB&8C!B$9Y3h$)+8-(&B zOk)`fAn}LgT6$iojXGyX^G23}#Mor?5-+?b#WT+6+$DMG@p&(?Ame<3;|G=G z>w4B*ad#9v69Cs3t)pX|8_zXV2hv8*+ecYaw+RlD)vt?;uL=io9rq^GvRQ17q-?ud z5u|6&CBsLxY#H-6!)xy|60Q1tJT-U9Kfh+ZvF>!)gPy&Wo3gH=0_yw1cX)`r+I3qG$5bUQfg6O0<&q^TbU?aSna1$4z6TCt?hD zhK1NNKMmYQ;O|rliRhimXg;~}uID^2#1{0aj70ho$+NF{XCCfp0-P(ukRl6|}Yxyc(cuZi9*n|+;<1tTo@e;Z+iMXw7Kr1?&P z$Y5tdWW}&?0p<&`lwn@8KAR=ei0n^a_@aNC!iS6R6|XWJKk7pLcegj##V>2X;esYZ zGjx#M@CRdsfQ@z{-hzoZ>I9&ijUWl)40)-3to~s7$-j>{Jj{4Dg}KoN2!g{z00>>< zv_TudgiT5(IQ;{_u1SJDKtVGF8ubYT&yX|ZASX+qTp_V~mH!1o*X|%QwNGa#e*~Zx z6#aj@^Z)tmgfu#X;{^?p4+Prsx8KQy!wvGKoNSPf)|62E zV+cq)cbGtTwD)lTq(_Q9e~thFsv9N6Z%Q2fyU9QXD62f!KoA)ee}5TyLbP)l?9#`o zh{G)qYJ-1}f_^H{8-k#oNB4sv^aZ^9lKp%S@Wp5OpZJM=mHxN(TzeRF0dE$q2lyft z*_UJ7T5x_SyS9GwW`X>C3j2H1qUL3L(bUNvVPEt~-=gMDQChoeI`cKl%#xbJ;MRJ6 z`Wr-UsTFWhBDM6abFF@vCq^$YA`OIzUe2!p6iVS>0nX@85H`qq0f;iZZP>}oz>jy- z*|`aNOi!bpI2c5}5#Ik{1vuh?{!Gbi@t1d`_X-c+?em&`zfYlD0tM;W(QAlshTD68 z$?C`3$B@^EgCghiSWqGuz(LjY>TN<2k9)lI&fx$FUE6KNidkU9{C#kxm4~EE+5(J1IReZ`N76~s)GQabS!>TfWR-c`^)$`gKlB4}B&+aa<00LG$yekB0 z+Ge^t_wCwoFh_o%lRljkc747{V7F`qj|+L{q1a@*?+20rWZ=HD7g-4Q?nK)8(|u16 z?XLk%>f;7rEUkq#IQsvSrpoA#Ul=2h8o0E~mg|VsDMLFy_$kD$=iH9ZoW-Hk@4p|H zu899Kb6ohK=SlW$EaA^8{B+?ZI<)nPx)w>09hMo|1RbjL?|e-rKQBmE!ATYbnwE53 z10eV{U=cnE*Mx>bkVopU@15UV&EE8yRRSDLM)a&xg-a5_mSp$&@3_Vv>Ofkv+pZ9X zW0*tYyR|nu>eZ7z;YAYkmd~vRh{TC^gSdLx!A8-HHf!juN0&Uk3D4(fHFJCl zoSACWkJv^eIR6H(48akVfimdTW~As5Y07Ebg}RE!NW;6y*~=Ba0pPOgdtU>&t6X3g zR%>Fpf7E{iGIbA}uK*%ZfTnaLmy*JbO&Xf$?hqURI0>~zolLlz==>|(tj)6KnHxj~ zUw~O)`@yQ{jQ~%JcET0Lb}fe9`20_oe!y0ATvO88EO zq5xYuTOiPXYmI!y%U88FrJY$Dp+!B-3%#auA4i5y^GS*6JX6~hG`~+a-PNY{nnv!e&j47sq zwhnR26-XA^U8? zjCOo9hQor5f=fr!rIK{>Q4ks7t3x!83%yr$=>}N%o;J7nTV;-Gupf7`Hwi-lY#PqQ&31`MC;xNs~lLpo7z_yA#W!!Ho)uRI_r7dUR>;MQ`BabgL&Uq5SccRK0G66yVts z`NPt@aSuG+Uyzdq7`ur(N*0SAeNq|m_e3NxvM+c5J-IX--OrdJIP+nsYXT};DA zT~^X{Cjc+?Hd4QL+Q=jX-;XF6!>F5EW%iX@GFs{KSX$E8c%)IQP?n)!4_^Dnor7&~ zx)i(E<>}e6TP_Jkn4ABM!#3PM;nSCI3$*~%zTmGw^d4|XaafkX0W9mxRYAF`RSS32 z79ETk+Xs|)VvSwrqrXv=6Usd`#?dJ++>K~b%a6MJX-7DC_s&1xZAuf3;Keng_oS1fPctPDbLMEvMyBF-2h~Fq!57?YpBzM@a53L33@!C&RMow~L8+4b6 zJP9hQLfuGO`Oa*g-0G00hLvCxtz2METlRq2hO&(Rjfb_v(I$%v9Ce<4zJaQ&gg|n#9^M3D*TLG@z&|hr0Q>R zh@6U|F6%!^rfmO1E!wPXDt+%h371O!7h5Hmob5wBN7xY+<^>dhem&L-Z$eHzs%Yp@ zp7GvNV36FyBK$YyZ%_Xaezm=jrc0>ZW+;qTyS;Z5@qABWRhj75s>cpVhw%1PIrEao zjD484p?iE(Siyx^Th?#aqb?S&jCg0kNCnPI;L0|0(%3cof06c;VNrH%w19}Dl!Bsw zMMxv1bcl$wbc=v=_s~cPh=_E9q;&THl9Dq>NlOn5AvrW>Kfdq#o$LHQ7k_o;nP=~P z$GX>A8|c9{K&f_@I^2pHuPR4d*mt^<_1CEk6ub4CHno!~MKKGT`z-SzMk%h7 z7F!=4enKtI+IGN?IjF`jDl{7Uy(b+2&6ZHk~nCb4Su|)|=geyg9Nw!>!lQJZ?@4DO6u<2J2o( zCD5DR+um!oH#$4@nOYda+X8rW;weD3ZE8vNoY_n7RiU}^DH7Ut155=; z{dn8^;#-b}MCM1LhqWQ1w|uRX+tqF&$XkoHJrA5b3duF z^mr_c^I5hq`*f8j1ssIFCep0gukJdrvovHsgTLhkr8k*LAsOUX`xB$R^y;rucZSQ5 zsBNJiZGUy2j|seB3)8&mvGBl)ei+w#T53CS`L<&^e#81MND4(|N?T#d%VqxI;Av@I zvMOGq0s`??7CT3xe{eGti@&5=SfZ36hW0ZSA2-YQ6kY-s5v4&h0XGU1>;eSS5!)QP zMWf%b?hvk|CU9W8a&w<>)tLS?AyVmdB5!lefRjUH{DDVra!s)(P|3Z9n@=@>L1opK z+6zKhr`tj(Q*KvIGN3?{vN)syqOtl`n+>|^3kX>E#dlDpVpC(LL8Yfa2}PrG!xvzE zmYqCyvrVrIzL4ClJ{yH;fVfqRyKCJF;uh(zuS|>ocA$fl%+GTY)VI)7UVu_wXtA3s+~5>_(k^hoq^cA@ndd`33Gd$av)J)g!M(n*sZwZlwUV zJ|qTsXD4;XQ*##@=PR2#A<}`E{R!KCX_{8dz=4_ zIP)>WvQ_yO7^HbTDo?HgtdpuX)7_;WfB}kh(VS=gIneA|Cx8`elyU))Z#9&=dx_Tp zXCQ)C=RsfF=FYCQO2SP=_ZG6b5-y1psoyp@Y+=;Ce19o+&@U8}${-_>gCB-DiOo#c z2RZGU!GhFNP8T)@*#(}qq~p{PQ{NAl*6gP0JUtn2+4>}Q;jVO#N{wS{)Ky1Mk&0B? z4NztdS5KJe=r#cwkb|o)jG5rHWWs>)o7Wg)giL{6qH^lI-esW448_~z*j}K zza5pdK@S7S6}? zn@Hi|A+wE;@Kq6G$}$JdN;#<3E_6PM?q`x7@BK-K29VA>aXuFsO@vLP#^LNW_B&Kg zqVzh#ibd7G-%N*Z1Kzl5C3Dn9IIIpXk@gOz%Ql)pVi)yYFW2v1}gl5FRG=Oy55~BYEaa`s@e!yvvWB= za#Gc)uq~b7?(Ft)%1qg{c;{YfvB>~!ev$CD9VtA)!dX%ysZ-kNuu@(XOZ0RCq4AS) zWoU4;uQct1x3IfTU1Wc66%pC>i8eWD&>j|&Q$MD19ICml)TgM5A>7-vWI1qW;qjkb zeA}DiwEG{!PrRGpM!{<~mCN(;YH4^HCO<)Q-c=6Cx^<1-i|gn5fy1_=>8Jxi8LtE< zhK7(sg$5HR=bENnSQvv`dJLvEI8_z9(25mUHmQCe!f^d*2HCK8moSm zwz9(<(uvM4Gv2Fnptx_e`r{Ol3wgx9B zK={K9m%qlY3rw1472thTMp{{RL41#ws&u?AZ#zDa`}DQ~rq}tIXO7H#)laB!HSNML zTqWRI61{l!_Mg}S$dSR~^TEZIN9U>3Pu=!z4~jUg3XzTd8mTW9Tbs_^F<2Ji@4rZu zw;w~}TL187+c^JoVt`QM%xkfqD=`R`oz#5=;E&fSxc_^>>^MOsH#iMY(+gU^Iqx8% z4PAqDCVt<>6_f=3ki5VC!Q=f}R?X}7Y7n=rB986&KhD%=fLh>C5z4Z#0TjX^EZ9!d zp*JAr|H|$DLG1VeDQfyf9j-oP^09E^@m$G5%+<%=ApZW!_x~Z7Hje;;8DUS*0L?Tz zAHQza?|e-3`Za)R36wYg))(uz9_G%1MrOM8Rc)Lm0{x7r| z1s;sQjlmp%gf_UKvLRu|#z2(PbgUgf`}>=S#eHzp!uBfL7yxVRF3$h==U4{yF^73^ z$+49`XAO8rj8CiuJ`>M+h+1?J|D=tYoB$Bmpko>n0v>HJE(aHW@d!nJkZP)Az5JlH zwoq?bJ9iqC?`la)SN|>F?ZE?1sfv$L+GU1}yK+cC?35(RPXLX)0)7)87EvB8B!^|T zeeiFwMr;lK#~n^z%B9`gX?glgQlv8>0co=*j~)ZeC%F}}c9`|rQ>X=8mqx&i7oZgp(0&yg?T3kp1VZe=m_(yx~E!}`wnBn-{y-t;DnwW$TdDUgh1%UUkeS z0`_B5+g<)dfE-M|5onQk-SF}0F`?jjr|bUy^5QMD5sa|o<@i)wcp_|dR4!5?gBk3= z|Cb4=ChN0N-aQTCFiU;xkC-~n0)`;hthJcS+F4kiXLN>u%8dEbV*AoMcCi_G8P;9N zTV&=;*d&#;b77r4*1xy}EJv6dm+<{1fqxD4SHPqA4?QINT;~m#l!ec|g`CohVnQ57 zVN?xrY2&-`H+mfl(?k)KDL%#NnF9KdEu(FI`T%m?y^1wK;t z{^I1&c~Bz*Mn9qt)ely>GWBOBdo1#;6Q#_;d@K#P| z7T!l{L$4vRpJ!7#?OVfV7);uNrp`h9$EjTl4{o>f2+B(`lnc&DG2}&K+j&#dIf*LU zi5N#3j0rg3e*4V$?;>L{-ixyErO2{ab>-~1F*{t(=7HEsZc+ZRZoq8b?&SIIg60{R zg%xgrSq{bkKp;W_U|#p43DZ|h^NNboU?Y#0t+M}#_sT_B2zSjImY}6oN%qmUrsSW0 z$d@*NNN7i-f%Dh01DxP{vaKC1?!4T$3FT5l-i@y)Au0x?d^7Kn26?)3U|eZWY?kZC zi0U8(#%Cx~(W}h#)_pM=rQCP4V~eOH@T5H0T#1(F8UMSLz>otX>goOGvi4b`^|?`; zcC+R) z{ZLA#6Ona=m%)tm9V5oN9iN*|1pl$g&+so;U_y<~ch5#j?biMh{uRv1a zFxDx2PW*GdbW>Q~@0ci3do@#x(oNQZL%;$f+0x?_iU8ED<0*hRr>>MpNtCKL+|mA~ zyKJ`|777dgEueY*uNf1P13bQK6ocNsK{=e@<(r9gf?{Ro2_9Oh%F~8;VWn9f-%RCk zc=l5zQ32ocXL0Jt7Jxi&fzkY~Iq3D6#Ju2QDKtB$U3cv2fOE@CspDLJhNkdgGs;^v zkq5Vh{G<-rHb@`vRfjx`c>jKt0uE!+hL&7W2zC#=|7=tcbA9fD>G7b85ZVA$IuU;AE#XScodlT2W@z^AUtjkgJ^<&a}e|pm&ei)TZFqS2x08At^<7I z?zpBD`+F+`dk?g3LmY@CmObHZ>7-;043hPF1b+gL*{8n)Sb&L~ZMUwBqRpqKa&kgE z|M{sp;HQr5KH~kmaZotelw*uPhD#3EELIdTR;eKu@_r%RMSDm?Rs?V$%bvI>13(>v z8_0=AA6x->{!r#t2lBc^>D3EBqDFT%ffF|O35r06Q}|yx9{)`RRZtoZ;v)Db4eQ9Y z1_sbdeWy!9dzd%)0M_w&n?5kINU}Bhq3>>cA@3g8{YP)>%lJy|unewuUMPlBlyV>D zJ0dkFYZa0)PUXef^e5nsfNcu(L2smw>R~dk3gB)~93D2VnKXwIfiv7H4k9W&GlPOC zG!eb=!H?zg2_;tMEv|AKM4L&nm{XRSHYUwu<+d2Y3y^T_b)G6R8W}A-@UTU|+XF6D zH6&Wxciy@|u23ga)|C;e6S3b7ymq8pKBvsqD-yvJj6dhc*V(?KKjFO)n03!mO_P-1 zbUSPuvD5U3EgMfi7|RRl{6{;8f*c7hkLLdo`%vJvy@IEr&2eT1rR*A*{sxv7odvxB zAHX#;xbf<4To2hkTs>)hpc(K?n(9(%z9=bu%*0lroB*B^*F2c~$RTd!Xh{VegEuP1PLXfnQ{iK!eM zh*UpmH+JW6>#^Fi>IRg<-Wj(!Z+zI5pI5po4w3N+$T@(#DH5HV62Rb=ClOO_-=B*} z{qg)Q^OE8|mVX);_;1%gc=#RqKCq;?wd&37VRZy{o>X1d7yS`w42Vqw6z7cv?NvuR zgk(!Z%0twhOm*T~00bog`yaH|TZn2~d$!w0{m|%KK8WgbBcQ>Ymtg?czdk*aZv{>( zvJWC2d|1P4^1V;0JGz0ba@)U|{zQZaS1kO-Un?YDz;K@v7V?4)4YRO+nWW9CV3K(4 z9@oQvU#=MCZ^7VI$7om1{i#oTpx>LE0R*vqWbGB(PBht2>TD&owSTg?mTWv%pgdAZ=#$ti50%bfY7b;! z`IJoHT=^4&ELFU4Mgp!}CslYh+5G zr&*J6gJFGCH}W4N!bMO$M)0&>gT6l(U(0k1x4xv^sqy-i+Aur!eh?TFu@DrihkB>7 zoS;7AwB>{Cqqsh#iH);hfSX_BFxMj3*Cnfal<$56&Z`@kZfD%#w@#R{EG%x55%InN zD2LzxBJNwinyYD91;Ggbq9@t)>X3XasA9HF-Mp-U!gwGIX(nI5hYBS~(&wX5_cvp_ z5|4d-Do2U>xA2&#ToP%tyO947@^3T|*klIm)5^u}NW1(zcJ`vLGg3(E;^*smdEkYB zdfW+|rueyQJ|VQO`J`WiI3|ar#B3&c#VX7I810nxBEpiT`lMz8^Aoo2Qnk66M0i69 zT6esA0N2A}bFKij+|t80Zzow&jjr-~&;^@cIQI+2dwRa}Vd#i{D~wJ%UfU*@m@^ER z*)bfWgDG4h(i5?ts`DqmT|Jta*Kxe#;^ z1@q$;oddvZnohDRnFwVTqUr|pX!KU|sVyg=5c}83R9Rf_MuJ-YGu!6yO|pGJkj)u} zU87`DbO!E&FItQyFo!@R%K{d)oKBeu5zduZKbGJ_ z>M)l=uE~GO8#9D+6EL4R*Ha;3Rlmx^TWB5(*1|S=JoEBF%AD8UfREVP!MLH=_@S!w zOQ%_0XVvG+3dWUNWcveO(4Sgt6)(+0GFkv)bGCI$*Sb82dagL5V7piYF`h&>d0mO* zBk^~;tJ-Z~5qcFtCw)l4=u5^-fK53)&wXQK-Xp=ZK0dLf%Be9gD>1O{!WMp@A=d2$ ztRwfF`lE4XN(Kx|Y5UkvjnDe)XSTnKlkF#2H3L3>%^g#jwpv>1hH`OZW>j^MF{?)O zC2-(d_WTLT3%Ocgl2H9Ilf9<4hcWr6{un&NZ5ibSmf)wlKa03^;pj3koMKff5EU0Qn zP#6!3G(RB(4kv&^UNciFqkaUIC*IJf-V@B!&#n_eZX)Vl=k;Zshx{|ns$wyQb1swz zmLJ|APA-t0oS^mpAEY6Uji2xX)bptM`g(%sJO688U<=b}ecmAHR(>+2YU-^#%=BH$ ziJu0N{uy9m6CISvwEYm}S^BG&1(gn4e+&`?rv9de)^{6lBxu_mGcq7)#oXnSZwL zaVapi4Wy@;f=WXzk%yd)uHC7=7LBy?Mf9<`cjopVSHfF>(qp?c!|4JPAZ9byB`$%1 z-7wK6sPqrCb+g5uz0|ccxsZ3cEc5(cv$hiDz!*;9o zxLA&(f}mn19n?|adt@7_Pc}#DSCB173*ok)m^tuG4Xah%iFxMBhywJ2+qH|Igj@+N zWELKyKYOx&a0Txj7RrWY$v`>=`pe z+NN9oEn)XEK+gFaNdSL9l*lp#;$7;*rRq5CZC=u!iuDGd2b?1S^8%}quI+6rT^Vj>!E9=ZJ{Q_hiocaxfOYQ8!(M6KWO-^?=3EgYX* z<=Ma~QF?z0)(o~DN@GnvK)KBxWM{|8Lb$cY3LX*V{`&Vyyu6B-bdq{{L1*((RDuCw z4v4cBY#Y`X(@A0zdrOE9J1CXvuF<)-lH7jMVKM8$R6H7BaJg-M9WKv$2v{*irV~9v z0su~)xbz)UEzO#xrse({c!9OA&%IcF4|ZZ~^%olm76zlMooQ>gl4i!?OCGyv$AwIT zoAuKnt1B&IDur2ADtw8!-dPt`LHaRfP{JKXZh|B`9C1gWgt^C3Td;TfjemySgw@Y- zzg`Yh;}F)cr9|oI=4dnrFr(N^*&SiAGO=wwr#HV;N-7gjG3>gG)agvL2ieyVkfGuW zg?kj@2?B2tr;bygjb0Z^zP&hLLksWc5r(Vlw1MjGFIv!f3`ScURZ5N4U`Uv=aeF8R z$Htc**knK|KaDr6YPU=Q6_+KG9Dg54y&hYbm{37@qWCc%3Dol2(BN)#4uC@`8V%zM zE;`q;TlNO3FPl~x`XIYlvGt61nJZrT`%}snFIHCi($5X8z8ZLpY&Yv)VwU?U{!;jz z1Hs9Em=KyhPLSVrukzLVlJ-~6-EBRpJ$H?7GVd`7^f>M1WvNSogh@IRt*{fe@1PrYkB?{%4d&+9y(0+|0USq-ahsbvWDbI%O zJPsh+I~D~Ef8@YY{gy=?@RONEv)-stP+=Zi&P{t0pZq{qn|1E~9%wncMF5e>b|hcL zww*+Pm_Bx)ssAAvDEcvBan(^=a!B;$^#k|hrwGAU&jsF6R6yY4<#2s)4;piCc+3T) zLFr+sUY7C_o6jAny~&9XiIRj|Zzq6Fa`ZuBoq;_Xg5RwZLJ`_Vbbgpv_44Iv9bV zF?dpJzjL9=3ShapLIw$UY^qdp8x6db-+>pOp|O(}((E=n2)f*JLnEo*)y!!xPF|W= zCD$s~$^GDedosw90_be&&l^MCgeLR3f(q+msQ8{(#rQ2m|5Cq_GlplefB7iL4UB6} z9$C$|f&7vgwPe;{Gpg*fJQ@fOh3$MUv*RsI3|)ql!Tva4<5TBzy?nKUzX4{8TW5O+ zH^^J&6fA=7H{$%)Z*IO{8gk?&)9@Rg?gv7K?`GOgkJS^|lA#7?>swx$BV?;Q1qgM0 zaUz;4kFPSK)W4{ z+u#?PJtNBXApZj~uYf$sP77d`G&w1lszmy-7R5>(7tg2OKPqOv4Q-h)s5IH9c;Kzi zV2_lzRu9xcV!!Pcr@{EdQRWdlq7To2MVEL66#G5v{=9^p65RDU zn%@G2PW2QJ@6LetG^rdoQ;|>{%%>cDQDpfSF z-<8x|K)uUgMD;z*X?@Z2QeM_Qrl)sOYHn~lw<8s}%>JnET>1h>Q}{$^Y1qNs4V_T* zKt|jm^{i7_Y2i!ky(-zkxdoX5m-Rn2&1NJgfv#*V?%Axv`Qo-{m!khnytJ2SEP3%fb;W zPL)zIaLSi05>&Jx>a71)=qwgLf2ov-f7hv>+lRZ!4UX2|3LxSzXSTUw^!+KxXjNxa z%`6O^TPtCSZyiGGR{3Byv?$Ia0!z0$fbK-GNj9Q8b6e&qu7OAo#Xch&-?%o0<~B}g zMUDFJ;pYuAXy;OEfjfAe%8dL;Qk>+;yaalDdIkPUs|#7=vO2`P7CLo*8qg(swNPyu zOf@1GeAA$|aMjQOn)E0R=T)`);lgJhQywflV6<$NHKxpsa)J{1e;9vm8`;reZOi7T zh}uF`rKp-xs}8l$idP7L;!jn?`rVP0YMd#MG;yK>iG+3TbZG0T5N$I{08L3ffN4(+ z3KhHOwvO-uGN`3UNI0TzdjIft#BYL)Dm3YmHkRDs4wa`|((Z1O`h6#~_NHz4JrsjR zC2WR0(h_%=%qup^8XPKD$g({ash$=z%afSq#WAVU%a(m6 za7X~ECfE((4*P_l?=6kFv9>|z4-M|OP+5_O;V3;&?~&vf-RtM1CL@5UhgH3*fQj|K zqbc|%wyfa6mK^Ib)B+||^+0WP@<0k%yD~6pr$5Kfr!{tB<%-|*ys=jy*ZZeJot0>H z+Cc$weMRT)m{ht9GQ5#ShZh&}fg8`U%O554no3h#HlB)wrdaB4=RD1K(_IhFSf4F` z{lQ1fsF0*4n>o8`Vh5kC)KIL=f8Ip^?G=8oS855^zQ?`yTR~XS!C~peOoDcUYMJb( zXO88_&z|ZZ)aF&UWhUg|d+Ry$zyW^>pk5$E8xFCfzxrloj58-2+}P9{dX6r0l!n&B2BO1z5|wMSNL*?xC#$^iU(T3O|F%z zWiw}F``ct1SBzh0GnIyO;nGQ5DkfI17u}Yyb7%qfTU(%j#%zDug6^;|xG@Kqw6i@1 zo|~qMr{2V#7rGP58G#m-Q8dgW_o7C*3NJw~1%O@(4CA`)sQLVr)xSspJD4=vaVrO~ zQe$sQl)_P9stGYZR)U}8h4~+>$GiB{`3k_U5Cupk5}#s(|9oAe;@>u$Nof zUw9M};A7cTTFrujo2+xkBvcsv;os25#0cot6-5cl22OBcbh>TJC6NNJla8kkHIb}T zAXZ$gc^Zv@ntBLp{n*Z>?$x#kW_nR`hyIykwjEZba5inMCgtI)a37+R%GncMv1w@9 zjQrO)X{(L$>E+qpUj@&L2%6>EJqzCNru3gU=#s)R2p0h%biq@M##GH211PcC^d--L z#ZHT$0BwdlZe=(UaPSdW{kVqD~TM$%;DLBW^#+!2XreI zV?c6Q4veFY)c@FYbb}${HYnuaaZRc;*j%6p=1i;pWx%=#{4QK+Y;rF91V9qjlSs~w zHwLlTwnN!h`hsM+_wFZf#$H2BLBZ1=`9cEo!Ul+b;bU93GRJ56_o*kFUy1~Q;w|d$ zDT}pN@2Z{|j(M!w8z<7DtfpPNJY4pM0C!^K`TbK2DdPVQ*3s+6<0C%%76^>i+lO03iqIawAC6mk=4; zn#_z4EZ9vSe?(Y>5f%;>K~ubf^L@#gV#FPz-nTP1_AS*aW|uDx zk%huQ{`&0iT;s`4JIP!(O`+6%GxTel=sX)nhB%O2+~{o!FNSEaPU0Xvp%1V2!})cL zwJ#Ji*3=fSK!lTwDex0!IItHud9erlp_bVj@g7D>!w0UhBkXFj|<~TZcOaa__hwV%DC8J2JzK;~B2OgO^U@?R2gOO#*KV{)9XL zse9u7AN-RSufCqz@`aoxnx*YXH49AJw|`>H9}T#GcvaA3>(W=nD(@v58k6iT-=qkrvztH(+IJXOA_kDaq%MxE_HQM6y$LXd1=<3Kr#F_uxv`C0? zD3-v08ICBb8L_DP^7?Sr%75tdyMw?_cLWA8J~5jE$_#q34x!wh)V(n>B(>ug{lFdp zF+KQAbMF-LZ<4Nw@v%|Ac|Az!umt0V@0Fw#pJ5k&ABfdzMCL88*9Mjadll|fMnfmm z?&}K`RO%cUV4dN!>sw{MNOTn%5_Tcjd%~Q23a85 z7FGoq=svSBY62s>XEvq3zbd+K+}D=-G( zK{O(~FbP)LLgC&j zU7Y^)f-@@PE^r2-kDKiosci_E#f3ljtQeC1s^>BKf%^OtFI=1i?%|_a-L}cec`lY? zcMQ-z-7X+i?9`ll=q<$i^P6V#{d3bWU$CE_g8lrLsU(gA-J!B9=1U@H0P0MdSEdu4 zC2!1`vovxw5Fr=6?{tJD;3_nt4FEBVWA|*9Q8<-zvvlB753n&j$bMN%=Q3jll^FF0 zxrJrcbJhy+=FWi%QABqn43~bcCG%76>%=GwM+;gMQ|(($Yxq>P&H|`ugo#y0Rr-?C zyf<7P-ECe1542^k90k0lV$ja;@ReBYhtQhdzCqY2<} z3d3<~Vn_isp-e8^mRM&3Fu(jE1$>)AC~WcAu-U&F7Y@tS@v~_4akw75H6P4+UP>dX zqp!l!7H&3W9&4jmT0Za)#n3thq6G-o%M=?%pzu89@wzEtmoqISbBA2D29GylS7ny> zOb;F5{8MK}sP7T#Rp+XSxM1OfxT#h#YGhF?A@Zkt10 zE>^dVR>~{}Nmu*$y?CaO_@q-nD=B~c^3M5j@Mw7QUyUEQa0=mxDCv3MNJ~;9L>dxcyw{_L} z481k@IRvoK9t~1pf$2yQYgtuku%LktLr2-FxuY9%$R(2ON}NJ<+2aHpmtLk{CDLT= zwBmrVZi2?kiRN)e6n62ff%;p6uReh0sgC}fkU!3S;{d)-VqyAE`&E>px-})o$kvJ12->d=SiG*k8mo;5R%y%AwQ7Q+z6M0L)x|()E6q+Ud6(g3& zO~dBP3r{I-rK|47kEH3(M9C?x?)r2{DK)a|*6^02zR##X0AOHRPlMQ-RxGFHdsDdx zRJP4jO$E5aYs8#}%TCO?tToL;+T@2s#FZI(#VgRCDDQ79IH_s9J~|ICV|sDT6FjXc zFc)f$5!a*D_L-`+ckwe<90jAxUJ?qYxe(13$EUWO z8YoHVd(ClZL;JziPE+TNV1B|6sBDAF>r zHv^+cT=|!ZpW+M`1N{sL_3H1cu6WTtst)@Pt+{TPXu8rI?;L( zHfd4&)1uYlo*8&@??FA5@u7yFSkXijS&-+NBVZSvtmDObR-EmAHG4q*f&eVRn`kof zOl#V-*q25XUAUuYiO53{b3);A^qL|*dq!Td$)eH2?(||`Pm%rWNHes0!2~B3UHRCp z%s1+R((46*7K~WuMcS2tN)4^atGNfgd$gbBd>?*8OH5y}YdNnm!X>5?2Bz)nH=ak2 z+PooS$fOVUe6`p4<)t#|XS4n$RV_gW8hh~fQvJ$xWM08DH$C_ema_-Nv3vrT#0yZO zT20HtGI(k&hF>JS3{?3*|A>R4VLn6Ry`;eN(vY;kR|cGoL0M4# zEApj1I{@Y623!lZvFZ0IIFAtiw92&YF{u#qlv>$Ntg8K%2fdc^cGE%Bq>HZ*$y1U? zS=iT5(L-OR@(ir}dZ@=RA#|{pkd#`Ex?@zE@cwP@cIJBPs+YMnFdNn1R;P5@&0h7N ze~}pn%-togp3!Vs-NS+Xx^|1b?SavNBfW;W(p!bM-JS>Q3^R>xrPWhhlzyTH{q6-< z7N5yA6W!5NdMn)OKqh;J8U{^?DKTDC2mvY4>o+m29qoJRMf0LbwRAN%TW9@G?v;MB z>a)o3F>l2_IdMpxVID?exmYE(P6Nh;W7lo7Bg@b_K~Z_dx1D3hmRv+`jA<0_ukrRg zpADT{7md!5fBn1Ij8>=Y+!l@=Vm_|s+fo~()W8bj_;VCBL*w8#n|~jDNq|1T#VBrP z+?B=PFSm+UIpQ*f7keG+M+%d^2WY7Jh5RvG_w6MJ>#=^sN?A9jBL&glx=}bEx^)rV zF!cM4EbxS2pH9=*`-x7Ek4JD|k#J@H4)R`2b?XInkasmc^6H=0vrJD;i%Wwm+|8`2 z?n%6EI{Kaw{6<94-I;A!M5jqGI>#iaC+6x>lw8fczeL-Msdw^5SCu~w5TSa0(+^B( z)*I(FiJ2993HqkKHj)l@Rt#$jMT5rbN7u&P&E1bzx+lpS~s~+A@?{Qv$FCKNKMddT!G1TJ1I0_D?wVQb;g(Qgr-rOIdx+?m!@DmgBm?K9A+iuOHFjo%tH?_$ioMQ@T%7 zxtk$yGiqCf%*D4Oq(g3BQ)Xa{-y?GzYGfM-y&iB~mqCNIpF_P~DW!yqi-XtB zOofzMe)Qgn_e2PtkpGBP{#{eXv=0V0hP_wK-SeGn2LK33CEH+R@>)$TW`oP|tr!uC z+ekh*rj_gR#}{n|l$ zS!)?Kbak-p{(wfvqixN88Yv`%UhFdoaWF0J+i;;HM|+{s;Wa>r1>}a3ak_ zp195^R(w$>ZXLqe*Xnb>ab$v^9PvT@2COpff$tT5Hsp-ja9DL_%@b|mjk5MOUS6lt zuD6=PyYrIAi^)!f*did!ykok!==|{d*=2_9JMWtFMJ(?c{ivh!az8p2kJZ7{#qE@i zu@Et>{5L*XY2RmEbH`^TVtoj0StAFi5Hq+2dwkvj(F>WMP zxZOSp@cK8%>8P?>n}0uhRV3CGe6J$_7H6Q0I2{Jjly_s&o(4Z2 z?`{U^_)1IUKl?cJ1H=Vj@uh|$ZgOy&jlO%f=8q`A_F8J) zL0+Dod1os%ZV;E_vt}^qK9wEEpU3tJk_I+h4=0*DDnrY=DpNl-9nY|M>=fSI9sLr~ z^>8j%J2oEH*;QQO+^%tZ5V0jYS z@x7p+_}RIuS4pqEMZWt4*CwV@OKMjXb%@-0Pqmfmf*!m59y=q=jL$Dksfhd9%(d|} zC>*$2f$X}`EUG;&^lG~auqPR1Z-qKw70FX1Wc>M>U35ow=}Ro2+V=tzE@tI1^Ki!} z?h@cKBpmGGVtITdKK*w~oCh zb703>oBp#!;}pGWavga(q%pI7=TU~QaTkln8k$9XuG%!SilYE$pS9Yu{cX-~(y^x} zl-H``rB15`@iUZ`WR=vXghQBhwRDo6*5BAsabeEi^vGYT2FKd6RK(d?c-zAwjY4;DGf@D()%7_?8z%qa znQQ^x2oc?%Z8qG1SIAEF;1aMAsRvt7#1UN5(gPWT7t&L)Igl+@8SMWsWw~*rg*8)B zTFmyxgG%; zPA@u4)60yB`}Bvc;d18c?s?b~?TnrMJAJJ3PVBrs&BtAAf(K|h96|-sk(_w9@*5mxAZL6nf+)&Xkpi5S^1S-twYTOD?}Yd+kd(j z)R7#R=3tXZd6oU?>)zg8;w#^AU?~r#uThN{mxXp`6E!H6h(LAN#!tU1`x7oA6%7L2 z^uA5My~TjyHH*jeUQbr$D`9WVk;&VJmyZlSFhw7T`zn7MuH3R zTc3cZjgg-=(?im|7VmMCpU{sQi|}U@dtV{8hvv&S7vDoL6bNfS5&EvaztxQRIrKUX z&@eNvD$eGkuPOFz1S`TVN1dEY(4Dllt9J!#_4r(95k6HX8y$Bh17B`LhBWa9$&!`N zb6tmQ$tf+x@pQkeku6>uNGZZV&M>969ugi!+iS0Xd%H0ErM9Q24HSg*+{1KyzAu#x zf~cztbDW7%mwWI>WRGnE<9j_Gp{U5!OhhNq8kV=MKA-t8S0z?rhv&8XSPk`rD6>)) zo`C~f-A6g=nHZX7(6JRWiR3q+HK^C#g?IbO*wPCh;*Y?z)KTrhL~pB>X6|JF`S{)Z z_tj~Mnn;P;t61CVKkP}+-&VbZ8*dk0J(xYc_v50jCIv4AuR;kFvSxF9J!^ClM3n?) zz_#wG2Vh%TeheYNkKs0`^D}DNE)U#{$F%?iqErLyidq(;r+yyxXMOOdNn^Q|^UBMfY-> z&%sq>Nb%AeEo_k&YH6o_+`Dvv(ix^w-b@a?}F0h6tkF4t{(Yo;rrZ4QY) z=&TTKy^r&L0JA0I%c63Vw*(38cl@LLk7PblU^zD(VjXMUa4$M6BO_}g4>%+qL7CH@ zlfUb&QGYy3`-EZ9Ka)Z#A<#rlS)W`|-!bAo#kP*S$o>RA$_@4WtS_kdvsT$4GWXPK zWA8g$M|Lqd^l{~NWOw84L@m3#pD3-RR}-soU***(b~-7B8(#VA2G4-`dH?BTBgf44 zBL$F=UurZQlYc!3B0g{Oec4OXcMCVawv}%6T5DS5!I+HIc(D@z5%43SDh*NH9~Olb zhTV-Hx|LDr*(ul40!*HuPUXP1WG8hKQoL)2aU z^uOy>sG-*y-8p+0NapTz_0iOenr-TLq@|;!3y3jETYnN2LrkUwoH$ zM-At6bvI~o`xxKrvNtHmLI1od&ULU(5MB8tRB*os%hvNkEe_IX7!iMQ$_L$&LvmS0 zT58iQjJP_{KHj0lMv z#%m%j>)UZr?=!k&hTkyuwqV;owh;g%LZ?@L?DB>8MAoS6dFFa>-&+9_v#!%m^Mgl+*Z6Ba%f*x8G=lD)>HihrGu1E@XW$>s? zxmFs<&Jr=A@cELysnb&Jz)+P0NX{u`j@5JHhN77!{od+N?hes7J>zW4=<2hC!S6Zn zv748pKj@wm7+Txuf%ChA=n#qy4|*PK6xGn%K7W9WZfE!)%pvi55k4-Ux;*z|?`^un zp;yfG`$^K@3Yy^da&^k~G`8P|PNL$^{OGOSy0=>TWqr3&`=N) zMIcVk3jkR@En>hWa`kTL8!gn-TqXGazS(j4)v$?!LwTsDlE95Y7?NB3s{UBaGhDnY zxOk7e4<8C&v3Sprkw)q_tMcdEd}tHR`}rJdCQnOM#xQ??y%~R+NYQT-*VSdJ;tSy` zJ<_D-P>TWiU12+#7#=<}5XYuPZ1?>_)UR94oqRqbeSftz{+Hq|OQ7sJQ3fJ+Ztk>l z{Kr7)V4Uflnpc^Ot*jP0ongP4ihsIqPO)Z)nU;QX{QiCB?W`q;JZcIWw)w2$kx{8g zPAolT04OUj)|(Hl7hiMW?)jmFe^0P=hs$kCPt`jZ!}IYG^HKSi0R}-a8!b{n26wqv zuPA62tc37xGoSwe)U|}yzsS7z17OL#2!{SWm&enCidVFYK>)5i*){Q9b?07)%^{}c zlrujBjwGKZcJw}G`a-h+!vH2w=Uv?*5_f!$%-4>L+6{U|H5Crt-Y?It=~E)e zZzxbO2FteDe)eB`Z$gj-WCNU!zyBg<@nk(GKf6dkb zP`T_=_|iu|mM59lHajB@gmLnznGpH3Y+ zbUiSLc-j7#?ie9>2(c6IC-=oOcOK^R6vpkrd;xE+*Ea9ZHvkfYRMacOxOq5Yiyh-Q77L-QC^Ya5n$vzMr$sI&XZ*a?jrTx4&^+ zpQ{DHw&$fdPHEWQClzZPtvlWUg8XOzW%;#_Rt~|qRY@(4p!HGK(YyZ=^FDYbQ+ExY zn_`rz9gX?HcpdmLCE2UQ~%z zqnkqXl(R#ZdLSwRmZ|CZFI*S;FvpzYT^uvRze3Sj;H zenN^gwZ6!(WTiN8>H}F(ij(bb$fD{YauB#S8i-F!x&V~#@xVdZ)Kdno1N;*)vy~>v zmrdK?OPC>a+b4s6hl_Xf)_*@d6QVa1XWb-psIDN;wlsEpI>v`AIA^=Y8I}C<_VSc| zPrXXwEeB~bF7*MU&6i=AY=J_P4JyRy)c6~(huA9@RBzrLcZv^TC=nuYpoWqj}dJAKt{_j>Z?;F7vt$}OW7MO2IzMUK)7D2i| z1s_y7yhF!4ioxFsnJ;XJAEsp?upLM|uH(M_y-nnmv;{K#ShwfN*A)w#gi zZlN%p`2m|HAuEDc+EU;Ou*`k4ZaNj$F?jLFE&$4vE&Pg2(eVhJm?$ta=2hzp;?z06 zx;3PkN{m~SF>M*o{I^V6CN?enlz)_5V%P3>#SQ@OV%)H593b-?_4p*}vj=8`j%o!>Cv*bIcpl(9OYaKn(gTT1ab6 zO!aZt@~KC8xy936NQ?d6`27^g9`7SsLmFQoYThM2!>L^_Rv3eFj%+kgt|w}pjI9?( zCODI0lRDTuzrL)Xu!^VOSxh@}_Tm2r1C)z|2-w-D#PC8|#SQDJ2Xj$igObM`!HQ*zL^4B@1HMF zA22V5Q_dpqFsavq7U7&qgBIPKp`$L;>eqe_C=1xWmxe>@@E0KEyL$i#oy49(Jj@Y( zZNZ-wMtt9{B9G9o(g$D%<3%~ToGN?mpin)-hFAI8{L#3ZEFok)A-3$B@@A_ zYorL(j=J++u|3o4MQQFpfyAdj?*02%`ocLkh5?`4TrNjR&WX1`+1c4Zz)>E#usoO= zco2T;u@bzQi3S~J{QQV+&vFDwg9c|W+Ap7k@JypL2>sVQm*^VM~ zyZhaFkIencTnEUXqRtWQjUZuop(%@N>#`{j8bPpSWh!a6mThJ$Sm{(M_mY}WIN90@ zi(_Q37OKkw0+F=hkVr_2S&^{65@mh#xH*X(pfoC!?{KpTjI$F0N=pdyuh3AmOWwu% zU(Vsvg-7r}T~eS6JP^k*#~_2_`xwC=WR%q;@f+|L7ieN|aFxj9LD7W1G>E@t0)52= zL1AzQ>BvUQDXjfM6ZW|}{6T&mktgUuyAs)i$ryC~yUyQ#UZ)n@9 zo#f@f5cF>H(6wnc)85T3VnK7On4^Ig}6>AMmM7f$s_)NJjIH-&R##piF_+oCV}b`$_^n zkaO!}Sh$6rP|7fzyRg8L8{Ny^eD>uutUOMtBQ;7yD2tkh!Lxj=IKO{GN;~wG)I)=PEo$^mZlIGWY^MM~UhL6fl5kPgqzdKW&1q;<32IpP7 z?Sro({A{Y%fpPb2_RGcWyVWfjW+F(ANwAZ=T9KwC7s4|BpG#S7|I-2H+Sz9p$(nSI zlA*P9{EUchM_fKv;j^S*wX1GrG=8UvaIs)t$YU8Fxm^;kN;HuD&O7LW2?j;rt09V{ zTUjgxjWm-l-UHK3`m!`xp?&rucwvm!@L`!y_1GU*>mMZ!KKQ*MqQdX}BuyJLJt{Hx z`Q#6s*kj~@T2U(!133YULC1Z1f$q(U=MYwVmK=dL)(vH1M%Ve0?`Dv5%3qg6OjKNI zbn29-D7ey3er{m|3o;i$+1US$#ztO7W40ukEEVbySxy&M3K!awvYTjDcjsc#zK#Lv zls$NE{&s7W&KM*NY%N+FZV~;ONDIWJxKv6sqK)pu0?38!B($2S5_iO2X!Rqo=wgCj zDoL*JXl$xvRCwh4C|K$b8&AuRX~EXEi@GGBil2~7*;Jd@R`;0KJ6fev5A$SZw1wg#S)GtIs}&# zH7{?Lkt5zJrq!cNcqzU4D=?^w0+S>UC_kjLooVx9K{b)V_hy_)%kUKo+W_%*Yw^EnlfsvJ#1W- z76xYzKQdpwf=g@jx|OJnFz{PjTAVC(shC997FCl0Op+{ihVjU7h%QJ3(@%m(ci09F zhLb_p3oZhMF}y4UFtwJ8(dM@K1HPT0N76Jg;Iqh}>}9TS2-#%_#!oG{<@(Nz0=K+6 z%fvaJcp8-56wKnWm1q(mTjNEY(3X*I>v~NSi1~=AHj}SRcbuc>VY1c}5LA9Un5meI zeBMad<7qcf^zp`R&x7xm#6F;C2eG2B%EI;1a*p^jbupY)bW(ylMJ1h5(dvr04Yew8u%3)`vUdIsiBgHEbNh}9S^q>$vV8EnLujXu{U^G>#fWe?=~9KI z2vG>*N{v{chEIf_K7QM)6~YyjwvlM0_IDy&nQSYMQRY(f*D@yjJ8yD82Y*J?Olq8Dx6QM#~;bQ)o#M24m(%ksH|#i zY5Y7(No&1<*am@ypLKU!+C2&75UfZ&6CU-eeF|g0X^H-GSB~fuXB!lMH1)^|cUPTU zJCLp5%~Y9SlQ$;i?_s7H#R6Xtw2n{(9T2|?M%h!dTzKDlcg<7rWALp3Ie0H7GQ(9* zj6lc@gJ7Y)+uH5l#;^K9o`DqAnMP*SvLpBd zG!#OZlAK>!!m^@UEld1bPPhjK-pW&@wB?271IK}(C!wf z*=Don138JX0#vio_1jhWHNGE3&^;0oJCVTk0g%%!*GMHE#u`X@E&+O;sjzJF_vgl9 zWAUl5?mQd8BX#S4hJWJ~xQZT6)@t9n>IEx^xaOI?aKAn}Ec}IHQ2l>&8wy|dt%Y)Z zbzjc8vO9<3pDGZbn#+;j2l(pL00Q-tOM1skeRjUu!bJP51$`(wwfsamG64yk?a@J7 zuN&*SnH*<#dCp;&OzFaZcH0=U3XYc){F>pN{-Lh<;R?~yxshM?Z{qKt`Bn2wrGxQO z1yEozIFTXp&m_$cJ6g2bfm2!0tMk-zvn{RIY5b?wX((N53=5uhl-&G#xf{6sIKB74 z{36@&3ze(>fudQ#G6%iv?}QR2sE|S$-7+%^$BKEbcJ4z{s-0p`Dtnb-@-8%8Fluwb zZSru;ZQ^hlPBmsbOimt%XIL3IWr$FJ4f{QQ)LRlU0?@9BbyW%#(g z1Pky0cw2$K!Oo;C&19~u~ozw5MaC+C;t)Y$KS@hxVQ}$wf z2}=T9tNME#<~iM_3B(Ii`rN}s5rd5VKsR~Gc0df$zokW9rgfeKeP)u56S{35HcEvX zVQNtL(k^eNGNM?Mua{+Mk*(B-vN5t$yb*|f_qkcsq?i$EubM#Quq=JC`{sbU+Z^-8 zTjDAPJGLdgfEB4{JOppiZH%hbX0Ae&^pRQNYwR|Rw)@M4jslBZ^$tQh74LDB=iEcB zw~u3~+Dkd(>pW@W!4mifaVeQ4Sp_e-<|}>;A|truvCO*LZjh~cot=d8l0#YGw6;a? z`xHZP5WL7c$N`WZLVCw>#}jjC@isYZ1OImiIfx%Ch|=%}238U6n1Z5D+BqxwTCtu1 zMb}^Z@P{Skt(9Q!;Mv+ZP~X;2Ghyru@BW4`(j5uveT1ENYz>VH$kTn`8Qe7*&E&c7 zEL%pU8~o>D zC`fzk1so7Y!pFTQSpGF8EGU89_C_x;Lp&mGLuvz`JRd#13`rv)pcEHlzPt*ecmLe4~X7ja^%H zIG_Cq*M<#bKgbOHdrf{>rNdnyQSGZY+Q4LYwVX>h5-iau)tQ>}#Em^LX*55{v7mV8 zY)XsqNZsITwKmPLF^AWhV3&vX1`xc3n7HFhTIc3yAm?UZV!yS6b(2Az}8 zqI;K2__lUt6LH$E3b?R&xvyOx8!^V^?YfF$MsT8t`M766hdQw3Qa!9+PeB+P2MU?p-C+_f1y137 zBGXL(DwF^~M{fx)7wYYQV!-_U;ikiISuVYyZ-dV$N>r>D_pnk43bjk5W!*MDS0p6Do5F4H_Eajt6{gPW>Uu%As{H> zR`*F zcyF;B%vsA*(1z=XUN6Mfbn-h5f&;(aVYYuEYLJ_ z7=q%?h6K;)fm1 zGhG}8;&|_Q75Io?06GoBr zm+2g7Eu$sA>}X9r@MBz`fGoh9$iI)pn~Qw-;EnM2gOV1Xr>2buD2r2soA_c~0xE(BCM}k=&CVnaXTLHF zGzAUE8yu&}v{uh#<<-;3`jGxGuN*yR3_!OAGqBCDRw-qwL;btA2tELua0tA&a;`jA zoUw}#eCh;_0zYps?s^2ctA(tdf%TwsV!bv!tPOpg$G6;Yrc4h;yyi}Z+OUwt|E$OM zih^IJ`9BT%N5T9BGLZ{d^(rT(@yo|90uH%)jk9Mq> zsg^^UpJrQghzJGfOuwjev2~4y(vg|3xJJ4Rw>iZ_^2n&yD=uX*{f zL0z|5+@I~KErWe^{d0w6Wrwm;RE0Gz@7t!i!7A**Glq@+Rk@8QNZqxeN-f}c2ZiYNTt0`RFCP@cBX!Q=eXPYZcoG-$$YVf0EK{9w zH|@se-NM%l%{8e%6Ij?13>Yo7ZC!;D#zR3~rO!md-j#6OS$EIVg*K6BZXdOFXA{f` zKDJT+1F=t1;p3?XA-cKLZrM!+M@(|wWbbniK$X=7E~;Gvt#$r{oqEn6MM38Cdj*F) z?E3fkUESncEXULxJx)}O!wQa5u*HRY*Lv9Vlu-zZ;~?mJxP0FQ?{nYdzwfJ2Sa_Dc z?9Xz(6AczYAsL8Tvm;n6O+>|KR~hoOEGSYje`;V-{RoG@+;b+aoKxDYZ83v#AJ=1S z*0r}DUiuH`>|N1FP4PAvrUd%WDRaiU=U#u=2lt}&#}W*xjG&OdI|+SY_k+* zii{{;MF#dp0&D>j>olRPEc<0hRnq*7_3?#i2Km|n#f2P9lR^hkZAisamiyEm^_ zsYi@MGB4zJ@;trfbOd>Xu|UW0H7@4hQS9DBhR;cc%*q`BWq_vUT0FT{6S!0`Dc$6Fr>B^BEe_k-Nxc9)H-q#59=DWe?$5^eW<6WTt5q9!g?*LCICmwvzL#r zlY}=w015RAd|cCI^`{-c1W_$j*g_FbNMP5cP1a$mUHO`OJm$G+L#9aholy+7359p5M8Zu5cm;?maF(Si!aT;N zxrUQ<^ImU@3}jEnmZ(}Gm{E9dIinQRHeg%QU#P@X?ZZAN?u>mp@77{3Q~I`xhw?9x znj^ZGT=;>}L1_x$Yfw|;KP+z>|9<5k`xQbAG5!KxMf5QjoeW{>Ewi2e?MpClqf;_{ z_W02P9wL)zoUp8eeaFSDqfFATJeyMse(Y+%GxN@vrNRfMH$g#9_~DLp@q)PR9M8UK z>364!hf=~Wf49iW*e>&{2=;%o!nt9!cmg_P{|7G|Em%A%F)O$C2jOQ zejI17PDyrc)2mMR@Q4ikmt5H*WLeXMt6iB93ca^^cOkahu05XUZJ%9e!F%BAXt;Z{ zV<%eni+Ov%+ianvp<$+fF)n3kIv-lomCvStwjMyh`c;^JdhW|fme~NHH##W=-m=I2 ze3hj53bss)}!HZ42Q^aXMezj^FZS*Y%HD^2lUw47A1~3)y?(mIeCA zUpWdN#bq_XC_Lv65vJC|iyKz)bxy2>c&zF@{=!!K`p~gK5Yg{U(>-=s`GeYKF`cPR zYWJ}f&AlHSJ0_PFhy|{RDYu0LwZ2+-4@{hlDDBUG(Y8J`?(aB^l}`%yTF6|qpy8y{ z>%~66bP~ppYvx`L;y~Ilh)Y;csX0SRAi@l)71TZg#S|z>As8S^o%-SMKeK{BfZUv% zCKcZ~ES&lu)i7A}S@(^L0C3D{CopTtN~%P8)>_FWal-gZk&wcSRm$$OE30H7ODqd0 zO=Or}C}DV1g^y`Nt_$VzkjoeE*z`2RanGR)WINrvh5uqi>`dtST*wZX7vA&6CvdYE z(Q;6KLe5&rZVLrzMSeIa3&G>xl-BQTq#cH~HnnCDjzEOp>=$nz15E(^i*bND>(5v2 zgJ0@W(I;cfDj2N7~V9*-+ zqTo(N0e4TTVz$az;mJbx4Y(3qe%;Ju^&5uzn1Z2;mLc&PiMogpTR#yYU{gbQSfJyU zDask=LDqDsT0`f>ROnehW}RYYw(|d%4l^ac4objv7+{sgr(0dx4=DG8nK9FFKQtOk zv_4*b)oFrKI=JK!>RGY|N~*orUrm2{<=VMr&8c8a=EiB(hX2J|KEWw|_rL2<{1y7LHMn zWgNsh9CXTu?A3UFq%{481-MjJ_9Xd-#khl-iA&^V#8)Cx`M27D&!z<}kD07rUG%Git zMO|?FT|d9Akg}YPP7@Y-9SP+m&TVz=@Tg2T4V}uip0Yw6juKI>MvKm1lU5N2&X_)F zQrj%)PvR|FHBuZyYClO#@tci@rk{@X);F`<`eE*ltinPS7>PH0SR?l6cej^ga&TEb z-%h(4$chMVtRC-VFQ|67Nis0LX5p{YvD~Dt(U>GgxPS%9k6=|nYU$48;$nZRswP|p zntNj`5EQtE!!wqlWe&PhQDt%Vi1gIpjapNI;oYimbXG52MWYrUFkBGm;HRwNPHt&R z=wFvU5kwLksED4Ehgxl%aYW{3YkGK>G~a)5&V%f4i)%mkn!q!~&^2(bAk@yXqZ=-UZuU$G`JfAk<}|0y`EK-MA3S?72IHjRLALvHCbv5#3>!M* zJSy&+g*d9Xh}L^~&Q(u$JMRtcx?jzs3^7U8?yvb??i5dH%BX|VnUdPV8?Gk4OJv+Y z!%Fgvm2)@dV0&PN&y=%>`Bm*~9BQ#Jo3wPjy(VS(2x`}_th}7#vd`|$RunwM%flD5 z)&mplgc-vV_2!j}z}L*YYTZ*@+?=w04hIDEJjie(x!<%SKG-%@`6vfiZc|HCPT29^ zjtscAgyFMw9AHlfQ9pL&fude1BG8NU)+NNn5p*IvejdSK43(w6$nu=au_O_d%t%-A z-^!qVE|>LJ;>!C}7+@gM%q6Iyn0|Cm13Ri;OhK^I2F}jy2O0-R9va#MfbN67M49&3 zp8&pqTV5lr9)-J?A8p$%^~x}C&=9IFwf8|xrU>QK&r!zRWcM+mwwuAFL1?V#q?E;) zys&WVa;zn!Z&b^vugq!haS473ra4%?Axv)eMNxNgK0$r?*xjV%;WF!|s*koW8>tOo zzAD9^RQCE%Wl%)BR#FQ*iPYLv4u-(A>&#gW^X4K!M$V7_B6Q`G-_nvM$3L>-*^TGx zya};a1>a;JYyf`&{<-Z0jZEmaKfII(x#+x`D;xc@&T8orQM(@Usx&cOmeH&tpDOk{D?@c)qb1YeG^(1;iIb~Vi&a%mRV7E zT0O1lrllX6U;7ISz0O2$VqvGKanJ>fw?7s5!4vM-TeguOkiGcB>#gJ=cVQ!B@*YFk z<1sJJ%LU-?+5zdI1Z8)C4eEC6H4bmZ0j1*HTHMj;g;i9v)_88b8l9E(XK*19vOC>O+3^bR zudlz{w6{6gHF;6COW}hBXvRTaAm|(LIILLSfXN@>qNa)1Kq^<8AK{bf%meqEj_MKY z*yD`C_9lSIPs>I-J2`H&`)Tjvn>cH%VKrNQ+NrWFKz+C~uC6-@ zu5_NvA?aQ;I*&|`OZ{wxeMDpt)bQ%!0_phBXfHdx*}O7SvjSZU^=LuUTByDil%kA_ zvLnShS#Q6slAJGS{ZLrBv019t-@r7_Wi6{r+Ma z!!nq9O8rYhoV?$EKQ8IG!+y6xUl&8G$L-nPKoSy$K&%~VZr6dtK$(u`8BUA(dsmFX zv|$cf({iLo!1SSqbw4U7jvp+gEK**bk3j^e*@S&z}4Y=~hbCRHXTm@0+fT zNb{rT=d=O99<50B(!hB(?OFe8;W_~Vzz2Xw*yJ6oChbQ>IBRAF;PWlzz|D%c^ky&D zVUBl{`HRR8iNA|bLk4vRz$wINr6a2&mPydYSMHw_@yyhz{CaZxy`gF;HPO9yh`Wd$ z!zASK=gy{8r!E(E3BqOH`TGTS_0!Ig%+%_Z<*n6-?CGDhTddhycd0pzb^livvW(9+ zQ<{k`d14=cKmM<|z+vy8}gR<@AFY<=NqaZ+-+y=TH>4E4zD-S|B&EgNMtXeFDx5jD{xSR(iX#wtvDPGk{Z- z5YP0TmhjuyyxwFcB34Zd6}9B*EbN{_S!%y1h_sZyfubhO85;o?ReP5mT`B)t)UT&8 zDcL@Owd|EF#2$-~J@#ZkiLP2*+p4VEH zd^E%Cai6(opA7X|HDPczy+a#5NNMm}qb<3}Q%oOTK4;ECi7<&QXPfw*^aX>)q>GA! zu#k$Z$Be(%*GIt#At5Btv7^OCcb?4$=VUVS*BFoM>CExHLf;u>rWwvfcQ2P*s%ha> z6OUL3zL=YjnMm7CBs^O_xw%@+!D-Z(hdbEJst@tG{XTWGA5z2VTfRQ>$RBwR4q(-_ zBzMqDFX=u@&T^Mv(yP^!A#P#ytoJDY;ZLe;Wy>mGM<@e;DK79-Nf|V^T9>_>UeoM;F$oXY6a?6+E%u;P4oQ{exLuK(dn*pj;BvLM!?^jdk(2DD8Kici>hw5@0 zZbRSN^(tKfLZIGy@N=X^BkugdA==pTF!us4vqtqwd9URG+K`IU|zfd!G zZDtc2ANWhAa2?ymZJHZB8JYS>c+w*qtVnKjwz)MVy^(Gt)^^s165Yej` zKya>=ulC5dNfkK;c$UtSs|PO$*~>&CzwrI!RL%i!!YL3hERC$KU(zqtAac2`Brlh; zlinQ_CrLuJ(p(&*f<;SfKA#PA%1nl8X)el^z}>yL{e^_S{|R~KPJTfCiM&-?@FhFb zFXE^hEjzUc+S#}Fz_HDf^m&-6cmEzA)#_V-W9tQ;^im zT#eOUrc{l<@tBQe-Sv!Ni$v)2w$`U+H=+WN4C0l@`yoH_7~&k>2*Zfbg#qVPLlk~evsS6~ zhaJi{z!9aa#-pJZgMxqUHuh2+&qUy5amRe)Qh$oW5!foli6z;8NIf(f3&z{%?Rw4p4g%Y?tA2}m9)gAwi*LGKI5=H3tezHQg7Seb6+D4h>k&sLDq`CP>q8kJl z14&DloB5SnG-{;Y(hHEaXJOoD#MMmaXi(L!26(~YD|}wMv5rGh_?^XefmZD%^4$s} zm1((7?s8g@mwq#i80liMKa7Aw7KtNo)TdrEI!I8RT<3kKUVKEg%4PR&{Qa;^qp?5H ze!Knb9}OZA*w4yzIqK-fFor)-zY|W+cRN*)@^#WtQqo7oC~Lu7O6UsB#V!D5N~Hu; z;NxXLZ~WWI|E{+uuoJYGX?r0eQ}hGu)d+-^@`z)$7+l~3xi`mAe&qI)T}19hwq1O* zQ{4OcCT1c6>p&;2PH4Zs?+=`Gr5J#5fXxa`Hi=UzuRhdyQJyo#DmEcvFf202XUtj; zI~ktzWM7VO+ayK1Y>0ZoZM<1V2xzh){Y_}fwsm#2)CqTw&akr3n*-ac zu+A4U+MNn*N2eGeuo`)VFOIV$B5@nPnn8MgD|};V98r2Y zUKNz8eqRXCBpuBEg1Ve1xpj$(rq-uT`4rb8iALmy@YBAri{Qhn3Gj4McYU|)z$u8~ z=T@c_$zAKQ3nmmA;w$@(MzZ-nqjf#};}$7pijQFg$n;g@W6dG%SVjBWkIf1##C&H_ zgzJMBWB~6aMW)-IXjbUEG+O6&Fo@$yIXSHWZR1_0IV4WG4$s9~^tczY2(T6Uj;Jqr zj&0^L7ggqi9VwHmh7>Al)vZ2%e+D>agj9~e%|$K8PevjWd!5)(7xm9Q{Lz0XL^yf0 zD^Nf;g<{pHq2qF+v&nava9!@oGYx3UP65$r-izq;w4hGVC=~&;5$m9*5B@w@`h%Z^ zOxsw5_WpD}QuffMvMnp!lqSe!7p|vyg`eGPkwtxb)2eybX&3%jq-7z5B`7{Zv2a>` z%74nlKU+t7be-<+#KBss)yB!MM%j>Bi2L0+)^}l@Z{N(DF6bS}Wia4IY;**45OA5} zro!X;3!$wfgM3n-hp9H=>T%By;q_gVLU<7UxW0aKQO?eLe(Lh#%3Fc9Xwf?Zk{ub` z5xjRlXt}?6k0Iz;JwdRhzx=V$Y$vtBJ4(PAmuvT5h>$ zX4Fu#4nuO|eH5@#?)OeBT8uYoT6S5gHMP8ZFV`pTeUrRBgnSu{mlu>G_hmrGy5Z_F@}}wTJoZ;)G^nSY1>;z6D)(%dKRo?;{QJ4ArfYqT43@|pyX5*7 zi(t`20IJJ8%`Tqyist!O8fGteD(7iP%?=0->{9*G6afE844C(H1U+!B%NWdRh07?c~3DU9N zt6VTbl%YCWB621x$?1cE29`*WfVv_^h6(9Pmsv*3i>l<#ZF8~C(+tGWlpO;(dXRnh z;f?K&E_fwwI#UeaQeQ(|lQ!OR5819!l#t2J*!8&oWdTt7Hl{|=xV!z2Alm=cKI|go z)2EsS5n6Dwr z<&IRvxP5==w0>G68mc%Bw!MBdjmj*Vw;GKPol^iZfM*^XYzcdix8v_=s5SOFo^E-!XFmbw)*l*uz@YZZA4Lj# zyJSh3wq%`lBEub}*ej}5Tinq`<&iYM*cSdUGq(ZmbY3JO!QUF=Fb&^XI2{+Y z6`vR|1mU|$79lkA5}d-_0ok?7ig(bD%(DP}`zn5izqIA9;8c`OACFburWzEsuXqB; zB-XG?WiMf}3ieC1riEhGmyRCc|n2iIfC)nv7Ss|v?4VHptj zLj7ZFr;>0JQ>o&V8h1<_U(&!NUoR}CM>P;NrgPWIhQEj>a;Yt>{(*B z%Evps8jMK4-k;c4 zNO3kq6?kla{i8Xeu*z{fZynavuL*y#b7m{|3vpk6F&>!$2coFJ?Dq!&x58#zb*$oD zzlv=97Bxdy5hvl_&E-l(L<5;Cw;bSv2njjdh+HM-K_FO@H8KhsCUDHbL3+ zKiCrHl>$X-ON+KEkF^eA8&x|B(JK57PdP~yf767^TP%%#o{o&+sjjfGTvPJJ5(B>b z+c)e-ZeaI~Ygs=%p~s8L;~cr<0L$Ii+F=fr%)NZh{XP4r$>?2HtWLipMZGQ*&pRjOBAjw_AC;+@y){H7PfZ(_AslC6 zo4zl1VrDLN&`3@@M051yy+-2nH~RfJT5%Fql*xwx5w3NCQ*-6D!~N`J*{0j2q~N0f z-$PU*62eD12>!|wTW8-9sP)lPGmLc*OH@eOqe$rD)%MoJ(T zrtMOmQ!l)W+r3;iC#-zXkDHbH4FiJ#0R3p`dNC^DSuF^#KwVGT5#{(?+FYf?*cw;- zP&Q@^A}=Su(mK&LhzQbVf=`gL=<{T#Iq-loiFYi;8d89dg+IyYA7 zrq-~!krQP9HTh=CHka$gycvSICrKxB9X6`jF$tf(MECRfL2%XUpv=q!`_{JGQE9|1 z4=Ac?j9C(k>>~F2p%7)yL{}4P=COMb>n-RvGrpE{fN8 zEp8XFQ+v|*W>+*eGI?4Qv-;>m%G4Zmc$K<5NB0fy2~Y(k8#?G(=G{+_BjPWg__wg@ zs--&iCkfn*ib6M=KUFr(vs;hcg2xZJjy#Lv<3bVtEdMT-KJqe2V;sSE-nr-+F+k1Z zEiG4j_j{Ow0@NJm=Y5*Fn4KI5=|aK&R+Fijmi$#UDDB`@V1ml~BF)O^c`PQcS0wdW zzuk?3wk4SmMUq-QPxdGIt2S{>n_T(SfKLW`n09cwc|KF98ToSMY2U)4U@leIm*M~R z!r-%TJ)&_$1X#WfgY&V7!ZN(N>hsEm1h_Is zLwyYWU;nE!rSMK{NLwm5oXhK|C(gJwU+^rAe0hZhwJ$+E#QU34<6a;E7DnNF!0Sp} zsrG^e0G>by8@&M=2I>#USIeEg*Vq`X6AgerS(4jk$&xltR%JZeRCm$OA^xh<3-$}I z==)qF{Gk)UaOF`r+b}1Mz$_blJ=ru+!bDxLtWO9wJHe+5y$i>k*gh=!<0L^e+<;KL zQR37J6}S>qkC@4lb8K?1@?0;jM2c$wC?7kCr&ohlR<0JtGUK_=5@!<}EPOQs1^rtU zi$0d0n;QdcTuMGW&Wjr)^Bh}R3O~}%+r);OlbdC-U653D%?l094!ATN+D6O7z!q<} zh#@$uI^+Xf=q-uyEmZS-qHhix`lC9*il7R3Kg^-i zvUrnw6*PQ&?AH`+KSuwQ31crfPDlCPP$0rCDE|473Ww)bb9cinXMhB>9h!C(r^ngk zb-R)(ex&}JV)u3<$~Ur$<7CjGXl``mY~x6az{hqK%KPWr=H@SgcUb?grKTTs_=sE` zd8uXg;IO=6#Qpm6Uf?x3>N&EFKp-0R7)bOtWEDLY<=;eeNPD{Fqa8yRNh~fdRrA8s>cD@yI&1LOsMV`fs_aE z1%EZIRG@8m3RwV}(P!f?n+nmwzPyCYN&qj-5@IYYzQx zzE=B1#9W0@sG<#i`+$FK7Wb|G)HeHpd&<`4OUk5$A4EwP%F-=ka(Wn^ zJ2OeDU#U;mfvOsOgIUTLbQc`}<8e|5R=Ld3!|V>!{qM?v1Wl>sPZbZfiVlgJw3;hLfJz zII~Zhp{ZgSlVkdsO)Mu>`4R&B2`Gs+NiKaoxRNWFyM zx)!`0=jrpNJ*+PU`rG5FYusxr3jGY~IUagwM6Aq3^%S7+)}rZ=b{rs2HX(jcqmv__ z5l6$LzU+*OiU@c!0(C*fBt{Un0qgSmcunRMpWV=f{yX-u3#0zAP;QiEIo~8DPdpfgTdiv4W5i9by>eYg~61T^hf>B z{bEPY?KfivUE!e*81jmN6KPwLdEIk%4R;e>*2(tWkW0`0`<4W}OeSZ@hie&l8fx%J zXoO4RH(hIRqgD>`)H?Xeq1}zWHZ>ten}PJekQaAFP?M~K7ITet)VWx?`zvg|ZpN_H z+vXI#-f-+2^aeE}`fxdL>>~2q2*lwcdJ-)=BW8~T!pJP#mmAMFU92WY4Y(juMZ(&$*cn>(nBv$}}k%6h+h|LNJ+`HOS= z>Fi*_=wl8N&AZ5u{7cg65gmFAz2p)#_gm-7-4;#y#z{k3F3fH(%%g+ z!5fAwK|~afkUp+2roIPt;Xejf@b@jAELMb9EY@vvEq=azYZlik*HB}|+$vyIM^8pz zA-i;mFXQ3`J|Un=bF=U;5eh3;NfgnIZ2y3wWck)@i`7f)6zkIe*2f4Bb1!b_QcOsb zXUqKcF{>!i$qK+k-h>-O2S0UcM%)5BPHozybo3EKmv&9%k1x76`?Croom^L`8~BU$ zo^a^>QR6Tw!m$Zw10JV|%)Y@hz(UNGM;HcZkFqfJNXK~wS*47sQ@EOy1!fIInpC_3 zvi4xT-6JPhXjJ55BX^q{yXTeCn8mn%s_e4gOpwLR)BSOBP90fuU@rNbLJiuxVY-Fu ze0r@O=k9QE)C|a{_fhu)3J3#=auZt;9k2eF!`)%QUwm`cZfC+&vz4oE0kwkeV*I4( zRfJnB^NKAOx8eRDy59OP$}igAo*7b7M5J4gQo2(qrMpu)hVC31lZQ*Ltt(DkXCJtWqX;S6fQ23l~6X|NRJT;hJpR67oU&`ZrJ1 zmvRYz-6bj&{``DN<7t3@ye#(+f^ncovi5m`XoKH)S#SklYWQ@YqLbkFvx4cx{!wB; z9O^wGOD0@!spkis$r;nJs zRO7r3!+(W+at6J{QqLp>tJr{E$J2D%0%?nIjBj+5FpoT+a--~>IHEv?5B#oYPRqZ| z%CU}?H|73sVuF943~2`raAVbq zK|WkYT}YVb#>bWYR*jGA#*rmwLRk{y_9gJ|Fp2w&B}bunm)>uK3D_W)s%9qYTh+8p zBqNpm0n|TH%17`QiuqMdm~lQo@8kU^#?&i!@s`c1MA*E+2>eqe(NyK8XJP~MRO?yN zF2=#?@Pc?%{Ez1kbcJo4FFgGo6}(C3pqt0csZk~Ip|^@xZK76ny?&=Q1GTJb_IHBy z3q)+3b%r)p#q2P@ol~p&-57h;#1J!`b3JefbWMo-@?JdXd?{b)ObD!qzkgN?ZaW_% zFmpQnxyjtvwPyMHi&r{9*9YH`32=Ow8gayV>|B;~w3h&oqH6!SO zGi;0}o*?Lk~N z8pA@w(98?MvzK1yLWGkVyiAvnZyBik55Y^Rs(n>+cAI~lb#H1gK}5%fVfxdeLuzpL zo>o_A$qI}5EU$*OA_Z;4b}Az2U-nwPV_mXj+mq;~CHyjLpe<6GBEYM zrKY*WrYPff;D;h_W|5$w0!<)vHT!0op#0LQEWCI=VL;2w!&Ge8|Gx108#yYtPifhLz12t_nnvjpd0 zv+|=S(-%++V%Ly4!J=xK?~>{5nx4tT^jAkB9Bk}NE~0xPU!HE=w=4>%XGy9bJNjR5-u*W zY`KS$;(D+BnE5(qLb5gA=Ay6WVeVN1w-Kf@&CI*il%En?(#N|bU_+@IHXt!EVN|R~ zg*QU+=dSAZ$F76WI4R{wmWYY%^)o<+Ch4I+F3D6M7l5t!Xu6-sWl`7JG%ob#Yw5}J zRG8!N(XC2iv%XiOJ+)@`?`9F^Cw7hY^gxXX!RETU8MVRMla}0$z73X}#0x}=B36Yo z8|(yH_PQ04_Iy@7eSejfKJnW!=X#1BB7)!B&TJbUFLyB9NNn(5Cv3w;x19DG^WbvG z&}CY(DCR%iR;JsE6*~-eGpjg?fR>8aXKi0BS$xTj+7|w67P>F&^eQQnga5y@GZ}&@ z+1dJf;9Hp{aQR;k6v{YsE{6sFPIrbU1a_q(gxj?G2-)j%pKd^rY9v{p^@LcQyOSr6 zrpX@G=+x9{a|nx6+8Fh#yPgb%f4}eMe@68Hm)m496K=2psTHpkE{-j_)L*wxzmG?f z1HCW(8*Sl{NgqdAdAV<3m21>FEGwGwF=OG|_K&C{RJeJ;c zMF!~0yzDenP*=ZXc*WO!wr)RJ&QoK=Aa;@1%s4aSF7v_f!XGuw>!u>7);3}7YQ+|X zQ^r{H0{g4E50UT%#C__$vp=8N>DrJ|B;27;`c0YD(+axd z+*M~oqpu#iQPlWd+Ih7XB;Rx4h#7B7W3zuTK;>)7S8fiRiz-W+>t z1Q<-hR2(v*dH%Q&&u{J0P9^}}MJoJ% z2x>^f(aIPd;(X-DYBK+X9T84#A^_4w66E6P|I71ZmmYLGPU=DgUUm^Wm6#TLdfu%L zy(ZhV|1&}ys~JaP-ZD{T0IHh}Kl={$naEPkbLScsnazCi@JVOUP%60}4=>c&boe4F zz77>U`wsxNpCkH^#G<2XcT|qVb=eE-j$nMLA4qhcPdzr>>1(msZD#dlwc)Yn{nikU ziw3Y&ul8`h#cAff{dZSYw273yiI^BR7(PdnwOlC9Sng|lJkk6V;;BC8G11~|kzHl= ze%Dj}m-;b}ir*M{T|uA0uuJiP$jg&$gwXRL4a$M;_ye&aC){>P#~2`J(r&AU%U@%` z?7W7b!x~4(MZ95q>*1~@;8$DsE_U~5SK4CE@nxBM-Lz{a+1$6?-|u0Pbxy2Cd4%c8 z)F>t1I)>!tJ`|gz#1C`V%?#~rDcTJsB88yYsjaPlP9Zkg5^>q}T}_cVcS|IBty+q> z?ur$`oYc5IqYbf^vs!M*8xZ78k(GviebgBc2y^d1x-kI%dJ(o1o2(DK6XrK#;La%X z=`amy=e22k(4QR$ooD`)z+oP}(I#zF$a$ITkC+k9-yVGfNSnK-x_m|-Ymi&e91OU) z9Hh*sGXGJgumN1s=3{4jitEOsR>WH5Mc?M84ny1qA?zfvga3cWz@ZQOKa6}jp7CG$ zzp^ZUL#zxz|ARREv%+0)EQ{DF9AEuE#m2E-+Al8H(brHnD9Aua>9Z;>=iKS946}Tb zQMCEn`&>EE;@ug8%+B8T%t$q-hB_5#bArWWtWk?m5o8H2GT(}r{bzq4zj_1)mmgta zuhOgbdHZ;5E?oJ`Oe#p7`8ZcaySAuwG!wtZzywma359}6j{a+#d%Vaq^3P)$*f+T@ zbBGV{cqoVRq?Yck&6VUnoJHhrcB6%Dqf6eI5A$iflbmL<@qbf4t><9 zc8BdnVc9@<4oK%*uyDK?nFH!v!)~nU6n$If{uCm$wlRFnR&hl)*`96I=OixAJ_~Z) zlyK^Ep5>}d9k@v0jkT-HAcn|W_O^5H(z|u3F!RZ7;;19Pc&#y*cbR^O{ZX6B?!EZy~ zrj7Jb&B=T?%e>$5g)SFsguUg;-Pa%RxcCQ(p2f>9f6|yUV5;v-qp?X!myb@P8lBZS zuQ~l-M3F1=Wz_{`T}Rx$)od3*Xl)lsYzOC}3JBe#z1G4CW?<{02C}yV4VCr^W?lC# zfli8P`MwO9K+a0JVqZBTE)E@6@LoJ(qCHtyp49Jqi+SKYEw1Q9{tpci)imJWj^y;w zkIDrmR3|L5y?m)N+{+`rX!pP>kDI|r5B_}XIJyPm0yt(rc!S4rE zJKDptzm*AKp<-FSCpC`_a+n0%5L15PFuX~!juc4rD}nEjd{In$jdsA9r@mA#Ib zy;dFVHO(%F2&u^derd`ZJ~^ImGrVpmOA>91OB9%F^Gl3_FWo`dO5HGEBfG82;&vaW ze=j`e6m_pMJLX_<;E&uY0$W9Ut|(L+<5Q!Qt$bcTZi(~yKhWpZEWC{_2c7g(XZ${-Ih2Qnp^TPskm;_^r{J_DQ< zR!0DApo=AZasT0PmE~sG8O5l@?IS)7#K2giLG>NTgcJ1@IoSrBIp&0b7e};*&29Ar z0Jmc*tqrtb$$fjy2FWtpaqkv_d7`kz)FzFcAEN&?S@X^kaOE)jJ7YEK%`)f2u;&Yd za=Y$ytj;{(XrVNK?!W4x-Dcc-Ay0CO5#;9lFfFUdJe372%^L%{k-NkHnf-By!FvvL zC;$5#5Eu7D8Qp{({CPWUIQA7anpoK)J3ibIEPy@N^j~rX92Ius;|KKRF>g_Hu?o+k zuO0ngD^7%4b!}GgR}XGm@EQrJ_!ZimxR7}Jjc%ii9Pvb>@#5`$c1Dw2>Fnm9`s(O5 zSE)&S?cqjf$wl}3tg-nZRO}hK6KAZ#oHsVR7$d;!D1xbk@H12SUrt#9D5vY#$-%g)(7-&e(-ys7Mrk{qs&uB=i$x6d5uY7Zfjuaq6Z)ksQh! z7@o7jyE{zWGkUa}5)K{TVyw^%`tg}y-z4*PrSQB4q`i!?&Zg2^<2DMcrTuoIH&cv( zXq2%rc}A1b<5;Q9Tt4;Unf|Ho5k$GWy7s!#3ahmqA`Bu!PHuCbPKO|N7NcM-n}Zi? zi7An82gr1{*1Pf^6mg^m80p+-^q{cH*GFlQ!2j4MF+B2R;us}5VqbeGbVy=;U`$5> zs?3X#2|(wkR5XaksRIjUZ5m~_Pt*E!u3@{}Ac#J-6l?h)?u4q(IV+|CQ@K@seW zVY>@h4q)Hf3c`gtTh71`z`BOAwP@;j#59h&qoz@qr3*swm{&M&CQJS(A+RlZgJ`Xd z-YyzaHjf!JxDl}mfDVdC-H9sUwp!BKy!5hc#B6%O@39;DW`ixiVc!ewe+gS%R0(r5GU-1mz3T5by>tFzDCX95EZc z@a|Y7wO*>q+p1_-CT4#LW5f6WYJz*fBucU{Tov7lth6nO3W-mHx2AORQn-J=1ny(c z*9(hnH|O~z`~u&=b4bpGq|l>*V%6&v4JJRPj?u4fi6UQlyEF2jLe7){70tBG45>L~ zySqjtfFV3Ffp7N+BaZ-Ywx<@zyOcNcIo1Qmo^Q(_Yy@wBG)8&@qkPy-QB*rd`Fq#Q zn}-gSQm2%Z$iN-daKd&6`~BjuVf?1cLU7KXgb^;6t_Z8S_tQ9`R$*EPHwu zkFnNzTv!-aV25^Ip%2RF_v<$PnB z?0@0Ulq!vPcS&eXjb%BA65|RXOCLD>$f`__{72&wGzcP-E%`Yz3WxzL{IkTL)EY!> z$^PT>{-EvuBL_6xPR(gx6;@B6G+ZNOS~m2N9^i|cQ2C=3BVf0W+;-mfFnKXFh4${E z+M6{uM|oQ6%-=l#IO~ym$v`{Dhqk4fj)g0n{ixM@4x=tSF@bdJVxtd|M!7%bW`Eoz zDQw+Ni>Alq>U=UNTvF6-=&?0t1)Qh#36esDO+3@sIZmo6oEBz3Il)IcceAu@gn!}(psY9V38HMtn2;stb;l2kA{Wo}>&Dg81O=9}Z>>tT=YPay%4UwuJv zImG}&?dNUo=XRRK9g%21^3sviD)W$h9nMT$;}7ech!ogzP2kO_d;=~afC=`% zsb-15&zRe1V(JF=CnCa@yA9Lf_|E;8DnoXIbD6f83Nu+} zKj@jY`(9S_*x8u#gmd<6?j)_)X0FvwH)|=**T6^fhE#d}L>Hj2Z%C8hqP}~J-FBAZ zjd;x6eQpqr(`pTz+T(&jBm^q9D#zn0ZS9eTc(QrQen=6G`67H{ztRu5mN*68 z5Js5m8wO|j(lhtMPZD=QRl6$2ll6UJE*h_z|NV+P=wCVWen~x=yX4idb>(uT*}MrF z;sd!gBn*W|`oH9;f`b?yr#6O_??QWpch7>s>(4voo8EiqXhm?I9t)>EdvCMoah=X@ z*J;d>cRqLQH~!rM(|%$f6J1}{^x*|+YZgBj1usSYUHUtn z`u_0nS(&=SjxKhhQ8!U1BLMKbXZHSx%{*GRueX1J^fxgrJrA*kFF}c%xT+xP{(>-9 z#};^x+qR)-dAzG7C5?M2+4| z(SyUx3}UfQAqcOsZJ2q404*Sl6DUp!kd|ZuIi!7J9(2!q8z!eRKbz+6C;NNxdJJ`f zk?dYgx^&cm=$bM#-vWQW(N|pLC%{+S{NqY7|F{_PLB^~#&tEMP&_N4>!)54z93vY| z?<gPYviLvCR`9K?h%y8q6$k?+`MV287II>{H9mn>Ga6dsaYb40M%PdMNYB&zVaI zzP3|Wl*namw=jo;=`_gd;ZP?ru|S`>f{9XhJPKC)U9fSJXk_=h$>qR8Q~0?BsbAn% z!BRaXmyc*Q9NccOMkGwi531xGEXP7ybyKI;Ua zic+N9`k^%j2_%Qxlgpq9>7<%mh!~ff>&$q&Upg)F)#X}Z@A}_>w?9;@g%O1Hj>OOE2zv9=gKM}k#Xm`yo+Xz;<3yt&BILcclL1kh)9>2?!!#b_f*C*QbS29Fm~{#A#*>f^nvn72>pM>iqd=eU%Pkl1_+o z9rJ@vhq6A9tV#Yjf>;4KXl#{+N-Lkc`CS(~i?Uwss!O3g?XE}ug|60gfAmyO^J9)wgKR*>IJ^IN&jR`$*$}ClUvq7K(lG#Sa3w@NB&omC}I(nTxDGnWodYCq}&7E=?<(>TgN@O=P%i%wJg{wPKq} zzc#Dw(e~NCZdlLyBZNe_M%Ps9qJu&1-S%aB1qaXk=o_9~-}lc)53j zp+9g!(!t?&Z%P#bvT+(%XV(CkZ=J5Abw(DH{4E(LO_a`L@X~;ZZ zK`7wO3^v}`wOoJAUVn2C57r`hLU!p@DTxm5bK8i>)M4J1^Yb97i4hCi9fx`oJLu-J zo&vr;V@?IS`3UY8Ct(G^5tXE33-_nwh{%ixd%x=pXt5}qaeDAfSmqD>FRs7kRs4HP zr2nEoZX2Ha%Lt`Nazj^y2n0GPi5=sgKNlzgJFz>DqX;Obln-{X!*WY;Jd?o+MzP`f zInik_y>H7H*=+xMT!io3V7sT>ffm`l-(*(5l#}%U)hr|YgjI3w(VU87)G@m4Sh!dX z_W;V}?k5PiLB9h2d3hLD?y36V1D}j}w+cUJalp8Xhtvn!!k{TCN5K`Q{kqxS`dv`aJ&iQWj48lrQF5a)v2J39I!r;0y!-LjZ$~o>(}*3Y_iq}TWJ9M0~!vxUt3-qS{B}=?{{woSYe^z!pE4+B5Hr$ zw^|GC6)pv9m(vy_2kZ+H&Tm*E!Waye2F^JGAaZ-zs?kZeXpzOE729pn7yW4N@%*2S zL~C#wCLKA9@p32sR7io(6#l#C*R2}e@;XCN4&brbo_oY-E2R-X7BjvA=Unpt4w5-X zZdQEDVQs(o(uM%+pG0y_)F5g_!OBiC<(>S2sP9E;2D3*>s63%wUvb{^iW#fWb56~p zaxZ5Rqf01;&!9ZnMjZEum1qbyNY0V%0dcUL zuJit!)3qX?mE5WNM-37Xzi2W{hEx2)Ff+h-wxe@oz4TpOoXS1!ssTal%V-;>o@ZBT ztADa9)SgW_)Q7Xg?S-@ltKhO5WZ?MZ0J!KnER z#I#@Mq6M`1W9Q7FD`|=E5x9?bG3`QFXoFPmF z8FRGXgZt95qk9G5TS5|JuY=-HoT;AI!dW8-d%0{Ek&V)vKP0s5vvxhz;iJ5F+E6+r zCb{%ol>;DTv*UGq=Symvzu7~R|St@T)M;4 z*s?`r2%dr|aSrpkCM&DYpWiuEOz+T{J|PHA7hRpjh2}l28|~iYp_7-0HN$f^QPPfYW?PrcFd+<65lz ztTCsNiN#5*v()Z!nA*GpAZMKHb$y+BvOLMUMaD)lSMusiTn5zOl4_c2al~eL8Cry` z;4Y?{n$8my@pkZz{k}QIsaRIm;>-d0we~>nNy0m#Ig+nxZ&*D}20Bs4kdE+}#}lCw z2w}>BOXU5!y__paXCK6i2!}`kJ(H7f%Et^jQ!-89CF7`VeTh378e>jXK^zY7)#4;> zoISAsxWaVpTKc0!pFLp5hA-(09ubzY)kE?}d0`ak3!QDF18WC)ZzC;4~P!Q?1beim5_jvtBO{G=k zc9%@+l`up2k~xdE&AI@=>LSjXILN&+0c-#h0l@e3t5g@sr=pki zZ6ud~e~Qmm`|_as1g{J~a(hNTd3Ar}hf>U4i#VEedkykC$)Nm(i8^Ot zh{F5yK6R{YHoFTJa$%_}_`;R{QRU_&t*;uyB^bqB!Alh&oWa{1_BWo0MqDZXOW!Ma zrFc9Ou!`17WbM`~P56F;hM%{owYC@4Xe=`GZ4@vI^E90nroFGhjaYO70z~ptMvU>| zuBQ=Yf6@1rT{*ugo=QV-OA={?{6zp@2{6r8R)+RAy_S-T@U-rXBVoZXcJg2y2?%2pszmCPO zxm_KovM>C_FC=SMZIWt5)vf$_b-~Dg5P}?WlwJKc!b;Y`i$T+{$KMwvGa0Z841msX zH#nneEJM6fpZTnQQ=<{(^?jZY+yV`zp`AlYb2*F6=gD;MZ{#&vj0;_>v@AX6b!}}l zI@Qhgbu-qOY>Ho!b&a^mWh#mq%XlL@|5yv~V3&NrB{4#G6&zbRy{#;WnJNYy`0Dy- zhBwr8o}f`(1Cqh_`WZZGSDr^ofRj*8M;p(14t&lvVf>^Z@orp9Hah@)s(EKV zW*~b3OV9hX(G8(CTl(#|eS(-ND%u!YTCTlz5FdFSpC+Q*X8HKh^(AAKXj>H{*G2Wt zyS6*+>}Nw$Egog3v<2G6YoXONsZZBQigNB-7-G`FZ)2-ds!(B5XW-MxH-VUeG@D&T zOyyr+HZt0z-a=FH14W`K*Om)0?mM}mX$LDag|g&)!TNurOhli0zI#8`n~j7K-X{=z z13&X6nZWJ_Wo=8lF9m?hc3%oB=o;4-W!NczZI?RR=TXeJ@+}sY`|gVAHue!JF|ib( zv70p%;8Q^p8C%5wtE)@OBqPJ+GWijk$$Ds|6PAC^k6Qwqr)Kpkn8=SAg#Lj1!7=^k zzxQ~qxCfeQge!k`!M34G$b7E>i)>hYl*99bdAZ_z*ntKkf4k23tn}vkR3Q8ghztSj z>)Yoj63#CWoEi)DRgtWE+ZTl-93QxsQ}oBAcCip2vp4#x#7`WSd79`aUB+ZPZz5XPD7&w-c*WmTOTYO}n^4zqb|h=_AwAqra)x0@ z+jv=*SKGC?M?-(EuPL%kgUVl;z;1yl0hJBui5f%7?{T6o6yWtJb@UcTXKs?cTQFM3 zPtb_zQZU9j@~)Rd5k8QY`eVhfY!Lfr6Gior!d#}GLI%(H^aW>6djWV!HSJBp_7j41 zN4TbzpRcI%MQflX2q$3CJa@fDmK+sEf&f+8N>uCq!;*k>(p7nJ?V*l$kMnMxjOs^@{?CH1mBiGdUA-pk+oJq$gM2tJWu81(|w zrix2b{N|PaPAi*KF2X$;yPtkCS)k>LL$F)9@ra&7G32A6eJ}OZx9Sai8|jGk$hYzt zB|N>(>Z@e9eAEIF*$Be9xSoiokLW`Nhts5jwmByq%^)AH%A7~$)e*3YXd-f#v}q_W z?sVl#BnMvZOGh_vgQv_jI5H%$va;l?;T08q@3>C>Yux*N;f1!}Y>QI2R`y*oG!xAd zIN91x&{&QsO+5en>t`6w{BwxaC^%qXN_Q*$K&0slT)*k_v>$n!NroOjms4fb4epfK zZ&TaSzX##Ghy%3vcID^j3Lkq9#xw_DyTUX3QK5k%6m`HR|73HitJv3f^Q_Tq&F5Kw zcZ>5^Lzks~$hfw?mGgqdayrH#(w{mEJyOa1dP2gvCFPFtN;SC?QH9ASVw-y80}}zj z_d7wfc$`8EEOz$J;x6tH9q|CgX%*lNKjubL+T^-b7LSkJuKKb@^89KU%W9T%h3K&q zN;t*om8}DmW;7ltw{_K_oa_?2{3s*MYr_>A*GMYucM-_AK+vp-nzGjdh8UkB&`?htKx4A@=OOZ$BfEHW$)I&;PEXcui3fZyipD^5BX$8_q5~~cEN1xw&-a^Q_|5A2}tc89U zD!ki@C7ngW;WH|hduW^-Q)=yH(q$DpbslyU${kZsdwQ;yZWWnzZ?dX<7Js21%vM7i z=+`4ee|wjr^E64|>GyD*1a0URdFzNp@DL=Rt~FSuzAAY@__gtQHJvs8jPKo$_TU51 zQW}p!9lqcMsp*tBUB)REXDJqy6=T+`+7?rI2v?Me9+8sJbI0Qc^UJY za`9blv{`=|D*v!zXp@v-yG%&A^t5cKmH*XbJueP)u2W{DM_E{Q*4ulZV_aiL7HvE-zZOe|JuPb*$SKXuDcqV*@)>E`%PP zU_+a$J@?96Sz2Q8pp1|Ds+BsCsgi{YLq@lI7V?V5iI^Qtl+&J-b&dAJy?5D z40yusbRksS*(X%83|NTk-CWvqmSLgoIvAia@2Xf%nb)GlE)hxp(bE?{L9)DaiogJ|3u)g6TLp(y%WWU{^#{NoSfoWq|5v)aSZ1!s~!B6 zg+9gW_O1Z#eut=R;b)zJ$}jFKSpSiW+%EeG+pf6n5gs_5K|24)HF4XqRQ3tgEDfZ# zo`E$Vs^_p?-_)bQwvj2}DTw*wpkgy$8IQ6efJp2uQsQCG&mS9ZBiU{T-4}Lp#~ERU zU0kcvEqUJfNpxRi43%^~=-`5%jtjh)KyCd2^VK)!2Tsp;^4mpmq??F7IM;RasD_|J zhxB3-Pno?pA$etWwM1>#<$esA5?UrcF`C|t`yhVl=jl`#6`ww5nEwY_(_$JG$8ce)3mhO#($He^pS7sw` zZsM~^pd0vP4ar;3^`%0+p2g-dAz2sNs-9>cTcTIk#%Pc=zmdIC7bC3BK4NZfb-Z^m z`p$RssLenozFS}z_cH11N2uGZ;0UL`gH&UsI+tJno;5rE_X->_ev`rzvQo5?dsv+d zIEksozYE80;$Q<>%)8&#^8Pj$eE+HD-3eNU=z5)N&$;%uZ^J2BchzOhI^`Cf7C%Re zekyeJ(A%FLN0*AXozqOpxnz>)&H85Z?K4@S z8w(tF2na3C$yu^)om}?3I+Mk~#O%|WAYaMdVMbKdG-UWD!bUz@mev)Lkj`38qSH;X z|2kdc#smfICyB(r5jNk`K+I1LgkVar;%zs=Ht5n4W~*4GPefR&7SmDRRIcb_YjI1f zI`~Q@;5ge+gU^ zxej5jM0E%?h{n^VS0oSM6XU^o1K{CblNbbc?u7L50B&Y+A?z;R19F0&cEzS$p(r)Y zgb;8}+q|DhUdG4q!|(2$B8y2kLDtpsdR=LxslYM(Q&&yo?Cpxzxr2YZ-AJ;LqI)^d zJe2lW`F_Wc*IQ^V-l;wX)W%Uq!woys9vn zW+_bAWtnI-y4gDIR8BXgUhvgNBU*j$?aEO)Pt$iB=C;NoHE;i80PRnzBG;};ePOF~ z^f-QU$Y-XwJ7&pe!(?c00p&+LS)(9Q%8K}wG7H?3Vd|^Dt_6vZT%wjYNAY;G# zr7?WX{qJ=lDYs(n0Uy&Pb7;fPA^i4yXnt10lZ>k@UW{e15G)f z`5@q#vYXuzGtDNHujFv%apdcuqi*0;= zAI4++E|QF&qrsB>I*OJ-wPpX;aytT2QUyc2?_68o`LP&_-~%ozZ~{r$dfCX(#|Xby zMAagGbmq`}-;B}!3b2+6Q?BU9NdQ7WEO5-i%*g2Isy@q4MX1m|N7Q0{xWiH8oLRKS zgU?$j&!2s70`pN>@R#z8(=W_)1>kf8Uxxyp04CuX!v2>)#w5z0r^FN6w4fi&og9O= zNJd|pb14!gvC-*!Ww@}AN`OCbDQA`^*6JI}TgI>#p3x%R9+m)B0Iz%js5>L!Q_dUr z0%4l5hOgdJvw0COm!!00wB6(kJxIz|IYJLDKf|}R7*v8OkP@rIK-HZy_5BF);?p~Z%!w9!oqhQZl~ERgCFuQMd<>B53c#p zq3YRic5gSwiC0jxhSwkIzTBQ=szZDC%TGH(GUhrrHs3u@PRq^UVlQW@vZ!}8aYHMc zs#k+YG%Ipdl&dO_k^d#(P^Gv0`~e{n6^C9Nn|uPH@| zOExZR63h!d@l^_rv@iv;*Uz*U2Lu6fkagjeQh#|T9vsi>ciWpp@L z)eyGBcqg&*jZ%y%-qm>Bn5!GQ1rN=Z#>=hFIy#WV{GYexR)0)r_6C+x*%`u-?waj) zFpQY*TxJ)=q_gn5Bj&$MiY^x8CQ3Ke_TNewwkcQT0-7s9AP6be7E;OY17_dbF2j@Y zSV}xS@z*#tpnh^Cf(8W1X|;fo^oSL5I#WZ#Hp$Rr%%pQ6) z3&X8JjAUQA*|aV0ROUd7WAxs?9R$Mju``k8vKF~Uh`;dvuKWSo=a&ym`jKA69J5;i zQt)Q_GU1l!Py6F6SU?uxLpOQ1n@Ir~3QYAX##$}MRFK2j zl9j(-X0njB5?DyobF(8e#$(ZI>yOwaSJSZ-Rgb>UsMm}b5FKnPdEujgBz!MyOF!7h z8LiJh!9d&V;0!S_#`TE-oUk{4)9w0HMo%BCK8XN>$q(Ii_OCCEAj7_ zlaABq#gP+obrN)t7vRc5AjXLAwd?*9z09Pa?hWxi3ZBp4!>(zkWZ$Cx9IIKI$CdnXfnvw1(wtvPHPJVC3zDq6Q+HHh1}?Cp zPkpwdOF8dPrd4x3x*BC)M_fzE^I>C+yrmG$&xo>;c$7;$p_}MJ_@y?#>ZUQ`i7%jS zldX$aU@{S93b&@{p4R|{2R-4pi~3fd4NP{5R5QqX>O*zt`?;QTRw$1No%%pt0%H^Ynv%#e)oT)boyE!L70$S)csdhABf_- z$lmc0ux(gOkT_AWZ;r>^9?;W!g_~3L|JP9cflmN_H{Ojv2pb#1Ru(gj6t%Urb?`y* z)84&#T;gCmyU>IJM(dB~6`qlV@Pa*FvwtE=<1Y3R?vra>DFxI>N_`Dx$IVOflaqDB zKNseCFiSpkJ(`vteW))dc;#=hz=S3@4Bs1|3|hf4LSi#yFDjSM(l*B(e}geT;Tk9E z0O}@W=Q)^n&o1(jjyfmb9W#Un=O2SaJV8H1T5+bjzd?ewQjPUbf6$`6KaTf)>A8E? z`ec(IIkgi&hazB*M^kq5`r>%>4^V13dPu;CP}~KZP5do!F=)`;#phJfG%5UJ+0Dwx z52y0er5;IWjwCk|ar5$zB;BaqCzWwVEWjrHsgo@cpkF1>B+4(yOzR>oW4XTlrCqXCb4`iuTF@`rN9hGRc;Gp;1ks$6l2ol;gH*V4?BM zWHBYjHl~{RU@!c^WZiLxO_~i`YLwXVc(_lmA2KMST~_B#y7ox(KFlPf#RMC0CghAY zfd;*^jR4)o@c$(vo@$xu6ll*t>hjCP_EbQb+8@g@^~@15U6%czE3d$u(bQNBR?At> zEb)&dD3-H5XG zsbQUBBkz->2aVreA~ecw;E<0K$-_b}tiPpSwJ8@!@jGCAMXC4>@u4{eOoS26p9m&k(Ba~V(Cl~d`i%Hm{@8R<=inz~_Fq$Ro!yng@kc~;p zo3(h0|E9N|w*|Gu+(_Zj|D?KS-;vB%$hUhXO_9X=dDk&D1O~0kz>K&Oc4T;@C9dP+ z@e$ARx^+E82lN>k$3ZCZ9C^05-K_`qIjsy#aoYK#0DcI|ApH4WWnS?-*(v< zQ}eeapHT(_GXR`a(h8BIIT9t^9JllO*0QU@u~`A&q>6e0Xm{hig;J99Pf4zC5(sCw zAR+Grx_CY!FYOYcl_!$LUG0KoB$|dfS=C=P=T3)(Z5W#R&-&BAC*~+=@+34jUw@?R zUN;y-g}mW52pnt0vc)no!MTrIJV7c6i+}*5>+8SAT|ryaK{ux-yASzm<%;T{zMG#; zj!GNLJeF&IoV@7<(*BdGf{hIx9o71km7w@dG8Hq`Mbl;GpLO7n{F5uB-;+bT29;GD zVOi>-XJwAU;Fz;hYny5q>C*>Mee0MK9^W*l1xGoy4-l1X<=f3-?@k1F&t}x1xx0?1 zx(=nqSI=KNB^7vNf@k%(D&qa~wr;nn)0NeGGjy5GM#25Kcu(&K@LHvYC71?k@Wvj`HJ#O#Q)c*N9#9 zs+5MVMCeboGW)07SBFsiTe#83qVVBf&*=_*IV6y^AWNLEcSB?K`Qj-1cM^^=(=Kvs zE1URC=cgAntRJ6c;tq0Mdy{R*9W|6y9NT9orJ!~>cw&^1O-|YWDz?(l8I3BaF>XIM zx^kKKx_IJP=))br14W|)9>4lIteRHSisjgv z=ilkh{7=8K(v53DYP=gEhCi|%a^4PH6e8dL(*I24s?|4!=Mr@W!kxlpw3le0VX6J4 zZ=}_zkIp%wv1<8)6+qhMYZhJ5a{N3P;E`jf5ZqqeJtzKBAA=NoDNiHjzJ1M^1t2%V z%44HxRH}_oOJS;e?1B-j7AlU#U8HsAi7_9KJwv zKw|s?v0+2~X~kbVeYXHQ#8Al4I<*txV_(5&$!T+sE607AJj^(m=O^7|C~;}H*05!{ z4s@50Q9hw8m<#csz1h$t#KDn`ItgQap*4z_~SL9=X zGllK^xlEFEHz&?sxY$;1MaW2jy~TCC_o`WorT`k65oO3M)F<-bAFBxVb6O31j>ulMHuVUuj!#tax*WuR|)=|;zm)E!&f5gDBQG623Wb7X0 z5uZ14$iZ~=Cj>dV&u#8}(rDKSg=>%L?L0r0_E)8*y~~>`G{KL0x^bJMBi8~;1HPj%XL0A~ z2nc)3xH1V2PGj8BvGVsJtR!bTd_1ozlbxTmY++MtNAu<6t|UqmoG?hM$e_y<Xbxx&kvf$&)}#V<``rbBth5-fy1`v=AK}jV9=@_4U1jkV9kM#VCgYvGRCNCn0>ow z;qcIb-s$w&=h0>bK*E)E)!C(HnjE&jO^&p+IH4>Lizjn$*Xz2C6u}-$y6}4|T=+5R zUX!rByMjGkDkD^tp;4+kW~>=iqY$172KLSbfAv%{a-q+Z)fS&l)>O7OP&m1Vj}#t>cg~<@L|B^YN+zeV&9$UkhhA11Z;h^;))iy+9gX!N89G$pX#~ zx#{l`q#l%HVxAtZUVN5T$nB}41zE>ys{2J}{?G81`LoM3_N9Sa(ev-8S)d{KJIoVI zG?@#MKF4Xkrk*e?HS?50^nuv7w(xjCzwa05N0C1P5%>;AIx#%B%4fP@Cdsm87crRe zKs10eHfGmgJ*?lM8vEO%G59R@S}q{~FUtkWSL|EpJ@rOh_yhzz;u7v5p=cv?NuxUt zu^j&xl21kCp*0HZZJ{6vL(GgsyO_Ot+_g;9w`^K+?peGoQ4XmBuC-Z|w_^f)yXAa` ztTF{_Pgy;Ajr>kKt@0V}6#Va}L7`1oo`tThM#GuDXCO3@3UU*+^Y54=5))+Uf=2E7 zeA|}nh)4@QH-JcWy#k_lQARPlBR?zWsT zT_q1?dZ875F(%|upU0Yfd$YORt|q#Ht@8D<_GyXz+TqZ2=QQp?s%BH{vkuFsAQ28L zemoZkhKuBzBa4DQS2|2S!P8ah%~BReT_UP(EJ0bk{Iw?<8DAQI2kYZ+K_<($yT|HN zbIwrRq2hx#tmI6qkdaq$f~uO#-M+mFCNNJ8W2Tbkw}ZzBajqaq^9<#8X3()||)?cg#aAl4a z1jgXTTrhk`_+zB*=JxI)c6g#XY(fYdoV2`ML$Hh>NOnZ?9r_ZlPY(u~E8MlrVno+v zHwDPZ7pAF15lkCx$UYcOAtIFD;!0VY#^+edl+|x~`|+6$>y=%735s8!-+A z#fsH}W3h5U3qW+xud_s#73?$?1;*ym0V@Cp*N_jE7>>W1-mqH0aCu}?5YO}si=2`s z3>nAhPDl!u9OW=QqdHV#=>_OoK=g0(MkE8XqQvq{_+>oewsl%_FXu*O+sk|$8`wI6Ac5~lyJg>`+H=cSL3vY&t0BZ_hr@lNR5 z#`74(uei(cEp6IQZWZoLzZQ6Fk98N3*Vu-fw_J|34-b%IXwKnWGvbBfZO^R3u-xV1 zm1bUW^92rN;f}~-kdCllWfwHD$Pe=bfVT7`Fh{ROG;l^}x_Y0wzqsFwu-4FT`oH`M zp(zm@jF*m;JL|CFR-~^W%*|o^)x(Q3cs0kjz-JX&Ts9};R$s?@C#xaaVa;i!9iled zAWdX&^%}k4B+7(GNIgRSq@F_8zCzF{j6;-M2yZ=fF2pds;NNjA^Zsnq+Od(CN_-(M z>?KKPza?+?Z(>PeS+B3oUw5nPip(`=t*N&BFlvq79hkVANqgeJ*8D>xglER@UVXGiK{KEp4S=Qs_eRUwsJeaHKA@ zx&Iq>zsLvW264~7z>!hG|Ey~kmDvTn(o^FzFOOdRq4KQMrAV?i;cYAqWfG$7{^CM? z&&I9l$Pi0`0dPH;ZLLk_cNKH~Z8`ke{D+Dn^tUCPSl3x?eGI zG?F#I7|wueJC}9I*G3`v^evd$wN~tCLj3L1I^>Pink8w`soCX}EYxm%nWY{#QDffZ zp;9?%;nZADhOkk8->;TloB&5T?j8ZpPVidpph7dZ^WHi-Ps?v7KmbcCsPA^l4*B`* zf?15;m@~|iuypo-Oz`@PE+?$dC=BOM=U?H3PDC*?6v|UF4U|usPS1;L@Xp`vAq6!T zc*8kx5r0mw=t_&TRhsWw6pO45^NW7TJ89||@TMjZVZbdHuQNswHeXb9$g+~uYh~P& zv2$g%nbj!^6M~QVy7iD40C=Y{Qj(II=#|~o1PgIzsQ!MARL+o;W&eDhX)-`g9sZaT zr)`rnyVoB;D;aJ9=t9%|@ES`^DGE;}>UwCU<0BN6m%}Sswxyp9RFsCiCukR#GFfVJ z?zZ=xW+l{Ro!DHsdW}?XL{&*y`!-gcYKYcDyeEvD)ZwgDU`R-(eI-H!%4U3CK+=Gz z?dk3Qt4?=ljr=8Ux}5#Tti!~!e-9#_G7FAcc_a9bin1Tl)trkMZ@AuQBFasFGd26q zjnbNg+`N1zat>N;-7=KXinToLu)nOzGx|m91gGRWh7Vcyqqls3zm?dPbv)|Jc{LZE z5@pKMe5u&-C`tH0$3g;ZsIQy{Rjrl%T2P-Z!isCa(wR1n-zoJds49_%5CHN13(-6?YIf#V!+)+*@ zfI^mIJm~N{xW8Q3ewkiDXo~<(*4}xYjg_>>$fKvg^$VSs6{%`D< zcS8H1a>vd4iBw2bX?q)3`UfF$uEMK;*Iwfw5qM}X7sAbN%!tB0Upe$e=)zp1+03hE zwyC$@^wdmDhVLJSBetnh)iyW#aX-0cDAd|QhU+fhB|@w2!fdia%@1kwLdP+=8Uqo_ z&`GHndn{b=WaNPLG#xYrA|DRL`HMeB(PZ~hh#g^`ni7BF-- zE^M`5B@)`9#0#;&;wA5P%|sGD1MJelYzE!gRi^#(9kr*o!dL~m@H6mM8X-{^uD1`3 z6E*?pHad=GuAF%IUmoc1+D8!#N7P?dcl^xEy}L_fR92n86Lv~1=@uwB%}wbSI`!MY z;ny;@RazNuC>6HVkh=qqK5V0Azkc2!<#<#u2g~*+rLkz>-xPS91v|n&P;1a;obyGu z${sb8UvPp+x7**$%D|+A* zjwUdKj(qfdG252RX2%E}=){K)$vS5Eb-n=19yj8J!&-*a%in*aoNu5jt8|Oe-B+&~ z`;rt^R$*QeDeI-})yt)x@wR}W_U66TA)Ur>o&7B-vh-Kij))=Ih>@!RYweqByS!*w z-|68bzL{D`_fe>Q|1`MGJ!9+*eHI#qPyP3z=T3i?so7{6&_}XL!@w^StbM}R!L%r6 zeK-3lBnKj*7ir^SPj%E9O$FT`ry=`W31^8m&aend^7<@143o!WZ6+m(dqahbY2Iyc z6ifvCoqySIBq*^85=Wb+A7Ti(V`0>@ zVito7`k{w#e!u)LS=ib&3UnrdEF_!KF}PAh$;Q|uN2nq?J$5J5WwwcA>fbJTWX{l! zQG1Lp6!S!Hf~AGM&S8sSJBv3DgWq`fy9e=c&viK-bQsq!>*Q1qasK9L!PYnzHlW~g z)GqK;V0_jJc3bn)K_oP=A#~3P;7@y6`Km@k{!(yfU37k00tLH*=d?uyb;)b^+2+W0 zek)m&d3tcxn8%^DPm0UU#juAS50c3S9^zt=udf7QKe8@9I;=LJK8<)PPd|M+% z?@zj?pi3PZ2jC;cO;G=ISf1lL=CAvT??>DiC??iOR%Gw@^B?ZczZ*>##x_EhtNl9H zaz0tkDKI^n2~FBge5AO*{Wvz$ZT|&99A$n zQ=@|x$q=8IYri!FpFwfDff|ocrx#F%r>YAJ)3!RB8A66cnI+C!tZM9;?(c1G!u3M> z5`=W=60UzyFCGv(0rWp{jfdZbH3r#V>^fQCFz~aous#5jMCpmn=!^~1IcgCdFZULa z|MJ|z@hEuRXx~V;i#<5FMawy;&mu8B`%^{*k?$>EEx(adR^0wpMBo$Z<~3 z)!XQ_efg>9m%?kc2npc^y9c|lapn1+IZ^mlSzyXa=!0`gO*YeyNjby3A`G_5%jCz`bN*&gRgFnGZKWf?X*t z1J~yXKW))g^h!k2AP4X0$T#w-kUSrS-5uyBuZm9(Ej{#N`JlVNAG|Q6{?3%leI=^bIY7^9H8iJY&^gxF_mK#*j&?HvfRqRcZ-cUVhPI{=Sj(66GEN488V{iHO zo|nmyY$el`X1T-{(cj1nduAw_lbToAOzetma@HarxE}7oxZsNyG7n6>D#Uyx#5J>A zeO?_dR+xLESNLdKH$9A_(_*GXmZF`W?AEpTr%aj@f?>#HOy#fgQLTd8&Ooop$3)V~A*X-<0Yo<-&Ud%-tk+@gKos0O9#I&XEcOQl6RjU} z=`MH7w<|i`a&dmMkpm0=9(3XU8woZ5x6QAZ(gXzdQ^NG?)3`203{V1Cx-HT4owe0t z?U3{Ts?Wd$qa^=oTZK!oJ(2389ju+`hFuF_?O|mnE{#O2S7MuXyiZ!NL*9RV7zKuBjc;Tq9vUv`f54cumUMrY8sTxW6=O6l=3Ww?Fwxza1XI4rH~mCwn&;FCtyrfdR}-N&@#b z6YSAZ&!V5++>}j=%wMjH*j3S#yl=@5*v&DZHst#LkM#o^vsDnyM4)QjASzi1ZU<;WbNFL5Q0 zy}d+VKP#s>PnM$?S+9OQmm2o6<&$rWhxOangd`0-xN2le#n^B`X^}=$dGtx4gZ<70%X(`tG3cCU`ht_7#!bxeqaW3IY=f@I!`=7%dkQwk{h&V8~_ zq!{~%;(vQP`^_wCE@M=jud9X|2}Y@(__m7+EcQq^MoZ^=?%8Bb8MFtL@{adn8wbBUD$9TS>yV zucz-uJp87tMG}6*D?%DFE|2A6e~sxx8`7A_EZSg0qiR0CNfdavK->aUU028$h8f`$)iKt}{fa6r;x5t!!2g!iM>2>&FMEqTwjUXn%KUs72+H%k+IaQ^ph%HxHb zu&d*PQ7PC-+dQ=(*Bwr`<}`r316l$cGn@Fw31OUNb^WX2$nj*Bw-~yju+nNJ(?$ew z9s1mll!jmhk?&u#=?&V7!iM@$26Q8E=;sga>Cuzn_*f|pfgjgjrDxA2Ar(qZp--4< z7YLWdSK2fGsr6VCz0&!$G??+@+EnOP)Piqwss*u|7{I^|OPHoVlEWWK%`+CrbmM-> zO>5fS%vQgBUedgUGs-`P>0%O6k93OSl16e7z$DaKcKX^V_GcjOe2UEvWul=Qf>E_ z3gQx3;E;gGwBcjEIsS42)bb_yP8!+kHQ?fF(bA=4lZ~;-7S|k$@2D`R}YMhjioS#M9Wf=RvlJ; z8#t&M7PO6Altw?`$n^|eB+Suz#2ciVW+Pw!IHR;A0K*nMBWZ9e{CLh!Q4VS63(FH7 zeP-OV5&UGd#RyTnA;qCxFmeB)GLrx&JdN6DBV`|osB4G_ymS}%ho|dZu!`#O4s|X)ARE=US#ftgm*ch}HRnU!0@cX>1~rBZZ;y3K z05k8PnD8)p%EAlbIe|4tA$Jr1tfp~C$u+%^jy_x?&$(A7p_@hEb(OxA8G%OLZ!TN$ zkLI(A7D*_|uLlCAos`G{tiV5h9^tVYo z6Jvu?OWXi*1V(%hTPMDwqDvQ?xkP2ZsW*ol=l7QSMqz8gPp>qlO4;Sx0d(tL_}W}P zS5LRz>1tDr#X_e`wf*|q0}m4yPx&Cf7H`YMmfTa82_M%WVM z&^6lG@axp+fYLH5I@PK!OljyV7uEi}a^B{zTx9H) z;#LNgza>gnvfRh(COKbbd$PEM8K&p_(@bd01&gnnPhhU}Z6RGCnm*^*ddQ+wHJp}b z>$1OY$1+P6MTO498za580;1@1xVUI|hX=7oUm5Q%1sZ?214sAx*kP}^2T`}mX$>#L zBe%QY~qn9315?1jh1cqjPDSz{84MT+Ie(Y z(EfdEUzT_~1r?$|+ zHY+xH3cq<~o9H01IJQ_hC=FxE%o_IG>;2A=XgXUwTAU!sj}g2QI;7$IaqO;H`KMvE z9%qCvcuk3Um}yreJdK*%YZIRF9z#s!NzwPGt#t#y=)7W%(uM1Vq4=N$S)-VNq@(G6 zg#uk6lr%P2@rEHAiR)isZ^FntEzh^Ff?LKtyK}cR3;5w@&X7xMZy&R}g^A6}%>D~p zT)Ij*-VQ@ArOefh-<`_8zT8|^a~mgA zq-c2=>c?8lwyVnhnt~w8+xg4e7rzZ32HmK-x#dkg7fwn)2@AAJ!L2-$I`Ty*k_x-?BvEIt~o4&dGGBxbjh}y-X@82IUw&`|sW;_+df4>nd^iN>WflilQBXpy! zxsa~OsSKkl0UvFI`s57v8ksV0`EC9B`}GhsBO1-GzCF9_G|6SyhIHssGK~AkdsKQwW(=lBvS02_W!gvd46m^(ursQSqVdLT(tUP-|bU(@nk7f0N1=t z;9~9Rbm#+NsN>$@JPDomvPK%7bC_Dm(;<^>hy-7UT?lC8(-Ci^IvHs>t^T)T-`P!i zdeyF9jXP&t^jGtn7yCplg~-Jjb{G8K>)0){yzV|kFRIkcY}PN|fVM~uk*17vHrI6= zoG_)=G24WFEANXplTz?}FE@TzrN`s@7KKx6BtHWlbxh|sZO&K70NDC9mG=<8yFshA z!-2LIxxiI;)PT89^exj{@%~$L{Q~5@&JR5NRu<9y=r*B@pjYf&NBQEzBx8aFctp^Q zu;)BvuWB9An^(Ij)`;DXWqhzb&DW#`r)HQ=UY$nkIQSX(eHz8U-8lH$Lyb?1&Jpaf1? z-if3U_t$2AVXaBzn$SCZ6=^P%J2s}6mrc1<0~#cq0d|O3g%VifUCZ%!uKvw>gG7GS zlJ0E`Nd#nmL>#T&|A0a~X&1ZRMa0Z3KbAq!by(nP=6haB>=f+em#y`>Kl9>quJ7de zL7ZEt$S;rxrz#A3I2BmN_};*hla#TC@Wf_=By&s_s=L7Fx{thRe$FDXCap6^baEaR za`YcqG^xiG8?5ek1u2TupqZ39?M4-k3~7tW5H><l9!QwSUWc<$W#X9<=(HSo|6krUb!)I&9fhGhz6*j(?;biyLkw% zdFWkC4}Z2QeQ?!|AgC21`uNBLB|subC|s!g8pJ5O(*ifuF*yIcN5V3_h&D3)US!nh zt=@m>ZdD!<17mjBTMc6q$0g^y6z8pk?==Iz@m9H+@8x$AlOn-4qvDkHq?OWIzs3{T zE&M_2ea0tE*zrb<$|0mOwSK&4Vr;lp+f~Y#<<}E=0|yrgOj@#U0G}NeI0N3t)KkPN zN;G;=l8`~pF691zgozpF{q0YYvC`eU-hdyqqots1wsu~_7-M}tvF8kDmrDyZ(320; zZ*lsWRedSmairt^<)$9P!#C$Q9A-wct_Wm&_&Ow~;+x6_TZP#D=6gLOYkADdxztId zG0mBoes#Eke+?Qc21Qz*{^>K#D}$>7Z)70=!>DuS*puZ4&pSzPemiw+mcW>kTI&3P zoDkU~o)uh}gvX6jK?Na0Lt1YjMHG@3-mBat5NJC-K4z)Jeno+%OG}u1dlc<^7WS;pmK>XYROoEhM(qpK0YKd`Owm>1?- z2HhbAZ`b#hjJv>p=xp{LEZ@k)#QNh!(r%~ix8*BjC68#*G}L#NrVgbA-QTZhcJ7@O zpqFUWIgl`8O|qatz43WG5cu|rXrFJSAix*tVH8|Xi0}v&Yffw(aU!^m4@w);2km$5L4!wg7lDWg9@XdLA@7CtryB;GtR zc>k%0s%LqI?1H_oV9?6HKT?h2Kjge(02z}v4@iZ|`*&bkp~7&RQQQ;^L#>g1U6WBk z^1;aL5c%W)CdIq6^~)LNE7HPC(HLi+7st0{5Fsdx?{K7axZ)~mb7|Tr1;a#n@9nV7 zvoDPj_aDVZcWLIUD5K3_@2S$xeRSvD92Tv8w7%XB@|Z@erZ<`L05hH`01N)141vB2 znwtU?8^C@`{>`~tHI0psEd125E??GlwttY9MW5RIpwa2@1>ps=%I7*MC{sa>8U*x^ z>UzBIyF!uHR2|zdo5cO`%l5ZVy`?2uwg*&kWpYXO!~kiI6B%nrUygyXCO7YpK)IuN zpWs~jUYpPHTN~%UEpFt;c#8pk<#}DlVNqZtaV&quCk;vK_<}&e@5uXhEhB>4GNreY z-+Tpv8O_b6C0)%vMZTR^KZFaJMwdCGPIR7gi++c$U+pNqed?I|9)HBvV&UdilL^lieg@$3bKqL>uaad$U8KpTfa~w)EBHb-I8twOED}ES#A%Es<(EpB&i-^lLG^35DjZoYVdu+{l5hsJk zf(TD+%DJrN(FH&mtY&-fn$gmF`n#X#1S!Le-M0e>ze=ldlx!O~j_YT4K9uiJ1DjR* z@FAi_qt0bM(JL&Z3g3EUiK3>kI85!YkC&|1UuF`8Ag{xKiRXGK03sUffQz{ONS0W7 zx>2t-p;p@~BVQu&X6AGfs3`ZRJ-PM0ERyGdCHd50XN#y~(AV`>C#WM^RcorVwQ79i zOm%Hr=0lEl#}=8h>rUyVyvqBvNI$DFT&b2A(qCI&3X3QlzpH$EF@y0+ zKaRx#b-l++SoRtv7>RO0sG_0i*x)3=x#=>2B{>Tc0IC^h+rk2Z<>zZ`-Z;^D2~lF$ z3$`@WMlrRc3J6(A)<3*QDOKgKf8=sE546?&gYypfFT;n{WS@pwR3E5D0@q1L1LqVl~CX@604VZ^Z_mITj9NSp`P=YEcu`y^fCL>WoZWP6OM;Aq;yX3XV|Y(9o`Xqg@0zX-&3v& zODOcf1KlG3AZ?yp`wzaf=*t3e8KVB8$}n?Xw4a_uEb~x1h&1{fbW6HDOb~SCgD_kByogb6E2sn$mV@U_F z6nPzjyG3PrGqnJhIl3{7^nm^&waOy+%TXul!z5%>P+CV3v&*oc8TJTj+v8?(bDe>+ z{PR%b*Sdtf{E|mR+vq$`@b6)tvg<-&!|E|Ee4_9M*I1KjmPDiQKc?mwT-y!Fb~fPx zKE57Vwa`Jq*lBXo`eSy_ijQnmui?2>2DQcPD=@CPi6BnL9qAQ9)Tm$8m|8%k~x8 zD5p*DINOjIAP^h$Q;9SCBiqgO@k6Z9a1a`x7P7!nY$blRgE$w>w!2w`gNMBEeNkcCzInb>9PjnjVcertF=ubC38;IWiDsZ#-lrgvz zU#I0uK?jU_TA(sTKT$}513^-CRTM40y^ks6Y1UL${Fy`S(UedFT{!TF)q`E2wN8E| zc@H)9DZH`cVdc;aN)5uL#{ESVXefuhLsxyH}JUuG^0KM>Kg(>c->u(!VyD)l))}?j7XTEVxOtAa^aM0KKZ7_ zP)_`ZyCv;(MzsBfn=mj)96I#8|9}U@vBL7Uh9KQ?c?bc;Ydu3UxhbdDwTBG{xC~vr zYN0$@A$EfQ7M2xMcI=jDdO)!)3c4YAP+(=7#R%ZGT zmUzU20Z%NHN7mr&XZ$!0W*FTx*3c(1>W!#86JZ!-t&5<0@2ixw3fm=JaSG=R2h4X@ zeEG}o<1vY*Mbwd^m1TN#Cls8G+Tb8g+@l1aZ6K`N%s90=K=OdW}k3 zv?#-OGc681)XejC6uBJ|gh%d+?s|w*n~{-@3sfq(x7vK5OuDpwqlNTBvVpOGWU=+E z7oTv~-gyU!pZg7P7T9l&yP{pglRH%!?vU{REC#bQNnF}O=rFdsNf2;yd7o0{zWNN0)*7lJCb*wDiuV!*Zv7NeiVO>!>EMYH% zxDHy)6Wx?PrD^=I5rW;!!dGVdy#m6pfPj`TliQ#%F*t=*99ya!{x?spT_RC^9zy7t z6O>|Pbnx4K3&lulLvf7Ey!=Z4?da84_oKy(HV>OWx)9&*7~6d+2qBWG|2v`YNZi_j zYUgAS^zDx<=&LUqP}7rNi%VjQ`AV(jKegzbQ~IOqOW7^up6M z`Rn+5$fdNFK``L1RfXq1rTE|B`Yk8R8j){5OhbG-9o^bA2Rt z#yAEBA-g1PK|4&ZR|79Utf!?LAKgGMto4m2?i_9s!=Nw!=K|>I!^wk6_$Dpv<9)QN zv;3sYtYVPr#T7L4`l;Ep?08XQpKmTnp8+@lz8Le9szYAdm) zYwVHilf{E_;~sI}KMnSEnhA;7v*qu%D*2`&R{nFNYRR(M?^vOd7)Yts%DU0s2AUgX zIxK$9wU&Xni;vSiKNjmNRg3X`uYlPF^ z@!e4vXwyBi`ruaU)SOhuY>pAFw6s(cB(Z|ue2j%D&De#A*30a?`a6%3Mp!(1Fy()Y z#i<^Go=hNr@@blAR7qLC0%Z?j*vkEV{M`WLUanKn1SK8Git@Ha;#&)(8GA7-J+=Lg z%~-++$%;;2$Xd(W16%6Zne5+NvT#7l_%BhbshF6KD!P>==bG0UbCjKjPC)812jKp$ zGZOlvoo`&Bc$;79_bMnWY>y*)^l-V=vr>d(&pq=DnO&FmsBYOK)P!kv2mwEGvX9=q z{r;bPNR^MoG|OlO(S=qQK&TD`*Frjp_oZ5 zE^O29&fI61n-^&BY#^L1K}u~g)374d2A69;>Bp2r2a-GgiT;N15z&Ko1y9u+Z;ml_ z35rKf%a_Xra1QF22P=Yg?j4GfK{E;cqemQ zfyR9yTXKnP<>cIs3((1&8t%&a zq*OIBwl;TY#8Zywp5YEL7O1i2z0&%9`<}BwDu>)t_f4V<2}GA%9D;iz@LG0f9D8TFlk$zj z``OQOw@95nXuJe?x)fF|ZDjJ&^C>LNywwiyr)ylDt;-&J^G2aj3n%F?ukaY=5fxl# z$!GfKMuoRxJr6GxitU-&$4tTlHA)rCg# zPx-SZDm2Ocz6L5g zrs0YLKy4oaT0{=$DB5hO^bTuWfM7xOhbHZg625;?aKTSB^_R1b5#2pmn zI~#ea148DYBZZ@`|`@At&89G6!EO zdR<;9|B|G-@LDF!eH$mg$QTEOqoRCl&DeWtbDj_Tk%$9?XLcGO6|l@3I>$grJ>G89q2vSq^e%TuH~0>Myd-&XR(_eA4SKBE;&YRe@`h zMs8`pT07V}OkvFW&gH~EiNk2e=mU51vScEPn?;YKa{WJkxH?*7k2N6z-HNhPHc$W0 z#+_ueRcVMtoBkGuYhPc-;8xcj#<8uN|VC`iY zDYs5hFh6&==Or$p1hf#b#Nxk5F?ymrS&G1T)pKQU+ZThuPV#f_*SmUhTs(_c_3a;i zw+c31CJ-~XlETG3SU*@V7%QA&>Z0m4Uy*jEbnx-4%YZf>h`959)pw>hJ%4!CNpx)O z*u0IH@zc6sSxiK+!>A`LblGul);iqwsoTUnxNJEp<@osAmE|BWtRof>d>i!{fvnr` z`;1G2%}1MqB1I)3Q#%%}w2CQ%aA8<0YgwGY`4aVJz2)=r0Yn_7cFpNN;Ar{Fex<&~ z1QC_A4yZLqdSDM&t0JV-y=ty$L)f-g?Vk6t(|rgTWu_u!l{RqYKi=5;YH(5pu3Z{=@5KJTf5e!L;zlug(an%4Oj;0iB0*a>II21sBO>T=X6b zr%MbriP(N;Aa6y=pc;jQ3}LCqNG<~OF2QJW+SN;=TRdS#_~qmbG)4!@Idg@CgVSE&pPX2q};LGl>0vn@lu|C|EMwxzWuQ1dg=FCc&?p#(u@uv z7NXch<;i2EKZV~$HqSFE;E#5u4VpTmMKGC zTA-1$6pLaC^m8*7L`!2CAGc#ci+{a;72hPkDU6=OHeQVA3YwFXQ?pF!saYCY)^b~T zcZT3|F%BI=QGG_A%6IRp!`G1xfzsc~_!5(l`6*zlqf0CtgB5m+=mDs< zUhl4NeR{lV<%{^^W~JwE_`;V54uh5cYXXARKLDeE_gT8nO1+hBzlo9dq>Jh zJ+R>hzV>*!SVbaS{phf_ua-H?{<|~~a=y`PiHkEXWCWMSY(rb5$U{9qDf@z*j{NHJ zU`F`TG3Mx2V)QGFcm+!wSoyP$jR;K`e6{-yA=Oeeb1f()et+l#_Yk&VxkDHUbD~>6 zuL#IR?x}0prVYrDh*~FUianX0e+~mD!WSiZCeDX>XaHM4J4_DwnlIo&sjDIGAAQh6 z0l$=8v=bcz+|LO5{639nC?A?WnVvYnU;KXb^sMYkO>0;vr~|`-MrZ^fSzbGWvM4(z z`HA2_IWl4*|2_!8ajqmlSjIqQ*TZ@zNS?;m1lEDxY*yYu;EK+5BFm6Y`AU z0Bk12!@3-?gP$ZeN29s{6+r@x(z63g-X|;Fa-k4XGWp^s+_4}kmR4pk_g_*Ww`;3? zgbr3K$^Z5<>jz5Ibh-Cse2c=s7U&{6M=GYd+w#Q~0XH!#KqH&JQWJWIehB!71PvP*OPF$G4S$q{t%Hk#>c#BYQ9J!oTr9J#9t=~#a znW#F4`ZPSety|F7dDv4sY==-ve>Z|Nw5I|G7_yXbwJKR9mMgTzMF9l=F9VMke`DG(|eCtEayEq|P^RpVHmX6<0r$V0XbE~@| z@-06JRt1}|n?aG=sjU$an#+(hzeK#uDQ++@e@+hn0nW}#MyC5@PMPr`1np|tqpVUz zAID1e#m37KqH)KzRqsx8KaY5jHn!J;wpu-GjG~tkBH=op&8e$$>XAD-4rud?p9(%!Z4S8&nbfKp zHyfBH#Kl=orl5Y_JQ+9NkHGUqHW=+$aT3BKxW0$bF}Zy5<;v}V-s9FTlA#w2W_J4SA00iugB+#9y}UA?fQ?Dz#%*Lz57z%tbrxPxu+i3^qFcI41f)T_29c0X z>F(~XAq13C=^j8rx;sVb7^NFQx}{^_&U@GT*1F&SaMoVWInUnvho5(fDsp_HXQ`0Olgn3Dx3?3d{`*;ekL39SvJ!fy0Jf7t9S+ADdmd$oVxEWmP%9IEi`+ zZIS7#`gZGHO8yv0YM0|*TiQVvxLWHnv<)N0%Nk-amsLK2;=?ywe;v_J+o`jSV6OY+ zJJACO7rj#5R{MAS-S;^sl<>cqXzKdR-P2tQA3b`E*Z z)QP6%20J5ic<~R%B==un3Pa>~{Pn*Q=jN(Y`?y0xP5{aE94&jfTLa%m*!a8OOk2o5);)Gxz_?v=|Mq_o>ME4QSS zzQNKGBKxREj-&$|qdD?1v;l@9Rt2-7TL||jUKBdhoZNlfcs+{2F|qLOF}H#SuCUdu z9HyBdX!>tjblb3wc2)OPz&8p!7jJH&&xuLTwWE*TiIPg`P=WhxO=9iAiF`YXpBrp4 z3imKxCj24!wdazAd*!vX-pzD8cH}hz47rgph_6 zW9qt5Ir|A0DU?8bon4f47iSM7f-8iAsi}bz3)tN^&vt;{!0{MqQ1PmMnZm^)J3z9P z9mTY5H8G6ceoK55;3P8Y0g91nQ`alwn(+u^@ve?D7N@c_j{AUqZZzOu@Hu&Pr%8q| z4d?tWYj{_Bb0-hH6*%xoNjJ59JH8RJ9SsAcPS^~3C5hO8G4je-mEs77!@&Sq0|~8{ z{mqz&7|9~dppFC76+6_=q-~{aEzdQnlrnYMnp{_@3{Dn@yeO4!Lb*+w-^vH{;|Ws) zAOZgQk?+hD%9O({ekpY9!jejYJ{>=maItxR+cux`8#6icVhdh|&X!hpa9l~wm*(8M z8B~<=G*>Ep;MR5Zrq{*k#1W?W+4ZmfqR@~j3UnoS>rz#|M!_L1uS-yGHEp^^2FK-9 zrVSj40#=vlg={}|8E4kTrP?Lw)BIBAizdxXIQoE~-e0)R`AkW~xF-FS;{cuX(14V_ zT4Du7ym1^Jms0EXPU+pwCz%~fA&!RFgodqKV=NivNbcwigGz~R4Ub(%aOr1T0{0(tjp7nC_h|Iuk?32O{U3X^ zhJ^r5*Sn2f_>o0F#xY+)FTLAf#NBG(d^5!F3JsSu2K6Y8` z!N(CxBR#!q9vdP#LJ|nc-cQ8aT|&i^F13=cDm+g+*DJTt+1c#Z6FJ$R{&s(AJIXl; zUJIHSlbpPlIywJxhCedIP=r|3WATOxoo^BqaW896I3URkWLMK~2LpF1x==%hN}=!dAob9LYZ&qmV;-65^8|EiOxL#6Y~ow2tglj z7s6AMImGkJtDZQxz}x1{=a9Hm9G*_Z`As>f z>yesdb7kci`ypt#LtqvI8P5aPmve2WzTUi8=q^k{-v={h9o|ng|IHG##S_;N$an2n zly{BK5o|+J|{*)`>3d^R(Ft2VP zbMvxvcl!DtCOY5{&;dpME*OiUrrbP{uKO{|-Z2pfG_6b;I}a#7kY~et@5^?oCTL=g zYc|SKJ&}ofemy~Bg;{{iukSx8|4F?h(}vLk+E^qWb*0x3Eyd2ksvT8#X($MA^hi%F zJ#?=(thsE+#I7`c9Bezzfat)BlO0}Y^oEY%z3Vker={vnf#&t|-b}2Kw*k-v52yEu zVbH$>VxnGyr@*G;8;&2Rn40qr)EKh%_&cR?J|}70550nKc)EjGzL(wLzmqnv0;kBu z^DWTU82P@WWq69F`7c1=gU8Zng-Oyai&kDKZe(+~F&K@Co}Q3?{&{r79Krha?vdaO z=$4DSR-SUOHZ=3NHJw&+tZH&nV0SQtbQf1lcFkz(GVfu}C|h%I+|S7@{$D|x*G_v- z;;Bc3&X%2V=+j0j(k@tukWCKm&7kEKI~ioP+|wJqPWNJYS84O4>-!qPhNuZq>oude zdYY8IGT;s_nML6ic8MColNvi$=}ciwi?Y!91-pEgBor#BMF2yD*rYT`l=42rVp-$2 z8x7#(>8yB!e6Xrz)$zZCFHP=bSf+xw!tOm{k{2MkNo!9wK7KP8GS1FnRy$T&UH3Iw zBk1Q*)ie32uRuK*S=g*dNZYq^P1koqY|N8}(R408J5P-JTPF7ikb*!AcMkI>tk^+7 z5P)oV1941nA|oTd5B6!n4!mn>RgG{{@CT{J0YX;TUfUY$Q!0)e>k?* zW)|sgyd6D6#X`_?znsD?<1sgQaGTuI+0bYDrI#kcKksUi6cGDDKRk(z2h)r^KY5r= zl6Pr;f2P|l{Rh&pSU!JTN_E1|;iHm!cM0Ygfu1d`n7DzX8_fabrCXSZw-5hg<1YBC zc2SRsdHOTJ1g%b3wM-+e2x}vWgi<(Z{mR&pAR6&@T(kO6AB8a{rS(heqc_gBAs&^S3G-4WDl44vM^N+Wzlky8WDd4-M1=^@D+ ztw<}qljW0EHnzD)xivxXtCD%v~1OY+)JR5ex@D7%BUS&PohWHul~TPcwr zZav|LaSp)f{oo!>`kX^KKV_rrx+(o}Wf5DsC~G84vSrz(4>%4}c;w>-(7VTDF84q2 z`v}X_m!Tj3l>Y+@^<5#%ZU~G4ufgbhsn0>nq;GMLJ4%y$ficwdW}Giu0dV_82=mZ1 z=o3K6j)osmE$x$%jn!!P1NbdTfz34*z;WSPU#@$nAl^hdau|mE%Mbo4DH>J*ZmXmh zyD%sWjG4>7-})8ypodMOgOyTEyhVked}exX6eS%!kx`p#v#;>+5l_#T4A}ZIT*CeV z!mN*B4%iBY33{J$BvNie)YM0Dl-n4x+DSaHqWt`N1oWd1Wo@!&^s;(z4z6(hfrnNX@t`YbKda$%;mc3=MK&u> z?8*!LX2v^WOPMKl39l6yMOt?pqev?mnufoyWXz=**k9T`$zNWu9=BPro&ch{{ZEY3 zKVv}o)1(Pqns+}Vd&tWLS50|gK)CG9va7)tE9y78zUFk#qxQUDOp?FV-=*a_vq3)| zicCB2FW=I*p4EasM-Txadqvo3y8EV1r|AoN{sIETi!fRW3rQcL-E zC}C9*AGMvF_LMOxM5Ck47A*x+&3%IRVZv~DY>Mj-b!ke6vxwx$Nq|)@3gD~8Ei%9g z03c}Lmy8I^Y@iL&5Y2p6X$~Omk$_sf#KzHgt76C*rA0!^f>UfYSsf)gyJaho`frt|nU9p$vZ6MjS9oPAIDr)bE5j`ax((bxX`EpgOZ z|IX++1fF!ExN+IHkCH`c{mBPY!|U+0g0Ry*jHALhZcj<0f{UM)O-)U-L?Md^$Zav@ zsKiDa*M(U9YvLCwu|{S~{uB9i4Nu;QEP9-pd`)k9AiKl+z~m?gnj0)>sr3>Dxr^O* zGm_xl$p?BT_H3f=w=I(={yquFKbKATu|T?3(dR)X&o7URcrqLH_IHpFAgxg`@MiRO zk9(6UBDz4mNo5DTEu;$bDg{V#%?-7JJtY}%W^|@TC1)N_Z)J252yibM4E`>w3UEZRu$hJ%WhG;@q~G>tZssx2 zn_ZuR(#KyIjpqRNAy`z|vRUXkRva+WM^l#gH(!}41 z>C6eDea#f?465c)Fkof;$!>5GIWfa;)8IWDBi$k^a{QL~O6R!}f`N#dx}@dR9^1o( zm(1?*z^bI)UplE3y+5D_;b{>$J1Dg3Kc*;qX~L8&PUzEHF^sb2HR|s{Nli}14DTom z6+T+!(-g*sHf~4SI45O^Y#FT%()48ahS59rAMQ zi1mE?g-uvR!O28ZlGI&UE=n`ipf5V5YC1w5?1I1DW_4^PNw2O1-%jGED6j>;*=#d- zZQ&o*SlMIZ%6{sy3!5M3u z<%8+E3dr>iYUdC2W3aTnk!PXrP;)WZ<*>ZWRh2eBU-(Ml+s-^A17*3NUrp0GF&b_` z^rQjN{xJSg)*<(LOLWefxt(Yp`PS7DNXu0i2o3G2XuW>V*p+ z%sk>6alh7!rbJ*M4krL+Ps}fGX~F|vVO}*ND6L#0b%dZ?f(uTtExV+bb!J@*O+mB- z@PqKW4H4QB5g52P$4v?YkXC0AOgB;sRkG(1AP6 ztR1&|#cE!#J9oSV3k!9V=sbe#C8>XSljbVW;h6TxGoq{e&czd2(Lw}w*Ma05BcNTH zg(OEf{x`-I3*k8ypRB*?RY*1nG+pTBS}Rno=X*h5; zE~%5~6|9_KJl82F5zTtoEoG=culagu=3;-{m`h5X53M(mbWJ^|td1x?EPihtU&>bxKeXG?nZ;2L+@-?uO5D!cyEPyhd`pT@#w zId2+n|1Hz&9Cvt)3rtFEE>1D7Vjy|RHkHS5_6iISz_fMoXC7;5UqG&OL<=7XdKYZLQ#oEx_9=LHM_ z0}EDUox0yR9%_^W<<_*vC4J6eD$QtP$y;(4C*q|^p72~U#}=_mPqep-cv(-ntnuEx z(>>&mvA>ai^hSp;x{!VGpXZ5Yy@#?s8vuiO@YHl#V*GJhZsDNY>Q?<=CF5^>V(;Jq z^iMLBrGm=|b_pvk+JJ+}Jd^F&xE`YP^KkqKV$6Hw!voeaa>X~^|LmGTXd!=f)g0$% z#ICj2@m=IVUe1rw!hQjsYuuNiv0LFuz%j^&YMu2zOt}qV-FDSZ+8CeEra`~k=uk!P zW#q~d$8UUSpvmS6A<2t?@dZafu{U-yp({#AkgqG(vw=a!D>lt_?|}6re4-F33mS&P7!fAHTqhI z7Q=%m&f_mi&Yj$B&&nM`Bhk0nkoZo-Q)qBo9GMFE0doUw$TvWC?@8H!=L=it$?qw^xg0jf|ug*93~Vv5(AEZ`XU&N zZf*l0-yTi|al@kc6a#Rg6?x_;aM35w@-1=*x<}hW1Dz0eSjKcp0k+Af9I zrWX7^TtB0mHbd++V&630{@cWfVvyq;NT<5ArYLXfYWono<$rH! z#1^|u;@+Sr`8U+zawg5|dhF9k*Zyv{7EAmbO?$yFB)s8yI0=7JTM0G&hvX(3GW|`> zCr8!0mYVp=^Ud?-vdJLD+^1LzG~d~;GWee)9#&rj>0DSSu+Kq;Kjrg>!c3|wOKY&U z7ej-Tvn3nYwIeLcSB|Y24Vz)QSu5UGB0*Z%n{36&UC$dnwr21a$foU0zfCqEt?k*E zw2gtnM^H{emWnBC&QOP)+V5}jh5|>7nLm$|58xPHnn+nq$%Ol=2!|KRRnfQ3Z?5pE*nC^-KIs8XD|qv85H zP*TScgbSHL`jKuLf#yM$S58bh4FK_be)<4lj7*`l;Gen zK@!CZJ#H^rj-o=s@r3%q%M?f&^Pg?f-u(BR06)>3oRdD@_dInV|FTMZoI^>QE66yd zk$dV#;%m2wONlD}68pdJ_Ho(H2WkCssL@lG?A@Z~!wu!>iAqm6gncoxex(uY(-lS| zSg-Yz^UpbygHE`WpB=3dqGH{(eOjrcB>KNpgKa;$LUe`cU)Kc8W*IsAkV{&-EUbW= z{BI-2ctggAnS`2{p)e8vw(eDW+B>n{or6NJ6dy>uW=H5syr(diBQ3{);bF^Yy~}9z zHh0;^#eK`BqFSdIP;Ma@f z(x6ozgMBeAr;?)h0Q!#Sxxv-0)Da^Al-84b%>GZ#!~r%N%PM7eshmwLy9i1S)F z>pVX;j7{*k9G$xPdHch@V5t4)Q8#ZIHmMSLKq^8fuSprm#Do`oaeL**8!^29+$%_# zbp3DesE{kw2ZqQ3 zy06VVGLSb5TWX*4n!RpvCvzuH(`h7C4DQCJNz&T})&RerBVB6O2BEIdm0y)`b>KxTx2Ht;F{iX1*b+Y|4M^cLxpF-ybL;J7W3|o-s5iE zzrN_Z2CR<;#dJre^Q6rbYfjc@9RgPcq%^&W^>uJuTk^{AUquQXVKNB^PLBq9c1)o+ zF(;h8lIZ^ODK#DEdpp}`AokoMbV>WTbPaeutJ77M)N^$)BY|rX2w7|NEzQ~wEu}#p zbogK^#$gpj5$X#h2@ATGsrT%JHvT`Qk36e9i4+W4l$>U(pZ+WimVUaOJi0rm@e{a5 zIRV|IZ~6$X`Z$B6{yyBEix+NLi&%cpKi`ti8kTf^I!mQ*2|;QBbXxqFb`iXC8J>WQVQbP9m&r$+}N)O z>8SmX{9>s`s_=1lq!~0))-ZeQYRo@0{Yo~hd-FFte&tG)ko`4#L%SU1cIe2&-62P& zuKjxKs)^4-tZPH**dEUHgwN5Y#y9$xTLJvDQcHLuF9aS=N|TzsN=Z)AIcm2XO)+{k^x{w6iwG(^2MD z^{aJO&;>pN&MD}DhQ)aDvZ9)Lov=(n1+N)$bbKlt2xxpAq*@qJNwnnykl2YmWaz`3 zMZnjwd)pe=>$np!*v6j?jg62*zPbP7wm*9L*+}@{?Eah%zktOu68*}n*!!#MAZ@{V zzwd2#&jh2(u6I`MQ^;(-)juBPa4ZlsXHLBWKQI2CCRLJ9-=Ol)H`eA8Q%|ECpJM23ydB`l2SWYSW<(}8#p|G!;k{2)b6`*f zSJiV0mdRnB2fE?nYSVleZqpsP_*5kRQL=Iut z4ISefys@}@P(q4EDA>)2XIq|WbS_NndC7^K8pN8UsQ_1&z=m+ewZX6`%mTj zJWH<6#BN{1w-cSQbiC|urVG#SP%w=a@#EJ1aY7&&NqD4V=Cg}>qUo~~s3GvDp&teu zW8SNuFv;Eragg96;fg=p2sOd|H^4a?P%CLLcOqH$<6Ana1mPc-XP8n&x5~cwoXjO+TghM1F?)51$3) z_|;!r*eSp!E<*^YGdB6r4#K24g>leDlV8&@6^VPhvZL=I7`EdT9JAI+SBp@;ZrsGk^gSvB#MB?ZtrB7~%LRQz z7uoW=dQTe8XE)JBKiXAFPics8LX-nf%R9@E{ZPMr69j+tOiDv2+pD)TL-yXAW-0s` z_F^-UekS`&Xf?3+Cby=lX=Y?sHc~;hckXWkGTn!k7{1XSyKrRd`(B3`($0 zyZZ|J7P^nE`$0XA$|d~CO7(BA!>dkfEQ~|wH*=l z_D+v&v;CAf5I=KHZ$J8t!R^rPC}K5C#}V4iAIf^Y^stjX`=w)|6zmg1C^V-1E|21) z@qPE4BVbFH@ok53w#UJuyh8(%;~xO?j{_Q8p!^WamMBg7&1BwF(`Jsk7n5n;En# zPm|BI*8nPM3yovVFux5?s*E~5I{oZ0yxtOP;E3e(Z8fL%PCeAhuEaiSTVC8jKT9?D z)oh+oqi%#-YO{7RY5e%IN1HT#s025fJnLN5Ub~9)4mw&u{jrgcOD{v2ri<97|GAY` z_Zd4{csHXtb>7UTVUVlldq7774d{j@|L}qGWfP24R#IvNDej}{kvN2H$I+d_9*A_X zDL+$p^t?QDt66dI;*jD-Tfl{m;x zKZ2q|Bf}7X!layR#1#pePOVfzcedHrV|X_i-;etqeGPPSnP-=b9d8cSYv*#Nb+A%G z7kP4?T6^YrgQbXII-x=y#r_10bVuh^`l>fx=?@$`7y%>)0ybJrY;>_I!TTX(X>h?_ zv4;nK{QXnqbZ#G?>)l?6js1Z}xg2c}ir1;pFZN081GG`_Nn;F4DcJy>?b$LXH}|o( z)Y)(1Qw-+1K0gOUJ18`G&6i;Ix!{E)Wsd;wE6iQ<2Up;Jhq8)0^7ceUANPz9Wc!#? z5yc|mUK_*!+$Ff;Fz2bs=jk(hx|_pql{JW*ML+F8#mkN=P`+`~u7$nv-vw-UrsZX5 zgITK3t-Lb9@}@J5;G^-Zh~*eIDPe5HKZ#_?kZ zL4;o^CvGbOXAL4I2_f7%syKN<*h~}ofTOgM@Cdq z&(z13IJqLoY%;S=gtD!`57p95#&Zd;h^^Im<~Qa^#!}D!%5>5b*Q(eC!a!`gpaIlo za_uS=$}BmO%LuJeAP?@H1GW387MznbI}BkTL6?lHaEf6#NSX?mVo*2umN zrM>3{4oHV-Y}Ria_%`ll;U*P{ zi;Df-mg%O2w8OgQ@>2>Uz4T-Lt7MW>SfrY0 z!jxzBBumj8#nU!_xH)@gXh=0(iw`R#CR84mmcgsv?DjFz>%%h(B^;fv;~YD{c7O1% zU1?1Z7k&Fpj??8Dlb`TnJ@Ah>;7)Sw`p+6hXfEWVqNVvR?vEl}HxMGojg^kT_kUk8 zp=i%%>60;rm~LWU`GhUQepp&Nw)V*ac`66|!k1Af?zF z0hot<7NIpThce3#P-KZM=s-4SKS-SbS-kDb2A@0zDDE{f&$9Cj_scfBWhh&*$AN&` zi#l))CXIKZt%ACMA{A96*fWTej5k_C3-(AqBgWZA5Ad2=kA?F!FoV z-Wx@r$PhJfyD1oLzDh93)+DPn8*PYFX!A*Yei3`rx!JKTjALIIpw`jKA9)x3V$M!V zp_>a;f3|7yI^D@Uxc>M_-`Ju;u4^DHhG4Qqpg8tq4$tY25FZnrZil!+zFjFMIKy*Q zDdo(x;u#1KT0|%a&jQHWvk-~z6@&jQwuF2Oaz#AiH{C?LTNynDkE@!++~jFE&OL-*+ zLYu8~G%BkA>_D#G{1y5$7-|g6YMFUSL>dy>f=z5$cc{Yf$-EIpNC5q6&ODaTf za6?|f^7zbE5ow9$;$+`o>b`lLk~?T=S{gz|jt9KgfEXEHg*}%KfVE!`;j)84%ndKe zXuF6Yao29|Ug_7KVgZlC27>{Sp%H1bKV>s6Yo0?%KMwgzriKLAzfDiIF_BuzPsENQD4X(!+ahkhzFJ z+08xu|8)V_Jn-BpWCDBf_K`moaO;$lsP_4XyryRlLo`Q$I@3E-6ZkLB=I9OA?^+Ht z_(P){j{|1adlL@tPNe+G!12yRDdVP^4lOoDr(?E@ z4NW5TF-P8&e%SlL=SkXGsL;XNiSxyuUTajn_6OE7R;j{7HWbvo(LT>E)MtqWX&!uk zmGQ!bnldcdB0E=uQ!r4{*Jim_HYCh4^#}W$u%S1lxx*xDlf)|IF3uBhP%%R8BJC+JstqffI*<;i978(7ad;__SSApD4#YWHB^p5OP? zK`gmbAALthT4-qYF&*Gjhl{Zp;}0p>T-=k2Pt^oSrhWjp9%hef|{e4(5F&OaH+l8v&~g+}q` zT!%3VjYv9uh(QN=A#)eI`{-c!xHq8F&johJh~vxyOdE}$dLP}UE1VhJu(CUIC{<>g zx}wg>C~G1i#Y)3Zrmh1!cIu;sI>ud^yS*ei=$`}D^u?dr%9bFV=~=64NU!7)5(Bxk zrric)@-N#?7A-!`pPM#6&>MeG{$OgAJiB=5K(Gi)G0dK>S?Pd#>-9yGMi(wS_y zTN;S=4(hOIMV1{0ADC(E>Z1eh@ct?1!ceev(P|9j&4zL5JA9K4j!3@KCsV`XvFgBS zCoTvH;74^!`?g-ir1PKRT_UU$3;NB#nsam0 zFu7EbO`HXCx1 zrI*x9L{hn|Tx9g_iFX{I^_Oe4J}049aAa8rSe3Fzc=-Co?EVt~wL(1WHWQPhBSADl zqn6`{n8~{h|Sya?wNnUKb5{_Z(;Lu_pb+!b|VqNw!_(4**!+i6Dp; zQg(_eeU^z|S$Wv}X?Qw_`?{Duf1MsgFA>wNUb}Pvet+FAjcN`MKhAwXc}h`C9)`{g zicRS0e}-{PJHEQ;u6a<%4)_kpVszvILHS=`sz(A^Y|$1?rk>;O)Ajccw2dCpvkNWVd-dbIKwfxo zS$6vx({t>Y*HY6+o_yXy1&ycKeaBL&9%tn;KaubD;IN+m}Oifk{RreBto5lghir{`O(~1u%$`pgmm7C| z+j#L+T=S%1s9K3&+4YUkhuS{zp%kfJ`wvSVw1Ahx)BWb_0bhx%W%}qx9(?QQ%GT`E zoIkd(IWQ1D`)7=a%a5MVY@1QzENZZ8A|@pR^CefH8whs*ROofsJzeP!(JkExXK*e3 zstE}W`!$4f-*#Zv#(w~TiNvwrDNu{KHcGB^tIb839t+tGSmJ%3O=Enet_NVbUAcw7 z{#m0=FW!qI4zQ4DCkuYNe`$T$(SY%jDnPZ0bPeGnvkvnCZ8%&j^nS$0W=-64`_G9| zJ#+GKCU+UBUT-oiitYGb{>6MG(<7r8*-k~vyRLvHn{L0-ty#{7SE(FhP8@Sh@}IVu zk1*!JDcQIaZ|m#tf-G>xi&=M?q=soV@!0l9&#>!Y( z+2q~P;nDKgVQau<8Oks{EN@w-BwhRF4pGQYHYgF@M^T^6oA6%n+UA)#$IYexENHE0 zx(vfbru;%X3l`R@#yfJPq^z9F4SI`P*)i+y8fp5t9vbiUr8Wu!|NlG}8!+s(WrhB@ zh20yeSn|_g7Es&UW3K$zR2JL*3F!n2YrJ_JUU#2r;Bom(?5G{)`OOJz3Ag}!;7Ft` zF`O@;1@Nbd25QPqCt0}|%&&M58p!@xvD1?EN^Nh4th;vkTb3?d4xPDb3f-Qd@&ga} z%H)a{K09)bv ziE=2)yN_LI@0^PwgkX-G7gLfxa2micl1*$}e3;~*N747S{Q*Kfj0Rna6waeUt~mSa z7gJ^GE_43WF4TkO_Rao%VC9$j+i1hZDRzAXAJBo=-Y9tN-g*@4k@sZ$^~GftjtW-w z+nzXTBWgA7;f7y@`D^ZrY&&zOw{lXbD!|e^pTOyzGF|!=jMi0i=+~hd<7_iA*Vb{u zt-Qq>Gs(w9!!ZY`%mvHh*non_evu*aG9L1>9Wf^847IYsRb_E?=&+Vhx1FFtzw@7J zV}+kP%eB4{^szwOgB-qE<&f!l=78&N)Q6B<17(sB>5etob{^a7hH=mrv5tl%DfjP)Q1K@9dkgGteus>ZiT|L=owupuqu zT+)F^%;EQ?|Fo~Pc^FWv>sSX-v02gvX5=NDjN9WJlZYfnzHsuV^Ik! z2dGqVb?0l@m6=U0Xze27#||yXaoz@@F_j6F3?Mt%BTbrlv)W9*az3GlgUaq3OTn!m zotKbL-%1sJ(b+t?-}ezK8Vnh+@Y{%>OQbsuEm5bwhE`MB#=J?-;1TQwa_vhe1bT(kl+r`!g#x!Hw$cOhe2mI-R{I!# zi?ea#`Y6DDes97X-OL$|#GO@gx8xE$1C310#%4f|H-IDKLs@vtlp~7PlB&!ze{y6Oqy-CzH z3^DZiPz)f!2!?$rMU-Y<_+%SKZ>t*SG@(X>Cp`fwmgDa)$hZBt`(HkSe$vo#;(i)z zO;|?Uvy&He*m*t?=fM4@wxYbe5*7bK#yRXD&8?y$TEm%ki7L$3Lu(~iPy1E>4c005 z85B-VdBz{I?ypHTVB1Gqs!=zw)~t5U1o%Va$C z+i`MoR!xm!PQ_v^gMI!}k^&oZYi2uXj9ijue-mT?0Hn0-7l4Oath8I6q)R1S>`FT= ztiH@HM9%`>v21x<_4xxxEP0;+Y^=0}56+)gjM6%|B|W9Bv~aGZIafA+ytAe@NLj+S zmE)K@172a~=8AfJI*>^cp&zt$oel+e0|Ov56xm1A5}vcZG>egLwlW$(GiKM;INX+I z)-up(X+^K1gYaRcTjPvUCioMjdSwX4L~`=9sk(uuX;_Nf9Gpo09c}N#{&4R7GpxkE z44P!o_4LgVY{63N7CJH7-j^^NfVrJ%maPH|j-6fY2b87d=t*+PPt(Zn{f;Z%=xc z11Pm=_74Fl_o_x%#x^=!+VhP!EH9ve=MYy6Y|RxouZ6ao%nXop#(Pkx1#SbR3cp(F z%U7i~SJzekv*NV+ZZOOLFDka-*SYe%F00Tol+lzJ>yeQ z`l;4xzfUOa*Ar5iBm)dg#L<_n%D*)KjD2%FZu$tt{M@D$M*CHtlc`E$6zdt}G6WI_ zenADJD2k?biCX1nX!kVe4Bkj0SJ#x*5A^Qr)6++td}>(fi0NYUF;My#+N~NN3=4## zhU**P>8hotDUPRGq(t}bod~KnhVQyIX%BjDZ{>(x@Xw=RaNIy+VElmw2wu!ipwHPf zZ1p(rX>qw4Y*hv>oS|jErnEhwbS;e{GBy!Z+IT9x^80+XqChU%$IHLRsCaaZ542q# z6Ti5Xs;_V67`|oF z*)yQ5rEa9zkp;b&u6A27-C0%E*08S+>}g0;efCiFenSyU_HpS#%S5?cV0S>|1@MKK z31Mq5#ZyG(wX^LWZ?FwcJKdm{NA+v2j>_nP*3&{IY1tT%`d#!(%rd87Z_GlWVOlTiaAvNSPEki z+zy%|Y>9ZS*z=d+TY*gFANEVw(_X_UZEBY!-)}z7%q8~npzecu*=vAJ%WzNFlX-GQ zF~Q`G?_njYHAkFW!{gy+mS&yrPK_P?^$>}YxahEg>A{`KvU(#^)2;mp;0ujIK0wJR z`hg^5raTp`RJuct!_36s0Qw?olW0T*WL=;S_OCtpAG+Q$D(dcy_nx8~l#Wp(q`Nzn zMv+bd$pNIB0TfVD=^j7?q`P5|M!LJZyW^Srzt&mLd2`;)yx;5kU3-7yleY*{Wa6yI zdi%Tv;r0taOUMOT_JS<$#)Hky{W<^rsolR-eIX@zVY0sh+qeu*oP4{jx}3~DV=T)n z0&=EC*HHVEP$aONZdW9~jE~&$>-~I8-^g407q^`BoYMelX!1({DhrJ27x1ynkD72W&vxIm#NJuCQ*qde<(TfBzTVbWY(1WV(1 zM#YZ-*5~myH3TWjZbnr?A$@9CYoCozxcSe83yKAP+kAs5A38>UCEiaxfl&z-HH~IEH1S5#e@)U?^TOZ5;Tx(35bc~}}#(4ZRJj1{YOY^+x$fPgj zBy`1*K^fnSJ%?Hq%Rwnzw4&xQz z{6*N+2&r@JUaN$eQwE#>`?k1bN}SINpp(V?SL4J6b`_7Y+34-2pAU@SQee||Z#Dh{ z1Ncc$aV#J5-dQ*ReeD$|Tk7Sj?6b^TLr~QN6*j#t#e6og#r8Dz)uh;~*C)d0UDNP| z&wBjCJacC3@@ufOER*V1$JaHYoAy;kyRxMg?ma?DxX|cb5y!@ex{NYosb;Xp>|mQJ zhnU`-LrI7cxeC(oVKjH>_pg#UM+3i~NU^yaaQ%Y&U0ajhR+98g)K?Am5RfG%z+)Qg z+Ox2ti{q>m47yB9Xvv7Rq)kdS%Y1gwWbwe8(0uE4qda35cr!mvdZSWx@+scnmGbo9 z?c95tyxI8%X%2e)9!5d|+3J}s6%O}gXP$G71Dv?t=n24JRgjNnIzWG2Y??IrPjKGB zDq1MPjI0<@--DlHvCd>u*GS(9(aW%H+-2@*NZ7)`tR{@gy+H1TPL&H96dki4+>@8@ zp6PYB_q*`MS$yGUR)1oDO5_sb&LxWV`Lov}N66gb=$Y3KwR*QT@{>v8!=(JURmHav z4gMk@xt_!>HmOpZ2H&OF9RyE0&q-{**%Q0~rT$+2P!xj6@-ct9%4W>4CT*+#sPxFu z`4&`05VChf(RBoB!>qy`#x@;ju0{ZxG0NfEQqFZC35w&z(Tz->Lt!IXcK7ukis&o? zloCsb#u5!>^&Og-fFOY?>vn|*@|D@q%MT{Ys4Tc!U{Fq!$e$cML&wtK!Al%{6GWx? z^`vJU17TU4sS6=M#!v`T)`DldD1h)xDdNX5a`6)NN_7N_W{Rp^@_{d&%_IKT%28O_ zBJ%q}3OL{7RoO_9UHvccliYeDyTPZMo14SUBF;VVdRjoYD886XFj^7N8G&nl(|5e! zbZafDd@n-i z*)M_a2N4wu_*b>{sry!a`|s!W;pXJzXbCd$d5PkyM*Mvro$YxpEv9Xvw`?QPhFe9N z$AK#*gZev2QIHe)xf4%@VicRkT?LDdIl&t=q-G&*e(-6(s@{7aQc9J(UA-)WrnrZa2LuvomCqF;trMWn!IiA|TTjb_{D0cX>(E0r>q z{lH_0kdO&AMVC}F;{=p$4P3ED9Y%SixeGx7cS}{NP*oI?rq$t}ur!LQgS4xI?Qm!k zh0B$V-qpa=SSkhvW-c2yd13wr1*ya!-}XDJKdv&cRaY9qy6xiT*Gdxo$#@fZ*e~C@ zYJj;-L@)?nUGG+n;>YxHPrjyqAThGS`9LaD_GOQR!LN@pi5K)0aH~3J>$*@gGyUS> zAP%cDisEkraC2n3NdCEivh*JUhNd^)fVnTpQ!p{P2igAA3|TcuqzZb1i2> z5@ZZo#5?0dafv%yUe)V6I9A5@(%T!k1hTU?k4L2oDa`^KG1{|})pg(*OTD7c%H(D; zO~J66>t?7+^dvG1`)9hCyHqI}AlYCTz8I`4#X7V7X2T5(lu-q&6s{` zFPf}_-do5wk>257gBjR-27|Th;^_eL&|I zBEiWyWJLCg&y-gKB=fta76?U6a8wrVFtXz;cm|9m6~LAG&@t5yZuY9&MV6iHoWyWMm{^ds+)_Q!PWZ^sJyn1as)7kfYY|-j$r41g3&KtR+#}U^ zQpD{itfF!!lg>cZjz`TF{$IXLywx*R{N*f<-~$}W+>;oFuD%)Hzjc+XuO7|^e*q=T z$?&X{qK`Az+HDoCoVQ#%VM5#&qH29!Xq3M_w~)e>CP7k=^QxOt+wvW8qa&&4sqoPn zK2UuYlbXkRx6$gLP%nZ#K5PCi%%qH4?%!4Nhrua+f&ntPqci`-3qmT;svf9gyq{i1 zhbg986P_aW+aUIV@gM*uH%dyCre$MifHCWiGZK4I4qk$AV54m+{Vnbu$c5S|0HPUNcGMEL*V|Lu@ODG zV$S`uQB~9Ch)zl@=V8Z|`mDtei`to$9Ho7fY3L(*Xj}%8a`~2um&@Q_OQsdW`1KQJ zJjB<1nlx4GA&6D)&1|`*&5074HYIgzmUJK;NM`OQ#%#?bwNK&FOoDj+_~XVkktW9T z`xLKNF3RlO0)DryiX-lv=fO)P6(`p}T5ZUILLhS2kh;@4BAS4!`B3ghOv>RLAlMqM zCT~UqZ_R43NH6R8MYdh&<3$A?a15cT9og8nyCZ4j}AK4+7AB< zBTtvYJ8sP{k^RZM>81l7t#?LusB0n3*yDI{F$#21J%W`2A|I1mt>U&bj|^k*TP4Zd z9@Fdr_@6lfZW%36YF{|y{58kgeQ@QK@eZgTm&XA`ufi(Q=Fw+bc(@gzPsL|QlsJOh zXFfbe^LE$Suah0cDu7|NRd~s6pcmt8-~^0t2Qle`GMOOv7vu(MiJQBbwK!ol*y)@3 zv|{pAHq1Xi^x5Y19Kn@rdu6k|vSvWmy=5=oDX?Ecfekso#1`K>eXVf)2u zBBM#cfZ3A;$D;UQ0~d_^=Zh}xYNz&%uQt$_B6MP^{{5MAh8Y-Sc#r0Z-irRUlz%(N zUSB;j$sBAlqHVflcN_HKH!0Sy*X9dRmB5{wKPFq%#J@O9hyBCEX^(04?#lIN#jh6? za_EuXSiQg+K#9S#p8PS&s$@|zh~OnI{yuk+4>&Vqa!^c6aybWfBW4tc0pNsZ0@qq3+;ZG`QymUfx$%8A6%+ zB{H4**<*%X#nO$sy>G%U6`HGxI)Rk8AvE!fFzLq2{$7EGSKi-6{a>E7Y5;B=vAqYT z#Ewre(`6;-Niyg)J2XKzRr6G%6>aZyT1){`F8+d`D~;g-T=d;}+e zh+a05*_N+*bY(gID8m22o6O?W1uGx|vVaQTT?n&V+nDGW8@CwTQ0w{RKgJOrd&Chp z>$(AtnTpVG(fr6ArBgW-p#a&b1W$4xKIlH}eSqZf^z`<9a020^j({v^xO=Uip=+M* zf0?^AJ>`C{Oz-8Q%E5}f4DY^{n*qn!NWn$&F+<->_YSkw3kJ%uFQ7&89|-wy()xWl z6Q4Pmx8hGxwMHSd`WzHuQfx!gjN_017nG*99=8hD8M$z>n5~mm944IIS>!?X@Ds2* z&8Xjlko0@FVXtBZ-?=W#aU@#|FZ8N`b_)u+0ij{vfrwB{t`U?i0sR;(C&ce1FuJE@ z=}FX(qa*svvZf7C3+D%fK6;pgwzKL5F=L{%x~{6QG z?e-U<|-Z0DwByDB!(cH^T&!G zin1Bz9`kO-YF@(9q+VJAVKu+?l{OvhNGU5Wb8ixT#GLOPF^`QeznQr&wBt}iUkQOc zb03oz57RSv>ISC?1jQ}v3yX6z>Xu-Z z57x2UA^=%B|D|Oa58q0663t_4r{!&+f+v|YzCD8=JsnIK16KdOo zyndeLg?N?i6nb8@bDME1H9(Gofu<42nL3u zthtx=uWCex|2yOuw-jncoK6I30gpGAC`kBp>%&~@3<|SGJ$CI|uc@O@n1q4!!JVkC;qENd&EgQHGFe}4q5q&d z*UV86p0(k-gOm>}5TpCP>079xq>l*Ls;laimn)YdV6;5Vasz zJAL%&gGj5HpoFZb-)aC%yJzCG%X^Vl>9l_x5sKSO|MTtgJZF~9fvqv?QWjjK|9UWOEIKOGKhB}FX1V`a%{{eA z?7kObaMZ68`z!}y?Ee?0`>$k_n zXSE?xnds}kY2wf6GDR0Pv+ukkbT7BM(x_am6Hp(a^8ML7Sir?!B_DwP^%<+S=z-FLA!DmY)DEE45V0 zNeRkAtN7gYc&G*E{L4*e9D<(@{#s_LlGNGZXn3J5;RW{iSM@2&%-IQz=T+s``)XE z$1nG95;CN4fiKCa;c~XSLm5InXny%ejAsXtvxnv%D1l{YuQpTOj9X!xG6;u3NACTaNyq*JY#ZZ%k9Q&-0gBvWk`S{Y;qlbim#;!Z^ zwYJ{dKbb*3>yCfZE2m~Z1$s+yA`+m__kv0W=|L`W%2I1XlRnpY z*wy=(b}@ocXsn%3+#lB<`i_SD8^m3Nm(K>111b=nH3V1B!SXHhQ*W_I{m)Cz<@uk% zETl3`*Bn7xcYpftAj9XdoVBFxum8iINjINBoZKVYM4tHX;G?gRL|8KRq5b_>OlgGE zL^rr-V)0K&eS&`Y%O93Fxg_0RW?fr@xaqTFyU27J8R zw5x`Sm@wn*_XpYDo|R*v)w8_}K8Njil>K-PNY9A-?z@2W#+gTGF@R^eKYbaG7j!Ot zGNcjma~Tc#45@&3ojHyTOXvXgo`W<-4B_cgum(W|Gk>;-4M2h!rEitIwQ}=;M4sEs z@n5#aqwnoBQXl6;jg5-!kMRX1q!P_N%MQ9G34g48Re0EDYPp<4<&z~2Ze}K4M^AJ2 z;uN78jUDEg*%c`<^hy3YO7zISMYnu?U7BC4bP9idSps;-Oi?cvoMWup`|1YLeLb^m z7;DD)!-PoWKJK|Ff1KA~cYMTcnnU9Nud9pUy>bTv ztD0=xZ__yyz)K0iM0zD)tc?bwM~M6lsHU`SFulOlF$;tUIvNLHBFs-h19VPs- zr$>J~sEr}*x7}nUJv2)F`!ijkk8*+f+Z&DhB2(|J6aed&Iulv4Qj`K6o|bLgN%Upd z8cTF}aAbUU^tSz#!_wLjT7aOCy2fEndG{7fyI!i8m1bGw6_*UctN`RXPmjb5Z!sjAbh+LU>W3|#;3Dj75Q z=_9*OC)nh6G;zPS^`Y3vdj};O9n^Na_9O19x?PW(%eZH#T9WDmUsXCGD4r?tNX#SA z{DP;`OA+KI?EKz5rvMiWSGSy=ffFc@y&|-g5W$pl9aPba8LfGQ1HIEg6uv87k%1C~ z1Us=~j1g2U;bZP7nx%NVDc__UZ~7`2SLt|pb0GM zNxeA+)}K5S--bS+YOzWl=}ghCyOMa7w&5MG`!cfgC1v9rwuhf?#^3o^sYcFT@C!BY zFXR8mb6hc0}H!M9F&QE``z#BI($r9P)Oy{aFri0F{T_|q@sGqsNqpUjlMf& zw}nY&^U#g0{6#;f43LnX`@}c;dH$h0PPUoNARia`>h3MWv+KCMX8pAa#vpbs6~v6J zCKEZg=FAQ6#PgiW`Ww4w1Ys+$#TgbQFb&HdusQP-)E>(9H7TN%?0x~Dt4=1g*DK^0 z;B6O-qfsspwTG9WmfOMNwNyzr?Vl&du1DWWC-^X?>!G#=+!mKQ{Ql{1YlkjJ6B*6a zJRf{`Sh4M2QZCVQIcui|eSYCv(I-v;@~#>IH(id`L_&L5OPf|h(z1B)KhQrSW zGt%U>Pos3Egvyld1f?jRS#^v$NLUq_bI#wN^I+WeHjOP3=!+kZ2CBSZexNhU>gP{( zlgc|z^|26LFiDm>E>@7W7NRICZ~+s77-u3>L}2HSsBEp(a&I(X4g^($gP^+ffX7f_ zI~uOM3yL;Wgdi&H0_dbM7FuweqD$54Wm8=U!{~WWC80Z4=Dxi^Ye<%FWK{C<8UMg* zVzdZyp?j#eT1aAwgAzF*xm<5LzbZ>_?fY)B`pW=|>nIg`L>j6m*lllxULSgriH1x= zGZh@;&fCFs*I!A)jBXN#NZ^Y;q9>mJCs_t9e@qgGH#~6qpWujYrMc|4+#QD7JVECg zI$f8Wt3EqA7+;N!gM@Jfnac<@&=0>kQ}zJq(F0fS^KDbfa9k}g*=Qx$hSaEXs2(R7 z8y~+-Xuk-ow7swZi-G=%7l`2@@|-=)vfW|Vgk|FfhgedCge-=6uyGQ@ZHhi`O|?I; z1+=eJ)??Mc)w<72P^9j-#nRc0Y$HT{T;fU1ZTJO(DtofDSjIO}z(*DT**hFsFD~Z>q?iS;k71Te#7A_f?&fk3N z0K~^T!3e{a_1li%hBEI&wLSq;q3cruXg=>~Qce32hIXSj3~(+l>kK6~?1>Lq8f|dz z+5^Ig44*)WlFZgZUpTHGza&*f)kpV~mO(opz7PTC3Ox)zm1Ev3Z0&W+Bq$*0|Qrv#S>D0aJhqA%g!G}tx zr~f!bO`~F{ikGsh-%QGU{#>q_AvRM!drzLfP7;As6Ti?RgI;B#U2F%_jPT%kyUZ`L z?2sHokEKn)?X79DK{+d^O5c^mH)4|0|9fe;dmf`3&`*nax{nUHHy1sq8rw&~Ain?q zXSJM6cGXD(jezg&xShc0$czVl;hPLvxr0MbR?f?q@d?SAw#DK%6?sz(;XHJph`%c} zvdM0l5t{<}TqImCk8=bZOlMVqOPa(?;35}uRBq*GDhw{S$wK*#x(tXE**N7opP}e^ z6^xgJ{tWm%9Ma;@YH{kIXIL>?RT!M{a5#GqwTZ_CMEtO{pw*bfV&uYS07XzZP*V|# zXaK5Qay_>=AuoPpeL6eT~%k)GGeuj@mbOK1vZTqQ7aR!UeTbBkx zl@!XGjsrQ$7iVJbG{m%E)2c_!UpQaH7andbZ}6tDf+Na2G&Yt!1zyF{USXXUVsChJ zV$?%sYnlHOZScj}rgy60Pdh7B7I${6HLPu))RV=04(5A2O9u<>0){Ojr-&?WLJL(_ z$BJ!-mzwv8u5?p~)~Rm%jNa2~XSfkeJT$00l(Wg{MYUJOtm;i<#J*%7^q^-8;4XsUrbss zOcm>!?Oeo9rU_0z3bjf!~J=9!Ttmqy9L9A`@IiTjQJ_OXjz683xs&QsTl*B@5wRGG_05G( zlcgmK&ey5f))u(->9%{o9ZsNY@|!+49hwI$V?tk23qqON zOT--NP+UI+MMuT2i@cP8X!yEp{Emc2pQ+#)0oq@>1Omh6=E2unG@FnO5`ZQ11sA1I zDZs&dWGpWOMot#fR}ZceIRK;K%~IyNM+T2pvMX+d!3q4C-aw?57)+mPl=$;!tayU} zS!ZLv&w70zVLuNv%5^+5DLqTrr6h_Urma$y2t3!tyVlb(n7&>w2D#%+z`A7SMQy{O{M(_zUYJJgI>NbZoYyj2gCxCNl3%BMs2pwczOS*O* zx%4vh^?36@wod@6vNaj70Scw{&c~x5Zma>Bmm1U#25LVJRyqJ!gPg9zC_VNgcn6)L zrJus`9PbV9{``tI8K!x8z2f&pm)7r~9D=yYP!nSmLp|euvxBY#CW#;a$0l>ATR|5^ z!IKY?tunsZJb4x%yZOEeIpBVXnN*lQ-x<3?^mLvK`&e4@pjU0?|;xkB$eA{&z$my%K zMLQ^wWRhw{@aIVUVi|My112Gm640j<)427wEj=X!e}a>>5sUxf*+{?>3k&ZBvY!Bo z5oTV-2JAHhZCa=$OCH_P?xy3H2vX1y#?m`!7Z3*z;+h&uaLv&^CKhPtOuln$$*Fn6 z!jR;8t$Df7O)45FIGYZf2d0qESZDk^!4=GG{uI^k7xZPeg?U)?!|o1w-?n4XA9t0I z-0ZhtwJg_mfGInK%M<{C$-eWLEr%T`U-)NPGJH!}A$aj*|CZLmWemR-297E_Vfc!# z)mr|i?=jm2J1K90Li(AznO_cMoQX9SKVP1mrtBKoNL)5{6ZDg_zZ9zRy->DQO3wo% zLypX>25;L$hs98%Q-NEfNGzZF)If+en40-h&aZZa}lq0M0&0G3#Jt=YFkKcm%J!~JyY^b`{T_(dsBtaf! z=ym9t157>0db0q3G70v!Mkh=E+8BVp21)-BX?D!{v*-ySbx1hjb$hF_Yvf2h2!}!d#LV0ERSCQb-1gJ1Eq!*05{Zvu5qq6?Kjp7nc6WbBoIn@=E5n;Uc5wwi zdN=O?aO|&{tq1wTvfQCq)wAc<_RFn+d`z%8W}(Bto% z;IubsxV|3f4utDtRjo}d{04=|mZzz(el!cSnJ6-8p}GUu-k-gDX2MpsSvd@+S0R^i zA=W*0+^)vB_oXEc%UKjxow+8(IM#fdCqaWPiA*}^#RdC@+Hfe>jDII3z$E!#1m&@} z4%z2IBk9YPb{q3cHJ2bG(n`|4=MUx`gZ6+>KDz$DbT`OjFP>d?f|e107x2Znq)kkem3;8Y6&S<7e;r&l}iNil{8#(^+Yi9 zEVK?9h#z4(ZjDw(*xpX3D+csqlW}t3NxugmK^DNO#ZQp5tSdw{r=F{1ZI7bABufxcp=U2^8vtYnmG(LAyzTZqa1JN=9&|bXy+A?9NZnN0r|jiWYW4qr&wvEof(;%pC|zou_02Ek}b4ibtp7=dMnxPPv7o_Lmk zKMAEC-^iyw06LkA?r!ywyyLbGm-RP!jEUWBfh=Fz%FOfz1ahnsBiSFq{EmNDG)zfW z^jO*gV;AAL8vquNsAuJG zDL#T2iHt6z?zsf32~!o=b}Obzi{MqTpRH40ypV6Qv}ZRk$~aAPZpHM0T14-a5n&ehv2Q8w3b_K5s8}6i(&5`sNVz$jRfhi+JX5i zQ-Xj63T5Ezl|eR(?9e6hc}!QNFyd-(NbNH~(sy72RIicNn;@IZ#7Z#y!bi!^C5I>Z z1IWqH08VG!1-F8W9y{jWdYMmv_>fN9AC9FrrL-uecgkpSpMGh4A#fPW#HqZL{`lyFZwAEYZ z2+ttxzJt0;Ye{9+7HGst0?NPoAKsz;q&Cftk!dT3gH)P2lsgFjjjKSZrz-_gvFZtJ znm#Tx;7!acww1u(h5rnMWhTIH7v1}TK1a<{9F6-ttnBO`HjjdnE+vQM*LptEr+qmn z>=8D()_5WMuk7v$a6UpVsI_vj$3^JAKfUrLJbw*b=b;dKQ);ZcQ?Y^Mv)zjQLZ04}x(E#ylkUDw13a*U z?1%epC@=t3_4a&g z<=U4+qwZk`nmllKz>$Zg*Qx3aT;-pGwohZjt2x8W-Hs`lvbw@%nIj*e?NAKF`&#wk zz~%ODIk$7KccTaApYG^b)B5gszMT{OGAo7;9@pRSd$?)ce~|>FIOtH1E`qM`bFuhuf$!&viamr* z5pQU!PcXOrKG}XNEPZOUZOOWApO?Ck#A^ss}HQ+NP z;=98$>@wZ~k)l&Pd|n_%h^`Rr(L=!HAf)Nft;*WdtD+f9Wy~)OW=kD-as@bHR4iio zXUy6MT6w$E*@I(NU6TcB2UTYgQ3q8+0cX7ZX}V#o=99w|irRgm}30eZ;LTkJ1yt zF1P2U4+(xhxoO>lN6xRO#B|Z=P788y7oyYN(!SF-&u@O(zxa@Fhfj`iZ#s^~^cP?E z*WlGs#)r{qvAZGTcMb>&=ujpM$?*xH3;k{a6up-x%ivw^ZGlttwPoQBwJ^tEMEZ#z zfBEa@U}JSPX4f@CPSh2QB{c_NKE_9KClnrO2{u*U?M_P^a?9tpReLVCU^MUGe% zi@>9XrketH!Wz^l7T#;#93JvbU@+CDFz+)E_?aS;TEx04&JgH5mKa}*7y#}=bcrdZ znU1`53=DvAOvKP^?c9MDG5{7YqWag#x#Q(N_iUr&7gFxYh#}xV@Q2&zw5Ng1;hw6W zFu6j_cZ!k#D?BbSWfJrxj0EVUZo4{rsrT=n!5`yE~BOGM4KtRX;eQFQEWBk>VGE8P*z4vf;RXY_r zr{{FPz>jKqEQ!CiRG2sZT)DD_{REh>G2g%M1Bk? zNUIBU4$~!ug}zip*`G%J2F&U7Ak!Vqkb5NO-|k4p2rFb4*hK>H2JGbN35F0?GyQz) zI!dMG0NC;umhz-pe(TlvqwhJ2N)^-F-erwL2ocJod$5J4^+>9L;AGu^OYYf_Th$h^ zW$#eyk%(^-=wHg|epsKDa1sJUs~ySyU2SetJ>A82oqm!td!Ps!kqTg9*}9pFMaLcv zaJcxFW$0sWg5>_Q?*vkM)_YVHP-{>nJ7TzDQERbp_H+?k(D5nunt2o#FxF2~eg5d| zT($`?X1-qcUh4Y6cyz<%{Va2miFuoi z%D3_Tefu$zV;QH1+Y1+Zg@`xF&qVo?VQ zI`6)FPBCIBK#{-1r0Ig(-jVm zsID5A8^r9WFae5s(clrz(6qUwe^_pSz@*7xXlQ7c7Sa(fW+UZ7^Smr)c)lHRX8ud_i|XAbE%+eA z-3$OYtdHW_9jB-6X)di!I6S%goV(_I0;`M!_&M=sPj%m6%fTN#TS3`3c}<{oqL z)&nX02}5sQ|C*%Kvb64j8^Oh(IA!u!f=Z4LXSuSl1MAHE2QSG?J1C|U!K;Z1O3#fm zPm-GQQA21k?hfq?>3qOdl#fQOCTi`mx{>>k4@Pnm!i># z;wDA1!Kvt1u?Ox(NxU0eLNCg!4-SUd1l)m95s#qv`)`wZrD#einAZ9}6o_xnZ|&6e zf*d5hy^`fMfp7yVx%(u+<5x}2x0D6Zj27htwsLFM<^4B$gu^bS*lWgXE~D+t6Pr_k z75-zuBwff>8`0RI0Kj)0(YvcUanB&2vUQX>VocLz?;#p}342A{0 z>gB zTHkrWa2Soz)fl~pf#umXKIDS7j2nl23_yNUkq~--fX&C1m~Qdn7ayW8@DbW~>a2uJH*nb|pGYHYSD6rStp)lsLP?9kB7FrC=c zK!;*-+RA9-fQxa_E7S9Cod_o?hyoqihudPyxmUj!xXrh!&^Vlx2hL5)yXnjcg${o=JtPm{-3EtlrFlHAPJVcc zC_f^+YHL_f*y`3>Yh^N=P%~mU*fzqhT7`?ae zc`&A#gfPN})oEwOW~A`8cUnB8`Nk|du zs47v51r&+^7O|D?VeGWC->~e+QJ|*Ff_=U7tJ5VjSS>2uWl(stsN6*67U-#%89IND zAPKA1FEb5{|F_n(s--Z*@L_FH)fA-MeO+w!aQvFUOdE9k|Cp*`zRRDx>e@guvDIA8 z{jmpy{CCxIq3XG5R0Kcdh=ZWw*9`^E4#gB_Kg2>X*dKjn*H$j^-aKkulmq34ZtzEex`?P&%Jh-5jHQKc+J$+oY#^g8Z$FkoX_emncqBETzX_ve+XyD zPK2{E&$c$*LcpqkRJx`&$@R?+sc@x8<`n?j!EQxmRe*a!wpV(@Ps7({qNl~;+rP!X z%p!&>TQQ~q#$^;oL|s{(*E{yKAZW9R7< zfr$9WgI|}i##G0@Bja-@YB}Hcq#e~c#b6DcQ0(0!Gj$48RuppLD@%lYxir}U*X*b)EjUZ->S)V`(EBL>w&p!(cB zq{eAymsJTfpJzf;IWnhL&>Ve~IBTbBWMS89F4V^D7o`+gHN|O`O9}bTjs@3qrqnRK87t&6DTiwmXsk@aiw@jDZ z8kMHB7f*|gd(c_u8@f7HS_S#E>Ll;skN=Km=BD49Gn{N*i#K~4wY)uUAJ#;fy}9gk4A;pc`OIZwaJ@mO z*mbAIZrwYk8TY%|o6KrCpQi-gc^;!mZ?=D}`G~d(9>;^;4;B%}>OtTp!TWx~v7GP2 z>`>B;fp$>S^_+l;Z|EDyZ2PL)pIO8r^^W`Xsbk(~r+L57Y^wD8nS;YUU%tlh(~R+6 zJOa9$|HO_F@-cWIZJ#R{{EODDvDq1|QCSw&*D%``Z+#E)no{>==*KEz-^iWpId=1} zDdHXvZuf~c+6*Ay`x8~fxdtz0lU;Tb!(P$C38X@o6Z*F9vZk)QBXXflOr{t zZ%^WDUeOe}6NaIrf_}vHhQqP#FgXeM1_0Hi@e`}U?$Fm}z4j}jJL+2digw3@*XmMY z1wpAq8*x;g&NZ59lBlAQ{G;;#GhJ~KKy(`JS}yn|I)oSZ;kl|0ghoj6;h;3M?Ky;9IJopog{c=%&7d5lex&Xf%~+g#Ul9DMBK&}Co%JyF-vmA z?&0N^8vRC!C7@u$|MYuf!hy53%bQbieGT!U&RTTI#t?>!IuTwf&5x$YiJt$Q)6{^t z%sYx#LC_pV(K>D#Z{7p7(92(5J^to%O-&_^x(|7k7pXD|@A?#*>G@NNk@b2g#6ItV z`X&W*N>3`tVCSRcNVXcKaohtD4LixNm&T`nd(-&tC{={sJ2Xfw@2ozufd)Om5yXmK zZ50))lPArzVoL_|jkk1k{TTQP;<9cGP=AP|J*ues2F`#u1*i&Rw%yk?kohgil9uvV z!kpSy!Tq|6^UZ;sP<0mBUN}B5pqpS)_MTHQF+g|y~u_H|SP_-TVWe}6<6+PhGuv3T{a@ECxDFoA@AoujvUK2nk#V155P|}f)+yZ zzJKJiKD0s@@(E;64Z_JI6qx)* zcN@}>N`70%%zEaz@|p1N*kD9+lI@c%k2yAkSqn@S4GcR$nhfrbZw49xc;11bl0``( ztRgfq!=WAY4s{T*PaHAG&H`_cZxyhP2v&?zfq7fY9blCko+1YE0RtnbRjPY z=Ut1DYv*4Nl+DErUj_!AuG^w-=_1$ujw_p}%8~}yuNJz3ADEZ1(-`st6(bSHvGi_Epjfu5+ zf0hWSLyHE-Tz2_tG~Nrz>qF`h9q%^#9uJ)?Q!YBM@}c{(2sa3SnL~a5Rn+C@zRL3m z7*@rNC~3hAh#7bRkYT7}{pd?ju|zi!jYnx|#5p7heQ$7tcd2hTtlzoXN9(SnO_F3& zJr7bufs$ti?cktC{ug*5+L#$}I+6T>S#O#Ma62k~5#?c>Q#_HdzTKGS0z?YrJTjW=q6KgtyUIrzTN9dE1bWH&yQq&;26N9m-6trR24da{rG;$ zGbAS#+{+9J!i!P!4O=CUZ?ql6;L~ve*JQ@57;|9;B|(BSO$e!EA3i2+E_^V{XQ8Fk zJlfT!b@9TQJ#BPM5Aw&!lXSm3>SHi?$n2>LZ0F;9DF@iANyPBMA1DXzhh5a2Zxqqan9Eb z7v1sMW-23#?*nwI{;no=Fc()_BsP2#?oFP!Ts|W@;FaGA8ueCgOdDTL2NGpy!ggu) z^96d#ewS0?F~%yUf>4p@I>k2gkn46IVMJ@KMXzS*tj{_`Poqdp?Gj^l?(Ifx_q{4^ z&*h*iwQ`L~h(CJ36TV%`wc;>-H7v~#Xy+~Ul1Rk|ooqktIy?&~N7^$B*ncJBeV{X3 zx!LcF5WX8GZ!|j(iIGf%-u$z5elv00QqQ8I=x9$om<`vF-rKHdE&q^+avG4DJ~oGk zw?w1?KRu_*NCf_Btq*jg2|8ZIa^(6-0oIY~SI)iBna5IX@^0*m5kM1XI_Oo^r0=6~ z9ngR2X)=1P2<;lt_1)VUg2!6bcF)H={+ks$&8Z(Jj`u^T(S7H>Z3+IgJ*agO1>Dhg zHNJyX^jBO!!3;5sr+Gz|7ytWP~5b*6Ju+_AYqcqEBJ+S*SUk@vHX6Uc+dQd z2k+!=P7=^Kkf=DovuBf}!W!_!GiF}t*ci>s zUz3uyeHq0CPPSHQMDBg&azbW+W%X^&=A!j%JNK7|rP<&wF6QGw2^z(5(2QS%?tAJn ztWj@_aKf~ru6YW2T9y$Tobclo}VV9wsGPVv~gYCENa?s8b45?&A?aV(s2(X zn(a!n#~AVN_bua1;-+}M@<$Sg4aCmmeph-uP&4ICoV^>u@*$ezAl>o^T?_abP3#D2 zH;Ci1!a!B+m6S z$X*z3#`U2)UF>s(WxYv5ET(1V6N}XYlR{^&s$hL!=_T}7R4|PbBP$nI6Q#iqXdWeL zV}PB#oJ!#tm_l$5tKkcuWpvrcJDQ{o72DUJigqE^O4y|*Mr}?tZ zK;K`KaC{_iTdgAg#Hea2RA8z~S@0bnXNmHZ`f;>7+wU;$rv5f?<0(A9E>EuPk3RfK zC@e4{CTLw~z)fOvOS*utu=D7KyetT|@a0l2zrIVZpnQ*ljE7Go;c6(ZUUnZ13xzf7 zZEWgPutq=MXKWKM3d7n15P6NdzWma))O++rZyL$$u#l(uFW|egijMr5p9wYD;)H>+ z*IljtcOLPvXWp6GXy#Z3EHAX6!6MOaB>*+$tM8JY5HIeu(T{{{jHBQ-DgUFgtO+`U zIktu|`&gHyf;^XRHHQ7s)AZe*pPKmsBlqZl=p{6k}-{V}#tchX!*Zt6a#AER|Z$>Tzg z6wU2dRbG6EGpr+)bNYuO^x>;E47?K;le??to!#oWyPz=*jCI#rli=p&7A`a5ckB)F zZ#GZBx1$r{-J`oYM&zjcL-bFf;+(mMrvsG#UyrK!1F5w18}R;%fNk6Ubot`mX(!y& z7qL^I;U~N}F6i4#q7m~b@xKE9`$p^vfN8o8#42QPB#X2m@P!vw5)iNputfsOWVuxG z73tu)v$#IT$j!8l>+@?zwa7v)L$dh4fc@-e+d}y}fQ>N;lp8X{Bu~j^Vk2lRfAb?W zFm9Nrpq8{{wN84K;oA{yq7sFwDGsFkWYOZMoql}P?vmna#mWIp_oT?67kII1zbWvS?8EMBOrsBf zqMd6LZ8Co$H!QEdlaj0|Y?@b_hti;ud+*irdKSgW5vKLatPS@xi?+gWvym`wWrqBD z$8$aWmPGn~m`4U)Z2hqiTAas?e_nF*3pq#XNTLxt4msQ z4B$xOyLD`TGFqw)eR5n(nUeYFXP<3RdA##Qmc86udG=Ls-6W!%Jd(&(bco%4wJFD-=_1UD5c6*-dsWhc>}fAt>p zV3LVE`yT0PVHrTF{M3m;MamlA(eUs7X7rj{F`R;_H|gRY@mB3#8{G9bxb54N0q)kQ zCt~d};EyrL^5c+kb|lR+X>Ez78mrNBOr$EYCYOJyc{xy!2V-GBXU%-w*zkL#l&v!$ zzeT_R1mMFZ`}nV0xTY4iLj$j!;x}MSttl0<=g6?PM!T+H)oDmP5y zee|;pXfONIX7u0VZtYlR;|*v_NpAQ}oDAIX#2&uNG24Hj{&uHbl;ViDDG@C1L;;h~ zD|5_8m$XN&s#h0+$((0dTXV1Kwyt~326+zEW9}c5z?`b}hmA zVG8&F^AYD?f8T6*;F+T+mtk(#xU){UcG1KlCCttZ`?K~b1hB*lp@#17yXH6m$}Ss1 zkNJnC1r~y>1FZ*76EHICdCWD(U2Fid7OeUj?Z1cSoCo)|UB(^@E9capVnn|z!|ld& zF(E*BMX9RQlQDE|@C`g=JY-`CzdvKo6wRc3ONImH2*7lZP$2ruZz9K;m4K>7L|qUE zlzU4}_u*ch6kLD4h*o{uBg+PPwymx8QhC*aYEWV-YK{SIQpm^0`2A-hr#|n~K#c?N zFTx<=-S_zQ^6QgEnr&b_)Q4r1+KB!BN<6H8mf{#Vh=1GuUeFtIsCdZk{0Ox&`vKMz zySL>6{;I0Zd4b6^ENu zbWeZ)sl#x0RR%TR_$f4I?EM`z9#z-4ck>jY?_0(;r!mZzM{>IV$UPZ^P5}%&i|&U- zoPDF>CsK|wH*3201~pIKo--&91;;#kY1QKn*qvU_nf+w$)k!jIQqCkmhP<_ub*gRZ zm$Y5!@W-{GQMjjpyKo*!_~zVR$)5y?Gc0ZOxvq5l+u{B23q4!*yL9ZCHZb;-9F_$I zeU&G3o<%qu z>iRi4U)Fw?GRMY1&E9>HY&MN8Pvf4@ViThx*fO01cnCRvMw3`8`gNjv2)t!&*~Lmd z(Gtv~x->271)0W8$olRsl{ma-PJn@W+3?Y!X!D_sE?Jr}U-pOI8qHVp@QL$rzVjg!#G-oIhw_SUP*Gc7n=h^w)6s3t@@MhP>%e_mBCq5l% zAtxh?1cRx1d`K%cATqWb_f)8UiU(uwS_xJ;jm6quiM}v6C>hTGN$&< zFB4ahzS}2wuZz>+B-;|1v8O)F|B55r1Y>Q(y&A~KtdRF)#dI|povlz9Agc;$TlG>n zF2;V-8Th{=@^(9C(N~`~NV}CpgFSwCOx+{I^~*}r>VA;52*jFTQEr)x5G?By$KYlu zH-T&M1!1*YFbO*U9aj84g_5?=FWAY;G$!Hu zO#?(}T>=G!papeHSmwwhEw7kx2kvCXPbB!%8sCe@Ege^k3*EOU`ovZdTgCn`X-BY; z#yyR$@3>ALYP4n45xiMc4#%4>5zxVPw{H_E++#wp=fG{W?$)4ejIHW_@2&AaFx;7V zh*P+|Sv%ShcrXeHeKZDs2Z+nT$fQTYwYQP&zQ6k-O`>sEDdxC@R_SZ-F<%()U2Y{o z-o5)OG7ojEL;I-kr(XL{K`AN#^r;4ES>t35^BsXdkG55dn5Cp=qggK0JSi5LJOH%N zSZ4S11BD1FvH``|@#e4L0l=AHJNj8Yl)^?C6_0sH{rR=nMa6Kj4CGm?(TR+Z*{0&j zfCs{MxyViTE;8Gj!t`S?x>r&rWRa04Ir>1|-<%U0+r4vMB6^=Ja=}~>@2$;qqhb_j z2y{WK82zcha8oo<*lh#WK{tgf02%`@B5kZD|WtS(^e;)6llEdVr%h|=)UMAtyVECpgNgY~>{fSWGx2Y+u z_E4dpW<}#}L>h%CSlUfNzvGGZ#3J|jtZl$^8ZZ`q9J^~0pK9+D5Ww01oWZPmu^id_ z>K=>*uxOtx!?^ER+p?(2%*?zY8RtW0HYm1ILAh_%`bQHd@r0M@w;{t#EN?Rlz`LBD(`#Gp=%%NKM2f4=JU$PD zr#Kt*y7$Gq+*2xvc?TETml;L^6P>tV75A69OQs-~hXr5v?I!Bw6vy)RJ2BfYMPk87 zy#-DYlXkRg@^aTqfB%-9h_s$=F+MC^kwJ7;nlJ9+a*W8^{zMqzAV1zIx}B~Va=gO{ zZoNn0b@a0VDDCae@Vp?@rCNhLjc`r1?$8^|VlPIf-CSBZX`n~tU)-i4LUPX&hQA>d zOLBXN5KHdZQDCoR>54iNxhCR^ma6qLL%DgKosA_jIniTo0+@1F3VKQmNjkkGpSf!F*eReHzf(j{e}7`hG!tV9vH|0& zC$iSf5r#RRJ)mTBU8Im8D~JP~kdesQeRjvKr{Nvp)#6psRBHMGVYgHgNeHWVqjec=${9jrG87Yw>glb$00DrPm#8ru zvHy#SJnBRXGPccxhbnXq|9EB8Y;ELm>fWY(e1%LvplpXV{G$#Q-F(#Beg^b;8P@W# z_($s3fcMD+y%6mU9YpCBh7Un`d;jt$>woFhEA3Y=!Q;2=mh#ReX&Hl_PWB3(r@=%1 zd0$$)wL@5DSn6AT37ug&7PPd?<5G)TA(S=^Q&UqGiVYThsO?u%Do;7%q0g5$Q9MBw zgO`DUfn0oilPPBIzlm=qWWhN8E`n&v%F01Gs}C#iBWKq@Bf+c%&v8jx92}fx^B$yp zR~^!BRJD-jyWQ%pu9cnfeAlW&tMu>R*%zCgvtO~WEWXMz-q5ae-f#RgMw6YE>%jIF zLsktQO2gBTFX@XAxVKfc!?$VM#exKQ^L3tbUh~XJ`JGD`>3#OrGAh1{XkCGCxVQU0xG(xN z{`vYkpo6F8I^?S2q+_?JL(nKS-~Q!pXZur0M3CguDPhd<30J1x>TI?9&AlJy4=pDd znKIQ;rRLZ9((J)g3&T-=2Zxn@G$(UU6IEBH2=@g?O+?%q7^T~qwYtYi`q!<{ENffF zI2f6P#);2XX2A8E-lvn4S69x7|HY@kj67$lBs85SA=5F?XHsQhu9$u$!0&9M_Ie zZD6is(D%~v@_~iL#pAV}2p>d90fK7Tkds5@=;(Mk*WT8qAjH(w-6AY0xlHR%bLXq2 zm44Gd>^-qu4NtgVn@8x`s($>KddNoXcB@T0@0pg9ZRo12t8aFtU;e3g9{m{R)Xf*E zPn8V3xxK~2#5_7`7*CeZSW)oyZjyXBYIr*4TWJ^*ANKI{d@!Rt%qUh&S(vRh3Rayj zumAKP@Acr|z-h8bJ|rJ6;l^M3XtjIw=6G>#)!4?y<^^u>lE4?x8?uOC)}IpI49h7g zD-RU}hBDm8|0JJ-Rhoe4JO7}CbayWdP|>ckO~A}W&?kK!B4{6B&j+>74mw%Hq$xBL zo_)S6{=5F|FSjW#b}u)sFTz%|OA^*rR=4MewcRTr@b=aJy@H>(O&r>NPn%!vYhQjK zNXyHU#tu9kXW^lSSsy==NoS~r-_@5v@Bc6@F?lc!sCxBmG#rKIu{Mx$d<~8Vd_DX` zI^RCd6F?3HTy<}v@rcHPtRlTo00LT=C{A7OmzYL;0gefSu}xl}Kvx59-WdtJ9(dj!TS=2sx~1sS5& z_cKz;ga?*e<*0rAW;M=#d`Pvye|qY#=?`5YU$J@QI>ZE2-l)75HYte_8kxlQ?3_uKQA^0SisaZ!y&!RySdv=5%8z0RU>*d;_1k5+4J-maxLIx*0QUIM&7r@{aqAQ> zE-t8+F7E9RK+E5}WsF&7A+5l&5A;DPAFe)21-GTJkvLDG_Uk9^j!4Tqe7#;1>&H%{ z*i5^)@L22$ZeKM*9*a6}6ggW!jIgbmL4VR;@pUT#>|Fo-_`TYFm4J_8sa$1Ulthy# zg1cwg>2Q8yI!qA@x}Uo^P+glh8-<3<)tDd{j&f6aW4~wfV z(hvW}qa{SXf^2i#qe1O2kK-?m@a~tVN#g^(!-a+S9Nc+9P*Qof1`TcP%}F#l`ghD0 zrX#f-LX#nec^1wrP^uMK7^C??m6+H~?HrHTA5XuRG4_Xph=*zgCpF0BHh^LAN4!*-2mr9TNJl$iDd;l1rV=SFBk89v3ZU_y7Qb z06%zHMy1^S>w}LALCvxX#EE1h;I%~#Mj$D#%l#e+dii3`l@)v*sq8%U=kQ@(VbkZL z!B|Ed>J{*cpTwAUBXeR_*HDb$ZHi-YiyuM9$()l%-E32w1}G`iQ{hP=>Xu z?i~SZu*Ttc@^VNNH_T?K+Lf9+{dh$bcxf1QF~xExCFZE+(mjyJ?H9UqKQFWR{mJbe zDi(vr1czhmu3sgkJK%bbYm7#uAk@#d$vI;ku!(=!?CfwDiKDsvZxFaHqOYF*L;WJn+bySkwsU6@>%Sf~dea?9 zaBQIeJ!Tw425<)G!WMM=Q-GaW+&K%~*xk$T?Ni{jh5MITO*#;ttr=*`%Zf-<5eT+{!tR1vH?Fmw;v{Je* zlsA7Dr2Kc!!wLIU_k=t#@zXSrv$}ik zG`N&z(!0rfAtSAR@1qYl{4Cp#v-prwM4q_5=4}^l z06ugqD&6`TEFMwz$I}DXDHx<;<;=l!i7{eyBRCkfE`BwU!^IimK*OEKd+Y@q zv+IjhIpvb!!PNXrr%Idc+W>*+rr-WP=iw3$4`!#0)QXgnM|qu4z!W+6lhv>vR3?7! zV^8GuOI9G974wY(zKNiGH1UmF^bH$o1p_$`iQ|#0p_sKXl*STh&s91l8H~>b3ygvP zdsAvx*S!)blXjW{s8bC1%b2ftXpw>)k%D{-)diS`gmeYQpiPgLxB)4j& zdkOYVjEn734Ub8QvD?+1pLIUmZl*jGA~1+k#UD{$^DNByoGk6HK1D@EHQS7Swd0|^ zcnqUo&CShynshh*1?Pc~oCY`cc4BTSxRRQ9X*Oo1_(=sQtRhU!aQ9?CnU5@ZKI7mt zn;!|!;$eapHN(B`Dveyr3cG=z6_!0ffj{~rFsq3)p_6Jv=0$oRw^{|<9p zYU6q$f~&K7H|BfqgedW+i-Cv%XV6%Gr{*5ctJ(QAPJ8t)!(Mt zs0^0N$3e#+ziBL=LtNla7ZaM0AOHDPBi6gwKN(nVCOqKF-5R5rZsYb8p+&Cld6y({ z+}l^DWB^4ev2+&L?YQ`hmWglHMQ-T*ktVnkH5MQNlwqmMi4fx@F5vP@5=MVD06M0B z630E8iU=(F8wp37Cv~}=JD2n9h>5tTbx9%d7vdxX0?g1i>8kEmU5pRbo+~64{GxmZ zUq7AIe0@H%ktm$w=BOLade^Wh{LvrR_sc~dsron`fVsSTaaUCxy^}AWGprT`X=X2c z;sk_AS*{KsCqPZH0D;DsDVVA&*TEggeZ4%!t!%tQEcBCjX^wAWX7#xpj)z8HxG4 zW*TiDv+*HEVu=jXVA}kou~7R_g2tcP5;+iE3Ps}HFN^XoiMah=8pa~V7SyMS@Us?G zLNXSILeqQe?mBQR5?vMbGR~_b40yj|jf$X1A`)5g=hydg&(fpkeDVpr&*rOlWL}A4 zKYYmar8->lQhIpA&lB!Kd^hPAS^LzY03xB5oOBETM*RM0ENePLDS_ddocw?J@Q#qD z`--05`9l4wLzk=U;HRS{ong|@H~PL=ion!MX?6N1Qc{NwdUry(FMU!(=CtfFk`p~E zoqbIL3(7fb3s=mM^Tr%mrbNlHsoY%|}{eH=5l{Ibb2UL%R6yT2E zqJY?-giIYBotE`*Z%ZC}GQQgo1}dta!Ek&awHzaveak5w?MpZockIrTX0D0@hz*xR zzvk*8QqzR!_gkPV@N%HSb88U4J7DM|TNmkvo)q3m@ei{>00`P`#{Kj_S~6I2C1a%FaJ^@XDOO@s8{&W2^Oij<*lm3Ey%IJuE9W5H`-JY zs&RH_q&<%%NLZHPiqj~I;j#L(zr}|pT;L=xFW1Oh5*A3iB6R^${~JFMO|0pyBq>?3 zwb#T9xU9|^Ux6ZP)g~6bQn?3jLa&B}{LF!KWHfeQ-cAiDQ32K$>gY&`r1Iwa-&QL1 z&3PKqEhssgv@{Q;=WOJPwYW`IiOp7=H)ZJ3amGrlS7Y8T%r68Iqez|bOa&S zzVcm+mQ}MGFva{eClkuFj{%?tjUDQZxVh2f^lk23pthUsGg4+oq)e))96Z!tB9j77 z^RI`lyWPDDM~C*Pg$ig#`kn`$Q5W_8xda{taPr9G3j~-cIWrR*+KnGvU@H}Y$iO^rA_Ty*59zHF3K&~~A(hf7! zrS@ZLyY3GvlDK4>uwV+(4K}0k_Q-u2VoM#Q41du1zz*`$B^Z>f=_(%ii=s`F~!M7A+(l3wafw5oiuBXIdbiX2Ao>lI0ZN%Y3W$K-#r<6O$_YZ$^037s zZU1tm{z9bN5P4t`xwgZ$h7|ifO#kkWpE0`cmO^A|KVo8?aq&A4dl+|)8!`t6_F;g~ zmID0RCkWR6iR2sF(VCcfOw9nH`OnoC^4t435+`KH=#|euvp-=<*ofiH!)7E}< z?IygG$XoRQu9}9)fv5GK{fpG5_HjRgkOTp|P})>XRw`Eei`fkE3Ab?Fd_J|b7$P6< z^ZGmQ#7tU=2frF%b>+vb?rWupWRQ(4Zji-C+m5YFSz(chzN6zk(llJC?Ny3my8%A( zsZ{M?5^jko-a#&&mYkexHnl6*FgPprcm^y^cVYhR^O_i1GSUVyuYoxov=$Hnyqi50 zwf&S^J8`MxuK;gzRtS8JnyIL|NY7k}Bw}%QWfcyDRTsXr! zaenN)-JaD5|M{PD(MR<|snm{Gid=RNchQFjnQ8(}dD_~?s+DC6RUK6!Ww&V(M`@nq z!G~PnXHu^vR4Jl;p{gIF`&-&Vxd8#+!jlFJ!ws-=o*)ciP22p{CHqP--pp z#2x}3uSNqgpXB+#@8t622;DFfl#m>lKK-s^b=5Jm_-Fc!u100!d3-dphi zw6=Ml#gvoT-1z2;7(s>p44gl)3~dYP)r4qgdwap^YJ7-;0R<&o5dD+|z)0m6`Y3nc zcd>lWJIXa&(Uci{2mxL^{bqs)XLG)!5xu039}xh;;}nEW2$~|FLp9Ip2Fc8Qv}eQt zxJs?~B{JBOY_ndq&-eZEPtx!|)H`XWus_Dw9WQqEXvSD{B_fNNNe*%`RnIaaWdx?7 z1D?Ugf^*k2S1NulBG#NRi0l@!CDs*~leq$(+=^}%JeU5jnUvQWB7|eNLsS)&%m+!5V0F7(p zyHjepARd6K_Cm5)k!2CKU3SyDP?6}4O1`5?85#Dqbns5>?zsSSjdiTV58SHGd;V{@VXG-aBXFR@c3^X1`Xab#9W0t7{EFF&|`TexM)646MPF)_=bv!fT z&qax8n(o=c&>)0w`O*P9z-vMjy_c(U=~li3o!E2!3$QTh)tjLW7-EJMZpp$N1g+n$ zcR8$?l2wf&I!=qHdTvFstG>^%5^*ZVAa|U||623&T(==1=(e!=Fpl`Z^e7IBS?bF< z?F)X#QOc48Hi=eB%wsgA%UPXq*Oe5!b-c9+;Xgd+TlJnZ36bP%H0WqOPsr@pq&}_t zFJtAV2OKidb<PZ!yJ|s9H#=i}?WGmZk|N>-}X7X8YkE$yrXS&UUtc zml+@!`O-7Njf5g>TR@-Z%Q- zGx+Vci+pIV>pAuv`GA%z7zrRLoA#pQTzT~-Sr=C?g8R>tkIk9v-{w<;2rUePEyND4 zoI2Xu-zo|Q4TX5UfyWTyXa>uqmrtk`YTbJibOEz~NaW)|e{;aSn|ykB!Yk}4BJ|IV z#3h(+toWnH;MzRKu1m$t;NH7H_1|6f8FO-%jva^ajE$+*FKtP!YWq5WyHG+YlK+u$AEYkG zmdPNkD*er7Zj^p%ZTqYF(ZC{MRiVBvRl2r>khNi<@}+f$P6qY3zytPJ)aricSz{4P z_(i}7EwyD1dusi5zS+;gI4rZ3>4{o%K}PDZL9|30H*7o;{`dZ+QeZ`_y)Of>C66xG z^9coleqcy`$i4lX5Y4>-hN%U^?Aq_RA;8k4Rbg8MiGx(xXayW!I!M`$=jxU1eA*|u zMfN^>AGMRZU*22a2}|*y28ra1d~5202Cs5ct{EN71yQ5z=03C_uEU3LWueAlQ|JTz z!bACB-Lrun5Bd(G#D_6&r2M}Z!3_Z?G7{YKN|CsTMMM~eOt>R0NnfO;v!>@faP{JBFuAYr?bP4q>u2daoYOhFctu=G`xLzEFSkW zY!T;{!K{NxdRb)yg(f%=d&ZvSkrD!`!|A=VCr#a=F_Hu-jZLML@3HE5HOf*(SX)t)BNS{_G!C zx9J1&o6Z67;>qSH4W99U>lukO8RGk^a6qhs{;`sqikzrMx3}A=UMOg1<9<0z{r+7ieD;DKdm?HbjoQT=e1h{sDfFsgOeTWpAIL5xc5SAI%mC zj3=QBm|?S1&HUu%lr5F|i)~V?Iw<`;)_y1Ss?>_zssuJIi>t?;S?-1ir8qC`!xedt z8k8uwhfznZGfCbY!TO)vF`~;yhi*-ZewIHS9|Z({5N35&Bx1TujJBntdu_Ek@FPH` zAVIVMEQlYP=tx(E=y+02BeiS743Gj)!QaMyc3pF^eB11gYb#$Od;D$o7&RA5yRTrw ziFpe{lUmaRq+TxjEIMln$$W*_+kac-RsBV3q7(52n!!@svk{n*CB{Yu{X($`WtNy- z8uL_75h2kSROMsx+-le?eVU@|@23Z#-<8gv&@O9lLKsvaxFqM<<2hoi=->1P@42K` zxyPH|Tobz_B5Qyk%1rDLs3RIK$Ff6d$wd86;O?alJnUJWH3C*qt^2rEV74n-@aqDt z+p$oFTFL`4C>Nkt=1X(W7|s}>sfQ(~Bm`X(P;#~j)T9;nFS8$0PGv{X)phu=7LyM77fNFy3V z3Z|&ie^zFjhOtaPF|3j9>z8_Y{KU2%_{grw-B|=?#{I|ijV8;^wVJ4o_H8&(iT3Ch z0m2FFb z>63LVGXjHUPk6er_^dDIjpPYPxQcWe^h!XVb-O|`1E51SJBDT`(0-YSD}aNyKA){2 zwVYui4dS`fn8R3JS|C<-(0S<-QJ0^t>>?gb=T#miC2m|<8GVm>+rF|_By4`P(zlzW zIw7jR>@GBTzI-`c^QeX5c^0*17$tVxm+mI=Vzc%=SzrUua9%-WYSxK%!Yq)X!;k3j ze#XS->-2omy=*al+8SFYW2{(auCVS&>6LjN)Bj=XtiPiCzi2!%;T zy`>-)qDQ8hxSPlqFTb|e{Oi5150}+BlW#6D;Ki&axt=p~V5)4Dkl}FFyq@t0LGo1eJ9cznyun@?C{} zwK+^=6y&V6LDQWL_K=R>3%Na7PSu`R18oQA>W;GkngNecZogG@l5FJ<+}*ZNix2cZ zl|bJeP#H_>G1RzQjQtE43<0FGa@FEt2&K4ku&|J}9z?IMe3c~^8Bq5D_( zHs(b5N%DSJz0e+5GpY&_aBS7ga>SFPcA?|NU5(bRAm;_HDgpVsUKJBj@C^o#ru@i8#>E`@u43YQZFjA1GS(wv8z`IE!$Y})y zcI`a3iT>8Fda7OK@09DS(_ambw7M(arIw8f{QMApahl3TK6LVs;8d+07W_S7d#FCI z`ZyTNa~2umrOU2F*DqJ_vq=9EP0<{%a*32gZrG=QI`>zbxk2K1nsAmha?(XA-mQ@{ zWlPjd&hK(-I~+UY8jBuq<$ZBj7j-Nwk2{w50{A0`y)Ll3J634SDf4@GKEtpgdb zf?UR4aJf(3tEfe=piVrVe;^9zBL>&%*1P4v^L`QWQVL`aw}m7V0z=e;u8@NCy z0P&m|Yg_jz-LGkx5BW!>GW`c(gn@)dTs$n4Z=?_COP31BPqa4K?H>RO9=yE%@XI}1 zR1*{+mx=&$2e45#KjtLZ_ZHH8qg$bjXIpiQyrB5PLuoSTRP1MX4Qu7leF=~`@m`{{6(~qHW%j^vDov@=fD$ zAEGBMV#>d>6h4T|9je(b#ZIguX##6@e@&sv-_6Qy)cJ}2%gZCGDr58C0;xB9I~|@i z@?r>?t!bGHHVlg$H$y#oKWz18LvAFp(^y}Se!n&LoGSzGSYI#NZ#PsA`PqS2;An&I zOQ7womeI&RONZ8bDAwP@#eD~AWO985-epQ?VJ~2pLEnq_(o7b+g(Vy(5idea(GzAa}~88#_Nf(1eMa|C`*?@2A~l+R2cNT z2W{%cJY7M5?Ls?zs|$6xz0XZ6^)fr?d|#7#Wh8-_CY1o{f|r;@VP|6@o0HML$e`~i zQR2KxJT~K-;^ThyKg4b}m_srAUgh1@4kR-ax9DR2!BRG7i`iGolFku)2ZU?%#4jV> z!wWRI;uracMwuk36g&dMlQsH@&}Shv8rPgZRPwDN47EO-Ik;ODU8>kp)k&gXkxnnq zefV?OY#1J6B5zaCYzhcC7-GSbeof4?o5r9eJ&T}AMX#bdqyr1N?IlKYwhf))4=l}T z%u72DJpnF3KR}osn6o%T9oRyg;VN$nVyP>-TD()r2xL9PejUOW?J&!KT=`A^`DOli z?r-8##e+M~!nhVBUoRz>AFdDoYy13C&Z0agT`pTCN#l{M%4md$AXpppg zHWsL^?ExheJGpBk5g9;?I%eulD<^uk*KZksD*L*?<<-)hX_2rvg={Bi(LJfOE{ zKslsX3=$1b015Ebqtfb-oh%t?-ja#4S%6EvTS0$uRe=M5fZqKN;hcJ)M{c)`#%7Ms zkLa2WsQ`dw?yL#*(=+k7Ymx*84vY;uRW=@LigXZY1{EK8>+L?3qH`O0Dhy$Kh~`Jz z<3$eJOVx6RzKtRCzMeuBLr&QZMZ{FUnWtL%TOLkxiciyUiIbp5oQOU3 ze71?OfYg#lyydQ!88~=$Pgt#fFFV0&j#)iy5=c^^$rqnR4P$Cfx{w=hzu^C$@`c+?LUe3r_FKa{k-Anm;jnKnNJ7pygN7e z>EAy~FxOt*PF_nT=j zAFnB715bCW-xe9i)s$jVk(us=zY1tajkUMAOkEYsW4pfg`n-1hC;z1Z7ms-BXKWK` z@4b1#wu;N~Qe#oak$^j7tOaKiw-Dv)^amW7zml(y;wK)C_Jg8dcJ;PCT(l*rKfV$S zKvp!=e)$Wg3ogu4N$ee+dZVG{4kpJ02d@NnPu=&o-pKeAg&IoHqeM-+&gi^89TMdu z`hv;nOzYMhS1jXo8Q<55bq23Hffo|9V+IM&Fs0C8Lx_OGE>^REMkucJtVCe%9ke7R zySoR_&|F{!9QytiAU*)>re+wY9{3Z4oFW~x4JaZ2?oB+@ba5 zG=mYXh@w!=W5iu>K#8=1)DHVM+F&)lCKbfvYJlYZ4|;J6DsLF_!!))+1_K$oCIN|6 z0${SfS+-t(`B^l6Ihyb{R_7ukO z0UYSOWf!~ZF|dm!yOJLAfH%x3lGmth5-wT)RRnR$TB{GqcCE?8DjrK+(5iPq(-CCt zalVFr{jR-nYxlP@ZQ0nqep<8=N6O4QT*eBm2y$YMafjoC=fQ(lW;~O-kFfN;4%==2 zTRIk6+Vi?lp!oe(^4#R)Iz6nyx}jGb<1y^?d=+VO-t z=Qjf9#`(xJ{`$16VINUW7NA`7l9c@D8e9xWcsFAl>f)z#@O?N`wNpsOfDdB@vcvgl z_fU@@lDc{XGH-CMfxwJvCaJhFkWx;LafN6Fp2XK8RaR=)R~dKvME|_fxnHwzDJt&O zlD}bQj`_(WYi~Z9@FXY{Wh6u+P>X>1r~U!W_Et{URv6eAj8N*%U9AY+oF>gYiTyr9 zK{E~A0T6%zSq{JnfU(ltncE-67qcb0Em3MSBe*%8O7FgHGuG+mE0wsz;4*=7_2t=W zEFP2Jssvo@~|c3^pz-YGQCpsAbJf4qcz?Seo8ZAVYs}{KQ^7jYm;p z`XCfJz&GBd5Y`16;_)rEjin~Z;VM#3q$Pea#3dl1RG{0t-JPJk)`=SlCt|Ctz>ma! z@6MG7-f+dkgwNH~>8=QSeZ{d^i7!R6F;YFg(_9YnzG&crd51M{o^vmBxC4o~%BX9# z^V+t|Y1%a0E^mHeqCy;u7=ubOHJ+1v2)Xpi6`^ zu)WYqi%Ow9vOWB|U#}>B1Tn$kkoHB_6xvIV1g$;Q7Ypw@l`waLGA3 zs+HNx$JxBPxXZe-%`hHjAxh?gv#y*WZt4ST06`_pGup0e3213U{GvP#=X~f@*_TTy z2dRQqB3leP{aX_^C5VDgLu!06aE=04(dC;6W50f6e;x!r8#EAgedKk3Kgdj%2Lror zEXeN0y*jO$SKOl4CeOA>V%IA-1|qW&WDXd!-|eJ?sQHu!x~_roP3wMe3jK+)`IQ&! zUGwas;j#Go78e14(Vp)u3zUN?G!K&_8Tifn$SaU?F0{TX3QR0ti&(6-&ASzRQM{(A z%8;aomJtgx}T;MDzhM<{=Y*a?bwYS>q&BOwn)rgW5y6@J{68eM6e_ zz5*@)uhJc!07gxW6v1o;%NE6^R3G8aoxEQ)w+6@DR2R;`=3|qsj}f~t!A!AJz?EeJ z^#S$X8Zyri*V3pmu70rC0Xkt%ZvK*$ANknL7n82{gt%HMn|W*rtMq!li;C?*9A6}5 zMLK>%nsE7|05J6KIqg%RWoU38j#$xk>BmiIMx%q0d zQ@{JnX%W)Wg8!B)eaYkBJ0I(*uw;CaXPYxL8y0br>gX9@_J4!x1ODnnjW2x%2L6TL4{c8W)s1pq zy17aR)%vc~ScE33)wpdd$5W6x{3M~G9(8cUAa9*Q24k&uX;vPRfV%@B6~*f$Sy5(q z^WDXhQWTTwQPwf)|8yMIAJ<+xJ5B>mFS(^jtcq}*Pg;0rb&iu%IKS*n&;M#o7XAk4 zE&LA!G!K-Kjl@(B(~vppkX&Llr{o+a?DW74waWMld<#qOD}7l%v3DR!@RZ@3tVcYh z?MCjt%x$hd!dAx|P&;|ne`y)@q^P>)zNt7$SK0xnenZ30|M6tin{%#=#~U|@FLf2? z{?YHf;8J1k#E9r?%0)bI<6(^pBdqBTh`7OkRD^HMZ8W^`^jj>S)5!(!I}9i)Qt+mb zX&?^V(ysIOP%!5rGZ=X(2+8xF{b@1z|zy zavs`!TGh_<7&lSdQB#5)v;{(gpYyr3?+ot3z5}nJpW6>{re_->+Rdhz!+Y}M_-qi@ z<9dRV9B~>b(XFXs-?6EzGRBFi?SSYZ5aZR9Y*@1PO) z0y-W&Qa531B=UaSHw&glp#K{pV8h}6JR=#N{w}N;zb#Imy!WSd*y2t4MOE^q1kPk1 z^J~q`rInw9*fFRNZ2-`F8d^#cV^p(R#CNl&fj}J!LioDY4G@^Q?^^a8!x~O#Qn|l1 zmmg4zLVqL%sRTc$&P3}pLTmGxQDk0)AuK7UA(|95e0cjtTOOMM5CfEKec)XX>qgI)58YHwqO!S)TfYZl$)C@* z)6Gu8U%!r19v=EfG?snXKA8RCG*|K7%4wi_Q#A3BlolH|Mhv!&?{Y4-me z3IhwZJWhS*e^$T)eTUZyfAnyc#)$F$HxIfi1HYzA3(-FTdSZ>Ot$tnz6CSV>0HnxS zpFArZo_`Rt9z~!9NFrn!(zhUqqBsIr&)xx3fRq3nx8+OeG(4r=HvSu7?dkpm(|_x0 z*g1FC-yUy#e42~U%m_Pg$aP7^_~fG$_XVJD?ni(sLLcBQRNXj*Cavsd(261PrPJ48 zJ>-%~S}gLhBFs4pcnykdWO{O5X_tH_W5Krd0j!Cp5y3IBMD@L>SkV}hmMwBMUpxif zTBdvbHiN>eC~MXh>51-;@TztyzK(arSq9gB zH)4K;eq~Oh?cGFC>a=El2wV>g=-(HpQeMs%It>M{)=ehfskw2-S|EVH1rWNv2+q9S zjRz1=-1q*zUJ)K55`ZxDiXc0v{{pV(CAs%M&}>_AW8V+slm9g%@j6*`dl!yR`nlMO z7S(`@mX1Ww?~{decs21pfJ8-aZ0tfQIGEv#5xt;91RXJ`SPS?4z^)jJ2#GS_(jO8R z){S|F7D?%J*Id6cf0XL+ZAQkaaV|Fto)vUJYbOqcMbgRsPFvJ<7-VIuDCGO&h8FF# z`t5XvTskI+CyDw)?#>+~9{yc_B8IM0ADqG~e{yiR_=O)}BYe(UOap93z{m^gG1+zG ze*!V!%~%8ydq?<3obvHsb$-?VHX9z>o0pJuFte`L~t z@f7YOC+`?H7#XP9d)a0o%5WDoq|S-SpevIN<1nSZ5N5>wVL4IZ@ren1NB5 zf>!|)?P^0pyBpWzda55`lU@L!`>s=Mtn0?nlE=fR5R~J~t~Dpctwd+tjtdHtq|8(r zY_XUZi;r$%RWp8IIb1F50z?A*EVUL%i@)4KufFczk{5AbemB-(3N4_D^!W{Ypa38f ze1O<#7msqbL5i~xP$5bgV?)-YlYm#!B!b1YcPmReSZD%gfq{T5L@WkDjseH5vz+@c zt3!6mC-hRxP_yuail@&@v)n5V>T8*A1JWw*Fa6Cxt!u!HlEIBIAKOyS)y{|TUzkIx z3liZ;>q1O#t+6c69l3C*P3RNQlb>W}1z*1nE#&DBzfm1UBb0~MhF>^r4Okh|=tE=? z8J=ab@O>fgLNtHQ8w8n40i>$U_*GfR>P=olP0||P~<$2j5Cu zG3^3`F30$s24eOyUXdNRykk!TF$}zqL0{wvq$c&Ytl&!xd%72~D&XJdJ@EA}4kcqs zSIl1m+=iG>Cth9kg6$iaftNCWuWeymj>>J+fCmFV_af3!xg60&Z8X4@zayt%=ThgL zQdp>>!8$M%VC?qgJnr=nGnz6dR&fwV>~CR`57c={5s>X~kNva`)}V!Nq5SN)e5{1A zxo82z<`-o@)W(atPWv}K2elO)&2*!!8AhU6q1nmVo2`8*u-;^Jl+d%I7O`j8EFaiH z2b&9=p?RBGn`AVBU6A!Mh41qOunJd11X`hA?6wlQL?KF1#q-XCvQWHEaEJkyNZmlZ zRtN~GJKq%%n(sc7Gascm?ox+s7SQ?Gblf z*Jzz>Zdkl3)24tQr@rc}$_1UsE-A?2-jCG|eJ!EbAI}vPXJttmBaG)=v)R)ALky^@ zak+9-SitG{zbt@@t>|Pyte(}Q#rjYuz6&~tukyn1`iG_ZIXX);x2%gKKR?v^y(&7pT-hMrZxm~o!+MqC6L_Vt?!D)T>VzW^5*?~qKN>sv(1kwv!f}@? zD508Jz8AFwHy{N_`y~p^bH%auXWoUofADxt}bHiz*Bl#m)JBaT3<21rU~p4J7FsF4hP5u*IW zC};Y5-IVOUN0r2M@t>XU8R6YNs`$xQ@T9C`csiu|McF3~9y16R9A?8PKyXB8^U0+G zuohqg#S=2FxL1?r~GLSSwg z4a#m6voNl`PgvDw(Da9ROn(_F*klp*G?96LjbqQ5EjkF51!yON#mzqRu>QPS7>Uu| z$=z0zd=^=DSoP9)wnD;ZBX-q6rZEqtcnG$VKD8*UA)vwr<6SIVekgrk#qEm0AXv$H z#pB{+xwx6u@G7lR>b)v5ec`0yp0|7cXt*zQ_yuBMMT;{>52dwJ_QJYZ*X# z4~n3Ez7cNuTdqW;1OXC5T;dQ8<4t z0)?Z{su}5Ca_pbU> zVeAm3=!=lCE6Ty_KpflbYka>_PG<3YkR4Vc0k~qxoJ;3hHeIOo>Qx?<-+At1lEU)o zM+N%>c)uQ5F*wp4Z0wih-`omA18HH8#GQTX!K4PxoJ7yHw+MZL$G`*q3WJS()LPs8 zH}FHZURF#q-+O+zl{ML#Ve?Yx8yR3`!-Q!I3q63pR~6fA0R`$+VfHk2<-yMY@{CXZ2# zQi;|}SR<&g)4LCE;`-%~>Jw(DNpP=a*wUXj?yF|A2dYV@u@=Cd`msMlLvWL`k3owb zzs25$yMVwxJAL(!_TRo7@68E4KmT=)>KDf-ww83!d*rX}Z;oU!jr-)YUZ(1-H=9Sz z=<^vgslO`n@YU`)c9ol#ngabmw}>3@IgP9^zyA-PP98SVt!cG5q_dYR`heKIryyhs z3QQD%0vT=N=Y``=lvJfAFCFF8aSCJM*PG29ih#Ef;%6eM9t_IC*Vq$Z4tZAF>7kBC zLVKFOz0EGahrhq%5$Y)cuuulz1q2V0)cwLX6`S`+ZaCge`@ChRQo3rrZKqOEk!g69 z>s({`Y+&~C5u;eSV#K~KGhmQ|{}$oU&^PoTpxVcdn@$Wg_Nsu3>ivtSxWWGQ+M{Vi zHs73$XpC^ak6@WT?QwU6Osoyo5ou1)ZPn%L*%W#oO(aLWBi>u{#C;n5_{%NcHSE6d zQ?+-&bB{<(*Lw*JpJE=V1FyzA`USI~g}{};K@#nsS?rDatA{ZxdTaP|w@*)FFIoZc zU$nva7l8sv@3VqL(>K;51V%qSk4MAh_JrY#f?}n&Z@(lD)I~(#cdGE9{9?@)-9zW% zA+#nzW;nNG0bRb_W5j&ujxY+l3a!OKvcwq_LNM=uS5;aHAH6i4{5+KiQhUE>t4;qv zPP*~doF7H44+o~E)E^z@vIdL$hc_=}46=YnY6AS3;8FsNiQ`5Lqr{_CEZwjTJL{z` z#!B;xK}dcJ#xqj=-pWHPBR5R?Y}b0hPcG8m`SNE0O!-{XW+wW*CPgYN1OsO z?BE~I;1Bdt=sOG-1#fS``)L{6L_l0q7#D@{nTR>=I_NF26e2*$`;2@dV}sg%-QWxs zv|h6OK?r4+8Kl($1|eM^b7?AFu9-=!1ydAzrScl^qj)D80+xlSGgClfH{Lq902Xt| zMqr+iufXoF&%Hk+UV`hDW?grbBK>tEM%wp3SujZwGkPr*VeW`nAS8gNLd_SgKhIY0 zrlh`T6y%yetCjZAfdDgC@~?XlJor4&)l94U3X_)+ZaFRMTQp=Y)5!eH9b7lJI&pHYTEjj9@=5NZgF_#}bBYpA41l21r-B z&qaAyP1L*rcwh^)VTh;W)NXB7o$?Ge1H~Ue!Q}kxkf&eybzcMD7|J$26d7X z(Z z9cuHQYkm$120c^5ITH8GRo+gyy}v0|;X$-N$BT4M;|h5k^drB;Xy#xDn_*x%O{@YO~?(mR0pnF7ceh#$PiKzCqxtAh3BEDKNOIjAa2vb?jaej`Dg zfs47ZjfExxhG>Wq#H4sX*IZRYDFWW}ZEIK^{taM-%1=_RIw{Cv-h^r69lL19U-b8x zBPXDP5pB`>3{{aUu^AESL?Ya@0mZ(FUBDHM-FO(fawhF*Y3B zS+vI?{C(aEnESN_L~(6J?4%U>H77FIrBuXfgXHVURuP~7!$@L89tv3b7cLLZ*QFlt zK{c?VPtMB%?%~z!nna!d^HD)Lsf7S<+XI{28n7M{9EONeXSx@g?oAob<^Ita#bH8w zyw3$;y+m$<_P1+Ep&<8N_d)D9oR*e~hRaw%H<;%$dc!idSOHF|qrZRrJFg*E8F8sb|OOdi7P>pjDh#=RztDxgPD-b5$taI}!) zaGb?fbupjW=MqA*zr5u47{^vAqkx2=K}mV6=UTCZ)kwdfT*(Cn4+KhmJ@ozwyhib( zzye_C*DMz`e<8TRKP0;forfezu11j1k|=IHKB*;=rRg=Z7?%9KsGMr!uU=^{^K20q zMkD;KUBTOmh?2-%tj*gq0`GGeQ$Bo6ncyt7qLFBeE%{Uvl=rVASK^tW zPOZzEqKi3Op7&rQiTb{BkqSPfFsYS<9D8 z7l&J!B^Yw>rpPG32bMKmi=f~sXkFk{tIy>}LD=S#)Td4B`FPMn4?k7V@#i`CLO6f? z2UY%Kh5#U1blU)@Vq(f5hlLnFg28sWT6Aih z0+a;+H)y>|YvFXa+UPUF3{nx<6Rx?!U+->I)8iN%DOK}nt@a7w3m6}#>afG|JUW41 zV|d3YNc>2ORX4Jpg=NG4v_+S7fIPI`vdPVBb*xR(w)>>lL$X+a=P!?-*Ec2W%qaNeZh;?&E10HG0%j)lL_6oSLcH(&vCYTKF@+R#5PgH! z3KTC#QmcsHy{%ac`;+U<$?Q7V3iVx*K`zDx6bP#Y9dTfgODluTUzWC!@<5QS$%r_K zPuHm0jt+63Fxnd|b!uDAP+6n{S%%i#PE);k7xU`kY8-3Nt^A z4qDljqRbr|!p-ht#lC73FvtWvU$i2b3U4^sOw{?wX(%?JcIV$pf(cu&R|{^5zn)aT z={akJTPV`iD}MZF-ja|XDYkyJ5m$)Xe&{KZOvFRo8(xcNjB>1T#nl?e2IQ_BCL&5n zW*J`N%TFp8lCP6-W0%H%i%DUWGNe>+Dm+iH6+()120U5r|ArtB5N2E&=kme!|g7tBmO~OtXaQwxn%u!kyF3K#L0hI;O~xA zHNPHo$HmlUH!Jn_!L69j%*?bR|MlaF)xh~Yj{0z}GWu;Ex!^^Y&VD(vr(Qn5p2c%^ z+W+T$Mdpc;R9ZQDQk& zXSS`@Lc*8NK5U@_G-EmKjP%db+|J`razHt5b>DVm2 zjTh7rhogV~HC!P+X3s=8TI|9hZWWC=d4{7YQ^EH|@vvfoLp;~z&L(!z1<}6FS&yOv zO%+L*Z0=Ka?X?+`HErKtBOX+XGoZ`Bg+IzIch^6@FR#IMru(rfusYfvckg%*i>!rzt&r<+%>4YspM z2=>;li`z9ZY^J`2R0ZqaU#zJACU!Lr9at+uL!deJ%WA)u)8a2x7kh&3dpTUl=@b|} z6s(c*N=R+poCP`0v*)C?cQ16Q>v80T<(a)W1b7GFn{a;D? z92_omW70nRG~cYAslAHF%!KfQKPOAXQwQtj=>Q5*g*tVPu7dRgTF!qxkciO6=UuNh zz1EPAqFuN-P952)Dct#f6D&CVLLgDZjR@Sb0`8rUUz()n=bsAfD)QZ+;r8Q(ObCUS z>&7>e0F)^Gmf}(oziq?$8b=nlwf5Htsa;-PzQ{T5$>E{~SB99WS4QHX=Uw-gTE=J4SkQyu&vq;Un!bb> zS2}EJx?c}JJ{fx|ON(O+CJ1qub*{KejP|>|o>h?{J8oHND@118P~Yr@dzDm;8F>SbC5`Y01Ld@4`HKr0Ax1S6R5?!*#c4~(jBxyJ$B zPK8s7%0D7}GT6cmUJaAGeos-f{HV)vL*B7(^Bmo+tBqBiXx$O+{ z<4GsZG=Il8I?P`KZi8Dgn+Sj>3g}Fu+J2uf#4Xe59UJez7NuGJ)>~sTg{~SOVlWuh zq5a-w;(s4l`ZiRlae9)1O@*^I|67MDz^HYcY@U3AxnYz@y~|k+CryHcM{Xq@)Z&tR;cO33J3=Y& zZOED$qYwj|>U!<+Et&!WD|^jrX?M-NOOfPmfZSS)z>2=mv~|=C`_a*>+cRDemAHH9 zYI**Bs%qu3Wmu&jN3FUs*4z3Do|MBa|CpkZAAh2f51sT%2gs5xD|ubho+}QuMsqq= zfX|0|7*rx1Z`%qid-0L&I|yhmfrx(eA#)xdKMu`ta@2K+b?t2>`7-Gc+(RWGt0u>% zAX+|@(Fj4P#$Bf2n!^Xa(x-HX-yO*nX6_sY!54)2@=5V+Vo1R)dT42*x!w^fRJt--v;Ae(d z+#6MZERygw$(w{J?)CKa^hW`bhmD0Vjc1fnBY=<|K%aC4!?bNT1#K>oKUZx!b7&;s zW)XiXF0_MxwKUmaLUh&C7*t&hSIjS|GlA`=^A+Hs?7_AemwG%^B`Pyp*b$9410!w3 zZ}On9KwPZ|FT^iM`&5Y9l6XF8ek4drEy9DLzv;Grud-D03%-;nw`gvCkK`UX-vKJb zk=CH^Q*<}$b;B;4pq7!NhN3@nk)Azh0gvnbmrr#)06%(LZ09|?N0K|^yFVuj*|v?j zH24->-%w|?v8p<_hJyj?m<6U4T1L>%(?AmSbycu;(!@&n!#c`t$*62jk$XDI%t_K< zO1lG;8Coe@fXBt-L~E!(EU+oXC+h@k`RPHI!^B%V!SFJGf8-MV^nJ6;F&YZYWM zK}Ar(k4LjBdGGPyzpVS@e3DtqMG(B z6%?`_UgDRyQ*WyvbYPRMyq@YH$y35#iGE5xFl35Ot30IHB{RhdYudc;bdt@~oq4lR z9%Z)N{>z^2fTcO53VeuZr(XQARZyVz=lk$@i63fX&6}uvN3AfzCI+X@Aa?O9U;)zvC4eXvrxD3r z)CvKXs1NZE0&m&Xel*5b9@Ql7Y-th7+KBUZ#?ggZSQYPy%~6wq{d16tuPpYM=q2W4 z$fVXasEdPWh5Qw)_`6+t#HO(QfoJS;WWEYnUhqk;`0L&IA62;9EvT*1+rN`%3gGh( zD9YaIyTTu%cZYy3v)aOgwnTb-U43(T#~aVEzvdUz(2o_#Lq`2p!Udp&vIZ8yUGk3@ z>C0vPDgzXhM~%OjBanayG6kwd@PE!(mq~3q2Uqa7{$)#500bLFL#M|BRw_d~y>43dF2X0c#gLb&UT345irVM0Qd9xd zHkEit_O+}yS+Rn-SqDFLKIKFqRU+((%wRVFH%I_N5jf86mophm>^WLq-hcCng*Ynh z+~0WL;eXs=r7|w|ZcuOg<@%dSN_|hP0KdA9+arid!r;00QQa(qfCS`tO@f|A_;G}J z@*tdW8l}ZWU%rD@;=*&Q*|zFS ztbUxXu^5z=*J-!+$@*iro}t2+{`7_0=s|D~!PcVLJ+FrOkhx@o$7e$=uWXJn)f%pj z!|C93tcTmbXn!NPvEvXTFET_|&;Qb5<@}fc53#(J_xT39q62WS7|yWg;{gN-q zmS?#AyJVV!2JVjMp6DV)f;tNcJBiIdVcXB*Z@?sIhyN4;Khs^S+Y|VfZC;G~ZC$9KXd$^SjSpAC=ijIF){0lGM}1H{CT2wOyKambu)<@D6m zxpHo_^I07AN`lKJFQj#&$wrKelne5~Dj4uIWHOGwe&5F-ThEESJ9v<|7pj%&{b-dM z(k7-@elxP1`rXku3{ zwSl_O5kNmfK$8%$f6wbV8z1^Q4Ii)36_3tp$t0bYX2f{%cbC#G7=cGv$Y$P4z>~pj zk-t9>09O3`s)s-naK=PhiJ&eE?u;(7RK4euoNrev_!Fzus756JmKSWZ?_`Z#>ZTP& zwQ%vP@6Bkrql$X12TQlVttO{WFU_IyNZt1<+U)x{BMvs3sQTNW%S5eZlf}JmB9|Oy z4Jxcu>}GHQV!>uE(==2Vfgg83DNlHi<@k+BI3_JUAT}{1{SJ=a`59% zD$m<4Q?Oyg2v)LbJM-nrV0Ue!N@k{EiGa(=je(hp5?0U_6lbzFZ}0Hk@uHNc4u6@G zmL{)w<-gRSZ#L{C{y@zww|JroM0b)KO@M@s*+*0lWcC@z_@AAp&KSEnQIFupk}c6G z%L=zWkd(Teu-o7u?UqKeK30M(oQy3NlfMh}A)BzGk*@TXvaG;lv8voudjP_`_JCmj zE1}6gbwkh;4$kn`WCIneA}td&e@X4#KwA4&D<#y(AVpp>^F0f77fghCfE^xP*q=dQ zK!uk=d&hj+f1h(>XUO?^7cChe2FVOobA_cpU{eE3>Qe}$38d!=W?na>Et;}o4cT-9ig-ilkR@;xn4hOAws1Z*z8xrb@Xix7dKSE}A((9?Dw z?IXT<_Rpc1ZIKwEyFO>P8W2zDIc_4|X$3Y*gUFW8@$R@X?v&xePYB=|&<=m9;}ryd zS32D+ONz5_+uuBR?7k0lP79qu_R{?+jdTXP&A{;k(5+LPk#0>~=IkN1PryV$1%R(x z&Y?Ff*^I{f>q&|+)ZRPiZp|o4?t$5m>{L@J+n0Gf=f)(MGSXu6Vq9J;o!VC+9Xq>n zE7Lq<$3_Q9EB*YS@W0nGVb97^e(KiAHh*aV`2(wQo5l?-iUOIRpC7O2L}xu#g!UUTHIw$r|WFD zm4^|iC*R(ym^ou4a>6bjk;D(WqB-$Ffh{wpc>{{WGRhkkA8hT9YmPJ`R43lmRkvGJ zDuTq?N(KVEj#~;5&c^VA6Sl(f=3A4*eMEND`2KQdAbpP42F&c6;j)vx3{z4hMv zx2MgN^*=vw7X*Cnd-ugaCejr8&h_ob>|6o5;g^4HJ-}x@Qt~E<9q%1oB(D(lCYi%* zsZO{Gfn5R{uT+fUa{L>XELvmQxV=z)Wk!U_2*Ws|e;ca4d>#g+l@b_xk5>{Z8Wisy zbPiR1rvl&EQP)p2YYfa}Y)$qNYU}Ck*eOhr)zEoN+^#k`Ek8KSA`e=c$i&vT(Uwtj z#eSm+dnS`3jQJKPIzUNF2&fzCMhO8SV=d%~`-weKOs^QA(+9|9(&(E7Tt{~Mus`GX zkjU-F4%h;^5d1=t0#N+%k9edWHSmzHWbGJV9`?)s%lVn;OGuo$IsmA{zCEw{!JCZd zF{>r!d(T8BWh766J9;s>tEpEwiP&FY1+P-3;!^Y*zr6|1q5u9eJl%15)W4|B7E0(| zblp1FiF$b%1n7sXVc=q|(Sg)W9O7dzQ=HHjk<+4&m}rg|DD8}8eHN@R7Zk|`&BIBY zO@UX~`^b}EE74z{?s+Tdm0tl;7^L3se*gkRsOCP;MYy;tjR4ZNFVyNyDa-qJ*pJPH zo&j2AVG>5&(IRIJnCriiA7i&Z8P)0<=#|cTUX7F6-GK|#b<_Oq{u%!ieU-gQ*UvjF zBf~zbz+*9q_4~4l0J#0n$OhPH z1<&p##`WI!RedxP743g{@F4chmkhXxtj0x*PWjna6i-w5_UJZcMs^VDizB}Io&zW7 z+r_TF{8szgZ6Ph~*8UnNw%~`Ds|oDGm^|vh4}rTZ?JpWmKS2%{gja))uB`{defiyf zypv3iktxAORBRsKeYJ2hn7Wu7BQ=>-e?=oj0hpDYYk%x8ED5BW96Urm$?GByATLst zVSFLO21h6y^EDCJ;kfsI>b{#KwR&IKYNBz0hide}ujHRFt~iW((<4XR?yA~L zL6atRr`qbhRIT}(Cg=$gbaqdU7?y&PSa2O+BR|IEz&0ntCtn;>m9ET zW;eAcAA^%Tfjnff=O(zL36BMOVpi5;wRkc2uoXJ1SXPoapybj8bZR_$FA}=Bv*b`6 zdvl?gOSL%oA7Ttwp3Y=1AGaJL$AE-LD?W`!i+WAF9GOZZTKD_zvIYGA=+^y%FH!aY zPrZs`cl^%TzVA~q+2 zA@dIu@4IgDI((^nlR|--FvOy}vocR4U*asZ7HvV6!syZ?PriWV=jM~l&>&1pA>mw?hkL7g~-bD{bO7@DAenoJ8D zag5{LYrZ8kDiMp5jg~o)MV8M>w~nZs3>4X}DkER9Xpdaz=Y<1H3AUU>70`40#)WI8e%~ zeIMXK%eOAw-4YyU;J2edAQQ3k&cqkc`n~k}mr&7@x$9eF4c`9D7qbf6xd%bA|3lVU zhBf)VasS?kk#2x=3MxoQH-ixh(g;dPC@HOUj|ORw78p_z0@BS8rBh*aC<;go7@g04 z&v86&p8xy3ymwvKd4A(FeC+npQWv4K&8qZQcxg{^dJMztkO06Vqhm4rbq%k!68W)@ znHiY&I(sakG3@RED#@fgq#ZCD#dtqKQyy1%F=M z0va1^4k*0WPL0|# za=l9?hB9;@&;$r45Q;kJqIFT;a=I?@PD@Ue>&g z#CKoBKVMzXyY+t^n=jK=-9Nx6_wM!3PYVX^leg`*ZhhPgW07!?2>oHFXLiY}kj0#a z;=ffK9m-U{$|!-lW($df5SoX}{GNZ#W9#w-5mT^JB5S7~r>H|YiC z`QW`X^B;V`aU!;&77K6h32{w0ko=jF%96Brmo*q0BQk$q_ZBHLl73vNUlhrbe#%Uk zou~V{k?V-{)(qgs@M6y|RsU8u`;s@}4yr<#gMwrBbB+Xh`QWS5iTU*4{5x*?q^8DI z(l!iR6Rj6|ljiN`O2dW`A~4WFU{fwWs2n`(H7_@x(){B(>F9p7a!~BSSN7+hajH$c zaSe)jzQsa3LM;}S(U7|YuRtpGltF7z7GKM5VfHS;LCby^O^Dl{OoEM-H!CdYyLw~{ zTrvv`u<(W`(ESBy1Lp#PHNmU>8uq&eAEJpmEItS-?)d2cs#+964Al#Yw=IFg0AhjO zyo^a3zJt{5+PZWf7r%J4NG}*ILQHFPkejLNw~ocF|7Dbeu9NeKMivl?bhx_mxN|XG z2|o2zqmUdvdlKSsNR*^1HJZmUmM^Yq$Y*EsFPlF&K+y)b^3umVQH7_b@k3%{JzPcU zlSqh(A)4nOX~aM-_%O!nIK@{zOzjOO;FwXVs6Q5b2)SJgO_ld2ofUlA-XkKDyeVvP z*9Uf^_k-H&A_SNh#P>5kCGKDB%S0wqtda*1F|_ccsy&KEydvG8aX2V3MmR*9-*+Lm%-g5oG7h2Ie)_xic zMH5K#cep#bPQTUccAhP|MB5ukd^ZpSX}2Td}ZZdSqc3jpGjE-YTo))_-rT-w?=x*qMX4UwfvVh1;)n}aZR)4pbJ`XT5yL~ zf;)e}R22L9inLM}$vM$v%DPUOTr@*& z1&7|R6ZL&HtudH#aC11DpPlv}yj|+-F9QG!*Bn|=5bQnO6{hz20mVkqKazmFUR=G{ zvTlbpWAeKXVa;OO!EJ{Pt0)fAKDV~%J@ z_xg5*`IovnflO{}9T;?`SzNB$ScO7(&Noa0e^t~tnA7F}lwI6+ePNNJ{#1H4Q5jBn zXkfS^*TLGdV8VnTr^d(h}>4_4KbZ%H=sH~lhm_sM*5hWX|tq23Gmjk4r>3t)I$RDj#KwsyN(o{S|U zBH-+A2Gn~qGf@vi|4|l0{j~iHiC+mN8XkIw6rzSmr-vL`O*mX;5Byi}l|Nj;oIfA# zfGR5bhKB?0_}?h_+kuUq`Ig)WhJ-s2l4x+i)Ml)`LG%csH?OD48*)B-RXaO-ewcV; z(zh$>oLiQw-S@oov)T1xrOb2F&ux?OT3_Cg)mDc9AfCBfNRI%E$ zYW0qp>jz_d*i>|+EkJ43GHUXT7*lnvE&@_qt9hlH#^b=R+nvc1;Hj(#iqdu`3 z`=If0a3lz=C`GxVoGbp@Zo8t4aS!!*hSFV~BJQjKV5#m3Zejl7-kIZWS-_`V;THDu zSX#W>z0DLiMGuQ&7W%YO17@mTdwV{eU3Qz%XUkK7|w}b+*7x08dOs_n*(up|>?)mPtu1-{0Ol zh(xgkg%k+sRS!I!ChPAq))w>zxz8Wuva>`Di=VkF(2vq)*&?KYgjMhd(I1%{)8>&O zHh$A}3S$D0>97>JEcZ5f&t0jT;TSXpXYd5EXD$F!jFFsbP2ivfff7tnfdwl)>91*E z)ALk6Z=bSA5U*!G1g{c0>8-A_=q5tN^Blt|6g)47N#zOiz6IZ%Gj=RcIj@~RZu{l? zuS(n-)$pN^cClEW)8@&G>0vyfkdm;JL`IlB)S&(e%e|yT9t+<11mfx;)zi}aK}~gH zTjn0{IsB&6NOrpbY!;SjXQlN)>WlxR>s0TF`4zq1&h+MQsg)%up|40BHoX zf$wrfCtqJE9TYB~Y`#Ab$Icp_DQY)b;37E?N9Afd69hP~#Zir`MewjaiI!aQ=}~94 ze~>}8D)YX}m#C?6<9+CFJ*E4$95k{ z>}IvCM`VoYVHMImo*g4iBHt@|&Vs}Tn-PyGCB^@amoY~1Z`;|@&bPM@eM;-pc@-__ zI=8j-^E_0R+c`@=6(Omn_2VEdxevfENzFcAE$lW1G}Su4zwn$duJX1`&n3smDjl6^ z`VB;?PZN@)tIG|&d;~nXa_z#gZH1qY`d89e$)bg?tpu(E(ZZoY)^mCreIy3Ahq{0f zl4$KF0E(pHVjh*4ta5)i@Z8jENgjR~B_XO%LS92-fP9$9sld@`zMkm|GuT)*?TWqk z!%ufRkzah?S6!|GBvyE=Efj*JnRU)1EehCQ(2M$acLg`XTk#3@sPi!sh_+R`GT~aCt81oCYi&2$fi z)#*%3i$4nfy)J0^_fRxA$&B5)qdN0gdnJS}R(I*8l!^)@ZDjh0XzS0{m@rN5l@$;D z1H!3mfsnH)*)9I)701ih6a8Hf1|qvB;fcE>nUKT9ht&?1Z#t&oe}8yazy18LV{yx~ zJlAlADEY}DVLMebSCRpWV|*a6v88?~@CEiOX_e;z#6!>1OarKS;zhqH+8x6|LF+fU zA&g`X#^IML&uFOrzymN-YzJdKkr;;n4XYdQ|K_WaH z!d+V|>unUTj+gyyI~uqP8=280_C)rn0#VliDLm5*p2L$psgLfNl4n9tMGb6jfkf1f zQ|WP5APkU7$fs)yc~4crF{I&j`<=Mw@F5YT=#8An;ex$l-E_4?7dbb@?fwTsypopm z1QdBCsBaK$R@>P}{nH z?xJIw=l|u%`Xoj68IR#n&(nnIlz3t&33tzM*asmYhP~bRvjaXyu#w5}Y;gaDpPLKl zVwl- wzANA!*{%g;;FL5cx~?RII)h4~bg)fYPf`USYKAwTokYp`;mTR5tkV&s=(k~KJL8@Za09DUDG6y%7fM*{O-7TwR3;)P& z!@s=BFfCf4=p3PmUqW<<(HcPEqF0unZ%%?eQs0<;d=JARHp^s4rKH}Fk~%`*&ZuOZ{l;%M3L?1 zEi$@`2;1sd6INyI@FU?>R#>RI=Wt3Iw~tKc<|f|sdm@-~*O&B`j)jXDkC%gK1KO+(j%0hUzE+Yj{N$E{2T3Eu5K z?g>q1hRe911K{a8vV#I9tR z=iui}$%Fa!4p--}O!luiGC_Z|Fi`-@Z4ZR(DvlBG-rVaX{sYV9(w7fDav8es9#D&$ z>|9j^>dmvUuWotHRI|{325n3N{s~c7#FvP{S0@fcEE=eNVAlDIP=9-@u-?P*VPVd{ zl&^Ow%(#(uA}60lS5JQNHZjQF?OPjDEYn)9y3$P2#g&RGHlTl-t1SQF@|(j^?DfXJ zP(`X$aq$(8v$Wio#>Bg8EXX$uUaVPFXnmuW=vO>>9oNstz(&X(spcMvQjA#BsJ<|F zhD>%oT-0Khe9>9N7MPS~%d&vlo*H-cFsbX$XXpP$6GoQF zmigp2ynMvP#p#M-a^3CR)eqefeD$Yz*d>G+z>%Gj%z94a$#}n)f-anCDjpRp(59DL zxpn9sL<-$GCt9SstNFdPM_3ukq5%y@UK{x-$Q_gJfIiMI#06}bF2DV6CVlD{(r9LE z{7+roKvvGrOR@PNFm;>=ksdENlk;*#fd74Nz&zotSJ%hn4Frs z&F&Xnh*H@Qd3_Ryn1`U!ov=QNtSIm%kYH{r;0^VxlyCzE4i$arXbD7`i(b>sgcdIR>aNggeLTAzw($~ z)iy6>az`Sj6BWc}C-<)GcHq_NZVRp!v$o}b$8iJbln$cI6jtt@p%IylqzPjvr>9dP zL)03{qmB{GqvQAcx_OD#NnC^;CH=6usouS;k>j;L%XSLSAwJf@zx3ww%RRxjCjFMh zswYJzPk&X>bHS$z5Q)!o#gG2{_0x)MdV*$(xJc0K$*G>;hyAl~`lsd%Fu*QUqOiFS z72Cyxh3}3wcf~VZkcfis6T27f=2;S~CnCWYAf)sS&mxTxTD69VArXS(jDA{vw);~Q zk+b~zNk5Y`)MnEfFePwxqX-qNuUMVCtD!wW`kADlZlxK2WGQVbE~(E9E%n z#qA&S-~4z!Y>M=Lr~v;-acQCAl?%}nSyQ}Pj3w^lsZu3)ew|zWqU8tZmaskUz1t(# zpG%=1L086hxqr`3u**v&Pr5A3%$#j*Z%2p9&i>{YvD71BDZ9>1i)$_&N0_1nPqDi8CtCatRzTa$0R?9dn^xG#(Uvu~!1#W)Z%p=*us^98 z)j4~4+iG8;&ObR+p2C-pO0x*k2vQ_a0@80YPAVh*s7dH2%OxY&7>WY&R7u!5? ztnxnnRJAm}+a|bRA42?oO2PYBtqIXEW}caNe&arcNj&l)NLsj_^wU=<^<XIeoWm0Gmala0=E~KXJVJKN3(YM!(BsCDV z)zWV2Jg!0tMBkWC2KttJNoSt))A=!$nFPo=1b7}mE+pYrZKd0k&~1cdyO|J;G+hZj zVKX&*pl;U_|2t1_BdC*@NJ!2G<+HSMo7()z1LOhE|zzIM}NF z!K1)4q#pAApNzmTVPwG_d6$2Qf$lZ}vZ0;~@Q;UV^vGl15Q;{o)A-@oGB{XTZ@|N4|J@J+jUlbxzG zw;LseUD7}8#FcatEL>p+Fg2M{*@~VhR!azqH1E!&M)(FqyCa(%&$8+4<=gn_X@kn*<2h5C%6_u z+++OphD_?i$McZVf3aj64UOH={9Rm{`${~_Eit0#@G#Gw()x|`IqeWJ zvs%_`-MDB;|IzZ$ehV0mNzOfoadTX?3$(r2?aj0X`9 zvu4C+)27jVMDy<9PaWtb><$XLQ2YxCM-$vZVL{ycDrVsNN>%p2Nx0x64-pI==l+w@ zq(X1&^y~Frl)|?BUI_HA%9kDp^3Q(_>Bo;oDS@MBlWrF7BjWc>GDw~YGFo)v8<^bx zOZ~L%_cAXwbzSXPdo?`gFC&g9BizolnHjLuy@|SsefKWqU}V2j_$aFWuQU^q4dHR| zbF28)GKzv55j%IN7AS)v&pwLNyIK@jPi*8DMg~PV6uhQ^WOf5SPD5eayBr}xXeg(7 z1K1V$1i}33trmn(NL*f0(>ifLh2S@E!hoa`manbQC)#GD2@y&lmFn$JA@~3zA?*Lc z_wEnRhaM`9)X~gOl|RF-$=6AI`q!%GcG!a3z6wldpHZNoC<_5Zf3`5k&+d$4|3fH2 z-uaz)DcSoRY%9YT+sd($$XyV~62XI_P9oder5G0_zNmeO7M$H=9!r(VL~yp+B0YPn z{OK^!pm0C0yE#4iT~`eD)3JM}wEQ~hUhIa+%VqvHwi&P8(-4=)QC1w0rf8HAmuQ#T zB9U&3owNTY7l?v^px&>C`}CI<5sU71DedotU$1v(yFR})Wjb#@42qx=`YlH-)g4S& zwjmD9T;|1)P2Zjt>xTBKyu1mcHvWST#ei!B+)SfONiMjB>3v&`SG{}wrH_q#JMx`Xz#lI5Hz$kU`4^Y# z3fSG|)dZg?=M%UC0aYiXgp*N*DNqcqQMH@B+N#q1-EyW(nMommZsInEtv}QYc1!3w z874mY-3kW_YDLwyu*oYHLJaagw=N3i@!bxc!#@RTdM&kKn)If_Se9?lZfoS3O$gZy9?^D_ATosMk*QF2J`HUe=2jwRv^&kHrd={AHJA%Bs`L! zLl=$QE6@0a;ZYuww?4&}KMr*Iu_KQbhjc{tv}0SN(szUqI#&u}UWhxttpGo?94I_` z?&24l^|keT%2RS+^G12iLU}OiccL5Hp*_GcJJsbpYbWN04)&+pUzP2S4lxNQ}aYH+>%Onn^V;hd^`V#8_a2ckHer} z`qQ|m38TcC{*oI zmP53wtkygvlHai~8fM)QAfe?1+uVK493^1j+oS#khU(KvFYkiv4nszOP)2uy^AO~# za{lB5b~72TIzrx)GVRW{9h**%|l`U*vsYJ$HKs;aJWWn8w;@i(qqb>`f5Te=*>%p=D=v=@` z_}eO@Kvv8n-5$ru_wVmkBcY3IbMTD>Np;=MUlRd;F>fhE<^Dm1oj;e!qmbnoUqi-*?O+} zYB49hj5sb?`g{LjN-m+$N2wc}V+oVxuhu(Tnsjt3QVl#72;Vk;Efft0<(?G_IzTM? z(O%rKgLU0Nk$a|6hz`;xtG2+}%NJTh*8f||iO4?cttPWro-cd0_)6Al&CYXSivEY9 zhH-g|4PeX3bmg{nMwxT(e3Q~KCTD-NA+50)NO0|SABF{##dIu0Kq4wOYbY=@d@)c> zB{jMa>aTzP^Pz+!z&?2yy|VPOr}v7;Oj60q&NOJrOnC;g)-k7Gieh+3*oNTXf% zE@087<|b&Un4(BZ#IubsJ53fru*2zXHq9LCK77R8Z-w`I6QQH9Z5)8W)x_%tvaNEw zwwN%n$SyxWasoZth+!BOM8H8-aabKf^}_fDoLS<8BWre$?&Cn&6D}eA$xb>agA=77 z8iZQLyd2gr4&}~D_DO^S5KBJ-0Ozoj=OMzbSYRVh1L$a^(#dRH;8_1cvxqrnv^P1D+U> zW3c9*=q)(wAcXN?P+Q!oEow1YgjuE0SZN8pt!ZK&7KD1AO}LUYQ8;-c1!Cp?Iu}b?Q_kIDZsNH@keu z0SYv%Ta0cvFvE&Y1+1%{l&@dBN03Q)?=HCT^{8HCKb5ZiBQ(7>l0$!`$5GvpUoh$J z3L7I~dJCPPB?^ExzJ%lj91QG7VvqgbD|{?eZecCHuV_lL5q4}ZWv;XL-{Rw|@pgeD zhu;`I*kXx?P~VQ-5xB-H;Dbvg>;ZBOzMSXQF=f*^Vy{!Cs{0atrY)D{mfGUE=)qlF zx-iFpe<_dFdwJ<ROlA%CI=)=r{zjHd-D3*W#%F&$Yxnw>gU=X{IkDV zJrms|XfeJcs>D}b_|n4HI_+XB8-CxG7**uOCe&f^dF(VdZqvIu(@o7+-b*{@kxu9F zi7Vs1d`*61+hdwrB4{m4E`>LH17%@k-Zl+~T|M&7XAFR_HZ5BpeQqX+cvs2C_yQ@m zlBvlzFLd8{iPPrfwe!hVMibe$MfT*3hro0q?tN}*OR0~ z>X4b2q+WX~ap>C#q8f5ZZ0GN(seZnHJwsveXm&=^Nxf0YtaQz%%bu)B8Hq=Q2 z6m))AA&o>acSancz3RicHd-wHQu+>#H}UYz8_KKBxV#gYJXG#_<5ITczm8-6+eK_j zvrecdQ@aoc`OA9K9cpQTQMrQZ7Tsl<;zm6C zeR%#@z&rX!p6)1A7B4?ES}o5OHB+_?CXaIy5Vnw^)qF6hU$cQcc6Hw>h9dlo+8O{7s3YXnWAMdliGnD(!^0%N9e6D{HP2mXJ>2>KmvmF}86>IDG**jS;7OaRa zt324(@IyaoB()_J_aq_@unw&^r`Ay_aSSRM>9(j!+W@-7_O`dsOW z?R4>vN0*IDBd3t901c-vN$P}Y9+NGB0XWy!k6qkTK_Nk-+VA}~C^q^V=&Mi=m}Ov8 zsi72;*Sh(dmlFAIcPne4wN_qarM~w9XDa)7H%s_{&`J8a^D1aW4{7RdeQLBaf+vUO z@QoVkcoXsUKXunc%FTL!i2#kYuni`xpkQ^nmtwJ_Zg|+RXT7i>zlJ4~7tpX%|B34- zG@eB?e^8QSP;cuh(OqMER(=v%J2lxrLx|>yfL%{wsrF^WNaY0B5o3O;<;Nd}rIq}2 zH(t*^hJ_w`yrA(tkbdRK)70ho+miXDPtd6r3E+MQP(_1Qz+SH*st5v$!e^+=$f0ER zJ?XxenuCzFC)QXRJ2q{{#_rTpMN$&QGJ#f?{_&q64#U331fg3en?GY0@^a@FLnSfI zo=1T%w7Z2IUy^Jg(ZtzgA1YFdqPtWK{4hGc#M|IYG4)QyPe*s&tyjC2K*(3czYsJU z>`ot1wJ7lCC4(lkmEkuxY?7)=zkD6!9xTyi*96AUV>VU&sTUgYYnu;4=+^ z#T{qnEBQkiVBtP#`!{)5dWbrsWAxScAiZ9&S164&w-G&WO@QLj-Bof{$}oJ`mn%F_ z`_S`8LKL%_L8!hWw+bt(p9rHWa6iig`ImLfrH0A=r2xSTxjIT@!u9H>?-xsZU*w4= z7moWKLb8b~EFhd#O7}j}jcxFcbu%an=?Eq|8)OK^yB9uY zup8sZZ2V%;8_z*wrBl?DS^yx1u4@9MBu`i?rbN9-Z;DkzL3mdrZSI<)sg%P~HSF2N zWh${TIXeI0%&U(MgyNarm0u(VN%}eTtwtrHPeC7iNBjzcmD{*=yPKDEgM{dfS2wl zZwF;UFB?93yvi^Fy-?^ODxxY1Bi51V{9aYsFTIKb=hAF0y2=OFlj6?KxGyyKkjUGb zAO^7Y)dN$+O2U!0zHMM*IBQhNw8_mTZ^ml&fhv>Hbd?u;Vl&C{z2^_QJ)3_dLKc{B zFU~H(XIWbh@(Lb>z}VJV+0Rf$?apBV*y`Y`3d$(J*uQ*Rk!>uIRt&|xI&wnCIF0hq z3+?y9Vc9mNmwy^{1zqu5CQ`#6=lUnHx>zQ==_rk}b$6iRpMn?y1Dfv6-MP<5bZHRg ze5r`Yx72zPBNOuJuE_t)OK=a$fIF~)$m|654(!!t#!yBkR?z=Dtzq+j(EIB`uDmi| z+`Foq1Hqf$ohKbw)-PJ^lK(-Hvue!S$1eQ?T7cb8PpmrgPrq?jn*Rtp^SwqfGjwFmnn^y5TPr5@MToz(ES0nuQ}@^O{0 z%MP;!(FU}6pN6~b`@HGrYX;a8iT9dP25&_^TGtfVW~j|L4WpdAGZ+XD4Is@&6Ltv8 zP|9ShBIBW^n89zgkAY2IkOed~icI(1Sx?5Ujd_f(Am2qtw{9PR}hc8!xuyoiyDqx|8=M0<(N@UsLp#$)pOZ zB7C+d?RekRLcf}#V=(#jLbM_CdYkG_Cpq^m5sdO5`_a+GtLik3kQ?MYCqm2X1B&d% zhA%VZT>cueL9L5m@1DdqlqiBbvCp0Ty+vmUBX`YATmrFK^qdI{({uuVVU^15`-h4n z#2ZuyxaT=V;XoawB9;9CVRd^qFGsYsGe}$~lx8CTVkhCq9bW}HV4Fa*FIy?o$%p^` z2BRSQLAKb5R3y4wks zKT*2Ndn!k3nS-yiQ2Yu`yXKflieq%XgGxMpd@6H@_=excLaW19F$4e>8+>yip^*3A zynR;Fl9H?{MXY?f+oy27|1w|oCiL`{2foz!IIo1gL#usy`D)jjRp7W^ZI6iI3K5^~ zq|hB%n&-#6w7b*Urv+jp0#m=IJroPWM2)@F<#;}s8s`Laq9m*eHQ2kF`Yl5G@fkx> zg&rL(0xLQ*j;_|dI)cXzQoz8wLIB&&MklIL!uS;htXY@Q@_jo^N_r)4Ti$c9e(0jt%5g#C z6|9Dp(bZwQrOYaB<0uc9#2^eM_Ya1uu1>=6~A1^t6{I-0s zH~*Zuy2r>FzQI&8CM;Ua4cJ_XHK@q9FGn? z)rWNpu~qxI1eV2}OUxa=!zd2Xqe?~z*xlJWyNe#eW4Yk#0P^w_%i}PnA2^j-kT^u|Z{lxY_G-H|Y=F7-YD`dSE<{uR zgl*n0N{}-6XOzQr@MT|c{gyb7Q_#&x`#OAgLY3Xwdwv7@$)@o7p*iIeH2756`=^$q z@!B#T|Gm^yIBiX1r0?QV)iASVKToqSDsoSVU&^~IdYoM&U)P~K%x?zex1BQEu?ro# zcOBtoSO-!#zcFOge0Y%lH{9Wu#6Pg9J>%=Pm%VX}n3#LC*YT3~ zmwl~8K=O+9&Q`31q?Y%(ACrH5s%XKj9KU-@ldF;s-CWo}HGD4%VVL`$z+eA5L*D;* z)^4XW3P{pXx+@A(yn9XQOB4{Qb_!s?=?*m`!p*_T;hET=+Qa`HfL}TyZ}pBq$*NQ^ zXQ4UtrEm)Iz|P2c{`0P@`L2d7QkTkr_e{wwz1vk+*qiI>i{JEJ_Oru}9R8)oC1SJeZXcOujd;2NOEf16PrGcGZ}lyl>Nyul*sV$on!P#N ze%xe?qy!%K-sYO`RKD$Rl5WPCblOs8mksAr`JDkNudtaJgXL)n+ z9uv}`-ssDq+uzv!O8K>_ zQ#{9$L*IR?eF_4r>vFU5o9Bo}Ao@`*93}~D@v(gi%j(V*7C0Ckv>Pd1=)`}i0gKvN zy*-s98s&rROia*W_dg#g3`C5bz37PgD4R?2Fi-3o{zt1V;%x#5bbIq-dmTt>PgCe> zVATVYe;uFAcelf&SUcu*rWP{oL?THzw!=ke{whnNMlwn6krlah1RDhI^6@oBA>|oM zd!4q#&3uT*!5e2wxbE%Dk<{~s3WL3bTVK89x-G!-BtyhD^0+adOVdACV_nZ1LU+>M z!lXonHZ_uUz7P`_zdgr1add>hEXij6}Z}a`f z=67f>r|;d5QkNliE4ew*v{5~4(zblZ&ocOp00PxBYe$rWDLMm9+QTxi^H`Vb)%oW+ z7Kxm4kTlS6!K5;4@N`kP%NL{+ihWPbmX7R9LT><+YYxiyecGpWKOo#-=z(~%7Aosa zP1L0RRR%9J@+;-cx67877EAxq9_Mxj-o}OLa3S-a64@^i()LGlNk#d|!~tup&Lo3Z z)*)hocr_lm3Js;q&yqfXdCK`+B$x-^%u=r513&%mMO9389$~trhYG9}0TzV9^APY1 zc-XGf;q3J@)oRZ*jm3-Ia+xM)*Id5coLyUO-elMkNr-FA_t$Mxo6zAEsN2U7~%^V*}T%~!Yr6IycO%p9vJXxd85VSB#)SqR%At} zepC)OjHiGcWFNps?`$g%wzgVLkev#N^H5psBAvlI|4B29or{6`6TgMdE&u-q*)90^ zqM!n?&h2r6yANCbq$rC={pSH`TTPIi%Uz!MRN#8Da=voXb<=UNp{lTnFN&y)*HWGD z4I;+(77|{)32RS|fscMU&vjQ$C)CR~sQ)a@v~}KXA<0wNZ0PWNJT#3o9V9_s`@TTS z(L-_shL90uxFSH}JWo1ot{Mw$pt{El9DNsGbxY2#6W7xiDCh4}ulMCI&D;S>swlvR z$d?Eq$;iW<$5gC)x6}w!Ce#zg4m?@TGr9~ncMsJdlT41#yL}o7AV6Vd>gp?E;(WF&;)s8!!>L z)Vidgnc(@nXzkviaw(==x8Y>q+WFh^&Gk1E8bTGRYVB?)UMe6x;;liEE0XpS2c(|e zRALg|uwI&Ik|4$3d-^RlHHx)WK7Y_#F@0qxDD!>r_9uOAqp)nbofY7qzPqp*&Pv+5 zDf~qJl)NYcz!9=5H$f`h*+@9!c>CY5=gALuRILDWBo()aAsd$HhL}Wr>gu+(z^FHU zO!=}Nnj4cZB!YP$r8EQ=!4Wz)KgU0M&F-Q^dw$4F#HR><`%|L=3gow6Z~gU4;N0`$ zG>2sZHhUL&zB}o4(b6Z+^-z7j1@&*MvkQ(+gC9YPCigi2`&c^;RAPAC$=&YGlRXQpA;d`a2EP#Q z{v3pRb~4Vy+GS{A_>-czV>W?wgA3u-^MSf>pifpl%kR9r&{Ag{NoO@ay?+nw7Ph(c zW#Sc?u3(3cRa&8{Odo8^>^)ZPGu#+Q03m?t6Uuk_?Ms;|tX@B1v;u>y&(l`ok>_El zpid`5kN;F>oM))|b+cb?tmqSt6R4?{m!83=HAUHBK*$}S5HucZ5h}#9S;6P3=EI*40`#(P1~$4oQS!6 zG43Vf?kc_Nx0awr%UFknH;NC;=#M!0^HI)<6Ijcr7!9i5*!7U&*h&lr zMb|*(Jxr3*AeDL?NL+7A>D0>Z908pHq8|FI3pe>L@gWgb!P7qD>T%8Q9aixY`z|}3 z;(3c_1uH65Z5!L7mp^o7*6k5Gy=j^ra_CVoT=!%wXd))mtBZB)THIpXoJ-J7SCiWpbTEZ^?9T z_^f5wIpqnRTwcX@OvJN)Av>jbWJxeFXJEujc)M_Ypk-^*lLfB*-xR8I@SlY7V^&Ua z`YYw=f7J;8b)1`aKQlD@yW4TH6#j9eY*%?XS%V7GhIb&v)Ahwa!6%Xvyx;*3hzfRd zhQB2CHjbY+hx}f9y*XK?x|$Ti7G|={F5mQo)BLEa8cA;aBF@Cs;46e=JpbAIU)NVX z-7%cWpRX)pIt7fHrUAA+noViXHH%ia!#j_>a@0Ps%f64e!OxCb+i?^U1Gc|jO@Cze zLq9aOq%Ju0XP;0=c}eVqeb(0U1)RiA9pN{f?z#IC6+7Hxk!0g|qt7Jj zKizeD7$lo_6&5IGbW&Z|_wpejtyJD}X$6W6MY=-xpJ%7WV5+e1xXJG7OUEWvZdgN7 zB~_*E63;lKxZw9Xy5-Hlzb7G6=kVY{AT=o(VGK}zZF5)dT>>6UJk?g3Ol zTDk|2X6Wuvx}_V5p}U4W^ZVBM);jC_2{UW2_ucz>uKT(bdSi$A;W5l8i$dhxC@Sch zz$mTUMzaK|TPD=Y$yH3#Fxv3{pv#RU*AdCnh4H}IMldndNe} z`(hhJS<_#y7;PVW3r%rm9FjF9x8$qh`5Q?4!rT$CzX3k+PvM+CrLG4?1GCVQGh zSVjY5p6}q=$t+57YMtr8!|G6V#p;*J5QdTO5L&ZCNiFP^AN5o#ORY)YoW=9rP(#>Xp@PyVLmw%~%xGc$Cq>HNB$0U2 za6m!1I_!>smzbdT?_)=>pF4UnOQ)x2b@b+q(@ENU(K&37>k&{_X1)(hTQSq)gv55I z?UZf=wDX7B8xVEYS?IXn6T$)yzXr=>7tc+?{i8#Gi603d?7BRt&%YYqo>st2wkg_I zIy+8q#f3bsZQ0j3Kb{Rf^j@zo*O~w%E^@a}b|OsnMQ-Va{4yfA@kuN;`23|1OpV`M>&!I~KJp=5 z81KqQLW6?(Gk}SbZ14r?2Z=`;fPlgPPlubBgZz%H@Y4Mp4bZdUU?c?PN;abY%{W<{ zYM=P7@8$K~k`m4zLL&x|jnG$<7yG+{3xO(VW;tjx+rR0+(I|D;JgI)+Xy|rEDX6%B z8@+OrK#hKtH$IA&%W^VwN71JqyTRee7#y7m7BcB6yyjnfkNhTe$pGzN#7bVz=U#I} zygv-apmnvptX^{ITv_owfGHg+9*Ek*0h1FW8fM@gXwqnw_?&Hk<#GbAf*taIhGb_n zW?N!neEut+#o!d9CIC7#@>=_H(2O6K`+{PqeTD!BuzlnFdG7syD_ww>E5+UMUHIW) z-j&}ksEHF~uBMZcL<2t+^ghI>dG`B`&7vQq{c&hrQ#^X;miV1+>x`cQ%=zbj^Y0;O zXsxpVY7;Wk@pMeesxKL6bMXdx6g)Qs>leq~pJ>&^qMxdOeW36LFr-MXFUREjTobx( zNyfavX;vS9)zIKejnnmT#5&ueiwXs9P^6PN06&5>d5@e=2-!p|7r#^KBkOepl={(_ zt1JA2T`tivQ2~hyk$@o&{)Lk~f;ao{_Uy(FTH9HaPVGv%xW{YFQ-CCSRqNXwuw zgWn@D8Yh7<+eZ~N`-b3UgN6L16lw~a_PRkR0_c~U-`PB=@A>c>6d7>cZ|m}^p@`et z!=v8m2LS~%`)E_LiA&4;OhytKu9WxUmtKZ+Az7;Y!)PP)D#ru9P`2EE;G!PzSYtJe zJN+}4RclTEt=Xj!fj^6$>Nz03nLc{)8lDrh`u$g^dQJCtg`I!3@Ib?_K4-FVj*yR4 zq7VK)_`rZV;hwo%495SkE^iiUez5;V#+v)u-E8CG?Q~>3P+5o(uONPwP2ny#?t^gH zPp3NLpvS9YV(AFTE=4NJ2+RpdO)e|XE(Z8c=vUHz<9u#trcv-t~ zZaUl;9ls20ZJEXm&5iBi5WJWkqk1(7Hm8rP1lrVGO~(eA3f`@GuUj=XwJprlv1wJP zGV;9SBi{d4(%Z2)gyr1g+vH_E4qLEzJzYGxz2UN76m>}eAposkde&tqpo*YA~m55F23${!e)h%B&!keh9r)YmU{EFFnKgA5aXtPH02N2NMMA6Vt8P)?v%dF=YT z(a5uMLKMics(82f*`I2YZR3tjYfUd5Dn=DXT>5K+PH9N-_6eDA zO1~K}x}7fp_6JAK58+rmAt5>8{}rh>PzX3ZRbZGWS_Ah(U!-0fodSM$)H_}J2gqba zi6pu~eDWmM2y3k#^78V!7HshF@WNUcT}=V=_>2D6)H6XH`R4JiH0z;I6?RR+hlp!= z%-#HU!VY{%f-~f+W-sSPs`t8*^j-Xa537TH!R`ynW8B5+vc(f!)wG{*(=!w41ll3SfHG zu1N7nnx0sL49i48hb+xUfg9q{3A$x+1ceZlqd~>XgBt2hEYw4UP?cWdkN#ce!)*e^ zU{O~|%A)Qc^<(;Pws|Zj-z>P~rQ%GCo71(`!}?NDnld!;uJe;=b6W;PBZ`05dh%UH zVey;)jKPsnY>SKHqms|Ci7r0S%IiY>YNuK_yiD$Ef@Ie}_`Xf^bM*Q4;R#C$pq2*O z#`mppQ{SPr4#n`A*vD{K5j_XXg1RnQ?CmiBhE$tTOur=u=Ui(e(DJ-H6gGymev zr;dYyofxpTG)y!LIu|$_k3H{=3p1!#<;TUc4Vstq2s2oolw9BNQW|py{H`0|L&t*B zZr+DpC(R3AbdX8ckX9QR{NQ7av+t~H{pqPesL^5Pw zVlz^~Z-zKi_B07PlE|(Vl3o+7rK=0q2=7OtUULPMK}*e{bdw8iBq!$BJ-A&MJmis) zk>c~M7qOZiFa^4_`>vRZxm~ATjK`rzi~j{ zD*hG*8M~fH>c<=WY${UpyPaYEdie)mqo+%xjP)=k71$B9}cQgoSmq8Fp9w=Bj}1`zIY| zdSV$oQfdPHZ-JpT6Hs$!4d7OCnjkB^ztRhX*KMfQINF@}%GRnHXTa3k&{zJ^U0(TP zUd?>F)14sdGdch*X~6Cdz$t`qdL!X;KjtfXqp<2g87Vi0+V)QUvRQa)(UTUw`Fj++ zF+cJ|R|tPs25eGzp3C z;AcLx$l15cU|!{Uin`AV7N35EyhtEb5ViWfkr)Ve_qmQ81Ndcb)0`!fvE=t+=@=ML zDw|$1;ZF}zAzu(=ogo2!^brAO6XwN}tQW>}lkS=EN6MG?m-jJzTpJW`7&YO)pg^D;l!L$2?NO21wRbYF3H0T z+q`+XkG_Lk=M$m;815?0#UaNte&vs-RG|*hcklG*l!mA5y_)L8x*#(8p27E5OHR(! zY{QUOeCzkqF4XiYFNjW^pgPK<^vkj&806I4fbmhv`lSrCKwuQv55D$~)A0K3q>4OR zXbzVQ6;e1`3!b-BuGufH`X9(uBg?eba*xn0^te-3rc}|boCsj^-Wro_OBPSS?0mz#wQ&J@>x@^s32gog>^1d$Zl-#bymMSVmV2X0k};!i`&A~=y} zVWA^otprk=g7SC*tO&0IG3eSPz>E$BJ+pH#@A9A^f`ktvYEzvm+r`bGGTqyLfp~;8*RVe=Ve28rUzCkxJke}3wCr0lqJ=} zPT>$&w+Xe)$72Mf3ChG{Xn6Hw=Cu_ke>aNE4C4TnCAS1r&`U2F2hK91d7k5@g2s4v z5j^w*`^30%?*REyw0(Vb8v!e?>J?DuiA8+3V8-^Xb7sL=5%&FIG!vpeWo@(3nhPi^ zG-eFm>tk+y&{@yp9WaD9NW5)I#Mqz(l-p(nBUwfZUjyF99 za`pks;8rn_{i+eJ7~d;A zKp^*M=usb=9{(F4DhieEdrko;y#M_let=i30ICiqREsa9$<|G^0F7iP%csWJ?WqZ( z26+5ZZKZQu%%6p}6Xm33W~O@t^cs?tiRD6Z@Uuizgmz~MMK8?F_9CEB5T`!8LAR4M zgI)0FkJ$*XubN_YPEiJq5QYQs#TPjH!0NLuqNReotaRNduz?xA5ZywMN(UR^?no0p z0w3;&Bi}^8JLe5a))a@hAd4CIZrp`D`Ev6AY^M3SPhj1p?}poTdklIBAvK)l8eA!k zHNk#VUvH{DvR&~zw>c!<$m2+!-W>iX{E*CfbUj)*2c#J=E|8m^SAX)S!BZnynj0cy zSJ%O<%CC+M8*kFz{{F+Gx+B|C!#dZv=Qf1iNbaJMq4M!1RD2r1pRrS8|O@dtZ+42sx~hfgA}UCer~zO$G|X`dag8(tZbYWG!D}%JX8>6af8$LK-^eJ9G|#d5 z!10rN_X}btd8_PnTO>wETGi*9#&7153TSt*^Yr-?<+wa&pXk%+Y~Nd=&#mbs794EK zwQApfEL`#=W_n?!HqrVG47&u}-FaKZeAr+6utGu@PHar$E5!nS{Yhv&$T{15;ovoB zQWP8AmJIYz9{>6Fx524hw&iAt@mju5FTRXwc9fI@gu}Tm=ty<~=qgs-DMoTQzkB|r z798Q`t2Al~bNGmT6~4F4_H&~6eL2wj%9r)lY%XlI-vtk2i!6yD@ka@8G+W4>KWTf1 z@~~n96m>v2m9{u*heji#K+3G?xAOoG@6;;1$OpWQPTn|sk?51{YeyZ3O?wD`6;@LP2Z_u&Wm;($nuBCMGkLIZXN*F&zVJGhy-42; z=CMz<@VYO6&leGeX9RV25-w43FxCt#D#RUGHXQS6!%27~)Iy zyvdcuCDwj2(i-C)5F#M(!at+etMh(E7T?K&g(#KbL$^;i-7d=HB6r#a&Fe#9o3Tu$ zCp?VmVkGjq@y9hPd*?sowT_>%0$%I`X%XiGkel{QToMU(=$ZPTy;;h{_2e^6jiBAs zb5^1=tKsGWo6%n~Geu&)NjSt4ezhXVSGg8opJg?26Yh!IG%{}M@jQKPC@kev#(AW@ zfiE!Ka;H;|^=`N!%Gq-%FokKas;~~XvDvA3X;x@{CE;ElbZhzR9%~{l;(1G-sa)xH zlW1Ii9ybmr9At??lB+6T`2@dsHILC|Vhr+<6B3E0?;e;vqL84b96UD;en$DB}h&c@kG^DgQ$DTVp{EjVvpK!SNuqFGUw zaBqf#0ecx}vl;2XDcRR5fTv0>URRkV6;M;=+Odw2EKL;uTG?*S#hr}|;5myKE%syi zB$^OLpoZ^RO)4v@hvyH33e@k*80%iT@az<*bzO3JZNE}*~ZmpS9-`$vScev5kvnl@L< zF5|PO*?2^@(yWpl@P-|=BH=?iME6QU^P^Bxp##mmekCTEf689QNd%bKzDfS8g7 zPz)jI!H*Thvf=@(0}IFxWGY^Aqs(zjX(d~pzog;fhb<&EcUP1)#{!}!B5?^4*2)G+ z>$UY}z2DtoHnKem+`tbx@g_7mgEp6mv=nUooYm+EH3AeF&BO1_mkB1baS6qwZ*nA` ze)t7ywGWTzWCc{d51tJ#Ue+I)58SOY$C_(g0$y&yBO5R^N?2PUGp>_^>@0w;Zssl< z%L4sK_DdZ1m=|nJ5Wpx>jfZ#D`Vk-UL+ssX;3u3bh|4@mr_ZnscX)K^$%Y8>d zgAC^)E-PH>ov=JLLV%bBJ5T;t69L|e@ieWqPzn}Mkal7A#VDm77?9m;eoOPLrQ_PN zc$r1Psx|7dNtY>n*O$OzBe64Dukx-FM~y?oo9j#szT?v86ZrP^?f{h7d%ld1Kt{nW zpq?smfpMc}_4tB}E}P*u-S|6__@9KcFB|o+x-pGSYx{9U^wdtrs8{(4xZ&W+WCvyP7tHSS6w(knZ15{O2Q%I2eofP6i zm3eN|OIcHj4R6Wr|7-+UHoQi?yk`JmnU21gyB|-I}8$n2Ve$>9>ReguO@1*%Z%Pg9lkwa;TsveSA2h@+R zme_ml$;yshL#c+1J}lBUuHt!JIi;c7GELbN+72Epo4}5LnHa8gxL@I(2u`o?-|Fb{ zl}{K8c?>Y{&`Dy{be7Es)0l-e(FknY=DYtY|5RBv#^D}t_kx@zJMa*4a*b>Dt!iOE zixAEIE;xsiL(<|I2{)s60TV7i-^k!=gnQF@oLG9qI*iN(_B;^<+xTV1 z{mseCwRzB50(BJAB`cF=L%{nQvoacCi*6&KUfJ!4xw;_361S)?QZNkOt}|P!d;MVy zwMoHzw|~)YN8^n_c*>V2XXy^`T&txOMWFA)n*~q-t)XY6_6M!)@7DEA{NFjucpScG ziAxK)$vwmY(BPDvJYm;S6~GKZmxtg}Iu?p7UcyBxPSTSE((jXB375CUfd*%j4SE{m z&7Wv3PXYj9%9I|ZB%4@qUH-dj;%&%l8i_!cR1uWpKXF?_rurUs(1NrW4#U)uJD|%X!k9VY|0X=yt}l88ku&$xKRu&ko3YZ_ zb^k<#m6v5c=gU|Zvg&hu+l;Bt8S*^zG;K0fnZXM$DWJmBBmWISfgFmbsPEPlWSD{y zcey3orV@L7z#hj5>8qY6m92AlPK$?$jUE{WIB3YmC;>h1T`#^n;+nD*NS(o)h*^k( z1j3?X?)SUL)3?&{waoV)H8p=ujB?aJdzE<5F4&?z0t}GBy4d@}^7wsV$J}ee?FGI| z6l1{YF7Bg@)giFa(#CMfAbJ)oQs@zZKXDn8MQJ zF2YZ53A_$9z_*nbT?_3eOKIC5y7|}|VexKxkk!MV7(Y5_p&?+l)U^of-=rx07jywZ z&{AE7#RCPlXI0@9%4iivab)atOCwessL#*|-x23eHUc<7xWF{LX6hL7WM3roULS!n zd0RxX-Tdbqxix7CAb~I76X5j%q>XsYp$4!kwSz zR@^4jZr%o%|D<+T7)xU1IemZ9Bm4A3*|-SsPwv6O5-ZOs2C#VXD9MrX%2GbP% zorjln?1Bvi3;{36Wdc^l>~$wv#*?;$S`*N%$p?#9Ob$T zPq6FmzO13UVVlDJazDp9lbMLe{uf=33d!SSNFx%djrOYP`yMV(bXr#h#5 z60F%X0j!MDWszJzlj9snm%Q>%#i-fgHTgk$zwsgd$gL4$SWGLP@ci`W7)rrXt#~E2 z)3tyvSuekYxD#EjZg{oT*f1uiww$OWIW5i zczto0^B(ZM-)!MSZ^3TwXpT+@d<;3E*tGxxyn$a*t6en@`1Leh>W85a6p!1OEl z+D&@laZWoK5d({eaMsKf5CqY&JH5*WOR3OK0!jqDrn{8C>eR znl)8u?Whoh33-ApX#=y7JH+V#u@}srCL!6pkG{Z5%Oh62K~K@EeMDA4a&YN3+7|i@ zNHQKlbL52i^=Cc$N3AizfV)e1D`O=$u4*W4X#<%9$QE6j?8va|%!Q8vFMZ6P@RzTY zzWr0+geJblQCq*i_`M;LwXu+9ZR%b#dr~D9!CK7QJ0&x6mF+2@d2o9B5x8~$IQ0U_ zINJN75jsh1R^j=aXn%30pW-X|*_4Z$6LOKq|jpa>*C+pu{sgh9Y z{OB_*;g_;l{WSSj)SvZghRK$je;4=kIH0&_gfjs$)`0n!$ARnoMKskeel8C=(?^6b z(B)6ssjrhZRE#?@ce~bo6UG4`PK@7aE?v`l#j! z!7LvToyQ;%@Dkty5Yg909pXUxc8ESyrhy@(Ll3Ccq{v=~_w=pZ?QJDP+L0#4Wmg;g ziANawXX@}Im8K&|%|k|cJ!KSH2zBu=cmi(2270RI|K8gA2Stxvrd7V{oaDoAQGE0+ zrBj%ZzTNJshyA#sS#Y@!l;ZSx#w*sXRj9*BUy!Yag@vWT#ZOvq4M|6C6c?~+RI5LZ z9=VD!D{aT;QXa~ExR;h_AD9hUr+0WMuKpq$02sOyHR%77fZhzw*0HSfiy0i{WkFA5 zz#QkijklN%m_=3IX-YmKBfkk)_fnp~TbEF^!U5dXD%~{B>MvWmU4T#Xla^4dZiF3L zSBAPQMlxyuLquHJA_FMQ*WKN8)PL`%I%5j{)Uvxh4jT^9zuO|vL3KKT4qQkDQ<4)x ze93XbuL(1u%(?t!Q-WtzY&V$8XOtST>f~e}WKkI0RPI}x98$z(tmL3iGNEpxzOIFQ zUldBh6F<8PrEG4yRZhxUC%PetZasI|2=uFP6~@``Ea?lXzjI3Lfn;^QQn+YOLPV}- z$=EXLUgYj*1e-Xep+9oC$0yyr6>f;kClyZUV2~4#T6IWA$t=)J3JJeTasEH>wH(;J z7t|XDZWMagi5PWR_FKDO{iP@;@?BY4K0 zaxvmddJzBR)lRj+VbnJfQQ_2Mb=*~w^M0#J$x&Vh5%I>QWvDdZc#HSVak(8UO*Nj( z!GB2_WWUP$4^@L=f2DA@-J=}&7CgJ=|0G}-X0)=PT;fcpJGTNvKY13B!ZW%uFajLG zY%g)54a%yNY^x5!UrF4de{$O7s#9!&##Jf zUxa=DCyit_G4PT)=K?XKq}!@1a3YCP5!c_G%mgI;z3xk4CaGT!zl>btoQRc91(l=3 zyt}5szO&2A^JCI8KRO~I4>>-b1AF&Cd)I0;f~gS{EIuJ9Mq1P5TG^0TX@7%UfNwIp z6VlQ+bmXL&9AsAQ=K%-euzj@S%15_O1DgjxJET9`R@Aq&x(^W;DhYVsxE<^^>tEcr zFM_9F5NA|WH8!mEWj8LsKOf&htF=MwrU@eFy8&g4xR}0e{;&7s2~iSR*gSW`Dfm&g z=mgXNjXW;=Vpe6$0m=7X3fq)+_d`aD$AVli&#-87Y4@?k^RU(iS=Q!;jyET5L7AQZ z47N{LWr$9De9c1(rf%}DxD{kYG$E9TzD)y3*FJ9MBO}|ZeDY`%9`}4E> zk0vlW6hr0`HDCR~BglKWCIWCLH8hldbUS&&rlr^CCs3NyIznty~`_ z$3~^#)W>@&;|e~7zx}w9zlz7$09VgX2a3T6#YSy?v&0=N89-p}lvWv@Ou_dIll{8h z*7L30;|Huzv7F!CuK^La)s+y(OTo~ZM~hFq8dN5nrW1c@R73;wzv+kW1UsN(DT5$b zYSY;6KMRWRA1{d0jRQtIz5*rxA|@}WR){%0n~fR6|YbFOzErpstPU3akU}8cG zE{mtRldkdhyVWnRVxMPfhnIIsUm`}DX+}jWss*POoeICA2CO{rO>Pm={RZbGSIFu{ z{|x(6>ZK$ZRPY|$Z0|=1-<>A}K3gB$H_^&pLS*cSw82K9i>BepM92)R|`CupSH^WS;9cWnM z5?4FAnEFLcaD4@Wzk0oX zOZ&!>i|t*Kuhg?5d_2b`_{ENjMuZuTYzlqUo&P)A=2tt$3s$<^NL2)5=Juruwk| zD;Dvqgt+Okenj6i)tB1uquQ^{yj&h)QnshE57SNCtrxVCbU2x)u|Dn=w4>}A^Ewr` z9vL4s@}oHBh2yV(#g4ucrx#eflX!OFYJYIy3OGTZOO%|4t*z-MdemR=brIWfzCrgk z^Mz4OwfxooMb`2|ipBXH9>^f({ROgJlGM6fTjohcz+G9M1jyWm$@pvxD5~7pKb^``u90GBF4l}*93HVd~ets{MHt6 z8#ikqLgOn|=NCxv$`dshpuz+_&lfXgRJm`<-8bZ-PhWC@PzmQvpe`39oX49!KgSl$ zwZhQ^u#CLB#w5a3fqcM)OyN3|Q?&QMu4hy6o*I{YBs&D%}LGt&FlDxLpTycw3k*mQ-?Nc!9ka^s_*wPXq>+kgWAjAg;*cvQO8n#P<;%Z^zrAXhW z$^9!ozx(@}+&j?fBR}8=#t9-yK=%7_h_CGfWCUv1RiGkC_e^g+?6DjD1yjZ3RMpGr zZ=tHEbgV3TYUE(wLe^-*$tS>*q`|rhRv9BB8WtSad6D_K;0)3&z`y zouAwuLB!tF>Y^JZD;HDfHyJEe6^e&u%Bwwe=;y^7-|Zj6)U)g%BCC)Kv~W6|03rRi z=JKG=mYUMye!n7qAOfbml=r;5X}Dm{MQp#tjo;VU!h8>4$H%zFGQnv2<4s7^*Ce^RaJzKjf{Q%20D+v4vM*p8>gY8bMH~S zeX6DUZFb-Ql5R6vH} z@zJg#w>~8cWP6HifB6bQk(MX9T`+L-iq;HUYuB{)I8M~q8pgP6C`!(L|LDEHs?8-! zz(9(gilPiKz?iLcOTeD~QQ@561{-x&pT*Q&O?5iNi^(dJ83>p1;OaCl!*)r6(MfdI zzZi9Ol7Ct7$)25pnEp5o%ZSQS9vE9~mbG?<2aF$!!WD;bu7U{GOaRHa(jOgmg3r8Y z%+^+~vqpPw-06@y@FK>{tZ33l(W_&?Fm&cZ6#d8=SPPgR%@C$43pT@mcC;Fko89M5 zsPE8;1x>sVppnW(kpi;np`(h8iNZ6XDQ0sfn7be^2N5&y|2U7j-r}aX9!kiZAYnVC zU;ntG^Xcx_%bq}hsk8Nu$jF4n8}GGL88l%Ba>114%PW$y5}4cCZD)ZqVpU)+G23oI z=k9ZY_Cp`bCT{846bZihjycl_h-mAGwFD~Mcn^twm#EXf3?=b&`rp=02G?e|>Lt022(sd8}{mxEolPOoQVLTgS{^}=?g3ZIK0HRttW zW9Qk4BkiC+zFBYyz_pL;zw}b0vcARsh!5Sws5&HoZuIlzI(1`fX`d}3EsbLTEYr^2 zS%nEx2Rabz)55#?m+rAMXUVb@p>cnPM~T%%jx2M8FvPPCi7t5WUQaxk>UGYcNQ9p= z+=ZzFno&iHYr|C3;=TegDJMEuZShp<}CC|!dGKd~N&>yFqI6ONM82-m;MHLeP&TgA`{+ycT9NR5whasAEpNke2!im|2v= zf$6@%OO=x?dbWDJ*nBz&GsH*041U6XHU30-?wR(xWu)?C5+b9;Dq({oyB|KGTFw6NJJ z_pnzBeC{xwz!-MLh4Eg#7X9>RNulcU9LWTE-G1k~!FFk}zTz?d8na}-~MyIn-uA+0NxrwsMrEKBJ zBQkMdy?-jWN)hw4D?PVuBT;Ibs~z^I9zTt7@lk?!IFk0nwtZ(YkBfGKIF?eqijfc` z!-*}B)b*Mfqs7Y>RSjr%4gaN1$njpxHDFb$mWjFw)_13|L!2N>s`yU zxBgqs{;H*@*e>>im{ceny0jh%c^$wSUwZi0U|JeC?X6EHL}kqUi6mS4NpQ3GmQiTg z^=~d9e=MGA-}}4VU8TZk7m>$+~IS=WHI<&Sfz_yi7b%j$9Rg;JT5UMEx6CE@0qcG;JA zt?Ch9Vh6Gy`p>w)e<0P0!Z#!?Sdy|B&vCwkITfCk{xNK{?W-k9Hm{j~4<>?KOB$c2 zM?QIZ;=(c@eR5V6z-NF-myWbmd06RKHm+!J^zq_sDf-PX+oN0RKYj;aTm8nEse347L@xS0@sW2VA) z*s#_2UHCNDqAfeA&E1UW^v3xfI62|B-30VmAVQ5oCZ;0YDv;cD!@a+zlydUT%? zdvKrA5fQY~ihhw3IaYT+7h$4KJ5z6`%UJ}`au)nr0suPqO_ZX%zxS3(?5^T>|l_eLc}<*|p9<+xE| z{obFH0o#=lHH&;LFE0z6?5@z}L4X82y4Pl5RjZU%`e9gIst(|ZrFceZKvW&#F5lOy zQd2SY{!LWsLYsVJhc2MiJ*>thnR_-Nm{e4 z48frN>k@VhnNLO-s331}A+oiMZ-AWQfmicuSo(Onuw76ExCgyF;FtXbce=p53Wj4? zD&4_vUvIggXXH$t4{ZG1-x$<;ckOw9bL?(IBGCLQtDoN9&jLTd=pnrW!IILksXEu- z_U(SD|Xj*)7t>vQs`c4AEFVW()UQ*C5v*x=YqMZ7*Wg7=jQmpMg1Sy^r% z<$C#kYqR<0I}wpH(GXdaD}x!2EGX3@&zVwPc{h&LFVnG=J?Z6=H%lMH_kk3ws()<^L|;S=azJJKrZfb zENY8a1T6Dzxt0Tm1|;IM3PJ(J<;5@IDjyQrGJizGyen*;xSqH8(}B_USZR8cPz~+( zc?1SyHZKBFmXgb^@6)#~s%ZuncJdok&2R42BlL|40pErqvJ7?2gI-lioA`2Ppgr&c zx~5`_vNY|t!V;8J*L2tupNt)B7Vr8fZxZO7MV-g#>^*+_KmyJW_P9;9_pqgNjE%P% z;tt~T@zY-u(E(|%*Yt!9P1YnDy|34^LeWiG4PFJ^BQ`&sx)AwfGGe2C#XJqOtoT(d z)AyC*KDunDrR_P0w41v5%$17Z18}~NEjS)+;wgO!H-^K7IutwVqAsf=|Bi^_<8`UD z0*d?PCA)fim(Q~u@}s4yQC_2;&hhl?VuG8Rl(^3mq34;GSg-Da;SSl_o;W6zbkFWUVmi}z)Sg+2Dk$w^A{7qP6EcNp6xE({|@X*W0(EQEyglP z-Vji`8+w6EW-+F9n3I2_gG|9BFnWK!k3X7J0!a3>cNSXTO2L<+xkBpqfjbVfe~t{7 zv|g+iFzE8=bX*-0>SE(xd&rd=ceHh_0D~K7fnqP(SW@2}hTc2QRa*yFnFLp%IFwg@ zF*`hV*vZ1U+L}msr@p|~^%D0H6Bm9Ny?onPQSSB2+yAM)2p^Alj~)DY?vqrp){Zjk zy@gSC`)5gY_mS79nb(=V0Hqnv<4=PO{b}Ru_~*{grp&kfp;(?5l|gk^zXITheC#*6 z?A&`<{%(1wLpWa?H=%@cXTcW_I;bZFjPi09_T>+ z>_hdx)gtK4cTq>_qS_U>jGc6EMd+A49`H8-EEt3Uw&wP)AkaQmP_(eFl9+Q#&flCO z?Mhl_G)?7-<(Lnee@7P?E-KR#I-vYcne6 z;qtpa{M>x%kFgu}iaU+x^U2Cf3_5w4`G5MC{Ms*KukYAG@9xZl;MEKHekjHK00pgdyN@wR6&91A=FS$5b{b_&J)!I)8T>lJV8` zy(z7HdS31r@L^eyrU>q)bvcRIgz<@74!6G46b<$zUmv7+#`!k6`Qf|5$70f(0HhNvWs=}8zq z1*cx;a}=8tTOj8g-JCYf%l;i05(pT^VYgGcQrxxwad-Q5>im2OIQAw7at)Lz#IJ|) z%>}}fw^f8~JvNT}Q5D{5%Y?yM+D$3CWt5PsD%?hyYK zZWz-b)*Bpne5XbVkT@mRe=(D?$STBD=SNyUS=b@Zj6pD0fj?lO0Fj8TPF%EHj>{(D zl`-ft)*aEIXxcC`_BtndI{Rv@Faki%>Jt-&5@lxLQ-En{M*J2la`RWbUkPShFKX<# zG#L^vz;@K8_wn0x)K!@~kF%N$1D^HUOMCn_Ss#Av@xe-`hE%Yf%w;2!JZbAAGZNsRTJy%)WMyjqiC_~LNHSAGidDgud7ZdS|`+0tBU_txc zcwU_~Bg_+y&Wu7yz}>x)25DjvN90BX6`~cAJEOMe|Ap8l^OdqbhknL2l!%m4L}$e1 zW9ViB4c(zroU-@B%Rs;Ujxi^S%9?k*7Ak@uv5J z(E>NZJ4M(sQt2f+uA(BHy(M1TW9K}}wGV|N>e#m=H1{tbS z>-qmkYG{`&BRt8hWRg(A@4s$py9Cbn;_{%{CZJdS>X5V0u^c~k`QY6lu}0Z=@M5-w z*Q$;7V@E((+c~-TKH3&9dR)!v85Px0hpxJvk+@?~6oY24_)EB4x}cJXlp^5#ly~b? zXqi3E1+z`dM5) zk}4NTcdy~nqNKV$FaBBU zt`$Kt=s{jTT1bLiVT)xepoc4*86-1D%`NxYQ%n~Vu_^oYW5Kw9H<1zq^&Se;K@S#% zY6boyzb+OC8eYA~y_py5Jo}QG5V=k3AZ4DWE(O#3q&_5BKNPr?th}t_=Q~KCL3o$C z>D}@H@!IY|Q8J4@&z^h;1pDfunSq3x%C6OA4T|1No(Icz)EHws^yLP24yI`Q@$5ZA zzvH_V7~Twme`PDI~I071n@K9zW3ei;x3TveUR>oFbF!`a7SrGa(;z>eKi2(r7WU(Q|=m`JzHW~)sGB0M+#1kLTrI+E-v?2qs!X6N0kgbGS0|=K`<&yi$ z-~%%funB%mLw&l|3n1|5*wru;lJI$cWIebq3MoOTlE)AWMH2E0WWEGsh`T#GpO*t>_3RD~aHHO4MxsLj4y> zYo1XD(HJhqT1oQdKYr7$8W@$6rByW22bMkh{$_abLxEY@2Spm`c;Fu76p@^<#xhfA zAeD_zauE4UrYpxiKq_5?WtB^w$4c-w05|YnIl_chI)1hqe1S9PRm-Ie-y~G?!MauVJN${-_5r%8<7X%v(kyaBqX_QdV9t1 zcvt_Jo%1o^l;9NGQDN$J_35DKs89ZF-5|KrcJj-_Yq`BSs19|<`JxBjeWgU#IPiXT zne`R*<)SZ2)p-H*q`$vc=DBhA|6|D3+)=QBZp&VRa$*NH0lOR59h>ID@5 zr+s?}+@BCv=b@MBBj<0ndG6)R@{b?(nZy?um>Ci{w9P!O!UJy$0!bIrepEseB6pbt zBtC>3(?%Bxvre2uzON~L3dM^J=vN7;!N+Rm(PwHxwEn}BJ3WxCNCglwMck4*2?Y|T z@sZaKs)dwhoYXj$)$!_+TJm9a_vmTO3;M0GMFKW;O3$(U9vYa06^9<|v{>KZO@KV# zU(AKWGYbo272u^_@a9F79uE$;3&OJW$xazoc(-1C0oUUFW9);A%KNWbjswNb3I1i} zDE4u3_YBhbGRUC%&RJrSz=;4rtO-R6_|@MOiQvMe!(Sh&BUY1IV2pBytyn!8z+>`j za@!n;V7WxWsHeFc24Sz6*k&s5Zc{u~=jSt$pG!g4a=9sk?hn6^CDFgve)RZ;`4Yl7 zsVG5syR|+jLX0y`-jVR!Rp=8l)+N3omEQRC!aicFRq5oYiY@EW*zn9~_v(7TXMj`v zY8-PhRHIBaOFlV49#ej1a7MJg zbEU#(LCR^iP=7+Q+8t{v(_E0Eoile$3eUuXDPdi~kqTg~M2!fl zVKSwxRbb#Yas1Dqc0%b(J{E;vo6~CA#-BJiw0R>%~?nFRPLC?-W zcQ;V=P$XY5+woHKIDQKD(Z_?0@4Dd%tChK!W7tmHHeY3e-&b2o>4#y@ek z(5aEQ+`j&CTxvFh#R>qR@345%xp$F^k$uQ(r=k#xkeyoJ$7AAfF(-&?B3IbES8S(< z$G|&-x|KqxYR3S+{!>M)b+kbm>!o>6$f##?RaKR72QTR0<;|EPJhaGr` zS_^+CBf23`@U-@+Uh7?w`u*2pOlXjY?&wvI%;elNlO`iQy%a>oguh%(SBa?0>QSe4 z!pDMCC)mTaC8F0?gMwt+S6M_g4{yg7GmwH&5tFlf)EEry&3_nL$z=S!@Cog0dly0y zaak&RtU7;t-!LqSg(5v zS4M1~EQACdzBSN)sa~rrbN{WcieDj5RgU6RwY}?lOCC?|QGY3}pN(56L6t?R_Suc8 z=*V_m$o6N@*sZHkITkT@h1(IH4(+O~OSe&;3buv+v-x0!o;L#ByqegGQY@axAD>28 zXynQSA^9M%bXOX=ssE_ki%D@5@Qh-@Jf2GN{_9#So|Z7-!5x*dxILloO1WBMr@^1< z+GcL2u-bb@(j%QPa35fo^|`e9k~q)Ppc}4=0<*>gZk_1T+-WRbu%IcXXMtXL6@OEU z2PAiYECFQ_yV<5j+uPf_8GLNS$48OhQr5K$tw=+BJRHQ!(b%pQIlAFRwOro z_mc&$h+S_*Z8s?=RBlCrl;9`e?^h%xf9 z#AOW3@1n}0^13-5uX{0_j_{ku#rAdC!Wcb~iSVBStpI4iiMV9Ib)|?({KwSwyEI}@ zF!o+w?vu&0pRfLVMZP7+-wUzO-u{=F41L(*G#g@$i_za&?+H)H$uJ#MC!H>u%B{Vz z*#Lbeu}ZXx(u-Od^Gw(UB8}po@Ews*iZW(n5TX7~n_d zMBSjNmNdlyC-*E6mDbMY>g2O3n936BWvx$>eGvet85it+w7JeOr8+x&1sNT%P zRT`AYifvhp=ZSU8U09k<=68mJ63VpH54}uS+ejPKL(6Xul4~SYkZ8!ONPh5zn0=bJ zD0jVoQt|XO;+7JCY)FTf83EL!idSC?TNe4F)={~Yaenv{bd?VJ<-bG+Z)Iy($755Y zSC@DG3^%n&=dJmBwT}iSuZ)N9?x-9G zeLJq@9`CqegIPmR->GZ7<9Gc8m)A*gwM9gwY^Q9fm>k-r%Wm#>7$Z1y+(O-?N4cui zw|B@nh{I*vG5lhQQ^Y?Rf@osgpooTNQ^feKwxhlL&AXZfA(qRW>}=-2?Q6D`OBz|C ztujf%-B)QUVcST-BlhowqkUcG~PR8xXc1b z(ejsKj<9GZ4@-)piEtg0dfyh2LLlgomgpm^^avV7=jZRrxZ>V|XBX~eYY5N`aHN7y zeeW6?IrBH+!ykCGA*#c{Hha9s)&jj7l0|5FGe~Ez=8LY!S_Q1nHW42>NZZHpMpqX7 zoNa1IljxOEIRvzI8%vE+Gvc#Qoiy5D!34AF$4MhgL9k)YLA68@l%}uj5?QDpY$a9X zBFIM)2et9iclqp{BJn(%BG#()@6C-?RL&t)%Y!$X9CosnPDO9|_z~l3aKwa*OrNjZ zGyr3dLkHBfbbf8u41obQ_f3k876_CehLy7CJz{*7PXdBMc{h}E(MAzvxG2F-*f^(w z>ZF9~^f0)%*yffK+b(^#{soYUX;vgdTTYh-KKn=XObHla<~%Njvq_9w zrCzt^!FU;-tGln51cZvK@+_&~GLHAHBPg8Mh%hU~EC%Jq9E!U^mq5NwB_`jz6QKXmY_quW zIwbl!57roT9tb+9c%?qzg2b9~LAv$LlLe!yY{4d3LlZ-P2K7u|7D?@08;}kRJD6&J z;%wJ%)A$hN_1M^jY^Vgr=){h0lVA0P?h+-hiEh`Be+$;IZd~aI4t}TcFy^65FCx`? zrvxIo)^wIC3gWfl>;Bv6wokWDpIQ_S0lP>=;i{ehhu&B*9|c$GVwcfr>Gx=*&2<@* zlGZ_TqbPZVfx0*QvGEx?W(OJ9vaZ{vCc=fIub7KwG6~W6wXr~=T1J!AFXLp%70`AdOJbp(*gPGvCx9+q|S9+&y4!yZ!}n3dUNiD>BEC$Ed}Q)v|%gIcm(@ zyG=O@aPRVy5t0>bix@^Ge+tQruFbh{w4_g}1qPM4Uwr<=!pGQ(iFj7X6zO?)H7dVj zJHLHx8h(|?xzd;Pib9U#>B`s8)ze=vIk3|8pUjJoy3-gC?)`Lu^~Z2rRyin9A@!A2 z?{m5G{|V}K)=>$5$D=^ZVDkZAr(@^4gYMma>U{cyBn0Q%J*K@u>$B*fC|OcO?a<>e z&vR^J`g*R%JHZ?Tj~{{^H<312wS(8su90H7`I`Q_ejMHkzlQ}dcWzfdBzwh@Osd6) zbg}7H(Za;4-_5vOpaTc&^Ylljy%WKeje~ysz!kB_u3gp|2khmRCFs$RBi*u~^r8EE z$70x>64tuYnm25v4t22rcX5Q}@shO5M=7TQ^U*QEJH4pGkvM(2&fn&GUJ!(Zq`mT! zR{$0Ue!qK&Eu)V#f~vf7g>^fq#y;B$4wG`@mJ2@Et|Vj?cq2CWidZ?TT)XyNQApui z@zX8_`?yZ&|JX^qX1)j{J;OeA;8@svz+CIi>G$c3j)0rRQ15yX5W9ham>PBvNE4iN znOx!8$V$gGoK6&$Yx!{PHyXiA&U#cc;<#t+$dthgkZ4-ASV!Zpw!gp8x{+?Pk#Wm4 z>LY{S@f*ZwvmHrQB340QsifrPK=;1Z8xbwQrPXJxkh9m#QBk*qXV%hC&Pp~}CN=|( zh`kqtD*O7>>x`5ix=VAmHt=dj{tr(QQ;s$=GqKX>V5oY`e3bHvJ>u1zd4Q8@SI%R} z&EfSP;=M1n_E5ec6;8g~S9o!Hy;$LV{heCDz+TbY?>Ij~m}dXYKt1?O6xO>6CcMwr zfuj*)o1}yFUv^QZhRsBmaYmZOE0%>dm0UiI4~7&2n!_(5v;%sFfVErG~eEE&u!d7S_56Ge}rJ_3Db@&;c#1B6tke_x=t*r<8cYQTTqJa8^=qLbyo)OP&% zM`a~!U5c%PMF5SO(-fB$h3W-&7GPej7$NG)uc6^&t|I;CYh0SxMrSO!7k9U#{md$f zLC1Y*$`WEwkuFRzY%_b&i(Hax)r8}^F&0TlqfdWr$30d}RZs>auEM2lPgloFj%-KS z2rHBm=-qCf)A|U8g`G!-!mrw*Wd`0^K>|#Z zfJ_XQ^rsiBSeI5~ZF@!wMgM{3f9+le(fANO{1-Fp1KVWaM}ueY^|1$R=ABu17i+B) zd1Q0Q5V~Q}6RMP8zHgkW5C6VK>Yk1_M~}mvwr31d*V~RW-iRE~*E4T7r#z`epuRK| zJ0osz!kS}yg1>*t9}i-H0Ta%=`_{+8I?UG78{qc`!iTg&URQHgiY`>Q)oQ*kDzs`h-tEW3VzsorHEI$eq*@5=6lJutRhQ@VX@|Q9u1=t}T?bsd%X=y}8sw z=E{i;!*hRnr1LB@YNP*XM4LUuibvwN-jPg@MrjH9L4(_kTCY7m2)2|I468=@(@%8A zsrZlDDJTI3OTVOUDcTXR@143UVzqes*KP9_bsd`~zNIKb!92xYPB=8)Aw^4D=2F|B z+AX%fK!<@*p@Iv3^Z^Byt@ZzYs&1RqG@gGgm|yw1Bkd92zDU;Lx1Jdavx zi~4D+7+ZwTAg$?S+|AFyiw5$X)ObNEq}0_UGfH|r=K`=kU*LfnczhuKt>&d74_z+0 z7Q2v2hZv%&a@I?!wX>U;rOMcb{$ppNWfZ+pQCH{IVD=X^b`#n_O#Seebb!Q~jvf?K zgZ(Q=0PAw!?)m+n{yfYRwID2{zY?;hy`8BE-d2D!H=J!`4d)U%$bPe<6r8gN3Hm9U zC5+e@W)?_D5?6R9!hQyj+;W6#q!11^vf7_!;XLYqn`Y%40UCCVG;A{e=$XH;nUnFIF{Q%QT9wK__uUoa ztB}T&Hog`RTx%Ef0y`2BHuf-<% zPeNyV3za`jmr7GZ6{~_0R%8<^fUMc%lU+}K3u3XGe>rszouc8{erfnhrv3e55+vlr zkNMZ#`<|p5gD=wwb%C0i0{e=iAd3yiE6=9K$fs?Oo17vpndLAd-uk+=2yewCTt6Bt zF#h^dz>3i79pb%*Nc4>Uy65G^iwFhkF1*LazG^OrKoWx1$eim6x%k#5m^+1ioAQRAoU8RDx<{Bf8P9BSMF|GLkl1_)F0MuxLQ<#?5{JKo;9O z^^BMDbhV{u%-Kvv+Bc)foSYau%;0_Y)I5=!cBYJ${x&$b>oN4W$_C{7vlIn5LkN-OhfK?f}a6ZT*SHI{m)E_3_Nz$i~P`KBtv*oya~;leSmEr)cX8QT?jl7d=4<|8wVX{AcnD?;^^ zS`m*@p06ee<%D3N?Nm(CCq(Zm^z4`1Zeb<Bay4xYorw|^}*%P?K zo`&-jagRhEegL-1uGyJTCa$^yG1px+n%;7*)Ih|^g>p{m_iX?3S&R^JW-X22)6rPk zRkca9R`Y`1xJ%~ZdQ|ag+waG-Zu-9B-kw;tB zbPc6Sx^(x|voC-X?NSdrlU?=iO}-=bhJU_z$y9mW6?BZHmo5M}8nveU_W6UYTEem8 z+kLULkSv3*n}py}42aTTJyEwg{)4;89e6}p%unyUufr7k1ev#ZT|qDR3DoACbhd>& z+`&Jxpbh|A!u8Q_Y?!|?b0wY1!0&Lri1@vq*(0mle%>PGhrMm!;`_zs;2RNYG{Sqywe*NS(6s)G%?6YJoskN}du|59-9F7J28;9rgruBRQ z(Uv17GufKq5?_Dw?&mQrPc6c`ap~+jSh8w5LTY;ls-GaU|G0=lj?b{d^%LB3>4|_a%Poz@`kDi(QL= z`xhMPLwNvr*i5)L==0rvXdAR1hF7acuo4jdh9Oq@GIP{#plw_wFISX95_gY4OAJfw zOATCRw&^TD^$%HV*s62OMwB42UyqO!^?=I3VeQ~-#jbhQ$%Rd2gcsFw(J{Imhmt9V zj6;d2WVK4E2sR~|m@EYX+U*XT9K2Y%u zGlodrShGZ(%H6Ef!x!DqGlLCjU_Lkk{Q2Oxuj&VMl6(<1?9zvVP+BF#b;+)XN`A)bWT``IC^!JxcBlSGnL0=mGG z6A@F{(Lp14TL?5hJ*TNZ%nQ5@45{;YZcu6}An)G&IbKta>0#0(1ioSZov(~D4e(wR zd*X|EFBuQ(scByfjVPSRdcDV$FOw-BrG%SDHINeEB#~@sMKb%PL~VdiZ=V?#`bxfNLS+8c`JIXYbW$rHj4-B5>Hh`lSc>R-ICW#YeLkicpa+c zOxoUp%A9i4p)6xd?qxIHToz2MFcAi6tg4{*)dJ*84|zG-T!HlpgF-w2Qx{5R^`2K>j$1ZBP6>FuL596pTC0?kL*_*8uan~ zd$HZmsgw)f{k-S0UFnXfUrKLrmZ>WpX4svvcJha^B?h8gGo{m(OkT84&5l+5l-S>` zTd{Sl|9zGmB?wvtzWH(4taoqrOinAc-;0%7{cY}?(1yTE&wud@GH$9z4->sybLHugkqKTMIoU18JA~Z~6f3ozntRJ?g#&W;s6)Ec zJ+qTLOLOEIL+dX6iad(W#Ro(}i2jNJr01*)5Cr#u7*)+m`Fe@Gh1F+HdyqQ$7*ok< zVB`lXmM;Rc;_Fa>JsfEg8kK2vo_`*fk5;rwO|1$%Y=k9xp^{ja=H!#2Q{9pO3CSYw zV^&|$s=NUi9R1oY7KH8cp0o{?4DJnsOpj*{8F1WpZT1-&i8?t1Qe*wcip5eXDSNRJRVGMqFCse z5mmN{^W35D4M}AH0F1AO;nI=IgkfH2W7q|U#7BuW zJR%zMoR6dg2a`Iia?xXto+&%)Z<(}h?4Nn!*|SD{in(T9CeYh+C|C}G9{e)h?2H7y zNSkuSqyVgMX!YMEIm(LAFl;Q5M4kO+;$3`AJH+wdV9k0haxl{30D<|r>~laFC%#wK zp8nUuvwUKN08(Y98g-Ag0+<XXvxcWzHW6 z!vObcUCLhr-okT}JYjrzbCPSbRAH|lAfyb0MSb#~qkGigM66O4WTF03Q05RtOuPL~L#y<^7wHIkk5Iq$ zVb{&$^fB9E|K?1Gq66SbvcBpBDX?3DIinD&X`+0u!SRI~m7TILapn};l#I*qAJQjF z^P1&TU+N6tmv`sb@qad?X*MkbBMOxjZOwg3D`_}+#uFo+BkpQw~~cI z@$|s2Q0wO)H5_SoG50n)xNGS28vj@F?iY$j8j6*oCSKbiH&M8Tn*8QVw?Tq zL@|}H&AykpYLo#QPC3_KsJ(#pqLE!E>%P@tg-fO3ogVdl zP4q#vz4GE;%WXxp0A4!YY@LWO7V!Xj#myx)uF-YJsXGeM49TTTY~gcfaRG_qT1dyV z?RJb?z`vM69^BH!a*lw$Tmf2GaiAD)vdTq62BxM}${ec(dvJ0yP6UCc_HRPv60(4Ybw(0JB zAlG^FSqp06I8KizW#Hu<4pkf5FSnnx!V{8>BVF7A0^OuheyXJ#(lYbY+fg{-xQz?x ze_AG_$6(fsApcYSe~s6rw}1OED$ON=zy7ohWht!n9`PFkfoE1OGA1|HQPeCKgE z;MH#H&I3)kv=*T>2AJi8S?=$p6CXd*K@JYlF2EWsrxBOH1Of|JB%_ zJ~k!4V`!YP@=_MKe4@?t5kG(@XfyW!&N*s(@?+WhJyhfP_;{CSyLr{$p=|lNE8(d! z57vx&FU5`pPb+#aypH7$K_;d+t!(Sdk?gyKVCtYp2QrSSF7zoCR9S6oWZmTvq^KHQQj;a-;=L+OnHw*Z z-sz^sC)Z7wc6tSYM$^;D#TVb; z<}auJNgWH&J2rlYF^<5QM1!}|-?rL?zrgw{HZ;OGE{THIWK$3z1&y4k%9K@8ExJv! z@&)g}rb2z^ zW6m!*_ks1yBkhisj#kSCk0~}GG(r1v*po?Zy4kZcdj7IF-Q0bgW4u;I=SFBi4F70x@2qaY)~6ofLG3+EMAn~TZ(uIiO< z$Su;4NI+Ws5TXttS^uj0DJd&C`XLc+l5=2{v-^Dy8-Ljd8-w}Xq`aX{+`Z1JgLVZf zv>qQDm}Oi4-4cfz4%h!>Rh0bu;sepPVpECpkb!=ekeD^1+Y5mIesXPj`RIN$+dA7A zATpbM$g9QZY5DEcU8>XUcb1D`l~;0$WCx}|Jw4N+I?z?BFCv}17lo)$mZg=qaLf|E zV}#!c*kCX4$Uq*u5v78?jpkbUC95t&QDM66{*#`AVRa$@gaeUJO0sYf1={IDD4-aj>1>XlQh)GWa@> z%A3jC!u~ILz!(p_%cRJ+W0pk`*aodOjp1p$C@J>xJ|B{2tDz3P{hC^+Zt)k8;%k{R z{`Kmo2hjj#nUhIQmsSaU!+)g$;5jsrrA5djIo99Se~HAY-0Xe8|HlQ+u{FB|ZLnKl<*bZVA(I z{5_GrjwsLe`5A!?p0_#PNy?+z#942&SrTc7j$cUU78D&^&=lf2&O1i1$Yc42!NqfQ z9w-4cP9;Z_T4*s${AGesQVVBL`Cb`0era~YA=&DS-*n=Baue6r`kFt$Lo4Ae1>qaK zkH;PU&oJ%uzz4}4-pcy6%P^8n%a%F|?Z39LA|*~&egJ@!X7vZ2+meqcQ=MpXlau&z ziLe)I$Jax@cjDq}u>ft8)8B@ayOIJIk7uOtrb8@OvM-WB+13TchUJf_ITOmOF3XJ= zuQgZjB%VhPAuWWuR#B(dPpDEC37RtRytH$D6psC*)mks(4q_`^ceVIRuVS`yDY=bZ zqK}Nh*sakVyN8>-Xaev-Y!hy|{_mXCM@INR4VK%N~{`V|J-L09uj0GOh!j_mefKk?`s%SJpH+ z^CXLvSs?V<-wSS7YiMk2{h7T7?VQ?G_w`eD2uC|V*Ji>_bMYH7dC*c=!1@jxcP+3S zdZZV&aj;+X*wQYnCQAHK24@(vo#z{NW!aTrorNfb%$zJlhMWxJGqZak@ln(cgJ3QQ z#_BL}=z}6!>tb%No4cHXfjx>dBX)5nl##v^fo8^VhJRvpA)7>4L5RN9f7=joTH_9X zFI5|#UgtR3RVt=c+X!tvkF0DzCU>njFJOHUe(1?R1jrL^m+~mNc^-x8&EILfgV_G> z=}5rXesb8Z_Jao0C6wylsWW0@>A&K=(&C@|}{GnUzZ>2nb&oduqdi4O+0xnh|`0?zIqV5DmeiC0Sw`U zn@2O!lHfVEzT5NQ4uA5;TRU;%9@9VJIw>YqKU-~fi2pClpQdIGQ?cUI3;E8i{b+&v zB3sw(Qd<2{)Q{3E9+Jwp@Gtx%w=AY6nLN9@SFZP$_F|a8d@^_FqqFfOb$UsOk42&7 zl^EVgYkM+oQD%d7eIubXv%i1EXUz$USl)f@m||h+pEs5e@qV)d=W_kHyMpo3Gr_l( z`vE7;3x5+MY%R(gkEqrxB9TFY6OTOjHaM4}LTUV#MKBgtlUt_M2JLkLzY>IR(4*M~ z^A=YtRd(XZ1v_T01#N3e7$bJwGd`ZC4kyK?_VRImytfCH0o^kpc$F+kjle(`b5SRy zD9m54pc^yR!6~-jJ*!H4kb=t1F4O$sr`2XI!;mldt7XHh?1{)9w28RI;(SjYF+qa) z6r52$xsv~e{*8HFa*c)z(KuFYUv()oF1VP<1o1`ttR89zQ)YjHyA768z6vqk75edK z-}8b_tHeS-(Vumn4PA_O5VyT~r}>vrvYh@7blfW8T*J$bufz6LfZ@qD;iAnQUS(dx zRK-qJLmQC~?<3jz7aQEx(apK^NX_kOs_k9zO{!nXJ~79^=-idpts>ak<50Z49;ctU z949G&i#*#L@xwKQ-(&?F?0$G!jHajAFAG}jj=(7DI@lDVJ2 zq=oYX;_6A$Siz>5)c;Itky#xrkvt%TGR~{=kWY}CU{mo-%GGwV&*5oqdJdjA*fQZ2 zBhS@hy_uk;Z|_UKlcYzQ4co}G6%B6;wp(QgsnJ?5m%Hor{k-PWPruYsHs9UQ`&PlEMHwG2{5`Tk~fc25-dUP@VH4!#@?CN)D-S zc}c_Xjj;QOaOv;iZ?Yb|PDkc67rrT0z1MX4%k6Hu5&&T9W=url)-786@ISInhC9m~ zK)4#0X0RC~2d})^U>Hb0c(bB4A<%_ycfHwnLR@Ccd(?%HhOeMi0B}hb$+_FW*aTyc zP4Pk5(A5SmO^Ga}X+KqsNR5#B1MXej@PXtx+keI<^w2W-^Yu#f`3(=9sq2bSyWl@K z%TR#bu02(c`|D(UTE;n!-vpxiyGvwg6sEc_KKSn8A8QzdnR~m~okN18U`NAE9u3Gn zkx8*pcpT0&Xb0##>T)8k^iD(HUh^c2ns8x?@7MG!Ja@~?J`sUT?CFq)jvD0IBOk;aj&)tGDoX-+ak-{#KuW>g%&S2-ZeTd&-!3pNS zTe89@2<|3klqQtJkK+Sx8Aq_Q@!3h;eqJfT3S+hj&^0$yO-UX+!EA!2kqaTdNGX%2 zvsZ#oRh~vQ+s#zGb>4{WL?5>nva%g{VY}6qfecu>3mLZlY(CO7d`CfxN*e^vGXiyC zzf*hJ4gkU!qh?=rNZO~)wO04nZKc#_KJlEdd7A)p^VzfWOgq`W3+KdAA6uivj2-r| zmL_#R4bEuBt4^nu{_8bPrYI0u6{sApf1%j!WOwgQmmSnf#D{F0S4`ONfYwld3(jx- zsknOA!D^ggz_;A|KL6u}Fju=KTpMWZew!1N7jB3SkXXfTY{xl}*>^#GE~MA74Q6C!)*$VAK^Q z|EVjMVqPONNr(Ug!=xYG6j4jyklVggN;1COGak#0o&5ef4hg~_DGHj)Rou{3-)u?p z-EKXKLu2p`e*LNXQ$9K1PF46T(WD>#n=ddx#=Cw$5~kN>Ze5FKvcau`$*n+V?sNnG z5^uoM${k+pz?x5GbrxOjngu%vx6-@5=B=kD`j5d_u%2AaAA91~aofXArl+rSU*u)E zIujE3wp>I!9(G!*EgRdmPxK9Y+WB&MnLWIRG+^7Poo%7;DHB#ZYL?Au%+hTERv~od z(eP358sgs#1|%MS@5ea5r7`Y#u#|JFa&F_!)a#`g9Y^IClnMJ5*rE736s21%H3I3A z#lmZp-fFnx{4PVx0`y?n^1Idw`=v9QjiKb-yqIq{b(P| z$a#I0%%;37fm=9xHD`gzg3nk}h6IoD#1kj=W9DTLCD?ho@oWabjOu^~)kyAJptda* zEgt$UilzaSbH0^lxAoMm7$qBj?CDQSPprxtS2A^jGxL#T07>^Vnx2ud_ZgdY5YQz_ zF<@SDV%cFWpgQKF(ae-3dOK6UgOG4+Dt_XS(e_W}S|oUp#-FEi1(h*rjMnh|Wzy z2tM7*m)(`Vln{MQ*p1@x+pE#+Q`AD25rB0p`VTDwimu(IH~p+(G!{}%(xQ^&i^>E@~k_3!r>*KqBjY%!45Bkm#j#YqW?E{cbWbcnd=*JdceO^)fwEO3DJ~8&DG@ z>n{qfB7UyVWBAECSGoD{@(W2FtkYN=xt^N_v1Afa8ane)ET}AHRv>tyFMv*6{N?i0 z=FlC$ne)}pC}qm9HsiGZYSayMrRilV1>n3x_JWB=?Ajmoph}9`{w<k9bzcdZIPh&-eZ&kTdXO zK}fvucczB(OXHV3@V+0vU?9lFiEs}v6q_X!xg4AsaNSq%6$Z%q)&Qqkn9y`!yxfQ3vmARpZZ7?>Y|}r;=aM&w`?0bvp_Q(x(04WqLUJ)1 zu%K-B9YJ0A6$-7p_;#ln0$nH#j;l;+4JYj@wl6bwWiTz63KRSMQiv;?N*k;#Z`p~5 zZ_`flk5JIMa*{jOziEN*GVQ?~Hi{o50g)c>F|snphL^6k{IZ2-HegD2#qSXTf05`C$Aj%7I*AP3BC3k*?2r9s%nca zng4#eb0b7{PXgJ9K7{`FY;nS=y{yjd0IpG2S?7X)b4=d>&-N?6I94e}d;&|#-UWWX ze}SD$mN%HZ+_tbk&i z;dxx8D@EW_UD=G&SPXn-dMmuw!A=Xxqso#=Zr=qe$12|jg}8ljf`hhQg(8xI z*FIim#mx1=vyQyiWL9o`j@=!Yd?R})WuvT^#3am%LjPa+COky7c|G;Sq}1^@V3}LX zWs;>y+72JM`Q}E9w)e*Z>Ih{A>-jZO%{RY+dEfhS3Bttugi>B|caH=tAhCq^a8$kJ zhYN)810NhH(|kh*ehLzLg9=!CDco*R>vpY;m)q@an~+bG1-?zqBZ{gSFN!Zv2V<^; zQjq!@X}=+$UIEY_hkoRhiRKq?$i8w-7SwwWv4(n|4yidvBe<>lZsyn7zO=Q$Zpfq^ zvU^E6C?3jaZ1nM~2-fMBXc{f)eB>3@M(QS86=3aV+*~IA65^4N4X-2w`2PB_6`9K^ z{V+##fpdCc_Pj3yraCPjEkdk)U9G%vTJ(soO29_~am8z!_&DBJKj8J{!NDgVXg37s z)^hdcIa6c7vFy+MYjT5$pKJb=-I_#iP5#Pde(qc1@n~~wdtovxm*qvJZ&C_7FXc6e zRjTQE73AAZp8W$8ibQ)DSWJwJt5B&WU^sZ;k)lr$!?qdfC%XrbKKJdo5&i2oi-M7N zu-DLQgUhypd+2Qgf6BKEDxA{5YVPNh7=?B|N8Al96OJvcAJ&Z-j%i8yQZi#EHfx1o zFIiBxMaI|t2M?wx_?MVbwOqG1=`-pD^_Z*?Arx~!q`*^0E6u0YqmK}<$um|WbsP+F z7|au|J3YW%8p;U`oDw=ZpMYVI#bYRHAF6u*BH(~s`htXy>om))XjU`(ne!MSBJX~O z;>khsd_w}EDn|6a0@|)D`#nh(w@)QBsn_c97wc@hf&#RvhfXPQGqY@cn@D$hn>HCl z&GJ_u4`@`=wpI2N14ugr?NG|V!oWnav&%Kz`P(^tju!0Lc76js_8OEblJe@UQ`n1z+{bKQJAIRvq3{zkC^U;0JpE8bfcJIb#z*H>V;X6|AH<5J>rUDFOnGooL2n2mCJvm6>D&gc?P7DO44cm-Km zb4dXnXNQXucW*M%!N%WjQK#SWXpehjI3!)1Md!a{2nX)F7U{3&45~5xH>OpYFhOrD z|1+l7dNPJY68%&ffHw@6a;f^%njqN4OV*f{fAm&r7`xW2ohQt3>c4Cv`{#w7>O4e& zXK@w{TEXWj)f(uBakL}T{lx!b>nxnw;Da|GG`PD2rxYkwoZwn0R=gC4;!vcx1S{@d zT#CE97MD*c+fo8R5c{Q=2L^0nQ4c0W((CmWh<6cRl4TwOH$AAa1r#X)a@ za5AuqNk%Q*g(QIY=O?`u6w-K5MLl&j%8u3X<$CP`Bk#SxxXV&)cry->u&FROCpbzv zrb!cWPJ!Rz%RABG=3nKpJh|p~ctEYW=g~D-rVJcYvpK$7vH3a1^oUG*64$JnY^6=Tq z3;pCbtd5G?(;tXjE)bc2er6LDO0Q>pFI%`?mxkO?FY6!v8;O?W?fJ_mgBm7bBj#?) zsP30B%j4coSVgIT{N`MULxoGDRkohiHu$P$Qp41t4l{4h$p4{++J4^|HQa@VB#CIZ zO>F$rL63Y@)~O)k9?*r#5&se)SK8{rgQBYIVOvsGqG7R|)gA~rO+d)6V_E-2FQFKw zzEe3GoAb`t|IV)19{;SGeZ2Nzno4B;ujS+9&F2p%xyoz@?nlo{zMAI%G+Y*A+}>|+ zji!gRqs!$pF6Gg!(CWJ-rTL(a%b>?+w|-Qo6v_JNs4Nn}ri* zkw0Y@p%E{+*dAAy+bE3x%(X4@h?_xRXjqrcENcc_RPzvUS%D5w0l^5l>B}ZCj@TKx zle`x{ijJX&`7bWvzt_!z;0pOyj@aFO9BnST0pz~F=N(N!zL-ce;?GxqPku7l7v|;B zdE9Y#58g@MFMq@z9l+eT6!SWv5SH-#kdGU9o2w}-cR*&Qg8q3>*v^C_#&Y}1!f|X2 zsWolle;EyPBPI1?{ybpL5qzk-M%ThX)ZNs?&(w*>3Y31wlWZeg59u4*5*72q-*0AT zP9TPWvN1^#*y*1G69!D$B4f>=qS=pm)tpaPdfxj<2Td8yAII1#KL$H{OssdhrL5Kz zI)F3Y7rA_AV}Ep-OJx8Il8FZs{G zu>}B08I~`ch@FO>L!q{FMtV7B^-8EmGQ|@0tc2MIUP$ca`uxRq!(Z7%AL^{7Cl5(^ zIqq8z#4!$7)EE|L3C3WES8y0wKAMkE-^YE9o0esBBD(LJTED_( zbch7kfC^}v)GVa9lKl;z+MS##k5_K$Fb#HZ%XO;V0JJx{i#OSp2)Wr-L?`+l2PTv> z<;G+fYi7^3O^|zYtb*G3kA9PN)Q6&TF2Pf(4@#5#unaVEwvy0olC6(qYex$&mOs@d zL$8KXlFVLuoHonV)edl__0PnJm*?WwyqSGt5N=f$;05&>J_>5i3|@FYsU5{c31{Lb zq~JV!#qq$C7?G12@6%3!olvF}Z_qGWo}I@P^JiU_hd5>2>7ZqE(nQ@A1QGc91mH%B zvA=k5F9Q3AHAlp$#};bvUT=r88>y99JCk&*Qr{Vw&%aA&K5eq`SCw?Sl=0k0!RQ2G zSJdU2n}qkoOay)_d|u^7A^NZhdK)WJ!V2Ml+*tqzDfFkkxflP zNC&T%LsQMc-Kya8;O}m3ZO$2&yAzm=_vy?@3`Bl~3C>ZN>-V3p3l(Z673AJXGJSjf zQR#oO(mKh4_rwu353k8dNB-fi`)}eDIu{@Pz*ou(2OzWFa(Bvx;!8Kbj=9PtW=x>T6W-?yY)MUHN`HQ;>&&z+&wSe$#-o}qC~ zM#030wyuZbc{`r2R8|u6zx#!%cueBLxKo=_vx+zxOUBI+-u23$;G5DuJw5Caf zfb!4Tz6w0S_BCaZdhF0{|A<0FAdbxe;?fWDnQaK&r>>JyT=>Osh2Bq$Y4UsC7UnVy z7?uZ4F1FH*UhDLwiek%anwTM|$;$zsok+MP(wm7^Fe3A1e z`7`++L6%&TOTx(?L&NQK&0glnJVK2_9T{*-DIq?I^gDGf*p^u@U^takT!s>V0IvzI zW!pu|4UPSemR&g4lk+r^vq0K)hSChVJCF6ZYhHEJS3JfJ)F**>JP#e{ZPJ0Dk6QsE zu#a+QMfHM_&t^_S+809Lt0YX*^Bqy3AAZWm<)Q;I_NX%(x?rw4i8itaYAos4YhCe{ zt%h=9|F+KMNsL?=7WU`He0NM2RJ-SKDz?ORD&uY00EC;na4OsVk=iZ#$WuxxoMg@v zn6HCu)hLX3u`-gavZiFgueN!)DSNM}$mJP_sDE6%yGYaI@E83coBC+~c+`H*VO;Hv zNp;k9zzKm4eaw_U_*AeR;cEM8onA^3a2YuY^Z$T~6Ge4-oqdWAzKMIN)ES{hPvVVJ$ zO0fUNJ@QyfK|+uvj^^-(oV}kksHO+r(5-eWX!mtTml_8Rq2EK*%AL&awsuGrKF1}p zSNp>_eBd>&2&dg&wV2xeuz3#Dam32`rbkS$@ablnE<>Hid>&fJJA0;=R&NQ6IQmuJ z>L#(`BIFFyVFP!$tL2Qf71!okp1j%?;snnE0fVdbM?qh3ATNf=!`^UMM{e=Nm=;R!e2{q24B|9q zRhp6gJV!;N+)h<&s-4!=ZXY|OyUNiH=PJ>?g@~c1g-HGXr;xfqaSOZNm1=hG* zcEL5bP<8M%L%@SP$n$qJw@cFFr!+(;4&7-webOa9;ER47PYm-)5CBGINX8%`y22bD z+=%|mjr%u&HBr-DE&5~2e+ixW{|o|;S^)w@NVou+O}OAQiP6^J-Wv0YjqUQyxc@%9j80HR7N4 z=I=xN8FIB7RN2%mI`q?}-0pmwH6yQyo79cfH4E=XiI?9!!V_K^35WOnL=sgSyhUu~ z7zYuwbrwVS(>$x_5t(kwh$F-er9^H8vRpi`X3FJHugj!W7YA%=PlpIk;8M5qI6@)bSGAvDmI%xUQ zmjahHD*xmdkNYo38s|xM+|F-FNmzMsVo9#A4@iTBERMwTXuD*Em#(jHfQ#&L9T3T~qN}k@Z zA?DhoM7Q7Rw!gxf%Gs5BgY9_r9^(BqJ zp8`?!_@wWymvjQ1&DIIHm+^!3=G)ruEYSh1r* zZO`+k_)Yv2|K*5qOq0{ul~E*GNw+u&Q%TX>x3dwn=qm9u^R+*UHZr3vts>mjq6*gf zPnus0F~e{%hL8oFKqtL~v!})xgIj!G5FuUEAb<_Bj^xoa0-@%ilohNgOgg{106%7g4%W zY`!#k*Uzx=i0v<>+ghwT7Ww=>ppW{E$QK0xT2g4)-KqiEZ5s;T&CB<5^juSHrO(*W77A)Ub9y*kG|fHbY< z5-Q#@Kb!7&a3o^Hfy)V=oB_u#Y3(&f!ab4@XFdAFJN&vtcHck#%u+eq#-&6;{hkfB z1hll}4RYuRdYAQi`nT+~jD-*BLbB0!LbqeoT>JLU=N#Ak2mNlwZJWwVp`)^s?u!XR zDMo60;Hx9t))hDdbO(I;M)Q=qKsL7ToUT7{R7N=UGz{jT$A8>$D?Zz#^7{qig-c83 zouAgnYxw8QE~86gD+Ti5%XgmJ&)^nNE)d3E-3kOs8uNG+ibC`ugxy&c_!uKsOv%1` z%>rM~?0#CA%4Bo;Jz3+L;Uizm%+%rzZrA*k;+eqfwqNFFXyb$*%Bl~$%=><5T7qX? zL;6Z!ctTjkiX9&WA1rlv<$4VV_@*sI#U$JRm*zD^Tg~KrC`BNN2Yi~{W?56IqltHYSDSc|#y-vDxzlkH_a<`v z&r(kxC+KeT{jPIV z#96MQy3{xp#YxK{JlnYh?G%z84t+N@t=7yzxSer$V+1O?=`0p8SP%sH0C;-*9>Z~l z%5c@!fO8YnmCH`u-sUj!;zOO7Qlf&6xth*I%b0WXWV9oWRG4r7KjA}74#jnxikpfY!N4PRQc<+KIS);%6Z!#+ZL~jkvFS?%op3mB293%jgHHoQw~&kVf4k6Y^Nlauq@#EaK1g14s%8ZQ6ZEF zW^45LQ-9o(cDuQ@XEt&E+n0lXUjy~{)id7wd!!XI&i}bX_^0b*R$_--4-RHUSs5#- zUk)1H8=JA$ryY)Ew+b!V)}fSH5;#w)2Q^8fc0uvq7w#i5;7{drNj;TXlj>P~E`_9H&oVKN# zM#OC`#6fohF%gHVyJmjsrcn1Rr}4w!agBosSz5Hevn2d9$u?)H6D+kIs)j>o>vz2^Fnjlp?lEd)P& zR9Y2VOqdk`*JNzzmY|u-qXFqyJaQ7ZZM0_~m%wm+RyeFB7GRtOAXC+vLV<&?aj2ce znWO>~5;lJRPQ4B~WFp)mjY?5yeE#zSXPp`RmptC!$2$ZUUdLq8y__*YJly=d07!g|WN#zU_Qb05RNHJ@ZQx#!(sxN46 z@vAzON%Q0(sz_Pe^M-f~s!o0DmrO;;NMmTvQdX1K$5TITJ=cA~L0N{)8B4%`V+=Eg z@XRHFfVPvTEWehDS@$pAlZwd#TRzT)-w($?$yvl6& zVk2ulJovFp;D=YuNr1?YB3)dw{H^GrTe07Z^)ITfWDg!!=`MiW)@nWhfp!fJy}I84 z%jd%WN1pJfbeJ|;s<>WYc56^MeF*~^&4pN}+0+3t4i zEFN2_^}1jd+iHpF!hclfm&pYOFhqU6%82}rPS&j}Cwu@4w%+J^JaNI42hCvDb!`!2 zjNB{L3CWa0l27%6Fdat%U)*f0DFW-iAG zO2$dk7_anzP@f^CS;j;$hKh`XMB;5N+gvIOUcV#OXHumuN5dZE;;TC^>stHekOD@Z zD%Tq_HLCR-mQCtoG|DL7aOJSwcG~o{i%a;hks-tK_lp*U#rbLkl?f zhI%GZkN&}fJVWV+S3q2R(6~%)l-j+csQ1E88Y7ku01fgwu{WtNQ>_BwHV=lnX*^(UcF9fN$V8jq&0PMB zbKYLEt>){oOOukpcrNNDd*4SgO`-58U2MijruIDq&+nxFi_1!E3#Ub01n;UJdSkTJMwLD+shr>}8!? z9}A^p2^Z$9jo~b8#-4oysMYnYL|}8@0QLezk8hsx_+gztcDfWGO`lDUJPO3UR()XT zFtDeHpF=AURKN0GWM|N^el5XEgiq6+8tH!Yl0PGR-g@@A_+9a7Cid*R+PsVOIrn24 zq1aAGSY+t7wg0OAq$Pm2=LlQr0C^?}FGnIUo_u?WU@^g}7uRV8uH?Gr9Rg7fO8??a zh5B~N?8ROFqt4MbH1Do_Az^8LfpO+EBp$E2$yHq7jN5kaW1JTIJ&VkZYohu5YZ`P5 z@j8!XeWK|{lvu+YLf()z4dwWU4xgmj0bpXe1?Q>W*k*c0hOR;vX^mlxP_3Bxbpf%l zS`CBU7nZ)KJD?Uru)C;1kPL?PMM|GtYkkXpT1_RnmgQkSjXOD>t5Y21&1L? z5E^WmG{t&GzN8lvKAsKPVnrx0gRi=_DUCsDG)*2slDd5VxW&$n2GII_!yfVFSgue{ zW%CK#_pkmp`{W&*eUkql`-Gi=`r74_EhKbfLSX#}42V14KqspNf9#l)VEvsB0kRL} zKK=3F2>jP*4HlDj58kcY>(dYA4m#E(JgtlZ`rSpzex*0*-I8oue^4{)c~ZCxFx!gu z(>An*Fx#Ej?o=8!=RRPYHm9+PY=W>*~=PL78FfCZNOPn;$2Wpek;GfV+a%LwamNyK&yoso?ER0)! z^8G}9-S4f>_1n9()yoTOl~eQm$rovBuOy8`j>;hTs=BHqL&> zSIY@k+Z`zq-xauD@(9F#!1}YKa9i!V1QqItpMlP9xD_VhECF&Y9Z)Za{#r|)36O1b zFIkjrQ$iK6)=lQZZsVoNj$3f^G^*UO4o!3rBy`|))XB8H@BhzG5tj)Cq!xr1V~J=h zfDA50)bPW+#|~r?BTRWg*O+2?gF0?DZjA7eg%L9%996h>!lHJoGudx*5ALv}8P)-x zek^?NC}>#p_ubjJ2=4PaX=QcEoZ&&m_su=(3s-Lqr14`d42B#-`dIf<9LloHt&6=! z{+Gt<&jG$$>C$d3t@{237e7eD_C@Ds)vEFStW1+z+)OH2M&$XDsSO=)-hm7fhW6p# zzVXWjAo8{V(U^K821Z@<6b}&|1YnVvpg+S_vPOS#a*`~rMqvzn%o#rqniu>b5>`s^ zi<;48<~8j(&?p!&4?+-SS1ZZ9Ot{+|d73rAxnM(w4lzNu`Z3zRZP zw`7QL^hsR|&o|3X$kJZSt;J2RVn1Po8wTH0Df4;_>WAxEqyh!{_yj(M-2%q{}1`u;L9?ePO zvWMCBO0U)wNm6SuKVu<~y%)q?uTL}GByZYwe5u<3`K~z=Irul2w^ILkIIb8i#II7J zzVq{3E)7z7+k%no*BISl!LwJLntYo$)3r!;0iCeu?}BHm)?< zaS>|V6DYu7Rbk;U2;T~RGG-dNd0>VXBOdqXr|Vn&rd}5lT4VNw2TROb+Z*z+Yk3zR zZ1+Kue{D5PiKs}b+k4R}WSKnYPZKh&!!_4b)SS~jGXGUc3E}rgM?9+BR1Zx2)${SM z__N0Cu};?o@#6+iT(B?uT>NWo@4wTd#d;1#JP6QaVt`h%PEZPy4uGKnK10~M6Yuue z_7yg~+4vVfzwhA_h>x+YLzsv6Rggt^-2VYH#oMlYrvcPp5W;3K3B-K`ZW-_XHwt$tLq_t{Q9SM<8PI$DkcFmtFuM+1*TK5)w>EOV9sqeCKBP zj3aF^j>PSC%`h#CRMgT+suPdB2V-3^PY%(tzg&#f8<xZpNOY5zahPoD^!An|{ghI(REzm-aRY0ooNx<9F9_zyi0SAJN68hT)cw z!tXO11}|#s4XOXqH7Q@2Q+Q8H3#x8UkC*>x=dCalVZ1ge;DfA33xVlSesM>~il=>0 z_7BY%zT_KO_uiE;S9+qro;M^AY!i0EJiUtx!%P~f_j4>NW z%LrI%4*hu^JW4}c3Sxv@+A7+A@J(l!zkG~>kwACWI=xrl>PaMi-3m})Hy%RDQ3za9 z+_gD+Qnq3wForIde_lnrZdGo#S7XA0ZmTpGy_iOy=Z636J-BSIC^{`H591Q_4GAN( zT-fN#*y6{Y3_8A;>^}v}0~n*ffsO>1Op8^sYaad~=xZ2R2~-%tmMCs%^{(h{najX< z(ZPj@Haz6By`pS_j-Bx{j{ENPy?7M3HSa^;BOte)B1?+if~sO&PmjBPi2UJCS128B z=mqqTO5=*U_HyAv4?1nv%dX2%qh zHt!J602NX@^0-#ZoW?2!w-|KIe65c=pWfE?w*8uO&!SgBUODl;E@WG7(g*3-)H2}h zzawG!v7fbcf`YNBss$*I6XPyoe`s+d3*`!#f#h`g^lf0#5(H#E@Lbocz)$kamgr;y zSF@S)mdV=JHDXMV%51JM%ylL>)WZ37iTBN3uj`aXf zETIPRWfVMg)dC5_+u-*Ml#=?SIM; zxJ`Y%r~%c``IG7>oe` z#Fx&W60|c@1BhY7#4@rT8weqhC~8S%q}vg+Xr!3`P?E~=7{ihzXkR*XB+-I@s!1UR z6HO;-ygb%BQM)r=s(3;>?7vpSge-TnJlE4Z=MC#EeRY;~lrHr#WtId+5Xm`D?T%`a zmkV2q)PfE|$93(*Zx0-R{ zHqG`HEeO{;1RD_UA=-XjgafVc-+Mg|mld~@q9d(EXhz-HBNBq$Chxp4_C;@ZKWn5N zud-k-MThzYhVu*V`WB4ZKag}IF_vVuK|*~y(mp_NpS9zvc*^ww^4fCQ?L=2`rn&4%sDSX`d?JU zY1vfM+At}Vxxt^nT!mN%X6A##ONG4?7vqVs`l@fA-(i$kz97yV^4KIRaDI9zUPO(2 zQ}$G6@e<9jJ)NwdtS35{`7vi-1iT@LV!k*RK{RvtUW=oo`ikPjhO5WSFnk9$y&mMX zM<;^yc-)*5P5-CyfLwmCw7t|HG&Qd{`s_;?fCQQn=wrF(CrLqqz-{lu*KS?|F*)L@ z{htp@JrQz&3kBbd-&V_9FU~|C?Bagm6p09Cjll>`V2R~LFs>RkRr9PMJKO)dzU7DG zxC_m3EMLDg0E?0FwkhwnRmK`vOP6M>d3_f4zDm@|SZ8od=j)4hurGDDO^iBiH-x)z z4sf~0xngB79-lrZsgbFos{vaEw=mS0bNuS`ygM~RJf95`-i@)~CkG0s*`nJWSS2i~ zcE24{_Uf@AJb;PTsp1C@M3(JCU$#CZ{#`Zi67;j8@ur?joZmT$ zfkUC~k|bxo!#xYD*qYmN7^N7|eBw6YeE#}!0x#u=BKyye9Jxj}nb^htK7U#COd^;G z2DqIi9QQ5mI+p+!%@eiu$^q^8&-xahmM{6YyIjtYt#f?LKg?C~;p3B;Y5(L#o-%`z z;U&S>ME~gNL%Ct(s59ks#oH(@-w-8~)D;G)%LdDsS=(95dn>)51q+xg@`mJW?voZd z_qqX2Gkgl1`Pl%oNk@3QXS-r{6s7hRLGMxs=FA8X$hgs3P zU!PBp$9R+z)t}D3Ai8;!)~Sdns&x`7CS>T88XF*hpCcHE*q%Wqx7*BZij1&Jg)6&72&MR*D*Vb6P zeh2%Cw|xtF>i38^AI9ZZx|CE}=T7b^qGlX_+gE^BQzfmV+S4ns_tD z^n$PVZ?vqP2Gys9`F@rnLOFR~(c_;Yua0@=2PeHd2yds5(bDIKVevWaWC3LvB-OWa zluS0vSiGPceAJ}Vxr;K_njCm9*PV>q-Qlo zF{z?^_VS*Lsi*J>*qWnJCHzuGGh9dR?G2#-+!+Fi(i4uwsmJcu)M2@;O2hVXi1!wq z-SQQORk2s=Nb>0spM-Gps`Apu@7~tvMrIxD$6*i8)4!A|Z=JK8eu_3a@ofz_2fA!iR{xGtPXc4%8h3}YV^ z?zZzpx1SmG&CRRbQ>XrUDoMddJjcs!6S$R>Any#;u+$_y?3sEbt=gl&YIxNnh2}Md zD_e*1x{lyR0^L6VhS9+Z>bl=#l3ayxhP5t3nA3~yC9XJ&bkou_Ufn&C9Zgr%#v$i8 z#>i7+B7cnNo#Q;Mp6<@2(ENx>J3c3Cm|!-pm~Dfl7GCY>V$jzR30U;YKA8Zzrc%;dS+Osepg`?=o^#M z9#iA#@0<7DJIihp>3c{qy*3DA&0j-693B@`XfO!yYSZUjUKDr`fm9(9Z9%Py#c6K% zVr}H$KR_XOGv>ZvAlG*TMzaro0KF!8=|t< zb5F?xM6F4c{9^a8q@ArFj#l^{L!LRbobw+!4|_SwCDO^2*Ge!lP4` zN#EaAy{tIwAhhz^I2@QJRtjuky)ewLHOU2$7uu`ydf(XDqV=484!_ZPc#s*Xsl#y{ zrVF*RQ2R&yTacSmk}QkGCM=VQu1g0Q$$-G{?$iS(*r^BUfvf7yEF0xIE5`ZOKMIlAl_=mz^@?%k`@a)3fZT&pCg( znpk_(;4lK+KfZUKCyd-l=2PZz%|NIdx?wo}RifMdZSnKs_x2Ya3mM1733gu+=6)8K zqQCweV|BHC!cI}syv^3VJT|pe=AQH;?^xCHO^QF|Uw<}oxvF-ycCS}n{p=5eJ`+Fr zNEBQJ-1+u9Gg4mqNtDf*f|WZ%N8eNa7)C|{IBeBoV41vp60Kx>I*OmSz}pZoYo>Wv)Ioqz=9rl3)3VLz98b~niCDd z$S0ey4jU6CTNr>GXF654CF@_XgE#b;eqe+&F3Mh)BVoqw`9QI5qaH zSB&p_?(7d@a)yO4_@VE5upPe-xI_t1AR(IE+NLbo+-7*;rVda`n-8EOtzbu@x6{m( zOE(>UVSUG3SJ2O{_vTq%;V}jkz-yrcMeKoeykF<;#$TNYg9^KF%Bg4B2IP^1579Yp`qs^xo9)g*cRmG=^@$%CLfPvwyFLlWu<5u+y~$n-G?vrJ*id)VU(Gv&K*< z9a`x0oFIB6jd}s%h)|KYb2a0N!|3DFn}ugtG+)O!yPxX7x0!FvElVhfYs+V)v(ZVf zXzQz(6V4Q(rIeqG!z3fsaLgx(86L@rng?PY5 zo!*!5eM0HQLE@Pbb*7-f{byhJ*MXoSZR`C7TIE73vNgA~4$pnjg$hYWsbgi3?_4l` zE@-iar@2H<-9QcYRg z`Op*OF4cufkrj0V`~|Ue@F>5!wibX=b_^-VFq#n2{bjE#`x6MxapL0y=f?gk z5r+vG+x^?^jqum^Q1Qg^z?s1Ys%Zl@p<<5}C|}u$33brW1`v1DdU57;>&(NoNIcb< z(@_CkCdLM_19}UGApxJcqHm(8MYLIxbdXJ>;?s4E_~Epu`q{Pw~O5fliYb0+Y&F`-DHZYR5BCx^rHV>hFm2?8!yZBC)dp z|0C(8Q?9c5`Yug)6L%$kmBC+U3{K5{;2&nY7+?9#9|g|E-HH(36*}X@@sN1sG`tgq z2K?9ra7s#uMr`8CQ_(fAI7eO&v+LIMeC|XSVC>NDRsF;%VhGkzmpPw@UjMUzn#PrQ zb${EG@-Ah!K{x+XWb*}S0R2}a*o=r#DxOUp^48wSid3-}(G>;E+WkQS_gQ@_VYGs+ zJ0m*Z|MiQ;wg0NuVv%F{$H$)TMVq|_;_650Sk79=OV+i0UH#jXP?&G&+r68mQS7=g zHzae*%jWqT)G&Tpb?nSc_}|7=5s`Tl#evO!1@G3STN(Nx(b>ZzrIobyT5xJmoL z46>(DojiAJkC`~YjHSJgj9+-5S}V50rZ*MB#TQR4@~`?T?@*V1gPX1X(0d=!|AGq; zA6lnaQ0NoxG$g16Nc3`m<7_qa{9J3pbc1ATQ25wjZs##vnbjwlNm=H&eR%(Myd+FA zHZV%&H*Nn4!&@eUa*$Z7TwLM&E&Rr2!GOoAoTCble*9qI*~NwdljiXNsZkQ#On4;A zea%`DeUvg=@K?3(u`Q2p8@dH{+~NM_z?fr+AFh_~>Vd>^**(5ro(~>#SfFeR&8Qzf z+Bbw2r0qP-Px1j4U98G14Gu|Rf!|TiSvH-BkVQEFeUBBR&ZURnII$&Rk5^gmWG_y9 zca_s$A8Zmy*Xg&S2!y_e zo>!@DF$wL+>>`Uk^seu0zTfIiBm9McA05&xW(#_=Lwvj$>#4E~*LYO=$z=ZMTXjF* z)Vq9|K4iWJT?kuFQax&Qz>>LkH|;~$3$O4j;(oBKjIIQ4l4J*0YMmnZQp7x*lElL= zUs9(T-yF&ar1h7Z=AGRP$EM9h_}=Qd+D=qWiS^lLFj)IeB=-`S4I&boa~MqQjl2q? zc{1MJ^t&Fl^Z4)%A%Z3E<6n0VO=PKn!c%}9;N2gP9*ZX#CP2Uh66#Io=p-XTbi@T} zgOcp%ByYAHCJCQvc|w|90L|*y9U76;MU|*|qhcth{Y0 zI@Pi-7@a@(8$9}N60QoQk~;lc#Tg6BIXDGyR~$k_AR72#Vu!-V5D{>b?7m13i6h@A zQ*zJw!XN?;k$Dut*#yc-TP*tkegru{UNWW~mn_0odgVGX^G$aOqKe1(a3%BgMlWf~ zSiZ%fc`v1{o$QSv>J(vwc%h@}qMwJ+qT@6dIo~k5;QGck9N{>xzgogh+ZW!z7zWG2 zSO$FOlVJLAtakq$TbXrim=kswe>P1Rh#O7D-AAHPIp6ekM0}UM*-b%|j5jdXa9#Q; zBhXn-ev)gxymuov2&ZgVBxVLD`yEz@<}_!h$IIEw;pc0@H!4Sp$r9T2yGla#SKa4S zB|7l?&ZwGUYk5cLOce(VHZ-<=_L>_xt;#+LB4#3bzjvZhP zrGS%V>uYQCP8PO(o!vF_qWOc+R7JW2!gEa*Po?A~tp5)7BloX+w!6Cu`lE6Im9!ti ze$@)AF^tTZHHPaT1mVUjVZB8xI1A`%ZE> z{VkGC%OZY80K)z|!BMXn6A}eNn8*~Wr-usT(-N67O2t_}wSo6+Es%D>!;g^Tw(1p-yq{A=$jq`QjvdAl6P-3g^5PL?bHr#-lz5EW78^ z?D=P-tF{GFMf@ne2%aw7%yoJmqAbmQgSJK~drp6PnQoa~YrsV1K7K>E^EOfb^&kR! z`YVDjZhD8k_@a|X_X>H-7su}f#2?MF*-#dQvVZRtUPM!wF)|5%*lAJU)_IKkddOj< zhug!iyxjh1FrO>wieXLK7&hG30}-I0jpfeLvP=ujQ-q^%6TPTRQjG$j5@-i5xd*$R<5IdxS-mjhCH&5HB9F)FH=l z;NIO(4?dv7YNrAvKT_@r?TVCWiUv4W8=Q8#M0*5>)*nbRVF`}+wp|2_a_X<*zRxuM zlAB9)Ji_A~sK7p59@d65r4#6p0zVDs((#KY336IiKha9ny^kApWCzRI?XSCUsY-zV z?Q7hEjpYrYI0T>vg5QxDO(J{=`@MeZqK1xMTceE$=J^Nb6=)Kbs!=`tMGRok*iI@q zn`O(xW9>1aTqzcJk`YDiNO;B&SM%_*`+xsNeBf|0!wNQ&Zz#1}99&NmFq zZ*Fgk275Ica`ks|=?5jhcM;b3VO<4LTdl!$ADcIqI5yN5wE#4`zpyT-jJHNBM|t$I zKCPl`v|+K_+BeJu(N<6UxpmHZNFbP=WX9ciMPK=?7R4}*F?tZ{JR2ek zHU)$-X_y`lDg;sjr>gyALAfh(F0U(xx34-uLLcdhC36dM5a^Pb1&;HrF0=H-3$1cN zxp(loxV~yz6{tV6;$n>dgBQ?+{jzYBUH@6>Jx~W@CNW1<+#2%`zLBRyxbV~?gOeI7 z(2J$iqm=b7CylDf{`+BMTSwk{TsTi~i@p?9-vf=N`E__3<4#5Wq~ZjE05sv(*>LSU zjMmxpcFKsuT|~As^$_mxP+)dJSSvYxwpw2Hsbkke=tB{3Nj+z?tqHX_;DS-Yu}5Iy2l&F7N!QN*drza!(x0h=+r zI%f$>8lFss5#l71$Jwe~#q+DGd7_Ts(!u~_tW{7-PU|aiMLGDrxFsJjG{9>&{{*5J z#SdO?a372!cQSZ)2%d+Dfkmt}o)cE4kRBMnT&%z4`R`qZca3zxej*iTx&3^)8xn5< zEs30VXxuD2c56O=?{s5fgHVD6W$6Tlcv-Q?#WokUnegKZ9_ zN|Wq*kv=7tAmXaan_O&7Ob;zis zUv2~-x;N=jsuT=Hd!`PPHa)BW_Qt4j!LX=z&kOGBz6A~jH$wD)xV&1kp{1~{I!?`h zp;z5Yr@aKq=b`W_UjjU2o8PIqlk>!J%|U{ElmH(>KdJ5hk*8_g{AOJh^(mm4B$mk# zP3nG;BtQ)>XkZ$^&JszfT^$EfQjX6f#{A{G_1W6-fX>z{I&SBgS;<>T&|htksE}wkf?fG~It$owzTgObHUvH{AO zjPwBhvy+9+Z7aXw*DBm^D`v5xHb0#;FlPQXH4JKPr&GDpR~4z|fQItxCKC%(t6n@b zbQ6=ZDn^hVDufQIQw89cb51k<_47H^H$jL6=vNfi=Zic`Xm-|TNohS(Z2crA)-&hM z28@uug>9=S9j%J_CmL3GI~Xdt*wc*1rX+%iO(|m2GfVn& zILiieQQ|UQw=^@q1QA!puB&DeOdN>MN?1ZZH`RW+{knqQZF$6IphQIRDM*4?Q8ffEa4&pNJ zsd2svm&*It+ADpguvTX{QN3?Ehpe}b`PhAK{(AnBY8VrKBA{amBo#EL9hWgHzPGD$ zk%N)JOvQl8jxco0;;`k-|Hal(08-Q6t;0|-cm zbT@*uIJAV)-5`B8zje;JXWe!GWAWeK^X>0_-{*ZIl7@>J4zu{ufH*OETxXW}rt{}S z(-oJkA>hzGm)$|^%7-H1_NZ%xODELgc!N7oKj2><%~xkY0h;k4^w@wfX2F*D{E%hN ze8kj9@tyl1Q`W!l9OQ_HjB_VL)((M6KAz5{DjnzaO5L@d13_sK^tiNfC#Ipz(&Cu& z?L}M1g)be)qw$(~bA97p*4?MH+?dJn`FQz73@O>n>yQY6pAv8-f87GufG|!SS?Q$1+nY)v zS%#ItO#GDgYLwe0rUWQO^q{u9mz^zg%cz@;?GuZj6ysZi-6dMy@@m zZhyi_J-y9CO(B1y=+}W;$7P#Qi>u>Y^ZF|A(QC1R(z#hGLE_<`nV_Xa+lc5idyN)8 zqq2o?4BeY<%5cr?kQW8>!`~wxWY8-8l^W;kWp6(9E`IjKPv5AGcieVNH&J!s)7Di= z#C3@!fw}(djCe+Sqx0~Mo|p3N)k+l-kU}qh%rI068t=z=N)+0`(Xrp zAwo(IT;Z*93BZ?)JIs}PEfbL%GT(d~mNWPfwZyc;r$H<}G^oD7K$8IRD-iyJ!7p!> z{^I4wCZ*5iDBlpA4SL7pXBAee)RQ)28i5_{Pw01hysgv?a^7PvX{TAH8Q2WkjbTl> z5z6BZ`gas?CF(GZmS--8XGnQbEOB3YVbCX#*5Kl|Mma;5NOT1(5f!O{<^IUer}k2M zs!NkKsm2Qe~To zfGOb*DJN68OgU)31x51Tq-d#;dHxJ~Vfh4ZloQlREQgt?XA31S)kb?`)x?dq1}R9m zizgreUmG8?g2FtpLva{ebO_S=Y7r{pterUcqs#A&JD7qtQU!vYd&zn!>D6+>XpZtI zHrAA}@H>egMx(y6Qmx}XY!h}k>I-m=rgj_H3Rv^ym#HYVaz=B8;4Oj)FHI=^M|8w9 z>;5xCOuFIZA*Iu;Ec&{yh2LW(U6)+GtNXY!5uCV|&iY4Op^LR-th)7jFn z4RUc~uYZ2o<`AB^@U?0G0UkV6Jv)PjOMwY0%0TMI6StTwedp{nMrQ2{j193xf5IsQ zosFzgdm(9TBgZKY-wA8WK+Mg!uOI`))xXbRY~TxsZ=BefV#dq4jmC0{F3ao^0<~mC z3`;dekP81z$|d!A&arRIz_-NFKO5F~k{R>g3A=s@3t=p0N!0Q|1{w;o&meuWtY&jT zJljbD8Y2R~nEcV1P%pw3pLwc_f#Uem^PbeW6n@d~O2Yp1A>Sy+ed>A#7g`1T!{vWn zS+nDrac)|pK^1u4@6?WPrMiy`4^p>oWEe{KO`cp9w4V?$G6&97=pQmtIOmpa1i7Yt z!}s5o5!j`zbPLIRZiapwQN2!5+<}IL=>!d0J7h)`WeJr^Du}VnpjIaEo$wt`W77KB zX?O7XwErt_t%Xcmg zBp$|rvH#YA{Mt(_m2CoO@;r}gUe>WS9cK8C&tjVs^l$%|)8dHFzNv`!zL=Ud6aBac zxrpds?g z41Kur7z0C;Km^3lvB+O&S_kQjOC@($bKDzFkn>3yCl44z)318Ld~;#BqVb7<;dk>Z zw=uK8vl|$*vu>siQ{I`k6qPZsbw5E5O5J!d$^`q(LB;lxZf7Dp!nclg1`i?8)h?M` zE@Z6ivyME=*J?Yn_A#%>TWtAGF3V?}GN>!ZrmAgX+pD=_0#h;Da#=p(bt)Flb|WBF z2z;{7ruSU~r^BZnr~8x+alC(x)!)bVBs`0}%1lP~{Sob(m`+WF@e&S})_6%QyUU8u zY{9j&co(^vPRSY4t1O~MbUiKKOs%XJ0EUdR#`lYU`NWcdnP;}#pQkmZ2;Q*cY?Lz7 z!+$xabR9(1#!4;1O+T@3Sr|UG=fKeD~9)`Fse8Tf-8iu?XUOI z0O_h!Bqnl4eNNGyq6&_R*r>(6;+o9&x8!Ds5)FMLw^#?5WEZOF9r{FYC2+v+bvaJZ zPkX_Tv$wI|tkzWN(BEQ)Q-xE=MTB?*Os_=vg1zs_0O{gyA2ld%06-{M*%giVTt#T9 zr$%sND&W`n4ZhVlG;3&lmWwfx6V;B)Sn z`p@mdss&aTXsM#DKPxnrr&u}BMz8kgRdll~J3!}5R{j&q@+S`Vyg>m9$lKh!L7joK z8}=P_unn~9qeo*7Y|xq0i`up0fJS_7PD2NJ++~N}L;RfD%6&e2$sb?&4uM_|Ma9c~ zSY^2ciy0bc+=9B!GWkbnYmJ4&fPtHO*ldM&+ZOdhZ}rJPow4TUj&IT>=&{dpMCb_e z5^gvzB~9c zr^}e7vjj?POMyUCgj*J#LTTxn3J5-8J2E}`zVt`NXqtS#-H6uTGA!?r)`b}(W4 zs--l|cnl3+e6Ad%R`66PKKV`wk|e^KbYXEONug32e z*~p5}r+|-$Xz6r~Y4-^z+cOj5Ek(I?yB42PqKFLfQjZF`S(AZ)MSwX$0r3S&43gvO zGr005G^!q`XALLNKr1bMgn9dk}UbfQ8$F6sgVB}3G3EWEizatF5s4uf|TIM zaT{{U{+rRHCNQbzS;rnxUd%qS1d@xXIyadp2rcB`A-YZ5Y^wA;iO1^+fsi%-Bj4OO zGG4kfLt2N1xTv9a836Z2CU*x~m^kuXZasgz-yeRdo?cG?aS8GIRR>>UxfcFf2Pr(% z^x@TYwcMSKYyb*SgC8r;YOB-DTb@(jLI~h!?GD6uSprUL6o{&pu6JWeS>G`ZQl5r+uumwa#?q?n$oIc(IGxFAeEJCc1l*< zKlXfYN$cymF=xjtcY4BsXXfP#yp&7hgi4({nWHwd9g3FQQo;2jv^f{c(@kca1Bb3A zt7$avvAY9apQQb^HG-_h`=rU0J*hN9VmUVzjrt_UG8V7c1p(z>wWw2fo4=;&PjWc9 zriIPYKE!>r*d=mwk?QnKX)HPUfhuC}r%Xhbm|d37+C0EQl4f}*gTSBNyp>}kMnB@U zg`ADP@+3Qj`}`TExCJ>hy`_LJ@PyhPdnt*RpRm43NF~!S7M>CQ$QcNm4t2{eRP8xR z>O?Eq%0jmNQ_5Uf$s!vp93=MIYKUMjy-E<8n4c_xp+A73@J%FUMknNn6f?htgp4oW z`Tq`qfSs5!*hjjn3J65!;yJ9{Y+Q6sT}u!hr)~udfm<`G+`9^HSt@Uc7_{%7dd3TF z8Aq@vOiRB}{_%sVw|FL!sH_n54zoA4YB(R;b57w$|8|c*MnfNRlBmkfg7wr{&k-5^ zefd zN@JIBwterv*_b-L6Pp59($^R7?E3k?Vx)ur$$uQ>3%W0=TWPFqX{fF^;+NLNc?_yp zJa#T}LKTPMtYM()Z3s1UGUqOF5-E0RywizJa8RKhx4g5Q#)E3O9uETT6pA>Nx077Km?=yGUz3`t<75yT~ zf;MI#pB?VKOM=k43b7qHVG@gZovb_wNEj;dBSU^x+E5@gFRm9g44J?nweu-IqH6PSaD8{zwAMROZ;DU|frXOE)vtu|{w*b5hZ*W!yQ!Ac{mvZc=?&kSydTH&GA zmNxiyhE2*oE(TncFDQ#VCOxP4{1og~mSJ1P?QM=0a~JmB`+=q=tnTnY!;H!$2A9ft zTVmei9)I7t5Lg=}{=JkauKI7tl;GQ8f<8Pmq;R}MPqu|-1B2Wa8Ikxug=g{CQ{U`5 z936M*9YlSVd_U_y`lae)`_u`~OzG)fQFHG3;AS$0j-IN#EXAqs;TLH!D<;Ac3`%IX zfWIQvC%)xq&nx|>*T=n9+HZ+DErWV&UyB5tnAt-DIUkHk$UfhQmITx^?QK ztqM$U^hp`5Vzq_=qPosV^mBc81TgymQ-Zh){qF6r0kGsPCUdr#sbkRPg#V$t@m9=w ze(^7sPb^DhO#gljpYNZg6iQkex{w$y5f-g>zlrI(Q*wHIA`o35nhVOeyb!hkP z;p|rNtefZ;yFWROC|@ax3z^rvE_M`*5&N?R`>_U@_EQLscfRd(>#DDUDcw{CNG%lU zm^e{0y0{3KJ>-@iFnyMiZ>Y#1JWwg@C~B&ptm&wrxprYf3C!e#q=WJd!a7^a#fdrZ zsPx@p!*}j96WwyHKW__u=YUL~)96P41MeJI_dSXt=F`eIokx72p*Z`@VYaG4Lj+(Q z(7Q{p(-Mat`_)yvIF;lCOZwY~zKa+|0v6bMQ1x3L$f=|5mmtY1j z#6*FmMs7f{Fv2T8N^@IXqj_w;m^u4W6qFeeLc$pdpEL`~=v+;gXdUR2ZRYuj+kULC zC2*jUmDw6$dUk5vacjUPu+a3TN#2e=vGcmK;Z`GGCq8*DPLqm2jz^w~D!m#yMD#F=+dC=sl?w{}ZFye^Q1Vht=81 zklivt;%kLptA8{Fc@m^goP?$OEc11F$8%$R)Ci?k{h^YEcdto~H_V$0R(s!1RYJRj zdPG%zb^Wr+#fKW2SWJzK?vI2ZiZCIzm_}}29YS7<*9iSqMS?0NR{F96S_53t3tbh9 z;o#UWu*vhCU+kLdJpjO`F!sNWXdNng!2O=7mrj$-{l$}E>80P#^4~5!g@FNi-Q<7V zV4o7iZ)}52?ZB8_MQ-BUFk+E76mMJ!XP+(py0j&guS9L7Da#9s#15Zn*+tMlOh3z; z;#NT^+AyD+LoD*5itL)taz@aDphQzie+el`hgbP0hP%@zhFd!e*5_4atgl7tIP!j6 z94+>dDaSRK7w~2z{hDAy^1Xyj4{Hw|vrcvX`stxl5aj1}I{Y%t=8I{JbPxt4m{=*S zL{!?uzvJ0~?ltZr-JVAO8E({Cq9O@yF|%Hlw0A=kS+u=N(YX042yu3YysIQ;o^$hM zGKPfRQ5CiF0l%c$GhZ@pH!k$S+}1pog=n1$Uo23+E0uS>#_>fxK=sw_|0ux30sA=~@)j+LWKg7+zsTd_ZEzlsq{ez}|fp@~A%5&IA4b=zxh zUtN>Kj=J{7uUaO8)0dGSvmYM5v*Rakt-K4m_eAy`8NZ($>h`Es9{gxGCGJeK^E&-# zFFXXkD-UkaKf%xHp&X(DnNQN8=Fjv)s?AfbI0Kk_)j_QIbBS)P!@%y)-ZKfQ+?jx@2$a$;?-L4}x+}>_0h*1Ek9fCL5(Tz=vE} z4cIYqaV70t01g84q=$ws9Xhoi$MPeo?Xf$LrT_SX(jdQBi?ivp9~52!wxJpO01v3N zEjClL+|;I}P-`~=v5h_Q*={Ir@ARo_|K?K=M>VP9(V0$f0d7X=HK3xXfaSooO82V;6kOBY}YJEWV-1s9d&^z~5T|3<{exeOzF_KsWdw z(@`!3Th3EMnyPPX{*A_f9RwRyT(pc_ZC7-!+jbTa0A$= zhfaiX_jmx2K9hy4^*kzM-zKYI5b{@0<`^tSb2T=b}3 z0+RyeT*Ui#?RPF^A(I)qUtfRFJpLPmGQKQ3f|2uJ{Tg2BUJVFsx(g%jm#cieh4HF+uuRQ3j z#=Z-9FM_PbOq}_tKM{VnlxTK|ePb7>CUT3HKK^o1WzkoHajMSrI7R3Fjp*abmvn&; zNtfTn#TtK`_L!^1t_oiS-Xv-iF9D!b8+s zAoOWkoPu^O*u%&LLbo6%y)|<2Q8TYm^QtOxuT>s*L1q`zPZEBu<@#b;cXK(9YR|?> zm=gfEBVgmTC>PsMSyAaip{WTDV3owtvQwS@#9zssO&;^^I{suy@-R0j{;s@Ca~st< z%aZurm%Psgao(&%A_*HpiW2ub>Kh}b54B>W{GHchE(?syL!s~PeK^lgqt*SSS!(nc zTAw5s{@^rF?=iqZJw+@jWECk==MhTb@5ru~Avf#e9|GU*aSRFU^x+*=T*g2y1yUa@GzoHF5oZR!lO^K;&j8UAWNeckg# z4Y=tqt%Wx)+i^eZtLqmg>Niz2VRo$)%^FTwcAShS{$AqHZz}(=4|5eB8{QWrqXxKZ zocb-!b?xuIV9jJrbl`rZ;V((71oL<}0v?Dv%#If>|I{A~;*zrXE7Z79N_t8LGTtjZ zBqNKr@m0`9S}Nf{$%YWyVN`lD86)PbdC%3w?$=rd6%7g%aY+%cj<$I3!&+2fKvV}K) zg>?tc0Zhd}peiMyXE7FsjMYih|83!8REeS9-S5ZFcFpJQ-{d#DIt_ftL;I2f#KQa@ z8_?#CUe|UxN{m*hbQp7E+w<Bjylzz!YfQo1pHuQVc zDy>?mxO&mob8RSsBJO7C?!RU?+MG~=xRbHgGhRIqE60_UCJ%_!wWHMz|E5COyAf7G zVBG6w6~n&+jJH|qurd_e#J#{7fSOGeA$o(EH}R>t>Z$FY{-2)8AnBoI`IU)R`!RR> zaY#D=@(7rc58zt|XLryiLNo!_W1-u>ahBNLfAviL8#woS8vu(r)qi(e65Oz@SmpMA z5_f;_7weI`G148qmc6$S`>vU1A=UAPlSPM)L->m3Z)?ng#riZ&hDfpUv45wAnITyb zBT$-xJc)CC7-maC`Bd`zIT!5HHa9aLIL1ay)4u9dEC2cg_@=sZkBP~Oj2W!tFgfKZ z(Cm;2$@hmXHmT341OGg4_$r!f#0H>v%qqH0X;+;#dG!K@0z^@ zgejP&e5H9U-IdZv2vt|bt$a|=pY(ZqFS$sAa)34Ck)VdO5KSTFc`=dhaM-ttUwAEb zQB!E0kq5WvA#?ip>q|CsbZZjeg7~2o+HnNS8|2lo=0%Cw8Co= z%T~{|fUoj2E_;yhUW)@TjA$bnhc|jnJ*7KYva&3P zPHd7W4mMjC+w6@nrtP3@85%R{;f?UPi)H8gLI{J8T_QMl?y>&QAF$Nu)~5^iF?x|CUW|E)pXbG!GOrZQKo%vK9q552L9YC6qPfkX{+ZA6kb`zt!@B~=@&4lJ z*Lg0JZ&C}A5T{q5X7AAMVD*}RqBI}ytbif zF~`FT@c=BLpDBpYl;gDV8QT?z9x&fytx<)cw#g0`E-m0bF@sx{>G!S}LzwBL4SewQt+R{*jYC=ah zN3$$V?Qg`=a75JyE-MJhItodDp3RgK*Fb*BT>=tnUXMzqteso+&!OAnjICfl1DN8r2R$-{ z^x@;>Fx$Li*{O@;UK0GPkV!cv|B43!lvTSFR2jimGI>=0OKnE0X&SgHpx(MkhtBir zf3p~-`%ncA#k*gr^cF;#V_RHc+rx=>$X%tx{I-^o2Z;+c`JSO%fDGt#(~P|3142); ziR*zA?QLM)I#VnESi)Wq4yX@8-?wEPgcM`#PfHHoWuqW0vthfX#T7VfR6jngs?4}U zX8>Lzpv~e3-dgnq#=qNHPITa2zQSj<83QG*(ZObpVVLH<zB#w$9XP&G zd^9P_%$Cj{ERZ{71>kt2WS)S6)BWN4L*`@~*o!nvRAH8*>B50n(!~YF-*xZ;54M44 zIKE_!QAv`Q;EOmp4GgIIO?br086F72lx`zgOi5ksRa?6n_9zxIHa2h1;kZ`lN@x+Jap71qr%EO(RupQQD1+e1_U(l+6Qjtcqgs z$_uLFV7^$sK^NYzyzC-IVtgG?s9`t0C9%S;F+S1@aXq4S4n7s{KSjYq1q>SnieZt| z&QudPzwTFZ{Sgiyu!cWmL)vJW-@y0cyPWf7r*e-G0;j(} z>IT5jO7P%%(8Tsu`I0=yAbEZgYP#hT(%ki$KOrjLuLQZu&WT&%CD7k%W&_59+t+)I z=u#a>yP9{K#_|;45nfFPW(Umz>Hi`+J$tGEzie+ht%kvDwU+#m$B4&2_lG|I;YrLpbI00jL){I7=I7u*=^W>Z#%WKynC|1@u4 z*ksMgB+F%iPMoRS{8{Y@bu#`~v3T%bBqjQ%SFu)dBW~Rr3=ouM{^JJaps~$`VX%~R z2TY05Pk>L#)y5sL>b9F$+ZkM2***tsXVp9J4_p?Vp*)E`D0Y|yn8O^e9p`wkca5wG z7&X#kN*vad^q>W13K9w%bqdCH6kE_w+Y-rG=fRU_bQ@E>mQAOkK?%0u^2`9&)6z@A zPD2iLk8PqAb$uQ480jAf8OD}B$%sp7Olz@l6ymeVDJiyQ#9f&8LfF$<|0*@eGu>3L zYQ8x4&Lq})YRh0+x0JC-Tg0N zk!Zr0TV&gYDwF|BO0g8q$|TJ=(mu5IAg^sIM+c>PRAj~pTUKbI6dw2e@t?k?snlBA zHlVF{{b@>n^n~Ug(eK~tJx71rc=+T&d(UZd^Q7l7G~PNL;cikvy#JdRcvpZcwX&=7 z2|BIO7@%3Y!BE*5zEsJ<2@eAVt3kHJi#oUp>nH_BlvXT`&LA=DND)zP*lIcMgw9Ojco7sDI=#%C`vcd8X z8k_9;efb&fxNTlgw2$f-9b81;(kR3Kf-Z(I-5oLp=#ne*cy)q(H7BW=Ca6Z}h+-}^ zIE}Z0>Es;<8svMltw3--e1wQSJJ3ir@zgl9Qe2;rS+P1R?fzeW-v1nZk62_54KDyR z(Jy~}?FYhblxjWh#olN?8?TFe1V)z;Fgg{%o$~A!z-%2 z-!KBuUfArnjYRt;7)ftb5t!d8_>2XFWoy)(;0DTNm5m~jNp3gTB8a#sP8s}N)P73j z1CKCesR<&N#Kocl=yrxm(qBWbySP^KRo{oTm%TynQ8SPnKMUtmZ;P>=0}D0h&vI<= zyR8p3zZ{zOjw=KtY)G_&?n&>s*1haMXx3EaCLah*35&3d_>Cjg4=&|iw&hWCi#6CA zt?B*dr?`iF7qbEtyo`|OJz^Il{eBYn{=L{m9J-Tb6;mskj5zx;v{b^uf_kh@O2Q%F zdXFUasey9`TqjjrgXpX|Mj|xjKCS|LI+@wrtu48;$%3~)!YStEd|w5QB!8eJs|F@8 zp%h*;BCi$@OQ)$xPiRoERD}{1PzROVZtP^s3rrTTE{uBb+LUBjWu7abkfipCB z0MR7YkZcQ~Ko$NSDltAt=q^RpE%mid_q9HMs5geR)UtJ^F&64Oo-fVQk6?_3gqf(+ z#EOZvqHy#frZZL(15!jEz13{G^^!UfZultOM3sh)gu>WQ{i`~}#kL@A@@wM%a#u)} z6l13aWa7`j^{~#;5K|Qkqh84lE}0Qu8hWGuVQl`-iAWy+&xGZO`?rp*$^Lmc3a2{J z)UK!U=@u?UCg65%XJXNJyneC~-GKWZers9vtIoc#UAmb6k9D8VBGJVv7<#G zrb*q;OK^j%!!d*>G3oM`tvmQ9np8~{9~`Bg{uc-!#)^dheOnIU&J$B(^2R#`o`g|0 zUsku5g$S_uI7V2m7p)ZjNlMUSm!{^e-=T3Q25?kV%hZPV2;>`s`1&pv`X}zIJO$^< z%&4&B33<%?No^Qc%Q_LDm~tmtLYG6{KsplV=7nGuVU+VLW9IKxciz}nr6&VT%B=2P zq{Ne=VZ)BKGff1qhCY{?5j@ZkrP887g@@1R*H0g6^Yv%?+nXAH=AP5Kn%_D$LG=3@sURpf+ijq_tHo_y9Gl(%EO4po`0L~p# zVE&txqNKPAMZ;{eM5AEe4_fGj#1|Eun8slHw?CS1nHYy7(`d5ltZrB^cMapZuel6O z7l(6K)#ft^##NBGGsB(t1eg$iyMvfG1)0T6;e|)qs%pf4M5Cv}>{@3b5IspW+HluN zVfW3s%+DrKnSTKVv_raviR=2O6QXg^d=|fL8JgOcS7Af7#IzbXcF}BuVJ~EY^d+5s zVvuVwHkxFdSoo3Dw{^>33DYQm_;gT6+V?VSCQFqxU98-fXOB&yg8!x0-WCi)e zLF8V>k#l4z|5S{sabNDz2P^pg6nTuSlB!2zwIeu^)qGSY7x*Y~Qo;`PYNCoP)(G=M zwKkBT|K(!}SK*&=i{t%)6=ma*Qxb6F4o8k32bwiXe-!`Qk-y!8;+MSFOGg1Vfht2{ zW+tX@%t`w#-Cc$468+7Zju%Cdjj0*N369}nz; zgS;jEg|Dl_3~Ik~q69|bQf8+QF85b~^3zf;g=OLE5SlHGD8o4!MDR^>8J~y~$ct^U+>;!UJrQ8|}(8N2-?HLOC z!Uv6{@tk6vuc@Qc$7)hOuCeV3JMvYIEG4r?HmJK|d0s91S7PYBPuIGT>D|w4cS%zr zrM4d%FmosME9DN60s~ zywT7u*ya%H)__TW*%1i0n@TPU^d7XpA)Rni(yW}`2yE3ZYH=;>U(m<$})GZEJZx)G}~&cYfDkl_Llzn1o;I$F!Luyh$e`f?G;fHaDo)6<3SodzkkrBtP5G zJ`->Ts$T@|rUB_bOCH8;B{gzCO1#ER3$c zLlB}znf;re2zZCRc?aZ|rFC2`uzT$NE<0LRtNozP-($6lrnib7w)E^G=&zvLx+10h zuoDz+f%$ES3NVi56 zqEbO#2<02wV))K8vMTa07{gitN7?{SX7t(9ZLwsa^M{zzV=RQ8zCd5d+6!^#Kaw|I zt~H?(0Cv|b_eEoOCtR$9t3aT3p4&R&@wu+K3OB&@uZl zLi6ff9DMjfw+A-}Z6ce^1!nx4V3380ppgvC5p6@=T%Y(-BV2EfljnB9k}m+{XZgZ0V^QGC!!AL^&bgu zJcdn4VvsWOw)YNr!KL|6M9P);PGRagAV#s%pE*b&tvtnquo8cxvm$eqaG0q;V4=rM z-CduB_d<_zss6TWLyBF<#ElZ;+i130%!T@TqjY#H8r(7)np*~l*gKfqXPhQ>eZnXm z-t%C+2MnV+2;Ef4zOj#BxuyhB-XKS5NEV!q+FXM9*0p5f?dNLZkG@Ngj*=Zw4w+L(oZMPL443DEXt`u)0ci~i8$!jIa7 z&{M4tXM%2+eYu5>5RxafuvgvX+%`sJ0xK<7t?wJV*8%Xu)P6ElA+MfRB+o{T)d=6V zy;M?ui@q`D*$-4#FLa!;N(SzYBtK8r28@1V8$5hYuAXxFXZVAwgmTr$2F*`H?e49X zyiOE;0iN@jlvZru3a#GQzV;P-G6Qi*OFliQ5XH+5e7F{1fY-p<>0o&pO!Pbf-y^>*QMVpc(zoJEerIE+Pl(ZB@pUAhT(A&?0k(Z| zrzb6}{EO+H3k`i?D}-VReYC(QIni;-rkogH}IOS3MmG)^pQVV=_$qxMTrGiuGF6n!23#yABDN7&l zRI`ONz9-VST*aOr0jTwEj4m0!eVTDWhi%@nF*wKzIij<9yO2fQmuQkY%|WlTjed4x zn2XhyOw^mn`#VgcwvsVC*ylT=v!iVt`gsGDaNv>rpC@%bpJr!{$3(Cj=>Cbh0;Ji- zA1ng;%6A=OJqemiIYle9|J7toL36#o(EzMu=`m3EETH=fh`=Pv(R3~__Mv4M0;(45`Y#YPLU4OheeU5_3pPq#V2d5QYM*=s>Lf~hI z7PyUHvq(FukQeY2Y7^BfG{m}tPz4QM?g_sv_Lp#F%&J~#UtTdwZ(BU3A$#GgD;LZi^lrJOA;Ih~xsF*i-wz|)K$Wo< z)RPMFwScM9F&FSTT%`b31%&9(ys5C?�ANvPU)SRs$s`h4T-DV zrf#C8{$6R}X!R;d%(yk$ehcw|g`#DzPD?##^349E%LEqhm1BzvXYJLF_IodtKvDF! z8`sZ$gTh<)x{BX6agCo^5|TQEd~fFDR@OxtO=j9uB?*r~8Vsf3WSP4qa? zhg=G^e4W8LGJqkwGNI;YZ|5}M77Ej#?fwxvzz*?&|M^msQuL!r%@`cPsoi#5>>c$`nKP=U}|fp*zmq93ia>mH%j}@ z%mmMvBv=NVVeP~GKe4D1>4~jTU$afzkWY?Z%QJ4GNXC7oHT%tK(IabLUsLfSEEykJ zoj$G{dtu3&lH5i-k$%%U-5UO^{epmy9ab8PMi9O5k`a9wob65h7Bg?A-@WX}Y@H7W z;ofe$rnC3{e)0G3e zfXG2{ZWO>g*D|LVt8)fhaY2Gup#42;cOE^CK(_=GY5Bh21qvdWYc^b%#t5@0^hVTY z*@hczy_pGdamM2Xz5Ct#zQIRA*>y`oQ$gXo$^KfAn!*E zN-QReRS*mGplt^JqglYlpZc0sC-ya`Z96NmqQj z#ef$;OoHfhSjKnEdKP6=Dtj_o&qsxFQ6GPzr4BTQcEY<|rrN->nj(^~?#Hu%A5@Im zE~6xrg}@7lG|zB+wl&TE2sjT(j*IM7q^vmAKLe!#JM={##87aqs8^LSfA@g`t68X9 zuPIfH6f1PHN;%gVe8h6+O-pS4g=B6DNZf(8jLAq8+yrsh)+4Pf0@~<3k@baiCw^(x z8YQF!4L@>+bep9u3WLm0Vw8V*%5KDurymlwf?APA3CUWX+6bz@_Gg(}J;3$+q0+uG zjVR42-JwzGiz3;p^sQAOfll7wxxDGW;P=?-{y*L7ys4v%dWHr>lPR8YynpM^+l*Wj zX`A_<5_Ylu@AiL{Fkiev)N??klAjF_DjH1#AI@?&f{^i8<_G^9uJncf2d-qhUXq7M zy%&Yp5}(Wi^_+uXV-9e;%y>2iL5W%OK}uEAtnXh-kUYJj&~qKLpT?POB_khu z+#werMQN|(@Go*zAdCOt*(trRY5-QH*R;#d;VVLvgQ~bX8impMDoC3f+@s{8)_SCs zt|bO**IR;5@Dv`jYt4_buDG(qRWdjSZ=mY`Q7CaFJQ?*wS0z*!Yii*VPI^8``co!R zGu}dp!`_uzsfqM(#IOaKZ+HkI4Hh-m`zm| zw`)^9=SaQ_ezUk?OaQeDWQT}HFi!sT8-*%FdT?X4&s#A!8`?zFTeG@C$|?xgqCgGSxA zrS^r#gyz=U!?Z8a=g|VIr3y?jvar5CU^Mj-6U|hzXA2P!){;Rp{d&b1x*uPT96X;8 zc~O%ac9N%a>`&;vUD}O1lt4$^?$oq2vnj5g#W&!S@@_nvbxrkwxtl}ny5JMH`4-Ek zbrq!bQzA{8fu>bq!AvS~qHoaGNFQk3LBbF>j*Scf?b!|Tyc`EMs2;R$>vf)SPaO7g z>QLiiM&T{Xpfk0HhMrX3f*{-ngnWmNAjM^&#Rk?~X=cZvOlsM-TRNA*dRX=JE7^%( z%!s3hg%*{6cxwB888<(k=3nqe17FC!I_Akt4hafIrn3+2YQAzHHmwr^bXKwlC!@OT zstmE>{~Q3zzz_gho(2*c#Onr-OghhB1&5M2E8 zUnCXnh^$f%w&E{*A)xYNg?P@=lBC}ddW;$5^ogpzCar}cN^m!2aUiW&k_~#&P;dG> z2@dk*w+$`(| z_D^oBxAD-!=htZca)fzeEWgIQ4Aqbn@Nfty|^)8kT&^!gC*;BvOG4d zRSm4x5a+pDxq+SR8wr;7P?mwKp9KnwEcELWp*NaFr-QLiP)sZrxbrdVJ)`_Y2_sbNP&9P87i)Z{`*x*DfGEa{Y(uh`A2VRQ;*~k>+FqM?SipF;!)1U&d8UKsAD&)nZTnAektH z7tU!JV)R@|K;`5I%@q~KlV_E=(a9hLeRvgE7IN}^=*46nQWabx_D$DP6PBxL*`&Db z7^L=n^HnXUb=qZf?DK4cfaprs&2D+qjT$w+QQ-ZB8!+T9R(;c60Rmjo5lgb)7|*F` z(J}gfr$SQX!Br=g#0!u4fS$oK5^8}Wi5o(GUm^K_nEJ}7DA%xS7}5a&X%Hy|X+%Io zY7h_w>5d@;qy(iKhE@;|B&0`>?vA0AMnLKA?r!+*@x1T)-sM_n9e?@E^W66pd+%#s zEOHhYTkBqgelERBk-O7xW|^M*ny3A3g>1wGqsipCw(rLfdxOyR_eP(Z2tv^t%xq z{hcdH-0@Gj_et48D#za5B^bwCL%2|tJM{V=vu&RN5H14^IayAh@~2?sJXIz_`fS&% z z!F5L4%k*BdE$KzFU+$Cn-EajdDhGY#2DnZHmTWo2hiyNnsTJ2Kw{VZ@)<4<`0W3tJ zFM4hv+}r%keQSI_W-{N|cLl>^UFcQt6E;?T$^$PjMd$V|TWRF^f|SV~5|%GqJ*3S{ z=+lX8>p!WeM(3AmlO2y~1tQV?j{C!M1#!*Ydq+h+Q{E5sFMoVh{Hx}CQPbyT8`^h1 z2gW2~NJnsfu@l?c#1q?c{q|84=G(4} z{f#?ezV{oMRS!QVGCdOq1J|28jFLxxR4{^H=*x99%jieQR>#wQYT3fq_gBv2Z9wPe z;$@1+-Rb#C0`RJdv`B*Wcp+ET{cllzulIv{NtZ2UuXT>2cQ6`$63PcGsQuEETEyI0 zw`phm!Oo>4E-&*{cE+&JR{))lZdYBph~d!@Vf3TR3lZ5g7dPRcJH`=)m-AFhZFk=j zir7TV5x8mf4?LmW>dXgi+Tw zJ5Y}7M5DhDHgzP;iYdrrLF{)@4vWsd-O_tY0+0NTvw<|RAXE$%zGr-N%f7P=<6}&0 zR(?@mUDG8-m{7M#EE!J5{#I87(9i6srX1(PP+R)HBw%-I7Im*0QV6~8{O-LZKVo_0 zI2VXJs3yRd`_X#&cE_q;?)yh6x{~w{eYeY6v$aB8aSy#dHGkE8(nE~lx<8&%)l^4d zbb_oWr@FH1^Ib>tFzb8cGwkMc9ngMGz3qkzTY~Yz%%M_YsXsjp+@^W7ijar=o|6G^TY+Hedu0x`X2O(6cKdXEDJS8riVY{Sfcn9R5c$jgZaEB^QFNZu`-M= zXznGJfm(2P@F6BS+ZWyJZXAB-(5B*s5GSW63h0F+Lfq2A!sU6IQ@vqVVV_bA1^u1b_ZluY!l z%>A~c!6aROcbu(q|3i|a(!8wXKJ_mV_X+tC_P=d_I_7bgcJOa6#A$kj__#Qh>k^;i z?7Q7X;aOp2L-fyTX!}{!hW?S*c)LI7!8D0I5ZCJVouh|V#BQ-P80cv2B7GxHsYNmQ4kucy5J=>T%EMJpFG;Kmie;EQq5WBDQ<1f-?NQkdr?Oe z%9rhl{RefVkMm3KO}0^7`aLvWV}MTH#Vl_R;|wBzi4D!f-_@b;kHH9e(SeH*OMb5{ z#sw#4vTkGA0M&dj4zx^ZP8BG=TAE<#b{CP zd(pJt_nCG;4x@k6@cr4H9pNuuu*msQK=Kx_>yXR8aI0n9d(y7G6Y!%NU|-&@>g@|b z7@HhL*KN05V5VyXR>G7J3C1KdAqYa0BJpuZBZwd4@G`+ysCH9u%Q=;`U}_OaG23@j zbXFm0VKn@#+Yf6*B3_Fg4XTwouBlE`z2N;k4DT<*5(S>}dWKDcie|~z-%oP0xRLaa zCKNFj1+`(AOZ#HS&IsofX`inX+r=SS0AH|t6bmlKdqL z!b2T(DU6=HJ6{6D#gWL92D22bSS)h(H)~I#Z{;6w8CHS)(i44)QHG#)IQBreM~92@ zl#!9+a9pc#k(@`|oJJI0&7P!*r#o7h7e)$BAzb#)qw-f}JcqOCC`6yDe+kQAJYN&zC1+g4 zwYVoEDXtFIVJWjTOBg%`V~bYjZ*p2355qSqj3XI=eUdFiB%U&HKbO#E-LQS~@^uf2 zF5=U1f#Y_2{gS{J6zm+S@gH#WIgTU=_1z1^C{ZNd@G*6m!|0EY0Ox zc!gQl)UK=Xj2LT+=Y!T#>7ep=at?$_aUljhBIVaW_lNPK`4pyV_N-dNNZocK z&0BWj3tr{WBU|Z;jMx=0;I~f0-2l$=m5%&MqJo?&o|tOOq+bsrd#%C>lV(rSDGIf>JC}r z^xsJB35$cZ7xBUlZ+AIsEoFbd^ zn=ye!5iU~4l!JRCVNqR))wKNMFZV@tui%h(liCfQHSiX~v5Z=ww%bjS5GR*J={CO4 z)%IK4Bc$c+oz>Qp7(H0)D6$d~mqvH7K5Aeab5a+v&IH`ZHPS*K^*;7tH!=^Mi*vhO z6UO|PoxHrPwYzZIc^a>$@fqHMKAq=o^YIvh7;$bAF3h^Vf1LzwFu235XpFp7dxLjV zxZjIN+0p~J2s+<0I!X$HQ$(auay$cIV!;XHriYu@@z#4Ey@r$eow4mJ;AU5ab}-37 zL8)a`GT3MhsM45P>OMfnF&|6LhDYUfndRVOSoj&dywd0HH^{Z2%es>0#IR5?2-Tgt zYhXdmbHR2R^Ko)^{OCmo2GcNf_|v2jy_}r!70TwWIYVkDl9$QCM_erMU*> zQDwHWB!gr%Dr;}@pA|j6VUAe09N|uJMu<3kAmZHeDa%KHqISj8HQ1AY5gy5$YXRx?l$2DHI1`R`C)wu2YyWx-T$`(?oHoM=)q&>}{ znAsDLlz?}pS=e3X54pj94Jb)W#mJ(-(u!N%FP41$kYW}|kf)$|$BQTG5^7&>enc^J zyq)xuzk8i}7cYW`eqA+EZK_78{w7xV4i;Mw10fROJ}o)Lg0sD=(_HI5At;?<@rf-> zj67LwmdIiy;^X}^8^^jR$Vs+`@nX$<2=>Q+mTrA9|UCE0H=Ho6+*iyG{VU zH6Ji|vFWis9u4cH@q}p0Ci}UPccjyT1wO>g-}e`#wgJAj--JaB+BjIAAN5q)4^_Hw z{jsO^k{%?Z0;N={7h!4PcK+N~ScB9O^6WI(M#PJvK^)Fdv8 zdulsb&C?$qd=HBYnY_@WQO-`#Pd`NTuUrMS96kD!ihcHb@4o`W$HT}>XiR#L6tS~^ zw~mxeTINBn{SKJKru;?cbGc^^s;4gSH|v9iz2jM#G-mN8RvrPhGrXr+yJX1WtGpFY zLmLm5Dj+D5;USXU=AM4}SquZ`^WBc;VkEQK>WU)v;d2}z7^1F&@Uda9aIB>0YN|X- z0CSAer&-Le{z*S_{9Y*^$Fub~N%fHpFoK-%(~>d9MP8##SJ{B?#VTP3G-pH;L?vwNR_%$Jx3mY zVy?bJP$B&^xRri~zL=S`^hb9!(?fEZjb7RnOIK=~aZ9a1-BEXjkpabvBYr)q@{JRD zo4xh>#63zRFwOg);M(bImkMzsPD3u2va*$W=eJ&CU^!zZte8jQ(W~Bet zAV~JSUez8}KrNI7ms%8lVJj}mO=|cbwz3P_3AR>nz2xoM0MwGrhv!M;wT6j|+5-!9 zUJ=X>>1m%&yph`3dqD3pX;(>F0?cn|6KF2QQWP-g40P%a$vaK-q@VM(r{gLBP;~h_ zWhAlfF9+RZ5RLi(H?@t8m6c-pzgx#dtMJW$17IjA|}?=ZMjgQ7dC=s zkYU8NCB`3nADw$eyVsQtTEO;LBj~)zBX?hKl)dy7wbJ~tM~^EhLhrozS)#W!($D#* zIL|JmPluLjeq2)T26!>+V#r4FF;n{WnNAAs+tV9$hv1Vq5FaSh#%BvMke8ErNlJ(N zIfr>d>INFC1u{T&HVTPC_&{-iQnkieSmP9PR!L2=VOVtUg;8e}LOkbMN zeM)rdv?@=0wiIV*doVY&k=}j0#;g1SGew7?<-O9v7B#)DkOKZMRcJcuCW!mZL|3om;PH>va7Bd@TS72>)r)@$FOjL%RCH3od zZU$VUe<&7^;J>tJ->d+t_X!(j$*XT^vCY6y=1^}!|; zLUL5t_>YWwcGa6631UyQP7-L|I=pMq>g132!`Y68qS{rWZk4r_$#jUBs1EMF+0V>5 zB~rpqXSw$yvL#fW$iCxN8Y%i?O<``ijvruu`10untlulMF8j) zRxX+@Izo-y=>R`xQ_?RWg^F!aGgRDGx%a*BB}qBf^ruIR^UTn4S$LcST1nhCc=vss z3UF9ituDGaNWuE=&(tiqKT}32H#sXX!KX;$6AT1UGj@R0PnFf&-&X)HRVn6teYVn# zW9I(7s@fu49HR?8byEYT<2Uymh$SwIHM9quBb6;hm0WW$O%dm5w2EwUPkpXEyIYFC z9F*4;ES*FW3q?%fYzIWOg9M6br9=d%DAaGcLALBXKa9NP-G6Kggo-|c;=a=t(jeSluV)&Y_93(Y9{5!JN>%zY&z!Ur?{-uHo8IJq7#gf>Mj_H3`51rOt{>+McE zmV`N9Jo;j!b@%&LALcr0<%qvT7GpqWVZV_azR(7cMDskogL-!*DWf`lWN(AtY4vl% zL*k#e8ShDj1GLlLhS{>3=xkvzlFCUCTQiAqla3b1KaP~Ks6$^+f6~T5^rIcjr!ryp z08g)1A}J}d2JKOR4o`6((N-Ifs~{iu3=mngH>tk@X_M!F(k4ip&(P?>GtXm}J-Ss& zybhcjV4P+nMsG|7>FG-l?B;MXUb*5cfqABS9hb!X(%C1HdMRvVvi3LQNj_!Du=QS^ z)n_3iY!kASmw!p7Z>~=!@IP8jifqzjSmUfo?gC(QK|$*a{bZZWn`*a3>cLr=$hw1V zSLNIHU{FE#!=Q>5R*!@e&9k|N9{8XzFET=G!Ty8&QBgqQcwfFr7hXRxz7Jj#+N1q@A8KE5+SP zhkm91?$YTj5D?$bO0o~xVyY7bdabT?Zi<4vBuNk>vox}AZjQIH4RYsuE?fg?$R7E9 zG$sqq=7Y}DE0d=oh>$PUnVa#M**GAdh&a*^1U!t77X0#YrN82*A@8tQ!R`<~{)50O ztyZKXVaEL^Es*fdd&6)?y>G1{tE#(Z<#<1@Z{_dQihAnOgo2AiR&Gk}aFE>PtLB{U z`40O+z{|P0Hx;()ZtIEimssh$xEF6Ta9YeHA}m&VlM6L8+m$=(g&eP&Kkrn;(D4j- zATwh(>W;FeVbH%6<#|;temDe^>bB=Mk=FRZ>!*bKR&Zk6EwG7GX_;j-@x)RgSz3-c&b78#n$AI87DnEf>ADSJg+B4%beu+RplvybCQO*VOZ!+KYSgCNAXICir z=G(?hz)Z4ESif*P-n6Pqj6R#n*Wr)LV$_4BHLyoLk-+{lU(ONWvZmVFxCjQiYFci7NK7WN4<6nM>Kt`0{b)_8=$>jK)0R3 zXA*Q*tti%+Wm#Q0b?fG3(Rtq>ju1 z!NrBGB>hd@*>d7r;PlVqU#I(!Vl-Ey^!-djp@>IG`2AsG$BGAef(o~AeU9=BH8`n> z73X4=7!&ac`J0sxri~inaVNgsh_e$(l&zEGi(A+B6j!Mu z9#c1#qNw*yBOY2iDmUUo9`lC-N-n|=$$L1nwdP?^@Bt7Q5D!imtg*^Zl);yjRC%}d z-B@Y=eI5a%5Ae^P8ohemnKbyOK-z1_@`^~T=_8dmnAPq)ixk{S&AiN0R1xYg%?_>xX}^-(fQqH z@JVKe82)rnhVCfEVx$nx^;7NALrF?9dS@PN?XoM_Xx`q_P1$Jq3*zawca|q6<4$=^ z@S>dQ^s@#fL4sFtJn%`JaFAcB=OkiIQ)ZLyz`)s0qhLfv41X8=nbWdzLXOqKm2JhuwY4>W6%Cf0$#o+>2YpThA!`Pu3JKS ze|oSRJnD#ty{u6@FDXgO%_ky;xeXg8?=1lNUqT+o#=jp%(jkvPi1V^?Fe%eR5^@zJ z42I+~845XqM+^USAyePOiWu70HH&O>*2VL9F3v zB@Y3wny7m3A{os!UiIFv>TbXu}QCoZQz_IpdpkXcTN8@Vt$zz=VE}AMS zBa$~mE7U{=iHi-ry}ANcc%L7xErd%KOx%|Z&$m~Hni2s#I}RJneTUndgygAnMBzZi zV~XWX-o}JofUR%&nsG)rEajmRixVM7Ksu-O^3cp*1r+>ZJeRIIa=~_HEj%>#5LXZRG=eW4CJks z&~V-wk0Aw_%&~T=-os_MD#+fM4sibL;Bd~VN*N!zEjqZ9l$)EGvY;;)?9(lh{YfQfq zO-|lHx*=w$J6HDLaJgAL5Z&*eVQ)2Lh}C=4`JFw7s8nP&0F##9G?`G!Os9?Ep~p^l z+4g({yb|APD67OCJh2&9{}JeSj0Qbkq~7MBjY^lcvoan@)tx-@Vbl9_BY(uITEvL6 zajw5t1zjG(dhV2aa3eI~trLun%?MZtl%$_(gY%~y6UkTb^j_Vu++k6vIYZs%g2W=~ zI9JeXjkkR%Hn>D|)S3krvFJvPavCx&ifx1 zQ=UBcJJ!GWlYeWSxj@zO7S@1`A0_m~&=ra<^u6Usc>wh9Q0X?R^J3WfNL_i@g#u^# zT3C|!s!;{WlV{XlXy$%HT8>vy9q})Hbb|B|bGh!Yjj!$d9OCYjF-+|VrZB`t(A34Y z_b6JHZ3iE#*goGV5+Y-Lji09}&`qwc4@6PR0Kv()i`Qt{NjjoY*N-*mJV={YcnJ*` zw5@%n=9D8SmhVv)yF^xQon-IMiK6HHc(M>kAXfE!qnr6@U}De{HfvWFN}W~6x3@CN z!hrjQTYItVuIj5FimP9T&AK|{Y`Nzj^u#_=5u>;q^maE~J&;})ze*K1#~+v9n`-8} z4`MI=FK!r&q3Y>{6tV*wdTW*9OZG;22JmL4uuOs#wPx=5 z{7$~|6I&KLkAvSr@Hn@ylY-uI4``cUkp6_4by_7&ETO`Y9|)Zo;scHdNmiC*0)p`h zu0o`ktElmbV7P%vM+~`w$+ws}{af=KC2UPsMK|ZX={I+wniL(m6}8l%#N$Wj?2Q3_ zjuqt>g?rG+p$*27M?~-*)x6qk^85|WdcnbcZ!kY!%X9kd2JLhYSLS>{5Ps{w3;c!> zT;OG`U=t}uT=WMqv)6)UqM4d+dkgL6qR(-1pVP@$ZP!2qt^?L8;3?AiyVe2B5Ggm^WK4tBY$Mc=<#RPQ5 zecV-MP=p{u&0Fd0Edn}mi;+OwBep&6t=glh1&XG;3r`Si(ijHl3CEopUwviWzKP&5 z`axB(iym@*gtq4^>o=D^*`6B6+oS&X12C~m@k#p4n~fd*$JYf8i z515?%e))s3xr&tYktWr#Dm$&*2hhu)erizqBwM31wwSh-H7ba0aX`$V*(NjgSoPL; z*_lN$&zDudFVj@(&H$5Yr;0Y^9XXb_tcRE$&GzFE;rvwj-JR0egtsmCbj9C!M$iCA zY@K|W^!|9LFI-bpUm&NHE;4@vUwhF~R+~>0UPm~t{cUw>)Ef5q9U>`-uJ%BMa*2b# zdQg?d3Ms)SKlgvSiG;>q)PF%Vkm|11XF<+TI}HEQWvvztkfdXM?!zqIjr~mwB(c^=Km4pvw{xeqaj-CA_ zQ9GytEQ~;U&!i?3a&FHcRW$5qmZL@T!=WD7#Y~>g0h+BT3{z{Pl(&lkSySLIQxJ_V zASmjrJrW}7DpA^a5fzo&7nH_Zh6N>7Qw4)*C5H*)N;{lOHq}6sQ-*s4Dv< zT7K8sNbMUn;L+J;@Yv+z2P-qF963AVbYGWI;H*MFz6hgTib}x2a-H#uzxE7^8KJhX zc+SC;RI7c#)3xT*eO2P8DnWpN$X2}G@OzaJdvlh0!zUF)$j4iM7_~Oj*ckuJDL1{} z;|0y46Cc~Cn88U5*m-yoKNJW92dn>6&6K{&loNX))YVhd7H6{&w59qk3*q-f64nN?%xz>8#*}9zKM=YB z7VbA+I~|$Z$WqgG$ax`8LN=;~hh&Ypqw`_vru$>^BS~4;58~8u{(c8Q7KU039dBLB zO5KiKazBGG>RJpq#2~#BK(y4@Rez_jcKZ&I4~x_yS-f#nga&!4oSdg#EXZpPbMS1g*uw6Y|2 zj?j`v1-Y>CrG!B2mfpVPtwk=P+VT9Iheo19Xk8dQi!vor+y8xP&}dA9OtExzZtsl0 zNX{mJOqK9y052(GV!PT7SYWhgP_cvzobH2vq{i;=#z>J;k*aD0Mbgp6NS`Q(?Jpb} zdEvE#PE|#{uh?=@bj>sdr|PsIzSTW|Bv`v2t{M|PTSb~ikU&n}h2%^9_njYuTg-Xjw32`4 zC6t`DpVLks6a@OJJYiYr^*VR65+{-M{En;ri`ui#Ne^+VRNkEc)4z-3E%^T9+aj(2 zqMHO#75XgQcND+8fh?^MRa2=`Wjpm;NbSiH#jkS$aWtxC9mZ4n^*|D3z>l-${TkI+ z)L#2EvLKrUelv3U%^8?Y+i7L`)Tc(PNmAh`3NMkL_{jU#?eqM2XwXwhJj?`cj@_-v z4?l0e1v^eVr`U;KW+^5|Mf}`GZfglHB_N5MGWq28-_PRZN%cP z7JBJVEWTP>Y%N9W&;Z&KQv#E&Hu+uOTIr4U;I^NsZp-m+LG3>DOo*jjtvGXgxt8s3 zrOkwuO&0boDPo;MIgG5dNl1Kw>LG_5^hxqOgouGd(1w0P*Vwj(|vT0|7uj8XxxE*Mk)ij6uf%z#o&J z>TTYSl(hYplG*nIR87Xuyv@h_!cTKn92lrjMF)LnYw|fBGoN}o zQ+$+By9w@}K)w5seX!3$m{4sf&5$q^&b##~BurK3Krm1*gOUbZq&B$r-w0v&EEt>& zdfo$SbGr?>XITXL4KeVlgyY}D!5x)w_%CR<^~tBz!SzDEof^O6cN4?46r7sWOS%2K zlsG5k=m@NhO`eoz9>3owVEOmgDM9j>H}5LS9_*;yCRcnqht2=y7rslR8kPJ|S5co2 z#Sm(v5H;y_E%|@43kxra8H|_kce2;b)d`AkY5iHj=5B#r)f2CaW5L>SgF>}39270b z_Z0WX>RH(u;}4&I)njof8dfH{f(`cL{thf8cs@iEGVAYLL1!}!map{}GJHwk;2Aj# z=px9A9ypaapY1QPmnCFtMZZ1iR~EQ>tDHjP)vHPZWAp)8=dvLC6NvdwF>yj~&Wmo= zgUHx+2Oi;uMevlfo$6QFCU^T4VyM8Wt<%hE`xkNx&d-grzT?x@eor9*k<)=@cOar2 zZ_A4P?`r~a|2jXXnZJdmj+N1e>IT83s$m z3D!XWWL8WC8E0SvSlhGM)mzweaYqH=>{cW4fFd4Z|f8b&xK3Ou$<18~FYoW#N29wYx(;#0?o ztN`a9zBqmRPbv|Oz~ora8delqwCr2*Grdw_bv=yt8Vx0{;S9D##;PGDs zqa|hHcZSAO3bGS3-Cv$+qHCRkEjiVd6{{7zH&0~#g_d}n%jk;paMjrYgV!|>cetYl zFIx;}QQhCysp4V_MCArFyBde0UdL+S+e)CnZBlk11_Tq6g{Mc7A=B$RZzG&3U#CEyz2{ctmL^j9m!K6|&M12EJZS zA(^`>%SJJP>6$2{sChQQ-nMdzgx8aJwz=Z$oDUESO<8pTY)jGC$U5B54rgTzAWtq= zyWJ1{JwIGb{>#=KO0WU@b$%VO>}V1#VS9CZoI|VMBcGpgpf}*ufV~rwSH(W%-lw~B zwlSpZDF9b69?}lNfG~lm!NkV(9K*K-;UDcIQg>j1+Fe z=3E}po@9{`7CyBRkBVZgEVfY%M4tU-Njt5X8gIK;GNWgYx8XF+Ly5gOD?==f84WG?u3`%;B{k%UIIhl$$6c9!C`1@=?`y%G zVnj%8r~VDRel62T<$kigrMcl|Rgwh`r#E=kGhr11OzdkdnAWmjT>j&6&YxQ}=1Fsq zM`1Ubp}D&GF$MZEzVVrF)j~bAU#0eWgN;G9gf*Ft0}*(?4+>Q`561GAbWCQ1-i^-c zj>J4rnj$6OhK3Bu6%AWCk!fX~ymk(>6$v>9(fWnES;$GV`>v)5Lrgx8o-k;QzH)E5 zM_}K8u|Tls_R46o#3Y!%UnX4YU7Y)Ec?&SDRH^U}yUVuookF?X_3~LmDUOW|$t%?7 zi{D&22oVHjGHDPT00Wx0hi-9s7N@c9u4~Mh`(+lax0l}1JTgL@fvN1IjWxkqgZ3X> zhv$la5A9_cyd3R)Y9QypXs?!i{SfYx4_wop)G%y=*W(P%<)(PP z42G`&rovbz16%F70a!&?UeTt2x4hCnEN9kK5AedgK{e%U+au^O`7id}6O%2^rSDR~ ztnC>RU@O&jdzhityDD0>Y_21pvu?xBQ8ku?u1;;u-7@jhM?aOh2cYXGV9sY$aRhHm zZWw%ToQ*E#9aLLh23(5AF=;Gh`YynffRD=w&EnB@XH|yR)%g+6MT!1VN}g?s-@Ep% zXXunbf_a;G;Pu0rkf85qhk-{^wNBmI8j^ckRWm7j&n+V8#Xjp6fbTx^etuhMPjDl*^M4(r^{uEn8x6tjKY&c!KL95v#tss4t*J`1`eyBG* z(0Q-8=SNSf*D@1xovNV*L$n34wiPco@M3o6wF_p9C1@J@`I_oQ%#2j($~m19FaO(~NB(%k&Y@0{dNVZVy@RcTV7Yvs0zp=c zRff;uAK8IagM|pMrs+~M`4KDyu>-%>qLI>K%MFX~#8!3;z6oTY!w}Z1{0x&J$ga?Z z-=RRThkCfHa5l6h=UMRBg(VYlo|mLEh;dlqXpxq`;jwB}c9Fy>IhV{DK3^w~XVXE3 zK$h1{FOLegXj@1CY7KBX7pHr_H3vmt7sm$`7u$R8_Z&-PXqGjOpIG!c6aK3tLtepr zYa5N?*Q!(8*V%=*6gC7!e-kqu939o<6Qrej?tkhQJOG1K(`Ml(8x_Q2O1CUDS|D!? zt5|J^IEq3^tTNE6EX}-k{TbB96bcb3e1{qx+6Y(}XpKkkIqw3BfyD`ch{+qV43q-v zA&qT%d3P(lpPF(&&nYhRdQ!wD2w*xs&Oe`U%QHwt~QpD z!n`C;m;08N;>gkUu4ve^bTT-ngwS^tl-ub-W}*1%bxoiUR0yTyo~&D^#VX{RYfgJ$ z?|pd%tVgT|qat(IZuOz(w>5*q=DH8-#`Ozxyc~P1%(U7(oci*6Pi38EHb;tpH(cZh z$TzdPfqn&BwSY<3;?(-{=;Lg)^UQdm*)wr~d->&~lf*vNuGmoYq&gMce+k%F2m*Vb z+-|0HBSZMX&k)j1F<@xnDlB%zVEQ6-VJtJ&6DZ; z`u`ze1dIvNFj1327F(dn-Ip++Df4Luy&Tg;Vw1tl^CbTFkl!3?EqI7K)66P_9{LqXdQ@DWVNVOItI zEC#-F=8=emL+Q5(>$2P@9P9Q^y)REcdmN5UYs`UZj91|gdrkwGb-(|3fu3a-VKy`0 z0o^sKh`}yl`Q_Nc0ID67WSf36Q*%Q{s@%sM2^39uYuB2-C_iU~IN5&s!3A*;5lAAM z0582PJ|Vabhp!9bB!@(~gVP}7M$#3Lw&=ov_PVY)nfCa)@pos{&$h^*e)0{Rn*Oor zOZOOEk0fitdZO3uBEW;i<@0)Ee}mTrM?1=Dh(jpxQ&H*$#5Lx2F@~=kRk2pzzf$%A zq%zN~1$Xb(MNLAnq*;ri8d>esQgD0xZ+olq?PSbEz5Ua4x@m!m~8wB8ck<= zg6Yxx#5jvnVbpSpw6a3b7!~z!({(+de)d~&LBlPPA~(t4cPk!B=*iMf8_PuZ{H0dq z&FI|DzUAURdl7&6m_BQf759DNCuE+(17EUc3M(~UgFThDujmsM#;M#bj?=uK&-gsU zn^0pi=5_xuIAFp(;+|+KxCi*@|6>0l<)fNBWh_i=IhCdxjL}5BE9K6r(O)jNM7)&t zyRWuUJH4msB7sV!DK_8xw3Rpy&35{lEBnn0^geTLRd)s?yNJ0FUF$nqfBnt!PUu%a zviVbEJxfyORmqm{nAfA4=K)*pJKosmP4KG9z!@7^3HNt#*Kb7OXf%>T8%D+LpK2Gs zy-~Iq%G=Pvkr7%G2X_X>9k*!(*uJ}0=sdg?~QQisndzvgY?|uf| z?yLp>k>}wJ5;+4q5)|PdcXx0SwOIMyPuB(TsIO{9T-5^oLkYEFs0j?Yh=ymjSr!m? zI+U7xB)5OtG+@?mQKl9zoJSdU0hs`N*uQ*XHOgs=`aIvsh7@TE7YP!#o_Yg6W4PI4 zDAbsK%dUu?F}gKzZ=mA&Dqey2=X0dk$lk_$koSXi!HR_g2Mu#E^jXbAC?J-_Q{O=p zT_XR!m2{CT*s@CQUqR}QT)9Lg>xpfYWZ?Ne@d=rTwGCy*pRBOfYUy2_zb0?mI2|mL zTVW^mn$C&?sO^KbM*tZ=9Ab~K;fXPY!)MttqX2`nQzOq?FW^RhEk;r|R5Ntk8vmwr zNt=XC8o_sXJP_aq6NZ{5LV0Em(9PQzkPVe-j<~)L+c|Jp8mA-^`mI~}kbR=4%{MRF zB=(}%L5uXqYn{(O*Ufb^H=AjzEKpM`o;Htd{Fl&CTmhf0?~{F?Mab`BxAB<4GQd`~ zIp;Z}Mh;T|1)>`x_2(QA7!Sz0#*B3{4eH%H-H+!pg#r8c8*L`?E`lZQox+)PNX{iN zaTG##Fx{4K{GHPuI5db}pDrxRN}NY}WbZA3{C%94JIN85luFcF*`Ekn0IeJ~J%W82 zDF)FeBClJ3R%n0)f6znnmA)Vu;_+;%)38o+E-2=GpJPKmUFU>?ZVnsAQ4n6Re9Yf| zWm)Iipf!54WO&^w*4`_{Flicd5djtr*7&sA{+d( z>=3kY{tVazEyo@KzLHD7y1yd!hkDm;6RVrNqGXovAXq&^sjJ3K1uB&f8_|4*W0UOQ z-C{s8*o)2k=+oWCG&UbSH~`COGLt@DX(XMfnOP2qZa^1Zvq4`oQ;H!{3~&85ouRzKw8VIt6f|qVVa-jL*zy z$%<`!?HeV~&zX7c`VQw2RE4CVNBMEJM$WHhE|-Ne!LqIGr)Ya;ldlam7a5O;y$TlW zFn~g!5ms(i{z9LC|FwXXeR zB)k-@Hd(T9!K>GHV>?w_<9_Vt_PneU4QBf~V(P9QG#*PTV3QO>1&ZW2OOaBf>z6qW=%dvY_PBo=q75U%m`Ywm*>9 zc+v&=2ji!a_nX(>HVylYyA!VTYHQOmi@iOU(oH02npll4IGJVniIEhFx8a`LaK5edL^J#rq`JQ;o4CiH|s!9KaM%&eQzp@S)yIx&&e z(bcc0og0F$UJY{(=mW3=j4=`Mn=9$vof3vrx2dZ5F@D>>&T+3tH+N{NOt3BkG7HoH z9Vw1oAZx8z>jqQNUstE=JzAWFmAse7Ua#V$#@;3+1LFOZL|nzx)C3~Mh>E&z-9KJ^ zjasoWm%SyXes`61gUwC9GVS1KMrzzyUxs@pp-@oo)-ipt6eg+ji*M2Ea#7~yk#_Aj zKv^zgT-K14ujS>@EaK*U><8;|r$;}40fO=z+KBwQc3(Lgp-U|=q|79vR*)0Jq^9D> zsPMBA3@Vj5ZD^YCLlTDz^iZbH6L6IVNLA3EOqJqve54_EuV1iY4A|K`E+j5gCOAQ( zlLEJOGt>HBvyc`503(y5qEvt8E*SF4ObjUmOl&xc;0oqE#0T6De)^o+xzZvrG zF^dbJa{a>=92%06Wnf@O?v-kJuA$JEMQ=)bP$cc6n|YuLsY4s>ZYvAGb4YL2CI>m@T03JsK3uQppLw`3-M0ZZH2@FH+- zZ{3|VpVVb9@6VH&(lbX@yn>T~)gI5=9EPACd(6hXr>2uB$+sBI-y`xxi~wUDU5~+i zc>MJnsKWkxfWc^l!UHQ{VY6}_&AUkKb1L=tzDEQ1A(}n{3xmR}=WHh`3v|H5LXK9E z!TuLP&X4y<%>;Ph^$AaGCoPC1E_WBt$7|E+b*)-8ck+DBvwZApRC>iuCO-$OK}}W# zHBxk^hM@1sYH3A&w2bl`ZXYQZ`7cCBOoIYXxUE;}{V`Bge_mPF%Ga;?`x+3;`PwBd zHhF-QSgu|O=f}b$ax6G#pszwloNqv;^9|blKZFy8FD+@dBJ92S)gv^DCwsV_SCjw> zJ1yZ_U_w;$!$J4^Ih548jO`;D(%s379w^4T&AmF)=rb(kz8r6^U#hP0cQ6~2mI`g> zx<%~j8stXS1|I*KNJ~(x#vF$@G~km*BD@j6O2>Lz$pL?2(PbI9PuQ8<*@||4v2Y}4 zpsurjz|P>g>w7n}Xv=oGZfw-jdvf$eMHJz^X97jBQJ%+A_rMJ_dXH8+*!ZZJpx&c2 zw*fL(1F*M?5%&s4Yf4ftqPKS&Q!VeRa8RpdC0K3mz>tq|z;noRcMJvUu$1Wm(!s;GJ%S-MDUExC)1af3fJJGl+)}N; zu&%>N@n0)rrHVi_usV%B0i8a%GVG?{y;pZd3+ORBUvTdOWtvOD>Uw65+lqN#%9ieC z#T_TXqcOyQQ0?2_v;*Iz@JzDq*cV(pVTxXxtSR#leLpRlF1)2dK4|S}37&F5sQF)f zdgA*W>s)m`sIcVn$(rHgZq(zd8N2p-IAgK%yMBI(U%Jp=KN@0|dK^I}jp3U{@iH|| z=n7_&r~a7V9?YKR^(<^`Oz%gjmIl=+|>36dCBG__r#KnGUuT zq3085&0Z?nTWkNb!EUP8NT{kDM zAtX7f&uMH#e+!JjrqlowBh3A6PWChyU0T{cAO^QxIT8}%c;x2*P^-UW)gbvs6)04q zJY&fEJ-d&8PF#%<_Gt`X;DEO&KkNZ$@2fZH^MZ{HR@baa`{Uk@x(U9zar3eEZ}|nL z!qp(=`!~cT{gm#BvJc$0!HmRj_Y~b7IEbXj`A+EuYbS|21J5Nn`GuA_iN+P% z7&woa-5UCrZDP1!1oc-zNbq6ppcb#|mgg%Z1{Hvyt0xt>c5^JuD1n_1LM}T(jb{o~ z1_!*s6bc89U}Z$D26}}%+61X3w*+ubA+M2i4yMu81YVWHr^Qtdd_*X;oAY= zkoynK{J~kshV8c7?AEO73Y&G2r%TH}S+M&MgSr6=`Vv_c5~_hg%OPJv8jl{jwvqps zh3&R6T+po<1JD^|YzTV!R>>LfWaKCvO(*uZwcyM}OS$mOHx8!NmIHq`$Ojf?%?-pc zy>fm_8NME-BS0U%Z4gkGuAvUz_|XVN?bw86$Yi9I_c_2l`b7b7{&qNDCllneWgz2G zy4EI6=>=9C3P6rDl?HC*DB8-Qc}QbBuP`P3btll0+r}JmfnPLFx;wSi%?)l4X1&7k zKjj#@LKw)^;1n{E&D6>TqN%qaIb;F>)%HPQzui`RWw-smmoZNcge<)yf$7hY7T9U0 ze5d_V#POI|xa6LSpgI*y7IAqZ;<7CO@{a(J*(#3Vav!qOiNcVZ*ywi*{yl?HCaEB5 z5r%q?FhSFoQo(;i-T9L2yVz|@*7JhN{^{M2b>NM6UmPuMl8jpWjuWmr?Ve-iF=TSA z!7XW|cC=6Nd`rpMR&Hj7Zmoi^Y2z@cB10=p&-mcH74Cf7-UZ3K}OqjS-a?U=cN`U`Rgs zrEP3yw8Wq5M3Q_vuD&TN)!Rz5$iOCAK+y*n#U-eG$&Tt%H!6HHn+mSi!0QyzF)p3b zU*KIrUO8=TPgE8CAtZ~>^e24BypLKM#99Hu!dEoQ>G8q>(JwPVXV?1_|67ji*L`d@ zLqr#Pudr?P9IjBnDj>rh%KR)sB>oTGhz2j-gG9FP?IkRNEoT5*00uKhMW}<-@rpd_ z4B`~^n(&g_DfdtAyrk+^jyCI#&ER#8Ah^8>@~k93pji*Vj7yO14si2$+$VmKpLiou z{`@vKR~8)&v>&}xvMxj5t$0506TkUD^<*HJ0cQgpc(z;2L3r^Ct@%$`mI+Rz*?Eh- zE?}!+#nx5;_vr!hYgNSp{W7DhqzA+#FUeK`kmd#^YNq}IO-K#TD5qATfK?6e1EgV{ zYsuPJS(XYiTZa*?7kS*t`92VG6-Yo;>*csP`UeifPqbm)>Sy-QR^&cZ!8xSYDw^nt z=ZE(ZRvhPLsRBB0GU>oP*(tWD4MY$S1#tlQs?`+Q!_KVS1^M4}ko5uV&HRSu?Uo$7 zoKn`Kzb;}zEFsY4^^u|-ziMD~Fj*kB_(iG*kHPbc3#@3G7bry8|Dbu3+Ffhhk47}l z9JA4K6g~B+#n|R83j4;S_I|2)7#w|mfEWtM7tIHZ??Lbfzcr~Ti7n|u1RKQF(DmNh zpY&jBr$K6iumdr0{qodLrnWU?`}TBFyju0Ca6H9q@35Jn^Y+=nN+KG>QXAIa`KRGL z2NMSIi99wy^2@_C@vmjf>BL#=$bJQ{3_};5%0%dBu*+djgddGW)FOKU+l8|UeEWjX zC8yaCBXWUJ6ZLgZe>6uOP&PRUZ*(Y0M6DKg1evP_I+#JzH} zv^}T|5ttCis%A-v zxmi%=oUhlP6kF58qa!aWz(-acB=vJ>z!gvJNJr6$L0N7+ONFjuxaZsW1ZA$GHFzv% zwp%*dAS28!$E5#dq@T}DX)Dp6Z(gxG_wn@~Ayjchs^F$1f&F@yep5`DBSAjXd;XU2 zmDHf(!oSf)!>JldgvnVt!?G*kyl_*gkIy5T8M#5TH(<1AR4u7^?ba#t;V}8gi%X8fJjq1>Gt)Q*G^mz7dgfiXJ5<^6*i%CJQhQ z17IlR2veF^ys{*1MB&SQ4Qi%MQ+B*#1HbA6K^+qY@W+PUTDX7k|I1-cBt~GIw`(|B zOhm9E8^?M`Hqbm2g2Em?LMI4grqLv7+v?B6TL7 zXLn5Pj!-3Kn`B?R`>v3fT2mJrJcbwrpk%8(kIoJqNIBxa@e2Z?#%~iCmG+yziKvsk zsw#ew=j|#&g?XInMGmx-@j72)uwf##U|0beQ9zJvk}OUT<^*Of<={B`A4LRiGnkw0 z3oX+Z#`Va3qj1wU9VS1&TZs z>h*OcoisgJ1Afx5X?ulop8L3EQ_l4ZErnfRQe(j_R4M6!qaLyh6VHeM6H}YUd>vZz z=+n6w{&Mm*CVO2GPFv{c!qDSho;5m~6glIFF7Ih)l4Ad$%tWg`M_!@I_Za z2>Vm^bHZ+|P{c%Nhx)eVn2|+rPgUX_rbbJb=rF;6|^v3VQZD<5)z}{t665 zEQq^yhNas45Y`2f2_k`96#+$Ms?#h=>F2~tCEpv~r0b@e)s1CB*t#!;`BwPv<4Y*7 z+WdLL_8?r1_vQV%(#r#5E`pokXW^wQ4wFdwkv$|1s%NyA`{jd$V~8Wx<)-7HNRIt` zJXMMCYr;Jt#H+3i|EYrJ3Du!$!OIaeRT%MyLv$ohKRiIq;l%U`#W@)fwA&6;jY}aB zG(6u8%ylKOW?VWZ+(tXitwj^|bPMfn2%F;!#wbYgEw4h71{^M4uST3TI$VEm%yaB= zFnw-wbrBrNqR(xMlj=)Y|859O>D((-XqN8>3r~;#r!(xISnCGkR07jOf)9IiSHv(A@=4;9M7}15W7`NAOm!;s@h$N~qv~^w_k*+P2qsAO&+;(IN|&2zlZlsk zh80JSErg%9-<=P|*ISCAErIM)l;x&3p>F+cMp(hiAMh=Jx$#U)qT`qT#&oXV{ifKBsgA>MfcTfh}lY||*! zlwqO1U72}liXx!vy9lI>Jzl1b?MvVaX#*_R0cZv%J~RVRfMkX9p}l5Vmj1Zm=S}Ss zfb>5{VnP?)${}>Z-`f|{5;fC?Z?}e;f_SLMM;e_5kHT5l`DJu$8Io^@O}8_r_CIm` zmuE=n6wT3}h8IB+3lnAh8|Eq3lS6=wl(c2%{K8wz;PnCOoM`TA!T>h+jAKV(^Fgz` zT6C$I+e+v{p#+on75A(_X(WPS!<>Ah?nawOU1`6&uq}S6eX>c$(_cZi1=#N^I5frppA zy;&0b*n=*s(42SNg*iVg77znBUs52n45T~MPIK#frq9xhPb6xj;UGU%6(U+B+vXMI zl1VpBYj&nxaR7=GlVYIDldcTbgZ8G^`R&d@1&~N;@b;PdAK2I>d zx@8=X`E=-xT2n!m7zi40>6Z)q`6l@LEP7>byBE$G+`3RE7q#vp#o>@Bz%e z8;KWUqO&jaGp4@5Mk*t&F~lnrtAC846_xriOXLRZk+@&)2={W|BE;cpk01r+=qS@3(JGY(t_o)7o6o!oeDV>eQ6D_0HF>AME6*(XFZ z&Bchca}D+{ejV=(DeOsAg$qnMCz!(ua`a`#d?t1I52?@>G$r zqC0c1a--RN+dyY#Y#~k~o?7L>SlpjGpQb~=O9s~t*GwPoNgBAhhR~KE()^Lb$3kW3 zfl`S{{Hc)k6bQpcf`Jua6lDDl+JDtSV6AsLVQ8|No*_FuA$R0fZhvZ$+e_$ooT@qn zr4U>Ux;_`*KQbVbLtdD}5HGTX6@64n10sbf&Lc#!6#5FSUavr6ZbPu=@LO6WU)e&d zlZ777C*)!7nFbG2b+Q&qHtHWH&ktXRdY)F0739dUv=BYXGwU@9eKWy05DxYb-l6Z> z7!T1l=E6*uTkmI3efD&uWb7>a8{+T-jAVy*C-{$D+q8MtgY0Oo73{dJ5e4?2lWmRy z63SD)!1PPZjXZ1}h=>Bas9TmGJg5wT52w>9LIm|a$C~0)?AsX9l?Hyr;Llm7{AyK$ zDol}~UPs|@zD?sxRVZA7+ukP*co@g?O-SLg9mB}NYMgjE{`7riYJj=i#JRM5DAx%F5p@P8e=H^FSDQCf7f^w?dQ)MRS10={caMg{&65bv($agT0 zuXI<7GarjmaqP6CNa}t98&&x}RE)bx44qeth%(KA%4;2%L4t=S5N2z^lYOzvqz&2wCU= z|Go|khC1kXQ3nmY3{ohjeBKQ9l0%B2U9jMekLAs65$m{c6j^ZA4aS|m+GjZoBuU?Q zoskJ|wq-*O39YnttnvmA@i&mHUHf3~iT1dJ3o6EeR{a&hCO}VHUJFVQ{C`2|%P0we zp@cG^0!`1opsF}VyQH}%K1pge>8&$TY(|cZK}yO|8>cKL8yg?#td^$XEG+FgOpSLn z&lu~S&6 zkQ-k%+MH^9*t00Zqe(}lprCci9go8nJi)4?#XMe>WhwvXr#ubz=#xac&WMFHma-)5q5EBy|XDskl z4o~*IQL!~Q7J-HiB3Qh3KYIr7g@Gbo?gcSAJVe{D19vh$k9=|OEGGS><#Aff>30%X zPC5`>J&|8=eD#R2`BK5M%MdZn3xvI91m5PDgX8^kAAPVn_4>$*-mO@#uVZOMBJ_VQ zCF3Ff7&o<}7IlJRf<@17{^p+#0w01!dP1o3zkZB^ohLZi+JIe`g1jMtQ+sJ~K_|~) zwtT}<_iy~QARv8tMQ~XaCT_v*HQHHHmwC0K7TO?*rqz3|%{3g>+sY5GvMQjf$5RVb zg+#)>_s7@vhV`4|J~(LMvG2C59OGph1vX0$65LKF|CP6PJeGg^<1D0F?z6eY%2EC< zEvz8(#xHud*>d0Kf|Li0VF|e;_j#xt-=DlPHGu>W7z))6sFMFRhVS|-tZm-)ts~MJ46lRgntoeXZL7+ET|2L#1vo0<8y6*{$CYi^o9gA+;OFc~ LU9I%vSN#41X$q{) literal 0 HcmV?d00001 diff --git a/docs/modules/mapping/point_cloud_sampling/voxel_point_sampling.png b/docs/modules/mapping/point_cloud_sampling/voxel_point_sampling.png new file mode 100644 index 0000000000000000000000000000000000000000..fe1d171f7cd192e4dbf129567c236974b1bf6e89 GIT binary patch literal 250443 zcmeFYbyQSe|29lIgwoOtl9EadFn}N--60@|fJk?DN_Qg&NJ=OmT?2@8he}9y3k>~k z^n3q)_wRn5_s@5|>sjlWHNzavoU_l_dw=%c*XO#f^HxPk<{lO~77`NDJvmt^H6$cd z82FH5+yQ%JP7)AENLZy7l9DQNl9IG44z^|%R;EZuvTu`8AS&t`#C|uPW0Ftg!~7D5 zGibAr)SkRXPBgR*ViaegLqiFp($)9B|5OUi>Q_lvfF<%Pjxd%lPsLR~Vt-~~*?K9V zp)rRZ@@qHabgt=<hYBPR_xceA`n>hJH9xdv zWa??8wuOSXsmRDaNO8Isu4i_*;_4^S8yaQ4zBezP`gbcYp&+5tQg+BMF)?_NkEH0w z2~r`A`*c<$q;aM%@&^^a%$ErAEEKc}ktq-~OCK?UGBJh)bKgf2dE0^CjVzwa;Nx*e z0H;{e;pw#gH$n`2V!G|j%uKi>0u3G_dv}pRal*XQOPhJumd_-gPbgE6b!gjEZ+|!7 zu_}T2#Em=U&GYyK#wyEohG*doI3h@%CLlj`^iaT!Xei;Gw;^Nqb!g9#Lh85kE74q!p%qW3h@dflqs3}iz zUNX$ZWH3ejo?pVz^73-MQ1%`zQlT_5EiCPbjNY8_=e@QXf^w-$o~4Wyc~WsS2R|$g zzdOUoA#FrDD9?Xk==($Vk*{gdqyp~yVJ}MXj=D4Hpz;TZs33ju&&r|PMxFSDA&8?C zAZ>@EkD}eKIE?Ah#xM-I)6UL~1@pti2(ZH=%N1vfWy*)7i6`TsI)sSOim_mX2j#vO zl*N$C;TvWuLShT)eUGYg?>Dv+aRZt`XhRM}MeOn2=3rO{ODdYWv9k`1A;u#krfuxd zw!Q^H!TWw_Z90PyMZs-O<4TmB}P>ASk#G7yPllo<*IyQ;dw*F zMxz;C@?_$Dy6R4ma1m@AW0R0Pq9AAEwR$zf4+^UA)m-(Ft>NHxhu`>4s15hLA+s^m zPklRLdESr`Mxus9y>06>=H+ouRqLngC+okjfNO?#gdEW|T6srD_@e+nL580}6i4T7 z`=rV9N`qA9yU8~(!?3tI*M7+# z$Q+RD&mu?=m;oXZF~7w3nfEbDF`fnm2ARRF;k3p9MdFWXq4<(vn4M9byf3K^unu?* zvLYiRzeF}G_1uCTVW2Ra1Uh!tjhBKNFL{vvI(pf*CVycOyj-89^dFB0?T_`+L zY3^A$-3unM2fm3PzNPnkHg*5JWy=1F;#H&Ri$472-^-~E?8~25o~p;6Ca(P2TbGqMx0QEJwebLWStk8A%{S!P{j(_%N&qRh!*ff5l1 z%YT;=lC6J2mjAN&js`!Uzn-|L(oRk^8!MYGdoZght0qg9_GaGu*XNJNT&q;GbXJW*eM;q2jih)_tMwx+S7OX=LUx#C zq%Mc&quhwoB+={S*M{R>a@x6%HspTudQf<4$Sd|em(O(;FO{@>@>5(`Ls+KK@Zv3w zYUq2yQuW-il1C+_#f>_yQ8s0}lA;0Bl3a$iDTa-6buIorb=PKB(pPk-rl?;ezDSg{ zn@E0sA7NZ#oU~xT@Daa*W#n~?Y9Wu6l?kP-zOmO&H2zO~_^I1G8+v}aMy=v?Id9s% z)#F*m9(PnvR?kP8t(qsBOujzxc)trT3jRs*h3nGH#^l{ApW(~6;N0Mtr_oQVx}M9M z$d{W2uNbg@PAZ)6C}k=Ym}Hvt+G?I`<|oSN;?J#X43RZtJ!uK6%e~PN~Ly58wRmpqM zY3=pe)u1=09w%iATZ(x(v|MCLvYabbx*u(oXVp@`QQ*^0vReCOR7;N1E~=H?m3Mn{ z3-8zQH&u5J#?^m58myXh9Pj&TS)&~x@b%}EXXB~&7idObxpB<-^x4N_i=zi;cP^4I zU`LNm2ru}!LP#zi&V5205Hvr4KZv?+%id}2xRLXd5P#EF;XmEx*B0KkCP6G=8So>J zwVgdM=8i9hJvJ+rJJB0bHcab#3E0nxwFvpCcc~32=SV(rzqIZgke!f~c%@Fn$@Xwl zWqevK=7Vqw4ri5aa_#noJOCin7Poypi zru{4_U9(-@U5+bB`yppamoKj)bPA^zr{4<})=}Aa9B>|dIAB0Y&e7jzY8N(s0e8#w zU0mqw$=}aEf92)ibg272ms@o@IX5moY4iav{>s~PH7YgNg6MGXuF%n(>J;{XzAyUbb-Pz>nWo?I7dyUM_Hav@lH|e zK*}O?ry2~+y?4*s?-^1=TQS-w%pjgeyDQlbUMMbPq&rSH3M}JX{yLVlerNSgaPQiz zd*H%H>V^gJ$s}STdG>kB%F&@MQ7TCyu@~zy@f@OOvG8*?Q|(uq9hT1=KN{~fD%S1H zxuopKgx?RZih#I0oEuSj!qvm&-s-qAxb;_w|- zZTR`KnqH2iB~LfchSP@KvY&-56-M)GR{>YekS3hR8XMY4S|+8BO0sG03Qu1@T3Sn& zED6QJ@fLk3GULj)F8e&nKyg5|ChuvDU0J>hV*0a5R`+a-z(m?4RZ-ytNhT6ABeUT( z!Bt;#LJRYAWgex8tVv-5_YeoBR^&H26Wl*Y=clKLzK=Uku31@DnH;6P81NDGQrgn* za{qAjlq8JAflI-#zeRA8{ta0@k*h_Hv*}h|AAZW-7xXXA`UlMpJ0)uqeLMXp5mTAv zS&h4PSKIf#Mt#lrB0ypDeFl1zF<@&BwGt+``8jK|S-oeqt2gfa{^y5_QL0m6?Y+-? zbKAP3W6oT^4fn20PcJ;&nTJ^`HE%7 zRN;-o)z;+e&h=ju2N^xJ!Fw8WR6e#>EzS>(wl_kTaS4~sXf$EeXPt=gYoW`dh`0S* zbzG(|qFVTUkFHMKc-0laj-~T{o0gVZR+e|++Hcl&df$f^Wral<$u-EA zl4fRzz4PlrbalgGo4VfGX9c&?k4-A>& zzqX~3S&&fw>_3rKge=wjQgPcNec}fCmlrv zsEMsLr|~P>m!_O<)^@k$Ac?p^!KSsTlQFHEwUvz{)J>HB&k<0teY=~Bp7zfnPL`td zI*KZ^lC}<}wEUdhoZR#a=Jd^v~@7& z;t>)O;^OAz;^pN4M{qd0+c+7!ao9LA{4L~P@b^8k!4<|R*f0YeR6}jCDRk3h0wbGTcum)`gt^pGe zdMxti`2XdX|GwhCovHKRX9_;z{`WKg?U(;NQ`6DZLDJS5T+#{l-`(}k$^ZW2KPQTC z-PZiyTHs-(VZrRp7`gZ;LfLgngCjN&N&<88#_??D73uH`J1{+~bOV5%VYrD>4~{{3C~4kVH2DZ2#Xw|G#bl@madzJQ-X**Ij*s1!b`-jfJWmo9*dOZxH(n4e1wq zt*vl#C;>}yn?+$(0ky|E9o5c|?{yX2yw!8R9Wt>|m|d=%?Xg*mmAxVBhbBuakH+Hl zd0g*dX$_js`B-+zPn$-?DchgcwVLbIQ>EG!>*qdaD=8(8YlCk(LheCrbRY%mL5~Rh z;h}J5hT1oq;c^QJ4NS)VpfCbj@r48=4JJ91E`n5E)9@e8QwGhiE1C|&$@#5PPlYzy zX|DGn&U5Z-8^07Y_%*Y=Ptx8@e$*XbPs5d2P}f~hCvi8wmM2g{#>&Ry7EwfDG`f$B zMN^udkkrHLFM2X9=?$vTfR(Cr*oKNrWRTT-@liE!2b(zIzzT9%} zKq`;q@y1v;_RXj~S1~G%VB3X03C=Wrg%x{(tEoG4+H<0Xgjd%J8EBxgY!ZI(LW0CJ z2&NS6eizA$qH=@Ak|+v+&EXi)lT_$6Vu_*i(l)lVyy4lb+fvlIHT?lbs0AHp!Q^BkA=$PEcAfY#MI(7Kmc$Iwkt##5 z3oAy>=%u2aFFyyXUc0O$X_rvg)X}NwXP|syF#JBrxYv8A#4CW6&A7p9O+f2Ej%O#V za69l>>A2sFvvhk4uD7PAlbatbcEvqgC70Y^q`UsTF^0NSpC>*zq5Wd#F15(?#_;>V zstK*<7Btzu*GJjHN2>$ak)a97u(SLWNbkvNhHXelSMc%Hl<;oD1Fk{W){EJuh3-hQ zrA+5Z-N8ZOz3pn7*&i0umG77IiX3r-mhslg8+RQ*A14UFI2(u$nlAPG+|WDLu>BCD z#Io9yz3wyi-9n#M9U);~R* zT?W*ITQ66*vOdVC5G!Uc^*PRL9T&YT@{n6xy*nlVUbp1JUQ=jW8g_s<^!J#kH)Wn}nHu{rD7+*i}ge_s(N z-Xni(_oLb(Z%p)JyDF=8-beVM$DsREWR>fSIxWKEnw7p3 z;o3Qm(rd#S+j&FZiWw68L7}xwLPXY+#yPK}fporInsM`PDpx0;ld5c?a?`JwmjSTU zrj_%?y_T(-mC5I}Wv!C0`!Z}AdUQX%3`WB~4%}S9jXZxghe5Lp-<7Fe`qWLm@*H)iBQ9=&=U5DeZlb^P(Cv%>*S6S_@c=J!am=9)&NY<*vNAs0Y7-PLr z*e*1U?#Z@Mqu^n$N6M|i`Ru8R9m;voxCUeCBvF>?7{nX$I4vM&>ry!#RI9_tNp9V9VA)(zvB3dkbST0~rN8Z-!2G@s}hkvs4X4n}`(muXnfjG`3c zwH0#xVNs|u!fG0{r)2IlD0bsD`}TBd?D8(%;%?GQ=`v@^$&tsX=Ubmm`-nN5wx%j* z^k}O0KI&HWzxw?tEm?Q6a!D;1H)v`hl!jUl=Ie7h>-wVX^CH@= zBdEhD7v7xjjdwTI8I~dqy$?JHlVJAjwDqP8y`c5-kSt)(pkgf;7aCi+zffMkO3wV^ zIsE|W9(ESiz06j_IrOC*qJ=>7A2B|^^Hg9(sD`n1>fTYA0l3V{@3yU4uTI>@;C+N% z+Dl%diY& zX6d5*%l(m_egTIs?nkS7R32fo3^5|3LP!0NvTVJ#o_j2JD;x>5o+-Z0lE;Uwv&f&5 zTBF#8={W}BOkEsr6+TT*I|IEyIirkt^z)9$a?=LMW@m;)M)&;1+-VbU?nB}2%0S0{ zp6+#3iNyP-WvqhmAY5rOJepHtY0a69{D$&%S{m=)BQ?;``LjV+N{kL}bF84Piq^Sy z4BXM~Zv(0_R3BQ^Nk4SHW*c0>HEucIWbdwNTg%#;EX$xq_Gf96&0^K(Za}xETxB#s zl&cbP(Qw0E3Amn|%s49ViNK8$`)bI^lJiX_<)uGg`h!Zub8d#F@Ul=0)`#dg^q%h6 z`u@x|7+eFBQ>O{Xarf0*Pm+xVUDh=^7tn9ZL_suQmgZFi{Wdnx4gV>Nq^`9Lp@hvj ztUAWP&WlK>;YedP3a3-8*AtD=zh~+%Yoy&K*K`)n?#d_*FX=rn~pU^K1AEXI67U-XNCEimHVWcc*eNRZXytuuc3YXc8*mykz zg1_wJtg~)|2^bD;n2xnG4iVZUL9N@L``##y!HHy?-aQai=mYbfzEOM^7L5X35Jp>u z*!e+Z|YO+8pn}_T2c80{v-K z6=miL2A42iTY=~Cgf^Ay9tW2fY&TxatD0H*&DFeQ{?%6s+t+lQ3v@*Af~2(LaCrm< zjY9p!dR|Qb<{NuV2`+&dCDPn^JTIf5^GBET4!zzW}RN`*&UQ0OySd!_sV7)StL zxY5LlV_~KSAlY&q2|0aUfm}nx5E4o%PUYODa^*`=?$bZ5GP{4;VMauMYIS6KYvLUc z)X{)lWnx_5A3gb_#`1w)wC}9*l)Hu3&BZ+KfINK~RaNDNo4re?DswS|SJS7#+H%Z1 zeKR*F_$3bgAf-Xy)E6DDAe_8>AuoiTufw_HCpcu|{ZgIX0=(_F9l=VxmjMIC`-R12 zYqJ18gZNgA-X`UYxC@5z*$Xa>W_WMdQ9LsoB6Q>CQO5=Q~vA&{+XeBkyDO*Y2{FK54)Vy9ovED{NNa@Y|yk^s;V`lQiF z?o%PLLme?AXjO-wKu&PvgNHhmv}@MB!_PJIaV3JH>k{n&h8i*L%&-y)Rbrg;fCx1? zf6dShdRn-BG$e+LmF$Q^<=oWsloF$amc(3UhRcilLqTkZ6JN2|WCS9s2eS1Ji_EGm zEHWQ*vlJtC!n~16rKpgG<#63Vq$eE08WztbrIs3zP@4vcWS6}@D>zHDUla_P7H_E= zf=^bYp&*~y!2*e2zi?be9>Y2kiZqmKKC(~Y-Z!SriETtIMl?IkDn_FQW*mpBBZ8tR z<>|Q7nUC8w`e@C=^9Yp$=~!e3g&YSMMho_P+BUv2Hw6C`F~x1N*(Eqru7|kM}h} z9qHjkO49IQo_p!L#JBY(=FV0BCVKUI%Jo>+Ms2UsS>sv|&z%4Q@7a5X4?CNr zrSp!wPP49eSb66A<=io|Y2Yrk55l-&aQ!X`ub|P_0ap~uN9f; zaVRT|;a6Gj%1MrIJy5owK7k$8#h2BZqe03G46oJ`kZ#j3YFht90`4idAToSz;jR>Y z2f4CzN~d87LkN;3Rj#08^~SG2+(C-2$F0^bj}H~cBmzk7WB0jsY;LtKrc1W@JY7O1%&o28V)2Q*lNdibSCsV)0DG@CySlI@AgC1Rb-8gWO_o zyBjw7Hf_tGl7IDwWrZ_$R1eqgfSYl582GU1Pvxa}22qR|kK6V5TTxN#acI8s zVF`I@4}2-uXO)ValFQk>9Sg$N1Lu%MQm>D`n`f^?LE_B5vaTSGr(RSf$z)R5gMe#(Tds+88uXD+B5S{3 z)(MYFZHl%7#Y{(tKbU3m$r-42q37xDH6x0cj4{~*1*1iLB^UtiLSvl46wrMLwOdXg z-^;U)iE_j`V=r9-9%Mc7Nwr5-rxn?6LycD~irEN_*M>y|#fuXa#8Y3g1W;OJr&-qUg{d5mp~A z?d(Mwl_ct86SAznBe^-BYNd~BGmDMqlxD#adI(F|-#4Dgi9L#V@W^M}#0fyKXN4m) z%-dD0UPc~*B^^KR76pWUmCB|HMo`z)2kJvdmRkmRNE z$4yM_vCy-lN(&41LZu0cq-SnchFC{Km6>7Aram1Ms?Zx%cPlg*DpeiOC*r-UJ$N>>aL8hh#X_k1SZp+mIn{D_^N;bR_Ag;KY8+qKknzh2PUs4$+)HHo+SqB>Hy# z+9%wOQ)Y;wZdGWM>KJcuj3NWfh^Xu7ZPz3=VFmlYb%|6nGQc?rIKZZx36xNW3`9LL zz8bc5_>o;5h8CYJVDG`mCbB>~hk)ZGiA&wIFOW_ud__;zQIwT&mv-3=eF6nQ!pxLQy)y((9eq zVNVX@o2&@WC|uH~_NqG4n1l~1UUsxCk_TZH>|okP-a(WtA8&sjYm7dY2+kB@i@(1> zXu6DN>D51A7TEt;2H(kuzKNZ05tV^0p81li_42dIqs_e%q2^CB<`V69$!^p4M__s7 z9n*OD+JMmyC*r$%ppjpoPV8XYErJgJTD?hJ4P#`XA5Ew}(sdRFvE6J}sgEwNTJU!3 zy<}*JQU^~Nr|~naO|sC4Du(F6csoBav;Ne8r=3jc1ckAhwGo^RMMfSNNK3f!W|Ug9 zi$pL{kKg;fT2X@!_?!4niw^d(UX|DOn!Au^(k&0f<$uJ;7Q5O|X7Mo$J@$3L)f_E( zP6>K~RH`hIhUpwz$gzQHQFCeTp@y^}GcrLD4#@O3?aa#=@zRh!>h{FI`i1fW&0N+G zcM^b&-gQdBs$<^!xut%xozl%+hvH=HmWJu52G zPi;Mn!OGJVHdV5#J`BMp2mZm(8*;)&9F!)BPkvDQP+lN9S-tvITgV=nAtGMH4RO12 zL{fWhf65e592*Xn#7RWDKhQaJHv-6^%y_OjXN>J9K zaG|w+R`_dqtZYh=OK}wEbfjSAEE^v!7&e;O(7P;?q&Lgo;tZLQER_$-p0`Qo0WKwr zggWoBF-{)mDmjEyTHLEu(!Jl}(K>fJj(S}_1J+TsZR^z+_wT~|=u`@bkhI-ndQyn7 z)>1qX%uO9;Gb5NsR3BP7ZK_m(NlphR;u!n5Z<=C|oDp__xf8BbQrY=hFZR*AO{nwZ zk%I&$&`AZwW{C`(p{#+bl*A_)OoLbb7biPg6Bq3en!AbwxdTmw?QHCDi0OcUH9^Km zI@dF}bl50#;$BopRNBgQSK@r7ITpO-=K4bD4hLQg9P(-%U}et0i# z>xRit#uFT~j{}00MXN6=0?Tk}*~fWjaF2r&E!}%so#KgYgmdoQ(+w?nlG+%W5Gke>?6Zs^!}>l#43W`h;sP zMG%i~^~rUm(kMuL9i;PP1)zMP)E-5s{voXFIvL}I$}|vLj}JIW#4tRKf-^gvKFKU4 zp_N3+gOEdGH2Q2~2u5QEj&Oe|_M+c|f}Z!Hv~K;*>~-&K^ZHq+6rC=E3^EyDTuu7{ zDV(D;B5swAfQfi*9L^7?nOq>+YSZeCh~syf4#q8j8vpLwo~GZv#WH%|+g>??AZf0~ z!%<&~{o2EvojK-Gc^={zZ>zI5|M0mEX%#JLaKhsetzdnk1I~^1(5EtIGo{*G1_Bsx ze^iLanmyJ0!NF2@s2R-%!wCWy%VX&k1@(iX1TS3Glk2Ms&*QFfSi;gwy`$vT05%|| zoFl-%nSEnB$)AVD{qkkGc3TW=@`7loy!HBAkLt|^_uCj&o|oe7+58VB-V?GJces2> zahuK|WVlZN`!>T3f607e5-r4Jo}Su?dH9K+#p*}=_wTHy92GAf8il&w{6O|SqaB8w zuQN#CZFW$e#rR$>QNFvb-Y3hG4Terl5W$LaESBkua8#ieJ}O3piCV)#VF=n028);D z9r~0siC<4!PDPttIG?SFJtOU*0ILebUElk7!o5|DbmVZ4HQ22nLapKr7ER)POU!}d zMhWY;#chc4UKVP2P!xIk@fr_itoSV8MAZd;q}5dWwY_D2mpVok^nK$cl{7tf4VG=- z2w4!fzu4l)+@!Xs-y` zmw@S<2Eh1!II|U{n=$_x=jXkAt=VEI6+qe;Cj+R=xu95A70{_C$7p(j0umN*+<5V-nJFNNatU$(z6)PqQ_LyHqH#4yahU34 zor-L6nDU%}@9v)F=`Y=R1CqM)bjuCJ`ipZG*DU3-N)ZWAjKFQ)GvH!g28zJ~_sWVC zmQpHxTTF4S<@%F)v!0|znK*~29F{4JFbBm8c2~kz6^iNXY@E~BnAPeuk|Di0=`fGqrl5;+)v;%$q?{9n1 z2yX-F$NocK`oG2Bw$lHRjWa=8X)_B2WYddcKFi4>z?*94Ve}{5YAGm~K}f^P)=9><%- zx8lp{K!$nov?e=yu=2$4Ba^@9RO9P3I2E4*&eb7&B1a-Ha|l2-(1a6=eyXpV^6_O3 z7#OiGh+x5FJZOK!O>rvPO5=_@;1(ZN6i`8(RLb;f)Kayc{E24^I;4?6i@Fy+XCKbb zwhe15JY+7xS-G$a6y8z>4QfubXGVZq7O_ea+yJx+sp zHy9p`6{#{zRGBM3>5&Ap87`$E{omUZMuVL#6V_OaF`=8>Y4$iS5x#G(2xcI_nhuq( z4}g3w>%Qb)(N{;oFAEYuk)p|f9D%w2{eH7Ot5~f)gXrr$ch4zrC&0PEU*AM$|2gB*Wg+Rr@uED^rsJ@aozb-Vy zcKBQ!5o|=4hw)EmfL+t>m38)#CH&@tl;~qCcDJ(B#I3X$vvh4cU1_`t;z{#X^&}T| zv6|`WPM!G?+fBqv$2_rKUm!`bR8|Y?4Kiagq!EGe}=WR$j zQ@D18-`@nBujLVMqTskG+NqKVPM zyMm$(RX`Nnyl47JXvri-w7}5k%#`X*#^aZ-F!IEl4hSmc5S{W&B79iccKjAiPZkos zY8j{9h8z$vm4Jx3_-*39blJ#8=dFTw?yF=It-d#H0pgcNS3O`{5_JyM*)KimxWm+z zfDRTJA}I}a0Nywli(wKA37f0N3;&e&6qKiyf0Kb*0NDZ5(3{x?=Msytf;T{+DRJGK zbH_da1ab*TqvS$2e%4l`i@1L-(XKF@6Ko>Q0tGs05dbhF`>NCR&xrYRkC`A{6Wq=9 z*ddfTMB{AQf6~3fw$b|Brv8CL2vA1%7o(^}8?;2G9MW5GXmEBmquGRRwTrQQIYRG& z8l8fQ_7vVat=Zr8IXB6i2AldG8y}+C`!l~rQ3!+KZHEJ0r(G*9d^g&TuRR)9J>Ya{ z%3Fb+v=B^UXon;ETcw+C``2Tu>0x`}sX@Rq?eu4h%}45Ox%DQp4g#)ekJ8~Aozhgf zfwR80#%4pdLoe&#Puo@l_GtH97191m^ z`JSC#_3QUP*Zfd%>};A2q|G|BtFLWJoA^d?}DL^VzOu|(|&Q~MnMK;b*p8yWUkc7*>-qjI0I}% z^5hm>#9@J z{N<{^bsvrtDYQwA7_ovu(|I!zQ^p?FfWoR~#6^DCmo}xWH3uu_?y5tV`y^Xac%3B zwMuNj8k17y`Uij2d#w@A5tmnczNh93-mtYy$EME+8Sj>>9osESQv6#KK+^5&=d5KE zu;COz%+Xt~AGu!-EHI9X=`@uvOn0MKtlysAhZSLuvexVb940$@xnRD9!-AEKrSJYz z0SHF^r=v=bE9o@>u0gwyxx@IeqeEXynrwSm9}f2Z2f~{|v8&?sl1#V7w}zJjb8ZaG zEn#;_(c7SLUV}tbJ_~_PA0mUHr3HBGGKfsy>$9`)(!$;M3V_3vn6stF1;wz3zZUbS8yR~V9~lD}>! z0#xd%Q4@Xt6`;UR4l&48BiOteT=&Yy+MT{klxl~XYLA{hhBZDbkwvFhMQ9-LR{hNo zWX1feovCSUq7kzcgI~lhw9CXYhdv{UJHv)J8@JW=3;LM7DwU+6t3LKC%F{#+D;U}H zV2!`dcZBsh6+apjWLRtRLI6xh_3{39;9JT9UYUwZHQX`W&-o;U`~FFvy>L(7xpz35ml2QBsK2H- zse+$o+XMOJ)bB}7nP1Gc<&uh27_qXk{LT3PW<48Bv0nyJrCkD~VlppwQpq;%q!&6R z=`1~RS|1j9fY|%s1&8F}jjBF17s-C~R80upEw;Hl^ymdM#Th&&FtI+?cc*6RJi&F5 z2$o8(_04&6TrP!#skf_r`AZ^|K2YY~$myhB@Ed3>pcb6z(=na>=v0`Rb(``xx}SGf z%?5$DAqM7jDus-PT_1M7Yd)i5yB~VHl&9hTMa3nU`DI6b8`ks=0bcq;B^?cv8wg-C zm}e^?*Gc43e;+V6*{4yPbNu)^(ux3v=V25c%?F*H#>Tj~7N-pR6a?VD=S&44!Nj6< zf`<;eX502*fiPL(h{AJ&Z zo_!)%QvN{GUznjLPivh8`M7~eAmU)-dFr8Mpnrj&bYG6E!Rveg7~afhiq0MDPhcec z4SoaSAC9~L>I-2)?z1J}v{*<;Dz-@?KfruL^id*^%pr9xx%e&j#IC?N9?_IY$`|t# z-7nQt>WKWZr#jSsbBGc=+2?ERtN1jJD=pZ_vA^X(AG)OsUaXJgSw4-BM>JiZZyCap zcx_Zl_Wh3^8!y&6n4`d{rEV{V%KrK+lA^67GZB3&zVp7x3=&1oGx87Q0xa5y-|Hii zDGTH3%1LaA%kw@LJB9{EC5@!u7PNUxE1Yz&vY!!}`}_@$Vnz@ifdiIacBn?_y1)eF zWR9!uRcZc=E>w}`L*CC?+ZVQ2DP&xn3xTx<)AQ(On!TCM#c)VQF&4?kI84WaF`beqXZ_! zL$}l?+%G8WlR?uYvPXfbg#3B1=|35S;O(fh`m)Is6>+7W-+|-UI&IF>-|qD3<6A%6 zv3?0oa6{F`hI+ju)$@3h{i!cejOo@dIbWpV86L7|BAURuVn}YD<(w?$d3A>CiwGpS zbEf$OVf2{sb^G=7CzIxT3Xr>`Dy2=UcM9+XxbOaQEvTt+;OFMhM%<-=={pWEM}J~v zm1Z_AOKRmrSfvkyv~hjC4Pb@u>{Q9{!qLt&n!f?eh6!dpqyy9~>(rAFKGFRHp}vBT zS5Yyd7Wqpt0;kN`UZ0Pa6O^H(=x#>?0#r_RxFY-FTz944+KKkB5RzRB21`MpA3r0} zm`Z&I%eD~Y3F?!(*yHv-!#NU$XGSl-?;R!;tC00q56j8;Tw7?atC*lE2tL6O0gfD; zf&}AFmm@MXWfePMF)&Qc558U2SB=I7LE;JpF1kG@&zI-FK$fs;jR-%X7O=_GeY%H8 zHHkjxZRn=<6s$xGJ2z772Q4Hy1SKyR=g_Hai(rN%eclY=(}YtcBhk(Ac)S&3O{wMy z`UTvGANQ!nDUKzCfh%jY_(f}r5~K;NM-L{#mJ0zYD*mO3A+?~6zTW>gwV?IBUAql4 zW`MB_2U=l?skwwQ@p4~{dg+p71r1u2oWYV=n>#mV_gV@_Gb#I$2{4o z?7*3OO)MC(-yTLO&Hc%hpkVjbTxu~$xHTyDf?f1+eH<^SQonfc_qqvCJ~kPc^`3`$&Dy;nbLwfy6Uc z4WZG(0if<+CY%|{9>VyCH>pfT62>JKxHZoc6aK1V_gGRxNSSxV{++6c360j;7r&ZL z$byU=G=;7H|E57dl4Al!1>9nk{Qufe|38r|x_ktnX4wWK6e<75S5}gr{1k|t8h`?7 z;N1R)2#QnRA5#)m6a~Th=GNfuxZ2-S{}uP<0TSn}Mti-#CU&Fiud9`%=*(Jk4{%XR z(f`>HN!Bx;Ou9=JIznXzHK6N6u(-J3JJoUzr!`WB@37nX50#_%MfMTF?%bvR%bSfG z+-B5Yc1j<3aX)$dFM21esA1iT06VFq4{(j+r4=nDC-c6(!JYz&(I6(uB>p2NLVNkk zS-pUaN9hbS&s7fbTANvoQmwMXkoK-8>a#3fi6x0TEYmt*S z|79QtAU)gX4OTv|WAzF*Pwpkfq589&0@~5cBV^x^?Sk-R4Yue0)kO@5(V;Z)u=H+xZqHkOKW- za?0=XL!3QUkF#(6-7Fqujuoxf4Y!6+q1OVPw!kVr*6QoK*2`Yu zl>AUvjlC(8MT2DK`RJXnDwiF-HSN~(BvfkP^d9p?h2S{tHf(X40~$B}<67SpqXpX8 zwdcJ!@ZbgOS{OsLU4zR`$sWmaFh3=*yE{&3Y6}7LT6Bs`Jp{}c%tg5n(|?#%g31)} z5@FmeZQ;R^Au34A15S4M8Xzd`)A_A8o!#2@QIl3J=np z*k@YmUGCv#+fz?H+GgYM0``d=g*4u-jnNMgyNQd|BCrf!43mc2^bjZL4z&FCIRTs2 zE0?wUwReuU25?b_qpUrz?yX;jP9smvG`y``dR=FowW)}6mw{d0@oNmtUL@J0uV-V~ z*UMcUvO!Mq_}3s5CXMk<02*@!yv?G)4KNaKbv?pW;gUmTfW?Si*9~p~j8Z#A*NqVh zjOEy79>(4DUI0O?)JZe{#u&IY05u&?K0n_B7TIwI#rPqy>w}oKe9q?IY84Mj@xje` zX1dOMPqkkm7to{d^zz#;cIsKAMh0%a#L8|yoqHbBa%&|XVQ_veQ{AN`ytABye3oI; z9)NyM{T(>Tok^|!O_Q0v&5G@$AO}3?K=l3WzhPML zNO%Rq@fQ9(|6;`x=++Gc!ei*!`bS7`$7{5LKspYEtaD&nZ$=0rfUkPxlRpb~dc$$V zi%U3mpi@BS6Qx`_8Yu+ry~uAy=|%J2h=tI1i1x&adldZ3XlZ~8UJZH7U1kdap3v06 z0$^K@;o{%UvU&uII1Bdu!{FX)u6@ZIj<-~Ny|~>Sp<=E}FD2=pcW|jGzr9$bAF9(Y zd1qj+$@bof#ft!?@6}(0;qy~kzAQ*s+SZRX5>a{|JkGquZX(z^V)a6DO;i6v&=5%X z3;Tj_geSX#gu<|cB+lpp6wFG7?^_Sc;VoV02$$G@CIl$w6vu%} zJMfH&#{xI`D`~{FnV#Lgh0`wkS3o! zE+8y+cj?l|W=wehA6@N4&Fx(_EE^L>eSi-O9Ge^E^m_GXOxHY1bDtX6AM%{dUBR0-1%8MWibPuNjVGHuvGgprYts#9Z~b(xovZe5~`)6Ga^bmKN8D(%D_u^|v9v!yO`~9q?TBX@-wmPhQejUW zuZ`XR4jfHRP(Z{>8gka~vMfoly)!UPY>ih1x|Ljp`#-u>vN#(QSErF7pn&wI8KTz5 z_tB_epGU?C4)1e!viT4gu2eDK#WQh_K35{}jv*}m1s#p$)7!qGdKO=u>F*Df z*RdtoL5X0PsAh+MSIh6TvEhS(^RW^d2adIt`?MyU1Awa`8fE4B+I>zpmX_r(7UoZO zr#rPpQvpUWxgFGDRh@atHGH}jS|dvU?iSGj@g}CL1S>PT!Jtqm_cvRRp8Ou{kg7{W z9_z;vO6`_L;4?@sqw$eJCc21VLipY^{TKM%KFr5_X%`*e%oW`465Of|&4C*(fW(f^ z`GhETbLmn`SSDP!Q?Oeb7X1ea_@R}w_-};pJ)0e`{~c2I@{`)VT24`)V3Xtq|6O5E@QUJ8jovfG!)uP6hr}e}?otm%j)I%5iPMbRqL5hO&xa z=MXT}RTf&8`~+%r^9aWFhL1**@op{0NSyC~*oh))RP zPG>%r9hMSJ`81$75N-A#I7WCe5B<(0%8H|oT?|f%kSO~LM2;n(uqTO(MKKPKlvl8x z39M6gN&tq&i98r^OjsEhWjPzh5*rsoJ>y(XzfyqM)w=D?A4O4@r!wbGDaB`Fq=f#k zyG}xBwFP(eij>i72A^i&VXub3i%}t(TWAu~Jdb6h)J6}}xcaUsrCUms2rvA>(RTTF z9#xZ|y`KdsKVWs^%E{x*a>2lE4a{kGzVV>IgwO?UftbzA#QHtEp=}78uC68`(L~Vh z0DNV*7JB6uaMJlUUM!L-$A;Uy`SnO{8w1-WevcRdK2>8!JK|nz|1*D`~x}+QFkZuH|yBlc`2>}7=5|HkYZfTL;^hOZAxu1H^ zci!_CoL{)S;BxJ?*P8Q=agQ-(>uc|wG@}8^rxQ_xjDp9T&VQOrx`K1Eon}haeo(vs zl2gx>zF*@Yjvtwbk=i%Iba1OT-yUwoP#JP3nf*bwaor@L^~E~{!(zxVN|!TC0(AV+ zzn!?3hw8%^4Ul@?=tok213a_s?Fd{v;pXsfFhoN|_%!r6`;@@dg88NQA}X5c@FUTM zFDRCMD3$Bz2d>bbnn;RmL~RKikJPj7{l~nPexUv)pAQUl8=_D5vU_LPga7LLy38hpX6frRU0viZ(ny22j!!-Yvu-bmpsVcU6kQWCFP2%3R7 zmIIV+-lxL?a(#85b1*bH0I2}kl$+&mQ1*gAPI=dKJUia)_3fJjKRm~AgT1h$T<2yM|NcK~Ak?wyY3f|Y^mt}T5kiLWq z9y`&lGTb`^=v>gHf92CeozwmUJ(j9W#|AAtNRaJ{&hH1r*l(N zET`id&fS6tit_npr1p098D`lf37qLeL&8!0P9UItb%MT?Rpn`@u{aJScsnNfd7z=9 zVJa6zl|%)#aeCf(L{b)*yzlUOw%cN?{#@s8SRWeo~yRV;PU8Pb9uRb@|rtFTj=9+RiZ-P&t#znD!*# zn|i+TjWMFf{->EdG0pP)uk(t9Ru4iGv;?Jqjd$HpW-_^Ns9pBXv$z?V$ya@apY_S# z!0rxOQR{gisLGpPmKLzMbJfe+?C2*5Xu)XN#ZeKv>HF3?UNxUx!@55`TgYVo`#&wA zRi7s|5}SHYDFH@|NF@v|YXnX2|E8t%0g42pXAwQ)ptX*>`~L?wMXzB2Fd};6>$i~r zP!#{aAOjdsL@Wf@ZwpE9bEp8kGO70e8?>ksbXPNAF=>UMU~2;HHEWg4jaDIqIiFhN z@3CBUVCUgt-7H9;T7X}qdGe!O>(B2?w$ewRL7+C_hDW17qimLmds3Ds@@~m+we~<} zLxcAv!`}(n1TjcDhPdnzi}tT__oF4PhBuSl;kGq6U^@{L>NeVE>epICRhb^lRce8@ zowds0e|`46aX{tIiTp2i>KYn_LU^D#-x^Fnb{Kh<7^sXyJ}_B0&7xDKi6^?ru@s{A zzX@65)@H{mEw)EX4MvrmN7yuf*HKe1;ii`%ZCtNGFQNsq?5Kt?4q*8b!i9bMJ9_Uk z1hE-3mV)TD6Pe#CAKU=rsbK_N9W8$b2<84|lpeEN!?65@2HV+a`d^h9RT>h6!Q*m& z))sI+^x-y+p8W;06otWIeF5YXRUU^WO;f?=@p~Wf!6NOCD){?@{`<)VTg5$b10Mm^ z_3x_U@1Ih%;J)GrCI2qB|NDzY2G|?nWC_whgYox!`uk_347kh_#_+#~JOBM5GXiwI$*-Uh+eJ)ScFsr z@B=P0AT7@TzLF+bWDO8}c%q+*{1)N`MCjaz|2=|c@Nr&b;8|$qz{z;?I{m0vcUoyy z!=xm7*&9!edc)87syl`>dBU`#w-CtZ|NgeB*D#)MJFj(|{D)^q9IYW@_`+w83q`Vd z9j4}~bl087PPX+$jjO1uyjk;I#_vWLGwyEAx&Qq};*B6gSbY7X>q8(X0v}2GcmuyC zWP(2&EeNl>6nC8G&3EzHnHjHcStM1>wNPrC2{1y){{cpVT42<7!CBRH~I`omE;>K3D2fr6mR!Lm=gykC3*r^m;B;3|KNat z3yop$-3K=U72nXLZ%o1Ro0I>oHKqixY`pJCfsMvG83G<&9~uRGdJ&|Hs1(-`7Sc8aEziu|odfJ^xDr?-F%`MIv>R?bbj3afm_#osk4SX#C)n)g_!HTY*V zmB}mXlu5!IZlQyFoc2uLtgr;V@s|T?(n(@DnN=J;0;bx7=}-c`Q9k69%#Pkq|GwWw zaE+SwFg-B>xxhd)@>s}V>(d+-8HijBkl@JOf;rff5#1inl+!VN5L+zgI}OqM=drPa)Y4c>P3@1Y)CnTW1;nyr};S1X9G)&?1{T=T9Ob zr*AU~iEGrmt-%PfT(8bbEheqpnI^S20MNS{OqKvFp#?&Whu%&W)C&1Kud{^zcLDCI zUhd_lM3b|DUF(1Lt{fuRS1;-jMu67`W8nA;r1)6Khvpp&iZY;~ON>1J2B2Ae=wZk0 zaXG+R1@NVzL z!U2&;6RdWk61@U$Ovc=G_42GDh{PhNAOfHBy7+9H_qlp>Mk~MhK>Tbsw;Ys6W5KL1 zDU=UnS(1VfyPqu|CJ2l-x6h?HGWXW_VF z3*v6MWCV^aFjI*PLjeFZsWkNBWX(9{`=$nyXgIUaw(c=zkyReIShfH%I*kBoQY&B= zvz3_osf^!lZM8*GlkeVg|IhOWdmb0;c`qcX!@(E4?p7|Wxg)?iK+5m;-lt4_Q6?cN zgcUH>Erapo66)@ac|uicM!Q23y?+QB0mdCbTeHf`%G4Iz(67l2!A8&Aa4&M&9P(rF z7ww`ug(-Hy)fW^4y9a(WT8_b@k-O+AY(;SE+ ztl^1AD9Ct8-3g<9+ z!HjYRfw9c8eKnC*-pv-0k^Rxk0fL1m!JBF76;ym((hC|AJSg-1W z$N78CF#L|Mm?Y0HoY$e0O z^t!|V;s7)oknVm%w-U5~8`3Pmt|}FY-wv3L=LiTU6oujnir_iA2m)=34MY0-N+2%G zY)0KEXY+NZrnzUNLF?Ml&Es*!k&*x5cl|n-X5UJ`qDS8QKBL2%oJfZ8YAgUPMhsu_ zOyIv<5e)VklG=swn_d4YJz5VQhvCtRj!k?Rv{t1mf240sdVfIB7SMxEtIa`WKq&?&R8+5jZIef5e?Ejw%ixOL0|D6+C;!+V|b6diG&L|jcQdvB-?cUKDU z(HVV5FZQ`|mqiKt=^hB07U^IgdM?M)H|4+yB64;A6~-Pyu!-5>T(ynv{Azr@yq;DA|WUK*Qw^Rhf#I13f6Ep&@ zo^y`DdB$%y6GT!!IiE-T6WtEe{wKPL`+&z?^odQEfZ#jWhl6OiuU^81p;L4*bi>Hi z+P6nd`8n~k`C18S6 z76?!m8AkMgGjq0%2U%_=HC>%7;G$+bRTQ-p@bD)jIMwe}uU1Z>0+DDRUkqA4nA4Sk zo`NJ_9K(FUcI87A8f7e3j8+rT52GOIXLOO(*09A=BIy3>0}Pl&XOhR7ux$42Fy!vp zlUwUO7h67$d;WLqEe3&?Irph~vN$Ue26|qp1``nC6fvmeRe-Nm0Sanj#l^d*NJx~M zCbP{3Eln50^n^Mi2Ia%ktd5Bi2yD)36q4Sd{$BedAZdOEC6TP`ICx2#cBCRSOa1u|n?m>AJM&^vDt(DtCh}`Az&&`( zxj9{|NTLFjVor&q4DGA&eZHM-gNpv~gIgr+?w?a-&h3ZSrvbdM+Q6Pce8b%Bpw_XB zmP#zx3zIy3JxO5`)dzU(EY(gyHhOm4D>`DI^$FzSked*bi29dq9Sbiq5!hFxRBEi+ z6N?%L{Ap-PNQmo3)#eg=xN{2|)4RRcBRr^^QDV)f!uV>{PqIO{jhf57wYk6^jDgM& z;Ooy2#0t8&A$7Z&icI=IN_O`{Y7nVGIr#7^RbL)ow7S9_*d?T9DgE%G@!iaMm0l0= z21WK?ea%{j-=*Q7wnw9b(ir)%FH#LgTWNf&tEx*%7=*A13yP|fTP%hMW-AT&+WQ$_ zruK$}q8Gf}EjB5^gU#h0-E#yd2m-&8B(b&|z3z;E;w}{%EV54#utuaIDS_=SYPb?C z+qp5e4aPYiNJuHY)`MIHwZ)?L0Q}L%mlS66uUM8?eF2=AoAXR|6!}q0V9Vqs_t$ zL8agseM~mvCx{e>6T>K3Poj)ZH}==drv$!Tw)0iF*N}uni)|_|?wkADlLHi*iKe%%HRlHOP4l!*pL${>a)~oCJ&Q@7^{5Id@Tevvj)C)#0Ko z$Sma!%Z;{8tDY>+I*j3v{jT!4xgnSzK1{gcoQ|5`#JZj7$Z=$PpEv&}aUGC?DCh$-0^kKcav%D$2+hVQdU#uAr-2I$CVCCoX z*uBr&4^MaDxXw>K$NW&5KXx|g#5_La_jivqc#X-x?H8r8_8cS>&jv<24G9D=n04atqBssJ3;y1R^$}c5wP^L6iu&;4lnFHsTZ-{RpT4Z z{!-SLnM=kO0)Y`C2@R}ifbu&4ke!n&%rBXJ&HD6Q&3LN}2)0lfl|Ab8puV7A^Lb6} zxLw35|Nf3Xikc?2kJY$iMStTQ$mmON&UX*eU8;RDc_P*fU0ku&gu^XG>#65#OourDY~*q;qu2@=YUvvz~?V?RG;E+K!O?hjM1zR($yZ; zw@oCf)zK0?XcUT@=jZZRh?(ZLHzXRe2!<9!_x5hwR->wz#H`=hw@mK(WUL!aao=v^ zj1$S+Pq>Z=C#)p`D@H>V+JRJ$R(p^vhCFX;E*?<@qEi1j%b*qJj}W_CA6cd(k7xn( zsQqyf;zYAjVf2V5eHg6;m}YFG^a|2|H+q8d&ueAH_}IP<)6G=hd||_xAa`eVcqCe# zjP4R)<2Ys0SbU_K0Hf)JVUp~pyXYd?6!yHqF0mk94hK8+8yJx90~U?y!Z)1hpTBBh z{p#}3z!ak#+*8-PG+M7BFE8iKpeW>`*RAeJ(>1@LK`=(`D?*LcGxQpDZsHBXUBQol z51j!F7-V2NwWu2QH0!ccCSL`5of|I?3Fx{v$0(1r12FvH#v<$N401RIN-gz;Y;5)| z4jRY8kS@xM*AZGBAIcon_JyrRNjdRUIqC_I%hb>ETBdo<=CJZb$>8xwcNS6#Gygc~8qMGMHn=++pN8Fk@$2hF(^w83z(BY_BB zj4l1B(+}ETj4FR$?4@M<8XfQ+3m>yRWE`0ZyeshJ-`Wdh z6SNs~-IMbOBJsKYXDL|{1cG9FIcJ=qdw_hk%S8a^r~N6U4`E7uP4Lk$WzWqoydG1; zX%y@yMA7OOmvnRZncb*4HO(Tgbd)#h>@QI~Mq=t_NIvtHY8~*EjTw;7R+z@wE_~<^ z^l;{DF#gg=ua(yQiOyat3Q3K9Z3ITb`9fH#AVDxlMBBM=(67BgIPgXSVZmIHfOx{B zjF5ec3d`QzMahGL$2L_E_=a6N@r?#dTV{iJ(YTyY%$@{?ln{Fy`8`Q3pC37aNF@}P zIPtyUgzgl^IcE-gOeqVs@20*i(y{JCsHfaZ=pflQ+gRwz{h9q`*IkS2zCR+ahl5|*t2mFmy-jg4o^Jux*21YevgA5CM2B|l%U4H*VFZAyggI7^;NC# z3F2^AqDgJ~M);MG>n8h5XU~BKO%)8(XR;T}PH6wWY^LXnWR+%P@$R5PN81o1rVAsK6w53V}%b>xwUJWw#@3>l=#B)xdNYf&%so zKn2{>oP0IKIgj6GDc+?GI+e+19@#>h+~+Yo<9n|X5tJGEvsq0U! z9A<8Me7t-MDSA)MDR{mpgw=V(C5&|s%<-nY`{4+*+iY1g_o%(M6N`FnVNM3_Y0Eo=g3V^n zkkOmH!-|n_J2stPXCK#kyr^>Vg71+1N4tl)NSagMQk-p#5Jvs$uayl+A=42=PBwC( z3Ch{EOG{BDkjaDvrF)Wr--$1D$cb-Es!`atswd*&aM%&~99K%E6@jo)v3wIO>d!C^ zS_5GAF=g<78sUXuL`{^6l;Uu~vM@AYojZQ)QfOhBeh;63nZjS3Q<+tMBjk6d4>|eO zOsAEdi_mo7OT+hD-=F^?kEV)y7j4uKio5U8_iN9`-TGeVKvVK<*0MIw<*e=epu~AU zw&uKc+^h=jVVURgO4~21X!9RFlbH0` z_p^>eHzeIfzCDrq{Bu92KOvB*7F~Y_iTbs?G<5aE|5H`-CI&!U-+51KD=I`Lslzb- zM`N8YdnMqWD&q@7HiD57D%Lo|UaHg5sk19(cH&|YCo=F9!)?No6?fCq`zCXINUVq8 zr_}EpZc!cSRwV2>zHK`zBNiH&x7W;GEy%Zuv(@~}U{EHp+^BASviv&c)NHz;M$+mt zq{~gFWacF~9Vc?b!YyMJq!E+yv0j*3)~j5>zA!ePJ*5l|iEoKLZ&cJZsz1M8ge5!w zPLM%Mt~Z#Ah2O5YM6~|QvYP=|>p{CAEB(`cd6@5odp)9}8VbC7j-_BW+S8n#e1UG- zVAQb*V z#pXw8kl^>#fn6a#p;DB~gS6BaVJh+qASV0z}{ zKs1U-3Vgv$$!((A?^YPd8D^_K2UC2hteWmhP2Du=?j0$$c_DEGr->1Y<)ZSs@sio} z0<+38zUB13+dl&7n=Z-tKJ!*RKFA_KPAHPzprxBS0kW!Zaoq|`-Ke);JPsE)S#_-@ zKJ6@K5Q*P44m#1y?bd?Q`q3 zx2zWiy$*T-l_hxlqv4xl`s%mzovvde?B6QtdJ}yCRzQEd;Hv@cwG;p{Eb}b`Wipc2 z%fRAFMwVmt5zg93^L%yR)y{M30-)qo0%QT@FO0oED;it)S%Zr+2~V{l=b zbq2zhgZ72q(hn%?%3<2>r=AO@wm`i_U)&|P2XpMsYc!ER!@~=r)mYl*rm!zrI90J8 zNh#uWVSWkkc9IPWWp*#U`R_L}12}GFDNEGL!0>x^pq?Clw!Py=v#)ZKZ}U*oqPrO*6?n({Oz~OAcpCgdv@b|3Ru2I30YIrf zvSf){7)fLwcx|i8Qg|0V;jz`s%1*V60hV2i2y`fA6!7jw7Jx_~#Q$6iBIjVTXE~a| z`J49Vr}W>dsTXHAx>C_$oz*#rBaZU?8HcGi1M=wkbXYGxu%+beTWuj2VdUSfePBBl z@faA%FW>#-SHSDwazV+PQ0elilcLF*#6t$1q4#{3)PL4$qYfB!gke9e$#Wh|q~5^e z@}b9xF|ny?J-Q{@;4@;)1@@|?+v(XHme?tCFwT(A-RZ#eN)f985(xhIRGe})c+Sd;wtJD4Hq#pB- zhEq!V30U3H_H-2>07OcK3>!)tu+=k6kXLaEPZAF$>JXBGnzZYJ9E2%5C?44yI$@=A zNbW!J4uh<}YPDIq!J##+{G{rr%bQf-&Chr^hj~xC%XE!foluN06=@E}WO?#;opkEe z83YZhhJ5}y9OcLWj$LpnCwdF!OLm1Qz`?Mi6;SCF<%3<+rNFL~j#JZ#MhFTK(}1jV z3m*T{je$hjNl{bk0K50Numt&zNy3e30OQOyIj#9hKf8IdpHvSX{Xm}$mk`L=lf3p6 zF_&7^<<=o}YS2#TKm?_K>89?M+w?j2tm1TfIr}O;g?;AC_uTzPf9^T7XKbPIi-mQ9 zcE1`QwLAh^b!&ZPWo7BJN+|}=^r?d8?|V%DDOST+)a-=oRiHdK;qsWrKtl(P-8-1F z$^%f8KZBDY*v6EH0i7C<3g8JsdL_ksv5|1&ces5sr^4eK7FJbk318Lm>TV%+A#0=q z2!n^c&qvsDm?+GK+DmBdi}5$zXnRX}_$t7OL{ z{)fAug#wSy4{+xqDqf{75Ny0hh<77j>Ykcn!R;&oE!V!?n13ZJ-yw_F>D z0965mfLS0j{n&)iIYOIl2)ZV-s%7oZ9xi^@)d9GT9nGMvodrW*>uCog#)Fp|8jRWP zTxtEds8V49-63ug!LkY#o)sxvL#*Ci13g$)A5LYy_}yOpEY?i`08aUL`CkBK<&Aq{ zw<%)=yH8UtvT6M9-ogA`FQ`U)`rR2%{|rD4M_bu3D7R4LPfc?)R!420>({(e@jm$8 zRzPvY`9*7!ziM2Eepuh00${3bIVp>%UYzf@JyH8y6Ij|Z4jN~@dWO?jW}&BBJXNMW z;mn-LnylYo(7+ldo(P_p`yv2TQ;x0_E%z|dDZHUb9!6vF9_kF4%5N4Rgl3p-%|hTD7)dzP{-a{}@|z<( z894pF%fYb^&va*&O(UMt6z5-w^Bylp(aawUO*Jav&V0QFjek<$YxRgdSnA~-vz)9x&+=lKAV#8)u~kaSWWT9rqyLIe`kd9{t|r@MXM9hi(Ku zT?=j!>YPgy(^*Ur6}6GQe;S6$h6eN0&aUK!hG>s%QDC}o1_lah4>n*feU{-Q7}Kbj zTeNL61qum_+vbf$oDGd~Az(&)DJVk98yJN6Z||qoe(_6l7)?bWSoT?PeJ__Dcm?$A zP%lWKTU>#EY(L#j_0SryEvRn}9#j~n7xDN)ZW_%jh9|r*s6~Ed+ucfbSU`785GtQ2 zDJvzFXiRh?hT6yO{t77xTEfAVFkKB#AEr_;r!?V_9foW4b6qHIEdR8&kHPvYr0aan za|^rrC;I2S49nm$$6`TJ`k=sIX1k2~l7Bi9<5`7-2nN9}FHH8Q+W4YewY2^aFb&o_FV9veA0r;vdIu30jVe3H)y?!+P z*v{->=#=cPL5M{`dof)4FWz0*hjCG<9ImkKQomPtDox;mv_>R-KT&Ex0N8oxwcRdX{^0tX(@n`CFm_-FLQz2al7?Ap{<$9ebq z10oJ0hJ43kWuJYDC9(ZTazQ{oIwTR+wGOcfD`AS%fI^q?N_uMq79_p>+dq06Q**Ra=(Vw;s9-Q>FixU`OSj*Cp$5QmWhZ0uD;J!ORD z?sfX%g{+q|PQb6upWM2t_Nx}T3hI~_V`nBf*I7Jv7bPDT3|}y#ezwGeUtpmglJ1mO zSp_A`f|10pUj0%(F{IhFm`0G;xFyIDMt?bK0*DP}Q<7seCJE3o|Ote|q!r^G}C&B|W* z4$^~>o%wH<&3-yn*rUVTMVlt?lN-H_NU8DIUre*nv+$$rxWfjAhI_XStdX>MQ=&3SH^ z-)f4!V4q9r{`gF0-ZZRUGvXdzsYwj5X8)geUNcpw0qUVUz-QcxCokdtKpTToaYwHf zSTtXjVcD;VqWgFmAn^??=I8o319(V)fWY{OI5^ogqb~O%i#{_t(&vLHo-m$Ah6)?b zHF`)+rL_^AQpv5y zolh9mgsPt*V)qwN`V@Z-<)Hw~@y0TrCDqt5jhpYf)#Mm4<)oE8rLW6yXb+&+j{)%2 zZB_DbM2~5>_!T*XmQbrNeLj@A}9>c#}OIsi@vEFn!w zbdsC4J?R_#NG%@{HQoXd{OlorJH*- zy2v+eN#UKn7knCYY3iIsrd0x531ez>8K~?fuVa`o0h6SD3V#lCy4F*$5wnDOJ=_|4 zcFqy4{u`FI`Y>s&iivK)O7+(X6e2{dy}%btAJ(cBGxT^d!`igu@KP&IDn~F=?@d6X zbaw>@Q9WhD`99f)NM*w~-H^=78RxSefvusITt!wA(pgI;GdAoEM`Ffq_Z|>fKVA1R z6Lq8>aBZ6ROSe;baio1ojpzJP_0cWi7We59e{L+)LJtb{4y`}3<9|fQ%_WT=KQ>X!!Qx3Y1kloX zhUnsYi76K_1J%8aO80lJMhm}PWU#)CBwoTeaODt;Z%Ev!sO)>9bthx`q{Cra%c1pC z;apfZ<1^-%?gGM?R|##V1J*Z^yR%LO*th|AUOhD06L}(pjMTZ;bh2zk1Zm}DKfBBa zpK7FV7z;C#G}WN2kYo&p6`f->cVsDj$3^zi=q}GbHNY!9L z^kdlXtslK2(QB)&6=j>qlz9%nvQy28zp7?Kd@Mo0)C_lf<_ah&T;;T8vKSFKvfmBf z3E!PIQaYuZ7O>bb=3Y0;vIP&nE^9RvL?hPQ9Mce(vkcxh$%`4$MLfnPWeHsG+O&7c zm2u6)~%^pP%AQ< zR-pl|1_YWZD$}r#6G?oW$j`eV9e}RUvcVxqH&nJSNO+&l53r_Qd>ye6s;&?>Jb|Ca zy7D!7a87@y0iKfVIpwXg)caze+M_4i?T&s2@)KR73IzBP*yD}xW32wBSf;%%1zBf% zT*4O}QiD)0_QRLn)FS~H^2wf0KlA;VW@IyocxoO^*Jc>BL)RAAMW)}PJ|GHIRV*Vr>_$U6cH*~}GPD&GguhS606;+5n{X&*5KaXe1^I|Iv}6JO$;N3qim~V6 zSg?&_u_N4`3isNstI)~K)RnO$DgiB-e2kzwPW2!#9nmOH6I>yAV~$3_x=9p)D!MR8 z#-4*)*V^QAPTXL2Bs1&v`N?dB8lpT+az2c9Dye(DH&d2E9GZlYdM2(%A}Zl!8HbA$ zE$~c#PmRvaC)eAsTv`Yt|HIs?2LWN!Q<0DmlQ62Lp~dHi-?d$IpN5L}{#I=U9i{;z z#G`M20Z`Q5^E9K8yAxCSuCJ%lcp;4eZ;K0@!Hl=YQGFY**D&>DUx!%@=y(t=flv|$^adS}ec788`Z^7$Ay4I8NgO2*o3(<%-_vAnGl#{WXTfpYpVJO_%VenDXO=eDmw0OF7jKA5^i4C!h2+dT zywq_@226dalz^FDppCU~Cub;o72vzJ62>(=3d_kL8|Zk7$@fC7kbzZGgXGK9^hy?Q zxmtEpv)S^W`A-_$4T`(Ow%Z*d81!YzVZ$P^@uoSi0K6XQVb05skw08d)4?uLC?^q& ze(h9)GhwZPwz2T=m{$HCZ2xolXKit7Y^GtmOh&O?i*LFYu6`G+ZsPs)vSDENtmqRMBDke!JEsPJl{6zBPSIA5(z@ zN6BblA-1I+`jrf&)Fnh3138h^qjH1uE4mYUR+L1&ZD}INuy0bgR%JzTyh6s8@#ORC*Za9L4 zA6{ljn`->Mjpo7wRxSyr{sAk6WD|_TVc=jIs!!bejdTaEbRVjMkRW@gM+4$RNW`5z zNJ(i=8Vj0tkc1pLg}b!6pRtx(Fl8^KC9M0c+$}$=yeXjBCCTn9!f6uJwrqFLb`I{Z zs9^1ZB$kdpagb~O_?+bPB2t|>gL0a2N4@0SNkxin+|iJdaB?lP^eP7vQ(rMc?F!HW#jq*qe1D*KZC%GriZDB>Ex~YbhxPOG3 zko`IdPSmfNJ~t3`J%m#rP{0Jw62T!TA-$;!mvT*;=|?8FwU0Nmo8vbm)MnCPL@31P zs9!da?z&IP9H0w%vjvvEUZVQ?`lB9RGQXgv-)rmY-uXIU`X)#B4{d!u*pBn~`r@PP zEaLU}*T~Zit<>!214>M(#?KE$ZAy_vg?FpX9J7pDWK^5pIa;=`zBXX~x}Q}{#iA8Y zYCy%P#Jo=om45e4SP}Y*F;JzRXZPV=1YR`h{rei4WL-M(YjBJsowyW1+F;dX}Ck?H7npI3NFqO+mfa+IFc&PqGY@MQJzl`bjKDEC=Fv zY~Px)Pz|%MAc*qBvDFrQG*W-TYnSt$n;so)S?Ilq?_JqjF<-{^v(f=ET7ER_vnwjye>kHYF%{NU)0x^4oPh0h z>&*7O#L`{E5&VsbMq1Q)S-BJM&Y*(gd(MzrrF)7{>||OK{5v?&<}I&Bg;yy9+D{s- zZ}U(dSIQf3H{k52T`qnQe-nuz6w5N4OxCf`K9XP7iFSX04k<{uIdZexIl}&`mHJV7 z{{=$~!%J^=Ara|uF|#7p3_<>2_2#dNZ3y{ZdEy2-G{o@=3JS61Prq4`z1_aEZ#un` zwhPR!f=m80u1w7QBS@m{{zuLPu^W27k*0ymWqhCWk?3AgN-Sohn+xZAH~RQJGM+>@ z(e@b};&mwuFMH0@PgckXJ+pC9_4DDM@wf)V!opm?OQ3rD2^jCx{c+u@>qK>)A}opD zMJ_-m3jqj_s2AbEE)%tKaMX+(uKve1tjWkP+ai9G zqsI`PbVhs#AimdS6$0SMpS!YKPqsE$NV2Ig9R(NhJD{xI29AMTdT>vGaW!9YzvVD)fQC5kI_l#AV4A*g{-n-@&wtSRcBfx< zHwFUN2xR7^2OLD}@E7`>=7`T7d{fiCqrC3DaNtD^BX&ux%x7^t-l;W}O(ND=oF%SA zW>6U58zE5U8Jo?(9UHZ98{JPlsx4`Ig|$^!<&ar6lr>VSrO;p$?IuK;zm~g6u_YsKgzKZ%1l16Lw2d}bnKmxbl^l$T1f%8)yG-uXiiWxFpjM*@^BewAw-niRF}zxFvK6)?;BcJplW5ww@vZJizxRc~x+f0-=(k(`w^ z3{lSW9UZHB(e?I#KOOymB-{p>SigtZF*EduKz~ zQMu#eVT2Y-ut`+>3>m6Ln}529A=YVNYoKmPK1OB6bYFfv9s4fNU?*-{7=4{kp6#;I zZv~Cw`aHh7M(&kN)Pzxu95G$X;}{~lKlrr6-IM~WcaZJKh8z(A90}?+LV#wlv!e8y zB?zBI=71@b)uE*lD4@Q80_wCB`zxX_FE3+`qCvA+Qf#t`kUgN`cDxzhVnCwLOHbd8 zVXuz+dP?hrSB2Hq7H=H=f)}$>(vMs1Edqt0!$O*K;D9JQFEtCC4H#^A)_p#K;}0|p zKoo7Zl}U~$S28zt^e@&NeuPG)iuZj95szrMWQg8vK(3&_E0oJ{Iq$XF^SAKL75{nx zD85KgDW*-B2riSZ3Z|%9C0q{)y?jgYTlbl5_NYi>**lu|CE^a%KaB+6Xm%KSZz9!= zO*{~E4oob0?&|-+hD!O&$F6Z4#bRHy^hW546JaI)sw?E_4-ij8etG3q`t8V&ddbec zN$h%{n-b%LfA6uU4h4IMtSVZ%G|?(4p?M8Bj!F)8dh+Q$cE$^5Evl0YA(=b9Fr2cP9T>!b)r`OU6vciy}Jxy+x~ zN>?j^v5>NFxvtoP zejeN*i~#~rKi5fVlFTsCpA6^+53r2$ypftv`wJ+x7@qC{nzO|{-Cjm^6!Q^J@S5J^ zmyM}*H%Y%nF>s*N`A0f;1fO4(7MQ+T@8L!qM1(A)NuqGT;eL^WPjKMI^lc*wukMV9 z8t*J9obl5r5@#HiAI&p=!5)Nr9NdQTb9XQ(EUUup=sa1orK+yzs7!B4-!-;AR^*jv z)p(Ktar%?=2JQA5({ks2O-loKTMd_sv*+$<`)L;frMOGQdP)Yx8MI=m z=yNaKn0Co-qziKYpGv-CW}_gLwjU%Dk;tMKS~bJS*ZpB zPSoXxz$ZV&gq69{BQ%^pt057XUny;#eQY6Vy6O{xXMen@7WFv3@3`aEv1L11(E{K< zd=u|jcjd^Zn{27zeGTn#1=+O&RxDrvY2XH&(~>n-&0fu6M1}}QXggyZFZ%n<7xrBP za3ofDDCq|t;25Zq<`68+Op3(TV~#2ShfAo(fL{}>tt&0e9!3o(dSYLi>JaquGGQMM zjsrl2!V3MxoZN>3^&&0vPYCi;dGBeDGLZ${ zxC6oEF~+!^@wk9O}Ljn@uJT#4f4FH(}S|`Gw&l+svQdR z8UTk&!i)zqw~r#}|H;(N3*oQUx3nNMDHiTKob}fQW$nB(#=47=i{Z^QU&g*PlN}>A zBL7~p+d%omgxnb}k=BK6z77vre@?)%&dE6SVDi)CR~wS(TalYq)>Tzn2MnJV!ba&_ zecK1rSC&7vX)=YFeN^Ef1)^S@P?@b-(-V=E+n1F&2)UkGN@Yvr)M(5(!F63-qaFi^^@xrYZh8yhqYDqy zpz^rn+WSZ7Gxi!cGI8*76Df11b;TadKf9I=wCDRaR{hi9L|3)d@)tM6;Gy3G`i6zC zGQ%;R$pu6P?b)%at3JB=onK@`B@7p)VHR#)0|pgZFfw4FuQhVCnSjb>Mu!G0VVfCL z`yg-xot|PqosVHBQ=~o#<6$^7A|r@bsz*D^5qeuSpU!>p)fk+H`T7pe(Yd^J5u-j3 zm5PY`-26J~Dp!})x2avdmzLvR_PX71Az}aO1@q{U+??L(cbe^h$DC9e&$Gph&aSxV zlisg!uNMZEoYqiA+8Z-?D=*X2izqIgg|k2=7n;RC6nbGOAvEj|l(M9=?QQKu?@wE} zE$J?<5+w$Y5^e2=8|ZfZ*v|W=$3MiBAJ*C=KFc8g?qMQXv#Mj=VfZ=E{DGqbhUbg- za#i^K_?0}Pr)`2w4fw5?@9_va1mU%Zrv9w$r`_|j+g8)Cv7JVZZQC{)<0ffryN%IU&*}R!o-w{ZoPXf#bN1eAuDM?GRV!)gcEx5b zYVpisEfm`>clXYue$Xh8pLh}6XadS+Pj|)$8D{P=Rj7RPs0zE&uq=B16C7i<|BHqm zG8Q}9&z~A2&j903bQSsDqu%~eiO|TyzhF>9AinJfqsT!bTECDj=r(d zIrmE_R4zvw(+g-hPS2*WtZWsG=>NlUW1<;Ou-&<7jW) zeON7;8QH5%W2Z30ks~B(>L7$>2r6BzwktbdBd;3EiJgPY&!lQIr3LHLJvCOeFaJuK z$uyvQTNF|>7=I*E8s#GFgL9(6g5X*p$L*n0pa!%fO8dP!!U`Z}yMANCe7u!|fKSwM~wH6T&J?rP0Txk`D--_n8MvdXT6bP0Y zI$w*!W{Z5?a|$ax?}1R`~-VpX_@$Uu{z1jB#W#1hi6i9Nc0l|m0Oq$S#+M`4$81Tt?nuu!Sb`a z69T|d$}l$BJ?;J~g)?BkOWhs%A;-O5CF-q^b@;j`qPwx>7}3oU;4^+U66U63V0ne~ zR?~8}#Xsw@8Zd4?F0|y!@L!E{PL2RHH2OV(9lbeBkE{`W=bdm`3AN(aX4QY2hY5&O zL&V(!dso!qJ#Vg)NFayCBTxEjb!jP^FyhC^-I&ECn3xIcJ5GzsDih*|*pUdViaa7y zaE$&k)CC(knICBKJ1NJW2I3my*6hjxOUmX?H6G0cX>q4?s*>U~h9Fq{8jQ*QE6)9y z-68285K2j_xy2P?FS8c~F}M}8omg)`7JmO{TmP)(u#R-BePWfmtxhH6u!x|jxf-=+ zo>{3yb>&B~%7{7fA9}~j%=oav`X_;lX;(SF2i$nQcCGkEp;SY#!5W_{zd_~Qe=qw>Ky+Oo zUTU{VFO!NU*=TgrbRuyq2vpBHWO-=OZ2`voMsOe?{Ioo|2e3oqR22o)Nq|_3uPpnI z-Aw5_-HTcO;R_e_-O`>ATUe1A{4@T=EpNNVee-)-4J_AhG-5wNcpAa|cS?%h!+KwE z?(0yQ4it@AQ-b2fjOc7X-Fey?wB-adxG7>EkG${Mde?8tZ>-@87TB8sgG?J!ZqROL z=A(L%L2zWZ47~jfvKw)sDW@tvpd=N=W25R=pI-~%Ps^dviOSHF77ggK?iZ&M_1&Ek z>DWa1RI%ytOsZ-;k612@va^Nhby_}770;(#w)IzC)HBtX-+-l4(=$5rcjV*y)A;{iB}N zCxjyyWrVf2u!m8WWk3YwxmoTN}p|Zya$0u!z+FqxQ#ZL8sAw$-4(` z;}7B1eNot^KLK@i!8NWL~o;*u2)6krN^eMn6?{pw$ zoq6}Gh)|v-8*rn_n#%`K(f6~ll^IBU;T~mQ&e%)zc9BMEZq{&7*Uf{15f7};=|B9Y ziUlV+-9(+zO=0=%xLj+QBWZx7csMkrz1wtAPFs&(W`S#Ov~-SPbW$c|App}{Up%Xj z&YDN()9$1q(I)fm{9=IOP{L-?Ue!5XT^J9xGdgS*xqMn4mH8+YpSWoSqSngar`)?7e3rqROnl`6Hh266uD7t3%%bnOZ z+y|1{vCi)vP<2XdGYhGkTi_sFVko%*ROt4d!T*+Pk9=ppsbZC}rqiTU3+h(n)qs%E zvy#TBwH;RRXuZ4J+}QKT7e~5{>B4yMVCfy!@yIarR$e5|g^~iGqErylUR-j##ls2# zvgD8=Z~VtFS5kkpn;{uhML4;gz%viig36iJy!K)o{P>h&2j$cHE}fzRZgPe#_(j$$ zXmQibJ5*R9>#^g)?mXom1TsZUMcS^-hmftmH26sxlt1x0#jfHrUVU_ksi5a|lLD5C zs;v@=%=^M;1dcP_Ub`a{M+uXqR&-nFFCLcmprAekH@q!-#C96+e&*r&GM3orXg+a; z+#%*Tw^FQ;mJ7NHy&f8I_c@1*R1A_0Gd#6A?6$AW-`0ElJt z?Y`gxMbH{RUA6gnRMEa%wz{bGTwG^;)7_OVVOQL~5C7%a{Us3+x>N zEzo>%Kl>QxH%jAYo`f+k%o^F8N8*X-oo%R0!&*s~64R_U`a2Mr5+7x^K{R0URxrx3 zXT)2()vu1|14Fx>x}s0zp}scDSj*xF-7noH6*2WiS1yZDmeB-!eEvNkNMo<3vOfAq znfC+cYQfd)Y5H!7pjRzI^Pv+}NQCaA?9bRjh|8C|=D<2*G%x!*HElI+6%8Jg_yBr& z#M_x7aNkVELvNJRj+6g_>nVLQnR2fBVJ;A~m3_Vy zzzV^{P;Ox;9)uie8&;!1?WXl``T`WAHdb8j;(B({1`jtpBnS0~L6+7nC=Vc(B>3(h zsXnX3pF025z3v{rg2UhtLI1HwZ*b%IQ0R`&1IWF+<>S1@?NkA|H1dN!WL^rA#d^?? zzccW9`py`-x{3*Giv%}F_vmXw{qiCdXtj$P`ufa3jtO_lr(fw?!mLrzR5*7HS`ahr z<6Ng0pv0ccgxWMfaz9A{k!UPy(;uT=ESYBZgwA7Y#B{Pj5RZetad>2RveB$Nr^`8e z?hu~A2!XKTgI%F=tYC#0qKJ_$JWQ5>|BByyFq#0rAb!=d>LxzlMowHdJ+b9r1U!1Y zSAqX+gd9KPuOorx_nFim?;8(M=cU_+R>!-QbY!EWJCB^nM%`~YToRtd!rogkD#6i2 zS}!IS+dS+iFRN6a%r3aPgv(AOyP`ZQE^5(0JTHEOuTCl34f*ac?qd`F4B;-~FZNqS z_0Fs&=)sz&l}S5ZvQu-od|k9lr?<{dYSgSzXKRq&?}Yzdas1K-dTK5{l+|AOs?BqA z1#=Pp{O5RHP#eL*J4|wGx8z9s8`sX&{#Y=PkDL{)eEJ-r_{HD!?<88}prO8#lWOh1 z_Q4Mayg%vDgr94@&%HJ|Dd4wnj~Q3PM~8NygC0D9*5e&L0SV)REE(STX+yzl?;TyY zF%d6~f};zye~hJy+v_#bJ?Jx@jXmd8e-|j$oIlodo_PFNL`WF3c!y=6+`Lwe_Xa5p z^j*7Px3Is5_M=LVX^eT&V9Y>+v%>xPBiI|XE~pIs7+IlP-QI2~Xj@~aqS+GtAxBGZ zJ=u1d@~*o}T>rOKkvx83-(T0V>D$U`&7$l*Py7TOdd)on@*r`2?03zIW7DG^-S26> z3S9_T661GWX+VxFsBVION?{>zbjSk8g|Ky#9%A+sUT%}%ETyw%E(C+!%Q1TG#Bsd z<+lXht~|adUkd4?k4xF{##pOD9Vw==)(t}sHVHWLC+*y(`IVW@4tikH9gsG6(c6U; zd!KSfw{K&Q1wb3=X6k$JaJoeGmfH0nhJN{Qiu+B12`zpSFCvObYskd#?QwA*NHjg$DvJB6!)6UzzAs@VhqbFhd zr?QFv^hdL^XwCT~y5n@zw5?%5Z>l$G|LJ;$!bRAr0J&FXJr9J|SO+U0nCEGG#YrO! z!em7b=A+SOlgWE_U2i?8Hy?{E6;%vCOR!-bK#5&@Jx}3EQ85n!+#0g-q6y0LV+ykI zWkIuM$s9tPGF}GrtBHT6@qKi&AyF}W8afiBH`=urmcdOt(vLfavMLWUNlh%=2(tX3 z`3;!j)>-b-KBbP&bm;=uqZ#gqxee4;`m|N6%mkgw+tI8zH0768ibr+iF&5dL z5?1M^RA?vCja)r?z3B;ky`k>EmsNB(<2Na4UAn^vF_Dos&Mxj{uY1D%9=>$NqF43KW6w^Kbqn6u%F^qo_jOj-q-NGmB=>*FQUEosJivo=a7Gsee(@S zZcG6}W+uE*Z%E~Ej~wuZdqIOiz`qeu^&9ts91o=z{QD2PkW$QEY2BwlI-d{o!g`h6 zzf`sF8jNs?o#1hWwaV-i!kMUT61YKVmzXx^2wQcBL6^q$in&Ea`KNAnU6em%$XtAV zeJzagbq|{ljf-Ltz$_So^4_7DH=+y{QRTW3a0OO3rI}4oiR5ipgCrx`=arW69h+-Z zKpD}|u3_ckm>ic*0k23xZ$ZlOxiU_4O=@pmkstB@xHUss${LkW*I`sp~f0-bqq53);1c?$DIXwvk4wTt5AKM04 zp-6Gxfs99wHzu+hi?+kFBS?i%VaM^~jo>v7BjkHL!-J;@JJwvb->XL(Fv_|QBuuz4 zm0X@z;r80i}lZyY(SppNipn! zx3t6(*D|MU-LR$%n}mFh7h%+Ze3)^BYha5b!5#C}__*r9bi~RgU8%k? zorgiyLbrPRs#HJ?OGVO2qZxkjnXOjake>P+Hz6<_Zh?|CDNjgLj`*?V{c+;MQi~e3 z;xf@h!CZD`_1SlbZ`pAMSY+=)nY%^Aw8>6ZbH9b6jOc|=o8ZGz<+$g~i7U?3FxutG z(U8`6MrQ$_-=5-ib{u~%_!54lx57oV_X}umz5!8qIEl`FHx-7XKq}02HqKbXu68Dk zLYfC16SXPKc`uxM$5DC3_!mbcjBfN_Qtb+Qyh9HDKiz9#E*$ExU!a8U)uB<1C_9y$ z5vwu0%^$!<1~i+Ei%m?(Oc9z0s?s(R$Y>|=+&xhKp}+c2LWZ*!yBn;&574wf>@8pR z@z^XGsp$Y(Hq2oD#SYFz9*O(V{fm-tn1vXj=)Af<#lTcnCL0+7bpx__V7+r6X%+c9 z`^k(96i$`(+z0V0i%;3^h!y{1gWdQ-6GrtVhID)-AL0qxE)K}xa#E#3UHD_^GE z#}}KeKui5@ty=LOIvjqWI~&zH3)Jko52K2{7-RGT!XfMrKm;@g(oXB&ZT&vM(0Z8N z0@0Z2+A|bG6m{`%+vzz_0#C+3Vt7VI0i&9etyJ-kx$_2(fS=R&= zTrtOov$D1(c^n@V7THC0D;9F|FLQvlPsrUC2OC$XkhvRjxJa+{RY}?3(`9*9x{E-@ zmdcfy<$zx@$`u>%MsVsuCmc6~jL1Yye8MxiiX}?R3pY&oWWY|qvC!I~&f7R*2OAWL z{*Gm@;%Flr@>eWDjmPr1Bfk4DoQuaQ3)o+=Vo05RhpOzDbO)`xc#-45%<|)XM}3z~ ziH9qGt0=orhgHU2T8!IBeG?%UO{u{b9InxDOh@W(o#nU;)^nQ7fY8z=6b6ox+%nzI z-sPU00Mewt(LhY+^s_ZP@h{t%Ficy252uGfj z;|$LCy9pp6W724??hB;*SZ2cFz+VtFe3>((W+>CoP#IfAU9;9k3dPF?9{lY(D!t+#$)Ztccx39$v5363Qdzda2veF71Z9zt{ zGV0jOrmXjEzkg3NU`@TWwRa@HkZh^8H|ZH{B++*0suoEH!`E_kksMiX=I~44r~k(I zx#DykJ+`{bfP{J+^!~WP$SRJAzmDy3v!HyL`rAVapj^tBSMW02E3*~VZ&wvWCmw|7 z;EtZ4KZ<;cvtY!!&~9qetA0IvQmHy)M5#LBDNV-zn%pUprKfrEJ#zhx%`*GaWukX) zA~3McDDv%v7DS3+1ckmc3e>lepryf#e=x8ZGW6WV}`N;kz>naXv1b(m>HK`7LO&Mw>D~P*1)@$X0^ZI@7poyx~8NWYl!^tmoos zk&XyVb|4r~>`o^w?R0j#Ev!dpjpvop#>FFHl+-VFVAm}tFe^Tw{AeywN2Ico9ZwoC z>eksM3(=V|*EAJ5x~o@jJ&J?DPX1GlNh^k?Lc|-v*~1cbY&rW#r^XgGmXU&kdf%vK zn}GCoA8%s^iO;faV^H2u27(k4@ye7KuUn*ar`1>^@Ne3*BSi@C zagy)5-8mjD14nk>-w$|Y6XGc0TjL|WNJVVlIiZz8uNgZX{)%d2HLFW$UHAtp_!pJ- z^Bd*K&4ms)5j^!@Q>_~~B}3LXed9*{eet*2_WQ(Jrn}yq&My7DDbi3`*lpgOJTxM{ zd%1OYVDWWKHWL~fFEE;13^!HbpFMa~qNQa7DDTRJpNpf~@54mspps#xwt}^{f^;=M z0NnwD6nFf&U35RtK%21vRE|C7kub|T-8Y7YPeSCWS)Jo*{ZLiYJ-(m;y7k+!N%`N& zeB|0k4UCX|plQ#+B;3XMYF;q(qBh?$^4jmXKMoyA0NRt#cZe3R@uPF=1U#4-szBG) zJgg0jdNM^MWjP8~y(J~)RVXe!*7d84JuQ^+IN!K)dQe|}U*Bcxzflm#wp>7|DdO7f z#x^Mm)v?E0b~j?Iol(SW9XprfSrdnR&Ui;W*#qBZWEO-U+IckVSwXxjIEiBOuJYa4 zm6Q&k9^E!bA!7o@ta+_Uk?r#szvlvP00{QuhO3$c-bg&L2dV>zidTqTjUGrPjr#%B z92V?!e2HeT;4Gw1TWksNmEP&Wh|kCnGqQ#0DY$l1go|2sbh#z8rI zmY!bO2<*sNMC`*D8AOJwoX)-8H%IFi6Wm2x{1u9F96&5Vy^!|H%7Og@JIs2_*!k zg^e-UpMjv-LYU9jTP`1A`{=gXVl$~kLw)Qv#0>u<*{oiI&-<@S8uN6!O(!K2L=3cw ztf+23gjxi#E~LG7X*_;MaXY&8PuCZ9DIr47#}~2KY1w+EpIA*MZA*9TbtabVRgALY z@3$`04a@Y0zpYxFv4XuHfAMO~(UNdFh~ z_L*aLgU96P;(J|0|9?U_@6QK$wZV2k&p{3v{8ZcATUTR4yVlbl((q>6vOaXs`rnNM zA9$tCBXaiZBLx_LPM^pJZN@N|@xT`%Pf+f;EmdG=kbpjzTR5RXXDbM%Q4>)LWa3|! z0!RU@a8NA)XmATX-MU3xg2hgi?s#CpMuv#oLm}>Yn8jG5L{U)=v#-x^7C~BP_Q1_mFTh zU_an(x!1eH3teUgg&)T9flbNJjs-7$x0VlhpMlUg#8Ek~Sv*Qy7CpN0;aXXiHZi;Q zKgFdH-yu{?%)87C4OFFW2NnZ9Ngso-3t#O^u0^F7j|jsr{Q)VVZs#+x1XE;`sy~La z)73#INx}!;Fu82th3^QswN7gMSe6y%@Uo@F3&=-JaUX{wF>%lJtpdB-TlP0q@m~WU zaTd~@#EfE1{LA~v&%SUw+Me~0dG)So%N^QC4t;x#-__Abcf?t&B0pNm^~AwKjcq=B zZ_PP>A}Nd3`@uOVkg2u%osaahAYTyD;cnXJDBF`<8$Rc8P{Ik9UR&0xv3s^=N(=9z zrc6N~ZDcC>00@;(72QEQ>+t00dZ$G=K4W8zdY-{XX_Fv!Ez%70P<3|63Zj@fd9Ik1 z&*EL4xuD4O0f*6iq9OkEdB47)TmF~TbD6Q*E#1;6I=1ALmsO(Ls3y8vtQsTQ!3Gnw zt{Xv9%WWi-dU%Iax`p8s?HLiQ*dv{oajMxsg7#Je5b5nfvoxc7Ggz25%E_`HNqhO_ zl1W@ammCD^PW`2k_Og0U)=c>Tm;l0wPrEI4c#$OanZp8W@`@;G?vm|N@1vRj>+Znf z@*$_V=mNzzfmLE z_=;3bIRawpxgB@eM92-$%eFmlf3)WsSK7O$WzIv9(jeR~c^W%UO+ERCWZ!eUsq;WJ z{UItl&z9S}??O))Xw%}39@0{)B@6RHxx@ER%*KAcS*F$cbH*1n;c>OgVLA28?H{5R z74vC2N-HbkFi}du)47clB-q-$&BMzj++R8%?qnEuHukdi=G*42lR&;-j@~6%RKl)S zsj9AR=P#p3%IguU$6*nv>>2U5v#Tu!R!GB#^=7?;>eR3$m8$e^IVxMU0oa}hxdAq3BFlK))b z;X3Dy=*YSuDzz9$44Z8bf3C&7y^r`;*aQOG49`&C#MaeWc`uqchb|mV?>n%O0vps; z9;a#k35)<68Yo+9?f|dR)=@(vSV{C6V&HYkov=@Iv{qrHg5;gL*FdocoR!cGI1w_~ zrz2FjTZqshU^62&OHn+sRMnLbi{9@0j7=@BArIqFAh?0ewpYYbRXw89K*tQc>sJyZFD7~~VI2q!Gr#+2hEn!Ux zwmkn+USg-Td?FIm-VWuhM$>V5Pq@aQ6Z7jD=&%^obwT783Lxjby_eZroY}$jUtNzs z%KDuHaX?jMDSl@w_y0T0bYy+$xNaBkEfv>)FV!q@}SqhK$VoY;CpCi;w^ zNBnk^>OTIkhwg4N7!6fXq+1p_FHkuQ25Y&CBY88ahE@>W_)o`i*4A>svVs48PiQ!B z*W3OKrs#=t;(wAbWfSf7r^5owq8OcDAv5dUx=G6ISMMj<4Q9#AqmFhKW~xmP)B9CF zNx6E)V_A=*LBR(v6FbQ8X7Mx)S1NXKnB4tr8Z6z4dwVC^{FI0^4|TkU&}L@u)rHJg3-RA!FD* z9GuV{;R``oR5C;)-WJyy&qD)>8ByUMQVP=2;iE2?#z}uO)+;ki1cof8-}SyoSEBSo zaT?H3k=G{43dAudXHSj$~ zBgLK(E#yR05@ySRGL8Y$@*`KII=Q2*yE!r!h*u9O^|zNXn~9X3CxUnCz$G#TK>);% zDx?DBKa3v%+YhY@Ut2Wc;R5ST(T4h@z6Rbw z|9(Dua3KyiQ2zi<5$R_r1Hp{X@S@^xBi;j4YMAmCnS~cx>0D)8ex0T&u0NLWO_+Lp z(LbRXe4?5dcV}xa6fB9~FE=bZG`hXL0VT;0>`;L_2a>nF%MSK8oJqSMjo6=s-G|w_ zzpF4uGz#J$rqXVeZzO2tN!6q*O+NkSKsjDw-NHQn;iYIdA9IhTD@1!yx9Uz?jL@@7 z^T9Yj${t!GpM$q2kxx79&7RqxLy|v7U5qu-9S38U{Sz&D#lMPg=Y1%Vqf|M8Qm|xST=XBI6pehrrk_Sh8h3FTa*$xc0{K* z16uc=Xgr!O5SIealo~n32B@m^AsqaC2RX_+M0#{xtg>D*@^^7r$!qwTgvj0>G>14- zq#*4nYNH~iZb~+?>Y8d@hm%@PT`=kMwkp``D~Pl*>nU&VJ%3IT{eB5?hZBlKl0yWF zj#_`QH*SE%Klx~Vp3{Ay8D`NO-SMRt>l|-wv4gOrZyv*^`i2gH_KE0hY2db7_dmzp zD&R#>nlrf(hz~E(Z8?32yc3LEDA|pJ@?vx-Hmc9dz;C^@nyXGWVdFMDlHox!gKhQIjE5}<-rh1LJKQgJ9iEdkWyZko!%_bgKz0S@@JS!I`rJ@IZ zwX#kKl*=B(u|GT;yG+TiW=mB&2hqaJZ6qrFb+n^9WDk=ygFbg{)CN~^?7 zbPV-%&S5E%Zq>V*LNj)|Z-{}BO=Zrl?XA7G=sLQoY;(Nx5DWau5sZN~5J`jCH}ea<3P=!J-P+I3`8S zH#4KMpVuT^-_)$nb7IMPf+~VCBv}_q{^_qP^2MmqP$&nq5{sa#jhH``n#W1=s^KbG z1h#WrZc`!KY^{v9W--Q=7lDp>=K*rN*%@9MyTBv~#?=cji4^7S-nF6E)IPTT8GdA3 zV_(1|_y8Hr8}8mdKXHCi>M=r-p-1_lJ=qhM@6%06p@^KR|BC92`p{#?jQ5rYdCjIS zA@jxd-Ht}z=0k}M9yY7>Z2&cd_1EKW>;rYi!4=H5kl~Rrl&nA4-YWy0< zw{~nD#~WazEdoML{iK^L7O9O)}nx!)c55g8it#lof!h+ zF4F?_gl@gOgdRd3BqQUc2hYL{F4lC(%r+UVkM?UwPZstHCg9|H3JYml!mY4J{sx?K zsDr0`tm6yw*>g?cj#i43mJ5aK{7DS(xHHR3nOOzNFcGojW(nh)_u!;gy1GTX z8-gIq?n!ziNhwtDg?5}jhfSmTiW^pPp4~$^@H_VUnZ2-18q-oS{W0ZWs!fT69qgNp zqpP*pHZohTjZ%cy-fnTgomK1Fj8QspYx7|NV6DcM7JANjsti{~r@~w&X=BCYcp`}j z`LVLX2(Tb1$NL5}CaXGC=x?c^+(DGj8o`%j7WZ)wX}K)@f{W9Z6xdiLZyR8x_TD{? z3Tw)U+a?5N!Kt#?39IggOJJFO&0mCi_@!LXQ5lEEa~@}%qi?#@ie*k2;WRtmpsc;f zBxQy+-zoisTQoY-!;r^s$Cp-DQG5oWpfdwZi*c6ABt;Zw3yGt+iBgs3!e|m1?pC7;DSF9aihre&fS#HO`rU&9M3z54QQ1FB}6>O3pG^ zNl|I{L0OnyQawjanNptb+s6#v_ag@0x5fM~r050Lq4uWE) zmA1i^Bevlk{%c2TB*&6wHUt#Zm@x?!II&8Y!A-Xe+s@yFka+xv&r%H9-R~9zIVO#! z1A?-vKcZ<458od$4|L}6%v&cp2h>{?`6MlAK}pN zVpwW_#q`d~%79@##Rmi*`fWL-`t~n0*3bq>vK+K#NNy}SI< zY5=XF^?@3W83+2qax2MBta7sa|3>y4>QMfvsGq(6PD{qe#nnxU{TkGL7%yYeeLqo{ zg@6TNKz@dCHI*B1AjISRA}7^j$||R#yd$I)MWI}lB0)k*vtba#q!yU_3ykn@c}vl^ zlf%gEwvu~7ToldN>b8=sdoB_a6Y=gE31C0IJzeS0&*DY9Abw8WGJ#oDWcW2NZC34l z8XHGU81#CMa6#UDi0z{NWTxAci=k0yr}m7a$ruZwiX@3;2>qfd<={Fa^b;4<=l8Qw zK}e&BeaGA0%@is-`7_0onK~1t0-ZR1s?9?UA2q?!+cyc0(tE+j2A$(m2(3mLqizsH ztz`tpT)7c1&TrYB2r_pBiqN?%Dz(S1_9-__GhDP$%x*SH~ z&yL(=u^}D`%t^5%8W;E67S@}6ha{3T5t#BdB7mbz-O+S<#`-+r>sZQ?aPvO|z|s-( zo-%M-GBXsu2egyEk8WpcvE~k5rd$cPO29_kYVHoQS;vQFV4P}IioF|@y+$&N!-Xn_ znHpxu$31`%8qvPv`W0!Bei#MrVK`%dZ{by2u^-QkeU;gc>Qh>6$_G(kQ-+tTWT{Xu zrqv$8-XHOsAhw2D4m$6m?SXHqTQy*w9~DGaOi)H_uruDp5<^z*adJO!g$)2Bymo=y z&olypTGSknr#?lZJ%Rllv8c8n+#2A%m}tV|k6s6rL96p9ky?~6Fr|hja!P5?0)0Z; zU*IV}b=9mXGg=1ljLO<2?{v!1e^ZF7B6#C8woh&!pr=sjFG9YnlYqs5uAeFVyql|J zDB2kC0Y`-V)3cPpruz|=lYBJ_bjTbRnPp`2CNM8bp2h;{Jzry(=L5%?N1yN@#k!XI zj&3f{7v%SZv{H!?fP`f3M?ix_tp~_{5>U(0Vr-TqGdBXS?d>#aevXV)j#mA%d z^NdzD5KYhUkOtUWX;8HLDZq)+O|f9(Os8F$#M2_9OcZ30u`mmoKylfwwBh?xx~$ji zCO<|u!GMCgr}ps8_BnOTG(b_H9**tsuLmH=-Jj+kg={OFiI<0^k}{;AQtiWM(=cV8 zwHVq|GPA7nz@wX53qXmbly?|r(EyeuI~F)EI8PclJLK`aAH#cT(p)SO0K5ySDdKpQ zBCV0rqX`);ffN})TVzWC)0Q8&1YE+uRWJUnht)PPjF8*ncRh)XkB?XQY3%j$pK0a? z6sZK1>USs;_H4r?dJr188xPa5hp{>wnW4AmaQd#Ld`vsIaxVOuD=K1CrG-6mDd{R* zg3o9V#CP4Z%^{waV+2qPw)NibjXFBDb?7^sZ#LSOP*fIKL5nHH`(tM)jB*b_0cgV< zf4a`AnE!zvyqq4sK1UASqVEP|Yy=au3afwvQ$jjc-?~+R(bRp!3pk_7smXUl7oXEJ zS`*fP;GpB-RSx3EZBQkI9E^2fkHYC;z>B3BJKN9aj|1e9afcB}$~hyHmXB-gA*H1~ z=UlyibYT76I-8ZPZkE;=czV`Sy+R*8zWC>rJ8GDrMIB`whBY^lea)Z=_ibDc zC7ge$(uhL?eYFo^_(Kigw_{w1Z5S8$9{QB4I9MWOcwQJmbW2q%OY7AYzIZ(k_w~dQ z=@}LMS3R#rLGyywdw&Mk5qVRy?q2Ww+x0i<%nI5S80hA%m12yhxm-|~rYtVM;SyOL z&3i-|<|IIpWsgGrlID_PEDZ{y1!PX~A7%s|uq?AZnx&r!R%ml&_h@I77q#1cnEBmjQy8 zLtFX_NJvh~*eG?5qwS{uq>$KB5)P_lI{Y*J?#vgbM7HHx|Il#hMmUrh*`!4eZ@Lsi zvWkk2kurO- zV8w@9vrJ9Ma5MoCz9a@_vIxEmobB%Ob4)6hIdfIJ`4jIbgpGc3&ij-`s6~et{2Zxf zj;^ye(g&Bu?OH3)N@KL+CPzX6%Q66sO`ie%4x)UaU7YJw5IC9Vfj{Je)^;uri7%=k z%*_5Z0FH}H+_g%)3FO|u=(C;dw% zbJXywjAjLeF4J~4(?z(X8$C`eUeJjC;mwY23d(M8O5`knFEHZzy|_Ce_3%jxWGhKH zWHPW%0x+8ol!i*Hag}H6bFXb| zbSCZT7ovt(4M4e{xa4hX8~5@qTEAH#)pvH|oQ1bW@f}ZX)aags3zx_H;!q-|bE7-_?WCoDkz|5*Sn zYsI%h?D)2Oi-0SyR&i9Di#aWe-X|D}eDI|gys zbf+EgL%dIPI4h?R@vF z5UOzou(Skw=fm%@{$T|Ap$XOU{oyqevI#1b>5jHC#<;t<=={9f09?PH;=C7=`*(zh zB+v6|62R~+?Mr3b%g!dyx~(k=g#`{#;waJ3gHCDbkNzODv8-gN^}{o3%U0=2o;vMR z>*E&3;19RD>P$=v$D{E)4t?_~(KOv2+POBcGh3mSA4uqz7YK$~d9a;#K@(C!z$i|H zaj6N#uAGo`xL*K-=up&Ogu=~@ zwaJ!BGAJq$X5wsI{9de79q#)*y-B7JuWfCG9IWH+qF{%FfkxV~BdnHx4eD&C=wl5T zzqk-@la{Z5aPtzw+3FC%@|}{%X#1YyDY1)5{J;X;ZsDJJIiFJA-1qSx@>}H(P><=% z>p7$#Dbf<2@Px@_>=FL?QC=&1R~9_@2U3U9#aSP|eS^wr^joL+BU@d9H?;AMkoK;T zDb{V3wiGA#z(Yod{E&t{9k&^22wboAv3QJbPZg(C2Qz`0vR z+FQHaBaVT?T0zVm74SXzF2+4o6^sigwV_uiB0~iA#h~o!Icug1gu>#n$2km?zHh&k zhGwKaqv5R34dW~AR7K~S5E<3XD@|#!@ilq9vbNj+ceG32k-i^?BjU^XSdmKk)xy9% z*U@GYH_FkEg>nbAQ4TAmYGYg@Yn(G)t!Rxqfs$!lX4N}BJ+N`GJN#czIeMHOg3hn-}=p>L;%j5XxzRmh^DM^E+9vBVX_JBE5d_NFz))2lJk8-3W%k zD4iuo_}8AY<8gcMq4AYM&cyK}uIzqQ6oYM*OQpJLDreP48EZ+%G@Lvz9-)1zbKzP8XZg|`_s zu49h_UjE(!(4;h%JUEF|zxAUqdw-_AUh%e}hKGLH=F-4c{~n{jw~vJhZEmXnH1?!D4-wIeVyiG)8(Am^z^2xAxNI4=sSGUS|X^bVAHAK zDjPjVKbQB5-S=fV-vmEk{Yq{{kxJj`qp^#jrwA~D!jsegatI@IiAOdGg+YSyci!MI z9_iozYH>MJEcoGSgi>F>@o)L~bau*RvinyY1=ER)mao$ke7ljH-}n06SE!hT{v&nR zNecVN=tA_@*FWB=lwb0Ulie-Etfyqxd|P#WIO4qj(y7L1(!D=~jaBO1UN0*Hy;^DXiNtvoa|QC%cvC z)EwuVa|$6Ob>76iUwqEriG*B@N@oW|Ip3t??^t z<{T2>NAIHP!yi7zkw|H?_y9g)H_As;>WH;aIqRyAzvTG)% z@GAYwcWq-s0gz3vndMVcON;a;oels?l*?B%Bfl1AK0YB$aUZi;4A6N5@rdfy5n^Wy z+ht}p-WvFx3aTU_H5ory)Z>fvVggyGduW<;MyC?%q~lBMe?QLg@89pCrc4d>`;y6r z8d}{V+>zcH;cD-^zqkLkM(M-dX0$V^Mb;2rt;~Gw$aG%iY3dN|u6}^FM;bYp?Y@J+ z2N3P$B5`*O`gRI{-*$N472y4S*!_@?VidFIdie%>kvsPVjFuoyGgj%n{M{fflX1aE zD=KigkJk;z5UR_j$=`j3(!M9^uXjiAHgYmh78f{4HH~KPUPa#UCl-mxvj2Zny#-fX zT^FrcMd9wQ!Gi~P2p$L!+}+(>3J4I~-4op1r3mg22=4A0+`8WH_U$qHH=KR;UNYx1 zIjl|CA!w93ln}t>u`b0h%8E*n0KbxoJGN{$Np!@MU?vU%6=>UgQnb9^?&4f@)I3nI zHo~Dj;tmRZjJ`$A@$0Kkwu(lJCW3#y?32+*hb?R^i6Kod*v4`{4i4Mp<`4jmjD6wd z5H9WQomNn7yQHXy(&BsG`4dyGWopY)o=74Fnw}{?ORZqWs9cjZ4>E#wv{^Nu<`s!f zoerWs1f!>*dq6@6+-8us@=KGZqFzBu3Rum7JLVYL~<3^9yHzC6<=6OxB;XK-?vPsY0=ZGU_cyHX(ppZ5(SQd&T~pkN(60F<0_m_AGXZ_ig!0Wr0>u&|#7Ev~2%TAr3>yH4_3WSgBTYWe*S1+p6J zaXkn-Ju#BikUq&5D+^l8847J?Z_Wa6FUR@;}T(xoD8 ztU`k?+CA2l>FX(@B;DN-4TwH+g5`F(M~HSqXB0I|@Co2?0nWBNZT(hC$2fzm^9MLs z-+4E@4RhBk>tKjL?tcx|#MR1)7xF*iaXqNfU*bf$a$W5K_)p>!u-1yxAP8wAEgJzV z$sl&Z6Mq>u>Tl=$W>0y?qhVm6%3m!p`d1uW* z-$J`&c@3HWNVYJ{*elaTop`SDBb?#!Dqnt%p1M#6+CvQPXjd5x4O_-`C#fEp9l))} zz02AD!`Y>H_OkC-I{}`o`Afb7E+dl#%yzNT+&sU>Yz-H8rsgy z%3Oz;xC;WOj_an>AHUtW2}j!12F#1ZVd#oOOUNIZRX)D+XW>cmfO9ozsxZz7z4wK7 zeqi?fx#v9znmaT_I>nb+`%wD7hM5f7L+Q714!8)`!a`vrK-?B20hAY0?I4-`bc$}n zXpEds72K`H17B2SbO@B+WXXLeSQFrgFAr%iw;mgo=CmKp6TfpTA84Dedrl__nJEJ&|bihn@tVAmr!i)4@bY5GBI+q071D8RI-FBNVr9|wB13dcI-LU1ehLt%xPcPZm9BR@&iQnP%Wr;Y8K^d<{$idRgWsm%fnDrwwHHjHc^CtAeqbiu<$1miIJ=XrpFTuK}jH1)PMS zEJMe3^a!!XPo#Hx{mS~)3b-7?0OCohQ(Wxr#sPs8TQ*hY{zrs!I8%mQ;IcAn=XL*; z%a2h5ge)j6E61S!ZieUXeg{@&=_EIm<3iswQuS{x3%ymeQqw09b|HrLZw^Lu4vrx( z>eqJ5dx==e=I~9tg9abXAE9xx3Zf?3GzXSXxZ4c1UdfVS{FXvy3CJm9UY{)U7B^M{ zsqGPxg|3K=3u+{Xy0lKAnKnsLtnI_&Xu~MU|KBHOxh&{2GeT_9nNJ!MSj)&SGyS{S zB7WYVqXp@MSODW(%}LvKnrs({M=6d}YGUwwUR)#SxA%%32UusEQ_E4P_^F_o7k~xF z2qaAV2>BfD)kP!E!xvzKLpq#@`x#@sfHf4M;-OZtl3d+-VB<2;>uvo>F)2CM{Ze*E z0B?l*tbYP!b5>K6*LmtGRB^e*Dwa&I(WwSzI39o#%A+^Y?f<~=tJY&D>O?^gUG6I| zZBJ)IVO)y7x|P@>bHuw?K?CAFvWiV@PA1nSQ;#wAcLUc?xW}a=p?}aHT0Ut4StD%N za(L(UL=#>4?}0BukIorFCCH9698yKByk&A01SP|sB7wD7>Q3hr$2WntUCi1YW4nx_ z8u;+ji191G+yxcZrYz8>k}8xk36H1aSK=?aFV0x5i`yr@b^RdChN{Siz4P8TKY^YA zg2l(TsLOgPrO(mI`92GpB_#8l5B>jgY7Y&7d7CHhZ&eZU4HrVPiN}J$^%S zXx85rL+VLVivzEM&oc5>6Hdx`s$>n)p9K9I1-8=#rWOVe1|yX>hmn#WPDxeU`SkN1 zkoU7K^SU!P@4P;hJUa%ewMQ4SR8l6z$i?oaZ~FgVh+1@E8{A{>GtJw1;QwioiT;V6 zBSFcV2jwC`5i=J0VI1|S7-WKj`Te`;>2b;-IQikg>=ZT_?JgbxmeochUlVn+h{ouE zI{6BXs!zA)%^j5XviiNFb%~Z}7D)G9s1uyq#RbWIHpJuO;}UU+X({}ae59Hzdc_to z#FR2IY|)WOP>akz+Q7U2wz)f>EzeLOPTm4J!4 z8u0)L&`m={vB6H@@_3~GmqA%Y##dkAr!1cJj2Ww)L{O z0+2i#d!bC$4Sr4un8fNy42BTx9q;BS&9RiL_NSx2qwr1XezK$(V@QkbPd7MdEBMFR zUGRR5?AA3K3`dSHN|tr&c3I4xNkb*}KaKs-6?GUl6uhM^XseD^OTt35nk4ux8?F#ZwgM{sIg;@Y4d@6S~S+Gn`xbx7=Sy1oXB95d~Arj#O$fa<0-L-1-r z_(>*&xlZ7r+_ar^t%hqU%8G@-{!Anu^C<2|twQsEQTo@v^)Wrg=rkTaA&@*04R`D| z1M30B3X1zvd5(%xk~6RYOgCa+zebCoIDK{}*X3AdG6&)-2;z zovH;sa!I(@95n{ZapHOHoRhz6$EgD(X1C2>Vpyyb?9BBORsM|AkbQ#%52w&8vX6f| z5Ep)NiVDu;nuMFgBD#LMg=!T5`rgS4q1U0ruU`Fu4^d%R3HB`+Mm0|ssfor++}Nt*4T`g3 z%^R1QN==TDzhlhRNZ>f{wVv2fiVq9*{Fw50CUx>6SagR2%#Jz;gR&1RcgJZo63c5* zg7^la)W+=Z@YkL;+xUfN5wZElf?(9vlosoTsz+OhXa|mi9qa>E5+X*){P)_A#Mu)u z;Lvre(Y77QG@duN7HJjKSLOy?~8W;vC+_G`s>Aod3M zxpM0ZNWwz!P&OCM*N*D~|KV~qUS<^S2K#{zFZwCbjp=lxCRu#3vtu207zC9sN@xh= zzZ)rb2VDN}H&G*hw(96CWwoTRUuOZS=oHE(_3!WP6XnA`&|X9DN~t2T0JtTQ?nP!+1LA0m&jNdprS7Zt_OvI>SqfUaTGr zz4sRJM+gr(4LU&-_~XjLzYO+E`vZlDcPL#c#Q49I*DZeKU8B*|cTdqaYL4hN{T~2O z{XaROi!b0mZK}!N<#xGNZz7F>Jl}JE*DqqSt$!H;{wXwOC~H9^*6{%ta$LWNP!UJz z`6%KCC=Z%u7^$HZGGEfLyGAdljSL#(3w0KhJ4hT_=t& zocuoC@-h)%%y{!<^xvjz~5Rvd)^;dEmkwH9F+7v}g+}NhXgj^7wD2AZkL!hbw>ZzP^bD~lR%Ji+P zc~3EFL^KwLIvsEGt-$3L9j+gZy|24zo%qa9YIN@Wz|nbP%_FNp&dJGl26p- zEAB89i{=n%rReUcD^5a8ZDq5T2Bk&|sOFT0zZWZSX(%=#8O|9LEmeMwPcRYtdMNtj zbiK+hBmS3#9IZ*CQ!iaKzJwJYY90%q|Iey}#$=&S@&EfQ4^Vsq2Q*N(l9AuRvNtGA z;U7TgVO$W1VFzHMXm*X;pHDEBjwM=Pgy*k`QOvl;Nf&iLR#RdNzhDJE8+81=rBRGT zC!L11wT$T{B&MJ=2R7q8VA5}eIto;TwqiL=K#6g^_$4wIii1P;o3m+2w^%aQ3oSe- z{9XWTh9)4ZGWK)i=ockT04U1@4X$-4?F>rg(y;OJX+YJ)Ovp&8h*rumR+DBjdP)c` za@zczOP}dUn9}oRoAgE4mI!aoh+PzY)zl=~$W8V~dvWC;AO|-F2;&ExCSpg3e$(kI z!eCb+g?Z_R@nb;YkZtK|?``d{Ua%U4zqvWA`UgFgjVZ(_q`mb~p>0 z=>QeGDAa#)3alKw;5hzoupeG%aWPogQPfUKR zzYBrZGqhJ5W@g`dBZ&(mq1()U1YK3vEkdKQnV!fkFhtQxKcjzvDU)TthFY3`DGCKKo@ZB{s{o<4%h- z=xT;eF%p=wQyPe30^P1{^}5q}0X%|Dpx)M)dT3CM=JFuhri21%Qsz33*kq3y|LIzc zdL~J+cMZE_~J-D__QDbtTj7bvELM$o0N@Ge zO~m^f6gW61=U66O1AYj6C+uezmx*PHkBVh|RH!q76UqMZ=>vY9>R$24GpD?HZJUQ7 zJBpvO>%Vrko11_fNJ-60b@n}m7&6=sW>+(D923bILVs5OA8>L|KH=JW8W8)cp)~oM zwCLcC)$u}=e;Tv43E4%a%?S8F_fL;T#D@$(m4Hf2XO?O?<(~@ySMybqwjLvca=pLZ zN^}NX``=m#|4b4(M9RAUUWNmauPAn|q?9S!<-7K1iQ*92HUvOZCH^%b8ntRlp=nf{ z5IT$W|1vwI>FU$3qGm%?z)UR|#{h4;se5!>md;p^9Gkpf4B*vwv@2$U%IZtF2N2OP zoj`ps(+tX*Y?AQ9AlT;_)e2482G{e~VMHV@t0iT(9Uqpb5BuRgZ9JbA@Q_7}ssJLg zF0L4-Ax0A2=Mv1b6y5djBCLMNHS`er)mQtCSxTsqHfBY?J9v1V-GusRY#Z%?FJrD7 z(eH!3?UN=-Ftaku99CK=R)^Wpt?blD06wL5@i5F!qx|o>j+(FDTno`|hC-wwZx5!R zb*m09E)y3kUKdNOcjBo3BCK6*CV0mfOR_&ekG>Ui36v6y@IRHM1FlA#*Gz^FlsA}Q z=(PpsO120p`AP8K8F%m~R`_CMObGje7*?oiv1yzr>i^`Hrfa=1tKA|1UB9CEwPXL- zTmqif*62r=$K>vWi!nNwC{c| zHy4|n9rGOC{@a0j$Yq795Kf}iG^&1~fe9-HxOUr&M86ap#~7a?Gh8zyN@8|h4)kyQ zY+z8QKmXT!xEX#z|JQ+(B5Az10-BgvXFZ!MS3;R89;;f$hqb%l$d8mgXkrx_<}K(6 zA+Zl+)lfIbO`nI}HuSAOn-HOpRoH3fRS245u{^Z|C*CYOKnd%AFT7nF65jTSy->&n zip3^{-M$Zgctioe;eeG4vC*7GROM#kI7I7I76x` z6muH#zb=C}5{fz9HGR;~U7&XWLO>*t@}D_Yt=_i%D*((xhS&HWn%p0)AN2lNjQ?Og z)&S2d?tq?o~R9 zmOCVX>&{1w=<%+Q{fxYGwGHST%i?>7j*+F;i6F?;#>2`riw4vuT%vL3#gFQeL|JNZ zqQEkn=}sf$4?p6dG7aOL%D5ESfM#ahX71t&Ki95k#_><5=nw=dm_$cxSJzhpdKub- zXrX^AB;^X{l!@i!Ix0rHnLytAH`}PreD5qL7TZ5Ae;JJ`RPF^`5ce3el8TKivtX#f z3#@n~`KY@LA0{mu=xn&n|L_%NO{L#ud}@R9YxTtLo40E7uodP#ab)78U226;wL49W zB$<3^U0&lPJ%9Fs6Yz#P=V|MZH<6uB?5w(NPeJpf<%De#9o=}Rw00A=9QY~HS|;dACH6f^69$Ksr8 z@Lvd!a~lxK%TVCUAe2zm{k8MCdWH#NTGNM&RmWZ_^j`w9M}y@B!*H+PW;w6xzQR;> zUj$3X_djHft(t?cuuMA~4;)((tza>Q=%6UDjsZB&3T;4iGK$2kl1X1*zo7?6QSzjw zS>K_*=E}T*6&IqT8`&P%RdyvLjjbczdt9%R6V3Gd8032Ps}r1G>^LCaZz7@Y0)(!MpP(cK?(Pt1iv|IT@| z>pjwdJb+RK^LQu2=lVe+G7bmIwA3bK=G4lHiY`+*GA!0TI>hTs|7ladh_hGdKT&6()ZB4&NnxZ~ z+Al%=0T2P?!oUfL{UXkRv>Xizy*}F_przf!k=mC}!{i+p`DOkw56PwA<=eKyl-Bxn ziskZ$hD(a9T4gCMJKBuelZ-VF{n#F(r{`-k1E<6(R#+4vvh(iVBa~4eR`AL2^c7?C zdNtC;|4fbFKIUxZ^`0cvwjX0%Q!JzuIHKqrv_npBn@cqbA`IgGz<(TGJ}SMc>>o17 z%gvkV&nDmyIi7`^;fs9mKJkBWu%#DdqXI^s*>cTTZOJoSNM0RW(ObN>iEK zOcw65C~Td|r(aqTuK$AmPf6DMbyI>F4m^}mh|SBWw`_#|LmxUg z0kjW$O3)9RE!diJNAeNOX&tsgJCfDo%1`9XWEGA8#OPjx%P*vHBur5}Z%p``eVc72 zzD=Dq-nygiFe9+;KNU4FzIoE?Wz-%YA5Z?B-iZ~QOvx4mkkgSE04V6-4Jy~)DjHSZ z9=Fhw1dA1cU&`n4uJ{CTQMdNtydY%J=>&`Lq`J}{cOa5}6^g%^l8a^@TlvFw^VEsI zE4?z2vu`5o_Nl?MCsgO#1j6CcE3za`UGQr0q*QZOC+Myq4EKEeqvn=xpp9-(K?amYbH5{K6~n;yEkh;znfZ{?Vba zWZ%9n#(Y-*czOIQsR>BX@xZ;twlypL-OZEe93~1QO z7`64iayRT&GNm290mOlnQVlX&&O$U(RY#hxD=snYB3#`FS>^7Fs~lcuP)~BF@YCTh zkJsCU6}G^~F>3qut0#_6Fk}$=NgO9AR0~*~3yOG4daO?#BEW?KBnp*i@O$3I1Gd-}t=&GhGKj$lrpj`c2 zE2RLWAXBBO*+aWL+#Tik*~fR>OK9XVPq6ck>JpIeWre1uU`MTZkS`+L@YoWa7|0c* zO0C^33h#w^uBzo)kL(Sj)?BuENDlYHE>-)HokPC=2_WF~EriIV#O*bSnsP?wR0>0G zCyZckc>r`$>DK4NH1}-kqwSeC^9_JU$0)xUWeUSE+_l6E(53c3IwE1l^ndtM7GhTk zR3l8D{Sa*7Ig4xBpw6G>D;iZK&AM2KayVH$t&n_@>Bsda|ka0Gi3qTd4^h9K;b;k93>DobfZoz;vfkauZ$VLBSF28@)Tlk{a@bv zSprQMl=}*%<55E6>*CZD%Ncit~Xx$D*I5CCUIsA~~mVsy2?KK@u9rwje zUUFu1{|WVSC;VhTgef5gZ%K0W*vO-F4{KtTO8gf-2C6|P39hK2o-Awva&u$V$~S9_ zsrAj&0om4gdaQix@wlTb%U@4!O=I-;yfmy-R|HF@y4Ue0&&jfb;dO|w_GJcnC(=)$ zM8M7O?cBIH!j5iAo^TS_gD1OZMg(gzU>Ku+)w}xa=&{TIAiTvzGY zS#&*)==``AJ)zI}%mFB92@PDYjsOwDCS@rRb>ckR28)U7u?!x29Tk{mvl#tyEq7jS zgHjAFJy=YxyVud@^m|ig%E-5@g-2`qo#&q%Vz{|Gyep(=Vjs|_J>EOyM-yWR3IL%ObhIoR0LFkE zi7p52P%s;LG+Ja-RG$OVGnsw|tpWbvggZW97=d$P3PJOOu93+$O9hA$u>SLe$(gLu zCui+T2;w4$kWfrEH@IbA2OyIExps8*&)xXT1ds0H#~Yqh?^y=RL1Mutn?AA4QlLCyU^tmNjNS*br+s(+@7C61-VZM5kP=$-uX;EB$j6!tN@1B? z0CX`UwmPIxM)A8o%T()Z58Y6RWI!w-T-O3ngk8Lr{5Kzru$X(Naowd4VFGEnJH=_ zF#9P&94L!+T;Y^~l!UbVa2Bx2eH*g){1-~BBxnAc*$wmO^%SzlgC}}{My(%0)h2*_ zP?=#}jT8s1XJ_jlbB7{x?sEkKtq(MoU@5?|=Oo!Nzi2jfI}p-+cL-x@2sU<(ldVdw z7gld>(rI%DZ8P}(uj2qCYW*yJ2rL(S6Bn3%5GtSW&`TnbXDo~F zl*;RXWaj{paD^3)E15=TiE?dsPGGIDA8*~I2UjGrNDBxMX%S^YfrHc3eAV?^2_P9G zyx%ssO+86qE3>|Q)9^YZ`sPe+nd&3bvg#tQi#}7QBuE;BzKL@nXU%vCRmoxG9SR7+ zKJEH&!Fhf5Ec^8teR?>7dhMD|D6e!Q!s*(kx`s)!+AS3pAWIf1$+Ji}iGUJ9{$NG& zDY4rSWk7aVv`Pnk~!j*OR7Kh_z+^=_`AU5##8s|z2iR4Bg}`YjR+ zOz?a*U6+8sOoN80S_j)R@(oLx$x;yX#}{*rbe&rp#L`KodpKY|EG1U&xgYH+j5LjA zMO3qdsGW2KYHuq3noBU}_|Pv%piWP-_A1FsLs0jH+~#BYH-2lDT;d zHsG_b@=DUL5E8P~zqKsj;#(NKab1d_c|j2#odrZf{?4`Q(@$#)9cz(U&PU1fl>C{H zu0cDkJRx3JKF5Dsp$I_h>@=9#XvUkt7pIAF&`pp~T%ANfc){<8fk%(Y(p;8NB7x2l znR`_J@5}*(#5;YSFy47wUr4#|!Q^Yh{!YFn_0FJQk$ntNQL=|SS2>=A8OQ)ee9SA} zys0hk^vwBYD=}EvZO7}02lQfRf4}$Uy|>PPf8>QV55q-Y3fBB?CaTVK^je0DZ1%@9 z-Xt8zM8(P6ZvSeoyxwnYl-~$Lk!&7Q!uJo(!&`K3L9czoTfr!-R)6ban_>jPO4*jD zvQU$7NLC6jErgaUcpKpL+jZhK7YY^x(e0|7rX9j}z>Y~qr6p;)`omK~`Y(I4tvV*W z_HeGY(7-0#G2X@B9%A`FyM#rpWb?cF!BrGB#jk61ui>YrGNlztx1ltVA8si~RZkrC zA=@|7$k&}gu)zScEll_^@wWjTxy^V)GWtvB*T#a>Z$0DjqR$ai z(5t1==>>ROwjvOAe5!O19VirIM4FGV0{rpY9nHhI&gKl@GkU8-P{%LZiF@E{I~~&X zgcNu~6XfY8@kjdI=no)8HJQ`(Yy{LlO*)$HTunk@xEqbOW5^s94hRT;LTU~19+O+K zT^VJvS5*&l9~*JeCaR?LhiNrx1T;uaqWi-TQuXd|+>E;WX-OmTX6tVQfjfxtz=usR z{vydB7z}I?h(=S?z?zwG;E8M7;GIM;>=5ApF9!2&b1zuIr%KW}7^B!kosQvXJCG=(% zWc|Y6z_1rZPYrBinDZF8J#zH+70Uv9MLX;-(eg|mFCo* ze-m_XvU4C(R=r^BhaYTf4bWtLfnd3$u zZDPO(f5>2bG&Y^w85R0U9J~ttK=~D7xVN~@j^0$J-hd^17z^6p z=V|tMNPd{L8*aUbCn-4|l+L*Jq6qC_rXx4j0LX$3RQe zyL{nn6n3vE65B2#y3?rc6<9v%Aa*d^J!@q)2}q(TTQy6c* z)U|&i_K76B>X>nq3W7XKUkKV{AE*nO)<sA{JvKVp zd6TEDC6Y5KJY;=Z99Rg#IQ$LJ=%~Wq$9?%ERGC-P^2g)JK0jYJasKy=-dY3x#I3(= z-eRHA*#GnocKUd@TtefgjWr;S;GO&T$hj(==&vb(kF%c9=nPLtzBkl+gZ+0m)@^04 z-~6j)-o$mnq<9y?6k-HKC%BPY-U9Z0F6e<@o6c9hg=XAMrF|9t4!1)Hn5$vTL&zU+ zhdDo_c2%crGmgnQdN96%D^*V$|5IhkUxil6e&@=deZ z^Wjax!o&w;?q{nipa`IK#i3*3-t>IL(Bz5~{u26H)-BlXN;QKni%d=cBF?#gwKn@E zkYi+x&}^}Z9hqTFHT0JM$bN*Ab?*DkK+}E&#N=wYO628Uu++kVflp*B^G+I`pZEI! zV13<1`M#MsXoKwu8@5LKq-mv@hF2t zajQq}n1;WlN#g)~b3kBUN57xEEWm*v*oa)CwGQ$i1Q4c)n*@t+w+*jnyoKeVkgRxV zIf?c-HFVXRMS&7}VGyK{8?BjAEE{Bko}FK>qe*czE+r&#rDjI&c~9@2m~$!FnuC4# zD(?tTNCVt;>h?UoH1u>|W}eOCe$DX8#@lswm*Jst0Th2cQ?1#|usu!7+tZk17l}qN z!cavhRK+Eix`w+P$8#E1cKRCsRZMXjLmqA%s0I%1V=S6W-nd&qqf%Ghueq zE>71a7-9CjTFoLITtGa`bhU=F%5@qbypEFPu5;u`@NW>ty}CTnsaee9OfG#&3<)7g zus1$I!W@0O*u%`Elg_%=Yp zTxW00UgNByt;6iEfEfO5P(jh7q@U~`(Yu|#t( zT_HbL^ zyr9Ti?CS55>I-!buMPi(OGx^pn~#YDW3!40I~#A*JE$ysgMAia+!q~M@zRv*^UktL zTILPX0@7f5-89LtqMn<9U;_ZEU=f{yRfrKDfJ|bbP`QC#;uH-Mu}K1uh)LHUy#OLo zar8}QT!B!5(E!-p4F$Da+}H0^+RT*dG>~97G#*+Xskocp%w5fX;k)7H=*2Q_IrkKGCtm2m);MKJ)*{4DI-!C27w41bniG#^h5wFGGQiZIG<^0gr@ z#u+@sU$*hD#1qaBF5jqVFoGMT7dQW!b||e#dabcrQ0MJmtIzx5UC`C!QUa0_`^c=z>-fDPz(-vCJDM$78H^zjX1jnEU80)-LmVWg2}W`bomYc} z7{d2^@9e8tQ`nXU~_+@>0#Ql3_VIt~PJEsOkiw>}m7 zox{dDrbHzO+2uz(?_(1~;yA&kR!_s93Q&gI`tSyknV0vDC6%}t-VUHX4Z5>rxskO4s;!KiGb&hi#C zcDw2S@J}S1Vsw`QK;+|D$|MQw7WG6Xv2U6a7;U1@ZtU(WH;Mov*-a;wSvvF|@f*%O zcOe*5QbXziG#*2EGwIee0Mw3W~8nm{^+nqg~M`BjW(>#m4V;T z(Oo{JjUDOjc0F$Oe)5g+oWqNH5Ce?7^AgaQ;@IG)lE=SeRgyRLnP z#eecKzvApWV-7vcsJm3dpX9b(Nl4iJOjkY!?G|wDW0Y+o{8b@)fY>Qz@tlPauYb?x zg?&_t6r~*_Q)%% z)eKO?g5UvS=sYT-n&g3pO&>z23B#_aEW^PRbVVA1anr|v?ZGD48wV(28mDEo4moDb zDht{RDhB}UeYkiagA)P!z+kPw>%ar#hY_WCD=HWQ(=HZG2sUp3e;D~Uyj80-xUExi zZSNU*TlUuyf==`eQVB?n&*QN4P419H%Ms=#c3t8FX$)h*L<5#T4v1_m4w@2H#zkNF zBTnA{m)uYZVyp>OjGGc0JujDjmT$vn1q7=U&yH9< z#cyj3{SR(Ud4Yb74Q60Immn))t~i1?CYO+CjBOMl^&pHrf(P<1QkzMmkMf=L53JPr zQbEBq0)KTn3nPaC#zFtBDt@I~``T1N&C3XN3}^C&Pl;>(_iJAb&}()cq)mIErg^#+ zVSK~G|LP`gFvcfdF{I@YFAkx)weP`jZAtQ>AI2r>j}h?>OU0)&R~5_+Y^@U-E?s|l-OVuUSB16`RF7!kWmL+291>`pFR>dRAM zV>WYBY=f<_huMfXhA4)}OK1n|DKcUrddYQLty@A+uBrG$nk>t0Nk}nIl_7GqaSFCs zi)dQ(gi$v#1k20boG*=6Fe06f>w3*gM{N2f@s-WuL_m7?>AOg`IK-eGsSf*e<}?4d}#_s zn$cTe^qf=^qAifnIAAH<77*?CTA3)_tJJ7gw6K}r(!BD~s8(~6yU%{;h!cV*5eDrM zD@ijy+D_k6IfD2A$o#ijKxUUP1D*P{n;auGKDK*?1tbQE&v!~C7%p_7>vZMZ@O}UR z(Ln1W$jTj}ZBf8cAVrCPCi^}rAj<5LzJAi6Ah;?}BbNB4AH#L}D>M0ZUtAZ9Ylw*}GE;lAL~%#_V<4=i%< zu$w}Y)#AU6Hwrh+!{n9Z`izQPC&WF_zPucWw$uc^p8R)mHk|s<-UQ(EoLl6J=7E0O zLRr9vd?H$}A77o~7LFc1?S({93K22!fZP7tHFU%+0g6Epc7UOI9nqF1(Oy|9fxI7V zBHg4vZJEEJ;zDLMre*TM7@}t{H&c$zo^lR`l=8MN`ahzKe59kUtiPb&&cAIpt3}9! z5v;@qym~wlE6vM9aw}>Kz^?9njBl5%ugf(djkm-CxGDy_ktel$Qr?HB$Wk_A8zO?G zcK5X~C_BSn)M4X+<$>{552QU*6@|wytP3lQ=#2ABMgZmK|K}t+pEW$N_fVD;QM+)n z=}u26+FQOp`y1dF+55qGhmc+5Ll82G_hqWgz zOrr`KCkb|o)}wktgPc^HvF6Rmpj(HSbYLy?mo?K$H~pTyE2R2V^Y1 zL*X2^X;$na5s7QCn<0uVt*whw1g}#baLE{5zid-eI4dFSBg0m(CwwDRL!bBYR)@U4 zUbVUCwlDKj`yx?tEkakhklFLr1zf~^A?Uo=4F}K+SKAx=FPYoJEkwKZxktR00xNRwg^8vrNu^BVavG@@yZes8s8muG z@U&QdDGwGS|GzANeG1&eNi_p(rWbHBqFCf`^Bmc&_zhJvlAJz9-8ay6!q}? zB1K$%eIm9jA|!Z%!|WT)v~RX_&KB z<&2l-pIb`qf&Oj!v>1o`O@t%XN+AoDh*WBN*KR(|k0Aop7@-o@)@60+X{cpF2MQKZ z1WqiBj90!}BlLNVP-;0%Mw(NDCxFSj*DE_HvMk-yO=BTcJ0gy5r~uC0eT+jgl~$GRpffQZt# zf$7aygIx%774Q>49_IK5m1OaX;QNiYM3-oE@7NeaSclAOjb|}Jc-u&(u(MG^;LSEFMsu;WKysI)6vTvTh-_(XyCn&xQYm?;D@`+tGh@&xje2 zBJry2s-QgS8#vnN5Gv8RnfYyluN*&&Pdcq*^SV0Uy*U{c0mCF&&}#woGV=LMNns$E zx#0(f`C^q$Lh}V4sTIbI8_tjKok_lBDcikc704pnkJyjE;B`*F>AZLKis2e%Dyn1j z?lH_&(d?9NA4Rz8%{sO#{%9iKzSQMdoxoMOyr)WJrFPTK8*uj4_$ zTuMuygdLfm7qEqRSCAkqobk>L{JsRk&yL6i7#85bXdR$J`;OFWT`hgL&i{Y{VF1q$)z>6(OMoyhgcDl$pvOw-kpnT= zVPxH6F^Ki;(w)r<#56wsl`1d~Bxlmb62emoei zF9cLN1i>Q>Pg|)4?=NG|#LrSyNaRJI=(&M*$G=T?C=9}1I5ONovM6&`(T`z`&77WU za}8?feR>Xuq8CDxL>xI=iggX9M4D}D2vOjMc6H*j06Rgy=AU86c3Du_BKi896^~(i z8T7fT<6=B)EgLNNOV{@SU^Xj^EEXX@X)Ch%wLaf~K`uthE&Uw4#A> ziJ#lXsft3@f@Xdbf=_~sP1m8Xk;|?>u)oy+z@g~8!S88x_*pMtRw*E~ys3%! z8F?ud<1omtX8E~v7A03|@COG*Ahm5adw!PxP9+s|pzIa!93jP;)-M-lIvZ>Zdm9tr zw^RxOuNX$(h(=#wbLqbs{+Z)9w~F$M)iL1b zo!Ayw-qAP7wHg1xZTEq+lSL3b)m!&t>=*Q2x>iP9HKr|vWJQO~#cX0u`5@=f*27T) zV1iQxpv+^@bgs*wUZwb^I+KwbKUp4`_vYP)33~~9AnAe?E_>+27s)=cpsSE3nf$nThChG;)JmVJyug3ILzXhLu>jds)DMuZ)KTWCw52sE(oNE8krs0M|9RbPKl*p{6B=7-QGdGLE@%N`VZs-AS#- zxbQO>ofyWng}iprzF~Cub#~al5l?XQx1EDcl<1k{WT zB}3&ItF;|=HZHSZz$}R)w4)dU1qmST8}8ab-NXvv3)?a>F6`oeUeXGq}Cppc~ zO6f*x$aWzxuqBqEgv~KFO?Kv^4?K|+@JwSRL^{f1H&s1D=L5*msWHZVjIWB)^A9n8 z7&zw>$%As`g#u`rFxgi)D(}E#R};+zr!5J<%{jZLnns>^+$20h;=WE9R;bbl(wCBs zc#eDFndSQn@;=mXz(&3OtbJxJ=X_I%=cU!pD|BtZMBzWC3mvFX!*b616LFcVpfBGV z2)=^{lxs@nu;VU0s7Ea0?8lOB&+7BKFTG zl)X<1xn2L}nRC|lYiSz<^lPkX2@AZFP3JT0*Zm#y)fj+$9k>f0wO$uNmUQ+iHuG}K zjzx22#>|tkPGU(7BnFWDRej1{Gs}5o2^F2h~%>ZqpY#og04nNBg zX}lX~HJSN$f4}9t$kCU~9Do5)K1GAl|Fd0#yH!7i2#e$a#BtFdg+dOxK?KijAD2_V zZz(`&jk6!Fj@mgLcR6Mq5@y&1>yw=QiXU{}5hcXZ3o^3VBGa<+GO2SzfOqk@q}jRf zmM4Vdi_G^kD+YsPjA>f(ZnD)v){FBFMbR`L>d`cUV^RMbm6h`mscm~3z=1Zyh^)XU z&fbG8fPu{Q8QbBAi`uUljxmjzhE@e`igv%emybma775t!Rp8G4_tGo&F|}p4H7aE} zGiuK0Be|N*_U*N=v{>k5yrvnQMdY-p2V+`<>vHjB>|1j!i-{C9cz-KjGOQPrgjogD z!GvebyOc}55!dF1tmr5|SrA7ISmJoMO`HU{S9Ug8MXXcueT0HfsME3=!j(gU-b3OV zoHM`Orj+wiP+XI$SQY~m!v*!W?JWIWR}T=F~xr>Jj>M2~xou72jzvDK#sl3RXmYxRPY z%SAL?ro=^`_5W!(KKJGb1#?C71H>rcdD3G>`-GSQT(RfWWFddfj5(f)ap-&|#KpzE zrc_uP4-)UX;7`Hu&&)m2&BD|WL1BC5f(FILp&?bj3>o#`5=58VtDjpUzl{U-#3`@DT0-2BrhLcSpl+ybfnpFxKM=L?QaR+kkMVTikEk? zU1F&d2t~&$nX_F-m0-Ey`9J59EGPxbEyyx?@mcb5LIr+S2xy86Q$rPJ< z5;Mbvu#}L+*GEZl;xd_{&s%P8-D4r6849JzFvUI#J1tlSc^XIFGTzX_c1#DE z6R;B{k!!e@b!<&I4|TD`ro#^cJJmiABN0RskKj6aKz#us*Cl{TX!p$;=uA9A@A}3! z2Jx`mY~AG}9>_q{|-H5o_jYsEL* z#P66Eo-rY&WHHSK$7dngrnK@*8}l;{A%lDnxE$QG0|my~v>dmC#pV_JUpFCP%DxQ?>l zwh*xp{Ii~gFQ6jnh9OzkJU|XvZoJxN_Ub=es8ul4LHyV2vBRT_28f?M?f`l{(|ZoQ zeK0cKQ3~6_dKo783Gb;V8sEj;+{R6YDB+J7jDx=`AC8GaU^3jh0+>MJq!4<6a+85= zTmkH92@aYR8yj?2p0RS{&(78EyX=P1mlWMTwQ{(9#^Xsb7n2RLgDroYF}5vX76BfS zbxdz?(su5R-^*CX2OQSE#-Rv)4cImgmaM|9Nn4{^Ox+Et*iOoiNzBqf@#Pr=BPHPX zHiCw#Wb0c7eMO^%J+sWsfBI<)sKdX6)R@pQM~Q!>K@Zy` zN|$D$JN!$BoC>K-*URfB znC{Flr+lI77otbi3EIOzCtEgmr%8{J2d5GrgxK{WcT;^mExUn7HzMEV5&Uo>oC)2Pfin+4YKg4T|OuLIn zQ^UpqB7?Ps<2fEd?fCZ76(P1D&{HSoIX(z)S+n9ZjV@V%Df z?QK|QpWG2qP3hUj+u8!TSJ~BY+yT9fEHmd4jHiYM{9c3ur@kTHunQ9<>gR(tix!5N~?^J3DLTHK>OQdkCoa>eZP2OxSmYn!^_X|pB{iyNA$TS5@fd}zxOTO& zdF^kU&T%fzMiP|VwlQOcpvylqX`O1cOkq+31h<*hw(tbB&b7F1nR5CHJv(0?3tKVhihoQv18UxJ8qtJiyUvKIOMzDmA~UlU-bS0sT{oW$2;<6 z#T}8QD~LK4JVn)im(D3ihYjtK%4fzorG%;Q1=1;-|Je4ke^A#Bk*(v6RhW_#KwKUV zH4i>|V(={fDx;OtwZ=ADopzYE9fUN!=JAAL!PLwGGTgkTD&Ba7n+XWavmC6Lx#NIX zZD^OUfEMj>^c_~-lk^hEr*0bzA6vOHih>LKK28qWukONg>J++D4&8R*F~FX^cq z>?~=fj#i;7x-(pZy^F39j5fBM7%tztY9(3o625~DMV9OLq`#F6Qs+e#!tLl>+pz{n zJq(4}+OJ7s#=jS5n09KZfM}}c=ho|D-HsW|x5xwcP@i0RPH0caFOsWB7)h2ut6Klg zpD=>QjhlN=Opi}f$a2v(Yy!W12YYTsgfFOA@nqUVX`#3%m}#Cf2B%H=i?d#ny}=@G zcQwUclDmjEg+3F_yRsXp{8Er1-IqR#ZuVIUxiGmLU1(DVflKuHR{!G!AcUaOO?-+9 zV1rPwgBc-S8=hUPln%Yc@1HhFkN+!)wdQ?vN3>#AuDXv)ccCqAEA^jYBKR0!5-F%f z5kxDKR$IvQSu^FAROCG%@xSOg4=$jB_eMPTV1zslYENhbw~(nJT45-*?dPu6^+_Bz z!;gfYS%1(UV>Asx_2e8F5HhKMehiK7C-Tb|rnCC#siC<=j|@)lS0#lP z&ZQ3>U(p`)J!sZE{MlK-PuN=PMLTCqO%2Y`lfEVjvDt4H(fp~l}vC6o9$Jz<+A?&-cY-JUC|F7|%LGyRccl^4=D-bCqJy7l-j z{Is60@t2oswa9`tl`+vVa%Sz+Ewqay+HiLtql38uo$TYEdV$do6&liSkWiaw60Ixo z?qE_O?u5PWI5dKqw3GMzNMCOQa0L7P6Z*fP1FHOm47o1y`55kM5TMmkwYkv_R6VsY z@Dt$+rg3N>ji1p{aW^6SIe7N386~kw9g~_)f}g!(~>ojOiaA$BK6Y8=>DL$E{}YXoZpzzWOCoeF|hVgOcl*P#mc)ka{s2Gpwd;Q6I}7D1m(1 zajDDbP|6t|Q`+^d0g$Wzf2zRm5A65t;5#M@<0PQJA!G}acyUZ|Q+^w$R7hCRaV@ z%;PmjJCj|`-$W);8a%?{(v`*Lo0&_h!(|Jf>}HpXggNWNfB(^c@82ejB_(jF!0cdS z|E5mlO&wYfA+}}$El9JVC=jW0MEsXs@OiKXy-^mi&jP^(6Cd`1HVcY;@D(4B*3BrE zs2A*S5n$!+|NG8TpHD%4KjYZVp}e|2cvZkrH-CiaFYd?0SF}A{PhHoYShc+PAHv0C zgsND~;=vQ4>eY(K#;n)FwOX3*K#zf~)W3is4X7U~ntu%}`Rz1upmI@R`cR5y&=S7+eJTb*}@sLOwgD|B|S@`?|H8ZU09W z+87k*b`DHI-cWcS-$s8)$>J?)ztF+b-_UwE{6sO>XepJ@p*J(o&7%y@&q^QT8x&UE!R|J=`z&fQ`O6=>G*K>goO+4(E=rvKf`Mq z$HD4{47kJBiglpd09wQw>gHA%YH>w#SfWBX`? z2TKJe#R9&=TOimV5c-3c60L;Ks~;J!b`45VoXeIfU(wq?;3nDOoLUCuwq6z$UF`~5WE$KN zSS6z0W@{{VZbmp6MpLewvY|L4tJ@#=Nw(3uUjU{S{uVIA*Iz}pnzI8UL+N52jnc_+ z3SY?r*4DotanF=tjQ799dQODkKhBq=N?6Mk>;fi!{-t=cCw5J zO__j?wBo3~ZG`mW4>x~9c~l2%qvGR+@E4tmzy+VViROE~x?+0?*Y)}-_&1Y*a`~x#>1ir4 z2*%xn*+R}9sq^IuUg8D%kHJ|w(VeUOgv~My)4AXh1lEf~#kboXR4T?MPEEAu5ubk> z2%vNkXBv#-{p*NqgzZ(V+$<_`)F`~;COGZTxzo;HmA9sPvt?1Vw$K?hU8yVnrp*); zHw(uY}w><9)+%xw-VTM$zD*VI2CSt}}>T&I^k zA7ffsY%bPpyab2%sw2naoLt^=Ix1z%$Nu)jSw2p87(%q2sD-If3;YsxqZxtCY6MXK zT+)V0!*G4%pOBz4i7!^Va)D&m=@xnbv2A&NtnIrjiH3;b=ijvwyXKA3PiSV^(t==tRTAwF0e2-Wuyk@9*L^8UXC3 zsUV_oiU+EX*Zl!?i^tXu5x}`)}9~s)${+9J%Zco1j9Sr2sU*JQpAs!fp-yYldC92G#k#)3qw1SGW8NmLa8<-{VoV$^Q&)yjZOcG2&Bg}z^P#Vd@U=?(IDF=?onWI7^ltHR#M+ zJt+=X$9lYy0OlQyxeX){Qa0Mhx6{XPCfA!Zrg3vs27ihsKYEh_RgDe2=xrcE8^|tS z$g1#f+k~_LVuB zAPO5ey4!;Py(#1J1Rx&aFj!~ye^F%ohjh5Hxrv|&B;>cHfa(de$X@8}M+g?@(SfC{ zw<@8hF|*{I5l+fqScEZm4Oyuu!STd{{7TILQL8L_L+pQd3+pe#oTpk{?I!hSQz@68 zM@b#{2woDM?9c{~Yh%Rs1{e2A4CfOccjQ&Wo&w4olukkjWH}Z|BfiFE+~9e$_%Zi* z@bpgyVuE85MoIA>YBC*FM=S`@U9~!__fEd>ZTK-C0K?~HhO90pwqw_YuWePl+&N^f z%FKAYk{w;q-XRC5fVW|27t)d*l+Jmj%%N3@i0E+8nII(S)^Q@Y4>zQja$=tfTjywk$lOkUe z`W7u46nk7gN-u3nZqx94S3cLVdhbyNnQzNWi>m;5&-Gqz;{8q^ zRvEYSoc0&Rb(y;E{C_ALJ&(b;yi#{v^ZuYaEP^v26{wg2_U1x{IrP~X^-SCYFX_oZ z%CtLiWk)|7=NcuqnP}%JZ*|Cc_MF5iIsqq|>7?p^#I$VJ$=9URd_8u<{D|Wr_kWKE z-a&xOV4X!Q4GjSU&=i0N)9RpvLG>uETDP^npezI@I&0uj-#`XWQ^W=ux5eHpg>UTs zN0^K%XB2+WU|4#(zl6+RcstH?Ai&<~RSR*R(#e}Pb{=UcQscQz->b)#DBG?~csT8iJ2880^>-%nk6gJ8~C z+8;7_1a(h52VS#Z{E3Sz>u5VWUaM;>{)PV`GN(n9is9Gc-(TO{C*be3z%@~!*mR|3 z>xMsgbyq3nfY9TxJ`?Jvw`s&1fKcFL2vV#gBVetlt;;z}T2W-D{dhT!w~1N+56TQy zRZRPiriP*eCj;T}DYaO+y_ZyToDAx$Gp_O^<|zV0Z8)1FSJJ9AInO~=weuj#Tizfe zt4v!9daiAYB=PRm6Nit<3(h6g&8)U;KnrXoaO0~4K-1d58Io1mDAL^|vzR+c0FFks zI&t#h4?Jy8gAE_;LF2AB|etI-^m5=d9h$Qs4p3&BCuF~}Tu7P--=#~;$fa2opM z$QG{hU6K*glWH}>Ur}KoRmC_sswvE#O~wVztQr_m9e*kl{4clx=$?+Xk;H|$yZ=Z2 z@>?%XI;C6lXJLSRS>n0nXS6^&Bs2P4)`TOpy>BQo)5RL@B~m$BijT|dFS`*MOlL+2 zFA2oF6&72bZWl1Mv!HLl$>;tBN$aSpndjznd|I@ODv5%u4;q(`VSc(HQ@v=+GX$ZOTKXdq6E~cbs%Jt+X zmdUzbbWaTez2*k`5bh1AI+=X`z&p)%tkS>U_)0&d@h&c;iu~ zNoa|54>AAf1JPm;cJUff6G%V>>ISs8A_IO^KjlnXp)LEVA#~59c%!Tz1J*xn$3WrtYe`E`~S*f(6=?EKFi&YqcIJ5C;7u=)E$^nMw+w(bbtn zF|_QJib|v)-(+>;4u3FSKltnmF)>JpjAkqtnV&m>E_myWz$PLk% z+0gP(BZ=PUxHk)b#u*csU7^n_NMMxD&dxEbKN4icxoQ)L@us_QnKTXvznid0yN0Mv2brN7;xeZr}O_|YMS_+`n4=wYkb4emJ@2?S|z z6Q6tPR$VkBS8tv$Aiw%kI44*lP)HQ`o4~Xo-i0=N#DouOR^DscsUCVm>?a7v4Hy`Cw|@j2z#J1kpVNx}eVIhu zFc;&-Mw+|BT5nEv18!3LcAEVCkSr{ysnh7;Xd9teSY_lm_NiKb8GTk*IEkUXHguqO zQ@z_q$?8>Wr=lY$0Nf+ir$X1M0Ctl@v;sv;mHXNf4)|__PoAePSGpRU{{DRbakyg1wVS< zQab1wdgb2Y*SwMKav4HYG`;>17nU;Q!`F=?t{1Fj0h9e2mS?lF+;vyNu(k~P z`&(9WMEmlG);~WwWP_U9Qz`Gidn6C|EV!1AHq1h1ja!0VHbK*7^7+F~A})Y8dJ(So z-9?JYorw;#@rrRU(dIMN@~1%ndR9a-Z=p$pMfPzJ(*~`Ze+w@gQA%mZrx{wg0vRU1 zxERg%wsx6&>;!r-R9HB5R$L8~-rst&m)FMDdCRPCwFx`%TB>=KDYfsi5mvz#mt;>>KArF7j&tSWyrZ$B&MCh#QGClq}3fBxZJssFCorrO1-|G8R=_Y#pI z@+k&+-0-bV=$7{YevFlXOD8-Y27Tgs{K!wVWh({UB5P%l1cI!@si?lH0O|Y> zv*?}BU<;coaDGd37iRF4g%o}nB@ysdEuZ{$oW}m7MJ_r1pH7jel>nO}fRaWAG#mc9 z8uQnYsLe$3fwP+<%D`Rl?+OFWzmQ*Vl6g~)G^{QN3pee&H$B!tok+9kMU)9)ul z_y0k7L3p4@A}y6KgVm?D{4=x2kPRpVV-+g(0%$p!W!gZI9st^}$JHdCucpnW5C2y9y4N-thluHCXO!>adHOKbLLtPc6f^lAYM6^c%-84vbQ5n~%;EmF!4!5# zAO5CQ{MuTkxL*N>D(BnSei4`vH6D?M?MjEF06r@l<~jS3=}y#(55v|6Xfd{A@fuXV zO*~d7*l)Esl4k+m&(>p#wCf3{^j8#@M7c7|2g^~-0XR2bF&8jSzG~~`kkapED((RZ z&AMRvy%MM71Lr40mTd?x9F9B629v!ii1%9_uZ44_-*P`581Jko{(hOLSKd%Rd)Bh@ ziCbl5X-x7U-5Oc30y6o82FBqx$y-?uN`Iy?^6^04(9pfc{e|s?EYn2ik8wvu zu9aTp``CYR-3k9L;0=r?<11wECOQ;;^t}i09saz3+-{MQ^o!rNHg?5<|l&Zt*QcZ#fv=&@I;(3Kcyez9ECH*z-NbT#`1z#}6C z5ZwZA>7d~WLzDMFC7~0+2e^BURE>uG&@SaZ?b!QLpL_TsvsIA&akuwe)cvA!VBWl^ zp)*v${>AEfc7iSJiKyLw#x?j$k z;__qA#C&WwZk_)OBV_bV;N72ycFax!66~urc#0qom(FFEl3)bYy~;o{v3g%Zm!Mkc$=%SuGl4unpGRX(L@s;5VSx<)rUE?{_rB_0$w*BZNOla$ zR|DyS_Unc^oh;SUC?eUXrGACB2~~_FIrFQ(t5Olb64OyRi4ne#Kk;#|MD0B6Gu5UI zGmX`3^y8B39IKLse9h*w*S2nF*%r_04LrZF2c~7`Y$?!TZ2;O`VvyzmafcPp`56>}-ilF;5EOFVE+-%mzy$PBmspu~c7ti5fq=QXi zB#avs0hY{xBfG{U3PBM45j{_>flX<7xO8^&uG9QCknCdq_MJNx`^2Wsd!?j(xa z?f1!Gy+_Sz(~tQ*ES5VLqWQi3!yN&=XegNg9{=yped|oS!fvEbV z35%re=&EyH8+Wy9mo&@<-*ltWHXxkPW7b5bn-c%;nyXo&akD7aP;-10NXDT5HeM<} z)3)drbIe8>FFuw2EAT$xbL>@cCRV&$?hnkU9N)iX5&T;D>*sf?x_`z$Q%O>V;vVRg z>$i&dT-XrvR2o#l;ojVx9MS3D_`r*xUu{E0uF5Sa z9CT}S?MrMlk>8^L$+RFB(4qMdK7-h6`ln~DB2N*~f#qf5OjA_IO5 z8-f+*wYN^sZhw#O=wII?yZ3(?HMz=^BfW`KdY{18SS;Oc5yiSaZf?ROr@tjH3KSHl z2lrX5`VK1d8{wbf1(*{2TTgnvb`wu?9n+vFhj0}7)Ev<9BOsK;?+CGx)PSnOjNf46 z0PzsJ$RY*+u3gF2Ie=txSZ-WLmDJzMtjD?zJZ%hSR51YPc>u{*8Z^kLdm%FdHj8tbOgPx z?;4Ar)tbnT+N|nB#E}-Aku0ASRY@)x!yjvBNyR%oHq^lwk{MLb9l7aTbIh`Gw^$2D zFMZL0zY=E4sIA#)EI?AXsKA@^S{WSEW#?_c8&};CoOp}GekB@G7#=jN7PXKd56vA6 zkG~z%uYH%zJbz>mU(lM6q;Edm_XXFZE?d^ZH7xl|7fHq+#cB<dMizRQ$@^y z|2tr_QwhSqev$9O8t4;$Cv5W&VG4k71*2oLAj5i6(Yq%Tj2#n37$NI(^XcWmyolkYh#2KWq+sg2n-+;&z_if&rsL9Sz2vtB?+(yCQ?&5oXv&Yq7x|?G3Z78L}}v&1v$o}j~GGv|3u|AD0^zusP4-ASlBTn20wpcvg||- zv0DDuQLA(>5V=&_r5%lNyRJl(T5IpzrASF3$79E)I6 z9Io_s&jTXA2c>`Ee|!{${q-T$iM^^md{%mH$aELP`R}V-gJ0WK{4u{FCCBEPTS)ZR z0*)%|7q=}A%YpBxg|s_C?ct!*=Kxizj-cJU0R)v%Gl208;C%v zloE97Us^$uZDDhIXm@B#*CZsCWc&X}_+L|~20gdA+UZX;M%Di%+Nm^<-}oD@?)S#? z`&hu!cKp<cc_5-(jME%-j(!1ySDhRB#P$&fzMBNl z(IE3JUrHrT4?TkV+Z2=a5c{6&oJuWs0AeQOcVx2ukP?Rv*ZjZl1cXkRn2uO#Y%O7b zV#Zb9TE_&Q+kV9g(KDv_fUI0tlj4ZJf!@E6|tF(oWdhH3&Z zTNNXOfw`WiQnt=jamv~D$e-=)e^z+Ioie}ID{!f?CO?xyRyEs}rs{A-nKnKz_@yk}^q~qT9 zpad7+HkB;S{r&oA8Xmui6I?NxobWb}m%<$N)rw?~ucxQBFIPI*9Zcv#3t{Q?FJs+x zsxxw{+A`k?_`LXK&53Aoz!G6ME5q`?WF9(XjxFZ5Q12l zApb!7fKG;P!!HJKiN;U5EQnGP!uWySVxfv~N$R@ng!CEexApki&Mq$mhj~rE9#UiY zyS@$}8^1D3Ko}$-*`!w+!SFS-z2;gEDENmmOrW|Ma-& zsLt4m2kF>(47PFyJkNNydKcoR?_g{R(+WSN>4Iw&y!5Ltukq;ee$8a1?-irs7l$*# zMPd(~&9X80ltHrC&`=~?i&}+NqpQ%%N!IMKV7_JiyDc=-a%An^pOk>Ri>c!r-Xu=D zHQksk6=vinyRC3W0U4^Ko3o>s8-sL_jiooWhH{i#n78Nxk|zpG{vW?uK5U;qKiv=H zM7&@sxL@k1b+)jl%&u^r*p$e4kE%8wYMwZl2_7Ebq>Anb>Q)v!J8G7AsFPA0eIrPB zMeB!Ok(LHIs{%KNZ_ibdd`;wh_0HdvN5m)QPYSo<)>z#+Cq1)aaWwM;dR$Kg> z>w9E6+UEzntQ!&ndF%Jos43yu!EMb=%`7t#>m=-5*x0DK{M6L zuG`NJ`!WN6BRIj3sUSdh}lssmUzEkr&Bw2sCPf&jtpuUER_)!EaMLrL?3FCE;2 z%y6mgVRGFTfWR@*0w}eB&ub{=m}rx;sMa6Ao zpkSm^+R&=$P4Zm2YK1vB)@%;1LHDvLYSz5W~(_ zSXR>r&xt8d&Bg2+-9m$a1$wXi_9|RhsCwd-Ww`ukZWNq^I>FYE`z!_vpAMyG!OU7g zMh~|YJy%!Xu2FwgPjR8_UdtB=ZLL~4X?xN3wM0fuM^zdW(x_I>b zx9(YG?;}?c4rnJDV$=7_ZdtJbOY3MJfLx>z^dnSRXo%v@-T(XmY!co`@Cby<^+8L)hy68PzrdBcj*xtTWv%*1{)V?h9ftT>ySizZCh}ye#_Ll5# zx2!l3)8fA;UO~rn3@s9`@p|+=d>@il&P&@)DOEQ%`&(0?F0G{0H_*G{#9kmZAhzyj zXOp7%D~S$plm>`_j2cgdV1dDb5yp}yCI7BjC;ZCA0^bh=>jw+Y`Hdy)mG3VoSN?S< zhd2gyuDYDKpiXMBd870TebWW8q4lD#@M$4*kLvK}gUq(=mJVYvM zu|}Xu`z))H>1NF*+icAf5%O7i*hM{eAG6G@G53dD(!e;>o_*H)&>`vuyXL(!x!tn8 z7+$@>_f$;u( zLKW+VL_aU47>m|8Z0EqftUS(1G(YXK#RyjsEq`)L7h}l_F(pR%VrgO8>c!+FwLasz z;FTzMW=rVjH#Q|Q$uPjsiuwuZY=F%DwTH)eX)S-J#BwTc)~0%bGu|aG6mjvI|0@2| zg)aIYIR;b>FpTE2NU4&@zrUTgc4O!`yl%`%?OB*YKo*s<_>#a+%-+Y#T3jTLtj*#O zuwT(h+q3Yai!2|`O6CeL6>=F$&+s8q;~>x2%{>tD=Zd+oRk1o8g%)&4>Ge zJPFE2gPJiKS1C*L=DU}tfv?hDLe?`2TTOh&GI-o~taBGW;aQl! zt```B)AHPerjT6mJ*@OvhBPnwAbtip{KWV%FDjvf|9!%3 zBLp%eZ226|%}7=jW_f<)(z`sQ&wmz_wuXtlP*Wnd*FQJL%f-#)RhElzAFI{bqcDR< zY6&ovneCGOLLU?MDAroFJpDu#FWZScO0Ws*;~~};3|!Q8Sw^<26=Eez-4n#f!&r86 zV>w9>-z7zpDcca%`g(#`@@{uQQnb6H#+-WuQ^#=agZ8vr7CSuf4BOlM0M$w(y`hJ` ze$hA5vyM_7MwZ}kEF!}u*azY%`0dgFsJ2hzd)%yCgUy6aEM&0y6-aK^tE*i}(BTmd zzk{(zir*AJEVYhR$vS*ZMn99Td=P2L{-X#FM7l};_6gmqzZ7ksV39JZx{z<(;27Pj z7U}Gm=%|i*M6Og2Df725-o90SrI>mD!3S0Zq#t#xH*9*JXzQ5afW0VP(Ute*(|Vwh z#LyZCZ{4i0StVaR+}Borp>C+E$t1B^U8PJwa_?*B{*eVTU${6((`uj|t)igFX`nvd z`)$jWN^l#om0wd7HaYVK7*k>0qR1i?;0+aI3T}`5nQ6DQB0n7dyw&T9@N}p{iL1Qp z<$}XoRW^G5Bv2$RQ(h27#MPPD&|f98iHCnoQFEHP18&ly6cm}0ZOY%_gC z#9TD;G=_F!w3?H>;mZy6^O)?MT&|L-J?KkBZqurM-10}|gqnxzlz128y2of~9_(Gm zzcjg&uU;?No0QaoS5Q!Jy}mvsp)4!*yyXRL+EV@a<&zQ8-so3u#?V|Yl31?9O<$Gl zmkYN7CCbD1Q!Y{4j~|>rq;TApt_)Fa{H0o=$?N0a`F30}NgnXba%L@bje8^sWgFPP z^T&w;Ylm3ct3@Hp1Z6c&1{T$Fq@ts;P}>cJ}iZu%9UvDSsV!RY1F_74)FfzW*cYsH`OC zn>(%~&aM1^>G3MCeOB<@#Ia2+Q5I(2Yie5k?pM}DDYHcW7xxG$kTIC1jiOB6#Iue2 zSf`Zy`@n<574w1|E5S&DM>JPLp`IbLVQauFv53`l(j4UU!{gyvWK-2Jn~BbBpK4us za*y`MqS8&CaTEW%6)*7Q6BFGe4sSS2hupal&j7;2%R>K%m_K6F`UYj#Aer~~yRwu1YVj`CV zOYiX$J0uK{!U%X*L&y?Al}c}Xzem$YWih&&Ey7kZ#*-rk)7MkBVwtlD1GxkM+OjlS z`oQn?pAyXRvwo}6+5Nz`BKUm4dM^OLwqJ4a2fYt5T-jANMpf?iPr%iAH?i2|aBKW9 zrkB!HGV>Qf`4?u|)qCI8WX{<;-g*)&r#Rh{6Lk_{<^?p*?%erc*6Gm}zvmUTx45R7 z2yKY+k5e8P{*~|&iKhK$!BNs%mlroyg^P7PB#+`d(p|SD)(zGHRh(u2l}CN0T(=mY zs5wxC6BRT5U8Mu|R`6Ru><6T$(Z;H!SQu&EmkRtdi~>~cVBrwvgv7CQ++AOr+!H6O zU`3pyNHdILVD}UDu-n#F6r-DDFf|$NE`Xgv5E<}vK^{s?^^48#GL^|XGzQ#~CDI@l z<`H%DKF9Q^zb_>de>-c0H?@1^Ch^N@Ew5%RA{ScL&n`LC?j#0K2gvPiqZGluM5&4y zSE*?4`MiB#{4XGSYnjhFN-AX1&%41nTJ1Od>{DqX51bYdS$%&I!_<2fj@xW zrh)*_7J$i_xvt>x{Qfx`65$&6(rr;Jj9n}P%_|NBr|tWBAQJl11z9+hy^Yjcj_-GP zUMr?x5Grj2R=!=oKWcf2wn9yw?6-@H1E0xTX`E%LVypO;0+ls6cNNO!inVf21bi0S zns!lxPW{&F|3m-17Hv}(t>dIq>=mwp9(@1PyozOwV5~@oOl%?_#Hp&)3h>Ar$E(cR zai|h`kqA%;@AL2HOq_i}7--Fj7}RVqg+ojIbaXw~lJLeaQAjuwEO_{2_+0ti8!Eyn zGV5-+hpQJY>dPOOM#5_mu_jTW)aF{LGsR-<@NaeY#}{486*ZSKkC&VFCLPTaBqxW? z*FNBidN-)@8Y^BE+p-EU&N~u)pNOy7-P#+|Zf3(vw0AB~DGdPs{ma~4 zr)01}vRcdydm2*>D;sk+4SW+5k%bu=yuUSO+&*k>*fIK{YRwiokqCbq3`P62SEWzv z49vxiId-_*9t#`6srjMc8*f}9N92Rx*L zE8c{)u*N7UR7vwe#-zhFb@}7%u_;9M=%#QdmA5W@taVPCua`vMs~NQkt6tQb6#dRa zzk6&zMmfj+@3gH*f>WzR_|Tf6%D+I>wNxSXBaonqfNY{zUjoL$LBRHVIM5o*)#cn} zk+#Z8PFdFi;8-AV0cM7S84l(>y=%Tt;yD8*HqJFyH>U}xhC69 z#?)lnwrv|L+k3s={nOt6!~J=l`@XL8JdT*^JB5FP>!Bv^i3&n1wF7TO+7xcvLPuVW z6*1LY&y((;%C?JIhN|{i67X_PmGJN9+|t~CN#%Di{fb;u0ZS%;m@1sh((>^pFA6~`Y9!lDJIf;8!XGaU2=5P|=V z@MDU2V~#rPKHOHO5mfW(ZJ7)=&@L&2Bx)7?TTV%zOSAjv_uk72ri>{XlOo_Md>(lg zu^n;`crPmgc94(<T#%YGS>XjCiqPuk}Fx}==oV~#KJZTLif4>B<^pY1$b z-*RtGeWkdb)6Fp!C1uOn|J`T~Pe*rQ!|eRzq{k;Z3dN$;#(Mf1n?_qbeSPQ7MMEnX z^E-y@EU9lDF$8}cO|Qn&1&KwU0NHi#Bw^YjNpu$1V=gHfgg>Z&2(v&6dO=`GlOm_c zz&9nUM3+n!LtVy9>iw&$f=vpfJ{uZzBS54ZXTW@f->Q@i&7TtQYkBpFun0$U0R;1X z*MVvAq*9g@>_1b_PXK`^#$XK_CP2i;R=Y;9>`dpY7G*cYm4w5@J;meRvq4wOqH}7h z_+gS4d}C!!DxWN?fUxxYRVLwd7{SplfguCQbFWF2`2AC+oLkq;;IJXoG^@!tj7a1; zzLamXaErTPkqi7K=6%tF^eJ_cp zXDSt*`b%_XLQP*g1ZHHL@Ivj^SzQgA{2cHwKkV0*1XTXhb}GBeTI|H; zdV=Ltxhb2d@arYh1yyQ=f-Gb0*(B}5+mz-*af!3H;*?6Y(^v{qr3IM+Wir9-*yESz zR@ZPvYwzhjm};nPC16_xQX2QVL*NEjdg!*Grm=GA_xXzUlE61fI`m)k){$u3q1Xf> z=R0+-F^Y>8`EV&q!fhlOi>}ps<-8ku zw00O6?3U|~T-AIC^z7M;__c-~ovf9tGV|y4pSI%gIsjoZdZU=DZYp#h6#zoZ#8b-A zxtxfNh8XZqFX11#B*WK%H-aKIpkc5~3&QO4X&Ji`5qZt0gfe z+0zp?YNj2-*h`13lhio&QfS+xkB{xY{26@j)EkuJc1%TtQorlP{qqUlp8a_kEz z@FC8H4_hoM0~Yc@Y8rwT1TRBd!zIG?Doi_N3_3$&N!#SX`wEgC((?ghyG9XCg7o~r@cfL_1 zB7~CUYjq<}<)VC6X+vwORo2O}c3X-b@!7oTSuL@(^*K0AqfOcnJF{vv^hnzZjiors zArMGO9!KM`!T-7CeiJOyjKKY8JxsPS;g#pe`-p#w_c8PR^TX@&Q8rj;5?syWbubwqE1BmQSv$0 z9`3eSAlBp;6WPueK{)VjUvlFa}{QbC*mNi<&Q;H{zbejV`ShIh3#ny!O^|ZP47k-pgWN-dX&lWjfO8 zDflW$hdlVH$szU(et386t-=Gqnd& z2Ed|s-DxX~V~&5jx08tVw#A896Da}hRX z9wpB3j+AK|Eb`XqSC%yc=JIaju{DIJTTOQ!_c18J189a(P1jLhbF&i7nKKV9Uh zVgx1l9IcK&b@0>8&U%eEI-Lg`Z0yHo9ukZ%u!fc3g6K?EC3oCPN)oKpw*dHz zeE{Ns>xeZHo-wFyd)PPTBqb7=CqnfXrP&l&Y=nlWsnI6saJE8LbefxWqC=X1fF&n)m|AZ0= zCFdY(-do*o@1})-UuUm?rZsD$qmO#slYwNtzFltG zIPQ$Wfa2vRzxU8z@w4Wl=c)Eb;K`3ss=I|iWBjM9Omk&)3a3Cv!A0b2*f&BV2HZ0ZPC~4i>E09b6y(q(4YP^_PUnNHdx{E#z`pR? zcH1>B?y}*yZj9UjG&xWohNe7-gP!#$(^(!v@?x8MW|w9>M)&In)m;1dU3|>J&I^ws zBaS@u5mfGIL&(k-fO5+Ylp-2}v}(`zJhz`&-bVR7 zwq7&3JhnV{6q=QjpflKPn?BDM+@h2SOT}Tfju79QHBb_yg_l(V?Zo?LnYLo2M7wR7 z{;naa$eZhrNaUF?r+}-|>su*k{@WS~;W$)H081V2XBsz)v{jMC1 zZ;JU1K^*051xAIuX^2P(Dt|lqf_ZscY_A_iD)JT%28v4c)zh!RJoE{ zvFcZ%CJdTZMMRgbF<*)m&DqN6+!$n;T4${Z2`=DFDt^Qh-Ja$AQiuw13jP*imkfOD z8P)T1Y(0@SfUOh7OHVvpeCk=v?R=Pwk%S`wh}DbB7zT)RV;zx5<*d_Pi1Mritt&;s z107$@&F)%d&Jf6GTxK*X;VRulxFbBnP&0)o z9>&?Wjf0&+7C|;H?;&XdN)jgTJ{$y3WU%5BWQf%mgNM& z1Sv~&riC1y5l{&bX@>N}1^OyC2;5Z_-5@dR{qil9-`(zi2fU9kGH0Aur1Gy@;bmGl zF|JUHaT6`x3~9PZVPTSzboF{Li>Z;~r!Qwt+B(m~FoP>X5pyqB{{+QAyX-)c0qDpF(30wl*z`w9S_ zM7fI0@)`c-l}=u#aGLg7Jos zyrRE!(wFnz6zeqeQ5hzz>X@>Exf+{?58SrHy7J?gQ>nTEsI23JvLfBFL_if?6e`}$ zXv70gc~p+>xO-MS!VegbQa9PoH{&1t?Qriqr>a6 zLq8#SenMvgHSIpfUEtPR-7$^`eQ$X(fpJ88AL{^(7bN=e)^=f92Uc1Zq)~(XMjJa~k9`(EYUbfGl{DT|&)W=!W zwq^g7-&l->0RH|Vd&{hSuz3*jyI@yjb}pqtf;9Jc*92nQFPDzU^PWMqP=jpQd*P#L zXsUh*GpIAHx)l2$LD$00Qq)e5GIFa_YgzS zy#@ikB%m7Vct>zh+@DZ@BVh*3|9FQSIwp;^d#2sv_Af5g!TXwh*ZFQa1pJ6R>plA% zr8u?r6=SyOc0ir^6ban^%c}_07DBi96X_rnakV)A%nl;S(;cj$xEceK>3fc?v-q%n ziE=Hk)~FNE!hZHjKEr_iUzu#Mp4@8?XH4oTrH`Si1DRvFe2T8?-a{9!B46B**-FSp z`bK4AQ_})J%}SZRQfh*UE746I4JoZ|M4cS@*iW?xnxOC(_8{h+BsM}6#U6N_Q49Md z8#D}9|Kx6<+l8lLoii9HTO{*4ZMqP}X&u3F z3@b5#WYM>wO0ij7O94`5Ri3&2RiV`ZQW#Q?4iP00N|@g#Uk=H>zI6D97q9p4^XM>a zhiRBxN;m_6rMFpPvWe?*>+mn$H~h&H*yaiqyO`E9C*xsbt(FS;n+c<`c}U4v$9<*L zwx@jzIO<}Rpf^r(yJ~zq8$4vRp}t=;)Ss;SLA<&=1dxCq7E6|9q_8mp6t=sIjtuVa zhCY>qgMc%uQfteruU*U0;QyC#rzj&5xlJ`IE8iImJw!?0ES6C57rL8lD{ZK_l#EIo zepTxdy#~Vq7jF87m7lW&pa;h>#-nEEa^umjk^3a0{oNPdpDQSm8#Dk&4~a?9C9ju0 zFZ~mRQcaK6%kGR#Kr=cR`V#4qKm{+5LOZh|3tY% z>C^|Kc*T;IXZNlKpKlN(g}w;87U)v$a$TRcrHna}cvZ z%fjMb_YZ2;f+d;~@vE0*^#_4TEcsuL?vIY)-aBAr<9E7y2R{d>R!@!T%sEc_>Vj0^OV%+-|&R0Av4LzD^ zC;%C9jiPJhYBHvBRVJ-d#!q(b^4yBia3KJr1l)>ri4LfYmqjyvG1_D#Px_DY>QJX$ z)}9&ZJXJqbHZI{06jCt)*I%gfbo67`%ajW6i$xfmd=N4k_~G)_14hB!=r|BY6-ESMxPNXiZN~Fb>cRmML z=LsNk5Rq}jwT=i0k%P26#;C&x>vsx$We6>?4fgw2a@j=PdNVfjeS0>o>wOJ*e#&{~ zgTRH9#vKJ5tIC;y!it-*3gZ_EHqkSY`-~&|Z(kzrH-+K$Hq8HW#_rnsu`ZTXRdN5N ztB#03bnn88dPiLp0t~VW;YBp<)6p13;<9idW^94Iqi$yvP1OJY1M-?ah>ZbGM_dTL z&KQsTsk!2IlKy_2STytkR7zPQ4(r_QuF2Scpp%c}j{5mO4ilI2B+#Own7pu(oovbLcOYm=Ia`*~JZM@sXS|2`S7Uz z>o*WGLxMQ3!j7Zqj@|<|@ma_Nk5 zji`3~On!{Xk(L1bhN> z$0pe!x;Dh%2C#Cvmp+-&E=0`#naUOztkI{u*~1&_N&*iLCt1hPisz*8{pzbjYlP(6 zKHQ^b`g@7;{b@ls@&Y>DUqCplkXXEj;#=3N!9GNo6kXbRfu*Jex7%HpHD#%!mN{44 zm0I1por9?#PjMV#_dxo%EZ?6k^b7-6Y@JMqQ_jf08?#d9?Dn*m*7Pie8`4qf&ZMQP zc`8;Gp7RD18W;rRKZ9=v`2h2tlX5sD9Ao#Pii`#2ypnh#g8^}@%Y5BzOGvZp$qn;> zQ=oYB3`vA zmi|PI#3)7U3kad3anRNMS^Sb`I;fw|2fCT7dvz3VjSxq+Hh50zeswUOF;{&tnw~_) z4js5)5cr03Q_%Gh%<(h1%q91;1Vd%S`(0k9MBDe+F4=m?aUEu`C2~KRq}BUN=Z+`T z+a0uo?2Y4R@Qxwz$AGo&t$tV!heVCOFk@kG0-UU_p)7EA%Xs9fYxufnl4lQ@<|c9Y zTF+%h0#(H4v2CkC$F7Aco;swF_ovkVKGFTiI9I&7e+6RT7$Iiog-C-|fXl?1*~eGK zzd{1mF^Kg2XTiZJ=g%4u3cr&#~5;lH_X$JZmBLAVJN zfH~)8xMcG~_%)zpRS}!c>onn7zsWbg8p!!vi^MNAoN6fY1h~`A@kCdfpz|$eTN-a$khQys5EG1y);fxkWL5ly#!=RnT2O<5{61?kPpU5 z8IA#FUAVHuCzU!RPdjgpjg@TTF~)%GR8C>NXKeFG>|WkW%i@6!Mk(x&;A$3GJ%>rQ zXL1$Wx_>{u8R=NZER<|2wH2iDCmo5a{7{ARtS(QI&q!-n5<_fRLuanv*x7-UFEJ{Z zPgk$RJcb?zVEj-l`o%zQ=g)!+3wwkiwNV!5QKZs&OWxg2iXZ}xiNPATrJ`-(j_~T2 zIWS~;(#%YZu5zE zne829jOzRJMy*j-*r^4I5ZjRaPWidfxzL&QQJgH*XxWYJMy+T8AbF4c5k-+%wiPhQ z{;xrQ+x)jgNNhuj!n^E!(JaWU27`#uCOU@|2-3}gep|hN{jC=OLD2=bjV>5s2bx!M zic`caprvOV9Vkk=b6xIWel?JWtHPW}<*l9f{V=N_R6(P}N7EE|0eFdbPO)@4C|B9m zY}2sVHJUG}mSwr=q4nI0`l1Yd*QB}k;aQ|$^K~C~fg+*_LFiIY10RqVoMB_M$8r))sn<3yw_iioKlrb(Kj` zpZfX@)4p1&BY56px}WczEjzykpmgUBsOsCee63ShJZR<-vgsj{1-25S?2=AG@wP34 zR_X$sP!T|%y+|xB!TR=Kir;?*UknRFi^P1_|2-Wikz*K88317!>h`=GQmxiz7{()l zx79_k5dNXR^rL*^G$X}OP#wQYX7F5$tAf*K9^v0+s%(d8es_=!rVA9Btcr}uJ}zpY zd5?~vp=|B7_c)+09tO~(Njd!j_+9Hu`EMjMXgm-kgzewv)1$T)mTm^G$kLGCXKn!QBb4-Xva|li!&Ci`cge$jmuQzm@1R1i zb%lvlIGhRv8eV`5`?be|Ui`~rLLEt?)2ePwzX|*j@hUTpSokifX;|EISXfz$pI6Z< z_^tewk_-z+<_pGgz5GZvu6#`+$DidK9R;VI1bFK1$z(+MX`%ZlJn)re*m)N`x_5Z{ zCM}O9A=csx53^4M_zDQ0AA8;fDZ{z>G5Z_j#q!wvE6VE+oTyL7;9QD9sF&}5*OP37@n1P8^^sHE{n$c1 zz@YM1WBhUrZx$!F8jdLe4l|x#0zN%MJwvT~G5jFHttUx=4CIPibo~GOnB>&#rcv*N z55MJ^96$Xfo`=$n$w1m)g*nAQ&kah<06ib&kpAy0j_9;sM#klTEW&>709p|_Z{scu z3PtaQ`DnjZ+zl8DLz9og`{fmq_j4eNu!|T%;qe<~XHrZ@IdU;UVB!tMcUIm(( z7K=|IM%Ml?U`nLckq2pf@%r`JWnhEI zCm~axnjsCFINysk*>Bz*)w=&O$mfH9HfK)RXee{hc?S*m^<_20^uB7{dgW5c#Lp(( z%z1N|6^952@oGXg$WnS;7e_Wv2t1yH`UbmDDZtrj> zFRS&2iRb;+L7+dp>mJ7v+%BLq22}*!L6eaTshc_o38+q%8`l2ZfI)oK5TtAD_(86E ztzUtc$ZPq?U*qrVsFc zv6dwgAcK99I1rBy9B}QikFt(_PY8rA8{O{(uPvih1wu@O9to)Df%$E6Ao)qCTc&?@ ziJgd*EbeNKO5ZcuQrl9H-s*GQ8X6{FH({5kb4$C@+zz=~fHsa8vI? zl4a68Uj*8lU1UMwy7AD(9SVm}uy#gCX(ngGn{v?Y|;>v+n`CCJd(Rtj$xO zywumohk1bPGygi0Q=P(+$u>z<@G5lgEhmX*q_7>B|FT_6TzO1=sYHF78zhvt1&|4z zB^;0xW>#y&HY!gwbyx1v_I*n=oZK;Zue|vR%{(?XMkUC(x}emvQ>Gk7)Iw9QR*HW+ zlfKinySLYt)poo$XekQv5BilUPa2X^m@b(w-k{zgJVDThn5T@VlMyIjgW?SUj07az z>L+z>Nt!bpF{>JJ$`Mamx>{R;u#*oLhp_K#(8i%e;7Q{zH|RZ4)(4L5?@a$lK#}^E ztst(@&+zK8+y6}z{OB>@;*ARv;5=GyI&V5key@&FDrmI*QxZR6ZX5XD{L!%Sc9|MT$AQ!j^{wP~(6bPH&Dyx^yjj|{S zQqnj~)4A41?I0RwTA(R>#0yf;S>ut4;L4I5+3Fc`qJ?kmy zI^h@+Rvy>9u9h8g^8PRNfJGeUYSSd#G;?qZN+RM1^e(l9H!yFVsJ2PN_e1=RZWTtO zqe1I|MW(w_$kqhiSOR3EjDk9R^%~NL%fvywOE9}cbKgX2)BpzJyLgjT6AWjQ!TE)R zkLlUnG_GR|DewEHd{UbpOM~COj5R;CR)T)G1#tS9reT(cHJk!{hoDJkFp`wWc7d$X zXUPb;othLW&#cG4UL}`_0AXH`35)GF?U82jzs#=QrB(njL6yeNhvU*by}@74Wji;) zXjV5cOW!vs)TH=Q@V|-19bR0(6OU$h=nDLeokN_D1=c$YBcls9s1w|o;*}?o0ziWK zDGw+K_!3Tfz;fE}DYE<+X(u0dV;odGNCIIzLL@GDwHffZl=NLEujmTQIQ~0noTSU@ zZ20?wUk-oYPRTyD%thLGN^b#q@eRYk6Q9XbP~hQ zQ8wcHo@OJhWoA3+{ItU={H0Nc6|V(lL+t1j*#1!o#WYO6H$F!qy(e(t7=bHGXzC38 z*Hil+UhOM3WRQwn*gWOL5~YqL)#((RInK#N~S1uh3>ffhbLh7s7T`Hne-eZ`rp= zAk;4&dZj>CjS9r;$j$V}4t!Kzz+v+)(Exr! z@`6P*Nsq8XqBH=vaoJX(tY5!@0CdA4p7QvdMRFOHNU@cnx)(LHy)?66B}(_fd+U&-qew^TdD zM1|G$x08-E`=ChiJcump)BHYgWejeA;a<(aID#=+P?R-7ufje#iL{TlKAKge)K}q; zsn;B+a50(}IV{)pV;q76@Dg32ayPQdeqv|4E0-dbfj?05&hWN_jeqomTc>Sq6&vnb zKK~_5sQ%vx1vrgHoat)D-JbU}fQ;P$mjLlI%;SL@OKc;-=hh3n64&b>$BR>u=N%w5 zQ`YxcCd)G&VN5v4G`}Y$Om&qAHqWSK}T z;gMlJldhs26RxmDm-4TDYr?Zkr&YUP>RB`ZyN`rso*3C7dr2(%joTE1j-Dn__}d)} z4)S7^>JkK*zfsw~Z#?(yoJ_3netH<2>IK8(+O7ffAAhk7kv1zj%gcG12sP*w6g(Nc zp{XqGS(NH0Ic09RD`?hyATuz^7t$BeX%;j&HQ~}?V^@Um)&dH^me>5frQJy_1pj%v zE!*bQg}FZ$A3mi5f6R!0x8A@r+!PdVp74+6YQ%S!U1sB^*0V3H44vR~j7PMbVSBE1 zd#n6CY3xN1KL2%!McD#jE(buZxZr zTenThp2=-AjPMWd$Cr};1$GJAgm^z}q$dG#LkNsH=|XDW>~yXhIO1wi7^JvbMP!uj zFu#2!xj)4apar)Y;i~YR?y9eh(GDDNW_R5~=*)2x?jbi{xe%Wq5{6%a{8oA1>JlOd zG`}H?byTNQkk$ddn!++WlC&v10#KB|SfC_86o4B9KQE`XeYaB$DK<-q+{?`~$dk&m zP>rFIWPbm_9DIyW-vIxmXNatQy1}FA7BwGo8;Zw4ASn6Zz=Tgk><7^xABf^9NLg30 z4pvdDMltF|!nfshm(}mvbyZw%d<=vplfUFJ;dXe<{kg-Ne+VD%39BYvp5_nfxjY2O zlBgxeQ7LlD_{>@}-fOH5qPd!h!A9H04ci0)w4*h31`P4VotS*_>O6^sgyCCWA=5~~ z^jivB#0pT=7<`@^^oU`bsKELI`xM_kX3T8(dCy#y}f* z=@+zb{UTiH2SDA%I~;n9?}Vr=hT{B*Nr5$__g5NX9E$Y9U?x#w2=a=&Hm{^)m>I2EgV*?W^)eiQ|C-!&8Gqh2-9rjd^G7AkL^>jwZ`sE z|COD@V;?;~^(2m%pW@07004Y`o~hZ<001I@|0->u4g~)!Q;!F~sZJAWj+I9fY6R(F z$bjk)Cg^@z_~qa86&4FON`JK9Wf&@88s4ww8XH&XBh*X(!Z-fVGKtR$;*1N5i}O*S z9y4KoO&|Gu*|-!)Oia|89M9wkGQ2REyvcs_d2rr*^{n)g=KoqFDt!uH-`J?_>|94I zNCTbnV3ACAz)H3gO`Rcx>D{is^Hf8>_3_J|2(w) z;9*;9TY*AOl}^*-tAOX7#eeXmS5&Tl@cW?PP?y0`l+&||+A(J9DvmT3^(uW^e)o%dlgf_4K}l;%%bJ^X zNu5@3z?Rsmx-dmuM@2oqA=|9bp!BAdT4t_m{O%jShfRQw!-ponsdt{wsFYvReXas?;s?F znOKfo=dl;M`jp4ZrFyQ{)U@cP!KDq>B22^&s`!jAEYD17M`OSLov0hc(#%_Je+PEN zlJAN6J*slPtiNnX$xZOh+RV+m>4;mmE@*ZV^RUm~omp0FqP-ZUR8j;l0{xPnf4`eP zT$UfhZxwyxPf)R_pfFzzxb3tfw5iQ`U0!`}^p^T(JCmNvlr&v#zFI^+r)l!U_uSpi z=Jvck^H4FwwHlG7wmGQ;v!Y(WrOsLZ)GR+wkXq5;c6Pwg4*E{2zpQMy-8u^)`$?8(egQ?@bC*R^7?6*P%0J)h849iI_;za|EDMBycztKEM1FP{Bq zxP`KM#bsuetCt?idOYgVK5*75xs-F%PpJ|-jCF%GB++sg|7O9Z5RO%utN19*S>3U`JUIpVK7$5u4eDE4 z`7*#=>1a~nPJ>fW)z62E4Qu<(=fZ>i{bg{2?vF#mF{hlI+~B3ln}N7^AnBg-q>Sox zY;9d#2UC4$*ZTVUgYgb$tNh>J**c{YmsG-gsm)xF)bq^xE90)Sf|B->j^x{+qcx zs(@|OAYpmEtgWS~#VP~)3~u{IrF_Yi-!Moo+PZ(1x;|dc22t_~3i|Ec^s+OzLmL_z zBuQzxf9UIHFDxw;xlE3ZjlGBFWQ=-ky>2SHD(8UPCUiUpNh%4-T-&|6$Vx961;~@}kbFOZ2Uv7F9Fl0)(J=I%C$+?lh6d5LiN6JX=D*O{Nr48K zLP0>ix-RD7q}mLReu7vNO;?q&BtyFF*&)SK#j$Uys6x%CrY=9^Ll}M=7aWtScdXH$ zR5-j095wPz8`?c(UZRmjb6%Mr$=BW%plvc9!;r`QS|pQW~xC=zOa8$uyq$e|EK#wD9t;NvZ* zG5N4u`sDSC(DN8gjbTvOKE8xL^(*!zRrVQ2!Vp2*OQPvVaxmTSeNHHG8ySy3{|CFx z0p>zw2>E!vUPlp+FS)4sj4yNwR_iVmY(Z^S`BH|Rn-iB*JH=!ia45}3BMc2VhLaPE)Q+RT=-RM zY-&n)=QVB=78NoFD~j3RqZ5+UO|H>?>mowfl-&DSMn=YVG>NV=vZoRyk}qx4T%)fC zb-8Xz=&VTB`+DHR^z`(t)3?#E4|c8IGBFyDt#?x3cDxg3>EIsXiM5d?$J^=8k=rBr zZG+>UWDemXB)iQrE1YUIWl1&%Uf~}D-xYhv5=fyEO|Nw#QiHaslGa_0nOI!jR zI0=tRe+b#}UAzN^@qx%yJwG$?mX2~_XDo571}IyRV0>DvD+t>9pAagJ@ugHg$RThr z913kKfH=3Szs}ABy}9*g-^^_R`q<#c3KQ0sl5iy?o>0CL@gfQA@1!1jw2yCjKVq1N zXL&6*t2_hHDkXY^6e8{uR`Nlavxb$>!mSVfwhUFbS$+Tv;BRM3xT*R;E`A5ajWkGz z38OSR!g%_VbGRo(G@pE*9c|aOwL=>BTe5Kz%zp1E^kYVh>c4g(5{&>-W0%7uqu1{C znTOCO)a5FJjdNKfMqP_#dR^qmW06@6Kql@2p z(Qn_nvhn64)tz@~B&}R-tsm_n!2@j_n9j~A%%dJJ6AhO8Lg8|Bt;WXE8H+5El4FSN zBIOBoa;Z8~tAyM2{VN9D5KZQ?doyL%$OaQSn~PV*|9z~n29Wtr`}u-Y;i#`osa~>c zJ`XRs@jzJPdXX3Wr?pVnr~U^F#PQ~r864W6;~IaHg;KRjyg?|^X`2r}J*$(0Gqo>u z0mX_0Bn*62@6I)Xa^{;Ba=6}{4^d6$_ed=5+k~p?NQ2RYkBto!*w}qW<$7(4$y?5o zyfoNqE;`g1z1P6v{KpL(EN93RPXDjVI7)QZ`B=O5qo6G zNx$!NHx%0PkkA7g6u^!0KOVmbR-4w$j0e>7GTD`M4`>jQG~yCL4rzO(!>fs5a(Zaz zB_RQ0k7cnvij*bpeYwWi_T%l@*N&bPNS_T>z*j*c;y-*%hCGINLnakkpX56$S5-G< zP%me7>unAP3m@AwT(6BMy}Olzi7Uv(Lz+*B%CY%}LG|ERRZX3lR?g>cc)IYU#^laAqKtmE{U?uo;ul;B?XZK`+>Ka{ zdY&hXHQDzvjqMbD1Rs#srN_Q8Nr!)N|2c=5VS9gJwMOSGJPJFm#Fa~LMKuvNUgTuq zrSr}iok}MWrBX;Brt|eG>+oD;>HDQQ(@XR86ErlY&@$o654{6Oe*k;^GPB?4r(KFpr(Eb9radG_<#qO->hQW^^$!v0@)sy8Y97M z@%@9DRz;Ut)G|Eq9WehXe-<3=--&2_eR6+bXVhe{MJ)Rc{#_*L2^fFp{{bqF0eCMn z_Ck`Yvo{JEdpzn@u^{F~&q!)Qi1xB|;2!fT^Yokwz2w#j?L;-*daTr%4!-~Kf_PjC zpghL4@3>EKwC`Pi`Ht<9r};peIyV4Ske#|Xvjo%*#V5`Udu$*49>b?OB_4`;?_pl| zcs)egB*W5i_no-Vcy$1l`7rX>Ds|59zRZA=tHi_aal?I$*nNHH2+Ef=6g&(SIDBy* z%Mjg8{GE1zaz<_xblAlCZu`lihvBiDgk1&Zpz-)@|VJyo!QH z3$Fez!_gCE0Cb^IHC4$+z#;V{N`M{-R#G;+^AIzEEea6Zf7EWSKO8f5#qboZ+Vgmt zyiXM>;M$P*UZN5Hs=JUUF3u@jOXK;&hwF4$l;2qUMuhw9%uB&G zlh!9y&FA88foxw*w=d_la|-^b+YA_NH2wtldZezjTCI(WhmHU&RlY2{#DeJ?g6%!zAS_ud`|&@D zy-*H3<%Dm`c`aO(v`aWLD+Mf%;XXXHR)}PQC3;c|hlO)i4O+;^qf`;X@89F2l^FCk z_B&epVj-= z1C-aSO?Q3L8C6IGzu~#^-qDorQ9%BSdhNe+1)w#Dqa@{PxUuL){IIop7!UJa)R$f9UyQ# zg=74qdXo2X-8q(Smw)RyX2WGp&KH!TV^^aCKJTehTTJ$_0Sbs_=`6;quK7=uc%+j9 zF<9N0#nPR!-Yv@#XAx=$lb`Q9P~yVJbKuVEhz$Sd+wHs5z*fOAL>Kjormn6{N#TBt z#!*N&+Uk0XGv)<4x9=+6Au2%!_~QOkMkdzqNG#wTLOt(@Z9xRyE{?W=bQSNly{mQR z!(A;6YekaRcS$-g3LvI$-C_Doy=CGv;Wly4Zvf>~qYC6=el`IqtWr-H%Zm}S&TsO; zq1VYqTe`%=v$^tXW0Sy3d)wyu;irc8b>6mDKk7#vA8K;|gh=!t4Qw1Flyk1Sh{Vuy z)GboM@X;B^Nou2lD75yIY;oYD?Jsh-U#kZB3P-~v<)YnC1rT9;ma5tQNV5It&)9~A z)G+#_eG%INm&ie=-PvCX$TVDIlegfgJ>kA>-q*KugzOn~>nIK?k^`0rlT2h+kI@AG zf$`#iC&f1icz>4F0bclnekke~D8cH?zWL~nvIw^sa#CEplxs*^|0r=pkiQm*ZLas^ z5yqg@_ee05`mGr^iJQ7@#R*MAdu8WqFk9Ta4$W7RNk0usVc@rVDyd{(HkY!9QPm>z zEdVI~_kqX}vo_oa4Po}G1xdz69=ZFXpjC)CM(yub@o+V%AWIGbgb5_#^tV-{D+tX# zfpaXNaW-N-Y8gZ)AA)n8mNAlTIsn~Ao3&;5J@I9}T1cPBAFa#XX3~`spWmP!g!?hU z?#3wiu{W-3o$cDd$@G@cJrzDsx;-}f9^(Z8bR|PLT(p_3SFi^nrW++ z6|Eiw3K>HvgRHq2{jLH@@yv|E5i@2UxBUD@-z+d~rFhV8AF4&Y`%t)-!I@YRAuGQS zVq>{Fh)Deg`>jsY`=kdX*yG6mK9k`Gg*ot7hTIU{ftJc&EL>9|-H2K-D+h>d_J`xa z+G%qach4MQ^QHZ8n(Qm5Too0$#9lK9tcZw+n6;K;XY*Y|_{o=WNxHreyl!#IX0j)3 zHurG<1y#vX8R{#K-HP`c{^DBh{^r~y!=L>zcZ;=%gemIQb%WR|M^yqe$f7yfE$9`S zYL>BOlUbqZnVj%2F|!w3GX<2npB>}Y zJ{*){thn$e9vQBs7*Hwq7{va&8PP|#A;cj$WnWs&?WXapO@XlqIblHWw$Yb~@_jon zmaY{lO49EbWkcR3L18<4T#{NH7gyIowD%uWO!a!VF7d|Re}K4*LIcMEY`c-3L0Uh< zMDXb%asL~&Gr_%O)3o81@rWB43;4YYxBVZcGo#z_ZAOapeq!dy8TRG%zq5#cf%bYGW@6COZPOjFJ85~L>TN`V&jX1p!YUhSQf&mwA)?UQz7MPd90KC zHl*7`syQ?%rI-QabSvhe;6nVVronPC#ihrT7oQ0cTZ;QLAx{j6zsc)3Ew zCjJZDxK021TN=FrtHS>TTLcQ6C8<$c90f`Lba7KJ4BvNj=8}yD`Y8&bdmaM5FBx9o z$k}6&kx2!hLVmePvOia2JDsc*qIJd$0{Br|TBRkOeQ9(GoqALg3Ill{!AcTeX{ znUzK$;J;5LiMLcM266r$s?PE+3O4H2GeZqsgMc(hiwxZD zDIp;+bVzrHba&U8=RN2BaQ=t=+xNZqUh7({9x_mK&XUi^h0e)*?dg@0a2&e#(wObG z)dZ^K@lHj7lz=ad--7hDmVGs&YorMe6mRlBmOlhDB7vYFbY?GDAFS!3kN4@-=%u4= z8z}jV#>DfuOhmbq1(|k959pIHp`|p^%_Z`TX)q=I_br8KpZnFz6X&}-pg&0P0QHJJ za3@}@RlANKO^H%fXbR|ts?i~ga0B&b6Oa?q-MqU93qYZMKVjtSZ zx;72k+4(N9h%9!dA&u_M5J@+6V@4>00klCE$Du}xR!r5s`A^4G z2r9tRVUU1M`p+ZNP>Pbx@EyQH_R7CMv11RRx=j4O37Qs$bC8!l3dc>r?CfwpOeJwi znduEa1Uhj8z_z2tfRKsrO&czpx);CWj&ZU{;hu-RQGdeVqK{RqF zjWxrc@E$p$y#bCBWgM>imQVaJ5K3DD@ukg0I|~!|+sS26wdf?lFG7z^|Lm`v2;mRV z4(qgr;Dr`A-XuF6c z_lbuE@Bo@CzD1Eh8a~>4hdi9;wjv0Zzp6c&B-)cymV=Tpk=3!>BcFPonw@ksy<_~* z)1bk-TUWmH%Jp%^y9vAZ9`-%;7lLXUHU>a~>-S9Cn7%RR&kfv)KcbDy!mxe-r$k8w zIcG}c%bPFtn^2TuQ88B}EgiZfd#b)$1=?}jK0dPJl?;(C9ze~AdOeU3=ARrmY9~!S z!3K(%qpI8_XT1iLv=8BnQAp&JlD>RQ9v8(GmCnNU0%&!lGw#1=8!~=2t@V_Gil(N_ z6%$<6w8_a+xoeA$D=+lLdRkTED!rgb?>ddZ_K70jK(P-#?U5huaq>f zWj4lR>eAw)pX#GX{Y6@DWrnRl&FoEA6@3i~=za;@mvkS6#6|wruRhoQJkC98lq2q2?_pfQDKvHW`-9+&FtJY4pV%7tCODD{3I!Lw?X#{co`P}O zYeF%|Kptl4rh5hAGtXo9TBAaT2L}O~*H?e+huH20JmYC*=*o7sId3m(v8Hd_10FFq zBkD+Z@QJkO)hQ^FctDbL>MiM7T~H#?2cyh|e`~L)plNFmvh!F)zSWHC@4q&=WfL#Yr^uYw`loPn90lZApJ^5wCkIji?eys5|%s$IqnU2 zF!Q(NUDU*lfA9Eo7?-W|AmNr=;wZ(cX#f}Wn!^Oh9UH7=`sRlDbt|$b&lvgLY+SAc z5uylDg0|SX7^Ya~|cIg3S zbw$Oor24uVgm8VYKTs9vgJ!!`^1`oi^>qN$bZMJGHWot$Z1=c}?A) z4%z(V>=8bPUlp1jCm5T&9FJb-=AP%-#QW3~mutLvn<}fbH5Xmg{CiQcXwkE9XiC)A7F)k)y$xz1%UG5BR0cH3;=kKhRwY?ovZHx1o9E4Zp@P;XJ?>&B}x=z^{g zp8b6KXlkE0S^wHM^OjJo_a?d3m3bn_^BIm541Fb868K8bLT-(7iZ1#?4q&rCLt{cH znXNmL$DHe<_bHJ#?32YE)dqJ$;(>I&CKC5dST{*GM>RIsqMzc`W@PXW0GJ{zmSR91 zvmumLXDIWnzV|szXp|@BiWUkXk`#9Tx|CE96Y$#K?NE*|`($O;m%s(-5P+iq z8o7S@z&m*?BV#g{ual7WaD8(?gDFH&&LggJ^M#E{s}VUBQa-LYuvQp1Y+b10`|xd7 zpUpq(G3gN``E)X%b9ZsNNYJjw+R~OiL?To9aWAU&V)`g$6K3$M8%~c#=R%@OcPR7l z6_ZKN`J1H(gQ1YuYx^KZU}oi}GzBLkd1h~*krue!anW_!b9=XZF6uEtnO@RnTlYwi z^1r_6NF*%g%fK(tLFw9KZu-o8KW#`72>TV%$&%V^Ks+wU&VS){lQ=Lr zB;d!#MktJ{_B`n*Cs)dA>P2fT76@&DyKbxY0Edv{DctzR#Q2AujuK^AdCB|JUWF!) zIrY0^^JY_@8D@VNwu>&x9~51H3~nWJ;9Ae55vN3C1*W5W*FFEJ2ZPHw$DFl9 zUm}U$Hv)gL^+Vb&4+x{R;zJ`T~DE473#E|LUJk~nzyO&%x$hNxKyRN6LhlJ1m zn^n0gAfQXG@B|G3*t^Z+WW!0t11|*1*?I!HP#4&L3{C8a7}EB8@T2TR}r-SberVHT%pwRP*u=VrAiNh|CHj2mmYe%ktpTn6QNArgd#+D6(HcKg#9Y!i zSJxE!rgWSx;zOY8uDxE1PXnvRi(5+$vX1$z`A_c6zf_j>D0bQC(S6NTlc^BHgDUy+ z-nF6MnAM~nYL>SEm_uPldT zhox^T+hFSw!_FihPvYi>{U6U>6+}2UgdV-3s`}p|9&iJ&jQn`{>a^p0;$?AD{spR` zTH?0hLxD(k-bvN0{YIiBlFBN}(cF>X1o5zJv;X6O(MAx@&{hfIM6yY=7c7jbCS(2@t6>Gp}n?|!UZ*A@J~1Dc^cg~G=Ey{9{Blcy3aZaPtN?%(M`pddLd!MN zLPxb7H%z4->lEHveKNC?+|#=C?B91kmdJfYykIP81Fhf&1xAoW7L7ZwrzCf+P6z1e zfsgRvl$ix!JDf+@oo7~r;42aNwIEG=u*v5&h^s}bgs+9Ikk;&Bq{J-V{8M#5>`6&KvD3J>0X#o&h8MLLlH17Ag%E!LNXZ__xI;Gc5OnM%`xeU^YuYx3~SqStknT61;%+5#{?U zvRIf+IpOHYn#c~&2}wS1@y|j^Tg+slrZQDLKax8B_7WL=CW z9)hd$jqcgdKMVLI?OUWn9J9^up|fuiSKhb36&Eb^02>lP63r%?%~cZ8*b@Epl66gr z0{|3gDi`z9ZVgt1n-YBJFK3uTtr&ih$>6A;mw$lfG?%ayRg#p)br{A!5Q%7a2U6`QP^-o}jV1+#EqB18n$KAO8HJg{d;rTinn|UcdYPT9Q z1<-G?Jlu62BPETyX+)aP>5`8CW;-3$%f>jiaQ3<@5o77*s&|a3)4E~;A%OSL9P3g0 z@ZuArpunoIuQmL#F_I7&{Nw3pj>3BZ8PBS;ZozMoP;5SCH_gK+jYg}bJ7NdS79VPBWnP7A2SmKBq%ypd$grce?~mSPvXgX9 zf+X-rXdJY7dVtQ_sJ@=R=rz&lq+^z8{AYUXw5t6}XM5bzZs}dRY=V{cPv-Wo--;ktXd% zPt9bTD5{G4rJu)h4dAbQrIG;~B6tN9Zv>&XYp%aAyp8>|y-9MZvSlEGZVASO$HvJ& z7x#7fif7zTnZk=O10&!LUg*d_^ioL|n)Mn!8p-Or8h#eB>@MT!x-4MktLcivnhzjp zbg=a3%JX}Q&>sT&I;KClQgV)4$Th}9B*b){! zDRMsrY$Q$b6N=$Mf#_9e`2F;AkSC8%<(sjbl~PGg3N1+o&sB1F58~US{|!=@_G?${ z0oB4QL}}-0{3z&m7FNqRo7uL44JcB+fAZdoW1&m5+i(AQ-vwFgNs;Pb3yS6s6ju7` zww(4-jRaSPWGXR@zW520AHVKNhgN$CBr9U z?Vf9r+!WqiJNB`3RWqBQ;5Az&B7!?U+t5{b8Q@zzftJK(5Of%oD9f;xlGhES0K6`> zhqWsq_7I8{#(KK|M-C>oQJ-lZ>=%Lb(g}{it|qEQahKzS{eT41%=h_h9;IYh>9=1* zhsk=y^oYR`(E9gTOc-U8Zij`>noj>5G6gT5u6S9rZ4*j|9f`T}EdxZINQ`9_hq8&b zk({1Xw4mcQbc(1@Z5-#zC)#=$UL0?{sa@ne=YruyavP__v&-265kz2s%*kr#_cx^cyE|6W zk?(lVbh$!v@~dVCGu6cxNA=%~{H#{EA>iNWe)IB}fel?X6Z~d%&Hlg{%T5|1Hjr#& zT+Anfb8F5T=eEI9S88iwbllOlVC|3p6^Ch@*1EJRFx1!Wlk$;IBE{a5mtz>C;Utc( zz)bi8Q{9tvNW#D~u^%gFYp1o|6`#1NnW}jPrL3tpBe!OzS9SL{LD_b{?_uiNto=VC zKX~QdS85A9%W2&amt z0~_2uARk{Qb_o86bRZ)R8VLw}MNxhcfYJDzvxZN!8%qP1Qn5SmH``^$s_rmUfszCK!~wwn?j(W3dj_2Ez9@|w#Bm9zAv>xlB80B4=sftUq~X^j-d>|f zGOx1L0HPqaO1~LMwyLZKcjEF$kp1>uZWUbo=0l&2?JpaQ-0MG#Tg~o%5z~{iXr37@ z_fpmwT>refNyils*Ze%cp6(S{f1`~L^>0_Ky|70ibNvBXBdp1SeuOFG<7Ckx%k5^k zI?s*Qz}@tEpN9JEEbRYwJcZy(3BH_3 z8cYbv>g*|2w75hu%LSOmG{PDfvUN?VqG#1PFdW*;8Q*Y42*)!l6avNfqtR1@9dpyh zL+Ji4DFk9~xL#0$G$GHP)g7_9x=Cu}(oPQXh#h&GfkJsB7(+>fRGRv=%ro6aqt~2a z09Z#XvoX@~6c2Qb%2|%17Lijn!J^Wt9wJFO{JJydl#&8Z3I-&E8q^9LEzhxLUoUh! zd4IA^xeveO7;rXg2|kTV8S7*ya~mquN%NZ^V|U5vu&{%r%!*tp$TuDola+kUfur$~ z{+&AUoTJG~@aw(ob0Jybv+H-c3-bBidqv8>9RC9nPkqsMv7u>r)i{jZ&zV!E5gU}9 zy~c?qhO|hw0{&B1XJR&3W6DP3R2ZU@Ypked*TU0i(qX>gHYHF)=-ZY;?M z60Jq;0WYjq@HX(!UVvopIG_lhqvSNRK4~n;g(rs@R+%l7wLM1E_vT+lfm)h1>G70rSVDY0Ytyd zRd#*t3(4nqg*GhX2sPZ5^&Id0wKlER&*9{mQjnfn^GV*O{sgIRq9(7$`Zc@T(q?#` zD$PV99ttzTPRZ8lOT+Cp`q6WZ>+aCm8|L*xmzIaridda8zq0eX+t7K}Qq0yT6U`P$ z?LT0;&zH^A`}c0#CQf=7xLUpYEP>;upjXPL9(0lj>9sHoK0VaU=Mwv}*1|&;qu6P~ zri6g_4E$0c9J~19oDu@y*nl6_ zoQSm_sipEiR!WVu7cv6g75U`#iU?>#uczPuj*|d)&w0cFe@Bb}rrYH2K~5CY3d|<> z7Y@`~BC%-d?T+2VHYpExK=F98W*=fwVSy78e-!J3r8vR9Fx+~(u?JE#VspIwlMK!i0Cui1#F} zEV2Y4S>^d?5rnw-@IaF_B>m5^sQ-4UO?1ujfC2@Ob9nO`lsqOl&*(<=jaacsK)Xm^U6~G*w?gQWnuRwbOsc zZLDhtGR#!5*w`j4TnWDYNXDTyw~V$<9k;a&k%i%2WgB8ec<#V(#88rLBsK!3o}b6G zTC5Zk2WjcWi$YJk#?F}-!=j*1VkwC~yDpN}IDC^U8jFvPys5HXr=BCvph`U0bg|v4 zO5a95pt#Jh;9zB`^Ix^yxgy#hTqsyz6XlKC3 zD%-p=8eEG}6Qlx!mfD%c=O;W1D&L77Q|H1GZ49klOR36V1QW3faueGY_(tQl@cWhR zcD*3x6TFpqTN83bhs0ta>SY~DDXbDLwtUhCa?)x-iSGSoeq`hQ*oP;+6G%JNVz20} zAKHb^p`79n;jqU4j<% zeWQL(Cs>`FnOjF-ip7MaSSg-Q^IpB4@_01DrJ)h9x@$h=_T3^(tHoqo=4|X2=IzO9 zE$ozJ^KWbcUqus%8OMaz^tXI^=$a>-U1m?OJ-%gVr_tu9YF%atL%S3LhV*NiSNJ;s* zOTQD=u#f&I{VSMgt*ABh2$I_OiPKItberXoXkYkzTL@}8O{lW-Bb}$7TBLhC#*zvS z`o!V((tEc=&J^%#pPv{TN6%6H#+f&=v{Z8O4CkP@@T}14Iw3p#AGve4SxS-e&Iev^ zm+wtW+z~XU;a*$)7wg|6ur%llK?1h4 zoG=1Y#+=eX4hvgM>3}qa%K-f7P1!r)C^vK&#bI*q)lD6atgE*5!GMSvd@TE=SI*`c zE0{*Q+9u2XpVGE2ii+(|sigr-oqIYV=Xpw=-T)9=#&tgQW7UPTr0dvw$U|&*m~$-I zn{cmSJxCiV*eaHtvF~F>C_4vm7 z;XB=3i*rpK@L>{AjZ~WJ+{4?>rnY8p=zYHQhpzW=q+>Iphz z0XH)H_u|Jon-tFSVDwk)>^rtR*dN~O=~;3AIS$Oi%}Z3GeUTvJ6XdXhCnf;3(<)HC zxIArS!bY+Zlh(wRtDWnref#y#;5BW=AlBz~p^^Pa>ZY-66*<>5M(8;$#*1+BWP(#J z23+!2un1>6faJYH=(fX-6e5p$TX^O$hoC|bign06%BHlT$E=-g z@}e5m8aS z9l8BA8{4S<>g`jxNoEfY!uT^;8jm5p7^`A{Ai7T-yCu4am--OTETub^a;Lv|DuM5+li%W zNt9Az;DQjf#8(5Ow~L?7pMT}+p06#4a~`>LgYE53mMnHgEW;ry0W5vsrQ?y;gtK8% z_r`=bF(NZ!%CsIUz&n(DeyXL7V%cpo{gF8IagpPH{shaYVirPXS1e+Lt8!0| zdR#8>1y^`(ZbmF17qN0)4V+usg#fyxc;V`t7=aaD--%a$$aNgE+Z;=?Q|F~A4k#4N z_&+#SN}h%Q?V@!~hcN^4Ha{_I*hW6j{lpPQsIiSYMOf!5eDVUk3U-?Rc^<{fbwI8e<}U|*zWX`+iGf_J=3S?&Vu!%+io&GNGJXK?7H@r z%N4JyC}ZcK48P3RA~pEgJyjzBi)t6VO)yKgob@)&Mo6xal;$x&jo`2D_Ve_mQ@YIBBMhqbezS5D)$y(9v zz&0EJ)<&``e(&8Q*2dypWl|1hd|$7LZL$D5!eD73298f^f0?A_Sp6IN{r&${JY=^!_&=Od9$3>qo@uxA`~y6}VUrQP zLL)CI+o%qkjwG8<4!;bt*Fqiz*i`XPm-bJafUwJWTw)3EvpwgmJHv|Ub1_?LQR^f6 z;~g8bTMz1$pkF;k#Xdga>Y+Q7vh`b!;D+8;bQ9c7n3Zfr337K>F}Te%f7!mI<2xi3 z`nsvXMsCNpGDGPV+1D_i=T_zL zybzaY@QdDZgI3gHAFVU%3>2AN?8NL7$w;w3IwaE16v2EVC3BpYGk}vpwNdsp_s56z z=f1I8;(?$pSGiQLr}WXx(sMf6S$GBKFLFXByv;(b!npNt>Ab87~^_jx-u z@u+dbo2WHW6%>QBxPVz#7=J6N!}Gb?s0Ix+Kv1B-e!OQeyfO2k77Lt^t=% zb)8omSaTZ|T+pEu#Z-x61AVs^kjD?sR<%4?t*yHY0F&;^DSC}vziZYr>hSJqU&an>_X^q(hYo5arS2G1t4_2J)?2b<> znIEM*9wQ_`|Ml~;an$&rRbI&_A2|FNJ`|uv+#gnt6 z(l;={38LgP>66QNk1FrVA~FAG3ve=`Vh{5u;)eWAyMk!vx=S3M8e?p>t~aZa5Hxf-P0z#+9|i54E( z6)r~6#PIK`>nhEz&Awz|@zJ{NX&hpgM7PJC4q8-#(XFLZ6n27&s7k7W%0S6HnYTw9 zdA(=|A}37t%8acYD-urhN=lCCsCUCJFyMtKZ;Zpg>lV!Wuv}bE?eX~l!kf?`4cWm8 zL(##grT&7%8r}uJXN>GP+vOgf>*Qdw@!h9;?Ua zXMfHNllsP3*;Vo*Q4^Z61lcKm^O4lYozq{OWCRa%73q^3B1P8@8~urPWIX2m2?@&` zTBDDL{jgBN@el5c=0Zyzd3z$sR)qb?=K&~5b?(hR;Yx>{SGZ&lnt}VKVc#~#>Q5eK zwDTXSEJvmOY)T`)V`O)fm1Gh1s&OQ*Bm|lZ;6~rll(u9X zYU8$-u#9Udx);HbL$ph1BY`1b!1iq2`{i1PIw=^$V8jXmvnD*EJcONAL`|KR2hBQR z>P_$3=K#8Ip<}5*ASuh^gv9TpH#*r1CU1lkZF+i!QsLxmvg9}tVm{# zs$}QrpYN+LQXbl`4{A>EBs_<{80_Aw_;_I>43SUQN~IDi!_BudqzXQrFuOyVVF-LV zZQWFF1PRMU4}h&!83oqqmpB~0a#}oq?)LuXixD*)jK1A``bnE!Ej z7WD58ed!U2vg3(HQ1ipCcfnn9_q2Cz3l=qi1nlx!H90o8>fXI9j=U3xH`glWU6Mi5 ze7TB$yJXT?`cEs;TovPAX~iM2&IiXcH#+`{_FcK!bAwM!Lv4I%SW4l7V3m4@&qsbo zvSI+|w%?GauBC^gpyQmyWY+vQa36I>>>g1ckDf>H;^YHj z|LpxiaZSt|hLn81>;5JaRies<`r9%xn(~?`maUn<*>MRE89)wzX8(~#2&QehXKJ4` zyZIn6G%_I&_4P~lAH{Rb72r>*4Tm&@2IO8E_6?y{ge2$}eu>kTID@t?R4tg28-R7!$VYVJCt4hl7wk@yM$4Yv5dvP@p&{gMxn!%}kZ0CKlbtkn@i+^?uzkl>!D ztni=2N$muaj?imGRd5>H3Lg_^XLuw{KAn8<6QsYS-FORvJKzA-!4!xmVft}|&Ek|` zaFSeGrwA#P`9SwAhc5~gue=BlLNd|EAn=R60eqB@(^}Q7Bl%%VfNSkpuN#V0G+9eC zv&E&)B}FB_b5QV%1s;u8)Ujxra1byjLT+U(Ro5y(>!g?_ETKR?9}bdC?oO!Xd66uc zGXdZ2=5afZh!xa_f!?sg0W27pISKtvfs+)&#CK?2`Fr=dC!&7sG;~JtF>l4bH31FTmPtr9qPDxcAU^)FWYc>f%>{>iv4&|eW>EByAX`;*KKFvT&_rhoX|B1mZYk4gS8 zsda!{XX$Id;U%j;I=n~dx(gMbf)qNolGlyG-=~X2eM68R{j-!xnrh3nzx2PT{3K^F zro@jrrs}touKB(_(y9b~Q3w#XY;JD7&oXK?R_StaWofPVYeB0Ul2n^?JY1CvHt(qX z@#Dq2$v?ImEFB3)SW?#k4};71F^*52fBgTy=IS=1TobZl@ikmo!>H-69Wgy{6^;$#JIK1gv-!-(dNfB^Wb9J1~TKrth_>f z+<#C=7H^~2J|gRQ*wTO}+;%=RJ2)M<1aHkrdP^tVQF>J_OwL$w2Y=TabGZlVC#vGdz$3b3^zakrSYZH8VyT89_Yu*_v zT8inJ+W(!U9Pud~o(bnuuLRlwXdvbg7uolDR~mk$atPMXLYq1r+T;jQK3+n1E(}`e zPdkG~0PJBkoCf#W&PR0MB3c< zLeE&{kEUrI;^m#tJ;O2ZL2Kx}#&VFBwt1Br@j2jWj`%H9&Xh-+#VonME%k(<1(sal zD`zvtjH5TG`|uF7CvlD8jE(q7!%z<#1->3Z|11X>4_0Og2b-c@%ebWA9$2KqFCS0P z_-sa_zt+9pC&~{P;w@I)Bqs`Mr5sK-D0S8RsJFNBh0V1((dGIm33hd)WiWa)QvmSk zMIW|z%KdgVAE(=W_@3!FPkl18q989S#pvGK;T5TL@!g1hnd|v}>=101rxaWEpUq)O z^F@ZaFZ>YmH4S%`xO=Xz)yc$l$HQr6j1XgW=-Xnyq8d6*M%|11c|2cS0M`)8&zyxn z;(-9W72Ii?^ieO06XXx+eN^BS0EqRZBy1&|B}@%>0OEQ~&bhv|DvDJ8SqMSUL`pn3 zkctF=0T{M_)$D8E@bLdpP@6XQ=YH}_BVYITT3jwYRBzYr)m_ z9C~FV4wwN?NgL=bCuhgToxFSVW5FyVNVa#=KrKLRvk{By>LiW7!NeE*k^YHBp4#|J zoM4QhWbm&|z3i>yYYZL#!HQVF%=Y)_me@`Ax|$AZ+hxeHrJ|TGJs6iahr{10=#Y1s zgQkksmA@~}*F^=FlpYYZa>emqu6}&z6BVM&_jx*3doo+T?iR8c&6TIIYhfuV3)=W2 z@qY{S5LKY+Hd+~lynY_w5M^}!fdQzaQXNurf2OJfjXWES6|lzNO+#^V^_$}!}a^pWOixA&R=qPpcSA_ z5Vb_`*USX&E>o9G--o&CSUp9QTDzWDhr);qHbJda$cRwZE_r`|!!Hs_5HToo(rL7Y z(xNo94^pnzv{A>gc{pPT1FXS7M)1Ijuexs~c{!v961#*&wDLT`b*GuPBuW=E{T6!y z00$|FRBHVN`wk*TRA0QeQA-+N%UclH+zh-{$f=F_R&pfP6v!o z9W%VXa?p`3#4iPMq%f({1W1dRwJOYPeAT9+*>#4;ZqA{7MB}(}0>E;p`H0yDATmJlh=Ho3)Qd!VZ~? zehtJ#itnrzUx*Qwpj{gau$`ubRc_Ww4}V=SxjL|-;c2GxVy>Qj0m|~Tav*w&}vrvSpX{}@qtlPm|l zq_bRV8%z~NhTp<-mGbI&W0k4}xp&Qny2PeHVH%sOjvg_3^K8s#FK*wL?RNekBx<*) z6hx4N1OcG{KDKQDjWk`pe>8Bdo8s$8!kS!KUbiDonMB!OPNrjs-ir8#e>ug*sScO^ zT759zj9p=0yJxt;!^Cf-4$Pw4b;k>0(FOCBSU$hTz=U1}@#Lw(X6MEpwtvMA;)-#^ znL4QN76-B3M-$09Ejt_v-;D%f6ZCuEJur&9E1CQ?JQyF681@!;Or{<)(q)zAg{gs2 z(2@~u0L7!}dWe3rNkdE`=U+XGmrBAZP)S8OvKI{8XM^`3{n!5dZ%;{KSC6qAycxj~6C!#-hOA7+yGjWttuDSl zjp+9b*xtRoP(y%_K&Mf8@(XrL)m?-6v*$A&Ywj6?aH>4gVzqwqemx zTfROoKN?1{p+-rzQMIKDzR|xWsjFvwEgkJck#e%uGtXY|f)&CVn*_+5L84;RP?xWR zHY%kT-|?J_hi;!IQ%D-2piUMA7dOJb__5Wf_NOX#P!miOXDZfn%WNo2nXP95)|d;Q z3gy=02$bnWqjUQG=S6kid$I@I4MHs*5}z^J1XW~rR)6V^3w!bvNBg)J@F)3i9gl3Z z^jQs6jdP7Rto`h*IzUPmatni#@ULGPi=2lvlx9!n5}zUvgg7@-DED3@1*FKRe8PL{ z0(s{nk_j;MkkG{0nv8sL>6r2!!&CXfbV@csM7qy10N3rP>IzH!%P_iD!-{`!?m(>M z0Coo+YOuFH&rw1Ij4UOK*s8looT4`rrK%38?}dKC9l_I3vK4qv5jggiitpW(43HY} z3`CJT2$Xh;7G-76rO4?&v1Yi!TMJ=4dg>g@-bOox7pu2mL%)=rIsPj!i=5thgr&$7 za)viDK4sbjbc$P~!R6kd7<2So zwCmJ)_>_DQ)YusL2y}h~yDyLOu_OXv!MFdiQpU5IvyX2;)f1BX`JYhlX#Qn~{-~sV z*zOwoX2QuMYOZ|XzGiQ4VL7GhZhRQ1=q$xOhlY`w^>;VU94MPJkxBu?R@-inZUo(OIEO zF7XQ<4Ax^zK4^l48R|8h^RYBA!#2EA6%L6Jx=)5uS)jNu%Dfa@_uj{64Y#``2Q7Dp zRR4d?y&jJzZZ1I;oQ~POUGI12-J*ia^|7^~kXZ&13dz?p;RKzkkbc*fl_~;xlc;{C z`cqBvDln0=qURpNB0{3qX(Qh9T^}UyBivt2cxcGU#zmXXlpwF?j|*9*C|Mi*zkp$V z3OeQyu+`)#)}})oLL4Yz*l(E$Q+6(tTWc3lG5U;;$8g` zJF=+c@^CZF&4}d97C{cuE~+mh^l)P9z);O$3-P>jwA@IiYV@T4L)BS-Mfrcxeu9pn zVJJ!I6zT4eZjcy20i_$HhVGC?8bn$^N#X-V&pCU) zw(9|7?aMrK-F+#R*q5zmUK~qnI6!+$Wl~-(3VNDMunJc6hIlmZc;{Hgz+=%mr^caN zW|&q`Ly##g~Q(r`#ZjJr(R)T|Hh z6T-Kp#JY9Nai5_C*8xd%a4n`Lwe@=67Q%&qctFy*RYO3GrN&bPsklnN4Wdkx0n4-> ze`JANb6WNf5lM&T0}+RnE(JW@kyn^+lGkR&qqClevlRI$fGCmfy)vvot{`#!tjgD>HPKs*}vspZ$E8$axw<3{#u(B`Iv_G zs<|VIcgo{7X~lN97=QNQ2=0;|mIJ5xaoXFKuErt2^S|efzL4_s(*N_=qs`;D{k!Kw z{yNm7oODQk-pI_dEBA~`TKm16OlOEB*Vh36#IvEx7#oCn2T3`a0g)TY4rs8Mbidb8 z^}K0Obo0jL+jh6#UfnV9WO*ys^AGdH0w=@V@d4vW zT?pYxoZBJ^$5T1#5Nqx!8azyqiJvpb6sq$^ z7SxReuh}xZJiK5jfa5f4@R#UQPuQ0T?T0iF6=EGf6qvZRD&1E`Sp($BAF*$6Nh|E> zq&Q5CA~}=>h6_vYy&POfS?3TnF)wmMg}TPj^RZ0Hh?e5WlWT^o;BK3n7*xnrba|B1 zy=v0(~;2soCrXd0FQ$Rs#*CzuMjmO*HM$n;@~ zf`*mK+llS2S^F#z-GfY-=W~CIQI-Q~mh*3Rt`V_Lg zve&2r5fiVsCYLp<)$!j`{FYKE{@objNfdYdaqGivMNjeJ$T$jx@^2He{M!NZ%Cly4 zA&n#};??lWKVBe7j)w^7s1771mdgtg&j<_%t5HXazR)_I?W)PO1EfgVEVhuO&v}2n z^@V7{ThpKte$n4(dNXgsA9}w`{19h`Si2df6_ge}pieU>N?jxptK-Z^=6k4rsLcvo zL*PLHeg#V#Z(VBr*qv`W0;eQwd~C_Kw9sIGu%~@frjb0vkrTi-fK*=%85>?6Eoqt+akBC%{KjCcbgz8plyCY}KL7r7NJ3 zL*3x_XO18_uzI(jwgzNtugHg>l<#uW`3PJ$2ch}R0_bOOuZ!N@a$n74GiqyK$g1m3 z=Nf_;wXdR_A=fTRV^^rN{%hFgHUEL=Bu=9=W=8|A>WB*7hBzp#|91{ygjm~aJ)-&r zE9*G<3tKK^_uCO~{>c(-?LZg!7lnaEB0&dd3P{Aa|2Mz@=hiSdPzmHU7OHoZmEvl< zn2-qLxs(y{_E!JgH+}rQrno|oo$7)>)M}Yy<*?V~Q~2x)sx2~g%JI%rami5aE<>yE ziA-Uzl>5KwDu|p>HO4Td;BREO?|+pC$osZU`f|p8I^L_Ut+{nDIVeevWSUk(bSXoL z|BX?vYTOtil*Rf$gfJsD(8sc_YRSma7cwQhp|i{}tuzCY&~(()2Lf0|8GBHK@CV7! zf;N)^UkBRzDp|O$B~qd#BPZ!V6L3teB9lqO&Ae^fOg~i|%TK+Dc&&b|J0KB&7cLXC zuMjmISWUx$ItD5odqHffy^aDST@aMeNfl6`>j5h7j6jbc5yOs`xfD*=Drf3FvHIzY zIFK6PPmId~F)#uK`5FHSd}G^f(ifCF7OshAk7o}Bux8M7F`eeRyr%+)xb>2FoBsR# z6Z!J7R!)C=95;N07fZ19!oi~SaMtGTg-ifZPJ93Y9+%2ZQaLREWJTEQvVRNA2LEI@ z;M)N}0nMA{^yGW871s;;xBp=J{oXwKfZy7;jA}HWtpYuJmF{P3yx7KMi+0jP3~A!@ zeuq&nw4bQY>OL7*n`isZM$?`#+J9TMBYudp^pEfQSF;w}F}EUKGt!+%RF>!=8`@QB zu7w}@+5u1lw#BlxcVn!AqQ8QSk#5-pG7+H;8XCp(8r@Km2czXF7$LB#P zr}P+HG(`sU`Y%NJzdLf??Xb;3pXAeN)cjPZ=cOwOl3&P;{=IcblQAR@FWTQ=(BJF5 z$EA;x>X#O_>ekWzDzH_^2QY`KSC<+Jl4e8E^#|oItCR+P)EcO0YNlp*sUev~kWPyn zQH%1dUOw~nwCE%{vj9)>p_cpIH0qo1w2@6mdE>V&j!m2^Ms{j4L=$!k zDF^*x(f@cb!NZ7nm<)PGr)oR^i{%fBx?y|Ugx4&P=Y^`&7m;W&559LoCmJ-xaxvPP zm>*21(1OJ@gHqh3po8K?l&rUtRBd>pwW<+;vjgC^9*$UB3v3&C$RNClM6|+hCXW_t z68tZ8f-1#lURe?-SWg#Cs+jVlh~zZ$;t3M=>Q+g1Js%w(_%SH16BwA$3kTrbY-sid zE6Xm$CUix*D=t+MB_)C;Y;9tCpKLEv)Hy$g8mzHc`=0ADw zlW#lIhE1w3?(Dcg@{zS>&^{OE^{Q+>CDPbCYF2Nn6$tszF-a1veZfXy-ceuUl*$O6 z_21XY`{8@sHY0IAH#*<(eBW_hB^_dr=lp-yX)lqF8sXfWhBX-w**iUNPFnX=BPqb5 zD1V7ijH$OoBs(^iZk^2z+Pwp&x0@fr1sZX*I-dPyeEY)8)H-Xh+6ii=`T1C6i6ko5ihqn-GeRLFy3@Oq>Sj$J1Wll4Rg!!u?rv_ymIBN0k@TDI6k zt}Yxk#gq7uqaoyLMn+a=O8$KzpvXN9GTNl$L4Es4AbN>*71S=8k@{XGs_UAWrSdTD z%?YZ5yk+&M{%>^WzThN+k+W5t1YxoRqCs(o@}z2P91;Cxh5iLHrP%37X5DX7JkT4Gm4_gs-)Qj|O;m-nW+=R5QDG!dYd?+6LV^J?I zK=uR+Ux{ZYW^m^-MWG_#O(|JpIR55lZvpp>RObsdA{gB|`7xMXh88P>e>RDBvTO*Y zlp&vN3gkDKS&{#@R6R1tPe#1zCMTPx#x+F5}8 zR{>Ismn$-_U{H0f)1TGl#V|d?azn+7mxFm;^i60;F>8o|&%r!dCM||PuPF3aaS_%$ z_%+H{N_kx4tiX>wh1Obu$m>6`;>S5xUnbGm4ZgdF$2(7h)qe zEjy!$q}tPXVZhRuFV#9H-^TGcJ9Kl3K8(5wzMs|e-nXhgdZ3Qp@@K!A9RWuiT*kGU z(owQMS89Ri0Zo6I$llx@o6-ni5KG+jzQ}CS^93{6HBq;@RuJ3z*}>G6eqs)R@`cny zpEp(ZaBORz%n06`KbADkrh%jPna=C-bnF`?Zcw`KvY*wzC8p^8sd-qW5`6B~ z#Rm4rr9BhaW6?$k%Sto8 zDwUN6HIHkF9W}m1+@dHy$O2k9fKJpCw4Fu5#7K@fVxYN= z+&R7-G-$V6dAe$n9S<1=zx%HxMl%r-0UWJavKL`@pOW_~GsjvE)<-k>O3Z)o5X}Pq z^7~2kR}rD)lYz)WBbEP)i6pf3{FWX5Pt>0{g*8C_fkbVlU%>c7ORUYD z9~ikcG~Q2*sEk&epKU+t>-da?4;Xw{{7RTfA>VqNfoAG^=e^=^{9$g?Y1ZkDpvoRT zSirQPFyf7mBJ9;{P#(K;WYJx0qv`XJs&ASjThp^ytwA%qa8aTL#c0C$w4@USD=f>@ zcetUyN%n%{LH>K()f_3Xf zGB*MrtNtER21(gMV#U5ImM|2HTw%c}%EekvT4L4Z zd3P^KX0cF_ZoWPracxXppWX+2Yx_tUTdU~^K|&51t&wS#0oJu#az6SUg7z<0_)&P) z5OZS0epgvH@znS6BcCc&AT*`^ObDo=`SwCc?@^; zGk$Lv5ev+Jqtv0T~7wt7DA_$Ucs06XG}H**8US^Pd}~EJkb%0--t;mz>q{rTYB&b z5a0P+iR7e{j;7C#*aU?7)z~?_PcXEm5@~z6FjYD`$v5mnLFLw|M;YYD?B< zH5?9Gma1>o?LP{cx~fo2ABY_i^YijlZ@m9rQxO{|_k*z#o0$AA{J$;P_$QjTb)#TN z<(!^{>|01nbzh|s^H6<7ufLOZ0_8`8VM>Pg%{$}8X%4aQ(deA1Gq1tAaR-7UfOx31 zwav5T)}i#=k-AcnvL-kK5UePdU&M)7f&hGO{etuv#BRV7+=Q%kS++yv;z{6thg81a zWe_GOSrwa=V#0#*-{sBT<7!tJs{eVqw;E zjDtYYsY!nKB#*-9XXZT7w}S@PFAGy_1)#C){X#?0h8&0dZcK-P$oFXsqa_TY<$>N~ zXmFO{q4?;cZ&9(V1l^yx60CgF${}@o;BwGwNy;@cq8fe($xs67lE1pWR+6TDnD;&5? z6Rk3n;`D%u6F2$Be^=JN&+D&_GQ91jbo!aMgNkJ8(hD{iI8c_VnnGjWT^yHJe0Q}= zMsmcb9Gkb&G%r@q0p$Nvc19g=ugdN!$nYkEOOVPA`8Hu=j!KBKD(@VeAO48xV-D~_ z;mQ#4_&5;^M$u^>$-YQvtaPf@#J}m3<8j)JqS4m)2)XRn?%U3DNyFu4vqcxnIM4rD zGzJQe%$TAqfIw-WeY8tqC6FDD>xYPj`^B%jYQVhUZ?3{{Y{Z}J_y4y3%D4_EqxvBU zJe67g9tQdkJFSrEdGR5y!CI3jg<_M0amV%xZyF*qjkLi2zR@qM*7~P2y&ZwBOThb{ zp;r4G0J*iH{WMrr^V-4(Mz1+s($9@9S-{Q3<-vn*4ms8uqcN>pF-u86XR^Q9M`WYW z4GX|Q-@uK*!F1{(j;OO_c%GKbTr z(nSIMZq~^+PxQl;01UfHv)Q!Ol^@y&_&JY3Q5As6+)d;gy&friu;L7TzeshY7?(%Y z?+C8W?MHPfZ1tNrXZuMKsjl*m{C0IK|MEr49TJ)TgA>H61t~7Nr1F>Fnxw$AdK1qM z$AjStY-K0W zgFKB!El!#>96s9|i?439e78G}lhGwjMCPb~DlG}*qu6xoSjxTnG@{=LJJvp$oKr0f z)@}Us(_inuoco}@$=0Wz-LKD~sDB*yF-0z#*!P%L3Lhm>1#~kVh=(UcRXB`eEtM!~ z9|eUSwe94(9p#An<}_T-m$2!OF)@&Av>vtm6Wh7YT6y^9e>-FjQNwG`rRPIxJ0{%e z?y+w)E3tcC%M2m|LndB-Df;8M(!R9pvqNoz2dfL#Vna#cV8_uy**&@V$Z<5yPzQ|~P$^6=Oq94?1RNyG|JBmVm{h4E-c&sqQ_(Ov3S0r~t zze}t@wj_b_XjoP3@JScTWb_5WO8~SU%TG=wm3|#fs3NqCK;Zf_Hq-oVIr?NW@QVQJ z=HB(twNh;1a*$L3096_3eQ{#Az@CO!qc&plNUM?0vJ6U)P%mNB9B2i}fbVt;^)ywDY#0gk_euG;$r1J4MB<&<&<%5(+pjST2q z22!<(q&+4SruLgJDzH=)^oBpYwz`vyi4PnBy0_o%hDVkLOL@OT`CM4#&IcGRa^|0q zkbE@Lv|UCY$$`0e zW4Ri>rd6)*Xgj3wf6=aMF*04QfD5;5(r;jOjp8%@s+kp4Id69vFn*C_7KE}!USUvu zlv2_gwfY9Yg9T1!3rW4}K3i(6YZ+NK>@c-3x8CSYn==F^*D{>x9q3$#=8=avh0 zf~gE7%AHE)J=zhR#88?P{W*vJzU0>7GrBqVR(;_Em5q^Y$Vu%C$qQ5|#6X|Uw=u>M z;izZMd39>~?|k8I$N5Tu=V_kj*BG4)Gm-b;UNF)qxta2V$RcQxr;SN6>VeV~CWP*W zQp!%aYODX8=$Bjcz;cJj5|Y!Efq6tw&A!Qe)x^LN8GtLSUc(WZ;1X~*_)`YMd^560 z(#4&e#42A|3iXO*TbbEnlYS2V z?PVq?JEM60=X})H3mvqvL9N`0mun@BN|g4zz&$ma_E^dyILvXX29-4S0hqdqNyM{K4M*1N0-O=22pOn*hQ{F!C zrkiFS84NZD6d3G0y72g~kj!mrvNn(p(l4ZIF8qN>nE&BT#3@gZveY>44smyxRBsB3 zPk=@`r_qn!`}_N1mGRuO?&KSV*7&3VWswmQ-`ropGQOKRDhp+)C)9(KO|V)ln%>t?cKF&g?bHI)fqW(mP#idke~6lhnmx*) zHjY~Zl_TK;5Id3*1sSM@kU`?ue z`9o`^kuMv)wq_riRD3j{ke@LErQ8^TW6Z=uiEGQu#lo&u^)XFTEK(66$0K5r7ZMzl zkDwDC&-wgPj`Kbj6WI|?4)@q`vf+gZ_WTH8TFLMyEmdN_ft9;D${6=xtB@19sIyQE zmtQVsbG!(~79iH*^5qR$SuMX$JmjN&HqlD~1ito`DY-wB&B2Oe*1v0>SYp}?Dn7G3 z6VvxzEX-xhl?vtr7POM3+B1OFn0YFHGad_DW+^FDK2ud!1FJVXzT*)0)0F0`IOfKC zo1FV_%{LO~4WKzc{a#js{V(L*2Vcr=`@&{WtwnO%lZv3wLO?jk5UcuBlJ8^=` z&L!!3{`%KCAB5yuy^cNCKwZ>4?S|ez@n_nQS0~-v??a7u>=9Aiq5p|??%~F!Ezru@ z^Vc?;>ary!Z-!Z>Ps|p6^Mr(|7ux-0%hkE9LV)Q`@No$&s@OoHfRzo$@zIyV7dKB8b;^Y02BhWyPb zX}nl3#Qt=8yY&!SxAx!`0Em6Mc6;TS-c0H$oZkpVU-+s1OM&tb{I%=U-YQ`CO`-?n z{x5ng(`<>%6+Ku1lr?~S_Uk4zT=~3lwpfVN18i0eE&|k_=*dY z+3&_+=ohVn*Q!m*Z%V@qXn`Gi2I`GEH)l33B4QT5 zBl@1|gZ`1bdS4J^)r=nSutBqcjDD*P5?SmFcqt4<`Wy$M{vGmUkJo(q zL+0M1yR__guEs!KS6J9(aP9lg;Mao1XM8TWL+5Uwk5BW?*BZhJb3{ppYX+b^LGtNm z0)GyI`AV!D&xt!GN2-fFf=rRJyVi_d(KlSb$R_4eSg{hX*T2DTh6}yu_o9{QfDZa< z@^^eCINqSk>{hz@5j#gH=?Z_|L+A>Kh;RDK3CSVMV0vYv(tv?NoiX3k-$U@#{d|OX77_bOwHf}E( z(JxQaC_tbT7{?|%3nJJEH*3V<#8h`kebs*IKL(l=uFu9)_E5;pghKqkaNbgHq!B2#4&5hZh-qckzt;A02+T@?(TH@7;Da!wLZEJet3{j$$W- zY-1i6KQ02;+1zoVls@lE+v#5CGyTGa!#y6{XX*L;%@`lZle;)zMP;%tieh^_o5P=)i5k(FuC@!JF^-K;7u8L4&>D-2SN zl_@>hVYn4=_=5Vqq(nksxf@5y4QeIcTFfU^TdvZ!;^bYS`JEQcj>soaz}3Gy1pSip zr!rH1H{C8oiJ8B*$~x81rRu7g^vfeGk_prr2yqOWM30U-*+$(V%SO>C(RpyT@cDo^ zV!i7=RW`NM<@wwsa)dh?O@7TQx8jsym4!!c4Vf=!hPkCsoU*gu6^6axaP@VTTMq%t zhmhvQoOs9DrB^BujB{{sEF(2($b@uh(FW`PRup@m&Jag9jVw7L%+UBYx&eitzFueR^Sxunsdvcb!< z-SZRJ2s@Q^Lc7i$=E2n9G4N&;p`8$l&!XSDqru@i29HFo(3F<1X7<^iG4uV?f%r=T z8t^Ae7UlNcJafnU z+-&{qitn+D88lJ1Ms*d_<^QrACQekdBt3o|WARXwF@|2UeN{FjNt&zS7HXGO>YWit z>BctzgmNu$IaA0qxjPt+Z~v@yomg?}g`(4!wrP!qJ8b^VE*q1a@9xLzB5?0Bag&*l z7?uyAa+Jf!pxOQh-cfVj#w`9dC4#01UF{bK{#>Wx)Rg;(;e`haJO7id9fR>L>WkKX z;U67G;uzA!w-}sA<6@J{Wm+TMYuX*+UMz;mczKHWgc&Hg!z+dFd}|h;Z*>UtOex`O zXkmGsh88@mfGWhh+pNBaNS0%QFN$x8_$7%&sVg2{pfCWcFY0s==+5YMGA?rsE#a{t z&FgO6kr|$MePS2Z4Cf3W95{9SjtKBIldZ(_Q*Y)n8GOA+``Y*8p@hvqsqAm@-5DL` zRTHR`TMK+^WySkTDyg*xD9@XUmlOx!3jatdi9!Cd4-*y!16eYII}0 z-aW4LP?Dzcqc?g!9GB9*FP{1cF$Tf&ca?-gTem17q=0a%Ra(&$)rK; z+JXNIcBJhvj_6+?*iCE4{~PW05VPp^yv)?Wzvm@ zqwc*)8yv+3%>pwrb?QCL2h+H78?2B|zII5|A8mK67S@|D_(ncV?zl{#2nwDc^U!X! zU4t0?3m`wST2Iu=MTg?2TF_`i5NGgICngO$^MmPMMPWdZB#*>#se_@IOrZ0G%U5AM zIzz6os$}4-E&9eh&E(I1HR%Ri=1&Py3ruaJ!j!~my{!N?gi#RHnr9eb+-7L-ii$`I zVz%=ZWDB6^TEy_8`Lrq~Bb*Cn=SY>z4ioMFc>6p+2pi`B`m zx2xw`)s3*E*<4Y^Ziot6juo6PHmase-TGjbi29uDzH@?yd)D(0$pOvG(_au(od*qU z(*16PD2r;9uLF1^hZkbky>r!iocsRo8&^>>j89+*KO4V|wM)pSf$JjwUN`|)Z?@mF zcpdeL{Ia-@2Ie&3o{u5G*GBc zhhwaflM6#5-fQRIP_T~1JK1tQLycYe>4CDBO5S1$-??U($r;{d_eb9!wT}L`gnRb| zDrOBBMIgnqe|z?jTew+r8qMtHX15(CF$x*dej@3gw7<0(YH?OsSy{))jz2psGjI}t zB6R+MsR#PpDdo>fzvghEOSC-mNSFxf^Tfo&6bTkzT>n>yhUD_}pAx97sorL@Qt3ab z^*h$Ii3)g`Az^~UW=?05d%1#gB*Eo6uTOv{fXy@q$yGKRt?^*K|HlFldW5QK7E?Xf zq4mO@I?xd~ z=^XfJ6Vk8`y$jzk_bKKnI|y=+z3K z2;=7bmr~s4;Ig9dZC@8{S2+Pz8#G!OQz+Gkqp(Y?ybZ6(?F`vaY5;85sqXvBQO@36 zZsb<*p>SD?r+AFsO>A)w%GjO~HG4$^6MN6-)$W@5R-O&EbYG=w6bH zU0hbMiBSJphL4g4Emlj`k96Y!S86h1gW8?*fESK4;sJ543F`GdAeu9*W`&MajQ)u# z^ao)Dp{+Qq>sG0}>*UTZFM)=AmIZ(_D?7U=(=cQ;F>+i1AZOb4L;Olq;PVyHlAvC! zQsK^F^&=%ErD^z=b2?4L1C!OJ>V}ut2?G58HRkXLTL96Xr5{T@+8Zz!fTU%Qcg&g) zydbOr*H0~}kerUz@Q77bx9pdDYouQU>=8Rf9ulvknQ*_80Q&E}a*c96vjmc^DOH+m zM0&oSd3!h#H$AbqxwJYDP{0(8-HCa%blyv*s+5FO5xo&Ln1*&Uu(OLFgw?!u<#oof zuyYPz#-{q^`!vf1RM9}7?;Hm%e|HZ89+^_vXY0XxB!o+adNzYK(<4rJXQ5CsD7CAd zXPMB)xI0h7kw7!E_&O{eqIzjV0%2xU*CbZUfrleP1n4G~7+Q$*CNq7`&QdCcs*BNS znXo^2&O-O6@aY9*ZzV!23C`rqXAT|QJyG%T0XT4QqfPkT5=ZaLE|CVGHGKg7W3Z9s zvl52c?>2~fqkvtO{?tnnu}Yp5dA!|Z(I*hNhRy6o_rA9JiwjIx%G8?+)`+Fb%7T}KGq2cAZ)q{6Cz75NVfojxCzseua7 zQMn+#rL;cEbBAhJZ|&;WgE>TP<_%eo)EZh}EUZe!C(57I0j7Cj5AMgnq~dUg+s?mPhnXHzig4wb z!##JdefTbFFuFO>$=nauvb<8k)eyq9C2mJIxO&D*DJt-oW5tK7uu%3?H-)7#B8Rpx zRhN~%^K6mvjotkRc<$xD8Q(Hs?)Z4GTUKq~EBSF%!i5d~?MNG64wh(ZvLu@JbEm1t0vs-`%f!>nE$n37UdfRj2vi z;JZjOD8Y=a;Q(zy1d0bvqK=l<+Vdx0O-;VYUz9jVg9`c&!P%Y!_b5Sk7d8VA@Qvmy zZdkp$kp`eb)aN6#dilGWd*EMjCuG}2D$Vn+Z@Q;?#?olp4Sgz@3$Y1onDV-j2t+Dvn%SMF(YcN&kv9KzN zfVhMQ`H^LWkSf0-izMl%qF-e=7Ej`cFIxN_T=oaVN>C$hh8l}`%PKUF@rs8O2NqOI zufY^$X3~k9C}WFPU{6)2RN#bc>|3{@7nCQ28Ig}5;{$X!?G7sXV}3>sTiZ(M72ZH| z@Jpba)_I99OvVtZJ?PUO2$O|XYX*P;2zOhu4m3DY?pR;}klFs811zPfkp@KBN_7i0 z>b);idsCSfpe=!u$8!ZFv(0d{Jsb$p?yh1z7a zQQ>yo?rMqm3dYUak82c)Z=u-LLCsd8`#y_ru$kg(p8dxefeB3azCkr=gDdn+is_~2 zV&jJ{YQSH__Qk9FWTa~K<(ET#>B}-Pfc+IRT9iroBaL?jd{oYS={l1%jBOh3v(S(| z+#9*kfq^U0SUiiB?g+eV`5L)?Ro3L8}H-@5FCA#2*(pWEdu?6n1ZE$WWmeHDp6~e+{X1e=14*03a(YxO{|Zx z6%SPvb4}=9WnE?cYyUOIN$lXINHoKTxai?;f8P2Pzldn8yeJj(D6~?!{#EM=#p*dl zC8B1BAgk>>V1b^Q7Yc*5%tDjuT<%(bAUiJmQ=m!h3@Qj_U>&Vjpr${7S-{{GHuXpc z5~yK?%F9r0d2jeNm1*1>Q45$9IBvX&USwrP|L{wScweU)TeEqyK@7RxZ;3ot4i={k z<>7RH~2FYZO$l-9d zMSbDc&%el~9<*fZ4-YG7>M1#fO*T1!G;O@fY|cLWlneb?YczvSYFK~3{U;I@o;8ZY z_LPk6Q|CjmMBt zYC7&*#k6$IiN@%7HI<6SMzsO&afd>C_+p7L?`C7LEr1hh4t;yUKI8L)vEJeqmJj#^ zEEO*)Y|F9aN?1bFzpf$j%A4tdH~9L)d?M7O2rYwrmS25dTEBX)ojHV}QB^pY zfPP(FTRmjvi>xX{$3AFx0i|Pv+i{%6^(-HrLp8m&pXY4yJOKP-ed4nnzyJFaW)v`Y zIi`jq&tL%wW^M7UpM^ZXdcPDF`AyHzIh%S)i`#{2AxdLUcoU8r!+02e?d!YM`C~Kk zBNjW|9)-bf-;ei0vB9qXBu*HImlt;ze>Lt^n9lqCz6})uNrwsPBG?V88*ur{{g&x% z-p2mEIo+^7+I*!ki+AZlxTgV-DAT@=5f{8BHpepLI5`!(1fu~oL6I!UY-H-r8q-84 zYkU`!!ns0&|4`|jwOxq4rrGF>p4Vt|%cgt)69QYGHAhjyL)^f+0PyDTL`m14?ArEd z$dHs__7^Qf{W#H?Kg7Z$wE6yqRIW;5l8O+{5rIlT#UnAvC68c(q)CB3QFQ-%?a1sA zJk21Z<`2uz1-5UIHQZfK{d<_{8+BmB{Dc$Y%!^`jA`Y$a-uO@ma?o(%(dx1jl0sx(+ zXFs;lVAqBEScSrv`ABnvq{lFw1ItNj50C9$;g1R;@2cK<-a^HcH=0fW3lP=r>=f&Z zXm}w~8}7x_hrSm4PPV!5Uz6Mrw8V}g#Jd}rYws|UExacZ*K|M3H+n-RGE9zR+`<8% zVQl$KUtKN?J3dGUPje~y?V6sg*SUrF$Y#FKZ}u8DVK~8LbA2BGFb=)8>O?)dzR^+BH`w<(B)#<_{S> zBH7Y~uj8^k5AP~=%XK?Z@Bxx6xrbGD9zZY@t5VfXV^+U3Cj_i=gmzdEiN*qOCfPjU zrjM4A5sMd9J{2mfR$hbjwC5OiDt@7gphjF>jeN2}NlaDPU2VSP$10G~iw^aHYkVy& zdpdZX?M&RQv|h5}C!IjNe0Nj)*VJ(B+ENpMZ}*j@4|*~*B|d87ium^UVMX>P9w3~- zj$@6bAF27{gQZb9iD#4AIYvm2JJsnkH5CD2-z={ba$}c|Cq=qf|Dxth(~&!fiZ zzc5}qht8Y{{{X9vTl9`fBAgjyxnqb?-gDo1 zG|b9A0oBoi*Tf=FYufwKB5Iwvi+*67W0fk}u5)m{%Z@xf%Ng)u1HGzw2G4n0qwx^m zQy>WLf7^+1IxI1@-O;qDKp9kWDr@c1;jf&)_V~^88oQ2e*@qp#QCF z;%17Ft|;YIutX8zih zzZ+>4ReXIy_YS02(r)a8h`0iZI%)SQ3X=)t6Mv5_b;5PKLScF@J0;ES8TIQ`GpW#k z&}eAuno{bZkpgcFJ}1>D?o!r1nh45XG#F^eZCY+X?O$7*<*URECe}P>kx=XtNdkPK z{6(sa%O=I`8l3RXj_ukTt->)yxt30P0Na0>-Tya(9_x&m&SZMo|41uZ&9Lz9K zH~L<~4@aGOApn6ZcWNSv>r6g7dNfi$V!Hw0>+>Su()-{5uvv5CBGJVujZ>x@)ky*M zByeD+P@O0k3TMV$y6^VPt*9T(j@J$#zgDEAZ8uf%Cyeo(sdTxz9V+pd6X;W<9Cbdj z8v)kIOQI*qgY%H}#>aG2?Zl#cI>p%#FnazXulg@B#r+@3uUu?A%Xz&rbkC(*)277o zfmbEfJ6)ggXd^@Yp`5X&rxMSEKt({_5rW_toM=f_bte+;ouKF!B`-N!h15^>_|Ed) z6F{J(5+B%?7x%0v$RDhv{hBItkkr zH^-3=iYTKiQ_aN_7XF+1HkeNVx}w0^cu2?s>QA%@r68;9G&j*cl2=auh?*rppbBs& zSXSt#5~dVdB^LUVC_;J5Jn87t2^2mSy1r?70RP(Sxu@JeS*3en|FL#JR@DCNhIgb! za|2EJL-r>_;?2))D277jjMXaV`3}mUwdRKs%HSF14 zyP7f3@T!^CyJ!CETc(SCKNwfzfZh*ik|WIL=R{Ag{Da?g_IZ*YzY`%6gkM$B=c@ZVi4h+ zmbOnSs%}4o^nDHdPeMSkBUIXQ3RCWj$o_tw$g~(|LcQ*FyNVw2GE>08c(Dt0?Pso; zugb^cy`S%zP^U!RWdj-aUTY#{e&5+c{K&vsMDY`xBCotv`_B-Zs;!j ztMXu@rjLSfhKI=PL6805=SJuUf-Y1B_y+Ec*7Psp4iwvq>q-~4LSu=EoDXv7{WFM6 zW-suLPgAx(Rp2ZM3a0Z3W+#1i+%=37`S0=SM)4;pP9*d17~Y#zAENA3PzD`YoUKfM zdI2{N7o5Y@%y1kXhi)cLNUAPnr=PFu6kHFm{>hE81_G?=cK5p1zmY2_?%ap4R;ujl zKnvdSp`zeBz;Eea<2SSvd=Z3euq0yTXR?H~SqF6Ur#p)P&V zn+g7sf>+0RJ_94p8$HJe!RbEkr?xjGo_N#)IV%5m@jcLft?*k~IV`wL zBr$BY22S+R@sH~&Mg{#M&UA>C^CrejG!H4^OMECs7Y@&BIK>DqEqw>Nb%cblTXBbl zKL)K8*DN}qYtY^(ARcYYR{rb^7orx}U%Omp*R;jccF?Z85w9uvi zDgTHe19%Y9_$;$LnawA8>017I>RTX>bar~GHvkPpcq2@=86!OQ?5Il9@sB4@GQRmS z+vVyMnLRzgKXp|jv*7Fwd@*KZ5}_LOmnjEN!CFZjg;+b=vk58;C6S;RW{+h-wX~Rl z$vt0(5gqOj3QEBNq!rBFafO_By&m1Q->Qcf?okab5(#+`{HwTQ0}s#VZf}V{&h64- z>Eo}~IR&=qv9AC8^>gfdwrP2AX)>X(e8PRw-^(Rt!CQ~*02`BG{>R(Jbu8XYfAhrM zaxe#e+u0y{dl@%kN7~=BqvYv$#wLDL&u|e&7kmnM07fs>I-6crRUhXJBA7Q37cYq` zTW?V>YG_Fj_@gB!zTR7HatMN$=J8dQJ1;olLQ&`Va+_})3&HYEyK1lJ@$w=6xe)1g zg4kSgPviw~HYw}3gf$C1=_~?DPK74`lpb6K9>%v2W2NRA%09b4G)Y}S$XOWu{LU3>> ziv)m>^Iaeb=n6U1iC8K^1X)R5CHY>M0~nA|a-3(48RjZpeE~i=&xA42J`9E@fy+Za z*xYKretD~JqaY>WR~WfBIB>8AD5YV5p2t^Ld9KHPu`#d{yhlBsDRMB+pE6Q;Bb5p> zI^+dTxo_K>>TE=ArrmVGT)TMMD0@l{IBISHggW&FAVVAEWsvg`VOSz!2CVV}hUgPu zh<(WLz{xyU#W^R+i6$J5{Qxrb8TMng`i&q0V_j3(;2?n2R@#EuU|$b$lk*HP!eC@@ z{50hb4q$r#5Ppzu3_|1_R;Ulfxn}3h80&x#@Bnz4Bi8V?1!FWfk{ni!5kL+DG`&mX zK6AowXH0(d{8k4OFcjqNzzBh40CU`bUX66QONc26U6*r-(V2{ zq}n(FWt>NZh)az#7Z^aWxmC`u7@w@HY<6A!afzo>mgc;dUJ z72A8y9_Nn#R~0h#;>P{j+OyFYz}=V;`L5#jX98s0U!gBOAKm>{SgbETu-c0dBcl$Z zN0Heb`y|SsPR%GAX74+9qKg!C-%9*jc&>c?p>+-ZQ)NzKXx) z-uH|KK7Elz{-cT=fA@(^{#oJv=d*(GxqyA-8TkJ5#-|i4_BJ{cP+4r_d7bVkgWmd* z>g^#1rZ1sjed!bTEYISuKv4ikY!Ba=@tg~g6WAhOXb@vVs2yxw07r>@wz>9vH)G^V z6K!&`80iPk9$A=+Ur=#3@xP{oS35_sNF=;89m6-3mKM zSE5=+OfOQO$r#s~l@Ta%9_|>5X8<0UI3B>U%o5J_%W}X;peG?3c7PSzh)i;x9P5z@ zU)L@}1X~YUM(tL4(^93v;mjRw9YvExYbf(N#!#_(V)b5y8XfjL5S%KQD43V|Qd>f* zm_n==s!k!?DyEs^{v?m-mCZFC!W1?F9w=(MtG3ZzSYPcqI;_OQo*+oDRx9b$shJ`6 zi+U`qq?7-&M0qT0r4~j~J5CeM66^|j0VqO|s1B$h90}&FskX{aE6%ptufE9V6Oi(Q zr#DLlP2f(7V1+uC&@HY9ZQ<|}{!}CI#5uqlT9o$p*{=T`XpNJDdy$Hj0=_74+2TNj zqTGIle)R7a#|a1qg$U0Zai>xO}`n zQhDDKM~|>Gq=L0tz={y7=?bYLqzq<*&?oxO{;)m40eD_@X&x8wBOi(aqySOI*r>Kq znFAaE>^Lv&z`|6Dc|ii2`%}&OIK$Ywd*!_Bi|JPfjr>l(0Eft7^9o=ap|Kp&Gi~f} zh0To`=^uS+ZHLz5e^qZ{$Rskw!SOJ-WeRVN3PJXUfZGECKaRQBt4ietpjfI z=PuT@yZxNhgtk(E6j^P+EcX)6gLZufj1oYdTv}w`zj==5T=mekxHrKtQB>7IkM0v> z#kp>KP`A^)fw;s+E|}yXKki23+>y^yD(b<&SiScbZ~5~8P)pb$cM41z_a0%F|8Vnc zo3C8B{xYH{C<@N=8dm;PvXBDY?&$qe@%s|hC!$UfAf>##JmDruiX=3TSB!_j)TvXwt!O$v zFiX(@3l;QhH0v09hP?WtQoE0eEy1Az6zF@%9abFTaq15u0@o<)?6nu3@h(xAG1NWisgH#3 zJ-%wMhX&C$p;F|{5UzytiY)XhIpV7YW&l zgeL*YaGqC55*K-D!UO;8+=w#^Xsgs`WbLYVj*I<%Mqzd232_{`GXM~rasVI6`bBz= zT0F1~dRxvIiPs7`(;u)NguxM7cjc_n-X9o{X7vNmM2OjG>Km*UpaKA=?_i&Lw!_2_ z$_5*RqYmf+1dxYPqPjTroAXeVwWA}$ffc}p{W*a91V^`cSe}Cy+J?D6MBsL@Akp^? zVP$ItjJO7@s^f6JEKmp-BdLFnfDd4o(7;gFM$NhNNr;<<>EV2wgL%LJf_*XCggqmi zsZk)WNX2DKhP2wJ7pTzfg0uYGKX_)dt<|+btq#>Wm?6TV=)-K)<)KLIxl+(0)NQ>) zE*N8-a;kK>x;4(r8~~OH|AQU*`x|Gb1dwn|zw^XKFG9-w$Y-XlMIsXlwfxGB^KAa4 zQQh_{(G95K{rjss{JtWDlFtyv{jozJk>>}+VqwHmZ8%bd(qK5yJqeNYc5cAiW0I+7 zz8oy-0IoBOKl8;-0(_$H<=)!s>vq0#cI?>Ui)~@$zprf$l;iOs$p7q14$MFp3*ZP) z6#fOah#aOM?3749fBfSgd;K4r{NPjZ9s28E|JtKyhyV!-mx;97-}^ESB7ac$CBGXh zFE96;wRnLKi`)1>MMd1F;^E7eB}`l}=yCF_pxR?C70gm>o3Vcf;4^u6ht0{~tL6E6%c$RD z8I9Eu@WTPwIo2_>%sL9C7?)pU?bEN8%+&~YfFD{RU?E2mAOM5H>MPC^;XG%^8KJmi z)#{@a>Ei)DFKpOn>niKr*=EHaM~(ala#rT5#tlwlgTmdGE9ZvLv2jO|%!4#D`{3vT zlyLYqDwhIBp8f;_z~Ip0%zxAHW1-rcGqFw`(pVtN>yG0ymmpj=|WU za5vaB!qWhWgfGGNunp%>_{W-CBzLU-jws9(OM+B%p@X+SnLozo$Q#oSa%0G)fT>|s zov<}zxM6}Ao0|4Se1smD4*(q&`56If;dg*m06yV8-#N}7I=r)84xv4O2;vJGvQ-qe z+2_uc%=dx?E*x>^!|R>xfnkI36diM(&^^vi zC?DV$&;=j`EPh(ji`OGn$;i0}UML$vre3-BAJh{=H5ChqH(R85zv|qhuy5G|& z>ULbsoXWr_JO}%d0~6OIo}iuh4#rnvAsFYsE5<1LJ)C^(&O7gP2fwFo!wiu#3kc#L zxi8du8t7JDo*3}C@4ox&)?07&Vcm7tUG}9fed)L%66%T%O3oMyxI~zoOg0F7(s;E3 z@Bu8a`k&~k70Nj{{)A2iW7Pr2Jg8`qh=+V54mLDrx{Vd+#~ypkPXqNyEr4_y@z(r{ zu2Yn*^O3B}iV=Wi%9JU+o`&lhs(h34g0VuvgP^AeVqlhL&6<_A#7T0a_H0;gGuqe7 zLCm$xeH*MJQ!BzlORXbU4jvN5P5b4+SL?o1@y*iN^592X`)N1WP6^LFtJP#=m!D$+k)dtaY`5z99x_?RI*sT#$ml*VNE#d)Q6$o2Y>>{9%VFE@TvC_t)A7>O6Ma= zw1QzKd>+Q)7h77Io|*o9DjfaPBhLl$@Vy)6q-cwYli>} ztPd;MtX>0}beIDx03;zvIP}6H&hP<15Uy^~;KyhMf3!m3V6I-5`Wc`H)(LDx-UF;q z-N8oXj%3)_QA4F}Hq7UN+$F{z3>N1efkYhPP2>OxWM;|nA0_r=i*kS%1J@NJjE(#o zB!%f`SHMQo5&=Hp)sKwthYsc;@`s4=$!W89P0F{c&Yk7V;$4q#^zcDV zzY42H^4thTT&di%@kP0Qe=>)FOaK|mYOsR=i^!cqS=pQQ9=9cr4{`Db)4OkYF*x;hK@)#vVC<%lQDCWMoFq)eY5m@GawsWw7_Nu0)5a7#s~ z3jiPaci3+hR#-$h5r*T81I_Axx{GG__xM8cKTbTM>Zh8))B#-akH|sk&4Q9B>?Pls zgg6rFh9gg|5B?3#eOCs{#5@jkOBDFre*5kAo8SD#hlPI`Y8u6k^An%=gx!7j-TpS8 z8T_V`#Rh>-8m|Aq4p20R+%WrxCNxLk{`MSZX)+ys`4s%s(G|R)l&3xPe(pHl!}LFJ1kO zbav}o_gPs^gN@Hp!goQjLfS-E3t${$hqdBgy;?PHbf1nnLm_YTZQscG_K1>>$)Cab zpQWU1R^$nfLg--L_z`xxa!U5CiG;eu3xNOgb@DI7(ui5XvB4Q#BL{Z1!s!4&b*im` ziwekq0U^f;08p-aIwK^P9Kzh_KLCtSE&7O~N9Ypl6ro^%09YWD%Yp^q(^YIc=X()3 zVD$y33$Q|XU714IwumjM)(SeZ)WSF(?gc|bm=|GggvVVj>0m;Qklj90MNbidAhe8v zjO5TDd5x2bLK+S!ObcOpuvN~ksJ#r0moZ1e+ak(iH=R+Y_mo>Br}p)&wJrt#C?V7? zU!CbtuGSc-y3Lt7!9ITRWcB6vTrI+(D5Cn3*nz`3){Bq|=#WbWt3=KWAd2e?NZ@k~ zfNU1)<3&`%1nLz40dP1%2t{p4{#S2P=Vnfs-=ZPyHbFT)<4TJKD09W&MC7iK-3AEL zXILHPbe6&)$w|WLr}ol>kphbf5rmy2gbzt`Kpyi7z|p1EXA^Lg{CH~B1dXMiI>687_-|J*+O;SYDW>wtTI5cs6=k|YXz_>l48;)5HK z_jo|zP?M|Cl|#)64l$U->|S=+WoaDE(WVJ?qpwiOu|VwTUa9#FVFOkZU{GKd(rK*v zki181Y>1DIJzrPy)WpsLl(+`*SYVbC4XKN#?Xb^=<*(S`w|{448T+hcq(DZQl5}H1 zPuTfzi*kV8lF-2<>lj&K?Wf;re|)Ff84G|#B=eG>#G0|U}|=W zH6gSI>01~Tgb(<4y>gI(G%lU&3HXF*z~QeH3&7_L$C2=gUK|`7Uk&uq5=5>r7Z)m>(3&2$SUSJpw(E z`zOLEq4)*>4vKUDCgje!-6_DOjj!B4EgsU!_I!GG{Uc!E{!n0L>ffrFsAZ6C!#G@{#ohfI~P{|R5HfJ_y~lLRdp-ikoh_$sTy%fo_NK)?06N z3QqmiU;UMR=R4o&cHe=vVG#JF@ruL?d{||LLBPT1ixOjHns6(e>Yl;~IPQ%%-tc|G zDn%NH3&cXx7| zb@8?vz2A-{zqO|IFIrjKPAi(K+$e>(^<)|Q)?0>D-`dBXY3)-MTUGX0$vsy&o5Bh^ zj12iEqY83trkupH6@Q;7^S4Vt;+b_-4lZ_zIoc}rheT}J$MMBc#k0jB#|h3=?AsX% zsk?eksXKA8{l}4IWuJuh!1@rj1lvOhTC@c79xAq3a@B;K;Y<=n zL|)IIpFcq%X))mrEp?W)=WWY4sGO>{R(ovkaC@nClr62!Ryb0&%UF|VgZdY;$K*H! zho1KVHiXT=a9t$_Hsqd=>jaBLpV|%!FxBn0(?)dIO;>gwYV`f5Hrmr`Yc$6#o-hu$ zA*Tukgm6BD1s3Z(IL%vX8U!HPJ?{l3ivKjleKN)ZveD_fG`3>umNQS|3)-aMH^ge& za=dTU@gc|T2`Rh5&=C4aI3amXusds&GgjYnY~!@a{e&VPA#E^ndv%YkQC<*CQ2@l; zBM3q471*uS`xvTXmq;R;a7E^)uhv)K1Ivn(H`ku~jzYedX*>Y7Xk)YU}}@#pw(Zv?Q9fWbfi^FMdn4HgrF|99JMw{?ccb$h@7+As)w(s(fd zJ^%#%b(iCV0vI=2h$H0-gv2=*2g0X%GaNb`c2?Z3yz&f{_7WmLF zoKA|W2E{iRF!CuV1PUY7X{`;Gz3~an<2nsSY=i(1p6I{snPHFaA8%EyIbs>IEjup~ zI!LHnO(UVO9WL}h4I-EbWVK;saM}siBV-B37BPoy3cX{jqeXsIZCoK|xaS;;Z$Gio z!}!Q&f$^aLD5_^o5@!IE0DR7$QsntYsOhx|@W6b4K@%|`g8$Qxa4dgwP5>&vCp5|X z05B}bQ*-cyVXE1aEr6!yUQ=d)haApSo(BM=S%L+KK}16HBM9{D4PR1l;kkG-33ROH;d@En>fGz|NFu*Hp z5D${RgmwgGsi%;-zRqa?KE>@-Hu7}ED`)irq8qB^u&=jh;1l|Qa{(xcT>%dvkHk_Z zQpAj~q%Hdz?2ii1d1rT>!rfHhQO+^#6Q)Dh6|38@5&)kClZGpFt;|Eu2)CoCfchVyZh#i<5!gK>wht;NOov6zrB{9r{pNS}Emb|FJh5!tU%UsCHc6qHXN()_ zprZCjU)2TQpYtIGfQyIlv|`-8wIjhCb=;KO^YO7P+2#=!{V;sKkCPykLjIV0Fr zS6vmiBj^Vt`2#8#_Jaot;Q;A09@HyWu5^_aRFTqY#H{j#2jk`|i8^<%p5&>+KJmT= z;L}w|UA%4dw%@KL_gRBN-AWJdw2?C;3QRAAYwhC~SVzSo2_a1Baep?3 zkjF%UPiT1Q*8TQ}<-1+gjW8yh)(koH@;%*)rFP9^Rp=x~<8-asHz*oO_`?(2N#v)v z<%Lt?EAASA4}f)%auVV(?tv8wr9+nZfcl5$%sJ0fL0S5QF>gaw-EUbtUz1e0)aj&> z*V2(?YplZd4=J@BZN>J+p>lhzd4e^yvl^{BKOMQ+hfq8Q8gaN0D=3mv4iJ%l?*MSR zn6qXX{p>v9{VIFaOgVNoz>-Kq$&#Mwg z00<1#HgaPch5cEBCkBe|c+0-q%+XnfBr)Fx{1kWZ8Ynd|Lh z{9yl3IsA+yxKEcz2mtbd<$LTo<@yALz8SiAZaHhLhw>%Y^PZ35dxwQ0Z1D*IJ}-$a z{<}vv_`SwL3an|afDd7i=O_&K&g*CBKH#b*ZhYV1@FLe6nE%9E8JI_qw2oL%sP!^1 zdzpN%$d6{Rl!dr?^X4Vh5P2;h_`nB@@BHWz6-hPL#X<2d)^%}c=Ua)?&M7aCANUM1 zKAlrM_)D@g5Dk2|*@JKa?_(qw@?b?hCfN@ID{rWTVT8K%g^BP+;`s6Gv(Fk*jyza+ zIHc2f@T^#|!YS3T5|OU+1>nQA2o4n?cEr4m2;7)d*)&pIGk5&;3oF*4a4j`|5EnpvV4GI70V@EMNvdr$MhW=jN3}NA z+gL>!Tyn-VTUFWUjy?`QtOX%+3(JcXikI&WG^JP_K3Q;h){ z_!kXY=wsOKJH`9}%pk)}2o|GiQJdrn#U7(>xic#4DbpVs556ha3x~D2Rp3{B8?Hj8 zlS@Zx)jq=dq1ZM|Kxra%odk?w-(KEw!23mu0>>&ZQb(Qop80JgU+7-yHx zEVds!z1ef!P$MK~E)udg#E-e-vMFhig$}@nXCEHYxX@bqpWxs%^&|+pd-W>NS>es8Mp( z^Q~jd>DDpng5!4U>Wu(=`jYFlzwV%Y_m9hL`L0IWrxYsr%yM2N$D5}-8r5|v$WY-= zNgVHOY_~E=H?#dfEB`XAe5mp@6cu__iQbGdYAXPO!ax2F67lS|IF1!+7?%6q*yY7P zkxMRAcpadD921y_vivriweKl~kTu)E{gsx}(Q5T#a^C5fDu=tn4z%T4YkP)XBOs?i zp<6@byVkT7i1Eof;;Tm-Hddwq+I%4rqEuXv?ch%SoJ(m_TL))vxcX2m;6)A!A#=;O z?U&Q10cD4JNA2ze7O4&T3-kaiz<#b&2oqZ(*B|fz zroea)Ai=+AVhDf$P{7e9v^QABtnIoNvjl7a zdl$_dH}1=?sM#qKw8hfl&c`oF_**01$61jvvv$Cy{zL zPpX*bf9d|Cz7&o;j1~9DPKEq63fyoHe&m8lKGuJGVXKb`FbiNNM3nm!b`miJihw3- zgd!rsL7Rwq%o;n?uNk=yJTFfK@Ij>FFIB&Y1qqD#p&zhaEKpF(=^6>5d_kZu84JJ% zS>Nu|J(Fp7ARLnl)w6*xj_&$EE^c3IFx`9az4pmZe$qiN=?JMdz(rq;NSkjTS4J)IkI8^0!y;FE1wvS!?&B8-h;3xnkK0_~T+;6WbJd8R#B0$;D6fT|Vz2aA zaHAPQ(MAaPkZ%J6hEvaGm>B>Jz-W{ly)4D4ZLMx_=e=ER&+Q(-^)pw;11`M{-qpzgEJFoG4k)LFZAaeresezNhR~~J z3JI(iunPM`_B{HNm3hWjEXNd;H4@S}521Oe1vV&rwq1Z^oJ0=3aLpV$XH1se{o6m< z+Wl>|u4#nwnhslzsV0&bvyoZNnvYC7D6qMwy~tX0&k*jUw|v|~1f&3pk-3P}?qTe( zBGmV3^rEydMEWSGi_HCzq4|3-P=F=o45hd60+96k&y_zyvD#Q;+=LneIAGaA(a>b; z-N5Yp^&j+H(mWxDjuIWf2LM6{AVBCl?>^0bx@5b(qVaIsKal z*ZRBwY(qX%crE~hE)~o7wQG|Dd@QuF5Oyj8pH!%xrTl`XutC1d`&xtPm%sd_{l#DW zh1YN*-|J+z^78nB4`Usy<8!iK@e|yCfDga~paAunsBl3%-N$iHv zaW_6B>9kOwm2ssqq#`f?00bNbjB}8?L~Qrmxjlr2^>M%R=ZT&#YL z%c`~cqr@~eAF#~&U1rMT=`=Yl9R;Js291-B?+9z3c7?!C{3?CPid^iftg?Hbdq;`w zEy^`fZ?crHGp^J|3@fy8L$kF?T_8s-&vGSe4C}H=VQ|ZpYl9K>e=-&|i#%o?iM15;&_CA}DTW!NKn(cvuv+ZEJl*%mE*^~&BiJaUS z4>{lRE#0{Uc#w=w9U;QgV41=;-$91~3UTtehowyIAO|K!&A6%iZb)O}6e1=--U{FZ zCX1DEin0p(YCMO%22ybPBS#+nsl(jirJtyzAz;uX=ev-63SAHSlBang+5Xw}H4dog zFUGNav;q)W9?%t|86^~YV7Wv z6;^jxg-bg|SgU4wL`IVp+W|W#cdK1HN+Dr~7T8lA=UQdkFb88K|6e`3#FnZ4(cZdN zFS<){T=~dild}D9lmlUMF#1J5BY*i@9%iSh*OZHu(#%r-r$T@R`RlJ-J-w6p;o0%v zioKF)-=}dNoki5>ym+X@8i=N9J=S8 zd(NBX3y4+gblZ|8ON=@WIPH8nq|;zxQdyuCM}-e_SMt;d8$gp2zL#u#a6EIt!xTUV zXiQgSa8~wM{c;)bITI~&mlBbcd~a={R#dRm-Q*l4h$t!EMohBy3FkQYiKqWzpCEEE zfByV#AC6&PUI8NX>6z7gY^TVPos9wvd4&?L5ECW04ySmGfY0SKN2yLuo`-F|x@Etd zzdgzUI_N9)tisEm_LY3Xrp{1u_r*u*u0)?J_V*B)!~5i>1wh1W07$$BTUMQ6FH~k& zbu-LN#EFMxscDIXfq@!^ICrCQnL^Vv0tM8$6Rk3tHbuZ^?2vk!oK<5FHqN$sg}gP3 zuK*Y|h_Q$`+2r^{o(Zry{KoxBeVQDF`Qfzlo(mfI#)yN?zOK+F_6v}aAuz(`TseOY zVo`$s4N!rpm@bDHHUe+~lK=~XI0Ozg?2jjh>-cD+J=hZf4=hcg02FvOG zdI4TPnSQ{`{r0WhuKESYAzuc^7!XLf8}mS48Ed46k>5E!{7s)7oN{9AN#4l+I%AAo zCMk35p_O~>vDJ~ zrxGr>c-kmuWeAId867F6kojedD4n64H%|TdfB$Q?gC*}o96w;jKJl9s4w7rMGC@8a z;f&OquXj|DU~YUcxMwH=-XrpUDZtVWhOdsboR!86hQ}+ozhPLXq!BKl+h<=}TYo z0_{OD_hgn2fKN|#eENDioHZO!jO72ItKQdkdpaI51w<84qN}K==xNtJZwm!l2~Q%2sV~-> zJT)I)5+f08NLCRhp8m0-2>41T@ZmvsT>Ybly&m#rT7_1EggoV85;K^l*W*KX;u%Lg zzz2tuu%fCxJ8kQxjY?oYY)b?v>MYONbB5WR@kJi$gxc0F)$=*6G~XR#YWHx>amv4< zuohOd_sj7jeyYsQ>d15Qxu{_E)D;&T8*#)=OCoePADi`GmcISh|#A zqj(=+5>YzSA2OI8@-k*bK^=~jl8Ia7Tz79D&n7SMpliH>|!tMyg!a1dlCb2FUj%xX+Jlng! z-kMu<59HR^dvji}YqDOmRjp&}ZhMb|M!+NBb71;bZ z`C>bC)r|c*kZHH&xXoqIKTQ@^;&z#U8Icr~h zV2z6IHaT-gXda<`Fp~fG@+mH85%x{=6-FM1j_)@9ol2Gpx#xjAAE{8}`^SI$NBhcG zzT$NQL;mzY9&>MfOBDE!mre*iAen_z7M@AZh&GCw0uZr8gchRPIFY{(0-rR_et!TT z!g~lg!jO9=KPBDv>Z`B%7X#F0x>v-AwO+b(sei#EKwHn=8?2c(TXd54(fhg$(oa&vTVlz zTeq{ucI?`z(vusaRne7nUldBLZoI?!9WvSSmiA6a!T{U{Hom1K=)Isw0 zTiffrrU@(9g!2^1dER^QkgKebQ*osd(OJa@FyMf~azqz1><;))?f$8?Do(2Yq7a3H zJ5-MNI|{ACLEa<>Uw*HzDw9KSP_bn=#)M@d9ML59=8(h+;AZl~07b&y`l7XdJXC%nde)f3!)C5RSE) zbU;O}(YaDLBeV)xZ`cI#i(nnrDd`?iMyMeJMP9nT<&XeHn>(WP0tXyp{%}YM)8g8) zN)I>y6h~Cq+AY6>;-u|j%>)`Wk5^^CW#?qPBZa&ROqHl?YkQfsWn_DMg#tcP^6Ko| z!oBw4l2w*fxxzZ~i>@e@@v zb*t0pJDVXDn4d{P#kZU}&O@nIYEFLq(l#U6-dP^zLI#t@y~sUy!K9%!sdbCLpA7K1 z_w}7FRSn=^zPb0gMuZp=>iKC&T66snLICvAe{!D~Bf=Jcb;Xo~*d98{xb75~a^NF? z#dXI}VWgfCz~{UP1$KTxrGG|)+Gd9G1@oTxqGi->wG0*W&1kI`l8>-NgtK-C?0BBx zunE?D<#(K^^M;fB!F)We&+d{<`+W|k>D~gA`aPLsn;eFthiV<5hkvJ%r9$p`AkRk- zrs#_z-}k@&ef!2YzTu&%e8-(k#`O(3-=W`k+;NA8Zc^Lmd*AzBc-vp8{n%9~+rtk( zY&YC+gT7xRDx_MC06_|yvLNu2pZvt`zyE$e9-osr3iW)BX?y_xF$jFpcyamz_;8L; zIEn(F=<}!BpnnMkKrTY@&<6QV<_YUbo*IS(rX=0KhlevE zb!o{ZLbPE27OPtOitXOK#zP-Fi}0z4X-84Hbrfs$W=N#saw78?yKewKv9jhkw2!RZ zZR@t|v`v-!m4_ndUMgheWg~6U*fKjP2OXyh5HWY$aCbae!Ckwj-lod2oKae!`Zbau z9)cJ^B-de$aza>%cGWWh8`PU{TuC$skgzHp!~k&mSgBqtafILm5t<2r#scGmqy5`A zcPreh#Wo1wkT-(?D5_Q1l29q$!67D`2A%|kHU8$_%2n7Ji~^xi5jpSlY*JRPmYx88pZg4PH?6R<%9v8j1r9`olJyc@7~jgHSC%Ab~w2A=TlNAJhpJ*bL*<@U!K=OfI{8Wb)P5lpBM*!pC;uq*c+UB*h$pU zFy;{pQ_nc23#fnb%Bd!_+RXK*E6762v_Yc5_MZNO!^0c3?KTnVfx##}uZ=&Z4 z!W4bU&mz2we=M|8r2AyDd+xc%KK$Vi$K7S3Hh3;|WdNMdeC9J=tiG%503nLKCQ`h- zt9DMrdxO9yjk8XOTd3uO>U7ssnq03*yFxn<;- zMFSrk?`M{8vgcMPiS~d(hja#V4f2K+$w|tQaKSLGx*ziPsNIvL&jqSp03QI$Gy$K5 zA*VO0%E8mC5$0H%WsxyAU$@H+@s7bwJS zw48SGc~qLymE0N>+J?9^VQ`iu#Wrmt$v!JvN&WemHl|R#kJ=M_@$k0c*=+)cN-PyC zMvl>uh%kX9SOH2J6gKGzB7U7MV7A?Jtu4Ehb5L}(Q4 z0aB2D#<_)2q6QD`1Ihq4Fkm>tusw((09wfXfOTN*VceLv9m*>qu^iCJ{2^_P!59E! zuhnWij2#X%V0BbmwQYU;pX{F9lcm}=+-jtTM_=<49teweNJU;Ha82fv&CA+i`B|Ft zA%(WHeU#N6&apWK`|XpZD{XGuS_yaTw6?Kl+MzT5+}b9nU~iQD;OR~Fo29#)!DGHS z2lK@%_cb+f0E&oh5MIdGnFEadG426E^sW;V`Gw1;IH2R6{rW@e9BeRtl-39%1W?ij zp!}v;MV7I5t+x>XxBn5x5AN-c{Q7Obx0&;x6vy>L1Y(4)3-|25y;r$2DK?m#S9ISp&@|HvmH%N=^*4{`I9lsLb-+Q(9V@Rso;B^sz6; zrXoM<&O7gPX5`vyuXV@1Fa7E7V^axy=sUg&p?@g25~WgDSm?Rk?|a|-?4uw3XlGPL ze~+`T=Nkk*eVxG`j_(iP!Z4E=8UNPGYN^;9*L( zFO$<;QjlefrWH9LioRZ~pg+H1pEDHXx^O&f0wC(3!mDuNaln!N1svftB78t0%K56} z(iQM|U2@e+^^Y(v6tT!ZLBg8V^qmTU!`Tc_1}9*68Es9)k^w>=OaLi&ZT2udkYR zOb8_a;bjRBASOVF8-~R4B&pm1R6c$FXj`#N#erps0w3op+WM{MXH% z)05FsXZK{j$Ntbf-}dX?uT%XhY*=Qqjmm7atMgXc$J_6-4)O~N%dGL%-yRp5n96Y^ z(-zDy&kMdY(ydyWO#k|F4Bv5mt#i|t^QZgRRODxU?Q37NAO7%%z1Fcw_gDtoPu~m- z0-yBFtrx>gH{(P1AAR&u9|g5%kf}_!5ek6XT17?r3UG!ou=0kO0!FA?cdQwqY(cRm z$QBdRit=2%c~7i{(FWA**=L^}x{&hMkV`}nGV)_mVHwryEMw2xmLVl2JKSnDStYhj zg&&dV?yME0c>9c+jf$yiw2so#tV3#U9Tk@xcX|(1d#BPJ@J*@}(|Sae3+85u97IBR z&YnEdWz+$hsJf6x#oXZ}y|!2RDOt)jlXG*{9IefN?khMkR9K_sKz)FK_$mn{2oox@_h9A(V;`GD6ZA z$A3%F?vZz@oQ=Twq@NST!c-n;w5t7eHd&Fa*UTMb<-;@V-`}dWS9giE5Iz75Nrl@K zvFD*{I#h*VRnJC1sZ3qi)*uE$;OU^Y9~QGB0XYXpg;JA)duoy6uS+R`1VXrS1$vZU zB3wkMAE1Dwd%&eGiNDX>@sDfdfRXn#X8>JGo(0K>G)0s(nuA6IB!en*S3P=qB4d^qM`m7DaGzz3fb z?nmaB`;pJfINb*yJa2+sH#dF>dfH6Hn2V(fPbA-sdzD25t}D-fR)YaPi^}RP=f!VZ zX5CJ!${cNeADFhvyINZh~WmRk&kvq3xcW?&Hbr16@< z_=G&4bcMRneHb6U6wf*59K+d9xAjLInlJ`d-j*y`;(roz8=FMOxOeY9R-QUPU&>%o zC4tWGjUfu>;g$GjRBxC=<}zKD@?0X#LFNXre*3p7zenIh3RnBZB9PyNV{%NbAef=O zE9KEiLb`aGwNJfVRKSR1hKi!uGF5ATd*=an;#g_M+1jSn@DfQa12C>r*wX8-Eb&l6 z015yfLshUQe}YviM2mJNjVy4LGKw%#0UkjELWa((7%8=}p>p(xI;#Sc04ovd?Q{iv zj_IWSpv?#6ta`}Y5#Yo=gdh>dM%DV$1$-`5m{nK62WI8RFK+Yv9>V#=i^#zzcj&M) z9Q23x2%{qjA3+72VC0zr*W@UT$dVkigd6aZ>kkQO$g-5fGi^w<9q1^q+O~ZCQ<$Nc zHk?-25Ark!IRg+7F1EQEQ3mAASurMS@AkM-&9McZih9O%(eYx7g+YWAMrU3^Mt_0mmY`|0tN687D$iV zHGg0m`iQ*tzkhJPigi{+>hb8>V$2x@J3q8=qSqSoH@o=3GYEAtL;+yQIEEY`KvlG; z#^S|`yEwY%x41{Y`p0$7j1tNTJ4#q4_YR?SUsH`9?yLT`0DM?jS(GaPwES0=QMbz; z$-dO?Zdz;`506$s-zFQaLcZ8Og)#0E12iqW+CG&3g1!5&zOx8-n|rH+pZ@NDPv<+8 zfe+t3d|$HYcFatjWl)<@w}k^ig1ftWkzy(C?rud}+=~?p5Q@7Om*Nz6hvHteIK|yv zdh>mE?#%t0f0;RR-hI|yYd!apYIttAj!K9|_o1AAy?760*6!z>_c_vqR3~;F|6ykR z%`T(AJBBq+$71aV|2T+~u74|)!Yd{Vq54_24L^x>>X`aB^Qm?5({IPTdf;vwFzKE-M8(m5Ck^N3`2R}Va%_Vg}D#KTDD3~~k zGDJ58cL)EYQW*R|RzV80b`us$o6%m^3@%T9o;WqojVEB?k0``+52{cprHwMd8$bBwk<%=>M8f(N5mOrQEtC}bIhA?J#;B@qZ4Mdt`LMcJ;~#?H z)rXV1+S9wQ9>u5XJM^1jd!hEcYH}EmaB*PbABSo@DTDx*!%x{IQr8nr^#orZ0tr)A zmPYs4_fLH}>fKsjt@k|cG>^adw!0?lP`taSk+}LgY*xVKkPr;?Skd?SrrnP(yOdQX z*^KD;jrJ2r`FpyOE9``ZE8n0qnpQk5m8z2T_pIAn?P3c1b zH-Np3_krWw=3XZ&rh}bw!#{~qQ{gw_Q@U|3{y26|b&a0cwk`349->Do>v1fkYuoOO zSJp)Picud{bN)rHc|J(M<#H!B1;jOe^p*?s5c+w2k+ta~K`a2yFG;-gSHJ*YDGA9q ztLDQM!#BVX_qiSsdsqP%A+nR>dD&n8i;44Afl-;_y$2(o4Xm?w+2#I|intFWcP9p# zic92N){VWpzF?y7kV^c#6i2{Lx#Q2W2{T`A1w%24$0Xn3MB^`3R;OyzkML;c@mlU5 z|6Kkor6d%DtP+g@cBB9>8B|~FdVJXzr$TC%E zC4@rHNz4~ptN7m16R2S+2!80Y5k)WDtifMj4_Uvm$fZ3Wgr=Fg@B5D@8(8=xmlV{- zn`&*NtTGps4aSmt%EKksg6!#rB3@|RbZqXkM(B#v)6AzTt1s{2&>Z?fo%ZoX?|UTr z2}qNqwmypHfrTzSm&2n+TAty*pRw`h3mUp3DF7Ag7XS-?K?!O+^?h zFYJXyn#MaTyLJF$D&EaVHub4sT38|2vVF~Ev3$DMT(QlOl6U+meB3=BFtJgwfXSE8 z^(bGo#PDba;pqd+(^`Hz*bX%Ds>=>+>c{_ggn0ostd)HI2V-7WIQbeCd^u(vTjP$N zH`oDp2F{Hw@!9OZz3ZUKG+7|)=Gt@g*>kv$8N6?clnS+QLvG;)-W$F5qKMqVP5r#k zGPN(dsp{-2<+gz8k$FwC*tWU1{U^mTRz;PiKyVdCTYen@RE$$V-krRxZgV@80jiqU zzgBRIG_SfvJr8gOxC*x=h<+ZXi$@Zr!Q|TF0^s(o^`Uzd#$uTP7PYg;)QShh}(F057=i-Qn6u8e4AQdCpAn$L%n69F&^Iu8Zv_~TkJRB1P;uyuQ&`> zgDt?tSH-T0C~WK;93pm9FA@PgNL4vvZHAAM7OE~k)z~_Yl4tsH&E@<-sZ*NEa$0{Gmf{>PI00@~{@`>vF z$JGGjyh8Ek&t%K+OMrt1Y2PKXC1i2~a-&rP7=r~$JskFU0LD8_5RJbM`9QK|zjDvl zLg8zNpq`Zpc5PrA)#B;wSw{`^6zR6jEvuwq4vNA$*h1#w8o^(pXU)G5i5*JcAMI@- z6>s}^Nh*nXf(8d%_EC(m*ls9ffY$*iJGw>BI4Ors?*39SkeMYm-x;p-ujE0d~MH@*Y#x2WH%f}#RXlnYhk<|=2+UcFe z^9B>Gs&IGDrQ>Jt%(@6Dp=cenFV}IRUeWK#Xlo@&`9HRDo6YQmN16j z?XDRIQt8vV`2`PpL5z6^11c>DbLStUH)T8ZO`;tx|pWSxyK0F zNKtObjvsR9+tl=dOF+n!!F$=(-oP#ccsyT*hnYRmwL4c!KUOS^*%O(r!14X1phl+x z$dnpSpp_&|7=zQa-!6r&AOFnu-JoZ6$5kYqSHkgk7K^(<3ExBFt{!W(qtzQtt)vgi ztb3S^JZ`=)%vD^g&{+#znP-vMT(cZChM!~>6_%e_K+B~^YWl`3W8Q$On@^==qR5(8 z<&-b@vlFU3Nti8ElqNH}m)S+C&*i|MSyD|>!@*iEfaa6R)&6w8)EcaiC)oMNjnAkI zzP6AhWQkHg*E2F1Gt;aU@g{7#$1<{rf3Y>Xyb)f6NlqHGU?U{S;2j7?*17`j2WpA+d&FC=zHIh1 z=u7Y52Q={51Y6Bl`5hz;!E1?_iGVUvK;4qq5c05!_7dTvLIdzZ+Q_U>kWj^zZxinj z&D?f}F8>RXO<^GYTOnX*$%g2z5XA3mmBp3xOE>Ul<8I;&E+v}d)sTyEC0j(*9O_f$ zGpJ z&LFsp7*T{5^@B?>ABJPBZRB38PU2(a3WQ{FE9x6IUPE@e2pCJ$l_Ga|&do{7lXs+% zg0Rf4X?BZ6%4(z`jQbc6+*|%hj7gHggmX*><1)8zlQ_>|v>(-C&PTI3b@W9Tx;ZCf zx;2(oKQYDCcs?z*e_bsT#*y?KDcLd1xE^L&>!DCm(Q)(LlfIwWBU}B5Le5*>!+qtrM`h3@4x>XlSJ9MmtL#PrX6p%lLF~5z zj0c4uz40#ZONLqa68h?rqnH~;%nkpALou2Z2koofJoj4KfEbJu*=23q@2w|<%h|Z3 ze>N(tWdFsC(|R{MZArl@+3-y{KlkiA;Sql1Q}uhrQogkQKP(rzr5h$S-D-dENd8uEUY6Y?Uy_pz=hNRCrl=& zw$}i;v_r4rq5g+B;*zAwSs7pZYLq?eZnThq?{9sA9fvOj@HP!`9cf@z1ch8%ye+St z#jKB{3E!AbIF|LR{uN$DVatdcrf(M_=yGo2!SM*bB*rd0qJku2iMhmmFRlRy(Ghy% z+k60!YN?ku6H2`Q-ww^OsI7<6ummp|F>CqnRbK`8w2ExG^TZ4Apm!KNB_yAVWqZPo zu^>^eeUrPk8*@9or7`r~hQY|c^Ja-@MImsi01@E4>XlvTC+T4VGdx1OIJYL7dQm%o zVpz?7ml`zIT<{!fl^_MI=n;%}=GD6nY$ZRb|5caLeHY(uZ5!(A`VZ7Bm$-rN5o1Mc zyRppX5oZ=1k2;m6EGVPA!h_Vh_CUK@b2!J)X$!wJ_2ogz`YAHtZIQRtggUtbuLb*3-06-O{mUC*2V#8cG3s*)wl0s0aw@W3VpiAY?k-G z^IWgJKjUrwtDccfRgdK0v2V@p;p5o&)5L=H6x?q-hPdGt#+Z{my!F*1Q(JJVb9vK= zoSgtswB5Dk;|4xW(dUQ>>~$5ID=T!3kTA-x!)vfk2N)dv`6Exed|+{0oH*$NR8XQ5 z(a%pL#i0K4ts>9o(WGn3aS3)GJIUz-%Yv&pZqJonB?!1r;OhE%&A^%>`~LSXa{D7= z{@0fxO=%j-c4Dge^N}Tv0si^3Kb+uW4huhQAG7ffm9-yeZAB`zAH}!Vwrur=ar}lH zZ&rGDu(7%-+7?*8D$$~h3J88`%j9~?hOeP~z(zCG)%`p^7Q*J4p{2)C49e?|E%_@Vjc{DSUfH~nUaJQi#9K(7glwr-C;LyApMjB^9cPPI` zKQdzNm@4JrN49F6QmqtUk5^0q&v40WMzw}zK|q~}1-A_zSOQ{4?q$`8BO|Wc#zuFT zio4Kgr)vCF9h1q(=decwPW9 z;Cb%x6Je8_kbaq5GKA}gK_PNQ-m0qodQhb~JV{2A+EtiYzL`EC2%k|Vm~=CQ&V-)2 z&v%aLcc49$odfLcekQ5=ybTyUN_ zt5zlSXqD^yh5~$idh~2r;n_|=)&%M(ZJOC)4}Z(^cxeYbIc<%rp`cel)@z3Y*KL#)kjj^ zMVesSN7XI9PW9;n34O{DB3557HQO~8qU?h16aKLLl$a+;6$TO{Yv+0*oxF`--GMSsE;6wS&B?W@ zeuK)VJML9A^m=uuZEhxOcPx!e%hb@&PEwr0`6h{J2Z(n!B@#!zY=ur@pX}BROUJf3 z2R^TioY1~zh>F77ZsPq#xFx*U8dJUEr%~zD@Pd$iY|T2-X4pqA0qn=mOZWBax1ucn zN3$nA*b-c6a(r)1Wj0XTSEnwGkKe^_c0D`ESBe>FcdOq0!+31V(ctkc`A<1P5qvQT zMtdW^Y1OAUoYC_c#S@z{GmUXxGk~f%$qA8rkPjktQEiBPHQ$S#amnsR#_+miL<+?)JgouTuWX5gE8#1Jj0g+u*Zvo7 zB>Ldj+bI+rBR07-(Jk?=u9Oc<@FMV%f=$eYy&wZB#Bxyoa#hnM$VQ)@<-8Z3taJo! z6D0QADAgXwCPk&*PS=!h^26ar#@B2x(o0*T{I3gv}gv~0B|O!aEQnf+m!6mr0! zhAqDGiR+H}oM2C7SEJn;Ens*Bj8l`=TNb*=kk?>Bzo{*Gi_lvNn8bfx;=0OF7G(!t->3sUIN#Syi0~Apn!Dd${#p z6_+|XUbAYte&`1SR?5Pe_)=KE;WfG z$%%pzdI=}YXfHOKF4p>UH1cl&b9fJuY&gZx_q@A+!#WlU@Fx=rCc+Ez=OCk;1m#CH zkE${^k}%%VFicrb-~mbc_Ogy(>+M{ii=)=NQ@i`2TM=z(6pHOheUlOnO%q5mDc^I#K-ajE65 zA#|QEw=l7M$8SS*r_4M_pJBj^O;JgystGeN48yOnG>cjp+84s#I z&o>q#4RwkbxD`_!Kg}xp^~Rags^sNN^4iO7rqaW!QJ(r;6h&!jHSl>n`hX=`LZKR0x^Jyzs6k^lZ}zOGakGOksCnD3KouV>YT8*UZ3iuvD3T!vaB&%l`s(doaYS4uUQvU*%`d$v zzvkv17M0ItjPZEpW~At$c~Euy^$0OT^Q=uFAFKlZ6^-Rv)y^ zr<^q_jjpNgrta>tF3Rug{OH1}2^r^W)tbYBhd9McfAIhN47dih>}2g2gN^conzIJ( z1$~}p-WwIk>O20v8ZSiFC?)(&=@udCHDYC{v`z7&uI@L~tVNfy5W;eq9JG?!GOiMb z1~_drY23&3a!lg%3}dvBP>{s;|D)MUdNcp_qoBvy^pxzB_9=8g$Sp33q(VWto>f`RM8}PE z-^>so*5~WtN${IlJf9*_2)_{AZ3kfyOqOlA<8LSBTB`D#415T}%<3R1yj~j^rJ=55 zOogrN%yi!_1~HTJKho@zq#_O??q|)rJ+|%@^^dDle`zBh1Hx163f-~ZC`C`#Y~lJ7 z+sG)oKDb1k+PiuFp1IE@9&79{Gpx+ zSip(_#V2WS_54-2fq`5+Tp0h~O1Zg9fT|3$PF};IC3t=T0 zpDQTL=;t=j>S8_;yaw1QSkSRO5kGkFkfn9o=NNen@#F(#eq6fQf^7xd;DtN1t1v)$7VL=7C~ zf$T`h$E%xJpH|J^21`w{Dj-xnA1bM+Q?D_ng*EqS%AG`CChn`+D6;cdRP`_BzY}>0Y$7j^ij_P`JY5d6 zyXBP&y`-rwhBdu6`Mg{Xowk%B!x8rJ^a;qnNtYdTTu-7Ma}hEUH+?ley}NZ9w$lxTz2N35 z@#t(?R%UIpS;riic^BMMVLkN7=e6n5Y>I#Evt#*^|3R;M+l_oFwP00(5I$5ZX4Z(l z#1-D|Ga%F7ccM(pqpfcU!O!IlhB~oD>ex(A8j}pbjeT|qLZGirNEy6~H2La1Pl;A5 z#QcdXOA8iLp+FlVkZY8lq`M7dCLQ&~`D`Dqz*yh+w$o-8R4IkCh1`h6icDu{?<|XTcpV%)9ES_z(&dn;Tz6c)I(r)nTF$C z2V~z^R}Sv4DV~X`(0uXgZtWk$1t7GTH|BD6d%&|fRHQ|pS_lJ@AvyN92IJ8%hppwvDl;@Xu)7VHSZWp?7HGO5U8um<3}#N+N)Xb^V$2KO~Sl*&C}LgOM>E476dY{L-kC{_Ll*@vHgbka+^t!E@j@^ zULEVEFtYlk?0{qBwyxInqEw*1K^)qLY{Tx~X=9CdE;d!U6K=?;{ZvBw^O zeD!&lidNaC+|5%r;?q*Qbu(GY%GtW_8M%Pl0k+a=poK~bH+HEZoF6tOKzU0$E}o}X?wZMlS!_4jT@e!nY>FF>)_RGpli)@ z6!SsG2Cuk*#dmUp6xa7Bi#x*yv1$&HlR=v`8Yb#K>}=~_8#|=t;e;>u6)6kOz7pNo z`gusn=W&7A#TziBxk{X!4ZzCy*`9}fC-dk)1A~mvau3e{H%hvSc7s^4M|?rw8iAOUW0U?j(r1T@ z4!Q>0?8w|cZ|SB99D7Z(Sj&!}BlL%wg4cs15yf$*rg?9DP}W+u1p%zN6h>fi|K(Z| z!*Rv#DvfeVtL-qh4s@~{z!Z?ExS;Ct4kFVtHXF5o#bA$hnT_p0)Dp4miDQD3;SAWQ z2;PzlPs@J_s}AzZ&)M3@wq0W2&}tcA-j1 z)2J;s>232UjT5x$adGb~)=*t#0u-PEwH%f*5-Q?Y9zm*_HpFHa21jR0Wbk3*MET(- zfgNrZ=~7FzuPUe*+D0VKlVVeo@p^@uZ1-5#+KY!TT0)p%NpBm8SF&6*eRkN4ge*^_ zBZ`UW4SSijG*)O$aXvd8h&Rcs4meV-Sn6Y7*OHQ&_S$*61sD*9 z_Y@)7F6=$X*A@9*p%$T61pN2CWwkQIv{bP#NDmJ7qi**O!VZrL9vrye)QuiK#t+GS z{NwdA+dNP30o+3apcGfcoGZiocKDoOy>IK%{xb(JRoUAu5J9vIly+oy61(rqo>;eZ zV82N*)l~Gf+ z=X-!<>3R>ZvG-Q!+itShUtVegisG;2cJ@$li(l;9W^TrPTIp!f>M}Cm1UHdq^p1?F$xm&-u51OR+b7B|7Qd2|+X0XD*@+| z2%+te!$aPRra1sZXqk5?Fpw&t>(?+FBXQI%4Z$nBf_AGxkREdnq~V$oybU#=(eS@z zDXcurn%xNaQs}0u?IriR?G9DnA_e9M2Bb<}eYsk>6TI_5U8F5?2_e57Ow}#XCND#f zv)cuDgId|}!_B)oFYz^is6MKT>6O~yBm;V0XdN+*@$mw=?zz+>!wR9zDTfi$Lv>8q3 zawoE5{PhLdN$f4hQ>1Zl>f2nC0TMf0X;#Rme)rWBCW5vBJY+8rmp3;OWdwDP;GGE> za*HEsRRvDQk7`H+Cn)U?m{)TD>2VvW?OF-hYuKY7AMp>}6zLz#_RBFK)frq#&J(8m z>EOGklj14S=gPIhy~%9*#bMEvX?jvwd;q(cVpgfg9n-e&R#f&j+plZ3563X!X6wHD zal(03MPP02&*#HMwax!Mz*A0Ha*}I;%KAOXKM3(#^;`FY37b5^YR%BiG|fm_Y%QTW zaNeK_)DJe@up$b%ur#G!kA?>a?X?J~FqV2Ia^`8Ej!CEGVYJE(;kwd`rH^zCn z-`@~f4-Al9;^|^vc*hxSRxJOo3m}A(T=CzdL-uk+4S>eeXdamub1-f-MP4;}PkYk0 z_9$cnJ}JdsT_5uRI5pk)kxN$qUaF* zH%9{>!a-v5ON7*41%S^0BB;$_FF^1wU_w)8+gW_sIGYFnFHK-J3i74zz!X>~$*Sdz8^w3q5{byq4h?{_08xN@9$RY~4F|1F`4F$BYgu{s_N zi}7?3L0K$7PQQ$%k1LOv`)XT!7frmtkr~DR|J4PWf;Z0lEtw;`v_}%KeO`K zZJNY;g#?F2jFUW~jzt#-hy1Uni#5%wrPrjwFZ$1WE%)^Scu^RaXz|2Dt*V+Ql)DE- zmFd>Av@--x1w_=!TUwhCcA092k}^iK2CHT|H*d#P{C;f5vGsD&I=eRTekgr*#Mc@0 z@?tl_ug6d`M?DBNCX(C-B?TMwy2|O2A|bd)FmIS5^r_28p%Tkc_Vn0^B5I(-6{rA^ zmlaiUg8@5ZZ*(i><%nOWIHf4anye48(7KXn=*w2s?4>^_T#_l$ANFd)I0HOwsX^ZQB zLp{2Rz67+)@JHYMMtGA1!1VxKEH+w6ncQ67JS8H6wEKPoda{JLQf~0J(0(z#eLl09 zCufCmA53eYQ$O|AGY6x#;XT#xX79s`#xSJq0|B;E!@b(B0W};wD4R&$K?>h1o-}Z3 z_KP~2XZ;U3kBw6xSYRQLPS0qsRmNrrBc(Yi{)QQ62HW1(1h;Zge~Ap|kK=MzGfwSZ zjoC&=IdC8Ni(&xGcAOK$38!y9=35$9YZ430d$B-Ho~Ev0`*jGRK)|tx(?O1&iLZT> zy|aC7EmbndFFy58)(j~dAD%;gIu7#TSdlGFMcnWbpj`PkcC&wTjTulg+o}*Fx%I^^ z?g8obizy5OLZQJMu)_6Ni(=d3!2iCpCT*SJU=cEf@u4z?FDwq%(K6O`Qzj!?^^r>^ zzDH#xmCPjgUpjW4&(4He{B?9vq;8Q=to!==>T2e<1#$^@dcwiM>kgQ!>d%ONCU}&Wf(6r5 zX}3O&rP!#(BKweXu|nl`nbFbn+$WQ1(TEJ$VGEOB8mRai`Xno=z2KZgoG`Kj*J#EO-8j5?sQjnEn-dg^ z;=7F54$E$FwGagOFIlP4>=h!G(TV!mnTXTGL~h>1KykKc3T1%*?+}t9K#?nX?8r4O zH$~yR>6JEs6gsgry?tQ%eqaC3(Qr=e>+6bMQ!DZp2e(fLLSVg9Qv6s9Q2ra1_^3X) zND0*=Y}NjIsqFp~UJSbBlNa)Ss+9=*Ondq*2AD_r+Y^8s(B(7#WhM3;5c;XiNXnaB zc5+N+HcW|z(^bI_^7kKmRl_O|{${$?-uLThV^TsmvoK;hVu`-};3kRasWd9%<2wrS zO;Swj?+|!%H>hahY$$gV*B1b9@we9Y%Ld#C^)H>n{po&x&r%Xr>EN6u@rZfc;z8F^ zW#_mfL;qegwoe7$h%Eb$TCj3MM6RY@=@u{YcF8MU(VE_<1Rl&%#y-%4Jx6xNd=8d& zYLaQOtoM%OPAm^U{d8I%GLB7uRW&G#RlDnCDwB^t_w9^q2p{0uBNj8iIhgTp%ur~I zawlYQi)KcCNwSJIwk4D}hXtG2K7St<{hfQb^1p{Q4q0@k;X=4lT>xL+rFbZYY#&CU zAh3v|Z9f}#Ey)$VTiH**wjMjeeWV{D6`*}*C$Ig@K!Gfj2TJQQih}?e>(h>-3m|Lc zfBGBKQC(M8hgq`Loin`syXv{}GlqDuF^WF2q}#%1hSRd?sT&qwi~XLOi~DDav4@`U z3#oVLm>jBq;vIIyZTMcZM*0!CI?0|@m4q+0o+Z;U%8l+j8fO!iT?JhSHQ);|1fwAl z#|^=1wNqxIqt|ZU8i0_D0>xL*r^#yL?mwrxA}LyoF|J8+giE8{$Y#Soj~D#IEVYtqt3<_eem#8jn#CIOdvBXGGCmYT%t&j+vgzLxT36f8Ql&Op5k- zpVO(are4?I*(_xEET4-x7Y={Z81F-2%4?BYTD`UKNArrb2(6y)q=9y zXPy_Rd$}xY!eVDAbG1DD8nGjmZ-Gqxyy&IU?9Q_uP_VIYcm}627Gx;!^k-!?@2TpY z)>aiDrwPs?;5~i96nVq(vztC^XqZl(SKd!7;Pq;;hF;6nUo?m2=m_f=KVp-c4f8d! z!e@eW=RF$OJ$o7J-mzY?1il`n)la|wy*(oa$c}T%+cV{fs%*$av~she3V1O08X(Xk zkNa5^M{@O_ZNe~cT!ztMv)*l25gARYj#g%|kN>;{d49^JVT3M%NiAD>r3HsOmOk@a zt0IB6WE2A&>=#RaM)X@jx4d|g{jf~0X;@kr9*EPsi0dCKb^E*6&izUMb=wQOFlBN@2chrlbG5RsJmr?OE0Jwo#^%3Kk%i{n*M<-^$1zbk=sSm8`h&pqgta4 zl}Xs|-{52$vaS-x8@l3|lGmX7fi6!Q9fd7Ac#IV4Qd=<9b?&dEtms&{($e@_ytnAG z&}4nnK`RHwsEYW;Ba(_bi=CDeQsYD+Uu`Ji$)cH}iMJz&`>XbqxfZG_nr?4I26N*DwU5noh7pCd^1Sn* zoWciNe*dbin~1NQwO|579yWOX#8yv`_!MciM;sRkTz2%ZxWyB&jUw_RQ)Qj)k(wCt^JW#Rl{woTIN!Az?c3R0pI7JVET!1}!&h0kWh%`InFm?H z&%NMWYPs7r_c#K*a3s-x?O%p)4%d*3S{c=VKy^6W;ZC1s$r?g6wx-2bPB-P@sr<hHC?nBbh3_X%%F)^Jpmr^uEt04W6Sc6*}oK)YmAZ0Eeqtv7bCXZQI{12Sbs;3&s zQ&0(TuJUK4N1#dFxOi`dyPD>~$J$z~H$lN)^z++!=Xejeo;9y^fe-|)utk8^8yFBe zwL4;)Dres=xdn@GL$E7}9@zvaaja`F3IY<6uGfYHSoDh5p%_rD%1&s*jMLj*I-+I? z-40rhfWbEE(u(PZSx=40kdq^o&31l&8#x{qzyS^2)>mH?0CJalB`GR~qk@EYnRy+N zf7MbZ>&Zl~ik9L?%+!sI`wgQKW`nTpI%^BpRsX_MwY0W3Yc`IIzyo7Ox>S|3@y z3jUx5){Rra<9b*pTZ5E0zAG#nY{Vid!(&m(AHvPVz6dHCnT+*g0_%Q*Vr97nE~lK& z`VE#CzZS6xrPEQ#4$K4UP`I3hu2D&CK?gnQY9CI zV2Gm4&cnl-$A8Y3T8aaIEYSVjo_6LV086Z6pTKES?B7d~UbmlVQv^zH!bbHp1G#cm zMe3T7@okO?xBJ*zokhtmk_>TLKE>o}+uAMZB6?7`@O_StWvoFyES?Ij%-?GwWYSc< zMxY>yuhEKFYk=kYG}fsBzz}?1z+$G`lezQqjxoWo!g_~)SdLJ$&7dH+Xy}=rPB|9o z$ltigsvh$yJuxNx03_@shK2B*+Xz&e5C+;`KiNV$^YZ9@)Y}pBRBH>EurZ|2)yxt%Xs<=C)|r_cl_h4s)+=5;flE40K z2D7i}0sSvpIG!@WEHZOZ*Ib3$1Bo>RzcEr34;!_PIlGZBdT}KG>96TR1^_7v;ZuK| zHdmdhxD%wpE+(89u;A2grb!&8_9%+1?d%dl)uP~_mU35hZ7olKUiyA>8&g5Pz&y^L z%6JDe#^m68^_xM7<6mERZ&Y}ioM)=D?3q^C>@#KO9#S9ioebK40&yKwSlY#kxUChQ zlvDRl?ykB8Dy3S`Y*?)a1!6$^`}M3Oe9>JTPxL)z$5&^B-!M2ac(-q2AemE>Rkz53 z&+Bx#k+B=(5d#oUmlc!$&g8RhHIDgr;=IQBaBS`vdOy-4d<@hY>NFljUZ zlQM;tDB^U-dM?Vb{7?G|!RO}oq>|*eiv8I4C`V?QX%T-6%b^duhC#?X@j}5kZ3quE zR!#|$VZn&ocpSVjmjMz zX47TTiMEJ<+`{mZn*kuNZRd32o(zi#hb$kxe#aZ^=WO-l?RPqLFGG_YyH)Am1b_YW zsg-;bL3RiP5H3r`5~11;Sl9!=%mp~b{HB%wb@Q%(hsEZ#)HMqZOzYP2kkPQM?`7M# zvEji~%2N~8vCV#rn3&9rm6%OXKlXHa?G+FQeSYps<~qOrM73B)FMz~SfIkqj!Wk-) zeB?<%ZgmaXzTO=xzVn<-{ICv*WN_N16LWE1AZiN%x~<*xHl9UGWSV@_&(@E|LLMpI zI9x{FZSC(bX)Pu@Q#fjQlQP~A7Q#oPehiiA_ScJJM@NLyxBxH8z3sj25k-HcjabzY zg6Zn7t%COc{++uAJY6un=||0bXSXDOQ6B2Zuj2prPM)%L22epjtrYSibdThzGGkiq z!}QClx*zo?dRqraFvnV45?>kyY%O`-jd8J7C8r7o_rVJ3NbP@+37|bArY@~`zqsBxrVg%-76^^-s zb;Eo#s+N9h$G=)A^#{U-Pe=}a7tUZqK$3Te`y_Z7hxXF(%E^=!KWvqyq`8WC>WxG=A)1O26b>^jycv52CeMyqtGs;2P(t?V- z>bxRBsk_t}_@#@Y6h7CR0%V%RF@2aChQjhMDf=+r9&kVe8fkRn=-+l7b|3w=evimy z+xtzD<$u{BOkittG_ChX(v9HmVWxcg`KK^8A!)CZ?^vL9XyEC@Hi>j;daL*dNxf)l zocmGrBuSVB^*d>)RtsHa!9_w0QRNgbw>%pCVGOmjGnwW6JgoRxmAukQAx9D~li@1w z?~j;M92_Lb$A;gA&du)=w&CUiU#8idZU-ljlnES4-CNdTh+TU8oi0pQ5Bl3r+o;ez zEOF5vtk|l5dbioPy`4#8rrhuY2&PC8VV6{v+`8JFS?J5%P7>`T9)f&Cjcf$vvA4sJ zNKk0~n|>C-KLj1!=z%UPTK<-Q-ZRLN8TYaX6PJQmZ>D0OVZLZTq#L9Q^WEHEj*=67 z`uTZS<95@UqGm z1S}Ji4+g3F`Fl@l{O(_2MRr9m9INrVB zFd0cWhdT1dJY#OimOZLU2m?IA)`k1{SB4&~^B?m0o?ON|y!pCeToC)pnFmD_4mMMC z0+hE96{N@e>Qi-Qv-$`&b?Z`RC;V*(2-YYm$L|LknAy3~&Tr1L@#yxRG3GA|x4@cTJ z^uuj-Dj{l=O-Zeo z8+IoKAF1Me(_{J^Tf=oH;M9Wulze=r5y3^@N6P3{$<_Qg;=b!N@?_%FZ1qNld2OP@ zY&B@E$5XSAVs+xaG4>dP=R^n#Y{!+I&g$=Ciwp9;DKGjB#PvB?NIu7YjuB=?t2&8I>+|58*7Y%pnOfAAyTS{v~TgHsbN zhm!v}kpH%RqV}Y}^ODKtHkgE3@6y1n{v+kN6rD1^lz z$T_kihw&UUyRM<(k*Vq<-PV^bz%n8(g*-o)=VN~xUFL*JWN-;c{vk!)?$Sl#Owlzw zvn}nD$bOc4;=8>C9n*q&gl5o52TP5_Bx=t4$q!(vx!)2K7(Fgs`Z=@O!nlvS`U@l% z5si*|)my~detlm7^jw1`-hCWd{0rG1${vUpf@%Zw3qV|;o%c97p*TNfYzW8uLs9vZ zewnpVn$lr2#7q7a&5K)Q>>;3rbfi|Ok@(CBZrT(~%J`1N;HdI!N`Od};lb}(N8=>C z;r6ViCKc@!l|1v4%<41Cu*(fbnIt*R80MehDgidb6p~IWJBf(+=Bi6nn!m?&QUQYg z$mH|kD)9Pd1K;V28Zy}Q35ltC2q3{7nUm4}BJKHuPm%!yzVC-j^Y*_XTE-r^yHLRv zm-?K8-}tf5;yVF2iOAGPqki%`_NW3k)Y((U-0npa8hW{> zCn9%`O1t2yGz(J||H6tCoBqv8bb-&(wMR$z?PHDST~3fuwT<@WgnQ3T@lLWsJLAvK z63vSQtW*vVHj0+TwZz+&c53T2p&q$wC?Hs9wb(dMZi~Ud(-(TOua}?;Wq_N+*(KaA`(w}^QT&rkbX_&#lKRHyE z*6{ygMme+p8O_oC6k6l+>rzpp7}O?YAnNaRWjY+J(rE!*RLqTe6=MERH?dKPft)FE zAm)dMGi?z3mxU&n+e@i$2YyYblNzSYFSq1bu5y))0577OzYqBAqg{q#_^B^Txt{Zd zwrH@scc$kYy7jrX)nefCnhgY`Ub(*eU|V#h_rcmW9mtv5J6d*b?bT11lbFnZ>r^TR zr4up)zpq$u_7oz0zj}j0w>GCCwYHICXrXAnFih7CI`{eNpK_&XNa686Je_4%8*CG; z6WrZhic{R(r4%df!71)8!HRp47AWps+}*Xstypk(hm+@B=bRsqFUhRQ+%wnS+ev~F zLY>4f6+9=CvKP>W#q0=GIKU#5E_;5kKSNWb(wH7zbrU)ZD1U`HmUbZOYYOw>@l00M zepZ(#D8}IWBXBq0?zJROiirOS4FqPvWu&eNUrS#{`8bZF5n3PWOST#MBwxbPe1LFE z3Tm-%i!-1x1wayz2Vog`qm685tw9HjGssKkpKDVF?y}0Ue%~v^v19MJ9p962P{A0$ z@9gYzFYH54iF4Xd?{qN1VS*EApx8UwaB}RBk>nM_;9WdwOcfh)iGzAVWik2$7H>lU z{+F2(LXJ_vF~j~bY#8rZ;vHf10<<%R1-HA&HSy-QzYgnl!|2oG2aX-il86#9w?DdW zR#;%B#eEzrmc|hHS?lMa-KEK-4?gVJ!H)8f9<9p6T)_`UkR={D^q#oj>A{$S-ynQCc~&k6o#L8)-RRx_6W{kb z?x|NwXg}*8g#(H`#9#`vl<6`Nw7lGAJ3jA2b}WfVTQJXH{w#1LlF z%N2%$=eaA6i7TVH!mS*?3j!rF> zr#XTFE102P<3Dh5FmA73Ki$-EZ%Q8!LH9T@j0kx)wYp$?DWK_q+@~{xrRl5G5k#5~ z=LP$pPp)S07GGbFQ z(6h@<@O}W~mtTU8wR7&U&J;3wpJbPgC@HB1F;V))ixNT&9hv$vUp+Y5FtcALc^CEr z?uJQZSr^z$y4IklTRY{UNaxEfhb}%du4l!dVyFM9$3(;_9-RLmSA$BfY8CWwedP{t z36Cw%N^plmwJ^H3RSw9auEUz)tD0p1FP!Q+ro4zlU#}pe{{bqlp;!FhYOl;}curDl z__4^DBMSx${}QlzjbQN?yZ;<#C$d#(L&UwaBJ2jJs){`pIt2IQi$)mv^K3QeAIm3c zcH3uO*+MdKQ3l6ET0e$)sSjIs5Jf?C{6gP&xBUB=Hj}P7u#ZuQE+6Ibt(qKFWkN_j zKd7plenTf+*Pg%pAyB-eOiErRpTZcLqL3M~dV(K%F~Y29Zuc2L5DSmm#~~(gRx7bs z{)V;LM;hS!`BYAY6u~S<>JLD;05aDvVMsOKq%$y+*sNi^zS(sC4H-{3C8dIM63=^- zqX*6ndvq%b?@4ANSM~@Y6#gfu`>gG2H76-_VbF;zo){tRh-#0xid7zNA#h4oa%x(k zMnlUGwdiYmlak2OSBA8nNs|k6an%!HI0zE`t=kjPcx#Ch4~hl2*Tw)EkPK2Rw}CtG z0`0%s;e0`SApa3uGd7!5glv9T_+q3yX-^W_PK#3+c(F(~|0~ss6aVm6vY%Dg1w||K zO;)Xv)$?)FOFLcPebO_EwVh^=Yi?~oO%^~94z^2O=8hus2V-!E|7 z+6*o9h{Oe(ZkX{Qi;cR^7d2Z-4;?gMwTsqwVPDQjy9$#fT0((XzYwR5OK%yT$PNt} z+DKQ0Azd=scVy`R{NB=r+wT7uk;Hwxh-*hsZb9=X~ z4>|PuOcUq)j4)VMY_a11j%&IdABk&KUcxNbBK^_aGkO@bJE^2P03wDRoR0R=a?0*; zdeXZCU9&r8g1vL$b@|EX9sU#bR2M)ruT)I;i3nKs#OvTtlxv_jGS>%+hulCJE+LF- z+_8!+ZUaaLe}yAzPQ8U&@UO20S6a?j*=D~e4xFX;L~g`;N%?BX=a@wv$wt^1Y{ObR znZMdf<>>aZj}RX)d!9A=@|Gx5>{`XKxXums>I$M$aQ`tMSUrns^!vzO)FG5FB^N+; z1jN4LmG!Wh%67Hq)O6LxlF?=Igq?{@GIx_(=73d-6nW7C+v*slR4lbkp4xtaOD+uM zolBF~qQk1c2iq1fR>svWUO=rG5jNeRF@Perf`j| zrz5^fn$rv3*zc+zS_t!4b=hUVN_yEC9$kI*TZuRe6hrcd)>wV}u%%!70=a2i3!xte zBLsb2`RW8f#1%Tvy!s+TCiFL?k_x+$QVb~LZf2DHh<@HLnVf;eHjwNd$7c?Gv z_4*R@$_X_Z5QFuFeUKQv3YTw1jSy9jnWFA}r2Ss`c{D)aU$&mpZr{UB!5j=#u7lXy zLU;O@{E}b}VShMx>;=aPDH^_v=oG2~0FL8`6F-*8jnoc9A01EoeYF8bwdyC1U^TXU zOKJaMJ*Mm{%x96y0o*(0t%UWseaEDo30r|J8p>CT|>C+LhaP4VEIO}CZpY?%0N+07!o zN@M`azEGQE;=BEYOO9qAfB?)sgr#lSAT>1g)37kHJ0F7s>m@cw<(XJ%DBk?B=|U`^ zdTsH5B4|tNevD$Cew5w4G1{k~_z!&)*NG;Ex{q=gr-h%#U~B+Tiaja+-$(1X=EXDb zz>3{*Dze0nO%ck<91?lPJ08^mW-euueioS7?^e~L{Xm{g#)2lOKjK&b2g97c6lAM} z-JW+|ys1EdB^QwjR-@hqVw$ei-9N_!6|p~ZiE9Z18R;FV_(HC+?~t(+mo^7s>hR=t zGonbsU9eLmHiH9zD8Sgvil3~NP9amb?4L$@_si+pHa0yOxGqfB&I9byGsZ;;qz;~W zgE~Hpa+`R;dUl?E!x;4}_+*WA!s>q7|LK*U;e_^{Z+hsS??TaHro~E*TUHW0;AcpQ z!&zMq$k(+`3KETl&y!h6o8T)0>0B1Pz`&z+NaMLA{a>K?D(ep6V!6&dqM#V1Q6DGD zVX!wLt;A~n7g@5*Q74?6X7#DqFU3#Sh^}#IZGs%c?Ss7E^gjIs0gm z>NA*InNvlxACNpsV*aq^Hrr7;)))fA=>d-tMaBud0t3IAHE6B*B#*M)su+_ z3%{lovriJf{1Fc~^yl)9SusXrp5)XI2T;)!TvKW2&ivo)#%p3=WJzj-^b!#biZKU} z;A{C()wl{9-`?pVtpsc@e9sgxm>P`p$kWe_*~Wc+-@12VS}kN(IDhiz(EO3_dT1AQ zL_0H!w&>XwG@Ts@869) zZ&>Bed?d=r#?fu8pL5B!Gs-lGlpaDSm=t?Vu*pCmu-%1TdmQhh2BB<~ zf21^4qF*c(9zLIH681W47!+99?^W^=n{Ij_i6LZfO4wq^wz+mfSACBb{*O%eiu7#) zPVuNvh*#Fa={Wi|?R$w$68$-STdY)=O7wP8=BZs+}VT%1LmjQ>vhpChnUj`U%T@OM$P+4{W!3XW9vD-DPpb3^Ge z{;p-~-+bybXjD8}Fu}i0Q(AaPIqOW4A!|w19ZiF_i#-^kW%@GMX{>Rnw z?<4X4ctbEr{C8Iw0qHC4W&)=SF-9E_u!Dk(g7qXX{*ZZTT;c#Kkh7w6#jQVD-=oKG zpCq+~LCC`FhxcCIc>WMR=>s^1J;9M{8b8>E8Y zpAuIM=ia-YPp5cvq^{rC0Ap6XK)##Fs1B4TEu`<|2|H~4JitE&X+E9}!YBy5^d5tB zhA%4BvCtm(MQ}U`46%-EO+*6{;6Y(OBK;M$*9m5h?T%d%korxIzlzW1oIm~tGfWTH zj*CLqn!T;CWX?&{`}AoZbgJv?>|PunSXs*;Aj-s2i(U8afhdH(A?HO`f`o0qYCl}A z^i77<@?{}Rdjk}p{EmmFF1a9=f^^M1^Kqgi^9y4dfc7PJEtM-ALpg11u?$7ND(Ttq%*GW#$E8EIMm9th*yn!BP96cp$X$QNja^n>V44L9teUk^$)&y&p` z^ro$Afy`LWO#llUThsM7QWqTpd&=qe4zp%XV*|V=9&Hd}1d%B)Q00rtsAl7-Au!B_ zc5&CM=9~vHd*C7^m8GBPobWg_WJxo4;n4T=NRL+7G8WW3QU{2=5WLD9Vy7Fd-UjYO2C^E}K7 z^l__-a_)%)jv?h-3yKGtjEeYf!lwMw7@V|-r(CcWxuE_6NNejRvKJ97BKm_SaQ8YG z@~C8l%=x7M1qY$uahA|w+d)BTV}irK`3-7aA-8Hk9B zw`Ou77>hZ@D(fIxAg?=(Ft1Hbh8)^UHEi}%8`4?OoR2f3VGWH%nkOWUQ{dzuWg@eZ zRlq#0;Gtvt?o^73?GRgHE!?RwNgL10FRcBvk<7K|N{*U_Xa$hJjf;Lo@zWqDkAtPQ zw6ujqz{+Qv82u!}kYgF|`YmJ+o(43>(S>Og0laF2d5lWPD1|Qd=5x>`*dIUO5 z{JD7Nd=<`!EF4w-Ofe_!!;cbQ-ic8}71AAJ-z}fh+1BE%*)`wYP~I49*clquI_aqQ zTK6!yE1xhNtdA1TxebhquLn;*u#xS8F@p@BI`oI()_OSNG#Kd=-@^h;vtqjas{TsN zGQ)?EHclHVk|&S~Ejeg*5=tyn1ha!NKiM&cR?U;q?u(-5GWOhW7n8tJLneEEVjq1| z0EVj@7-;sF=~b$`6_Xlhf*ysBLjD`{0qdlyEKz>{+~VscdUQMJcQ)--fYRbg|wxM(j|lg3`?2vS3O z7&ELPIm1rs7N}?Ne?W{6{L`(fD&NONra?(TFq!)VCl zyY0?O6F7*OpvFhKQ)qbZ0DLy8`#?;`UB7LL>7l!YX>d0H)NQ zn6Y$eS<&|F!{+XaQ75pH!$V(J)0>G68rsitC2Xrnvjk@{X!;t8QQ>l>Jb!$jfC8_P zSQ1MN1n_C0JDp#QtxxooDs(d|kq%5TMtb!`ie`+evwn1vrs*vLvY#<6mjz&KOjD84 z;TpDHG_vqEH{JZPK91lkY#G8#Pzy==QDF7UdXtD#mHR7#HBb-QS_`V)A*>%Y4k*E~ zh9#!0KM3OGvZ-{*!ML(Yf)qW7wY{{joeE!;>f!RSn83s|{)s;&6UAab?l1L(BCe&0 zdN@Xar?Zgzg=OFYhN}bGA7`@qJtt?)8#wpEmPI?OSESAaj++z?fUR~i_y8=9XtD$m z7Qo3q+b@5-YuwK1UoYt1g?BU2Ra#9;oG!X)&liK&r%Ohs_e|kT|7!GACTOpFvXXX& zAKtFFxkyW@#WoDisqJA(cl_i^-Gev@O4HbkY}dC|)(lMbJ2?Y8e{>IcP^K~dWI}n% zX0(Gl0KUNWCSsOc*SM%&-UIMH7o5vS#j~U4Ky?GzQ9yOiZJ9dP-4(Hi&CoNbXH28N z(-Qk$&qn6Peb>ES_e&?gaW|IF!(~E{ect7yzQ-J2D|>LjP#k`NxSo`#~ySlEdOqbzi~%p1emzgx>CD`q7$PFEZ6 zC>_K^WxI|s89A)%+>7WU{r)g|f)|l?A+i@7BRT|6JQN+%SW`0dLjZ1y_jeB%UusRa zQNAu(t;lERn@3oV$2{L&WGi&D)IlvVX$54KS_2S3<}JpVa+vq==%YF?R^Gnj{2Q%V zrrFeD-&Y@)!Pcf<%zEQyz~q;R5Mj<8Qv$n+OnC$@VTu#&)9(k(B;|V3+hY!jnW}+^ zmMG++h1ge82hdk0^x_0wu^D{64UoU7bM=QM_*hDj5yZM>a~3O)lBnEJZY-H@eS?tr zAi5_Gq3)qG{3PK-;=_6yGTa^Kv?NpiywkZqu+&-g)|=Zi&{JGzvQ)1)7`i?<8xyzX zYg*viI%gs^e8=BRA}vk+WBsRBv>O4kVVx5IUffU|fR+Av%tP>byedW^3isbu&Bxef zX_g9B$`jrw?w;@1YBy z)An`O!4CV8F0dbFy{X#;-#&Dx8WG$;EqTFgN);>2y@cgMft(IVmD{7DYOi*i8#j&9u{H{nIfe(T-OJ#>$P zu8)9}5Ww=9H#Os4_q*AIr_B6UXwK>B{ww}N&q#e_WOmToV}Mzu25)l!Q&7~gNMMq6 zgg4ro_sn;j4VQz~W~}^SGeX%#QGxBG#h2Tq1pO5 z(jLT4pBfoyg%r%&EvdvvC_WYej?pgvkyO1R5lPg_Nk>QLcz3e=zZ%Z(mEsb%u#8(F z2Yf+`$l0z4JK|(8+|>KgyFHIevw_G^s>PTq!E(V^D7z0?iZ^?anj!)89qFjNaiskC z$2yG5KveV*t;D;Yh+ql#3Tl^+Oxf=uOO7`9F-z&u*mVG*g;W2BctIt{_CU00u;pb> zgt^Oqy?P4Qk?*b8f*m2y8)ZW5>S;?5C=Qq_I+LVvfFhJ zX;Hgw&4MHRA*akP#WN|3<+2b%8OHrxKVCUK!cP;9aUzE-{E(M z&_|v3<8541v~Z%jxVrxwN&CMMDm9^gpUb2bmC8i`tFts=MmcHD6PXiN`>oO*B+WBM57m`j)mXLIZ;%I-7=J0R<^e6{{FDD8slNy+Bla!O3R zkTp;nvIfX?o!|elLfB*e_!Irinq8~y+nuhUSn?tP))Qpg%hewMZ{p*eO^*33rnZ%~ zB;+>X8lFxJj44H2`|0tg5*+Qf(j3UOngRi=dq4ecp%vzHo|8$CcW3x{(l`Xej^Z|Z zhQC*tn0F3kIq-GtD}mL>o#c*xp4_Z{lv!drewhyBD2a`LQ)8nYL?ty?0BUppJQ=$ymJNmoJ)X?>_;2W+)g#Ricg?CTD zfi&gsYmx&0ToaD=}&^t)q;2Sb$k66azJ-QP1nlV z7E-!DH2L$lKa>9_z#pjC##%aLPFU=->Ura^o&PM9TuVAf-_+33nwOk@K697&2MGX-sxI;CC5rF<3zX4|e6S+CNX)5|nY?IUibjuhEs-O+?K1lZ2IE|>;77k;JWwRQf4Y%1-6fv`29 zD4P}}b3j;$3BaI-S%`N)h4{k?ED@r?#S1(t)8b#r8c&$p-664#>ZK8?9*|Lc0uq_) zBtj7xE7|sIpL_7asp5&Ow){U#)mKq^y+8ONvnI;Jmu6`sGlaMKn%CTYtxWpC_GJXJ zlowhkwrCSzYQL|<_p^(0%N~(Yn(L=oMI=_GhQdF3;I8_Y#eP8s!kAjc9K`|G3V;r$79p>`3qldfwtw1&&>zSX~rCWyrZxi0r*`ivC@Hn-? zLv16p(q5za8Ei|Uj>@tUSaqTBBr{oB2J=U(8RZT$wJU{Z=-v4)%v^>k|9+M<$ZwO| z^JGa)3GGJCBxJY;S&k7&o_MH4TrUW9XGduGb&^{afKTR55Zpq4C4{CX(*An4dMfs< z?_-SjN&2h*ZG}nWAP>PDmNpEMy9axWS61!6_w=AgLc4pYJ+v)z=bz!Nu9vs_?u~V5 zRo*S|cU__%8{BvnT5eWs_G4wkNJxF8HF| zFYq)6QR~&1Vekwm5`VIh8J`$0=~nfnD-W3^ZUmc$=i>{?e2Aw_I{lF=^MnqKIRu9~ zvz$A74PFhbu%jW49stl{vuOLeL6S(^*LjkLJ?WL}TL=w&ElD_S!q&0ea`g?GtP+Hq z%nO|DzUaN-Iz{Efv^|K(4l;BA=y6cLD3PxxgMtX7Z-s-106>N_&+!G);B9UQN_-IM z`Q~7108k3!r1)+g9|;?aD)$SKI!d`*TILsej*~sXanbqnMV2RjJ!5~sc1T&;^^h*& z$C0Mj%eYVD&v~VXgea@# z0djT75+w^6ty;HFm8|VMoYBinK%p@KUEuAm%32 ziXBO>mvf9+oYwLBt($yj88n00msc60Mjf_yq&&E5v|4$qNuolaPWt0nBL!e;YggG9 zlR%^ToCC72bzC^LU}Qz6{WqrSLobl{$N=Dt$4u^iit+)*8N)xf>DV56cSNdzRj11PB$f5w zmgAh^T;>j|vx^}h;Ez4;q3{$Dias$8vJ0pwfuvRk6kstd)vJ=?FkS7Eb1QTXgyx5^ zB411Xev17~<2G^{C(zxJ2Y`m_=1*5*_1f0`9m4EMke5Qi@dz}{(cKyzeeVA|hT#Gh zbj{5q!Dt~T*@=6`Xzx3TZ0Q+h%f|g=>5##YrFJx#sH;juh`|WJzRQyXpf@2l0j!DZ zX)4DO1TF2m=5_K_68N(~R~2evs|?=;NMo_SamV+^6^s-02=ub`YVuTE*lLVRBJQW; z6a^AmwbvMOuf{QJW*Lwf&~M(wy2dezEtk%4ON}qF53^uL5>c1rIP;L%d9e4*9sF5h z5=};h)mf|-BrZM$V27b!Kf(LjtfsSNCSTl-p7Y1bWBNOXU|}D! z4?*D_9VJRVHg3BQ$L%E-Hoq#!KFk!#Ym~c`JGlWu<&qlin#Gh|wRaeU+5mEn~ zKX<#lv@+rx?Mip(el^1nlew;rb?YPiRP+l5&yQ&D8HTi9wi4>Y|47)Vj5vuc_m5~l zHq|e=6WJu%`X=-3Dl}GzRY&I=E*jNUF5?q62yYxaQ1SP0>6p4w=_8c&nxTJ$@X^h( z_qizgkTttKqo&42)Bx8$5fG zH5V)L{eNBn8mSD)OVQ%CZug}GShopCdXNV|j)E@HD{w{@=N;(sD45j2{1jo1*-{|d zgOowIGE8(qv5&sxT5!XE-f!HCG>;5&L0eHOUDWh>F^k-uH0m(15+oru^rldA1!MsY#}tP_2?GUQ+_;bfi0ImDL<`9%PYEr1 zfKO|Zwz`K<^GpIFyW6;mVq%-SXAH4_HD=|dy{9^UHn{szNj-c%RyhJrW`<1Xn_YeW z@tbHH?{5hHy2K^^Fs5xt(>Dyq)299txc6qR!I!wn_>xb%>_LZ)?WcU^v49>TH0yA2t*7If=6jVw6L4?yM&RlTIy(ZMy*PEijoZ`BVN(XFKl=ljGn_(S;OntTJ7&;B ze{ZvD!xnfD0523wpe71)=mn~Ujn3E%g64y>^$xN8b#-9W^O3=)tf08oFwXudk?YUqN-ut8{;~6f zWG$j7<{_g!oI`q0=1lrPOQc{uYx?cQ+$0tVT8qHEfWD1$WIhsb;FN4rBwh3_K#_sW zU6G^j>?4yd+zj!qgYd0qS3hWljZ#%_T8tdzHvmx(s$L8b;}-VNw;Gjfx^X8#uK0cg z%)bIw2Gw);wgwj>5A(?=I&3qNSFfyfl>a~&KX)TxU+BN`cB{nVxGuC3JDl}&b)G?B z=uToX#)%qpQwV&CPcLa;YsR%IxX!gmg_wc|Rdw?MGMVa3!Ssw^7b_H2Z^ zCH_r>#L#UrkANYJ$+VV1kl>YB0$hAC6VFv{-{puyh%7UX&64)2**+lvmSfN-T!=IT zIemi25lzv(o!G9@PzrzGFom1XZEqr;(}MLCbJZvJGvhWtMLZZymk~?XLKUYEi%}Bz zNArG;FM|SV?IXO0%ZEM#1D3qXtOHsAzN=->S|3V}4PIU=9PF&aBmopMxWy1R$xGA} z!idG(wh9#-zpvcu`&8*tM)BBmm$qH5Gma#cuSU{TP~x$4M+BP24puz9%%a2mz8j!zlKpm-{r2C+2BB?ZFSgAz#tsid|uRkWue)+2#<&(AqelQn*UY;fs zH%1$GO4!aZ0T;z%(_m&33p$5Qn?vLSpvj!a_OoKozEHGW zgjXP@D-Dz1K4@0urgjZ!XH;Xyekes=<;FY8aX;JE?5k;3A5V@_->2GiWsGBQ#?;M* z;UmJ!x>{9;mJjV=5@}HW(}O?8<_xLprqS(Svv|@l)p-Bo0r`CO0O|u8Mh>FXpM==D z4OMH0QXS2uZ?B&)7R?uOC5K4jCZ^TR9@O~T)WUfaI20RbSz*bxAI9H#Ja}_zF>Qbu zKq^kWd*=*wyX$aJKxW|kil>IHv;`m!@DCdFoZteZD%SoSSrG4*u%qft^r!$PS%T{!JC$kyi*?d41U2aXv=_XC&~1TXndG9e zKajDTYyx@_`f8vKQBhLCCHmojWNDewTnuZ|U@)p{2)&&Fq>!m28h-!RzJH0X@~$8% znPgGzW>c?AZqqa&rDhy!oiczpepH0BtKrW8&73tD<1_hZbZU!OcmT5Jw|#$%TsQ^u zz+t4#Jl6+oMemf7{>%5%OXcJzZKIFms0%THNd^NMG)K-|g>^OA*D5w6LQ$ktldqn# zsr_Xc0zBid>)~!_YRiBR7csSx-~{n~oCk#(hrTgR*Y2;Ivv$(|c3^L<`C@t%Wz~&r z7jrF!LLg9=u(=)1a~5Gh?#pn{O9XGk@PEO^^1N|%*S9TL91o+afv$7Uz2drL7l-Hy zLC+U0n|uMUKL1sPv?x%lvN&b9{}Z|uOMeP|D^&1aU;*dC(fLVN#0R43u_!!0Q}SUl z{A;aftr&;lsJ4YlLjXV_>ju>A?9aG87@e#WMV*(UMdxbJW_L0@9-QMcL`+|>ydLo3 zcL4L=NKW^^M+o+QJ$KZR%*r6&$uMjI6(bEORe35kY2@;Y1{|uujCP={VwZl$VZECADH2N8B3#*bV6-lRi0R@ z_NIx2=ai?!ElfjWk%wAUmOi{5eWc}ynGtXekwCZ!-3Rc22L*s3f08vKwt^=!*dlUh z3SX3~7;LZA#v|6K`XG#-qdDMYWz;namW~~ulx;L893Gq-J~HhV0$I&Q>}il#{k+uJ z!U;}h@g1O+NMkQw#?}Kb&ZwfJ0@=(m8cv%79D^vHHQbPzD5ALoim+jb4q>n}W)t@b zi_%P7y#6@9xcp_luvKhLT_Al%{lCBj+Gf-Rh81Q!q2Gb82s(*5{=AO|0e9iuq8FDq zR{?p-Wj3&&_^zap_-(78-)|FEoT`TMzWSQ?&l~Su(zmf3@@F}(y&$ge>n)hZWgN^_{9}Uc~e9HF0g|dWuCTm1q5lFTvHiz~e zwh$3r$#a_zT^glKzA!aN;LvV2OQRB(9tI28E}={>m1||O*m@)?O#6)Om&%+r?70+Y zGO-cV-L`&&+N*o8x9Q2)fNCX!?XVD-LEblnG%0NvXGjkqfBaNh+iUU1`a>NMhl7C> zUaYh?)NHeAKTSVIAWf(6=2{nO@P1Wh$lw#_kRSBGQG@->``(}(Zh{02j59R!8PG>$ zEyMUwhR2beA5zD`Lv*zjc1S%2aNZRJMFi%qHJb;?C?+mqWj!pl;>K+~?wRl}`KNeE zdzW&gWbcH<(V&YP^z1jG#>0zsC6qe&4)>A#jWdCOduv@-r$~wDDH2MsF}~5RLl5%Q zl3|y18GW4%&=)>}$3zO@+CkJ`DvbB;x8v@%7`C=jTC!IeF~mp$8vBG}tT&X_LBfGj z)!RN)cK0yPFIcyk8!uKR>w7CFgt+V-7k%;myDH){h#UVa1^AwwYyWK^rQ^Ye^j^nJ zce6DPJs{mg1-JQoXA&!=h?oi9cS(>ak{8l!&HtKhMbt;D*&9coMP6!+{2>(C=YG++7A~pu!D0} zC-*LUb)A^fD&R$u3IfDVc=3)9TG$V*0mcHP^_B%4t!E{gOJwK1d;=T2f%x4{IQTto zX5uH+|M|L}8aIE+GaJ*ezA)mX6V-~4=WcGCpPZ;mW~DGSAB z8ngF+8mUMN;g#|BdWm2+6%=q%i%24E1@8*SN#+G=bY^^C|7qYM88E`r6n!Cpk_~eK z5NEu=-jfr<>mj@Vau8M3%1|7#$bKqwYVg*tnHMwvRF9k?9_kR@m6zMBhewM( zcfpNPR2if#(_1C!udT8=QzTz^hyyzQJ*~o0N(B_y1>9(p_6cCb)9lkPdWTs*rQBMp z4U0T>)c-KMF(~8Owc)*k{`}z8{cLpK zIvp@|epEWlv*R}BT=;%)i1Y!)-x(%^no_{L()*eYfy2X+te;^V7VV4HNL__F%`*~d zNPkEHNwNBBXdQKB?9wX7Mv95 zj+LB^E##jZod`q$JJLv4veeV*^`v&;Bm^IIpGOvRKMg*ja^$m1azG^izI~$)FXe6T zfBJ`}0f!f}AN|*LyqufNM;3y2+5BQ&(w6RM_$I;c^jW6d&tM18+$4vlqE*4v5SQFX z0;np_8|?gDw4jS1)sECo^Mb<5W;-}TF?3~7wV?5Vr^Y9tVujq)2b2Z!0W6fY2;SX1 z_xgW{tT+5TMcqgWU=c9g@&TY8jby27FJb>hbonLB4uhbw`O_*VDo{|Uu0)=*@>U~^c$1x5&q$2 zy<(MBM^Tw)2)zy{mJn@_M?^X$XuDyr{tM@M0Lw797@PT9>2GS`PPta)(pvRlB<^K9 zAX?A5MKC24h|{wW-uup(mokCR>`aRn^jLpC`TgWEH~#T@BlQ=6@<>16y=+pbS-qoux)B3d+PGg-r{c!124=a z7!&&UU?}Nh+r6D_BTA7~{%?dB8KWnePKlK@3g6Z-(3C`RdM#F$7u^j%zLhHPkFccx zyGHS67bsKa(rfMYe11$NDV;Jw{>=xAFd_9gb~o=`tf8vnj{5a8_Lshb5tA+JoGfdy z(Uf5bQ=ag9sqHlYM^_oIgToPNP7K97EA*5;Df^Tc=-m>1B0?LGQwP^Ek98^}Y6SfKGC=LF`FZS$L{ zEF6|i7eFwU-!z=)YJtNpR#XDsc}N6U3Q7_CZIcyTBwoHZg$tv8g1J{BaZY%^jjP38 z)+zB`h(AyKwkP78bz}X_ z?3MW8X1~kj&4=Lcv+8J8ipfJC;TpNu+E#V@nb3WS_$$*7Bljob9$8g%>N0QC&Ha`ViEZgc}yeaIGB6W626@~ zq%(;d$9{U8z5ApTPWeDbZ~5KwTyzuC67RP0b2$sPwq18X76Azct{0F@Gx&KFrO6_x zfmNR-r%K{^EG;Lry1I&Cxyu)2ar$pS@<*lLmVeS%SuzT35R&lRFsOhy&_#%hei(f1 zQr7H5)w>?v64~d2AK4Uun6lSN&uMokK9r-eQC40<;LC3rkgca-Rjx)6a?vga9GXYL zf&YbS7X7Isqud^E2CSNh3~Ms_zfEv%cAugQCMma*pL{;RImocL!xFHtK4 z_@w6VV$yf}wTStM5vt(|MLFQPS23!a(5aYiD~35dr2KAjc91S@OJYkI9a+4p{>M8N zSY)`s>uRlCmTDt$>t*|WV{VgL%eN~~xprBXD=*f8<~UR8><5Q%ltCQRK-+TzmRW!^ zIg1X}pV{RtdbU_1xHdiARe(64$VsfcIvyo!v?P=lc^sY1m{$MCz|_l%UYx7sxPgna zn&r8AesGOwOMfsN5(+>l+Hb86tnzE)@!D<|_gr`L>TuInfouk)u|-m*M@Y)=y*@H$3=JfRL;kjNb5dJY0N)9_|Kb?0tG2WUzhJt zl{Hi3**k~-*x$LR-R|1dT5DU_MU>;OI>k}%5=_*`{;PVm;H~|QPMIo|C?mzr`;4_WRnPi=m%ks}z0QQp6}E zGrKfEd#(zyQ=GvGFomVuMBh$Hfklv2>A4n)1yL?ir~2xBiJEzGE=>NlAZ}6?n5MxtK>H4q>Au?LP|qn z#lg?5#T%ih0My&kEBYe7#sp@*g)Y3|J z^v9XUYJqrFx_{xH1KVI|R|s#;t(NBh9Te2>AffXOO0kYB3{y#Q0Z_CI)*wShraUHr)vaKKvCG z6qiaZHaIzr8q-E48;bu>$obNwnzn4^RsrDJu;S;PbjI689Dyajfx<+>&7I$C`Bc}205CU@Osb_#3LuEZ`WOfB2gnAW~#HsG_Gug%iLu|JP{eRSbDj+!E!JD+%h zIUqPHB+NOa(LL~XjOFEURAKlrWw|40S)d%a$DM<{Hu_&rYCUaQRcRl7k5cuQQs|5B zcz-=lhlWP>dzGUnCzJ5n%& z7vnmb3v|BVZvS2>6ynH|^O;VEN-(9c6Mo2EF{jyv?{0LD@B7VW{VoFH83}`}9Uqv0Y-z`1J zVMai^l1O{|p-S3i^tYOby!@dir37%5*e%_XAixFn*K%Z(XBHH&TAO-bbGdM`?{Ji_ zMp?UNUO|mmVe~UL9ReeYvcOEe3{X|tGRm+%S3zorcDTyeb4o^Oh2Fzbg3%M1;|f(1 z*NAqt`x=8&FZh{J%Abray>2>dP2fEbf|S|FHXoVS8cuJ7mNzsc8n^!zKX{7*N@Fe? zQ1|g4R+p#7xP;jRKkc`eu2XKp2Ez?EFkS>JY;{`aCf=Sx^kKBaw>dE z*2y? zJ_0VB+dGscr!g$MR}0Ru?Y#$xU6hG#TPT-q2ov>^@|}IwQ#)xz~08Z6b5K|NSowIl5&|6$ZXezP=YPs`JR^tzFWHU7ISSO3k_RetZikns-~zBs== zcyDLLCnJgh#d#5=NMh)^8iJ?SM1SvovW(^-_8=wQ_%aj1Oubxh_BIxck6^#ue*&^6GNSK-!Uf%D|9dnG_hN(Ru-t|DhfI3-HW&Bi2%J_RtM0m zSK*Kxy43F&!oo9YmiFXZRm<4z*@0z!Tg{y{RtkHz!EK4;>U3W!mY9O$@PC%p-X#llP!NAP08{jQvBZ*{a#uMWh#6lGN>LdKAujxrD- zi~PVm?Ep$k@@pGCVt|!S`iTZ;rWk|+h_W-Q2uYG`Y|vuVr3zAY_(9*M)dPcnt4ug0 zc=mVCk$$ur{nOY*4k@NkF1n>hQWvh4ZT?PHPKSGN46Lv5s%nI`NFgksQgQ5z=5gt% zwb}u21@Hrl!KGW4LUvkRx=K%XgRA7%;DFQS`+tDe@jp7x9Vz6$}vS$X1npoq@> z&odAEwaj?S0yaMTrOoa5sBvY;N_P2FZN|$@iFhjX*tL=VUjkj3r?_R)`@G3(>bUp- zy5v|eqFP5F!!mjSW*!SxpkxQ;x%WvS->7nx@e9t!5AA!SD{0VzToj20xDasIZ)wYv z^xJ!J`5t|C9K}1N`iS)JIfN#u129ny=Wz6a5%=B5swvNULURPW9}V7-5oyAqWTG^v%rx-;uuyTf+Wsh5~4G8A9)Q?eS#G7c7R+1 znIU1iK&A9zwT<(bWBze61iJ2uC^A@H|7Ro0+BrrR@ybZ1?b$vg^tkzmYFWg*Gf?w@ z|Ae7*W!qEgcImR9)C_n%C&$|f#CW9eJxc&Cq-F1kye(bTwrtGP7vg$Vv zd;+d{8W2bt*9Q~|W+KuZkp0{ujS%H1NJZLv9}IlNYb;#2(9Pm|w`F^sm?&H;uozqw zC;3*Y>!FOmA_gtC2{X_r;+)ef%o>rHFKA1aJ+C!u);Qqhy@zbAoAqjuKBJc6P6_oN zk#M)R!%@vaQ&=uT#WQ3KrmM(+l#D73v9`}>-9m|$)=6Z}`Re=iR{k14_ry&3wgVmV z#*Q~-VtCN8pw(2Cr3Lh#-PNh&14HWeGvHi)Py}(AGln=4VnRNUuAubY`N|;|H$u=j zw8sdu=vX?4-MD(iOlJw%qZS}s?NEM+_wfe9C%f*B)`N22i`(UJ|D^I;Q>A1aXD^fs z7dIRaOiy-vs%@0vj!lQuI@0g*1mOw@daF~0g@*F5EUzz=b7qF#W<~NUyPO}&?mc}W zIiT!xqY+i2L&|Ok_$dj=+?pb}YGH*e)-uPs(9&`TX5) zxSTwI3X+SW+(Q+Ot0TT%4N3`Kp;kZWr-`v476{p|7N6G@_yCIQ^f;_}Jk!NWsPUn5 zo3m2y?n1}@ajz~(s@@;De&|~OJOCdAfC+tkBI44~AwMG(qwnEz{fDS7bAf39vwe(G$Xn=fShQ=RVqV(ct&C;AwoK5eMkFC2E zAOGwa+tmwzS+@_{nTTQniGDI@R!_U1Tr8(EIDj3M#OTcC!zMc21owL;T^QFH-!l=2 z0q(y0Zb?P|oXNR^ItDKol9i_;=%XzyEpZP4;C%YipLQN8@pixxiW^-}Y_##NneE^5 zz$e=^8go7aK1OcfM-hlQg|DwPd|WMpRHVH(0uTX^Fz8{y3Q_=A04-)H@LlyQ4CLG+ zEIq~|hWiP#(6EWclU!M{f_`4KI|c&WZkj8iGPj^Z$_5WeiHu5nlYpM{`x*s_QZ zLfPW?EoxE1MXaS>2`-iMr2ud;m?C(7(I7S-5zKES#sVR>$0w+)1YRk60v zfS~!B%SW4nW8EWJD&Kid5E77>6e|%xiQGF_hX4xX8ZtJ)WY^AgTWlN?F2?x1$D2vD zYXIzdhO}p_Z1axgD1x#YH&M!rRR_x;OWHiHZJ)h%u_M~RY6Z_foqKR`Q({cu0_o84QgCHtG;dW@3UqRNxGG1@!f1xP`ScXl7yUQTClK;O*d z1l9o9M5miD(MM8s^Ww;)d^g^Bqri|0t@W3`{N+qek@I7+4SXm7miuph^P55l1#!^y z>*#p^L*kzxsyUq{4}1cCdbt8VPdxF2izV`#ta7TwX2uUi4+|E9eUO3$21^VI^tIPs z>+4c7MIMRbu70xxNYhu|D+&O6zsm$%M=f%|r zq6A1106P{_gY^X$C*m4#FS=aau`(5uWnz+;Z3oieLWipoN@OBI`9@JSumnKD{R-<7 zpq#QBRkI)BhD6s%^*d~4PrljV7|^)qhGThS2*^L8)`4~NYUJHYz<`TZJi)c<2hX-T zcCtb(?-I2n&{nWWzpPZsP5S&7Xr7^~=Z24iCHgPFg7uVV9uFWT0|T5N_pb+DKjIRS zqVNM^VBG6bf(hbzu=1TfyHdCJE0fz~z8_fhaD{^$0I+w_LIv~cW=Z?OJ&`*4%vFmV zfc0AjKl@Q9fIU8d0hD`FwoLg?bROFGoocmvO#vI=%~5CT&bW5Iu7CzB5+D{Zj!S1r zVS#*9V~E)QSFh`&fLeMWM1W8O!EusfcsEG&`n#9Rlk=3u+ppO3r5vn#!H@wRTXIhJ zVS>XzJ{BLZtFCunZ(Vr7kazu514h#s9AK5@*)i!yEbw#_Vp^H}MM3wr$#ly3fe(B@ z2pjm~7r!XP&E#cz)<7Qk1pHhX2vCZGw)pr>R++8h!m`Fp0KT+XP=XXl6!70=ki71? z>yloIdPX6kgSSB)T1FI;SVpOMCo)SGGnpI{lo0a;ILjtbrMv(h>Hs08>EP~dQg-+y zDe7&N$oQx{8(Aq`<3-XoS}JAX31u9MNdH8kl!T))r({T$7afuLQ4R90T_Ta11rljm zeZnliDX}Qb-bAE4A6%TU^kk~gJientEfPb{>VqG`(ugI!9wmR?n$% zE@B){-^DXVnJ}vnOWG|K9&2aut`++m^%Ltp=lwpa?sngLY>%?wjkrX(M>Tc_>lz6{ zvC1u1Vu`g{E);&3UiHw?tITsmlDm_q|V;l>E|{z9fJ7mw%aR_x$$Lvq?BAW(+bmZ_lB zq8y^&0eCn+$tLHhWd=omMN@@ZY=&G=IM-0)fO8ijARGXMa^KoHNdpWy0khz^tYsoF zzWsj>?Q~=ZP#$w1F5rG_RBFQ`vaoVOE>yR$IkOsEJ0rd$NFjgAT^gsfMRUFYSe(0; zE{XR5AOeOycF|mCAxU%}zj&oh?$f+A#5rO8qK#ltbFof({H^b7NoXEEmf7y-S5daJGG6B zIA%VGBiN7jg5`wgMC{h@U)FLQAo{tFWc#E;U=VvA?u$BqPJ#4)=`)0;x=#rWv`IMu zya0l*Kz`vpN&@0(v-fCH)1Pauqit$=#I27%3_d^u+ChZ^L%z*c(=G8qU;d5kyB;&i zMJ$s|;FWIw#iba{%^|x>nbx z`;vs+j7dx;X3A`feu3raYhU}CeD<@SJ>9D$fBy+;AP;;JR7|#hrXx3t59bUD_{35d zXY2kGod+LK7;s?gBCaS%fl&niU4)Lw20ptcvpfvS=6=C;EDwCrt#91JP;i2F;iHp= zfri;Bu9c~vY@l>{l@88DxlsxV1`bR3umYbpb$ctFBO3=ASy)vi!xk1Q~HY=rM+VL@!5XAN-V%9*4@csLRh8(Mksi=Gcmi5`&+5H`#@a` zh#|fO%gZ69G=}g1g&)h%3O0^{w7GwhOBn(Li`9)JM>{mJAB zwHp1?(|aA5BL@x&G-P(1gBYPdP~a2KVniGBzGJwxF{zMB!QeQrwJ6ql#CET2Xb;IN zO2DvxFr(shaUM4$xqVmL^0oi_ZSlfyS2~epM zXvj$_3K0DGJLXUM+0gFOAu#ZkhjqpPNGXW#8C1a2rPi!Ny$b5}kG2h20lBZr6}Wv$ zsk5=%c;#m=9ds;kShDnF%EULx_{KXis$T%D`m-Ka?p!ec^4-h4hfir8phMX$-x=>O z6J37YSiSuc^$`2v=J?I8#O~`I3s|=g=d*3;fTQVb6(PO{S3cZvgC4W}KF@6KhZhC? z3GFkT$xiP*z#2=OFZpo(_>ceCyD7gujcOndd;)%$bkw;3K3?i#6#k$E%L;*@_|gVF zdxTpJzz*>O9|l$K0e35NyJ0p9Fp-KvH&OlM%7t&L7COpKnfaJ9L75!bIR<)M83&I_ z!NHd$bVTD&l*#R>p%yvNuQb3T8Zcg|ikD6nw`pij-)Kly)<@pE-+FAfkoc7I&8bpr!pNWu zs1~kF(&}PVDC-wB$cHbS=h(JoN{yQ70YHg z%4`_U63J~E;{)~hX0;kY84XJqbwvWubCk}SSelzId^;l&uBNy+@thIB4xlHN5i!v< zll@Mc@dBg&*my*?9v+ededDrFi53*myTcD@9#p{1T*U;}&5cNnk}+zv$s=tc*Ot4q zJr761uKpU8Fwr;?o@>TIT?l zVr|EOG?J}ewxm9;b&A-oe^#*irsjzvX)30kVSV1k%pBLtzF<;2YKGKF9d~`x<&!^*0pzb-#fE!>zM!}14Q8>%|Eku zP!9AeBik798&xj00e}P$Lfuh4(piC^Lq_pM$%FxneV6Ji`X$PGJnBXw_dj3ctTRY=eGS|=6Y6h!{EY(zNWYD@(GbF z6$?xv!9|T@Ue{!)FYWDd0FQ*LxZ*(!uv*>zV7`kbY@jdt-;b!fi;_EF6 zTS#6#(Ca9n7im5H;S~$rrD84&c6gtAqWjF`_kVw3zr3u;Rbh97)vsL3 zH9j`3iDA`!O&jW*s<2$YtV9YXMqKPs-_WRRR14980cvkjuoSJC5tZ5H_RAzdFksEn zyG|RU|L`inyjwQ=Prb2?Ht)^(_14*wuYL2;T@GmO(q}gJn9C;Z5*I}X7%1nTU%MpX zNw9kU`5jxGm6Kzz8fg=7)*qgCsZIc_(YT=bdaggcda)xrNO&?I8z`?O@}wRpJI@`r z=AfQ?vfJ|ZbF6cJ2utsJvU7O1*)ja)Ef4E^)D;YH0Pr!Zh__vM&vUx1TM~8p?I6dt zlT|M;rP60H5u0hA#EUMv$mtc|{qA?=lb`(L$tp_zx&hZf9{2=Y!E~~@06vy@GwA#? zR$aJ1Fi6me2F(z|%pOlZvL5C()8Y zpN^f6chEPtwnPJT=;$^HckWcH&lVXgtdvcWMbbMOR_g@`ER}^#4Fo8aXI1pdtf8F} zQ7Y?b^;{XBf2p({Xmb>(rhNEKL>jLQ03!oIEMwOxS0aIW`<2c~1-D486!Ue;pXXhu zmX{r!6EZjv(i!vub$2S!M4XeXR=9?t(8H3oa7Klj4Nr9b*x!l4_`&1bz-h&@-l?^u*>-`FMu@sp?(5QNocma>u6D`>-I zjl4C91ZDV#3KDj!OW-bLF~jNu3m5_MxcptHu`m}afQprWd}5C~1}oNTWq+HDi;5^~ zUa!p4q@a`TVGG>E0`J0(qeCw5&sag3G|y5?&+J+`Ujy!wS(Re1na=l@TD#?5jX}aH zg|!b$29_<9{pA|pMGVWw-?8BMDQPoUjE?pUNL!ZzU?uRV48P@GXI84?2P9ZQ=>_}% zf@oJ*neA9u3Q-iH!p}th;;z>n)0_k0$0*u4546C^vml_A970(A zpk&8Vh$|<+>2d|Szp-Xk(l+Dg-kF?WLWx)|1dA>JAk(t@x#m>&vA&5uaVo%w;~Cem za6$lp=Rhnl;$Hd9K73Eq@3QSw5-9fpv`kh8O-OVy%1v%Oo<9?@Jikl?T?Vg)AN=44 za?35ZWO9o9F{eQdk4S;N;ie-0nTu5|&6wH$LXpOqdgrzd1u3VvZM|mABsdh9xwC7M*Tph(@VB2rsgEX^87e)C21 z9RpXgawXdK-0m*H1&Wv?+@7j5_snFTps2=aRLfem+9adxhTZLl&jWl0wH;`Tj)EkB z9<2igH1Zw&?mOn6KL_kDyW$q>UP$SEnOkm+plqA z<=RdPN}Q5SJPOvR>(8C-^2;PDU#7nkoAm>YV}hlQSSI4R0B6K;k@x0z)C~_SiC>}L z1sHkV>8wq$1l-s=mFk=ZjAE@t_C3*i_&@L4?qbsbo4BJ}gR<2Yrd4A4)GWVek zAUtR9I^XTt(+&UzmXC_bG#E?ci5+9x=!X&S(z~9hUD)xtT3W0YUJ;C&(@mhEMgT8~ z^7N%DGa#P{-5>qvM=obgs{QlZPtO|21D_l`H#*gzfsf^%X=w?ThS{nM7Z`#iQG_qJ zK=Zu>DDCa-F5u8E!9WaPU|_NV#-}6{Dyp@Wz=L>hgAv@G{3UEN24m1C-nsE-6 z7cZ)FRwEK%dIi@&;!Qf#+;>Qi#j-_k{47k(DHnzlThc6KKiID5)-kRPKHu1SjB$&)1L~-O!G25YakDNa`0Sp0eo^r!)(=s zIhYT=&=+2Kq5YiIB~}i=6~6X1m|&)7wu;%;AS73@OBR!biyog?K_R33d?>q>pMlbs zl_&Oud>`(X@R6+wden?DuBMX_T>@{^lA+qY^bHQ{Y_ie=N7YS0uajva(s-B7#&1|# zp4r*uXs-K4)YV4;02T`Z#OJ8%8*X2Rdj@5{f{7vBUZ^>W>Q$L93u_Lbsxc|myhVP6 zdakanmXeBUwfcmlT>(`{UFl|46O%Ei_?yz=_nhAS2v*;z!RpN7ds)<=@&<^Y;D1Wv zhhpP&I0u9a|ME<$v)bSy*LWr{YNs=#ihGPX^n zzLVWkG6DnMJNoZfi;-E4_}wNY5?uoTeQ#@6`o_c3I~Epl76G6ev`m!i4=-OJv+Al& zie&|WkCmIrC4_gLz;~9@U3j)ej>9_rDlU!j7{PeP>=XN;j_fzT^~L^P@wRK$?Ynn9 z8^DN3J(y1cv{>?{lQ2#aB?Wj>Kyh4l*v#CKzu40#x#bhza##(t81R4D7Go|tm zbvm+xkh;K0RFj^nyW1{xpV`x;u5_VE*E!tpu=HeOz@5^)#vF`$7CC-k$QlFq=kM0?iP5XM)s?@J;cQwadsrGgb zYJ7<@C#fqQaY#^%rxE}RId_O7!omdk1c^D%(@#8Lm+E}k+Rl6CB{1N*5p$OgfdNV^ zmI7~kiUmnrr(dm)FDO;_J_XSxbJP+^9;j+1%|Nh3T3d>@WP3IRz=x&7`dG*dD8HZf zo6Y+;8Rx>S7Qn|igPj9lOYD|C zXCJq5+U&yfgw+jUA~sXtjTo0|u|(OA?nr2|h;tvUM{tI)x2ouO9+ zyF!D2aN#0;C7u9w0J_%JnDM2pq5RVhy~-@>6S#WCKh@h#AM5fI3zB%21hxZSASUQg zz+wVv0Esu>p$v3hOOS16`CqRdl8wrI_KeaT*OaN-lrpqo{Tf!PV_e<{mWPr$8Lcsj z6}eendwrYi>(zjHr8A$^*dUjzUhII^BioN^3{sDRl^(}h*Q{U)+G~=79=G^htQMan z)Y;rC)+MZ4B%_68Z$#@5kOokNT;Yaw!7;>f{Y1j^guDSI2f?}r;LCQqr=GolyF-B{ zEP-KVr7M`21Wdg1euVaEfGD<2@ty4`!?-iAQC8?&sGnOQ6E0Lh@mU>wAN z98c*d-soge)@D?R86JePhsy^bmjM&Og%bAU4;@cG*l{RX-H@dffV7{-JP;wPq%ark13%;fn)e0At?j^D>ZK9i|<{gAV}FC z;t06scASM=4m5a8> zeR$iEcb&Fn_nGosp#piSvq)aoWW-UWU8g)1B}H=WiW%~r)y=ML)7}{?U@k+jbP&)D z*gq45XOAZV?<)0ks>Cu`-$8ruuJfG_VoN{IDRy7R65e^9JAFLu-9Qn`lhOA5l*8{n z=vYR81SNH*?HQee{*id0E3UZ0@8$FRon|$V2R=D?V7UN37L*?}8<|xXzR_Hhf%6^j zc!&L*(URa&&c#d%f>OwUWO-s3tRH^(VYltlOE1mXjO|X4;-AGX1x?yuWE4gmU|`P% zEWi$fQMLyp&d*FgZi=Q*(b=Q)Q}5GVOzF3n2Hb~eYXF~E0rWhqENH~x993(@BoRQN zx@r|kgSyUbSsrEKVdc#j^8qYmdu?1bs5rB;ryWtDAzJ z8G5~BLYcqvzz*4?;0bFF=Y)s>3m3VB94pzp8u{q@dC5+bwQckxfL)Ydgg8O0Jj5xU z%EEmcxQ@4EJG${h2Sc(`^KUyEAz8D2Ku`Wk=V910(Y_hYvsnKmscqpyzz0N+y2}qzNQV1^6scP;~zM zT4!0Zb0=C7b42bL=$A>7x>&752+!hWjUSp@SL&=imM}HZd9v|)Y&;8X9`~+n$IWEp zUei4X{o}T_Zu$Bndz1!z*ttFecz9<0qfx0*;8R~3m7A7Cq%^(}&|Q)~2ZhlKvc2B{ zilzjodygk`e=KOwbX&4(CVI$YGaa72w_fQ#c(-CdOm;BQ#daptu<)hwn&2E>@jiFf z?Ypz>91Q>fKmbWZK~#4=h%w8156RYf#v}zt&=E2rKVtIH^8diP8Wd?$vU23N<)#Mm zz$XXwoD1LsfFL#{7YRkFGG@+jnP9e%xSMo@PL<>7j8VuCOBfdq)X-r+_~3(XKjMip zrK)r%NbxUd(grS1d0^pVK%)KtStuAb^U9!mC4Vnar@NT*4aNSv&$yr>e&%FyQx%o z{m0~4YM zkdJzFk-4!F^V@aF3Dm`=wJyp zMDX9uG&z}{do^(AD{+}A3f`SfF!b$}PCa)?usMi=3fX{EPRkyW)b}4-Q zP6>7HRDjbik(tZ1qEB?63iTh+1hN`XUOh*mH49{X^@kOuymekXf4n7S=@}T3A3eWM zjwle@t-Lzz~-P>nsSb?JNh)i zZ&c=K+qhwEqug-msuL7Y`XiJ+146M&CJy`v_eR_D_ETP<#Jb;p%g^Vc+3HX(r~?~Zn1RINgK~yqVaf*k z`4Lkvyh;Y^eAs3KKeK&S-xg1lO>2^$dp#NZP@lMeGUJQT#&GLPW##eSE3@dWI%B@C zd+2z~ORtg%Y*!lUMG6F<(S|uKy!$Z;AKt79VqcbMZHq*!6bvPhPPNG;fk$AvWlr zpKf*WNRHJ_tw5E^wnsb?RUE_qS9U!}At0WBs(igtw0rCAd9AP8o@;d!>B=7=btO?5 z92(YVs$fLH>*B^L`RiX_<%@ni_MYgoc%Q6~ie1uwSsxR7Z0vWyPb?Vn_F>t0K8&|s z0tY6suyoKbo(aMv7h^MH3j%W}A8&ifq#kVS;#qsw`EJkOmVVA3yRY~DSho-7Vm(>g zpvFOVWE-@A$ZVCH|9H6u>3z)19{++gNA^TYf5iWz$aI+DOO!5Rk&-R zP+oP_Rrd1{cZ!!2^Agl0|SL!i)S=%-aJ>|28`G~9fdNZ^fGXn(oftQRz*Jm z+gm4Cc1S3??Qp+~bHQ4H@(CTY1?DenP#WP)|EkuWUB>{;dFs=V1Q;lVarofN5&o7rMMb zSc#Ge?+<{7{s}?ZJsk)P;+3hbXIQ@V*lzc1JG3rHAd4jjYZ-LsHz>h`2|1a*aQ7Q> zpli_Oa(@&Y3-DB|~2 z3N6+>JQ27i!ekHaKekP#x{uR!JMEs>Tb>DZMcX&`tz49e>+-B)KU~{>^Lrn$ZN@uh zv2GvE2k;?o7P&&%*fM$E=qWIpB3KFy1i2sb|E5(9D^`1Ib6q^6M3xtINRh@8Axto!_#{f^H==|Mk81heJfg8j+O`0BNBdM^ zRadmtjm1(F()Ko{%yFILO5+`oW~J~ZPDFL@q(YnWwkz*C;4_i(it_&L$M*;dKLE(m zF9Eusz9#1Azg>|yDeH72F!*}~JvoS0?RE@qYPj|x zkQ<<1*cisr)|2TS5H^{68!^bZ-{)m|)<7QkwNv(W4wI;qJT`=8e*gg+=D3?HVYc>c<*oApBD(3f?>a*RM09F_bX6X4zhKa=n7Q2?Z5_#W>n&UJ1)~;-6?c8(AC#=$LnAN8( zdD|81dwL^s|LdKy`C#9qrQ(=%2g>eYRpwXEsgmDV(=4lIzdbIB_l=1ki|61y02W&3)Tl9wk`yAc81VB-pMX{Gc+okxS{aCH3-=3+6fnk{D0=F32u+ z4-`qHx=E^(Bn9G%^OT(rM!r*3Xg4;YW0N@6rtG_oBYw(2|Al)SfZyBBXk%0D5Byv| z*Za`tqx4&DCME`nXF46rYR{QA!MgP+EWPXAI;QO~_7Ug9*yN4PwPV=d+ZWh6OZ(7= zoO|xM?$lU+&J@t>t;;iIJr8_x@TBROP(b-GDBDYy%}bk$7PGv$;Gf5evth#qr^H`( z-F3%{Lg$OA-Lhgc@Zi=4h3Hg-JU-Opx^?RU?U1IzR!2w82hii~sCnL*T6t2{88fK> zUVsn6brK~a<=#w@FvWtUeHcLe2-ol`tzPAVb++e9C{H%6JZaze#F!Lrylv9eO=+x& z-AQV}iHxhO+e=DtFjt~=i)8%Vo0DD=W;Bw2?uE=iXZyDu8gQrYRtr>@emYeV9vjho zK?-~-wc2NtE7kVAMro?AlJ~Ekv%$YkDb-`wlSWQR|$!Cj#oQF@=|+94i1H7ZdHNI(zqqsQomyPeZ7;eeAljQ zl*^Q^+k|UOCjtX2*RG=j^36wg%Ny#}SgBS<;<*s4kO0#KN?<_T)6M5MI@c~EFG1clnVCEg+cMGZn>`hf3dE^l{E69vYIsxkGUKge{ z6e%nw>Ckl33Gpi9@<(MS2qsSa?X<3Y(otOf3zKM-(`Tvmh^3>3NZ4PA1fDtH^{LuNwuAnO-%MNR`dP?SRt@5utMJu z@57Dqd#un0ee|OrmB$}{+->^hFMlcTe)qd$cgugDCN+=;J~?=hxd1*>u~cMI1th^F z$rl1!7XHOHxG?L8TU(;of=sUW=%bH1#RX#yF!B`Qwg1}S@W!;E9WA1pqQLsS=x$yE&l4j58KT$_TV`S*MOx!8|B*BC;%9_2shoO2xLNpyY2U@s7| zKFgMVCw1tXte^5OZJoX-==Q}p1DO%7SqRsr{PA+&C903p`FF~{M_v2TIS|UvglMXy ztX5{)kB!wVnLxYgrkjqFBVaMZibT80%k->)Jn+fEbIk?tF@>E@Af3EAnHHZwVoMli z=Rm2zx1RWlYTJ@%LzxaifG5VOu)2bV@-8SI*; zQX*2?c`O+6ez$v0_3RjM_|TT^W4~Ddvw^H^#qy-Or=;8Uxfg7|S3*6lli+83NTTHp znygf4YkN{?P9g&j4Rj)Ii{{!B`dggWrI_2iQOSL z3znBIP58NTR;6=0+tJn~yAE~9yz&WW1t}>jm;O+hT&OH*_Rj54vVsY{rxj}Pxk2fo zt4k+I5R#VRByGff?>kTIb+Ih_HFl*`UF)E5?p1}K_^K+s_oW)^Gq2wtKsb1GQUrg;LFtrg|5>yBL#1l_A zml!%Zl>MN@4^20nZ#*jx&z6BNmBk{Hdykih6e~xN)ZUrgXQE?JN@+JI|3p;<>OU<2Au>C$qY3iG5uCz%(;a{QP2I7P(md%uQB^$W+wZqEl)#viw%vZ(#$dPvG>h6)<{UK?t&;ahb zda19elC2s8)S|IBja4O%>|kqKzq8U{@ww^3xyKdfbjuXcX9n;hPtcf>DZpe004r6? zL$(Cc2$Gya9bTz4;gp~FrJZX1InXt%3}!_xK>v3yo+sh{BMAu%cqh%3E|CK3=bqyM zBiffKuYTGWxt;*DP)`G9{mMT)zT3s`z~a_WS)#`lIuO*RAgH{kP%4U|(o(8!ZZ#9K zxH_bhOv@ZieGub`-+RvGepq->R1JhMGfzxQF3L}T@9nRwjoH#~d}O@#Wo?TkpG4&$ zo`*>}i=REysJf|R%5TZfVO_)9B-8Ph+<-UVe6u4(fE4QX+iy?EP@Btkp1)S`HIN5B z!Pl_^JwXE>K*+|88&l@hnM!d{OaWK~(|bGmpmXbR&rd%2q!7r8AG2jwo=RB~9h-`# zn*or4*OYXY3{=b(W!eEJx)*-udRTZY5h>SVz$1Pt2&+=EdkJzI^@!qXii8&+G2olB zlj#e0%??$9`v!)kdZI^9rEX8^ z+SWNyA{Q>1r8LFm&N8w~!O2l&0V`5pI9$XaBv`32K4)nh2$b8I2$q<;UO6lWHJ$_- zZ>%o>6Wp!dzh;)qQHtbj2toYh?RjN?uT%61+DBlL+p3^%MRTRBn^P%s#@mk1@{?nW ze!#D53+GD&j7*uO-T4vPjn=zQOC-#5;^@Uyx}H(ydqeY1)wW zU$IO2Hb25M2V7f!Wo?b~;o3$!rjNtQ7o^L#pL@;aK8ykAH`D_Hi2;+XnfB%X_>cc6 zpZ)A-U41f^-gD1A&OJYuWy)Xc(o_gvjH#0+rPcqJ+#Oe_sbImo^9KQ?$4$3!6#DGtbRvzk_I!8G}Eb;4^ zqVP~|7~8zDJUn}p0WUCO-LGQ7^D<>3R=MDNRxFkZdO{sLoO_!n7?Q$biB`^X2}>V) zv)kon*?weDlaN*&x1O{rYg@OH7_8AmlUJ|McpYU@yZhBP*|_6?(pUE=VS!>N4R{Hc zRLZRSN?E4###bwG0TvSynqpxf7KC`7`pP1isc|6hIlIXL71wyu{CA&Po3JDS$Z)qp zaLFTY4AzKS)B=+Y%MVKacb?cIdpZZ@u)27`UIuVGpl)vy3gQ;mhGl-JQ|4Dp_BG7# zqo`zilEDj%XiuiN+PW!RiK?*FG8Rxb@-Qh`vGp4d~63B^F%_!1LYj ze%BQR7Pnvg;unI;WM0mk8ps2m96ak>03V~5relcBt231%(%D!br78QknlamAF+Nvb zd8HfBr*fTC$3Fe^(~i0l_b#p-l*HyIV!)yf_)vbU1C)}WtUL_%1n|yDd zZi8C9=SUq>cIZW^cO+FTlUK1YP-F@Q-@O*fc-OSwc&1*3!oZRJHWh`Fn2m=u2`N^b zH`@oDHGn{M%DYX$3j$l$d(Li@qKRR7`lZeC^gdA)1R3eqtwNhVI>VOAsY*#Ix z9ISDTdgD;P0;e$-BZHOU?Ag@{l#-J~Seav&0G)q%rq#K)kxvFTHvkp+g2<<{c5by? zsqT1d=heg>n$dR>v%b{YtsrhlxSm#rvev09V|YZ0Ck8cXYE&x9N}QGFWVv=)`|`Fa zTW9&q{t?;Q6_R}eicnR`3#0nn)MBISb1R~RQ<1002RW)gyx|7N1xv4}gbl_R02r;Iim-B_xK0GN-OO{zsdy`AyZi6DX{UBicxiA+OVfv!OnoArDoadKuUo$ ztIODk5*Z9Bpjg^iE_2kn2dx=g9gAT3xur+PAhY5)(1 zgrRqDR@d2mJu*`R>gOHHA>-W7lxYk%tn(Mt$*-+y%*xfVcKmY75eMGJHI`^lpGR+3 zhbsQ#vR>({m(H6^ew-C+TvqP*#FKpO!5y+)Eo28Y|IyMJ${ZJsC_CM_yxBP_RT`T! zvm_!nsGFL09|`4uILNc0 zZ0^HzXB@Q2KNt%kHp2$6<@X5i` z%mwiA(o0X3e;$R9PRGa#Q1UI1ly!uT_AzBzL&$f7={-n!_St8hk3Xz&xVr=;-uy%W zItCLPP$)Ztg4IDb?}7Scpa*OsSQZi`BF*M?PnC0-vXhRLC!6=qJL&~Owr)$aJf*s( zDHR5eiWRs$dtlTlvPTEU)s1OFI@GEWRt=bVoLY_RAppKfi3v)>5owxem*TNLcNu0j ziDkjXkr)sZ;WACw6SU&HSKY1d+;m7bE8#%7YTk?0y$!({184(uU7##->E;M>CrR?J zO+mxcukDom2M zr+Qr_t5DuE#vWKo5yq9$<|Xp_(J{wzM_asTVXeADo*pz^1AARvw~cMvw$s?QZ8b?_ z_$&=iLaS z+WlI?Hy(^zIf!kkTRBv(-tw!RrNBrPbg3%)`&*=RpXmkaUzS&aVTN=U(81_ni1@QU zPjBLiUEzO3L}MTkvHN~O+m{XZ{R9WLFpPK`L%`R%;oC46zJ8cAU8KJIszsn4#W*fR z`_LcIwz~Xb2ElCN9TBMr)4&nRa9k_3=bi}Z34X+Wvwj|Qh!JKOdZpI0SgQj_$&ET% zbf{=FTFkINa#m5D!WUZD<){y9RT{i|4d1mprNm-uYD%lM1I1G?=)v_zu1zY`LW!+` zT&g6*45UXjT0WBVH>I{t&m;jnAN9IR&*9B}4rr7?!mH(Fj*6-+3X;spmcQC(sH03p zv{bQ(MxQHwV~;|AQn!6<>Y_HusBG-*GK2*X5qTQ)+Tlz~-iqkapY-nA;?w`mzf+u{ z(%Oj)yJ$#jIE^RZMO*uyOLg~;!-xO)P=}IicQ-jC$;GH}_?~D)NSE?U)*199>;&{l zVQoLpplRi>;#Q5iY)bH+9R+7cH+Jr;Y*Oi-uYrryTyBS`PaX;YvV43u~)Y zp}(U6gMJp59q)|3l&azDp#1Dp-q%asEzm-2AyCvcqwBI$jtN-!)Fq}J@{ayD?)SUW zOqw|uIc8%FH6Vh{&1ke^h>YCD90 zVhnMv)(Sa-d5AS~UXo@Q>EjJ9;(Fac+&WTK)=tg)NS?!A8`7aDp7}S|xg%yEeYh(? z5Z|?c1~Cy!ApCZO4ioC9wqTpXTnFEURvb_$qQdP{H{vcF9#V{0qLLO@(rbP@^Ic5a zTlu{Q4)TIAP4=A1&Bf=3R2YE@-Qf_RDE2!DR;QP2m4H#kiJ+^!%aZJY1g;?(Kp*n~l%mK@J z0%?MxL;1l`#Ygk|%>SuCLx*%l`ppvjTY$5gU(>S^r;tKtn>6ugdTu%3hVSV_3PiA( z)>f-wO5845Mv6f|Kg@k{82VL;O4RG~(cw$;^R@14jWBiu=BSmVM}nE7CoRn*!Fxa(_$yQ*o#z)ycE@7Cj)3v zmzL048q|+vTXH-=@eYsOJtkPFU@%9l8|4|XfgMN!rWQE{<3{FqPN*`MHvS?R%bYge zSU&ekL9a3ruwf@6I;%!sz$ZB(QVN*Qz%j9%$ayRCf2UCV15ja3*7#WMN zxB5+|{ti4Pk-ru;ji>dYy;=a8NLv5r%a?oLwroKC&*UCLvcLPlHsC+zeRD9dKV;xk z79{sODZwp2{SG4F`W*%|goenknj1kIS@1cZ4{6b9E@$#5BK}4+%@Pp<*ec4T@Tv~k zZ&*_&ej3pCp9{ut;(yUBhTUC(y;MTO-oyVmm_PyKZc#;%-!BrG} z7nSFW4{ICQq<&%a(Vu#GsX>5Q+3)3Y4l>&YTifxyO^_03)`D78y0s`3(?3SPEwYI+ zBZ(2pXjjQb5uE5ODEon(>!p6h8XjCyP7X_Y^=V2NzCwk+7L;Lh&IiC@NVWOno%dNg_; zY8(`%8Yndcj@qbefrzz?KDW;LV7^#ce^^?kQfnw~5_PWUU=9~%562Se^jRus#z15` z8t;Z@Q{v5K%D`(NG?8Q0Qk@ZV`cW{(#w?8Du==kaMF|jIessZPa1)tT72yRh!R#qs z_w#!%tj8>)(4YZ9%?#kK;dEnB{fuhdtb%wghn5$?a&dlgzebFv)W4xZA-4PtT{9Q; z*VN#f76uu!oH|g(LQmZ5tDxFSwzd-AT5%($N8x&H5%EY6?*#exp4x2Rj13D`PHENm zv{IX4A2NcGu-VQbtIITpavs=L9-0&;N zlo+gbG9u#4L+>n^e~>$6`Bo#cs9g6E`7WwdCLzNvb3s@R1j7wu|4y6enz2b%((mkd zXvtH3W8DJrjVO~)K8iSo^#;2!*95bRX6+x9VbDjR(ZRp=acD+eLznpl8pE>H@|^&M zsqkMuok36I>~i0y+sm|-pi8&Hi-5mh->K1mdw;8Gcw&xgk@EwPEzg z5B7xo%LTnE0V|hM@=h$2f4UCzOIe5+OcmIr&|tCt4=K z^;fUHH~iUlsqu4;wFK=$YnAqhTV;PZEGWh&Eh^4;=as?ZFOk7bABx{VKG-M}rLJyO zt%_`OegKVpPxN3Uwll05`9oC6SNC>Wj+w61S>tjs90w~IwVdN}2~st4Kw-PZys66U zHz@)Y;hkk#ntL^_47128t%w#NDC@R{LcE^mhrMiL%5$=hfMc@y;vlqIy){pB$b*gZgIb zHS_Q049s)@e*2cItE^;zGYwrm1KPBlCi&Fa+N9*j+SY`iizi-6p^XLu0DzZsuuHzs zg1z~sa(#6rASB!YwxY1EfpI=EgRS8VDngT!xDRnno8Mw^4fiU9ScEldc}7|Lg~BJS zQNkEy>!TdQzDr6p%qS@yY*2brwB@;3?z=c>-00hQh$c%CP{fV)CnDD>a%qYj@+uza zuGGa_nC-&pu>ifyRmGOm^%V38O^?0A6yo9hnTUD2w+p-4T(>-*GNkRk^{(snR0#z+ zy6Qyhiaj+Tv=-k+9A)PK<*K>~2WV(%I7X5>EZEFkl|JCsDeNh*r)7+=Gj0%}~TW9O{n zbZ1CHce*P^<){eT4Gm}h{_p<$p+bT82Oc#qXXJfaGS-A&Z z3C?E0ch!9d7N=5BB<=;qu|t#+tNpR)MCKZ+Exq7oD|eg;q5#%r*FQ^vO8W$>%n8Zq zZcW1V2jFFpjet>5-bsMlS*&2L*Y441KeS@`Fhio`tBI1@@?+bdYeuT0Cvd&nVVF$? z*^kk+plF@o8n(&}oL%JZw764; zUr9Qz;ENcYuZF#OFmfrOqp-%)bw}$7rt9d_bT}zz6e_jBkAktzP}2xp7%hMHS**&w zY&Aira5@Y_{!Qv{)t^AYqmwg_1#1%OHr;JDVJPx5GwV$EEc$BTlEjb31ccoB`bcw~ zSn=~(!|s1Ayoz@CS(Hqd=TgM8<_{Ai_@Xs6R}v(I@S5_%7|RSO^$^lV#6yn%5PU!R)FF!&#l zZWdnFDhy09j9a50^(qxqbF>kvheN$Q6}=w=8_eqT2QEn?seat~!mhb2-|3U!HFVkH zaNhD&G~(gWXSqkn3>GWA63T2~Aiq|GG;N+oDkm1sh#HkXw;PfZh+!v>$XZ?* z94g~IY~SHn8Gr~=TZV5@U*YVCsgTd(-!{ycV~dZpK+^N|&Q~Z4tu{p>o2SiUa}vpq z&sKDTH?V6~5PP|`w3>YAeyd1jX!#&eaTJ(j5CQ%)`H<)Q zIRE$kTcfWBqswb#zw6*z;M~k&{UwVJZ<@%Q^fpWE;{4zIto-Hr3|t@>+Ay%d$WjqT z&zmjW-08Ju4Arxk%m;Y0(QuLZ@Y5s=N3e*EMmw<;^uB<2pEv@ux&p0?5x}k;5iMKI z&=bHolv1y_4!JD`yTltnvX!NP%P;nlfq(>nRG>rxi?KLi_9+m14#1T(J1?|XcGdgc z$A95o_QN6+-=D;!#c^i=N=-)Sw)q??p-cPIV2a6#L^lG*`hd+4Kdt_UQ2@@zYeIIh-uWWRJum+MA&+X1Milgm{HF)p@V~IcoT`cN!#tu|{dX3v_B_-?YyM*qHhh8BKAq6e86-;#lyZlK`;| zIR77BieXp$e4`FcuZ3aPOxFx-sQg0q?YmGwyM~*8i-1FVqZirN4_hkiSz>m^e=aA^ z*EqNk!BBz-rK63O5~8Q3KNH#$Ni2E8X+=*>jz;6+YB#m05!?<^-wsk=gFpMyPp zMR#UuAHC`l_;Vz1-_jQv(X(F7>rn$V!Rx}&OO6Wo^>_5h6(OS353v!pf?8q35puTk z@kPAfeabb0w&r`;+dL-zeM0g5$;H_R3a2;nNM7t2Jwb8U!OMF&QxY ze7Y6SJ!^c80%wnQGgMKDQbvOWS9RLeBZzHET$<-Px?84c(q;|XejkQ7ai^E~C!@o2 z%9Nmf&$Nc-0u?37{PH{2w0Kdov4-TE;xrsFm($DpZS!}Ytfc?b-(TQETas^f!cY~u zoqEVPd_#cXEhe}6zG~Z_~JpGmqK` zi1aNR{pRN9AQ4I=qKU^OZ3|OO74J z#@IC)0j=ZIH5qTqNqUC%nLf>9bt(J+3Q76JW|(*?t<8l&@zV?hDGOTw)qE_h;f>Bj z0kgBIwG76Zn1*}0YR+Jv;=>bi)$KlmNHVd^vF{6}Ji0KB`9^=@Iy*okM@2_&A9|}w z+?pkIixk)<4KR~swTk6O#UxZKYAvETV5vlIDF(B1C`-9b-%hHOhf&u+9#E=I0HF^_ESJp>Ok$f#2Ya+&`~O@xO(7u0(u)ScXP5DOZ=YlVc4q2>K-O zXSc}ob)qZNNwIAJuP{_9C4;=7h?l7``*k3h>?$a~ZxG5EKIE7s2k!mJ%Hkw1@o>!H zN%n7^V7^+wk!nOx6k5NqRishnI%_Elxabz;dXW84#U=9}cMy_`fMG9~L+Vs&{0ov| zFB`bla$Bu+stB8RS=XcD!;tgt{Cq1lrH;S&3<=~m1O0nydMtGC)b112YqBr>c)!e= zUM1ZX^bCc5Q_o #LB0+m_S0PmuAzdWG{sjs9L!qYN%e%HNmX4!=i^n;6eOqQYA? zPnwMMf9W>W@t8TAhCwjBOm(*u{@&iFcgF22CfnI6W9?t1XipQ7Mde7SC5)~_L~O_~ z8(SBDOg?oeU92lvtR1K#Jt<3dx?P1ams7%IaoqBIN{T66H=YMbe+kgQE4Wx-rXq9l zJc)7dxM~?{Yy!+3mIiJj%PDg%5kU$r=dCjUCHHY!)oPF2uLk=3F&#+sEJ>yjXFKY2 z;h^Nq-`I?Y9sJ(d1CY&P6%ZPbu5)-?O2Or!q7_RTp`Do9i{_cxsMudd%q>bU0^A|3 z2aW}wc(@BD%m;g(w)hTx{X~-a{AU)6{)5M6X<>GT#Lm<(83Gu z3r|FNQHuNHTcymX9f`?HVG0aYzCA133&I2=%6c|tShkr#eYIl+cR^aK9#3C_a|MIx z;BHvvhbhlC^O@ox{J4DwUDt$eR#MaMnGE@`9HZ<~Ia>;d_t5;~XC^F=(LYYJXV;p( zDsSoDRJuW9;IjMEf8kw#kMj2-UBc>lvy<&-Sw#H%+h<0jmdNbDuBkN>ValGeIuf0h zyOX)LCTGfI$}vMqs>XSehQpv8MVzlw-OSSEm4>Z&$M32rd{M!aO`C-87oidnVc6RMWs5G zmG$Ym-b5RXhQgXzr#3p_I=y>Z*GmD&)uM#qv8C`76Wu z)DIbd%X6J`K1J1$+s|E46WBuCYz&tiCTZf7b}E@ot6VEzhaQ^})#(jRb=DPiUAlE8ZN<8gERi`b`Guv8Vt2rIatRhI5! zSdH5}wW?V;8%bqKql``6FxkUE@|KxBH8l=W_$khYJXM~jd)Fy^bQklMMuWPJ9p{c8 zBkLJW@2QwmGyCf)-cQDP<2-5+_hoJO_LIXyWK1RC| zET;07Ka53T0>{Clj7p!Taqi}ULCBtos!O24i;(hTwo)(K&T9YNx;K}ELnTldggLTq z`R7Er8@#5W`Y`B6fQ`>lhE;YHp)9dx90}whm>hgl#WY3cNI!;ovOd%r36vhjra6#} z$naF*Y=6d+l0vQbG}$B(F&MMJS7ieNJ9i*ux*yfO0~1P?)GEq^1m&T23&Pj@W#07W zcgeXcNDfeKKi$qwB(_<`5mYej>~f6YU)d(Z@1ig1b=1bfi0^Mw@)rBk$jPQOV^f>p zqFI+PmD0k1E<)PpqLxLV$<4)p<}2kmrdx`YQv>a7?wPOE2|ZR^LRT3nUC}gbZ%e$O z&oMlsK3>MO$ZrCY00N~7d-vf29%X~AQ>dz5noO}x>$~0< z+bYKji5}TqNkQ!>t@(zJ-fTESrV3TmdDP)(lkGvQR_r*Jo51>?isnt5g~ncsQr$3{ zKb|g|8{z6bIbyq>ry#uYA=eRhR?Ub)!Y9u_wJzov^s?Zq$IkJo=@S_eD0>@;((_>sX=m*4dDeo(0 zN#@|si;V)`|E+H~r-d#Bo>`%3p?n<+jIk!p0%KEV1kowE{(LwivWfcC*yMp{Sz@}hk`FnV zEEzp1wG4g!insNVjv?^jb__;ivzcHDAU1JVLm6hPWD1J0Ml!0-%lYTy%*M}GC_lSeI<}^bB zXN*LnyXCk}M@C4a;P@HCd}8m!8rIZ`yObVWCn9BMo4mi2iWS<7v26)jX~(#%p=;kASK{+(iIk`g%G-Az@LP zJSFS--K-GvKQHR2tYYHNHvc#7r_I@(gQtn*fIMK+Of1yGF#aBwrLMK7L2Xafu~G!2>w)I@ zwPL_P5rV`W5()DZWdF8ptwmJ_Se$n^>zQWMH)n*#WbkWe2H^-dIc)=*XpHa`%C};) zwTu?l$;oP_rdF6}(K+;@;Uig5Kv=Qyad2jvqzuOB&x48~iAIZjS$AYD87T;@=K5qU z&8fl{_+k;vS7d8P--1*VI?>PEi%hLj1(#p)^3hY$%cQh~XYs8f34|XK3tGyIVt5Yf z>L^&Insl;o28x*vXSHshK>nw8 zElMzjm!6;6hw=R(O-}frt0jHK15KC{cBNiq(X2WhnV=5Ul z>CMmD2%6kjG2K4Q=h3}w=(!7d>>k!d_>^i_z+NJD3=T3dLX$CPowbMJa9XBztdnCC zA)S=MQ*Kw539P?|2QO^wxbQ#aoeq2M$PsQE?52~U{hk(=-u0>7iK~Tn$z?G&wrQ1U zo>zIaODBDMNKz`I z^m0barz;p!o@(qf*-mcV>SXPe+h3@`E9K6EdzI_@73xyYPf{H}ay9I6 z7Z=&bkpDQ*WCJBf1vXtyZ^UPWss4VQ8m+W*!32R2h4PNB1mvy(ABa>r1}ii+^j+V7TM@`K zu8@gMplC))m&1^O`2}y>{ogFpYRfV6;#u(lMw|?=Ts>9B(MQ?SeQ(z~O#Bh>=6y4Q z9hwd;jJ!jgCA!M`rA7?nHZD&d8LZ_*i8OpQO_#$<=vqBE=^=lX4PSo>^c7T}^X59I z%Q`O1RpO>s;+j(O5o;igMS4<=Iux1M-(SYgYsIR|(b1FR@Jg`Pk!D(}j9`fvBJH3_ zjr=jPq>TL=G*uI#1X==H0y%5--0lPH;o-~Viht**yz1bC!A_fpfZ}F7eHiQh=fF?JW zTE_iWJAAP`cTt=A?~rwO%%TYA*t&kj-*Lp~5I}X;tk9Ib}3F4lp!62MPY706V1S~pnX8)=zZqxtk14s+i-{*4ZI7~fSv#sNtVrYu?Pp_qi zcHR#F%iGY#1(5OPa`Z!o;@f5>OGx0Bi4}ynWL{TlV&U)DSCEapQ-=7UK&3*n_OtEC zNg-U3@T#i_1~2bwZztmEr@26WVLxSo=0Irhx+Fta*KR7R@{2KK1c);@gxso!#&Z)t z-)trHjYFj407Edl{X{s=NE6o`O>>i@(2*VB}Maw5A{&g9`f9&uu zY;?P{li|{X*h@OB#$MALgfD8dBbwc3ejl2VyDykJ92mN5KwR#6oX7qp^j8p$&)0ma zlktZjTi(|-Vbj?jXVZ;rUem{ozvRy@Rn@lwt1S-Xby+(HJrpNv$7>m>^%w-N4p9$&lr$4Vr z&KvBcE=qh^3McFHGaJ=8LvVk%bSy9|az36JfzYuZ^ax1$i{_wn1rutCIXniQF%~~L zFIE6@4)pmzS{^`q@kE<6nW(ZjK@QbI1HrZx1HYecy$+IT&+G1}z6s;$V)N=@W z4m|Ez_!^9e0&zxV`G|j^B5EN(m0Fg5iep&#m>&6)m(aWDLeAx)FfQ;){l}e)SG*9v zmxvByC*uXb(5=X~63=&-b&%(h7XF_Tnd1a<<_ZVAmx2kDM!iAjID}sUtCXSDHy-)L@B=V<9cwNrf5jE44Zu=C!Vw^QSuGEp}T5 z1NQT}#`KrcUq=0%gc5CQE`mTw2pNB@BX8x-gMkeywkEgpW{N>eSNWIaCJ~iwZ{sBI zl^Yr?3^wqM=4>@V00mhL6OERMX1stpl6guw_IrleA%(ybg@QQ`($XMF;4I{$IUs2y zF|oV1vo?Sqv2paeUHS%EugfK4vvP4=1uiybEP3sVzL*q#42-P zIJh%oBc&WMj*PZJc6I}@7hDpziY`9DDBew|F5cF7)j{i_mqL)EF;7ODxfMO^bCW5f zF5H*s`zj@tbHDi<-c&~2(@VFP=jYWgzAM1a(T$GXAB}7isn?78bHS%kAIs5=-|i4(7#qyn-{inzHODn!b|aG`PmZ=sSC3|H!8iqn_Zs`gCWT7Ysy%+~WS9i$zDgl5dv;yFi;SZJ!f-s^1r-ir z8URbxI!8h9OyNBmgWo}yZdXmC7^mY&#Z147_)@@ic=G$H>BsQ+1z~()ti*Pcky1b* z`bAZOB%#L&qYxn+2;q??YH1=4NGvFM#duW(*g1sRj#PK_vSaZkb+ zkO@5g8C=KYIBOx@PDTN`kD(9DIP&jcP&A%6>?diR5q@{W+rNU9*1fd;>WfdUiJ}cy6KT$sexni3**WGnF8DNmNQ0%9!b5my&Huyi$gvS z2UA}h5R7QD+}=B9wa;P;9l8y9PsFQfe$#2}ORH%=Pr7_jF6-b~WL@0Gcl?2p zDQ%bcn=xqabB9A=H3H?GMU1zFuMF(0fuBeL<|fIChMq8O%mt>yV_aeqSokou*r_ZG zhX;fC43?zH{1`l-NY_E2khX3r1^m~!Ncytz&WwW{AoelZ6D31PbcnZnmF&p3GJA!P zC^4CU^sb$IVa8u#hGxtFiys}Q>*3ZK%q7z8?P1rP+U&_w>%lOn~yiKZ3d4Z^)w%Yc4432Aw}LiQ5ygQ5IE zXwlt4?-dvjnNFr<7)9|(soWNd{X>2=>`Y|XYj&r{YA@&D} zr}tA0G5fhMZRM73#H^xDq7l^3=LJ4{zar)*(%&_Co6FfwQ+;Xt%L$0D&N5qNLdHKL zy{U^G;FGvpBUni*V!D0EYQnR+2_RCTh2Y8C4O2jq^7d zr>LXRxcjo|E}tetKRY61q6qvuViTQ7qJc*`*sj{og@H^fC~T#eNMnB|$(LA9CEEa+ ztOG}Yq0nAMJ1$%nF2N9i!!Xp%Pow5_JKz8vNgUjv-Q1yxOGPFzFU$i&hjg3eUZ$en zL99YBh@rV#ML{b!(qA3%CaA>cmBaQYBz@3GT6P2-Z0T2sD7B_fz_%-K(mZSP>Eo!n z^2m(|GzpD^UtdZYz&vyJV`3w>q{KC?IR;?x#q_zu*P_C3=OkJl`^U2OJOPJm&h)Ol zL-$)jhRu{opZPJ@Yt_T8womB(g(#MEt=-T@?}CR+)A`S;)CkOn);VUgRctX30QjVz zu7lQx_*Nt_*>o4x2cDc?8R9yE_YlA_xvd*0biPQucIh?<=u?D#+cJ}BfdeLhq*+07 z;_roxeIE`-{W<6PeWTs!2q>;&02uA!RT&vffIN4e<>fnimaM3uz`&++^wz6u6XNP}6x;DpGKK8!g9gbkrc{z6b{Vf>+SP|=N| zn*^nZ6g&^X0_k2|j@gypFpG~DI2si-BsGt#=MwhO@azYWbJKLNv9hrRw58r&^g7eQ zRsKlw2zMDqJ-!Q!uWpK-WRB!B+Ikawe@1ti0Qcwg_qj8;J8-GXY}KSI{@TzxiUm>=w%$&RjuiMB&V%y4vUTilLNAIN;d$qpstuU& z3l2VBN&#)bq<$LJhR}ViKS_}J ziOmCg1D%>wM5%EFecQqR;3$+TWLZA0n8isdm3^rp9Sj0bucMyzg#v^)nVI*a5DK$e zL;C`6qC=)PcuOi@7?oGzoA}q~hYw-@4rPAW+YvY`4(92h2@7;`#352BeE*_6^w#;& zS~qF=w`W;#-4W1!+DPj;z2V2ggJz&JgbXe-vNI@Z)l9&QfMx_9qcKWp`RgrIxnfZ{ znL}Z6sLZC3v_RaPj&wa%2c_tM(}n`J~Ow*1{wDv=m4L>v+T>pO-rC-0QgjThG)>NNzI zO^Bv+T0Y1X-!ea)!r!8Z9Uvdj{)s>ye2i!#MFidb7 zjX0Zffjsu%;jS(S>k(x9x#~ACErF%dN)!-2?aHirOenWxXwlpSWtQn-Ej%0?y@KLW zYpdU^;~=5p&m{iMTB7n(TaV>FHs*Z3J2?T!C|4vuLHJv|u0gkCadJS&jASeX5J~gM z%uFI}nuG}iuMOv{M6Q;xIOrerrmBBid1=|%fzlIekUR%GCH0~OEr-yR<rB~J@UNFep3Jj>~T%3<6^o;V5gCc># z1r_*Z$o=Ls z@)%Bp2x5cK$$Cd*B0sCdLDWSvhVd0k*bYFq+~G+b1W}MD4Rwc*_b~xFI51XvU2pCD zx!6}kx5Ag?zkigIADf{qL^1cS5&-@3;)*t~SY~;wGcsqXMDA&E^ z<&aH}?M;2p-B1I_%EepFIC^eqjOXT)mwb6R8XCA~io=ZqKvjs`HK|{kGB*YW29qGl zQ-rfha!`T=*+TbKkNh#bx7W2ze7?T;37qj@TWMiBTRo#`Vk}QdPVxwXU_altt>3;q6C|_0#7wuK-F9PhDkiz-KuVeCaU3PBP*Uf`L<#=E5zmcFwZPlBa zp&0w)-PSzyPB(1XQ*tW26~z|R6$b<+-$CCe%nkuGB2GNsyQyB$Myn-d-QNKEC^)1( z*8IuWf())|2%-#8ctRf&IybHfvy0IQ(bl|@F?be+fCr7IT7AElLnH_dncjOtz9`@W z>fU$jg8B|R+edZ^K%t3FKj-V4Dp;~u2=5LBBw~2vwb;?HChtlNq&S9X%8O^V)e{&n^C#PI?hXF&HarX297l z%Q5#H@Ed{!X&C|BsFBG$8pW+kj1p z*dOn-uU+S*FcONyh>yX^jh4&>Vs4-XUv4oW_Q%aMGm7j&K;%^5Z;3$t^~+Q`AJ=Su z^}b!6zq;{D{u6Jn8V4id3FLe#@ywz9n@M4_gmQ$yT2N$k z5ZBA)QrTR&zPA(hWU4b`KJLJjiuQM1KYCi|$?5+(A71So2o?-T-|JrE`GL2_-JkeJ zepWQ48_;s$lo5p?DRU-ogkG65d^q5YvUGAcSWdY>f8(u9?Dyb$29u71bUIYbNf^CT z3T7q4S!f;<%9J-NGS!<~^A1UUX>{jhnI%WhMBr&qKdx+l-e}yV^{sn6kY|-y1kR#G z`EJc{HU+#aWlm+dY3kC!1L!@8Ra3K;L=Y?)exViy#FTWPP?z3dYKiy|O0oY=Js^Q^b0uvIKoTgOZ&~VSw}zv{$Hu1Z3YGu!S?S(gu3kX2X<`Yf`HuRtEen+m-|9p$1XK1KDZF@I8>N09^NvYXtl7_mnAY#L|1VPIH zXD9)TCAf&L50eBWB0pED8cmoL#ZkNlexe1Xg}AzbKf@>S_*Y91Eh-b>NF5a-KpjLT z%--z;BX>>_xXy_jSqZ)A9GWvA#yzCp{?`EID$oZY6AJ7aQ_$Hr&r5b};08eNh=jpM z>?w>*l%b+c^&tPmX&%X(nad5|Ne@aB#4oCd{I>Xkn=l-Z zIl3tZ8%=Fzle;4y;tVTBl-FChsH~P(ChNzo138g|@Q;{jxaY?dwN=TtMU)TRJeCab za`G>lVo&aG)O`&nW~)kf_Qlp>WduXtEsB-AI}cQYkAEWB%;k$HY~m7@H>aV);uKuCdRy1T>);RQgM_#gq>H-tZ^Y4{ zTK7nZP!2##)u<{rZFTwcziTnimJxuy7yO>^Mfc=rFu#+(BQalR?j(tS376kl4fVtZf`%36|-NnvUjYB@5r)N6-{FH058s-IBesB{b}yW$b%Vqq2n(NcWBN%F@9JHA)##KP9@>DsC&Kliw}$%fSd% zcN}G=bohJu-CN;A6zBCXhK@zCs*I|5CPR!W2|TC+zh(j+J0Pyi@{>A(KVZ4~>1umh z;rrJ94%|mOP}e#=gbYNjqqlJ=q@jUXA2n>|<0wr}TRvUN9~?glP)1g*^6b7b-z~Dn z#uv2?A@QYyBYh)jV`Wj$>paEzH$Z0AfCzTu1V9-!DsZh97x0$3PWDAc(R3a zRdq{nMj~ZgL-gYhKfHc)v0JcUN2+2CCo*58><^{VNEODvf<)K>8@@NAs@8cGVEU0! z;IWJ^FG#&?2!WtkPdWk#zm|EBB5}v}5;iHmpva1^EDy?v?+(d-h;YTJ_Ag;y6!rQ^ zR#H8L-qSjKFI|q9>pmB|-v;`o{p-4uyOw|ofhqpaL80liHwKg5*AdEJ?%Oo}w|vgR zH(;XPUQG8=2X7@0?~q>PeY0Ip)_1?@uhNgVJhy!}z5B2X9YODy;Sv152G>jD5Ix=! z9}+=*_i_`m>EkG$WL8wuo#|w4GtcL&#wK#M+e&$ibm9u;kglNjVc10cSEsuH zBogxX&0t}}jUCNdXyNW5sL4tw*uC&|Fac|ftWPwNz0Q-J+7kOX!KUaCVxL#d;L;nM zg^%-o54XOPgx!1rp28&Rme<&jqY|G704=6>B`~Dd++kv`RXwl+T7x5%?+&be0qE%&WiigVE=j;DUtvBlghg8XI4_**J^<; zOG9dq*d^&n+(^cjR$5oIdr{>;ETBwhE!$;=r&i~@uCEt#g~ZG=>Df3vk@7rb4DhzTZGXhY``CBl z3G$0{sY=X=_SL%k=KeH<;GYA^(OwjDZJaf>zGEOgB$4~j-SMo43g2~R!&P}vEL)a+ zXT`oiC`GAK-sLCMGibJ^%GS_xs(Th#UURn1ZM!B2u_4o-(8+s~t02vWtFy1TjG0VW zgsA54ow1$hLrv5B4x}Y`w4|tZOJ$LV0o3518$KIFOp|&cL2-r5yZWx?AubvG#$N-nWJ(qZEaiJZ33T- zUU!>u2h2`#Q7B z`g&e^Yt9~-@%J9Rnr;{Vq0~m>e|zU`EWOTOthq^*JRiM;w2wb;?3G7ms7JHDb)chM zd{MW@c9ZJ$R==EIFg=R+#}+8ba@^Uo@Yv#2`CJ?FeQ;kv=ZAfU980cH8_r2ad=F+d z8~qjsc8tSn8qxtwLCj_l&ry3lSNvO6bV+;ezE$;&nU2J1({0(!W%g#K@GXQeZr2;= z#d-PBd)52qefUEugKdPsX&ANE3!Pe#V~o&4f2maS)$?B=djD65#MK{6>IZq_e|oA| zXSwPkl)7fS8hX)U4!AqUG%AQse(W>e4xq@UzWLDwGV*qo5jMPws5@(oW2kS$(>D2ar&(L4#mX3Y`+gqbGFLmyB<^wAK$? zecpC@0ki(#Yg+%BT3+i;@gc|mpkGY%02cho`=;1LkR2Vb!}q&{t$Lz*ov$a4yJki( zQV5m})0|$*krM0#1v|Y3=o`N|4^bQm<@;0HMigHJyuf%)Vj3rTG|0o5CoIx12{4o` zWDLNo70eZsWK-os#zvP>D}F9HdO*Kqg!01fP#7OM-Esf9*mq4#uXP&a{m-$GxdJFOfk3 zq$=7S)VoF-kijOD1n}C2U&<*x{OTlyqG=%V)hX>a64o9FmHpUPl)^YuB*SkoFp?dZ zUP&eY$JKiVvi-i%!->6T6g5Ju7&ZH?y~Qq}wMuP8TWVJ9AXe->YLDvBDs7EQtx`da z(o&;p#AvMuYSef>e*fqHym;Pv#m9Bu_qon>&bjb6+3dMkfZ;$%$D>U`0=@J@YX@KP zw>{$~xz?47rJv}HV`cU5)W&>*z6iFiOxYF@pOtnG&PSaEiQ#=@8H!G7Js?exbK(0| zyZNyKBm5hDai{6vUgpN$Hg=A(0Pj-mW57>5mwUV$bvrn~x{UpdqB4qQhZ4ciMCKCe zDD@Re+?JL8`iRBy{lD$@e~Ig1IlM}z#81QCb)~B#I)zvH1LV3sO7RdjUD?Tc_b)|E!bVu*T6L8$$3U}?G z3X~+*Gi=izzck;{B#1^8=43F2IbE+PBSPSDA}S@e40inUSvE_^u>7Xbb@DDD>xW%} zSX0@cItHI>9~kirbfv;?*~SyBWQ?;0Otxe5!<>u|$J#gSZxa6NrU!@Qexsxb*$8Lp zcgjVkBC6KOQN^@w*mmpUNPOw9DawBupa)l%?iQS1gU6jR4f46s=z}#_`YYCLuJIOz z8(bltyU50p;IlX7)favCby2ClxZTeQ0r7X^_9b)4af*bB#cutns&e|l222~+eH!X< z8om%i{pB;yqs`X}ER3*^Sbe7RJR*SS}RG}maBdoEqF1$ zbd3$sZDTe;Kpm|~45^T?2q%)mvmT6tUxO9Qonqw*2)=Vqh>{^zZSP}lN0r0|>74pv z?c(VpqQ|w?GDViko1;I3z3YF}E3D@x2P=;CavoxI45XAX3}h&zZ=ChK zsPqJDvzVj@AB zxh_X~PDX`FZidypZ;y5}q900s+_wzD3O2*IJ?asazWX?<3uqW~o?r~0UNi&mY zJQftG5};9Xb&~9+!U^WU;5oAD|og6&)9X=y{E^Bs-=5=K0xwdRQ z^LUrZ$Z1Um!LMrZdV&0ma)-YwJwowhR6qGVG1PUtZH+$!tN!=LCy{ZRuPKvo=IV1! z$_RK!B#`-B1dO!e6SkJV=NcAf2^m~9w&`cJV8c^>mOo*r4Z6Hr(#>x|5uWk2Ps}aQ zD*D$$mQ+lyuT|9jenO`Vo-zT5H@s83FFTHAkA#eYXT)%d2tLas*>|x{ znZsrTu`vy~gUvV`;vI*htbmq7K_;CV`W1!a_L9$eEN2v$9A&D+NvWX{vu=VMjI`TZ zL82YTKPClWORyGNgjn8uwfU@?8@b+^5eI>`NUfr}XV}RQl(tj1E!m>F@IJL0D+vMZ z9|vk<0)=0R81JVnuv5=_9YYz_O%J2Q)5mx{0>&XvBuFtOl@ZIKiH5m#Y60I*TtoIK zBfe_NTTx?7*?xBM8fab|kCw_Mkx_pcW*6?cBX^<&#Js#Ll5^81X7YC`=U=d>!*+}_ z$oCE403(5E61hlY*hY{;v#XMY;tex%%u>^Hf+6)d$h0hzOX;V#f>`rv_N;``_K9Y& z4(+T9I$=C4l=Q*8tPNi0Lia+gx@Ln?w3^|_Jj^`o#V0lV&~l!>SCT~W^cMAz zIl2X1R8emz6PIk4IHT=Nu&Pu_Q-!>jn=&khc}WH1>70hI&iUPq&%Rht=KQ@fu<@50 z8QF&p-i0)dL<+NxP6H=JDyeBOs=k@1+ZAH9246Z)fjejJrw+D4S0Ikgl@Mj!$Lo@r z>Zm-ueQ($!mmwIVnvu`Yhw><%c*9gytFoK~jila4x$NstT6Z+*3C1MxxJYPc{Ka{6 z&!oLbI8biRdU3>9HoDm_N>K;jZJq$R2ETS=#%7*8>X@$YJU?-1nSMV@8Z){IC~OY^ z&4=G8`oNj{zI*05!#FRrKS8Ghas=s_oEN)x^~f)Z3Mtx2GOE9gGX<1eP16o!RBVGR zx6+L3TQMFi&7b~zp|35&T*gSU$qon|{47@X($*|eR(Me74rL5jKiAfsQ6M!!AO&Cn zJeF??ZN(IHlTq33HM-lRf#yK`;-nZ}mU8JfI($m`vY>oFo1GrFscy;C&Yo?7xt&f? ztBvs~JKHA}y8p_MOMhP)qS`@dRK&U}m%$yoW}fMqM|&RW!PEIxe@`22+%tT<(ezyz zFe(QqOsbVz7e+dmC_n!e|IS|nr+?e`!BbhXwcmO=PTu)6Cify9VTkj|4m(-~G?fbMyN z)Emv@p8BU9466rG!tbls&pf1^k^3L1M>A4cRuf~W$SBCe)*pzSGB1jemt3uiHl&sm#gB$`?-M5W6==XLHEcW7Is8j0|>9j%xOf zj^^O^?#7tQMQjCIgW*ACp&;l;f7_9)A2CKru~ei~)Hvo*W5L1od`XD;?^L@JV{tx( zMH2^}9vvgQVJW)Qe{P%+l|R@rm>Mc2)*2{=SgW-L(bt;#<-BR^=mtwqS8*QHxw!ID zhc1C(g~0%ZoOSWW2>sJ`9x8V7u#l{fPCdn(UBN>Hwa!^ zD;BmVvDW5#h{2!wpBlZ*0Jj@EmI;^1cDZ)z?_#VSLp`Vy;`Y3|6x~e;!#2oiQF*=) zbqJXSMMPVU&(_~7{?MO}T>{(3NB>asx2v;_lq|e7s$;WJx@n_D^P&2n zD>Ksg&p(toa(|KjOpK~p!ukfLfmq@v4MqcW$Gd-LjNz-pzHX`Mbc+~fZ$_Q{y7AEg zwotuh@hi)TR_tfmD>q=Q>k2?MY=-$7y*;eHcvM1u>#3{sYoY5QZ>DW!Sg ztxx2E08%Ur-;B^lxrUmDP7S=bd-U<3r2pX&aWNTp8JErLtld1Syv7^2RvPl*egxWr zz;mAS@;yNEsl3T3(-Sf1ipmt8OLN<9-_dycRiEcTNtjmcK*=_Ge+f{AI!cM(BbQ+- zwW;n(ypWR}T1d(6Lw9Qp)xpV#&dO{rc}wAKlDNzc*TJx>&U#M}+|J^3&!tju1@}UG z6^O5Qzz#K}!8~nk-a9i#^ zEp%54e=4`nfoZmC9HUn2Q9@6pL@{8C>u)gRrffErXheRvHUHBH*0KH%o~c#HQ9gWQ z_RA)q&SW*PaocO`=YL?Pw%hxGRr$~B=Me_!kkgc^ug$mv4jYHXk-U3SDgfukIK^Cj zytnp5JC3StmuW%oh{xki=%nd=2})LwWri9lY4t(8oZLNt>fu@?w7s-g_;j(pj}#D~ zVoEY&5P4;R7%mlFP1!iEbYQ@rZEh|G6?_xe&*7qEpk4)#h3FM} zCk|caOvV?vF8{^9AOp2M+GR-ovdi;`vvY!FCmnz1N7KX#Ek8J+wt{?K8s~^NZt#kwFaPOT511_n|-+-zWJjuotjH9 z>gW@+cv$h*T>bmWJ7%I;Rz2jG`yl(-nn#}~HW(;Xj!KHAbpluU>CMUwwT)Y5%6+_# zf4Efs^AK`;cK7jgpRA@E7dXtfed`8w{-?hi&0YY!PhP$GI=qPtn$9__L=@71I_ee{g$xh+S$rZKXK- zC;YyLXqgb*vk1Lyg5u5{w%z$-I&pbw&EBE7h^1XJkaZT3j$I;_gQtf)>0!`^o_YM+ znoc1M)iNt)6FCNEPQ;f;{pPHV&Sf#uX3DUm6;Ej6u@o%**U0U+w4$_uTFOU_K0*hT*H->;W)9|W@i7MRU0 zcN84tXImPY1(NaS>p%-ze0E1l%?#=On*l!Lp+UbO77ed$GG*5%Ge>|~WQDO{liY-Q z41x({*e=i`ha|jVvP#QDbQ*J$ObkZVScn}tw8!-HZfwUU8`pGVc0Uzls%B{u8YYe* z2dRtDz*`k~L9scpNxW}n+OzQVSu>{uY8FW~jAz^%19!pHg(7@8zGOdMO4;dZ_PIG> z#HmX5y~+8y0l0UL+DA*g{=PQ#JjZ9-q7zUxtTIZiU7t3-kQbt+F$Of(Zpg9apj7<^ ztG){t8measOhkU6A#E})@C`wUrZgT!X;e~*n$~tQzjj7N2J$}hK^I}r( zT}yw9ifAUAyZmb;{I97<9NodUeooDi{Y>M|_;M zoB4rn#7SZ>hW_;1i9`|i8f>p>tfy|O2wGFiSz(lu|KFLDpZd*<{)0#XNN)F=-DlHl z{jEAsY}KgBnN*WD$Cw1$C~GY@;wr2@E$SWjJbM`By31)oCq(H7kjD2CKd-Y>#0w4Z zMm_4S-g07TU8@eF#w)r2tXBS;0xjXI7a>!{ypRcV?%wmh^TB(G~(mr6csu6W`}| zKgT-qqf$KBSdtuic#Kkg^s`dJuXxNSni5|ddhwv+TO%OG!1c8vlh#7hLG|hYmQm7P zU+D@zh6l{a^g5d#S!SJC6|Kbi!FI!Tqny8AQ`xlm%t06}P|fPUJ|BR>j&G6+Me|MT z>Az)J=Eilg)2u8`;{(o`_=ffbT<+$s{x@m+i8wH5bI}oXJmgfYemFOApnluGefKlZ za7)L*wF{QJqsio;$7=UYPp;+%>V75H(wH|TXkbAGmdGW5seinfY|;Pc?~)SmMU>|M zD!pYuGSFn&h9cq9pA+4Vv=~ZwZ{@}g1p8&>)JXgEkRdE@#5uRH48DMatGMu%0fpJy zc`?6i^v({NBx;QgbKgPB7O@3vFE6P@tD&8xMeiCkc;^ZZQp9eTTg#=gR0hy?5pBA1 zD~gN3hyzv&pX?5D6OFC4lYJgc-1TZa;%>v{Z0KhI^0miS-KNTb`{c|S1H$p-#%sy3 zU25>eZjH>1#RE1FhF0PY;wNU~F}3QUwd@B&TBVYiHIx^$Yy-yiT9* z#VkDmc-YB`Hp+`fB-VFbkaT;bign2IFT|?sb{!HQhSb~j4e&5@4&3cbA5UP@>i?U1 zQ}2q17OGrd++&P$<5>eslI4syRv-YIcSTW+MC&r_ihNbI6w7ebc9Vz>5n(pbz~#>| z5oBr7ukKzsmQQk^${WAubU#<|glV4pnW=Hq+rvrxMd&@$M_~rYGHY3x88J*SdOuXV zjoq07y;vyB=A4fE`ioUvAd)&1UFz^z?e~1n--!ZJN0$Ku79!{M8Kqb5N9?A4!mV(x z)#O%ovHXw~Bh+*$n*SddURV0KSoQyeeyN+Ke2tR>t1O_&zqGBD&AN47#D(bY*IQKU zfB&?6>K6171w20DW&PW9K@nsTwg#2i-P%-~yTqiW(vXQ(Q92E5i9-%oQ0|Nw*R#D< z>NpL488s)ChyqMxl!16HoDPmQ>OH1_G(u`~MI39Iz_i;1NNJ5?=q0(~g26sMsH##<1(l2K$1dUpyn<_xqK`RwmR_ zQ#c0vC@tA&?}qR7nGWAm=zJ+KeeM0Y3=!=TFpU1gzVdpPLi={|6M(GlZ0}duNk5GS zXiKw_@aO&I2L`^EtP+ppvbmlCUI6CEACQ;3CK)3sN%kiH2UV~qYjKXqVi2esD=x>y$0S&W0aF-7;s{@f4##RQ4?EFgy=R4Sjqss3)k{QX?lY z@MmkXp*=o3--#|N^N9ev)Hvq-&;W# z^yN>ZY2e3u8H*kGWq}f2*LshLN2_<+F3$fA1NdZJ!YE+pGS&ad!?)ATkH;^bESArC z&a?$8m5qJBsrd8TrTbue2Q(~{uB2o3-R(JlIsfK*5)@Fz9ThhJaHXe?=#d`iGLpKE z)~g??SNP30YoS#k#RuB0f&0tjk#>pNMr^x1Ghc^iiw{VIZXSr4lORjVM=3;iYWo#= zfw;~F2>yd@?$StihjY(4on-w2fjqtnOQHGZTh*Kn+#eH=yjE?Gie(rVJ2HNbht4*k zQuJ1VfrNgE?;`hMxBGkeF$_Ac>G?aSJq;?nWm1lK20cc5AI13N3py86y3~_f({~yn z-0sN^usH9T?4Z(j|G<~VmcnJ~DUW&)-gn$&giOUA)nv}|e0yIx0I>Qh)NSG~R(E+P z$e<^mccL%;tpZ)qW1Pz7n@?YI#c#ompDJr))r)U20h7gu>u>K32YkPaZ_L8{_Qchk zJbOwUUuGp~vo08F$a^LPF@1U7UEcxs`E~xcrSyRD<*gZQ@fUnRjvt3(84eYvh_})4 zC>7xgxN4#K{cf0r zrLv3;6+n5Nl}klj?c@e|@$Ep+0Ot#Nb zghc2}7K@zh)%38f(*b-$r264KpbNNnvj4lW;Ipc*N}+Xdiief=V+o@7V)a6;&VU}E zHdxiAmIkZ3wKh&DUN;$-&imadUJ%n4cNQpxLyvDjzK=}6ll9o#MWJIlUw4USstBa8gU z%`f4w^TBK+H>7Q^U@68}MW$>^R=Ec1?o_;+-Hb;KAIP$REHl^ilf(Zv z9R*xGJ7$eQ*I4-S^@kUbm9IP>>&%XzO&|A0R8>op|EBXQkMF7v7e3oN3hH4$uTP_k z&{#%zPp+E^O4ZwDgLG|qYUA>1zkv8A{ZyPKn&qD7?}%p;8FGJCk+3~86MuZ*&cu4W zLz(rjTXP4Q+>O~MbkFNeP-b(=T1$<|r> zvRLfZ`n;*4yc6*i@G4mJ=?L&4R?Kp5HP>1h)~XLn4NM5+ri7!{Wp-1aGK%=D&Ul>4 zMAB47VNSIPU{^f}9!)Mq#JTN>JpPf~N$)OK5oa5{{Wxa;pH`!(S86{!0A9=WlLIUL zaumt<0`P*;UtT;^^W8rmJnaOQRt`A?eMP)ZMi2A&wpNyflz#Jlu_dQ0uGjJKo7&C) z3r$s-$jKHfjbB}QO(*woza^{Q?Fx2ZS&91d?fG^sdwe|jDt+^pYplWAnhi8s!XR2C z=8#5&%h>H0`$1o|IcHWcUf$xbk(TIuF}NO!v5CVx%%aXU=#hPMFU1nACc;W0V~(u7 zJvluk9uONa&q&FTU1l?L29M>sRTg#PeaHz>gv{V{+gh1+YVZz7<(tcmdY|=JIi_=d zN$ruX!DaRZ-*Jl+#xf1BKB$T0_fShe<#_yVP|o~oinN6&*|Q%qP@@i zyp12b5Z0F&mO?H;aK&8yl}>+5tY9dD3=4lJuwdxwF;ue|V1E1Ir)*|9l(WU6#^ARR zrH-|>3~l}l=z=YkS7_9E*B5`b4h-9ZI+6_^cnug%QLvjMkRU4)TyrOcP-#6eTHASYDE9T1(PlFZ0S$G(fSu7ho7oJ%{Lm zabQ~*6k`)2RcOA$$et+5UmiS|dmZBnjDnVX~ zO|3zPL3957MMgQIZI68}r^=pS^svtUT|#`-gWc2B;U{Z!w~p5;3@J~zbDPIvFQV^` zW&nLHY1zYmq*rPLkSjF5JPjB(68oOB*>g26b|`VgK08>X&M+S&q()(cv4@UkqG6LO zakaLP4QJ}|pn3hnmj!iVYe<1cTa(vRbOP3=`h)Tl&;P}BcBZ>#CLk&FX!Atqz#E}< zzn5oXbmCGq_jYJ0+wSE7RFvc@clRIsUVM*M)`fNdC6FUPD$V*9qR5~@%vHjmmzR0u>L(^hW$dfbpPY;C=@(XK-u0jDQr~z zFjrddotWo`e+6XaOwk=dWDJwG62*eQ-}wJx_e`zBA6_wnGk}DW4N+U3x+^_etd8Qp z4M`vb+~?2A@n$lSmv*B2{0UvFB?ygGerpFbj$w<$Cb^4zfSw)z__0YW5z0 z}I5TD>l_kviu*L*q-(g2$zk_JkI;_MP3;nTXJ3q@CDmGr1e>Wv@HE`%{D^W zz(MtcKeY6kptxlWod;t|a69CV1%>+pXZ-E_CGVv0D;;@`xk#vRvZvf8uY(gk*FJ#( zC-&|p?kfBU&F@}oPwR23r=Z83)y{w_ zmY{AzVffC+srQMVjq_m}MaqGzO7r)?8fw%y6+3YzU@JIXFH3wNkag0wOYN8HsMDu3 z=w|aBm6cIHu+tjQ|6RG5c9wv9&N!=`!J-(Nl$G_r``?|&kpHX`l!)i?H$Ow*s*TIiq zx<+eTpU+SMS*&U?xCeyI-PcxDl`D6_6eo)ns2h6HZ}F7`pf`krp6B2YQ5MvYcP~b5 zFhDSb2zB~yGRw45oQdTx?ezr!%>NnKy3}>Ci<CrLaIt%o(zyYBt)WV=$X_SG zc_Y2%dv-7tVkOq*eIgf70N}TI|KWk>m{!bu4Ouy|dHpj^NuYwpL-KwHOeIvx#R#(& z`@@dPleYWEW&VUVH6H<#!=P_vNm!7a)D>Sx_n0U0TbU^&_j^psScmO04Y2tQtNfc_ z1ERC?SxhbTr>!}ZyR%J|62E+mg_*^MDX>dDU5T{I_|#*T^ak`00%VT;geAg4mgKU3 z`CEsz9agl!Y0?K5t}SVt5e-s}Ai+f4HbT^kCU?`GR#AB!Tgc+Q;eDPAjgx0D=MuE3 z-b4VoCaUIIR;WAQBJWXZ+=+knOzbQ7n$^Mt_vmv;ds=ublK+kV^0jQDa$`gz!;qv- zOzm5tcl564)fQAzuN%e+NUVm1bhAZ(&;4Ewb(zk|8a4jpZKjyb;*n~sionX#2~@d< zTt#9?u?)w?&pI8cJgzgd3U$&_Ix*1WX%;i!cddkhJ%ve)=wRGcBDr%(-cctiF@ifc zI8-KQWaur?W3<5J?|;=^Vt1dMX^(Ou_=x+rm4&I9Rpzxmi=L3_%oYz1wE|=fV_=^E zv}EJy6JPl_Dn{eIr2Rq)CfUE9yGQFdRa%BE(oedG52xS|(pIG{5fCmvVEDd40Rp=l zPWI~*-DpU`}xD`ebp+>3Ae1cD<28SYqQNS${`ps^8heZ_ISp7 zRmuJacaPAhnjFzi9LnTQsj(l2;a%#h&Pav5*aBw@-~z)p8x6iye)t%7`NGHXTXQ@y z{`l{bQMdQpu22|No7e<=Iopclbaa%Cf&(zf0L`@#^9cIrZ}36EOnKqEVjDoya|@XDq#eeOQCbR9yRpdGbr{N1TXx?eZu z$m7~Dn&UTgX5F`6RW&$$-rMWQd?~oYxTl!qHz(!iweOf^f630kLE^7k3_)RqYNDYj zAat(68sL^hg5N%}IPYv4w{A~+_~5fDRxu5^Dfzm!r!;3kuBh7JGe?U> zXYs1mm4&!N`_+}1$Fn}AYu8?YF)GHs-xm|1zGmtN-=66Phg16leot!kdWjnxh;lG@ zUs{cR{gDyIvODpVvt9)=YE(%HHuB!XKD!#{VV3LNnAD_a#3It-<=k75nn>;3|Iz>B z3$eOtCD-oJm*^OHbq7phL(0N6J86wg(bM89_QsV6oglq#1AW@)FLz=jeru?DYr4FH zAAxkrn6HGKWL5o|zK81lCoN#8)pnuEs8#ofZjTL|johv+QSPTOQBa)tYj!HLb3?E) zTa`|B^<&og$E@(Mt@l$7=S<&cD}X@G*~@j_c~P7^i*Cgi?qChHeJVc-A{!-Yp_fZr zS)YedJtd+l@h~Hc9v}{2@jYmN-1k;8AknMovzb~i7bMZkan-tkKJSXD>w2>5|J&s zOv*LS14Vxt15h^S>17>Av%GtqqjNYw>9}gy1fxbCe%{nBA>GF>rc{`rp zj3$S3M8KUS9AS23SRy2gcUaCJqtm^>O@ScsP?BSL94zL5Rm{JX&B-@d_|z6&aGTVq zS|mnwQ%mv6{--F=SIr4^LxAdj zfXxer)X*!ajv5BJLG{mMa{9vRDQ5G`TAX(KE3A~zP*Yu4inem@FN>za)j1Cpss@HK z{`pE=&l!=J$ruxdCl*Jd0CJc%NWwNdEm4`Dl_Y7lVRTyMy?77F9tT56}hM(fjX(X zD&grH) zuZR(OrBm<{G=C_wh^Nd59{D%?esg40E3_iMgX&oON@S?1P|CZ$g1!pV$Jmx6S+D2Y z{bwxOQ}vAtq#>CQWp&&RA$>_OlQ-*Lxr^ADW=2Tb={z78s{61d)n%Zr@!WRiJGD6R z_n-ckic=CyG;q=$Ho}=A6U>zrm!*eU^5btDvHao!D5!(V_*doF9z5U&o?-jJH_&dre%mkDw=!$(-yW?1? zB?P-HVMuuPlGzSOO1-jmEmjOgPU|06xLyRKVjIcL6XRuu!X3KQ)W-nsg*^x0o*D2!xzj&jf59Yxd0r?ff}Pu z>zk{Vp|lUKO&Wob7A*!H^n2_yT-miK1EhR~85pqzcV_9EZF(r?N!d5d>?6b=Pm_-P zOem~rHu;eayb2J+_1_m;^XBV9p;zI*Sg1gBszKxx4{}>_H)|sl13;BrfR(Q}zT+R) zV+zQ?IJJQ{4zcgD#7!!|3kS@6QK-H4#SXIw8Wf_)&R$U6d=nSC|JC59ax^KYybze` z)`|X~`MH+%i?N5dZ#z?J+&wfrNKi>54_y87e01UF{2-uLSksvW!O?sg z@J3WZuZb`vCkPQCTrRjhpRDYOrU}Cy-E?HVO@+k7_C~TbQ{>g6V;-13>Bs~hft_so zb<%3DrUXN}4J@<(MGt(#8)6|vtU{lllMduDV-^EU8}f(Q31SwwKTo$%dAm_yJrLcO zJq|IkSFIuL);L55FV^Ad?@q5ebddXafk9M%XbSumBMZPrbDGO)F#!ELN4xgl5zUK; zwPSBe&4a7z%9$KT$Os+dTb;oE%&eV$;FW#=Bt5K3>uYdPanz1n@)#r031QTHBjDUv zKuR$p{`?D58l@)VuBHY?&BEKPXN`i_h~{oF4u;M^CArfIEKLmJVD*h~$oQ(6gmdO< z(SHF9#)8;-%vvV;CKo5xsahEOtN}BqVgl(E)`@{2Ay1QT06Uk0d~(A;8K&dLG;p=b zZ{b$So)SB1Y70e~?c)!7q9l*F_pc;N(fOH^kAK1;a6%{wk)4$6U4l|AVSzSpz#t6J6z3W2Mp3IPPesTVos8q=vfimz?xv$Q|EYANW8KFvk` zVFKnNzth*Ag?wG)bp|0qhlZA8*(fTJnW_|Aq%}#l9Shk8cxoD)nL!E!JH|&KLRUDx z&ihI`vwWVqJ{t>|V81$-W!=+>8h7B7y*7!89#EM#$ZBW}Tx2DIvmRAuydCK;&548y z+wO#V3gEa+4U?Aat(HQ;=_`@Q(hDJcdlyDaWJVvUq+<3leCI2-U! zj8k$tIHxNu(X4sYXbPL!iT0X?GpS2EU4k&K$Awfe{wzg>fa0D$a^Jp>@D#OMAr*h+ zG;lpk`Eoc~GK#RT<%Q>x!`UMWAsonFgPyhC`>CAb1LN2x@lb>YJUe*TxEHLV6Uc?? z)kRxc9*qA~;|XP=A&U@ofBxuKNBkh7I0tZ9lnV&3As}x`^;}C2yEE(AM<60Hc)ENW zNMyR;J_V64IKoo(gNvr4CAxy}8hMI|D68uBw?m1|!?HB9Oh}94c-WyJX`MV+4U3`v zWC8-5Bnw$%b(b2GSgOdAeQ|n8z9iqvE$ku1 zmt&zhz|VBBJD}O}Iz;sH{ay{6u$H8zTSlW{_4V*yWJ#wiAL;?B2_sxt$f8m|-ZCHd zlIN7>y$}J!5--ApsChy0tSf93#K3ACcfem;zlqs&zR4kSJHIORY2ygFYcFgkPEexR z$ctx?z0$|3Y>LjV>r-5PMJ{;|&4Blzd&gG3g*y;2u*6Ei2@A(A#=h z@xnU%czeO?-&)3mbcZoxB6nL%|1GlbaPRP93Q{BZ#V72aHa9n2LxmEfz+Rc`XaUD3 za57mkbS(6w7SMJpYjGbqO{ag=CkYk>g#jY2+`D;>BjuXEIJRP1Fr56s-z@G;+*Az4 zbpQ=fi47$cIOfCP>c4js-*kYeNgeo$ZOXdEoW4$VcVZmUa zuse?W$@E)K)t$4*!=IivX1uET9~Q}bU=O^C60|C%mupr` zaOyBW&mvFao&j#Mw~i_m4^1{JYyzE30cz7uu4;&9?GbMFpfv|kEcdi# zZ@2LL-J7GeV%y>5wE*-Mg1^t(k_usxyzgEf8qrwxzzaOHcy~0eJoLdOA}sK#t|eI%!6#K0lf2RI#qKt$sr*OTX;I(d>e_INOQd>7qLvQoH(~ z;p5|5%4THGfV4|3RxMaE(Tt9U6q5z2g$2Ix(iF@@bqdg_E?9XzmM*Rdm;M)}CWq>D zACbX15mK&`BjxHdH>18=*|g0<0fE(VpG=fRsH0~dC2ioRe`e3_Ls%jKW6~eTceL!H z-@5NjZv5UIjFGw=cE{U?)dy%Pk3p!Py~|w_&Vk3XRM4a-mBAo-yIe+GgF`Z%B|m&~ zZGjjM6@D%?1ZL8R388@HNYervv~k9#vDITD@W<>tGqu#n#{} zg8FKQIzgTFDzt^dqALEsV>MVOCuiKiC+P}R@x3yqZ|^@us#eDA_k)7UZb2;CEK}71-cQz4>O~DNycj4X?CP5`C!mnL zc&K~rF;&9OK-FT#7K4ojC1KwDL~<6oJ+9he$zlc1^jl9YyexjemyP`s?{(jvFNnut7mpW9fz>i3pLxjc;g1Yr5)jHOE?}b@j_H%9?%8IUkA}-i31v+L3G27`Z zsJjqNDuu9-5lJZ@Y`$379y`?WU4!a+Pnzz}dGD76gkA}y9 z*8TxN=ZJA;_bE4YoZMGz^iWu))l}L(@KDgLoW=sJ0VR zkX%J?lfrjy>~OZ}lEt3Zf@KLlcR_h2P%!)CG4R z7aapj0|<2bASrQIP@(1h67t)t!oTRM3Wrm<6LdoW*V5X1abE=5|va zdGVST$#gq~91WxKNX3D)SmNm-ki8!W9yB3_M3LLHlx9hDEI8e>^HOs{I2K7Gyi@l? zi}jR!fd<-YkZU`LvWcgefC=N7p9sw*>JhK^U0Gl!K{#|09fDK7ELaH<%u^XcAvpAf z@I<-)XKpjXHXX)}{5$1g5u}BxvTDOisZDl!nC}WYpdx@*tFg`x92n*h zzV&|lyb-D3$*M(bZjq0Jb!9Rq5n3S0>%x=;EYdx8?oD^Pn7(hmD67xlq*-yKb6lY9 zB?l|9F=wHLQH6SVJzJVmR9f#)VNluQokXZ`|0nA0WV&dA%73~b8mJ23JmXBB*TRO@RPgy-0Mj$`Cv@?3aBfw>E{Vm#*u z($CH1R2?o417v={)0&@F=9APE zJ)8ltC~G5*L1BzEmqwya#+-nY5ycn-nGhI($;i{bN8|-%@76E@*$MPrPb%6?c`{b>mn!o=PHGD#Um+5#R$%pLO@(61S z^8%Gq;RG!V!q$;w`uR-J_ZOfxaJdXmcp*t9)d0X=&akV8(4SLE)R)d(HSZGe=wSkn zFIQO8K#tgx>U5RCttbCI$iK{#)ybGh8;nuA%#$_u{nG{%2Jp-CD4{Kf5=&^HEVS@! zT$ON&CRTD_Ir|pG0sCD&t&V0$B|kj-Z)Kj1<8-|Le=m7kVm`JxX8T_ZzbU}e9Rd3lD7>J$tp8(Qz z%Oy`9HYK-R^8CkQ#(jZWJwItAaey!Xi$0Ifx8*9pyCFxg)&75t`6c#KGAmkNFN@-O z;=w8KU4grx=8{o+Urq!LSSVsioXuI-`lxl*7C`oll>zX#wh@95TZvh4YVX8Esyt7~ znfy-NXjB>de1@;YB4g&>N8R(VVjaHox7BE{6$>S#Q7?2vhtLhQ<-V(zYOiQFjiTQZ zbv7Mg&R6(vgm0c6?+sUI$MF{S-7-Cz1;!G8q7U-Gq1$wpUl!1jL#jDen0* zt%3##3?0lT_pCul1Z9q*(OaSxE9YR%OF}ar=IQSvN+BWDKoc5M9#tr?nD;4xF;MV! z$sT~1WeuQ_LAU0sTbuJDp@QyQup>3Vb-w-SAHx>FL9C9O$OLbAcj61k-uX#O>>T`_ z=)bhey^gpz>^S_$Uk41M%TOx0!U>&3KjocF(K z<_yrnAqYf=(3QM|H#Z=>xfU;)8%tk!z&rdg7HS1)vO$3gdZXnv|p&{}4v#cy!3qLBB9jqlXUjqCWuamA&+$OJCi4$YXKw9Ao6mc&h zkB<%-qPKiC>4}vmSFL^skpALFW9o22b!A~M1m7_(wO&T;z1k=Us7Spmz2#eiWvKPB z%4ARXH}{^dUu&6@C)u){t$(u+?MdR!Y5*LtgBTOcu2#$CncrFi30@aYXWy0wm>tiy zj0brr?D{NT5>{upDw#dtKwDkSqQ%C#D(nc;j9^0QS;<;Fja-rWT@t$4-*gkjbBJAw ziQp$$zc53ApL-c3@nBYIG0gRU<0q?mLk9ZcGfa!3js8YitCZ#{~hUHOxlfvCMv_A2}T`@6tL09yHM zrwa7?cRha!y^CQg9^tC!=}o{yEo>uPy5iV{9r`ZCL$j%f_?oVU$gKxvMqM5ez|y<+ zNL1wO4}V@P{5oj)-?{V>r{3?(PMMYfLO3c4=Uwo?npRudMllD+3AiZ^lkD^@R9;vW-2D!trOR$McEunUU z^<4+`63S>Z^`i*7hJ0@RR?k@%$TM~~b(qzNXl^AxXPLipP8qj-myZA)Si_Xu2W@2} z6@YREcEv$ny**sPGe9KFz$r0NGpOB;3=`q%=bZUef-zrw?kMW`=IibY!>bsOwr&E0 z|HerzfYIR8ABxDAuJr^i*p#zpuy)Zrh?>E{cCS#zu%amkmy)$;4I1lq5|(sY=fE5% zBz0%d$p5S-CD%V)CJ26yk6>qGs(k3i_2mxubb=$ z+WYFisJEzH7(hxXK~PdaKtfO?h8S9eqjV#KN_TgQlENS&-6H9b0@4V=&`1p3E!`b= z59hq^{U7e<@*AVfH}>8up7pF}QIps!P&IRJDGx$jY8;vDFn62u^|0!5)RthYG-buFAul9J@JO8$(1WcvG*lrM}ZVAo@~ z($0{YL{=hv*Z_-SEk-|<^KIq`P;4!XkLXOmlrK!Kym{#N8|Vv~`Q>X*Q9gU~kt zhhv7UHS_05SpO0gc8JRAHsubZqafidbMG4&sT+hVIQW z#g2edOsz9KjR3raqz4L7ddJc_oCyW~zY=s7G1jWIV0ahP&sin0ehd!C+HRO9eHQJt zaq@R$`h;k zM!@{e%_qxUzwjB?Ta}xNR63e>jmPaf>7ClYH<|%{ohj%raymK+H#~0wP`B7FygeoJ zg~0EtZA=c<(TdSbb7$5NyFdD+mQH#U?t5b5ruqH-B^{1NPDTi}?6NNyIaYm8TtsVE z+h+~F%a&T<{cj;4nE0~RoEcj- zTK~6N?P2%3z}&S;OVL!CW0{ARn+a-Y2obFfPWnEOPevj_HSW}$EF~qu?7nXNUAQvA zgJGIJzZF!OvGG0_V+|YOg{KZEiFSiY-V&iA8kJo5W0-r#D`DsyWbj%i_c(NzZ>`ch zx?~CtmN$iEmq7t(m-$LLm+rn3*>V$3R@U|Tiot1d#NrjlGvzbw^W!%ooRwH835g@{ zmyHbc?q8sKj8B0T!Y6_)5Bb=Je`|?~$}27+C52DALlNf=;Xo^G^SM(ung8dit*ms? z8w~&+c*S0C9hIjWKssRgBA)M;LBy*Hur;`MJ7m+W>ra+!C9XsP`pS$z({}{8Vzz}; zG6DkAD7$~6EE(?SG0}#ptBlM3eg4p5gOO!TL+e-cjmI7{08L@3Au@zi$LD^bsJQ94 zK%?3k>%o8H*1d%r50?&}|DzK+Lr8?TERF3i(M7={$+uCpFAPE{NvH}d{&w-ea^@d( zf3^Y8MlW<92mScDw^)bp!rRZ# zkXe}G8xqiOrL8B|`+!f_)aEu9%048OKAwvy^iUn=V#+)RGbA%0cYnt~vFYo_EN}zL zcElnZp<~uGQUO><4BDu$av=L$WrK+{CzB<`Nw$5Dzi1T)k-PR0-4k;!P7wEUo%{9^ z0fI95J7zPu?|HFoe-3lp6LtOm2F_CA`iwqj{NE^rOV~deA&}%Tm^(GZ;lKck)}~zI zX$p*%b=TUaAmrGslUtzTsb0z4q?8L_c2pxA@CDVj2^YRspHO4gx)zNjC(PUaPH*VK z!!w`Hecrr^!O;ysEFI@AIMae~`Nwf6#5SHML5kpm-~LM9!5!y!sNm6fYzKEYnwa_n zq+QiX5Y2h~$U11>D^i|{d-`itRi562O*wUav%&A`@=+v>O4~{M2WIGHVjz?p? z@9oGdOUWllu~Y%{uM&YU8Jzf-z$x(+hWdj>Dg>=f|AV@=eyl9=k@+OfoL|-@x_>J}#xIn13xZVcKmKTuBH`Uoac_)LltciM7W~E38bg5;e5K8G%-G63@4ve#a6CN?!dVRbX@AA`K3wHduKv=_eX)QAt&sj$optYy z{!jgVPmah5YsWsFz8ZA7K7>&bIQwzQ^n?g3??w8m*GB#s8id|)Ez?b=gl`-R(U;?J=#ECKWfK*-#k4$r% z??#6&p!PVPhsMHBSDuS@O#}ct zoH`!n?3;%%61lbBHTwzW^Q4=(czu--%&=N91C4I)tCexqymsUq_(Tg>Z9RPH3!mAFLMHAvk}=-&5}I`W3{nlZ0xH$2)cH4XXEZ~^ zCV;Z##04v3Tt^=41TXG<jQ44r?4-LGGp(63%EqeT|%;P79 z(^{PQfGzDRV08;QiapJ9((U@-U#tF%WW)mB(iJW+d^Gw_P~g-qZKM~qv@&Qd?AU!r zJa;tjrlpo@;ixohv%z=z;YC%$4<}}{wNj4XSO;?4W8LyI+spi0^ddiC&qg561=gT> zx_oM71J8};LO%)t-FA1MiCqtdat0Uj)dUgjAguey}K+0QDc&d&o|LrD6S{ zVho%)%^F~#EQk8l%ACl5lB@x=qDXg5v2H+er@RW5q5bSvoKm}~F^Cy)CuA@$IhNg7=%wk8F1!(8#JYclDUsepl z>Ljs6OZFd!I5gZecYo0oBBku^2(pvOb*98>gX7V7 z$0Muq2UnvfVU~jLOH5^+O+-&S(sO4i{tJS9q$_@7T_qImR1d<-sBEO5Za!^?6 z!^YNkPk)9oU9Qg~CowBX{Z_rY1(;WfJT3;Hu>hTHg2xv?I}zKgba17`VEm86ur*YD z7&;yX6A<-NURV@una4S19o+a92X{Q$#q_V^r~PO|X=N1zN+nV15p$BZLB{V6Vnw(r zMLw_pOLDzU0VoM08L6Ef19~;%T>A!_gLnAyN2@-r&MOZd=g&vjzW_kQzwQ1Jn+omN zNh7P=njBld{l|^bBYv)mk;>a__po7S8&ZlwCD_I3yJFY-xk(yqc7dtFh%b zbA1NXl+UyGs9M540%RQXU0;^`dl1@xQAI*&?D(FIOcxn+ZH?FyTNM?4lSD2+oGbgZ zGKDeoGR^03l>JZw@T}b~bj1GI$okHZrc~GKx~o%!{4b`ggG#n&7o1g*elZBlntvI^ za;gs{>%qR|LcAPq`*OxV#iB;=b)&zhyqL%C!h1jOiX=`6R)_vjePxuHsPxcCuLG;w zZiB0u*35h`+sH}C+oa7nXpSYAWrIPUFc$nhj?jd?j8AR(-hBJgsTwLtgv(hDO4bQ> zYsq?F3aG=~pXTlM0R)|3`a3nq+eV+tAZbe7CShLof)hoi>@i3rXx0%}3QkYQYq`sz z^QppIe&WO>?Y|4`FJL{$uQBnhO?As|h{5@vMxC!kZFCS{T{A^HL1~S&3^K@6azQ%J@ zfNdfp?kw$ ze3QO6=BO`mg?Yj*55WjJ^c{Wc$4Bb`QfeOyWlz;f;x|)@@Q95s);5N0?*Zn+nIHOJ zKMaavQ8<%=67WFlKMfE6XP%&L#O=^`Nv`c#g{tq*e7oWwyL^MLW5}I3Ne7~^v!zB-JKa=mASmRraGsndXMl zTty2u<1A(SIS7A|T<*o&O~f@18tfV_T%lQ%o!}|-9lb$^wmyE2s^&3P$=dfa(27ZH zcr3jEyb^Z{|G=|9?y&+6ypAlT#>lbuO=d6a5<*N(zYgH+}J zmWJT;m~d$FNzuFaRXioXDaru_9R#VjA?#BPpk6A=kRy5>)`HA58AmgTkvEyRS`(^5 zhYv&LAxkqcSrw~&W2~d#)ehs;Y~&cI=ywB~aqo;2j?~mPK%avQm){k}ya#3s$uihA z|Ly{JY_aYww*>mJ`G-2FJ**4d_5qMt3owTz+UesUkM$B1Gw&79k&Fj$X3qvAP`Ch{ z4W@vFDf8cH@N}F(R!%*sFpnx}F`gh1l}Lr|wy}6IQ0^4ywSL{kS`OS zd@~Jrg*0sNb%AHK8xT)%p-F-IwHfSS?#!N`^0i#kg+Df#^_y(1B%``cx6VO)tAiDe8SVhQw3 z3Jv5a3jyO5C>n8aNh4|&Typy?8;S&zL{vze3Gst&(Q0ks6S#=(b@3ZDry$8&MxX=I zTlJq&Nq=bjK^3MJ`p0(R+psoC%oiL%1be@<-E=ejEOYbgz!KN)*4GY(G>d_3GzJnJ zQ&$$(G$Tx9NcGV}kebwe6Bz)2xk1_MV&6x)qoB`Yt<<^wL0p?Dz>;EcsAeTc+$kz~ z3a|by>|`?|^zF*J=~NJi4FmAL-_SJ%8g+&QZ4gbGPA~r1C?)S~xaIK#s3;V3-FfXK z)^)m8WVb#cyyP`~mP)6UzX-B9JB(QxW=onkvIX4ekwc!Uh3MASd|L1U17IVK7>PRM zbniU|%2w8v2vR%->yY#sP5sSr4EJu>rUAg6g#aX8t6D8?!7(;Pu@JC#e;?I^QG7jVd#1?!M_EOe($~ z#ZQBm6#fav2wxVqaJ)0$JzRe%Aaw8xq_rlPVLp|1fcyMZaAF7p!%IS=ZsU*9S?0uD zQxtlzleqPJr941D#-eW}Q?-ifP88tU{i!r1WnH)7Y31Gfh=$l7vMVz*_=v~iRWwRni~w6LayY{5 z`a~WLx~UDuea|+mtO~14yYKwS4szZ_w6XFJc%8v{!XXGH`j$=gR>0 zh+;@O>M@FhW*=7d`V{*5SjgL3aFGpJ%hmkuTr)<7a`)p@$KwnQ=r>FLKEuJmTRC@K^mr!FYn}MASdL;9l?o_>za~MLdL1JD@5z)S5d(I(95jFY_Heyp=)IHJ zz3iaXjbVGY&P-cUJjhHiQEglXQCBY4BS921Hcl}<|kTpm;^C*=ANe?@5SlwQhm|tMEQ)J zRo9NrTR6StmNoA+UhB+;&%yMETQzb>OIOh)k-O#AceCF*qzR%$z;0doc^%;}%U!fO zoQL*wbY%Abh;HOo3>W$M!|#qshzf;qrm@0@FMr56q)hxcxS|QTc;veHq}1j*_|~^F z?j(?zhu)LBr)CjrtTDovaUq_@+i=&`%E%1FvRFw^PxWFN>uE?072rici9*Dp0z$R*Sm%ou3uNfB-K{n5cFUyjlJ7|?<< z`#0Vv-tUTFIedo&Ay_a>7j^Q^n#CiSM`?oUsrsF^f%m8jv0JvIzPh&CknmZ$vxBub z&wKE$$JR%0k$K}^zrdp&GZau;MQH8a4tPbttzW^-O5FFVa>3{a15HbsPs6;rL+yB_ z9pdbiJ}t~=Gz1HRCgwxscyf6%`%8W%b{5*!t#ULuUzEdx4qnEl820Wblth$3kri!3s1=>ZA#-_%J@5!eDfkUy6rx=ea_EoE; zUc^rs$2OIUw>&M!Lr8hg22LaBBFeSLz70C^#zsnvnj32w5aIwtn=OwHTq)afsp(of z9sxE|+jZMFc*L|jk*dOrp0Nf{k2?-ca3BQEGE6n`;VdlvSdas*KbqBgS5|_T$U=CL zK~2T_>wD$7%gPcL8r!egKdQ?qiHeA*p+-1b^jvoFNg24^?=-wK8zcVUuKis{Rj0w% zN9u3jG;je?g$Cna*YqtOJu5BV8c>!n7%6@uV_yvr(K(-mx?;Q4;LK2M*UK8Csag*? z3Sb{~k6-1oB@!jZT5;Ov_s;amGa3k@y{nE&8L)9Xh_`d~J!mVK{3UM_J74Zn_z)KE zm#NLLJQH8a#TLUYa{zh3MONdtquOh=dU?|c3YI;l;&E_ zE325d$i5RdO))gTWy@aSjhi$o6(g%FeP08W|M}-10{6@dd5MEueP^3}b9y8ccb~w- zdGfO#?@F)gj|~v-D&w7i0y44hve5oOy*W6@P7qv}xLJEDnIu*K{B}q^H+@g9B@Uw> z9dZUS^xN>yQ&f(c)ek7_ODl!VTC#=R+7PmD^*BcYLUWdDr?)4cNCXHX#1~Kfo;%f> zM{uP}NSv0b=5?nm5i(7> zBkqjtjd{8J#Nb|Ru$PXHD+%sF2$)p1AmyAx`A|Lpm#T{$nU4Lic=Jf@L7EtqRYYr^ zbZMX1BQ)=BjbUH*w)!6LQ&JflKuQt>P59d)ClcLmVN33{Kuc(60%0r>yJjfqQoFC4 z280Xaj|81pR78PdX0u4cSF6;vMi`K_<%cH;A@t<8F#Ojn5P~csdlc$wDC0iZ#FB=6+uf|1KcVoFb@{2AkZcwG-eSvh48GBJB>O9`Nu=e+wgRt_K0C zz24%c`^g039x7%XNVtZbWk<-2o+*J0sn`NTahKyBs4gkQ#@+YO41!IfRfpt@?5Ik` z4mZY!LC36ym5q&n3Fp2D%wefXvAN%DV=>OKLK$|#y57kcd^0Uabn|Dkb7gQ47DSv^ za%NyJdz~B`m&{xkyGX{U7c?>nZvhndJ+FJJYW}Lj3US@^eWHs40v)}3<_(`I)ZTK@ zY`;ZT*o;@?A5GKJ*Ih=Qh zmYQ^m*gf(<)_Wq@O4rEqJT0qlyIh_uj~5!$%nj@|q8LC^s5^AyL)cbDd3i#ZW3~X* zU$oI1hMV7POzFXKii(g_5B9kUOc9y6V*p5{s#hv6E_qesI;+*y3J)|&hAex&7QoQi zTS}3Opm5B6T$?;Iv&R#iMC?&L&u`TFk*{Z^Fy=)~_53{cODP4$K{qh{0FUaghUXT@ z!zyR)V$b&?HZPqu`SWn&sKD!&zO8DNYC(1w!-cwfg=oWP%|T6sy~pE@pzhTr zi;j)xe;$=|Ckc(;Ru+4sZQ%07qi>9_RS{7w@RlMxlNbeo5Iil%3Q$%z^u2)qM~o?o zE&W7-Q#w!3bzMh&r?2N_z`K63vq?JOQKvhyFSPCmDbtWot(NOcNA-C~=+WsqyWs+E60diRadh!Z=rozfAE2&c^0XX); zq6RH!J7NCySp?@80}q(H!LAgQKBFL|G4#?%T^i>b_14NtF=#^=0Nf3fESGDJr9}tQV&5&=bzKcP242+W=5R_JbD} z4y8>%w?dkcS4sEJdAz4NFrCE9Pfa>vj-7`J4QLTL6Le`3m&YudP9PO*-FoR&0zizP zMbo;9YfU2HIHfN^ScP(-P<&a;^Ry{q;4aSN^OUe)fJyoM3Xcrp-Q?ln!D}e{G=?c% zJEYyB6^z;c%jwSPA#+QM+pu0NxeQWL=XKO7|DA371Pra1d%Xm(t%&KQ!?`#^-_SEm zD>ssO4P#vsG0t=8XhIlV3;e1_I04*qHmX>RHYwsRKbzR@qLlvyz!fTtP$c?wp5+#h zD}bg@D_MXr@o?oUB0Dve0_PO~0+w{Ax^Ny0%-bche_f>F()vwE{uI&5pR3#8d!cru zUhoBw6$?)2Irf|i@$UqL_K;h?(mC|FdkL(Oz&plCR@)o_(MrYwaZ z@<;{fecrfL)h=LyK2_eKUt&3-=iJj1+nFsO^p5G0QlKBCyvfPIJxnQ#>92ZI2I<0x zaJbUoV56q?;&Zh&KSKD_qvJ_E2?A^kjJ0@E=bnu=|a#KuSIa z#sg`g|89qE@F5G<&t3qcsgTipOYI0go} z8u6QU6@&U$?2P8^V~+47hA--SP}m{ByuPfn>y_9|!)W$sPH05-`>Xi^L0(QtX=uXUol8$}|hKJ`7u24V>qYvpjqMGM{=Ol%c=6 zgaos0d0^dMRzYbn>jqo~l}@$u-}}RT3NS%=`m`~)Xe7pqaRDz@mb#8H?BFh|DOTDW z<>eGy@D*%&Q^f_%|D+F=a2icy%7r&o04n!b%t8S8D*|I4$(hdwR5Qo_K8`WBN;e&2 zN~W3*2ofG9Zvcf2BOrzFx;=qW*uL=wDTDRd(N-mxiZu>=pW}9sv6=b02QM>?h+vd}QF>rH3B>_0ol%^(xy=o)9T^)RZ{9Af-Bld${ptxj z5H#(<2To1dzcJ^e5X$llv&kgWpQnokAf|G$D9&Ad1Q04W&^-+#4f(sFB0B@iC<;0v9Z?p zEq$0h@E-gzl`O<%um%v(qUpIsI{WVznx|9$@d|KtCEJ^v4FipDFf7uf1vUNLFE QvA~aloRVyz^y_#32jv8rPXGV_ literal 0 HcmV?d00001 diff --git a/tests/test_point_cloud_sampling.py b/tests/test_point_cloud_sampling.py new file mode 100644 index 0000000000..8f6447c69c --- /dev/null +++ b/tests/test_point_cloud_sampling.py @@ -0,0 +1,15 @@ +import conftest # Add root path to sys.path +from Mapping.point_cloud_sampling import point_cloud_sampling as m + + +def test_1(capsys): + m.do_plot = False + m.main() + captured = capsys.readouterr() + assert "voxel_sampling_points.shape=(27, 3)" in captured.out + assert "farthest_sampling_points.shape=(20, 3)" in captured.out + assert "poisson_disk_points.shape=(20, 3)" in captured.out + + +if __name__ == '__main__': + conftest.run_this_test(__file__) From ad4067df891b2d65c22f4cbf75cc0d16f5584612 Mon Sep 17 00:00:00 2001 From: U S A M A H <39458672+usamah1@users.noreply.github.com> Date: Sun, 8 Jan 2023 13:04:51 +0000 Subject: [PATCH 561/940] Change 'Path is find!' to 'Path found!' (#773) Minor - correct grammatical error :) --- PathPlanning/AStar/a_star_searching_from_two_side.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/AStar/a_star_searching_from_two_side.py b/PathPlanning/AStar/a_star_searching_from_two_side.py index 0318970cc8..822f5ea500 100644 --- a/PathPlanning/AStar/a_star_searching_from_two_side.py +++ b/PathPlanning/AStar/a_star_searching_from_two_side.py @@ -267,7 +267,7 @@ def draw_control(org_closed, goal_closed, flag, start, end, bound, obstacle): if node_intersect: # a path is find path = get_path(org_closed, goal_closed, node_intersect[0]) stop_loop = 1 - print('Path is find!') + print('Path found!') if show_animation: # draw the path plt.plot(path[:, 0], path[:, 1], '-r') plt.title('Robot Arrived', size=20, loc='center') From 98d5851c4da12bdb7c500682e32cfb5277adc782 Mon Sep 17 00:00:00 2001 From: Kadir Haspalamutgil <31936408+kadirhas@users.noreply.github.com> Date: Sun, 8 Jan 2023 15:46:46 +0100 Subject: [PATCH 562/940] Utilize numpy to reduce calculation time (#767) * Utilize numpy to reduce calculation time Change-Id: I6e421a1c2524a3d8f8875121a1a6d2ed832c3150 * styling updates to follow flake8 Change-Id: I909d49b40e6792efcb796846c97a0d984471d3c9 * improves readabilty for d_star_lite Change-Id: Ic329c2140f2200b49feeb03c588d7a805b96cbdc * removes self.detected_obstacles Change-Id: I4a0f2a424f17f44de3b444cb9c2e8e715d761d34 * styling for flake8 Change-Id: Id55c5972cbe76a2f6a69527dbf770f9bdf059109 Co-authored-by: Kadir Haspalamutgil --- PathPlanning/DStarLite/d_star_lite.py | 95 +++++++++++++++++---------- 1 file changed, 62 insertions(+), 33 deletions(-) diff --git a/PathPlanning/DStarLite/d_star_lite.py b/PathPlanning/DStarLite/d_star_lite.py index c250e38f91..86e777d7b7 100644 --- a/PathPlanning/DStarLite/d_star_lite.py +++ b/PathPlanning/DStarLite/d_star_lite.py @@ -12,6 +12,7 @@ import math import matplotlib.pyplot as plt import random +import numpy as np show_animation = True pause_time = 0.001 @@ -62,32 +63,40 @@ def __init__(self, ox: list, oy: list): self.y_max = int(abs(max(oy) - self.y_min_world)) self.obstacles = [Node(x - self.x_min_world, y - self.y_min_world) for x, y in zip(ox, oy)] + self.obstacles_xy = np.array( + [[obstacle.x, obstacle.y] for obstacle in self.obstacles] + ) self.start = Node(0, 0) self.goal = Node(0, 0) self.U = list() # type: ignore self.km = 0.0 self.kold = 0.0 - self.rhs = list() # type: ignore - self.g = list() # type: ignore - self.detected_obstacles = list() # type: ignore + self.rhs = self.create_grid(float("inf")) + self.g = self.create_grid(float("inf")) + self.detected_obstacles_xy = np.empty((0, 2)) + self.xy = np.empty((0, 2)) if show_animation: self.detected_obstacles_for_plotting_x = list() # type: ignore self.detected_obstacles_for_plotting_y = list() # type: ignore + self.initialized = False def create_grid(self, val: float): - grid = list() - for _ in range(0, self.x_max): - grid_row = list() - for _ in range(0, self.y_max): - grid_row.append(val) - grid.append(grid_row) - return grid + return np.full((self.x_max, self.y_max), val) def is_obstacle(self, node: Node): - return any([compare_coordinates(node, obstacle) - for obstacle in self.obstacles]) or \ - any([compare_coordinates(node, obstacle) - for obstacle in self.detected_obstacles]) + x = np.array([node.x]) + y = np.array([node.y]) + obstacle_x_equal = self.obstacles_xy[:, 0] == x + obstacle_y_equal = self.obstacles_xy[:, 1] == y + is_in_obstacles = (obstacle_x_equal & obstacle_y_equal).any() + + is_in_detected_obstacles = False + if self.detected_obstacles_xy.shape[0] > 0: + is_x_equal = self.detected_obstacles_xy[:, 0] == x + is_y_equal = self.detected_obstacles_xy[:, 1] == y + is_in_detected_obstacles = (is_x_equal & is_y_equal).any() + + return is_in_obstacles or is_in_detected_obstacles def c(self, node1: Node, node2: Node): if self.is_obstacle(node2): @@ -139,13 +148,16 @@ def initialize(self, start: Node, goal: Node): self.start.y = start.y - self.y_min_world self.goal.x = goal.x - self.x_min_world self.goal.y = goal.y - self.y_min_world - self.U = list() # Would normally be a priority queue - self.km = 0.0 - self.rhs = self.create_grid(math.inf) - self.g = self.create_grid(math.inf) - self.rhs[self.goal.x][self.goal.y] = 0 - self.U.append((self.goal, self.calculate_key(self.goal))) - self.detected_obstacles = list() + if not self.initialized: + self.initialized = True + print('Initializing') + self.U = list() # Would normally be a priority queue + self.km = 0.0 + self.rhs = self.create_grid(math.inf) + self.g = self.create_grid(math.inf) + self.rhs[self.goal.x][self.goal.y] = 0 + self.U.append((self.goal, self.calculate_key(self.goal))) + self.detected_obstacles_xy = np.empty((0, 2)) def update_vertex(self, u: Node): if not compare_coordinates(u, self.goal): @@ -167,26 +179,33 @@ def compare_keys(self, key_pair1: tuple[float, float], def compute_shortest_path(self): self.U.sort(key=lambda x: x[1]) - while (len(self.U) > 0 and - self.compare_keys(self.U[0][1], - self.calculate_key(self.start))) or \ - self.rhs[self.start.x][self.start.y] != \ - self.g[self.start.x][self.start.y]: + has_elements = len(self.U) > 0 + start_key_not_updated = self.compare_keys( + self.U[0][1], self.calculate_key(self.start) + ) + rhs_not_equal_to_g = self.rhs[self.start.x][self.start.y] != \ + self.g[self.start.x][self.start.y] + while has_elements and start_key_not_updated or rhs_not_equal_to_g: self.kold = self.U[0][1] u = self.U[0][0] self.U.pop(0) if self.compare_keys(self.kold, self.calculate_key(u)): self.U.append((u, self.calculate_key(u))) self.U.sort(key=lambda x: x[1]) - elif self.g[u.x][u.y] > self.rhs[u.x][u.y]: - self.g[u.x][u.y] = self.rhs[u.x][u.y] + elif (self.g[u.x, u.y] > self.rhs[u.x, u.y]).any(): + self.g[u.x, u.y] = self.rhs[u.x, u.y] for s in self.pred(u): self.update_vertex(s) else: - self.g[u.x][u.y] = math.inf + self.g[u.x, u.y] = math.inf for s in self.pred(u) + [u]: self.update_vertex(s) self.U.sort(key=lambda x: x[1]) + start_key_not_updated = self.compare_keys( + self.U[0][1], self.calculate_key(self.start) + ) + rhs_not_equal_to_g = self.rhs[self.start.x][self.start.y] != \ + self.g[self.start.x][self.start.y] def detect_changes(self): changed_vertices = list() @@ -196,7 +215,12 @@ def detect_changes(self): compare_coordinates(spoofed_obstacle, self.goal): continue changed_vertices.append(spoofed_obstacle) - self.detected_obstacles.append(spoofed_obstacle) + self.detected_obstacles_xy = np.concatenate( + ( + self.detected_obstacles_xy, + [[spoofed_obstacle.x, spoofed_obstacle.y]] + ) + ) if show_animation: self.detected_obstacles_for_plotting_x.append( spoofed_obstacle.x + self.x_min_world) @@ -210,14 +234,19 @@ def detect_changes(self): # Allows random generation of obstacles random.seed() if random.random() > 1 - p_create_random_obstacle: - x = random.randint(0, self.x_max) - y = random.randint(0, self.y_max) + x = random.randint(0, self.x_max - 1) + y = random.randint(0, self.y_max - 1) new_obs = Node(x, y) if compare_coordinates(new_obs, self.start) or \ compare_coordinates(new_obs, self.goal): return changed_vertices changed_vertices.append(Node(x, y)) - self.detected_obstacles.append(Node(x, y)) + self.detected_obstacles_xy = np.concatenate( + ( + self.detected_obstacles_xy, + [[x, y]] + ) + ) if show_animation: self.detected_obstacles_for_plotting_x.append(x + self.x_min_world) From 0f50d84ce6493ac192de9a743f6b51485dff0bd5 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 10 Jan 2023 07:04:10 +0900 Subject: [PATCH 563/940] Bump scipy from 1.9.3 to 1.10.0 in /requirements (#775) Bumps [scipy](https://github.com/scipy/scipy) from 1.9.3 to 1.10.0. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.9.3...v1.10.0) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 9a990856f1..b613447ba7 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.24.1 -scipy == 1.9.3 +scipy == 1.10.0 matplotlib == 3.6.2 cvxpy == 1.2.3 pytest == 7.2.0 # For unit test From c8b0698a88a7b72f7d3e0725136acb30f514ed52 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 10 Jan 2023 07:05:36 +0900 Subject: [PATCH 564/940] Bump cvxpy from 1.2.3 to 1.3.0 in /requirements (#776) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.2.3 to 1.3.0. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.2.3...v1.3.0) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b613447ba7..3f44e47f21 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.24.1 scipy == 1.10.0 matplotlib == 3.6.2 -cvxpy == 1.2.3 +cvxpy == 1.3.0 pytest == 7.2.0 # For unit test pytest-xdist == 3.1.0 # For unit test mypy == 0.991 # For unit test From 5a16a113c703c9e9a88daf1c681ececb67f7f95c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 17 Jan 2023 07:28:31 +0900 Subject: [PATCH 565/940] Bump matplotlib from 3.6.2 to 3.6.3 in /requirements (#778) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.6.2 to 3.6.3. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.6.2...v3.6.3) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 3f44e47f21..a2b9663b2d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.24.1 scipy == 1.10.0 -matplotlib == 3.6.2 +matplotlib == 3.6.3 cvxpy == 1.3.0 pytest == 7.2.0 # For unit test pytest-xdist == 3.1.0 # For unit test From 15ab19688b2f6c03ee91a853f1f8cc9def84d162 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 17 Jan 2023 07:28:49 +0900 Subject: [PATCH 566/940] Bump pytest from 7.2.0 to 7.2.1 in /requirements (#779) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.2.0 to 7.2.1. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.2.0...7.2.1) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a2b9663b2d..944c1ce217 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.24.1 scipy == 1.10.0 matplotlib == 3.6.3 cvxpy == 1.3.0 -pytest == 7.2.0 # For unit test +pytest == 7.2.1 # For unit test pytest-xdist == 3.1.0 # For unit test mypy == 0.991 # For unit test flake8 == 5.0.4 # For unit test From 489ee5c0e367a64f19b6cf3875ea6282e78bf889 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 26 Jan 2023 21:56:42 +0900 Subject: [PATCH 567/940] fix github scanning alerts (#784) --- .../two_joint_arm_to_point_control.py | 2 +- Bipedal/bipedal_planner/bipedal_planner.py | 1 - PathPlanning/HybridAStar/dynamic_programming_heuristic.py | 2 +- PathPlanning/InformedRRTStar/informed_rrt_star.py | 5 ++--- PathPlanning/LQRPlanner/lqr_planner.py | 2 +- PathPlanning/LQRRRTStar/lqr_rrt_star.py | 2 +- PathPlanning/RRT/rrt_with_pathsmoothing.py | 6 +++--- PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py | 6 +++--- 8 files changed, 12 insertions(+), 14 deletions(-) diff --git a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py index 9f835c8b32..012a7f72f1 100644 --- a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py +++ b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py @@ -45,7 +45,7 @@ def two_joint_arm(GOAL_TH=0.0, theta1=0.0, theta2=0.0): if x is not None and y is not None: x_prev = x y_prev = y - if np.sqrt(x**2 + y**2) > (l1 + l2): + if np.hypot(x, y) > (l1 + l2): theta2_goal = 0 else: theta2_goal = np.arccos( diff --git a/Bipedal/bipedal_planner/bipedal_planner.py b/Bipedal/bipedal_planner/bipedal_planner.py index 8ca5ffcf78..c34357df67 100644 --- a/Bipedal/bipedal_planner/bipedal_planner.py +++ b/Bipedal/bipedal_planner/bipedal_planner.py @@ -47,7 +47,6 @@ def walk(self, t_sup=0.8, z_c=0.8, a=10, b=1, plot=False): return # set up plotter - com_trajectory_for_plot, ax = None, None if plot: fig = plt.figure() ax = Axes3D(fig) diff --git a/PathPlanning/HybridAStar/dynamic_programming_heuristic.py b/PathPlanning/HybridAStar/dynamic_programming_heuristic.py index 8a78b15d5f..09bcd556a6 100644 --- a/PathPlanning/HybridAStar/dynamic_programming_heuristic.py +++ b/PathPlanning/HybridAStar/dynamic_programming_heuristic.py @@ -150,7 +150,7 @@ def calc_obstacle_map(ox, oy, resolution, vr): y = iy + min_y # print(x, y) for iox, ioy in zip(ox, oy): - d = math.sqrt((iox - x) ** 2 + (ioy - y) ** 2) + d = math.hypot(iox - x, ioy - y) if d <= vr / resolution: obstacle_map[ix][iy] = True break diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 25c50a0cd2..289e33fe4b 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -192,7 +192,7 @@ def get_path_len(path): @staticmethod def line_cost(node1, node2): - return math.sqrt((node1.x - node2.x) ** 2 + (node1.y - node2.y) ** 2) + return math.hypot(node1.x - node2.x, node1.y - node2.y) @staticmethod def get_nearest_list_index(nodes, rnd): @@ -222,8 +222,7 @@ def rewire(self, newNode, nearInds): for i in nearInds: nearNode = self.node_list[i] - d = math.sqrt((nearNode.x - newNode.x) ** 2 - + (nearNode.y - newNode.y) ** 2) + d = math.hypot(nearNode.x - newNode.x, nearNode.y - newNode.y) s_cost = newNode.cost + d diff --git a/PathPlanning/LQRPlanner/lqr_planner.py b/PathPlanning/LQRPlanner/lqr_planner.py index ba01526a2c..0f58f93ea3 100644 --- a/PathPlanning/LQRPlanner/lqr_planner.py +++ b/PathPlanning/LQRPlanner/lqr_planner.py @@ -47,7 +47,7 @@ def lqr_planning(self, sx, sy, gx, gy, show_animation=True): rx.append(x[0, 0] + gx) ry.append(x[1, 0] + gy) - d = math.sqrt((gx - rx[-1]) ** 2 + (gy - ry[-1]) ** 2) + d = math.hypot(gx - rx[-1], gy - ry[-1]) if d <= self.GOAL_DIST: found_path = True break diff --git a/PathPlanning/LQRRRTStar/lqr_rrt_star.py b/PathPlanning/LQRRRTStar/lqr_rrt_star.py index e3f18a722a..0ed08123ea 100644 --- a/PathPlanning/LQRRRTStar/lqr_rrt_star.py +++ b/PathPlanning/LQRRRTStar/lqr_rrt_star.py @@ -179,7 +179,7 @@ def sample_path(self, wx, wy, step): dx = np.diff(px) dy = np.diff(py) - clen = [math.sqrt(idx ** 2 + idy ** 2) for (idx, idy) in zip(dx, dy)] + clen = [math.hypot(idx, idy) for (idx, idy) in zip(dx, dy)] return px, py, clen diff --git a/PathPlanning/RRT/rrt_with_pathsmoothing.py b/PathPlanning/RRT/rrt_with_pathsmoothing.py index 616c73a697..2ed6a366d1 100644 --- a/PathPlanning/RRT/rrt_with_pathsmoothing.py +++ b/PathPlanning/RRT/rrt_with_pathsmoothing.py @@ -23,7 +23,7 @@ def get_path_length(path): for i in range(len(path) - 1): dx = path[i + 1][0] - path[i][0] dy = path[i + 1][1] - path[i][1] - d = math.sqrt(dx * dx + dy * dy) + d = math.hypot(dx, dy) le += d return le @@ -36,7 +36,7 @@ def get_target_point(path, targetL): for i in range(len(path) - 1): dx = path[i + 1][0] - path[i][0] dy = path[i + 1][1] - path[i][1] - d = math.sqrt(dx * dx + dy * dy) + d = math.hypot(dx, dy) le += d if le >= targetL: ti = i - 1 @@ -67,7 +67,7 @@ def line_collision_check(first, second, obstacleList): return False for (ox, oy, size) in obstacleList: - d = abs(a * ox + b * oy + c) / (math.sqrt(a * a + b * b)) + d = abs(a * ox + b * oy + c) / (math.hypot(a, b)) if d <= size: return False diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py index 5bc04c8ee3..1577d048d3 100644 --- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py +++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py @@ -57,13 +57,13 @@ def straight_left_straight(x, y, phi): xd = - y / math.tan(phi) + x t = xd - math.tan(phi / 2.0) u = phi - v = math.sqrt((x - xd) ** 2 + y ** 2) - math.tan(phi / 2.0) + v = math.hypot(x - xd, y) - math.tan(phi / 2.0) return True, t, u, v elif y < 0.0 < phi < math.pi * 0.99: xd = - y / math.tan(phi) + x t = xd - math.tan(phi / 2.0) u = phi - v = -math.sqrt((x - xd) ** 2 + y ** 2) - math.tan(phi / 2.0) + v = -math.hypot(x - xd, y) - math.tan(phi / 2.0) return True, t, u, v return False, 0.0, 0.0, 0.0 @@ -103,7 +103,7 @@ def straight_curve_straight(x, y, phi, paths, step_size): def polar(x, y): - r = math.sqrt(x ** 2 + y ** 2) + r = math.hypot(x, y) theta = math.atan2(y, x) return r, theta From 732ed3ea6be5856b10727aac0e0f3724dad02d5a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 26 Jan 2023 22:46:00 +0900 Subject: [PATCH 568/940] clean up informed_rrt_star.py (#785) * clean up informed_rrt_star.py * clean up informed_rrt_star.py --- .../InformedRRTStar/informed_rrt_star.py | 261 +++++++++--------- 1 file changed, 126 insertions(+), 135 deletions(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 289e33fe4b..4f0ec31988 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -11,6 +11,7 @@ """ import sys import pathlib + sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) import copy @@ -27,18 +28,17 @@ class InformedRRTStar: - def __init__(self, start, goal, - obstacleList, randArea, - expandDis=0.5, goalSampleRate=10, maxIter=200): + def __init__(self, start, goal, obstacle_list, rand_area, expand_dis=0.5, + goal_sample_rate=10, max_iter=200): self.start = Node(start[0], start[1]) self.goal = Node(goal[0], goal[1]) - self.min_rand = randArea[0] - self.max_rand = randArea[1] - self.expand_dis = expandDis - self.goal_sample_rate = goalSampleRate - self.max_iter = maxIter - self.obstacle_list = obstacleList + self.min_rand = rand_area[0] + self.max_rand = rand_area[1] + self.expand_dis = expand_dis + self.goal_sample_rate = goal_sample_rate + self.max_iter = max_iter + self.obstacle_list = obstacle_list self.node_list = None def informed_rrt_star_search(self, animation=True): @@ -46,110 +46,109 @@ def informed_rrt_star_search(self, animation=True): self.node_list = [self.start] # max length we expect to find in our 'informed' sample space, # starts as infinite - cBest = float('inf') - solutionSet = set() + c_best = float('inf') + solution_set = set() path = None # Computing the sampling space - cMin = math.sqrt(pow(self.start.x - self.goal.x, 2) - + pow(self.start.y - self.goal.y, 2)) - xCenter = np.array([[(self.start.x + self.goal.x) / 2.0], - [(self.start.y + self.goal.y) / 2.0], [0]]) - a1 = np.array([[(self.goal.x - self.start.x) / cMin], - [(self.goal.y - self.start.y) / cMin], [0]]) + c_min = math.hypot(self.start.x - self.goal.x, + self.start.y - self.goal.y) + x_center = np.array([[(self.start.x + self.goal.x) / 2.0], + [(self.start.y + self.goal.y) / 2.0], [0]]) + a1 = np.array([[(self.goal.x - self.start.x) / c_min], + [(self.goal.y - self.start.y) / c_min], [0]]) e_theta = math.atan2(a1[1], a1[0]) # first column of identity matrix transposed id1_t = np.array([1.0, 0.0, 0.0]).reshape(1, 3) - M = a1 @ id1_t - U, S, Vh = np.linalg.svd(M, True, True) - C = np.dot(np.dot(U, np.diag( - [1.0, 1.0, np.linalg.det(U) * np.linalg.det(np.transpose(Vh))])), - Vh) + m = a1 @ id1_t + u, s, vh = np.linalg.svd(m, True, True) + c = u @ np.diag( + [1.0, 1.0, + np.linalg.det(u) * np.linalg.det(np.transpose(vh))]) @ vh for i in range(self.max_iter): - # Sample space is defined by cBest - # cMin is the minimum distance between the start point and the goal - # xCenter is the midpoint between the start and the goal - # cBest changes when a new path is found + # Sample space is defined by c_best + # c_min is the minimum distance between the start point and + # the goal x_center is the midpoint between the start and the + # goal c_best changes when a new path is found - rnd = self.informed_sample(cBest, cMin, xCenter, C) + rnd = self.informed_sample(c_best, c_min, x_center, c) n_ind = self.get_nearest_list_index(self.node_list, rnd) - nearestNode = self.node_list[n_ind] + nearest_node = self.node_list[n_ind] # steer - theta = math.atan2(rnd[1] - nearestNode.y, rnd[0] - nearestNode.x) - newNode = self.get_new_node(theta, n_ind, nearestNode) - d = self.line_cost(nearestNode, newNode) + theta = math.atan2(rnd[1] - nearest_node.y, + rnd[0] - nearest_node.x) + new_node = self.get_new_node(theta, n_ind, nearest_node) + d = self.line_cost(nearest_node, new_node) - noCollision = self.check_collision(nearestNode, theta, d) + no_collision = self.check_collision(nearest_node, theta, d) - if noCollision: - nearInds = self.find_near_nodes(newNode) - newNode = self.choose_parent(newNode, nearInds) + if no_collision: + near_inds = self.find_near_nodes(new_node) + new_node = self.choose_parent(new_node, near_inds) - self.node_list.append(newNode) - self.rewire(newNode, nearInds) + self.node_list.append(new_node) + self.rewire(new_node, near_inds) - if self.is_near_goal(newNode): - if self.check_segment_collision(newNode.x, newNode.y, + if self.is_near_goal(new_node): + if self.check_segment_collision(new_node.x, new_node.y, self.goal.x, self.goal.y): - solutionSet.add(newNode) - lastIndex = len(self.node_list) - 1 - tempPath = self.get_final_course(lastIndex) - tempPathLen = self.get_path_len(tempPath) - if tempPathLen < cBest: - path = tempPath - cBest = tempPathLen + solution_set.add(new_node) + last_index = len(self.node_list) - 1 + temp_path = self.get_final_course(last_index) + temp_path_len = self.get_path_len(temp_path) + if temp_path_len < c_best: + path = temp_path + c_best = temp_path_len if animation: - self.draw_graph(xCenter=xCenter, - cBest=cBest, cMin=cMin, + self.draw_graph(x_center=x_center, c_best=c_best, c_min=c_min, e_theta=e_theta, rnd=rnd) return path - def choose_parent(self, newNode, nearInds): - if len(nearInds) == 0: - return newNode + def choose_parent(self, new_node, near_inds): + if len(near_inds) == 0: + return new_node - dList = [] - for i in nearInds: - dx = newNode.x - self.node_list[i].x - dy = newNode.y - self.node_list[i].y + d_list = [] + for i in near_inds: + dx = new_node.x - self.node_list[i].x + dy = new_node.y - self.node_list[i].y d = math.hypot(dx, dy) theta = math.atan2(dy, dx) if self.check_collision(self.node_list[i], theta, d): - dList.append(self.node_list[i].cost + d) + d_list.append(self.node_list[i].cost + d) else: - dList.append(float('inf')) + d_list.append(float('inf')) - minCost = min(dList) - minInd = nearInds[dList.index(minCost)] + min_cost = min(d_list) + min_ind = near_inds[d_list.index(min_cost)] - if minCost == float('inf'): + if min_cost == float('inf'): print("min cost is inf") - return newNode + return new_node - newNode.cost = minCost - newNode.parent = minInd + new_node.cost = min_cost + new_node.parent = min_ind - return newNode + return new_node - def find_near_nodes(self, newNode): + def find_near_nodes(self, new_node): n_node = len(self.node_list) r = 50.0 * math.sqrt((math.log(n_node) / n_node)) - d_list = [(node.x - newNode.x) ** 2 + (node.y - newNode.y) ** 2 - for node in self.node_list] + d_list = [(node.x - new_node.x) ** 2 + (node.y - new_node.y) ** 2 for + node in self.node_list] near_inds = [d_list.index(i) for i in d_list if i <= r ** 2] return near_inds - def informed_sample(self, cMax, cMin, xCenter, C): - if cMax < float('inf'): - r = [cMax / 2.0, - math.sqrt(cMax ** 2 - cMin ** 2) / 2.0, - math.sqrt(cMax ** 2 - cMin ** 2) / 2.0] - L = np.diag(r) - xBall = self.sample_unit_ball() - rnd = np.dot(np.dot(C, L), xBall) + xCenter + def informed_sample(self, c_max, c_min, x_center, c): + if c_max < float('inf'): + r = [c_max / 2.0, math.sqrt(c_max ** 2 - c_min ** 2) / 2.0, + math.sqrt(c_max ** 2 - c_min ** 2) / 2.0] + rl = np.diag(r) + x_ball = self.sample_unit_ball() + rnd = np.dot(np.dot(c, rl), x_ball) + x_center rnd = [rnd[(0, 0)], rnd[(1, 0)]] else: rnd = self.sample_free_space() @@ -179,16 +178,15 @@ def sample_free_space(self): @staticmethod def get_path_len(path): - pathLen = 0 + path_len = 0 for i in range(1, len(path)): node1_x = path[i][0] node1_y = path[i][1] node2_x = path[i - 1][0] node2_y = path[i - 1][1] - pathLen += math.sqrt((node1_x - node2_x) - ** 2 + (node1_y - node2_y) ** 2) + path_len += math.hypot(node1_x - node2_x, node1_y - node2_y) - return pathLen + return path_len @staticmethod def line_cost(node1, node2): @@ -196,20 +194,20 @@ def line_cost(node1, node2): @staticmethod def get_nearest_list_index(nodes, rnd): - dList = [(node.x - rnd[0]) ** 2 - + (node.y - rnd[1]) ** 2 for node in nodes] - minIndex = dList.index(min(dList)) - return minIndex + d_list = [(node.x - rnd[0]) ** 2 + (node.y - rnd[1]) ** 2 for node in + nodes] + min_index = d_list.index(min(d_list)) + return min_index - def get_new_node(self, theta, n_ind, nearestNode): - newNode = copy.deepcopy(nearestNode) + def get_new_node(self, theta, n_ind, nearest_node): + new_node = copy.deepcopy(nearest_node) - newNode.x += self.expand_dis * math.cos(theta) - newNode.y += self.expand_dis * math.sin(theta) + new_node.x += self.expand_dis * math.cos(theta) + new_node.y += self.expand_dis * math.sin(theta) - newNode.cost += self.expand_dis - newNode.parent = n_ind - return newNode + new_node.cost += self.expand_dis + new_node.parent = n_ind + return new_node def is_near_goal(self, node): d = self.line_cost(node, self.goal) @@ -217,21 +215,21 @@ def is_near_goal(self, node): return True return False - def rewire(self, newNode, nearInds): + def rewire(self, new_node, near_inds): n_node = len(self.node_list) - for i in nearInds: - nearNode = self.node_list[i] + for i in near_inds: + near_node = self.node_list[i] - d = math.hypot(nearNode.x - newNode.x, nearNode.y - newNode.y) + d = math.hypot(near_node.x - new_node.x, near_node.y - new_node.y) - s_cost = newNode.cost + d + s_cost = new_node.cost + d - if nearNode.cost > s_cost: - theta = math.atan2(newNode.y - nearNode.y, - newNode.x - nearNode.x) - if self.check_collision(nearNode, theta, d): - nearNode.parent = n_node - 1 - nearNode.cost = s_cost + if near_node.cost > s_cost: + theta = math.atan2(new_node.y - near_node.y, + new_node.x - near_node.x) + if self.check_collision(near_node, theta, d): + near_node.parent = n_node - 1 + near_node.cost = s_cost @staticmethod def distance_squared_point_to_segment(v, w, p): @@ -251,45 +249,44 @@ def distance_squared_point_to_segment(v, w, p): def check_segment_collision(self, x1, y1, x2, y2): for (ox, oy, size) in self.obstacle_list: dd = self.distance_squared_point_to_segment( - np.array([x1, y1]), - np.array([x2, y2]), - np.array([ox, oy])) + np.array([x1, y1]), np.array([x2, y2]), np.array([ox, oy])) if dd <= size ** 2: return False # collision return True - def check_collision(self, nearNode, theta, d): - tmpNode = copy.deepcopy(nearNode) - end_x = tmpNode.x + math.cos(theta) * d - end_y = tmpNode.y + math.sin(theta) * d - return self.check_segment_collision(tmpNode.x, tmpNode.y, end_x, end_y) + def check_collision(self, near_node, theta, d): + tmp_node = copy.deepcopy(near_node) + end_x = tmp_node.x + math.cos(theta) * d + end_y = tmp_node.y + math.sin(theta) * d + return self.check_segment_collision(tmp_node.x, tmp_node.y, + end_x, end_y) - def get_final_course(self, lastIndex): + def get_final_course(self, last_index): path = [[self.goal.x, self.goal.y]] - while self.node_list[lastIndex].parent is not None: - node = self.node_list[lastIndex] + while self.node_list[last_index].parent is not None: + node = self.node_list[last_index] path.append([node.x, node.y]) - lastIndex = node.parent + last_index = node.parent path.append([self.start.x, self.start.y]) return path - def draw_graph(self, xCenter=None, cBest=None, cMin=None, e_theta=None, + def draw_graph(self, x_center=None, c_best=None, c_min=None, e_theta=None, rnd=None): plt.clf() # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect( - 'key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + 'key_release_event', lambda event: + [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd[0], rnd[1], "^k") - if cBest != float('inf'): - self.plot_ellipse(xCenter, cBest, cMin, e_theta) + if c_best != float('inf'): + self.plot_ellipse(x_center, c_best, c_min, e_theta) for node in self.node_list: if node.parent is not None: if node.x or node.y is not None: - plt.plot([node.x, self.node_list[node.parent].x], [ - node.y, self.node_list[node.parent].y], "-g") + plt.plot([node.x, self.node_list[node.parent].x], + [node.y, self.node_list[node.parent].y], "-g") for (ox, oy, size) in self.obstacle_list: plt.plot(ox, oy, "ok", ms=30 * size) @@ -301,13 +298,13 @@ def draw_graph(self, xCenter=None, cBest=None, cMin=None, e_theta=None, plt.pause(0.01) @staticmethod - def plot_ellipse(xCenter, cBest, cMin, e_theta): # pragma: no cover + def plot_ellipse(x_center, c_best, c_min, e_theta): # pragma: no cover - a = math.sqrt(cBest ** 2 - cMin ** 2) / 2.0 - b = cBest / 2.0 + a = math.sqrt(c_best ** 2 - c_min ** 2) / 2.0 + b = c_best / 2.0 angle = math.pi / 2.0 - e_theta - cx = xCenter[0] - cy = xCenter[1] + cx = x_center[0] + cy = x_center[1] t = np.arange(0, 2 * math.pi + 0.1, 0.1) x = [a * math.cos(it) for it in t] y = [b * math.sin(it) for it in t] @@ -331,18 +328,12 @@ def main(): print("Start informed rrt star planning") # create obstacles - obstacleList = [ - (5, 5, 0.5), - (9, 6, 1), - (7, 5, 1), - (1, 5, 1), - (3, 6, 1), - (7, 9, 1) - ] + obstacle_list = [(5, 5, 0.5), (9, 6, 1), (7, 5, 1), (1, 5, 1), (3, 6, 1), + (7, 9, 1)] # Set params - rrt = InformedRRTStar(start=[0, 0], goal=[5, 10], - randArea=[-2, 15], obstacleList=obstacleList) + rrt = InformedRRTStar(start=[0, 0], goal=[5, 10], rand_area=[-2, 15], + obstacle_list=obstacle_list) path = rrt.informed_rrt_star_search(animation=show_animation) print("Done!!") From ffd8602e25d16f7801421310ca6892f08531042e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 29 Jan 2023 22:22:11 +0900 Subject: [PATCH 569/940] support python3.11 (#741) * support python3.11 * try to fix error * try to fix error * try to fix error * try to fix error * try to fix error * try to fix error * try to fix error * try to fix error * try to fix error * add docs * fix conflict * fix conflict * fix conflict * using python3.10 for appveyors * add windows CI * roll back appveyor settings * fix windows CI --- .circleci/config.yml | 2 +- .github/workflows/Linux_CI.yml | 2 +- .github/workflows/MacOS_CI.yml | 2 +- .github/workflows/Windows_CI.yml | 36 ++++++++++++++++++++++++++++++++ README.md | 2 +- docs/getting_started_main.rst | 4 ++-- requirements/environment.yml | 2 +- 7 files changed, 43 insertions(+), 7 deletions(-) create mode 100644 .github/workflows/Windows_CI.yml diff --git a/.circleci/config.yml b/.circleci/config.yml index 075a613be0..d8f1e89dc4 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -6,7 +6,7 @@ orbs: jobs: build_doc: docker: - - image: cimg/python:3.10 + - image: cimg/python:3.11 steps: - checkout - run: diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index 83c55b17f1..a7b5aba5fe 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -12,7 +12,7 @@ jobs: runs-on: ubuntu-latest strategy: matrix: - python-version: [ '3.10.6' ] # For mypy error Ref: https://github.com/python/mypy/issues/13627 + python-version: [ '3.11' ] name: Python ${{ matrix.python-version }} CI diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index a3459f2560..6f0849a43d 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -16,7 +16,7 @@ jobs: runs-on: macos-latest strategy: matrix: - python-version: [ '3.10.6' ] # For mypy error Ref: https://github.com/python/mypy/issues/13627 + python-version: [ '3.11' ] name: Python ${{ matrix.python-version }} CI steps: - uses: actions/checkout@v2 diff --git a/.github/workflows/Windows_CI.yml b/.github/workflows/Windows_CI.yml new file mode 100644 index 0000000000..ed267045ca --- /dev/null +++ b/.github/workflows/Windows_CI.yml @@ -0,0 +1,36 @@ +# This is a basic workflow to help you get started with Actions + +name: Windows_CI + +# Controls when the action will run. Triggers the workflow on push or pull request +# events but only for the master branch +on: + push: + branches: + - master + pull_request: + + +jobs: + build: + runs-on: windows-latest + strategy: + matrix: + python-version: [ '3.11' ] + name: Python ${{ matrix.python-version }} CI + steps: + - uses: actions/checkout@v2 + - run: git fetch --prune --unshallow + + - name: Setup python + uses: actions/setup-python@v2 + with: + python-version: ${{ matrix.python-version }} + + - name: Install dependencies + run: | + python --version + python -m pip install --upgrade pip + pip install -r requirements/requirements.txt + - name: do all unit tests + run: bash runtests.sh \ No newline at end of file diff --git a/README.md b/README.md index b46195f35e..4ad19353e3 100644 --- a/README.md +++ b/README.md @@ -96,7 +96,7 @@ See this paper for more details: For running each sample code: -- [Python 3.10.x](https://www.python.org/) +- [Python 3.11.x](https://www.python.org/) - [NumPy](https://numpy.org/) diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index c2be93261b..0e90d672b7 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -26,7 +26,7 @@ See this paper for more details: Requirements ------------- -- `Python 3.10.x`_ +- `Python 3.11.x`_ - `NumPy`_ - `SciPy`_ - `Matplotlib`_ @@ -40,7 +40,7 @@ For development: - sphinx (for document generation) - pycodestyle (for code style check) -.. _`Python 3.10.x`: https://www.python.org/ +.. _`Python 3.11.x`: https://www.python.org/ .. _`NumPy`: https://numpy.org/ .. _`SciPy`: https://scipy.org/ .. _`Matplotlib`: https://matplotlib.org/ diff --git a/requirements/environment.yml b/requirements/environment.yml index 202c2693d9..13dfa29f66 100644 --- a/requirements/environment.yml +++ b/requirements/environment.yml @@ -2,7 +2,7 @@ name: python_robotics channels: - conda-forge dependencies: - - python=3.10 + - python=3.11 - pip - scipy - numpy From 15a91900608199e9bccdf68b04786b30f6772ad5 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 30 Jan 2023 21:33:49 +0900 Subject: [PATCH 570/940] using ruff instead of flake8 (#787) * using ruff instead of flake8 * using ruff instead of flake8 * using ruff instead of flake8 --- docs/conf.py | 1 - docs/getting_started_main.rst | 15 ++++--- requirements/requirements.txt | 2 +- ruff.toml | 18 ++++++++ ...st_diff_codestyle.py => test_codestyle.py} | 45 ++++++++++++++----- 5 files changed, 62 insertions(+), 19 deletions(-) create mode 100644 ruff.toml rename tests/{test_diff_codestyle.py => test_codestyle.py} (78%) diff --git a/docs/conf.py b/docs/conf.py index 24b5518b6f..e7c64d07b2 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -1,4 +1,3 @@ -# -*- coding: utf-8 -*- # # Configuration file for the Sphinx documentation builder. # diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index 0e90d672b7..497b85a23a 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -34,17 +34,22 @@ Requirements For development: -- pytest (for unit tests) -- pytest-xdist (for parallel unit tests) -- mypy (for type check) -- sphinx (for document generation) -- pycodestyle (for code style check) +- `pytest`_ (for unit tests) +- `pytest-xdist`_ (for parallel unit tests) +- `mypy`_ (for type check) +- `sphinx`_ (for document generation) +- `ruff`_ (for code style check) .. _`Python 3.11.x`: https://www.python.org/ .. _`NumPy`: https://numpy.org/ .. _`SciPy`: https://scipy.org/ .. _`Matplotlib`: https://matplotlib.org/ .. _`cvxpy`: https://www.cvxpy.org/ +.. _`pytest`: https://docs.pytest.org/en/latest/ +.. _`pytest-xdist`: https://github.com/pytest-dev/pytest-xdist +.. _`mypy`: https://mypy-lang.org/ +.. _`sphinx`: https://www.sphinx-doc.org/en/master/index.html +.. _`ruff`: https://github.com/charliermarsh/ruff How to use diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 944c1ce217..a3a337a198 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.0 pytest == 7.2.1 # For unit test pytest-xdist == 3.1.0 # For unit test mypy == 0.991 # For unit test -flake8 == 5.0.4 # For unit test +ruff == 0.0.237 # For unit test diff --git a/ruff.toml b/ruff.toml new file mode 100644 index 0000000000..fd02032f48 --- /dev/null +++ b/ruff.toml @@ -0,0 +1,18 @@ +line-length = 88 + +select = ["F", "E", "W", "UP"] +ignore = ["E501", "E741"] +exclude = [ +] + +# Assume Python 3.11 +target-version = "py311" + +[per-file-ignores] + +[mccabe] +# Unlike Flake8, default to a complexity level of 10. +max-complexity = 10 + +[pydocstyle] +convention = "numpy" \ No newline at end of file diff --git a/tests/test_diff_codestyle.py b/tests/test_codestyle.py similarity index 78% rename from tests/test_diff_codestyle.py rename to tests/test_codestyle.py index 89c228e285..2ad3816ea1 100644 --- a/tests/test_diff_codestyle.py +++ b/tests/test_codestyle.py @@ -1,8 +1,8 @@ """ -Diff based code style checker with flake8 +Diff code style checker with ruff This code come from: -https://github.com/scipy/scipy/blob/main/tools/lint_diff.py +https://github.com/scipy/scipy/blob/main/tools/lint.py Scipy's licence: https://github.com/scipy/scipy/blob/main/LICENSE.txt Copyright (c) 2001-2002 Enthought, Inc. 2003-2022, SciPy Developers. @@ -37,9 +37,30 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. """ import conftest +import os import subprocess +CONFIG = os.path.join( + os.path.abspath(os.path.dirname(os.path.dirname(__file__))), + 'ruff.toml', +) + +ROOT_DIR = os.path.abspath(os.path.dirname(os.path.dirname(__file__))) + + +def run_ruff(files, fix): + if not files: + return 0, "" + args = ['--fix'] if fix else [] + res = subprocess.run( + ['ruff', f'--config={CONFIG}'] + args + files, + stdout=subprocess.PIPE, + encoding='utf-8' + ) + return res.returncode, res.stdout + + def rev_list(branch, num_commits): """List commits in reverse chronological order. Only the first `num_commits` are shown. @@ -89,23 +110,23 @@ def find_diff(sha): return res.stdout -def run_flake8(diff): - """Run flake8 on the given diff.""" +def diff_files(sha): + """Find the diff since the given SHA.""" res = subprocess.run( - ['flake8', '--diff', '--ignore', - 'E402' # top level import for sys.path.append - ], - input=diff, + ['git', 'diff', '--name-only', '--diff-filter=ACMR', '-z', sha, '--', + '*.py', '*.pyx', '*.pxd', '*.pxi'], stdout=subprocess.PIPE, - encoding='utf-8', + encoding='utf-8' ) - return res.returncode, res.stdout + res.check_returncode() + return [os.path.join(ROOT_DIR, f) for f in res.stdout.split('\0') if f] def test(): branch_commit = find_branch_point("origin/master") - diff = find_diff(branch_commit) - rc, errors = run_flake8(diff) + files = diff_files(branch_commit) + print(files) + rc, errors = run_ruff(files, fix=False) if errors: print(errors) else: From 7c1a92a8e5d2c9e0a961728e2cb008c3a4747e58 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 Feb 2023 07:21:09 +0900 Subject: [PATCH 571/940] Bump ruff from 0.0.237 to 0.0.241 in /requirements (#788) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.237 to 0.0.241. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.237...v0.0.241) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a3a337a198..1e8a407a20 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.0 pytest == 7.2.1 # For unit test pytest-xdist == 3.1.0 # For unit test mypy == 0.991 # For unit test -ruff == 0.0.237 # For unit test +ruff == 0.0.241 # For unit test From f9b2fb62afb5f974cbd2ee90434d6ab8c4f6140f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 Feb 2023 07:24:15 +0900 Subject: [PATCH 572/940] Bump numpy from 1.24.1 to 1.24.2 in /requirements (#790) Bumps [numpy](https://github.com/numpy/numpy) from 1.24.1 to 1.24.2. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.24.1...v1.24.2) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 1e8a407a20..0bff2c7b5a 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.24.1 +numpy == 1.24.2 scipy == 1.10.0 matplotlib == 3.6.3 cvxpy == 1.3.0 From c627f881a88c47ed6b90c90a9353e38c76d31d7c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 Feb 2023 21:49:10 +0900 Subject: [PATCH 573/940] Bump mypy from 0.991 to 1.0.0 in /requirements (#789) Bumps [mypy](https://github.com/python/mypy) from 0.991 to 1.0.0. - [Release notes](https://github.com/python/mypy/releases) - [Commits](https://github.com/python/mypy/compare/v0.991...v1.0.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 0bff2c7b5a..01bcab20f6 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.6.3 cvxpy == 1.3.0 pytest == 7.2.1 # For unit test pytest-xdist == 3.1.0 # For unit test -mypy == 0.991 # For unit test +mypy == 1.0.0 # For unit test ruff == 0.0.241 # For unit test From 3c1162561ae4ae95b4f946fd75f84d198b7ff8d2 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sat, 11 Feb 2023 10:48:51 +0900 Subject: [PATCH 574/940] Bump ipython from 7.31.1 to 8.10.0 in /docs (#791) Bumps [ipython](https://github.com/ipython/ipython) from 7.31.1 to 8.10.0. - [Release notes](https://github.com/ipython/ipython/releases) - [Commits](https://github.com/ipython/ipython/compare/7.31.1...8.10.0) --- updated-dependencies: - dependency-name: ipython dependency-type: direct:production ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- docs/doc_requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/doc_requirements.txt b/docs/doc_requirements.txt index b8702ee750..c01b596539 100644 --- a/docs/doc_requirements.txt +++ b/docs/doc_requirements.txt @@ -1,4 +1,4 @@ sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 -IPython == 7.31.1 # For sphinx documentation +IPython == 8.10.0 # For sphinx documentation sphinxcontrib-napoleon == 0.7 # For auto doc From 06bb1d82121a7c4c9d906ced5f60adc14c12810e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 14 Feb 2023 20:07:02 +0900 Subject: [PATCH 575/940] Bump ruff from 0.0.241 to 0.0.246 in /requirements (#792) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.241 to 0.0.246. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.241...v0.0.246) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 01bcab20f6..2f1aa41f29 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.0 pytest == 7.2.1 # For unit test pytest-xdist == 3.1.0 # For unit test mypy == 1.0.0 # For unit test -ruff == 0.0.241 # For unit test +ruff == 0.0.246 # For unit test From ebc1d3d2f3bd3c273da94f74da383390cdb35ce9 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 14 Feb 2023 20:07:31 +0900 Subject: [PATCH 576/940] Bump pytest-xdist from 3.1.0 to 3.2.0 in /requirements (#793) Bumps [pytest-xdist](https://github.com/pytest-dev/pytest-xdist) from 3.1.0 to 3.2.0. - [Release notes](https://github.com/pytest-dev/pytest-xdist/releases) - [Changelog](https://github.com/pytest-dev/pytest-xdist/blob/master/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest-xdist/compare/v3.1.0...v3.2.0) --- updated-dependencies: - dependency-name: pytest-xdist dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 2f1aa41f29..ed3e084c58 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,6 +3,6 @@ scipy == 1.10.0 matplotlib == 3.6.3 cvxpy == 1.3.0 pytest == 7.2.1 # For unit test -pytest-xdist == 3.1.0 # For unit test +pytest-xdist == 3.2.0 # For unit test mypy == 1.0.0 # For unit test ruff == 0.0.246 # For unit test From 5641a491b95c4a5f90315b71cd01792319af0032 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Feb 2023 07:25:57 +0900 Subject: [PATCH 577/940] Bump ruff from 0.0.246 to 0.0.249 in /requirements (#794) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.246 to 0.0.249. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.246...v0.0.249) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index ed3e084c58..b3dcf0458a 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.0 pytest == 7.2.1 # For unit test pytest-xdist == 3.2.0 # For unit test mypy == 1.0.0 # For unit test -ruff == 0.0.246 # For unit test +ruff == 0.0.249 # For unit test From fa254376f6017a6f62701bf56758431bc574cf89 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Feb 2023 07:26:14 +0900 Subject: [PATCH 578/940] Bump scipy from 1.10.0 to 1.10.1 in /requirements (#797) Bumps [scipy](https://github.com/scipy/scipy) from 1.10.0 to 1.10.1. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.10.0...v1.10.1) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b3dcf0458a..8e537c44bc 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.24.2 -scipy == 1.10.0 +scipy == 1.10.1 matplotlib == 3.6.3 cvxpy == 1.3.0 pytest == 7.2.1 # For unit test From f79bc4e139a70d42f4317846c1d5b1254e0761a5 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Feb 2023 08:45:48 +0900 Subject: [PATCH 579/940] Bump mypy from 1.0.0 to 1.0.1 in /requirements (#795) Bumps [mypy](https://github.com/python/mypy) from 1.0.0 to 1.0.1. - [Release notes](https://github.com/python/mypy/releases) - [Commits](https://github.com/python/mypy/compare/v1.0.0...v1.0.1) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 8e537c44bc..05b7c9aa13 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.6.3 cvxpy == 1.3.0 pytest == 7.2.1 # For unit test pytest-xdist == 3.2.0 # For unit test -mypy == 1.0.0 # For unit test +mypy == 1.0.1 # For unit test ruff == 0.0.249 # For unit test From 9269e190c27f7e146190b4a3c082d04ccf32bc94 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Feb 2023 12:45:30 +0900 Subject: [PATCH 580/940] Bump matplotlib from 3.6.3 to 3.7.0 in /requirements (#796) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.6.3 to 3.7.0. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.6.3...v3.7.0) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 05b7c9aa13..afda81a29a 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.24.2 scipy == 1.10.1 -matplotlib == 3.6.3 +matplotlib == 3.7.0 cvxpy == 1.3.0 pytest == 7.2.1 # For unit test pytest-xdist == 3.2.0 # For unit test From 3f5b973d6cb508faf707f18cfcb76b4a4c324215 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 Mar 2023 19:06:13 +0900 Subject: [PATCH 581/940] Bump ruff from 0.0.249 to 0.0.254 in /requirements (#798) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.249 to 0.0.254. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.249...v0.0.254) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index afda81a29a..5eb5d69364 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.0 pytest == 7.2.1 # For unit test pytest-xdist == 3.2.0 # For unit test mypy == 1.0.1 # For unit test -ruff == 0.0.249 # For unit test +ruff == 0.0.254 # For unit test From 6e2f3df1d88731730028a78c834daf41c54669c8 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 Mar 2023 20:49:11 +0900 Subject: [PATCH 582/940] Bump matplotlib from 3.7.0 to 3.7.1 in /requirements (#800) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.7.0 to 3.7.1. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.7.0...v3.7.1) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 5eb5d69364..141c14198b 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.24.2 scipy == 1.10.1 -matplotlib == 3.7.0 +matplotlib == 3.7.1 cvxpy == 1.3.0 pytest == 7.2.1 # For unit test pytest-xdist == 3.2.0 # For unit test From 1f96f4eb55c5860d00bbefd83a28b59e0b07e128 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 8 Mar 2023 07:57:25 +0900 Subject: [PATCH 583/940] Bump pytest from 7.2.1 to 7.2.2 in /requirements (#799) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.2.1 to 7.2.2. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.2.1...7.2.2) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 141c14198b..35798d7e86 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.24.2 scipy == 1.10.1 matplotlib == 3.7.1 cvxpy == 1.3.0 -pytest == 7.2.1 # For unit test +pytest == 7.2.2 # For unit test pytest-xdist == 3.2.0 # For unit test mypy == 1.0.1 # For unit test ruff == 0.0.254 # For unit test From cb08c39a9388c90290b797014f0663c0ed53d2f7 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 11 Mar 2023 17:54:18 +0900 Subject: [PATCH 584/940] Add Normal vector estimation (#781) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * add normal vector calculation routine. * add normal vector calculation routine. * add normal vector estimation * fix unittests in not matplotlib frontend * fix lint ci * add ransac based normal distribution estimation * add normal_vector_estimation_main.rst * normal_vector_estimation_main.rst を更新 * update normal_vector_estimation_main.rst * update normal_vector_estimation_main.rst * normal_vector_estimation_main.rst * normal_vector_estimation_main.rst を更新 * add normal_vector_estimation_main.rst * add normal_vector_estimation_main.rst * add normal_vector_estimation_main.rst * add normal_vector_estimation_main.rst * add normal_vector_estimation_main.rst * add normal_vector_estimation_main.rst * add normal_vector_estimation_main.rst * add normal_vector_estimation_main.rst * add normal_vector_estimation_main.rst --- .../rrt_star_seven_joint_arm_control.py | 6 +- .../normal_vector_estimation.py | 177 ++++++++++++++++++ .../dynamic_window_approach.py | 3 +- PathPlanning/RRTStar/rrt_star.py | 4 +- .../VisibilityRoadMap/visibility_road_map.py | 5 +- docs/modules/mapping/mapping_main.rst | 2 +- .../normal_vector_calc.png | Bin 0 -> 96411 bytes .../normal_vector_estimation_main.rst | 74 ++++++++ .../ransac_normal_vector_estimation.png | Bin 0 -> 282297 bytes ruff.toml | 2 +- tests/test_normal_vector_estimation.py | 19 ++ utils/plot.py | 79 ++++++++ 12 files changed, 360 insertions(+), 11 deletions(-) create mode 100644 Mapping/normal_vector_estimation/normal_vector_estimation.py create mode 100644 docs/modules/mapping/normal_vector_estimation/normal_vector_calc.png create mode 100644 docs/modules/mapping/normal_vector_estimation/normal_vector_estimation_main.rst create mode 100644 docs/modules/mapping/normal_vector_estimation/ransac_normal_vector_estimation.png create mode 100644 tests/test_normal_vector_estimation.py diff --git a/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py b/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py index fca55184da..0f449bbe51 100755 --- a/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py +++ b/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py @@ -5,7 +5,6 @@ import math import random import numpy as np -from mpl_toolkits import mplot3d import matplotlib.pyplot as plt import sys import pathlib @@ -79,8 +78,9 @@ def __init__(self, start, goal, robot, obstacle_list, rand_area, self.obstacle_list = obstacle_list self.connect_circle_dist = connect_circle_dist self.goal_node = self.Node(goal) - self.ax = plt.axes(projection='3d') self.node_list = [] + if show_animation: + self.ax = plt.axes(projection='3d') def planning(self, animation=False, search_until_max_iter=False): """ @@ -176,7 +176,7 @@ def search_best_goal_node(self): def find_near_nodes(self, new_node): nnode = len(self.node_list) + 1 - r = self.connect_circle_dist * math.sqrt((math.log(nnode) / nnode)) + r = self.connect_circle_dist * math.sqrt(math.log(nnode) / nnode) # if expand_dist exists, search vertices in # a range no more than expand_dist if hasattr(self, 'expand_dis'): diff --git a/Mapping/normal_vector_estimation/normal_vector_estimation.py b/Mapping/normal_vector_estimation/normal_vector_estimation.py new file mode 100644 index 0000000000..996ba3ffee --- /dev/null +++ b/Mapping/normal_vector_estimation/normal_vector_estimation.py @@ -0,0 +1,177 @@ +import numpy as np +from matplotlib import pyplot as plt + +from utils.plot import plot_3d_vector_arrow, plot_triangle, set_equal_3d_axis + +show_animation = True + + +def calc_normal_vector(p1, p2, p3): + """Calculate normal vector of triangle + + Parameters + ---------- + p1 : np.array + 3D point + p2 : np.array + 3D point + p3 : np.array + 3D point + + Returns + ------- + normal_vector : np.array + normal vector (3,) + + """ + # calculate two vectors of triangle + v1 = p2 - p1 + v2 = p3 - p1 + + # calculate normal vector + normal_vector = np.cross(v1, v2) + + # normalize vector + normal_vector = normal_vector / np.linalg.norm(normal_vector) + + return normal_vector + + +def sample_3d_points_from_a_plane(num_samples, normal): + points_2d = np.random.normal(size=(num_samples, 2)) # 2D points on a plane + d = 0 + for i in range(len(points_2d)): + point_3d = np.append(points_2d[i], 0) + d += normal @ point_3d + d /= len(points_2d) + + points_3d = np.zeros((len(points_2d), 3)) + for i in range(len(points_2d)): + point_2d = np.append(points_2d[i], 0) + projection_length = (d - normal @ point_2d) / np.linalg.norm(normal) + points_3d[i] = point_2d + projection_length * normal + + return points_3d + + +def distance_to_plane(point, normal, origin): + dot_product = np.dot(normal, point) - np.dot(normal, origin) + if np.isclose(dot_product, 0): + return 0.0 + else: + distance = abs(dot_product) / np.linalg.norm(normal) + return distance + + +def ransac_normal_vector_estimation(points_3d, inlier_radio_th=0.7, + inlier_dist=0.1, p=0.99): + """ + RANSAC based normal vector estimation + + Parameters + ---------- + points_3d : np.array + 3D points (N, 3) + inlier_radio_th : float + Inlier ratio threshold. If inlier ratio is larger than this value, + the iteration is stopped. Default is 0.7. + inlier_dist : float + Inlier distance threshold. If distance between points and estimated + plane is smaller than this value, the point is inlier. Default is 0.1. + p : float + Probability that at least one of the sets of random samples does not + include an outlier. If this probability is near 1, the iteration + number is large. Default is 0.99. + + Returns + ------- + center_vector : np.array + Center of estimated plane. (3,) + normal_vector : np.array + Normal vector of estimated plane. (3,) + + """ + center = np.mean(points_3d, axis=0) + + max_iter = int(np.floor(np.log(1.0-p)/np.log(1.0-(1.0-inlier_radio_th)**3))) + + for ite in range(max_iter): + # Random sampling + sampled_ids = np.random.choice(points_3d.shape[0], size=3, + replace=False) + sampled_points = points_3d[sampled_ids, :] + p1 = sampled_points[0, :] + p2 = sampled_points[1, :] + p3 = sampled_points[2, :] + normal_vector = calc_normal_vector(p1, p2, p3) + + # calc inlier ratio + n_inliner = 0 + for i in range(points_3d.shape[0]): + p = points_3d[i, :] + if distance_to_plane(p, normal_vector, center) <= inlier_dist: + n_inliner += 1 + inlier_ratio = n_inliner / points_3d.shape[0] + print(f"Iter:{ite}, {inlier_ratio=}") + if inlier_ratio > inlier_radio_th: + return center, normal_vector + + return center, None + + +def main1(): + p1 = np.array([0.0, 0.0, 1.0]) + p2 = np.array([1.0, 1.0, 0.0]) + p3 = np.array([0.0, 1.0, 0.0]) + + center = np.mean([p1, p2, p3], axis=0) + normal_vector = calc_normal_vector(p1, p2, p3) + print(f"{center=}") + print(f"{normal_vector=}") + + if show_animation: + fig = plt.figure() + ax = fig.add_subplot(projection='3d') + set_equal_3d_axis(ax, [0.0, 2.5], [0.0, 2.5], [0.0, 3.0]) + plot_triangle(p1, p2, p3, ax) + ax.plot(center[0], center[1], center[2], "ro") + plot_3d_vector_arrow(ax, center, center + normal_vector) + plt.show() + + +def main2(rng=None): + true_normal = np.array([0, 1, 1]) + true_normal = true_normal / np.linalg.norm(true_normal) + num_samples = 100 + noise_scale = 0.1 + + points_3d = sample_3d_points_from_a_plane(num_samples, true_normal) + # add random noise + points_3d += np.random.normal(size=points_3d.shape, scale=noise_scale) + + print(f"{points_3d.shape=}") + + center, estimated_normal = ransac_normal_vector_estimation( + points_3d, inlier_dist=noise_scale) + + if estimated_normal is None: + print("Failed to estimate normal vector") + return + + print(f"{true_normal=}") + print(f"{estimated_normal=}") + + if show_animation: + fig = plt.figure() + ax = fig.add_subplot(projection='3d') + ax.plot(points_3d[:, 0], points_3d[:, 1], points_3d[:, 2], ".r") + plot_3d_vector_arrow(ax, center, center + true_normal) + plot_3d_vector_arrow(ax, center, center + estimated_normal) + set_equal_3d_axis(ax, [-3.0, 3.0], [-3.0, 3.0], [-3.0, 3.0]) + plt.title("RANSAC based Normal vector estimation") + plt.show() + + +if __name__ == '__main__': + # main1() + main2() diff --git a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py index 74ff064e86..8664ec1745 100644 --- a/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py +++ b/PathPlanning/DynamicWindowApproach/dynamic_window_approach.py @@ -300,8 +300,7 @@ def main(gx=10.0, gy=10.0, robot_type=RobotType.circle): if show_animation: plt.plot(trajectory[:, 0], trajectory[:, 1], "-r") plt.pause(0.0001) - - plt.show() + plt.show() if __name__ == '__main__': diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index a7aad49d60..f875d3a76d 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -186,7 +186,7 @@ def find_near_nodes(self, new_node): radius r """ nnode = len(self.node_list) + 1 - r = self.connect_circle_dist * math.sqrt((math.log(nnode) / nnode)) + r = self.connect_circle_dist * math.sqrt(math.log(nnode) / nnode) # if expand_dist exists, search vertices in a range no more than # expand_dist if hasattr(self, 'expand_dis'): @@ -280,7 +280,7 @@ def main(): rrt_star.draw_graph() plt.plot([x for (x, y) in path], [y for (x, y) in path], 'r--') plt.grid(True) - plt.show() + plt.show() if __name__ == '__main__': diff --git a/PathPlanning/VisibilityRoadMap/visibility_road_map.py b/PathPlanning/VisibilityRoadMap/visibility_road_map.py index e9f8733c83..5f7ffadd16 100644 --- a/PathPlanning/VisibilityRoadMap/visibility_road_map.py +++ b/PathPlanning/VisibilityRoadMap/visibility_road_map.py @@ -62,8 +62,9 @@ def generate_visibility_nodes(self, start_x, start_y, goal_x, goal_y, for (vx, vy) in zip(cvx_list, cvy_list): nodes.append(DijkstraSearch.Node(vx, vy)) - for node in nodes: - plt.plot(node.x, node.y, "xr") + if self.do_plot: + for node in nodes: + plt.plot(node.x, node.y, "xr") return nodes diff --git a/docs/modules/mapping/mapping_main.rst b/docs/modules/mapping/mapping_main.rst index 14a7cce70d..1c02c75cb2 100644 --- a/docs/modules/mapping/mapping_main.rst +++ b/docs/modules/mapping/mapping_main.rst @@ -13,4 +13,4 @@ Mapping k_means_object_clustering/k_means_object_clustering circle_fitting/circle_fitting rectangle_fitting/rectangle_fitting - + normal_vector_estimation/normal_vector_estimation diff --git a/docs/modules/mapping/normal_vector_estimation/normal_vector_calc.png b/docs/modules/mapping/normal_vector_estimation/normal_vector_calc.png new file mode 100644 index 0000000000000000000000000000000000000000..63e2cdade70313466314c1f2ce37e6968910d830 GIT binary patch literal 96411 zcmeFZ^iId5nT`2aJM(7K(Kj zI5U7KNk>7!$+wl0(^8g`qt|kBu(GwYL_tvsiBH6YX|EBzx$$xk!)Cz-MH9Uy&L);t z!Qy%|P=JIpOS3cF^$(^oFmC)p&*)G3ghb0xCzMkNQp$yMTtgogT*ggihpfY;_OIQk zJNcRFyxg7G(S3PvvvPgXjqwK29j7#4YKbz?YA~Q>qG{!##z`!NVk(URF-0S!mC|m) z$HzxUs*N>tT|7detP@#5;@=0*pG-lQgpqQ%>Z?XTu5*2$*j)0n7Kjv{@G@V#O& zh<)`^F_~MQ3UW3r!lu68C&H%2dsnRm9^|Bzdq_frFd0_f~?@?+=`GCqrY=Y{Z{b>^!gEB`vys6^(Kj&EvMjjHb-C@*kbNkuLA zslHCJdw!1z*3t2}LF?D!eu3J=6cD}jtERdS56G}t=h;LImdW{AFV!?QNpL-$qV7*t zc)rz6W8a_a+^~4noTs0(MkCZZ5UzD*81fk3E7Wsf&DHV~$jPrPnxiB$m74Zp>lmWl zQ#&o0l8l$8Ip!j#Ow02|wzOpButswKTb{LVl?g~MBQ>6Sn{DQiLyh0ZB#9>i0*2G6 z(yL1nG{g*1i58xnBeB^ST?>J>^-g|PZb{<8xIXlG&H+o-Nlga?8PC3>-lxB(^T5TXG*6B0mCT7rgkRzVpTU|$d zV|2a7dyZ7%=n^03>d>2KB`5;vu?V2_l-c-e((j^0E$)=k3%66@z-2#Du+ysew?yL^ z;ui&met3qY9>>&?YmjF9=-g+C#H}GXk`3siS``TYZjprlqETVjE(xQ24n>6eDGFO- z*qpHl-85EWWBjh!SCAy8NuWcs#IC9bI%+Ulle7y67ar&sP0viG49RX+$tHXt4~`Mb z##obn$tclIxQ`vs+{ddHj`0IyAt>bgE?*cQ2OkyhQj%Pfg4&~H)?9Ld@UwS0rVmS( z^{qL{sUp;yxEsk#RZDe7?`~pj+S^GTOW+5Y&xXH>6p=E<Zk|B-Nh4?O3 z7Q_<4(4R~JAt6j85(W_v8U>GpT(v-BaXOL~RdCpHqKBh9m0YuNvlX+eaBy&5<7nV8 z;4lUb;aK7*l5#&d1bZ`TcUW2Ai$-!XIWW^PXR^$&HRNcqE07SVaI%Dz#XMFQ)%27- zLn>)kz!t$cBzg~Y*@eJv9QBVG!S}(X@nqm7a6FhsuclZqTMZ`kc$xj+y&hPPJrh=6 zAdZmLF4e_;tgJWo;c=Fe!ICJc=0n75ZH!;u>%Qxr&*|=cTpJV-l(gsCLfJwq%8bmS z8mvAfc@4V4`W7cysG{>lI|9}NEz*+68E=-RP{8A6iYN_v75*w{&-2|d-Z9=>_>sW6 zl}qpG2O;eqId!BiQn$p-XscXId&)>c$0zJ{+`0L^@OQ}y!9R#1rYOk;-&qY<*K{xT za;ACOE#FbsA5;^7IVUgs_Pj`8G8{LoHzX>eF`FfwpM;fe586faTs*Z z1#g*>QyBTs!&FJo;yx?YOW{r4OH&Iw63dF8$d1+O(iFZCk&&;%r!m;AEmIby$~hfe z+G!8E1czJ_*X{|7c29GT6*g_wh}vzNa`VqvPCvwb)McCCp}SOAOJ;#vDPJjHBwxbP z%-_e~Th_5ZWEU`2T3*$?opjaHISuYve={WaBL7Q+Yldss5fzmHRlRy(50_DBQPdWA z!fIl~ZP`t>cFOH!)ArbTYhNqK`zZMd_TcyIPxAhH`!^ol!4{Hi=>`A6Bnd?;D>~AAjYWnx8tZIr_R$b1=y< zmHB$r3rjp-{O)M(CdskcF^49H<|pfb70gHhYmAjb^7*9=ozASD#<)&d-|2IWjadkTUej7Re~?T$%jZ<*7vrvu+!OW_ue_1SUzbRYa?x$ zGBB;9w{Bbtq{JO0%P`EY2(DW75EqgJ*Rx*Z@&xO3P$|!{ZmLl%JD*OR@nF#U6E%M5 z)6wUoR&r72)bP$&OsRNi%R44fE$FG#0*ViNns=JBseBeq`TjMpD<>DYNHRT|Hq-a9 z8fjkWgg}LW6Mqf!ax9v1@3WQG2{HoJJJ~wPTFd_3%ba3j6i?!k+kK;ttZFUwEc}d# zsuw*XRU$=J#vhmGY$W0@o-bb4;gyFs6xvsB??3GF()+BpX@p&*raxAx;-_<+e?3%R zKv2X`r2OQ-C`0GztLfS=&=*GgU-tD@POfGz*r!VD1($`YwxaQoc)K{sksXKPBW}J}vIU-eG9X2M5 zB3Qa(n_}H3$n0y4pX=3FKeDa0^U^dhH8{WzphXu1d=5rurYv(6CbsqMSh{NrYU)3 z=JCw>PSMBDpy$TpB9reYe+^O(PPz`+Xm0J) z8=e-QMkAK!Qe0vWooGJjUvc;nRN?*<>#O4$qPO*cW;0SC(U|AUQ@48WeVh%IL7kw2 zh>^{bhnH42Msj&_)(fs}8$H5lFDqPn*2Jc^rhT?^M|#4lzE%}aXSmmHXtbnzxi4%V zPZCdh`AThFZ(xoQD9{!A!hK+;`e(1!hI&Mfpf=Z_Sej1PX!Be*#A;kjwQ zTu}A97U(P=Kuv$Uz9Q6Xgz0nFp)TnLag(#Sw5rvZ3HICew%lKDF`@N)LKR87?Z@RK zactFWbX0{oGxqHT6*jHszU0-_YEVLX86mk#pF#IllH6QgubWl!QP6n}7964v+B02HlfC?BSzSAx#s4i4ecaWg2y=-0%WKPQRjQKV^}|7c_U zX@C-mcn$|+4DH3RPu}@nS?QFX;={Il_^R=v38&ZAk58#F<&>9ltk$PH=ht}{3p#8A zH&!ML8RtD^vL76l6h9hDLV12{qjUXrL(|2tMdWk~lU zySBNLrR7U!8wZ!f{hngr1h%7+finsU8O!YpRrxXVF7W(eTbRC!zPg&2xr05onT5kM zOKuN)$J^(ihDxHyXO@VL9XbGr+0J2+YM@QI3w^6>KW z@bhy4S8zFdzH~A3;CkuI^v6T~dJe?W+1$z2(Z$x`CH?Jl&7L{9x=1iG-Zu2Vzd!nE z>0$eKOD~=O92PJ@p4)GD__%p_{`YL)R`J`jVp_HymUadZTYF&6fHowB9`cI+zW)F7 z&EGBl<4*m*?-b$t*PZ|P=D&C9I9oc&IoJbDx=8-LTz@wE&oBSHQJm*?G;VH7Ricme{O$0X>2Z4NH;yR=w7h+LKa*S|j> z1R|Zf^N(KtKKlzF6%;>yFGP&_b|8PXcsr`#&~4QJ_U?Jmn_!i#cMuvPwEsK^B7gGl z+kt0&k&}kxxXB^#vH$xZ1j6g@+54l>x8n@-h{v@I(4hbHgOCu~FY$Yt|Is_?E#UO0 zsc59!fBJDd-L(I>@OP*FZ@T|)y8mNU|7YF*=S==`LI3AW{?B*+C+7bDgvxz}UB84OY%i51b_2d?j4X6JNY zo6#8I5Ylj>|K-x~NP(L_HkHKTzV*iXApbUP_rmXH=SDQ5bLQr1=8=7;)Mc~O;`2f( z&-Ukq?WI--g<5Kp?1)0ivHC){@?(RB!t_4=jnhJ(sqt+$J0uU7_|NFx=LP_eaml8d zdR=-`tEUQDeMr;eRwDla^{n|gIOCi55*g0V5N_9JE470=)hikO&kKr##^d>kk639R zy`Fo(VKDOkOVo1bCXcfn&x%I1G3j6PgvCgYAcD&W%6^c<`XFi++dF`T^DRL96oOGU z!1F*ACPEwQ`crh}EBDU~iAM^s*K6*iKC4UO@*6Ixi`HK*7UMJ(x)QjYvz-fyDm(MX zOG~;vyQnAnV<0kBmF36QTML2)7v;yUk17+de#QK;w%<(w$Z#L;r&t(adjtxxGgha` z^**_xidumGCvrm)C7cVjtN~3#Z0*6@JM>^&a&8wd0QwOZ)t|4wHN4^gtGcWjj0p`y z`t3GiW)&3Ibe`Ss$&`{Jg;y+S6SP-nO)yIpRQu9&J(RjS9NhlZ>vw&?w0)EPUevv; zXwgk~!r;P&?S-*24!<%au4lgBaafnUK3&*;AuvwjyIJ-68~2sa1vXvw`eu2r zTOJ`aglUQc8bUWTStJg@C_*ITAwrs~9`x?nvd7zJZSL7#mF+*h;i2=GeQR^Jzoa2o zy_8^7)9fWN{BwyX$hB}LsPA=^ujN+ncw2QDuw)x#$=j=l*J%GsILf#Sur4*W`O`WfBZC##*EFNBsv^)hO7 z2;u|=7C#)|d-fu8~<%=a;1Zi#CWO)tECy2UNZS*{U z^nz~73K+mhuX*j0l4IPrWx&>dFR#^x`<4icxBrdHuK84O=M(oS(kY*lss3!`IBICA zwzSRmx0C7B$Vc0bt`FK20~1Nw$}^Wdh>K^~xGR4S3}1=q4%^$dF>kPR+1IW*wT6=Z zJPa$HbZEHxF|lj;)Zs~pid7!w*Es7&uBu6*qHo9J{V!{`5;nSZ#5p=Ep~oKFA_e#S zVUykmJ^gTOVy6YUiAzoLc))8^&P){xZ`70>9}ScgF2r4oY9zRB)E)~H0Q0>Zk^FiR z4c((OB{}iz<7Y@x;ePyKl;5R!I8uDSo#~~lESw!~cbIBdrYz{WzlgI18O!BkeIoY*j^d-2;(D2>bE%pkSm$ z*6WL{Dn%R9Fv9rFgw%534bMi!%+!}P4-B1q9%e}#k1}~c4cagXut*YaP3bLnYiQZE zRLR$QoRgnPVy^kk58P%2s0`XzH(0AKJUM&0G7@9mnCKA$+j~PpLxiYOlb=O92i0k7 za%s%=8*#}7ONy$d$CKSm!(Nu{{h)dj+a%PM6cxHvvJm^?$!F8I8&0wK_+zb$ZAnRaPCcp01iOQA{3v zK>}}RF0DU}n5WR^FA7Y9*+>)5;Ly3gMa$T)7WP?O&EkPxW_jsuP7CTjkKXN_{4wo4 z&ucqQ$=AGszf-I!a~Bl@i$$vXA}g`->;tO7+}P)f?OO8cOb?;ZzpMU|dUYnS@kO$A#u_&%F5hOS^hWmv}aEM5yR#Rb|`}vbRK~F+3p( zh0$pZnc;iB_R`t_5$pTzdUNhNW=+rUbCGrdBiNPl-cgP#RuWyPt)@OBvT%!K%j8g7 zQ(|ee$Nt%m`W~SP&XoP|4&1g=M#Owp|EBAYivd+0*OQj(i=COxuuor4EWKg$U<1ex zEcNk$$S+rw_FWZD6DAh6ZTb_W%?20C;f13Id^`Ngkyr=Ut65PsJUdC<1nC*@%&{D!R;4-k*3AJIHOe+)8>ZA8cAZxmByrH{VnTi5Mv zCdEoUI;)CJJnv$SC{TUsUm+3nm2zsYBOBl6A2KUD-;Q7^XbA6E>Axg}T z-ayigXpd>K@I60VyJpDRxLsF{%D&*>&Q;zTQc%1I?e(w+8(5O;qpK6~-hybHaFh!2 zTYlGRLscdSk)K$hnL1o-Uk=G?isIQ3*DKQaJ*RdDR1WiT3`WBK+Q7WR`V+pCc7h9j zv6c*Y)Jom;{Kg0lfEcYj=R&J%?+fMqG>_5d)Dg?F{klJxuvzLXJ~WZ-jDXXE2Xa@S zL|u65m#wZN(t!hNn-U_^;9v|y54b#RpwvurDn!L?=c1u16ltTN8(w#+YLpjQbW&4c z9(xqGRQbee%r6_$@9uQ`qn)~gS194T!@ATs;L zH?tVJ6^67RNDNjHk_3#RwyWGj90$GaMkYL*dhhL)KQ6c9XSGzJ9$R)hld&8S$BVYg zFiug{2i~JhDv0bUAfQxudAqv$K;8s77=ATlOil0&0I@YYsA#UAt@oBD*n;7^czfzD#zw%3TLgB!!UE+gQiK` zIn>%#G9w6;eFZdV2Ipcz1(qK=LZDzz1d2cGCxI%ry^~-BkDV$lypPb-4pvzO^Cm7o z0ow`#!lF324Q2R zBne`Uv8MQjAmNI}5SDP<97gck=;yZJP9U5e~jaWo)5Kv8udRazZCX!pp5& zP4uFDZif_l|C$01fe9Fsw84svI9fCjqo)kM{t5?)>>-FYK|yO%_LDmRE5>t;<{kW# z$rrOyE7FnD^}Mao;q>%?YhepUW}7$Df=K7$BBYO>b|;c^8?S;xkQU}S-nQm>YC|d562yw?>)j&-`Ah02Rv>1CkjbU zTl^2|zmU<27?%*3UAAIEl=!}q%U&yaZNwb{ao&38GzXxG85Blv6C2gr&2N&>WC3f9 ziu3gXYdWp0Zv)6*HoWJfz}}PeFUU;|dlN&%s;pMXfN|NE#@ti43Dzq%Uc>4PCFLk= z=W?HX)iyaEP)SUB>Bg%Q^RHof&jd5F50>z1yz70vQItq2!{@zt%5J}ZlNj82`c+XL z_M=T?1MEzX!tmB*H>aZ=8@;uHok4)73rz4y#=C)JzAkP{IEt|5bUD?*&7`Vbl!)kD zfzDH3m}Py$9|M;)Y#4qB>Q&G^wO9yHF30dqe&qf#i-uAxw;cFb*A~s4IX#aeaB06@B!foQ(EczYfd9C(DtHmEQcx^Te9s zb67aUYUuW1mhmfdA-nN72w7RMAg512U*d5SNuWFNX65~Cr#w_pBGd~2>ix5=CjJY&-Pb;P&v3f_W+S%Iv3oC zpRZ_}c zGa9<3_3-f9BqXn<9_UR_j^T4cG(s#^X-)=qLgJQ7EqWeuW5>4~6XsD8)X=x$(MzLc zoy0U40wsd>*g#jfh&R=jrBf)r_xK;)CnG zHahnSaSG+pQ-AWh?=&kocl^SUfZOD9hZg{wil=7o9Tl~VY!)%#eh9%moWxLNI^o+S zV$>WWFG*pR)~80i3E$mKnp2s_I)zy7d^`E62BDU6IyGVhH`4{k90GfpkbQ$%P7&oX zn&{g%Ng?FKK5BLzqos#E_TGqjci;WRj-TBe90helD;%UNo8-_rv7{E6v=pMFEZ!!r~P!|7U+zH2uy8 zk;w;uFWQitw4{S(0^alJewgnufDJNN^S3@Sni6{k<7_Cv=-Dr0(F1=Y2yaG_oyoXJJ?=5BGp!O>(7Rz)QLuNK{DQG_Po&J8+^y`AI zu=&LD`irk+P z;(57sLwA;9SyU&NeJ{2~*jHR^VRj@F-$-szc4R?;z~iQtcaU&G(*5XNRe=N9uBH*8 zG_K@RrWZwDbSr>tHF6m`1~`MXHNB_2A(RRxl@l*(C$A|EZ^mDgxE?nF(hzorA%q1> zl?fMs8$s$278_S8cjkllST8+^9d8J-%f}r>5P6`0eO0hC*!U7M# zj!1TY@_H?YyH@;6U1-W>5Wk#DsR!`dX=E7oII@owo9@L$y}4qxgM<>1)<5n)2AWTu z=>Aj$!BA^NC&p9bV`jn<^epS!;Uj@|D2#gZW<#+Tm=Q!jT2+2GR|>T|c?`*!T9`O5 z2+-n&i3356b(o=*8y!Egv>tN-h-j!m%P+pM_*wHu>^RJ>a^7- zcX}@$$ie8LBgW1V0&6Lc+>0OHHxhzoF(Qbln))MHQ%%C3LNav$OMgpxYw0EpwLA3_ zfpKh~Lzp9_~w zHkL_%S@$sTO2n5*z^Xf#RU>V6XWKTNU4uifIQ;1$f_!P1762=RTusEnjmgu&I1H(L z{|VAe;7($qAIbnm2#c2lQr7-fa+6J=TNH-Bai>79EhkuoMlt7H5^!@-pA0tz(7wT` z>M!@Zm|){p=kjRsWt|IE{?W)_EOE8>x9K$MHDGxKj8RZ;+` z9pwgMAYUjoi@JrKw>Zoc&8LGU@#_g2Wjrg;YMerWhlxBa)I5&~6OLlR?C^E2i@UZv z+4t;8iy+!PT#bWoSh*%?sf%!6tZqC(E$bgN+URnzpmR&FhII5q`5!t=*Xh?*nza-u zQ<8#6slJ_-byVZc>pi|o0GiAt^VPfE>AOd@C(~XzQ0!*nJ!tr>K%JtJ&;&CGYCB*< zx>FFW@@mt?A`|q6IVqVu&WZ8$o}9D46&$mmME>KWUkf?#a`85%Md>jh&N{u2-_85* ztqc+ve(d=L6S+`Qx8Df_{aDjyp$zu{AjWc~0gU=j&`AN63DZD&C{w>>B_{P2s5MY% zDbY1jhXAoABufbYd^3nj$iK<*KuaaX^FB3%=a!jD`;-_z7vL`iiR~K&(tZ$W8M37O zrlq~Q0~j8f*aD(=#3jS3(^Ebj{m;PZ2u=4RlJ)o}dC@T*Is`lN##C=rP9QFJ z8vH60liZ<^Qk`T*c6^2z));LLN<^YkWog@kkBOQzSE+%kqgaUODmpr7_;VWSU0@i>hz?N-ot zHC!iI5ffNHVFETW>(?MQg1+e2iDC&lw6bpr6)2uLw$ZqMb!(6CH&FpKW}*$2mqA$G zcjXuXu~*9h2%-484hRLyz4=y+E;zOVe}noiW1I3v0DwsYeY%Cse@1@K*|(UJihRJw zv$6C$X#K0A58J{P)U$-LByQIeONZ<&1qK)Y) zRSgRb29c_@wO7UJb$@KYf-oC6YmlW7Oh)cn4(?AZwtk5?;se237%n!;qq@Qd ze{66%sRNdeG+1^`_6>Z+$c{a?c4i~5!J$lz$^^Dy^Eeh%&i z-RQkGOBEGg67I*&vPTVLn4$H;6B7wd;A;8w;8X1nOAPO~0nBWzeo`lhm}g7hJTh$> zauOe4ML0ELkc&8rfZ|U982V4ckVVsx%vYKRhTpQM^wNx9eU?n}ILCG;uI-nl5hRD3 zsei^d7bv zIq>lyG(Z4j&Y6gtYfbn`e4aSovlq^$A>d<9WPSZeUFnn^K~#?mfi->A0{@PWx5&hd z=%)p>pS*0V>O9s5d;jjakz}&3EWQw*N(gLSfb41$@DWn|Ium^8^b}Uhfp;MgT>@q@NzrnWW!gvuyb>AU(k1{0_S-=pQtQpT1 zHn7*$7rourJubz!&MAKP$t*ExHxF;~A4#1L+b(o@yLKni;+*tH2!Vok#W+BfGC3J4 z&tnmSBHr97C@c%TU?-a~+TpT=txHJi9BDvuz|2D$gs7=%K&px!$e(J=mfrFyh}i3K zpUvz>V{-*LA3_$~rkiq;(4=E?#?KACTSrA<(6HNt%fy%xf@~=T{m#(-NLr|%b6I$XHozY7#@N$) zufP%+W`7?#Cr3Vh!5Sh6R;MhQ_aTKoh)j>fqemHg^PabwcMDq;$P;1>NsjqESqj8i zHCdB9=4L>Q4|Un>Jr^Q`YnV;oo1B!fvC0qUqC_*?_Hpn-38XGR4^l6xi*>Xd&4=;0 z<)r}$?(?sP=OfG!p&-%$Jq zdUM0&xK&`EFId9)Sv9U0!8YFCEN@1lYScQ$%Hv~i~ z`Ip6Fp_F(~rI{VD(k);3d<_Z@ybLC!&K)^wF(*>weG6(8U4dMlV}c`J<$xIro+} z$I7+S3*=$@9}H(|!mG}#K#cFTKK|wc%XZM~-yP@}-$vPXMfrUomE{HaCEjucuNmeT zg}>*6>O@gig`Vy7BX9B>Q!Rz}g%5}In|;;@Y@xhCP2FJ~_hsQsPZ^_e)_IJ-_Qh*v zN=g9Q$Ct_1(^A4S-sN7N3+Pb--k`?AP@XCI5S8TYIL{CqE7yH`7Fn6M7Ci9y4dyTZ5411|Ua;6uwb#@@Id|9Wo3Uh{6 zJ#}5dI7>pM8bqY)lddCAxC_LO2(hqChUDP6+>pTC?{MtgOv3!S+nA5yX`jVF522A8 zSAuuu0nXxyVy@LyQ#LL!4?rVH zo+blcrp0d4eaclYPa&6foVbErtq%0;i-0mqfp<#hahmhbR}2yE#_31K*AI#=eF<9gku0j_y;hC{OBZ#mpGXec<84#CZ*CpwTE5x0eTrS^Bpo-zujGFpUE zlf0HI8D7O4GeCAk{kHKE#}6G{Hb7g{N{c#?r9#f@(e_vKitU;WD;@PIOwoB&5Zq?G z!uHcqnHvSv?D4&^cEHY02e8LFnACnMiG%>65$z|?w-gna#XC>~74K2`4G<4Rgc!lE z#AA&VU>*vjM{TN=W4ZRA_|1Of8W&s0ZgL1QTaCNA+t%wXQs}1W`?Z^1-+=euTExmJ~#KWL>cV64CJ#o! zUwwrA&!VzWXvazBt0MsF3yR&;MH`5+}kviyldR(^pURxt%`fA%h9e2h;@s8a zAOQN0(A}#KMUu1?A1Ts0wKMeJ(rh%Yzo7lrQWpk_TC#D%75FwL`iyFaSQ23!#2cPV zx2%m>l>4X|W?n>xm-x}n*M&%|cp+wNlSIa65R5#B?%{o$7#Pq)$;5y_!ZuI%=ib>j zfR?XLJfZ**fbXGLGgk8M1z{zHWE4%r?u&1Htnp3$vLZInB&7h4Rb}G8j&=2$h*aiK zO^`d}Ymg3p9K@qnB@}xx_A(1dr=!4UDSh5uhaBN?vEA=pl|G(kt82h^l%r4kS1L1d z&O{(_*teS4aB1nX7^A4rM(btQcCs z&xdjtlesF5ynmqWB>eWr9XnRdjLou%72EG@U^4l8Y%Z+jWJxG1isuT86=s2K@4k-m zC`X64pDrEJ$*TUORzvrhCpILA4;0V#FAH+KJa6Z=fJe%EqDpGkOQ#WJftHqN_ zFA#ul-iISU9C4*g3f+b;4n(YkZ(TFCBoiVwBJLRfR)d{0Gr16GSbkU%;(J`4DX&QV z3gU9P*A{i0h)tIq4ZWW_gJW_S5*_%y!>?&iBt}5Ak?(zn9q6OOWhY@gM@iiP#vO{g zP*lAzgpm0UJaXS(SPXFr72-CJzlUJYd=6HbE|pQ0XBOe@p)#f4sg^y8fW@;&E4&w7SVa-i}e$kM1aIE>4Oe=+gZRg~m8G5}RuL*RaeSmj}qrV)>JqWK0pVBlG@ zquy$kd&JDviOi92K%|8P!J}jU3Op~aVt~?@jjUUH?>Cw`A6^YJxkS`HMRJs&!0--&jL(*XST{*10=erN&9ftqUd~ei9-WGvs}H6CvQ6DZjG*H;mv@cjrg_pO zp{VA9oLDWm0{pmYeHBQPW>&ELc7P0Zvxp&YC?JHtaPejUAFIYPX40Q+C^%h~RUDPM zUM*}<2Yi1)vBDc`u9}G#*m-$%{d&mN^CzKJz#BH6*ZpA%>V%?E%uZ+D=)vN`d1}dw zN<>(M(SdYysJDaqXS!&|M8cohb?7=z^97xKo z3R7}vZz%$pVrF7NBKgJqf?_98DUa%psO=n($1(>nIPx@kO_Ya{IPF|`+=eMnrnLS8 zwDby{2U!b@xxRx6yJ&kvH`fo~{Q-ttaTm^SPq44gq$Bxut#aC4ia9+BAIlJOO&(5C zs%Eq^TudXZ{sqf_20Q4bJ;Bl<(kkvGCjf*m=aWN^C{kNufzA&+lzkzT;_D?`5dXR4XA@ZW1w z#{E|DYmf)N!2RC*E=fPXaj})zk-GrE2EPGx5TW&0AZ`2QNV;7ZtYWr0?l+5yNlmzi zk=AkE1yuB`((HHyUF1gvc&#!#k=HlVYCVhjTFw#yxgcf+{h`i9-`UssT~d{9ODoBwa6eXzka@ge-y;; z%P=Pq_#@WaTE2)tb_*Y|c?OgR(Q9Nmnj~Q`8JvTe5zGKf(aY`dI8VY(1=#R_5U^R_*$02J8jYs%9wjxWWQEt4 zPLJM|RX7!xt2WSXpg)_f4ppEOSX#VZeC66y(pjGkqPS$}2WrsTRGLaga8W4*OZWLe zKn`KE1At<$w#wc3Z+j6A;l8KMbdj_-p?Ym^Zf*R46J-REXwB|0`9h13OSK+`F*E&`D$@{F4=+V0G;tk0NSyA zW_nDN78v~gRNPH<64w?`zKz|OL^`gnE58gCbbK0QVb3G5c%liC@1W?%8W7UJ4UZBl6UVyr5HEyJVftZ`P{2=eu= zASK{CD4qI)aYWPr)y`d*SE3o63j*`l>r=e6@tC7OUHDKvS3q}hKuAhExv2fA*5)xO zEyMm@E&w=h-R3V$Klr^_h7tie%l!HBd&V2HG!LFV$;RF&YtK~p2|OlgaUdA4tHL#s zVHS6JN}tYDGD&xYr^@-v(srYxMrV!yDtbB_Q1D!1>lX!J7L)`(d24?(FJ0~U`5or) z_;j4*&BA8XISU<=FWJ%-Zfh1yzSCpMn{bMI@12kIddA3A`+RMalUd6)_jRFo=rUr;y**sB804tdPL7m@H1Gd1d*Y8gs z?{hPr;`KiW86DF!durCwnjqP@*EP^tgnz}kk6M~Jl2>^V0037%M|=4Ky31M2CkVxQ z!)VQ%R2WD%$+;pB`GIQ=!xW%Mc__(1E)OKO{vS*uap9@zUj=Ao2zk3t6{` z?mx&g6jFdZ^WR~n3&OH_43ndKSxu88Jn0zV#dFUe5X+LhVfhLb8CxO9U(UwQ`wODH z7n%A2^hiYml$rJ4*4!2QOl5ihm{V#q62Eors=xH^67IvFb7+o+-f-8Np`8 zg)m5KG!{<;()6|3^SA#19~rIq0@MiOy@#10{JCyn1&S2bL1^~+$=274&y49A^M6E>sY-hr*Vk0Y%8Rx8GAi36<{=g(#bpR9lwuKJSvuM0RIL)G{eTjf%_LU2m(gSOEw^ zV0M7*&J&?R!6w-bI>fjknSqEJ*GlHpsR9tiRtk{qdn5M@tkaiR7pLA)3(zt?i!ske z@}9xNy@8#jZtw5-edhYODt$-hd5+}H=^~rdeV_Be%*f+uuboxlhBNh%ave}nSX?wo zbabo@LsB0(hzWe^w+RsE@+lN7VDax^i%I#97*AI*j-o05Y_=}3!4uz?+9 zt#}6^%X)lvuu_|?=)EUTit}kU^Yj)U9&VW2jJKKxwGt=iBU65<<%>ML#ys`^An_fx zifeM}?;L4CcO-dI-CHU~a@K7vNerO8%-~xA7vbl+0U3e>E?QoOVx%Ac^r8xXH0uk5c{$+D-s!UFY@d@{;*m?7&BGHaVIB(GTp^!8)N;h;eK1; z@vSqyNaByy%f^E;T!@10?ewjCQsRfUe)*h!HO+;`G35GvYX_`#)7$*EwyJ+!K2D=D z21&Sozgz_r-#^h@bjw`sRzYCif?^{8z09|#>Jj;@i3_Nr;;)?kWnC8BIZ9FK1IS=2 zSXqW_n_R4>38Lbf#EP_@7Kc3!zJoOW2cGTyR3-!m1s|@3>-QqW^N@wxw+PAy*com< zqCn|cO{I~11-FK5@jcedB!1It9S9ajcOqkj31JaqlZe2l?LZ`NKQnb{^6QVHja4BV zrpm!{b!Z`hef$1PzPKT_Fb|uB51ESQ#Lr7+EY*D;98;11uN;U#(x)!$Z;`CW;j=AW z6i|VIKG6UuXrezvYO}V!&%Cj#@Y~iL}hXfy&09PqE0`;-KWn84le-M?(^71SlALp=}YB_%o2M zia9scjmT6`vVNWl#yKHH&%uV|e6qUh*~abQgZ1eu>LV%ym+iNhaRG=Kw}P6K;AB$Y zvmXGBVhYKzMb!Xu_l41AE>JvmRu{S3=6a7E?mbyr2Aucmbx|Vo!K(nw)?J_5WMiag zdgaYURpEWsWfD1kF?~{_TxqG?yDp~#_+z#>KZH5yL$3hl-J=Z79gA~r#-z15>oTB3 z0`uwtJ?pLLifabg3jTn}<_FKMt;(*b{l5hG zHj&ZPmiqxv2~jUnfpQL)`|92byf>mt@3qsi9@P_I#WXy^fNm%XY#=iZYVe zTu^-OyCys{6U$^EK~DMK{+lYQ90%9#i%fPY3T-nq)tTQ;_nS`-8?93k;Cc`i$w>QY zA}DtFb_iPr#kVCc2kg!J51JhAC^}z5_pvD7yVoD2Z%3P4&Xe~`T@6a*&}zIdl_QY& zwY4H5$Qh7u>(xUe#n#!$u@`}2uhrM*;3gbrB0&Zlh?YE19`t3yQ;w9EW@)n6v zUMvmQZX~jEow{WyJ$ZwCGOQ^d2CHC|<7e*8BTpx2G}|rEpP{kZ`Z5&{2mlHep@$hz2gDNyQ%dbTbAJ90M#M7&mPQ%GFH)K`)-2$7(k6u%-o@xuQHZTiqrt zKwa>tECpDgHstjzrc^MH914p9bu4=hz6Yt!)HL!y{7te7A*VNaQlkv?P6X2z?-UKR zS7?JKpoHO5?2kMhQU66jz07yE&Uz|j#;W@s$!Sp5B45A|q?%&ys{IgbOhBmuiLg4ocKRIt% z!nHYM3>c`=d7DJzHfjbkF?3YhVbuYM=K#lTCVmn#-!OoMrnNd)>Fu3r0aS@KL4LJZ z!n8#Ob=&*%a%{Yarf;`8U0}XN!WSSc#9jcpk5h{(#M15*s1*CGR2+h228B3;{g$`> zI2Imi1N8Vmc2I|CjnwsClwy|8)vBUY=+l#$k)ui3L4@zv7ovOU&V_$C(?$z2Kf(%f z`Sc6knFUo)tmU&6u!kQ2EE+`7YFyR^f?eU8$AtH&4-T--oZ4S%`o?KJ>wRe-Lr5|x z$Ey@}Gb4DbAK112w>Y5NX|E%0P4CaLkZ~9y>#(si!`Goj+4UPHTw#Jy?xeLnRgc_ zHO2Sf1)Xw)aj4#~P__InB2qL8LRzXKB6C8(@sMsaDSZHH0|Xgbtus7xIVJ%BXS|*6 z5wTYb;BJXyfKNG%R*E+z1xg=Q*Y%R79zQw}I=Tjkhm|Xe8t`pN(|yb3Dw+5a02lW6 zE7GMyAJvDgs(rJ{UEvUmt1+|6y#ZExNtRvU6La@V;ZIH28P1MVYWrP;@ojW|lVdLj zp9&+IM(kL7A*av6=^w%smSvPY0ftx?YrcFvzd%7v@<62o66m((Ow51lXLitT%V*w) z{^s&iZRQ{83Cg@YzMt|9aEM-)DX(vCX}RA{ev!H-v2Ky2-!?BDD4N?en+|^bcf60X z)of=D#?Du_`*aiG;LT*sQ}F3Jb>@=wbt}hHka~*X16itH>iLfTE7T$%7G_Xo7zG_b zdm%XHEplAUHc#n^ZMX@kXZlSEU9n@ETuZ(T8~y|dxOnT{_Z2#wn4OVj&Z~0*$|e<0 zJ7=lxnB7wbDDLpB+n;cx8NPZM|IaG4j9d-D@{;_TZ~8L3e4*L3bzRJ_(1H5c*kJZ# zNO-gN=Ld|4f%h@s8BG8-@T80;YPN%YU`sB^Tdr1cYOvnO(5c}TJm@$53_Bv>@mj1kfRfiB
  • 1p&Xu?kpb_P_}fs=+vv{2Wnp{FUr1;xOVP-`~GUWtUOL};g_~% z#4%6+Fxq}33ll+UNC1p)m?mteIY{!5!CjKI6%hF+ZP-oM=P(600TIQ9+)g%gC=rZs z?e}G8@*eh-yVw<&Qw5>z9nj33y@q2C3~EYk9XtEjKq(wdcrlm~Re&TU*s`7K=V`fB z&weUUwsY-F!yMmY!OOgeX&Q@L{oH>o5k%_LXDYz`uUd^``QQ50?$!KF7^KG&A@t7Z zg~=xn>9hdzJ^N6ltiKlojyyy>G;KQlw&TMy4*U{EtZyeCx!dPGF)_V7UY{H!_SgRf zux7J3<_~~aaj`i#u|mUk-q41%D8cC+d=YxaI__(-sg|_aF383_H6Zwjzy>Ox;1Y<@ zcAsX!)3zdz(iXf_?HoWk+ncZiA$Ekn75696&WRP@5k;eSqUk^hwXJv7Pmu*Yy$=GnDBSnYWPMCLY_ zeXtA$hM=-x0!3;98ut+yJx4p$b}^)2drzS9tG_q5fr8goSTV3cZCAHloqFyTVxknn zLEP9^a(4oF2%r&xqzvlGoJOmNufPH{JMp>N$9_ctHu5E}aDaW5%8u}BE)+wx-Utzp2t19fM5tUk0h1Zf4*$(e zXZ(&9fBw-|O07%!I0KP5}$@pRF z>)_4af1h~{;2*;e`!ZLf5GUBjN zi|8E>;MoASF^*9Ah7>Zqxu`!BOd2Z*iW5T0P6r8m^*!xfOjgO~Grq*|_5>zX#jU!Gr zeT%qkU%W5twF#2pnbVI2_^G5&MT;0gM2RoKWjs0j(?NxURm* zimVz@;=@Y770Z`T9idu0*1y&nXH&TVB&2t8j1|&^;Z+ReJDL91X9SX2zy<@qwe@U; zpjF3F5M{tEik`i7?hE#dJb=>QiW6DqW}LwQcRCTdD`7l}OwE^~q+>`~xOr0)z%7qy zHukX{zfmPX3T(>m-S`1^o3Q>Qebe6p(9T-T2$U8&;cP+Rc6#i)j8w0~>d)tLh{ z)x)AIM9hPM*i7%Noh(D{O??UQ2ZHf54>|D}CD><0%mzT-i~hpSpZ@n!T{i|}pJhCU zC{R5xw4WVl$Di2!>l|F+ec^cjl+aw`&BAPS5rb;DSR3oiph~rpJ0T{qPz~l&bYv0} zzqh^&OzGVF>S#iIKGX2iGv>xA52_o&!8)LW9qbi)8Nt%VH!M zj2gR2;ee6-phG|+hkO}U>)jT3*9n6zqrvd5d+o?I;eO%blCqo4euSVr6j-u!R#28K z+KwN!UkV60@1oh$H#sM#I%6e_{Qg#KtNV49tlz9Xg%^RJPP`QjbQk7?U3b_YL9YOr z9r#VCUTZ(xCb_4e{DJmj6Ij@ zX14E*Of+hjO!M>j#e^ISQ~tONNc=E>wAd3QG4V`S;D8Rlh9dmj1N|j;%PQk(p!>!2 zSebK}1J9CXe96MwK+?NM0)Z4{PZP^4t(tOAb%J6IVz>6ayAb^c*(XhQ$6Hh0c&}Rc zmt|#muKE)?f~_#0jp!i*pEwY-(z)1|DdiK=8vZ4Uh5$g*o$JipG3?xdf+5Px(xfygJ}i7Uwc_I#YFd z(=+?v2~SX%WG5ERouMT|ox9qPG7M2-{TQysExw7b4A5ZfIHoA*OXyfntblrc;18TJ zcCc&!yYleI+#rW|jFU4cCC8JL+VruQ!-{?6;3ZfY6ujpIYLBx3g2e;bsbW25MK+pJ1u`1@u7TE$2l1Bao;_PGH`G(jPbZ3tS&NH-bbQ(qXpuWe^ z%XTmKQ#E8R`qyVd;cUvu9Drj8K9~na@5b{ymKd7VS^-E0)W2$t zRGWh1XOtKfLGd8^T_ToENJn(705r;s++aceQ*hjY&5qz%5#JRbv^#nEnI-ZHKjAIVodBV)O1Ezx|8(A1{`)x*iVzs(( zg_)0%)Az$Ms!T$+H*M?z2E_nnti+c+i&y1x4b6+|b4ZqNSEoJ~{^_*@i=PC_>eT=g z=>PILC!sRuA98`x7KDlyP|&o0HYi1b!u5w?{h6XKu~)urpcXFpQk26&rcnqLD#aS4 z1H(b%)S;dHts9(ur+;^$)p%G-@!0`-}Y@i>`4`^7|H2jvR^JvTY2y#rLf zW0{iZ_t6g{?)Oi(`wLNdM2GL?7$ClHYtL|qjIx5lF-4UT*zwG(=rN^wb=H1rl7Cs} zWMpUkdF3hNUo zz$*UR1 zy823y>K=V+mS3I~AJ0_FV*pmbvKmA-#J=oH?;rq#o#qVk%QXT3whGp2g$Gx@J?&(J z+I@+8jg8i$8se(S_;_v_yM_(|A}03BJ_&fVk2tFdP7Nv;fF6@>PW<=eBrU(FV>*jI zv`eAtN)>46Vq6#5p;T=hw`3kiTD?x@DShUqepspnEly(BZwM1i$40jdeCszBQ2D~Z ze3KD~B03X#`vcJ?TTGLow2adfA72Fw?n`RRyf%lHr@VXuaIr8U*F-@X^%#3EaY+OTT>NL3ShA|aM~rhL_J@sn7m?J@N_ zV|77GVVEId@xE6*o%f$q#)`tGs=oZ78~mO+u9+e9KK83r8#>1)H~|ukm(iUqa7pCz zG6B*m&zB)3>MmcdrupD~@_;u4EorqEB-x+I;=ifVAc&Unq9~Sd>yhOXRtZNhGHfzB zTZk#+R0wmHJt=g)Z+^&3nCAfsH!2TC2*7FHtKw#uyoQ6JX%IC-^##+*DU zL0~<4>p)`!WK&Be<0YDEY-w9Lp40XwzSy!XMyY4!*`4TA7P3*E4^=y~g{G6+^qI9E z#T&M$Akm(w=Jah0#e|6xsUc`rpQs&A?T~5nN|YJM8th56$CN5LrEAeeRwdFuZl>ML ziLmk!t>A=0lw;#(n&Y!gHw`b~vpio}Rv*oZS1;a_3^+>whV8uM;DN%Y=)u?B!?Csn zOwnIZEjKn|+>mKqt*NHXF|6bP?xsbKGSp_0QS0E~z{%L6UKAZ?wTGZ zm>`O77D3js8=TLgVxMA4qAhxJd61>q2~-VQZ0T6_SiN*_cjK)r6BSR>L$5^8XuZwi z@g>lRr4ZOZY~@o#myZ!oR4 zCRBga`1T1U%;YV_drUgLCI7&S_RTTFM}DKAhVJ<=_a<4~(wAZiT$x8NYYS? z2d9%VwAw@%Se-V67z8)*M$<;ZFIRlo^5OE` zA#{Hbknm^s?FTW#fsbh`^j`37C{MHN2ra~EP`~Up3Fp#hA%tf5<&i`utNSbp70G^?irClgU{(C#$!$|TC)B2i z|5YqdPonb7ab{P^6z|3;)sG&!!4dDwF}0doTc}MzJk}uH7w<~E_t-aw?|fY zk@7C7YZ3NiA>>F|lS@i3tWdb$gBUT6QG64S`4C-AqKq^Qby(M@3z3JNdpy>y*}R~T zKCK_VP>+_~4(*SG>w3KJc+sO2%Ne!IRQHdD)~SEN4{W76kkM0a_IqBOtOXoS0fhCX`D9@CAm~$=s%Z)z+uJeeZVEl&I+ds~j4@&npe2cKu`S6rQVVi_Dg<9UD^ireabK`qJ@pzR6i_DY3lA zvm|oKF^4lE*_FE0R32KWUyyF52`xOcnw(&t^jeC_k~=|>JTyQSxnq0^jWzsfdP^d= zccty^4obs?m%-PnPuMYI-^pXrtOoeg9@}jg9C?rb+y#Lqz=1#BfFaSen#zoU$QH zq3Sq~1&?jr-q#M;+WlxD0fjx7d&Y$_#XDCA;K{f%yps6xB5TH zH>q+!;Td5nVrWyZF;ClHVzf1h4oHYL7H&1;Co!e<$-!l=vdP1o#>A#t1n{K8GLWv%II? zpR->MiSBqYLL|z4L%j!AwJh@Yc-z--y;kvx%*H|Xk4HYhS4YFG1^^F$*g?(sJNY30 zN8FQh$yW}_49EEUT@R{`UiTjk;8Pd@Ke`3MQz~L@tgOZtX>eFS!(`?XND<-JyYuH! z^stECFM*h*tM{MeaeCtWn)2!9+t)22!bTQWxk8u79wK0pwwsj)T9Y}HkA3B zWlcHMdsqD;Twb6CNJYT^|G;+h2CT;ph-idlxuqb zjDM#N>e*^%6Qh-&kqP4IA=dw=<<1i z>9QEvWKF(L0LMoVj-qZsN>G%isnNNlcw#X1>U$@q$WNaB zUtn~Dboc9m%+1uWpO6>`DB!QGfgsyEJ2U@&s!{AcWV;k9LP>A-fRNA}Z?8Nk%I|F~ z$2|Bb77f8z`m{ieMjuW+^gf;!^iSPYyAyw_Pohxf|MyxgB}1e$PZ$7)mTVxC`u&zR z`PJ^}lp?NwC8}pJ*Ln=jAL22b$9NP|^f)=!hsF6QjpYI49p4mWlgctn0QvE3HAC@o zU&Ry|Kgbh9x&lP(o_kAs;$I#~#^9%?;&&0TYD7L8OeK)0wx>)YVb_DEE{B!4;{wCw z|2-y^J5~1W=`m=%%x!~RO&O4UL(XqPj9U=l!dhy%8sgj4cEBgOQzr5ZQswDp9ILpr z+kqF8`ZU!q+A|-L@ctbF`%KJBn}iu+ zh(+c5u;dk3$DMqGt?TmKZWh69(N`b_L%Ut+oDB$Z=6-r0|LjUZhcf#TSnEz?Uz&nd zDP#`FC`UU=~%hN%BQ*x6k!KuVDh8R0O%1L)XHJ;=a=_?#|=W=)Z;nt68(zqQ1oN^o4@i76#} z=8V}#LI0>o7O;-X3BIVX46qd_;zF6303R-KI3hQ+7FIO~U5twaslR+7!L2N)D5iR+ zlPI-Tu@Ah+K<9^&5P-O=YaoC$fNnqtkN^_m4I*Mz&)yy{gQ^z=JnBob)BA#%yCFAc zIX4t2i*v}jH;TQ>%2lIsA@U?Ub!mbQ~n$*g^2-=R&ex3tiMV=d|OhGW^8lRaU6GZ zH}J1f#4$8!&Cv2Vgj^d-bkIsKM1heB3cF1v8;bHIKEgsoCpAN%eRv+SL1U>3Eq2zGzV7d&}llli_ zt*2e1rN!ClOY0xr0e|n!Y0M4z6_5u+0fq7jGzW6|DL2q;N?$vy!{FFI|M9kG`AziL!AU6Df|>HfAX z!4Ky+yps7;345J^N|cNq6$jdxd^udvPMWozF{d)Q|PPvqG4f8O2EO9`MCF zH*VKDp}p!PP+Zo)7x4_)_+fgrp|2m*%0*SN;PLvAmv+z~{-=ZqtnBhcstQ2v$&*#yq+-_(WWL5k?p zYQTA5unVc@k1cb1wcReM(t|l_8PDaEo$F2Vn zL0nx3vom~&DxdCpHgT|8!c|^n;zB@2 z6m9a+IxK=Pq=@6sgvO=CdMF}1O13ctieRL}JE63wU}i*hv-4R0JM#}HURV+<*uy^d z)T+Ohhxw4Jx47>M-m`VRe6Z`=yXm};(>>U9$>)Csf@eJsqhB?3kjPl}{%I$>vgieB zjn(yn1dVWmW5ShkY<0|uus#yXbOwq!9997akSvhH7zi@xqDYFlMm1vV(ADn+4rACH z-ci&&&{T1JSe1{B{0I~#VveS{-V;&-`D5sGNi5>dA-k0yL4HBx-!FJ2ZGd08$PDmo z@weFYja`FZCnq!+5Gv;OwcP`!gVhvD^T?Gypzj?og=7fk$aL+d2tFuw7u9`n@|U%! zasH};T`qs`e4?GF&xod=`8-Q+<*6?7_-V!DNyonziznKywMUH}rL_8lP)HHH$rCM0*2(sl6 zShgDNJh+t808>z8_OUaW##QD;O{K46P*HIPEDvjuS{K056+F$@SgSVHZxkK6#PD8x zoLqVnBi5uwOFV=z8gQ9ADkGk(2#lrandThBlO(0UWTODow*PJ6QFzlOAtPka8FTB~ z-@c`!O%Stz?U#C!t6aYnEj}AW(&NcDfv57We@dse^*>4-exL7UrX*J<{x`2CR^L4& z&kRzgD)MA%%@DBHnK%f6EFgwN!1%%<-O_OhNMzc@!yWNKBdWj?ZAnMMA+$4{HgrQR=@!yMa_d)Z1KRY8!4T>=H>2hr-?vs>YfGn*QkpQux zpcw@)aB&NV*_=$YULUQO?8o=|9P!mA1tz0L4RfB{Xnrm*;ag4Dhx#RB{BFU*?B+__XoAv)5~26 zwJD^8K^eC!|B$yfa39yJ7iB*1U6-R%8Q-{JS&UImM=Y@JXZ?W}->~9jE&{!Z^Wh4& zzbH!Zw3xYZN7qtb*G|@M1XEU9{hs5j+W_Y%(B^ET(ea$g$>JVZr)qwiPQ>CKJj1lT z>Lk(xqlH8)uMChVz+q6BY`%yNKyA7e{`%&CGfRA(_K^FBX-0DDaC|Y?P7*+CWMK?@ z$_<+3rakG14Z0|gQQyj??6feo^gGJsJ%=rc1kA)NHs>V5LWmtnRGFa=hb~I83kD^22Rl6 zs*Y3D-~upjR;$i3VlK+o3;m_3Tojl2*9JmLn))7n=W_ei?@;$9wv zgYNUksd;P=aKhhz$%>RL#JXXEGi$1V2G>umzAA+|jILP7#zW zd*7?MLiL*GmupgVG%jCmkD@Fg6~*rZ&0XR@q6Y{)^g{KkbJmk^ZSeKS)f4y@gY7>( z&~DS;01dONAN9+%Aso**YHqdV-S_sgv|xJM_3yrkvqry-Nqw5zJfQk~CK51|$Lm0< zw*(X`AodPr;u-zv1M&;^w?wSt;zzVlh|%a+p{lqikbtQzjk#9o-}0u9>CbJae+}|5 z{ZQTp$%C|Eksez{w-4B1IE)Z^LHr+p@w!ypU#0sXl)B76C9M21weBjfP<|USjR%iH zxCh^J1ho?T)gpk&u%%MGEo8?P{)U+sDPex83 zdh2Ss1Mbz&i}7N~mBERTTd0L;##gbHf4 zzCK$?QAD?6lZAce<}s2sia(BbOjnQxX+cgz+E`YgyZlQ^G?>cE_|&=isN7({7PRGk zEjSP8;<1Il3Pj(+ir)(Wd>_c{YS&lh2>^k}O9VxV_&}{1Vt(pK#*7J|mFZ5Y;L0fZ z0yQs-AzNthNRQp(zLF_Yw#3X-#Df$~51#@z;Bv!;UkLO{RtBelSpH8olmQl9+3tN4 z$C~f6;)DG))G~lvA`;Z_c@>${XaKdjjP%H3?~=MJMM8*sy@=<(KCPe~823ViTSnZ=^O}K) z640{-)_EpHmE=YZI2SBpD?nzHuB*i;g6KCLC_nnD`9P?bx3G`LV%tOp^$3o|2g52bRjr z2}RYgJHBB!Gn#8yxlPD+h|o$$tcY#VG9WFLQ&m-ab_XGBDdVGcC{zk19KfC zD%_Nc`@^_kobA^6W@St|0(`5|Jm>K?21pcTMcb=mFnRd6AC4+E+F6t836+uAupa;L z)H5)1Q{Q!A4kVVX7En^zZ_~Z2-M0~XBKwZ3=aD#-^tD3ze3PX`O**lTjhwLP#SQu;m){%b35pmWevAL+&Sp8kQEz1 ze;R8#ws{P}IJV?Ict=RxOL-1tJ5>w;5lg%t=O>A&n8E<Ymi`s0})` zy4W4zzEAR?(7tdV{x3>CWgR86_8n#hGC*RyQH|pf>-v)jpanpyE&3W>GVX4^G4>t> zoQ{HEURw1mF^|JdKfU=EmS#-UmGc#JocAxL1VX)UQkTW1Q;eMI3yHP&E&_6tO@ZzC zvtc!#cTnY~T?sz*Fz+7~6`)s4cV|&_d0_-5`1}6qCy}Ux8n9Zr%K_t)Mbhnx64fja zxvUmtIEC*nq4ee-*(dD4hK{;tb;|@K5#H)mm+Vqz%_43-`|9i&y>M#ep74?AwZlBp zCXbiinmzE7NP3p(CvGb3fb}gf0{(EXC_Ktn8t2l0e&lUuat7gn(OWB`q7zZWcw?l< z{WYl@Zvh|bMINk(M-<=~!#?pM(3#bv2CYKanPSu0J+J--UaKv z*F{aMU2kgN*V6${z$n$v-FvqD!v&2QiCL3I7pt3=Gfd8%%F!?Edg1rCo zQsaS-6TraRwwD<@pnL|_`^KdU=C?t8mW^C*tgA^n2)9o1cfF4>*R?446mIgrExkek zWEJq^0sv_$qSV!`0G9%3H!E(1XBQhyTv4bP)bp0VL@i}cFMn(LQ#PY;cHB)U#%~rI zr15C2=-`r(WndpMB^IrQ_cE|HdOUZeu2nWLg!Y@_^;Ls%bvu+!nehN~^y?ru8x)rM zMJ9-cpe(_ffbQJ>iuoxOZk*p02io$)rp=slnZ{|sQLs4)x>hX6S&IFu{RDbP!nhCH zMd?COCNlmLz5F5G0(58*euJCNcpdM7GT+tS0gTf|inYkibAWOaG;iouhNChos)^>( zIf+)nE4O3m_oGu?Opy;s;vfi>w9UNXAng{=391s2Fjy1#O$J%V#y(VaS6=2HTrPP# zuQEyp<=r$8_y3mMjGs|0Cb_6wmQa@|lmKv5sI|4xzxt!U28{R_=hnHqnZN?BJ?b+D z>SgH+V!T|6H3#nI-b)_}-K=bF;pg4>(Tp5g0;eDo7t@*o0jvAw(*DXo7LjDVe7G1k zApcBv1IeI9&doI*?~9qeExB4wE%nL#apCR{2}Kb5fii4zOF^E5Rgl}P=H$H;~Ulf(l+4{dGcgnI&Y9|W)U~dIpC6ElYJDkt`@gr-#T;YDjE#0Ew zk=0s?C1;UT7juOE9l8M*nLYv0vgTvR*c&paTI zRrytCl`!r{MABHqr;6xDS!L5xK?cz?uivIaPwsl}D{BfPzYq9LJ0K^0mx;)XD&5i~ zH1%f2foi-Z18A@Jc#&fQbdiVb?>xcbdP=}qVTXD1{Pnnzg9I5A=F{;Grv}7L@r3&} zg@81BK`|hwW~4oY_x)k<&g@B`SoIA(lh`ge>O)}To~ngMAdd1&o`INb1uDm7INtu@ zB0$Z;xf<5NwHHI;f40>Au*p4?42o1p?d6@Kih*|B*7_tR-$&$U2og8lr&X`#-!W;a zvueUeq)*LOC5PoaKO$nc2fopIY%+no_=ZiC8XH7`j)jGpweyGK1%s{z^0bl)2>3jx z;?j>oQx<@+dAS8nBwv7puw=k;|oI zID{VIvG0l!SQ$mnW!{po|e z$hyI>he6P*SJi=$9R4O`?(v{I0O48@y@qyd4Pl}&#c5&|p~K5pAo9~qeRKzaMiUlj z8+{`Tmo+kHNZ}Wt#V%|!!{7n zKtfU!$AA!NvBYGeIT)#K=-YR44BeO@C^J1r@9V?X+)2pg__Z{_-k@=D8Nvx#F-GZ5 zZXO2VsYnX`|KFjFl#f6H{%}V9*wyO~ivo{qkp}2NH_Tgz`|)(Tt^3ar+!#ehYA;+A zxEVYjL%;V^nWi4Z9i^;WQ8|6iJ7E1?gC``~A%WXAMIhT#bJ`9q10i|ms)1rbw=hKN z!8Hx!U~ryrUAtZt4Z^>Qj-k4Wcj_#fxn|nKa$IwKd#;|yXI(P*L9(7927A@aE}bW; z?2h-lZwB$U58#-|{J!UhVji5IxEUa6yVXvBCfN+Bp1v=J(gP1H$|%h`S)z9cd#H#F zT3KoIE|xzy$n$K-60dJnLB&-t`Gp{A`Fg~Y?~unMbv$1i3(F6u zDKldMl|D<^76-UL9-+5PkVV=Db=6cK=*tBIYr~dn>D>~G%V*B)93jh(BPC-I-gWOBIf&j43Hq#RhtO`q%5IEW;Z}M@WUzN!&jX^ z%Z<-5%)s+AOyx(^7yh>;X1x!6VLtTy3eo%HHC8@`EHgHZVeJKt9E-fa66-jtAHkKD z@)yBHFzb?DI2jU0d?5^w=G^gYG0?0~473?z|SEnqVoGB{gyFYcjcxp96;jV15UXP&8 zTdAhcQ6&%d@4Mh|H9LT#uN@zy_Q)H*@h9B-(`i4c{XV{vIbzv*oBf-{zCmpUo1_Ip zrdt9bOo-r**b#UrjePBn7Gv*~q}6AccY21P**k1(A9k$5PwwMT@kMJ2NjD3@^)ujPniC*s7I+G@ zf$yfUfVAQ6nIVVBZKe=5yFNA+M`j58_G)2)+Vo!IDNy-_ji9OI6ZU`yi4JXDAtDLB zIF6$*1gLpuC->sx&Yq7JL?o@6&E*4%g=C4-Pe6C}*lH?;T_*pHC}E%#Lv0?5nvgct z1?~YpMdnTdCAxUggpFO`{N@L}7(bMJz$w9)N4}u^*%~;-V-PENPIg7{d7)T5Ra4J0 zx~T8I&p9o@r=_&e$tn8!90dS$DTuTX19OoD2x<<2u7Q+n&OMCzRp9U!yb z2bM@2Pg;$xq?qkAy!o9%Cs;7ym-ei<1dGzpKZVO=LqLs*=8hctHdZ=BK+`@@bPkmp z?O6xxv;}RfE%qXjDQ-Y3q=f48{)v_&*S3Eu+pz^EE^Zm)(@7=SrSg)*?^z$xlR-dX z+lNOWltI9zAY@##MZr)5qx$~obA0s(tp?KX1Fup~SXXV-TI16Z3@I`8Nx>&wY1yGh zV4^^iVc+lS+kKO2-XB~J!sT}gtH9+e)}B4A5VZ|fwN(6aV57wrI#R0wxM+tx)CLgF zk*CW41WS7^^U;S&SHw} z4iUN_Z^FHPe8LBoq}>w`qKwr1$7~0dRi6E)4KNv4|8q|-?ftHPa2}ko<#@jMgCelNKXcZ2Exbe_TNqs)2prUyLbzW}(wN8)DU;9Z?o8Fjx`sqKSm7pI= zh$i@%+X-*{$&-I%i0Z%{2EI|vd!8v40WLiLcoDx9b~D!*dy3UFpI{+$22{0d{|rFO zZ@AjMJjF7rLs^>w(%#~*PIR2WfWFj9<+c|Cgto`i7??w#?i+hh%g7N-Oisa~uqUh~ zHJdHRR(%*Ci=zNPUy=pAEC@|nlp~N#fIoy-g=hLEukJ7plmGGhxyAtbO4Cz&Vhks(5{{IIFOVb|M=;x2w-MLMb}F1T+;2`1Oe}6SOQ8S zfr?CJ&?IDNeH7?{UbOaKG;LNt4BYsDZf1lpfCfTvoU_bi^sJbKJB_i4(Bb&uDkMP| zfzpJJt%ov2X}nc@erEvLCETVrKn9KTWx8!U)>Lj3veR*~J-8ynu6TqiI4F#|z2kMw zcfI?%rMhVZBo%!p&hKD+ND09VF5UOxGig}TUWw6klw zJv4BV4^o$%=xSj)f$!N9xH$Ltv0K;!5jt+vY1s;J{ zd%>m`ok%%^mg_YQXv*r0$~;lhFOb{upSyH0aD;~!ifl}WTL91n+BhO-0Cn-`s(uIg ztU8a2-an5seuRovniGtJR~hv#f|P%8hIwqmab+C?*o#0j1^!QND=Nizk$9={lOD^z zpO9*|VT1%3W@6BjKF+hb8tJg9e7oBzvbKboo=p7_VDN)epDRD7AXxrRJAs2+cK&Jj9ig(=$46={H9H$&i%3PcOL z2knI})kpR!780?lrFh>{1*;Z^`FPMiy&h~PFNv9_5aig8xcBP~yD>aCx5LgG;_&t> zcmjG#UjyQkdo}`siAR)qpX>9Nqk!_SKo9eL=bFh^4OAZcgvcYiSXrIqlH9I94nV(0 z6U6n%T2hj9V+9(#YRin0%xA`qYiu}aHM?@ynE2|qXtDjb3@-Stl-@c&hLBOn*Qq9#_{`#ote3pYsXnH4bWH|Ivv)pUEiFjtmER5yRv_l3%KrL*k@XncVaDT z^1qgsR87AWN_X{qUsZdO`zuHPF2t`T_MJ3yw(v5W7S@5{8*IqHWl}J4Nuo_r`0rvg zlF*pXOLI-$pAvpaG1vA+aJQuPMI;(A*5Y)8;?;fWRZn^8*$ZMDEsHd=Aj&juowau| z0>OO~_%|ZXy6PnBQJ|j4O`$FK6uG^b8y`R6cIuUJ{ z+0fsG*rb(Oo|j5@Ei#H@e@>Op@#sVlcxn$>5`U*MK9B?l#QV{1#b|1Klr4MKPB zhgr+)PXzmd>r(ert#`dfj%4%qxovQ9(%|}NzJqgauDHR%op*?QSt+@o?R)WTTQXJm z`&8s_(MtY8lh8ICK$0>`%XbI3Z-eVlqXl22xVaJM#_N()Py}Fm3Qyua(uylCSYeYc zd_n64QPjRnLQC?>{z$?2AsKd5mad5nd*}VD2;X)K$R_l2fAPr=Q$^pwhGjmY;Il?V zb^3LY=ua+qYa~DJy34s?=2a7@H6VkX5PbUiaC2h#Cn&=y>4FYFVAaY-(4B6DKxuz; zoXCj$xWcQaJ8cJ~v=w@lrjF+)f9RT$7PP&d%3$BA{HR0l1_KN8zAxK-t=sDhw%K3e z@GC+`UsiOzHZc8icLYgS{d&?ObjlCv-_N2=kQ|b$2dP2Ik+(@JN=0AZEm_#R&q`}UpX5FoKY8mGS)?*l2KJxzlSFxT3i?8- zH+S7Z)0U_aEJHv?b&Qv@jdRd8DNxV##?X=z^;gQ;1!5!pzX#Drcrg}z_$)eNFyuB zZRoZvNPB~Qiw-Lbjbu&cY~J4RZKZBB@|689WKY5ae4i-8g6_SV6e-036)#*YM5GBv z8*SWj^8Xe+c76Q;e7+RN9-`yd5-_J{r2O|?-i9V zUKd$V?E(BE4G0ud!Tu1L1d0Ltx_pMNP=0n2`ZO7v7C5ep5^kY*-WUk#!A|Zqnmwy5bXVanwHJ)lHE!1P_W`=QQ_x zl0!C_s)to2iCVfaOI_(MBnduR*8S@ZS`y{joeq9iq6q61UvkTz-2KxIu+c zLYo&fN<2bNvv$nf(5D!;#xr(hLkgCG9NIpKrRykDLG@}JpMhUd*h6(&LOr}Fp(s>XfkmAU1hzn<1j+fGe@c`Ibw`cA z0!(4gkAQ&Yk`#-JQG!O%z(Jk( zR3ulL`C8e8clbHjyALwt!Me=!&CyR;pM7L!zx#E`2qUInww(JGyGqtuuqmIX z+LE?>p6x26gAS5B`02pR#D?awYc<3m77gz1`~EybmO6onD( zv;^@XqDyrd#5d!S;H+XT^ySMcRH7E=X+oZNB#0KU}7+w<6KL6 zut$FzdRuELkTD!u_(J-whft1V@~e0;86+CX4O3%;tM1ji<+%N#c)C%rl(nN_rk@Bx zAY$`mE#Ch+0t@d+{sPIGL0HGQ1&}hm_wN>WYLVz}aB$P!3$(_gyt!{6k}reTs(bPy z02|fNu^rzNzY2+)+nH+mNjt)-Gc#U09;^ zy)f*EQ#LIbA2cO&d>Pk@(1UkQE4mhPq2zdmh*j`nKN>t@)N0$gXP*VCi?w#)JF_Is zAg*rqvqe*SM-p*~B%%6Dd(nxT(&yQqABi}$b=XY(?1E^!+I~12CMhXMwHgl`xnbrZ z6yKy0deLj+uPqdYO)G<-c}vWO#n#3siR&E@ek&WitlN-gpQGnViBJ=~d_Q#ZgDFo0 zl&OrjNh##xyQ)P=!j6MyXb_t#ks>eMWe7tAWbW#{bv{~>ir;5_Y?!eVEN9>*G4SU3 z&sZJ3-?iZL!-X8)p(O>SbuAI?@ncd3&)wZHl?%mH|ID6gB1A=Us2?XO0n}~J#!Ix@ z+7=UN{>W?1xA?xbkxN7K+D9Ytr24?QG4-i9iY4aBn=J8H(*hd`+gwA(Z?Cbm`Y6d1 z-l*u22;GJp@^gt;f^!HB)?Y+M<6|1pn;;J=mx>cat8_W^HRu~w6preB#>!U1G8m%O z`-?)#q`R`ZR;BcF2~(}UV8s(7+ZpLmIUrHSbf1}Z^`@Hq2vYHM>wp}q?p5YnM-vh|&&L?doTsrB0T5o=OVi@6?4iOTuR>XMg*6qKmA`m5ija%^4 zwE_;#p8j`aG$)b7NfjZjei{(1y@OyF84xd^7t^UYQfuXob>E*)yOs2@J{%O(jIXQe zPjU(Q>$ZXpe$9Wd3gx{0S=y!yv;9k>nk!5z!;&BvRYN6iOGScc5yvY&aT;lo@DC&Sb&o@cJ3sQAClU zJ{geh^($<#J&UKVyzLc9iF-w;Za}zgOB{A?EfYiy7}9wF$sJQ{U0d)`zNp8Sj~i|b znFqLbn+(5@F_+w}=JJ-Ii1{o3HM`NAB!We$%R0pi?@I7Y?k zZeU-TqSR#e->muWvYKW)J;@6$aTK=diN^V9Osv(%o)*?XyV@1vH3K?1>fRgv0~IJV zn6vDC6k3wNr*Uc<^b-8xTNgBcH4$O{gvPmn=v21c;A2TQ3_l~Hg0W`0$Qp%Y8{%SW z{RZEnT)$7j8mu;j%%tPZ1kiZa0i$DG{o$DE*X}4PM~L>~8jzhQD!mHl8~|6`INt{W ze&11Yc3t6y4Kr|Ic$#6ek4Nxf0D!Kr0nbTAb#q5N?J3!mZqze15%2+U8W&KR>H)0u zmM3OtmJ9(4!STWSw~|UWEvE4(@wLBGpW zb9Qn+t6R8>h+8w!9ErMo9lkk!=cQL~zH!ArX!5fV$zk46H~s#;saD870NZNCkW=o9 zqGdp+o+AqdLl_u~KMZ6l>goeI?SN8hV9E$QYN6fPH(IL z!eWEXM^4bNN!r3{>EM{b-NlZt(=`tHx|0s1Q+Sf6xpy&tqIsyGL+KfcxPdL>L2dX3 zHJ1ndtk|8^k6NUCk)UfZj|s-T{XQCGVWv06>w65;)ZD)Op|XX^VDgJ`0PTljWTo0| zI?yflZJjQ~oZyr`DSD)}r`d?wQA+=ht@n73tn5)ZnTLigo6J%Y5!qy9B%>lFzw7k=e!k!L_xJn#)9v-otDfgMuE%xV*R^~* zepN`&hdCYnc_Uw!0vHsrBhkw%}Xtu3-)e5Haz{d_>+rY=6hJP z<7k;uQJXF7S^qzC+N&0AK~$J3CFZ3M-NR6r4F2~t;CL`GT0ft$2`f|1f}ZI`5O`Rk zoScn$pXV7{zu^#76!=$FN@A*8ht6=c?1#Rs4LQZL@0rtPlfWoi z+2YhMFL93JWGad;+I=HiX?IHi34S$!VafBRu(O+e{Hb#) zQx0dVh6vf{-604&^8-%5(USJ|b9Bk$va;=Wq8QOfC4=S*u?+lg2QtnKW=lK01*$TV zm_+y0y)<+R7zpk}E`L62`#J&tfH$wxU*>)*2E)GP8Q#JSE+ZV!W69mx0;$PyB+-&ExhSCP~Rd3H%GU$d=4aqTT{8te-fBDpo z^|Q6et)$8BnAJ;!N|-yvPB?+t_ujv6YXoBFEiBS}EB<2IF+X(o^%Z+d<@lDjs<#ib zVZDo*g{s5{QWX9{HF5G%_zVwg4&JxKrz~5jCd7tEcZeG6zGJttL9ULd?p^z-_M3S; zpLpyXYr`mAbz|=Yx2Y2A>~@^m=*uPLn+7Ny)scs?{`!`4fgIA}RKC+5M6zC1(?KSm zibK%{pv}9oY7(J8l~#x@Nn{(A`A^Gy2I`^CcPe4U*709vJOITGZ{BS)i_`BmGHkhN z5TV~vRo{ea1HmJWL^>=t7TWv%;SxDHoD4puuP8a$_pM*GKfEv52uL<3i z%|||Im`8DmTH+&TSO;}8-b=2u8YirgjvjO}*iCwyfayucI%~N7tQ#UF#Gb;HlxKqM z?N#niCzFXay@DAJ^al3F#zYu}ayUp)U2&k+6gI9mjnkLABjA!omi26fR+IqfoOD$? z@Kip!T17uGUFII(nuVflqbsTgo(0k-ZLX*k)b2$<)pfLx4$aB zmM1%zSoQ&c6&CP6Q{m2^g|=8tQWG5GknrGIAV3Oh2a2u-+z1S-xYbn%GCdEIVC$7T zmYoc}++As}BFMR2hdhqdBfH+U(3?cT@%);a>w{(h-OM*6OQbjQggfte$R{8^%xh05 zuG@ll=Lwe*b&E>K&xw`lBZdbi^7}n+DV-|FG3CzBCu=>Kr6@&G`LC?Jk?g1oeTio= zRekN3j0~QZ-B%VZsQF$ZCNNK-Cr&~yjH;&&7(sBq2xUBXe}(uRhv9(0UKx~=1+_&K z&ro7xS#tb^<&N54mu+#8pC5uZ3@;l6uZ~-3#e*aiMl?Ec(DpS<-<}YW>xvuf#mn&i#3wjR-$X&3t*?1TB0ULfPBeoIU`@`Bx^6U#FJLSq|-CqAVvZ$lq?XjS(oOE7;>MYDtoi9CCcs{NK&mq0Q$tQ@Y$NHL@u) zGYy5S67OH}G5E}g#qZa+az6HuF3mctoAE%RNvYMD81?qGWXB)JJYo?{N{*aaqy-&r zt^XSuS^|({+AnH3`gX zJ_d&rK_V#+C`)4Rft1BOx?27e9n&b)m}us{fNm2&Ie)$tGKEJZ6wbdQ4~AD{V5$6x zm>)5Qp|g9K++{jc@e(R4UGj(SL%nc4IGdSzYxO&IVsBhFllywWIw`3mi2B+;rTr9+ zdH#3$Q9sOHc)o=-J<)i$Scsp8^*$#XGgQUi$x3y)}}`eL$l{}%p22A(r9XT;opvpOsA ze$-XDcgq91rv_`!E@%JH4-B8X&NzNLm|+NY&y;7u%f2ya_teSX`A-{kZS(Let&QHozn(i9u28M`q{@$W;kB|X0J?X zi>nE|j??fw_id(#HG%R$OX~lUR?I z<5b6;W3!feG5@B03fDNLkI3M~_0xI5fvde^I(G2xtEi%x4daPb>NEW|%1Nc*tbCJJ za)iYd4x#zTVX3hzz%|ZyX-+zRE*F>y4{=mgRtf%Ib$70PR~PkOY4rm2FB`gR#=P+j zg7Vxmd_+t|%Ztx9D6#V=pWg#ruJ9DspGhaFWEGw9=eAB`#RFtmL~=rkqI#ZTc?|K? ziyI1%0{ARZ5{9s^<%DrG{)=S@QHHA$mp?6r0mnq{B4D57r6?adA=X7i$;d*aV6bqJOb-N<&B(g!moaX{t@QkF z^fy@cB?C*Q2!P}sKgM65E(#!q!^Lrkq@O!%bWlzLa z8i+hIi_@)>=xYqxb9tCh8CX3ybGLSk&*7yh7a%eUUJZfY~QGY2-af_?e z<%1`%i#qud_ijl_tWYv0V9%dv3V%)RMe_b&SNGz;t#21m5B+I=v?t$C3KygteQ@cM z>@tZMuYaGBR=FRcPhHJkwJCa}98{Ade?9l4)Rl0{dUsPtTOV{xR@;-0J5shuZxZKK!+0lUto1cBCXA~hE_$`C#r|@Wg@r{k*D*VD4Zzedx7P>8FVD| z9SMgQUF*4K1)ug-Tylz&xGswtQZkcMW)ga*G@z$L_ z&N!##&z%?PLzwKs>Bq&IQ%cc|BUiJief&;QV)SbK<5~)C#$AZ?(3h5{%}8Du{wB+q z^5wQ~;#JCdvL9<7`YU*Jxpj~{HRxsH&Ll=SE^GF*7dh7c=Xm!1_v{}I(QF6y~-lN7kImSiWIS$=-b6_o`XzA5UA0Zal zlTbG@t=vUrK)IiN43;RFJIBB02H_8T>nrWQR%ECpTdUUQI_`Md5^{hEo5_EHh4zXI zq_a)b80RSO7bUBnRrUk2Hxb2}qw2G$xi=q0H~9zlnhzT&%-l?IzJ0Q;U_acER4G}Q-tu!mFFwe4QH=MsTtB$VEmU7# zT0eQt`-)-MCyD&qKP~rQjC=@a;~Wjw`8v-*59<)Szy;F1m4`Pb+gBc%uP<~$0+SPA z{a#3QABRWwH`sMFkb6UM8~%Z8f?Cq<8OXw2U??5nyhofcLnwHbK;R4l>XLU##aWdg z4i@MCXya$NM{us4HOO(VC^zT`J3@W1yYA|A>Ps2AM4Bw1dxij0D+1gx2u@%ZFK`g| zn1{ipJ(~D0*k<@Z-3rl}bNlC~l4gT`f>mrKicYo4@wk`OTI@p`^9ka_lP=l3 zm$|l%bhH1$;5Esmic&wKE!TKNVI59oBC@q_JSKn|QrUl$!T30d?T1nO{^oZ=Y2`Ni zS6U@7mhf`&DJU0ueAzrDA2%U;A%pRUWr^wu9HX%NAn>aS(C7KvySyF(^keq~sxgQP zOXcD!Y)05Unghes93kUrbBrZ9c<7SquO8eaf88s-c#HZcjlGTOv^?Dn5(|H1$Ho3u z-9xK2aiK}AnTIQNe$Z0Vjxe!)aqAq1wS|teVZX0GkzlLGo8wYfE{fa%=vwzvrlm{H zu0o@hI2Ok^=t_zj{s(!<-hq7vXS!WZ*L}3|I9agn^L^&)ARJ0|e_tG~QDLnHcc@gq z(cL+Sf(Lqgb5SqgN>}B}$Uk6Fl7iJE9l^B^SP|IWR9zPfTv@#brP{@Cs>9d1{xzx8 zvIzHyw5ufqmV2Ky;8|4@L($=ELM(K|x+UI5^F1R_p!vpPMdgUek@j}=u z|7H`GQkaoaZ_^904j_=lqV$Z!*!%}qWEb7E!m08f?;4$TYjug46Al$e^Pj;)kO%(I z;6pl;)xusY7sl$2!}TX0mDoqvu=Alf@>BC!A_!o~Z$rttl zv^a~ieia@xFc*V3^(c4h^aJ2O1h*au$r?uJGi6V@nZgR`CKuRhP-R!fedo_k?)Y94 z_g|2FIMJVRYJKM@D;Z}T29#&w_|xK_(w}%OExnqSpGJij?=F3QMw9Hcts#>9aM_3q z6+R)dEvURvT7+b|1Gj~MRX*~4mHkv6^&`}T@VV+aY-J|)1Ee8bOItqrA;~FY({1u) zfl&xFk478ALajq^cDNF9pU&_G!M71o5I$vtO?z;v@%g=iz(vY#FT)}<=?(cnA>J@u zy9>I~+B$q`3NH5$EXBMsL&|>Ne(U7DccJMc@{lNLn`|J{a7$sPK8VQ`srN=6rQ~C zvY3uxVC4rP$>nMrRt0#DkEb8yg@scw2dL0wJJ1Vs^5y64GAhLc3cYL)sH6)eLiyO$ zrcT~d7rH{DvI_6AV8c0Ta_mC{9ln#O#v;75P0c3A3h-$1s#ivrKWQBxv0pxjY_qIf zP_UuKELb}`l#F%*HZ*J>iOg`FeNcoJ%vCc@dRfGn@g?kQ51?&%6HiDxKEMWE7YKh2 zk-7Sc9#DSvCnF^E5utFmg4ad6Psj4Ako^dXyT+U0N`fzz*1qJ<(|)k?F@pq4F&|rT z(%tdP`@)aWJ8jbiIzKi5(SAYp5nj$G{?%(9XK;9ZG-=i_;qW3Ypu!#or{5sI#|-}w z*p-9KumYNh00?uX>0OSy|0XAY58k1EFOJ6zZ){3N`y)_O3Zj^`jef6lmvJMsZPW8g zb|A=g0Zqh5l^xKDTvIVy@X9`STGyZpE*4UdH|7fdkg{5w-v2;~mvu}p=1wWq*9{QZmlSI4NZg+UjR;6?#@6}OVOk{%DB z^1v8RiRa*$x&3v*{+%=8ou=CWsol7>AE*4SsM@LDihn4E)#{bLL#XpeF^j{72?^$< zpbR5*z;QK;52YS8V`Q@0-wC0#Wbp*f>9bp5FC^v^iTFM_>nw{6IA4dl$|yt@=MB3(F2zTuBQkE}`vmP__tf-m9>0_JMF3M>~=->KrYvqMA zUk^XUJh5YS7=%~!a|lskEFrU&_D)bag>{y!Jh$H0cqE6Wa-S=AKM}pVmu^ZIqfn$f zkx(dFcr?^MXsb0a1zj%UIDmkr4J|(HB-f zOL*8fLN73`*Bu|CFXz$auWCh&$td=D`@*^4bHy*M^cQ3Bgr*d(-#EDyF%GTAh9T7& zQOlv`J0m{CiKzJpod?`MDq986B@9J>_`<1%Lx=>BSO7Aj>@L{_PVhAcKbmrED)6bw7f>zgb`_PmW$2a?o89(~>Ec~&1;UB`eo@{FC`LRRK&x9GTxo6tW z#rpT0Bc2Ml3H?hf<3^;Y-klnLkFE#YboL~nJy9&Pxv5`n-1+@5(IlCK%oN{>jW!PB z;7l(5N%_80mHgK0&EN}-&f0nLPN!ZUQDK7{1<+b;)?;CE|6N-wJyS22*zO!ExET#V z{-&F4cV$%<71>an{_Rr-1mb^vtZ`V_!qrqaLfsvoTMx+Yo;g_C5aD4O3z-B z-e7#p7~`WTN1H+7k z0o9HtjmB-PT-^Oh$AjQuc7lBAKg1%vd$_4yklkl00RS?Z)P z`oaK%ao)b8Fp5?MGQP;h6k8)6Z>7h02PIrU0KVI3HduqiRz=-MmW+kg_E|lHN_OYp z2m20^@fu0oJ>w@PbrVuR(Zh&(mTVxY^($VWZTqr%?*?A-q` zIF1*^TP#{)>G!#`OF{z&2xh63SN&a z9peOPsxQ>g%d7W98UuFVF(w8q_1umB5i!Z$cm*8EAWt3td#g^~w=h3**;ZYJ8?XP7 zSKKuT$wHU*i|BJhvRc50Urc&k5Mz5qJDK}y)0vPFSPJ5hq`dnIt1t`Xh08>hL-_!! zZEVa>2*q=MLW-Bd^e_<7?QkpZc@v$%F>bM&!TU(Ek~M#5Vo6Z`y5+Dh>>RPKhw3^Oayk1|ev z`F2}YEco=6J9YlI3E+Ew{A_JwOrQdi1;I(I5^Z!dl}OPf7W8Fv66==Jt0jC1yS2y+ z2qv>Ga`E8^zfOIAS6378=AbP?+$}Bj1Z3L2`*#sUEVd7R2MtjaYt~ft}{D6B@~; zoBWu2`cwxZXi_=hVhSj;IKGO@K8%!ZJk`2i?!l7Dw?e~V0vfubgcdU-DP81D;z=2y z{i8ezEXKJz?UQHi;K$##&dYAXnda>WA;7N}NEQR2xk78=jqSjJYUNX3;eCmj+lrn- zg?59XNwn_&^=0pD`+_pUY>>>9bNaR816oWtTpv63jXwU0c4MDmbsR$;Yvm)d0 z9m2~ss8PU19E(VJ@Ce;#+9wpF&JZ{9PmhAz1^=D}C7m)`dFFN8UM0Nrwhxr@Rv)44 zPq~~cqr#qYi8ku>ORETrVP~>|34S&1VIjyS?&fFZ5R@+8jb0G5Bz%q=I8nXbKg*vK zo3;bvmX&#HIdp6OGxz$Ut7(|*s}SP&J| zX!bRP8DIRR!;2iHt4rcNujK)>e$q0>)-}s3{E2+89PAj2{%E(}6BPeWbXJW1)9ni+ zM#Vv+JvKmPEA$5b(HKb0;2=UFRKw>8iCa(F=R*SEBt9oP53Tt18}MtF@BPCoMtN9Z z>e7U2Pa*tAXN9$n0(|J-vgO8YKG@@<%i&X-5H<9I9*>!3D*)Gp)SsqdLZ^_roN^GO zMVvMw8=l%rMP$I0Xo-K%=?Rn!r-@FdC{G#sd-qG5J?s+o!i`Y8k8|&Mb9q`gnMZ9_ zKT0ZLsq(D=+8G9yxSRBtm7fYvt|PI`onyWhgsyxV1XB_U?nCf?jt>YJhEKLA9amJq zyQpJ>I^$0V!$I+v4KqZB|G4cqM}xzw#4=FY4)9B2F&)HhCC9GV&N7x%@#OXrf4EWD&yyzQMGei)rhg1_=2 z(l6%e=&PgH)fCt2jhMs8mk8S&kMYm9!?p7UmMU@_M}ivpI)p@!A?bg!bgw9#wKV zf$$5bSV*z=r3UCEzXM0&ab|0UVnHC{)`dr>v;tN5!)UHtk051@1t4XX0`qd7q4O?x zbx#eY8XoQoOP2^a(Za3GyMT%RwfoPwN;oy5^fw`f;yU#o*dkYPc`dQMR>}8$aOVkT z9dVMI&;RQ{7Y+Pmfb;F9RmdKcpL$!-i9k$z?eF`1|IG6*awJz@Yyy5F&*@pEe*Yt@ zeKe7wr_2M*S3#p`7TydUB>S}!p-X~9D2S#uuS_)f*gPGh`aJby_JVX2*SOvYZ$5ma zZcAY=j@-hj_r?=`3e+grZHkl>e^3UD?C zLg91)q_>y!vCy8L!zL1j|1gvP-82)%3WX(*OlEHbro(FAsM&-v7B#+BhZluXA=PY& z7VIq=gdhY*iPmim>+id7Bo+9z6LkHoA3JB$NGII0sB?P4ptG6XE#pZq@K@jF7rvFR z^&TZA<(iZTu}KX=wQwKQl4WLw28(ODx80Hw5qU-=sB>3wH;g?5=pUNUk&g!S9}E6# zPey?-eV_CiWn8|>kos?)aH#@;vibUFgcTj0<@54ccc!P6H-p~6AYCSDHO5Ga5EquvB4PC4oy0 zP4+y77dz~ob;?Q#K8A09^bWlxFQ`y#UAqVM=>^ZFvQ{DdwXO zaEET8PF|TJ#oAPT|5B7J)TbR`kH1q-jYmB7Zh56iD)mw#CQiBX8dKpuV;gs}{bH$N z@3jxs#SFNpNv>~<<9{pkum`GDYJg}51JrYcJ!M&^VqP@EAW2synK2l7l z1nF3%vH+U&ecF<4r}-TQwBQNXVYO|}s5`T1YGi(jzO!HIE1xU7-`p;%K#{k%i=Q=| zk^kKUrT{o5KV_@erzg^Yf_6ELFh56ElHjp}<#EUi?@IxH>)}b=engH>I1wqkRrkTD z;U@vU=1)3TxT1&OJ6#fMec*WR($(Nt3qCPzE!wB0HA42M^R7ImVnAO^_+7*uKXqaA z;UInj>y8tv?akpv zp^!ZeqVxDiy+q=t$lj}>^`B7UQprgi6f`^LeNVO&JUy+CzHEmZbyqF9oey`s?El>H z#yMK24p&mmxnWyHQ?45z_8Gr5Fa?sp@4pC8yL!ac$6`Q)D(NHCRvYR2%*VdYaaDVHZYAyDq~3{g$%nR!M;zwzH) zn`_IaXWmd_80Wh}_Qv0Oyx1y?FfnC2F}US->t#7gxqce7+C3r9>OWQtZtkAhZ-Jxm zSQ=|OmM+ar2{}K&9^EgiB;qDSe+%~)^dMCYK%K5@(*?^*b(vy|YM^0lel4zc?FvG3 z2HvL>FW(Yl&6@stso8TYt6u5k(M~b54uFifKHmCW zJPFFdj@4g0qR--iPVe0XOI2JtNhHT0T~uk|Y}3gfQVuP5v?5E-z3=rqP^qU95e3X4 z7}1abvYPVM6l6v)D5mkLd;Ko1{HRHF6$Gy3IC|KR4OApyz8BiZkia5$6XC zkf~h=(GyFWGfdCB+wKYzHpM!VMywrpSy84BOp_zA4+>W@*t32eakz2rvDl$NsW$4z zsARHYjO0~V{9f9=vQjD~5AB9T@*A@j;0=E0>Pkl(5`Yzr>TFjX^akWG{{Qen+)YY1z1OY7}JJv!|Bx*v60P6CoO!_h7Ofu2g5}5nM8a_cm z>WuptTp}f;atVq)IN=+r_8YPgbi{=*S`Ih_2N2cQiA4+@V`k!s^>$2H1n+Q z@$TY|x?%U%2Dg--HuuUuCxX$bz_WQfiJp@^Nd1!8d%>XwI*GN8%J#zng2=eRAAh7T zR+TFMVtFta{3_3Ca}`&zyTx8i`-l>4|#w47Ai8QvPskdL7 zWL|4rCJn7i-q^XsitDjRXIWx4Rvi=qN%ev1)u#?`bHLj@So21Llh9~}s%>f8#^sh8 zx-r7^BO6zpXC{7kUQ9}de8*mXE_82Vyu0XRh05lY-XQ<`&jemEzi3Y<{vNv!IC9%d z^|^O1eb&rxW#Usxms*vG&!a`pEQ5FnJI|XxA6*!piDX&8)DzHxqj3q`;tj(M6WefR zva`N}2jK!IlvHfW-l#}?NvTQA`q}J%Blk!TnZAgoW0d~1^s@aywc7Jg*7q4?BF=Z7 ze4K^hr~c2!vSk8k_osEELW#}d3em>(_-qM6ShCX`*Z9kD8lfTOz7d0B_Cul*r-kS} zZFgh0KACdLxFkHg*U)ovc1k1v4!nR*8BZb=`SemwXO0w$jL99C3dT{5h|bboqYjt+ zhoSD=p`3whp2i#Y1|;Ds@gZkbnYF}rwSGv5S3Q38hZ2)oRD7-c3I3Lwwu&ka%S_?e zei3P?g%Ff~zx_0>6p>_Ep#jD4|3I2W9#*c8V>aIrO#0UvAi;U!R&QoZjEItj<#qa4 z+DHMS?%R)H%4H$KN}boFr5!u7SbtTJ=)4=YfBR^ti?}URsEGH%U5oa;w*qlgX`JY% zoAUoU;|B?{L(Ovc-{+C(sn)|l3;rid1tkXUtOQa^^S_1YCyx3pxo_gHa`G!2Z z%k5dvhtNw7UfvNYA^9Y}0z8A{o~KXVV1<6n?zhnERgpUjhw%vgU$fH_`|pZQrtAj= z+y7PsIqlJHOdP8i`0wP;jRL24T|0rDVQQrnYKJ1?9)C2E+DMM}Vl`$Qta@G>7ih(k zv1Dr}?jFI-78sM>bVG>hVzW<6<(9QA(%?RX>kqedHl&^Tb1C9}$KHQBneeb9@v*(w z9qc2ir@(#WjE0elGBtu80|(i6SCRso8RDoI?}Opt zZ3A0(n9myLZ{%YGKr)0oFPQ1`rz{*1xwXnfNo{3IR~R`tbr;`VXA5DsWLBk; zDdrb{ISa}g?wzX_-T3X=k_tCgFh|FVZytfV6u3)BmnRTg%x{=z*umdu+2YNesc|Fs zHR}%%G93X5u@TFsEDI}*6u4bLDlLDX;yV~=c$!XvrGMFNJzJ1x{D_R+iNx1*yzmhb zmIaUCkjo928!tweB(rVh{D*!-Vn=76WJ=nYp2UxK819JTEs8kq6-8{ft{?@8Rd7Lkn&za zeRZsL>{)gqB<4wEEOBSJs64AyqoPX+e~bHK?J; z2n`!vQ<3;eDn33z%sDA^Ybd)ZDu}-^pia546{2pXJT9tv3v~vw_?5 zHo3^brEG*C&jWRqM@=T>Az3Od~xGW;c-~mt`=u6a#5TOVpTSkEH?-B0X=$MFXe5aVv;~baV*O7HqDOWf+ zIZ07&A%)Y+@P_`@`3E!V8}JcS1V9w1T$*OaKKm6$q4J<#FTvXU%uo*hjK9X2f@eeS z1Qe<6-nWd9bwD{>6Ptm*3akaUXK%w?Vri15;3hALzZjX`rsQcGp3kOYHb&E@icVxI za8sXeB;<(Rem8KY(vx=YtJd8+2r8PqYdOxDHeRQ?E1VG2*qN%a@X*tSx#MwYQoWOm z3Wpi7!@zt6!q_Dq2n605Csq2S+aF--XNm|o&3}*u9B+iC5x8~>WM3Q+AmYEOcundD z+Vd(K6Hdu;9gw)@H1(EbhtQaub--zG6AO675(#~IxOjd<2Z@#X{)Q+k0|KIl(z^1RmOfA|8PC>$@#R97GU)$7f~#_3o8d8%<8%vJ9%3cB($(qi!h z!mt*^biEA}{C#El!2_8uv$=0z=^H2mPdGWy9&|>rqAnSyj}KN`^Mro^O@EEvnP+t- zl_|~ELTis+4gCQgsF5ennsOYD zz!#okY9kh*iz!NojxNYU$vZ@iULmmxWOiK2vBecm51d?-C?_L5GE-;xF4i!@ebFSgCP^ zU|Q&D7$Ze(o`@e-Zmt4Vmv<$~!c$P)guD_N!yT`>u6L0NJK|e$xa|GGP&qF^A3Nc|b@r+*myEHsjZ2R6=KdRnR#0O! z(6jc-wv>2e1VxI0@Aki6wmMK6K7<_7-pR5n zWsEuo`I=7mED{`LlRf61E;TE@+vsbc0MwlEN4*%Dl;7Nj{sMcV(`Z3|UkOtLl@X(N z160SKY{q0bjrez}zddU~VK&wG)PH&0Ggzn z@K+v22-zDLu0AtHe`{G}y1Qcdq4+~L!jV^KzWf7twKK_9oL(`wg2|~vH8cvxFuB{6q5W53qj96Bl7zf zX`}uqS2($~W||rn@}afZ=yzj&oFc{7h1@#je*vp5@NQ_Df9PzKOWu&d;cgnDs?|&V z%>kXA%v|enMb4kGYxR-~P43L_@OPwsOcmFJ$_$Hp+JgomaF!bL^0xp7ohgiR1O=K0 zD9{!IKMl(rLBfz6VX^He0P6;Q`nk;apNnNmbLjNXl)w)1F$0-FSuc}y@Hj<(t}cEq zAQH=j5Rr6cq-1Cy4m=Uhho&-NmVVTK1q1=Q=DYZ$okswrHivKDQFor?QiD@GB+td5 zWyxD+>e9N((N5bcsidxjF)v{?&e2cB*1dlYE zyGZxfviI!mK3uJjB*DM8lk@%hIS|qkPDo8SYYokP-?*{z>8rAgYiZLV2d9r2xgE0n zjY7otUg02u5RR7ms{jUTL~m8r!OYnNzCk@v*WrN;Q;KQLk&kl=6Rou|Cp%@ z>~)kOWRu=_X!)LgA+wjH=N%0-ecaJ71%|TU$>Ew99n|WcS(1!Xk=l1D%gL4Lad+Q+ zd(fFiMeP&YOCm1;t#FtBEk2Af|G2m0zD*V-{ym>S8A)JFskIBS%trEl&8p=wW#BKc z54)%~eZA>a`u$uMI@fo-yiCZf4DfX=!g0v&_1?5_aWw^zp~Y(1vu(~|68GPnzwHNr zkFH5{{PC6XU3xX!OWGn$!g(RL^J;i5)4GuxP3H%xH~xODU<#VNR@@|MLsn^zFI}*c zOEy-ku)){=3a5$};rp|=Mx$|`@u$~E3XI-{T}}WZ;R|_WM@A0x5g|I^`j(OV3;uNF zRGefkooJcBug%t&5~`J2La?XU6tqk8ux6n^V~+A{N@7l?^wiJC~i~&;BJW{xFX`-%WMw z{?rs6hNa8|^547aqli;0NT5Ljcam#CW- z>Q9Z?DNp(}(Bk%Gzs#r7#uOJR-8Qk?_-!U})tLnKomkp5_8D@pas8u9>6p&Mp6szu z*iK5&jqmL)yN!~bJAegGpMsT|ZeCx-!I_Z7;x7zh4~vn9a71LW%rdQ*Ic8KdMA$n2 z7g`AsB1Vuo5b%@?bZL$fMUjc*vY#ch~wJ`#Z%xKS-JcHqtXLL{WM1L;`oK7j&&T`KSR}_ z8Inxgi#0RyHtf6U_H`Vlx4(a_WjUaSn}OOoP>Zm_3qJA&nPHi$QA{bNjL1=K>ne`<_=(_1x{TP4!uJ{LujA;&QuR%S~$jyCW*UyxDI6iOxL|1pb9xaN=^0= z*9t&$$copc?+1PF1R)19PW%!-scr=c^O@JAc?kxm5@d#0o7KA-XEKzxCnyxn{Nwj5KhAtG=$O`i^l|ur?$~X% zV^hIppl3&(?i$lXV~?K02FeEne}n@Sg`t%0X#yRhRJY$iYwX6(;|uq433C0*g^%<= ze61;BzR=G|=m~xn8}ACY8L!xP7ye#xMJ&dfj1| zdMHbl(DDAoy;;HE5912jR)wbaYy&>^{`q$N_l64#Xx#jtZW_WSDFx32;SBuun&N#D zJ^48?`RMMuv>S%wY1}7pZfFY7Y#nN)=K+T}FndAJjVC`CR#*l`?d*YK`Qb!G1u=_& zlz}hJlE&uJypZCVxOH|EMUYJ_ppOGP?wM>jla-h;mxtF~ygH5o-ppGnOwSp-xLGhY z?v2qA2*<}Ka;r4IxKL%;0=s}@zRsgCYtHsFK!Tmm{4ONRgm2x|@0f4d;t|^|%f9|1 zZ~FIJR2~IJ{R6?A@xguUd){GVCGgSGs zyUhiiDiGKM@woQmPRkX!y@WqSYvXsqzqaFXN$d;9yICD|9l}(OpS89p>V~^u7CAmo zI8RDXb_hpr^z*27{@F<;MoI=AZFa+S`LOe+bTgOp;LF!Eeq28@!60zM@}cFp1Uv+> zwF8(HxaN9$Tjx`BxZNPGfTBgW2|8}3GlsQ|Mis^QK(WTI-Z5z}_SKwg`4jz)UlN9=O5JRv zZ8n64QLHkb3(<`9?O`Au)ZzJoV76%fK9Uw?m_->uy|gZ!ec<>u9wz4TTQeUWNl`N& zKP%4dLn4Nc8&8u=%OoXg$vYw|Lg7Ivv@6W0ITR6j=?{! z*Udw1=?cG$BEVdGYLD;O78=Wy#dygrx%s{eEbtv8>#^``35OCwUwc-UT58CN;u zy2;2rkIY~(vv?VKw}(803RD)z8>8WG`F2XO?AB?QD0Cf!PcXu1dYik*0JMsEku!9M z!*H0W&SD{>qLBUd{D(_w*E!X$9DaIReEfSNUzpVYD${&4laUl`cuhZg=EG!MUD>q4 zai*;ZB7fRJvmoipAiNGth7z!<#i3`MqfWeeBJG8u3tF^zQi zJ76-%l(Qw8?|f*Ti%ZgV4w&}opB>~mMe!(TB`3mRw?WR|7r^->!8S@z;945rN@c^7 zbnSO4&4iz>+6kYZ+PJ*8NaXQc@e`oT(VYjaTRs^V8(|XtdgF;ZI_4Lj*KM<=r1xaP zzJMT*#82}eRr`!NQ%Qq|(ax}pdW*L3l|~>Sdi6@D{+YyJU>k3V6)JrV&L`I4#T6l@ z#J{krtp24(a*u9Yh+~mDYk3RY1Kn<^`4hw}>v!N-9fVZ2>-K`E2Y^mB=D*9o$B{pA z4(Q0w_8E(+RdL&}j`Y2@)+#N6WAi;#DftLD|xrvi3T840x3FQe8nrDc>=4YR;#aw#2yTm z`kcL-dFwK8WBIPON>H%2Io3$mwf{VhjFFI1x{FCc$7rdoOVS6=LBeN&$D)1}=TKz0 z?Vaz9gdm5~$?7^5)`M?=&nbXJv*6{j2z9D}yTGeL>lfjCf#JayxEXOZUkc-YHalE> z`~&RT?ASl27oQ-sZ%3SpD>@54XzQdHe=`l|Dh8)NvbakEsJeoff#>G?8RvoW4nTwwG`5p<|ke++LXQkk=qGs-1q5 z&Mlz#CY*kVT>bL?bwtH}4|;_Abj}Gr4T|mG)&S3(?Pc>&poVF%h1}{G3FvGbCLXpqwbRj>1eT7R&e9#`kc-0)a2ob%Q|!2uYk#a7M~a& zuG(7rmSKUsRv%4zNrv55W1GoT7|s|n>=zk%MvHSxI}lf`sP4QEv<3%TUvYI@5vVk= zUz`48t|0g>e!;p|2Vk9V7kulufy`KsSQ)wao1F2Fl_-_}*S7thPVwX7PP^e}O)?M_ zb5mO_pxasmqxb2}AOeNw2i2SBU5ZU$?!$^x&i{gJnigBn&ygmD!DXJoyuI%fS5MWh z=7(6B-*wBELrL^B9!OiQ&2n9=h%kD zG|R5HHD>o)3r2Gd*dI@-dDF;rw*Itg%Vl$h+i!w!6e5ezYg)HyhCA)qDpki)DDcBM zGz4nwX2wbbpk4ZZ<%#jJ=UEIp<(+E><>NhR$$nmY*$xv3+8v&^@h5 zi`x2S87bB`mL@deFnzS-U>})B`I9r8+c9xoNmYDXeK#hLTC-DUYY19!_okRErD{Kd z^Xwr+Cv^sAZMfi&3I~aIZP{x-ztKMNGXiD2_S=OS|9yuql$8u6*)}SPdC2X$)%=DI z14F3({8tahD;{!+6R)VoKL(8xf^yVpIeuS~m9K!mzhdNaZ#|gJ^zGp4rFPEpUJ#4k z!Lw)ub}>w)L&=*t?cgS8>-$>pW8N1HYVoU4JVGi;hMTFy=U+)8@v$L}>rM~4-`%xs zsEf|c)=k+3rETJl)_ImPZF9l6`_$O^vYsb;Q#^TAz#Uv4TI^!K5}C->b7LQbQMHU& zlc_Vn;|n%_+d=KaDNKfQ%0xVR>iAAI1Wo_&O)}cdF6jSZ>MX;e{GxV0Gjw+--4fC% zH6SfW2m;b2A|V}8Lw8H3gd&K5C?Gj>OG|f3hjhK0|2gk<&L=Lua52y9XYaMwy6@lZ zOz7zfGWaYAQc%RdrJ#6%EzaxC>;z`z(+JET#3g2ImOm?+PC76a!~4 z-vU*SasbC$WMW3U+OLE9qv@%th}uLtU3r}r~5G&w3`&7W@&cDeqz(N_DdmbnNd7B zZ(bT!y5Ozf%>GqgJ8SPGZ)PzM|6c>|ef#u7gB`lYmqfWWFn|;?u&WHg!#x4o1~%ui zM|q5Vauw{#rHaq!6(QKhCiLWfB&@2uI9wHolk4QkbBzGd@hRv$cY5oJpl@J-YI&+h zGeWUd;SgAC)3GD11Sb_1JQ799$x9QiyoW_sBr#}@K{Sft%>hcXSqd!b&Sue*#fRoj zEZoty`#u&vfAayx#MM`cMmOm!$dPcr5FFd4-tdiGN&P8!LXyko;g&Ap?fKMjk8I4t6-6l7SR*iOis2}Q%LiVWS5@;Ea7Q!OJAbmMutMVfK&^l`ne!O`3f*dq7!lJALiZs>7A`*1Rr2+KQA} zq}QoT$LA3z3-dM(#A$<<3MB)oU9x(z4fYLwV7C84Gh~@S*!9E-OLd2s`GJ>mAWdfn zVL~00`F^)9KMeWeDf7Q9fX5}q5RyP~KM*naD*(H5f%3=G+F$(-^C~p+maEQMkd*N- zUSuQB^+zMFKSvON$F+g z!i__o*V)_~glsd2EVrbhVgW$;@w%p^)82iInm=9^AB1MZsmVY~ujNPNLOz_u3IptY z+U&8t03`O-?2mxoG3i5UF@YMT)#h0;}ACLGucn3q@7m+P5w$1Vsrk{s&@bis-&yW z4?scaro%W|b@jakol38!3D~TjGfwdCDG1qsz?>ic5h8M=N-G%@^oRF^n^-QtgV;56 z1xwAiTj^NHfow{$-XmyQ9++ncxgc5<0wQhq+vsB$o{-=vY$8bA(E}=SIj(+DE?+dxlHgozUm#RN3 zO=Fn**c_;8i%r=rUXc$4wV&uVUna*SwTm-kx2;|MF?hF|taP}m=zC|isQgD5*b0m> z41yf;&gKQy585!$pIa^OYAklh;`ovmqc^>+p8f8Pw9R;jSoi=*1`eKIT8RK@Z1cXh zs`tK<$_15_#CzZ&_@SBR18v|I3!+Y5qwEN%?9L6^wki2JSzE;x$R3?)%klHlM zaFn1fF5Ghcw4>Yam==|(ZhYk2bWJIKiLPQQb<`|Iu}iMsD%F48PqN5MOy*$P!4#T` zg?`1V{N(qN70nL*&&Q1iYdJC&ikT-3u(TD%<&>+f1YuMe6_ z+>WTodEWQi2!Jc2l`(LLSk;wOgmP#o_w-7@t^REezf8?gG(GTYCsG`f9MHL&2KgJf z3frpTvc(sKV&ra|xXM@u z>ol{_x=#!NrhEdP2c}h%=27EoY%GF+9tuv@F4U3d^F;BjfhkxRGt}hyF#Hkj$VY>| zvd+zhBHK#dXy=tU(UzEz-c74Le6zyJsRgTHDANUyfYe@88GE)>H@GR$xd5R!7d zib>D9z*|LR6j;OVUK*^I^~}-}x5NY3+k3uu(V(acnyH{@*J22v6|xT9<1WG6!5S!u zXzMYh!QjH%0~?SV469}w>ZhE`ZWR~hBYI<1bcq?(kfSe+Q;}N!AG$aZ7>9;>xF7dg zT50Co=rr-!2_<51O8(ZT3Ko+25D=Ol6>m(!?!{+hm7^cuA~|q~DGIxp^gl2^er{;G zob!yvIl3>2-z#?P3QS-Al^h`l-FM=D;Q&~vFB^D>nO(mM`-TVNRE~@Ke6!KDR~sKn zUfOBrZ#951PvH3jK*m(+r8klUn*^@HIk#!z@gql4bXli0mU8{(^kNUSq~B-c=sbp3 zBO@>tb~Z&5Bc}zg4EJa06vmsCPk)`wyAppXtIiult++US7BoLozPdR=N%GW7}M^x9$5L>SG->JjH(=MPtH z6N$$EL>Nx0x6;sxhgip+PhHDk;~(CZIhysKkzx2OAEEBlDxMkcB^RtZ87V9qkkXS# zjnFCEnE3Dwfwsp^fMWRrlpNM)ny<5*BE@e0VZAObyJT*kD^71Xo_n;)Yl__P->Q6pR#V#7;YmupqP*+78vcqb*8{Q3_cH0r}k1gVz; zk>Y$9{3CHN2_n$Cy0}AVpHgwG%Y^#Z#h%xBPHltZ)YplI+%dY7Z(3|OH~ao~Gk$|y zw2_QwzxKRp{d$rLGWS3I+W3HF(&wve5&YrVlhaj9Ms#y)esGMX2!Ju;kzisW0|kM^F}zSw3b6fN;`Mk9L&4diy1=zv)Vfr1(6h z3fTA<<|CYlHQHq*u&AAKXSc=cY@DBG``l?Z2S`Y~>5#N*B7&2Fs}gqXw!p(BpfOOW zosb89W(H%c_zxA{bU=u71RhFVM|_t2h;!RFk>7nU;+MfwqYwheU2gli?9^ zBwx4_<-0uyaFiG>kHAb%8|9gP!*4TmX~negY8x`t%ux>_;^#w8VPf zk*KRu6x-urbvDsv{wz!dh@tNf_?G3XdRWWR=$XH`x*Vg`I=T*`Q5UK8Y31xMoKYzq zf8qvZ_fwL25u4qF^_!onKksF4uWrVx|KvZf1YO>#4GTKPsE}fGp)H$dTVzk2cVsJ0 z5D;mu)e-!Woz)es2UuhQL{-E{AYG!Zr~wjP{piE=Yki-Fo70(7F9at7U+XJF0BP$9 zHd~NzlBs^gnG70=4OH%`l0;?3ZV0l=0*-%^2yqU zT7mkUHN|*W@pDG~5RJxm*2j^v*1cjJ+>@k{_B0j~AgJv1cw3=rtMiq>;F z9xE<$eM^RjMFMk}%t&ixfAA}89QN=I7@x!Ue@5vGW#QFJ##FqqW3l^@Mu*Hgos3`? z=jzW_f`m~g^(N5i3Ul+6ID8@b%LUI4A>R5-UGQjYMmD3S4PSh6A#pb9?IfuFDQp*5 zt&(E*T;^QPq(tT!q8@UnsBd<2XS_NKK1vfs^!EGCyPnAiL_R+Y1xSTbkdQ^6vFn)v^MT>IkM{EFA;?1cr zd7{2#Vd3G!P63S@qH$r}x6FJt@!yc@YPU zy*lV`R}er{5qmmj61E>l)~F@9NB)R-hfZ;)!`uXJ%K9zOwY;>OA$No$q+YQSeK*y8 zts+f|f}D}jd^#x}qwXND8VDo(1#aWZ+I?1= znk_^wuBu15V9kPVkEM}@QOwI89@{wB$d`nI#1}%tj37#6LVwLlU8tX5O+4=IQPV4# zYV=rSKvKQeqc3!@fSmsakq*x}{;&rZ|4Q#npwYj$cd&R_UJYgo2Z?lU^QSwd%McVY zElfq?$uDax6!b>GlqH-Y2_Z7)st29j{`<@fw=rpt!}Xl2UbeNXJ>{g%cS>99*^Ui? z+Od_7<8F*HtV8>1n=Q^HO0o>rd)TfpD(yev7lsdORXR!x77JK<^mZDd0>*mqt<&B+a!2VT`*6W_Z`eR6|8LEhuyd4!`$tL z%R7F5qCC(4-PTTdza2wx$=A4kKRCBEfBmu5gqDN2xI!S6Sq-~p7$kt4b%I6JS@8nl z*#)HQlV|HU7f*X(gGuOz2QHbuc#a9u6bE^o!9O6fvIr01Lg}UNdy>if6ItjjUADqF2xDlW8To_1Z9gji&^t9h+ z-^VsP(Wi205bpNYMsb>haSV`<~-Q3dc&viyj6DCHAAtgGVm`D)>5shChY4PE^MCtJMc9=VT*8l5582uw z1Lid52Pra!u@0{^H};N;Xm+Kr>00x`Y@q@+zmt0FF66mio_~WbF-lrMLsarXTRuKN z|ET91k9cu$JA)fX#`&C?<-S7I0=RD5A-cadALh@bXwzkiO$y7{In<7@`rSD(n<~aO zeRs(5&e0amqI3Nyw*A$n|I6p+BuWG{g+$z&zl{AZBG$89ny@=>a?TE+ScCSB%Ka~t z*5cFFG%t!6&(in2_MbLMCP;{V8i?aCSxqBxz?l&JM5LZ#1>)Hic z>U*0Tp$o+0?D}#{k6U=3#2!&rSSYrx!j`^-7|B8i0uF%kLWyZo-=Z}!`)6(S)se=H zd8;vS43`BXby+zEFtn8{S~%Xf)^3wYdO-qlh|_*dn~4ry9Z{h9w9-d}(BYt9>cGes zXF2_sjx_%&;}krS65-75Nsw9`MB~*T{6!b%3s2zF6Y=psiZ8#KfFRH*~+-H|#)c|0A5GKlyj_%e;{bU&C&y z

    odmKJ2^(K047;SVCa2em*Wf~wVlH42q{W7D*%V#VuTT|3LfbUclxt(O;-Mq_|V zemJ?{bJ#&qJurD|YKIRsoyE$HD4?P55N2(YZX#edi$~41_?RAcPMZip}myiq*UR^{Xl0tB)HPJyk!~mbS(W9yL}y)pbvB>FnJecUMt*l$w9Mxrd_CJ z&Ffm2(jVIJuV`?+Y%K;`^5A0Q3eEk|3p5Mk(*@~~Bpe=UI;G)DxO(wr#(ET`4srMyAHk%l_Ca{xB+1MT6V7VDvor1S$JT&=}`Nq0*x zEah8%#%$iyj};2BO}(Pnww{w+{m{9cupUY}my!oP@;-^RbetUC*y5`OP^0OLjY+ zJudv-bp6$)oy-CyZs7`WXQsuC`zAm9Y*Og0A9Nk`b-PEd2Q-ejzgEh_p2v05SP&2@ z`+w?x2#z^?&>@-fkD`!Nj1eZz6ZfT#cQFAez`*e)%$i1YT2jk>Bw&zLmuG+t9 zU6~nwh!AL)X_1_D?u;?ITf<*}WH`mrL1TyLU4}=HD^m(f=%BDW-5AT!zE#Z+g>|EK zSBi#NUtb_%aD49nUFD0h6^mB0N|SaaFUEy`i?kFUix;mI-W?k70OKwy$Z91W=_TmO6x$iOuJE#cxr zXx22y%Cj$C`QQNPkYDu(9xInhd|b1C_vdO=WVv45Zvs3t2E1_@JEUl9K`|b(@O}Q4 zy2=KK9(#U;cXv|m|C9JRGlyMpB**)aW5MQ2a9h*5k+SQdGJVD%{vtdYOO8@e86F}- z{F7VL-yCC{qFa-3w!k8bqL^Myri2maZ>_uH8kU9(4NH%ZOD#USmD4*_+9=LwalXAU z2s@XQCGs`VOEhI{NTSs0%}_E%;gAEsJN^*JvoPU&JE*tQol7uzKJqB{18wR)x9VGi z(WcTz@ooEY^26+(vqrXQvnyB5n(rEQl59|!d)`TG8?^a%8g)L)iq1RI38h){-up|} z{wbX!-qf<{X~LO_b+&Rq%e6>ASxTXxyX7b<7EhEuGn&<+ro}t$>p3N@G=hs*T?6}{ zaylGMjiQMQ)zrRLa}s9~U%sxo5I96k9ZUg%(!jl*OWZ`|fuuV(Q1rSwERbKm=BjPK zS+j_f{6lrkx5eP(&am?;U#b(IVRiaV@HPlB`zSV&BB2c!ZcnihuyQjP??^Qo7Pdr? zUNOX7&i88xJsLZuZ#QbI2UKZTUS^jMf}*x3FXzy$hyg4cCD!*9B)Ay zUm!da)e$}ywcq_XbKP(YC)Iv+fU=GE2L*xs4}#2OV1Ayh7E+%ZWAK+kt~@J{ppswq zv{1@B<)3pMJyFT(KAU5+@oLeWy=uIDFMT|-fX`nupYhJZJj3P_Dn2f2+MGu&Wpsp- zx=LajqV{f89)RlWG`#w#po{yFSnS`eZ%k+){7moMNBspp0Sk>Uru(Buf^P?H|o~3@nTP zT1UA*=@r7X!f_Z-7a*$NA0_sDz$(DrGM+Rzc&dx6xT3@e=4L0cOE{j5(_e_OpUVfcXrz1C zWzlo7#6POov~fb>C4TQO*fh^lQXf2`BQ`G<7x=KZC`$h&uh??vwO{1R6!47 zqLzb@c9u6kZ1Pe3F~<+189i#S6OwlI#g<3NBq^iOXiAi{CrpM^q>)|Wl5gTB>K9^A zPV<|gxF6MJdS(X{ePxBBCEk9mNyBFyv_eRO zqcYxsImLtcMDjQ5OKv**&@853L7}MVgI2F9AkRArwlL71gcODvx2h6!N z*e9TBBX!yOvV!7P-Z_W=%zFxVQ5}hEA^z5ckV-#V-3AdioBN5&%JX%4_&aFDGAv6} zBgly1n8Jma!{qw3^{n3Q;d?~bFJoX=Z&eu2RDrSmLF61v5 z0ST3sH@&x$glQKN=6u&Hw5E9z-%gl??TEbb3cvdDnJBOIH$Dz2G7Ced%#TAtmg$rJ6aP0j;?LMf;Cd-I))A-Bh zTR+R#_sOUTlte$~$7~qf{DC9`Aab(@Qz)N1PPT z#V!nt`GQtfJPqg*=r0uy&Xfk8xzu$|17Szh z+*X$)1e4hMz=l+zRKJMb4xb{wHSjY^SI@bCxkF~|^(vc9ol2i8{rzES`dN58nG$|b z5=d}d+mjYRslyh1Mo+%sS#QqUt5Q5tVfzwQ!)!xX+3InLFQ_bNIPFN%92ZHVc*#%s zp=Ryja*Ui8?!RYy;H;QpbzXbFc%(Vh$R|DD6wpE0ciO=KU8Lw0z8sqC*T+S=-#A`O z85MlmeN6p~a3CkP9Y)Sz@?>r9k?sxue7~Pmv%zy%^mHrlM?#=FN zKVjnUyZCkKdmU9;+&Nx_OefuON!AJ)Zn=+2_WkrSd#*X8iAI=~%lI8gp#hVzZO`r3 zno-&Tb3~XzJhSw@%M;!&RP!NZxRaXx-A}pVCwr_CVr1UZ5>KS=Oo!YYuRKC{@~Cnl z7~t4A-X8p>UD;Scg1x`$-xelEpi&Pjgxh+Ckt!i$sE-2~&ZK@H`_b*LQ;8!GV&pI` zn4VrM8+b6hwBgz0%~sm*(&>$#?_Ph^{RWckUXhXYv_Z}rj(_*z@oRXk5o$`*8!{?0#0Bt`8)2Rm9LJSl<^(w6Wrgu}c0I~9qD0@8kc(&k*VzVo)^wh% z7KjZa@SPv<)mC}3WTQRs=Q8z;(py-iNBKovz>3q8YM~|8vypDah>X0(!o;R)TV&1R znXu_q&J}D$Y4X6;?r;;K51Eq!j|G_v@;>#XbOt<|PSx_u&y9-Q%&2v6G9~Q7kvuyW z@uo+QMS=nq(_IE>C~FOANu&S9KuM=-x@bvYNCAe)p*IS)w%eA5A?nw+8Z{REyQD(~ zSD#{x_}Ic(A+PYfbUstr${)@3%U@Sw^|fQ$^-zcpVu591q5$B9WP0 zB{9a8$9OWrYKXrwfQv;OmGXn0W$=pBiGU=CU>4E|apTI+JHHPqZQN(3?~<(BXu6#J z!5_#(SDPRxc8MU^4^&}X5MSfXQrudt?^5H;-!IX|SWp~~*{C`YFUPTHVso+`IBN~X zrs5pP6W`yVL;ae?Q2~8JjXJ>BMGBA^3#e4OWl7i;^~kItJ1L={v$C%*vb=fyhzfsj zWIlQ$4H>ymTg-#;c&mVA0;gC5NhrUd=U%XcpXeR(4{Ulgf$ z8PUuepI}R|Q@fGK)8$C(&d!BO-{cj}e`HOfauoM&2*WNBk+7fh!v+>R+i}Ji#bsXP z!eaJpG_z%&y$r`f7_R4Y+{h5|yL9>CiB^l0R$hv5cb4xda_{Udm#>C0yO%_G(@p+|z(~_%8;e%H(cDv7DD0*`U$bFvN0p+RA zo9gPyp8GX!iSD6w0uG2=9S<|e#b0&*w>tHNZB>+VyJ+KVn!1l-UL%l1wk* zY<9nsfkZ*F4-$NoT?SdyVnH*H_V@jUKpux6o5ng+`}Nid=D9lg=uP5Aas!=t)WaqtfXB6kG24MwbU5(U?wc>cq^u2?A-}r;d}61M%PSi=>u;xcpDmp zp{Yj|^H7RyE(6bFK<33Uc6}ZA zkn%9C-ukV|FqA#nh@NIHC=D7l79!$FooSb3>XAc+H}{1zb9wY)@uNkilWsn2rJ@_7 zb3@9wheALM*ohv;N5(Nib_hJlA{f-XI;J9e(d{4o@7M#TC)<%Bhry;E^TIVnck%x~ z7equ95QS&d0#k(ZWC@;nL#{M5-PXmw!T6fKPeuH=%yRk72Mm4QWEo}lcF=okE21a+ z2y;vX!Ui0z-x=^>t14u(XI!##k(a2&6>WozPY9NJiH&sI7l2OC_oV8PMOdV~WN;b2 zL!>yg&~!6eg=!y0DCb;sXvxUtFHoH@*RlOUxhJ6v!gzC-F6)OqNu&K z>bG!MR&$Bw#Dbo_{f+at{AnQ0vb(1beaD;ZmWC^b=w{KkG6QKHBC+UW4lQdM3t|>x z2z+xUJhxpALSNN`F^~YakoPNK^(#l`ozCLB@tIuHs!HABEn513wA7jYCf z^L`Bdf(gFT?=zU9Z&8bRTZm>tdhBC_{$Pp-on}Bk$dLGYWBw%q!GjMM<#kxtcV2<( zEc}prlH4umql=xjq9wTDVRm{ZYEB@j9%>gJN;E&c9f3T&f2*C#sXcHpeRe2+ON zpsQW_=C67qF?;kn!IMpT0p^hR_{}e%QrzK7KCQtr0nj6#fP$o!0Jgei_aP7qlrMJJ zei)#pv^U{!t{~h<+05WR8_`y z5r*f!e0vW)aXb6)*~#ot|s34EE&@sUg<0lr^P#D7)v78KcFKVzSzo92AI{_R8Xeq-J#2uNw)4 z5Df^21{>wz@zsXMULfU}AtZ*{*Q-g;+<=fRaPA%E$s{0(%{b&A^mEA_D$=HRMbkD~ zR=^)~hxhy&jT31;@2CnmP9WGxBS%+&rQHwwoSN%vUq40jV;Dfs<9*3~A$9b(e~u-v^N9GgnI4+^7c#Q&iG zF_%Gf@y~ty=TA&o^cJot{jT+kohf8f&lL=NHaI+59&j%VOek63M_0LkHoKlpW$X2~W6QoFCakgWrP2$>b!UKt zK(E%pSpBN}Zd?2Q0za1Xc(ZYG*nBvkh6&vTUCvG$7{F^L*)TPFVE8^{#K}1{Dd5^( zBEBgqkdAltXC`)EKM`H2g`VgOp&)a7UWGvikPSeWi!oc0NY z2Xg|47PbMs^ogX*94aT&5Tx|&`HK4l744F6%0i=-B!;1GJJ%zgx=qIIH6@kSdY}|& zco&V;Ide-O^#(o1Bj za$TsToT#qCjOZNz`@cyno=Ei~HtIolCDCHi`h0#sLMd&RNHDrAS@=o&{k`D1*cvG( zRMs0dF{;uFy$@bDblCiriUJrlWoWEB4Ho4s&liEX_3vZO2(Lm)=W=h-yw=4Ib3Otq zD2HlcEk8L$d;S&+j!z-`wG8O_B7{7lLY&1}Wev-BdZr9+u%XIL4fQv}G}z_wg^*>a zYi&#iStaIt zo#Ec{6|Fb7~ze_xsbrF&NWmU%6 zGMj)tq|y0!Bd0zuGDfb6F6$%VcAxIIH;&q8&zV}JXK69HdY6CB%&NxPfvFzQyLE+JJ3ZjG(B^MltB zF6ibY2+eE5$xF;dAr6jn!W4Qb@{(u;XLv``Ere1x7Oyic2-aiVym%>G6)?4s_12g# zYU(=w_P%2UFdOZry56#R^RKkaVkUxW6t(@9$QEmcjokevqJ#cB8iu-u|IZo#HNbPJ zK`xR*wVqrY=T!-x!mowDHh{c9gvW;#BX)7HvWwPsoCd0=^kQ~FF5UC9y$#R(*_L{j z{QimNTnC{mU{FQad%todG*FK3VGN&RjNVSGI3m0}-id#DFCnbKc0Z^9=myHx%=BVU zzP}*+lf#towW&LX^@E1Cu3G*?wzF=x^X}tibU&L^Z_A_A#>roS2eYA6+APu-iLfV^ z`&+-YCp?=}0@kL74eVwYkuX^m&OMMSS&_i&ysG2^cv>f{<@TR&5WVv24#&syKk}cW z6Xa0W2GP(>?*8oBbsY0HEk#5bb$(+An6}qnCX@du!eN9=Ks*!+g~oW(xb4-ae(yJ6 zjEH)xC_XwT7X2#<5vyc8wffX5!wX9z^6(DKP2Lt&qQAv|FQmcZlLe>HR|W z`d5TW%>x(X|;J#1C*PBAy)OaK)#cGiaYp9>#LeJ>SqbGyZvXlX-Fd9o^M# zU3{a=AZBCKCH62RL!kmf78U>QZj9fvH@*2Hj0i9McAWmJPEMcRFG&clYKGl|$`q|B`Ek_0RFEULgSk_1r#A|BKr zlQ$scp|L(4H*05}!O1irS~K@N$9i#1J-nm3w)4Y}*VLo9*Zl0kar_MNvCJV*x}c|>es-_QNcXGvGBioHh|Va7H6g82DJ2OAPKq-TG@o zJbdxyk^{Fm+$A&;QKG_Vx8C8;9!Vb0Zs7R!75ZazaRxTK1vZm4tM&Qo+5c32Ic|G< z(Rb|au@Fk*5s@BfM0skaGE5C0g;)y|YcQxmF?B-#R!-0b0J2`GVc8{&U0Le9|0W3# zNQsI2#UX@zCt&IS3_`(?{uh1EnJM*{3ja*i(6j?=K3`rrgZXhLNC@H6naam8Q}qYo zb7{b^JaoP1(HvDKg-zW)zuIH@IWxj|3?d;sQBkE?MSZ8uXUr@OfOo6)`s?1f_hG5;w*k|Mb zk_{^_bblS@%NR8jp&a!I?^?!Adx2&QZDlBj)cfNBzm|Oa_+Lw*>s*2u_*ukCEo>lI zI+xO?yovk+lNz-^#iGJml-SFjL8$Nq#O<1u0$^5+Kl9v)nX ztu#IE-|h~!_w@gnOq9D5AoeYbS>5G~6^BD`htrNVbP&Dwwr1ct6$S?8>&{E5IB#7# z(QshhVS|S#M;R4JkUHQny1=nbL(o{nJ;HN8mIRTyPgQ&l2)}@(anCR#S2IvSK`T#_HndUF3x!(-^H4KjFv>0Xg9Tr&$qmP ztXGJKZ6}Y8ZlURd+%}I=6Q(deSEFa)`b;Wc8-7fd@V>N-U`gd4k((^}rH=vPNhhL& zuq9vrX~ji2n}pjQh*PmO5hp8VKFC3PjAQ9O@04&gvvB*Tu67OF;>+>n{%*`XgmB{i z@S1%DK%@~JfJ#d;#o;%$>%3Ic!0q#Xel_RAdR&2ox%26dF$&4+CRc|;m?*~bPP;rh z_S5zeYUqWpxoZ<##OltTy&9`j?RN|S3O_j8)@BOYSTm7m5+b#@i{Z+|mMMF+{-*?O*J{?vB7We9$@MbDdcVNnSW`;uI4FIAO8omLwx<$CeC*Pca+vrt z%2}=>$}h-d)GFpkRE9!1_(9NF0#P z54zoTMyQ?1alLJrWGgEF9FHH4{jxXXi{uu(!BS#amTV79l4c+`)zLaLx5hq^3m4_7 z)&0|B{J!e6yR|qSN~7O@Oo3+p9YSlOubg!GYu(F=!B6~%ZIQ)?6v6b@c~|^$WK}BG z>gxB3AyFL7%mTF|GSAd(UV`SU7)sk!RR8bS=c8R|>;bPdrj#XghvSrTCJD8VToB-H zN3lTZLZP|YcY1SWFrV~(DTHGB1m#$a%GSzgyS*`J{bvq1@ytDce+y~fn*>Q0_gtwL zx*77Yx~@%!DysI@3^WJw5^Rl@pNk+F!`egE4+QUZHRa>rgJXiu_g?}Y5<~q98^JI8 zCBLm!(^sr=4PL`>vRu(6s9KKdSjdq0+K*L+MLo~X=OdX&eA&=lSFhI8kx|sXHi;Bc zm%T?baJn1`OjD#+I)Z4S4njd!d|0G>alogh-z!Iy_^J?Phr0e-ILeE9QxaPamy0zN z*u0S9K$Nh(xr5+FrqRF-inP#5{5QXPB9ifW_s;^tQ8WZ4C0^s7XKrZA-b*9^;mUM6NqTE4&XDB7==X zp=nczrgBRV-x|vt405|S+z#UQ1o1X02QnS;P35Qs4%CRejL8*Ni=a=I_?>rA!jM-tZ+c9Ez1L$vcU`b5cdEnC zw4h9N*2hKQ_IuxSOU~HfDivcB*(v+7U(TT}*!9jkvLZPIVolB^Uq*1_G<8XyPPRF4 zR8$&_!*g_&y*~c{1Q%8H$Z3kGSFo%~#0gPL1Miz4eCg{0xvLmQ8XYJH2$|s3HTEh3 z&PAiIpJNZaYbR7E571gW*~&2}pd1G|x7{kLfpV`?L-2#@C(pHM3hCureli8?GMFPP z;95s6NW9H(JOXzsa3VRzY%GyU*iuv~9S2aEWI(9@+xKl(je^$EbI>;gDNGtZcIRGwJ) zL|w^Y5{8AvNyr78BhX16eG91~Jj-8iGnZ3>lc2ESJV=lK(yWq5>M^X=4~^znGg>t| zne2k%ZBBMY30gI>^q9Y@m5Z8y~jZ(#zPleP#Xh3x zu{aH*a(H7)k840=lA%klES)1_TBjZpAxoVKV7dTp9&U^AWE%G?AwFhss?*u|5${7( zW_~0d4&3k+Y!kF|L=Wu9i3#(t;96GkMr~FKWP1v7b59EsV|sUkjta_CEAzR zE5~T&p2XomDwn)}>Pnt4DbRE_?~g*&#DX#yevGm5%r8DZG#4ksKcjD;`nAp|)6W!d zRy2z_Y1mo$9fh6a@HbJ%j!8Xo^CT9WAtFNNv+ke!l*unsJk&?=r_ut|?W)(Z)kh^t zH~IU2evQ&#V%ejf*K&JN_J-TT-4|P%@sfhcfjnRcP&jS;4Tp`y#T|9(>QX6>?LaWHF zVHV#@MVORr6pfK?7g}^r;^II%z=cGZ_+g!Q=i`WzJ$RJ9S;DN`QpR-INciMH>1r_s zT>ds)M$dL;j~?gwAsUmw?_3;?RnL(x&kGYaZhV|yfJ$W?$vcVqwlWIC>BT4asto6* z7mK6Yu2tpf^FI17?mocfFEUHN@h43f*Rx7)$s$y#(<1s-4F2;k&`$7&$^ZPE{5See z6QY2OqxM~6=JAQ<=sULj-E)~UDN*^it1^;GT4`V=Itqp;2B)-Q9Y>N@iuH zy>H>c`1Zig^Ky+nzgX=P*BPOy`VRVXZ@t&Kyy5`oTl%LNDB)&#<}Gp16GNAQwU@(* zF1Sk&70U5kkl9-~*nTx|kFM$?g=#Mj09Tbot}^TUhVSv#B55)Sz!4f46NzADO>a=R zjli>!g)#2_SCa0MZ6YFgu2&32b7qhU%Ye(3vx%q#IB#`M{kI4JdW~BGH|%y za8#GpS$yczY0h~%CLDFqo@MJUA}ug6vGyE4>x~adbk7TzB7+r66VE!YUy@R7`thV3 zY_S$hh0dTkju(y(&Tjb+W#Q2Xs$ZuxbArO#=S+A8d^?h29(_vL&dfY-C5KgVhA2cw zWqiGX!chRwBA>EPkE_sbRz182kYmzTYvmIU2WMC=r%(g6o^Z_ZQv%5!tj%N;K+#)s zu|jwErlPHd?maahgXBFk9<%=YvK8kZtqJXO+yg2C5OwjYiLud!YxQsom8hM_24#ep z{Hr-nTYLBDA{f#mkxxBN&G)$ku%sj~#_}HB;M&V{my&_PO z{-K3#yIw?lD4vE4=`&t(WO$=oj1i%^Ow4e5N`A3v&ZKlfL}j4_?0wTsj8~j@>YSwa z@3|MJvv*e#XM0oGQ&ZV@d%yer*B{UDTzPw(EVz3#O8Zx3RR&|*5(az7RE*q+eVYmD z$$Ck_dgus~_3lG`S#~3v@?JK&gh5EN)#A!**`mviO0Cb?B&HXo^BQ=Qr`MC&Vky;f zrRD(S(zvO&IEna7o)NV~9xlfMtyGvUW}cM|YbzG0jFere2c7TQbOCF3rFZSW!OEHg zsn^T89vZsONVM%S<0FPd$Db%!{=_PH7EG30+ZiwTvg+Vb;J=-z(HVPQcoCDCLSy0_ z;hF-Kvn_JBc6Xyvtt6}*zG^Z_m{qrAobH|2&V&>ww}y9}my%z-(G|%Vy!;27-{x*` z_v&r>2ir8=7L68E9TctEB0dPJp)aeFAl-i7b^4i6I8Jixh&`4HuJ4;n*^cIhUrs-l> zW@sPWvV#d&ZttVO4MA!+@o4e^8jO*H{T)mg;u%{~Gg1D*U^Cv*xH~-A%z;MSviSIS zI1$qJKd3ij($=LzvxmEOm$ zO0BiI`iR#=$w2foYy^^tVnahbIY3>iX{OMFyHp?-qCg@PI0384!<56X33EmKsrddg zppGcWF+=Fj$>htoV>fCdo4MnXvEA{n|9aW67wGd_|IR`hFS>ygSsoof?1nQR6Cdk- zZhpiE8g<3l9N+3p@ulDn*i2++nK?e4)I!WdA?dWNO-~;AIUI3l%SSZMwnSId19xTr z!E+Qg@iN{ixm@yH&bAx&t$Ee2WctJV)P7DW^nN|ce@ zMJD|(3qV2sllrd^XJR^uoQ^k-!b^`p->W3+Pca>nVyx>*SDXh52L3;ytaj|R7B?12PdPF84Ca@Fxe@EOvv6OwIQ>(Zsz}C z>n+2w+S+zu8k8<6=?3ZUZj_L2q#H!KOS)U6LApDnOG3K4kq+tb8~5|>{qE<-_j4Vt z<7Un=$GFB7XXwSl?Q;p7)F*cCLWHpMe5`&R4eT(KQ3oNSGslwm%u{`bJ~UMPLT(u} zgJty1xmU7K{lWCKY=|N+;qveKhd^>(@uvj2L>i`~3~0(yY4>jwTYQaF*Z3H*V9t>V zM9*Fxn%NuIkyn+8(H-BP!V(dz&=kEQrF%$4QVC_Vuad&AzIuy6h=y>I6fN|+?h8_* zz(EW9!fW)6#r;_4JI06{`ypFGm+nTyr`mT?i6VM_lrq;#jjyvB10_~5v$!6{G2T8> z#>Uf93O5>#rL?zyJRxJxQu2#{_CwZ4^Mr$bOLWzah;D$f&@qavK{Rz%W?2Gv_Xwyk zhs&&6TC@3n?+9tEZWaC^$aM=RvcY5fNLf2K|67HnMTf}DH{Ew>G$7rMzn%b1jXhFS z2HS=0If{GX4*u9d_Kq*KJMh{DeI>yEKXOoSc)_l(|QnfvE28i*Ob(8=(tJ(j_su;uE+RD)e zGthF232sxHb*OJGSlbBht>dDs#E@vRwg4gG%{?Qb+@^jP2*uSqO0>x#1@5ebcj!?q zGB2gn;tg5TU5AARrG%eM3X12L=1W6^gN*Xfy5G5BB4A&4QB;m@G@v2qt_J-|c_{Pp zIkBO3o0PhOX*$b>A16DtkMN30xBg^7rg(svp%{*%dUmNtWC1|lEYrI!|P|i2l?;c&$IqK%R7u&`8nE(bq@0S zUx>yByJEZbp$ne--`<1|8>&1Q(Kxs(VGexK9^iEvmzJbPOa4uat@6vCl!X3f-OrD- zf{$5%3jSs+hmS#8l9!|@59>p07SWo;M#Nx+xm4l40qDi$LH(;=CI8tN66LNvm@=S_+Q|UedCIhz$%Q z-GWFz2Qd#8U=hL!y3uUCo3IaJHXIsBn}+T{W;Id&Dcf_H-g5U75Lp`MaRaS*-_ax$4W?M)2Kv5!QXiQ$~v>X;?IxQz6oLS1BhX{r+wkr&rq2I za4v7dUXf5C1*gp*g@((%Rq57xyZ3t(n~}YkvqtZ?e=;5civ|Q8M#TTc(xZ@i8_cMp z(Qkn`?FH&V6afcAN;aa3G52ph&LwzqI-kIF=U`|ut@Md5JUeQ5ywSdhT#`6!+1I90 z2~nZ~@Lx>dBy{q^d<@@EOZ@%V&!r<5)n47OZq+w1WxY7Xtwtf;4Wn48hl-@WP&?S(y+oQ%K2RXAhZ) ztKcS!E;8SUS;~-qHAf%OLRp@Gg!zQuq4h=xqQ!`EW^j^f3?>C{|4Bj3_chbe_-_ZH z3u|HG30h3t)q2}0l;SEym?D+=#!D7iVAd@M6inn!=Wv|AkqZ}m3f9kR123^57n-+N z0#^-^JA+9r_yGel4Jot6ZbD8P(RcQu)6tfSGd5ZH9K-`>-{>0{x)G0ou={7 zHT(zO=oPn#qZ+c4EbOb~0!sg~XH7$&S(E-!$;lbt3$mfQz5Dz(oxoqJK(jeS)k(=4 zjGONSKB*Tb)aBIch89EgcYL|RYp}Te|DHiK(%OLd=SX*}Rpi7ReFUnKPUcZ2O`fVl z@N%)Y+Bnj~P}hW@XQ4X!KJ4fgM4vcjBYpPuey#0r1niVOBmIIVtFr{9bWxwY{M4{s z!$O0NFTWVTXTJR5o_5c&FsGtDtBB8YY?;l!>L&o|lo4Xzi{IM_30=24cyCV|k#P#7 zH9UuAn{oFf?K7wr&gRV!jj~+;j>BIxCAx$FoeC0C=k`Ki_$b3y{$pal<^iWjdTls) zgGdBa7^?uFe>j`rh~U4fiy8b%U0m2-$W`nwi#e^{$aBUw&8e0|S|wMJhsjuPcB-$e z$f{Q##E&AkDH#6T(QyTLjr-nkxPkTX$iSABr6#|_4m!V{H|(?)IsYzWVnG#RQ^Of4 zj}wGVh>OjCkXPbWqY5XN8zdf$k)X=yW7^vpuM1w3#BPRGrFS!ff&~3cM@5ajw1Nrt z2P<0yR(ioR&)UJ8;)}{n;4b*2uFk#s_utB-%s=4?m26Erm(pQUjcg7WwJIh%`?qX8 z_9(E{VU)i=0AJ~f(!&XL4vyuRHpd4xjgJxRLrwcqZKH5B>+>MT+ehQwfKssj!&D}^ zu(D-`UF$FJRdMmLw1lqoNmJh?S!DMsk^MP?^X&Ka*~^IHFAcP7;SYe$xGNUwRZmMY z`l5zK$r$`KaAi?r`}-A zF?=c$-()ICyCDb+Ze@YBr&LH8zbRWxXwrutJy7y!T)+SAHe5O;Rl;)n{yX2yw>d2n zR8q+l--=mybphE;fbHL=wO78iP8vh9V=s#y0y8gz8Hqr^x*<6}*Zcp0lndWWaH+8GNF5uIbx-1VhhB)BR@>?Qf zVARPz6PzKy`U-l9D}%Epe|A@dyOv(><^R1pK^zGw>zXUTSRnq0h&sx__H!)svzThH8*bbTg_-eHkelplMl{a3;;7tpTWfQ;7)~NI z!qmKYoI^ypfO1h)Ee07}8F0~$T=Kp(nh2g0JQJJbzxqo!N6Td^h`tH_aSAhlHVY(| z$R{KyFIP@dD;2u*j=Z%1Tg)e-#dP9cL2)YfX(}u#o_gjr8=OV8Jkd|!%J)UNyUtrf zW6HP8Nb>QMUmP)|;M=W9ll1XFNbB-E(L z!v!2wb*{0*vO9mW=8b68P`gV z=5(6O)!w2J?QHb+Oe8L}`FJy;23)zX)xOI$rz|5?2$L%==W%US@smdNCyRlrIO8Gx z{I%<0w|PRozzfHT6dx`}%5Sk2dC#|o8#Ib(c=ak3DxK16@Mucz>liBrCL$Ve0XXUs zwo!uWZ4EY#KQ%CD9;T3D3bp+R)&@_Quf^U+i_lPB{OvEGxcFGDP|LZj`XL_YiU7=IlG}&E0?s?IRl|N#_KKSOtog zfvneeqtw8!uX~y!{I~vVX@GFsFRvo9m{*<+$#4R1WRa|CIdPnNqWBICMu$X2CtSE( z==kBxr|3i1Jrs0+4YsUqkiM18e(mmy)mw7?E_aouKARuef)75^;O?EqO}4R zYK2BE(NmJ;seTm~VIc1seI@o?nVJpuw%(Zm6PKTd&<3HfJV{h_w0ecmdYCqwE9M8G zQM7YCTPz9fPxU?|G&mYXb6%1Ub?eEElkB$HS7gRgxLLU{{2KrM-f_PhKp8h2xVpgq zon99fEBx=w&+U}x&-%Z*F5U5VBdi}>=EK`Iy6gGI0(9o(b_pdNnoPcbc$=%!pFKCE zbumsDD;&zrZ9FQnpD$wlj?=Cy=_8YdRrNG9X>f7| z=4J?Oe#-T!4FfW}NVwN1hjgSz#Bpll77z6-e7Q@L#F&p=!Dv37*6 z1jBE2%foUgaK1M86DJ`|VeK~BK#e!nttjAHn7cDy)XB2!wHve>xz-Vj+6n%J+-WB= z!mW_iE{A!SUc}(or$HY{`BkHIh5>Hl15d*5MTEPy-GM- z#wt_1J*9S=)4mGAC0IFMnyhRxBm3&fVn+%qzT^S&zyk^8bQlrynVJi_Z#k;{qM0wx zpl9wvoB1Vymc>$8x#~Ro`s})L8#pH%s!t=LlN>*`oL`q_HcR-#-*7S*=Y6umKt)1) zHq&d}MRrh$r;L%$Um*{z((hZRV36{*e&4#^cG}9Q>~z-=%O0!SDgTLqZd5TC@jW;b zss|fs9{vSsJS;I67E=TXpUgNvE7116!)BB!hno~-pAM>kx@ONytZxuZv43=0)}WLU zETa<}7I*FOa3s11Mp^eVbF|eVTR+KHFV&VeIWHG^u5?tkJ>F``zLDOT`H1I?O*?lQ zW3%caf-d;hhp<`CA^KH#h|NM8WxY_nle;oVSoFQsIH{8{tKF6B&46E1Vbh;tZ;hj! zjm2034w~v;-!|-2wfZex23cosh_u6Bp9!9(+j&c@y8vBl514-w66p7wS#R&ds6(Gm z{Gnl2fNNO!>>z`I6=pI+*Wsb|+0R>p&fxG!t&}ImS6?Sk=3c>=RjP>GZNNHw84&%B zhL#XGN!(-fT_h1)ey16@6mMZg2Q1&FGnLIpK;bWC8(YB9TG<5CezPA;Y}|2xXJeny z7B}6OX_5{*=C4rRm%r_LM^l#C?gjb_(nsBhZSWjvk+c@Yai5QCu2v5wuYz35#0Qw; z-p1Gj4>O;Jfmhui>YpHT+0UyKpA4=07KjaxG(uqUT?Jp=M8kh{u12G&E6U3A`f!() zikx`5NGaCmTv6*%-yd5tOPy2B4k@g7=BsY1U?h4%Y)1D)hC_!oCTvvhy{xuMj*9sW zY6A(v&+;5_=J#7s>noHIA{t7)v7!InN^j+mQK0KaWja-&jXco*rqhmH9@xu>}`=LovmxXDDW$n%*vF z>TkG;dT*r2w2Sr0i)|sUPU`CqVAOF8_=f_1B-Rc^-#^QLB7k(BGWeW-_^m0@vHgfw zi}eqazfN;mrSF7Q8d^VfWIiWtfQkLZhF7CbjEU;*Yb~C%6RINB#phz;81KOFG&Y) zCur^YHcm_}E;%q}_*`Djt5aEihFNYsJq8)(sVd7+Z^`0SCHF-* z!-}8TWp8IU-|2$NoW)sUpgFrUh@@FanQEFe-@bm`qgv1ir<))agy6AIQ^p5G=1P6x z`Xc#2*ZA2ZsR_(WX;K0Lo*`}cX@Y;U)I6A_GjN#6YVJw+(omTrkQt(zqPYylhu9Yy zS0q%TI(w92GJ0@Fs&|>cvF)CbK`=3?5fODD z*(7bA5Ton4#QlA)=4Nb}117QYy#mJ;IMU8?4mYBE5sYtKfGgJO==GFB>PiUSZ)cIG zO^fblo-@9NrDPSWT`ws|0SAVk6|UJ8?jq9XX*tUv!xEgd>3>vgrCl11WNsa5Taog4 zy^Qm4lZRx-%b>Lv5EZTl!=lMpo`c`LsoT}|DFI?ye+qQU|NersMzRmy50`EK0vnmi zBtHoWrp|oq(*BN&0RKz_%ly}$1w}{wa5n9>c$`2(@jeWfwVQfIhhAu66-^2R34!t7 zQyuN%sDTS%Zqet6`!jrTuB$CH^`$MYKuwk z-A{pte%9F$L>krIodqlQw$1DpvKGmpUB@xH4v|7>+{R?=Uj1_*pl*ck0hLwBn8;@W`%%HQ4)`+{H zrR-pv`)*G?y5FT_TFa>@TlB;O&}(9!4RnbyV5n-p`Ck#O1yPi6i##0U8xRFMA(n~$ zU2dpEAO@4Vfc?&r7pI!i`oq#P8e#s+cv2O(2gx)Bny_NEU|9kb=rBb7Ur2Q=R>WM) z_*SDBkWYEA6Hh0%$qPqgU%jhj+3kli+H)a%ZaY_`l>MfCdajKc;TJD)S5~N-B`|eC zvxPE+i`$jEILWc^IyPq{7{3xKz)Y{_qk7qKd8fqlsjn{J zq$`!NE4i|}jfjSMb6q;6)}AqQ`M44Dv*IKAO}%ryTY@c8@a*mcU9pS*_Y>>uU;VF{ ze;Zf7?-w@N>I*M<_VYQ-YgDa4H4emWBOIXMFduc4tf^A3&r@am+>lM1rz+s8f2#OJ zfcz~|kfJW}E7)%T-3BsctU3ppa&{xZFxH7rWS^*tim5^d#^1iinPr{IQle~937r3s zHF+3KxsYoS|3S1yi0=DF2j8Yn@8G;_4 zMR#QGe#P@S@8L*0`#T}si1zJoWlF7<)rq|^%U8YsIW7wQr7#cHPt!3yaLx{?D?S$n>3 zf{$O!i#@fyakoN^Lc89*Wn}Pyae?Ny&nU@HWXNls2mF9zeP>mR!#?YX*>Dq3HoT+Y z;B%*~{u6I10Tugs)SA*=N1kJ2RO6G^UeCyVWt*#8tWb*Zwun)eMS$3Gkr?aTTz3F> zlE~68YuOK69?=+1AIfAw^$vrxs^J{7TNowXI4h_yv&&jQ3sSbsia@WqM%{nmQP2JSpDO?~umZ}S=Rz{P8FF-$x5WMAZ?yV}%Xc zF$hfwS|Ef^Y7SV_4-TlGb_ zulKN>4vR088rkx!Ap6gZncbvw@vEQi+5tB``g1O7l1ge_*g=KA#GIE=Ehdq;1~nSs z5JAeaChxZBXUOe+Wa6x%1fvGg&CxE?W6P$P)(ob*MWJA5kyz@0&$~2*j#OSZCdfbw zS4Ys$id*~XBB#u(X(E#F;}$ zOq%(#fE{Mxi!sqaxh;qbnjKdI`|b~a?8W*HPP;|OfVLVt4mlgIww>w;l1iecBz!2`KoS2Df9h`K}KmA*CkI zmjmT>1C!Ln*NiO-2a`0Hp(dCw@AP^=Jm0r7&34~<1)Q{sGWUX1m+Fem1w8*+@|cgN zDHZ{2CuOB!r!Vp48t@IW2dU}x;BS$CPoD*o(bDS^Ux9K&k(C}BsXEW-kpEyrLM@Gr z{kDC9$f!;%UyfF?7ePg=h(JP|lHLl{UXO5)uFfFZsjw(gK7$X@$R+GUoA#~h9|K*c zpNr7Mx~Q?%r=ifP1mhfJVuL>!3CAtEj}w*jjCOvypJy^F`nS0-!Ut7!wp@)HvZqn~ zQvG&0;VS~X@UqCZVKUsR=_&CV^vGcS^3CXj0LlIE0`JeK(9XJPpFo=1Dn)>@A$b&H$fJxo+e z+H)m35A8cVHlb%~M_xuUod#BnHfp|hEX$L9ojO^~ub@1Y!JJJIpDkHdl8wK1YwW*! z>%~5VRT-w@(olaehonB`q|juy%7BFvB@`{Cr__cfX%krS|fFOy4D2i1|zH05K-sF69U@ck)BTmkc>XX6!OY`8==7>~gi zVqFrR4K`F-xP&Fh_&5F5QnMObPD3s*(5Rs8Oz>J`jw3-qwStlY3@p~rU9OI zYQwsa0o1Ke9L_7~F6P|f+cy?{bgf)d*kDQ@dR4?#FgB3OF|R2)_&aC+iOSyt86W}p zQ<_#Tle_i`9>voiZv7}71)fwf4(vXXiWujj@MAAlhhlmHwGFd} zbTr|ve%*E!Ag=Pltxa2pup#eDQ^yqdMJt3cLF~C(0J=gd^8E4d6~y^NB1CbD4|J^f zLk&~;iC{hXnaoko4_&|r;md@6qjVe-tRvC6rb%K?%jRcG+1}`q!hYg1?h0HIgS7hK zUy65boJx8+cUpH%nKtA3m@a#KbU7v`vK-2i{|Fy(X5dYy6QgzwUuwfN?;my&rH0cx zUarT1XoCn|pOX7vo4Oe*<*%<$uapMI zK@3jvQq9q43!s*Ug89`3#rpz^-Ex8~HYgshk(=&EP}$c4PAp}9)0eF zI>8<8W+A`L>%5xj|1DS-;3oJ&+j5%@s+T@)8EQ)TFt= zcdFf-*>%PYCoy50QNjP41;+DcEN?h%QL69Kq6=~cmu&OfbVvxxq}_QWAY~~qThRHLEWO|>zm!u|ryWEP??s-z( zi?;R{s*cl?{LZckTkh33jqj1}`XyC}m{WZ4zHz}&qf;==saC_iE_5pA=fo6qQ(Ai> zx2W1fCiAXQ7gND()Dw$rDXv{c`=K~^XnK!Duf>3N@yi`@CZew?k3eWR-yy*@Cd!#j4pg#N>(0d_|pp3$`UM0VnUrwrX4e7b^O|2nGG(x;4Tg%4ag1Yt|QTRW;N<;R%`N zzISd(Z=EX4k=L=#4AUlp{fIVe?DTY2YAk(kB6*L9e1wbN<>vLI+@dc>xE5>HXI(Gt zdqIgr6{HvBK4beXPW~9{y6*>JOV9GDco3M1ZjmuIFNYN4Yzh_As)p^sk7d%ll@0xBzj88EX|`zXM?%czg{Q zBugpE=u)K2`oBvarHcitF#O_rAdOJ8?ddEV!yC&+-F(=KNJ!-kOuW|8({^RHy2j|x zRb$su*=$?=6v?y`(JY_Cl*2TRluW$>y55vsl6XEyJ^qcw4516Oxm&?Gmm#mUFbfPM z`)Aq{SjmKkArfTSQM77X6`PV`2_gVRa&NNKNX?#MmQ5;x%`JvPaLCM}YChuRnm# z_Mmqi^C=kk{1?9dZc8Q(88+1e>p}8{9S|9Wlb{mVc<$SFmIW+*2H6LYAZ(S%I);k zjPxq z-#lCcoA5yhe#W2-%8O{NGfx&geYb~QAQ~;45#29Ra0xxJ*)3xc2yRRUBM^@B$3;69 z==g@--iPrOrHdny8fGAShxcM=F`-9SdZ?X`RMXg;iIZLUs~IM9fP3FkHq7(pKbF;s{jkU zIw?bXA~3=bp)ktt^YDeoY#65sjBWbaN8W9#+W_W)2Jbl5Lc_*;8u?GP$D!lM*g4J4 zV|Je@isRu}`xPc+NPTeRN_^&JqcQO*1scbVhQU`EC|s;LxF1u?$p6^ujuUWDQ9I1g z06PaizT;&ykl>c)CK|tA=J%?nGHf1@tqRB(9Sf9v$xU$_jRePXjH_^&>Ae@ zypq9Zu9cm@-7}CjpCk>gB|A` z4n>SGu89JOa%41p9JKuG>JB&);uCug`Ey#cr0>f2m#lG^3hsd1*1)H?D zt*(u5q)#&O^}{YoV%E6>C0}C&H`6zfvzIB2zm}9hJZ7ZFGopZ``1xXO^Yd+}$dmCi ziEF03J&j5?^X|ULzm}>+fP6R`409z63 ze0LTg$>F5X+E@}1XP~rwUvPx?%)6e2DKx}?Mt&9p0!KZ4bFP^xV&0$^KDCVYD`kxy z$@{Sss@WF0T;t9uwjuWJ*b=-ldd7-+RS)?q^3FQ3?B&q^&-kyTn~ zkfz*+$V2Z+*)O;~{~n;tA|OBfs1LWOHwaUV-LS*pS^t4Bm&9S7l0DXQmZDtozm^7Kl#q*-0r1n-j=qx!S78+gQ9ma42`)ZY)LmQOd+7O z%z}9b{N6S-VIsByvAJ^FU#YzHD3!KD3%tEqcJLA?WQjj{Vp(%}L{7wysUfA|OJSjB z^7j4PZeB9BDV`dG0xdzqMKwzfr9!hn7^pv7JHo814?TRc_dD|le}OG$Kmm7M`6s-% ziCHgC&Ge&(lHC>NJwE)^cyl(YsD+Y=rgs<{-dyfv%& zz+y5`P}%M2=ANp&!p5cX?(L)f#$!i%3FGQ@TqC2yUFd=ZHqdLRt)4fl-f($F1=OB| z47$apk{> zU3Q+8{~3!$!Wb(t0C`!{+NLVT1BM_6O&YRxJGU-2My;;E>azUM|x1mqvg zcw-h;R>WQ$Y(qy&C@ATyf#u2;G)`Tb3B=GHLaa}~$>Zk(`!jx!wwxHJFY$RcE2J?soA`Io(vst;-)eW|nXbUd{(nUHey+_~d#GB^V_fA_eiL zOkqYf4n`4t%-vy0eDz>%Ad#S9_m1b!fi%VU`6dTLg((fB8Tf!uQs0H~)|w}MxLl5K z&x|t3uv&~9UW$+o&o{ZN{>N+t@lE(8Y!oJs(vG&~GgH0bo^vG`Jk}E!Xw=@>0B$>1 zlCjVzXh@u_#V@F@%fz=7F6Q#;4 zYYIQi^e#2>ss?{WDr1hua-Iw1VbZgZNV5G7t76PWg`R5&h|?$DDsauFs>~|`0jT5Y z4v6mw26Qpr$Zh}UW%)?ySl*!!O8llWPU$DC1kM1>x(+|N=#Rt)Ux`}A8?kiUeYyqo z8TVX4SO345l+t(lDRvjDOqej@IebX0jNc?bEAO`7?`1qkZxSP1PZYF+{qJmjx2vv_ z0WJVz@!qoo-#1{k89ciecI4kme!8BHS=q$6#bUE8+=(9tK zW0O^8cp@1TQzqURXUI0g2a;0G#D}Lk>PmVw+$`D9ewg5f3G&3m9rzF&XoU5ONW5Mr zFEBptr z6n=0f|7c|z?wlTC_k*?URgIWkOaS(w{DK;*Ro_LqX$cnJr&+pk^Qlq(`Ku+ryI#`v zRVw$|!|VcF<#8`M&qb6|KqZqhM18o`5%S_DLR^af_<^q<;w}+#p{9r_gKDm^H#kG?ZiA5Dp;rh9*)K zEHexPb*~M`Xo<>f)`^@9?pqj?DZCOp0Nh(5CI`~2srD;y#Qi$7W0ntNz|3*v?<9aT z#YBSlE3VpMGGQ+;ijCRIwTH)-ezZY1_ z!So;5f?)_V@S0tCbD3%QwU|(tyw(Xak?D|b0z|05x93$Ly8SG_ygY;EU>yLHBn09P z9O65Z15;st$~Q9K;!>Tfc}fN%;ac+-8pt4`9?L-L2b%@^rHdD0tgJLz1_xdsShS1+ zDxTx=lP&_x6C1s$0fx5SK+fD$p2zf!+;-LCCu?VE+bvuFJS$@?Gb`KtPP^=7q}w{*=j(amO;|@^Q9-UOeasL!qyYjv{V(x`@4NQ$kQgPd$r#G% z(uau}=|PHPu|?V6MS{y0tj^`}Rx!BL{uN;DOjt`%!@s3|1q~kR&>sr66pUY6z%q=W z5&_47EWwtKnqtXgGkXm2gp?AtHouk`texZV)O5|qvrg0xly!}z7lxGF`v+tC<8vH! z?s$T(D@8rE^!s3Omh%QhdgfAQab~j8b_7rAr(a*79EquEiLtrpZPjD2P|Ho|u`MSd zlDK!(^iWv6gK&u4N2LGX(*#4o`p)bjHEJYTj$^!=Sie_h!%4PCog58P^ zZG6C{n$#M4T)q6q#;;N&RrI_-XSA(hGJx^#=a$o2q_!sxj6UD!4oa*&bk78(dkNIL zI@LbWxcRErqV(EGNRXu>41|(|$HJyzzsVqQp3yls?PGu{WmIg{_Dn)4JaIOtgQtbU zAfn`xwv3vQobI72R{fSN)lt3l)`jM?7hp}ToVJ~vvH?OPR|cxo*!*Aza&jR=4IlJp z3531HRW$kz#njLQj#+tJ4%K35$31}d=li}C?;V-S&KJ)nU~5jhr!MXTc{=~HtztDO z*a->ILlkFRWE(VB!H~Uv3t_n5IN;S&fzX-C`Ma%1__QGkR03`8b(veml&DKmLsaf zN6RB@=+c4CRY>SX+xqiwJ20OX)>NHwH_v2Mm6*r;sicP^lN!&cH*h5SEtTj~^+ql= z1Kjr>IxI1ZOAsR?%_loBFkt>?apL^_OUC*!DJZ%2zdOfx0k4$R*No*GLD2(zCe`gu zyN*%*5o2#O9LN|~7)`KN)LA;8F2_15N-GV~^C+qe)rA6oSiDjBb&jO?99g&tx;y2H zZ;odi-zEXJO3P%vjBdjE?{8cq*JtbN|AY^6f>yZZ^`^-)iC0MTBqGLv(266mxul|{ zWpk`Wmd60mjq%Q)Vyxu<>?p8+Lx=%D{(OW;GoN23&H|=sj^gjG6C5Je$MBut>E6!7 z-(z{)p$~+m{!%*cp>I7gk{#0!`&CMIPwbERC>RLN&CTKe{o%wvsK|qGMo9hs0qKv6 zLL*zm_^=0>ad9;|qn)96dr(Dmlt*(f4Y5pPCBmDq=>2gbO>tOhc6w=g`A--CPl5q+ zPks)zXe$IKNbL7?!6Z^0T2SqoDEVpPoJ?bAB3EJ+?9Mn+SyYA+5=p7}KSY1eKetAO z$xD+#KtyLJn?PwTMhG_H^S|fYwpozF=Kd|0gvYG~2$uHa=uf$Ufw1n`{`fWD8NrqN zpPdT{ift6i=y@<20E%3fA?(vS59Iv~&ene71;&LR{O2khBoFBSs7;rTHiHWiJBAHv z@e{y{5F$7BNVDw4NQB(;CNX>iUhv_J%#12E&PDGt_I@Fa)WcczNL_+X^RmXq{k@9!KjbBec@B#CEAAeO&xf@`W=Rn#Qp}gMV96F5lIZ;IT|jo>1BI;6fG#1MB~`SHsAS9)d{XpQ>c z{R@`J|BAcGc-heQOU-jX!Q^N<2ZsdCzARZx@n{-bZ(^KdH?IIb+oxbJV6od9I?}09 zLn~@NBc{q1^vXly{{Q_YP6lCpcQfkf;)C#dZV=2Xp1r@g{ntuZ z62T!|h(2Kji_X1K6VMUs;mX1Kn$y|<>I><*g44+2f}W3Ql9A`Wv!y~aKh3Wo3r90oDTLgiQm9!5ww`kzA| zutiY~pwxF0$PiWiN8m`9trhS0v`u;n9%gbywTJ7YeFKkOT))*S zK}^$*Awz>J<$oSI zM}h1dNZ_=Anrv>~1!$u=N%|>a3p!%{bpp1tR~PT6E~Tf*7$838M4Xm!y{SO0|4FHv>U&H zT|-3~df7OXcm?d{y6-;(Q6<4K3NSiS{jbe)FpTu~aCQXZDCu^6^N@^dawQH?(`p7< zOKeA0!}DYyktBqxXQuqGm#vHu&EG0E?I+mwRht5%8;ZFFZwiL!eqBv$nE(B4(Nw7% zmH0n(P$**Eb@-)*ed_nKRldo)oV!+JU>Bpp>84`+*Z-|4z2VmRn7M3QHzo)N6nla* zIIX6{9lgO_vPONO!18ma<09I@9j`x+9Zy(8C*6gN9&!P zBCZo+hoD)J&f|?@H~nM5hEEqbEY9cGlMtu~0Efdy5OFo+zc$6v>i{5c zu?iWMo`P+C8$i_Nc6J)Xa|(vXm0-wy3IHZFj`Un?^}VdT8|6^CYDvp zpdW={A;NHvAzDOHHA=il%3DV`;_d7DI0Y{I1?#g`7!yYmaWFSTgvnP7{So}XORbLBcyZH@};CLZ`0@|Xcjxg3#219w|_ zar%ok`wO0dd#=~xNs|x_FrTez`|~5idVp3@?FC>53sZt#juRA^)4$1t|L^hYN=4!v zer6pw)6{bc>0~tt0YtN>k&L@DU{~&0daM%lgg>Sb5dyYOO_rwa+6e@@t;N*+enYe4 zGCAZhOziENSelR+iO*k^LEHCC0Lu#J&d|y!Z^j%o4Swpl5?IdM4vM@?`rK`X3TwUD zxdg^c%x*}VPY+E0XQv|uNW*<8_;>n$x;-nP|GulKkbpt+3|9W4GIZVh>V4A?MI@*# zFEk{{+!wIOCoYlTq&=!%|8oO}an8FlK;-5#9~a&f1ueo(jvihwjXhCZ*Hlrq@6w+( zw3JB&h%d?(SDVX`#_KSnqN;qD{}arck+jxvEUA+A#~}CRhT@S2G8K!Ag&>N26}{IE$vMmCkOQ6nMATbca4#BL_XCi3(C2KdVxOYDXqvCIEU>pdlRIdS ze?z&$@tOrr<9=k$L9(0c?D$hw(GB41>(!F`Dv)P3N=^VXS>JWB@NcByQyvaJ*1*;U zIOwS`u?%J_Fv%?o-r8uwfH=7Oxl6?JeI@P!?!Dmp-2jg~a~SGdC@5@7IY}|KFQOI9 ze$PjS3SV3SCPLZ@bgl{=e2#Q?`4N2Yo!fwYmqn)86!$r2>avS^93;HtOd`QS6OEkE z`KVDF&xYKvRv+tqm=SH18v5Y&!cPC-(xeVEGXyK;X1F ze`Nyh6w&4@wV>q+xOn6P{H|3u5EdO^&&Ub^0-y;a=(rpz*dmiZpPk2XLp0WJgRcm(f0@-8}(F ztU-VKCdyy7Iaj4@VWIE!6K7<9#rV!ZJEK~;7484!NzgC>w^dWO9k)L}OJL*2%||Ju z6>CxAt=3Zb>wFZDC1G$Do7qs^z*^cKAC^ckLd2GYy}54$5ZwY>CTGE?6>ZcdFisyi z)A|`EzhPCGbTfFB@Sk8G5z$5D(5_-HgU-9*A2F-tv77AUI}=(K5BjlX-ozSD(^Tb{ zj^K0`nW^g_Q;_9N1)@te&0s>Ci`pvlSx)4{gsY#5sX-KLt4@2Zdx5R0?&}r26iC8| z20PpJs1>fAmZtz7a8o)9w}`W*TbPmMYHv(oWa%$w6psfYgxu!`(YrPrKGOzIH_cc< z^q&I00wCtI}MQjv0!)$G$Qr*&VUkr+P9`zEGe~8FN)~ei&yLF7!oDH!+QW-rg;b^ zWKEGvfFm#Ojt*Io32!*l{HZ64341s2uJ%gx(T7(($Sg^oH^+YvJHT(bmv9Vh%yxZV zFb+*dT!tv}a1}MGt+lJ|eGtCiVJA@%dH!NeOsklt{QI#B7QJ8(xSIhyVpbUDL$h5L zqv}eso{8qIZIUh$CpNURA}AZjykDO<+hHc(c%;~=V|!=T<#m%Gag|FiMQv=&BN&1n ztGlt&n1UH|*q-jdc44Z4eE;_42n)-8zy9ZVNy)<2BC~a*WzVHMN6pXC`m1#+_T&?a za5yrB=?6{g4N_`LXX$S`q`@n?T7fRXHS8K$V0ja%m1*H6tEj`y^MF31QgRDKH%L(! zsWzFWPpt;}7|fosQyO-s2*uQveogD;+j{qKtDbBT3OrnPf_7vf=!hnDTxFgmrD%P6 z)tS%^v>B7mZU2Idmhs!q(r1VU;nVx2ru2I1DoLa-ZvuepNy<8(t!N@#hKv`U#b{c5 z64T8c$S@4DMo}on2lr}%3Y>{QMLJ~_Xn|}H=g6bsc@-xs}4b=Dz(opWXNA?#B$S0E*4RS2W_KB(LJ@yldt3#Ax{nrR~V8)`+4O zP;tAuMB6#cfEb~9IGG>n;E)2`$EOx*On#a`X~ZiFG`J$w!n|paO)F-#$=oApOQ?(2 zsjPBtrGfeJ62kGF*8*>om##iuh5WAK=RY}a2M8Nn6P1>fF>awYB*Z5s@wX31f@!~( zufvOhXiJ7(y6TXq4#A<-uCQjhE?K=VW8di`9HJ;;nN=|R03g1%3>t(_4UzwOxauWM zftG6fBFs2X&%*T_BVPU;-L0=iUyJn|t z`Eq-RGiaf4@7LtV1uCqpkYdMd2)(2Q(kCeXGQ!l9lxAx>(s8|8oG%v<4lZl9Y+c<| zt^gRO7li0xAdX~HYS=6hlaULNq|#Ce`E3Lz|M zxE9(8fKQ6(d!m>?R7iqtkGC9OJfrIpa`l_1P z>@I!5AuBU$EOorlvQttm;-+uu-1pU%CF(H9(R2fq3rc9KSBPjg(fDGD<6;nN02!p? z3y_~oG5`Jj53De|Q5f=_ETt}7Nz<@iTiN;oN9CaC@^EFn9io!+byrp9EEGon#*b7U!)~$<| z{XyevWG6u9mN%3AiHLUHQDX5QSc?!UIAuWr>6!SZ+X;-k@z{jbK><1pyJb6u}D$ zy#~m|#s|m+B7%k;F;Gy_^BJW5A8LNf^CUC#%{MdWecv**;o zL;<7|cBN=Y8ld0CZfQ@k$4TU_ebjII_}rZ&SU5gmrgwj`D-Ap{9VEtNDgYY4m;#o} z*pJey71Zz3ssL||$;b&3N-wjZ9k)B^lFV(_g#?+eb>-nCw%RY8r|t!{U(8e0VOluT z+=w(HPJ>-=%vm%;_2!R@?ngUXniandk<@2O$&=%6y#{^@%*(D3I=%T!zuX`C^u}f) zyyETF2{3_YHwUt;pg4_#0t(>i-^yX2`9u|oo{Me%+^_!2qCT%P{%r38P@}l0lAwWz zjNJyOCQ5Tk=mM$1p%XKN^-C2d7XAM@2`KTgCU6+$C9)YYZwN)v;_kuIZc!!U3Tf9SKs>NwoITt$k;SQF+HsZO4c7-IryYQ~S}D zPmIP#^O7I(w>cUIW1qT&kqztk8|MZ5M?#0C@!1$A1SUH|BE2T}5<1|2Cxe^dx3k1( zipnfad4_%$Te+s{yc9T2{#%vZ_9-{q#BSC5_D^ar(kh{N%Hx}Y_se%FTq2uEDsHv5zdpCzwVX(oUDKgoN2hZj#U3T6rdCSDpgY?!>P-9(~kEZ_I=;Sd+q4f7A5w|SacUWvt2bnQFU7eEM=W1QS+7ZYSz|Bfwev?l4PUPtW3 ze%mo~gn6;=5%V$}TjPRk#Lw<5*FatOw)%M;Ed5bbW(*j^4)v>}8!$aHU=iwG4(Tkd zZwou9(@k_V^EuA{|#9AEDY5zKf2F^cxzXU)XGge2#u@wnTseA=TLL#K6 zk@%juKNY{=?BI&#c1a*+V7c?!npHW0+g*Y`gSjt|*UtBNxYj|5r#*5ngd3|`<8u!M zwym!P)v#?O8IRiA7&Fg+P{C9h)C%Ya{pHh}Pqxz_j#+|4vBW=~n*^2^!8Z2`IBg7X z(rv9O8uQOpfubu?eG}vlEExxd!>D@$VNOSz!^7EZJAt2CQ z{!2C=IngqDnx&X$`3?3ouPvcZ!fiXcU`wJgN-A?X{Aw4=)GeES+c{0gq=B@M5hcvB z+dG{w0-Nz5l3sgZOx-;EML0$KxdUZJ>VWw0APLCz@cLK;87r@$=L$EeB5Mdyig6sY-R`Bl21RV z5X8J@l)6x*A1L9J15_n>W)V2>kc6=yySLxvx7g*fmh12UJtT14-*)28>w?EC)T5`2 zRy(`@9YXV716YjM_IV~w$>pJo&$QUl#X_gjgOC%!^*C}P@@JyB)Z3~Sq=RNEHq zEw=l3eoM$`;$Sp7xDwRrXjYzU7RmSMZ|})lT?i}f+u^{YtCnQ`SEUS@3^o(Ca=X53 z=I+&Tyq};1f({IDScT6~s?ErxDYq@oAMDI*t4HCVE)}F9I7`&vEU}9#+Nu2A%8200 zV?+&R&X6xCfA^uGkB{;3ZG2b@9~af%Z*L4L)@&ljHvDjFO^^zFPB^(ZmJ`p!{{dx3 Bj^h9T literal 0 HcmV?d00001 diff --git a/docs/modules/mapping/normal_vector_estimation/normal_vector_estimation_main.rst b/docs/modules/mapping/normal_vector_estimation/normal_vector_estimation_main.rst new file mode 100644 index 0000000000..a4d1bf0df2 --- /dev/null +++ b/docs/modules/mapping/normal_vector_estimation/normal_vector_estimation_main.rst @@ -0,0 +1,74 @@ +Normal vector estimation +------------------------- + + +Normal vector calculation of a 3D triangle +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +A 3D point is as a vector: + +.. math:: p = [x, y, z] + +When there are 3 points in 3D space, :math:`p_1, p_2, p_3`, + +we can calculate a normal vector n of a 3D triangle which is consisted of the points. + +.. math:: n = \frac{v1 \times v2}{|v1 \times v2|} + +where + +.. math:: v1 = p2 - p1 + +.. math:: v2 = p3 - p1 + +This is an example of normal vector calculation: + +.. figure:: normal_vector_calc.png + +API +===== + +.. autofunction:: Mapping.normal_vector_estimation.normal_vector_estimation.calc_normal_vector + +Normal vector estimation with RANdam SAmpling Consensus(RANSAC) +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Consider the problem of estimating the normal vector of a plane based on a +set of N 3D points where a plane can be observed. + +There is a way that uses all point cloud data to estimate a plane and +a normal vector using the `least-squares method `_ + +However, this method is vulnerable to noise of the point cloud. + +In this document, we will use a method that uses +`RANdam SAmpling Consensus(RANSAC) `_ +to estimate a plane and a normal vector. + +RANSAC is a robust estimation methods for data set with outliers. + + + +This RANSAC based normal vector estimation method is as follows: + +#. Select 3 points randomly from the point cloud. + +#. Calculate a normal vector of a plane which is consists of the sampled 3 points. + +#. Calculate the distance between the calculated plane and the all point cloud. + +#. If the distance is less than a threshold, the point is considered to be an inlier. + +#. Repeat the above steps until the inlier ratio is greater than a threshold. + + + +This is an example of RANSAC based normal vector estimation: + +.. figure:: ransac_normal_vector_estimation.png + +API +===== + +.. autofunction:: Mapping.normal_vector_estimation.normal_vector_estimation.ransac_normal_vector_estimation + diff --git a/docs/modules/mapping/normal_vector_estimation/ransac_normal_vector_estimation.png b/docs/modules/mapping/normal_vector_estimation/ransac_normal_vector_estimation.png new file mode 100644 index 0000000000000000000000000000000000000000..e9b661e79c1d8283e61c9cbdc991e6cd4ef2dec9 GIT binary patch literal 282297 zcmeFYgN?tc6I1N+|Rsjj+JbxO{u`qeq7Zb$2Aso-EzVj>|S;i##;dW(dF8ife1=r0gC zEB&+VNJyB!926CG)D#uzbv)hd9Gq>DkW{17z-aGu_Xs~e2D(XLuwW1*5e5(y5Xq^d zbAOyH{_%-fj-BB}XcUc+NkSM*7&ODjrhjAI(_Qp-m^v zH=~(=?P2i1Fzn)S2Yxe*`Y~@fRdv$B7HP7_Xi~>q+s;dqi%1s9LJswn#dCaGS=~-t zTwIhNnsaSK_mW7Ib)ww8P7n8wk9zM=IyGgGbod4_LN!4WgKRoM9bnaJB)RK6&;yH6 ziifL829FZeE9kNq+w1djF*Z%U7nHK*+A=m`|N)p21Z~oaK;AYFgo*xx9XV z-K-2sQa+ll#ZZS z_GuSq=MwLEvT?ljGfO1Z#G)Y9U5b}J$nHNs@uu2o-?1JOk|up5%tiLj#krig2|=xR zhTD$nhvc@37b+(f^$hD79dnr1?+X?SaYJNGIf7a2+7QnQv_rJWb^>>7p%8s{ToV+7 z4jgwXDHQ2kx@MHFRcZ2YdUU)u^ppj-dvXy;;x@>Y^rHP#n4c8Bk+ajPhju4nzsD^N zkIA+AK|PPAr`RUP_6;y@`va>H?@A$ToN8AvuH7ab*QrDK)HxlsdJRd8+6;-UBX-S1 zjBXhn+>v%_Sx+E?W*+X=C4H*lhw?1yd8eEg0oJE*_au5|QngnF{ptnyFO@iwB??gY z)T)hh>l`8GF!qwWfUP z*DSG2eG-G$d2woV`y7S~vxHFqMO*0}lXK<98D{Z;=#?n^42e4GKNzxDy@+0*=fASe zW0=Swe?^QBCKM&W!#9qaiGJvQlY%*rzNwDMR+#iRX;9U>0INWypbirgGXPTylL3=4 zd>YdhQ-y@*&w>r_RL^Tb2CwwYavw0`!Nf z?(cV-9GJugFZJ0)ID9x;-!gJga8#y|a%^#=anKkvmI)PTz7u)7&3^IOfWv?t@~*X5 zDo;VTQXk{3n!#M|+k8)>EpZZU;k*D{)IY#|(7wMT9nQDCDKQ}#7w#jZqvxfNgnX*0 zhD+iAf(P`LRGAWWy&B#4cO!2~b)*aDyX44~v3Z!{E2BN)JR;BhBmQDvW3Rbl1wPVZqmMScyo*^ z%inn$`L*Gcrru-GUsQwU{XxQ2f-##g zTTp^G{g=px4cw&wj!_#evf9*534i^k25U>Pw<4jmw40NE|Qh zZAvcDAHseXszNpttW>U|hkP)stM-=jYUb{i_c^3RCP)c?Ir#^~u@vZ+)n9N^Z? zdO0LC?FHV$5u6=f=9(+%JZuzqKDOWySg~Ce#*!Rz_~NI(RnkOigH@|kt5m8~&eA0? zE-+R#a6auEHdk3)H+-D_FfzEzF|z-0TG8oOO`CU)ckC4vl^|8?>+lh7JvDwtd;K-*9en({NqSzqGz|-FQ`h(0H-PxdaK= z4MdmvCG}$V`yuhQr#v^H_57XGP2B^* zL#LCb;hPe=zr5{ku`8x!q~NjAZQOgwyYf>vJbJWGsGrfKaD=cvzo;D!-?hfRre=ScRMfF>F*Q3JYbbZxa(Vd}#frMd9p;QqZ>GNr#lQew#Qw!b=_6jkauajAU zbb|CJF$I|s4U}P!^Ox8!wg8{YnB8K2O8&g`Z9|~5jkDfiKkx*)uzk}v*GJO5WMt7y zZ{M*MPKh-|n)ANkcU0Z3pOlCUM=L8Fi#N((fJ$wZ^-z<18*sY-&T^-j};?i(@E<6-yP+@Rrj8Up-I9ID4tOx%EpKdM2D`hBE zGrcg*(KGW{ZmN0XWPDz8Zm@InuzIiP5@Hqdd-YfX>>UW|hOysO0$PslXb##)Ffq%C zjY!f+gXY>-+_%^cAcG*vh4lJLKx)_brA&{^p3DFQ(yAFGj*(Ih~24<@FCZ}i?>UFF_djC~tdJep3Jo)-Qp zoawms-sos`t-eb%!H>qFtop}-!PpO83Cx7Sgw|UYI9Rgpc|r}1Jx#f!rJt2Oa_P4U z0!Nd1vBl4ef2OFX7QH7QZH!|zG`h;aw9z_GyOfF*1~^VROzy#^tnEF=;AbcHC+rfBTxD*SqiKjrCm693}{YO?Yd}d|H9$m&ljMe47rmy0Zg)H;%6ti53GvvPbX( zv^hLwx-!tGpm(>1P>(&L5w^6pOt{&~#yH^DO!3Y9R7DZq{cRBMV?S&|BN#3?SUveH zJ7j-HWXu>X=!IKz`eWW>;pWz^P6vb|_!ww=zTa(58*ECIKzkg_9VC5i*JXTFhqf}; z;zWf(>whlu@UR=%nYd4f7i1N*e@lJkZ{amS1_M`>e>XR7MFj>5eUTAiT~qTX%0~+2 z$Vx|V&kRG-u|mpSlG}-dre0irl1p7dB0_-^X^$=vts}|NIQI52jv65)Yz@`yUcW}-K%~);P@YjDp(0Yx5JBb{)xXoq&)AWW|B?S32`SP63FTjPv=H&r zlY|IQH2;i|QzDSi5O0Kt;FtUSf7M2f%0>Qn+7(fTB(JNeriO@htvzjRT>&55ynYEk z&qHKjxT_igkdR1Op29P=x6G%A_Gca58G0GM)|9YzbK$YHakH}J@pEy1Y6nTmPXdv2 zvGuZ~_j7S}1xWZwGybE71S0*E&C5vtk1AeH(u{_$b?6n{JZFK3B zZR{l8zEb`dIpR&4@q?F_y96(OBbM3I^Slo6gD|e1Vnlcrg6;l7r4tEB4oU5m{5!vAhf5fXrN+`| zr`i5Fk?7gOpPbYqcKeeCy&6=1YH{2+j^nU2?&ZDx?z;4j@g|9p!B#ajfq~J0J>!5r z#Xo26uW!TS&BbESP4&)=^vS6)WDIZ}cwLcG1A2tk{WZH+p8Ct`AWx5u5<-uU5-Nv} z{``OQ;=Ybw{|0@Xi0wjC?EhSIoB&;(TIqk=$bXv8(m_$chv;A%MsD?1yyqgmFDs(&WiiFo!hltYMozf zU3&8bRm()eak^`0dk6g~CrEN&;&!F)ChR{{2OJ8JNc^V~;2uSwQ+>MQNDgnIlpTeD-O6_^$Wgv9oVq<; zyQKy{-UOf2xKDS9HcrF`aF@`6Hbg-iAnpUUayqH!3{iNr7mNIey=)!R-Ub_L(}Zuk z!R^i^+b$$i!Ofd2sWUCd-a+39OMHQSzFCW~ZBYoYlMUFpX}WS{n)vd0#$OMmRXq4A z9&6iuQ=25TW#zsFG%Y2&iY#OCcILkA@qT8?AN#rdDmhc`sUmyxt`hIp=2cYQ+04Dn zHfW}=)$Nqb(G+W4!-&gu&KTXlX5@#MQS)gyZx-xm1%C7?xDM$@&^jAv{gZ5PW}Sa# zYX@ovm=r}{esw1JVTP^kjH-9;4}BmI;}orI52Z5{nQKc z2tRo|<}{%-JvNZEX||6F+zaV@|E7=^e*HnJEWoAB<}LZmti_e~syi_Gv)jX8 zx23)h&SbxE_<5UmEM-hOXsu-MobC+#%zyYdoUA-7t-Ln7_&Rf$2R)ptPBm!R*9#Im zImJEU6ZhW#vsqi$a;f56*_Ou>17aIV92GH!OB5m#c#;a1d7PT4U z;E3`h7)+qg+8IGB5|3nTi{-8SIya?;^vY*V$C;!k2}IAIR*$TQ z^sz@`riu5oUZD8oLd(*^>+Yr@-Zr3T+x^ms*lTeB#*^wxZH)4VE75=0S|X!pxt#LQ z?55G+X6NME^+aTC<)-PobS)C3BKju*2-X+eY_7V#a#y;tkG`rRa|4j|J)eU-%w@B~ zlklKPL=nRi>Bq@zQ3L||E$l1ik5}ftq0ThB;*E@##2%O`%#>^&`c~rIfExpWEi-{v zZ7tg^Xmgs65bkJlvBW<^<-C~}$+t@a-hU?Gaa> z>Udvk(l^nD4;QkJ7p)5ySLMM$Gfd%$_nffg3-=pPxGYUBXH2j}hM9)2Q_PCg{g~{HAu|Y1?AfIUnXHu2n0BU@6c_4K`x;V;{2?3{jGA2HmGUA8&fj`g!%~f*f z;nlMD)dRvaCW7)7IkLg6sjm;(qfQmCr^RFXWx6ZMKQc)pU|^+*C|R^+?=_pM>?X0N z%R;B;9C_(tL(Wa}&TGV;Y_&gsLV)b+M-$!A6Be=>nE7ul z$E=^y#<)o`CQth|Z_uzoZu}v2b;yCYt=^Byw^)V<$;!^#-jfBNk+oo*Lx;y;!&*L! z1v5+W7zUqsQwT9iemnv6!vGy(?`oMn>>J#a%hPiQjr1OG&8KYx6g}&GHc8(=M^9j* zLGsTqEZ=mjD-eM18|p29=qW|A4|_pucvVg4E+3N<4>VdgHSQ8<8?hA|gYiqFZW$wz ze^i9mEY*_ACUI>Z`9;iQsLH6WGi+Zj%+4_a=XUQ~PwurGzqLCZR`=5tjLX;JccVr7 z9D66BQ`?1-GdLH8q6)-m^+F*UF1Sq~p*((aXfW6>qgp3C6oPlNd{JD|h2@y^rtQh&8kG`Ancg zG$*IHGZ*qzJ^w}wBf#8yS>ys+z8NP#<)C`s3H~nrh$H*0>=dVjUO>&>umZkY%;MVZ zVl-QnxE_Y`(c6;jZ`deCCF6<`4AaE^J}3+d1n=(W$jh@!$NWbDtlEB^L=qu;kJXZj z@jGAYnr&A|yzduQS`&R`du!t8Yd0uaeG%}$=G!o2dgrRuBvt2duY`|Piy63CU~2CZ z3~jr|=v1{%Ao})_zN^{2h_{e4N&}ae!bmG^nVx1hq1t;Fvjtj#cVAJavarg3ZS;vx z0Y(1oPmxT`m?9y+b8k@7!jkKGxcP1P!y;XP;tXCMh76xdr(_>-^tnp#rAkmyH6u~O zQQig5W^J*%J;XNO7833|_oMvx-5rq?JWOUcOv1rAIr4$l21_28^kK&gExP>;YZT|G zu})QPOuhGuul233v7Q(PJ$$2#u$A9@S)QP3qMoc1a{f~JGq<&rVdc8C2k&7V?+9uR zT3Op25MeTl`&hocz@>aLCqJFazUofmsJFEJ` zOrGhtd!;Iduf&kCfWOtO+5wZPceq3T8!9o`j`o>mz_Xszrllj->;jt1gXXdFyG6#( z`n!)k89uGQvVZk<$^JEZBLxc zbmDT0Bl{)IKCjtLB6MY)v~Jht6OGftI{#tdZJo8M+1(`gnl7d?tSn)jytQwoSHbrQ zbsHZ2uv5Hcshm-0JU#ZBKMqk&{84OHde6Er~&(j>Vpm;u{0{m+qq|X*TH1;R(uRmh_;=cDk z@lZgB!y{#T4H7#-wg2r2JdaoAE7s(y#oPVAh{)YeFx42n#~0H=ANRLMF3$erTN4Ne z$m{@E@%-A6@9MH#Cg*EMG30?+zwORU%wX$ezQK1@;Fgkuv=O8EBG7)3Pw=mZZSCp5 znIgi0qx8$fEm)5Y2m$Fj;_Aw?hmhZMyzGpwuHooAYh-4$<$Cpr{I@Q_Gh5%h^~s4B zKH&kbvR{`NlFS5aI4H(r_fp4 z!zcA3hyLAIO*x9OG~oBM&UznADqe-;<^z+pyGB&TkXCvTf)Q2QyS$Zos6-a8k>T2v z#xmioZoJS+VnqGgr{FCEP~kz`(%1#%`5zDJCyi0IVJiDr$dTwmrs){)9NC$gWsQ2z z{I1Y^zweXbPiBL$uE~3$S<-Fyq8T5%R3(BDKD#1SL&=1J5`F2t98{{NzckX8IX)Qg z|1hA*tkScvNOz{&X1WsrpE1-`D zo1BaByH#bF3rK)XQEjVOtrl)*H>}okB=Xp708AQ`t5$fdOtIC-;Dl>GofG`^` z6J=9);;T~`8(W$TIo8WUbd62h>>b6T-K-53L}Ny?hgBJ=L(qlMpS7Gb8H+WIhh|>+ zselus(r{SWEGqxUm z0MdY8vfXuz-#~wG`A@{V`I{p@RRVH(8#Yr0?18=ZUKC=-8~=Cirps<#aM7Cv>=g#h z7-bW+VSHzZ5|!tMh~qx77x%4{1OUNaFPpUFW73c?#;Awou^Z6IjSudp7QLfeCG$(A zAbHc*#k5~k3Ta$WaAW8}9av`LZA*u$SbhGEp6;@wE<|9ryRv)9w<=W7e8D@!+Ga|Z z+0U18JfURT5tA#R^Tg<2+f%9%XPY)yPc~8g!MKDU6~!fs8HrMpI?J%%jo9i|mtTmFqq0rCQEV z@{XwVSNiZL^?cJl_}czn%Stj*n7NQ&@_DBLhZtu;M^eEn`b@g!WpjzkSO_X zmZeHgDDb}HRg?M3PSA1@FY6(i{Nb|dQxAU&4$e%LbuKBVs%EpGXg&sV_(^LX6 zR`PAJHyCNLl=m46hF{zh&|Yl>JNIvaDlAh$D3f_Fvf@y;H!Vv-(HEUyd@Ajkg2QV^ zFk4UWgvkSh0t<2jcwENNX?V%ZD3O`|zB0-$UPnN=Ucq^5enh(meU#F-6qIwY>d7a|_IK}-yeDmDE*|IN{0ciO;w$v0d*PAc(qBR9FC ze;{Bv=*Y3GVfp)!;g$D;X)S*!dGwCLa)Z!j4ik2X1fy~C$IRcR1l|4Kukr*VA?Kfq zG)HSTSXN)&GSD9x)(}xQ90Sc%BF7+bTy3Y}sRz_}(8rc1E$=d{T>8jOK=%H(R&RrjiUYqs}iki@dJ7*B8{ zeU1|Iqbv_PwNhyM*xCwn!8*}nLG(=P(wZpht)fgL>9d(+1N3$8@xj1Eq9<9T3gJDP zAY=ieu>Eu&_9TmY!Mn=3HU_tht5;g&wG^TO9# zIjUpN-qBg3RA$%de?06hon}CV_605WU9I0EtTh)l(_)A>t*;V3)7$K^gAW*0pQr?; z#FA6oFT#|1o%OK%qoY)+$|iR;kDR@a%Q^?7lhcnkhBb=Io8G_r!OxJNt?QySO7EkM zv*v>4ReC+|;DlO^4zyR43)!^4eS-o;Ol2f>wb8zhYxq$lFOBkhS_H>RZNa32@NWm^rgwbQR>=2BFpIJYGW)**PV*&Up|C034bf$ zJJM|kO!b3VXfcVny{VtF>|+ru)SEG*s4^M=<5`>Pql z5jyN4_oU_|t*?DmL|^Y>N$e8)ir>xjwsL{6BhnDS6|(+hEmg)Q)i{yKJEIX+`H_v3 z4FQhOQOJ2H6@sN|SY zKktHYx*$L;Z{Bz~um*5|a3v5G2z!q6OnA?ip<796&@{Ul6f>b?>RN{u(NPQGb^jE1 z(fIP0dQayF&I&QbADb49gCNX0Z-Kua?AuYy(^;`WjYrOrqM^4ey#8t{wkD0Sp9{4| z$Kh4H_f;U9fm-YQFdv7e-RDa*wA}Kdd)%f!nON|r%1ni@L`O%eEJCSk>%)jcJAT$4 zKzQ6S(D2_6hEr|F4IGHEek9sa?nw-%u%e-h!cR#Cz%~(a? z_0{y7s! z|5q_9!ue2re}*S4)1*!_@MhsNNqe@4?7>aN%%ASnS6##ARQNmu$v8M7Vc`^2K}|_Fg*#Fktw5Ex$S*$ z-hODOd^1ejpUy)`rLfqrgf{V)C2D}M(ruXb$n`SIqe*D9C7jk^pp3STR^dW)yad3*@v&}=?Gu16@Cf9BTFSw>c}wX?i;fVYuau=E1QaSu}7Me6W1xB_I`Rg zWAAlv;_ux3C=)TA(*Q9 z%Ct5Au-4|}Q8?jiG1Sqvx)7`PjWy>&+07-M^XZr+W0WNdmH_2`oI}UQESi^!q9cK1 zBho=rIyoFGr;jOm(`c<7I-sEJz^@u}*#2YtCQCz$>No0j19djdrN{B{895Du+m3OU z?#VoqOp;uZ<&~os8h4ee+BpdCtJ!59+0}@|`Ow9YN`|n^Vq(06#Ov(ehYME6ENtGT zfD-)S_^_o3K>&n}%$hN^s^y!>t`hXq>#HPJa^$uT-=T2)Kmy9q3?r*ue1J-P0{SnVUv9 z(g=1JUv^(~iLQUg(?FrUb|~GecmA^NXYkF}9{btHU%@lfOEWM`qQq_SET{OsAPwJP zDt%#*;6T@<$}`99RcxXGO<#KRSK^fA-BOo132cI`nFh znc9|DLyWH;`8a6=(8!#J`uvv)8+eVHhGXNFR`MUq^A=)zS@0^vOGP%O1J^<$Kc?wR z$dh_ar9YU$3wn(u_^69z)ZqvFa`E=lefZrPNeZnDGNrY%uS?qhpvR3`OfK(fh^vLL9 z&Y3T+L;O+rw`!0{CfGfy!)A|14BGCdAGAKt8o+|4S18&>oz04lV(7nU%G^yP=13hF zjm={z^mtRt0>*wr3YTr!Vw>NHy%(Gb^Jy~mF7lFHbPyUJ5w2!xaH)F%C zC&#{Rf!aLO4;4QFo2&RQo;=Ia4clLx0`L_+JKnu&7Zc5dOWdbxc@ExBi2cRH4*j%k z<}Mahi!1M3vOET&3Cvq1Fk#kz9+%62L>|cEBiba~KA_JDgHn;X{XtPo{)%^%@Y^sSL8g;?gDx-Wv$6G;?JMI`3vt&8@xjA;fs(x|{ zp@ej*Ja^ITb=>)ZO8f``|0xl4-4J*&o19+>U6{4dx8^kJ9Fn%|R$klE475I*|L!9u zVuv9cEZ=r(7kp8gCe)=Cio!%@p4-o=K_(tJhH&QaHtyynh>9DrHzVA+k|x`ww;r2X z*-9pA2jn?jJ9shl-&J}?XHuD#imVCU%Jn>rstU}v*D{HGv{Uol=>3&Hl@?lWH;*)5IhEO1T|5i6 z5=4_`;*6KAJ8Q3-w5UwL-EBI5E^$N{3w3T(-5H)~Q7`Wi0maE=9+cTEvI*|cHQG^c z;oWwes}#mA>z4N8Y!oEIQf{4eBhCgf?43veH4SSf_acRDS6EoreUZ0qz1NrWZF@Q7 zwLdC#p&v{Sz0zI)Ht5knA0hnqK1QBvu|n320QeVJ{D=wELZ;JXz%|wG_%g)&Q~bS? z`xf1_F)aVlsaHeBS@G~R_>RT3|Jm@6p32ynX@c3j7x3Y`G0d8)(D<_0$`mRQ(DQe2 zjAV3MtLRq5aH>+NH7J{*GkS~!%~8{x3~lv;X77j(lyo)?_ucV;%)m1FUYN?=+5<`A zRlaQ1RlLE?ltueY(!==J>5ffL+3me8s1y{H9sF^oByNu=lgKzOA1INtf$LkZ*f*8# z)ND<@->28`{f1&;ueM=?RkVtLY9QmNf(;D)TD+q!8s8y3$1TZb++7Gn?%kFyKTF(} zb2}CDMD}U-kvdtv`{D-9-ZwTw(rx|YG{l$fd$Ic(Y=S2L(Efa5m^u_i`vTR{r@7gkDOMwB5^xjA$xQg9;-$P%NI(%@X5BuID8y|4)$QA^OT74J^tnFtox=G`R;G9i`x5V6>AqhKIa@s@8-Qr5G2y*?@Ax($y#N1oqP@IG8}*eeX~|>hjWaneKX@GN`g_CsaR4nSs(iP{qjv~>XW5TG_UHy9Lj_vbVGtpky|P0_}s2c z@9V2=#C;c$r0qb+GY9NBEeA|imgk}#t< z2JpVjJ0TT9$yN_tYvxKC>r(b)jGAPSPYV`gjSj0+bu?MtAgrI&nX6pgB5XE!PH${= z5i0Yj$TnhaD$9I3#iB%JvPTh@CCHs2G|J&)(GwXE%o5aVC}K%%qcf0rHs}3~J%zd= z)%z5Hx53DE+a9wRKf>f$yxA|Rfj+#FzG^F_C)63s6+dv>T+98&8F0JHP#P5AR;s$XWiWWoqxYjMQ6H-HRXVi_)`rhq2TaipvMpr}~ByEaK@6r~E*n zK(o5sFdTDEt#mvnc=6#i+pct0OC+9iXX|m1 z5$;06q_NbT%L4d4H3`;mq9*=d&-HI5l7>{U4UkRw?)8yS8?yY^F76>TQ-inV_dTuH zREttPZglD0W_6FHNWLGjc7JC1ONGI}k@6@M0lOKmh8WdGQ|L2OzA|rHDM`C)n>gom ztuG^IN>;R{1wVwr<%fyt4?iJ6UNVt=HyHH>r2uk?%(S`cBL$^l-l7 z$Re#tiSV%A%O`k7w$*cXoK^ufS49@E;U{ zvMlDGMF)HSI@o5~pex=^(p@X8SRDCZZ1V0V2UZED>y@#Zr3gAdaLazjvP!Eh8=h7{ zTvytzaEWInO0-{`KeygqiA(1Fc5kB~3Ka_&qI2rCl)7BJy~XyMcxKJLQh6*EX>ELo zxVu%_{XN5;NrSQT{uw(4mwg{PJ9X&oH@u(^E6=K*FcnKAYXbneUj$Jj*{(HM89q(33(H(*$0ZO4PNr{P_0!N%#qNKG@GQ{CM+^(_eP=r&B2VVN_BTHfagX(_YRYoad}q6 z^raN0C%>`?Jp&z6)DcGtedPeS^|CN9Iu?m7T@9Zz7lV-RGwc*O<;4KzIYt7ZMUxWq z_2Kft!MublqdV5y6!u1DIknL^r4&JGyi6ZGgLlWl<%XjLUC+SW{p zt@xnu%o}|HJIxegu*c~Zq4aqexSPzsYm91xwe(Os#Fj0lAPyL-$!I_(Yhe;j5@$k4 z2wsoL5zjOr{6Qz_Hbx^KnjW8y29|$mheLBZTi9E z{O5oM2>(xCY@)#&cg^!AbF`9zQ+N$%CSYMG+d_=_awr?^rR%q zbgzuAG7xdfv8m#b=Yr7dN@ncY5Qx|Ycip#t2Zs2e;8nhXfh%V4GB_HA#3=I_jYiQP zFG|O4Pr_SfEX|{v;ZQu05uZ)d!}QUYHgke)^;%5ks9{SLt=TL$Lb78QyqGu_LJ5=_ z(2N)=ua0`hwwR>T8rtev-0~%bh%lMnXtid);TZx;ydVeO>Hms?74I6g>$5_aXyX#<+ z-cLwpIEt|VPb$Fp?7Ss?RDAyS@XUq%w&u+cE_8KJKCWeZsO^i%aJ;#ka(_!QBe1&> zWJw{9ts(y1kJnxyi~jw!1{EK8G7^9S8-Du zxa0m+snz2TF-vLp`fz!DSnU{C_HA*@LjAJ>YG~;%$sqhAx;tmr<3uDO6#yW3MkjdC zH{Ge{c+zR(SF=La_ZcAC(wfR{(-@aiUo`!9D(4H}&``GqT*1`@9%^ov+2v>CqXv#> z;D>F>?eo^hWH>tAPQ`oA3xuXG8DI8*$?MwoSRq!!UUiqtK^kcN<|d!(`j<9O>s10c zz`{ij9}pK7x$4gdx}(G-tyx?sdl-ln8rNeuYgwaE=`h0#6?Q#XDeZq$R5vMiMt2wN z>VFf<-jUi7Pc4!@a*(FL&*i|M=6O5#szKj_{vm?tk&7vc6Qee;3zs`#xsZY=)Y#MY zDy+-2kUy(hl0J&1CNbboe!zqdYT7;G&%GyJOfQ%(pC{CE>$ju^-4=zic+QGX$5^9= zTjU!-U-hf~4x;&yk}%2H)MWZR_4~(F3ocfAkG+9L+==wr$k-ry)L+R>{Ja!}M4u;cG zrY=DIVfDdVMn!E7F})Do#Jdtud}$13bo>~3rpASgS{y$^T+;gU%=Hh`b~(;^NP1aw z+}bB=`k)@Mh;)jBaUZ9+UOnp)=4CNv6rcHO5_unzB_W>cUQr5geLL>Mk$5?k;+pao zIM3l?8{ft5T9$1Sz5 zU4>@@&J$pkP6_syl<#Ald(9X^3huXcMytH>E0+pAS?}6Z@Y(tkw7TY*_)V*;4?vk2 zDgSU-%&j9}X5|-7@|pxTibs4# z;`zpi57*1_WSg(glSb)@xzO2>>Krb=kq+&m3n-+X^iOQ1A>7W=fdp;4GKHCULQmd&Q-MayC9*Sl+pTFE1JYZ4e7`O7p+Klv`rq_l+8dPn%^n?d z7nG18x}TEJ{Pz`a(Z;>~Gv9xu8y_BXD%5xwxW?1`vs^s?8)yPziqMz()hdMng zlSdo=L%Lc@&8-(U%)AUtCLut-?Cn-nqXq$71u0S94c?`*-A7^b2k`NqS*b~uu|T>8 zhH|LSwfb1Ri_u|iNUYX`^=;QL*o}^;<-6M2677vG&Oyle&tAikbl-+B!{A;QnCBah zDEN<#LGyZ1O%3p%2-eIbOM0Ww+1rP3cQDiG7->fL#TxJ~lME)Pj6d}aP4>3KG;z0( zd_Sdne}!Cw4YpF>A0(z}ee9E&D~Iuu;TED|}Ws=vj866eL;WVk>nC2P2ZaTe%2d zbvDL)0aV&J|Pg${gZQW|M;~J(G8)PB@aoMpxH&6zUy& zsY;8&-K#%pLqJNlU*k!+&EOHiAIIU2N#3u3Ydrale0;aUYQeyJ4{K>cjD&nV^?q?j zM%tf{TtE5sN$x|}-hS%hQdhcA(70ZsJzEovxwDu=clu{R^dMt;ujrN zxcuGkQV4yRXQve9jn@xbX!l%L_)~nNzqJwv`!K1(iDli*^dbm_Kt(<-<17%{A+NB6 z`o%H50c`Vpzpb$0IcoKC;IjQl_y|^Qk?}+xl98gXK9g6d9b0ROX^{)e=E-Fryd|q5GU~H1+Ztd-7)n9wGbCj{nSU>a7!}D*9 z#KK52Cb1r3bhq=9T}&gh5#G?$jI(>YnC?lb;VD>BmNzN?TxF#aPGx?D^i0Y-pLeea zjLw4yZ@m-K`Dj7J9ol`H$m^0c-|x+ec5Hg>$0=HK5+-;B3e0U(SN06HP+`a!vHn+A zj{M^=0|#pqe$Q!C-i^>oKe?i~pQKT{c!BK30&Lc=J{ZoLgwwYg8UGQo^U-eGlU%Ty zIYuTDQ7o6X$9DcGYne~N8$Wd)>#o1aE&;`oL4)7bIt`Pr6@SPjQ~I4jwNetC2sih! z!&b!rX@C29>n^+TzA$;^)Y#T%ChhR*jm(Q2cQ(a%^pH7qlmZkc!WV z;*Nu}mklwAA|RPD?{svli&wMnE9@51!Y0$^`CTew-Il&5#|kPqg(M|>Aidf&bJpOo zn{ar;L2?m)6twt#oNL(xpC0o#CFnBwtHQetzK{qf}MhJ=m!6XB4NroA0 zDK4X7L5f3L&&|q5oPdJng{&S7CfmXQX0m{SA3LcdbM+QhX3o*hw-yrmwJxsCVK`v7 zUt^~s+w8R$UHiCq=yiHuWwz2UVa~;gzgWXNe(Li!_QQZfx^Z-7y{oNW{jj}c>Z$bM zK10h+TW+NYGpu`9{m--&x?_6_UVS^!2;AdgYs~ zFO*XKCbDVBeyujg@ZR6UzQ(u8A14SP;XM@-MTo=JG7K!Y`yQC4VdyNM(vfhKL`Fdc zzRBc;ewA%|Bl7OH>rK!bn+$kTB}v=B#Lk+c{+8m^Yv2A}Js%vbMugXTFopuQGpjI( z-?p{_W0oT5w&}A^PBe7k;@S8$>!N8^baUBWuTccm+L#9RO3fB$g=<>2myrqIX%?-H zY(wih`(}4bdqpSW&xwY-)E|sm|7@H-Y;NW7_$4(cw|a#v-pY8I6ix&Q*d?xqQjY)! z&D;AQI1R#xBnypYu=*xhf`?{=?q1Q_xN-pnGBT-x47Yh54-xCWZG%d)*Y-@s?4`Ys z**URfTpG_f@;O_orHL=z#%ZIJBChikmYEJu(Fwz~@OKwlMSNblL{BU;biU|ZdR8%~ z(9a*k>8};3Q#xN$<`*#E)m`Yzk)6IQ*XN|fbQ}H1=x`;DW@R39HN9jZ*67Jd`0ho& z|871Z7`}!BH+qF{{IK&b?ls|nD!xt4P~2p|(kOis2Qd3HgL`KzC0cKXYhX9Z&SBpa z^JP{nNcaUyJ>YjQv(W}IMMo(!HiAmZrI<547Mgk4F_k z#T7dYs{mBtX-scKP;iYgCkB;swz;iSx)R{#(rA%^ZPpgIA)~Pyr zh5Q)td4~l_i;O++P@!EwgzRyRBb%U|Sl-#ePt7r6Ll?+UdGx+Qtos-YWxV){hj40> z(lHAii&E2>Dz(4!c!4G26nAP#rDs_6%#bp3XO^%E-=ED=#5{aIZ(DHNar!Hc`ue~N z0;UhK7%X@K^cr9k)bBu%MU)_jb?O~whW>iuyQK6S*Y08zxyiQ|?}cQ7sF;>E1X-+o z^aISon#5B$4|g+%>Raq+-R=4?iP9;GE1R@T4SZl^NlPqV z1cLCceHz9w;IS}LVb4VtdCk57IqE{|{xyUZ%0}g)AK?{-&1sihGq#|n7O|}!ad-88 zK(mtr!rlM{_B1J7u=rYkl@23!sIOCE3JXstp`*Z4bUO(IS@eyae;S(0}K zZtr`8J~iK>2kgr@j~)O+@BQ#(bAwT6TOwj_y1E{OH>&FGZekhnLE26$gN(?*O^I+Q zMRfgr#h&^ml*BML=rSbnW!|j)mN_W5`#DdQf_bqJe0jZWgJrhbBURR@LAK2VHEE|i z5Kd6L?Q*!;K9=q~5Y98B{NRlTnz zmSxdO8k2~Bs3-RG@g7>(<3d#>eLArK|j!98?a@w#(<58*&!b{x%LZ7y^hs>#N4Vu3*oW#kNHa zu42F3#KoS6ja=N1?IB^wM$B_htz=WN-kA9X_l1RKUhI|MVaNV9e*LmdjjtjPx`@1| zpX{5=7B%)v2D1dQ`8#HhBVWlU^SyFnV?o3Z7YED-F6@l%`>aOi`7}DH zUplJMdvOactLP5fCtu@cud}+Q-rg^Q7&gX=e6z_w9!*!t(|F9G@_D*vY%qfzzbMAi zQ+7o5`lA)X{Qr8=UY1 z>}nRX{^mLV$P2{?b%Oi2AH6NVVI0N>1A3)j@rVx45%V@SI^grLFh02j9piHlm~vHI z4}Vf|Va{;+0vDaqFCC&|{3%?`z5Eg#(XamalV$TYj-fvt##D0J6+vu#><69}k`To7 z$UQW3X9I9$pT@;!z!>guC0lb9FU29)@)hvbe4d`zC?X!&`K!P3>-|j&{uv{P=_szy z9QZo-=97)H^pXwGIq}7K$lF-)1oVL1_y)44FUDkXAE!oMa)Vv_>=48w!lraCP6nwa z5hN_iq){3|N5ongSak(t_I3m=nedfNJAoN2Bd7qNf6fU3&2URmYkZ6Z@uz4L)EK@d z2naqBL*x;~+or8T5K~afETDeh_kCagdIf_p7YYqCWT6!g$q3_J)C7G2Yg>X?;vkt4 z>;;eWEuq&07~>K&I0VTWLqiO3j>fyl;r31r@E=YMwssIZN0UBs7J?QBs0c;$a@Lic z8y+3wa1_0@+nkP-W3|)84r)3h;aC?AOfM0QSxB??~GpT6O2#nWyzcE75< zOF9t{WanNBpwkHe06+jqL_t)772P)uI%F)B6jcIa{N(PUTYQc}L@^|IOG4;@U~C-h zNO3BOIn@XVN!OyL&zdXSXSe(aeHHBa4P*=b5>)veV=P-WKG?W?PGVq;#w5_P8)Uf8 z(0vJOC2EVt#g8artXfM1Bv@oaR7OmQ$`-uWcj=ga2wuc%}X{GGyd zD05@wf7yo1`{{)-=ua_^?DLv2@@eK!ez1~xwoGodk)X&gxemX;o)JOpaFxc!jFWz` zMRw}5WNyxI;QNimYw&Tw)@2@iy16Sh;7K3ozPZsA?}r;1DKy1t_^;CR={igVG22$~ znx{o;3!t!o58Yz_awH@!9r64+4Q4PE;~xL`$9H+dmmbpxWRGuTA^pgTZp~|CW32k& zs}b1<$%^aj1z{*3C7;Si<$1 z_S(23C(_)LZONnf>t*=`nX_Sj)5V5{P2R%pkd^gA;Pkxg+5O0dA765v7 zKY5Y``SJ_w&O9{l=TG=Zi{}>Y_~B)_8|>tmvjj1_^;v!o<{piQ+{HA0h|hOlI#lwf zKlGPw!2|yEkKXK8ljk6F>8Kpf;z$wc#$_&a%0;I1%-GD&oLuGSjJ=2-_{v$-?Qo`R zSU+j`Emv_%=Y@4j ztj&uKxx_53KIfivpS@^w9$`)Iy+*$@{D7JoKJqhTSk&0Pdl~ak2kJ9t_mLnbS8@=) z=rEl5HkWVl@FQ?>m471-G9*`V3%SO>nLn(^R*Y6#@Vy8_zQ1xEan18$I3KF-nm0L- z4ZmrF4Btt2_$05vlD^TwGi?D2)|GD+UW*>dN}gow@Mi1g?~yK-4BV%52S(;)el>S? z!5`6Se#HOjg}Lyx;ow3nt_ZH{i%=Y;ab0i0+TOp~);(#`35(q*U?41vTxF|&xbo6b9 zZUqs~4I5`Ear5;7#Dy_xlu_b>j72bWB-;f1RS04R%9+CrsczS7ifpQ9h39LB;!9X%)+?DWpJu)KF;^w;^||BxNZ;oX#O2V|Cf}oA&HgvFg7k@als22C@F;-%#eDO04PK(`bYxEcC5deFTcje z=}SzgLX;fI6YlyPE+Vkg*~W*H0sQqtKU|fR4}GW4nsZ(3{X#Tym5B215ffEE^!m~m0OSA5Vr7aWRwL8<)hj;`*$e77-&}n4<*KIOPZQOJnnh89JumrDOB-p}+aM zf5r%6eU*>X2OEVo-w%6<>mvOvonlY^R#eRr#QJxi@@rx0+TZNz;z<9}v|KEM4^6yaszd zh;7Hr=MW5x#Y#p&cuj%HzRx(D8C{o2tHcviYGZyo;7(@r@qnKda^BNps zCf8Jq>r3CB*VwbG#>W@A_$k+-1~2}a??g`U)%+S;Hb(k4uZd@lud|tkF0)b1XAnec z3;mGsHjT}(4}L;CAsdZs%#DxW6U0$+Mi$SD5wN0rVhepK+mn0Kqr%d>`C&c=p8U|F zW_6hGMj{|;;OVmtCOwj@6$JAKXSe=QF1kxzNbQ@Y&DOKyl*71xmY zMYxN{^7mZiFyXZSkjAP`6Mt7}bdMkAgG;CR4szlzW_52~pKO9&BSVdgKjx40 zEna9yOtG8qki)GS(=2}Qr#K{f#V2Xz$)Acp{OMQ>>u+B2kMZw#C%ukrKGV%|I~jEU~ZWyxHPLvK8%?$OAIt+VrsFTS|fcJutj?DWS7;_|8b z<=fPXbW@JZPmkrsbcgP%2k0i*(}&VcHp7>xGw=w@V#n-wm;FBk@d!eMAbAnkDY(BW zq+p{7yqvS*M-j2A)0n*-rDvQBpRpn@Gzudixrg()IJkLEg=4b{qA)>TNM7sn48-c9 z^JNtQf*c3DNn4d5X0RL$%owq;F=|cl;=mN6cE%yIw6QUffq=CwLClddG6}9#SjILC z01O|tFc-8KG3-1_s601(^fyB!AAx<0Sn8A8;Xe{gxOy~~S`3h&N}}MY05Gn3m zV$PS*wepwrQ}Cu^jzU?~6!<-Jo(KmdF?k>f*pA?@_~parwX!+I ztnneI6s46!C=B@siMW3JpZ_wxdHMk-37KL>BFc~RJIG4ob-%i&@ti(_1TnjTJ6n3j zGoI09YEEo`OvNZ8wc^LP=>I%l zuRj-3R8AqkP>3TN=~vk$-Bk$C3-Mzaxidx(*BJO9m!z71vrz4#Yl{fY(kcDWy?F#N zyuGe3GJ*+z2M>SC!Q5k>-I*^tHh!mXO43l-|=}<5J*Stfzx~HGQGi zV=^fjvu!?!A0cCLfDh2<3>&ZAW@42w&TH~Iao8Mf^q?pDHdl?`5YH9RE@Kq;==3tZ z)(5{<@y~t4VR3Hn9M8Bnw5>d*uVLa zft(xJE_WyI%HK=oNL;$9)|>5Xh{qT~>^(jQKR!b2;)fBVr&_$=GwHxs-^T0m`q+Dh zXP z<>!a<;LpT3wyB;LD>S-I=h>xL>2I-OOjn0}`kQ_7OJa~Q8n3zX8~Pcu!|La_5X9ui zkBO-+c*;LY#`EM$c5vf=EF@Uu#hKJ%y#DwfIEr!fM9y3~B#&mJE>A$}ssq@%#Rbi0`3pWs zJx%sx$7UC`WdyMtp8uft{^t7^*}rj`J06X^)Q9F?8%KOzyik8S$p8*JZO!}kEA`X16J>OcP06Osc~6@lrp*Ya4fts*BBo8y(?>n( zQPZY$(^h=!_1hF@+7g**GsI~tpZC{(3Hj-}Ig4G_L%@Ix;N!fLc z{$*x8!u%isi0Xjkws;wX$=Mtq`4F zdF7RT4y*RP>-ULojS!kP!f@IWrac+)ZH?sXu}G|~2D6r6Pa6r)^91h`4{Bbm2$+7| z*L~fzkvHA1*XL#*$*wJAOuy!9zGe!a`g|i3r>z+6@lo7a*2qPiHwW>NU6Y+lOlLdB z(+Yzrzq@Ly*dbOm!n^CMzH6LvCOReuq36r=7lvogp6zj{{7&`dk^VLkYT6bmy6$X} zbMRY@Xq`4PsO#OZe}9uxORjr-X$9T1CD1G7Hn5=2=5Xnymv%qglJh+*>OS&|R$z9W zZiVPvo12F}oq}N_J*KUonCe>|pP%a_={{UOKGyhe*viTIL*GQ9|zlvw< zW~`Z~9KLNX=`p-)U2LM){H$EE71b--$Jo7AeO`>?d)hZ1dcIoN^WE)-MW=0d;k1!F zt9EyT_mN8@ZKv{!Mxyupr4c)O_S=Y}Y1@6;^;*p{FBadR)9aq_UbUi{NIX){6sGRM z54Ufu^m@V=7TKS;)fSYyuBl@RhkE3{8nN16=SRgBzVEO!wOCtx?s*N{RA<40p2C>^ ztH0IZ>o)V0hl#mg{ncOHV={lFf4*4lq^49iHZu4I-LpCQvw8}Kg{g71bJ}~3wT+J5 z;D#$cA%5c=z?H;3clff2vMsi=5L&T=yJ~U9H;WwrY1VqWqjW)3bJbQjbw`nr#|g zkq@bN<+X*WoE8rO?`8Qho0e-l;R#Qewr`i%aS+0+%^(+|GiG#3sb&E{@Y0Q z>v2MSM%#om{kCuWw$8Dwl6TWjx>Dn-M|qaqgT2aY<@$@_?=0qgp*lmZ)fTz;Vh4Q} z1IV#0YV6$4TUk5OZCir4iUy9atsGC=isO`X6I=+otw!_&sRYeIQzQkU1WJ%uMkGqA{BO-ofJLJ6Ws7{`vN5jv`fC~q!oOPZ7>);dEpcwU5qs<~r&W^Y+51a;EiOrx zBzh83_QNi#_+{JPH&0h!;dLaf@s+RTBP37~G0C_DVx3r3ezUDu_XRz~->_&Xxg14; z7><0UF6SY7#;{JKBDc$ zTlqev&+F28U&NYWea50FCDY+B}YJFT&M;! z#g@h9;rQf=Ha#Hy7WwBI_hBZ8#bE`b!fCjuM|W(zu+WcWTerz&9{%u$_u62nJ2!1a zh$2{y)^>W0b_-XsXUqJHKG-;)ZEWr6q&{v7yo++V(HpcE=sEjoXEpXkAp}|Jphc^@ zwapb4?icAGpU;ks(fI1~Vv~a0q9uRPcJ(b9%1&R~Z-Q8S6(jjcIW^xXhVpA3)o3;i zwXbAvG;eX5&LOYV5#{6c?Oy7Mwqv`G!C1!HGJ=?l)m`QxN8dCr8N2^B&-0ODnEcd& zCI3VBVZesud=|RRag+R&?whY#M~-aK%c3RyB}X}^I>%-j+i@U>;g5LcKiCn{Yn{z?@&fj0Q5exyKB*r0DK)y++V1qui>#9?iD&eZecE(Y z{aV1VaMzA+?4;>I%f9Ys{_x@>kneo4+E3h&v*4`e>2!U5_VFkX#OxWDf={wRLVZIX zL)qBGX)#*e&Gz}2Rhz!mUKYkJ(5Y94IT5>W->T}1kBj1Z-EWK_R$ExqP-_?`-?nHG zu==YUyv1W z%Yf`WQtSvYi;|9I^H_%<))&VtIpJ&t1Vw0#Nirl6zUr#0rtNE2qY5pd+66&ebK_tu zNi!e2w(S6vG|-ny2y2|n9xJJrfVA^udQxErSUb~ZYIllz?Sd#)?C1}c!_}ioEbWM) zCmbEU8f(Z!gofa3&gM(kYMux%t5gc;Rh%qRgR?`DRUh>zSX+r@SAzOUY0C&=MFx9R zAhM55n_Xang8s;{aF^8HtrdWZ0|nKlP4J?-ib!*kI7_+j%KqBdm>i+a_UC z(Ad3N3s>%C$C20glX>Az+#b~s{Upl5wLc_DKdxToPNb#n-Iuj(?W8a*m|J&4jWB1?Yd3mLpfq%78qA=!n)!a7Q$ZfZ6bVc0$ zhHvVBqQT&j@(#=(4$59}NOXj})Y<~Pik)vX#To5tNXKs=Uk|jG9K z-~5!kZP`v|ebJA3JBa0(7R1O-Ub$}LH!T=j9FSMaV+sec-3Ai;Ca!QD;(6IPj_n!5 z&2ah|BCTNVk1d&NGQVMK0QIv>8mRpYqZUy6d1Vdgenyn%+fJ^2rb!DJ{oJXRVD)pt zn)38Bgl^dD@@E?H($B1GNoxN=w`SP=j3VP{0`CV{x359=vk;pjSbFwJQ_Ozmn6oUM zrP7qC527h%KdaMORL-{=!(rKoS3QHc`e{bj&wgq|SU*eDn3{q0ms?WQ&+%zVbwBsc z4^A~@zrp!ZZ71%e?N-|Q4C3LKn)B@E4YeY%pEu*s?-msL*?}!_@8{AKcJ;ZjM`LbI zs-G_eS7#J90;!(~;|xpZ*SP2jnQq!%)6T_dL9w5|)RLFIvytka&K>sSbd5ajdNOt| zx@`W=m1_ywqy?LPjuBaD&e?G`mow$s0>$Y0JvEP3jP^4f^>s}dKaa_olJs$t z#t*iHsh|7h?5~z^ce`nYQ9r+_1@3-k;=I1S#@^{{BhdEF%4&pVKjX439CUx$R#oSH zyq~M=+;QjiIS;N8&i#F@pz3FfwE*1D7h_}l+4y3YxwL}1;|&KGv_z%LupAwuPMj{MbKig}#%cvnpHR(BIm2 zO!RXT`DJn>Q*meAMrYfiZTJ1;*pk#9>&o}Hor3-RdhtqJ7Nh4i_UH^vXZ1Pbk$q@% zU!KGs+OExhu39VD=5?|3IWbCXn)f4h&Opjp?ME zwk_86bD;T~wh+=~M5moe*vOM^hy3;?c3$&m@A6ppXqznhdGf|ezvTpc8XFqR4;q2f z&v0&qb3ZS){Dk?ji$=QlYm<0VV_f%9jwAnd{wCdpohGh1f3j_m>G`&NbCbp<8nM*v zwvm*3zkMLK^TTpCxH&u3yw{Zv49P&OksG$nN&Sp}dZp1x@`te+b1XkHPBnqrNh*-5L6%4}R^iH1n6I$dAQ37-;N|{P-TVhd8uNqxQ7we=itj1 zv)f_g8|Bu<24DVLYYTn-w?cf*@8{@4Tv%5JhWA?MZ#v(0^mo0NgYrk3Ikd&&9j{2KwYaYGL;&yO+c87xEAH8LKg?KmEAG@wSrrzt!ay$*+PA}W$(|T#8 zM{{P2{D4}NUlI??58%++HzWGl=;Gn7eEzW|h*v^=g*QnKI7LS1*8=_c1Y)AC%CGS0 z@wZS&O7Dk-+Sk4IoT!3C0?Y9excmD5GGkXvAsGCy0@Aq%BMBga(hpN0oGGRtvdqEH zj(lB$*ykCyVv@rZY$aV4a3rddVn66n#ywk5?wTO3IhC;~ZpeVcZM!Xc(k1y47|U5J zo;YoW=<>HYl#{AHJ;GEFG%pT8K;aNL7)HyXZPE}_oR>ua&dc~TgazW&5A~dBq}y0R zIeX8x8r^>&f|F6ql9Q%@m6&lh67FS$7lIhk&~_t@62ulI+77rr&e?Gs$NvlZlJ{AH zm~OCP$%}-JACYuy>c|B!w#9!SYKl-|?|c*7EgG=>RT{l^(Jhz$Brl3=S3O_$Figy5 zZNdNBYHq*SSotD;Oo3%=7Os%l^BQ8BAA@0A8SY83_xZdZrbF5xiD9S^cd;!+2H&>K zSI)cVyyqld=BuDnWJ{>{05Tb$#mWJ=vmrNZ8nB*}0;m?e^=1lOj?~ z8aCr&)3EZ{DmeZ4p+d$F>ab_}wrL~Nw(GK!BW(v$C#I^e(?^&fCQo?5+mBk&Ir_@~ zYi-9%|DhlH#y9fq!?r7em|s`OdQ{jdAT;t8LoD7I!@7y(aIF58U`w>cJBfGsem}l~ zoM=06dNMrbm&OQUx~2H$+mOWD*aMj;EN2N~cE<-G&)PS`dcy9xb?uH{gR^+bf7Zga zzWGjZo9~3lCJk{Vkw+rR$rQ92!Upk5o=A{Yb4a!)=inFl1p4WbUuKKu!(StaD{q0J z&s4rOoCos6d&O@!mkt=8+}02CA(@utD~FjNHgEAvoJ3$NgxNWK=nK1+d-`z~HjP|Z z)L@T@<74>=awQjb!XL96`MN?Uhutq5{D z2oLem_z*trIGY=6UVxjpC#P%2LG^_MzDQqM+kM#=X6TCe!u}4b(fj=*h{;zRB^wI? zY(wL7*#&>VF61BEG_i(UkO};0}G?Jo&j3J8JAiYj4ih(!0~BXSpa$P$t3}J64lAV0*D^Yv?!#xnDWT;43 zwa}#Z^xV!I!I909EnQPoOYB{e5q4erKQDnXMxS%BF`v_njUQt3bV5NiueqNhN^-7{ zpraZ;h=`I1N&qdM@yGg6Otr5Y_1D?oE}C(`#g1M(XC)8jYaH%jrxN0BY#!^50p1EG zqy`;AN@x;kJ`#D*j=8u2(JOxVMQ{soK41R9dxzxW>;l}nk)MGjbqo81Y#D}tDg^P>oUwoUgm@dIHeeprYQySHf;Ui><{WY{is z_NnPxoKn2G#uCgif|&iuTf~if+~Xb#Jr}q6>qYG_6U63iUg8*^Mb5}r`KU%$ z`BcTeMYP%6b9UZ7r%1J^Am-9dO+4~hg`b$KuSJEb#UK8fZpi=Hx+ZqP-z7HE#a%Qp zw0+gS=dW~xtr#CWZD%_6`?9ODA$mqHEC#k8=jjU(6~B##ZL1^TXUz4vU5s^EANx%Z z^Eu)uA1RKOY~;k`%Wf_3lhHPf{gMg!^Fd;W#)ryl_+LcVm`2%?i%t6X-d)?paUqDs7DT3;YTX^a zB`3bvh7CN2_*MBXf5bmo#9=%BzfKb`$XbkT=gfEe@_9DIN8*3l+3TI;UZ-Dvi=JCJ z*0*nEuzAnZx2lm=t*v~-I=71d4+}YHkb`%I=bF~4+f(;vB%bMD`zFo(T z<;dIEoIFZSg&S$-jQ70FeaM|nlYRT$v7Rq1x{vW)IcEp4{N3(ud7m79nQYv9UXwdm zpyr?Cl~pH*85VuzA7b;e+-+Xp^PW4l1Tmu~1Q*9n(8I>4T#V8sa8X7M!t>?ifla80 zI6(!`MZnt#K>rfA_9GHq@ggKP zNT_$w;6)A!FZZgk3P_$)SbDU3r;01M*UlZfGi-MBB9Y9`*FS1E_^R0Jk4{Pi?E;as zD$43U^iq*SH#vq?2_S{0zL0McV&kVL3VlOv3>yb7$+hEz z&h1J@!+RXYzsCq-{zB1bXNct8PK0fm`@kNlMK{Ve_&o%sMCpnvuIPln=f)b@OEwg) zbOLdNq~bsHS>(ak=ht~228ahqA|hg}(4ya!Q1NHJ5y6KTt46mZ>IygZ#V7OA{%_Gq z(a!I?AK&khUVDViB0PrkVcW)m7;U zaPL>N@sq}doEzKy#g-&@=NfS%3A2E!k#p@Jkcc8tJx2#MHsXFh=l+U+O^&e65fi>4 z;;WrVC_cVO8Dm%Qlb`sp>CS^bsP+$Ch7saY;#~=*Vr}^Ck#z}THpmtoD`XL9n`Z9x zc$OfBIUDCY?8Z=NZqoQpIKu$h=WmT&iB&KcyO0%|GzH+01S}GSze7l{75Zo{i&_<| zbQ_t1oacl1Y5rQS0;{saMSZRE8nQ#2M!b_DJzvxgGeKPA=1-BsNIylD+((l`%A4e$ z7H!A;LiK}OW;f)@ZpcHEpUXkX)Hkn|mRuO6kvHxpT56KHHJTJ=)2SeD|pY(k{cM#JJq!T&w zKXQEy5h4DvU4D3sxLtLk`lds4$-T%(BYU-(d!1>E4RVWlZHyqML-d;OvVgYCzs&1< zzn@cMU48Y{UB7DMjeE+e%on!waa;YT=T*-kev0fD*WjXFvg1w-Ic&H9`IB9XbODhs zH=uj^6ob@Ra)R2R;G1yzBtJ4R{>nT3E${MwpEb`-+HoO>Z5p!Mlb@6?Y|`jW`;C*n z@JB9uo5p`yyi#KzNYw)CH1c)HZ`;|`JvZ?A@_k6chdu0J-9A_8mmcw@VugHJo+#Il zAMh=ed#%#fD(~Sp)b98ri%nxWT=jJn2x1r+r~KMgHJG`{)zn7xY297jg+V>Kk6gYM zhWKWU?A42MLG`qH%Ks}~*5~VSj3AcpwI8VKxh3DWsULuW&6a9(dR2=f=C3~C*UE?1 zn6`O5wgfRDaM*RtuExUWm# zu|kQE;qa=cSELDA5?A+I)yYZz%trxl^|jjqB$bLT0Y=sxrW_AbRC zXG1nfjxlGbA6PiANzylLk|CtHB3|)D#wVe{WZn*9GUrDGajU#Yj%^yBr9elZB9`c* zMpiD1K>`xulq|+%NT>J;1*@Pa879-xe|~URO|ncUtoG6g$3@I*?9l!BV+0Q0fv_`H zjelTU`eR?P<)2pYw_v?)pqGjw`hi?THj6RxR5+E7Sk%v| zukn$Hegu;p)XQ}3C=kSaIGrbJzN=&{R@|%+;&QVyjf^AnMGYx$C$hX11%cvH2CoZVUUTcam7*w{TRjxLk&vbpG6 z4dmM@=5zkKyoUeLHxfc#KSrR95yTc2?|p0uV!@_%wFtDxfnnq9t00#IFEG>Bn`VRJ^tFX*h(C^pha0)o6O z;@Nl^l%2PT*me8elpr>CI3q6@w}c4c!#R?Had7NbzBqOPR^ZjhL9u>NJBa&D7yM(q z9EqSL$x|pO9FSMAuHuc1ht2LRNgvsAXcCB3ntS+KigVF?y}MSyB{>{`-MNw+EAMbz zHK{TOdToW=`FwPqP8Q)~teh@Vg3gTf%Wizm*L^rupRYdH1!t-+x~!j*(8dU2gp%Z+ z@1W~rlob@Ycw*nTULUq*j$$M_YW=jM+_!A3Ae=CoHa3oPeP2^77=NU$#;w4lOJs~tP!yXlzc1G$V+*$IjDC53*kH{b>5Fel z@eA@l@s|wfA~Ky^Pc_0rpNpCTRDLeriY@TF5Y3p8y%q)JCKUt44?YbUZc{?}hte%y zleO@?Z7kVj&ihRe{~vpIlQYSZ9Ok<2O4K{i!QDm^=mzeH040qy5I{l=;&M!K#0iP+ zfdD~k(4c!K-8)J76O>iQ$khh}{G%x^#9JM>uWC;s%%HRF?8MU2UgOYrfPUd4lSkWJyECjRkz{b%B3 zxdO+;p8A;B)Bnk6Vo!aDoqnc#F9~9PMSg>y!R0MQUV#3v=j`V>K}@Fn*D!v|`6odv zHaM3_5Z}|8`R?SE*mwCDw%*u*O;Pw5vgcpx%g9&dlQFSL`fdK=w+UjwJ_VAH zb4a$H3*+vf7&)`{PUaA5E(z%&47yq_t8NOEMz$#hn& z&~36bh;^%=^Ur|rne&o|L*kv2omJ2?P;|>A{g%u$TY4{uF>soI&#C~wpL5VW5)YEh zk{AXa^g>~K^h>MWtS%JrvLVjpm;oc*xYiFkAo=28-`G2a4W+YI{u!9RlpuB6)c;)AGj*YRf}=S&bQ35N!xCX8%LIGc<$d+KRb1OOC5Y|YI>E`U?|#Ym z*p44gN!aTIF&Ua{G+Cw2{Fy@6B>S+YZ}-~yY~9%*gC#+bpmzpH=em8X31V%*&7jaE zCVNZvGbx8TeKpA^=}so}jcy7mB?8~G#e~%=e5}Ca`%dy*NC7{fTuiQ;LCc$43zm;CrlvY6!Lw=D?a$Jy&g`};jbUnU>2H=cIQa}nPfPm2@C@1FmADM9?wol56x-uk-)@hvJ3-V@Bo zs1xX)R-%qUS9HMh!1bkM1cxB$$M{PS3kV$&9294QLLE=G-aweJb@E%C_+FJIOC%A^ z9y9uLYq&t3b1^t^o2K(J5a+=D-Z{_jV<1r=QLO$G;4v0Dm8~2EwBwwfJ^yFG5SWICE)}^0$$E*hw`-&#Ox6rduxK&?eyes4`YKtvLjD+LVpyv zNTAYHgCc{CbAp&ouvg^lI2Sr0X(?eQp)^jNQ#E*@4-#H4+2lE=WVqXDB=6?Q*8(F+ zV!;s(=U0E@GyQMQBlx1*+Qi;S0BNVbIc=HmdcBt*9$PI4wF+?VcsT#|BmXuLsjirL zWlzopYe^b*=W8U0XSMm*sk5K`Ruja-lP%{r1!9t@?5=jwT?r%!A-D1IQT(ao(U(pT z+gFd=f6fVF18({$vFZ+`_Y{4XKVmod|GCwZ%@Kcn?+Ie^Eo7LND1tes~6# z?6QRfY}zDJ25%^P)E-VnRt%OnrAyQ{5LWN)x0bO{xk+MM~hKmxzjpl!z$3R}my2oe(0Rbm_e#3L+h(LqZ7z z1PO?cP(zhoLJ1H`UVbz0&Ah)e$(@{g&$)ZAwf0(8?Y_)-6EM`;f^Qh8a-&r*-}qzB zsMwg`uMV2pP*p+2>C;gQy=Jk#!W~N*#{Aa%*NUN7YLgU}dX)=SH!(gzaWLs?J_o7( z$Mad258rL-_?9=Dzo9wm#T7)QlzlWC_9tk7f({w$-@ks;R6Q#J#|@7KNQ0>6KE3mR%;G1XzwBmxO}cS#2BmIk*@4y0h77+_K^+A~~0WBU#Vita3-F|+1Aii-5D5I*I# zdo;?;d5Gg?pYq>TIW}g?5V@4|8hEDQ8;|t>-b%L}tjI13CnCSPxK|<|GRsm-h}REP z8e>DOSsy?qT^LwaZ2H0Xmd=Z{6F;#Ti-NkKdc-Gm6eSl6R26 zrYepYb0Xb$bYq#Gvysi7gN`XfLsIA-m#C(-X#4hIq^XkAppxGwq2ZJ4-IAOHiU(GY z2QTD6>^u|qFpCR?w+PGJflFKHJ$r*J4c_KLG2s-gjO~}}k~1>6EUhMfn1Wxa#HWcM zDje6Gw)y?cbYe^zy!eQNjQi4VBQUejE~mxQD z?O>OcZZ*ihPT>=>f@Z{tZ<`0)VBBYETz61+b$RePueI?DPcu5ge9XFeLy%clPnVC_ zl$69MW_AH@7@+IA8QdPVh|3pVledMxO8Wu=4l{7#AzL zz3?|H_mh_3^DkmO{>3OIC4pN`tzL3e`vfy9NV}~}jr#W+7c{?a z2eU{R`kBdn0lhtV-Yr;XAz>&r7;R*h%c2wA-gG7a<8Yr9)_? zLTg1=SKIW^zZ%%4amV%HVtOBaq-D7PEB{lh$AHJ|)4;=`G+awX=kmd>NoSDRbh_n4 zIwMce$usb-{3DPHKlVpO@o%FhE)koFS@w(umGyCj(_qP&I!E>CuSNc2`aLC55W#{Sb6kwanM}Q&rEaXlmm@-XH#u4 z?zb@>Im$}HSE0`A&?dJD(jmtUcvF8#%ZVRbgE!v@T=)f4e?>dZ%0kUjax)tKtjvy^ zGn8MySaDmQw2bUH`wa>4HoHP-t0qivR#3vnq_N!epg%40xb}+B)muGj^KinUk1pOk zdSNj8nR;dw&Bbb?eLK-#Ef{CM5@aT^Bh_3nkl9npnvyo(QtVT7y@ z?P7Nr3Y>VjShvH`ToD~p3_|$iXK0jS+{d!dmCt`!MsEL0!KOcE^`(6boA$@3bjDZc zlnrKA1e7sKhe#QimwQOLl_&I6>j|EU9$8NRXEi~MwpPP*NUvcRWxSTA>bL9N*BR$F zbyhOuYub(vcIxDI0ss;&&N%hg{= zf*6LV7&yluZ5S2@TYFaOh$kI<7&Qx|^r<@GZd+Tj6X+&6rtESMek!f4hQ7S8j6JdK za|vE(9bAiY>5U@wna}&6?A_|t>%^ffr!llAQm{9R-b-Y822V4KI03J7T`z@M3yWNV znPEb!S4MLz3>qul{O^1ke@XnVX!Qy|st-(1iy{23B%mq}YRb>Yb9+qjxG;!CN-7o< zNFq=DvOX|zAvcJRB;fj*ZS{jRV2DlWDhBdkE9ZuHN9mn^$K#Ti10t4AXAX|Dm(_gq&eq3sZ9LGXGbj650X9rOxjzUx__Smyv#MLL zCbjcUuT}5fo9ZvE>`jfd{w=@OZ64=|%1Kysfa&YCG|rrk^6D8l&i4A_MiO}aqm)l) z)1owjFaC~|YqW8{5pb}#ocsWFn$-$HC9dMnpxY{*adNvCJCnx^MNQHl&lwV)93s2-!YMu{{;%O^{n9AT;jB|eR=_7)Iz&D76Mzoyd-6R_M2|AjgciVjq z%svQPr>PA=D`fwtBE2WW_aL9+dd`ht2z&W6rsv#wfJ9M!>;XuM5=0I6w|l&k22t01 zFqf>9sw8-kvDIk`H*fllcO!u>HF88W9lK%$u9!XZi{ZgBDm-2MES&Z|V~AZkn!m4l zQ}+@Q8m4nqt{=KgZtjemEMA|@e@-IYJV8n5G1L2 zZmko%w@WK0+!1EV#pllQp|!XB#ycRzdj;qvny%*j2Bat505$9u|i!m=N9huP6zmXo#e`L=#{?LSC-YH!3V}Tjg`6@B| z>i=_J?_$z+LA@?F2zm6HoN6gESSbuXJ1-D2wYy*+&>FbT@S_2acj2x&qO?BRbjcbV zNaG*8^S?y}1t;)&U$60E!?)tOSaz*69}L&X4!>>iUNn|94_@*PIq1-mkp$jicyA4R zWP)>*&|N?1pnwwp_sIw5aR{3+OS}Gek<~GQ5zEMLaoEJjlL$6Dt)8n4a9AS`{(rr) zuG;TeZc?qrHk)qkZn6p~6V-MS$9j5^JUT+`TWio(AiJSJ?D|m z?*ETMMI9J%Q9H#di8igx`Rcu)EsU;h>Z9Lv949ELnR|Kr!Xx~TR>!V~x z4lHOdk)bLwvGynM3-n2E3qT`4HwWU|mHlO4#s{LF4QtgMCb=t;M@8yXp%E`0|kN zT{_ooke}$tP&;VjFm7VT_)yrmE>M8>&TUh!IJ0je(FFELR3yuCdlisTy7tyQ&`9da z+1CBkgy(Ea_d~zdw~QMUs{4-djsO1jbZ|w?k}rbNKe$uf?)2g(R?^gR+0zNcB|TiU z_Tt~eUvA@t4F0JN8h}NcnU?#H?@%6n_ifD#zV1<7*`)a#u5Sq&61*>6!cAn=R3&w; zmH)>a<1yPEn9$Wky6m63;@{76km+pN!jT8AXa4#q@@O!as z{5xWf_ZKW#j0tyNGiBF7zRpLr@lq=5k;FW8j&OGkSpMcU1a@qNm3-JQl_nyTd~8GchQf=a?;PIw09-|8?e<45`Q!kI zq&R;Cjc+7+QUi{ms50|FGNGe)lPu4Ax&UY_B1|%d+38BYVZ>@^YU--EXQcNQNe1Y%@ zGo9%{>&)aY`8(W=wg9G?E_P^<8z1E$HP9a7^q&E>lgQZ({9BH+hrab@d$Ma-rX72n7S@mL_Zm)b6RYd=%S) zszp^jnd~<=R!`?F+yOQ{Qq9Gqf)7$YvB-=! z=Bqc~awt~=o>*$f*&2T9<>wfePTQ5#oO!&FF0OWekWV-#bXp)tj6I%S_kosLNL}jT zSgY7tz*^4lQj-rb|N1~yv6@lh%fh8DMTs)cTnFa01pQ5uKPLwzD+wD1TP_ks{%V%! z$La2=2!RPgr;4v%Kxckwarpt`OUeMAa2~YMp7c`%Q%krEhA^jtDqm}(1C3o^UOnW~ zyw*w@ETM*t)z@NpcT6^08)ou|5bz=$&|8h_Arv-_13{Htq}AVZkz<$RD!Iqo?Xkeaao^&396kj2qk88=~jfB z{lbCxpXN3SkZ}{!DM2Q3Glw2fuDP5U2b8g*41xOjV;&^VDb+wwqx*4^zA5Tsd?3Q#_x=dbrF+Ma@-%gAhYm^r6TRE2zpaJ zyhX}8?T(4(sGhlMRNok@k-B2o?g$z?e>yhxetkrqT=3<>yW$F_{o=LFdS2vFrQ;=G zq&dw|xvKhiaD7nalU=*W{4(A=tMExM?vI1Jy1S$Pjv&ZJb7}M+*LUIfE@xJ7=EHal z7S*$0VPd~9maU{J6m_!JD&gv>mNwT@uGa2LTTxKG)D? z6Hsvs+&n*tk*D;2=>qTf)obGw#wh+T=i{uh`~_>FQCo$XH&zKL_L{-SrpUi}d~Vge zv^MVvHTSgO6G+^()^=lKVOFsf3zJ8O2h`6^x)1kieV$l85wBiPSPTJjt4b2N=ry?jp|2wc>iXD^Ta`{7~N1 zFZdwSt>+>F3jN`Qb1(a!7K}j#&^Vo2{G?i9`}twH&BaDQW}zR_Sb+kaiL{soN)`iEWPOKauZttvi#e;Q7aBD2PKKI za25#KoIE8jcn_Fdc7}hP^sXJl&G>GT*h|MGgW5Qv6)m2xn(Uv~Jhl&yo~$*uuo5DC zIyqCyP<6mED`}!kRkfyWw_@bDB&z>BW{<7Wb}PqiQp~p(HeJ< zoVJI&SKAM>Q?aO}nzube{V(&E6#k5d#+z*%BeK6yrurqX4olFE2hu8_f4z{CuBvC6 z{_l8aQ@c{cFLcEx9u_eB)=66Xh+ll8@hW1;?~a7Z%>HF%g~&vH3v482CJ6{DQuMg> zGln?lo-rvam+0Zzw8|`A>^AH)p8Xn2OlYt_?og3M+VpKTcl?;jIZRH(2XdT|JUI{8<7SOuI1Rt|6<>kdsrJZ!RQ0SZd_Ks9(uCj zk7X_6x2lQheEV49s!-(~tPJ6-n(2C-do2C@{qa(_Wa?nbUX{~tkekM5 z+dak7O)L_b6Zw~!KNlx2aikvkVf$Zcgrs_*qH&H{;9x?_(&G84o6t+N|C*vleS;$T zRBd?k+?bCr4oSK-ON1)mtW@03S|C#i#N*8!?x2d<2wpxlv-plS`L+IH<*0n^+Re`349Xg<*Eku!F{k9*gQqL+`n7F5 zj~6J9!WJHyHhcw{Pb%Zb6f1@P;nmsxHT2Fp9QFvRZBeZ87jDW3LocgBPir4ps#n8C z-KvlBcVod7Kdl+UglAnlxy$arPluWp)P0*Tw^4nL_HAiN3@1_b3Ggg1?jH-- z;fg;sQVUSsa^4vESI~lakG44H;0L@e_L%X~u{pU2G_`6itQg-Ih9ibSB+oyq3aqii z<&Uzl*ea36%KYYJOh!TGL9<1-@%P4Ofz_-W<%rc=z9iO?KHHsir&xe9kYyo3{cnnX z;O5-L#v3LvdKazztjgEFNO>Bhq55z{6BnwEfcH85!(eal)@eO~lB}Rr6A%&*ZqdV( z$lSgq=&%0a0L~!MB>3V#Mwr4L$J1n1kLe(A_nLWBs`ac3SuZ;5pmT2fQ}SmIe~Rm1 zuw$61)i{_9HP3ggGEJg@`3C*{dk^gH1xlIr1Ttk#*Y!UNo9-liTO>k)>}wK$fgz52 z3zl>?Og|idv=-3&d4Rdkamdf{GZIWiG(Wl`VH#+*pcTihKo!QQz9yO4>%3 z3zX%<9fdMVVLH~)ohTRINVD)=DVHIH`9uG!AmA*aT@udGBkro#w+6WiXezJd z;yM0tv9L=KCUA?irVWQjtW_aOcQD+X#$lQRqMXL0BTw;i`LWZ}F2@89vwD}GS7a^x z3~qRJi)YA;X%|R_-Ju3pNIlEGX=(t^!(u5+sYJi%MiYr<_lZBP-T-d~N1#X%2y61AA3mguj8; z2DzcnCZc*CRIvdH=;KHw(X!#zFhYYCejJTDv$t5y5733%NZbXTL1h262_2!amiWNF z>LA#w2M-e;WH1$wMjw-uSl2j_nVu)+TEVw2xr%ue^^vy7I4)6ceDco%Qf$VAl@EHk z_1&iv1C3Nml<6YP#UDw`;abBdHLnI(971iC_=`n1b7R`x%OMrILTMjj0jOI<`<2+Z z&*IjErjuUL%z&q=pt@#-j)Em)tYcpF zx(PJJ{fwOYGx(jQ=dKEp0_yyu0d@edJQE^&y%T&ti=2c8Vd6W)SxRI3xI@mc@C$5Y zf)d)(f!-!ZL`vLKJvjX3Vig%t zwK?PU*y8z|P$mD60Xqpk^^TWR_t%u@|2ga3Ybxx4fa<=tjf-Es-?gValJX(-`yyMu zjzS2f^HQbNr0X>voR`t#GiIaoA5Ksu@e zKvL1pvf6giGg&#O&RbL+CcGjNH<(_ErUJYGN@@Km-_t69orNjFuX%OUoSl+BK&vX5 z1ro+*aI2);31{OO6ZFG2P^0{}+N$bW zXjK^tUFG2;dt0CFp*;%r=`dKOvzA%NnP`xVD`&VVAtRbRtU{imV5gdR1+T{u!Sa*J zmXYKd$T!U}1krsoviHs+)qqw?r3)TqFb1c-8nU1C+mm9mDxCs{gk?hhW>jv77p%K+ zGzZtB1oMI$Yf2A4Ac6g)1UITTY(BFY{uI@k#MV!)nyrbNaeR&Q;3+r-w`sgq3@@O^ zY#~jbagYrkt>(M;YYNL1HG424P1E{}_0&-?dr{8qje*PdK3062l%VIH*A_i!o_rkh zF@+`!Hi~HtOM&e$|I&ZS-=wC3={P{Hz(QWsX$H49UO63N0;M$V9NHGlnV+a)GaZHS z9>LlQq?qNQ-FvpSW7%NXg)E`qjV)_q>1{iXp;fVW zISVV;PST-G5kDkkd7XD0V9pjz36a40KucSWnas|Ue|%X=te^v7gOq=LwcI*{$9-=h zl8au^`j;`1H>bZ`{3JIp*lQT@B7^5y&^-K z`${7MHjM0e*+cYPs@sczEh`5&2zn}2Ow3Ain}YTs!UsEN zXQ7_VDj`3?N3t>6@_)T(%h8vW#LtcXoJ7pugKvJhAe-ne@TQ$LT4Ne+3C)#U3JF#_ z)18v;pL>52l6qk-_b`xs5=rD*8C>#iMa3q4KT69 zl2ZhoZ+MJ*yUJ(|s+_jekVJ>9O+ClK=b)LF_HTr>&OS*3g0?7G*ujIY!gbc+>BR`r zm+tt{*M36?T?tzdsZZT+W2Nw5S)aU}q(v@eP0XmvJvD-|Rf}wnbfw`yQ(vt%7ED8j zyoA&u*E?EAleiuToTXM$ZQ{-nJf^5$+@hc9x1W9MyG0Htw{gYaOcjLsPM!_!4m?sH zx2r^5IFXi ziVDm6YG}c5g=qmwL|4nuBLL#*83ZV*Na|dj#CwYA#djdLuq|QZ#Z`BVR>=#hGvTIf zH&i~-;t6dHr9z-qI+23oz>);h`|d1OhHDRo4NT-33i!szkirgler3o zL3Ri0=^^X6B*mPrlDU*3@2al9wSW^wVghXb@ZQm37M|kYj7T7&SB=)Uio3NZ?=-1L z?HZX&ENfgW2twIXk~H+3iO4+lr`zTI+=*m!!;r1d0PgJOmDZ<@TO*Klj#;aeCul^S zTldyT6XAD=t_{5QoMJdZUyD!+`KxhGBsv1TI3QJ83~1|c(oa~nN%zh{ND-+o+xGM) zN2)f{o%DsVxtAy{qQs4yF)mr-rnFZ|i?T$zeGx+g#t1evP}C8O3kV4o~rxa;dhX~09*D%++Y5^^Cz@{ zZ8?hHb2$Uj%RKxIZs#iSrrO&5V0V@3GHPYhLpv_8f5W z#brxGSVE}V*?!;vvd%j>;w$?tVOfg!)#Vb56dpjI{xlT!c}FU)=C`O^URqtfqKqU) zv#wPD%T#9Xhk$AU#v5g8(9NzS^lmS2ihr|jyvtlMcw6(lQ9X(v=I`e!*{HImqMn_5 zJev3F=Tb%&E+>1lndQ+(Z}~d8l7|y$u~fvLHK4?3_07@oa1c z$JG9`%);rj8&&Eg_n_Ac-g9rA>s|_B@WI+pin>XNIe1~bGr^&R%FP#DtMi}O*cBh4 z&~Nm56=wCAzPWpR-hxn$pKdE?FR{G%CH4`VBlLHe0Hgi_s7~+C&_jpq(Ie%%qk(tZ zB0B;`a#_A<95Z!gJY#cE9LS*5ZSV_GO=X>H0)Iad4izT^s`jTS!eU;gYbUv2RoYuD zp;;zRdjt7Wp>)vYFLNw?WUyPY=M`Z--MPxF(L20^mM_f7ALy(EsMXo8;qMRMin2ZD z{Q<;X&2ESxc}fY1J~2LC_StO5Ahfl`vUqiMo>4P7RVJ(E@;z=LDyuJhZRRpH;-8h+ z0$Fbm^1}rPR`qLWWo4bnuD%!S+Le zZdkx!jEC*R-8GsvO=+gO9c7Vls?b9khAHJM(h77^ymf%9Pc<7hXU90}6ik!0zCx1o ze)T(tQLlc39}gE>vs{Vz+8mS=?Ur)fKiAUmnNx93j8g?xe(m4n{fo36J`phJs7Xbo zY01z|E>|~?#@Jm^9ccIUTHn!GgUUgGOd|d6%v(TPctWH~WgAVrh?cAX98YP5>lf(C zIEKS~j~rcWegI&8%+aa?+SIS=6l&N+>V(~TCr0Ua8!`-Z?(27IbJGE0L|zFpe_?*c z^i)*jC)t=vjMsZazU$7JcqYnwW5f3sE8Z*2l)oX(V9aYEw_$PqAlziF#r9>hHaR;DUeds6{B)JWFW~v&*oS)ni5sSdM%rG zxp_Vh{+tbe#XIP%gTY?br5NYp#eSxxh~sE|O0P#;Lz8}n4oO--KIqVkmf&brY!@{x zfqs+a-V*K$(uf0^+QzqXXWO^jIsQ4g9NkiYRu-y|vX^DdNX-1d`p$;JSp4$0g9jQ5 z{w`|6pHJ-PoY$ZdqRngf`pxz`QMHbuIg%P8!hZ8vk9L-a3f_bt9N3(feytb%uw>mH z%5Kret@Gp$|E1Gbj%JHew%|?mS0=eTdEOhp^X;WVmJ&W2qCz*cGIo2>Q>ch&GgNvq zZOo=llu~3QM3*CR(89?f7eJS9dR_5TJAsFDG+f#8EWH37gFzKw3c>CwS!+4G5>vlf zEdC1>Q-{7n98vy_t7@Ko%36jgWGk`xBMUE2;yv+T!P!E8%#E2|mt@z)dlz{E9gw2f z=IMZ4m7Q5%6!AVW7iDsDc&9MRg6+Dn~Ru7ln(46az@tVfi5kl&Tv@2YsuV&^R1mw@B4O zcm3KCCA!EWrWN*t((CljpJzr}DD*%{9NZ*ezWp6ojLl+!hko<-lmRdz@&ahgafdLF z;tk~64L)xNmR~A6Olb?C%zQpFEA#m7Q%n!?yCX7doLEtx>P31_;T_`ie^cUT$I7tQ z6ghbc>hA4ua1qV6v!Kts;oWGa`23>A81SQT&XFr(T)_p8o?G8b)}*;7llYa(F*v$g ziJ?y|&D1_;Y`MMfyUf)pX{y%+P|b15F$9MC8pl<<>Us9)*f8*2Smv$6SB4SKBma!j z{^GDPCY$B0kR7{quD_=ZX2Jx{i`59CrA>QZ1GoZ4u7|gJ&!gY)c|KFCoDPq-jZA4~ zDO}A>uFsc&uo-}PA8Lt^d!BcXNLF9{CT%F{w=S_1J8oH!)a$ej_o>Jqt+I$P$y?(R zqDx?RsQ# z^;P|@S?pbk_|#20;_z*>~D$v?&pBg~C_y zeDfM_rOi}%^5mX5qjAl4(ykkpB>L&E6yZi|!KM~M?!*v+&(c6$dbY=StEGq#bB+=} z-q9Hv*p%CN7_s~V?DfH$ndx7vi~1<`$WXJj(;WHUqjl+w)aJKQuvPP6-jF?4Il;C- zy&z4Xcx?<1)tTv#d>pkPa}l=;;0HxiZsd*K4h9o{HDbQtc5 z%zpDk{trP4V4%XpBfvv&um0*X$q}Dj2y7)iW@jC-qPL+0vPUi| zdgZ9>BRMSHIi`Ke-|&!240clOgvY7r_wD%gHDXI~Pk>jUe(%Ok+M-=MVswW;;d|rU zPYfAcw~ZlMWME6ex35XO(G`}M7Or=BA#v)b2C})9H?V$EglyB-HWN+j^Ax4KXw<3x zz6<|4$m|b8ZC`&X>@SZOy9vQpF60kLyK#6$X_L3$UjBOnKa3{!+~b|M=NdzsjtNE! z_Mn7gX;gPr%&j)%Qt>jqBG1hppb}CQiO_dhlMo(?(0!G#H86WRqv?MBu9ikU|Ab@- zfP?jHAFZrYzfT_Wt`YOO z34!J410*;pIj69v1u#fob1=s=@G?jL7>X};^BIC3TK{ivhm3&<51`L&@=OYB!Rz8s zl|c5^kaxOP$L_k-?=pyMc$RH8(EZ_tMuL*KTb#D_O=uZUTU_*~kMD1geq3(f94^h@ zD)o}cDXM-;-$)AIwUc*{BxXvFg1q)xi0h!O_^%Q+1AS!smA?FYVo?P}hg`_V15SVM z#l;T<-cMbM9P2!qd)wer{ygw*nPair`pH#*fx&{z-QrF>BlUAIQ2A!L2`yh-E6tbN z-);ZiE1DF&a+Yy7?sMT#MeMW?)3sq8>LadPhL=O`>u;KVW$3Xv-0q4Qt?76j8Mv#? zU>`~?9`_;K>y9eiJ3o#|nel{IHU0)?9ZzBWQmG4_Y25wN-4Paiu>@mrn8cmO!*Rn( zVXmcvaWSA1^2oBnbk2}_(vYz^!!~` zPcq|k5vzEZzjShQ#X2l=>@}cz>WPiG*F(IX3b+@I3jQNPWjFg-5;Gl7m4g$I85J#+k4eOjsFni3v79{c-CJ>5Lr^Q#h}bGXv_ zf`-|-G~n7?)V4Jyp; zk!H~Rd85`J?g1<8%lC%iFZyb`Ue z$6+ouFmdltnVAkJC7g z|9flI7pZeWi|$Ch0s!RVwfd3Cs$FD%(&yW5m$)K46fZF?)u*`d>=HvcJpijWGIZ1b zyd(C@r|Gan@%&BMT|GE?==%zU{u`>kXd-U?0#HESFhQz_|5yX!eac6ye7oLkPY0o- z=8Sk6V=oWZk)|p`;wr32-*?zU_SPLXp2Z-k;W9+ANd1cG~p{h<^yZO@)~nKl8<7>FUYHweI|T& zR7FirumrT27x#aewXxpGY-T z26rcEfyuQ+GqDGR9!x3+3iE;#gFiKASajuBk*!y|lGmBHzj1@9j%vsnZQ{#bm^nH+;E^VsC1T9;9+g~M zm&_|MOf+7Y`D;?R$*n8*Jt5{H=9eXd>C-er$0$Jmk;T4)fD$Y|Wob14aIGsbl>Lp& z-7vPk=YrZLVKgf9$6<2rVv&S2obQgsr`kV$(XS*r2DJGeOAffw79A+>s`JgN9J|fs zP`RnUAdCggqq}sVr8v0hp6d}4HR=1j7{N(K1oy{=MtON?(k=?Qdk?pu5Q*sF^Llmi zhg}8O#lv^=#%G~3^}rRaJdDiq91;rd)<IB*oj3HOiwQXHKPJ- zq~PFTt}rdCipq_Z&b+NPmDxQZaupm%h79_;k6XY6Qk+J+%C=Fm=b| zDEG1iW}1Ya6kp%;>218_k@tGlh4CLpTo}MtZCVX!!pgKB<2G`qZWKE{a4b00mCrY1 zdh|h&5A$nry$y7ZM@3_I=-|JifO_-^J`VT-a6tjz=AhR0!f?&X+k}B&YHKdVSjYOA2f4-{ssYXo*$w{U^YwH?av0;)sKJ1j9>=x zFiX&meBV!aFFn~m_S9Yiu)tR`ULgwjd8|?dyvV}602A!8b-iHm1qfkwArLG}mh}op zc9fpvf6WsGR)xUJn_14#Rc5G%{s4y6vnfTdsDmgAT*KxQK4J0n{H3|YD=@Ta0;_yH z=ba?3s*NvJ!x&7PP!33KAgqIXI)zqw7*aF()Qex${ZlruP~%*0AqN>r>HX@Q77dnO z5}$qHm3#MfY`HQ~62Sudz*Kvz(a55rrO>>IKXePB-~hL3;|BbewA%-EEJdR}gO0Q$ zuDd+=r@CB;X=!|H)kh)88WY=s*1`|9Vd5nRg4iYak@^xRp-x2^Uo6}DA4azBra3=a z!t5hvFQty#(hBoaEF&&Kn%q90 zI&5uV1(1>^#2sS?=`|kwH~b#g`N#j^G_#|i2Yzy#bzv+(Rt5#knRf2w>$$#g!UsaTa^*R$-gcePQ9+fo|}3W zW}+|Ts2vh7#Ri2ZK1?vuhUSmA#$|TvWDaoWdgUH(5X3l9xUz)K-Tw(wS&BCxc_+rB z>ozGO>6xiCDL*-*M)X|{1i|0e-n zYpUe8zE7g19$L3G*gfPa2l568Sb-N_?e)E3**-*Us@4!;t4GsvP?ir~88YLgG&2Gj z53gyzzqr|3xNaE63t|AZzU%I`jZG;{*q|_sepAs4H8;&NU;Odcf4FviD?XHk1+zx) z$MQZijbTGB^vKeM)YI>n3*w6t=wIfMs1?c5QKTuXU-@`t#exGRKECz4e{CT2r&YX{$*+=A`D!Z zXK*x{Y-GjlbGvXF;Leo92)Sqf+Z4unbF(R?YsrEWHSCi35RKEt0!^J1JHQ5a9+Tu@ zmk%BXfg_5I5ZV*sRm`%uXPPpq-7d=i_wdlTuc=0@b%7Jn1(m>4O!?ci8{=z%*o#c^ z9f$WBsWP4%CZ?hNeXa3zMq!zfj(3iv5q-8sWT6~|mlM(gTQ!kmwY`gAHP9D5wH^%L zNlX&zgLo9q9PzXTuvtc(l`w-|RX+Y1`B`RO(a!1RE2th*ErT@IYGUDHq}X3fv^`?b zw=YBqzqY6xuZ(>cvZRhIjuk>|8ADs|b@^7GFvIf3@r%yD2o;qKxBWIF)|nCyZ-f0Y zo)b8_gI0VCVDqcbtv=H^Iby>LA&#ip42r=tP$*Y{k`VisgtFcz+}EPbPR(cX@8ONY zcpo!JMa$?&Ys5q34f3K{^lEyJgX7%us3GV>Ky}aTZtXXdg%aXt^L>IB#(Xw8d)ygq1d9s+wvM=B0I@T$(G9>UqEJGgHWSUa=4{IMW|mA|tgF!{7_3Qm%!y3vo@iTdsK| zy5i*u6<}{Um!{2F{rU%G!(A)?7)k|_?{~eASEKyqZ-majx%>ZP-`yLmzHETq_&K6; z88rHtuZK(ZeXRx>uRJj2{Wa-OT|NVvSn@eb4aE&&y?!^ z!*0#mU!8^e4~`Xk6!P??(SMD&}BO)b9@| zp^c;=;5i?`ZgmvS5PQ;YT62G#dA+#1d2?>)0Ebsmo`gpqo3 zy~Fsh@AWtg!=`SnHQawxX9fzP3>f%cq%ReWQ}p@#!6nu`(fP_x0plr^g6dh90~*(9 zXx5!0y`XB zg_Fus#=-8$pyc{c1fuVsen$yp;hR*|wk?F|wsS09tI8F=$>#X|9&w5#$hZyD&|wDo z2ziNR{|bK8w`xSG2ZUe>-#c@e28`e@=wTlPj;P-|$_<>Gr*GYXEy}H{SS9mL(BoKT z;rbL`3E4`@XhI5LazBSo$mgLRYG*Hxv*~2GVQav5D=PYlALc8SP1og!aLPYpmhDWD z2^$nYDYfm}3BMk0%eyN{5@pctK`Vts`@tOzc`koH$q#s;w^zzlUN^a1TzzH<7lsxy z|2j$8Y<{H8-=O~0Be1F<-d@v(MpmP+QUfNFWKt7;x}MY zz@ivDj*I_6dg@5x@+!6jd=ea-69V)V4va2GyR^hEe%q#RfJ{l=vs=kOwuJaR%|Wvy zsP!QeY_P_DI9#FtO1Mg2q56LtKVVAVfScA#&))s_>ghCeX>*w9aXyRda6>A3;mt6j z!8HIVr|9zSIb|L~jvGHbCJW^=cKnZY7~8J>Z$oCqGNCLy)5B3ZKPC9Kzc1m^jqwbU z{M53Nydbv}QO2X-b7@)K645J)v}Sm(%;@lKlSrbOI~tWQjJ z(PM{#zNdB5J}LMj;l7#WUgykte~sAY<^SgD!vZ#R(33`#c9<@Y!{LuV+6)6(PtCO7 zDl>uE#x%kl!vcoO4YsI-U1fFPT>J+a4$_D8m+##_1u5g4f>xxT+W6Wn&7u0*7`)Pcr z1MbGt=Q4Ir2YWuQ{l?xE_|(Y{ms^)(%R-I9NnrB2>8ShOpoan|)I(S1{tC=`XN`_4R_&@Bu z^gV}&R&_8y`?VYDN7ev7zCyB)Z%FZ5ps zC@c|~x6|mM|Asx}#ki3B@M+IL$NQpU6LRFt%J(tG8Rud%qrupzD@30kc&hj(75<9! z=k(wYI(F}|5`+$9*uQ0I`?e!Og+v&VKg<14zYOutX11LT#CG@NU>^y`tz$C6SrVCdP8UTzXcR4i5J#>b2PJn{JJywUSjE-ZDS&ib$*aS)#n( z&rc|qpTC?0R~RCfJu_hqqWeJZ|3j>9n42w|WSPsHC)kYFlpJ~7GO~6=pS(P0J8Ej$ z?Z%i&j|n+!U8?I?tS_Up4iB((4CBdT$Y_}sJ(LKl5*xXR z@3Z)T0bgeByPo0lmdY6wmrL||?1Lr8y(>QXvC{l?uVTtX)c_T#H|-$37JmIuD^~dU zgG)7Aa&%gfEF+1qOS9+5%N#hznP?>G$l5T)@CVB2V|wJ0a4d<7)7!J+hhCEt3PrZt zerB7k(+6#?rqai6j#LAmb}p6#ICY&LNoSNse@I#Kh`RGQBHWyP`P)eUUQ@cXmg4DC zYu+@cy3%XeOQ!5!C_T3uRx*u4NCt)vjJ4RZKX^8`J2B)aM;v*Xs@d;8-ZTVHw|0D0 z!#TAqz_}ABMoGRpRUSVr_{OHsO8O0PNql#g`jLzwIPf%Lqqt=^F+4lpskx%vt%oXc zqfeioJ%d$a8$1Ymd^d8G!r5$`R&a{Ur;lrIAp2$7F(){n$G5;^PUW0k_y_Lva!x

    pNOwCuNn*iZ6b zW&4~YPJ=%k{mVsPY$|NnlW30lu(zSW@~gniBYQfomCu2uqJu}HKcWSx!iX-ZS=Gd3 z_&SC$N?(lc*bFDLrN??&pRCU&xcbx!e;1>1A#Q!o8!d54k!s?5Dt5t%4kpql zHGy|La^-t*OUsgsMRG%|91-2(Ckk;!zO2&o%`tzNcL_L8i`pq26V!<7v5U~^FSCDf znd-7OnY$AjWDx`Lr-=P>ps=TFKk0+2ZXH&!jkEnsuljki9E79ArAs%)Qla~`aqY7* zi8Fh-XVc!Ul(&{~+RViCXCJWO*6$5a+q zRLY#5K;|5$`wOEvBUVJe=6)CVjC(RAD-itCds|*SG3UG8 zlUFg4>6@J9@`=B0h;{oqlaUv0QayelQk$u9ywDmGHXTFtwyIRCQ0A28${RYnYp3Jr z^i1CVhc5P}5=;HU`{`FlAMk(ICmPSYcG=oV;jV6jD$TD@xp%^~AAi<50v>?k^vP}U z(>K?=%Vxp|_3zgY8n6Ahk&Z7b*veuh{JM)~)J?;9pJqwm=lln@8(Bq%H@9Y2t0Rdb zh)-p|yl7YTQdW?ZNJ^iEuj|sP2A0y06(5gOKD!d(^ut9R)m8NHP}t)`#wxxk%l6Q8 z%TjRUFT8V&M-e5nUZwZ^L#9eD5rfeCOzvdRPwl25AU%;+$TdEttfHMGf+q($8hHA8 zgSm_vT~L>XmuO!8SsV#(QbLVY!VM|il9`Vmbw>$V#UejRQ)AI z{3$`{pZmc%#W^R(mo|DRhKGmQTz+^KM%JGxQ)bf(Drl1kCru`a|MD>lTK4w{(VBj; z^*&%XQf7bUyt&AX#;$V6b9hd0IS?My_KmoYz0AvL>>CAtnEZXGtBr}xwB3!a`HA;T z@D0Y9aE943$|)S|DZ$gGJZ8sfJ5jtDjXt@|-L{--2!kN1B?Hy1k@R~Ti+A3rJ<#yD z{a(Xz?XtUjMrw0lzj0W}dqET_nxM#-Y+bo?se{>T~pJW*at_(9t_>vz)c=J zb#u7P**Tzg2 zu)P`$m{{nr3#xo*datA*q(9}j^N5NSU%h+<2@xwCe8bpJT=Q*R%0kb+DvVvxF25oI z8foCXKivLkylwTE>e4Squ)7?zr4-6&)5M>Z-uo#vQFFXDrZn{;=)fR=p1*T!-J@}& zQXy!$!}Dk=zj5y*)$d*{tyac!nPf-3o%7Y{`dyz_NZtCUGd1E{u2&CC_=g)N?H40z zWqrFnrm;}tVz26yq}m0y-QM2lSw~ADkIV=w!(?gkQ^%2` z`b}?bYHuBpS9EFVRT121sTOCtoOCL6L&c1x>doAIj~Nm1Mcd6>N|*U%@s(LBb#uA8 z9Wi4O{L^#+X&39kn)5rx%a^>hc*Q@5hwQ7??n61CxMBHbqEVN8Z_h^~Q3ukd>B4dFOC zca;WJiCkxnQI=-eG;rP=uN!st(@Ic*7YriA-qZL;6oG7Jp61-Kq`b@CNU4duJD+o}+4i%Q`m^(b8?z-quA^udl`Oqu$6*5`|3`@PdMUGM5dK6k} z)x|m{_Z0S5WY5luB5dPN4T3O1J-=ov)mLPyMC;M_MMn6Y8|JI%!GQw9kJeL7!+O$X zI)1t)vPIH2X zPSC1A32H<&qyJ6t^_;Zfde8mym5*@8vl8m5ezpv=`M1PXv)^0&z}cij(i8bKqph)N zEsAxap-66pO-|;M=pOFT4Ce)@;q7r-X>cUOg;Qx9QiLon6U2`|4*IYEelNtm581qR zG)DKI*Z%PfYmIlf=>1y|-~agSKkxWd7l#$$8t=6p@!z|U#Vuoh;P2*no#206XDa6M zBSTi-uX9oSx8eQ$i*a%eSWPVv?*F<@Iub8Sh%#g~u4eu(v;2LVb;3C4lo1}z|GG}F zb|1{NFs5koe+p|K2+Otz=i>hmrYx=tE10Qn+wjK!6qY9tR=KXyOL%w-fuv<@`U7|BqVyQH#IB zi$7}dx5Mx!K>fe);*VPVQHwux)*m|SUlHLC%lUt}_=n~EKQHPJ`Th4k`J)zp)Z)K5 z*MHRFk6QeHTP+UHi(LzQ60{d)ZE!&WR3LR=<#&Upm*wOxXI_?*=ksmOGELUYjZ=>2 zZ_7!#UzfeDJFk+b8Gm0VPgOqF?O^G81GOB)_9AK1mCo;-1cKk~bfCn)BCVniewOys zIc-jQW^5Q~=q<~h93s?Okne?m`{CcW^D`jiKsc_uk8}U8KFl>hAEyw=e{}xWJ)*cS;@KBU*;cdu z>)`&n4)t3DeUvib;QZ$V{`nmT)_2hEZ%ePr|9ygg-6Kj0^s#?W_QHP=!td|M7UEJM zEB9;G6aLpYzp#To-~ukPyWw7_CX(`Bo{CKHLCxZZzb6S$kNzO znf`xUtlxd4gFa3ep%?z=g6V<Lc@IOlNM=Aaz+WMmuf0W{nQvBg5{{Ki` zkrQARMe37_k!Xft!@8RNudC|SMn~1|(t6#5?5R;Vf?FCEy#JLj+zs^wuSH(z$twtk zN4DgxR;J<}E6Bno%IUvJk$r+aeGo=mD88~&wW(Mc`ownNKu+p1LlF1*+u@q*r!Fyn zM<-b7?HCY_Bj?ie){NfWo$eW@GDm6){`D zpVL*LmerAl$niE3IJ*S~9R2oWMPo>6Ax=xvXFIjB8(HBt`-UxfOW-`&Q9mHdE5 z%~36muz$%goo<=0Xmhkyec?>&SW<7ghD27FU__OlQusBj6L*xPnM~LbUoYw>KUaF{ zE9;(dogqFlI%m?V#HcehM@?USpiPm`Db3fvVpZzdDW&=a^ucbw24($W6K@PhHcn2u z$BPn=y%p20w|7+V#R9H}k{34|%&mK?S(PTEcU{)(0iKauhRyn(L z(pm?8ioB%Zve8K^v?XeN%ZDLD>+-4cv_J`uxBJ-hoN#V-ZpnF)1k~4{YL3RkQcWjKaaV9&4^W#Q!}*{MW;F$ zmAvoz)p7d$$6*X?`x;?1`;R4EeeQ&$ZwkUq*X-z9^ky+B?h|6uq7M9vZegJ-m(9bN z7p=q~Kt+Cbl$AWhQH-GF+^9R*K%Jdz^3uD{N3+;;gRV`Ny3?APD2)w18`qyz1f;^K z#XbuxSd3h3z9_ocLVN|LZIPqH6S{dH%j!a+u~E(XD_gF@`m%%MCU@3A9fKx!v_*3g)CaqSj1QZ0F*Y z$y1%O62ld9R7DV2uCy3f++AZbC#CrsUqxE^I?Axz#?a%lruva=tc#|Noa{ql)3Wy0 zaT0D@Gkq7iqOYd1^z)?azS8xg#IHZuUss7LJ z|Il0ffy1tWnHE=mN_CM(p`J9H8* zS)r2~AGYZk=AQKM)3oRt#F-M8{3ziS)EYEv|61(xg%L8ImT`_*dcOA4uIx@&N`ZcP zwzp2aW2&|9=+8LXfjo||eCi7LFcUn{oTxk6oQ=IEN zX}zjG6@^5+A3>Mwm@VDexbR}@JMAbk{uojc=O>DAH+UQX;Y^8byB9?KF;XuP!E8CE z|E-G=L2CMy5*9`q(JDfpuS$E{?hbV?t$&gOq@>kwOwWReC^>+*{eAeBLUAV(BAAc; zIw86LVa-mrN+c2LmQ>8N0D&pb+pYTcirK8-lCZToQ~AO30!-_uX;~YIW8XSLlPvV4Wg;%L#L$-WyHto?H(l_*!o!i2 zws`O9)(BjBT3}k!th!M+==278i#P_yalGsmd5`U)zJ!Xc#KrC-datbp|0`G5N~t6; zFZ|5XMKub?E}vzLxcoz=I)qgQ8CaQ4RF}Qt!M%*f|FDkI(CJ}`=fMUlFTe2qb2ikx z*IOcJkl5DZh14`g($546S)4x*bW9Ro^2qzhgYUa5S-E5qXj`^hScyJIouFoRzx!QM z&i+EY$y_u7WB!8wfmU%amQKR?E`rfT>{*sKBO+HnE+akcFhDPxR!(pMI=~s=!st4y zV{y0J{wGZAE4jihql3*`0@JZK&}`o1Pb9shl1$dW?y(cb5!x{Zl}K_Rjz(F}%>vH# z7o5G*MJ}o*j7$}KTb*3@PXcn(?o5d)U|{(!P1zeXLqmb2?Wu^o$+EZ#{a$jTB{nSW z3shm7U!p5WmNuX#XSXS?T{kL&8KJ7OY(*jcZlU;$+7-+d2g9&Rb>C{&c*nR11mk%rc?UiS(t+Xz7kq(l>vh zs$XW!nG{5b(zDzm%{}||A(9QIT6-7L-~8;Q*XB&s!tmC6S{BiTI6Qs_S4{@F$Hj~9 z?!jo~ybOdc;-NEx50*{>2~ByFnh0arB~F)Dv!7%_Z9>f93mgdD!k#%%uZ0(U<036C zRu3RM`EMXdorqJb{5LOM<1fIpQuCYS)p*R+nGw%rmfov|iQw7aon;`r4g3t=_glfZ zd8D!s9~60p5+@scD}W&@P4zLv*rAPeSvKeX?n?0`Mss%EA!b{?-p{S-^PIgU&UpO2 zp9xG^IPmuexaRr%EAk`}m$c^jBz`3+HTgo>obL{DC^8{Pt4T)Gn0i>U21?Rj<3=s}3?DOQ&V&hYVFdrhqz^zoIER7%Zmr2Tn`@22yKPt?Dc9(Bjy>hp9r9hT~Be73S z{F5$x6z624K)OfJ=^I7@&xM{hF+uj>4dg^t#527@xMD~!1Sxl-E=UTKRE3c1(132+ z=_rr}7U2Y@ePY_-(1=ZzzOqPCBmqi^ANGU<&wjTeG8Fm_YJ|H0hX?srWSolkJbLr# zA*3hPL8jvoYp* zPo)~S7Nk5^q)LYp&%XRP|Jt`}4?jR{?%6u!6BD6q_HQr1G|OBd{|_|=>JE&|KFSF2$VzT8~?s)hll!f)!?82c!u(U*YfgLVE!zzR=>9 z5rAj27!>vKYP3(y5oI}6l|?dtIMM%yRA%|D4nRa;VGIW`izxH7wHX z5_AP+VE!~yhDs#BtOcGo?domSd^npLjc$|<-FK*K=|mGd4hHXusf(Yil_v6h+Ic%? zW64f9uL=q|95=`Ja|tkqEiy(S(7L5`&zON=0+c(UY32*k9J#AN*;F@jJ6{dO~anpOG73w!t(S~qm<%rcGacWQ1qo7IlAm3~;ljVC8|=|u3U z3%Hrz{5(A48P^E2Y}HH1AtoSO9BCsdGtmmbglU4$_3-DAHz7W~94EkdF$j~u)d)4Z%1uzK@?--U{uc9l=V zF*QtY>g#i@7-TBVj(9}n_^`)I7QZGe=0|*+9=L?FmWqI$4dh7ctW8#zA2yJ{i&+r7 z)oWjvG*wg29dP-#o!ei6T+iC3`y_6*g(+A2*c4lq_08 z5aAr}D@=`fc!wBtcrug4vKz?T^=$RTO4N1fbEK5sG!#D{+YXFh@H}OnsaQ77;K`Ja zNRfZAG3_d913)?SS??$NMpw_UQUv|44OdZ@s&Us>pN=Zf_fA)Ad_*awH*0n@U(j}c zb1wieqM;uY&jyfjnSSd;;-0V2<%ypQz+>dGsanoP6;^NDst|+pFLtGbs_;~@5TZhP z>qHHs!!YGu^b&XIJ9_3yw@+GiZS<}`EFsnDh*wK*A-2;LLyMUvway~;ITS|{K1i7! zIT!}k>ehLvoZ`D?Hx30K=+$k=d4A{$=;6%2o$1~sU@xEC;%2K&T|+`s(J#z4G$(s8 zx!Z9}&nk1XwSaa(o?%CYnQSYP#zx$`5ujImK23#tbP%q3>R~G-k3yfc(U&u(|;IYrrb!b>ESV`XrKarM+m8HbO?#Rm_cXHi;Gk6(J`Eh?Kv41DCArUlK(C*RL zPJ27wKwWZ)p9R0Cqv)}W`XhfvOg zw8T&U{58s7d){H`b;|m+@w)g_hmDl@dFhR6YOYRe$BKt^Anb-0AiFXpVf2c&M^<9t z_7RCm)DoTc*5BZ#$NrTCTI${d+6+QnVWHFD7gQ3e)-Ojk?7}*~_MPNw2S=PfugVx3 z^XfjRsAMz?5*B;}P}uPv`e_q$iz2OYDIC{?pMLWEn=`Inkvw)wg?ydvcgG=^E%I96 zQYI#sQoTu_UOWG4&4)d z0QHFAYEPZlq;%O=@@%L6W>c9y5b(>6_(?9!s=ZD!eBRv<7FI0wJ3i!dp5^J1>}#G; z_e^EEaIu+hF3^~SFZ+lg{K^#q8e(&xHenaUW=E&w0~k4BN__%Tu&b>P(ASjWImz5*PhwL(@x_%v21TNqSHb9Gp+ZFa*PFxng z*bFsGKIcB;J!D`N!0BxXCdV%UoR5O9w&KCG&$(vah32aVohs{&KEbo*79tvh^J!4A4~F-Bt??xDL`>l zE8ZzbT_ZP*pz+=uDKT62G9L}8WAsZTwCgUnovw?Uir#rrCSfqZav^Arjt8Of7KM4c z^MI|)*#4};tTVP9?MS$r41Cv~+Lz-uS$(%oP?Yt06E5SgngE*=OB`W_-=r)`iX1lb zeC5ZXaC@7cTp}Z>qexL|3CW$sDZ$5tKf26_a5E1QwVvGe^fFeBlhXQ-*aVEdW zag;|Wj{I)9Ebe7t)3x45OtiUH@%iOml%{FVlr3@j@x#B`K7eTCCHlLOG0JQb0WVwE zBhPzJ8&Y1RF=oV!XFu-wsdf)|%;mOYMuNYalh|gp&u2p)0uF@!P$ELm5^fsCG9O*@ zNzPY*`Pyj1muPd#$L0bLKO!0tSLM%0gWG!MkDg0x6Gw}wLd&kgUgigUpUp{{K0iAM zO|h-3tT@@I)|yhhb#)0?#jJ{zy!<|9nN3zEVYeMUc(?e%@WRrr*j-Bd`waa#^Kn;| z4K`ZziVWy`I$}XYW_IX!d;@)r3n|h`IxVNr(nS(jB!)56QoXu_s{Q~>h+-)^77Z3_ z?&xsY0fcG`s$Mxa!9?$<^L$GM;e;6ZbgsHA%pfgZ<^Izf;0up`b(t6n!`Ebk)meME zBj*o8sNE4tvh)s7&D-;a@;76|p~x*f-X$F7%)KuiJY0nps1TMaNCINMiu8lyGs~RN zEMw`@WsMvIWUFb+Vk6)*CY$u9wi8f&D!km?K4Os!y~X{iS%y#%%F|9|TK^b$xIw)E z!6(55HU#xjab8Nm;rk%^`;-WX>!wJzorXJdG#4u}0sQDV*BU*H8Iogp3)th>1eg^vAv6>hLnsxBaYH64U z4~-ewuQkWBpZ0WvuWLbiB3}`+av>alS&WZd1_Bq}y_-v%bz_D&&G_&KWk{sgJhL(d zlcO>#B=UCms)NVHO#0+|R4vR8o8%yqc8%AXJf}~lC?0mI4LmA%;yiKu@z$Xej-NcC z>1$GaEieW;GXJDcFLC*c#&01i^%~`A&KOn|{36+A*u5D6Xsc-O)X@>4nglnGMQ$Og zrvkWieelrjC7{XmyQzN;L1uX(9k=qI^%DFK`_FcO+4uu6qT5KjhaS6`0bioL`MhSK=ya7q+N)7}YVO$#DlQE|9% z1ki6eOxOK(Ul^SGm(d} zhJy^ob7ENMMH)^*gtWrbDc5Q5rbzhihmVqFh^KOBhI2Fnr4O3Y=b?d9uRP}-?xxrv zGayP7iBb7QbsmefSkfaDCpv)2Uc3ORfQ+erThiEcx!v6I>R>We#>v5^1|@?YiF?xs zi$GcXp#IS8Vu(Q}6$LVE-LYGYJ=`%NW&3A~9Y# zge??zlfsSVh#j@6l*k*Ji61rx#ySU6)t;Z7#In?_7FLIBdT)9zTUsfh%Io$Dn)Zf` zjSU>T?lg^0pSgVK%l>t4@1K-1P&<3gmZLjkmd%;S6c0_&*ry{7fMfzqY|ya6h0uk- z73-hCCVC@Y!oFQca{qcA@d)<2sf=wd6Xf?|9|=fs=Kms6XfqhTc3WftP?${`KF9qi z!HgqSG+^$9g3Y$qAzCPl`!C>dnAujJ;~ZS+1#(9CgbX>1#RM?bm9EE_4xx1iI>N8v!05k{>a+7k(4Xb_ z9OuNPBzYBOWkYk;jY0pEKIaEM88%mkwsiOFL~+qpGAE;^J?TI9shh%RgN5Ia`X0J=~gYT)u2I4_+@43_c?8L@?vyA#WDqXRx-kg0~n&(&rqXoq-!&|EX0v? zGnhS{LrLu}MSw^yO;4wWF@P!;mI3fMMxjdQLI8MJLFrI05lDlFKam%VI`R3T0nQFU z_;iNx>)h1tirprfs+f*?j0(Cm5vRbH;t+i%ITt2KR_fTje5STSfz(m(>xctF=@9ZV3Ie?nb0@y> z^&he4;|9?3b>2V&wnmi%K5@I@QOM=D0>n1>*!hJr@k|BdXbbR#DPWz1EJbsR=01D6 zK027m=~KfJ%dWTT-}0};FD&|GB|-fUffRlEf^U!_iBK*Crp-bkZ^nyF?pY{DX0hG6 zS<><5dS5Ywx=Rg%KpB9nZ^8Q3QZ-{Gu5cuC{6?;s7A)ICVx znH`vNyx=V|XWWy; z5#h7$OKFLHj9xRB7&xSN-;=n5-cnaVMYuW8tOxW4eo?^PWdMtZ`CU@kUcjnCt2Ms?{J9)eW#ob1wP?IjQ_kc znHS(+p?^A*Rj(hW6TE()}ZaH+yeg!ZYdL~ zQ7tlO_V$~#2iYl~NEbqoa?tvtE?b_dv;A_)VPhX}`?+wD8}rOAd5W?y3^=Jj{0h0; zm@p?I7$cwcC^>>oB0*CJ+7Mk+V^a!M*dkB+3^?&>ckU0+?)>@`Yi?j@Z>raf@;KUu zUD3>1pY^AB$gfVuL5?tMR-|`lX}cN0oLn*D-78P|k@nZZf;W#J;EjpNq=#7f)FGwo zCITLUCR;rafP;(=yi{-;!PWFj1MU>c=6u^+#4B?-q_hJ&()iW{ftT=!DX^KtT#~w- zw9PCUdNj3&sgbx7jBJk6$Jrli@m23)62=9O5q;pq{QpejVwEGd^cJr>6;< zm;)d5Q-BXrU?s7*B@UtiFur@>8-m{*bqEK*U<)t4WTjjPG-{n@INJ(pGIX7c&t%Od z$xNd5>kK4s+XBS_IdM30WaMIJGb{4yWNzPUB9~I=?dDzM>(GQo7?efC|(bHgHsHmk6U})8Oevwwj2*VMS-m{)gwM_2;^4 zqop|rTBL-_nv#23H4{SF-Iw+eq`vQ5=|!I<6r><$WbeTY&V3s1WP|75($ft$Ufx1D zGF;pnFM<~Kblx%g4fy|%sMv4-$m?}pa|ht`3F?ASdWTIiT{h`1{luQ(CGe4O=CTtu z5z(iyeI#vu!!+rVa34M($tq^dNqgnbv>Zt4H=K*O;3wri)!29{n7t(cSBd?}>0M{-A% ztV!k!9jSFcgaI>y|C>YD z%OE^fMfvF?@P)^OWlr8q!O_Uy(Gb=h#EXFht42)F*w*j|W8G_URwt2=3M2NjH7gkv zF~kx#f>eQ4HJSvx6ht4-eggWggOg1u4K{X#ry?n!V(R?0N)NCMk`j#uDj@ARw$op( z50jLto*14_42$lIaC(+{4`O}y#T~fR5{utMtN>dN;n%@XK%}97Qwk*9(_I|T3Q<-i zM)7(tt2D6#<-^HsQ)Xd`Oc|^_Ki%X#TkARdtXJ*w>OSl}OW{;F5o*p6r2Qr+VXE`I z&-HjSP5p@wS~@8F%2V{>cR5+_ugmO3ZzhT~s}Y-M>c)R1=u*3^C#lteALooo3? z!Srk)Bg!}*z@C(L`t_iSTBL&$q1d~93d2dAoAfz9#hVMFNCDa9yLAb&f?!>`?5tmL zD$S1D*4I`XEvAGP!T0i&MIE3AiaxuFP53g04Ol=`$9Gy}Dx7-L2+pcrAMd|*L3y@U zju@zA)qT25XyNO&H{!BT@al98>Bqo93wX-9Ulx$`}nQ8!G{K!WH)Hb1ye| zvx`NdVScYZ^GEZ9hY^hg~x(QdOW_mKjb_AC3*BVfWoQx)4>zQr|W50)UpbtY>? z=5Qw9AAy!u#an zKN+7knsA#7$BXO))^0^Cc=0WM53kqkm8NtlPa+41V{PX@Eg6#b zHWxzV`lb@QkgxDHR4i!;;hA_pxL_6?$9}4-GuG zC!h7pZJtXnXT`o4C{q%teIee2o2wGl2<(C3dnkQ(ldB>*pTC0z4&TobxC!l${IfoaR2@HtBK zd5n#iL_t=wFR;XdGhmGy=mM^blS9Pu_C$ZxYK-R748EBD$41GE1J&qY{8nD2RG|Ci38HeohfBVxs<3 z84X1e*OA0m357spKOxzld|z%J-4EPunObbr7h}_}gu-X=;#2;e{Ne;9bYh?GiEHiu z#!4(z5%a7jUEyxez)#|$&Tc|Ypm>pFjL=#y^Q? zMqEc4F5g)l#ae-cy)od2>tfRvoa}tPwX4HL8h0s`mF78gpClh~;%X*dW7z?z;iN@M zBR59nCIF!#AL9-ITt1$#Z=qY3N??CNg;vEy2Z4B#f-aY~P=w$vR>UjB#0kp$08!F- zo@u{t)9|GCTr064MYb9;`2;5v3S1*c%3%r(tII@}QXTuu;vK@Eg?HO57L|c>piyn;WJSd@7y9+Sq=C~f#{ecm!X45n9LVve8QFDt(; zGUaB5b@T6ZVI%=0ex_-zdk=+keB?4&4$2 zdMM8iBhU4KPb0+l#TxLgoGsnJ<<-o)xShvTd>2yM;B^dMN!8W5zd4;Tztu=0V}Q*< z6H01oM`d1E-mk7dsct%%I;hiT>qUAkYDWTxy~cTU$P_Sg1#0}TuRKf%mpr#|nN8b@ zszEXD*ilZKg_K)t6&o&pt~%AY_jM%ZoQzsc;%M4AMi!gfQf*vv23ukEr^93LhYr6V zV77)z_Z|f@!Vmk2)%&F?P%VW`RSe!uxC&DZA$Wc9Ict==9J!!l>Fue|8l>E1MGAg= z3`U!t^l-wlhqXcVHQ(K>a9b}k`@KP3N?Z6&N~lQfvYIm0PF-)~UiG&S=%VG7EU~1( zO-Tp9M^I~oku;MsJ%V9gOgCCgVVN0S_Y-R|U=bYH>a?(A+)egG4{$ukq0SBIe83qP zL?)`#gK9JkaLEVRfuST{D|_Cb&8jGnt6f7#zVSME#|ds?n4Tl%s`2JX5l0F{IW~_K zV@y%Z3`a_6umkx{aT$6$E=Ond?erfcjTZB_D1=?3=}T&r!xbQH?v%Sm&Kg2nhc(T> zoqY!#8*H6jmY|1WKJt2VPG<2qKpNv{k=Ve@!@3%}n0aaL2LVdA+0WnY_#A)OIuKhQ z`BjW`Z{lNeXaF|533NRyWHTIu5A=#HJqKgBYycw{jKKeB?M$FUS-1h_7RowO5z%!ue8azxCpm025lMuH#B=iOZ9tQe)k zA#d}g5^``W+W_ejk=%Pcw-6%P_Dv&s0`~T1eAsfayeP-yIx;GD#Ate{w`k)ix;nRvV}pV(`O`^5N-I~=K>GUvv&EKkmyctXKYA?mh{rWvSZ?0iC$P@ zF#0cIFw)V$60gL}VEIY|ArkqBj74POc5LgXkUo`zsg_W3?=;WD0mmNLurOis4!=C@toQ|qd+ zz(PLI36ZO>@w5~UfhiN>U~SaV0M{N=Un-drI}H^YO6c4t=_BJn4C~&cny863XwK@D zEw=Ad8IWA7tfT}_HfX7812ee;QpoA-lkmg>=!WZg_XlSpl>39O52|?f^rw=Mk8UBB zV0SVENRfa7?+FROC&^aW34Oj%E*C}iTsVKC^GKxrNbO0Y@pl3HXeM|tU1av0>N89% zKOp0q(`@^5m?8d21Sl**D64)62%#VsBQn)gjp{T1$b?{4EcbV-;$MHl1&nOXw)fA$ zo1ipj%#lmi_Focb|IDK`f;`&E&(N~>SHOB0{$gDnxrO6Rik#?-;ux>0%*6*)e+w?G zc>K$>2 zjDO#`u>_!AbmB^onK>xOCEax-)c$LEi{;+sL8Za-FE2ZE>#_jx-kPn*;4LIC&iww6 zn)o@Du=U7KA`qXl;D@&s3wDb#w=M3i=I11Ve3MD!SCF~rE8bJ?Al#~_HUmli?d}(k z_W}t~jy+N$uQZNy6emM{xnHIaCSL;UOZ(1Jlf^%2u8dhRBFpKSwQ&XMJ|3k()S@ci zNGB)2mK@*3TPnDqNZN)><6Vru8)2*l3m>TBMt2f$Lq%|OaM4(<)d4cxWg$cY`~A2F z!FU-V3W0g031NOq3LM3WGr{UfBT%(^V$1rn2x_E!Jc+Tvvllrjxb}^n4WS{voaMB6 zjRg>u3RqAB8DSmJasC4bYQoOn;r~6A*02lyhg`--_p6jAi)oP)pEodlShl|dpFjj3 zkhG2|wiW%AmM{$X%Je-g8mz@(zwv%(W3rlt969e2+WKVsR^~a3BSHx< zW{?1bOhSfs)&cO6mu0{Mq#N)$(i!;Wt7MMu1Y4^&cubjsl|y&24r>Z}JG9EM+U29M z(f#{4|1>XxghD`zCumhv+Fyf}$WF1jg@D%0MM%W78UkL9m^t`5vWWPrSxW@>*aUbPu10cj z#KK0&1caEs8a%>wzwuo-CmT@M*OJSOD+&-U1lP4ol(&FpC4zeF8{lr-20R!*WR)~N zeS*dMwuM@w$G{8qI@~g0M(og&ebeuOhn{fT)ir;8F_>q%I#jSM8D~8HNKDs^R>1!M zq3o;UqHMcvhmukpLC=mgN?o=6CL^@PbLJ*KHl_4ZWkdn|r zK}ktz&z|S;dCz;^@ArM@oc|nznR~ALy7pds?X~vJ+Jy@UwOCIZVUZYV^19C3sc_;u zExc=-^k6>!0|X%$$@y)uFeqgt`~~_RwFc1Rur9iqpekPvO5Ce~VQFkcgEf`}Cd+K( z27%YAB=A}?ttG+saKv*gvwkr6ty zxPnYilgRT~%3TzA^?RTQ6TC9qvLCm0wWR4HCo1GBxLQ^TdT(VKylZ5HXuquJflc1B zwtklHd|~zy57!YwP0(@tjGiV-f2-ktG$5D%NnwBJOX&SLY^y=WGDLFfvIiU+_iZq0zQ!ZU%vSoCUpBPwIIKwiz`7K{%1LRA+-~Vc0aAB z3!y2+CD_qp%;G1N4N9rMY3f0gxE9}2#zKY(43Kw>I)$q|(c=|BhG`A}%N)FV?`95=LXkKMBD)2PV@n}7 zDH3OSFmFihiVOm^iW>USNxH8n0!aK|&CG#)60kKE%B0i?4M)!KJrp*+=WN<#WWp55 zn@_4r(XZv22G;kl5T@;ws8b!8Yx<3|~W$eJ$-b><$7a5J&3WakAI z!HNn;bybMBS>lg+<6nu79nP{!`>%iM<`cJozNlr2O?m|9X4PL;bK@Fv1(dPovfjW& zBy1ZX?O(;GWEWE5d7jo?g+KO0{YN|bPhcxI+AA_ft}`TtTcF_9-=< zSJLz)zLy6PZ&}iF(Wpy7Hjaf*j7aU>`5)y)@&tKNxT8RxNZ_c8+|Sn}JWsue*DMOGr5R6@LZdj^*Y@bw|jQs+76zAFWA?U<$ z=%y0#!(Bbi#;&*a9|_qV<68I)_G@?QcHci84}vA@mUy5@8r)3alTtN->pl22ZOJ0- ze*VQx(p4L0fwLhF@W%zuW~Ghc2(z(4^s_iz`I~QQho8jF%@q8jo%USggYt`$olfDtsu7MMHEzAKUq1cB4u=~oqbHv$&FVD^8&^KJbH0Q5*V>>PORcOR zq3~Rk=Rb>ZfoZ71ceV~nE`VC*s!;#tDFSh-M<7mBKDcrU{V6aWzQz!|j3Pp=$Qt2L zNd~3;9?|}jf{i~fMWR*b*}b9N?`Jk0;|qizoMQ%HE*j5&IM@R^?Dwww)CFB+fBM~^ zZbO39WNu7^Y*qHhR?8ju&%IIlYQkBS3$VH-4Th&iS@PA3JY2|y9%XU2w*u>g|%x02MyV>nBTE0imz283}#a4+F;}^pqxq-uFc6 zA?=61hj)p zHCrYpY`Oroe6zs#TOU9=uj+-8?W?rjAe)Xdb*@uU+F$FPumIK0$-+-JA|nz{;4*%) zNZv)|6{C2^(uZCQ1sOI^1MDRj?dk{|@y?5~e*?ijiK1Y5+o*7x)6&!YD#miVCTaEZ z={Mx8-cKcg%`^%6Sft-p?eytGK(M6C%w}$cYf9k3f@MJmotEUY&zDquX6615hY$)I zftsqc*IwN$3zAb;$+m#bwE2GD%D$E_XEMD`33rw^x~p7&E~+!nk#zMA4;O$nx3_LT zKfl3)3B4^!Fv^8SwCH9i%{YF-1YhRBH!D#oIvve`v~gtFPPxt-#Ummxz?-xadVj z_)wuGRctQ4HC8gSz4x^yI#jYn-leFG3ZJhws}~z8`J~yoJ`eh2aV%1goG;Ql5cetk z-p7Lx`PS|Ne;I+>miy6p>h^Bb{W zx(XW31Wp6w+=unbDm^7x=9Y<(EKclBo_(UFeHxnmSG>*MzjE_=TE+c%i%<%*oz3U= z80KVM%~t?|pcW+)l^Fn7D5r9u>q4`=3lB--!UD6SfTx|r@z@74#$c=}62YtKK(OM!kh^KP^7e{*bE z{w^;$VIfnGhVrBpqOyq7ivMNNoh6i)UbsM|X#xb2!p4_5#ev;2j_rO9sjyTSLFFXl zJ9v_A#%J$8CD@yw23#%X_c!?CObz^-OrnOL0@OAn-h@20un&S>m;PxmfUNyc99p!F(fxd&l7rZ@>pi( ziZeDxKVIW_OjNO${`}trDkTJg%H)BlgarsxE>S;Jw1unedTw@|xC}|56wPUu1>uj- ze5UM2;;?!)=eQ38PT;WSq~c4;HYLWD`J;_KZYRFzw=;*Ph-3q9K6P7QP!--oeCw*j zd@gEPRiUad30`ih*34(4mJNcc@~Y2bnH1t=*VHf|Ty$T3)q+ri*)3p&538nbVODAI&c$F=_ zCFAbJQ%ageRDmYfI9)SO(y`n{9@DxZLVjk#`z6pqpmWIK=(qj%W@s5SL!nWcKxmYz zi$1APJ{Q8fM!;qMR^2RBgT33RWG*1)-TG#SC*7A%phW)@J`Y z_fMy-2=1}IIt&J~BPfwFpPjQ&MUi51QyDb@xMs z4&fQO2(K~9QD>voyz)3oiyZ%y-;ai-ipDqC-w;9o+C>Eeh z{8?x$|JK`et0YrI)8QICm#(%nnwgAppI`(X9xDQ`LD>U(BZA_s{t1*XHB-Kh^-7Z? z;1C21Do%~g6_T)|R?^JkVmB$Q4Bbu?-tD$L6q!6#QKxa^~U;nJ*A8*3KEl7$uNV;>%4HM41+$6CjuI>Fg^_QBdD6!JC&jp6`=l! zs&X93f4(4nSzpO4JgFO?+M;Ai5?qyu>%YADe?bPHQh*GV)9JUX2)tPmN60(4B?(M* z_ef(ogk1i{jdAk3w<5Q{DP~}&ft<`SY6%QbGQskCIb1LtrNE2CeCZEY0a_-!a&2-4 zTB%U>(By%l?E5#nPtQ@#N%mTKJXp8+rP=W!f(s<}9K2fe_|&KipTws!wX(z?Vin4W zVV1%Qw(PGx)`;pHbRhJA*q~>4PO0(sM_#g3?0_q@JRi>`V<%y>QPE$6metlDyE`n5GYh($IjNzT#B+1$51iLxVy0Vz|FQr=YEW zE;us%t;#o)lOMISZVd?0 zBPrLuZ1J>_>Pq02p>!}Mq~%H3xHED~B_j7xT)rt4gbr%2?KlA>w_E&B%{+;l{9Yjb z5rilCQ{N5D;pKc;^^k$mL{ipwJ2`l{DB(DH4I;JkR(h3%5-~Xq%X#Of&Ef1wl>91= zZt&DQ>5peLh2NYS5T`z4q@5lSRSjXX#!l4_b6MzkLFTV^-Cl%KDR5_7LgE?04 zSF0PW)C7ewE~0pfAiw=f9^Oa;_3RlF0m!B0Gyme~vO*imzwQl7jRO07p>kDrl#3{y22rFt|^M^{szZN$irdblAI zO7Vs*yZX}apK8Vb3)7W6n~31`jFl(ixjoaXMOAY!qI>oxLh0LX8>t(5|u z!R@#=&Q(+6eU}hQJ^cbt0D^5)s#kXq44d_gZEc11dryt$@%58%%n5m|oRHVHuI?@5 zqMU=+s_Gs9*n^@+_hx)(ZEutPWIbWnSruz#GoKa;f)1``!c_wx{6h|`OXF&LDB-Yo zcnvmkU}~!VbN<5;|##vIM*b!`E2U}1h>LVF#i*g``ftp_kODUf_PaMS$!i22= za&m!Aw=NmNV6vSV%4>(O%0TS6ls1%Omh#yyBKi#Lm)Et{6L+8GEHh?o1Y8T48abTT zZKy@66mhg8Kh-men%%tlDIpBCtQ(}iGo9|`H`*_3F{+KRdK_?;jzM+IOH0OX7Szm( z`R4h>9+vJ+>fhSRujOt04dnWENS%#aoWn~-cvzc?7e@P3*7#GF z5SW6izk;WyrHEmtW*}UJeuHv?TPb4ytMbD$j+1ms+2IXHB^Z;!VuV~`aS-;l2<#=| z(-D?!e?vk}Av|&>SLaBa<~P@R@6YAWr6msJt|d#{X1Ta37oAvpQ-@VzKgdAp`x*Tj zofQck`!46A44uvBUksaa*Mg?m=XLO!Q@531S&^k%_+W_i8r zb<6?+zxtCi9}xH;#bbb?w4Nl_c~b3C?$4*FS<;7Uaix@K&+k2FKRjf|y4Yn0Ne!Gs z$3C~zmAYHO%>8z?Qyrsxyu*z~`g~M}r1!1BukH=FQdS|4!YSb`d_3*t18e6Qiun`M z();y8rK7Cvwa=C_+(r98#2OF3Xsv%|+h8=Ov-HH?l##Dzkz{P84M*uZX&nt7?K$I> z?bv*_7j7Qe$hezpVEC^$wTSp@-ueN#NtWBP8aL2~uFSMJH(v?r^ zA<3E8+yF!L1(1#&j+5>}t1wiuwAO&ET$dL2jn0HdMC$cd6cJJ1N1MR3xUYF~FyO9J ziI`i6zyF53Qjyt^13GIPb6 z@@VXt8Yyec&KE?;+IFh#;?JmX&;lutX`Tg6jO1xRDi~8R)#fg(1?OIZ|L;lvL+iqK zVE>}WDT}S^oy`tXUwN&6lRa>z{Vwe)^8hcc&-K8V{crZMSoA&NGLG8}$W3hq!{Dn#7 z%%aCuP04zZ2kf7iw+!E$-)b%YZPq;d-77nKK;zXq-GX_UCEh4HfWE_A*kE*4sO+na zr9e`k`BeF&)uNE7aNwwY?{4>f=?i71E7G=QxC(P8?MdIt{m-KjGc2_o)z5FU-M!NU zdXzjjM<@ba1xCDJ<2L_#x#S3<AVNgWymQ@l-T0^7Wj1@DI&*V!yaQq{cv5@mVn*wb99wPKYTu0{7M zsreL{{9cou$&xUis$EIjtW^0}ML5y2oNO}>ev`4LGJ1WToyk_86gH}{Omo&A{1$Ut zdvJQt-KTYaa>MIxywguEkLdK;^ZLJX9gH%4$_jlY^!uLs(lk#G{SwpfyLq76lr{IO z+!8(ARsF#7Gs-z-RJ**X&`;@hmdBa)g2ENYq6{k!{+1EK!MCU@{WjOy9FA!%Kf#cf zGS)0)A!&hTl{m)dGO;!oSdCqA*p*2Wa5>qK-%_CE1G5vSW>dIh-%0glJ#MM*`xSlL zZ|5Mtn=jcsaH?&^!7+18yKOW?_)})B&?)P}p1==ovGL&Zl8;*lqK*?Cm<4GTBOvD_ z!^{Edg?5Q%9fBdC_FIx^B%vq#eTq;y)vmTPQ?u4MeM-VZncU`o4@?q82H%ftt})?Pu%Wf`EKZm?q8cVw^M$U!@}){Wn_=)UH=Im`$MlTE$bN z^vW|?hKCb<%N(P>47Ewe%}--l$-C#`Gxb3J z5LE!+%xw-d@Gs&QoTsx=$m6 zjL2Mn*^iEH6Tz@|zagQM@tF_dJc~{y3C7aT#(yI}j(GS{0YqX6ocXbxk~9W0ufwW8 zrb>GI07*DVdD7|1&|L(J4$k~>fXDbs#U|xlOem)HK2`29x|!H?bpmhWpgAJ=QEdJM zV@+?N>2P+^+z1uemrSpUzNvQXPP(80s@fQ{8v*-STXdh%#MuwP9ZR;=ra9M=5w{AR zHqE_(t(v!|OG!hv6RA6z3AMm!J{EgnPfq~kC-m23WG)3;JGCGGbf*1y#{x_8%0!(g z*|2*qlY!eCQb~asmN;rXFxd*S!jQxpBz<|+F4I{8ch(xO{=CLA(PhNqUW0j zUTR@g)?%G;T4&kIv+J==^P}$dQB23Ww~e`$duqh%TrC#PyJ9IU-DXU&wlJ&oh}R*@ zE7wQS8O$efSi5^}nUn*BiHqmHFoZG=T)BAOqsSGhH@9b2y+_Iz7Og;r`L*XdaN)C! z!*wJ94r=f?jm}D`Kh+El;Nt!S#GML*`QxqhzwKn#>2YUwV1Qf1UsFOl_Fbp0tv8U9oyV=ckMm06U7oA#x0#fdZBu3@yztJ199 zKyDbFu!)z(`-)2Yd|B4`<{>`a%STHkw$ognTYi0$u8(w6IjyxG z4b)unmB{{XCh-GW$P@RiCnsolqzggoQK~Iw;Y^p&-*Bh%0#gH8NASEPm7Q5r4z}?4k3mWDic{-2Hne%7) zyED1)hp;gF+a$bj0_c3H(wTy(xpZ{4K;NAtL!|xSM>mJ(q22;U7j6(=hL8}BUcE*c z%@vGlKG^yMh8-7}z%&C@jr!y%L$i42YDHcm<@1-S`;;FGN(HKCz7CNjpMok&{l|$~ zhtu(|Xvbvcg*gS|)Qs%3C?aB2rgV>pZZh+Sh1J%+1>6+L8&`5Ub@92i6sM?L?gQ*M ze7pzVM^@K4!{)t3R>J8^N=KOrSl}|;7B}t2O9)Crtvq-&zhw96bcgd-wpcnmJ=ZLdHD6I#;V4!7BRz&Mnxwp;UP6LD zUydwlUj90K2akzbKj_Io2)Uu(MH|_1>63X_&q{T(-!Ghd9YO zc1vxn`HzE1@c4*)auH#CO<#=@__)@V9Dn@f<3f+;p)8Ktx2O=qO3To2UQc-a>~eT) z6snXD%dsX-%12xG4Qr`P`{D5`YURTd9vWRF?Cz*bh0%GiMk*k-F!iyh#(a z5!2rlHxwg9dhtUVlT=SnMbAvW03{kHu~y$l`Xrpy_k3Ox>UMhPcaV{DX+0+QBe-Zl z$OXb=t#W`Z8!eU=Q*$RMATpu8SpQMnI6nj`r^^mD5&9%@VH*&`(Lng<+)g03lQbG&+nq^r;z9K5y;w3+WmTRVaw#7zlHO$}zP z&aEJGLW{2U2R$z~ohwb-2Z-w3`gck2DmT^AmZIm%y-L)_Wxw2+4^+ z=W#wLtD8;3SCs`gb*cBnd>VZwd?i;Xj^d`LW_d!9$-9TIRvBrVzdfI}>gQljO@AX? zNq5c_biVU3nx&$>8c4beOcI4N_M7@#Myg#=KsfQ{eM5~WtJ%>oB0qy-gk{MWya$hz z!)ZTEQ{Z_w%tzs#wtoCPn~dmt-%H z7X!pag4x|SWbh=yBX3VGWpHA_6*J+Ub%%8I z^CG{_3+#=loM>06uxZ+|_*SgZJ$^SJnl{hg_A*dnsYqqsdlT;8sfz5N_*wq9vNO+f zSVw81FVMm5#Yvpga;E3VHKmE=LkGvDc1m>L6KHY{4;Pu1o#GO@id@&2gz2F_PtLU` zaCM>C5m6EAxB6N+YK!LUJWR$w{KW(KSzBh56-Ywq`H$+pgpntrYbagWj;VoN%_R2 z77mWtKgrC!lbJqr|D^$PP(!N@2(meO;(V8uP;Xz)y3#_zBQNb;K;-KAKq~34LE7mK zm49h#*hBuwJzGF3=O&?k{k%{!p}PoXhaXg&cfq=B(nv7W3jl|DQbjY?GTS5k8(HkH zhb?OOwNo0p#LJ*E<9se86%_hNG68W#%sfHVpfzaF-j%U(Xl}^N&&C6Td9i z%)&^Ai4VP+_vh65JG7Kx`k+e4Fd?40h2XKiQX`ejxcIR$)rwMHGp ziIu4a1t&6M&2U~5m@B@@yeF8he*H-(X`uh3uB3UI3Wj|IZS^g^i^Rvy92-6@7))`G z>}%;IWvj6mt|KQdU%hZjnf+|q)vlt(ZSt=Qof=&XPd480ikZyzp1*xPr~UKk=a+P7 zSDhbzBBr9yRk3=__-x4Ps&X}Zg9FVZCq~7{g-=CP=LUC>a;&IMP@ttQgE%? z1T&HF3g1(I14Y@37j33%1j3Bqr!1EQ&MLCFZdAsY2TP_0o*kw~(Fo7)L>mW7vYol? zs1hvs3OgrZL4@CbbwfiJ6-!Kv!`$F4KN^)q#9q$$IX8~a7NPEJ*g=wf)WBkf{PfF5 z$FF@Bq$gLz73vj?C*Fh>g)2309d9?@!H5cR+PoSQak*&n8MYPN(6=oPeV^3>MLX3_ zNfGz!XN<(uEqXzVJ93xTyHNBfXSw^{EnmMW_3Xt^i}(Bg65 z>twNF%#V0ciWxVA6B$s$ENaEU2#m?Mx24>QES~$7(OGpccb^H@;I(3K1Vb;ZZ%Bo^ zt{5!&K+TqZtT~{;XQ^uBXb@DKGK(rvlZdfaMJvyzbZkj?6fIHg#yCYhJRD%Bmk!4FXwbWHP-orwB$`)ju+_=wO?a%Q}y;fiA8%9>^xA5Tl|PbHI=m+7okTK1gj`}J69(cXWk zc$WvIxM-|t>HUSwZ93prD$Hv%k)c#P{rTwcF&@4A(Vm+X`a}-0$N6W&5(LeHnXfaM zQU$&yN+wEvU0qyS-^FiUKXmly(Uil(z;vg@vG;s~XG9)Y`g}{YilSttMryx09I+|u z81pB`**ML>U5_0_4?MDIyW1*vYXDN_g>f2Oo2Eny&-z>O}kYO8Gf+JZif@`xw)}MYN#<7wrnNwUPg1>s( z6nNn4C`@#b!*4Y^NvrKZhlJ66j=~RgNcH>byJo(kkpe zE|`2?Cunp2BJWTv7xF*s;_f$jq_`X=e=uS8g5f7;{tMo}yg4sk*t6gNhSoq3)sq5?t0 zEVq8s`4bUZ;AABY(Uv4JZZpSX$R^S0`XxfinZ-w8p;7c?-8d zgG^A0K1UJvE^BFFq5DEuil)K7;|?tij!o1qy7xnyZ%FZyy7)MXBXeup^dySQG)As( zRu;QXjEg?@zNd}0A}4?ZXLRE(1A?iyCoxwzI;XJfhA9yd{&q)MdJ_X`Ie+(~Y&8NS zHZyys1t3a(9`Ul=`0Shd0DE0YZ) zKy9_!aU`f8<+N!%5<<4{@{&;zSP0X(@64V* zlOf@fWn6pr%TKh2I>YqZ?T6;`M}t%DBaCxtq9Q=&W-MvKiE6*{C?T-odcs>30U8Qq z%@h9DQWZZV*HE(oa4Y4HJZs@qWZ6BcrVvPk-x$Adq8BVV)M?M=C5qyr9v8FN+nx4VkfEXhif7-7vZe^Ab&{gj@@3FZ!eXb$-+=V*SVm>gu zK$b=%tbl#@U@jY3W3kpE&V&5t{AEItUK$#3T!O`LE{L^oB>V@T?S?-$td|T=?ns_u zGvO>37f8Gy3fIn(bzt@WOyo9V?sbd=?VrVhI)qWCj-=Rx@Mujv`a(L?;RlO*sLC;8 z?i(M`#4G663i9n4k_ohf--)s=4zk{q13V%6%SVtmOmb(B|J7+4q$v4uHu*b-#sDUq z=yRFN5E$vnOQq-j4QMCrzaA6IZ zrTcFfj3ExQg;I^1e5>k!6C%Uv;Z7=;mV0$6aNdqECx;MYGC{FAvQLH^2f{z`}~f$QM&rUZ2c~lfMlQOHra` zWt<0M$_l0$Ty01h?@HwJ_~aV7O^pmfS2{_(;gk_~IwCATh7cCvT2<#VeH884{C#yH zrt+Ju@Ux?M$=k)6@o=FGh0aZ%=uxF!{!xsX2n=n}gMoYmh7r@}_ZadU-)SwsC4}&B zYKDaCTmb?j>2`_Zf&qLD^yZSu0$adF{8+V9y3cH?eGiOqu&s>v(GwT6Z@nI6x&M~m zw7O^6EMPE6lZYH!p5hHpN`ea-rV0oMpl=kkXdLYft8L0J(0(Egn?~$Iu@z)_7K6rh zmKO+2*6jxaNrcM~K*MFIJU96*PKI4zo5@x^uW0tT;(HYykHX!Gimm(t6Qr6bQJ0KCX{R|Df;U1YU)gvBRHGem8i*Vm8hP`Q+y@W z@WCW>5EP8wp#8g0&SjYvFA89#H=`Yya!#NGE`Reqb2+%yVwKlC31v2 z$u>?oxb{w)N8@`yPo-l=??w&Ai^2G~T?Cf-1#j@3;8_AV-I2F?d#}B;W?!L; z0Os?|e4ioU>Zp-o54p&&B$V#4ttU}^Iz6w`PM~P`KT91m43^|ROL9jwSn~B#$4+y7 z#o*fFwK=b!dIefc^o!#awoz5dqktvGYB4$YTTA*PGI6h82iN_`Pd^$pNEBX`r>7X~ z&51hlwjz#AVaiUoL#HaSO*xGap(G=VqgP-j@3Ec@+T&JSbh+cdl!_=Xi(hTAB*q(A@>*)Z*Qmv*Ph1c3NGY8RJw+KcVP)0$R!R|zHGwdwVdcz4-fX79tbfd!oamK z!kLG_{VY`>sJSs*6n92(zn$5|C@P};DCFIY5XZ(cz&{k>8?-no z+`2F6yYYOo{Pa6fSeosgyPasf=Cut?KUkkn3ps|SaAzh=n43<#fU9^V;9Fe@J1$d9 zH$oIPle`|C9Gy1NY@eZJfUQ=Bq?PB&l+$)^>yhc#A_-NFl7{l2n3on;Gj%Qy^3qLE z>(B~dU09xv6)95eCG17-;CDDqKZ0vuHte|k%dA=>4Ft&!;;Xn%3F&Z&v320@y=hYy zLt_ma>Ut7f9~yn@R;OK`I5E1pr1Lr1Z2QjJ+l#ac&7hffqxK-e4cV`XGj!($r);Gh zSJW6kg>t^Jm;SrEBIR}eXm6CL-!uD51`yl6ez#|CKw!iVE|pwRWI+$DGgTrm^3o56 zspfJ!;@Bj5*oNER5Ys;Ikm}8la_fm^61|k5JQGuha3fdjsT&7^ffQ>!pO4l>y@0iF zNLHb5v(&pU>QM(?-z59#m zzxc+EX|)^YY6WjIA4l6FpGd`+9}y0cqE&#MztqM=gcq&)AUX{Zxg_-=A%MN=x^Jo- zEIBc1f2IzBF(7L#5maQcn^np^;mgU7{6mZLZbk~FK0i$ z38Pmd3VnCO3}Va-;=bh7bPXxR0MXAT{M`t|8*1=_i%fl-3 zMvV`9oQUvL&F>oC+Y;dguoelIsgNU_56{s+h*2(g^gK_5Pa}Jk`$bYwQ+omb|htD&Uqcz#<`9=7tL zn>+jNtVnp>+SOU!yW8O0DINpk>HXG;E_vq(NwHX?l|DlwY(eZ5umHBy8LejAj$XPL2X#SJt9NHezw&e(oB+KLUoNn4xutxRHQzdC zTtes;JJIve)2+|-*Sx>5siZHgOQh9Kv<|tU3)P3frqMKQAlr%bz)+<)7b-JB8ClP1=^+;+zJf}t@)3EnGZ4FOQe zlpad^dc(r{vAT(HzGDppFwzS*S$iEOVWmR7*c~b_5^fwE+cxl%*`oSRYTftjs5`?p zA4;zG+x{%_%ZR2s&d=3}@(fOqEHSHd^^TXm$%7Ji;E!cfaAt5OnaB5P1n|>vT}!j^ z_4Df`P}FM21A9i!ARF42&5j5&T$}Ja8*5~1gQQasd9-?4>vXH6_4U--a7xXVwmm9; z5#uIrw4`+a+OwPR|6YYCKd$rKf{heg%phv%%dfbo!8sIn9iaQx#Si|B6(n1PvU9l1 z(uFl>A5$5y=eZ6aX?%->zKj^v{($J`SjMxGVglF*+sv+L&7N*^O^$K+0-1WZ@w*|dXecZC;+ zDM+ymdHz*#eE+tzmK`)YK%pGZ=_5Z|)04oXnKVCM<=6{j32(_^jcw@~LI^baur7YS zxUAY3XG7=6cLktvMDO(BmIR05e(xn`D6yOm<9C|8RxGIZCI3oZFI2GnT+M@OzhiCy z1j=RgJ^6QHD*P%zSR}6h%OX7!+eXTI%s(bXzY8pZFfy}ep{&K(N*G}U4-&OI+}{y* zV|0udtF%ui%&h5R5xB_9!OQ?pQt}5-B%Y9&p!u|bpG&ommIxp3`(4K#PM?fp?uh~T z@GA@1_W!_{4;FCiwsyaNyhSG2V!Qm(jaB8uNotk~1M0bo37$Lx0fQt*iYBXNFT5H^ z`otr1d+5ArT)mO>T8er4NeVbd=>F_}2JRXLuy?*8JeiFC^#*)jRq86eP)EG~l92z*|E|V#MAiN-v$Wt!Jmu=v^sOAruyQ zky%j$+(#fHjR^(GeQT#PM0mUV8?}kVnF!(P*w^Mncmt|=AD)Mr@CG)%r!02C16y;K z;NF@2XlPjlXPq3V649onrXv~=;IZxNNfqtz)!W+G;GCyp%UU$jeVNrx?ZXu7y{hujr@)wgs~akJXbBE=H$^-83D?W5xbzwcV0j8 zlE)LA3=M+v6m#HLV{U){T?=2NL;vcxG}!mf2Fh`HiskSVhGG}|FgZDSFGrj#+UXo3 zPLV{M{%NZP`sU5o`(L>g%Bi28bKYN|LfDGL!>}sH7rc*EGR)e}D-xcnmfqYfU+Mbo z>frRWi@#|ujrIbdiHT)g23c9{=hqqdBF9HDbX`!7d}p8*Tub(eXb~ST7c$I6x*6f?w~55n4v26k@kP{`v#mb+tTo#uI|R8L>g zf8)CjHJ0dYPXVyM6v!Z%_z*Wm`kP`kQ`xjDVl|LK_G1O@7m0D-zMFOA05Kw5)E3J_ zg><{Z#Dq&Wb5+MvceHI8yx4=VQ?5PmT+0$-ARXVdugMVzVW<3$&oAGewhP|XtA-n3 z%QyAK8}R4z9e9N6EqN&OXwD5bMcc1#ug>%Wf#LvXTEWODqcrcXBM?s8m#1C3FNlYw z^q9FH!EyDzmkZplC9AV}R-wnH`0hSYMc}(v*D6-6vyM(S5(%Rc6EsEcOa{IoW5CUi z{}?QAnl002!YR^MlrSYAFeO4o*JI&U&z-lsd5scDPXCkT0iR+<7&b&4dMCF&i_$be zLKesDZv0@1dphr-A6&N%&qx`Wa*zOKgwB_dZ*H_Flb;pW=R0_C3RSwm|DpB|-EpFe z3Ym;@ZNH4b!dSKo4QiR|s3V`z!UGi8kUS$P8{jE#G{3sV)<9Ab7=XYbD7A#husPfb z{9M@{1C=ibJMl$~g+mz}DZhY?`Bb>dCxsDN5e14TQL|n@;AHfI>kKcJt^0-tNro+# zBVEJHg(5I__1L$9nTb{b^p}X8NF>8rYdjCtMa9EPM||aN{t2pyUMO8|Z6o;6Bp1=b z<=`rD+gqyP-ZHq5t*!4kNQ6&rG0$~|9o_DO1V(R?-JTf7VXu+J3d?4Tj2kkH>w?Wy zEBj)>lamNvukvbp6%I=o#yk%4;7BLEi~xbYc;U7{jPr;sZJ#BavMd#{?ON*&ngs^?RE@}p)lo@Y|jxi91;4qJM zQ?ns$3S1rAt$~E_n{iI=5)r=f)Ug6NBK%!+=A0TCcKwEENi`gZ$Qsp80dVvi*hn^? zqJap~JVF?&>Htj;Qk=K0RX43YA2m{@Y&KW?ET;Xb$VVu!YR6X>>{fuZFANlmyP#;+ zTf6h#5!yM~*PG-4#tGUrZx{uSCaXPXdj{~3SvfGOTfMPEF0oc;4sBrG#Mr zcgS@tfIpG(*f5cSul%VnXT${lW8x~4-1HwV%!B7)8La=#eBm(h^{1y$7O!r_o9~yk zv`lNJi}%_M5+6y}m7U4yMms2~idbKXV|99^X1;-QjeYF!jtd8T?`(*kzHaC4Ju|$1{8&5@LEVFI6 zv{FTEw>88fkgq8`wS>lOg)#ZQuMdFNP0hIyXA<*R$vnA;;$XoNYoJAGvz2 z1rV)~=-I!EUFrsC(u}V5i|lFzGioT2`^cQ>cw==~QRll1>?JqZrY{BjSvb-*M%a*y z1!Wgs5BBZ10=ncVPbM4*35kU*GMNkuWwy)c%pC%o))9NA^7AgC^b~Av{NBkRXPkf$ zeOGfiA%>?aY(79duK(b@V(R)-4poWz|>j-x*d ziIXi(EMKx)%2iJ&xj>p)tzLazQImOtw(M&z>pL(&y`-n(*2-YC5{|zZmXdIE?o5y5 zj|AA=3(=HxTqzNB+$IMJw*;ahIBys7!|FM*{y|A!h5<@SY#CpHoTUFoh)`@W{gPD$ zDmXmy_GK!ZA!May1704o5@H%;%l?Zt9QcIzN8MQ=oqs(BvBu+7Is+7}j56ew2#mIN z|I0RI7Z;b3v7`bZgqRzswK4{jgCz|pZk*>PL*UGeZqhu`k2^+f@x>$;Ox2DP(FjaT znCbiXz?Gd454HoYjKY=ZvU_j}?jbzSJGEbaujgmOlWD0+`~GUL8);q%;mMKy`mqiIQ`K}l zUiy1FEJA`(Bg_MuK?p|;9l(ISi(RN?7U2qx^b1^o0~hj7Y!a&6=JE@^Ho(*JnYC;I zPs=b^p$dJKqz{|Yu?S2P-gx#_ii~C8PF@vS?+7NfYr*IlRC_G9zltpnQ9;+CG}v1B ztfH)ZQYkdswG1X+>}+2kNrQdt=pyx2L9*{iMnao1OWuuqLfa)uxB76280)n(ZmXT8 zl__o8G+54YTEaO40zfnqlynCw?dHzt;O$h!HiAyTCH|K>-5i*v#cg}0CIp6l^M)Z6 zCt;t}*%i^&!U|gp6EyMENXt>V<9J>obVVw+X3EWjG}s%zkr9l|2+Y0nzPw3r;pH~E z&yK+RGvnU3M8K`r;!LIr0_j0{{v{Lm@gQ%3uP!Q+_%}HM@%#7HeZ2HPa|#xl>}y#* zrdID6IH{{$lDhILo|KsOUMG|FYoT`Qu+CU(zxEl?FEVa+&DMJbK|LNZq--PTX`=B?`IcN~4D2eC#>mv+~hTy~=d5p}4--&&zwn<74Uae38DRT(RfJ zqJ}A71Ej+Vjr?Gqhejb6OshNJ-lw(&8h$N(dS5k3&{81m$gxLKZnK?YBW4_+aI4qM zkkol_oNYPD%iW!`Fa6ZC--_H=xpnyBMBU&uC1kBX6mTJ8zA=NCcj@@5dJ1FqHz>fS0B07Wx#Y2jq@Ym@HCer zDBMA@?rD2kA<+NPo!sJLjj4cN=E?maJ(s8J$^!TJm6svSNCv`+B2_AAL$pl+c zGgJCwCds(skzzC%)m?duI@i3rM=@GoWn0B=0o%Q7#`wUBtZtm^MG0a=s`Q%Kui+P_ zbFs|3r!zA%Mcih4h7LjvhP&p6^@w(zHyXZEi*7EA^l$RSNzF2*LZs|ZTuSG8{{m6_ z=GUH-GYHFg{}*F#9adHMwT*7rw9+9;ZRti(QevY>hjgcebW69$Mx-UA1q1|1Nu`8M zNq46p-QC~Z&-4Di^M2oXuXCOMyttNotu@!2BkubiV;qgI)49$JSk;*0k*Np1vI648 zlIZW2y$?KQ&BQJ`hx1iDP9u+8zU3MXFv;ztD0U2ZtvfwaIW&~OLKTXTsDM&}9h{o}Vpa1}C zR^ep!#1y_0flC;MPegaq-)z$- z@e$#LOz(w?aF)KIl{fwBAtCy+@_|s-SXVKNxbXwrZCCQc>Gu~zHTx32>4gq~waU+G z798#p)tKar)ym&o*wZ5UDSlvn=fObMU$?!D<`hSQPiuyHs=W7H3fbT>8QCXA^5Ad4 zpZb&)y1y!s!OZAs!8FRi!e_k0pQ{-BzoDrKo;LDF za07#T`g%q|W`W5yLxHVWi0;kt5?e}`!+2t8;~W;EXners5#|u92>|T$s!Q0i@I2w5 z=`;X^ZPAGS+yVatJy`j^C%<0CF@qu-ZaFAnJBDAr?@$>o82nTt&7g@Jqd z>fE{fsEh_ht{+uY9pXXG-_tzRIU@G!n-2NswLIY;F#iC6CDi97$>|(wYrhGvKkw4u zj!nwc8FyS=t*`1f?;?9`1%AB7byI(q18kFhW)J6ToTZ_#=>Pkrz>QY;EBL+HO#*B4 zX-@#U&<4wVLBuj%YB>G@x&)@&{X{D)XXb^^l*mXOc!NVwl2B}oXZ{&HGN(qR=#)Gf zWPhnGVix93A!$cJ+D70HMYd^_TQsnNUleqoS`&J!%pn8SWZS7DMYc=B-biUh@=R<=S0vbE!5_kQHa1*J`*}_N zfUs=#RvQ0}t*$^EdZ1}sbpy3%GIs0rMM5YN3vpO6Ilm0{6KXXk)xo2P9hW(Fkv)Q^ zDYEEq{^!H;V%mHK>!ep`>s6DB-hj4bTiP(@MFe1i!Cz__A5Q;ZNxW!zWer?DK?>ih zHS_rgnx|UKipdLEs_(a!8&2n3VH9U|0D?TNBtyvGXHm)Eq@kg)u5g7_#fl<=TBH~U zxP7snfJ*bqMaX`EY7T}8zHEnJcN`m$HU!?|+;hv?QGvEp3(CpPo6%zZE*S^j5LV6} zLt++YJ)}-{)ZyQnh=sqceqUS5dGQYao|un7sFS;_NH?!z2fU*-R1r-GHJH4DtmK%A)r{mC^2;Rd0e z_Kjb`&q_ePUASuldo#;aLnH7Ly$!-kTn8LVED++>fifY#a{Xq$Uy%J+u8c2jZ(o4J zSIT8Aj(U9KR851W(|HdfA%h0JV5SHr&p-IsVHUj)aK}oMOvZh@QgI_;QJzqXp4Z_= z_Jpu<>VPyUmW+a7yRJwomTW?LK^x>b&?2O362z{Geptef1)a==f6~++bACccng5Q_ zvVLpS{*dO=@9r_DvH1-s+o|`N!98A>&0JBFhEMee|4lzB7RjSjbBP8_E~=K#whms^3aJ= z!i(axjF+<76`K=hAcf2TEyAcZ4Pj#_vFpUSGEy`M~?I40nx*sDX_y zV`HZ9o8u+mnk6^N>c68rF!%txns%SqUOojEjw|bT*S!D+-!q6n%>#6)egM;gQ->kt zQf6g{pdN$YQzSPkAjm)mqhYL0=mw$|>PZ@oolJK(SuS=j&JgGux}&L_X<^B2Qg~?7 zPMW}A46IE^ubsnuuibHJeH4SOG7|Sf?=epNP?Eyl;Y>xaT8b=shW806WZ&WWxE7~i z-T+>7RF$Fsh;U6wzAkI#YD;X8G_I7{lsc#84w(3 z$T_MyRS2)@;N4|y9K?N{o!405^05%)=CP)8;N!hXh%?^)l-oaVvUedMQ!pOAu;0O0 zfBgoRf@?@}{mn|wyLc@+_&30x(mkvzD)~6mA@PvP?PVYNMPer{<^UEV9&d7P^FNOb z9FS_MUkx~pjrPX&y~1y5E%&9r0j1e!<+f7L0m>1U#ul669ldOZn$bzx1=d#JECFAp z-J7SJ&i!elhH!+ z*w)ZCERx5DZl9M+>a+ybis~HK^$C33fKdoFn>_u0x!q9I?KO~%ESg!=uy$@<>t!CV z^YH7AoG?GK3Simo@9URpqSmsI%l5eN6F9Qvbh)5CX-T(v%n!>$SRZ|G@~_UZX04jzO1N$G(YPDHe2=C%d~@-%$e%u zv2Fq(aJFYLWW}eFi;viRkBHaLP6Of>glUqMv0FceU>6k?=^aSP5GEdryqx8$N}0%k z+Wx>XJ5~a=Grh97u?kQCj*C;HV3D^g?N`!($#B^mt9Af(sHk+s0gnu|EH8;K9q>M? zLg4j4gm6!C3(XmfCbQ^E6LtY)_c+olShBA@ie}T{;yjJnbVDV~A5`%=(5HMjKquO> z-&k9djZdc%qi8Y;q=1&0@(kiokXGI~&UKLLHP!qDag`%Eenhy$C_gDug$iqnKiUWS z@)v5mZFrtN#BK5~ddpM)R=2Ex*vLI}*wrg{br(O$?`7h=XMBDB>QC-o*NBCBBfsZS-~|I2a}(MpM0(d_*?~$E~E0shzjP7)cUKB0(hdMefBGP8sIt91@tSP zkxG7h1Jt)?T9GjSb&Gqd2JRT;Ehb{0yS;&bM0%IBRDyj}VQIZu^-svCtqopebbY); zpX&c3#2tYWK`DbG;D%~dfhgropHT~>JpK?N(S|Z3bPwaX3O<9iwqQnn&! zz~i>EB<uk(xjKx+TT}^n|B2jT0_-F?Bmub?d!#`5t-hfU^boh?(+W%tf$a!rV zz{5(+Dj8eaRds9wC^Id#T*i|JR8YV`xQ5$f7w17BEaI{>nGJ17P|U_+mFD~onl`GV zIKmf9nI-AP!lnqx*5Z?${o9*LLybkGu0m(8&jriN>0EH}!$$~PqHzE~&i$AJdlfI* z+3wle75cB!?djDctg#q6*CQUqaJc%Sbos7ajmi%r&P`gnc!x~42HH>BdtZjGHGUY@ zBjgTcD`*3gvG3gUqPDisVmn(GZ?d_>{=q$e@PhmH@OFUQtOiQ|!VjM)pQu}lACvDTSXL~0J&Nrw zf!N49Kg56_U8~d?V%Ifdb!3bil`ln`5hJ z!XRrGxm>C$+GD=K^<`3}+_!MHQ72>HLhcZpBGgaISC^Voo#?K=X{?v4;i;irrJP^I zB00Mp$iOVOa-z;1ZBx@Pax34hzW!$afTfpV-Fv_OPiDM>v5i<14V~1l z3DKF-Sjf+2({GT;>XDO1&Kr@{CfBWfOO|ob09u8(==r(7dGI2XJJ-}7+t7Rr(0b79 z>m8Bg70@m}dk@Mnblg1mN>IO}f57H6xPx1VHBu=+AOAeRD6&~}<$fVfY z8>%;x6=b4+&M>~%RNC)c>9(ksCXV*Bt)p%*jXxU4R@Y<_%YRxF9&g#*?%Efd-a*5& zOYQS*SX!{I)Um17@WM+H92Or+OxVOCjY$s67WXpw)6}tQeM&qpu)bd>Rd?XrxZiQt z&;DYb_BYyE+|2aH=`bD-twWm=?cQp+?s?A3&g?XUd?8EEvgYdt;hW@vE#20pXG! z#4J!W9h3XQjT(WM_jr-vUh;6)o?vIFYk7eCbhWlUza;J(>*YOQ*DShc z>MG8^eP0gDz}DwIceUmiE1q*_e?#;7p5OGBj4GkLE9XC}TRAn2N?gAOaJ;5?KbDYR z?YGPXoODE5e^Ty#Gu%zbBbs%PsoE1V`()$%Rg@rY)M(iH49|t{m812+cXy>AEmWpg zR8=sV|My?SYrAGX!wZ8~MP~mm`v;h18GE)_yr@NV#K3!Eq#MB+BgFguqc*|~8N<3x z(zcdRx?-JtrvsY1V=K5%XwWlRn#$AcuQ#ig@9oAQkGW1ht>M&$Fi%OMwe-Q={LH zeCKJ`Y30gh{_0oBi!A4}$Nima^YdI#?czS9jag=6RfWv_lgT$-Ocm!FMNIjnhAt&v zMHM#2gKjQ!7SQ>0hOigO3t`>Z3?eZ`e^UO(u~VOjiOwOqg9$HI`PX_`89&~mMr9d zWS$8m_?N6UdUL!oPR!vsr5Q&ig$Q><-u8*y&~i8W$Mw&w-UspG$Kv5A5I6!?S0keR z1uh2RZ6?iRVkU7Sj=+T?&r?}Mu;IoI4ngZ{m@!Ox$x`|85lu~9$LY9#Zyq-dmM`RC zAxN4QP3xioxbJ=Rc|6JBFYXN(7Z1n#7{OOg$SG4+Z?fd`ou%|uoj0RlsfPGJzP;*_ zt;(-%W#xBAD@GL6trOx;Y^r_zXjvlK3?s@ECCf}5U!PdlDEw@kCp@&NR{HMOaFWA9 zh3obJOm*Q~o}Q1piAb#7)f@DzQV-}mR_9qlySC`yr;9JnyiRjlGjWIhY&ae=Pt*v@ z-AtJB_%fY8%e{TkSdaQi|1X!OKjlwXPS@#DT>2J8+LQ#t5Ag|e>cq9;;}Ut+y}$fc zTmSdwJdRV_LnZU~E*B>jKco9mG2dpCMl| zO>K3SCi@|mi!i(!CGmN}{D4+J<+zWP{&M3A75!$L8vhz_?Qb7Ai`*_Nr@t6V7|k(G zdq3*omAXwv?mw6Ka39?K#l-26l4%LB zR9+44!(I6-?q(nc%ToqcVnH#!c5x0A2}Gc?s02RpLQDO`vW=5JY1J^UH1xTsTJd-S z+u~b?|L^S(D*Nn3FV?r(wb)4N0H9%2x{Kf#tT&is@A~ePYICC6TOGQ>dfY&JX)^C1 z(JYjXC3=)aeO!9WPIKp;Tyq6Gnsct8km9b9pi1@a@x3nrR{3|eQfc~vtmDUXYN(i+ zl&9+dY+A+2h&GvJrkc_nv*wJy^K))k){_Zn&vZOX4^veiDa?&~)xO$aZ*=_CQexDO zs?^pobF)0!dwqLz>C*pZn`=IENw2Ln)bn5(nKb&xRqSNC^Rhr@5^tKfOZ@sd=EcoX zogZDAKd&U&idvlC$L^e&-G5BB%O%f=kJyQ7?Y#H)<1T-lFdvB${WK4uH?q_c)K5W+ zZVpcWu3i6tBm1j{`)}SF9470`={Mz@x1WTt4Ln1gpwI1!T6*MA~OWqF>Dq?_-YH&HfmrnRhcfH-@!5 zw8n52_)>0QQwSO4@y;0rGopreH*4hgrdkv|PUj*8JD&y|)(i!--@TtrxZQ%6ZOg~? zGQ0<`f1F9{dmI1DKwH}JA1J;LNQGw4-)+uSS`VAQqZLe$G9S%KR?4*Cp#5WzzckKX zqJH$nGp5V@s~EYg%Qx2MF178bGm%S z?olJSeUg;_tJySz@-a`Ej&fMg9Wfeo=77P~$ATR7B1jW=@n=C6`&}M*ul<`JyQBYx zZgjRnoPP)0)o)JP0wE{i1{_ zmbn6>Y-5-d5^GbxqWbfTN`{YMc)}^q!>C?Zol!r8r6t58zE7IfhTNe@ji)m3|XiMVPH8z*& zAS2It9!N!+E<)=GZz<(~`Ja>Hl2N{Ts;cxJ3|tzvK2?G&H6`Vco!}3K*{6|m{de@4 z6$^pJf5ZZkBGrn9u`lyGXuPMyGYb1AK`4A{+nqDFmx>*4vi3wbJ_0{}l)ln+3H&985uTMGS=i+`dO z&aQ9&g>!R>c`uls^IPA>e6H|V#+f`VkM6n**uTdo8`K+vCx$3u3$vd-L!Ij@0hCV(kXm92|3Wxh3&z5&zbg#T>N<}aJ2G9d7 z2g4$LC4jE^nqz=0WQ)POju>->FIt83)xo_@wa68QK(DrpKDaOaRI+GbtCS3B!d=mJ zqu|$xEokcU+YGkw9(*!!T`6gGfo#UW)xVMkg_w4AKoR^Dt0l=OZm;Agqvr)1E(Leu zLVCJpc$rTNhL^UOIiZo)m*tWMEv!u?($!}U{{JIK05_heM>ISTP{~1U&E*yxGeQI| zj(p0M7>lbKHNhc(k=2;&8?;cgE=NttXfZP$1d+t0|Cf__i5PiT&Erp`Ank)(g4gnl z9L;=6=&VEGW)g~wMmeTsPwYs~(wJk7xwx1qugUvO{x;*#v2AhDpY4dfy(2-&M6F_w z_LVNaCS`B1CG_T(ua%#%1cXI0{nV*^bD*B| zkr(7{^B3PaJbGF#MPyl63*2aIpZM2E#C)wPn6cLsfyG?9|KM0a@7KF%%9Ha7f75IO zEW{nn^4;D7u$L|Es@S`~t%{2U$(=3TA(;zk!mtr0t}j;%Hr!i5E*sCeEET8>ufs3&j(3(~5MzyBcGw#GaFZX2&9KLw_aT)#@(oeyq6 zmu?S`On^_7Yqx+T@)`IvMp>Y1H0XiYOOK#JBXU(eNhB8MOLo~F=@d-#iNK*7q)Ljh z_gnHHjPo;p)P$DVb*J+VPP+=;?gH+{7diIC(#y}6fRP5YSKWW{DcYu!Kl@{UrSOx~ zpQPw1^(5_O_%OY^J&=k;dK*QKSXy;-v2-Q6_9fJ~mnG74P&2fSzJJ|<4Bz3x`JP-* zX0PY_7>eYYYv%u!fwuJE{d9|N5;}5*lsadei}MH^vo;ixu1KzLi8q4c*sF%eTpUy} z@z78dHq8v@5v-)$ESNy(@~aF6uXtmi9%1mG!`kRa-RA_Lo-w%hjd-kz=(7nKyvw?1 z9LqlM&GkmXo_Ge(+PgRq{aq=4?K)A`SgFj*=!6p25x<)CfUJ&71M^>PkZ15Ln02A@Pa2;SP*2E|tyjF(x#k%LUfhpuB_Tv4CP$<`5 z$u0fKzyAU4gMEc-_}0B1&D5#}zldOjkn!lT{u=u7!#5w}0^a+}RLnyreV8%DJy)Sw>z0c9ZIZ4belo%C0gV8&e^x|mz3>EEw;co_Xfwr!IDeW1Nbt~!k zZ`uxye8{zbuw?SusVh%gL*xs9w)gq3PJE8;5n~wVh@vAoO*SaaD`?Xik}~o)qY7}` zST(@zZfHnxGp^2H8~BFu9b<{#T~1N76Ysr5;JB3>KywI1tgjrPT|E}jKa}EXP8qdcv)GQyH~U6NQ|wMMc&oh$)KMuR ziKJ$_SeB>vGbvCxHxF^BQS0CS>E72W4h2my=lpaO|F2J;>E8qb1CpjLk8YIMsEcaw z{k#V1tqT8EvlY+CdQ>TOo!CyQagUlHT2zoL2KAuG@=qTVRe!QBpaD*> zgcy7xm1ao%DV}BD+qSov2<8)9*&d8XmQU#x?+9UGK=aSGBr9$eX_vzS9t}S_t~W;~ zxQA}mRNCT2P4vn~QbXW!+5NM;D5B2Px)Nszf8*hXSY&vG0NlWnY~r*Qgdu-yCRU&0 zK_bLhcd%N#EBY>pJxVK8?b)=7^_bF90jZ(ZCw_#|6B!}PGrdvIUwSYR&4e;3&nWc` zP<)*Q6YAL&LH3vSH7!y1DeJ)Nz~nnDq_NEqeK=`+6PkIS3*5=E3;HTszrn+4MrC4J z8shdTkXW(V6ze%U0qMh3MpdKgV+v9!fey5NDH>lkIrMi#;dX&S;d<4|3>?k3oE^LZ zk3_c?CV-$v+M&FiEfth>Sw~p1h40cOV*|&m^XKC*#Q9IhS)v7>s?hkN%$ktn2Qfk>_+FzlAE&g7M)Du$T;>28Al1`>?%YZ-!J|RN@ zbqeZiHiaajnU(&Hb)D*`M?{abC4NLjD%SQ}NpmO;_ow*DW-PcnN_7>d2$rtPt)l9` z$&diXZ);(jg072_Rox-yimnF1ClDy0YFCBfcbzO^M0O>6nl10Tw3}E5jy?HG2|J;{ z1lm>iteQv9l2gS9gZ{v3C;S@{Fk+iN4$9y{KTHx5CA-TrEtH`xsckGLQT_i{VNt@W z89u9F0(_Ki?TPDOMWB_GU;5V7tzx%4pKAtRdTh&mHAukfDPI@f$3@(AHEBB}iYc6{Ql+!h>D`tWPaXjx-s zy7NubT~IWezKt<|p8jiy5^{&N=Z8Pl!Rho~-J|<}PG9ca#R5x;OguuVM&^#ojTKO= zSf#*;0!nLwk{TwWh$OE_yGRD|1zOAq+#TDi35J;fqTH4VhInQr5f=u1GrR(H>ZhR; zq%-*>6Xt;v1jOnvAMoF;O24j5Ed7hcbZ|GRHOSbX#|M%Z)*Eo>oek}*tx<=5tlfXz5Pax{ z%~wsdDDIAdzntkmnyG*C0G|!h`8e<a9av1Rj=!Y;XB#*x2u9NN+oo5>$ww@pNa$dkVo zf^X58^F3mZpQ5PydT%pZe$!!E6UF5IcKcq8Jg!-@J>O?Vpfj-s1wt8LIPk4f{hm*d)(avH9-HiYoZKQ|56iLJ{O8#5 z2c?ep{G$KMdlEE!9hsb5H=2w*eV9_9r!^wNYC?>3C#u8rP`yiZXcBaJkCq#VYwiem zOKbAM(_&*1BiUkJg71VIS~04KRtgt}i+b!B+^drxVS^8FR4i|nFr3JuAGL?Ty~Tg*&0Te1eC^YpyyTDGQFH&)vu8)bGM}>fQF+XA6QWGc5X~K zXFq|v*f{61Xbp}(wqc4`nT`NE#D}=Ue*?wSH~fAjk%%Jta82!;bunuN^P)d&FQMQP zs?3?y6l`bRbvsP;EPAjPwHZ_GNBZ!PApgnbrj_&^Rub$2L+<`=;nq40K19cJHErb! z{z`6QmKY(oC;1;Wb4-9pyNz?*l=UE5U*(sW8xYYNWuRbQg5><3j=O>|4ixnliBx#vgGD4Zq zBGHpqJm8%6=!gIo8~hm>fa9UCglwFL+XC`jf64O(hv{7z>pe9v95?V^F2s}781 zwE$hU`f4a*x-SeSe36e-TR5RR=zM=-o8ZRG{#Jet3-xr|-9hOPGdo7SoVPx#Fs;0 zcF5)qwhmTWd&&Av8HBe-_ur05r3m_{;u8t_+&M8kU$^oiG`k4?D>>s~Kd9)FH{b8v zs-H|P_~G0XRGp3l`)O-|h$+8eyG{(XUK!gCRV8pV5kZL2)rHYO>LN>~uNnoX&VrH0 z=lI7KzsZEb$QpB?y5IR;!^HaGXys|(xJMycSD>nd72QnzU^seOh4Gk0S!I{^tKP<; zTp(AbOGZMR*R@zJc}lf!Vyf}&UB1t0U{t0}6Rldc~6%8B&u3lEOO zkRmJd=wFtBGfZe}nyDD%4UBIsE&H^%-ZM0Z7SPaM7&~nD=dQReXwUfBd%uzx_MsO; z6=_x2L_gRlI{QIITt1nAUkj%#Lyctr&Ic?oQ+?)lASF?wuCeL~1?d`}lChXTMELWt zM8DUh-~`pkJs;0XImSZvIqLX9S~G8?TIg( z8PsO`^&5ai{iHA@aGwH-Jeoz&f|#pX_^z7v$iGs02TULy0KEd;PN(JC4hCC$oWWP_AlSpUeEB5s(M>C43Dktt?uH!m>xuM9VRf*e z1ot)EFsv!39>|rjbdMSRa6m_5cMrt5o8NktUBeMhy(D;bbqExkF>eXQ(nMW=G>blb zf1_zbzRU1Uos?B3mvDo>Ug5twQs<%_P?1nnZD+p;biCCU)h;_A$FFlQc8Elw2GVxq z9O}>6A#1Gxr=U|(4666-LH!);aWXZ8(kB$u<^m?sl?H}I_BdgOL7p6i3I#KyTWkZJlt4k+<*_J-GGGiv7sc|(_?=5LLHf9}RP4blS`j9n{t zx%-H+KfRC^DWYSzlVZ#0(MH}?Q^n7L3J%+bs;=Jwbm)etKo$Z;l6P5BeFeK?`_UuJ zjUtrm+pzbsHNym*3>LB_lei7p2_>$|sB(7_w2hokaGI&=!z7MA6AH_IP->Yde>JM+ zENcVbk|Z9?caFe4cm)#;bW4%)*AccGj$Ns-n_LoLO1U2xX+=HQW35&$xxs!6CbgnC zHR~vL{qfuR%Ug9Q@{J;+W)>(qxJ>AYqPvxC*$ps8_rsyEn@X!pZW|xoRC!`rFLe>f zf0`7)WGFbtdJ$!{?{05x2_oA*#oyK4oe<|~elKQnkW8KlkX}>oIM-$_-r(Aj?8yC3 zaD>43w7LR5=U`5LE32!&q~aoh5{|Yndww^U+8!?BW%1Hb!S;hO?<_|>-T4P?zFU@n znw*k$y9XL;rhS2okyfWH$*HK!zpd(8+P>K@- z-DKz=-QW{i1IKA=-gKhTd^-;!;;#{Y9HoI!B!~8I2fywwMMd4|H3-pF>h|aI7tl|P z7nCCISDUx7QKhr&K?DWt7YmhzZ+qX0mwhaMmAlz(oLJIy@r;&;im^m~%!LX-y!kQL zM)Kegefe0v(!kby9gmHiiQapc4#HNl@ALKG>o$-8S;$5X>hrD{>>DBILC5IK2*?-p z_O?-vz9rYOhb^Pe&9asLWYk*cD06T-QQ6^0p}G)3QP@)|=g_#FoHP8x4HzEdHiwMF zL3nvK?*nUm4jqGzl72Cw@?6o( zifPGWFs-w1jq*dKR78imnFiWCU(vT-9~HC)QktY4^d@fH88i|G+0sA7KR0vG&JN@? zW<0)H(wE=GNl9o+W46QIqpSpo@lxa6zNZ+Cyg2pvYTBh*W!IJQ;5Di0t3dJIO7;Um z`>ADm62Y}d*x)n&J}YLUQS3)fBut>`wSw}~?I(2?8$~M*j*naKjH?OY4G0@m*(CI2 zN*Mbe#AkMbCcYbdSVVwy=nVsy8x7H+$UQB}UI*SqG0^j8Zi_bKB^`ZD(0t$pWB4tN zgPSj^Xo#_JQbZS!7D5XA`cHU5e@X4xB$q*}{2O0fV%m}u?N0vGMy%5CT7LM@0X3#m zBN${|B3ej!LB>1SA|edG;xX>VBDlj#ba<<@r>&>pojh2NGM z0}JCaTzm1n$G53*L#~qdo(YJ;-9++rrvc4i!@Cb!57aWkXnD<~ENPLt`ic**)ifxqUEN>OZRc02#5NV$vgA?tFms8DIgr z(eSNRwhYatD znhTC*URgH`TA)bYEDd?QPJz{$xmgdh;iBXg|^svE^lq9;sKtZcWELlqz~( zLixwd>1|?3zu%lFqKM?lWIM>t*UfEd{*%S6fbhz|h(SLG1*1f4nkgs+>7nX>w0>KD zbYz2nn7^me2Qh`qVzr@j61hu*G(#0i)|Dp+M@8PpWy!BK;XRvT;&FbUJg~3D{6piI zs9pn4Jfp~aadcWr=@CZNUh46{+3=0bPmH4^MCv?PUtc-Fr+AgvsdJ+w(Y#FH{%gqF zlK)3cT^EKflB|+ds`;*zjnaQd7k5ONeqhaXvf6Oj{(3u*fFd6vj9$&o81+O?DBrOR zBc6HfiEj3=O43@ID^q^;Q*W2z2P7T^r~YTdnX*}q0+_br$E-FRJW_<4I46VO{xF?> z>X#j_Iy?vza+j_KJ+STqQmuO|5|zA`yz^5o1m-MPe$x9t^7mBqDimI1e_Skb3c8o8 z-<)UO>S}G^tVl_t5Bk1k40(-~o($xwEDDL7#3I*#d(%`f=7avD4F+w8Mq16#Q6*(S zTxa;R5(;ade~_F)K}33f#~h33&?#pWjW>}2;s!-B-BwLqV1wg0d)3CFf-I3H48wa1 zy5BIS-4?th6oplIMPNvgCn?ZU8UqFY%~n67$RTIf`UD2w>zA4o1dBjX?>X;BQh${F zmZwppgskDV#J{x;sAiIsIutt%UF3E*r%OMfAQ{s8(|n}hMw45b+5mzcC8@SY5j)lE z#Y=v<;O)gp#Md3}<3zHW(UYLHz?uJw+mPz?yf`iIppE~z+o=C$XJ#FMZ)qBfN1KDf z?W8Hyyzr}x2wI@jKNMmIwPYael|BKDDgRAwC@-+f#UaNDTPVAW1z z@Xxmk!B*ILMVGL~jyaK^!7eNs&ozpQ^!Sr%Ej+-swMebbBL|XkbuWDpSHLIC)@#*a zq2$z10r`4aDNNL$>%K>R!E+<~8)B}3)F&iTraJ@UDnXs|p!=oa6Xt0uSX5E+wiO{5 zNq@6Q81R}HdH)5`VHq?cT=}@$4l^Pgm7N1s_x86ZWyv6h+P*a{S^;)tRPRa1MZvLh zfg^S(;SA5Bia+~>c?BQk9mMFN?aq`fq#OfWl#BqWm1~cxd_6rWWeEyf^B`dUFb1GlNSGg_`NYw z2ahPTa8P9~q*gBi7pn-J+pM7(61`#NwOs?Coo8QdTOBh_^5@S)X#&qvpY%QtmrAz zRU41tCp9#)g|ZXV>^fIB5kr?G!#scU)Z;%P zX+Iq@mcG6Tu8(kz6hFwfN;*ic!7FgTK`!Vu>dz9SK@$Z zolWNcP=jT~r~k9$G#778nDwf)b!fj~_v`$wEys=KB%qC5uWeC`_Gp-4}{fQ|ULpGL(@BU-XNvf&Y? z99k&YYJ=ZyoEn4!w%yv=j{npb^yvdN!|GVgk5d%Tclqr2?x}U4&~si=OUx_%pKpq( za-(pTEFnlwO(-0n=$@lFNQB+XzZ|1PR@apdXJTwX!0s{Qp7eIURx_AMfl0^-#*Yxo z&e#y9UjKNx*)+Ady8WMC0C6G47ZshIst@wM4c6nTXZd#q8C|wa2XHT{1Taf#Cq=L- z*PbtqmLvfGE?s{r-{|Vt=(wLP+T#t6(6c_CZ9r9@K0@7}QV-GJWN^XZ0Jo zf2Wf9M;(tCqE5HnANrHxx70ZTMhoCeTZIUi@=#&5GC$tgtq>j}0aG3|Nqd+*!>`CSl;|AANWmELM!TEN+eyp$GLvqrZ z+spv`#SaB;P<+R`A3}GPC4;dK22-$FWq9R*em1>v{4mRx67a_~D)7f4!sw%c8**yA z@ViItX6O@+fE9U;u1*9=xOKBtdrP&ondv{NsDa%(!|ySB9QSjB-MFRklMm51lQ~^4lT~MvrngcK zbORPwC3-Jrcb)#zKAZWb~s;u!qBAI|S2z^Z5W@6OL(yNJSvYSXXQNG&F|{Z`4&mb zM&XH}-79!ma4AvgYRz1n38;4!a3Gqj%bA{g4nWwV(!>Iqc1GgJt>~l0hin63@fBY2 zB~61Xi?H&8#e&Qd3A4BQ5<}RDe11QcC!`OZnrn50H!1;Ck^a`<*DOeuen}TUPXGkC zhWo+kuO@-g#ir_P)q!Znx&K!7Z1ij2NUw3i`S@+@v8oDTSWrv%+{cA4NlZHRvcW6ektO`%NyB0l#`X#@e2%~2Z)2;aBU`5T%=PX`9F;c zqEL+rI<$7b^x=iKg4k=%N+N!5C5cg|N^kl4)Mqm5N@Xxt?i?|@S(;R$;wM7arDylp z?nW2JdE6%{S_0pafU*bI$VapLz=l=>ss&bxc+;zVlLNBE^Y=QY+_=C>ZIAZb z_(jA1J5a*2-dq;aGF@$ZRA#f+80=-N{riqN9j}4;nN#>X{L#3LKmqSYmWzqvQvVaN zv5uz(Fxfg|n|9zbw_XTKI)KXHeAy@jPf**Ah$)t(qom%nxLWFGLcTK4C1(VKxE*>W` zqh(Z3=W;8+?}}pP##!-)jF9UoK9R>Lr#tF{IHxdFi;aWxo3TBoU)-u~6ua;X`*7jl ze3c0lBh`#{-%zA`zhCYXRmkQji7DYIC8MD!SQU^OBH{Yx*oiY(S-Np!JoZ{IG8aE_ z9l5Kh%ak2D>hO7!!#Fm?SOfkc6sr2;SXRoKl&wKY=6S&W3)~EE`4)+rhjgG~aVKhN zr7*zG+ZK; z$p?{5nnRL=-i2iVCey|z*b<7o%PlC!FdN5MiRLf(0G208H5xqxNDQq?_kTs8p?Gg? z$KP}6EjL>LP>V{CCQ6yhpsr@OSuU@eCw``*B=+@=L07u(L9BSKH`r`>et+*{<~>j< zBHTr<(uwhSBcC-`$;~$=Gkj9rl-tC1H%i(DV?XI9V3KG{l2(Fi5>R~rZdXr9uGVpJ zwK&LFT!hf5mG#`-<)wnz+D>pfw!t;>G-}B#s#Xzal5FW*Ec`9g z5Y8yRYtZF)5Kofsr`#yEVaE?5>q0HX241HRWFwnr%7!h=RR6Z2@X`T$00oS!gP0qI ztWT2_pd<;S>=PXzA1MidR)TJ{eL=6yv)!MHGRm@A0Qny%-VUnHTBH665A3ngAAAB-%B2tyEG~` zACE{?WNS?tF%*nS4Gr&fE2O4*1}}3rXn?ByxRN{Eoj{jaqTLFJZcsuhITpwZ!47ZK z{{9>&RWb4Hj7b5!AQY=utwxL~6ksOTd3}mSL-=c&gwONPjporCKK~nB(vHuW6K`Ez ze3!0fwpQ2Ps!iDB!R3I@P5PK8><_HT?VAJ8m0+&y_B7zO=7~23uVC=RBfI~_*jq(a z-G%MmEV@%dNlB4Vqn*e6$5o?WXw_U<4lyn z!0X?vuFL2}a&WQqYJ&}Y@D_4E$hzKJZ^G)>_byoMdUKG&tLniWIpyr!OtQ|8 z{3kyLj%%Sh5T9D7t3PDPY&DirE~CF5KkZ2TwE$Qe%8T-^q-(N33cV}l|;#U155QIK18K*`0;k?Y@~HQidgpv9{Yckp25IW_oi;zr>*CM8jQjm9m~VH*I?+}idPH4DK;09O zF#kbAb}#fkQA%~F*a{U4y8qTmy~AlUdO$=G1o0A*ER7F6hT~9tF(tgELgGTfjU3;& zRZ|pvD|XRNz+5w0+>~2A1MWc^XPZ-9P?__;V#W!4cPzDn2qDqYLoPA+jQt1&fy#f0 zxtzN)S>g52m=mQD?KcPRm85dJ5BdydabyqywL)T%jcifBY+~+S!1HBs)!#On@yby1 z2UJJUF?T$eRincjDQD^7V^oJVoZu3#S;;Cz#{TviP4P9Ni{S0fT*o&jeV}1Kn1B4W_V=@GZa6(;wG`PIbE((0RK=s#JLaw(24o*8OSm^?dT0sm%| zTGY+v17Wq>Jw&k3+o58188_2240p1yR02B`h23#Eqf?*EuqZzwbCLP4TT2d6?=~Zy zfoS<8BS7YqPe_|*GS&Z>&|hAbV|3fAzpP?qERo9|#NLMerN$>*Of9#oC39g#5r&{{ zS3h?<&19v!`?|W;?=VSc>p_kE5q2RH?O!K}hT`j=bqF`S|1-4dR6!%u%~Er|=rOHy zkD7!_g@R1N)jLh#^s{-BEd#*Z9l>O?Kwrquc2w!fEHSxZSW5zJByyWVGaNbncPA?t zZ6E@t_5VeKfr2RaLz2O4x@ckovdsoBXcJTv-g@4=Pklsp2D=F39<&F@dTo$e&jm*q zk&%(m5RNeen*~RH4#~euhf~SKgmx1Wp>Wh?zpqD-=7GRE_v@L_9a5y{NYwDxD<3fy z;*n59Dg+Zk!~px{L^+Gn(pJA!U%liO;f0-xzfq-X9#B}v=VfBBSKS+7^}HpyFzNkjes zh>isN4GsRy-|PtyV@V>6r-;Lg0X!O`Fw&mv_Usx zj5LPFUmp8(5%^tnI$muSH2NouMz}zkiSY8NK!ANbF;pj?UD^fJzdWBd?vDG~-7PO&cE($Cg zn+NxU?cUk;kJ0UV%UCIba_#!j^mT&54*^~k@u-BxC0WqAmBz&n&>LQ?1rPqYjgRIz zS;J0SCLt%Yq||Orl0DnG8NUXdG&qt@B)xK-k@%T^V<5Vpbj}$+LzF&)v>ZC9C($%r zWTOs=zi3xedUx>UN>C&2V?5=i%k$Tnk-F)%Ndg}@m|>mqlP^piz=?FC#$ZSC^>2}< zv3<2J99`jUw%nlb{^czbEmptC-Qzzuud*Dq1?0I$G8wiK#C`*@4Kulcccu5n8(PaJ zN=D`10JZL>!0LDcG`}w)%5P5rw(e<$jV1Q`EU>EBl2*A250@yf$W5nF_R9bP958u- zc}@2Y&7v1``k_U_osMq1HXJHb2t+FM0{&f}V#KAM5!~ne1acD|?3%>}P@FCw_)*NY z-V*-@Mq%-9(fb*tMCmp%{F+GOrdsE1h!#!1y3R{F7Nqx2U3g>*Hn|y7xYQ({S~wr| z#*AT@UY+b7=r{CzV{zhN($AWL=Gk9bn9*@XSIb}7^YoyohPSQ$$j~GRT#`;kWCu5mBL7FyPnNH0Uq9E1c`{v{f4@-KS-pz_+O zJe{_gxCYTob&yT6KV-Sa`b_>gAgGZ%<{(j{s|42{iQGgI8`z|Njah;;Ao5+#OVoG# z`~dW;#1D$28&Nq4JcRJqeOftH&$bj27ABD%1ra4(P1)$9hi&%N%<|W3bzHcA0rrg0 zxaHrdF4T&eSxJ-9j6SF1@9`T$;>CfZc;r5>ncsb9!l0O3oJaURLpdPZU*YFXal3Q` z1T7MuWfn-*cS=HO%~JUc`sl0bhG!>;v9WX{vaFL4d?4OAi}4KN6n3A~q396|qsdGCBY$GUm9)5?Yj(OhKGO8Ssi1EfvH zLoHl3zUoxo-})hL4v+9j0MGoDT;$p`#s%i`YiL;cJb3H%9%(SqAm-~T39@yo!swV^ zK#|jVtigau#*U%2cDaNtb`m_sw0PX8V{z$Q9tHvh9oJrk2PiGyjaPtA&}+iR>kqy~ zYF6}t&77*#+%6dVfgF-aZ_!{*0W_94qp?5{pMA$U)1;3%Qm*bVsxlo^V$2UEN60)|A(%Eb%9V zsbaY?XNqPywJ7l=O5>?EsS(Q|pnd_8Q@|8ih^u$WcjHK(yj$W8Lm%v5r}Z?p=#F;I zaJmmdN$lhXt^=J+;z~8A->Op}gku^{uM%4Vf*X)@#m1zM^xMUV1;p05Nyvyx<>*^e z7-yjcbZzvxZ;&Hgm|e+>q#eG?Wpj#>opOiVk=v0Hy|I zxDjwn={hNFX{@H|CZv$j4&Z_6*xoK3cWB5%QvCIy<(TxmhCKustne!hi^+$A-~62u zR$|Lj|Jj#yg?|`@Icp*Us${;|@a$6b-gcSiZO3Nzmw&)~#fv@u_6#|A;^?XO+2hak zb4=5BH5;+gSmQX8?H{vfD)3~&CL*uMq>ZIY3M!>Y4BRXK6WWA7SMR*c$b)c_B$pEP z{?%)ZHEj3BnzV_6etYV&_ajJ5-aLb|-l{xyqv@E@Z8_u;bKCKA_PpeK?r&Hv{Ttea zHuc^o=b*|x{ibwyCGb4%){#e4_Rud}j^8V?sbq#cD^&pF!rbxzOv2GVC^p6oRK!jz|A zEbfcCWz#D#CfCIGDS;ULPDrS7toiz|DVv!7i|$1qW~~~9>XbwRE&zecDRBG})2PWR zjG(^8=)Lv{D^p!rCww=cQXkj)NZ->2=yTf%8C z@4eA^FGBflXiEm9_Ofx9+>SY(;FY!XyT2mukf3`>G^}Z2p@*E_r=M<-iqb%ZSNLKM zPt|TsVyjPnmG2f$)GjWt8}v>58$>L8mP1%pHw!WofN6~!5dHtVdW-tj{UFtb%|#kH zr%Vb3#dkz-xNs@k$(O~l&fwlwKt!{{Kafda%VJZ&vSRhDB=ayrVf1v+Y;(4Hz^9<8 zZ3*b7g!lhGgu-T)??uRT24cVtmy_dF7ZjyiyHC8PToYk`Txu5#6y;sb9y6LuHKROV zACNzjaKG)iT7yk;Cr*W{N!HW90w*Mk9yttR4xG06$6PKICfFtqh|*HhGACaUZ?M%J4B;Zz=KSLPONdk?xl2+k1sexnsB}JV)B|ZRa-8z=9Y)a##o^`ShqCgg zAG?*nxZpxq{UfNHm|2Zn#n)OwOAk2Q0b6hHk`~MFmeL^*0a0U5gFR$TkELGj z#qOqTDZ#oBjmFT&Q)>L=7usoq~V?q9-g9kqj{upVLL~I1156Cie*1t^L>9M8Y{fzH}X;d`vhd{Vfv> z^P=m8?^EDCT;9m(WWy{(At)_Xa3oHQw`))qjV*MAx!D6fQ@S#aeck~jgd=N(`YnM3u z25nG>+3cBj9rZLr9)S2U>8QS7_R!@2QKRct|KEY?gBa~gh-l{oJmCsR!YKo7!yY{T zKG03HG+Nv$fr9>z8tp2fsqw@7F|-;s4bchTz}{<+%dzoe^%tARURa2(b$?dV>DY(# z?MYY4b(YkHe)ibRx{PA;r5>W>ZcQXOkux58PP%Y={guHBh#1A7y*@W&y*?L~pUcOX zM&VxMpG)m4S2S8<4!#958XgE!Yu0?1-NyRmI!Pg^L?Ecm@#>3=^AT&znE&QD3cL8r zbZxv78A;6T(`VyHD}C&8kLF*zw=+ZE*QtDE*D7IBDYp97IGJa}gG>5{xt#M?DF#}8 zHODb?0XF>gfzoYKxrd_^HT}+eTW2xG;O;1K)Bj}!`K^Do*yxmxnTMOC{rQo1ZUyJ| z#uPPHsX7r#q&j9PQTr1-Dhr;M$I7kiIf17?I9IrjEACY+MN8*M6iTrO=d0anck~)H zU0aW$b{3oDvv0lf-uQJ(EsIo>wrek!{up$Owi|G@1^v(+@!$Wq!*Z^Q{Rr8Jez-oe z8gp6o>x`pXmJoPgGzttd?SQEMPGNWt%;s-C9j za8RUZLgW@x!+Em#v5rO+EgDSnxiNQiqvkC<wYyU0C;2A!3^wlk31zUSqTTy*+%NuM+N&j zKepM5sEF;Zf9?acEhqj$jVR94+Es?qm2I-?(kUhS;+(PdcZ!f)%9}l^KeR-@-ARRE z9`2n|7zn*$44?4K+a2>GVNrF8EL)&w2xcR^&y8-Q=4{Y-YA0U3O_!~)j%2Wpl@@t{ zhD|Pc?<$SH&Jcv*8o0EqGIgj&c3&zDyDO)fZqYw0_0&3Jqg$x;Epl!yfEkRv_tAW% z5g8~qf&ba}k_-3ybP%X9lJIGxJgVo1hW(>n;m~}A_LUV7ZoLSWdCtRD2OKt7TAYR` zGV92BnFC%W%xZy!#ap;?Mj&Z~&EqDa68Dg(kg@x%Moa6mJQ-3WrXB&F2EPQiT-<;^ zP~1s5YWBy2jLBd={V%T9VGF4fFMy>uklcl0Wtf>^!9US9$$Zj4cae#$BSOt~q=FFF z4Lfp`jtAB~qN6EU2$q+9&=lGvNvi1-)Iapy=Xa+P^Mfnj-$L zpLf@0IRHgiGGRR{icSzjs|}|2Uhj{Nu)9wT62FN?oi%{G)`;i1w?MoE?-W@h8vUnq z>GGB?f2KDT4zYo*u*L>vq)MqTLQoM(sJG`nEXjZ4edIwe3+Z49!HHGq&mBwdZ&UjS zQw-wB$LWg&p7U$p8}%KbGW508B8TI@U`YT<(>i3qa~)fZOSFG=pAGWALMd&ZYE?ZsW+o*B}^2;L$alYHx8S3_g{?IJtw0zI?SW!~qw$=T64 zZwTxh@o&Z#=pQl8q(i=1y&&Z7mf&Xok4@!c02)3%i|7N|$l&*^qx#-|FIQmgJRpnz zbDo@RO=4iNBH^Nn2Ha`9Rtcf~VRq}{V=7E3{=XFD zdLI>%)A{OP%se&v5{%pwAj88>!~#?~wIu22G%<#5?e`c2GO$I-E;m_SuWq_7#mT2NOn)|{AjHgeM2eEiJya-&*|(es+X&t7b}%Cg!5LsXFJ?DOU%eZvuU z?;qz-$%2fOb0N-+6<#5_e4!Jc2Z5fQWv-xIuV}9CXc~jZ619>f1}*PD6G6)@YeCB+ z>&Gv@t9>iie!I~b=$W4uu=M@h^_N&U)xzmkr=#Jq4t5y9Z`j@KypF<2t@!oK5Vizr z+s7MtDi;XHyVbX^Ux9Syn$KdA806g#lga!gAUvmR`lkB++Fl#k}hR&AN)OfWN2q-J0E9_tG0Khj;AUQ14s}fQE-u;F=>!pgA)j)K>CqvTN7Vb%c5SK_<|tHLuQB8`cV0+ zlZFvt9zl0S?8Zg8oor88?Q^QhJ1H`vmMa+h6CuflyF=Q%?Xk>g-}`mS1_CrhIFjSG z3li(k@FcS$gI7yuH#m~xu>w79@>@hy#Xhgy*Qp2n1iYQEXn`ENPW-a2hI zY_2t(N|k;eK!W=?)OWXDEQbynEdw+2oYZ4JYCEmE+$`Sr1V%ed5n`9Bj|Fb!H{DJ! zPiZ;D&b|!s|EQ%_p`0N5PG2;cb2M| zY5z+G6vX4NGg4Y$tLJnN))gZe?KR)dWzW;5VmNfu>i~aUXb!)q33AfJa0A;$5aMIw8S?%yP&IlWL=X8vZ=_K*lb8X=e|uo1vKdrs*mD zLXp_->yqciq1x*Ee?eV}6XX7De|+n84@MSsgBmx)h-Uie%TV!$5_~O%gM&2wb=^@< zG$Ca@0gF1^@r}R!YDy}7AtZVCNkuIUyy?aa(R1f5J97tLcJwbQD3dsA&qb+q53&L& zG~anIlVnCcIC0@+q@MXZDc~4L08j@T;Q-%=ob0Og(uO(8MG^^nJEb3=Ogc5)|5z{V z@c-{T@27l0PVJvEG*grqYkkhnR`je@@(<-h@4Ms77lLrTglo(ACRpvE#1^Rc0Akb| zG?}H>bI$_Di4JR2FqT843EgVwfD=h=EzqjYKQ|As-v0QY-I`;qm4|RGOi2>n_m$Cm zy+TJA+{IAc+!(y;ackkA7QYPnCH&-L@}Z6j-r^qADF4S$%>09{4h3tS;+f{P$2V;| z)N;=Lz+=mH5t?65>eCzlnf2b@-v1_04^DquTP6V(aW>8u2YS(Ry%#H9sB{br6xOZ~ z>=+`^0e8~9uxPd1dqnc9jXEdOrMMYet+Hm|@8;Im?#3r<6>?4{`W&O?yEB10I_u3c zM{X!*!!Hkl2M@HF`qL@+p_w8mebk>`ecu7Qo7q)zJ|mk_Q<;FF!{0akn0DX3nh7*)7u_)2UCp{xS-{G+MGrAR{rjigCW3 zAkSTi5N2%Jb|Yr@lf!7&N&k#G5RU=75CEC54RbaQXI$DW0nlaBQ7>LJpyH6PHz${r zMehZ||AH>(yQu*oO=^_YB7*NNqpOa#d{A874)tXY>R*u($$r;!iw%c@6ovIk6Nn{} z7hn#;DbIMCVv|CoRGZi9&t041(t#B|;r(K=D{@+ONRR&_sMn@uuAe z#*(Y8Pl?xCFs2GTI%->QZPvr3rNXVbBv83j8bmz)z21g66i98qf@!CK%(_V%=7hvm zJ`5QJDEg_=KT}}8?MXxboetpw7LSqZO_apeomzkbuIjm>3m=JR4k;ex_rUS+`1!@# z=3_d1054E3&wS`uT-@MH{4=Px_GvKXaSfAvB1n~7(*ipZCF;O0MFfYNuMUy~9mjK5@)kE(XV*s{e}DQW=gZ_IPUsumC&X7>pZ1vU z&w}ALr&!5r*G8*5P|jTa%~tMw*ZH7w{E_(E`Q8U$R+3uq{E_8-m8}Et^NY``|I3kR z2uTFmeNgRCf!cs8&syt&sf|Ngxt|ZU0Z$UpzHpqAz0U%J6uZ?^*!;-hYY)Qta}*+h zo^X7AQ7t@Gz$bDW*qzD%FZo_ku#en#D2S}Q5~(H6L3U2ua`*+c&$*3FR8`4bg8%qs)i9rd74QsDnqgk656uk5{ZBuL;b0T6a;P}~mo^g^w_C+o9 z`S$J~eD%W@&|XXCNHyH#5cp|2^3OjLM9P?@+4;a04T4Q1<{P-j#?{U7P#^b@$jT10 zzPkkND}?H>9SmQSUlBbllQU4M32{k`L4C_)RT8oR2ynB<-*@y{-=8&|Va(JX;)USv z#N+=PhK@Oni>-2JUWTO_bG-ej!^YS~0|X4}76VrkVA2sNgR4cs8&geIeZ|x85I!}3 zF7?JM0AuX^Fh<;}ZkS2BV71&xqg`7+ywL0&9;be%3x zOrFLMdPn-}31P637;Ae@MF2#z`1xAX#5&BX*ff#urn*MQX z_BLW?u||p^nEdxbo}Xi8Z-&H%`@hFlArHg`$E~7*hW4+if3!Q~%wf}PACGweWQD~u z$+r@;*;EE6d7;)lFji#)Q017?u$$AtdDf*b}^$B({{LzqB^#V?jfT`6^-0q*$K%MOfmm1Tk#Hb@}qf`SZOrJfk z!>DrngBT;<{vvfw#~ByYG9CJ&B7~l6M;WYtjB7Tz}Ja4~&lK5M0t*1HkV3Uy*^uN zjtBeqi96Ih&j{eB4Kt;{B&?)vt$Y}MF1%OwhQ{~e<9cXcssd-xgyi)7vrT^MG~6_o z7TlD46$Ar|Z0onHtn9CGbN4OI%|8^*%KY>ohdJ0^6SoarFifDW_~+0s8-IrY^v3aQ z#=J3@=YptK6|~FVm1(s$0HJ5*WLXUuA1s^9R?n1rzz5{iM#Y!^eY64aD+~{IF1A8K zUy-FSLUN(i+{=(Sa@Iraa>b<-j~00NJqt)HEwSs5u@Wt7uAO6(H`fY z`;6?FnGRxXq?zl}*m(nAeSF`|zA6p>LmD5Q5aR+Z2p4Z2L0hW2+k!{Iyx;w8l`g|* zk&=iDF4dMbGrA!!*Xg58aoZHsZ({b!ur#rvYQ%SHN5f9aL9dJ3TKzZ_;iGE?M?U~K z9n@YX3m;{+$ciszYEu7i>{#hx==cHp@}NU{Flfq$?mj%K0O3l&k&lE@;_#*_YtE=6 zGHYM}N=3*G)LI+RA)X@O!(oL5f6Q^CdD?&=7nIFr2N0c$=f{@M$}NvmTvOin2T~|^ za!Dkke>zF{zcY#V;$HjIoYF4&*S-_Kk!59M_%J`0vHLSZ>CH)SlMKT|jU$iUcMey! zy*k1&g~f(M@6)-RA{?mZNcJ8VU}ZcGe(Z%iZ5Tj=E~!ZW?lpul3fe&zfcm;|yQOu) zD@47-&FvHz3u?IeZF@|9$1hPYyHel%{-M=#TkozR8WWe44xf*pAw(nUHMfVQkL=&; zX=5`boF{gwQY!Lf?x&ctv0;`t7pP$qzRZ@*3R3A|u zc+|2pFT|X4ouXv9EO5vSq|LLGFXK_N&v??Ima13#sgpsB3g>ZvajV}CerK`SvbtJf zI&`6r9G|;Tm0bQ58Lwj5^2FttAf72G^Up{rY*)TX$S^iGr?&bG(Nf5D6qVgAOV_bJ zCuyzb&+wHLL+F&bDalsiQgu5e^=>N0TV_!HnZMZkxeBWr^Zdzst%gU)P1a2uaZlPk zn<0WcLB9m6(|&)$9oaVgwheMP+%;*nH;jn{@8e)DhAdlfMPmSRRJRpjVYqf82?sd` zw^@G$4Qr#+R!2)Ts*FuHqf0z2i4SRP9did?U1A4T7fo|oakYo1tHg ztFkvK;~iZw)Nf&(1fmwbQXb?Qg_74Llj8fKNLi}&=iHf`tnfLo$s*eAk}9VYICOS0 zy!N=djR?dpvTTO&f>4OBIlB&?X(@ymcsGRa3NA<~3cgb(aYr%7sGF8~v^dQn7jk-b z#lSzCs*^cBC>di zoQ?#aF*TdrbAVELE|Mbf?nvAZ^QE(h2~ouBJOYcq+^eB?{P#s(uEHoV9pk~K^_rg=q>ylUSDT^q#xH=qETMcxYyA4aMS7lyRbdh9qh>u z7;m4-<~|V{mufYR2v4p=bPtHnNYM(m5}=v{BDzG&XLMS z|2;>>hdWJBFC@9bp{T$w`DVi4_JeZS@SbC6hzJ{e#rhvUd{J!n3o#*g;orTVI`U1_ zc787Qr~>E)B;IqZksr|8@Zkgz(SE9;$ZzoBZ2Xk%>}Le>R4f&Q9Bd* zF8eA)Y}5C@m1Oez9s9V==4x6+wW!5SQkFz-))IQG7r&35RREVu>*REf*4^`#^X3}+ zza0_kSs##>D~)@ekQ{R5ulDjN(fC^u*+X?Xp5JLDU<%L;5;MJ6A+pd18;Ji!g1%a! zBoY)C(Y`+jIb>@W$8FW;jLBC>P1t;9n1xBmmYEwtD%@*?EJr{S=m<^QjM}(*jSp|U zBc!lL(#D4y%RzpcWZCB!3QRuzmA2%-PN#b@Fpz+G!K8|XW)VhE2{W9Qx^%s&p*-!x zqu;Fi_gy>R{mlzq!>+zXtL7>R_cyMJVWzWKg!^Na9fG6+Ve2pLFCHu80u90t8YRb) z!$7X_BN-9L4jxM3dsIqptNKS>PB!DYLMvp{cAqMz&RQz8CW-lbz1+i3TWZF>+9fc* z(`6JUZF{-U2>`D{BIgnVHES1rmM{t#Tq;*++DZiFT0S^#Yxou`0~#m@k&ivGE~28M zYh)xg^YsfSx>9Wr2hPSW%J_B6alqbCFU6#304O!;14b8^nzyfin8>@3DdHcaLoq!J zD2Gz2c^H*!VAJUTAVoZrP~jG&6BC%clRX6s{hfyV{--bM7tnvU)4pedH8sc)9bjty2dNKDLB)sLscP5z)=#2+{<r@7Fb<)$o zh2*%8|EC44P{XvV=KwxjxH;J8{)h~Mf$-QSvQye)PzFZPpyk)@7a=>Df(5Uih7b-V zU|ZBdxQ1hKc$@C(ELMzuks>f?YQSL%3vMl;1%G>LyvkH8owbX^bwI9JfYpty8c24x zTacjZRmLP#%lN{|s3FW=K#C!IRS~T#a8|rs)mm`$T-T(F;Lbl!E>YWILB#9Lp&dE2 z-)#9&^|x|`HH!y)6$>v z>i^eb5JI?U5Q|{)nBahJPaTTOh;G=}CAoRv0!_R2Tbbt_hB)jsb!P;rOBfSKC52pdk+!hDT4_<6pl`JO z{iMb*fxEx?78wDi@kk?Mq<20B&ro{4DgtPt@t)EK{0gF?o3#DZBqZdEisMJ53B&}V zC(6GFL=K>^E^j4HCD=zA!R~$95|r^KkuOcs`h7|whmwUDGH+{g=}JP1_-xyIA%xr> ze+p&yH)3OiSJ}7 zjVnV4CS-ViB~=odkyPpo3b4bRokB$flzkId_LR$`WPZx7(XH;Qj}=wI!@4aUMo=-i z%$f%TZ-3PL0#Hv6K>4Y|Jd6@~wX85o5ceQE4e;gDf&N=!B(w{arc3;4B=WUhVYr;3 z7T+V|?wMb`(lZ-5WHV1ghkkO6k%v&q-BNz!C-huQtvSC`IGgQk#b4;`;@6LEMx;KE z2?`0ROlb3R-PXjVMOhx))mi-E{ctUbU3clk zuYh$Gn>I4af+cA>9@e~xd=iT;Bufo-ovX2FKTgEqe=k|+QH5*;hRyGpismW?mgtG+ za5*pPmeR7MWhrIx;glf>iA>?Nu_;b_Lue*h^2r(<9JQ|OC#-@`2 zYd#7l9r+Qk1Bt2r&5m{%!=clkF=vLgL^Qlnw1}BY!jjzlCbsZf2bqa^k^i;-KM#WO z_u>UBxqKP+g)?!z35tUAqa;e$8J$I0tRxe?Zcj`5_7w!_6hG`^O3cg%nXPRCWm28S zJ(JfWF`YU(ek4WF?ukuG%UnSVW!}(xbI-!T=ropUTNN#RoIGzsIja^Fx{oOB4*jc6 zfU$>Z|4@m>*%usSBU$(A#+#2?*KG#xACj$-*rkc_kpQuASmwO1eb+<#=Eum~H9~Q?a;1U$vrLa@?WoTRZD(v#Drg+E*SzKfk)N@G8s-z_P z4KW(gIEU-qKQVUUFmf6#GrD-3)6wA4q3={>=K3QUaXKd#c0(K(q>~c|bim`iUM4+T zAnJjJ=v7nF%9icIMt15gtNo?E%sV63WY+#1vV=8V8kD|EayI$%{Yo&B51Mf-e{Nku zF)tc=VxHl^Q&{S6#rFI@#q5F})o|(2e|;S3t#t1A816VCdpfnmgyhb~&ZUDn+|H1N z9FgV6tWEqj&mo`uSAHrZ4_{+d&PM;*qel}!fqSh5SzD82u5=QR=Vqu*{=Rxq&(&AA zK4YF)O=;IO;tLAivt)ndmoD;~N8Sibq8>1yYWyz?fXd7oA%LSPXBM*r92-z!eRV;o zaHF&@#L1phrCMsmueWn3XdE{F@~MjpSSN;|C20G&}m9!N`nzo3zv)nvCYQkEcdFmfr7zpaIc<`Yx5F7;c zb`^aLAWP{ZKw7-*WMBwMo$^mNUdQ01N~u=MZXKb* zXUJ!{dq@%C&LxS|Yv3&YpGZO)8b%){eH^SOfqU~o2RlWXz5bSuZQiGr>HLrQv&g@E zdl~J#)E_FA?3D4&i^>R)5Xd{;(#eJ>Pg4s{3O5rtH4TgC@(0M+GkC{#4vN%Kr;$VQ zoWsdTg!4rF^a=f%pgTcjI@ZOuzDi>kWgdLk$cjT|-)y4bU#lQ*FcRbyWjE_2V^7|`Bs*))9?@cIg z2R#xjTF-Vp+w~2+f}86-!gswsm5`n{5pS8yJ1=;wqgi2%cZTIPunN-ca#bNF=HV9Os=%Fc2a{A(fJ3Z<+dgiiJTOwigZ}pa$1%p|B)p^?8?G8M(7c{Zq}-- zL_hG^(xa)~L5EUtFuV5)$AirHi8hgZ!WUZpr0* zuhisF?_(0(WPMn(Hi`~0Py7c_mNm|_;Kf;=D*QLpPK>ytX_&pf(y)4wv*Q-)Kk9lr z7@~UKExV;3opNTXB_Qv+A>kE#G(DwX%auaK>G3AYV7&|F{ena4j>L|f7z569zHv`V zQ!;xxPy5$(1H;Ywb=h`yE1b*Y$#?Qn7>~NmDJBl|-2RXbc0qN!*;bDb3cH=v1h5&W zA<-!S7yEheBou4#*7%dO7Bc6-^;erNzndPvX*=IzN}U(a2JxJTpD&w?Yf`$@l`=;N z_H_3P%*KqYpnk6H^SbaX3Z{+TKcMly(Esc%dBAtK$|C;BJk!V3oxMc`r?@J=`kx#I zzyaBGE?9syUO=;%Lju3&Tow-a!oh;^?F!hP9lWJO1`Ov1T{jKL%2|r~80gjlFe85} zY7nlY5lSzGEr%pe)E9Pzt8aT5TDT>yZ)2!Jk<&Dpo6dN)L`RwT?nd z^aST+%<;3Vkq}Vrbn}2J4JgkuFEnmbDLvIQPQt=nwX^&xL-#jPE|I@?Cm8L$OdDSw zhV#{F2M%u+JDWon;9#dQO@gD6>$nZ!YHSI!z;@6k!XT2~c>SiqTqV?SP zc6*6MEsg|%sd^yeDn(ez_PdBzv4%-qT5juVI52(|FaB)fdbmk;` z{7BjuSxI#l=;?W5MNO;n`2C)QyaxuNI(u#L9~XFYkEhvoNAh(cM*htKFb2W;bz8Q1 zuf;jbu`^8b>l$JidF0ZglrZrFin!(#-srUP=78!hoCO;@?4Ntlqpqu`Q!^X1_tR3l z)1Puo{t@1U$yMXtl-HzM64#y_u&Uo21asUrFN(LtQYZ&mCiUvtHJ_?CDyTC)gI6Xl z=|<#9GEwDorA<{v3xK--g<_4@_4zaR$30nlW%01~wt*h!<7Eu-3;#a=YWEHA<}5~; z2;j7N-H9UwBzG5Ur_OBsexEgG_d-m?`UmvZk_1-5xOcKcIk90WsjXVw&p)D2AN4>S zf}Kr5-EzdC{XxTH1xn|#TiWxqyFUdn025VbVN&to%qniYT?|f;$|41_Peyiv1H85D zFQJ6*xqtBDc>G(5J$20p(W^u1Frt4B*8=eMxo8Hlftn<`1|Q@zi5u6_+YkRw zlI4g7&%>oY?4(WDVdAr?0n+j9eOMyJ6(*8RZ(pKTaqs*Y2uIGa`@_f(v`%Ao9jNYs zs`wgvkU8Qs&X)Uka*JM{ziIF3)x8XROR;D@UpK;MJx#d7nAGDRvMCVJN3ulf!l^WG zKbCYzpqvzzH%0YlX>DFxS&(@jCuE8%Q6ql}>G`X<20#o9{7PY9#N2@c71C4)s|m ztJ!lNT9CGW}%+Wx=9C+O)z9|m&)OBRIpPDdoJp}Pg z1A_3o#G^da@H0KzvPx*W^W5#et}P3NwS6iM`7oYD5|&K*i6gX0uR+0UyZ68i^i-m~Pr=GI$cZ7fQqcqXE*sx$CvfWJ?>`>L zYcrs4dgg_PgORxOQmhMV#2QjLg^8uC8x4Dpv;}}#Gd@T9ck6z4>o1?u7-QiZjF=so zmX+JYs&<*?ilM0H=-%asU*#ad31VM2=#*ts5eC2Myyu|+PXZo#f9U>09&r2ZfSkrZ zK@tSMaveLAo4J_d$cRJ(Uk`UwB9}cw5qKXdLYK$kTaY%B61GuXr96G$K5eA0BT)}S zk`^(_TNuT4FB<*JcplFai|x(FzM)u6MD-V;E$ur743W`Q1|xnKE)e2LCdF9ij}gK2 z+!a%D;nwB)dZ#UR|7tAcN@}KxcjJ28vgS~u5G!WES$InL_Qvo0pL{`K)4 zZ7&i!k9$=W+(<&#v$Gf{>-i=;3bPL126Vm7%2BXoo=X`s2B@ByLAeFv7Z#%p0F3-< zTJ|LoH7vn6f$M{ZQB$A`YR0V-Z~LFutdWP;qI=WEHpPQE!9}~D)2n=jNrcX}*b;sf zzs6{Z;Ds!!AS0^AWmpt=Qk^xEqRI>JF>Yb#jd(Sk_n7PdT(&1?B2CNv^(aU#90$KA zz{W+NB&K<86`f)D9bkNsW5STdyQTd-20$=XL47A8~!E`QE8i+*EAy?thWfLSiX?N=^41f~0v) zv3b95yHulQ;ryS=VZ+E#pjPWb&6W>sZF-(=!mG*_%RZ^8at+@C!^be3>23!UiVPta zOJ#$j>ks%dxkcmWTd=d%9aI6k$?gD`}^{nGsvN^gHPQ-ojJ<7!Mjfx>q$=K2+Qed{T`oFyb*i&2jc2Vhfh_S!Ss4g|E5V@PkyIM zko9iCzTckVE2XYT8R1lTpQd@4DTC?x6oaW*HYIiNedhg8zV~_~gwQIg{(jrl&;KZ4 zT=tshy-$Z0!PwU_2I*;T2I(1;fadcTnuhLoub%4F2ZZv;oLkK!3%}#aC^B{p=~k2b zIXJ?SX^r!f>P7sa<{xKj*34z1C*0FlrwP{chFIlpJM2Xhf|Je}3NANuVVenqX{JRr zGs1rUyV1N|lur_ONh&zAnbnt>In_z5CQBjLjDurgkc#TM)fl;e zfTXE5%Td^!bVo|~?c?9OxVg5>cF{f8Zz!IaDM zxy!Z5#=+aWrAp;hFVeh>zP28YcWt}dsMp_WE+o?U+lGLxVY~ThaVQ_ehRYvR)3WHk zqrod5{W4-vUZ}%_rvSZV|IhkZ2p0+llzS-!l`c64%UYRNLk^eEy+2OVDf(9yL&ry` zUXT+mvC(&RCBMur;Fy)GTN(_J`4K~4r0u3MStMNmplP!Cbx18dN zTV1e4cHg1peY{pKDsGO}>5;?KLTV?!lk&;q*i3W_jg3YL^%n8nBO!e$DHiZ#&UoP? zzB(Yng@PAKZ>H-G&sOUyuQ`~O_bGXa4Wf1#{~bH;WIUY~(4li}*kK}0?~%q9Q5-i3 zCNar*b@qAP<|p$({EN>_UO(e&S9QWXlMtU|ogClQY2 zILte{C@MFDulS5ch2jQ4VGU;Ur@^Il0+rucW$8r>a&qdud;~_+(s9z(t=;6cn3ZT; zpSDKnkA*6IpIe`y@WKlOj&Y%T#Q#UvS4Tw|b^XpTG)N;2qjV@G-6|m=-JKHB-2;ep zDBVa%cXxM)NT&=95`&cFedhhX@7}xCUH31a#R3`5v(Gtu?_X@Q73s?4o3gUnj~y-- zomJ&kXa4ku0&2-eGwjAEw+nL|+qH=i7n=H3h7xu{jb92mP;hw~dA3;6f9pk1ZEUkD z_-}8s8-LK1P@p)d(5_s&s%5kECkw;DJ~o2uYd;~V(y8ek z6$_^!pj#<2pq3$6%Lz_xV8g&l;^Vf?r3E<#!cy&3@nElGN7uZ9-UNQ7@H^FQce2ct zjP*=rZ!$a-TaL<2n=jBYW;Zcj3DdJ5zcJ)J9Ic(ua;QpLHd{Zmk2@Jbq?*z^V8C;e zu5{Hq>@6#b+E-L&bd3VH54Ap4kuDdnRK@yNnUjqL3(en;`c$^94emum|Gcqx*sWK# z{Uv~xV>Zx>NmWJ_pN}eFAhi-0cRZ)vHefv;HCs7II|MMIG&I3*h93=VkaoI%V8AJzm41uiC#ktrt_IvCh2dx+4dR_{Py{pamn zG*QdZKy-^-ZtrIahxj>05~IuuUA&BRjXSRH?W_DcI4noUw0&2jh1m`#)IK0jN3BlB zf>@bREeB@g1BWGr`4G3@n3wA_@uTTskGhYXbMx!9v+ngizRq3x4XfXl@HSt?rg*Im zpYV1G-L09F48*j{5FKqT#cswj`+LJ9Z-)KmqwlQ?#Ej1(%(Mbu-7Weo0p707<@f5mKlP_2uK8kiM2?^1S17o=NQ=1Zo zK+r33#Z~$(TJ|CiYnxQF#!XV^8PMrh3U|D6kM&C0D*=h-?aRZPi_zKJPQTlWQD7I$ zB{djutgrJZi0O{11lEntmWG|cork%J#|Ag6e}e4{0=W>Z#!W{4F^Lm;+H)@3%P#}7 zEbloiivgVH?8tM|4unwkTycmWqxn7$dn~P`x@DZxaN|+h zhK0z}#;g&}m>~vPosB9Zg^KJ6v{Eb`ZZP^aTLVml-Ka}mdq#~OR*2q)2MYZUu zPp;Bg0>21bodVUl-t8V1X!A1(4^qC9&TaPY#fMrHw zrBajJM#WGGe4fuNLr57xGq5GO*@i}E_D)>3Z;o!nA7}>|ox@uUuSzJ6j^{SN8T~Oc zAm4Nv2S#|tIaL~o9o_k_%zLbbS=IaJI)@Lvr)D1VL4OY4@Y=khnH8STV2R)4mg}fF zw)#^wzd>j{1iUzhA)~+i_;#qzk%C~V_3Ocas0g4_M*Uj~H`6UD;=pj=cQqvxn4^%! z%bZzVmsvo;q5{JH;Y3W&RtM)EhBkjmETqvLeO0S8YE{Ckkmj>&j|}I_rd6w%FMQ(n4d1$c z{ELYg!tFA?>pb=Cb0kk&&#`Lg>f-PBe`DyI%7jl(=W}J~F)VhKti^ikU#=-TdouG7 zkFG8|8)@e^%%8MQLbAdq8>uce_zop((}-h{d{(E9y=&>4)6o>`DfiL+rjLJ-(R$&$ zBTEXkzk;b$AP%{>y!ZFBpKQL-qm@&KmZLgK8rd{Lb)^frMDlQfLb-qkpmr@xVqVDp z_xGrRK6b&F`H}AK(u_NZM*F<^&;CAE99KTq;YoW(*H?6-diY~atENbLfswG;;u=%R_QS4z=TBkt~o# z7hP4K82_RNSy%+4aWDZ>p<99%z|N1~b{QlRVdSY#H$=(&KSuRfkAKV=&ke3c;JsRh zB)nq@3+lVp*YwH1==xCT2;(dM(mdS%5FCU-mYQ(U%rS&^YE`UGE%)TYW2xmqbb#eS z;&=W;K}sAtQ{)~>iG-N#DA@(U6iWOJ#h_U!M#Q`L3AD?*0oKO zU35nio2t&-^AA6~Fs`EBWgG0dTZ@l)V$KraNWPm`!@(tzn38N<>_$!U-sxSOLi+<8D^SDj)g(jtd4C*H8E?K$l!N<3O36EQLob7zugvFj; z)QlRt=5-GiI{n+k=%Hhd&$=QIgHOBk?~XN$L^YSSl8-d>tM2M_Wb@WHKIsltbqvZp z9B3z72iI(+y(rAn{hWCt_CBaqtZqCu^JN}OLGdHneX$|A^j zQdDll?0CSm-YFGq@cUFpOh|32MfEWQ%Ous_(k9SbMflvk>N2Xmg;S!KORV@*wDc;D zJ>i_6L555;Bt&7$VEf-F^Fdz{8<+kVg`OG^(51{lYw1FLYtt64jsbgbF6T;$lK6G` zA0mdFDjF?V)$RN{sVarjYYZpVw**@pKkcb+Q%#T;iSn8I>K+WMeQ!6MH4?~=9rdZ3 zNh?&e>_|GHD#`y+o3zXtxNa?$xJylXwAS3xUGqj}s;7lb!Pc#9_Fx=&Le3t%d@QGM z@4u;?Nh(wb>*~fT7_cJR`=dt>AP$`(Yl^^k(Sh7GU?fBRtIn6tcLG@NVWOeY?0`&C3c<5 zXg8N?@5Kh%1=(LL({xuuLjvmi4pCw4w--G}l?MtJs8|n8-^8;L#5!oeAL*;(u9MC< zljd0^3dcVreL;C}In*g$f2kSJboOQRL}T!M@XFVM3{2^)+o-W*y_3Lu;=_(>voAIc zu`801=8@=H`^9AT>@&|#c(<;XAZ9P0RC;FlH-hSj%;Ixvcc?+N!_dvIGtBfRA zIsb=X_2x-9xOK&}3bo(h6yiqJz-;X)IX;q!OCYmNm2wWDNTs!BSkNY7zP?^C*T5cP zL_n}1VfkmFJ}nETr=#6{VCRrW5+lDUpq(eWN8n+PMo92iWY|$x2r47J;v%W2yeF`1 z!KXU))_o+atO6=w=4*ugo9vb4Vr9yU#S8g&;AlWG5N)O{Imd)E+NqupHJNH!LXy3Y za4C}3{eEKKhpvFyOT1{aFiD2;>AeqHxO)&8$>7Joq`Ehv9P#Y|Z}z=@*U2PI(tVqJ zQ|PVa)>Dk5p7oKkqL6;Bboju2Ffr++kM1 z#VM7HQgq>4g@l`=&4T80YxajlvWly-tK?X*SPA7cdeDk_c|SR+PG4#yf+W}K^Mj+9 zH)^Rg%vp3uvAw2SCu0-623_DOtp7hOG!PUW&vhK?0lx~f6LxqB&9vQGh?r00ct?mk zR0x6Fiv7-UN8+2F`f;}pc)}>UU<9D^>CNx#9+pvC1H#)1-OGT%sdfkNCG-Bb+SG6@ zB0|(5*%=jSV)jnvp#<@oowsz)xa{eFy%&d2{}l@XB{LkD{$BbhNquN8BHFw4l=#`o zLyEr56;vee^32Y@*81>lkw5pRVagZL97|Q6 z4hyr*+T#=D&`Ev}^QpN&2?u)9q2{vYD9Vcf^dRV4-oCXAgwmY{$DO7*@UWuO-d-lNT?102V*Ihkf zyW~QzE(JpmmAv;nQ^|}leDd*6xz{wtt_`HGB0j26InH~?C6=YY!ouFOc+X zNLa@T90VYPu8=MaTt{`xoGEef%6ZSjhF2Sx-(6akUF)M$i+&&|#f>b}!X3UD{Y_hI z?03}35E8rydOY7_oVy(mN8=tn@1z>QsQR6w5e2k2Y*i6I4y1D_p|L2$GrQ5Z{|Qte z&uS>X{y-b_4f!qKqAKQBz7c}9K;haIY~BRgC~#7CE!4nu2fxEAk}oP}seUJ|$4 zQcW5rnV!ZcT$O3T|=p=GAPsQ#r8vqd#$mu>*y682i~# z*Qx=;tQW^*TY!r3B?Z??N}uP=Dt^NBH&muWE2Cjpo8D<9(M|1>tPF(sdkY)Y>x-%v zEyh*<+G{^rHUW*(^nMPpM?VF8p&6MKw|qurQQg4R(N^IY-iv}QbrHpgy8g>y zrmr}Z!T`lPX!xhH;Cqg4&tlG?5r!pTep_ZP+$zf_;;1>e*(mYu_FFV)D3?7vj0YgY zcpihDE%)flV}6rkQq%qYaq4TRy9z$J2uvKl6IRbNqm(Z23p$ zIJNf_AAQ%69JyNf{yymnA@U+i;725L*2jng*1KO4dK)jro+YAj(M^SCc0Bvey+e`l z`5QWY=#$aIL^?H6{7BTQ*~5#`*T)zIeHRX;XU}U#v&(Cl4=xHi%Lh)GFWhfpZL|_Y z-yz~8><0c$x(bTIjGQG!VY&aE)b=3dVPp^HAlGO(4qIQXfz|SiKXis$CGO*n-X!|?|wmN-b)~Pv%Al-)kN%S!2U7|}jq-aq~;BBr0Yo;Ic;P6EOjS1b$7;$$rXK(!LLoH-URYt!iv}~s@ zDVk^qVi>&DA)Zh3i%a;hrPOZUws>+LkOOj7Jtq>u@un`49lq5OP*h*#dXfOgVt6`N z)zsV6WgklASiNQWkNGen*+U61WxK|OU2Bs1O2a%WdPCN^#QPTHxd^lJs@LB?4_ub4@iHSmJ&}=YoU>wHIK9t2(P|i^(bGpriz?Un@ZBO3Z6# zECGbJDMB%MMlw(ACv((I^<*k^57xxv{QBRY5qcF`AV1vxc{(4146-C^@Ef5j6Z0T5 za+7hjmTtRA5fEH8z2GCmSm%m>jjrjD9{b(z+vF9uI!2Z+7b0t{@4jHYQ@qNpm!@-2 z3o^F-=lVh@A0?(HlSM*dlUcE|oRf2gXoa%lbJ=V~RTwikY{b>4{2HOGDP|FyX49ajiBO$r=+N2&v6S5V^bp0 zd+`(HZu8Y~j&fak$vX)9-n(y~nAOkg$6&-xY61fGUmaduK2@mJeO&KLs^5K6|v zxVX-!B+UJ_760$7uLwcyy1Y!Q*yF5Mz7OIpVGoytfQ~KCk?$4s z&t5A(d*T@>n!?gv&VlRjSRn8yYkW#;LOr%;DaU)Ry`(cLSw<2Sx?OTdJT?S>49_;$7!poW@c5OVLudTps zPmacMxraiW5h^pS0x?^9BlAol7M5x`UjHmRI;a!&+lwbQ((E$g#OmOuGSrzv-Ol(g zZn)>41;RwY#dyEVntKBn!4~In;tBkYrW1^|UEl>#_0(PzK7A>AS511{y!zFy>gS=X zyzOS~^CulM30x%{k<;F4)wEr&w=OK%SJ*VqT$d?Jtyr)jfkAx*M?N*0bayIaC)N}f z(|*e6xIeUv@&pv>4ZiWPH}qS*-l6^{uNGVwCjZRunndc~V)9Epjr3H9e=Z7qjq#ou zolDDB70!|?Ry4^8JHpV(ce3@SyudkQTI8LuEDS8fa_en7qK^>B2>@e{s3RZ-8_wPx zoK_Doef#qEeip=y4Hrs(%j^gvFCNP>fU%mb_2XD#3qS(Xlhfgta4S~}b z-|%C{4qglh)a3WI70|n||FK~Qi0$>Nz9>sLew5Jzs1T96;1OpY0j6~Nd{m~PPf4gk z0kjp*;XF6M+Y{P%t&K|<+eRaRv>>Et#~Iu!p|P@`IO~uxo6O>!_TO?1$hG2bOK+>Y z*0nEqCBqThNzfasE>w!)&ar6J2)@UtC3^8n!Q;5Pmv3ID_TRpg#?qapXJofHXRA*| zGBAM;oxGXhht{#GxK<8b*$?0P%!amENctHXqfOf5XqRh zpE|wvJGKIGkv#Eopj`U^zCX6TjbZeK>b-ScP(9T+w`kW#R4Z(R_# zfPtU`z>=+mUT!{D0A9<72(`~VAUI!b%G3%<=wW5k+kpO7_H@$$O6l`N#Zu;v(`hKl zvUK(l4?_tUboCZPla%ZY59~~N=E{y*4~0Ad{Z*_vC4SjFdonlrREsGM*7Df2J;D9& za)w+>z4o246v)P&ngOO}Xk+PbT&WnS1lSy_--09->sz*PDyV*f@stJYH9QbR3d({# z)0Sh3;+k3{TFLGVa6ROQ?N}yFK;PRKpbmB?{)=E)ss=7GS8@aa{(p9EoP+dnb1@e z$sr0sz5|mG6wmZj!Vt-!F>{Bqx%-D zriiXtq55jevVDgs6I=V6*23jht3%Ddo1^u|O513oQAzlkv_&iR1>6uP0mDuW+McE0 zL5yb*H@+gN$n?`JHHbORx0WZb?5c8a@J2G56hdD#cb>esNYUs|oR9ect)+3cNX4x7 zno%uuM@<*wLo$^z=zcjA{{%Y=oS#kop`XvtA^f^(W@c^nr@;qx6nSxoQa&uv$3H^> z2G)byyP2UVTu(DFr*XZ{FV4?V>3(C{Q*_q^TFgYlPOTZixH}9=X{qMTp#I{IBdXlg zFBtP$Q!V{ynjjxNB&qZF#vG7b2Z!VPo})H^x-!679uus&JK77mS`IHm4X=81CuVz5 zhC+^wI_p7{6&Li=TQM4M7-a6EfosnC^OZi<0ea@xURmog1yl{oB4xGN<7}S<%yF*_zJW^yrT9UmHZMqZi~dpdQnSvCw^LUzxg;*^Pg^+k=^6?vI8*QY zD5aY~(HdC5I#rtikCL|l$CB<_g#WLr_MymK+vh?vooXm2O(EgV^9btSPD0nf6nAa~ zvt_b%)3v(F#dZk1a{u7_G0SEE5UNjX<~8Q%po5+9hdMw6yRuxzHnIRQqfcVJuDJUa zR2@=9r(|(}&b4eHX69~MDP@z7^bwaRIV$_f`ii+65a`9lhG$VRb^6{O#(HVCj#oa3`1P}PzFXhRC=O`y==#hp zCTDx3lX|~O9oZtuKw0bkA!;AtaJfXQL~y-Bb^FX;SWSy4KWXS-r6hwEz|%`U)~d}V zsdd_5Sxd%3B}x;(zp`HgC*f@nS3K|`Y2{}8Xn<8%h=asQ+98jJ2E=8ByCkYgN}kSu z8GH;dH3dH<1_5GX@Dxq)KtENwn19jBWPqkpf*&sF-)%@Vl_pYzaA3T z9@+-xHrrOUpUI!XUfbhP%h*$q_Lu8(&O-XTcf7Qlv=3NAFs zJPWKKzxK>Rw#u`9#`V>Z0S6h`MX;nVFhO2lN*R+ePW-uCyS+*h?}(moVCNt9wOWgN z_3yeKJZ1J64I59ZR_GY;av<9Hq%&DOi_?E68{k5_sWf#nk+rFqrKYT*;J=r9`C85H zNsOMWmY36G$<~=tC=;K3WQNmUC)_Wp{;F8ONL4S1Q)eAcPloleq);#;DC5k-`Y}Gu zgAw43QvnKKbp*|G+ZUvOG~7=`?hX>y9S=x`07=$7`$_+Q$*zyv|4vqCM7h`SYQR#T zfJ}UOSi*(AIQ_3s<$Za;8s66^?D-{-Aa;Jr&Px5-fe}0-zd*^zNruh;1J~J zL0%2rN8cK@piVw%82AK%j~3tF{$IRsq_jvYt5(EAXJgH`!s*st3m6unKj-8f!4MQeM7yb?sJW$Lr4bAa{<6pEi5|W>h!e&*^AoqbKY{V zUMw~1E;jPJuZ*>qa?}<+T@wBk)ENb=TssTZ`rom2v!3a`RPXvx-RyrU}0hWl7m~jTjZ0RSL{_DHvl*@xvk} zu9chn(!8DI-Xed3{I4F@zZ&K^$p#<gyGf&S{>?3|0=#^_fK*^RIB{ z2cA~j1ge3k5KQ%aB&Z!-j>Z)yjmbs@N7eBJy4!wtvpvXYc2c}c_y{~?zIdM|4@S3q zrm4f(aN^!o+j}sZTyDtjULyItOK9DaE0Z`Ehwo1xJn5D+C{5Ht>%J zyjwTP!y$IyLu4mv!7`BJEu(S`F6pPM`!w%GheOWXW?@h0h`qPt9jT`yDVP;tQC)|5 z?{gP9^-wKFGH93xCkM2jWbQu19I&J%aes~3S+hO!45yDGm=iTpH z=s{*2LUKsCdP3lt2XJV1(clEm>HrS{PpeuBgSvyihsthAwcp^e111_X6>(PTL=Z_; zJUZ8UQqB&=IU+~B4ehSP$LexouV9Q*!SRUY{#y&}24xR?dQ@rIN_{etx)C zoh5U47dEHz-;Ke8QBQSLC56Q{71?QB6=6esP4lM4gNPhJ%YV4=Y>ft^{|)tTyvl65 zRTg>pQslho_Gp7$rX$ngu`Bi9xUh346{_m?e2?zoUl-b-_sB-!`#+lNMbBbDFme{( zD5e_IudUYHHFCDkM8mZ!4O$*Q%|^dF0Le0#ynJxT?9Y=IEDhQ89hG6nf^u4_q9oXO z3JF>fiHUBW#%;b;_@`$ghz`7==(mpm{r-Mvu&V^w^P1g+=gc8l=r`Q9&7azD5d}}O zo3B>wMu?T$D_mxOJ&SNa`8+aSOl}<>nTWL?E844;rER~X$Ud2BGm`uP^;uO-uR4`H zhy;`tG9zLc`H|>5+T$w9!4BJ{`kN(1Nnt7#QFNT|>bhbD%$4NZ;%Mh)6k!j#~g!-RRX+{^FHtww(057m*0G(!=EX!v$~_ zaVyU|<8pIiYdPpFai3t$GyMN8IR0DJ4kI56wL&pFFaw3gajo@A%1OGPlUki>X2W`6 z>w-a;+Z6H6d5qwUmcOH0ZYz8f>3~2zE)lsPXG9ptt0f3=>iOS*6eZh;kml}0uZJ$( zuuC3vphWCE9w6mE9m6wyd}}2fwnTWsQKB6uHaVT3+^8|t2O19^qpwUx(G_pENa{$S7BNCM@(M@W-fPnSw6E zRB|w1h>%4D8gR=(pZ$}Q9Q58ml^?XNs;itSh&bw{FcN}J5-@PONTR|Y#UAsQU%h*( zjOMiYnMw(mw((?W6U=^16(?y7>`?rTZ@I2gz|Q%%5UhOcdRDS(I#PC4vMoYHoCf|> zG*YCMtHz86wor0o4z)dli8|y=^?x{fHmNzC8q{yUZE`}e*04_ps~D8s5B{fh*GpD@ zbx+5l`}+K7^Pyw9rNim*UaMKXb9&zJLnsCvWpinU{bbGuX_B!s@t5-CP>QVwCHFHN zAe&ifd(-3ytkTQIEF*y3|Ng{uy{jErzOVW8FDKk$g7B~Q5b8+Y5n_PM_#+6Oot+Kx zK+l5?zPZ*^qJ~tXJ_SeG7VhPcfO+EVHaw{+=s~^p-fbExKSmu1aIlGfCwR05FQ7Pi zN*Wxp{5|=M>@59{uKDTt3tKZH1)gMFOPJvGK2vZdORQ?inopTV>3Wi$yAuBiT3UuDyL3Jd8E zF!km3zd6s%F8|=)lN;pU=K{HoIY|F>lj5`XEp4bIKf9@xJ^anW-48D0zTraenh*d~ z^8+;G&z$S6!nxF7g5Jk1xoS^f*R94QdS>caEKSW3tIaKLmmG)pb)0%9Vd5HRkii>z zrVCxEwZ71k5xwAdkeq~GePzujY#aW5Gj8nJB_js_hd}hIHkz;gN@p>%w5@LgMfk>iS9s={h=Y}j)43cPn_gmAlYvAt~pO{ zWk3OGcfUZIVNR#uRi`$~)mihtqZwWCq3zGiRJlTVSHl2u$)lFZ!sUQ}(s|*mh6>9g zV)~m-t?ZC=2+H}38BT9qg&v+(o!52Gy55Bu9zh47RWIXWyBvy;p}Ly)^jMko5Vk_V!VEN%ljKw|(B^qsr`#|F*njbO%MU)wo@dd)j|;Qh?lPFb{RxD3Qv({y(q; zJjWaL^GoFBdf8~?8YTnK_lu!Gx_R$S013|5BQNAC)lM7+t;mxbym0&VT?r>{nk)CU zVa5e_ssq4ksm_H@CJdn7^Sd9+S8K0Os`SK7%%mCqEwaPoK}x+!8T3nB9Aql~O{j#?g@OEKO^p%Dy*{{_%`nK|n|t zaKq;K!WsB7E#lJ62RJ!BeeiD|_{30v?q9ZCm>s{XBox|Y@PeAO52nw!3~kDLQPEU%sZn9xbBAhg@WGI`nVFbttFK$*qLS8H&t?LLUAl zd$=VxqAmwNC|CzM^sn_l=2mXS|JEOn3;einEzp2`0P(u zIDq-wKxXKo;k{@j3tPu}<($Zj(@n<3_!=eobClc?jGsK~{Px_!+{wNtY`ZJg7nE3SBfUQ_WX zThqG;)h8*w*pO%nxo;N!8=+(u}e9SFnEmHJn!O*<>e22v& z;{2D^^~2SRmSgR+uzm4L^J)P70(#)+(7w6DL(Q9)4LUa%Ua-~ps15p3~H*EbJzJv}9UI0e~$MbeCcY5Qb zt2z$Nd_xd>;Pcy;7E(s-<24uhl$Lq*MlhPJ6mhYOUgwg&@^~X{;Pt!btAuk}I)|(1 z!Wzo#W41!DSxd7SnkRy{YHbn?u$yo_d1AZ_RP)Avmi@=>!Der@bc9=jn^%1omUI4( zB7+Ldq+vc?GsH)HIU%tA5eWDuF~Grk!RuZ|vxE{A}qoO%m|Wt1)ba zd$B)k6j^XPe{o1=u0c``6tz4$q+Y#Q%%5mQgVn_ezT>v-d3^!o21G=Xn zn2*d3oR3B>f(%Jp9UgE(?O(kWa3|I%t<7b-J4;F4!=k791Q*B>8;kUL9+9~B*}T@i zjq!)rhxAOSgh@8+yZO$pt;g0(1x3UN45M%Hvy0xOGU_*4X%j)h zR9VLc^SsVjlZ~8$NK-gidrYM^9e}zW0Gczp;{FQ~DFGmnrt|uf4@StIFQ?eX(Xc=2 zDVhx7jlMT7(mn+b+YH2rl?qHk_GEF<-c#*Enn)z?<$)!!tU0crl}-70fLd!_MCR^x z5=mj3Jp83~^aTRfk{0gsuwW$w6%1m9cBRasvYEAqV}K$;urCXUE4=<~FI6Mu^0iwL zLlxCKgmv1+6I0}zCpQ;`4@Y@b36kIujTVtkSHjMH$!F8+Ng!AB;dEY1XG z3-h2R1k|1h&hJ9fu_GXDUgvhOQ5z(vVAS(L&*x@eYsP@^Eb*&sz1hF1H{e!YQ<|EF z-JGVaZNtLO=be(K<@B+Dwmx{QWRQ73Pg;$Uj!raIJqEEQJA3D`+YC$v5<1SL7I=XI z7aUn&uWBdS*-6b^=O4VowEh31rwi4lA%L5Rdn2-HJ*;d)Nwv@>vqe9|;cVvu!G&CR zP=Adn=xS43wC}JmP|J3 z4D7nyW>=TBSHNfb1NB}-my3?+;jC(~SXH-V(`41K>o)9ufh9=|Vhm_Xw|K(%vDPky zk;+29#<$4^WL!t9CBcG~iq2O)r*x|^VJd<_`X?8EFt*NZ4p-Nmqv`xA;D?X0gc6(C zqLeju&dAvAt!BuHBGLvn0B2%UW_+FTyp&B~m_VMD1$SmpqhR-m*{z>byWC zZ!wW#(q`PWRhUAh#y4+kRoRtL_*U3CxR8ZJ)%?(gQ>@a0->N)uF}QuRkbqXK6?L)( z;%(<>b0!QG-c}(1{7WdOn{6)@oy)fX)Yo(u-z){VIi7nNcG?O-*J{ke zj;3SOnEXDRU8V7USQ2rE@Y(fJel_Q2s>B~rO`Hj5v?%Wb1ibH&d!PSEHDG1<&U%nK z@O(7z`uZFF5MAdNN|wJ%fgp@EL_bxt_t=Z31>?H`;|1ifdp1`|pa)H>shB=w?zW-` z5=_ARDb18jFKcaefiS$3vyG18yhV1x9?Un_XOM{M5`tpR@m4g#z5;}}2X52W!LJRq z;R|yZ5rt+kDWz$N?UX+@l&FamwohYmj7WMc$vXYWW_m$ZF}J5{O70IeX}t0Yt5`;| zQ=;YEwmpOR;oJxn4mS*)(chuTw64*G%$e3eh7%&o4HX|G#8mtv$9-JrX?QyicAodR z&-KW(Qy&~~;N~vo^4K0V@N|7K;D|pI2Y`v9xPC?YNZj-Vt_QCGn&Lv;hd8mK#qykF zPs&U1iY7!6u^=8HVzxj9%5QE%Pko&gQR`AaLj*HZjsci~h_Q_=+`BD{32vFer@`hN z3TC;fvS`lKu&G7>0HFi&upYY!fT59J&^8M6aw{JkcGdt>Bdb>#24s;MB@sBn#X&Tkb0cGD_5@7IR8C8t8Jk)g zIz9{i5scmMy=#jIfIm3^`oBqEVZgn1x!FxWwS>Ij?AtLq_%wPEVPD&<tThbSp;V?ZW9v73XXq`I01|x7maB{0f*4-y}d~uVDr|kXVlCC zdyH`4>Fl?^3aQjFSbrWi=n9yUcVED~VDaQ_pWJ#-6fXbpCwMwM-;h*6BSQ@<3>at< zoW1503kcPyWlm($`<1{!-}xxU?zgXy+Swd)~Yij zJGQ?#iy-xFLkI}yV^uylQk+f#=AO|}BjWE?VSP)a>@vq2*zn3dhxHL^UpnLYGE~amzSs6Bwy{MJQ7d(+hWx~Zz6p;;M)s-Kn zHJyH|z&ysQ{m>?zefqPR%haWj?jeB`Fv&*;jt8Kwjgs3wdzbO zXI*k0JUf;G_n<(|1PfD?R_+Qhu4&ZRsuU&Oiy#mwhdL>p}|EWb)9ApTRl2U0s zO`y}?xRu}%bD3)%kS;I#l`LsCz;4(+6`6BgP`I1rIFKL9Hc&s;DMKDjl(7(2{tk8h zz;~k6i{cj@_uuT!l0P|m%OfKIW6yP((0&dVu+W+_6|${_z^UCo3ly>=lWC<^?Ws>sK7a9>;xI(Uq!R+4#%*ZuN%j%| zEYQKu72&s@Nyz>K1z}(gAF_&*u}vKV2+GK!Ch*Ers~JG^vIBemJkfoP`@Ap#ABVPY z|F*K;9~jhOL!hI^00|9>V=%fZ49*sR)AJw0-W8|(_9#mw?%{q^Cr3xq_@pOS2a%+W zGy^y<<7fK;T;H#j)Yr$hDYEDibqOcLq2qU}L!W*YfADx&|k5-x!W6R1`2`B%@dA~%Z}9!|p~KIS}} z7ulDJ?&Aq<#eeQL&-hfi5AevnW=l0c2VY+zaWxvIik74LG%I|v^h##9j|SFBgjT^^ZU z>qp({8aXog62(AM^PVf%7C%reEaxV;EWAZ#X^H$c0F#n`pT*H?2ziiYxNV2vi(3n< zx+Sc7EZg@?gZQ{@{+(@m3{rgfwEgq!+Z!=asSqWS?=ZztM5+kv`elhsb&(e^UfJzl z1#_(*IiMOj!Ba|goWW!JlEj`UJy{^38O6}CWji?ljG$)quW&eJLOqPBZj;$fn}0*vjee!J#^zk56a$0FQ`Eifc9Lz!JR+fMTTOcGsqb{Fv-{ zD{0F>F^+z}gh4F3a%#tpNkDcSSiPl;BS@An+_6EKHImAbC>4S|QcQvGFk!8L5F(O1_ z+exA&+$33S6gVL|pizuvIW1con?uy(FL+vbvon$@B^+vWU+I8^WDRs-8UCbLhu0K9p zg*2dw*ZT2Wjgz+lelC9!a_$Pio%bmI$E^0C#=uq$0x-Q|Gwm@7!00X`Mrdjr(+XtY zP`x{rT9K=7=Kwy%pP?Q}dKKUz_Is-EJfO)-Z`kn;576Kn;1jU(?S~s18>+IeY?PUNKgJ8smG@(wqRZ$s1RtUjQiQpXZ70AEdJGA#E}CyMilIy(o#3qA zI%6J!UU8F~zivfl8kaNb%4iK+ue?(L-%Su2SHgtzeDE8Hn;V$a$#=*59D;5;g+ehEg6K0CcD_q-KtLvkF?k_}T$J^UkBZ*as8%RBQCR=w zx1M{Q@KfR9R&>iS@=Gm3RC*Jvf!fm-5^kKhmFdCpA zD@C9?ZHBPItR1m?1YH(z972P7WXkXH)v`<+AWRPcg{S)G`A{ggCcBFn)6A zR90YkZY6>|LJCtqb<4iX@Lzjw{Ok+84*u*HhFQ(-S0D%i#~5P?5Chy&1~GV}HmX}{ zg&6MTw{a0AoEFLY-!w=#1=VJPhHLfVGqEp2sCfZHiL!&nDF}b+&FgyGghxr@*w!xt z++IF~v{mHQbpQVNN`7G3{a%p$v6DvkMCEDfi){ZSNr&FIIb5u*BmY?$q;LzI*cX=C zGg>!Bi+io7{@N|;{+;G8vdw)DE+$aD_C0x^?wkDj$Kr-}FGG0=A z${AUy?#0qoC~fm zWY{z&jO;>==Ot4b2$i*$~$PsqOH=l0|Us3IQEQ2EsNnXC!BrVjMSyVdO1FdgtG79LB;v-Ee zXXbG#2c%j-hdy{>3j%!qH>vmyxHhliYSYxOSA3rSsw6$Zr24VJra3Tw1o4;R%>43 z74`HM!MNGhrOeMv3ckx{Cy;)am5ROgQ&@cpU^gR--}nm??9EKr0Q3k( zT(02qC54_@AccjH^cnV7iLL zO}|PPs#}bF71G$IEcWV}#JEX@Y|Ks2-)as_y9j39obE`n<_Iw#&FD}qG{Tkda^nB; z5?;@ySfpoa|0ID}=C%_z!TRVSJt01TG_`54*e$B6kUmeAIcxmIwW*l$P$qhKkek7I zj;%@m9gqZzK(?NpY9a~;CDPpzgNWj}UT$K{Ys?wcG~R~FT@v;_VUGFx^9~L&)vWkY zL9xQH5V6i*7PSYMNN}HE4iJIFO&+6)1fgF92H}gT!GHFwsS=kidk=HHiXrccJ{#A^ z1>Om0$7brOg0G@@Fsd_6^>j|U%jt>3EBk-BOyaB%eY$++jej)v;!gk_#1VEWndjbx z$|H85*>Y{hzANAMM|!Bv4d_+bt}%CA;Q$cRQ4XcRD99yRq&Iyg4hWkWXO7aFgMZx- zBl2Os87AI&Pd{iL3jI$ajj=sPcE!Yv+ae9*#0#D$2Hq9~Vi~~|52cZ@&GlWfsNGOV zVx;)iifmDLP?WX3z)vwxCla`+dF7PgAN%OfkjW|Jy>`vKRm&MZ_?Jrf`1l0h*2IZq z-2D}k>v3BExm;ucKuV1B(Pj^kI(Sqa*1Qw~6j-T~i~}T9xf?x_hC;vJ?OS;_*LC{p{m<{z(J^N# zGxVV}w_{=Z?e{591e!Tf9bG!SXRq1hbIt_XPNH5llG5t7`FX3h8TtIn?`)$hv5+45 zEx<5bf)*aMw~4hL1W3o>8yR-oTcZ$wP6Wj!=KGX@TUTTh=tO|fCm5K6@$mZ#1s9hs z0p!uDF?Bt)GX$u(UzpF9F#?>j-6&o_J3x_%e|}j4G8tg7(p8d^ri30m{9>OglHWMS zEKj+GSTw07V_a_x)bsn#HkXD6GJnK_4U!jC2DAblyKL!^#(Hbp>aW@Xm0Tn%`(9tJ z`gPxmO80;2>}(ihr6+@ZC2b$*QNw?WTg+FGJB&>0;4kzrI(t>ZQk$lnx(7LHjgYwC zIZKhdP&8t}K5^rir(ZV+n5)}Yd$Ao90%Jt<>{^Aq5hL|l&ZX{Ze-MCwzXlH~jZKmQ zN=MF-5tn=FPA(%r*-x;S3f_Od`gpLq&!)t3nn#TR$3+(W`uYNe<{EkovHW}|LjXqp zb1e{fCUDvQboGRrfLfV}cB+HmYYIuPf$GmwApw`NHlQRX=xJ;3x?eOWyhSJ%Q8cu((LhT~tgQoE43&63WS8kIO##tK%&_;jaWT3l^fa}(90Xl|ZIPU# zxYfWh*SoXtUVgcY%lBV?FT?%P=wk%ZNgzAO?7~BAPQu{3D;hxfwzbwT(m>EpU0yDR z$JqPIcImHLqXI%wJBaGnxV4XW4DD!9;+U@jqg8+0Z6Em35ob$ zhLGF-7xwZ>m4MR(oNU#bI7UD)@TvBp;_0Ft8H^%_Jb659k=vvKDEvxl33G_7pi@}H zzFn0<+_yCkjzZtXcQpDS50Bl5PA8r-`V*tL-h(fo8hi(Tm}V2XKMq-mZ@?O46oJc3j|?6x4I2y|L$M-2#|*hF zywe!yv+3kMQL#lJ!-MPV`Uk`xPgVU70{&U>&uO}DN(^><-b?5~W=iOGzWF^$sCcpp zO2rhF|3rgKCD+ayHaMnrUqx;^2i~=-XcPK=<2XuQo$I4;tii9?{}t!7UmNVWMB=mg z0-J+LR*sduILCxqLYZyrB)RPlnZ51qjRGIF5-F#jFHh-@lf7^!zhxOf65X_`=|gNn zL#v^8SR1)m&&1na{gVlW(raS?minYQ1p?RH27wKkV|5tI1H6)2AGE@1(PXwYA_UQZ zDv3U(bM@?hk1HJCCHWLER+ctY*d`L#-h(# zmBanGV6Q7N&qcw^FuZARuZ))1-a%u2Mb5BOQVVw5nSZkAXl}xRM)IA0L)^)>uWN}e zUN?$@!Yz!|uD1h$8QR0iqSg8L`hkY{K|~&2F^OxWEsI}h?ox>_c#X3VhIFMIu(#yzhh&;J|I+M~A6qI0ByRvm4)haagEft#OauXH0%4d75?A!hDT}M+AOaUVShu zOnI(wum4T-x!nCfmB0n@r<+lXv#X5HmUHQw2%4rfWDIcobbnWM09fo|A$9LR103@a z@*;i~QU_{SwfY%4BkLu;qB!Yvi_#oUPik}izQ0->377auXw+Rde6?bZrqs1v^zWCF=Fj~N1wT-WqWJh;ISr_rFjK7!@1!ACWTW$A*B{6RP#}*B zvu&2?0#3LuyP3Tj(RWCV{i<4@9**!#JR!};nMZ!Tg``J1mMCJ1SYVSg1ogETc&qXR zG%!TvTw;W850V}SKj*C6h>=(UMlz9Fx}&$4YmLd-hRN>=T2?ZflGs_sThL$tf;vi) zU-MC7(xaxNU9|DcU>xuMX0lW!qKn99vWHU$nYG&UAb`dTwfzxcB)E#igL^~KkPG}K z;|8m;=bNC5+4Ac6;n(-kSHcS-Qo2hY1c$O@q4&scNYAii67##sqJ&~7B~~o0PaE;? zkfzjMp%mnsC?iHmv!GS?L`X;31^YC%S4Axt>Q?u}htbq^O}AHe)wU10REAaAAU}4F z-h>h(a=7Fy*W&xI819D+T=O5hP5=^mAoGq00b<|vpVVvSc{)IP!!vBCmU%WuT;8y5 z&YLx+0}8C%3!-M%Da;~r4MNz4t?|?CEFhfGYdd3$bdscFBxC};Up@*DKr*8~h=F+x zB(fq>ubIcQz(=5JXm{@N66*JOv%UC*m|d70?AEeB(VYiGLp%Z<@D&Zk(@!5n{E$Kl zN@rYhCg*bA0Gi(Z53(&G2JYP9V~XDGSDUUI1~^r6r*qK;D>A;rvfO8c!EZUMgI`pZ zrIVmd>t7#w+Qac4+q5+n?nKrJG*E9({4*_t9W!$7q}a1Oe&*9Wh7+q-U#REBe~F;rPh3Id0I5E2Fc^S~o=WsJS9*F@Jz{!*u|GYZMM9K!31q z)eQO5?$hXsZ`hy%fc?2HRS8%>suQrrnW>rMGsY2V$z5#CX;+&wA4V*mg+X1uJW+Veb^i=gV}`(-~^*CcoG=0b+=k}jgPFh24wz*0!|4?!f_$Es};(j!s4 z247gG$(G0;v*XUlqnh~2)EomxTtQst)MsW)g?9+A1rwB<0tVq2=zcqn4FgHd6MR>s zTlWO^e#9xwdbx%b7fdKU#1Pg|%8QBPpXc6+;gW?9pZhshhlQ_;i7D8tG^%|8q$h;< za3t}^nD5PH;0sn@Q_@r;DA0 z4=-{PrnMeN>luR8Cij=Ayn&HfbXcjF59gnY`Kye1R7-CR{~o(vP>F96VUlLjt_f|+ zX)#l4?ymV|M{)oPqjXowE_;CJc7wmhdD;sIrw^XqgO3uRb&GbOhD6LysHpDQO{{Z{ zvTif^vwwfSdUHLJD_P=UQo^I7D2d7Ms(CdDsMxCmn3i$-Ek?t7(i8$NIK~UZvh%&r zL?LYlb&G!yCwdd$pJ#nTR4Y>$+2Yx*qf`m2-;Q{9?}Bkk>`S@OdmC)(sN={=CEl*6>`U45Hnpd8rE;4F}M(cco-Gi+IX*=*E*){OPAshxR$?M44zB-s2lD3WCKhT zc>nF(j2A+pchAf&ogFZjMw#T_M12~-5%MnnX0B%-r*{ltnz;IAl{GFfv*MhL*0FTe zvMqMnuM#jJon$G*@ha8T50yJ13X~Ny@htoWkEP(^7d(KvL=PvFib7sTB;C99sjr|J zDf_JWp}pV4(>~@brrn*K6MxvI6}9^rDy-+OB^DZi^-+HH@_CjYFc||+?)ZF?V5bEy zHxBMoy=l+#Awvd#&r3v9k~wekMoKs1>J>iR@N_E+w7xW2s7|y4;&uY)v3@CYdYP|a zd*sx1hDaqSD{8gOC1M|pvF^;Uu)_h7dkm?q89divzS%y&foplIV`La8hT+j1`h~3m z8lC;C_rt3V;p-gvg!6JjI))xe>3Pvd41Q56>Jl}BTzA!y0CN1)nZGD8Ym;OF@|aPq!Zb zCIx0bY;$6!Hk2qDs-;iB^ zMMi6M&*ZBCa@XWZ95Jl1*}$sKCV$a0J{)?s6EY?G0^L?0et*Upc@JYQrx}y{XC-l` zXN42A3|)Z3qSO1Iu4A5@)!-uD4@#54XwN?Y{mrL!^{q-PfTp6=X`YhrzEM9Z8vF@J zNA~H$Bf6M^uK`-ylNufnFI=5!y|gC}OO0ssk{h?rrMwL;yf*aNh|ucpiK18rHJWz5 z{uGXSpOpSU0~!H^Z6I;u-9id<0?*<-3WlX$v68);gXcsi3ni^Gz3ntAC3D4J`UK^ zyn^`02sQYu`S)+ul>kd*uYLJv>-}abZ=j^xxhkmODsU{^>V4MwRlSNv4kJP95>Pz<1+X?(KlNn@ z0uPul%@-L{4Cs#hk9;iv;l1{2q13t1tjM@WQk6}o!6xKaDIxY03X+S->`Sq zz{c}Z0lpjJMpE3cAF}d&A6zG=NZxGkKC}8&C>DzR#pK{UCbh3(aCiMQ9Z>vZ>0IfE z)FcKGlo(1EZd4tYR_ERJ9>o<$?_Ja~GFixJ!J$@Px=h~G3& zz@*NX7QZ5oF?#^y@TW+n)GtT* zYkaqx&)uaLkZABIEF^lOo}}^Fh4ypFN!O;5Ra7Jp=tUc60}|`S05T{fzZ8oEtgE`v z!duM*io{*14KkB<7|s}ma|O@_EfAvGwvIV9#>#qHhdLD|<9v^{2tE*D@Vc0u8N|RU z>3ubW_u8^1)K-TvtPlszo2h#!7)3cFzd64upM8zp=SbX%96Izf#rT0qYhvLp8Py7J2dpfYqN$v~1x6N$M1lf0oXtde zZ;Ap(VXLPaA~L~F@<6pH#>qnl6i5?NjC|zFTQA?=tX#D*17jhHpvWdpz{D-bH$wYN zxRZKuAdjdHPNXPiM+sn`Ht$xS+DfNq*HdHdYGfpl%EV71R0IdH=qO(L2sVZ#Ai225 zH?@Gc{Y4!XcuA=gX!v&bZWr840mws%Kl)UptfFoOYj_;0Y5#!;Ma8D8)hs43!N~W? zq-f~aV7FJbY0sX?d0pxiE%_y&Dv&hG8P8W$lN{_ZyKH=vk}T4n!kh5lZ4-ulPkgWW zYH@x`EJ!xmS-fLXH7_xD4saZPi2$AZEnPyoNQujZ~ww5}2 zp^i3z941t*BK)x&>AO?AA={IGZScCRTUA}hXe!HQaT_gJ+mXMzMOPCtV2Wt_iJXN1 zl;qsW3)Tjpq@+ks@pLt?bWX2XWE`?S05Z3Gnvf1+!nn8g&8L3s18hNoAJ7>65x)es zB4Y%XdR~2mP!=MU#`gNTuUBm;w7T{m*uE(DY?K?T`BU|0!lTp&1ua~_afwALcJhe< z>13)%BU3C0wEq5Tf;5UQ+&etjQc<)cKJmJ};|bHqczp}Q>BD18)U-7%6ZFs1`(*gv zm~p+fq5{x52Uapy1!(>B!rSO2KQtpHev{P-3gV8{Mj?_~6?M&m-)bAc1WtHv8*OWq zcYn@c4@Dt8o3Zog%X7vksYU4^kuau0L9_osS+}<+xTbl5nkB3x7G$-XJA)@nqk+_M| z2YG|9Aj1werk~Asht126iJdVoU)=!8hCsyF%pbfD;kiJ<+A#dud+aQhydWDYtCX^PL;9|8W34#4peiL?A*moMen2IV zuG0Z4f{#sjjDIt}axh2vs7dkC@9<1LlTZIVsjW-W3C-+dbe1>Iu;37`(eD1VVhqg%I{g@z}844rZ1^9LVoE# z|3SThh>Uwoz}GMQhg+ghSKdUS3JC3uPmgyNt;)rcAK0`B6tRy12C-KfQoS0ANjPLg z*L?#iuSMx?NgN1dG|?V$C}$u|8MQ5G0kRb|3helDK*^lX2p{(L@?4yY;;f*y+;gf|xU zyXEHWrwqvvI`vW1D|G6T%(Snnix{6!zPBwCnt>!uP+w`$C$S?fT9AKN%sbV%y~%iE zKxNgZz%@Gn!gZ$HXRUM@tI`*AOXlP;kaE>pC3meO@C|u+`Okd0J{LrqNYk1pr=~aau?%NU~GA9by4$V6bJyCz92d-mD-hR1p)Z$yAAYOmz*F!`Oa&@jX zZVQkl)?#KC|2%*!(NiAJTnJjTNvI;aW=~hi2XQ4H)eI2y9!750gal(?8howFohz!C z1*Pf%SiW&Pi#_mMHt=sLYwCVyF2p}<9lC{~`mPle^{ z0E_&m5;TNNgbvnl!wb4udMduUZ)>dncE~(@@vKiVi zM$toxk1oMW1B)zB8zIXY$itvf*s-Y4P=7Vac;?x9x6^d1xD$Ke9@&zf;`K8#s`Tc< z9T`YVlKJ0C6?gmJo`I_%O2B=GbcnqV1)3la=0MiTpmh*<9@i903Sl<*KPcJ=_=ebT zfGZ{`OYW0OoNrP=suqm&3*cYmrM$QVR&`R3c+S_c4V zmG;+%hAdD~Fcs1VbV?raEfKZ8D7rYY*q=t!x@VaWe7Zke@nF|q?m<=2lfTD*06;(? z@3uZrC!L`JW`4Fa*Mr2({5hW&a3{(?;x{8SI#A4>7OUTuh5jMmlB6t1F5^L4Ky3FN zIj%Kkfa>U9i)#Xj`~(ZImLd_;-t{;tNkaHD%g-tS&=Zet?RBpUUh_91r7TD;QuWB2 z9RIzkZ4fu!YeB9_A21I-J)UyvTnxM;$Sn&4k~luV-~n~YJ!Q4R9+!SWaB+h2LL3Kd z1+K``!vUw%Y`9t1fz~OdIP~xXI2uiVqYLPu&9We)kujUuOzx-6C%Jkb4>CIqb$9C2 zNlU&Shl?MrIEF3D$)U3fO6}u8aoE)3IIqfi4u( zH93uJx;6CewcQK{##mZsJ!jI-jp<96SARU?`b(xtBuV4yR6)AhM|pfWaKU=>SQU=s zV*BrWAyJXMV1Ehe^qTPD}ZXo7~#hjl8BEY|K$1*~=aM0M|LwvZP%} zL0?(=9DR0&_Ev205pzVD+;_k|6Vd4<>mul;0W)@`plDWrXfdDoSZ5NzQI&A~*oE{u zmjsk#zwt(q_Zc`f8986exBQFV~~b+6cD^ zpkG%Kvf@Rb-YvDj({;M}9mxIe+Yvh9XNlXiU_4j*_$E=J!{yi5;48<~kHr@G=x|Yn zS=bjWi0*giO8alf>&y&ZTQ4xD%9V^(bgQFPPu}`{nKom~D2D0M+=tmt$}m)wY895= zumeORQgtN1V^#GV|DB2eZFR9L%A$bdw*({K=)XUfp;Z4Ru)#<;VYM!Kg-*w{mT~G&EOYJBr>FiEr{4H(juS;hNw;bJHOL>#zWYO&Jd z?OG}mSVJy3^a-p>L@N1J>siPN2mYVL-U*gqK|Cn7$ z*M!(Rp1ey#t^=Kb8GSCkErKX;v6W6LYoj6%H-3k3SQyZ4rs>$M6)a1wRuW!Dx9BOC z^G6qhiO(0)9V2)5?Ur-Hn;Cq1;-%)#pN-gb+RaO6+9kIXW)DhDamBr|>IdHv97A z6PB+0_00m441pkEA%XJV2>?+Yhet!_2SEq+-jv&b^m7;0CPGD+)X8MSA;8B^&zYT>x;!w zLuy8otrOfi$4LYYX6g`D-3vL@qtB7vro+@OPyVCzX-Rm?#I+S1iRu5mThcl+gdxMf zCA7C_mYam+hwNJNn3n8x z<&hrn-3;lMgOSL<7GQ;CZXZty_b&lBtkWTqaZG?8nW+#3Tp$l!5BdB~P}x7?!nabI zKIUQ=49$*y~ZW z$hOAStB3CDUvx@mf}n6+)w6ZY0evQ|4y39~^fETU_iJt1OK9ZqAy)n~{XokMZ5MO` z+!#Lm6Dr|4cPO8jx4n|(~*LpphUF;RgTBT|QMj|fZ|fo(fq4et(1wF$hKFs_#9lk}aE zO>VH_l*sw^AL6S<*Lbn=c^B;-vN^ z(%?m*u_nMk^=HdVeUtIQI_}D0e|AfNcyd7?`qYBzg-;6kBy3~gH8if?dQ68Yaow3V zjC!%KCuHD#+MlNL%ZEwlSW#PWpFTyuxGjbupm#Crua z!Lz}bxfF9ltecuAI4ITqa(emW?t5UnJsoCoe7bSKcs``MXzzXkKP29xfv?^lVLHGV z&R^B3klRsNfG1Thr~;s#uwJ<GAxQERo~kHL9Su9I@*`Nc)!Xh%EMI?r4I ztLhuzN2gRymh~SXaC}uNgn$I<7u`ljmYEkFNkUr15%JtKD`CooJ8uZ+sp}s|V&`MA zs4p2=6Rze{8_{K@41Y2hsCmomPP_1tUI3GvcCd{jF^SP9R2bA9mQ=|X$E1P;p?;|{jL|Q6dX}Ls8|M8) z;cTjGP;Bfm7gdY-*F^^2p8)ci9Fq*gqRKM-OUjj}Ur-o!-0_6MhtX|uu4y4RDfv&R z6#R0~OsAIbTi;qN9m+j$3n*FF#>pG+0hU<|z?XgD_;+>KPUeQNf4GH5Q~mcuL;FiD z(jQs!=D#PLIm}x0&2hVSq*l51RrL;hZ`#RGcUNt2(!138hroun8aWmq;81d89#~`5 zod0^CIOW3hU+q)p{ zUYZgke?Va%?*kgVVpmCHsvxE_N=aR3%Q$MwK>)gBKtG6&I6+>9_73J~?=Zqw{WRFf zgBCF$ZCg5gk)P#=^vv_oO`hZ1Nu3+HR_))kAg>cD6H(oVS0^{zSQah0_&U51`}E5} zPhpCW5%n2i<9$_3|6%)s$asN#ZJ$N9$^ktaC1GS_FHMTcr&~yc0j;llORavdpc9K{ zpvGBS5p|D~avBFc31?!QVvT^K!SLi4ay3bFY2AowEhJEmPp z#pcg@b_wUS*-`2SMBLjb6;OPK;WtDA2WuXMZ*hgBR{z?cvRVBI$=9XP$tG&9P0CN` z-TyE@F5`JBXfv=?1{$Flk)(D%&V1;Jp*f;f&l9tnpk!Y-|LsyOywZU z97Fgr{p?fyD=*a^Z}<`RHcmD@5i*}Il%&jU;%bLG;nZS&CgL>(Rl7#-u4bdlLEoP4 zeVcRJv9l>~>;8~jdS2tFV%)#U0s((P3Y~h6y;ED+CGIQsbUD)~vU1Uf8Wgy{Gz#38 zLalY@&HP!BioC~)-}rH0(UNDjX89u*CbbuoZL}3~I#AxQRoAAx$^mh0yiEzDZRT_R zX1*KqsgF}EI$ED?RBW3rHKbsAVZEq;QMdKohooDu_v_~4*B?%s>urRzN!uF zaP|_BTam+qDy8O;vtZxvmNognV{cVBm~`hzujTcYvBN=b`g~@eRp?;jD3xy($wA37 zX`s-mQxj8@-$Eh1#Q5Why;m}K{ISbrj&&*%mw683=0As1EVA=nC)BxowOsshVV&Hr zr#D(S zYM-5VAiwxt%(5EzSIiEPB`VeT09CNp`}^g7KseSW<*9&jhKS$x6_b+f$0fvPclXkN zaso={BHGP&J=0wOQso!pcPH%iXMC>jqjm`m@gQ6EpX~%=Q|(A1_5?rbU2H458wXN~ zQ}P2*`4}PG5Rx2JW)9|b6JI)*hZgDG=i*($U54oFq~vX5YaI#6^gquM<0&d z(Ho+8DElm{^1p1S;pa-oT#Q@8(U9w*bJ+%f^6jXeUwQjkwsPLM?gKEN5pdmC>Q3+V z(WQcX04*U@fvqLYOrUNv5^~+J5xrM0$Wn~qG7sW@=*t0A2pEWCyYb#PdLO#mT7cs% zv-3oOEn7&pZ0Ggfjfu0&=Jn3qWZG0&*cy~e=-s}^9=^1x%XAf_dC}miOn|lK9nnVZx2x*O5)QQn)$zY)p(S9$*Nb<-)6r5xE3O5bcw zuTSr-e)yA@UEOv2|D0!5q8=f3DudU?tWsQ36kH;;@DV<=ey5hVU~-7Gds}^aFYcXO z!lL=PRF@Xx>F&y6?n0msge7`sr13{D_Ak;2ckfP~%k#|(w1U18=Ft>dg_MEgk~a3Y zS>EO7Vf3o>F}7j8pp){L$8Y=BiSHFzN=tUQKa1TKV*CCHC|dHZ&^&CDMQ#bdxVKJ2 z>cP_OlE!LM5ivCKI1tn;_Q5faP$)ZhF%TM_@i-OCWNX&g?6H~dH^2GyV#8~XuUtno zXPuVmxl@bDzhtJH(}};sA}TArBh4+m2g7%%-YKLGAzbM$Re0;Pv0)Ib9>Esc?pBW3 zvYP(Y-x~b0Ldc%5-{|3!Y}PjeIlvKreg3PKTL9rdYpA{+*xdQ&>}luu z5EpTtzfHS!R*t{^niaU8uA})j&8OiV_Lzipu}a)-@V(ydZ>JZL?ffonQYoU%JPNI+ zqK^K0(nS~-Z0d#+GhwS_Bc$b?9FJGM?f8jS>8BhekD`62SCY2ft~*Ks1A?`VWZwzf za2Q|LL0PA&3+gtIpV%;vY_v21rVA9&(eHHP! z2*+)oZn3m>dGg+!BYJM(f2*BD{D%X}aTGsCS_0wAh72H;~ z{D)cwOPt;^4~~}DKP_$zZfvnMP1Unjv_G7jvcCw`kkUrbgGLLq)d znVV1+HT!8au4Gz8C(u)0i4$4J)3M;Ie>9H4w8fxH?|@I{J`T)3ROT30iz0R@8eiy7 zItE^ffJ}5O->!el{e*(WPTc|4$ZQ|n_b@p^!7)XgioVv>U;(Us`{B2cRez*a2CE2P zrK#1>J&`=PSBFQ5I(s&d=^&wI_=x7}TaEDqzp-|jsCdPb;sW47RwZt~F$JcHj=#Ri zvZTolTa^xeO=iW@V_N$A`ZJp9kYIt{w>FNHs(uN*)7#vM{RE~Mu9(rhd*F>(NVONt zGgpY(#H4R|jsLp-@B7@iS9Tm7rX#c?6i?2yw?E5Q3&u|XPW^Y=e%LT(HhTCTadrD( zDa`0@k&G%yPsq;KhWJlAb|eN|96^Yztd6iI08J;>&$PqJ)ipnmOO1 zgnHCtMbxEDO8VEFzCZOjMRHBtXJfJW7wQS>rUjzxWE(0G+2qCh^@Db}fBct?9 zQRb|7J7xGZ{@kKWh9k!N(Oc+zEzBZA`JI3=bAAa+s14sIN$I+wEY@_Zk@%GD;e;sW ztT|h?#{Jo6D2zXe1IgoMZC|#D~WIeu{qT^3S zcz4Gu&YE)86XW4`mmoeLb{6g5P+@LAyx8am)E(7F>XHzRuNHeQc20{}*FjOB^>t6?9Cx}8nQWyarr>yLc8wim8L zlAYK;Y5V6GwUsqe{2=;}LPy(OWOeed4S;}L6Y8dE*d3^GmNWh`8Fu(N7}7;{OvXtNqg)t~RCq z`{MtEZ-?#baTh_A2F@D+8$a<83X+j;d4JECH~X8)2rXpxz&jy{DCcX($F+7Jg4;m+ zw`*Z}P7mls_Vc??7hb2|N5u+Son2YipDiHO-A&m!tsZ8$wb*9|{<2r|YPK1neBpUz=-Nk9o`PSZ)9*a} zDdOS1vd>pTLgqeBDv8#6S*Mf~&X&r}++2|@|LDJlMm6Owt0D-mB)=@8#@Q~!asQ~= zhVh$vq}wL>qapKdy8FH|Wd)(d#Aip=dOfju>fw!})%aUhM~W-YxwKbpTUlRK0&)49 zFT0bh_7sDRfVNqeii^V9f(@+e=bDrVNg2^_E9>(xfR6A)3z34%0SPTy;0FS=I+!6I zydj*K@iy2MiJ`=O%fV8X2^7wXQn_a=kBp7-X%C|i8%r=6!}%{Db-apAzSGM9rPPra zKsv2@#fs6Jr>qEpq!pycUdktQmKy&s z7kGcPI1advUS^ZjPpcFoH05ebWNyoU$*1=-DO}S^P;oa@o;hxbS$%-q-!Q zVpZplQCd{K`_uuInimK8$H(+}PK(+?e;T)mrH*z-Cuc|(zPDpm6xPB=23Hv?Xgm^I zenLE_p6=CUp6>Ae!cqhVVs(sN9PG9Qn>{kBeW&E+Pk|(K2G2iLr+R6ka1_9H9&!s= zHBk@g4p+U$**2$$$lA)4KFaGo@mEDd`G;uKOo5OiugbZv`ZxQtb`epqmFfO)SBRnn zdQ39umDoSBvMnb~OThDO2VZs&RU&V)Aet74urYC)?5woG_wXPF;kC&Z&_xi~s z=s}Ef>wWh`;ZVaxh8s1Q=Hr~{A@wMdOY82X=Ql)hzqL|dSD%MON|Ee{3^&l6-IZeQ z&_%aka71NR$=dH=G~qwc(2$Tv5=i3MAMA+!)lj9F-axB_3{M=4Pu#&6D8hj6V=SQ+ z-#ja_hQA8IGcbr0#VC>MR{Qis(H$%aNnvIoN+u_MTow zBi|b%f!j+7S!$5r+L;m;UMwsidK-(H!G3eg`(*n5oWAo!|fyK7*W6~IBJui#k zf-KH2-cV@NX?2@gW7G_D(q=v5K{@~pjGw;!Pr9-jv-t$1p4A6!89P=J;`V1(c=wOa zWysisqMdJ*V20IGrT0JyX(7w1QQqQaqo9A|>~<89TiiTQ_%i|jt1Rhsj=5+^W>I%k zh|s^I!=K{H1$D_8mv2GfFm(y#7v6>~GVGccx>P9Z;Qs<)6g@`u{Pp=rq_iaeUB&sw zRJ740ooB-vOlC5mZg;mhXK-qv zJd#5RjLcy!MH1#Dk$p}Pf`pzQ0NuSn?c?@B+gIm`#xq&_476P8KUvss6CvunwDA@Z z03Ga7%8{@C%{|0`3w;Bt+?!%5A*Bj5D_fp!a12WUOmMfv(cRlx}UQ1 z%c;ZhXV;cH-sd3@y)8sl5o7E;;|g#4GUc=lW(yr-?k1r22VSnFZsAAlwXfgQGx?Q@ zu}Iu2nfyIhU%qX-sZejcTbcW9VT74DqbX({w|_HvC7+Xwmz4dWC^1{(aQBBPR^Ka4 zb5z8*xFCzInUn)8qzYd*ET*w3L*@kfRrQBjnW_t3Ic+3cL_)eNY~Iq zmmo?CD$*t0Fw!Y0oq}{oNdC^;-{*eb=Xuw=et)?Z_q}H3b3W(nv-h>H>)O%8r`IJ3 z*u@u=1f##?v@ME{{lp+SuC&L$)~<}^PV1EqBU08!PA|)EjYm95i*$|VF-zabpS-pj zuS>|xA`4`uvL&B{-nQga+6%4@-jqbd7?+O=bUw}H&PTa&K2NXV=_rrIr4byU+bOE` zUzSKU$@u2VbnoU#AmJWKw;%*i@oK$Mh9HLD5^v`p8=80jHeE&)~`@tMFLZ zdO$&?v$yhI3eUF(nbe9Or0tLam>(Rk{N2?+N|CNnUEM2)n3=wu4j*@lUS<{}h8=cb z3H3hCyuGs_W6Vx1LnnS1)pY1;H2k8?v?b#j@!Y3IwnZO3ig&5ay;TkLlz9e*BT;TfPJ?~podIAIN5A$Hab+y4Z&lx;pf66`NO#T;wo1>7I~S&e z7A>Y$Rt+f`p52C>fXAB3x&%=y%L|G+fuK$Tcikc@FYDEz9blqgeZ?+b{WuUv)Z=fR zzQp7pKfPwArmL`mZlS`xjxuUrQDdWChDXA8m=TIJRE&@xI>`2!m4|<6<5hg{sS`aI z`fQ&{=uyG@3hd?zBJ5S+N}d1%NPCf-s}7>W&fD@v<6`L2-0pINzBRHYAiG74&US%o zE1^v<+mmi4YFg${8-qDY&vP589X`b4ua1AxvVDK~vsX8h+GRm=!p7I(fkz@9dr|~D zDmNOPLvYUWo9upSRRo#LJWW5r(xK#196dZO%dXI@3*WK$VL`Cg7yo+4ATQtWu3t~F z;b@|u?Z)|jtbtgdrp?Qb@m|}3J1WyK8w*zZ$-{8vI&=QfvZ}GGZBq%<`ocd zaF*V2Bpk&M86S{L<6a4ZZeoef^mq&qg=g=uDT4UVR33c z#oLceQc?}@i0K0pV}m6W#Sx>tC2-HLN@!jaDkSX-Ov`Taq*VpTqfEZe(R6~)O>-$6 zR|L9~S;uou(*DFPwomdgqy@?A_W;^~`+4c!DrR1BtYRD0{_-?EtJrIJ`V(joEx`*U zNZ&K`J2JY343yt@k8B81)}uM zs_oJ;*iD;LnzcKkc^4OJYNkIV?87399khNvo37k?o$Mtrn8x(6%5<=PewH=2h$kFC z<_bTC>8!s%mxxg|G9R!AFaaOdDTq;-jAEM=GNVjzTuRf}u7aa7N;w?-sgs@DE~j#|Mg zq?gpsU(3jKgIRTFJQ{qX+QJ$rh211-6s%KK(pvE0f}~3 zVdAX_(16=_V=|*+O^ZVXf1ykIUM>H+fSd5M?;EE!hjT|Paa+UuwM>>VmjTV@3}|;^^`=#Q-b}fYOp~uF3HQtlr59d_XLa zYS)tc2N7YZAKZ-U1_{;iaGOs8iUN;p`GKMz8Sl8V0TT2D6`tdv5=YDIu`v{z0F_#y zSW{$;(0OHI(L+R9P932=hxG9h>4ot%Q)>=&K=0`%39{Os_XFAya}@(|8(|Whi`_SE zj9L|WWwRBr8({Owk<{asF-^#-n?uDS2@}&u<}!K|L23?Cx46*M^UhTj^(1b@&Bc&M-I84HOKIsA53`)VAHSZ%d8WeVGRy+#^6J z`m0d9PPyr?wt)k;{9-7%$!!lB(4Xi_?eS3CwAPy7XBDw)&s`G1)+SFN`tbdB5{1<% zV|g%ahfq(TPWzriZYa9NRNOn4HV=7fmuGavooDl>#Ovi4bC0ctA)J39C2U#mS+gt7 zdjwT?|j8a1Bml_7EC_89Ssz7GpBappb<-!lG`SIi4`1Rc|_U{ zF|P9VH*FeWv7IP(MI=9Y|^A|J~WkdD&c^Am_| zo7QS6<$-k-Dy$C6%A|Pgj_ZGNZjY{HeK|GEIgDqRPie@yh+Ah(lYh82F*Ssq%hnyP zYCH!IICJSMti#2N5ZCFMcIw426v~eqD(he3;$gvD_~6+@dKB1*5Sf{c=SRGln?dQJy0P z(f4w{@~8>gt&*iPRRR5xGe1cTaNC_v{Kbkue=){ub!GzMgnwrEAT<3&`*N%TxFKE1 zMAA!lKEIQ}$70YQ6HAdZC(#SYYabOg>$9d5+42ce7M9A79Ef|}K|~<1fUug_Mlh-0 zuJvowC{4u>y{tP!kH{LnZckQeV%dk;230-4d1fo-wy9$`*hTsy*YB^d?7D@=H`7Ii zybXN=Q5UBOY`x@%tSvQ}ws#IWJvN209_uhGrY!tgXAL4A@7Mw{aiIA9wkhGa9I#Ao zqZPgid5GIE|5XlSCkk>Mnw2|JifB%gZxc{Hp|7WMMH8u{cu^A2aNVKzIJ|hLXQ;)X zqb~$~K8ZNB^+FB2NVnTi)#w_|L&!$Nv0gm#!1yw0ra_S09L7 zu?fio3LGCpgE>U$2{QcjuqxAUWO$Ve=FNQRCtJARcZxS%5KjJvq1K!cU>(6OYw}&e z&S!|JpM2}sHVd0sjC3T!#PG7hA8z6YC>)YkVj2EgfmUN~fr2&}`7y0e42{%b7ax>< z_{2SvAQ|gkPiw@Mk166s#7mm`dLu0%V?Iz?(^Gtc?* z-`*drP62C^NM4F8ZWG^BuQ}BWWrXnp4{VZW7-c%{q(~AE-FRyb=;GFyvtPlAJ8V^& zje?Sd@9bl$4G5Y+jh{)HkHRZ7#)}dcLMUzGG@C29Ax)s2m}}no+yl*sud%wG^Ep59 zQ1FO$$E5OvL$C9t2N{0vI}TbuBa2x*f^T$=TQm1dc4wGMHdA&44D-naY;%w+#?~VaC#s!$SpoXQu&IX;`(?BZ#h1P)=i3*N|VE=SjC-Jcyv$2k)86nmu7ws(lC4@G6%qO%OJ#^9?*t4kyemu01{a zT;JlCcEqks$~ed$2}s`5`7ULSx1BCjbkFWK7XA@1vma? z%3CM4cpq6>C+QCfoXP}uOd1@JHNkY5PZMv!*5KK9ObIPO{^o>N##z9I#3FLW)Db{d z&35>!f725Y)sOR9m;mO@8Wn;wj5QNi9z&x_QDXk55DUlLw>8*D`j$BhX*5;LuOnZu zPmS)J*VAA^ZFHknlqirhK9hW-&IL+{Cyv{=g*#odIH8-LrW#%)+Wq+c7-yo}!?OUq z<#f5@H4LA0PMJ(U9#h$|g_PTUK`3FOkh~nn7jZ(5(%(=%dNf3Ri@Jvp1+ABkfw(6! zgzm#Tj8iV8*AL{saS0VLUOkiD;z71cGXoeA3!!+IW7N17$aj76E}Rm2@-jaa14ZmN z{Jrg*mc$M7>7HD0(Eg|52t*}5vE+CH?qecSJTQ37L0`1meJ8lAZ-e=1_5 z?Fn_3W&!oO=CJ5@P&W7ksrXsqseVF6=+dJB;dU9=;0J+%TrTE~2jFM64DK&?o_G_< zJ_v2J{3Dk2cHP8|agUOj@V(q^G6dDoj4hIiS1A=b?jb;K{}1722#CqZcN(j6&VRat z%B3tFTNf;6nr0by-|ixB6@{V_5$&&!V#u0XazKuKb1(!;1B40Ssi05*_Nju{K>lnc zShk(1;))28WGs3&GN}tN-A5DjyMEl0+JXYL5Z)UssR~90GiZc#d$CdDluT#2KmXaA z(#NPA+qh>bS>uDq0n~eL#*eQXcxQo>mk{zU*K#@KdWHC9FTzn z$*eTbzt?ToH1sKjx)oopuOBzX$ZisyT+9RF_<&1}Zow^>ka}0u1SW?xil;wK4PW^~ zt)_a8Pp6TmyJtyIwbAZA{%9V%sS~oKn!`jZ_6$EMO#Y~}U7CkGJE(kg2y}i((l~;K z0Qoiu?iEW5XkM{zJ_+R50(}`Up;VXkDTl_xqhnx1v4x{!Cd=mA`8QI(M@?X zpe)|G;=;&XdX*a-$*JIr=8a4FF8jwh9xtLuW!EGdC69+nCprcP9;9|{N`rabfKX0W zF8v+sj*kQ5_{Y%Uw%%mw;zJm=@DS$TD7MYaB&$+!ZRel!=FvAgNS>1gIhbn2&mydUj`lKEU=4No%b;=mOoMc0J!S6{XeETGm}BSunrw}0z~IO%=nH2xo;FW@PPYv(*{z;`O3AU7bo zD}4tSHezYyZ?*Ufi94u~rR947Pq|qgONB>qp8IWOtsZoCSO2@SJ8v|73s6jr@1B5U z^J!zTmPJyofZi#{3lGlcAnc~ z7b@h#&Bj!YoXn*L@Ia5@Y#HFwB96*cO5b4C$4;@7M~(nxsq3#w*KF5tEM{oQ{_i8z zM#Qu=mQMVMYqW&vVkj9Rs*_jw3ZT+VWjyqG(g_~1rah~U_f%=QQg=rQx)jqRsHMb# z?ejz|7`;+d;w78+vc$hQa@rZ{g9W?7ox+$Z*xK@xPqy*Ewoxf1^njGnssx@b9j4<8lK zi?qBK-shA+_EJT1qv=Tz`<^{Bw2>_={PNa_4*i&XR*iWEIh#R0$mKg!#>y?P1Sl9{jZ?UENCHR#8H&yTIN@uf|{ z{YBC+g|Fr{8|RX6Z;7)t8!D zYZt^eR0SSkI(dkYH5J3-gW`K^lCcq)9Fev*`T8WJSjU81aLz>pMhXm9$w1LSk^W}R za`YzyO0`u@2(u2UUIjX?0tkb`tM$++aEL;UY*b`BEbIPU9#E?N-OvUa7ZHL#P=Br6 z#j_vnLBwRLl1m%LmmynMTUIj9qN38j4uEEv^RYWM$O&^*yARN83sAn3w1!n1FhZ6| z-->Vrlh9mz`$0x@#uY%10HWI6_)+ZiK(O?ZyNL`pirx3 zD8n|4?~O0kdG)fC;(J9k*|%KCcR13Y9gu8rzD|q#X5daCN+h8nY(AAU-@s=SL~O0h ztleWM_3W`v9Nm5pc^Quh4meJB>e*m@$XCmv`M@&9kbc(J`t6~FZ~NnlZBU}+eFflghT3?W`{Qc?iS72G) z^%m#2=0P!fY@e%ViL6oYAx6}SuT1bM%maC{uQn^(sEMIDXd~tIpz(Fm))k=s@|nx9 zI8Bz=0Y?XUGY&P3D?o@`GLshgwO~&@SI;uXM9h?LTCaIHAg^&@vJX&?;l(F#`luUb zcxKXs<}`~B{J_ADrHj;>p=av8=+fBRzY^C?7i>n`$%GqR)<6hTCEdj6@zUYPR_fqa z3MF+tz5t0N(b zP4@peFXabOHDf z z+@#d$ISRjFN)pC4B1=rpMH@|Z{P!{!YE~k>tc;D0t}Nr)$87A0@8g0PwWmuoXJ-@m z!<=?(@wo!jX_ch;UDNfsKaRN`KO2Sh}(|6XDwf21ki+nxOEsszu^y6t$s6%SUQ~I7}VakPxO-p{`OLuJaQN-4DH8^$xWdhxVU~P!}Vnu#YotUup zUk|S2OpY62OpADqZLFpNE>m$vEdBdVI%_R(oFbd?&(xszHhANVsv@RQN@dn;9Pdiu z%f^0sBxuClTAnLohEpE<}aoG2#bZ7K;q}dH5=JwR6FRhV|q2AJgQ$a-cOG z2?1V03V(0`2I>TPF6Y6bu0+b5H(leDW19BfiD&v3$C`dbGUOb^q+w%*P7Lml6%zD#Tz1 zzst!K8-5M~oyu4bKQ1+9-@Ylgis#rFLw7Ds z=NZ9&xAKvY%SpiwA0! zUGsi>8sICBda80DNGe;ZE9JWYaA5dvGac}-Bx(2?*ao`IM(oW^TI|0YreO%W4xIBnPWQ!I2L4Wx~6?>G6U^&hrEj`chHST z;V9c`lr^a)u_x%<=OLJ+d2#t#xbESv`f248-_@_b>u8yt^3)p;H*7srmHaeCRuNmo zUIKz+@AS!b)eOX`o^a~w3qlaQB&(5L=Tt1EfK~`vN6Ms&M6S&?MR@~&ARvKQ5CZ_u zU0?vzOTx+gkdg*J+x2Ixh6O_L%_9?UUM}V#B3|)+NST=NR^|W(S*kcYcK!{1Z>_u7 zh#+|H!>%m~OjDF43!U_dJ<&pPt3u7Bo}T7)a%OZqbzP?HjY4LVt&367ujA2^7)wYp zzl&u+@3=UN(Cbj+^e(~dmalnc%GbqK_d6&IQJb>_qw0T%!vZ%P#Tn;w3<1+&ACq$LKS)q?67#DF*$$ijUyS$s;Sj3Py^T1`W zGnYxd<+e&S+hyy31U2ufVn6~1C|7`C{4L#bi*S>92$50E>yLfuV%nCQ7If;aZdTj| zx==pKCnoWkg%LEhHE5ZBSt4>SgL`~iJbqif{)a}m=x@=jfzYLz3iP-u=9tuf&W+Gk z_9^g8=}H9vLga*`Okq5*{ycsj>3UG@*NomY|x|y+~B5C4@i7L?(MgnDV`Fxv4s*NiNXZ^?S-FHk1iQ&Hjm?zkQ>R9sr zL;lQjvksBI-%sGN&?TZJT`l!2T+G_TKWv*}qIYhlUtQlwS2!m!MT$HUU;3)U{``1* z=Si1WCbCJwEQM7!J2Ypwt?+>!=MEby(xbL1V!e0sPGtBqBo&XjcxqW5qT*99vtOGe zrWEL@a(xcHzMf~!+kD&BsE=uPZ%->#_QgJe2u>>VeKGZE4ca!35$VVt5M%OT={?Fo zW5_N+B+p-;7-D!7@kP@%$>gE~Gd!;{>u*=vH}`dOJfU+5No0{fGQaok@x4oH`?mTO zLp$4l(v3?R9^Gt&0%NLxCfGD~xdCjvrQmj@*J<3gew+q&rN7N8jl@xpVyeQ-;MuHCmu6IA)n@&eyvQvgXPu$0W^{D&t zw8{7sWZxuz{--$*ji^+l)?AUO)gJ4`_uEK)H1AW&jl1P(mcmtjDSO;kQv**lsj z7(=()@O>Oc7sf_0jZnN3xko z9`s;KGPFLh4Jm>oqW^aJ_7_AH);44bkmrn^OV~`x5_QrJ6j2K~q#g3(feFLQc8t{9 zyh`&tK7gbRaqa!p;i=$cRs4Qg`vRH^ z7z*!oJ6Nus1J*a^vbe42xMt;=+mW{LylrVMU zo*X|9N}-CcuaidnQ*;8m9x#7^D8gD5S9agBsjqZBi2d_Z&G*;_hwt*4#$U^HemrIK zDfvv&;V30(B=DQf#^iYa%igQznJ$i#WBSdcm%WUDsS=p#n9zf1sp=^Z$*q*W8)iT? zk{#d0phQ%vcAD(COAx+RwMov0nMxGbHamI$)hB&xZ}mB=;}g4sH4N)_xR zO<2GHV=pO^M#x;6r~+0*$oq@o`;(8=CsdYkVF@VUX$^4TR*i9E0Q^Id zNM5{lZvf}q4HA9}R__pg8J6mJ<}mW*#U(OD!u*FgTr_STkcj?CSZpd#{#e@umm2zy8}hL1 zz3n+78>5I-)+j7$>!FkS%})oHyBOXTS)u+QBMG)%qsqM8O%~;ZjZO(}P{a>|Rur}# zwwO*l_%MT&IX1UhPz%)i7rHfKD&o0Kb=zSGYaAHf^NARt_>EOH2YJt=B$n!UEb`eV z4|4HeF90I!1l?!R)T>4=_eq28nB#@DSQMZUbkT0Np&lU)k6?8Fl^H(ZcqzcSmQ?Cdt#vUSNtDd?BVJ?=B?;><%fih)_vOseelO?#HkL!&~;X=?S zbKWIB%QW+GV!I6^y3Zg2%8!pUM6OPkXK#&9mYEygCZ-fz;LVgKU*_A&3HkenzD2@0 zMV#mp=)iEo=W1PY4{vomqFRW$cgI&w`c9@UFmB+q(KP~<-~ZIy1FO5Rvy8tSZoA1% z1trN%z~Q$we=IxWJ~kfeDP6_Jf>u6dvwEBR`a}OF4FQ$5|HoeYf;b18+`;%M$43i7 z-Y!$%c;p={zp>MF?tp)rugAF5B%m*auU(gG;lWm-P%F!mFoGV`ZOi+yC*;f|;pNaF zj|)AV{T3NmClr*}9bNpmXx)pV^{3eAuO@8&CaM2=@r_`r?&#-+39^g4Ze+gKN9MR_ zZMjmfex#PTMr0W~`Ka#!Iaz+Av}R}98TBM`yp>qX2W(}^=GX{5@R2gxcR|XJS!iwV z@u@LBT(?b=v{Vj;u;#<`-5NQwE4)*B*HKmOK#!(pDv+pvCWr~h3&8rO9!cL?p5I*L zO#-e*vu0SA?|6*ol7W@WQq1MMvOx9!3k~SO0bk038nI7BQH%?Xo)uq}P{WOCZ4eA7 z-<3TM;ESgHW=rf(dGBgVFArt}ic}XKp%xdSaRFFgMz+7Ykfg{{p@3{35l^ z{w#*X;IJ)H;9iaS_4?jmt`I9BZ;Po)#j6qK+NV}gR~UOlg?HSp5fk!lL#!!VA`%MUPf==sQzlq-zd66QsQv->yF(s{ZbOCH}7+EBr3KD7&N(q0lAa zBs;@2EF4SI>&~_`i8Qf>fL`oS0Nhx5^(G3v!Nf@6%!b*>B6uc{WU3L0_W0zjzu(3nP7IY0AfH}nWHG|j!CvihQXZQ`L=_zXhT@7HPl5Op${iUp3?1l zgdIMRI0hc<8hm>KT*z%kIG!+ewlE$tg{5S)mJ-UBbr-HMokGRS_OTnG1MI$)HbR^o zfnD&*%cday{xUP&L;@0B*-R3r zeRTh%K>bUPf~aJBBsJAgZoo}^#f+_v#HjlJRSjl=zS!jfFzgqxe9zLsfEr zy*v{-el<$C5P-wj1l;)2D{&~u8+O`4BKY05bl!i#w&Y|6quLlNtOnhNvklNc+Dv=c z9>9$XhPl6q4PtCl086tDbK%YYQ2$;46o5-d^24?OzgU0#w$U$XEh7;zZ*vo%@lyM) zWOj2iANqsw_+cWn8RE)q>dNFyd;-R%xE+Y4?We?X_GeWS%)T5BIan(nsb%_}v;b?% ztxK)s$KVqDoO|d9KK(+VlI%qQBj#A=nNKSQP~m3y9LWC#QzY1dCsgvw-sEmeyu}Zt z{wB_KiAti~GNj8=eaO2v!#MNokSSlm(|~ePM1j+>1Ow)hq-&KJZHtdvKWM&h$v14< znC|EeXkZ0acb|iDE~v5LWu(UFF~{jqrH#NocIA5=7N{Wk+1_J?gZTEblV;_7|0`A1 z4Gzs)$k)Tb5P|N{VboK&YJI=TVRmEgNxKnfwNoVZz60!|zh~kl6rg{rAkWcxTMlze z0xu12^(^B6pmb2B_d7LRlk#c5CDa8Ro|jFCOKLfFN?U*jO&Am{t^S7r-VsJcr?V$> zM2|k*w3J7bJwr~O3kq?>O0fvld)!sOM|Q4<1(t zD`Ds2cH5G?A~c6utu_}ke}piG3`_5;h-LVWknFr`QTGv(M!~nehQohwGcqZ0yOed4 zK`zA~AWW?_aY#9Vihrn^&ITmL#00kAKVaPg-!p@t(zhq%SA(PyT-fZ6Nu84LKgZ@V z!|OZk&G6dDd+5GnfVnC`Lz;}Y9CXQ~iO%(GFd0qV`Ls;~272RI9RPW3^)$9G2ZzT7 zTjhrudG?7smi=BDrlGL?Y{6HeuR5Aabv~BjH*-7da4}-IW@C{&6z^REHQv8b$_dTs z#@L&11q!oA_&Q>O^A|GRP&~{{2#+cf#1+L@R$zYcaWU3hBo)GEOjDb{2s9MWE%KGL z%t+CdhgSm8D?h93Q^j~ni6B>e;U8b9P1HBv+^*`wKoH69pfv{)W-Uy@thrieB1z|s zL;VfHSS$`ERy@9L5Vme`XzU859CKSbqUIb&EtHlhuM7c>y0Fw67|X|joW<-gV5SXB zi*-izC!s5H75|wEk#`5+?!dF$iQMyE{+da0c!%1((TB&uSP)Qj(j2wkPWVAfo;zm&T+U;R4eJJdEzr2!uG2VrTjsAT$@7(wqy!7gCrH((r6Q{l4={2mkbWUIX zPzwfgP%^goU^Nh+KcyI4bGp`I%_Zu5jBxuF$)3z5ns=~SG6CW9Ekx?Dr3WwbtLdx_ zf8AgZT})HTxKDkHj01eEj;`HHaY% zRd&^_QQe!bb=n)6thWBMKD-mYYb9}b_wS!v$!+a-J0sXjn4u9sE|dE~8n%Xux+}-G zNWC|TeYSs=KMx9!H(L^IKkvML^p2@Wx1u8nAC-O4&i^D>Hy1Nru z6^@EHBKodl?{C!0zQIns1vH>8mO2@3nAZ)sk8>dU)Sfpdjl1*%vUr5EVFQUHcKL!# z6iXRCI_gp_=GxkK5MuTX{?gjp9{;@h4tSL6><`UMJ5q!;w|8{;`M(*e3L>pS^d5K~N}B7Mo=N z#jRFN)~dH$pM@(@wIlv6^wk8mSqU^NEf|k$U1j>`)r$h~R=z#gZSn%YdxFEvKNTw- zb6Tv9xa@v6pMK|A!IwM@;8d3^zeD{wViu?S=@TO!90b;rOF`}(Jd~~B)D77A4PYoE z+$xjd1<{}8m~CF~YkMJCMF1vFG(gK@!AZLK;?4R5EnWv~klc&)ivO!|^O6G`f}dUu zm&eo~@oq0q9@0coQ4tYY-M9H5!_sh&8Bk18_H#(6BW?ECpOGx5;#}~w2CJN!rl8H> z=y@P$ms~Ag>%V63ry)q$1K%;)@>T=8CX0@_0%ilNxt{1pU;Z8R=a#%!Bsl@=xQ+<_ z9%O?2Ns+!Dc+ZNWd5)9WCUMkvO>F*mb;<(POE4)(pG7yq5y3~VV&dP5n|hO9CH(K^P=U3f6cd47}m#)leFTI51qfmL^2?>{FVy zz$p&aBd5Drr*)gfiMAz;TK8HU-RHo~V%rFei$ErYi)irJH#1GBv&I2LI$1hbjpk0r zWC<(S_qG@Qs$9%9wH9Pgne&%hpU@+zqFKXkm?7A!C_T7xN;D#mjhKT0j zIG}dDsd^R7m;qnp>wJFnCxmQ6M`E;A@=pgV$?xZeph{44_t%f!WrY8tAD{0$c-0Mv zP@~RT{-q~M%Qnt$K2fP&a`|fwr#*A3bs;AYj5$`dDG9nNdL%>h!1MArF{(qR&$f$D0Rh z>FJ+eL2|ahqyIoMo7NL7`hT}#Dyw^=j5;S?@iUoIJH*sV(E0uu-qD+xCe+!~)65z| zrs(TEekX7y!%iZ>+S+*Xd^J>3ZV%~a^>{il;VeFs^X!ZE>9J(O#!oANYc~bU(#zvK z{Y7w@K&)A1AGJSGV!Vr`kV13`CXG3rq|UgI-A?!}TV*$u)YzDgg)SxDmFfe1$ffek zSL1#FHUSOEZV6};Fb#cE^h=hM3cridjC@xcL_BY%<4b3jbaQU`s5isy|2 zwZDG>*Pj`m1C@8S4gafu8-jXW@isM0I`=?Z)AHw$@f_@4eM1NfvVBB5G9F9f+cXCL+mK|5~_n6#LQEWnc6 zxs8BD?mZ>|?|OqN26jjf;}=^c7PudvX7mgD*L}^i@dh94xe~D`qzt~y4dfPq88E|T zQJ-&9!#1(Y3CV}^K1<82=@K|Juo{{Kd5L~1K4!d7P@W$pEohDTumBUp?9sKsm?RYaw)EzkUvY4E?C_Dq znSUKCpq6t{E8CvH+xwXMWH&AHDq0*cm>%{0J43?EmH~WY42twGa42lPoNgwdM|VD`kM#~XbXasC$Rp{OD4QTf-mX2H*$jhkYY2H&cmi?he z&(cfvEd-(Pe5yc7sPyJs)C6qU2 zwZHAVOdwe%&?<6JIDb8(6U~spwRqP`?&$Gu{DwSBrKZt)cR`H2+pz?c#nU5$$AY-! zn5bW1#?%XBhE44>(4|CWiCQpxZhlA$D11>wpO7UG!(AD`Y-!@r>FwWfK6?N3(YJP4 zn(h6IRWWitW+rU3{KjNe07iL+_&Sr?iMi~F4$wJcKjF$MWd!RHtM;lKg& zJYZ{d;uitDvSTQL@%gUbN&O|piZ!?UHuHX09CA!r-rT=+fizC)HerSu(h%YC0T|dS zibw>WwqTPea)!3bHew(z>25po0kCBTbce|900>b!JzZTLP|O)E2qM`S0Xrp!I_bI0 zJmaPd@{}bz9@Y>uVMGEAyhEm~tP9t~MSF8=APQSjT$9V$0Jw~OLRDb3AK&k0(L4L! ztrmC8bJQ1g;?*<(7ggNdJBYplkp}8Xkb+ADQkBwH0(BCtKmGL75(dT+_8qnt07L`( z$AYIv0toR_-=QJ_R!;ahGN|V!4-j*eN5UOwh|h`5%InmXfN8A%SEw0hFMmp_+P`hy z=6`edFD(f0ksff3oh5T{;C96!``9GnaA_EiQNyI?JekziW0bP^zVvUrNMOuadG&H{ z_&4Cua(irhZ;a*<_jG3JR#g>()#0`ste$rOgH~*Hs>nd?S=4!G>u3t)qaf!ImLje!nh(^A= z1Zi6K;EJ=SK7i*j4m%guO#1r&u+9no%LcWlJ`-@{kA3U8co^YdR7JT z$@5yAdbjX~V?FPFI%i}sAj$)W>GHKlneiJUYt*z3s;by%E<&sNJnudS)3o+-K+L{$ zy!^mB5$Fkyw<} zkrMQ1+wsDmok1yb`gS~_#B?9>g*ULRxyv#8PQy@lN)g}z(?|9~pie(dmRt-07tQ9u z47Gs{Lh+_h;k%}LmvZdQmqj?DRYXQUd5vzHpN7VMk1!h4$mQSrivk170Es>_0_4rA z!qfdwvz=WdzrQcB(QXncSlF1n3ks`EB{2oj=!9xrnhSt7)qrgS@2F~5R-52JdH|^e zv0gJ6g#;+9SJw%^lpnmFf#CnLYFwQK!j*sKIZ=XpDy3leY?Gt8}i#={e@HyN{-lO1_-~{e=BQ_3Z18P7L#Km=N&7L8C#qQe(Bx8vK^| zM9988OFE+mtlFHfRkfCi?9O=)M@h}|C}0?@s}(hh!sEP+n(9wLmP&6n<&k?r%mYe` z^b}XCSjv~j%&2vM+Hz|zG>Ak(2NHHw>0@+0_~0%)Mw^ciwg1mt ztivZCBms(=E>`^j=`mB|bEp04aM6eIv-3vD>8ji`z+5c|5@#h zzx-<0#gb%PzQ$dSmr;Do9oQM!C^T!5At@=Y7P0d)lR;L_QvBzNZ1Za)9?gG_-3EWZ z_nh;zEH2(~&-e`(h&u)6>A!*JjrZGh83c|K1@%h{7)&Y+`mFo&jg=c_P4Q)BWdx() zP_$|y{-NyS(=6}rR#zj9OZxN9JGGZPtVCS!h=Ncig_%f}^cABSpN#Xd^Xs9;(+;6p z;}=o5SnvlKy`{8j~t6Lqm%)f?pOm6X;{bEU)dIxP&|p~?ktR%svDzo?R9Sy;45Zk z*CjJIcofdVZM@^>`tvjSe0zyIkI~VucLoZ3FQRf{GboydlPRUdr#@!ZEtkVHsGqRG zuqwgY7~Cv=5aL+(oB3ps#DCHkj5&S$&?S`3(eE&IwsOK~le_uC*|9Z($%#e^$BA0z z0c!h!E89&olnkd|tfRFPtUd+#3H=0HVgCyS8bsUR_InQNW`W110Y+mRY0*q&{jsA* zA#lH)+O-A+R1iLimwy+)mJf~dw!ym9_$qd0tK#hIJgaN;i-0?j^p?Ha5RkG9;wz)_ z`wsNx?kBV4981?uB{i3BYs`*5^sd%s^5UNDwoA6#O!9>h_d|^TJ{Q`b{bgja%dbn` zT;sQ-w`A`K9^EPAd<~sFxMu?%Nt2Qtxudn~$|zy{qlYm|$>R zIk=Tp=lDyjNZt8~$sAY`@l_B=GRRs)xQw2`GTrAq=kT2}36>_Bjw|P;%vo{xu9EH- z5$Fs({W2ok_2*%vSC`1lcN9Eh#J>y5uaC12!E=hQ1DhfqnYnBO)JOXZT+SnFf$)sN z-^_kZM&*nhEa0XRJ{dwsoU+8$<+$y<*~ts1A+&&_ShQMsuA0ebA`7%c+|PdRe1A0f zhDS-_*~!wEirJF!LMMkM8?*8_1B=nM=Ce3>$BiIc*fXj)@4_(F z_9hiM8kWfNf+C*M$Yaq|0(CA8+nsBi_Wv}%iPDYxDZ3GBB1I$>H6~#GAW-~w7Bd$+znPlm|-P!>FTa(~|g5j(1?Hx~8-62X^bcy|qg;HU6# z8CW&W0b&dVhTyg2>o!WU_j&)++NT`Md0k8_(AWmcnuO`N(gY zMcFXhdMMvko~dmVc3S;a6skX^&_B5DHt~a2ib%ds&yWH=Ybv?>0c?iz8~K-qp~xFc zY_d@@#}$dVor5g*WOVwF-+7C%lDQ2xx=Zt~EPAIn1BIjGNdGhZvPwxJIDiCT(Y7p( zYv~zyoQYFRQg$Q?(lDzQZRZlOWoHT&Qwlo39xPbgkTD02=w?*E%1K>hV7ai4A{?~S zf?3-+{27HmnlK%%A`LU2#8EAT79OhGzJVsMZqCpdiRLJ2AJacvYL z+UuDAoZccz_!&52^Yv|5#9|&Rr*++2T^g1v%fyIs;tMb?D${{IC9bHoON8S|HgSqc z2T~n`hRJm*Ud%}On7_RBGZ&8Y1Sbl91qLAf0=JQb=L5Hc$|HH06m9mWc{Z?Hb5&IJ zNWs%a4yhWEVg3QTw!j)L#?BmBoPCduy6p@Q0%?Yw*2$&B zW1M!f-!Y)-5t^bQ2zszIo_22^Nr5ZPi@J2Eb~#3Drc>gWk5d01Nk1tDu=sK*N9RCZ z%J@k_VgWfFd@c0XBlN~nduK?$!@Pmw-rMuvxtSDFKBp?bIfKCVBjSC|jkzM(q{&d= z>1m#>HS9s_h~ zHv^t_iO(vBEe(kE!NDOdwD&>Oi@~$y`@jx1O&uxvI9}9+&j|o|bzp=d_%iCM2Wqvy zpKcKkgT1m(+Flfl1-^?CnN#=#^KV;D9}ZY+@+{UoGVm`)>;K2uTZcuter>~w0}N6F zD4^5~AgHtff^-N9h=NGBV9+HX-Gej=q9_<(fpn+H&gk?lCo z@Qf2e<|(I9LEZrO{!tnA1tp9|U~pDzf7)#aU+>M`S>B0y;eB=k(4~F zHJZ#KLA_evX@74wDwsV<)wo0@7%`i9u(>rzmAR0djT}y zp2a;(tpX)Z&PI@D!~Hp$*kMh5UTn8=16!xL4G?fVspBWQ#|{SYly;PjOVf06l9eJU zh4tXGlpM;(l`zq6bMK~0(8RmnSlsjw_u{+ivj(3|mYS$|A4@%+Ealk`wc+r5)xM9t z`ty6e$juRUWxqs2hxCZ;X{r^Li&q?H)qL!+5nydJA zA*32lUX}4)0?&4PI3X~U4PnvvZe}dnor{uM)AcnzN3Q3UiZ;&}?*SQuHyu-a^m2An zy*g>ay3O0{PMNK#Hx=m*;X*o(sy4@`g01QL!D1iER0m4dT#Rn_Y)$KA(s1E7uPjHg zUEJ|fWS1EMQP?u=>zGxffk4?drANS@p-MU0o<}Kl@R7C{)Xe+>upMTEn$_>^L zO;9{Fj%Jo?8GN)V+JjxgD^`Ymxh{uJg~R<^Ug@s<%Zu>O+(K=$&Le9{W*yA63@@90 zn^c|@b|Y~8SKnl^&(__AJjS9U6K6RFv5%GQ2b4+*15Z^oDOIBD-)6{Ck(tEk@xrO~6WV>t2Efw^#-#d46Hw%2=d?_omd%%XLR z_!xW8S&kbGdR=oO*iWc&_8gIKC#n4y_x7C$rSD#+jy1Hs$@k-_rQDUF+^! zUbl$mAeghX4_6;A(;nHFI+4UnvK&n=w39M{CSKFfbrY0&oHL}9>uBs{C!tv{k^ABI z6+Yz1h+m4kzzUutbo5o;401N2;<-&OLC(;uJEbE9Zf#+ptfy)zVu|{a7<04q*ql%&MNeDyqx1WXymTzBs^dH7`&k%k|vvBxz~ zqGcTz0>-)cT6Hbz79}MHFEDXt^x?SVtJ6P}OupT{B|)omGW`5mZV}q+ny=J+^?W`? zYB%W`IOTp=x$$iJasgLM-jJn)=7W!qPj#52zBwt>#h%V5IpH$aeyaJo8J$h0ukHZ` zn}aR=ue`1(pZ>~}ymPAQ?6D{%C)g+UnK0j;Slc|C3_i(}x9YEwKUS4x&<;p8SS|-? zGujJ1clbgvcs$&iy2>NF@0?55TILGlYTm5GC9}YE+ne3dSANg6TE>ngl!I5wGPM-M}=>1X$x6RDbhS2?s1IkZUWfL3kb zZ0M9QTc00DRt%Q)%N~mtWL#F~$K#|u)FV_(b1LoRF?l%|48_yy{#Y^wyttvfY@sY8 z!)N9*V!^K8$%2;x77yL#oNQ3&9KOeyCKPONo$b`7p}xTb`CX$as@1*)!I^3K$^2iI zQ5cWx10FRyIN|-dz!ckpG6AXX$qij?Uv2S~$y?6TN|wYm#zw~J=+z^QbskF|u#ZA< zCum4)J1?FybJ9gkFtoJMj~L|en#6r`5y9~FpE;zISr zejIO~xT@RQ6m+-bpL3Gjarpt;4^FA3B$|VnB6A93=H?Qt^|~PJV^%iuHdX^4A;hy4 zt}Dht=D9HvIsn(!OSu73x*ch0@YVl7*~ByJ{=UIA(fwBvjFAeI{4Vn_USxeK+PB}; zQjV2@urW!j@m1i)>z$KN%{}!Zo>asF{nR|6(&j!MBVbk0SQjAr!%F;lec>ybjxR%F zp|O%3I+it>Z)GylTNg4{^jRj1s#X>1=jl#v%baX}7cBnN@WJ(`H=>;%I8AG>FvS;$ zrry%L+u;1`oKxby47+0RcNeFY>4vmW%U^C+MV}bo$eN~#7MFsPqW`|xhpBP=x6}07 zvyzOB6Y!TQfu{7hlt&^JHpOAOFP3E=dnmBaQW_7O7r*$rP5yLbxnXHMWwiJY!>#`~&<(U_yg z6Q6R0()H?gnf0#Yc4=l7<*uQ{Mjc7_B=ghk)(HV7&gBq`j&DkyTDH?4li^u8O52Cx zjjfB=^hUFJt>$}^H1B79i8p;=&n7|}HaGjlmA*>LQ_4CpO5RiroEUq@9dd6=h0oS2 z6RIs4T_mw}G9{mXrdwIncIxVBP&zsLV+*4@N6Z6s<{X5+C%}zR3LakiE`*CNxndBP(p~XnN+l z#f#1tSHk;l@MtBZq`$jTVyI_raaCDxpeeYX^M|3apj4-Il~(SDb7RiaZ^1?0s&Sb( zY+q_hsHq{Hh^{Cx&CHj7F|u%tcDjFCWmLbmB5Je#d!~h%-Yz4F1yW<`DjV-6A3kU& zd81UaGQjtQPBik71j9JGVPV7m-1*Fh!EvTv9B%Gy~* z+m)oiiS-$!rp$&*;pJQTEiNQ{P2#LD+g0~*`;fHel2*l65n{%)l{A$~^*!@^e%plV zynaV2`>fmd9KMRqAMx|x=0{S?@6$DWT`o@GEcvr_Qju!$xi@wASyGY=-E9}_H_Rn_iWScbKR07HKaaCHhL9?MNh50CPVJjsiZpYYhg&_O@CKOZz_MNzlJ`K z!=iRV4h3v5q-+HB!DWSLBE@Ej-C+(w9u{BHnIn9D)&pgZ0!Q-T<2>h&8!yyd zZ+zh8eWa>UkajOgq2w;&$Ry;C`8aciY*re;M z3arsJO)N7#{XuCvOVLnk*~hGh#uJpO!rv!i=t}SB-><9Jl_@Q*H`}S%dggtM+wp0# zZdPmX=NLKwzQ(?54@oHav8X-7iq4uv>0*|Z9PA|3zwkq(O?HTsV;N1lllirLuwzYm zrj!%Ena!a{A?Bl^|1+{6Td9>|h3!~?ZNg=X5r?{Cw=Z}Zc2UH5Vnn@KECEESH0I|{ z5HOhNzA8ONzLb&ej_#dEy+Wx8htp-eU2Bz)+j4Q@^7K4hRLXCvRjPS6 z#|Ip~(zN#Kv;K2i&X($KA75xU1&wP-INfzDIa6Y2;57Ye4+)>1??10bcm!!v^)P47 z5?JL7JKtUN?d|Sd_~QvG1a@cf?AZ(QtqH zIZ%!Lv1WoN`*KK;;lu7j+B2u(8sTVa{rYbw^O(<*#>eA5T};h7QdxaboE5JGlP<1J z1kmxVHQkR*HZ*=O!>c7$LHWXrrL=P>&2H;k$R3YG;ze9zeMRF$^rvd-QJ$?&Ha~Ls z28^cDWNc^c3{048^Bq$^nQ;%yUuXSQ)cAxAhyTGr|6|f|D9=Op=FLrcQy5-|Wv@Az z9{q{yb7T|R+*zdh5|pSv^>y=fy@+AFJ5M6@&gJTkak<)-Bo5cLsi*L^>MqMuDZG{? zTo;?}Y&1Wp8T{GmsaLzl7yf|a?iiY@#ooI%c;{ZhbM# z%)`*E8oaP&Eo(REEXt!sptqYHfNHG_FeB>_ENP(NJBwJr0HtGE56R} z@q^hk+fwPJrJ1+&cUu_dgC%2#HP`zoO9~fphJ(-UTDLOKk2wA;3@!b*GoM?@Q<|P| zDy|vX-V3$4OCGvBEu$l1v}wi4biZs#yHyE>Xjj6Sl5)cbhRMsiqS9HKJPD`TV<8;X zmx{MRYzS|9JRWP0OOuHY@e&+x39f&hk(O6!)yjOmMS*nC#f)aD>||opW3|&l@r(%q z&B}%UMCjRqAtfjH+EU0AlyZ^pM^19?Qc0s@3oNE4_vYY4gdRu}IT`87#CPX5dpUld zr&RdBDdp(tB8Uo!0s!JwboN#c1xddP7Qer0vhP}58$?IAM87@&XpnA0FHRrhyc~Kf zVAN1DU|eNj|^xZK7otGk@Sxi*DZ!n+AsFjw0CI8415A%1n~0xYxRTXX zmbmqa`o3DhiGTNxQ!i5_BTJ-vSh}|Kxi`c2HQcLAI6k{d9C(He;!$24mr#!QVxMR>sKqQ& z4$k;;p^B?h(ZuC8nIR*GYEo&Mr&ue;`nOJP$x`exDtsy#1q|yHt|Y0tOpJv7sgmhD zKR*|)pRd0#k{6x~Rt#aas`ht1bc<4X3sucYNtEC^{o^g13%iHUo5HZ&tnb6&)s*7D z8cQqL6cF4Zi6kn~MG^DQZ#CuxPEwjp~=SRU_wuxyWo?Mr4GN@PrMOqe+*=4I8|Y5M8%Rx*E^ z*xG~M=6N+F2|6dgSARKVeR>mXw`-zumTqw zy44D!0$5uCa-G#I8Nq(8Y+R$ZqP{0>s%Mc`e;q?|3aa4cLP~2kPpyZ$$6^;;95Rk) zU$PR+txm}Yl_M#Nt}wqTH$J`)d7f{I!4)G)Zo%! z)Jk!Gl>DNP0+m8WUW}=Ng>)M>^wgnNpm~`23OrG|2Q0>0Ntn|gOmN8w@|4#53|hl3 zEpT1fUW0;9YC_=yFhJKXITh}jz7Pm-FHEFO6YZ`q&jBnpM1~U|dZu(nnFFFzfBp6A zNe`kAP_pskwNN6`c%kw|`JRw)3Y9isLL?4RntN4tdAExTF%mYiN5h1@gTASgE{1N@ zo=FTQ5yZKdw#+Jz(P4wD8+ND^&=%ug`7X2mis!tg=ap?%$9aj7fPF1&4SU*ld}*W; z5Vi{z;_1nNAsub6Ne6&-vCf523S{q;k3;oB(L}ST^aovk>5tA_cG&w1zsv(@`(;~h zQunV|a1byAFH;KoB0M&P+3Hbvmk?cCqBCVojV|?Q50&P?iX8K(brXL?ER&qg`{`m` zuwrBWvB@f9I>NF{NZvd^ZhBnO&$l!Ikj~)bAk<7(JZL|1a7`U_&A$^~GFL86q!_B5 zQ*t&Ohceo_ysNJkfR80&w7YKj_rUAL2nxk#5#t)i83ze}Gg@Eoq}&Ea5AEP>ych znFqhd6nt#n9to1g!!g59?`9%6vc#RsjIe3e?B@_PS!=A$=qhTdxZd~K;3V4IP{{lm zHwU5PWqPjsunK&PBP>iaNcI%TC5-RyM=34_MRrmF*vjDm%Klm7b%`RU@hb}pg*VLP z{nYo%!Pp*RX&TMYW}J*Q7{VngE(LB`l*QA}uW>GovCc44<$}n;_;XswD?2hTrwubj zuGNS?YK2!u(Gr-Uh+4vi7A#-Qk$ytzI4Mka$> zLI870$z+Oe(UEm&Wmfm8h6$Hh z&U`RwGRAvL#V8`GH5`GOf}(!^C1LVU!?H31;%=G4^VH*~%1@JIL~C(;ctq-`jXJ@L zngMLRnB5pKDt3P`_gYj!<+3bhwDsWY_@qyC1k8JaG(BMhQ+I_q_oz$_tD}hAIeF$| zUWYq)IV}{9?=4PojdBL)?iYJ2`;|18Gs^X^$Ih4lzqf9$wl&E44|`V#?457@+ctq_ zIs&s(q7YHK$i&t_5lm6Jc zlq2CvUTgCD3WrCp25=?mXY;a&(POHHqmGIs)W$So0JAkn9Mcr}zrD4iumb1KC9XaX z3vIc-4A(V_OMYN+bX2*ez0xE~C=o#(!P2SMgPYiiY3m^h^GgqdIqih9T}0g&SvL=` zjS1Zn9uwwB=KAd@+rDU9r#zyFDUumV%khLAc8gxRhPa{5*k73@z_Zlcp8|G{);p+d zIt5L%b6^X+2_cKway3T-F_(@z?**I#4^X~9l*&McI*OPv5^Q0^Icpy- z?v1tUfg~8ioAj|XefX^g$I@-8gKD1#NGn4lv7&DDx<^89*2FaMP)bkvpBxc$Qa4l^ zt}}<+c<}gBY18l7(3_{Bzg?%jqtKV*9+G{DV=wORey(M6|IY&JUFMrNPUOUbM8KW< z(14s6VDATJK5GN^zHz{SS|%L`Z8FocV4^DDH4#f-nLNHZU}zi&7nVf`@xg9dNS z`uf$7D`Mj00*%K>GR8eRXf2NRSDRfh+Y22x|8lKeB-oFRFt;T9jCg1~!*(UM^oafy z29geNr0x%>(#(R;+25YVljdx8ja%Wh`ICI5%gIFadGqheNeakO`SdS-Ka^ue5S(Vj zp2uUVH;#v}ipKTs(6G>bl?Ot$xOa?j2kSHMVag4H# z_be4Weh1`-frYefa&~ilMQsL$`}`bhLdI&lP=pI&zCH>^`qWvEQG#fef^G6Be0*8L zDSXI|ju0+Gw%iSVXj#;J_bzPbUPP^A0XQnj$eUF^pK;xN7|sSpWN4}rSNhQ?_FXq;6={!~G__Fn00_14lc zLoqcmWs*ljj)YK!O18$r-N%zF9GAZu%f5tAxIIhD@^imh9=D4jVSrzKF9S7zW-zK@NCT10oSc{E~roh-L zJXjo-Qw|cIc&p*Jp~Of+rO8}Gk0I#NPO6MJ=�N>rQV0OS;A}_R@QWI{X*Vx|=@1 zzk2L(pB3o$G`@(D%aT@&VhEDwM$9h9?~}h07lgGz^zEDaG!PBo^sJ0%GmEt3%W;Lg zje$v@wEs}-`DfsRPjIO_tgy+>4JVDzF31DeImCCgb{HEOGLI^JtnB( z8AlC<6c>ZAc!!UsQTWfp;q7NDY?pLEIsM7}-XJH+jvf2D6pIIrD{uHrKrP32{*WIr zPIe~YwL-!iug|6s_}L?|6Y2T7Y5?Kq#9Prlz;$7Juy4Op=G1+GiSCFr<(v)uVfb=Z zzgH>$D3AmxG~mB8?tVK0XGJ}h#ZCOLM1ZzX^g``*HVOgg>yV?k^8r473B)&%uU6>GII!PUaFa05qdQHu;TsH1QzyL`0c6 zO5~F4oCs(*+z;Fsn1U5cmg00m`{c2Iv!dRaxz}@)LN8evZXCd-BwEzKjF{i0PXQ?AcX*bBtFSnuRJ4IxnbT@NJ}iFFlV&fpb9CkB|#Aj zPdWtFNiYw6As~#sLBIa7eicj(hK#boEIg(*!TvXEBsS#nxR~votyl@Xm9*)B?__ip zUYkz#o2o2#G_L=XO`mJ&^jBI&4Kj_erGF$;8Vjsl=*-+pqTGgXqFDt zGxfSsb4;+@?epySzOv##7G&b`T`3uBT=AfQ*Cfe>Z%@TY2PKk4MjwtgXS`qds=vrS zg-f21K|r>N-orAYA#@5G9?5)ldh%^FEpedCjRVwjUcVdJ#qi^&4~ByQYsbW?nILYt zCwAJm40281h^=niC};d#lm#bV&)u}E99ll3uOFsO zi(~?O8D-nP>j^_8^ilOX#z>?q|HKY;%nt1+nfiZm>Ho0ACmPZIYlxF%PiQ}P21G{_ zT&~g5TkqX0zTFOBR>ftw;=Ix^1S?!iXrBXbbx7PDf=IX&rDU)X^hO%M)a(6gY#ix% zym>s2Bmf7IcA1Ltg#D<{uxM~izN*lW;#hYKjOmft*j0UL99ZPG2EV>DEI zOh@QmH`yUFMWH`5^3aEyHC%1SM&f*N7jgN;cNwsO9_L-ZK08k-ctXwO`*oBfokSB0 z1K3IZxu3t*zzvnTN696D!-#Ma^9C3F3tKVoJ5g2?rNBLi;;D+phfDM_w zQ5jZ7LNwg|P=rl(1EI_?)J(-Nex&u+P}Pt!p08c6pKggyjX?iY#Sd#-cK;JEe$%Kc z`VpFVm_eQMjVz>ICqqgeU44k1M|I2b9hH-u8u^tE7H~1xExQTw_WO4(E+nFft+<<{ z(0mLIgo7;fYLKieDnu584D5FGLeqRI2gP7R zSSQM_Amsmv#)yOdta3I!>3?Lm6(*~`)>MffqJ^LU(>?o25O!jglg9%rH3#>~f(?EP z(eC0%aB?kskBjs+qoSlWnLunN{}NGO7KNsri=;v-HgXXT%d?b3RlyR%3y+DXcKS>V zeMR=`w*e!*TE2e^Rd7U2Sb+xMD@VVGJXWo=VE4#arQ8916(54ubhW9=+s=+42A!( z;UMX9lkFfE{zpA=?-~e;=D1IxoR`=#ynf2lgJ3lVML}^cq_8=UAk2h%s#FVkT~Qdf(uCWcy*11XBAn(Mz^9+Upj zgZ#Ti%8&GM6_n+UXPRh?&%nv-=8@>eHETXZYK2-KN`$Hj@SQqbVoYggFzqD z*YA(Diq=2hYuwXd7R8BAf6ZHxgA{7~T%UXjqdu2o2>eax;vg6X6zY4A_7v5K>X=od zcz2j0f5_5hDhl;;l;$oDT$b0BStaDud~@!=B{qRIN0nc|i=okvBL%ngj9eXYqen`X z5qHPvUehv8f`Dkp@YQh|oK5DE-5Y4o?vr(V4lxH-^X`{x6xQlR zRQiFE#6-rC5kz+0pQGKjh1jG|RJi_ma?oi#Z)S01V^%ls0BYBzaw~p_-ZNuf?%3akSK*Y-fl~tBRl|2ZNJB?(zUUI(?Euvm*=|1~UYiefxGn+j=ej9} zV%i+-xVbq-;ltGy3OL!5w_bL(?BPsNOQ47wsG*gaqadm$iI#j#5-Wp~oBAlavkQk; zFn1rS^d2lgjb-XlSsYUfQVf0^tP*@uG<@XSy$g!I#%LnMBLQ8E4h~;UNomfA%f-?t z8&=)^{~esaL5^QUr-(Kb^({Oo36X+JUY1TE(cTPgP6Qw3mA}&uo|@+Ala6Y1OHOZ{ z#Mb6y$~xnZm~N!Sz%6AdH{XZC|A`kS5AE~2k=If#gW@_R7*@e>+#>3r0mtHZ4)%w+ z_lHM>Ig*U3d@8C;C{F&T7KlfnCo0_dB*xUX#m!!qBQJ%hFkR>tPfKLIcZG@MD`K0h z7vovQNic-{&6NG=Y^)DVgQdv>oQeSVAC4n4RA3}f&?S}Kx!W?!KCY4dQq!rAc4jBM zK6M$&20i>rLN}|!A41D6Ic1+}v!k2%bUZs=#H42G#It6K<~BAZ%w&v*xReqmZ!-jI zwH)bdNs7a8e%^-~8bi06`4B7%B$=%c@@!P5bdgBzO7}<-th8J5&O^W%B)^Rfo&fD+ z+-Y9aN91viUyY+DQO1H;4Hx{iRq62w)FHt1ViayhE`qkZXw*UES0?b>79kM)i( zUq>6N%3fe_1_O*rGESbLr+8fZ`wqm&!NZL|8J|S9l}s=6=F}Mc_?`4EftFZVk_gpJ zbY-goIN#7aQ*QqT39RWXsUF5!`rlfX7A)>O?O#D8O^fB*cOnSMG9KbroM`zbSQk_e|n*5AFmiq1zW()$jN6X-bqK>c_MVkC>$ zgYch)Mry;x<`6I`D?`4TCsK28=v&Z{{h$<4lbkOe^&*VJoM`DXS^7{$s3&}xCJ0GCL0Ogc4I0qr5>;XG@YQ)cqbQhATsUOqrc;A%=rvXsH(t zI>Rj@9qCAMFf77LDV|H$KOG}4qK4j^UbFqf+l9icd8cmmxR zei1FYT^!>#RUp}l%xbpR^8yS+P?tKXK*Ymq_o!x(Jxav(3-uww*;mvYgoxVT`Qj>&?{W*B-q4Nf?8FhTBfs*wtz>J&Ie=C`0yxM&mlQ4hEo<-%>B zFzh`0D6ac+a;>yoq#W5cb7im-c#>@~BjJW?2%TgOF=ir4DdOG75Ql}9y~Kv(qoe5` zJ$pX7UIrcs>8_Y`9qXJ|QpWP&OG<2h<~P3Z-P@dxQx#m|$grLkvYtw>1O;Po3?f*BUs5Y60ueyAq9eBH_cBPpzLD9!|qa;Z$+|DGe(s2 zM0UBve>P`uW7WMJNNs_mB%W@#{8k9IWxiRZ#pEKe1Vf1e_rsMiLTl(2``rxnl8N5> zSiN*Q4e{|K9Fs-2?|D2yK21MhHp?g{Ik%*}u!U^@USyd5IbJl-mU*ob&9;N(9;YGL zcA|;A$?jjab1lt|l4peB0+vJ?wQk_eGD3cZ-Ql+vX_6mNyP{m67Pe#Hej2U$^d8@9M%XT}Sus%k004mf0(=BD=a4)Q~E{ z-3T(Xi*h^Ai0q!;g?JE3A`kRT75C;J6QQ~sk(Q-L>paQ{J-a=a4b~9mI{m`Kcew*D z$b17-OHk;esm=LRX-#F1hDs<5J#*V`xgH_;KX=Cc4~4$nBditsv+qYe@2y#}{!n$k z0h%JjwfJG~M93bKqtc6@H8-wOCAGWO|2~2_1Vi&Cwq`Ar!HpjC1w$x~AMTe{eA3SG zE(~r;@Ysa!2CZ-p5y|5m9XRAa0TC(uFz;6&n)rh#mHHE^>$~S}_dJ1Ax5#PE7D%zf zuxqDoJmx_`5sS3@@O?d`48@Og%J%a05+V8423o;#v}s40__b&d@vg&wu13>8CJ+99m)wcH%7|avt#J#d&V|a5JxA^YbmU zf*Z$AI56D0u5@cD-{!{|4VpJvutPQE_YtVlq?^nnyZXhUaB}?lj8Eb6fEq}rx-AU; z5~vwBe|-n_nD_rfg9X?<*~4}m>LYSKByPqXAqmAfKvyOEL|`%GcC0+PBBRZ18^?Vn zp5B(!v+=l*eXEgP<4zozSxY3{Z#-`*XsT;tk~#4v?2z*bS-dh?4ui-a;~g!v)=P&F zX-i&Fv;6wN05G1UO^46a9BFrfm`5Zd6^Vcdz&;y2 zcFe!!YmPl?DbuKIhfjv;$gldLGjyyU<9hCQ4CUR9=B+8Ys}NwZsp?z(=5Oh_att|p z>@R$ZfWxV(e;54;&R+fXr_rK-O-4J;81R8xuvMIRCsnA^U*?u2mTO+oA`SfcPQ)vH z2@`N%$yrO9)}BG|WItPFY&WW0f!|NUaMk1M}^wLV%}#TIPrkJRsU^ zCTbaz9wWDL%(&ELI-pj#J6Ewin`ffN6+6nBpS;ZTm$K-QJMbl>NSucC!Z3m%*p=u0 z+wlu&uJLHi=XcMYn(}9~eO|&&L)&BPOPFza`#|nT49P**>qEjTTIfzWa52j%`{js> zsUcqysb?K+1 zA&x=^&8T9J=~IUeFvvmA<#XCCDI2h8T2HUCxfg%1)3*qA%G#s1as^z)HFjg5J&Wau z0#Yi{gBfGLBsnX8izNRM)ck2Ke1@5#fld44|CJ6rp^Fih+4>&c|4w@Klv|%|(PngP z&Isp1MqaB^kD+s9AC&rTZ2sw}WEUsNksyXBhZC`Zr<5_Hv(!eeGLkD}k2JP;v-2Up z#=mnEsjgFEB$OOWTaiY5WZRpLg+j<7);CsiAm84;aC-SW4{(bjSG}#%;PeDQOTKTyOT$eF2i+W45B>7--qkybXB+uRQaZYJgGgyH3};d22S-(D%~UA~ygiF(72 zk5+7v)~v4!4knmyW1-t|jQLa=Qs~rfoD@TTMpCrtGVI-j$Z*YOFjvE;9RpbSZIzu3e=KOMS)z{MgW8b7(&N z-g49UZ{lzh0eZBr#i{)dbxk*Tvp+?x{}H(ePx^kbXO#74Ud)Xk;VI9a+DNr`;fz!h z6Nv?ak}_Y?^R_v95KWxTENf*T?1VIoTOG>TEbXaiMY8QdCuWmBw-T%~^`{>6K7q%% zmgubmVK>SovpcO}Dc651_e0BT*dh1tp{8~$@TXm<-S^{wh<|^Xvi%UauU(Ab6>^|{ z56=a@Kc|f8Bd6IE)X@8nb&AylwZ6)E(Ym}C1XB8>CZ~CQ5KA;M4DrnDi=wSmlAj)O}I4n}1i z9+|H(mU_^YZXC~YHHAie{R^egh9fCg-4j2PbJC~DuMTS+<@)(Dy3+%_`i>J^4fSUMTJ>Cy_-_$TqbCrg(ue@(jXv8XkzsJ&YI~I{Hko>@4zhY?`N7B}g!-F=1d` zMQ-OEn+1xBmDxQAk6ynDr|_an8aH83D+N3j`tsjn2!xMgxBLD{CqnnIpY&u!SAo}Z ze2A?RTY-$j-~x&hPdRdZf(m{ONC0wuAP@a%Y(jw(=*JZw(t*@x_)!1#b%5znbLdVG zKU8DW!z&QVH!DOT@+mJ0t}fy5q$GYaD3XxAsSH45O#rDQ3rZvv=DU$sX!GB!jCmJR zvSILX3wNPrrI9zq1t%B5o`;=hk)v`{_l26m-P&h_E`2@`OU9Rnyjyh28BYWNW~ch{ zToh32=QRDCqAY(-ZEH7aj99rxje_mqvkzsJx`fR4Gk>OO)cMh-O2D;A#~PHTpodxM zfRT38aX1}s*nM1mjsqQyi2qXHN{U0K^|=D4}JyF=32!~ z_bac(;l(6bh^@te(~&+jvu=WN^lrI9JOLicn&%wymKZv3kO7AzLPBJbWk%%~*L@D# zc-B+?w!MCMHCE#53EVZLB<{*Np32Rn#>r&BDdrHBy43f(rd8pw*MIcy zun}&u^BRf6MOd=*Z?yzaJV?cdhrxurpT7Y6bzvmj??@>ig`4FUs{jj(JkVprp11?U zK3$PgtZ4oXHC)taQXDnK<(kJHzxiGRwd56{m7)(l;u>#6Ol%4p&ar=XP& zNc3cKZd`i^QO{noi@1jbg?)?8yObXE_4WBS)#Rrx_gDE=A!UZIW+>Gd@4*1`#<&xM zUk`FDO00Hj4cvYAV&Z0o?uZ2&U-Q+AqKC#WVUofr?BM2xS>IH_LTq8uUJTmYczhhj zSkZ>x+Iow)_F^Ad%yLr^0B^^31rfgPn0!+-m^CZc>*bH=ULSw4PrZD@za!35&n9VI z6;JzkyfG3%Gq_k58OuOKq9mMl1$_gYl_P0P$jL9Y3B}N+Utj-?-FxLaN0I%|JYF{^ z2OY#+M=mIKUxkQ}*uIO+XtVy4x-fa>O-EHj=6m(48*BMiQE|3__3e2MX5Rc#;> zd!ei!i(EMrC=2hPr45tyv19czYRP3IvLqikh-ja@N|-Mdl60knG!Xj7pHcs-Pzr(5 zNb~)hJ?@(n7))7x@ssmAW4tnsw9*?d1IGyTjGVLZI*qbfL;5+Lu1|D%0<`%86&oE& zw{$eTb`lhU{l{)U9}z4Wqj!UL_Xn>xw6h*)3vCbHd;>!RHew}85>F~ij0d_mAQ)Nm zBtiECVCAl3?-pPqr$tzk$Utqzvb46vM@d}EW_<*4+~WAJ``f2sSd3(vI{Gn!3{t)F zpBQp#7MOpVWal)r+3MEsR<&)ULDJFH`!0L)xF~aRwF0Aa4$reHbN+`qnTFFyn|0}W z`J~j|`Lhke{9&QTBM?MZYQ2B-Qw9#1<3VY?hZk{OLaem%lS4%4!OGo^59TM6UI5oBdQ& z%CR#{o;(%ITIb7rOGwOyNWuGjSRlADkiTvKwFEwEnJ(SJ_-xHHW|><~K;lo{gRo3UHUS7`U$i zDu>ATD-`~S@RDitY;Qj@b$1@Q$*>HfXn)1};H-=^d1Etq{>HbTAP<^H=F}UhEZ*ud zR2|M^b~^$SV%|Zka1w7=3e55+wKlKhc{sk9vNxSlDzo)QMjx9PiXM}sCzQD@tYs=d z-^^EXk>#{2%o1`f`-i*ff6EzKibfbfA^Jx)3z}%M3daQCI9na<-}Hc1_Yi~hjd%aq zX~6uL<;rijv9Ckk-(QtuJ&zt?6TZerIdS@tM}s|8(wxBbqV8Me|LPgx-NKVDMT!kh z39#lI@S~~=6&@2zsPR$^FNSfw9KVQ-!B6q42fiELkd<^Asap`fS>I#q`N{2kHTfL& zc_=fmaj0#$sd50WberFrFejlTCc?Dw{EDAlA*4&@^aS0Rc4bET7M%%^U5k;=p$y?9 znVO3Qk>@2JT%ga+uu{{*zsx&*Dc_&E7`U3wcqSw!Dk@aXBK5<6Be?Js=4*#D@&FW8 za$!YO%@)tgra*)ycrE@aF6Ivzmn1hie3LklWWN@~l#1jMvtjD^e3-2Ec+Weo#bJg{SH6|A@m?0|z zP-``tA8(QGVh3&n5vTprhj7^#t%d-I(~C)c?YjHsr!M<_E1)G^EIYh}rc*=i%lk8w zKzhBTtwhLsT6M30*2S*B`1=dzR`L1W1>dTD2e!Kklo-OwF>9M`6}IlTBg!+~nMSjX z{XE`cvszx#5OuFpylOTtZ@Lh?3Sgs^G;u9}l-rrE*<=fU{z1H-wxEG)y0QP93TmmJO56VUJ!>)cRwvqttr~+fUcLe31Fjsh z>u)XYsZ7GY&a)EbZpHw4-LuH}22GTs@#K2}dClPnO-|HlB=nuRL9d28a4cecQdwr} z`g%^Zcgqsp#hs$x)ferye3!+1NB4dU?Vr(hneTwHMh-}NK8p8z*p;qR#v{nHC5y>( zuw);NPKs^{mc}EQZq= zT*&uFSt42hufRdb#R{^Mu?w#RBlzGt)Dl}Eqre|IE-{}jLg=HSz)|J`fB{C|YxLZP zntViTq8ZX?QE7S1 zeuvENqwS4)nRz49;aSE2W+&=^jja8xtc!Nl#P?MI8dcDm8>;oY_89HG@tz3mg#!CV zK%xk6p4%_^@nt;tr)gfFEkU;RAl}Y#&(hNf8Z?b*HL_SBA?vB>Xs&}@8qaP~dIP{@ zt?+6lj9T&(<96=A0vCJs#=R+7BtMPuH_WhO{$M7^12+MjTCgHX$@020XTQH@U%^4F zy=U@dRUQM3l5Wj2S|W}C1Xe4cJ@L7plW2Cxj^jAOfieMTP;WCQeqUhxV4p>_)WjF@ zK$B};G0Vf$>EsAM_>Z4SNBqp;D{+?*4kh?udlQn21Bc=aM%9XYli!)<~8t3U(EHsew; zcmC?E&DnIRES9Vo2@|8Y2TEP%TVN&_$Hr&!{)OGa1!{U67yfH)kRB$9mI!|1whKyx zmNW{8D5RLtIlheB#!kpl>~lbUq8|L6QX7Zg9QtDN?7u|X|B9LZ9TZ{-+ajo-vMCN$ zHyLxi6f=c@Km)@Phd;$sLzr_$!rk_aPSuQE@d(+FJ(|jpACpxwaeN)_7I2Mm2NB6Q zpUD!(2Y{m>=w*3)wPvN+3)40+63T^wV5j}YZ4nSL#_X@XaJ_mqU7<6p}L1l9{n59XQrR%A&bZ$6~+2y%g=U z!eu{z44z+~cdP2Fm^E5(LbNMz8`JVcPI#JavT}esw3iJQoywHE3gbW*cps>Me3nUC zv|izGr32-`t8h$>j_4K_?#4pVp@ioX0;#uS1im#L4CwzLNc?|cZQlqLKq9+;Ftg2P zEpHyd% zp4KKRZ90{|;|n^8hf}jqB0f5}PdQiLMtcp%NViX(_RmEG_s*c*IZEK}5Q8`L4;XwZ zpf~f4BzL-JR$@vr%#nq3y#I)JJcC?@_&3zS?hA;o+dkes7vsb1gb}%6_7y-HO|-C1 z;>9_$rx#mJOho<)OP|a8O3Guo`PCqgnW0uhyQ)3tb1!mG3+YmFs|_J~WOxwG5E_Aj|u!k?-y*+-Ehv9DCCu zEvRZFJ*)Dkk;i!a{O@KV6L^J9Fsi1`JTbbnVsACe4f0<{OaEfebvq_~jD?h1 z5IUs}bnf8nEa{qeGH2dBt&IT1Tyzz;@qdkvL1yZyw*R5LKwN+(zHNvsgFxUIy??F( z9)bG7X+G2p5|N~>8tD-Zjzj5qTa}=*vEO-ybZRB@c<lBYcXOVlp9ljmyCpY8;5^T$+e`bXoE85e?gnUsM+$lDZ$tMM|1FBlcb!1*XI3T zu7(PgGiCp6AjtFf7+pM@1bo=w_(<78W#2Z@8xj`%_FgsW)UmWD#xut2r9B=_PEb&O zJ))F`{aq|O1Xn@L8w_nFltIz96FRLjS}=tOXJGc%=ZaCbg~gi$OxFe%yOaB{KY2fx z`O(nuFc_G>*^{P-$#N+tGXZ!E`gj_=4c`(_jz0pKwoXtIar^5$0kl%uC^lsXthPNe(A-J^eG%bg%wj(C$PEyRPYTArhQrG{fK8%m(cp13-zdp?i> zbQpR5Dwxl07IX&L*(*=LcDmHQXQ}>R5MvD5$lfI~RZZ>EIA0Ay)rs#QQ%)B210)=C zghLLhaeX zhm&cGi)~=lD};E~YBR7pOrl+Q>Qoh-^7Hexjf6jv+mj57@4veUb z2y@Mt(0W^oZxVR{S7v-8M?~ntm{TuaeerO|XX% z*nHy?eeV4u8ZPpAn<3(qvSVn2!8A4}2icV}AUv_eDmeTo&UenKdgYZG_qCB}l|D3? zKiZqbrWEcNX|Hwv2^+J+TTf^US%iO(`fMJJ&mn0fABDt z294p4%K4o6fQE~ayu~w_L4Y2U2po08I5O@Ff65Q-1?F4y^?7+DxPD4F^nWp;G1!f zIr;ki!hMXj!c+RgcNV-^SGyB2Zrm?|Dre6~Qh)t{4~VaG?v;dZvfYoNsHqp(EVc8d zJn?8d=L{m&Zt)>(mq1_3Q9vfizo~ zoj4?c^G9Gk7@M!!uQ`m1{Kf|ruQ_~VSW_QYq^UQH9M9usw%v3q7%2juB4?e}e)Q2x z03L#iKa=56;`f@+qSSDD*%{Rs*Z)YDJu&uGc887Sx|ZC#@E#o_@Vi*;D@DT4`NP3n z=oM+K$Gm9KIikS&uM#_p^{YQyzjHlHM3f!(edL~*XvlkGX8IbP7C zJDrMBIJN24yByhgH8x=Io^s7Uh_v0HwbVjR0>FSmw%N|a(atrh&p#9F-9* zFnJbf;IShP-o?~{i^t?4G<8MuhZHn$7&n`Y(TH>D+#~V4dQH6t>6WV>_rvxJc0fq< zt!z{Ffa6$b27NNYGfr(m|MsWQ$0cVdB5U2EP%&9?WM8RUfK{WCjw$g6W4zX5;{@%j z;sTCSrS5VqPjDfAF=KkQdn5J@4z8?7*uL{NE1O1~5bRo`R>MY1rRXxjSPPlIpXaGz zgX%XB?e1RbP6mU(~buA8RKM+974iqJnsDikCil^8oSM zGF-EOZT@)?TBH_5_qPUpwzXwlL{bPza z6FzcaCy|*(1Wa>eQpj1F$6I7W)sO#6(+_A4;$dmLJ@?^TSZ*h?dZg zLgYH;2hrU#GkZvd2a;u98_VWjPwD4m%3l?1l_FgXjRE~nZdN3TolVRfG17Psw4W-pY8PGE&xS{cZNo8WH^RrDJP#Yd2)Q~M~~NLSafcw%(fysL|eqO8S^ z&GR=+Nk3gD)p>RsmWTar5moiwqZw`hNC7_ zO6AOVlBhYuQFbbpwa%AW5dU+?YG|)C{|u@0@5LcH25`4;dk+$PgTk1D)uDdxg@gFT zZYyye=90%)s^*5VbJr7$HR8x8a(+Ld>LgWrh;W%_^_J)>AZ-J$dI`M*FhkO;D_y=_ z+`5r5018%SA}tOR%LKfc6$Uc~cZN~j+az}Uy;y;KB-IPOt;C^FL2*;RILYmbkqh=J zq+bd43zm*QJT&4P%f26&=hn&sjtjtuPfIrwhX$}x(siSTOjp${0b}PVr6^8OS=(?j z&YO!f(P%Wm;NdWy)8xs;lf1+$3_q>ZXJz6kFSG6)emT5)(w_qFl{ANBnhXGKO_)>S z?*lnsGw}TGM}eqQ6}(9Qq>!z~6#rSir%SKFwR^>)$0d7;1pRS9$vQsM&>>0k`5Imf zp^#jioQj5AyjyRb586EOazkBcyZ8qk^bxg#7p3g!yZ&hM;2&qLd;nx+7x8*1su{Z1FF^d8rIYcnynx0Jo&@ZNt}{ zT1)k#oZ+7$&ZihQTv3E64Qn#yDEwhpAo_%C%gm5W(!ekF4josPOV$=c#5trWjy`#k z?pp`~h)obPc{*wkb{&FCPc9okbz9%Gh*`=JdB?OD*O9(Ut59#1Go+NZeS8nxO{dhq zO4Q^{vb(cXjM%oF!`(}FpWDQ1DZ(=|%3I9AF>NC(Qr^hN=C$XhSL=KGN#Y)ZTYjUn z)ootHiaT)5Gb)NlJ4RQLw06q0$53z^>58TKoNYFWFQn^>wXM?IeaGE@$nLnsxO+3v zl}zaIM&&OR17v^FBT?AtFVxVBbHZ{P7bOkURtAm&d2_F{7f+j6QZoSJj5eR8h1?f( z@U}Y4EtL4;MrAk>myWa#%p!&*AvyCTvWBbWFeXBuTfYKX1;q@^llTo}TG3ht5)xH{ zAsvsBYdxT+2A$->+ca=3q4!84aQ z2(}HEwNPJuNh}kis75QIe)@Xkr{IdqFFuh!wEo{JmDIMCdV)l9hj^7H8!Ns>NVwz$ zUc-t+7bPOlgv8CzcGr$|hW?B8w@H7PO2ICGjuh5>eBm61F|Hf21J~YVV*gFvxQiG+>cfOFt)93J!*A8%z|wd z|6m^@+KHVZ*8RKJ9?<1jyv*3)mR{+F{Y~*NRlq8c26 z5zQEBxrFwr-@S1evp=*EoXR_nhFIp{r|dt~j(j^ZZ^fmgSD7O>sys!?tm zW}vI(&B9s1c`g?Z{QldwaAqzh>v=MOOE#1t_#rnrgoBTM?t2)tFF2Wy1Z+8YaQI{d z2Shs29zeEusfM-3~HP|CDTDbs4A$sLl_r7b$h z0hG5#_R%^SQ?-3tcu^yx54Z4qRWi%pPO>=zMy}o%GPgSiAmA<{LCK;c@tP^lM!oSn zfk!V5Y9bm8#U=^$(!nWItF8>_x~E7{v1c@iQ3LsLHp56&hadf#dOA$nxm{V^xx*ZOWsp1NQEDJBVU*i@m*K1D|yXl8s2?oatAbuv_Dyt zhj0bsNUZgdc23s^lGn>SwP-GP;L1G1=b{({n;r*%A9}I@?BqTqRk&IHBIVnZ^!*@= zHR^4>+o2RyUKeM;CWAMrR8lhJk`OU+Cen!TAau-UTi;%f=^To{u) zC-I^@w8jBH7&C@li1mqEmSkFnZ?+s)WLLu_?3~_#b+;YMJ{r8bD(@jiU`z$&po2yK-$e;^LX^K|VTwBG}B`^6A1B7b3T13#im zhx$Y4%lm?Tb_u$n;1$)DHs*uTH(%d}gHebnDYyYxMwlvR?h68RF@TSOyg!$h_k)Y~>PA(bKK z4-mZ%Xt_#IraP*^9_9`y&-N3r^Ft~Hy`)~69_L5@dX5=mVDnYH(}@}Sqd9!gLuypn zbh?%*&Kr*X8$-yFrTAvI+#Z4PPq|?%am*hWMymZ#gl>D;5Q-HBY>d3!28haxwhRe& z|H}d>JCi5jC*ruRW5;*>%q;1&Lrl<_GT)S(axF6{cLbErFQ4%QB*_+V(tE$?qAOth zUe$@q%NBersfHC+hEGy*%}&~eP0z}X8A*H0A39)7gkAfDL2*cT@O%qNu#Hc&6L! znB5Mg5humx=Np+(XHkO)um;_29$aW&+8&+U4`gXg+2?fd2=nR?om)gHdvB#kig0~# z#iB5_KY3n9GR`{ht_$p2zyqgmEK>p>`Pof{za&(@NC;mv!*U)iaLtb_Ce=ke4xOyt zb$O_u$mnval!})%nHFx$X?F7`dn_1-zm_5kNIC_%Za{cBJm?w^ScW-R;(Xtq`*3QkWasLH zJ9uU8*Iq^q(w@ntmOQuO$6mW_^kIns%TsA?>LFdvzWFKBy5ZPR!d$KA zR(GIoET3yh(T{oBdY%wEAkGFs16>Js^e4oUGb%)mv||dV+SzKSK5d$(PHpK=d#3ng z6>YoS-yC^I{+0i{{!u_uNRpW1Ys~!1f2$=PVih=n3v*)fcg;WmCTQ7P3!|s~Gm*a@ zhMBJV)q(&k#2169F?Vb0lJb9->8>Zp^q$_m7arlSixn4RCQGv@a5aB@Iq&`l@yF{j zf-V65@@BvZhCTJFP@JH_R&n9Qt<**UCv-IiyZuTpHoKmW$mo z_wJaz^nmmF%Zihu)-r``ln>>eO;gq~36 z{#w@(bX5dmp1Ngfj%#6)P2HJ#WXRnU*EU(Aahf9j`lIH`uug<`X<)l!socWuSxuv( z@6TdJVw;*PN7&*`pij1zQcX=(T!#Szz96I32pwr#d5cGAC8f08RsQ68X(Hd>#|0kU zSeAEy-*H+m#hkL|kj3~;_)TyrWlp*JoUUm%h`Uh0HGme1FzR%4e+-dNJiJ3v2yKa~!S=rVOv>-C(56gmljc zohih1ZkC7o@d*BGvlzmb4iEbfO)uy?X|$~ZE8ysh+*rBBLp&!J++dbc9Ko5gZ0Vk? zp@DC%P^_-*!!4aRQIPuy=?!{1O%G-YLsRpT+Wnc83XmxQ zZ!Y6s!=fO|uiI{GhpWRqQxxk}+16T~bw#;cv|=w!8Xf1`{y@iR*YF(JcfU;U#5mPK zi}kg?o2Qh0r9Gc@M^uz=3+m0M(&oaV`X27Q7K>Y=l4)zWofYx(H))caqV3bpYdz~RVds^lY0%Lg&y#06(Tin?;SdF;YiyV!z>SoJ#?8%zIUj9{{t{J zTZGSqK(ZLL2<+(~X9$}7?nsn}WApO`h5Go6vmeF!8duP-r_SU<9awE(fawEX=R;O) zQ*tvby%6lo;|RJm&zol(o2JN5QK~0+xkuL z{;G%U6W<(8x_p&Qh3sFe!cnVB2POYuK1=6WYc#3$0gyXBwky6TJ8`qzyL&p#f1_OJ zL6VRG`kg|HnSu6X%~%XtBPrw4hoe+)aIUv@zn5co=-?Ufp;%?mh|B0!$ksJfIt;Sx z0X+>ICZC-&;ML8VD{LS;_9Rr}C~Mdm@kpE?4+sU_E5kB~W6^|& zfpzJOqwEOtAJ>+i0NMc&3`nX>xwFK#QrqLe7dczWRG92V#>J$5yHwobWuoTR1gVK{ z`%ITE$+(BilqN7A`pIh`mC7ZmPM&Z4lDr@fEIzwX(ea2hy{zz;N_X;R%{}2hn<9X1*=lG{ zbRdtAh1_=eKH4($7a0oiEZr&?E^&kGDTbe#JZDe?{*>s6>giZ#vX)zejz9lqSYCa# zXX2maRic_h@t>aZvMbob^3?SZ6~mb?WM?k#kVc*nvbsF~+5#i|pt?MinG}hAb6uj_ z16kI>XXTV4am!}{TSJmwAO7OotJz%FiA(I^2GXXsmV<$y1aVIX5RRPmylK&Q2L35X zibH?cEb}|tTz6GJooRz#2#x7%_HX;H}a<=Yr&4G)Qv@>pqRT} z%BbCf8eY#u&(>SPZ1z|{JC%1BM(J)SRIpz|eLY#;*-$^65iiJ3NUK(|c|- z#1udF@q0z*2F>R?FU%2bSJ9o2m9Mp!QMg#wsg;ZZL#Ain`?0ZfZa9AZwST9lhb!kM zHNneP4Ha=$({d4t1x>rhJJ2E^saCn7wf=&Os=?*X{N(j?_s?Ff)N>0MfL4`#chu-F zE~enO(%~wiYYeF5cQj`qnuVn>gqFj!=QPTCoF;W(qbjL(O{b|l5>{2tiGXc> zI0vsO@<`Wfda%c!)a&iLYl8WT(z745({HqOw5QJ$|JH95PW7i5aM3`P>Q81$ejP_qCCZ#CuaX^f_VZ%bou%~;=6_VA zm`0n?;Tp2eItf~4%v;8M@&t0KsaMd^4=*znISBgGYtr2MIqIC^Dg*#{uaYDpSEfBf z;Vz`fUR5*BVRe7!ye=i8&S#bx(qLL{ z3qW9QabsALcb1wv>`5zT4og{B0BGiU8L5B$sy~j35Aa{~y}-tL{{|mxWwId25=$jm z*Ly0PD-M4|M{JPxP(6{;q*eAV;wyn`$;+=k7Eotp5r0B5eB!Vd_dvAjT{aFDUuO+- zG_epTgHxK5+4g9H_qAZWU__&VVU4F^V?lq}zU8Tw%4=wBRFsoPKg_%@ZLtb_EvS#C z{Gy`9j1OX-ZfX=ej~E?yOC?AIft^?Uk;|gG-x0Cot`iK^cx~V9D!E-Uk zg6HrW=38VJzYkJlMVZ9wE|pEC?D$Gi?e-~E&Cg}M6mvSwC9P}3Sv|agHPX@BC@a&d$`b7HCK3a8XIMTutSMU7k=PGPs0mvkiInEP74`l1&C!??n>D0qZ1qvK7*;iYn0uHr96gXtu{!B(HD^-TKO;?i5J)Hp z50+&*^r2UO@$hvo8tY9kA`wy|0=fcrOm=adDq(Ue_PCHHG% zHcsuT&C<--`9adHQZK`I8Fvo~y>}?V)2wlp|3l>O$T3~?gw{B}C(?DxRy{}2S6^g$ zm_Prx{itH{O3ou69KJw`?;zXuWzne(B%T!=9Lc9jB4PKZq*Fc0fF~OE zSjE(b#H79l+)pdx4{TotpAtZOFHDueasnO|un|UkO_@|0vK28s`MCId_@)X79L3N7 zr8HD_<2S*asZa9w)8j!BBd=!dBEun8L{77&MozQ5&PnJTur zyF76Z#n?koUxISZ@G(Z1aKNN&3G{N~tCcHD;-{PV@LxNVy_t^vl#PqLa?iAlR zf#7yk%m!?>pN5{B+5fz^UhAUsoBd)3y=-GIU)<@%c|7?uFlL4*0Jl6RhOA)rG>M5a-97)zv1MeL1OoBu^`XJR@duh`&nA-?)5u8*5LD z4Sj#*v$&245pUv4^T_FO9Xoo^Fs%E@y-PF<(h)4|4vkd4(1Y4FRh zv_(PnR(R0fR-U??JyrjjR@V^Qbn)miG=<2Nz4i3j8*@nQ_e_BMud5rJ4_2n-;IXcj zGm{29^yZ`B)7F?%vi{@}V^?2o7+jevQCSpo(2b#hCPmz{0xnhZ1d|)T@yYVlIR9Jk z)L+S|ox?KQc-^cQdTMSfzD9`2?g_RU6Kj~u8F{3lc2dT0s(jDbNU+_+=O0HaTM@3= zhuJ_QRJYVPgmx=S zg0z+P^U$>^5x+M5dxn!xyNXxlktI;GMt+Br1sr$>ZDcsD*v$pf5;XBRE$w?JPO~c> zm1QNI{HDpufe({YWODVDot?&+{|kk$IO9~ zN{D8W7pw~@=acp5#B8ZC+~jX?E6@-sn<)=17^ul``t!)SkAXZ09L_E-+574?;1=Hb ze=ZgC)S0vs4n2GHq$}(k z8~n6f>5d#ZF30W8Teld4q1LhZx>#C=L%=rwO(sCN{Ua|!dz+)M)@WbAEwiLO6OKU@ zkudBn>%g{ml%-0dHX7fVi}cr*rTm~jz5UZnrSD4LQtQ0{iOs_tm0<-fsNs)1RYNIE zNAvjFX|xK2qG^DrT@>PWxj1D`oy|AfO^1s`;_-YZLM&Y1Q?M7uI5jN?7>Q=R`mFD+ zH1s4u@b7d1h&xmxmy7$?@>gET{Lj}&=viTWk@wr9*AOLXhVm(lvdjzcZppGjg{oD=>x_u6V6D``R!Ib&=Mm zMM4E0)mOWYvCXtSD2bV>-*Z7}eFBjM>4TOr6&RJ~pW_f7gAhn)w$4Bt{|r=*C7g!j z^19bt?X7W~UvRCJ{P})$$6po<+U-5MS^RdL&L6YoY=fS8nm&|)a&TM-EL5JwEFmDX znVG5ClW{J|vovjvpj!&Wej)^CM7)wqxPeDO*7hQ0!gjnfsEyjyv46;iQRa)$OR>Xe zojf=s-r=|Ku~+)`$v)wHO7eW!6I8O3rZ{%^pQ3A=T5C3Y;M0Gx=#P7VYnBwm)|5Qn zt1md(`*4jvOrd|-L--Hn_sbE6=A&p^qJxk=(sBE>`v)PmgaN}}D(WV2@od^f-%%;!0%t{h=sg+%k z27l;3=(d*QDvHx*)(4OzX@i_KfbPtj4a4m0U__7zIq{Zaq{c~ty_U5H!!ex^NsK}! zkMQLMD>-mNnL3`Ew0xj_dH+x~fv*!zR+TDbc?S{^UYDB@I)vk!`PO%ns9J8oCffXKjC^j3u z!det8lK!vV)t#o&zBm`(WXaoJ@Rl{zcd$Ur$#1ygspGc&YCLO{fw5UEU}CwkQy}#8 zIThRzc>CtSG<#I-F@XouQ#3U^s520|Q+&rJn%nBqhP2mK(M-^ZJ%TJZnkNcb$d>` zl!REqFwZ2w#Ck2YL;cWztc&+<;B`iW==JQM?>o1AuHXOQRKg3R;AuB04_Yv>Gk3i6 zKGa0Y-zqOf^JAQ>+Ek7-EbD4eKH^N~^$^omLWT5enc-k57J6#xK*C_ZutXE{UNbw? z(~1k?%SNvH?L8iMkIw@KVi~X(DFZXf(DhzGep*k1TCdHmQv_o+ZksnxruV5CZi|17|YKmu25H(WZA zQXk)skA!`qhu1V|xwrjYW~=`zKT4XC-Sh%7saJP>bhk8!#o=N6am_|1y_^{dQgqwS zPWOaY)w>aKj)h2I4#BsA=_}cic?#^PwHMeZ^<`p@zqRel#;(fQW~t~@Rp!0(8!BMu zq|i9@WZWWFOh5cncFo?}S;CH`{tRqS?*MwYFmnL~hq8gc96l=e4oPEq8hxlxlO_Ht zGd_5&Y&iMlTj1MEjrqE>9Qd1|m(yx*Xt0Hr+1;hrS)N7))S=H=Hdj*`OTS9_cQKBM_N1GDBS9S&|yvIF$&NAM+ z$g)fu?-OA>t`AQQ$eTuczOpSMHpp+X&qs5f#gOiQx?v1?>-u3P+FaVqKiLy*+9$j^ zQ55x&Kg2llb?ewsO-+S~!W8EWG_AI{XuLxI@YcvrSS7a4N7ViPob8PchHh$tl~98i z>N8an9c9M>$|GUdhBV)zTob)*SA9d`zOn+-tutiFuA8jw$9~Q8nF-D`t?3!Wz!3Ld zLQxk{-CG)lmym~M8rUI)3Kk+ZHjxVEM_1)tH>Dp=x`$v}nRVPguAfV5A)gpOBFV`geBF-?~)h; zGkoilL<2q%Q-$_?fe+>6^vVm0yMZkO?8Ok0n?`sUx5d*w9^5UUFAefT^65V9#GAW& zS5%y1A{@z^ppNCK;Mm|R1kpK=RBatSLMg79=phP`Dfaj|V_M63a{Y`M{{92J^3l~f z+T($_c1M*{368^(A$90R!;#b_xgAbRaeG5z1Ks|XiZeaf6Y+5k9*u3sjq;7s+s75_ zhtPDE*lex0L-v&|>2J9=ktX1C`tNT)sjs=xGR}wfiDB`FNRA1O(WXq#oKvM}xb!%| z`-(ihq>){U+^?Vr`;mBpLK-2L_~``*b}>YByaO5n>*$}+*a_%IK1D6W(4e3CKgduB zkXb*ec%MetFHqq;U|GXC$7KUqhq&>&y({G`gzfPaIY+)goubwSe?WfF3t_c28WReg zuqsU17DoltxrGzCza!F-!zUV%B~k=qGPtFNi3YpH>GVbizn2*$cAIat`ktv=+f*N+ z^gB{(F7|su<}do@A@;SKIZh)qv!6w9MR2(`j_|L&RUi>)$R>DFI(`0pQr>`C67`}t z@&w;#H(;?AT}18achXg0@x{{L!QVjI0GjI}&3~cX4xKy{x@w=NG`1Yo;=1vj1KMIb zu1wGoqvjl$&3dGTOdMxazlPgESTYV8nVdp-J2e%G_>g?#({t-;dqOns^UJPhDq^Iy zg}s|!@q6l3K5vH|H*N&Wu@VdPe{IkIlUrm>%R2emP0dY-u7xzMbckM6CgD@gM&*<~ zY-4oWRopy&^}b?$0|>Y$vj*clu86x_+uev|#i0Sn+8Mer+w)C=WkhCFy#>5Qq;D$X zcW2?qIw#dCWsz-Cw&w@q)&vCSlm<*=dwOsH@^&WMb2n$LY}9y!*gL;rjQpf#PybyZ z5=wPeHdn=!h`nH^4E48<{VH1ye%=NuFE|e^;9Zo^<^t&f`Xt5s5zl-zaD54G#%+T3Dj>YIZ#=aXIL4x_7TBpg$Hl7tuM0v z^_s!Qy&a0!xQZ0rp_Jq`O)MuOG4@`hex>}|u3Trb1J5kO)Wj}bxkpI#VDjUzZko9c zxURk2+K(D_;uHR^+=4f?6f?r2{M1Gc-@#&h&Cl5A$jLK_@l%{%>b(L!7{nwu+R|Ky zK=Fz20$EAqEkX%+>5bCpRe~C$gA2aIJg3~Ls$aH4(+Mc#yHyA>yOh%iibQ7)PU28R zDkeC0muJZ&a0-%z+H|Sn8P5->U$Rs`*@kV}g;j->%9vBYrO+%c$X|tfqp@(`?oK5a zjY;hhmUF?HxrBb?yVTyoR*4q>&YxtQ2iivm9|$TpDyE(_?Bt{U*?Y(p^9$Qpi}gzi zk@q@W2{p!TPso+=Mt(X}#tTmm5?tNi&O2UEim2hFohQTut~HE4#cVVW0foxmxrDjSlC^{lzr_3`GwTv_PH|%T zEo=W<;!@t^pUs*=z+AEoAqoB$zG|#CkJ-4d(~qTkJ>CIK7ml>qhrPqvq;Ukt4a*Ns z6wwLT!In35p{zG6Dpqk-<1GEE3GPxix%g<{k_p4*`*q|?usV&BD?(XrbuU1r-Euj_ zc3E-@-%?pNG;*ycG-{l0>2a}+$fCOjJkRxTIQLIrH!ls4+Wj?wB;$@&QzgS-LQQktlBfg zWmQI;vRZ$vG_Mmvxg7o1W%T@O)IA81?_juu$Vx+;xh0qDbkUaF>hzQc#5rww zPR5aso&N76fgxnB0GhY^Tpw<@JbskYZs0qsJ+7dqfk>@zz|xQ0u5B+wKk=Te(&TnR zqXnu36koMY>8(|iUL`({~j(#fE?m|KHRvg%}&^%*vhL)6xxlm zE4TO5Zna_IhHq>73F9|Wy5i`QKQ~`^s1x?wpI`bZ{!8UhvWAU>n`SrlSk2k={qdj1 zmfuh^d?;qF`*=ZGnJ<6ZuwCVV6w<%>HjEhdrav2%rUw&Cp_YLvo)?C#z&ZvMh zjr=4I&U3!OZy#o#&k0w2NXf@$-6EgUMRpqRT>vk%E-UkqBl5@@Jk zuiD0sAot1V+;xTGijHfKB>!+wSRQ|b)Dd%mm zx1J&GJtxzV_`aB0lW#q4dU%q&m^SgEfRF%JXcY+;ermLq>O8&Y?(aKV${%7>wA@T3 zu7f$bU&49ney3)}d-S#R9M6L5Pk;^Vd~@u`Xv&0M<> zr8yHF-q>UH^+TL>blkjYR{UeeX_1U9<7_myoqmW*l6TRSYF_c4!O`1`$4|G~ z8rc&}l1`@!A4tVMw2qX+qC0*6UaBy*9&jTG4Xt z6~ZMtodJygi@iNdtp*C7g?l|n8O}pufk-dW6`jRZhK?B*4(I1uT?I-MVM;KI-k)R7 zhBo23cP|F4ZYo3y(y(7lav zuPCLdzX;VjyAQ#xBGo6EyQe-V z9alD+aYUoxMY-g8dF#=*v1FroPyg{K)G+~bK3Z?u9D6}oaJ_q2=IJFsw9VtM?dldd zd^$!1O#JLveY#~rPt>yF7Zg}1~^E}Dtd+m za9<=t(rzCL4+ijJ@hW@2P2?a*8|K%Ns56Z`S~9=AMYotZ?Y5$5+@;fk)S zJm}jOBjt=@yzVspoX;cFQ5-{ZE_Aw&G!B`dk3_R+)9|~~$jOK26>NyC#u3xQJ>nI+ z;3ZXo;+8AXiLP116Xs70P3XIEX2d*_sZ>g(a`++s_lsRi#gu#+Ykjj_Sd&V9UJXoi z?LG*=^*4Vqxy@r4%K+D2Xh`E8!UADY_%t_64{lp&DQ219G)A6Q(+Hw?Y1`c3>3A>H zJaP5w9-kYOOIJQ8bAvWn`G;`__uezxRA+q=5SR@#euyO z`Yo$qNNaRg7X#N9um0)`GbCDk@{tL&*ZY1(El4bgs@OKGMX6W!Aa$xXQRv9 zWg%}hy>f!rl9~y{)rg{)_;(}*>L+qm*A^Cqv}@K~tN;S)ySSe4;)1Xz=(?GTNB+rzId>_ZJk=t~J2vySMZdY~A8+~g zHFqU$%aM;h%yN7k!O9;cx^o_^XQMOwPQ7V)%+@CaluN4~c7A#sY8~6+{-8^9E)+`a zz4^DA2Dg(8TGk~M+4%taEwG-(3YPDaMol<9J2~0Xo#MF@xn^=alvp!b0rT$O!z~E2 z5P20XoY$^UxBvLa(x?zxIfZ4M$T^`k&9%F>(SKz58&rLqyR7Rbg4^X*A7MRRuLG7w*KOC#YOV_6(Tf-SQ8-;|B8+_P_UJs%s-_pt3am zoBWLzjyla#Is|oleZSnzutN;t0rH+3hoev_qt1H|m!87Ez^7t+Csj*?U8XerCURty zbzFB`iAEs{3yzu_O!M8#y^n=^TfVT9jWX)Hr~~nXlc>bnLQZPn1z$rPnVKCHZURRP zyI^r{zdtKc3B0UwLa6Dq&xt>d1Fv}^%X;48?7M-j(hz!^IqKHuKVLtUcE;FUK3*RT zaTOA+Dt75S?-hr1Bt5L-AQq333GZlM<tx=_f?nxP49bxf>r)1rh; zUT_el`R%ch){=i;u!Qpn;cJ=m90qt!XTj34VUEt%At~nVP$l?mf}Fme%Y2ih8qa8by<8+{s?jM?7U}K zv&}CYc7gtTXaQck!+YmzBlncIVxI7sw|*q}^kSj6w9|`uBJu+~1OW)Wr1I51*(U214fI>;M74;Nm~3qN z#cqhC7^pc8$b9%iKf~WnY%XS;CTBb}+WV+|C@_Bi!1KIjMT(dtqo-re!IJ_q@mR{v zv|)4UEDI-eS#jmPRG&gFizQB4CR;R96;|yejav$rzd=a=l68pq`e$q0>I5EzPpmA0^>`exK2S|o|D5|sLmf;JfeeG{(N>f)dg%goUo?sO$A*CaNwr4_Kp zn-1VUx1Gs8gK$Cb`Mv7j46@^!Frc5Gv0mmXW+CzW7lH2E%i zg1`TO_-cVz;>t?#S`wl=a^36b7r`huX-6{1DAXu=5pFHEyeBY1@L_HY%H!O;7Qi9Q zQ9^-Otzh!_=sP$$1}zD`g?dHAXt{h>S&-W9sg7^)D?v4fn$?6wFc;nVuQYUU6u&+l zpfkGKPb79gp!GYX_NYW?a^MT~j$d#?2YO<6{?@>W?vVIy$k0*koXkayLJgC&wYnWh zrg^I-=0??~<@}Olx*jg5@)ao$F-5aC3nZ599_Urr`8cZw)CNGDmG6GhAMOuO`;fE1 zv%LL0j{YvQkpJ}U*>KXU?A~hDq2-A$Hi^38<}K3rh6kDnF5T!sg_@|wLFGxROiU&J zuPE2(Z%IpNoKfgT)&DCLu+2^7nHUqd?m-{PKxmxjM7E)_WLF0B>erARB%+-|BTN~z z$WF5XHkD)VG>%}7<4XlWwtX-S1Ch|*gD@BF^i92QA)PA9h*~b!CrL^jfw2{wJ5==o zJjrtTGvvPdV(mSV?}2yrYPS8EpcVFqbwMgrqXK*N*4gRZ)^A9X@CEZ35#4 z{Pm}O4j?gy_`V}dCK`b{+W*r+*3|w|&kEq?V72*V?VO>DeKD&XpZO&*GO(oGz+GnB zi23qx?yhs^YJQcb_ZQ(U1h&l4J`O4F>AD=BECmkIdilKkP?03vzHTfQjLz5M=_2WyUj;;+W zEt>N=+sVc*q~cveG36fEO#YP0uIH1$h>1rqnxhg1r8mJWgttr=)pK= z!iBJ#@RXG@i>wQj-r(fQ=8vJiiDToU)&g!2=-X+e*v0VoJ4>Xt+04C2*m6Rj%`|Wx zja6)kTxjX%BktPU5ZS)z8!9^A@@!Xuj?KSys0`|F?4A(z7t0kdZ0d~F@IVy`Qdyv@ zK`DT8Y-S3aw=MB_Qtnhnci?$8k|D8`y&Mgup8oKFoIkhX1@Jo^H%cpo4Obr5{z0EV zO;j2Z=vw@a!SS`is%8bn01h>C+j~>NSi}HODgH_Ai%&qkLB)p&o0)%M)0ep;RBKC= zc67rjfI2NW&1X4|39VAL0KYd$th%z|SaXNK?oG~pj?ynH8%$D=6b;J{J;|?baPPJ& z?Q-4Ra^_m#%UCF2t!iQ2v=3}z?a$d=b7x75?G1yyQ=L<3GV1U@yLKeX2aRgJO>c|c zbRw_bNg=YCy^EYCUdrffVMrrwJ>O($)O6AITp5D* zyBkmaJyVCqjl_d!vPNaDY;i|#lONrwG28J0_#bb?l_RtW43cU)M%pLt7DvQ|- z98u5EEY)kO%ZaeUM(4T9vv*L{t@q36UG8$m{285^-Oh6@D!RuoXN2a3QoCM&I4c~= zdT^)7O@Pk1?JAo9A*d|aKdhs0`L*WHepYX0{Xi^FZXUD(^MgNo*;d9fOj31I^;TNI zk|Tmqn~NzZb#b_AQBdKcJXKARX~LGqyD8flDA-@Is|TXb)`=gbN2Rf=aRSac*-ZN$ zJhT1B%%S5V!k=o8YdmA9x5ewK!>|^W%F3yAP}aL5Y-l-8w5FL3Qhsu;tG9BD3AGUZ zW_p_II05B*EcKg=>|VplV-e$6-`vKy4S{(cpYggmff?_EzU2=V6^Oh0!PNGYM*okk zw+w6YedC9v1!V9AB}XU%BHbH}0U|I|RGNV_qepirsFdVH22&6a>F!p#W23vfJDz*~ z{{I)xb38A6Asge^ec#u0p4aF6#O0bcH6Suuq)nWfhC1f`+r-wKj*}+2$k;p=qFd{g zYVvOs8fsSW1pR=yF5ueZ&najqDP&aNsRNFof1PeL7k=RPi4 zWDw|2sm4GjPN;NI`wR;MLL&)B6BURvYy;TbejNB*)VbLBplJO0=HM-dj2qKxJ& zr6(4?$Czy{D8>fA!mf-qP@tRDr<}P$&4YS1uYq_FnX4tLF~ElX@7GJ6*?4v|eIl4ewE0IN&7q;DbG!z%C=GMEY{^)L zak;g_?2sw;u*>0h?NcOqX2u(w)Q{1o?h`E+8*~-hg~k|Sq>Aku@A}nHybG(Gxv5YR zXs0c1@U_u6w_2$^MMRd!Kwgf?V0qZlH)TUOGlF3s5ix3mh>##DZ?DO;vK=sL20op~ zd=ic|jO9DavgOfQ_?3_@Ax;!q^fO6vF>g%m+oe}Mc*Lw*?9fN*M`8QqM%WfN@|TI` z99pzBR=ivSX`OpKtFiiPV))H`60ND_)VXyEWAD@z}S$QhNygZBt z^d#^&gsyk$r5~sz5Evd>yk~+biz@_hwl#j~2x1O@VEWLQ`vsp`xD^wJ#gkbbeo}Tc zqTp2rKX`s6!FQ&ccVCn}P!`!0)L4UNl+3(%kz(v*J<>{Wj_C=c1aoMag{nvMjII)j zJ~e7LS!m}a5luI$?+EF6WdmR~HqzrwwqceR5*3Nd;0@KaPM^*qiTbztpXRGbw92Ac zMW4DWhYn;Jx4{m$<o)K8UDai?Ga zCC&|v**daH+d7%?_BgMUbj)lPQRhOdm=ILz#+}akvcT{VSfR_s3HA}i0#kKMJUWl0 zc#Bt!Yt01WyR)%!KkeZA6qi*7VpGgt?N+dmwNU1Dn)wZzTP{UY+T4rZL!_DX@vrp> zb=vLrjS#!jjdVExYxl@GkqB#mPcU=@{!zhCJG4ndvwxl>a(!sC^y!I{@L7Ev0=itG zGMW~;N{64N&jPNIo~l)FU;xjAzZr?1ahJ-V?!aPN4vP(Rochi%50_aa(PL&#a%Fm- z_{{;o%XK*WD2SWjU84yB4P`3h+}Y^+4AB;-T_9CmK-ejy8|}Fmm#H1z1*dNl%ijn56vj^=gfIQdDJO`E-BK4v zq+gD61xOZ#W#v}GrdU_VtA7*4>Ax3O_5Y{r8O{HWLS;UWr5(PYC9K`O>i}!5qDX z2V0{0XwdN6qkXcKHbh>f#YrjrymS^A1SdaQ-%KXT{DvPf{bq+_E}Wc=H3ClXb4d70 zOXKI9#THXAiLHG)I#`LPuTjIJCE-8hi;9kqpcI4_=ogJtP=c9O!3)O#{z|Ey-@t)O zP2`X1ViRWP2Y&?J)Pq^apl&6}OtjU}Dy8s}Ic%#DO>8{zxR$27qILt!p^at`jq9dq zL_yljKFdaPv4Db_7gq0+!Oyhh{6Jr_(cq)?O}qt?a^f8SU~qpip;ulzT{2EExYHLzW=&Igj;^e52SchcD@l=$&v_}7%mk1>iTw9naANp=8AeL z>I7JO!DOvtzlXFW)kdM~JZ@12@dR^~PDlOPd)&BOC!pZraaTL`F_lKcCQQ=#L`CDc z)MXZQp_^&%ek*lBN>M@wv%j^U)NI>?&z>1W9sQJ`$@sq)^(UacwbfEw#qqA(m&h0;gY((9Oo*h~#qSE5zw;Y=1 zyRuQ17$QQqg=dZ@`Pn=sn=W(hl zbiZD{zQF8m3I)>IEqsi8cW#EricNvt^T+LMlyrM<`qVBO8~(j&mwaqq)xn~B4nr(g zZhP83_qU(Y@^$q#lnMn-IJF_!>y?G?*cvmPa_! z6ltyNRijB#IEuO;Vv!=>b8i&hU}@GTdqiucMk8g;#NRH<=*FZ#vJYul3bk0`+G+aE zw@I9&{|}72Iio8Z!%3;(%#|Ih;QTc50^=OnUMnd&20Y-m$yStDbY1RL7X9FQp|0Jp zO4#HQ*DbL(Y;N;8wzhWRhA-FPODDHcrBAo|U!t|VKId+F{a!GtPno}wWI39ab(ZiLEzkH=rsXTy}8Wwvb*Pp;af z`%lw*Y*4wHLVi9|U4PAm(?2$4VS6A^&J~1y`mfsh{Ju;9H3e4Q*yRJtgUAaXU`%!^ zxohX|i3wUUu_0tbI{!(l^-UjEjwRzZAQ1ugGrT$4Tt`c@o>qf2dH)^5NKimDLqI=S z=w13>79-u=@9rKv*SoAjeqXr3GcxyzMzi5>Dd5#x)_$jQvG0q%UG!lLtbPmp0IDcN zev`5clH3ISq(!?Ns2(jOUD)}$z1C0eFTvSo@TlX=Pz)bPaPsy!Dq=)XOUqzmQvfvL zQc#wfZzkQv+|d{U08311;aSH+(1HXavo@~|hZtG6*@#CtQP#zumY}aW>9|?9R)XH8 z5^l*}7G2Tgr|zEmLt`D=lV5VBpB_!PZyC0y_?>pb*`@%3+AX}|v84`h%XE;ALj7Ma zfW&5@izcC4`Tm#dp`wZggXrJ;mh&u{jR!|PfrDLvY#j34n)$t#I?xwnA4$G53i5nB zzQfUzSEKbLeDK?CQ{J657IiSJQF{~IWhPVXOz)C~f>~Md3XtNnr{v{7h<-;`l4!So zx8UbuR?Q;`W^$$^2xOonCRM0Nj0y-F^!#y$d2KvHq5@%@(K3y%?BV64mQ-Eb2ZY%Z zJewM;mPTd|8|jryM7d&p_e&d%8&y*-;L*H2yF;I9G`2*L5aOP1BG?AA9$u-&QGf?E z7-i6(23=ImTM;UHtl9qo3gw4P1Pgku)uQKbjNa46(h_@5@tJ%+zSX zJ)dMj&Su)v8K#ZATA$!XnvGqhxD!{oirgdMa2Ah;V=Km+fFskONXE=Dlzwzimprqd zWVdMbdousxxd)+_S-g*tOg8ce zA&+Rlv+L6gtm$qSZXstB1##a0Ziga-CO)b*s4hy=_+?Q_G28^lV@B>;zK#7(emG7N2vX@qV-Y0T{mbz-aXQ#O&!!z|9&knpWO6Lc#ns z;je_|~0bcYo;v+8k}muRh;jRKEbSnOQvzg zSZ84rA@cTw1QN1(fa~h@{dc&%iq_&8KsIqD-CJ?iYpdv{*~`n7Fv=D<%?8slbxW)Ffd(;Av4c{Y6q z;bO-U!n3p71>-Y7#Uf9+)&FKguJ!9AR#{>3b(Qhd(DL(ym1Q=~aU}n8t=m@8&O3qb zE>o?s^Y8VmVB5HXH&gfaO}{NrP$|(j(jye5vw!LvEl&aU{{^yP9ONA2iGAaepqbFN z@T>Dxcc~G4?gr~qcso{a<1YJfMuLV%nWM%#t@fp0YI(>->-7nHXp%#n=M#L+RLJy6 z#5Cj7L55U>%jgJz`bm?e%m9T>p)t%4z{LLpNMp#L6F_BnQt|Ae|IeOG?#MH$cLZ~c zDx|itHwrmOTO0VKZ~a8Hh$=<$FYI~UZ50cgbym_Qb)W;kl@^%!N%uHqW?YXn72|0e zR7`&anSDORx-5GHJ+iKBZ4)$#+es?BxnLD)9{Q?D960(9}naUe2(odU| z9;E2_8^&>orOoYmioHtruKOn!)BS z(4$uobHxoonBbc1q@(Osm`$mS$mgp-W9E4ae1Y-2OjNen{H>!I*S{cY^PyLI6%EJE z<=~ID>9#L1>y$qKct1r3L^xnj5buJlCABBF$nzhs>(U%e?YH4`%Gd!mEk~_+jnd-Y zjdvT?S14$nt;D#__=;g~?oTO+-iEG2hjE6njqIQ{k3OqUFIfase(+nE`f9v?fQ!=TG6XLoW3z1|e z-dQ02xW5|1T=!<$f-PyrmJs0wa5VxAiM002wN5kuEFBwOOlrYCUmQwUEy=zj;3h)w zuIQ;dS7E#;SY9!va$m|3h}ByB~*XpWK3 z#*Q8`*JS-nu*Eilr7E}13zWrYPLR;%ebz=lT6QCj?t#%`1tfXyP}Jw~ChASEob)wa{Dc6T_6%>L6yzb4L%`c(3`|=c_umQQ)%$&u0 z`b#{;pOP}Ny#Li7cLDGT*GQFrl1QXz&r8SkO5CBwmbrkvRYne;4fIN{vvWbMETlX^ z6J*dqUkeZtG-t7nu5um#CR8O)lIbg83w)i-mS3}LUOSSBYK|FJ>2l^XT6uO3jiqCH z$o$z?LPURpYSv&>orHgF5X6Jssm$#Z6^7{EX@cH!asO#=FlX7 zPps;v)Iu#kV}SDIjK0c5&fG%chiyB}o8@J25IXLL6TOAocBfWz-ewIqgr2kY3q@)? z!8@6vnK{`%D+%UdNoQhyogQnJ-_3b+x>O~#eI02TkBEqM4aWN89~FaHre1$r4=x_^ zfBn_4AO5X%0D`|~-OOar1@9=ghi26Z9vf=W!{{QKILiRc@nUknWn)H1F4}qdhiv z5;2J=iGxhXPS3m#yiOxe*FD>>^*7#4c|0&N6zX=(^Urgj+DvQWkEl<$qMi6Z-&|mj zcEjM>03(uchB9u8(M*8s#64!m?zj7GE4`CCtu#JefKjr@%s0DsO!EBaYcU5z9I@>B z=`&60{xU_^gp61#-=_q*zx-vjw1~zg;(y) zR8qI_hpZE-cck|tr?}}%hp;}uUkSqhJCG|NHU@yVw>N@CBAR)1I=^EH-YL`gB=zgXJ@wX$S8vn%Lx2)#imd07plFtB(~{JDd>&%88Z-P)I6*ninm-+E7o* z+USzGT6NoXTy>+gaYXQPq2b_6gP`2=U;x)S1ok?QMm$kXuE6#Dl`qaCw=$2_lp@dG zU2}tziBsDpv20|}$3DwQCTI33l~z=3SslIoria!60Fzn|A2wh&)ed=UN{;sqoEr2B zGkFMgTN^2_-50NoQdB!0cdz!%v#!;ZF)iop+>^Im==2>v`ZBq|M|le`-){y2uJ%2Q z8MbFqiFz!QFNo?aL6IdMvVR{d%>s!|_7z8Ch)_J3Q*kmEroU2~i<}w4uN%!v&J8I? z1Ka{Dj?eQXXkpu9}db1Ccf$h=ps34 zKj{YLm4{)Q0n!;#0!VpYAUXD)rtEvAMUd?|{P&DIS(Ib?O1mw=3zfS~T{l#t!5W1c zU}hB8128kJ2htJgtCD`lGUzHbv^_!V)d43owYrU-Y2K{QQq8*CM_(9tmk$12T)EJS zN_p{wGhCB;W9|=y57~xeBoW)M^fDx*66BRkoS(L|y>($2?T8vEoZVP7u!$J7LG#sLVJ!6lo?1Ip-(5>)$zCG$qjKG|PrH2~jK6)shT+ID)_a`T4JTSm4nKzW zmhO+ZfPQ$tQme~rz6%hAaG}(`E03E2x5rvsmNfJN$Qtpgm~FaSfKSF~2C@gLaJ$mG zJ%RIcKr_b9uzX&TnL=b9@UIi|kj6&ULX~_z0w6;&9gst|kzGcyOLAYc< z2MtF(I85`X@9Og;!w1o_KE2j6@z5Bd{Mv_h88)WctGStSo7VFg_N;%#C8RWo^4)xU zC2GHsxytRRZ31JtSYWdlOmWsYza4&v>XP&WY~!U23;v7l4&{}`FD;v` z@wp$`^IKlw-~0@F|CO6M@`;y@5n2FayA(M}8dV?NWfa2&#oYMH3}B)uj|~+BW#_TT ztaX*-alH%PiYnjDi=a$&6R!zu&J_^5i1`4?ZEXCCU9I(3XY1YpC-*6yVg_OO>6(m* zDUUN7ltb|%I?BiFWJN_m8hlTYzb{^U(Qujg6=A{XUmR+%l8`Y^U=00!o*&{$9vb`Q zhG^#Nj(bXp#&*xc6mYsXgETSg5H2gqM=YWHi2t&Bv+j(dArFfXu)>Ld0A<^Kz&SKp zAc<{3gT3_%WpUyFUOj2GGRVnhk zLSkN{|Dn^W5L9W7IHb5vsMXdGRZ_N!`8IFh4ec2?0op7n60u>nF~m|;i1La+W6xpl z;RioM!CC%8)WLHd9LPs!S?1>))X#RUSx(>(!?)AUgZ}kCGE#YV4!T=il|JFm2(@gKyYO3q-Z|)I`c-1MP z>6C*EPYp=Y+Q?@NoFPm?%38weH-dwCzc$i{=70my+`L48Rz%_)^?HKJ%v>I2lXR}e zll)*Zh2`7Y&yc(hZ&ejBQr-Seok#8V5K5C+-oR;!hKIF5>aP?ouA_y*o*gEjQ#z8i zW94s>(SkF)ixcT5pJN8%&B6u41ZCU)oN-u&5N$}F7MXN%kMG@KiVVABM$nBhq_WPs-N4ffuoJQ8{OLzey)3ASZ zx|7%Ea;)!(@T!H_Iwjke_5@ojf9hVwv1h5ha33UrdI6;L8<5P;#D9yB`Er@#&Orl$ zewWFWZv%9`bB4eg($vWVzPfu-aUVB1igrPV+Zo0Bp8FOxe75D^7gbTd6Vb=px`|6B z;v#FK(Jeond6G#*C%R-ta9a4{zV=nGbJ5^+@O9Wf#z}yDX}@xYv-8(*C)qXz-@m*Z z@P!-)`J7psP+q8F3#9HqJIEc%dM9&m6;>5~^?TDvH5(Wcl|X2iij}taxj-~JN&Rpv zJctiO-DmB)IXq|Vpg*T*rtUc64j5KjHnni);VQu*3 z{gastaW_vpgQIUkf=O!s-$q9QvLlyzl~ z6KS7(G&&P7lZ?LMgnd_+Bp9IL-wwbuw#@|Vf?l0V)~pYo5g$GTC(e!>4sNb5;_CAv(WB zBj!Sw2MfFz>BMh(!N`rHHz5b{oIHGi{%+rXcL%D3zEP+s%1roor{lX_IQwJtQQS%@ zk3N_pr|njiXuGT#GB$!ojVrgIyu+}0(|Kbat?yBq4b4d}4)I4=3p7RxMSlEyFHys- z=tiERqnY*%p(1#P?TPps!S2~#mx~o@CBSZln8h{a{-{jA=FP5oE4)q)=YrTGJC}kZ zZi=czu4p&j+2dNKihSIiAB8*vuH=1!*|x7S_NMG48^j@L&1au}0<^=Zbx<4QrFrgh zT-6~H6DM5LcTG!$#k#xvtv@@?_rOV0kSu54oJYpI=+9dU(76x!<*@5WyRRRQuf;~X zguI~z=dc9>)4U8mSUwG%l|O7Ul>sE7$qUzQdS722M`09PymX8qJRdcsHP0@j$s&XC zjWyU{+cbq7w85v?rPx7#>h^-^d5;;mo4*Z`0MmF#Vhkk|NYfqIm*WYPq^#*HtO(Z6 z=u^$guTdUEn2Yk<&%9X@99#V22^{3tf%P!gms^rN?8|O7_`S_6bnr?r0)EWSyxlin zUGJ>!{3K&8{Dl316nh)J3U2vj&A>B1HKy#<(zUUl&Jz-c|7A5~?*beFt-KG@^jjq} zAJ|)U2jJ-clSNT@kMEj zWnE7Xx-a{-gf0a{gw_x=TEuX9<@kG_^l8p*M53ffPkD+;QHNh=cEkYc@XMttkW6*2 z|FnCHk>2sXR&Kkk%ip&~d$n|blG+$B$AEvuw8!TWsgLd3YDRl8vv=}6{{F)pJpg7} z)wcfHfeaap3s1#(Eng<0sy`1Q~r z{nsM&I_1ReE}-(h>S^pgB!O3|RdDI4T_)mgPXIr}PV_P}BUW+(ts|b+5x+9yk&air z!kF>Ma-RQ)7A??P#J@|!5@er8ot%CZUP@|D)%8ted8O+x_ebrKUqXwn8jmAy=E^|% zLdQ}tN1<`y6Zg|4L!)c$5ao`(l!w$*7dR#9DisCX$1C zB4p%yo3m+=!@GdA;)G@)Tz+0{M`1*TXK1nXnsYfR>~bp;(vZ1;i4jOLTo538Bv|Jd zG!k;jO&$RR`%eCoIs$?!IAd_HkoRb32>$Hi0Zj7&UBZyvqvB>a5Sk1>A@cO-xMVwS z3e39UIJGY#kCwHmVAvVXGvEL;*SBijw7uiI> zLSuAU-p@52zyX&xy$1}D9B+ek!U|Eav%TQjJJH=_h**h~-tQN??AN=F``uF1 zQL=k&9wQ6Dh@KVjS3H}Q01^m2z90l@K{%*m%0G(Os`at=Brjg`djcqF6khR&nZalr zm^qe&^=6h!nFCEm$!UDaBcUdL5^r;qt++cEfsF32%qr6z+>~E_?Ix`Y3-IU(3`E#3 zy~NCklN#*DkZ2LV5ly+OEa9t&RpvRaaWk4h8Kcg`EILYes)J-6CePqRlg{s2wp;7# zhaAyf&`!L%roEiHz65_Al;b)8{_AfQ@93ElUD@!U@o9MiWR=e(GY?Ud)*#TYx7ItN z<*2pUs3q9Qe;A4toN-e!?Uu6>UCx4zp4=%2V~v=MkkfSZpin?QgOW+%7)z-y;%D`K{S+-R_7(kr|eIX1Nxp47cZF%0tFY)c~reU>O zDzFeo{!U_fs8Up4!Odqtf6sqj^z0c+RiOKG#U1Iu#c*Y1_S7E#swNa4k^GaA!WchpeVD@?= z#zxa0Aj0%elD&J}(|Kv{jM4H+-M6I^Oz|7ZS~djWj^T@a=pAi3+!DRJ`Z`M1qj|Du5+%Vq_;~? zszb&ZuFKP_kFLtn{jF*ydJR;2PMSoa`(@d|FE8L2lq1B(?p_++Lp=2Q41T@7b9G$r ze~Vt`&w;7Jk!dqt6|*bz2d^E|b7sv$&KNl1QNZE(EvafXfO0?WG`mos1x$&=jOvuS zPSkzh1@*^lHc-}4)JTiu-2Qln!?dEf!csVSrZjkrg2wVkMtJa-GVEngJ9#WWO9>AHS^6DV zxg=Jpr>qF<#cR0f6?P~ zk*I;K|S#T9cTJmV^F&!lqju6^&Ss z5t+-ouLN`)bTwZfQRHP0OJ#QXXk_kiDEAV=cqZIqA29%~?Gx-|uFE4Uvxom? zXU`|RMJr^sPXuq%fX=GspzW1g>XDKyj_5a{^zVjdafE9$Fn_-=2e&#P@ zr&L1qdjqp9jmnBG3#~g2{<=%(jh*!3Z5np)TBln#WUS(^8VVXW3J)=^#vqB&k&oLH zWj$QUefX@g5ctUlIAdPr(zo5dx4t%h;F{}IFoXzy5yf_B&IQ2KWNh9Wg*?8&5Q29+ zp@1(y%eIVCSD(l$x2H%O9b=sx?JwcGra9=_ZqlfigQ&?NX+?ey@MFCM2`QU2oM@5b zT;I1?{*U*N&gM$DN#D?LVd8%gJvTjw-v zQP^v{V7n07ra<%X4H`VU=mDU4K9Wh3C56woMw~?NoF@+gi=fkYdu~b;6JxRN^$&pX zZ!rwgU!zWrL(EcBx&PWFmTgNqWJ-FT(Z;V`+R1YYkC%|@4za5+O8Q% z@NQiu>-}T3CFFzLbK8N3>xV|4P?d3Zctm<9yZ$VDUMl?bft(^(@Nh5Z-+nVjw|R^d z2KE~nD4P8@9fu#DDdqPr^$v#xnt#Q&nU4oqs_UUjXnZR&*4D_haL4_(Xio--Ka3{W zWaiyTT<)KOc99@n)1BvN;@O*>((XFqECVECOF>lly|Be1tbcE7En>Y7B< zynpHXV>tQ5DP|=LY0LupB5^hxf`%I%wlQN|mt@M>4Ot)XjjsQD{SW>4M-Ie> zENf=6L1B`gSt!i3T3^y5$tjAZ^|JI8FlP#mJ&FS=1F*FpN0h6bB~7VOIoPe}Cy#~~ z)FIm%G8jBL-P6&-Cu)a=Q+#@@az?%ihdygprH6*itX@XByK9neVk}0Z2lpJz!n=ld z5T4FfHHN)>2VS1CcvcjUdJ$R;D6j!$p>OvRUh1)vRDYT@?;g(jWexb5Q`MlHJ-(rH zQV5j4%35p~1BS@&Kg7p2xJi-lnNbRcagw&I-U}2aC9Aph_InwK#(UCe$?UlnC4X4C zC`Z@JkHueT{Ro>|qQw+k%#k8ek-0hcbzD^Vtwv`qfTQ4=B&=%hiKW?BpHucW9xmH& z3wH{*#%k;FOrXS6Q{*E+acGtMc)N!bE|Y8Je}g7`-{=V97B{dyqC-X4@dmJ3_`x$*cD6J4Hs$P+Uam| z`TZ;)e0TOf#WNifqlng#P3i(b^t6Y}?*ds&|$l%cL|JMZP$%0D3={5sLUwZuHwDZ0()b>vtnk*{AS3MF(0O# zjkGS(C;SaDHuov1N|GThl zARFr+5zs?m#AnhK7oi}o0*{&8G19d(jk9y~Q65OL^hwAwby{iXz2Mi^w=?(8>(qJb znS5o$7KuN6LyV52dl<AiwO`Z6oQfv`n966b%B^+uI(P)oKiU^X+zf=A z!HQNFW1$zcm6<%CN&ek;ygFq=>}UVB{L=kzEWOeZIZ&`UD;YLPYO29W@sqvU0NIpY zlmexZ;l0ca;lxY4x_=f=8qvw*^k2*Lv$+T?34Zq#4r>P_-%=XLOvV@<(dVvm&L|9S!Jm7{Lnd-`sk z|Ie)$H9;l@Sor4|om<+3xlZ8XulcO4Zv(!H1oNN>#FZa1B{SwF?21y43JQcuHm)-& zg~>(c#-d?2zdAtQvcbdL&i-dD$Ct0q6Yy@AMzf_U^Xji_Wc-WDprM^@2!KHJqxMK%~HOg2rYRa^@GdC(5E8G($X1fo1lu*wQQlxyuC9&=yCU-$$f!cd^S)oyLD z_pv}oUj5Q|yIv+iE_itYAP^=e_;n7#vjUaH{Z8{Q$MUJ9CS3+Aezat6S-XQzfIw%6 zEReUD=KC(q40A%$TcDh(M!f&`iCI~Pv@B*ORZFn;U|=@XZzZ%Pb}Xe@{wQa>WKu3u zBF-zog9-&G!4!juTmwb~6Q9Q7H2*aocjD0MrU%5j0&`4|5J8OXcMiI~ZeakBqY-nC zd+1Zq$QNApGUW%|({HqffppN%P@a#_3Q?~_&SlB@icly9vl;eM ze+Hz^V@~0YSmEV#s9BxLhxwWgv(a{GQJ$|chVy8~w`Z7V-Ywha%MIM%@0KJhEALp` zp4%;al}D~U?t}6EqP?tXXJjoy-XI&XO0=Udn7{Z^KJrSmrSix4$l!pHJID=>M*_k# zE=BdDlEUOgizld3yNYoqJ#c}2v0opSUv7y&gxsRRaN%9jUKJVzd5lC1y8L`Eq$yt82nwiw?gTd!mZgAN@#GP3{`oV@ zaQx9Pk}~t702Z^4Uj8@zoeo$Gdgw5mY?T3lrt>fhGsp7#EL|N-61Y zwp)wYYa~5N=%@Xq)&N01iQSdZR2DnoB|;Se?W#kV_TVJm3hSKN|8t%v7SNuJduQ!t ztY96r4zt``+C@eejqe8#8o^<*i%HGZAgsWo_R?f$aWlc*($9ie7z{MnN}oo`-tcZ19kUCijphLSz@z8hWf@jn!A`pndh8vj>vLs}g73<-@~V`5MTS z*sk7Ymvdg_|*_Y)Z^J#cJAyeJeVSbeSd#X=9 z_5mBZow=&mpo?WPb|1%++UfJ!Ss>q)sXyg%!;%`$0BP-2-*Lqa=!-3RhN#NU!mm30 zp%?prv{B`4A5}j!uWKAGr816|^%GT^CEjdFn~ULe+Ad0EC8bC;gGZWzE_%T z!`bg3jh$6~_mk$We}fpO@))s|@n#&{|MEmFi?AvVNKW+?P5aX~3gx@Q<@Yj1l#91u zN#&VykdC+8co54))vfKpJT{UP)|&7;I^sxaMcp~l4F0GwcD>NlVmDbwHKd*zfToom zV4DOYs)sO6aR?KAN3f2PbP_E&_6L*h{`Jgt^E(chT^I;#owr?0GksZ2Tt39EhnT@O zeAfm{8^d)`h?xXqJT~{gE*pRL`%y{{k~LJ$k1j;N*3R57VwyE0lbn$~`)5ctsgkRCxRGw>p~HcP%L!j7J!jDXuw1+*&0@*m(@f|h8w z9pMZD=+VZXh$Ib?KO^;$CsYsg3IAXd5LkP)`Gcz-0`T``CXb2%GNA+jR8c9s!Pvl46^82tYD+z|=J8YwyVmSgdo>=9=T-gO@4Ffu zDW0YxNH$gs!(KJU8AeT~YL^QPx3(Ld6ytBIG%v16s8QfBpEW-N5L4x?*viPuI?O_T z#BHxdLqXJ*AL-KWJB*%m=+w&IBFiva5Kh~6i_2-wAtRB?5rbkE!u;rR)NYuUb7J5& zma2Ybo}Z(k3VU3}md)|WcWy8B?$|Bt_hj06j602ijUTT{Omk!`-zS&=c;kulyzkEJ z?G$k)1kU)00kuD%frqdy-OC0!UKaZw^@fxKJpDAgt-WzS`lK>$#S6SG>In{jU7~t7 z<|r{A3h12)4GKmwJV70cx?^Sx^E+LvRn)b1rQ@mRY-Ry$s!V?{6&b$8L@0HW6 z{oVLjL}~Na4_{+q-gMjos{|0f(L<9+Msc*{+EUAVK*iO-9zi@sh{~V;jl3NNq}A~i zYL|h@!Aa|sbh^(WX2aC)VT#T1k#{)eO z)fcF%Xv-|O1NN&{W2}U!Sr2j%oDA?&qQ>e&l$YwnvCI{`%vzg268}xyU!HfH>oePC zZ9KsYqVq;|F$pv~?JbC{a=_nDWmXaE=rWG)ba&~bS9I&4PapO%VqCi+AWFQho_VYG zcxu-FBI;TMpSL!@`ewTLGV}TX6FJRsR9|>-U1*U5+W#}&i#J^j#m}Om>XrUVwqu_b z(fvuWenATCq0MnMrXzh7JUiOPxIpT7)l{SW?13xl!3;pB4F8{x+;|`^I4pfVl2@o^fcmN-VUP*Fsfm z7=Kvf_S7Bc(uK6iTM#TNUw6{vtK~IH#-2m-JbQO{zlcgnMa|D?upgg5UvwH9_TE}Q z(pVoK$l6_V8q7zpBMxypu5u-VDWaRa>qk`p^NQRd%ijhK*eVzq<^ynGe7ETP6lyUZts30lapMaE>T38dgiSMM?T?Y;D5Hg0!X==|gJE@HiOcB;&-Mb`d! zYK4m(kAU^wtBqdLK(!=hz!h-6g+0rAo@E*`pf96P(wI;Q&WHP>h*HQ5U$)%A?vbW& z6l!E$Utq5H8R5HNJ7&mJ_2Y|q;BJRvu1_)StEi#^z^Szy-yzqeXtM(3`-Om+omPdb z-G96;M<8n{GXJSgjhGqzdL0T0nCegq`L3#kGSsd-oj-Oyi0|N6rc!$T((w7JUUhhx zVqqQBl(Z)`lIZUD4L$vp@!I(p!ZAgI+@pUVmxISokk;gGSqde%ra(AlwOWN?AHcCH zJqB#|mUi@g$IL`qzr>b9@|QN=YbA2l3+TwqkQ;i9?H56(m|- zpFdk@!lYj{0DCeU!-U{+#S$B~!B&)~V1T&_VT|pw>Hk!tJMI}QQWg+3U*ctEkG4I` ze40-TApdSXi;R`_5ySrzzjq(zrW4pxC3Ahn+b5RJ13P>K0bDO=zLao;s+U{}H+M0f_YqQFyJ?5FKRdtg)hMu>D9JTp z+jiPT!CsZQy{vffq`h@J)TX@QaKfi-J?d&DDg@td&VPE>`|{RbYK`lEnhE#ot!Y+M zflH>6(~4{?8^_cg9+_lhb6_Z&m(@wE!fEU*-s;uh{4Vr!cT@YiHjH}OaTX<&U$yqz zDRZ*?CQ~INU~EV}^;<2FH=l0j8I+LT9|&5!^V8Iz`%_^AXJFpbWQQAz`ii%VphikX zaJE1q&xE@#aRAC+k$$EpJ!7M%RiU*h;kV{=uMN%4$bl5CyqAAEb$b*kuuAFI5uSu^ zO!NO{&)QVE`mc2`m*J6Be0hECPbCGES4?WsQ5@jk06q+#ZYt9K$WJm`@kzi3Xff+uYC1_f>A1LnMT5qQuaZObD ze|}3<{(2hUJRkaGtaO#i+>9@`I4!c;<2=c^SiirC^?@;U*2Qif-?;B9I{jz7?t&Kc zY?e-6YA>*May^!W%V#HJ3|t^ejnVczD#pn9g?iubyWT((!J_?Vh}aqJ0Z?pLjE-7% zrvXBGb-k86v83;M zO8=te!Rq1qq_Z(y=)YAf2B&23SfqtbYL@XgY)t6CAFbtaA3N}5ea7uxbWNpH{mKvV zZP5qYwfbPEn$i1{vRwTTYA4}LYPMU@Iyd>6+Yzy(JtcHv`~E2|TIy4Hznvs!8(T83 zX1YdeN^0y;=|MyO2Sdv8kR?66e|7kzkdm3na%~FLqO&Hn8njq3fLw@5i3La}ruxYX z{D z=~ol2%oP&CKg!#EbAD8lTEvP-C0fe4U4#;U?*ANNZrQmI&|u0?r+pru?_++_#84;f zcO-JTGLU3E$FkplnV&X~yaOY!yolS$%sUl7Hq$G4R1CBUYG97?D>D8%+k}zE-XKBe_3MC%XkW@~Ji69F;H*;K?}XQL=B2H- zeJht}ODS5fOmnV@*oKz8nyj;y6L5IT$KD$E~S zFq~}uvGSg*a=9pFJ-ssLLpI)+nNOMt&h!ls$`mPVB4)8oxC7!3ra*#~8mJxBeKW}f z>haxf^I}b8tx^D}#aWp-yQnn@BP#fDrV&cQ$dGK>CJB+>I+7tTu_Rdn`e54A&LmbP zP?T`=7?l}~30>;{whMd6uD@^7j^;>hC@A;XuD`z8rK1%vsQER{*(o4DToCBAcY-Gv zomhXa-*><2ISIC2U0<|^a{SufnanMpk|zBq2UiU^LHVtsLNHgW7{7~R&T7_5Ek1m! z$|ZH?y4*kk()mdl>3g-0VZXxn!1Ko+lOL2lZhz?#bb_C&>u~=+jJ*X^l=jkP<18?jAxU4y7O+BT@#^-NML73n)W33_T1r14I1pIp-Je`+dj% z`qrA|VzHLP^W3rbwXePRwN;(25AusCcON_udvcSOmAF`_8|!W?_gPP>`|T~h4rA8G z#hFC9Z#^uUgdJYl{mtTc-m;hA+SOq1mXf0trGA$zSBY;&)R-q2e?Pe@8)n7wtaQz4 z*LJZtGU9Ht3@?#>fIKUSBDA6Ur{#h$XbMQH_GqCmzQm^rZ(Z^JBkb96LY%wts+{~_ zcR{MN^H5*&x(D#ZZ3T5?g3VGpz=;jtLN*fHZ;dq-rTCY!g@8ng&T%)JxxKR%Vp)>S zKY!zysdfXo%Zhm#NGD<+kLUz5R3mLaZu^!^?z{3D9Y6C(HBrO2i!?>z}|EBT@D??^@ek1^LnF&6f+L1jqf0BSV%nAU5@DMOj@k5xqzI8`Ey>68XMCFR}XP`}%PElV4>JZ!=Sq#q-V( zEM-(126Hx3zx_TjV1ff5@rN{Ty&aS#;TKYQgc(YNc-5aCPDY($&d+8U3*5p%)~u|O zbhxYj+uY9*D^lw#y~ExHZl0fDbt&1;7ZgczS4jrlb=#M2>ihSssx!6~T+0OIr^cOO z-*fL~Y%Y~&Ut&B;$}!^eq<{L?jxH07_r8DlI$@wnO%3`+EN81B1qkWD`Ta6m8`dHhS%)IzmtKWJn$_ z{yL!Xz1l+4T2$kpRDJlWuKV<-r?Em^jhjZE<>Kgp?n-+t@1EzlQDs+gd?|UbTcSA@ z2Fp)Wmd|A`;yWmu&3vb$;dN|ZIk1t)9`yEq{7s3%!`l#8S3dqDuyqcxbQP%^Ykm5w|$z?39*a?h)F; za0YcwCo8#xvxS%2EaYB|~t)KTEZ7u$%5`=#7AKiA|C zR0s~aLP94a88Zy^pWN|e8LN@Sv4&jTk`e`NQ)b(NpyRI5abB7!gf>&Vd_U`|v7Dpg zhMcnVzPX%?vPhO7UvxUe8vU?&e1n!Q9KNc&<)F`!dr)G36<-U*eje#2SJvQoVSOwp zY~k#p!~9`#FVXUs3>)b_E9njX@h8e86HlMO?S&HI$6t>kiuJWW1dh&h9d?ETWdjwJ z+_`PXQog-ljv4?CNgnG{>z@13c?uY&K1^>&*volZG_3N;Y5w)0AuRk$@e`8h9P!HD zTv`|*?1}*sC&l@dOh-ilPo?Y4m>~Z9Krc`pFEa`@B3TzXg-vp`6G*->__!;hy z6Vl4AwCjQEAZfRmc`?YuC)KrgbXN{LaPp+}ThRp*FF-e7uHwbK!H5dVxJr-;YxApL z$#jgw=X~%byDb~0vWWeXG@A=n<4Bbyz+pIA+re!HM;m*NEh-^NN{%e3+@`*>utL|8 z2BL%DnMHWW2^@}6g*w`Ctge7o0o6F=kDXYJqPL#nKNi}(&$NVeY|pXF0vvKV_Z>{D z0RuD0%0PMcb$RbKQ8WsuQNvZl!V&?+o}h41quW*t`tD030B$1;XAj?#T`~M5mYu6l zCkQbt%_g=D_hJ&kH_DXXByqa^x^0!@t9+$Kt<4p?2GxIS0c278{OZmzg9?v(HB-!j zgYCrZlRm*kJjWUbZrKizmqWp2$y|G zy0eQnK&7&(XR>e$R2_TWcK+n|%!6e^AY1-$)^@u7v%5kLpa7q`cC%aFu`@jiq_{8^ zw*|SImK^LB+JEp8;Ut`6{{>$6dQHi(MVBUIO2$cLKacV%KF0lEc!{a3<#1x253;}) z$#I;=F%e-FWj@!Q*1BJa4*a3#6te9JWkKkU>Uog{+Kr54-a;3^L`tAGjsk_=Z8h|= zh|weIVxq{9eT@*WdeEfYm#lCWqr7m_Ro{lA6#S5y{zoTh? zhoxzMVCP=e=k0gby-TZ*(=%N7&qrBA`g0lc`xAMp6?5f><^_Ge4Apux@l`&SxO(V! zOKBe2s~!gXp{g3V9jXnFc#%#(gd(j@NCYN8rkb6=K3PZ&?%ef|hlY>SM4;D5dkM z!PBXoNSS7O=gBnQUT7$Pt^uZF84I7;R>c8bCR?o>XEguZU_kEv!||j3j!?%bowGL{M+XeG_C{ zA=@At`m*PtrYd`!xzxa|dd1ky9rEFnu+<-e+J2r6A36S-w3ATvQ{}FVWYJDB=%QqM zwN0}^|LXy#&SiuO`Bw# zVmu}w2|I(_B_jErd)1@Z(q`b+(KGu?NZBu5&;xyd;hL60YdFj`P-Lm~wKKG=-5(EF zWyhB5a~>fH|qyoG(}^Zin*yu%@1S zlCkN-KO>8#lP}bMqrv1Ce5Y0$vzyiyq-dh4mHiF2Iwn-*d5CX!x9&N6)0_r(tR^tC3nj&py64<-^n9Y;#cx)ZXTt!MmO$y;8%}>Wy06jpzOIZ-WgH zLd>?NF~v$BT|_pPrLaE@LFI8}OS7=MX*n2%BUvCw{l_6)0xZZlITDQL`YU zxe>;}Y$I~~^;vx9J7K;{(zX+(iwIHMmSziWZrPhJL3j?I>Jck0H3cnQ!tNWbk6I$j zHonT0dc07s5b$C_sy-O_97)KtR>eEKQd?Jsz1gUsl05%RWb4Wq1=*cL)+_HYtQ1rQ`HQOxDt>~p zI+Q-S9J?R06Dt-5(Q=^Iyof7s!_Z&aI>!c8>8rdn|HD`7?0YV!7{}NX(XV$~iKpwN zE0(3lW`Hsk1(2o1!D-QM!SCn(0PU4-pt|5Hp7$F~+Hez)<)lhPKp1zvg5=l9h$Mq0 zR!yZiv<>@BghKhwL%zZBy+6;W_5a+q!oiG!a3_Bag27Yw)~pd6KSs{*Aq)uMiyQTHTNZ02amWoG;q z-G=Tm#FJ0bc1LjQt&>|~J3dfdibgdcbJ2^(*l!;iP@A=;4^m=3nIQ_-9=s)M#1#

    dRPd*{`-@1sRqZ$_`PdV+^?@20qcH(2yST#K0vxPDvsfC!WZ^7{#>s##Ovy9OfjlGIQ__zfP;(7ADRfju@&6F zLw54hmUs!Y)a^6X-FPemZpvA5Y#%ZwzZ2V{Vof>@%ixRYOU4o%qcxu}d9`;cCum~L zXomM_Jk3519d5jN z5rNS&5#k>fjGp4de_dWKi@Nd>)+tR!FPxrF!$AB)*Yd`3SZhpP2R>@R2=S&Znqy}^ z-tm!^)_p-b3&5cDmR8(yop~d?{YQzf(5jo&2(czq<}mhCp2l$2BzI1+$Ak<`2#u{4 zB?^ycQkI3(o}foYP4f@MDZL00_E!3gPB%6s`gvkoe5Hz*{4UpF3>k%4T?R{r^ict4 zn28=V$PYPJd93|>Ma3;L^ZIt?w{K>r$A=OpyFI>ZwpwZlco(UiehIW}f>F6FXJv?K z*o*!U6cU2VEK>pi-5%H=Hoc8ZRWx{I!ka_%673{2iYk-<^)0-rCMid0ksuf2`t5H)priZr79X zua`CkY&WV)(@Sk(o6$r_gmUz}n$-8z{xziZfYwq4@@^151!+j7RsT&QMdnosC{JSL zrvK@v>tz}mM0%o|0XA!xV0W>!UIAwkaO}FJHdJRv1NFCj60;s>xa^O4Zal7g+IDGs zd;6Bp+BHpG-A_H5PEQW|bCK>hBn#2DRGV#&)e3(%ls~WaHSpbupLp5;Sd-J{H*K4q z#QgXo7C&&O7m_!Is)>!Hc=aCZr-^h^@9ph{oJ_dUHwfyxsapr-RnF5H`EJP@1)R7) zR8oqb%dgocT1apuMW9z7R1*zms4-*B;{Zr?KO@@!ZAj_i!@){dj^N1zGbBKANWc`;8M3a zj+;SA+J8ybrP0dUnwpwP;sG4kHA%O|@}S!-(x*{aUXte+MttQKxHeFKzA9Y-2BCT(%BIfe1-NJwCCadAQ4Aj8E;I*~_jBM4gkm##z8Am^q9r!AxnREbaNb6%h_ zlIG>)`8tyz>XsyUAz3o2SiqAP7Rf|*AxWB7PyO6DHkdmM5QkdQFVK5OIA5LO-Me>- zjEzG`8LbBL7#YRfOhzl5N8Nf<+*SvpKpHu(7OnS^j5&`2wcRAgdazz~u>i-!Y%S8K zK+B=a0Gag6$QjSVUwUD8Nwyyqm{haP!Mfh}3_iI!R16bY$tnKxljf!lYOv587Axw? zE|nZ9VBXv{IM}+_{pFL8ZNF(=7DM3=(_;^^SF~>z@$|^BDEHu=?85I@%cQJ5gnXm> zupM;FYDn+u>gqikrQij=NoC)pbzBH0q{WYA*I*gob-=AyyTi$=YTS2MPOkB~#BH*a z))-z|Hhyz_NF_}RVFiV@m`=-efCL$9UK;Qofeh8+cVG9;?WQ*hn+p^yT)0d@;Y^A3 zeY5lP?B(V!VKOd08YH+NzaE1HA2RLG;K2+t+ymOhW}eR9(6%WCNP;vZC+8-h*1N6V z-$&fr@~ZdW9JU2lHtV!r6%KGyzKB6i@ymhrBXO%CvQkTVBS*$ZEUO53p9P=7An z3HN`mI>q83imNOt@1FsEM))~m1qt2pQG4klnJ)qIa*cghXZqx+^m+-iP|-sANmI`0nz z^D{wYkX2duu=W#F?Y@{c2ap|fVl$axPO&N0=~PrWqyE+NIKV~&=j<_OW0{sbBW&9F z+zx+V<8RFu^HAnq#-H4`WdX8^3T#}3zr3=dTaNJ5(=~2DR=Nt2%gMnmVXLUKkP|ff9(5Ql1m2+F&9jkR7*tJFq;B35O^O7 z4-H)bmH~WH==}yo?qL`m3_Ixzh|{Iu`Q5mHtbM?&uY?-AX$<@03gUpy z4AijZ3a5d0wT<)aV+8aKsj%x#57r$#cM@@6ib^`ZV)d$Nu-GjNM9LHthdBQp|51`i z?UjU%(@rTI?J96ca-NLIjV0fO)0u4@PeLB_=}t1 zp?-U8ks@`JAAbjSvBfSc%ffUx%!*Bj{Hd@N7cCfq(7&yRqaO1?UZL7f7&RATd;Sj3 z`8#uSu&%*Tf(ia4yzw|91;M|9EVRR7y+ z!=<(%ot9^GLyv#-B0mOEQc!4PQ99C;_VVnkjyO84OX%bXWHm_p!LFJuKHqwmK09p~ zL2+xTReLK!5O(EM&Uc%W%dX=s=s7+T%qIKqCVhyHV#gFR3I0zj*(S7k?McNz7FKBV zH@+eaiB>}O4Mo2B-?wD&J6OT6za7pP4)wnw$?+>LM62SgQpq4QJ2OO~|8_mtrE9hO z(4aL<)3mb+{MvsT-6=K+joUS{mMVfOvH*z`Fnrg)gG#Ng#T`X|oSQh4`jxz)_yNp7 zD)MizUo{aBpce(}FLI*fSk@{4mU{=@c=?K5E!~ji?dU$o9WwzH0_-!em&Mfv{>8pJ zKNo3^!l`{*G32de^d=nVS0pGG^B?3Clvm$2vQ1NMBD9DUICDsJ)*X>9KL{C8{b zU`MpL08%GZJm~5m2kiMiHysO8wz1rPxjitb5qMef#$3CpC`5 z-urYUxQNcrnT!YneoBe_kZ8&c6Sk$3{fULNXw~VQ;@@U~wo}zski*4Bd9Cvq$@nHL zT?4%OaIje*L1AInrLQsDR3`N+di(x-)I*=@;twX$pK$0MqB%oJol zU8-=0`Y)_mqA(><-3n&InXcMG7^Nt`Q$GSsyTYZBI{!_s;0Oj~Aun0JNVbd8e z?!~4*I0<2XH1dUDPhNi2Z}~>tdR2I)^&dOhMu%Feo#z)#FdhdJXHEN~t_Ld7Hyc=- z780L=Xlr(M_HBH;l93S;&>TIrwA`pS3kwjIX11}tdU<%?%U(m6rL@*d;2(tz$fws# ziASdkjQc#s!ds(_yYTG*B$gFMO_* zWgU>zT^Y!?oJ*C@IUA@S#9xKD0tW+)S_Msy+*SZ6tHwC2WPgy+qQ*Nsyi84{VPK%_ z>@1M@EqkfTS9B~;Ri^Q@+*VC2%y4L^Hmib~LKRFSevd3g|jr7VhhWtJkerLAuJ zp-Ta~OecIhLOKa8iFh~hg&_Fw(9Oz@tzM1!j+SQB{;;jvS%>4|vpBaq#J)Wl#nq2F zk{G3v_EnV(@W67sB5P)NKFe^{$_YdLf`D@ze9gNlBr|4FMDaYG`pvdvixGOBJmj~ z>t1^aNsc>GA+n!}fGpf$5G7832b=K_+jN}#agmRWTHK@;o+A?-PUV23)AEtoHqjc+ zP2N<9V}6?)FOKM2DF>Ae|qX^ z6BvOClVQ$*yizuWA;O`~6}vM7f)sMh@<-FRmT@K5BpL9b`p%GzuQ8j6?$qpBoZp&= zw5kIWrI_a?PVeZS9w^*_tsvEql4ngA>w#3>wSv4lJVm@7ku3gU2oTh(VsiUCJ{l$s zG{@!DgZ3IG_4}*TXV0Qf9Q%ehEcX{``je^o(yOZCekY0td=D^8v){IZ>}+hznqE zP1YR~yqt6`3&dLfE5GE^uWikA%B6VR66~u5^>xGpX9q1HZ!hNYdfAh$sjW;MgAjq% zM=PUsZr(3<82j_H+I^*&BiXlTBKZ?mf3cB~-0|+ZQfqtrNT*tf-(U5GhPd=Gc|l$% z+ec(JE;jKcb@E!@)IM<_@*;9z?KB_^4@TLdz+n!itf-2ABZPhzXyeIIH zYLBnY8ys4ODkXUl_fw)e7jF-~g0*pntQF?XQVqK=;o}B=Dad=`-{e1L(_oTeT|~JO zn}@?i60{jgVYks6cCbFy`^<7?r0h*iq;&d)m2XD9r-!utRALQzL1b3M_)D~5U8F0r zk16{5evf<9`Tz|f0-rQ(1+gJu(tpzD9|K<+WDRz@a8N- zS|z|RIdY!H2-VsdGS|L!R(}>k0rJczvBl4#q+QtXR{Fck0|K%g(DjuQ4kR9le~eoA zQT+VV&dT-4`}tL`zF7WZQP(Kka6R!iD}H7=Jm!2bMK(1bzf|hLD2dr`;pA=z=+mS{ zYpVAwT)Ts~Gv6AO`9bW~JSZX4r%_0rMN(Xy(lzoq5^Wl+WStw#PEcB8R1elfv)(ic+F^L|&`o9*m6 z!(!?06bz3`HTx?c&xO*xbQd4kXo(e%$zeWb*$evmRo&Q;g!NU^yUq*mKc-7(H2Dut zq^;zK2$<)bW~`0K8YT)cTksPmif>@5XpF2*Mk^Qe+G+9(!v#zr-LSU;TKcg9B$$18CDKaP@K8&}6){4o{wx4P&w2(~ZvCm+Bu-Tb!p6%g6pMMrnGApN_ zxhBZ~6&Dv@x%HF~XmjT7VIoa{0(j}qR|D4$q2F4n5yYR>T}r-2_OiSkeu)nxqz)Py zPvjW;ox3M^l}3q#IwfiRk9wZ)+uDzc*y0`zmlF8@w!DB(w(d^0>w1>kpHE4w=V!V< zz&KrhC>(V6VBPa}esUx+0DRO4V`ZHtxun8IUN^qYf^vHGT&`bc}yH5W=KJM3yc>`2Y*CI0D zll%2&ejclX-xEE@9{`?#Bgu;uOR4N%p=EWEVa&-pVb>zSyhs-wXW7p-c29daU8BYv zz)*lM%*J-V4`0kfVic&Jhe8(kG_WSH8!icJZoWV6v%&*h)V$k=S;Fb^j7wJR?q3N~ zwsw1R=W-hntQ2KZN1P^a@>B+Gb%XJmhe#?&-{VF^VBeI{#Sw&> z$S)5>iA_7=Lg~Z-J_LkZ6P;vXp$tY?tkB9^(0qF5-D!I-aaNy9qyD|C9>ei%wtoK7 zn&`qmpJhW%PTq&Mnw|&VqXyXv6LGgYaT^pr#zX$~Lc@=0uG2o<$Lcg(9MUJqTo;Pk znHa}4{2=+i;>ND=B!!|L+kDe9op0?6JKsku>717|`aD{>nQy!c_$MSY1Rw zkcpKXH{u|LbZk@DagTPLQ|?Vulc3ke&5iu8z_XQ5)EGqVxoQV_dI_7850&#geV7x- zasi`%OTFexR$JU2pY!Ea_ELPOO|k%|)Q7CB*5?R_U$I4r7q&|28-AB%Xrx^H$qnZq zFNvhG`f>kN*sRp<+jN3U6fM{=H>F*;{sKxhWt<839l^mvB_WEEkn0~|uM>c%&~|m3 zTt*@ft8jJ38hp{lc#oUl+gcG$f$DY~;c#(Lajv^*8Ka+Iy6Gl!wJ(d656izS$!>`_ z#t{!aXwekrXv1pN3G&|Xlr!^4(^z)q!MTNE~s#re9Fcm6LmfjkDGHomdjrDC*Bj+N*-7PTjt?6j$NreE7_b zEJb;+(9;?`nl{0Gtx$lMwGxmHTfS94q5eph*#6=2c5-f&zaqqR2z!@`& zJXy`}Ok%yn(HD-SLfIl=2IrzzAfRER{Lb>l^0zX#nDcLjy_1~^qg;oxNa$g@+JN)b ze}dy5+4<=r($bX^UPBh7{r5*f$pGMI-(gx{qriI+(EJrH_nJpiWap}^*PXQ+i|Jf( z4gxAyP+9N}!;HkX(LPUSv)$`Rd(fsS14(_7GUV`%9I5ek9X?gi*@4-(0FCv<^FcSf zAF+iv>;zR3XC?Ed+c;pfKz*7U zs?A#E)g2%d9mS`^1<36DA=DfgRgZ25Bmq-b*m(ByyJ#aP7_^3T@NgEjA_uSztLFyd zwB=3_xT4`w7Ow42vcyHn?4?0-SSx;H2g4J_%CYWg0jhM?knp zvue9?{6N6OVD&njaWMok92hMp%C3WK<0ZKbpoJ^Et^{qu8P}#I!9UM5i)!&uM192W zs>^Tg!xp>D-dm2nzoCb2&;Btrn;s~1i8iIG%BNn9hQb*untN&X;R7^lHnt7VgvavV zh2O2oY^v&FSGRK178VqF#7Gf!f?bifm9{h{W9#k3?da$D&%HG5?YGHn82~we9Ig@r z9)Y#!T&UC({t8<0FwQe9qd_h7$dL091-BLn$6IfGPN^LFOcWNn3OEV2$9Q;1_iDZt zUK`w4VKwkbPFgmTPB?8-+(mMe{5((>bUxYE0)?~Yyo%?my!|tvrNhLcLlB{cOD77vL96hX=f;vlHKZZLC9Rc&PCky>r~JeWlD|F`%7gVNmMXu&+Q0=mU5W3Lhc7MKS8W4f!VlOLB;eoi5{6hIpFfFK;$3%@w zY@QZEo2cL?PF@UV$chYAw8h?2Km8UMQFL3MM26_WRqp^pJW&vb)_*M1y?y)jE(?%> zgGNBK!s)gB05rQ&9PTH@{3|g#EJgC0>lb%PFTQ?FnS%Rp`u(wmCxD0ebFKhoV4qlD z(GCaOf@QNf*_zdgjC-(*r}E|`J4S$J5&!Un@8}wE@p-BW2DzTenr0O`U$S;O!8j7Cvpa|*t_I2 zIpb<6k~8*b<7D-38^F!l~j?5Nt5t~*K>;0G!vWRelEPK#hku1{+t916ZTv+yC{ zmN(7_($?aole>m2GpMeg4K|w{IkB)toL3uYXe(?`W7@I<-Q5Ab!ax&-dU4@Nx!y$| zOEcMPf&aYiQ&6c;PK~*q5?vD$+&~_=I9`ND&F7J41d0l}iaNQRLNDWL+Yr z&#@fl-;y517yIcd@RVZ1Ck&AdJDn?Re5<3@Bp8ubz0AXg=VchFD)^{3^uo6sMnyp8 z!Wt0tCz$<(yz2GTtgIVr-rU-Gv%5WN96;0z1m4en#ZIZenG3y4THMUEdjAuhS|6ce%g*^a%sSj;>PIlhmu(H2M@A(k zc3_LRFdOxqa54$7mXrzKsu&(TzgxDqLa;K>L%B$n1Mi1h-n02(oVZ!b0jem*Zx+-; zHXy#qyvNGAH2f4AP5$cy%Ay}cddZg^K_Eny~GYN6u)+>XCtFhjd@d@ zeyO5hZ%rw;Ru^LHf04C2IYHFr-2D#J1)O7HHYm@q`eO*Qzlir9SxQY!!k<5XN*3H# z`gsm(Pw-IxXO^pOR*(70&!0aN@}7SwbDSWRFHX?<1`AzeL{8@5J;>cx*nD z2w4s&=bj9;vtJ9o$6GBRiO64BZ_!Q-Rzac;Gq!Qd|M=kb>B;|dRl>8~VTHK=vnl~3 zF^w>ht)Bp2#)KFzU&}~VT@B-)y-a+owT(zjrbYgt>&LwXA%fP@cDg{yg zDQfiJUmx4Y42z120%maaF%u!K1SWiSZhySOfl&Za8seK0F3IYpE%-2{ug@ZXYuh>M z?IQ2Ha4MYdM9BL$@0;|nZ%zuN&R{DXr?ChtvH%+Vszg)ewzM6bRE;%-6vpl)@s%IX z@h)y2{vnVcW0pz~U#|!P3Tz2-ureY?i(mE;811yum!RgOa*R}wK?t!r@?+XC-I^Uk zYjFjC2ptmitV^sL+z|FIbg?}8WlsINmfh7rd{Vt31<=o3fPCiW=Gqnve3rffPV+W6 zzfwnw*OCzHqD;P<-%EfpBKd1pQ{SW=OZSBopA930YQq{0f4f)c zr9$z2%gF)NSp!8LYkJRfPrKsK99yJ}Vg(>;$_~ye@NM(63^NN11$hGn4gOm%Cw^fJ{;-~xd`q4ovL@A*nIV$5g)Xw+J(k!FrW8P7} z{y36;0R(9}hH`S3uvp=pV{|FG!Spj@vxi$cH$Qq@RIh2_e^kil5D>_S&+H|mg!?LV z2HWrvkcmV5g{qr898^{g4j!owr!Sq_kGvake#Cs~*d&*-)*}~Qdg)weDXKW+hhZ;| zhrTpDk>$Z4!}bsQbCnzv*7ypf*{tYj|CY4{y^oKNA059K%aeXe?sz*wjBDt6N*Fav zy$2NQtLjRlUz+t2U1tdbF`$OIWCh?~Dm4+NJNh(tsc zLHXP4$cWHjw#49Zq_qD5H(TC2eUlDi-P?X*2m;;gdkg5*rKiB3zr)T(i&HMDRyVlx zH@8l-?Gd}mA4Rpub}UGlLXTwWml7e5E!q=uK*=XaHDHS{Z*bj!nUHBo%OE8{Zs?k% zB=3X~S3$pER%!ciXWUmZ{J-TNR~GHm@QN89ad>wrs(t2f*R#qRKE+uC^gl>+V&kf= zTzz3^oL=DhLj+wcX-ZVmJ&l1p=!u!(Rea7n#D4ss_Ul~up;rC)3|%GWG17x_b1S+x zP1htZ57}LHcdz*JKLr{x8{@SwtAk0n$DoBFj9vAKF<<1$uocNgJ&O$j6rEri$R2*P=Zf0jY#_GL)FR|}%Y>IwXcGpb_(kyf^)74Mc!Rn|Z22ch;{h2WrHy7y z2Y-qmLg5?RIt89y#Nk+}c}rjt7tnb81HXWiQySD4RZj=2MCoQWf9&R(6FHb;2k_7@h?4EpzJin0H# zzaiD)C)}AY>?uf{c;KbX%`P3h}6eG-60+hB+vBJP)rl(XYr(Rw++O3w|We`|gzFlJqyq)Dj1& zdJKVoa#Q|SPLx^JueVgX@#ibF3j1YzrsrDcZQxz$&QsCeqt-L^{xOuv%i~@I(EJ1J z;(g1{!)LM5i}n}9L1ZXvSO!Fn0J#HX2#Q)J*UDj;bu*-INC6-`kH=;GB%#CyZ*cP- zSq7-tIyj^k61@rYK7^gvx^iQEBv(JC$rBBW#F zWz9QRA|CF94f{cGAXzYQZDCwq-7xL*C`Wqe>K+8zRo7e)6f-!VGq$=KY!U&4@Ws~R z^8E;=HTAEJBmk#Ei(R9y1KsVQ{=!@KaZ(JSe{T^j5#lYcThLK~10243vimrM>$<~R z+AB#FtgGeB@h~nfhRmqHg~~w|e1{*pZb5g9JU-n=_~_J1@^d=N4_X~|0Qks4PT`z@ zJ()!@#}7k$QuAX#lVKph$$c|D?N^^gG5vSvgMtClYviCjyDT-OJBg{^3h1ymMz8en zhmOqopZ9Vu>O4HrBFpE@sxuN;p%?2$JQ1YBL$!8Xzhg<-@zR}g(2-V;RsG)*>v}-1 zySX5nk_=0s5m(t~78a&JQlTP!0E32NjPtJJ$p0>cNd9 zzUbq(r&VIgDZhCg$>I)$0s%xP0 z*z$CUpHyJ1Ev>+Dd>=nd3$AtFEbu}%+7Y#uHlVgp*VT*fk zEtlek!&pLgbf_XX_K+?MdGSLlt0$~1`k;n;<&E$r+;DAdV6DX;-D*NXA&fnoUD7~W zW?#>Nv|it@oM!Y}Yl&HHG4JI7Xb;OA!EFcf=K8TE^eY7C_|}n50Eajz5bZGi1vRG=(SvvbsqTFI}kQyUUU*)yuWN&7;9`Rm@k_7YKkO}6^tFYMkxpDLuB2H<=q z7uTn<7bM0avhx~#tKl*dB<1P}KY9J?EwEl(`fCB-vH+(jKkN&EdgIwfO0`CQ;_-m9 zlah^GgUWY6>6AD+Y5$5VZ-01y?J?WE<1dkr?Q+b`6pB!Z!!+=r1%@KZxwW5k zj_oflQUi>5Kb{O(KJLRUi9nBL)PPi-#+UouKq{t{qw~FXf4sdj;M5gVATP-9U=bIG z@QDmF0ugisJ>+aOLKG*TR4@Vu1ggAQ|2&K*Me@}j-vTwsQvm#oEFdn@@TO&Dg|#pt zUYkcsepCX&;+4GW2m&TARAAgsiW`@II65{f<{ocm9r--qR}88}JBAsSFi!S9Ha+#t zu({6q?mcj?q#po**Br^*nS8p-0R(jD!_y**cC22p_4jYpk8eP6>=H;7TXr(N3J>2u z`~-+}Ao7dG{9l#WSG{P~Kb(Uf>nit#fKg{qI4lUSU7LQxkswo|FT80ovRI*LT{3X0 zG8!<5M;>XenxMEdP&c3DpZX7clm!phzrmO35d^XQO>IMWD%lWH3sCWkk;wRmg^C=| z9B44S6a4=h7O0W9xetoS&1YMqaB*N6 z*)y@0%)W1hk+pyid=Cf0wjl5MPro&PT@~ZK+58+27p)VO|HbelAu@fUlRxs!EE8F;ltFqpGMGKqX zckPsHDKKq-Xr+8bu$8jiR)XFvAn)i5q>UT<==|2xl8Hh%QYP-m~lcYqf%+JW=TS_HD#IV zl%$hN2gBHIMb@!p31bRZ7*QIsPL?yH7#&%rVQ@b`oadgN+jIW9|6KnJ&n)Km{eFL+ z<^8~3(Uo>Krw-WIM4SD#st)j( zkjr19JYh7dq&342dU_ba2nN?O+NP&?k!8uQad!!Gm*xb`VMYgk^jN)X<829yWweRu zp-3OlLcE1e3nNS^B9(Ms0})0_!2@%e)9SNB-G=MLEX=8cz}-|?C%$46U3ih9(DzZD z#rABj!y(Ft2vcW;6xr2pKC>2_Ar`7+9f;vOd9#C>efqr@9^?C!B3`(1+H&d%MKFo_ zSp&dj1PO9UDKw#c#$F-#F3+1zC$J)V2UcZC=r&U+6_VX9@mjwB)IECV)~)Lc<^JT? z0rY!G9So26#Rx#}fs4E+9~7*#*P_tQ+goxRWqjk1Xl)em>6d0uqI-$15*KM(0JU=y zb-N!a?X@)QlK3$Gf{ezp_M6ur`4v4s5Y^g~^w~=z163-=_}m`RTYYi`qsCwS5P6ol zS6Ss^=|a`KcbS@HN^E8M^1~(55*W^F)@@~_n5qzj;Z}p|G&qhvXnWJ5#tAN5w9)>H zhRm2=^mA6bKfg!In`*Xpbsgv(Xvfi}nmHmVxe}4L#F2h%%awW>eri;W;VzG=5f_*G zdZr)UcVSwAp=X197}DV^*41y?u_43g0T{XDM3DYNokK(k5w`ol{#+LI?wTtr25%pYYJGJh?(}UaM);SjBSiDJgVt?oO>o}dA6%a!brgeD-lhV ztuVd#qH0jQC#q<6E0$%}{b)GlXVei#YYFV2U2y)N5Ml7jyGE1mie~Ako9OEBore^C zua4%+JKm_OQNA}7DVu?q$t;W#=EkDJ{wUFBTWW|atT3K_nmcvr_za(&URq0+I_nd^ zU`=yxQeZ7}A48g*Y&V=2jz@IZUP0|gY#f^SY7a%OjPO(@B2Jlin}tQ0@6d8>SOeY` zXULlZJKP)vyprK#$#sW$vQ_!c#UohWL|EyT@>)SRRWYp<)w5T8ZKyz6icO)0Fbeu7NHKhksq`2cCkMO3RF#tz4;{jxneJQO^otWT*~4$tuP82W&TsnUYS53 zYAQhFxdxL3h|J0m~m%p`eSGWunwGz*?WuK5(uXm@Fh^JVC>L@os&qGx@ zHPz1@q)Mk!rLsXfBP}D>0$ruUHQ;F@0d1AoGHUMa(mSNuwP4xN=EX*1*32#LfI0S= z0#+T@bDdHw2LiJgBe2p-!5^T&kiH-uKYKMZ>cJk`ZuV*{aJA` z;$cD$nR$?q&%|Bg7vmPWinG&93Qt6Qhpq!S0ZTx~a|JQN-qGROL~ zy*hOysz2OZ@4YvMl%WZ1vzNceIuOCO1rY<(DF$t5jNN7(%GR+Otr#a>o*4SMJdlSF z(^iI8W81#A+^TgJj<^#J%_@13BQiH9XfO$w`8zw(=AtE1)E?&<3UVT zfrLo)#>%&{(5Gl7!50vK#!LPwWiU~+;T-bDLG81vA z6SkGmU1MTm;=%hTAdllf2PIG4$h(YaL2Q+XhpR^ zUv(xX85@@2B5RpRCRgHNdjs;0g|nx4T~>@>(3e=Y>NGVp?AMkSivvHs{dn#`6hRN| z*8xoFqvQ87GcvZDrQSPn?3h~;RJir1p(n+qyy7k% z^T!iBBV~Tvo#+4YFhp7mLlhUxfCIaY4u=+lT*x8R!};4D@plw=#$@F_zYUf9C?7%f z{b96|vnAgF?5$o64?To>@yj38Qrf=#H7*pnPG|1x#2V-PS$cEv7p1COFkX|??`C+U zC;kgekx;|)21^cE++tQS2@W&~Bv3$`{DfzZA3l}sP?gkC=)U@g8wl|@TFt5-ZleLv zE29oq&DeiUECU@|+2Df%@&*@_ubPryTo?7Lmejuh4F!7f8?RwZtLjP&XjkC{gR7N7 zzd8YK7PrIocI#2R3;pb=qM~m{L6^eMZ6(GVlXhes%jxfMPY!s#`R@A)l6Jd8mwABey2`@R`C+r)TtBYzC$gkrvp1&jUgH$gudka zArZ5qJ>_8;llV38ZGS?{(+ZpM39wCCKD`x1T*Z%GV;26S-Rr8@RcwC8vEBi087JQJ zE5x3cfM5`{sA22a3O>MJ=Mr&^Hv)bYl`OeF`N_-HW{Qj6)=k16JEOe%eU2tj4 zxw*(9O3CDFgDw5Ru|P!62W)0k274CzYKV3BgNYUv%Ynhx@07*u`y)D8_!DWZ^oLRq zU$>@NStc6&hMOJQleBPD)}Ua(v@3S29iC5;GMSLBnr6`+%z(Jgbz9&mU=Fm)2D;a_A+9JB8!(Fx1IZTJhd$ohg>rO z*l}A^p9e#E`@?< zgAC^&XsVeJfq?8&IVlS#)2N$e@)&rnd_nmTe+KBJ>` z@OGpvCqX~}D;ZAa(JZEWa!4DqvC-4dCfQs?#*aZpa}2rEGrQq;P%qTemO)U1{r2Px z4#q_h=1K)%nNUa7a=Lcn$Pt&A*w~$R&&N?qDV&o8!$_(dl>r74FZ5k)HAr zL4yV@4hikyQaEoc4&VLaBo42+2c3`>)Y;D~Ve1tZ6flvPED>JKd3i&;siMMoJOk_k z@$Q{P9!M$?^ha)shm5R)MC6kC4C~N|M>qh+o>Z@D`XeS~^xaXp&MjAs*x4rYwXr>J}JSOlsJa z9tV<&wAQ0WgV>4rD#sVs2K^vmdD@3evfO-q^C_{h?xEbB?0qx$T4J7I$@b?WW9={3 zZ_qh=j}jey2D`zag{tpk-^m{sD-{6f#6%Vxc_s-qm;+3H#Y|qRjh&qrocc*OfEk(q z2P=g6D@QS?`@WuTjBV#jFNxOk+Z9VdsB^1`q<~1szE`*WeO2@S_v}2*;_kUoQLl6= Q*fyi~SrE;0cR61BH*yT!@&Et; literal 0 HcmV?d00001 diff --git a/docs/modules/mapping/ndt_map/ndt_map2.png b/docs/modules/mapping/ndt_map/ndt_map2.png new file mode 100644 index 0000000000000000000000000000000000000000..b99706297955c3b31d8bd33299311b45be14f9c1 GIT binary patch literal 21736 zcmeFZc{rAD+b(?Fw|R&RnKBfqL@1fZiiA+eJQqqb&$C3Ph>{^0iXvkqWV&T6B1L9y zGnwa^@3=g_^{(fA*82Wie|+2at+vfp;=YFSJkI0XkA2^dGxVmK;t_Hdas)w+C|#G= zKoG1yf?)8Z#PC1D?fql$m$P#HUF-IK75(a<8NBrM!|35Sugxg>If3*zT+pkXDI;WNC zUvIwTBF@RlxlF0i{9b~J6|YiXlTl?PpCOgOGxx~ zS!_OrA8KXZ#MoB_z(>6ef23Fy_2?E`A2a&meDdtsrmpc9`hOJ{Zkc#K*>0EYh#DM@ z+KZ2lzC71kES)lHnU3fZ&No-VMKeT@m%KWWAt9vITN!*$;Wyt_tx~PMb<5JfS-rt4Z-9o%!%)6=K8xi9$bdrP>^lHz82ithK9UN|mlJJxXAj&E8c zBO+e-0mJ?K_odc4G<9<=wuf{$IW@v!r`0oGyr8%4{Gd?jx#o@!AQ5w(I*J&S*w$MX zwP$IbX)AlmBK$_}wS-M~L5PPSoOWv1Vx03pW;~IMRLdy@9hs+mK4tAe-&6hRmaL4L-J9jE55G81UxDdycxl3C zBXa!Pw{On#{Rye5Crsirt;=>UNJ;hocAaQp)-SeJSo_=QqpLUlb|W2)NA&jl-BI(r z?v|E`i2M4i-unDN^HpkT`R14B$;ipg;nyK#2>b`i-JGU=o*Wq&;olLua^(ss8ChAn zG%O3d!491_pSl(VE(!@zNU13)4S&eaTfQZn@oMn-V4Ck?;BRWmZmY0WX<42LklI`Q zonut~l7NJ&z<1AczG}x7i^Y~6?C)ghe&qDoS+|(_nUIHk|%;@O-$PeQjrbuBX(2tMkKc0{m0aL7a8* zueXZS%gf6lQBhWZJF;Z*^p%S$0!c6-*hm7eIR2phJs;a|Rog|F?(D&G9iRA6=GP$bq@?+)}>$C;emB?jXBUbVj zX3DGB3A>9LMTtT~LUxIXc5SQ~nowgq@=Z4BU~;^#V{X<_IA&|tXBr*% z@6G#cVl)S@vVRT!+u(y1=7i%{!YfA2L~K2U^>N4GQuNC36BRy&@Re708cV+yTj1MY z*#)Pc;?Ra6aO6Sn^HKkGwOZu2=ULO%l9o)Z8KxSVK05KRG!*C&g^E)rP9R9R+0Euo zS9+XnmyIb6%@QxUKc_J*)0Cn1N=5x6FU4s(1cOOD!pF(!tAO6F-%F*}bL~y=j4zIk zfubcotv*#jzAhiOJ@-&6Li>I1H{<={2nt8EqXLH1HXpGrwrmkANSd|B7FGWJ|v zWq^9J)O2$pj5mMU;r&mZM8?L(5O*wo`uBSu?ZXL2pCR3QYZbOM=k9 z-B2UXP#pgY$@D_t-G>g}T@tahu)y5x5$4t9@`v}ZL$6UMgmvG(l%sbw!yl2u+?1E! zRZq>QILgD@zkwthl~75zrWe*@<@EIvsk3Qew|Q|5ofRojMt{DpQRQF^F5#`Bk5)9q z;PBzF^cVN5yqj@Q=;~S>ZS>KIf{7eId`I`%V7Zf+pSBxH(hxFnha-FJZx_ijkzDpl z7wd2 zEej+hB*b~4a7O(eAx!< zTK3?^Q}46|NcBY5NEINgl^|@wAz{^p(w(`!&>JgQiz64ax21lMoQ3GV66dc_ks0$q zvh-3d4*R&gw{5;>v?vjspLZ}n3bEMNfq(DkH6|mQztyYGD#D!KMCV+K=Nx(IQKY%N z%JO#BNVp?>fIQ>y1NmRb{e>7Po(Ui?1^g1M;PGEbp=%*5B7zXV$`yr66n>Knx zw+)|5!v;ho7jK30a3>r(#yNT$h9JFVCHNj7Ju+6l`U9)H&36TCw#ueehv z1s8w-teg3ulTU>cnCqpvoFIVxQ zYYc(Wvr|@n)6iu?VDG(Xiv4U$gtIN#DMZ5ti@p%I@G)B2%xO>eenHY*JOR?0BD+xj z1)W25sJLHBd*Ox`32|@b{2!b-`V@sUvbP`)1I6-oK=#l?T2EYh%;{#-lJ{$KgQ-J4yuFXZ~QGvCuxM6<)T|E1@zs|HM%c z60%8zPIdW*+q`@X6lESByI)K(2m|uu>JBD6B*X+=0EN$<9ewlW4bnYnO<~W`;fsTN zlE6K~YC3gHj^NrL)+|zs4=;uxl8ZLKnQttO_>vzXI>D4QtbTYM4!8~v@yCxJk-HNU z*qeD?ZesRw|8)l*;v>gJ_!djOYlB&~V0~0WqS2ttE1&;@jpEhGn|-T{jtm5=1|^`9 z>-P2qlOMel;oWHbV2(8?0kJfcIZaAMF$x&Z)>@;Ht%2T;t}*ibqWj9k4^|oPZqa&( z7ejfN)8^J2$t`D6{HWw4Pn^C;>p$Kcw{y6n4`Yo-IJS+LdP2(n{G#yUVuBFjz4Ak} zD(40iFIVBiuQW8Si%=r-_QJ(3();t}3*K5U{)ziR`s2+yd3KUts*J5%_7h=WR`0eE zG0}p}MZ+HrRJLM$@y9ESGXk(fbR=I0{Q2`HOne*Q4sQb}hDgzfD)v~hL=r`;2*Xk^Y@x^4e|=1* z%f~=W%|3g-`Nt3L3m2jx2OVW+SBqko7IPSRyb$(6LqI?vYHw$Q;Agthb8I7k1Y+E` z=Vw$Z_#v>vW4Dk}czVm0_{&9>Kgd5(Ghcjc(fsn`-EXvi@{F3>-zrWIR+dM7cu{ED zmMksCN(B#xvmKDC2mX>~< zo_@;MZ_fpw@pV8`3DRC7GhO*sqYY1Ga&(o8QvCLr{ezDjH~*-c^i)adDBabu%_Sts z^)(F5h>C>-a{BaX$3`}{pIMskv2*{z#>ej2b!5`G{OvHS4L-tc^zH@CJh$=RuKWd? z>#9MI3GKx)rzFmd{yb?_4$(tRgktqV`{64PaT9uR=c`8>qv%*!Z)7OPl7H&TycG!F zo2*++jE_gh#Z7u7MMq=&0S?DXN|ip~e_Fgl=XNkRP|j%2zhz$3QvhirfQkg6$#W9& zUyf4)#w z^wg=x&z?O~=?#4JXm>)@hg;ceZyzT}*~ZTSFq~^@z)gDN!0hAE^|9xI9vAVujn{Q` z;{}@6y#B35QQw;qaM{#Ip!7d>P7B}rApiVN?J94N4_a9x_ZRv~1g<`z;=Xt>29|HK z`v@7J>(Zr$<36_vUpQK|C9fH3galIzQ{x0ly>=e9mG$)Wz#``y(S%9er?IP8BG%51 zWtaAR78j@J?JWfZyyl{(q5N9Hh1?%qeJ>L|PwtixO0eqYYO_))2K13aa`Udagjvka zuR6CVcIna!9?f@x7T@WI=ucUEPY|*~x{|9uel#s+pbWrZ2#JVe;^N--SivowEIird zqGLt|hu>=F>K|o0B4qW*i&jGpX^9^$n}oaw7gmM*LD7#Xu>6tO8eHWwjKk;_HEb2z znZOnsK=|)>f&z+>MN{+j1{5DyMr>~eP~1JqrHyca5%ZIwY37X zgfS*^$fVJ8S=ij*DOQzEX~@r$orpbm+fi+`v_(_5x+#N*)akkH^#Is-tBNJT(ue8xj!`QaUTXwQXb#-El0ae#+ zZSy8~Ahv0pJ0zJ;RuKhpKl38D4ffNSl(n#Tt{X#NT?xdUCMc2U=xA=^6sR5Q|G7N@`6Y&==@}~jSY93en(rv!0C27$zmAi` zzd_vFZ5&ONavm zjJ=twFKqJS^gocHL@S$^O~UZkti6~NrU2+2ZbLvDO&REO=y`fdxR$e_2+bcftak&*Fyi;*7_9UCA22zz+d{`P~at%>6zc7wB9K9xxvzMBECz3gwb`9VTaw70h> zyUjadgw8enR3gzV`*?Zx(r6>(g%JC^Bbg8J^4?zsDbeQ%JI1>?5-za0J(K_K$B*;& zYRJ!{_sBb-tcmbko9f7-gCT6NELs96x%5j#0E2QE67-IJPp;obu^lWi_x;_iD^VOK z1&DuU?UUE#k6V(m=J4{$*IivjOuUzfQoNVRn&Si}yFcC`iqy$Be*Mb!OQ@^rE5}g^ zfuH??XD1~rbM)&!Fbhq&H?k2D5kpSybdga{e}O_%&JAg~dFcR( z>q^5RGlRJ7{)h8MS71^rPV@4HqnHUWhRnh43br~*$HYh2ZP4Qk`XxH#?KHeG($Mgz z^Y5-=VmQrFTupI+tbmqCf5dq``1&V+&zi5=a#*OeTI zaaUZ)Xrg7U76vO@lBHh(K95OE{ChuNC!c*|$WK<J<+VP`-Ke3d=^)1X`0?YL zZ?8R#;a5#}R#vrWz7w?+Y*xS|M*S@M@{hlr)32V%Rr~IRgoc)liN_iKI)6hs?96Tk z=68T7E0r&^5V606%U?n3jXkQKw1g6=Q@S+#FkGr6S?* z+r1!Av4|b=*TMdRLUO`VH)y~IEYW&+1sXgnn#^R-*r~r#wJHVnQrMpu-W4D`;?20 zW7i=8VZ;9QVr3 za&fL?rOUXo0DxtZfM%V*;f@6e9})9e!j!)rkaWZTOuZaPo2yhe^sx6+D3ou7gKO09 zQ3U9{tONzr4L}S@X9oPLg_=6^{kC?t$@OqOX2pdQn+}6z2fi}9i&xudRZ%#Z_JrLW zj|;eD+h3|{k`hvl#=)Dvo!JD7&GjT$?B;NY6Z5?vob(P7zPn=TvU``Ht|K_X#}{!X z#XH6-*(12Asp-)fMa6^tLZvMR`~7dWlhWZq8|QA1EbeW1soigXLjNoGtSKrBJ+`aC%qM2|GLg~5u| zUn(6RZqJ1I&DR8y=s8YMt{fMgC^ss{3F24pqfC|0#z5npDCveHqW$=K9Zn6A!=||S|$}~gbKHHa~q?Spcnj=Vsq;=z!$XwXQ z?|~9K4oG7b-(t9JdOv;p%?|Piz~f4ubi;bD z_IjC>f|L~h(!e$ilpx5qwL;_qoPJ3tNzjp__q?M+%U6W5zq!MAZhJe9vw!H6Mxr$E z39RCdk6|}~>N=64eAw`lYs!ydydN2v&F-4cpMy=VnLoLsxBvnoUu{@`p^%LtCFk+* zRVt{dE1wsFUf$59^R~@kMZ!TDI|q>lLUDA%?_je0tGxHrO#bTwN^3~#Lw*O+X=!P& zBP`8)aba~7+hpG4D4=L^5;LtMZF3^PV($%n5e5-2&1tgr)5AV(3gK|~=)-5vHDL75 zUHdyMX78_%7ya~)%Z$cW?*kvb#E`b#wR}H|KRJ38piH1&)gHElKfm~RjYv4Bg8K8x zZfLNm?Q@8G3VNYZM$bXdO~H~+*7aROz7)8*yd&cZ-*blIn=ZKg)zbfTujYMv z1wA$|KpKP?yeWC+$@Waw?m>3^DcC22w%dmE^(o1@n zIu%MYnH=Tx_`O#7NI?I@luS5(3<0^Hul3)Bh1HXs^(2)b zv2fEz)1s^{HwhIhes^o-aZpfu$t^Bq-FGwXnsj;x$ZN-ez(^7p&!tSe>?M3D?L_{9@?9A zaLE{NNQ4f-;Ft|}WZifz9Dcss&8v5&GrN&1O6n`HHz>xUmf1Y~N!X5A~XS^d&mF!{H&pWZBPg_B8+%vM!*Iy;FVFkW(@= z(a}?c5MrbgMc?}^4EFcGCHW)avN`oO%6;}@qnO9?DWLHthYt2dHwL}zhGj2F^ok3W z`uR;R$e|@}+7Q9N2x0E5yq!er#s&?i-=_sBFZ$c0CS8-RQ-9cB8ZA2L9taPMln+qJ zvEd!?w^DmIhH8JNrAx2T2ab-!m-|X1Am~b?um|?=>OGFBzAo|Y+;L<1-LQG6M`O4Y zBax#6nKXbuXeX>?EsL!?uI`3GmVxV@;OCDlEfoW>7BOJ^{!Tc9H{mQnFhQr`q#yQ@ zFy%y^NmQq`1rQoG{iRDAwJEP&deJONqGfIj$jbg6F|x?*B0`Wzupf zPVt;M&m?jqt~$Mr4Y;flW8Z{?m5J!rGls?awgX=%*(6@b_-x;-^4?NOE~>Opp|vXw zSTp#H*b@lS-OD0l<+KPx(*jd)jZ#;LiEtMsUODg1{opiaoW>gs4Gs61+!Ec5PMvN; zI>|heWYz1bjW2kTiJDhb)YYvZy`oS8_(mx5J(lVjm1h4u#SxHP3b>jc(avp3BhYlH zU{m{_W1v7{jT(RPG5kPY(t`L+1^liI@X!*#EI;J3_2_8befRxX1fbtuI3pZ zcjb@0g%%W`VZZfQnc&m^MEaz*#)L)Wu5V@9tyKion1U9$~q3 zLR>sSA)J9GcO&O|0;=~ASs77GYUdd;t5o{}Uwn++hu*&>p2_6pX^ZadwVCPOVqOq_ zCt!Q4G5`1zb~VUKEmLN-rR|>WCQEs1XVsI$E(4If_xs%uuo;|^l1c*EsnBUs4e;aG zD@HC(?hh@*xck4~wSzhjMK&-iXedLC+3zGJDjHW;Cl6fM6@baoo~w&3BlKHEz`0;D zwX$N0PD&(_|476zUL#Sc7@x_neur)t54s|c@oFDEdK3qnWJ{FneiQf)?hjUom)*`b zPZ9aSyp3S7O+c3!C&;FBck9N)#0Uc0$l?7AB=eOPp|+!}th0TLr#ZRbwWwi3BO@(= zxvpzyFlQo$%Vz+u>kaHB;F%XEuLdvnSf!u@^f~RECfFH)fR-HcUU{0Y5~p#NmzSc6 z5eY!$J#zmMX{dYrz-hn=MG^4{LBVH=>>iJ;QhZ)M$Sa$OS$QhsgJ18vprNsOuZ=xe zHK_@963o5M56A4PwodzPHJd1}3WtRFoh`yFwuUnd`b=lU#fv;-L5EaAA`yt|iMAB= z#z;0yJh0YJkBeFYYu)cY`n2k-p7Mo5MriR7L z-x&Xtlf$>R#F4&n_wtbM&Uu(}DKKGR`6D)^VIB&)hrnJ2} zT??BI&|V;IKn7|lFssdk-OROoplBnXUTpz<8I8WH@AbViZjj)Bt)}8f@F_&nQ1o&5CBf$jT4^R>8}NrR++n_79I-7MXJGeUybNkb zgWti9NlInjukW)9igruyeLG^A3z&i*boO4H0!s<2gmcL1s`LIz%E2Pw)B@Kz{m*to zYAG^4gPQ-pb_1H8sn&CSGNMAcPt>Trx5q^$b0i-CZO=rv?BsQBuu9 z4GG6sS+}maVpPM3y=m#6gim8T*?pv>Cno(4?);fdSphc2lY!f=D~~O|VwoJ01OFDI zCUN}U-qd+8t}rt*Yvt<4uCA_XY;DaQvG61m6cdZz&LeU+_-un#{vLpir+bRd0Q13h z{(LU(EFNA6<%4J2D9Ff8o;o!avkrWGwTGrj=r7}Hbv7}Cip0u@x)u{Yp!TyS@Uf0_ z9$`GN())YQTh^2N!I1;*sx`yBVqHG8P>EodPV6oa3<rgtNCH`w8 zQRQmTDL_{6T%EdXY|Os2v~=UOL}%k|mHT&L71vDv9xh)vd$8R6vqZpu(iH=QW?xT{ zmB;8)(fCXEW2}6dP?{~y#5V!(0pou9)V+9dy6p|Cl!4Z>;Xy?HW=w>{gwN3V^c_ED z-I00AQ2@x@%8SR5=P@z9EA9Xc!53uq{RI!VR`d&tp1hsHuhyN*pUM_4eC(Tp%{sTt z(i~#!4q7rSex*oedy-eZ?`iD2WwF2ARlPr-(L3taUlUF((-g5WG+FUr`em}T*D?%` zm;haP$gYxw2om<<)CPA+L4lyU!Tzg-hav`PbRp?BPGYQl#uf2?uuNzBN~rxIzX!(| zdxnBPZPM-Fmi_kXePfUDW2e=VZ=gIi3{1uDa&w&VIR=_7I+UZsRSqVe0lk8DOrPW^ zJ@Vt;k3?Z9A$LIo*I6WKCL)qqDA;#zdvBexu0!i$^+B>)vH%eqP!GotK09YozfRRucpLCH7!yc*xx_ZkrjNKa^oo#)M^Id2#PH+n^9=4a z=EKPr%>{q5G#&F52GnHhh7G!wc4?B8#%A@6AkI1|-jN zj;NwVn*IK+2l6Pttf9>ERk#=ZqW4^{Or~Lm(8zI zo~@^oGNgDMxbo7US;+F}@#D>-QL<{VoOKiwE)1BPi7t}nH4AMebNzFDJehy-1IaEM z3j1ra8`2Du*|%42S!l4rE~yBW^YluGCM&^TY`Fg#&V-e!>HE1w8E}qRw%`rd{U5o=mq@>APc3j&)RM96%fni>KD7O_gGDL<(mxGsLQ7lqC8r(8B;P% z6%O~PS_9NUst^s&+5WQU0R$w6kS4Ec+uGP`P8d9l^D14VPEUI?-oF=e*>y)nf3;*O zGC8mYGsA;|tI;Koj^`g6N|Q8(kpGCktv;?~75FgIe*k~?oa@)GUzskL69RFzYN0sq zyEV?Z4=lt5kW1TI*}4p!j-b#AIJk2K=Rt>)MQQ9epi6BSi~^N)GutyJ@>K(VX99Yid20dhImM z%?^~uVF-wyB_&bH?Pcd%e)q>XPj_bjBxCL?v9kjH7jS=*lSj4cD-o%Uey4tq$=9A7 zAt6J*hcrM&JJ_!R!xBhn!Vi*6>hpVSL{6(EHNovw933wLofR?j=jm$_>R%R{_93AT z^K%hSj|HJX*xYnSDH1?pkV>8Zc7%c+TjVf$?TgFII|!bPN1(EXWy&E*l8o$r{bg)P zonbVz%g5X3O?s<*Bz?A5&A@Jg^t<*wyul$9yv-)z@Ac<%ZB5x@LIz9A<=)vI*nSD@ zBUcB#7Ah%^i$ol^Ev*q1kdsd*T~)sw&3VqA%pHfc8RNuQ#T*@xuBOz@AVB69EL)iL zOKg9@ei0fGakn)|91xG@!LCQ!LA6N$V?Z_=l_xdxR|uZ7pq7B06?n)XA_|7HyP?;! zGSHf`(D2h>iX_Y5!c;$S;-$DR){yjkapA=$jiFNto6NA(Ns*Ted<=skloJ?_yvfcS z?8{%fww>-uLt}^XpKq|?QU-jC{2XtPDRs-XWL0x>PH}N@_??RndoRsb zZWtquPEH_p?bm|7-W|ViVDiB9X0>m>kVV)_N1Eu1;OtBfStgNdt_u}3e{5wSSYD5v zY~w|?f9~(?03V4D7pOu~t?!;H1}b*)$E%*sbh3qt6)Kd$d9R*AoK#-6I@KF{rrdeB zp?dF#%3N<1pNV|BE=rq5Thu(F7?R!LyAhA%8eHAm?#{1b`MK@SJq`Yt9K*60fvU|% z=ojRNV`9F`tM}ECWqw5Jm{@dV=X>_PefxHLs9JV!dyVVdxew{h3^Y8qwzX(^!aB6D z!ADl4F0oSaab1I2h)Kt2JmF*xqFVto()cSwWedm@-D+Q-fKYMU+gw~^l0J#GTfNu- z$%AbjcCTe6@I=4)Cc$aWa(KBH^f_DnnB)HSwojzJ3MP*$XcR00###S(ubq?OynY>s zJSKSE-^53zJonaGHfMz{78N3sO(wp%0poI=!?i%(#qj9M*Bz=X3O0P#szN!4fvW*` zuW7g#k=(-Oc$|rDsr|`?>I0cqqIT<_NOW`iX&D;_fNOr;(^D70gaPX$L3mKy2d$Io z%E$O7+lstEuHL8OL$F2%`SS8D*WBKP(j#vd|NR-av*~ex~z{Q7x$XEn349f!pj`c(OdiwVhShU8T92Pcw zy17JG@I2YEllmo=f8MDw$ywmnWPGMxzj$14&Qr$7%{elO-X#-9nmRzm!-KbX|4c*S z$Zl`!ddUg7q3W`(YQrb5=mfTTC^Z@(;Crfk$|paeTGqXvC)hp4qK5`u&!f`+o>l`A_qz6O*^o;!4WGbl zqpzg&>=_g#<>wjR!7i5c<&j{zvHz_qdTaw+$UMcDD0CqkL?OL4B5h4tc{9K4&&GRwzHfal zvXOmM=t-b^YP6Z4$C~xUix)FZs%7#k*I7Uaw3zQNLm7a$YOPm^e=8OQgpc`yu@CLm zu=U$C^ObUc1|=t&kicz*=Iv!kpzJi{8N!2rvIgUzpV?e>mCv{Eh{y8-WM$jdztxa$ zEiHFj>q09mn9@so`EUmqsLg(DO}{_rmie}I?dXOcUxe-NV2?bN%9@%Qsiiu)2v+eJ z<=At_enTYl7@%7|j?H{Ie=qJh4My&sd#Sqhat7p?3qWuI*c>lwF`$_uIfZp0z^3X5 zOrDAy8co!4Y8l2Wn7%W!A3V12x%RhSMWC{-Gfz5BL4GU>b*(-^ANRFnBWlrn2o5L& z82eToi`Y`oXcj>vDRN&jZP59ru8?Ob>F8thj#s>!`)ej_oP-_9Gj*AL?#o@nf3 zpstX*LkyNK`sSIVG(0nh4=ZhU5_(U5TfRi@F%g3_kB`+c9)_xG`IFmhcl7&Y&oBTf z`K>g+$msSvuq}{#Ct&-$v;4}=@lU5KmmvGp(W6MokTI)(qI@0w;Uyz5KP`(sn$}=p zYp;Vc5ShF_15tu9{|~Qry(K@s4_-N zvV$5Lc^aB6AN1NsX=$-|GC{-&)u}(VVPwGmf)ZTl7c?CqhCXYZ=#CF$?e041q(Zsh zSP2Mh=tzMxQ0lpr{%0E{Q0n07OOLI=<|1>R@canTe8C8rzmihYYbj>`MRBL3neNz& zD9Jq56pfP108Sx$-2;vaqNIf!4JlR8fx7Rpyn5BX(jdjQS5Ei!d`O@PdmsPxZ#Z82N&u>G^7XL2A4 zzXLJ|ibf`2Xkou-1t6tcV#@{+*sVo68lIDf(^5s46q`i(us$i(VU980pjHrJf$xBnbo zhG9|#?0Z9Ke+LmLf5_dkuN-n;W*$7QABmg!1F&-+xKSb3S=~quSt_|Zc#l*`Q(;Ob zLF9{TK=Sy1=a;v3T6Q7JUl%9PTC8lJM*IfWOSrWe#`Z5z1rIao!+e! z<_}O|FkCfN$@xW9Y0&l@u~9Y>gr+9-gG>e&$)% zb6{E@{fl25uBGIVNdgRuw0bdsf#^PjuB%zv-z(QP$jhB8f$Kz9ZH32*RP*3J98pYs z{B>yIQ(i5G;YtBl8O%5m|MDeqdwY7UK-7RONh*lvGTFR9y@NF<7P!&puU|i{Hy@5x zWFHPgHNcU=;6HF@j=|D9-R@QG&qChi5@u|lG|-5B>421C5H{#vtZ8CZ-m}T_uZvNanJ#^!-LLH22QHK<~09#f|SC^ zc<}sPyFtJJ&y$i`AWLm-jz)cJZYDT!_G}2W7=!~?gYLOG+PQ23oEi*hSIA{&R}n-n zPqxu;PS~g@Fx&v>JawrhLWpZ3{FiG_H-T6D*@C7h`ls(uLf_2J>3P)fD zhP)7YOLRcq-rKu|?g&AxU^f|`gP87a_nqCO1$!`-Om${6qLvAmiJz4|oSYVi9W-Om zua|4x*}XH9&x)ba=QCxhyYx_B>Y%1W>$;NJ12rlmcF&OC@6|QI2?(fH9;WDZqmiVm zn7=Bn5vPco_m(})cj~dN+mI@x9WXMT5fdwQ|9cFYF%COY+JTyPo71O~-C!lr$$fO* zAXD>w9C8XAf*_0wgN`=`>M@%1ZT)p!!SV0{97m0xAINA2hSC;8LNG$~BiKED^P?8xpab zaIHP@wX&(`E0{QW&=jQP)AjQHaSBdj>q*k1VOXQD}-OzJ?woL)kh3@D?mziIs4tG#SwD;3}C$sR9 z-R1Mk&~rF(DEx!ndAkP@)cIsCK#W=aa>C?iojo{+>Vflke z%9Rg6TU@~gi1V!saFwjZVwptl1UpfPLSKh0+GeQ&N#{0x31ZqEIz%y<;4?%Q1k4`L z;d{%nb;30SPXaG%^9CCIm{<9Zv)Gt{*x7pfDW^Jwu~N_`esTx;lc6D$S=gE${8(0? zFITheFRLyhxM93@|BwWE@^Q8!Y!XoIhcq37nkpnNX|t5d z^5O;Ig$qAFzFnDldA^m5oqvJADnLTVs2((GlZZ~}bLv40?{?S;nMBO6ivHJd45^}~ z4q{0g)5qRDYp#S+lkUtFIpjW$sVgfm#gjbycJ&8vp-XRT(eOMv*x#r|iJP$`$;Mn9 zacbI*shq!4%r)zCIeMeJe_h+hjgeW`d!6KW4t)0=W^!3;%Ode$H&Grd1~JtGZf%$b z(xzmsi5it?zdb=p#hyrPf1LM#Ph zJXO}A)VZF38Z>lHoH_FZO~HUUpkEi7Gp>@B?buHJnftoTho|(}5?EPZSTOv`J>==z zJ(r9V+kzce-0>8GZrKhF4lMlHwq@Gr6@7R)M-am`)=XEqfn=8tQadg*ez^ zJhtct;yeVZ1O$ghegI}g-K{7U31!7Q^_13?Hra*#4IMC-$3xfUm^wgEW(26rgT3bh zMGpes^=}lkGqv2*EciJzeI%%<#J| z3>x8+{JN<2C1`2 zM-xq}2@U9QKmzQ$cR}<8((6u954sBV^z@RQf+?B57Fsmx7TzTTgYfuN`&;LQ!GR|r z!+^|9DQ9VESwj$%yD=FP8(R-OwdiR8K+v5O7LJ9sFPZHrE;O6N+EjVt4E=DalqOi? zkLC&ijbI5$gOq7A@Fn(@T~z|el4$KA>n8)t<&w~fjej*_JDH-_(h!VH>j@bC<0*sI!MJQ#A1L;2#px7LNUq{xCGyG>8(j6lgS{Kvq~ zVx%rKZZ`@19t>Zk8iA()x3=LDy@2mDOrh2C*f$^q{))C`LpweCi3unNzz)&-TSvZ* z8v314w+-~ffU39XA}(VVMuP)OgzH@IIGLZ0bzKMzm|Hr~!w~`@27YIN@nDO%@ITbv zEJu*`gg_mX*_jpkbKayi+HHuNk(A_3z&i#CQSWV@u0hvVSB6qj|Ccicv?mC_KT5C# zeoZ~7NZPmln1qLgjr{9;gIie|-0D03l4sAYT0tX*VfWI>lz&ra^T7|_4yKSVZVRn> zVx1IU6KD&&r_xTu^XJ!1`?K-0NHJ%8>_N0;33Nne=p8&Oa940Fr+&e^(B{n@V z|LVb-yWjV(2CQHE*~{X1{!oU3_7*eL}xgv}`qzJ?r zpt#%)bWQ^=q=*2QA_{T`YF-De2~3{}5-!$cI_Ds*XcVGH5^z0#1wz~ZIFcYB4Ei?Y zcdsT?l0aw5zgjrpSIsX%H3xrAL)Xp!{r3O2qk$%EzyqZ#t&&-{vl#%HffXkc=K#?! z?RiP~!Jkv$!iIMC=$M$1SLV>TB(HoE&M|?U4($U;zz@=U?gAHO2I&K}mjgDw1zm#> zlxP>su=3#twBc-nv;1Iw&4APbb`=(jgxf>Ls@sxXT{6KK4>b_7lG@Xx9kzT0q@ zba_0kOBvkDEjlm7Bo*i^qTUCfqKIq9|1XvsgS%wPhn5?QN89aQ9dZA55{adi)y@~f6d?)GEw zxy=AhG9dtrra_}_PE$a+R?|67BvVy$3POG`SC47#}!701=M{1r@#^}*4%?!v49Lp>~7{URgb zzdw_KY@*9p+mED=0QltV>VRd1zi(W_{H%lcU=p&V1X;9-A9~#W+r8G_`u#eE9vDFL z94#&2&;R?mV`Mo7C6ST~70;nJ)$F4#YB45f6{QS>{&iIL2Td7mTLYS^isw(%Qx4f= zKt|{`1}8xScF&SNfE+2$m_wRRAyFUNzyeWsZVGcLY+)*Y0wOYdYEL}!!Y~aUQV(qee z>URsd6aY>=lwAb1l3aTKJ8!-q5cViIhTEY86_lrA6B94(Gxi^XgnsJu=|Yf$W1c?; z!yi&u@qGBTK9G8-NdQFz}p zn_dF6!Q}rDJax5#NqY?R^mpM&>zrDl=(vY80I}wM+cN7WoJ)dA^S3yR1Hg34B_i_Y zx|*5@YT>&BO*_G6Q+u0=Pnm@p?hRIWq&0Rt@#_bY?kOyOll4-W2fI<%5LMfQ{XJG$ z-y}!{9=)h%3TWq^0<%DB-W5MMo(ln$7+V1Jl#Pf%K$XqEjFq=cjDx{>Is7%~U(U<- zG8I^;jr+lwL$pn~>bolhE@d>005LxrK*Ej(F~NU(v27E;E@~nL>7N=v?R&8Hg43kg z$uLEDUlH?j?2vB-0DXA6K&{ga{&9OTCLs1<5=WtXjws28`JdwllCrBRIv}}{QB$7* zUcqm7l;a;uWhV7OdJqL;;ln0^{05OF}IGe$=H31^MK=SGJsxetkC2 zfGa8r04@#qX@Fa27BofF0eGX_*Q(xV6xPSc|N8wG@$pTdjga^Ap7JvUh81KwNf?~n zN!bImV+gE`f4VGU&p`!f3F8hm4;>53Ur747@FCACyFWS1z)oe|C@_?+&JXl8b}E@&!rpVdb?X)q*J3RRr%_DC(_aE}y3F3H zCPdyoL%OSh)fN&SzG7yv-zZ2)OvT!Svi-}=0-!h828_akoH~0pQ_f_5 zu<{j%YFPq)PYxZ6>hMgc+hP{HFmrt+Ui+V{JHtrW-Ek|G+skc|Uh90&C6odBo2TqP z8BBfoUA-LWS4)5jP%cH-_gh!d&GbzROG_4Ls(ZZzzC>pKCD=2Mqu)9#;xEJDi+8{y zeGT3z0+vfR2og`)VF|wlm~l-_Ei#ICLja^AK?wGH-fNvY4NwY6`GJdDdJ@9uKoAU# zchHW!25?qJ0At0)&)@pw_D%}8qyNB(cDWy+F$6LeTLU8%Ccc2~(Hp`?A=RDvu zt-WcoPoplq_5yA3Wrj!-MH`FX!chm;;MbnQJk$$PLWWxdVTC0iAfN%{!@KF}=}ge- zCIs@?N zvp|M00{n_ztw3yDVE5Z~cgKw3N43*HpH z$$x{*%E`$QDZ$5w_|F$^I=ryt!;%mOf}5OkRMtmA5XEEoAI>+K3~LBdTvn04^S~`( zY1rH8L2u2;T6?StG44xt;y>r!Uez;T_2Fid&sM;HvSg53){`{CP94X3M?Ux~4X&PH zKkxLNcWK;_R`_$c1K#NNT)b0JcHuQ;UBc19XCexo5!zFL@F9qp4wnsrWYHHOa1Qqk zL<~U}ZsE&9ke}aW2p59z&*NMG7nu?JflF}i{{NT!zaBA?YI|ABXV}tGhta&ra2b!arE$ny)TCeJMch2NNj=RQcWez=fKY)^qqg1a*+J`s^mNN51WETgAue z2!Jn*LgH>M4`V0$rZiMlgZuJ~v(Hgo{r3HP$Ks4z*s=0gzOGKz`MGeXO(kvA!Pm@8 zm0!Pp1ueQ=xCj})9o=3Uu5um2H4A5v>Zx*FL7${t>155E3kKho*ymtAiky0AitoO! zd&|KK56m~+|IK_yP;`FVtRuyYLSy{6Y>qdcM=H_i8Yc=peJkXWv*C)!?N`IS;D|3f zMmNqLZdbW7n6?^1ABB)4vNMd6PNX;o-3E&?4Cm&0Q(Au`YsP$j0h1!@({jJ(ZYhzlliVzuJWe4UH(2tmkhtl zz6(Snbd?EiO`jmPtyKg?35c+bGM&Nl9*$BLr(n$z5=9#&qyy(V_1( zFeobGjVdOaSURABTSOlF8)S0MNNAT;vd&%6J`BpiHN zXq1VzvE3MDft2sSBebN>mVBYiH}Zi&oc@W%3!0aje3X8T#D0E^)YR{IAF*+Wr$`}Z zZdKwbaejT|?7Us$r%#NFHisXlbfelXzLS|VCR1mtYvNbz<%mq&vyo{MX%8Njy+9k9 z^}RyBfc50hId4iye`qxTH=hx5vdP`37LXe&wCKvwH=25tQ>shw@ndCE>HCelN?}fl z$6|btTgXN51IqH-Ir_1U17w_kzG`I_3atG=7a}Z)F4VC?No)}A%>mJ2`2y3_7F~|0 z09MHBHAGxa9W?h!l~0Yrzu%-qStG(C`{H#Kcuskt2m+i7jyw##W3;CCN7u&J8uiaH zJ&k-@?Dl-7$?+leECFN+-&5bP?6&~o=GM@1{pxru7X91=S`CuLM=J!=G#B0&_S$F* zGAANu>S&D>bna5&%GAp@i4%MN)n$2T-k77)IyQ=Oq585;UZQL{*?BZkr57|*{yarD z&nOd#5$9Ukp<9cg%DmPy{}D(|n({~%)R3F7)3BZjhUXX)+hvl%F~V32glc|*aPS6L}h zv;LcB@cZLefxLRVqbNTfFX&;i+86Ubl_K7Ab64BbANpa@kXM!}?aR;N$aK_p zNxn6B#{JH4pATXv>+Y*1#l=?OgCO(zH)P#oKVJ2AbbRSdQL;SpX=`hU6fj3USD0xB2tsszIFjjME}JT@JNXE5m~)X3shx2#dD!{S$wl93xK$ywaJJBt~3 zNBi#Gw^)hyD-hhz>{@3zGWt8Q&=EsWG0@E@QaK71ILC{Wnl(~~+e@kA}=)}0#99qDH>jVlHQ z1`kY4^VcRDv(IwHYy$GB&+4lX#F$*eT;b)rPf_dC;S4j(m{6y{QiRUV2g*CqsXzE? zb98KM@x+xrY{2Q^!wTx{=nv9D@Z+M0!Bh?DJ^9%rU!RFbH)y(Bz;_Rpt2Au;ayoy! zA}aCRSuWN>CrY~7jG_I-YaO(-BHz7xClE$ULqoX!N%Y%_jilQ@pz9}ihsAh6L|>`m`}J=i@y!0b_JCcrr@)oY93XjlPn%;J-AdfBLt zOdVmnKeyUq1(iUaa&mUriBwr43EyUB zo_+lE$@bSfY7bL0~YjDjsDqnd*B4%cLd*LSWp7BcL959(jfolN9I2@#dj5Rtx35ww zP-6Y~yQRkd;vqYwR!*gXi&1#GF1CHXATX-Kh`Pa$cKiM+A(7~8cu|96W-NhnK@)%(K+p5F>Ug`$OO zo0j={#U#V7ri#q67z)S-B)1`}#JQxam!dqjH`Aq7!>t}9doDNM#>ibbO?^Xe<)3QA zr55wEV51eopXKRw2#Y)mJ67r9E&F}}-)|NU-<{v&vUM$J4lMF$3q#2bqc?p|@LD+G@KTY84_sjtCjOS`>b)(&G~yO!6Liemxulp3#;n?=j?V(3Y)Yx__}+#E z{p4%3`$j@%00Nu(jwIiZh;`Sl<4dd76UD#{K8BCnJnubS1u295z~MfUze*~t{2-p z-2c(YYB`mel8RYVt(o?06UK1=eGu}K9SuMt)M5QGT0$WS`vx7#n8t5@+nVw)1E8PT z5#BdiXmbt*XXyyU;MCtTJ8biJ+9Y4=5abOem;EI7N@6h>BfvSLpmnJ%qaPpfLLRrIaOSC?v} zkHw14hw!&jOEC=SE=#W~uNUwKQuwYJqA1I}{6*++@WX@^T_e~{2(Kbo*n%m-)Jp?& zm3UZof43xlZ{sy(BZDWSfPZI>oR(2}zixkPo|Q!Ivf|e;-Mj$Z%o{E4YF>{U>jJu( zBIo_XQG^2Uax^G=Y3@Wc@TetvzEz2(If2W-WLW_zktA#@P`@$NtWKZU^RYT)9Vdwq zJgn%TJwfAbj-LuCBzg}m-pF8|9gjxJr*w5|NN$`AhJ8PoQ^KfAW=by0v#ZZv@mcXp zX@HSmeC}9I0ORaq3gItABCw&VUj1&`<^Dm-Upg1D0^bBA$g! z97{lH5~bZz&6Jr#+Rfu<{>Bh3>uF(_Y=!OmriD=;`#}?QP1l%LvS+{D?i#0B(z2Zj zp%PYrFOX-kZj)pzh8?UjYSZLD(fpWz&ow4^?e`P2_Tw0SJ!^Nt1b^g7tg+tni%6Jt zO%>ovj@YQ&^^$=a@z0=GR%T=~4en%>KNKamGxVNm0HBZ_9yIHPoJt8U;!zLVXfEs} zhrG*Eq8)4QizK zIFXM-IERtpo4F2J)$~nNiV)5x@F0nMb14{ww!(x&V!9I9>=R~@8^~I#mZ;yq!A~j~ zRQ6Pq0GuG?_FV{JFer^0XSCN;)zX?N4ssNeI>ea+MFTn%L|uBpsIuLV$gC_}san!` z^3BDJKX??JwC4llFbGT@jmt91u<~fTK5wq%2|u-vC=aMUq}#(UBH32T3C@>y{)usy zp}Z4)s|tGztJiiehTcQYFs-SoiRE~M62og&vWr^pyEo(5 zWn8cbCCgYw!vZ;?{Vn9@V0mI6zd&L?bU}1>1nVntwP8`I|fo)G=#WSQXLoO=yMbJtIb!8DF z`h0EFf43T?*>ujgYmj9Zq*O96Z(B7+n5@}%IOW9e~Z~TcKH&1i5~wTl-RNUV8;_i-gczJ@Y=6>vou{8@)yVngNb_RI zg|W=t|K>Z0m+%<>6JwHhH2pE>ES{Xwz2R)Vd!uEd&OBvCF_jQLE*O`||B;M+9eH$vM`RBCBnz$@RRif**WPhHOX^QGL=ly8)0d7k}gb{ z%*mP_l5&@=w`?qlC=`$UWFO;$v}Qzrq~)7=@~&0jRs&N!v+RWMfruBfWuw`p6QL~^X}8r z>P;aUci*0fS{OsApe|bKl_26lwP#b;{%RyKQ^v4I5Ri811*u|KI#1U5lw8A7qY(u; zt?oVzVgYFfJMHJ)uP;G3}FhCr9 z$HEX_?xJz(tt(dq5VP~lZQ|O7JfRF9y(5*BqCetXpo42z_KVi*Pk%L9gm4;r^3p!# zRAApXYo$vI9cEr;3Q|nVNW#>p8H(LN{6VvmL#Js3%#sqT+R#K1=X^oq(5F4w{)?eD ztHFHfql7+(Yky~zy#iKx^=4W23@fx5#Jlw6>xjspn-{?RdQ5+8)nYh{*A!k{PNUvI z3UcQL?)@lET=}#XDu-!eGeP0jDQI#NP)x!-!)VU}lS-d(1 zaO86({crEGA&bU_x{Rwtb~Z|vdO})D5)H5Y6hS}|4?dCk@zrcb!FM5J6#0fineg)R z#@%}SavM-0Zf*Z#Y5F+3bN(!yc^p)Y_9kyF(r5acAMJD0UZqhT&EpN*^MTgCw9vdf z9$xYJw7okkb5fx$z4sI`Sgi8N=tU5K`zeEi22yK3so+wTGczww-SlvRw&Za=VJM5# zVDPh)qRiZfcP!E{rHI(1lOg(&@w(7pKIwJa355h(n}kku&(cuL3elHW&I8b&zRyyg zoGRXiJ2u0`*6%?LCS*TU{?qmi8Dlyqk+PGMFWW+P_V&6+By!@pj?R0|%(OHG@TSZI zUZz2{{cJU}IbXG?@5e_Ekzh(KxOtqd{{BIaluiy=IWJd`sC~}qFb{8z(&6X|Vd1r% zRMansxi6OU=N+{GNED-cVSs4MsXcx;v)P@9%n06QorPJx>!aRxl2oJl2cEII@|GeN z7fnwpT~4WMLGQ-pq&GCfA7SvU_n$nh41d&Vds8h`o<); ziE~?XohjxF6r&Q;JGK2yX{v%@wJuo1{%(uu_7{cKcxm6gVD-Uj{S!gEnC-)EnaqPc zU$xKQFj?Kjy+WDp1NRfRdL%#;2Nul(fb^%rfW0UTP*r=EN(OC$9-h-stX~(Fs8})a7ML-aw`0TZqF6_-F^>-xS?f%Rv?Ntt*w#0t8@@E0BVd>l} z3TaJx=OIU-Yj}9jTx#WC;xWL}Z2hFtm>aN6>V?ZuW=R+2sQu0Pl*uqjb?^O6Ed_;u zXYHSJQQikxpj@n+Pmh0~tJ^?g##Hl;gqcB7*Y{C@+-#ETXOf#0KNo3mAV+y)5lB~0 zPc^C`g#NutHCW6#>GvZ6B5Ri-36O)ypt$(>hbAU@)I7RV6=`#SbM`$#51Ta-deLjR zs1Gl3pxsAcD=HP0SAcT9^5poy`Q&J4Hd$dV>Z=yOgUa@M)T86c)d_|_AZT=<5agR` zE4vT9E3+e4VQRnX+a8X*3rE0zjhv$5kY<_aN!6_!}hq3?n9+%xrQ*!2Zh0T zuKBpH?1OWIb^GT%d!WxK1;91z5|)bxOC|0?f&-y#0sgxJlb|I*e&gRCXiuoUf*>(m zkWO_uzlu7P-?_@da#}ANk=((9 zyn^8>)RybQ=|KoMxER!QJnM_Ofv-kS2l<7=zzGZzSO%?f9l zd=0@(@4?4*NT}k76j~LBf8mt56u>VeC5FCGfn?SwcPQdmiUq^F3)B}!4ijRD<3DuP z`%X4MkvV;XNW?|u8;WGIkY7IhlP{=Wj+FDCAaJ0uYiHQ)7tM{P8~DZ#e*uE-6wj5t zp=iH>-v%GTPxIqhi#Qcz=b=^Jvr%-d-C(u{3sZs&Q1|EmUcWvratr#>4L=YX z5bgz6nEpM2$@T0!7rCUL(T)&g3hIeQ*&XAmr-+eO@PVItGJ25^N=$sHmvOE;BcmNB z#NnKt3FaCbgmwi*;gD4ots^&$KLmLJtOcrizA>@?IQSxAcbP zF)IW~1D<;5cPZ_6gy0Fq*{G)Fc;cKMz;ti!t_gar!tatlA+*cn{9iRkApnlY|6%r_ z7fU2wuH3e9Mr<6lBIUs^VaKX64a}TEb zvoOzwn1va5Ai%Mo;@zSPLjN8Q!7RLUzZM}OsOmKd2_1t3Zb5#SH-IfB`;CSmiPJhF zPv92N7@%Fi6F71h($moZZOtp}^!C?E&HO_w#KS>}0nOpVBT!O8(w@ZELdS()2*kIJ zb8z|xz~T4rpPmVl0CgD02xn%ft zf>#^>#n75K(wwhZm78($-`!y55B$CJXH> zw;zE*Zs<-9LK(rROF_%2aD$6UWTu{?#@=A$xqYf6{LSIJ6tU4Iwuu|# z^%SA!0=n8iavYrt40T@;HvjA^?XK><`*?q{$J})^@sK{+qBZJD^K8-4U(F_WwS^te zx#Xdx^8q0h%av0bh+1iEJGe4dX7o=5YVfQb@BqYqd$fNH(L@w1JzzjjK}~_?wbbX6 z4VlTwKkB2CyWi5j6uG(~PUFwU@X)OxWNHsEiiH*fszl5x3!5*MSX6wC^yd%7hk9O# zBU4Rk!VZfN*z3$2+n4mL<}-IUu6A zS@h=_zx(xs;g*@~;2I7dq1DDrn|^J2MTI_K{(~CT)YPI;wVh+&OO9GPi_)i<2agL7)qN8(aHSA5| z_k{x$L$&Y3?^x75W@ZrhSv0D1Hf@{ket2e{H;l?PU5B0Z8rDi|`?Hk7Sy+mj3<0Du z5&fYv?7Gy2-*S%;M<`09H8EQQJmhCjOjU#Xjk(!3A0`ip12#=f_oIqmq8NtEVCc^YBRzdEJVtHfsOL$?=iVZ3(e7W=|+?M;r~kRkS$T$`{B;`m8J0 zl$EWs`-YJ+#d^D}Hn)RHgHx$rHzy)>v){-)O|JGZjcV1v^!=Kkq3>rP?~eN(^%t)I zzFDm_Ly1EFV2A4@tZYTuH0f6|0$V(vnIUwzko{0oGh)pLi|U6#_+(?t;P)T%wVf%* zT9+TV*1L|g2P*otGmb}p3C@-SSf&g8`AMMap!&AxnuR8mRe^)#&GIqaVb7JCC{Apt zu-mHHu-jy4oTTgW#aa{)^Z^n)H*~J2tLy9RXHRuKqvs0WPdeWzCQ{N4*ee9ocaz)$*zA zEeC%wsnsFar&;|wP~;4-zV*+y7b`)8+3Zd_egM?J?j9&?=nFFgBeK2royN_T*R)rd zB>VbuW0BK?NWizx=Q|wyd+!$qTT4eKjq9_xI8<|x+g7jMVz-7&Z=&l+Ccw3GL&)~t z6`!4|kbujwx@l>cg$5%IzZ_ih+W^;fKg(m7C4^*%?dW6586B#%R%%aB0H|&)War!T zeA6-!J(s8eE8d)?eyT|nBi~BX310QipR>)M9)iXy&_uH6j{p?g*!8TOER8zN z)t+Dnp4ebTGQZX>M*pDrszv6r_G=T14wu1*0M$kbWVmFaaHzIYyOwQjIqiW0Fi`zUtiHvq^|H}|(sJRfQj?{;KGY;k6frFOk{6|B#w~pT zS_Q-a0Jh?O)6;(mDV-2y=gz~#<*qD*7KJg#zzlTU@9W;nu&bgF@Pw46Nf{&L4+tfC z^0V_jIPy0;ztwHbT#;eY61@<6uKkKZlU9(dwz!=@`=;L|;CC_UI{y$y`2H)BE z0r^n?1YF$|9&z^qQ>gM(TI=Xvo6kz!BB%I!=3 zZ#W;GQtGi5W{>dy`T8#<_X!@~$!oZw<$yAuX^m}0zV01|yk0&;pZXV=T@y&Is@;=e zscmZvkY1G*U%CB@#rpw4K!CPB{Ve{O;vZWmK;LqYZ|?^}TDkBP{)o1Vi^^TjOjpeM zwpytVp?S^FyxFLciX}#+Tv6q&VOJibhaV5k(A>`Lrr{su z`Bu0@g@D0qD;dEUDST_&#lB7Uj_0rp%fA|E6f7IVNP^~q_i4Iidn>j!s;9^j6^~o{ zmJb(@z_H*Ym^eSxK9qNCneP?rQIwY`fseLU^4-OLLD5ToeE-%$y;pHxL%^Dl*8~%0K4a|9QEHO3)nNvKxOfdfuok}aCh?l zW*``*Q?&a2s!G2RN3Q;)^Lt2^5)2{lBDdMqeU3AnRPh+wgNr}L2)|!<5f>7Q%q-BN zDS>cyFTtQ3_)lm}Z?wcr*=StdzZ(T6<&%Fh4cqB1TcRFa&UXIL7?m(lOGc)x5Rjqv zisEeNg^{b?zX*+i3bVtcqV(YFF{?prrcOz6*1PMVngP;4v0mO1DrPEN7ic7kd`2-S z<+tz|zcX(UuSr5h_uYro8&we%Bx3d$rgUOxl?gnL`R-~fVk~Bq;Q9f#nTkR2TMFW{ zSUT6sgT&Val5nf5>X>MSE)G_N^#bGu7dC4HmVgzfB)v11gKP4gZ37RN^lbAurW6Yy z11zuoBw&f+L@wrf>{KpBarlGsXp9Qj#2(p7&a?XWb!F?VCp3uwx6TqVw`QYOt$}!R>$==E#AS_nmP|emI9Z5RhT}evb(b92y< z0_hpZWbO&z!QrTJfP?HwS zhk68jczS@*ioT&gp%vU23#>c>?WD0lXnB7%tsf`hc5J5%gz5mkgqgN@3v4Ou%5fd_ z)`QIjEN){sZSkUfYjNr6S7DFG-8bhu0StHA8FpO^lsQbcv9Y;rCoaLEqaCGB8sTmN z_Pjv}ca7%mWVoQfc{D8$nq`&B57%3q_ohE_u_U<+S`QXl1ZQPumpIL9t8`^O%ywEG zyCZeDTE75lC(P}Q`!#zr@dl-KvD`d7H8v6wDa!H=BaW{y-eWlW1$4iB#+yoM9dBF} z76OF-v|2p$<>4nLoL0E50_F*aiRX9kzPed4Md`fQ$NM~|y4uLF)UFfojjnugZ!tH0 z3Nrrir4D)Gn0gBbzlPlMRKuXs66Zx-7y<=#%BTzio6Q??=D6)j0Q5OOO9FCM5T$`c z76D8^6&@cK$EgB1QyXjR`M2o@+J`lS^HQuB0Lld39mUOepK_+5xG(He>2Aqxd+%go zLq*fW@n85j`V@Z!mYQMOO?NI*KTr?CL?^{ToXp8yJA;Vbqlq;oR_|0`YcbL@cK!$k zcxGXi@4qAWJd~>?FxIR%Q+XwyS$l$Ia~|E#&of9n5kIgCH<;$dgz9D_eARi@-q-Yj zB8hUA=!}Ln^)B!|Ij%lrl39F!12D2f?}zI;XN)`qhQ$j(>|GGk@8jFGJoEP z_QwMhI;Plstr3riymh|@P@_Vg+kbyff;9l_qPBIf&jAi~XV#r3(E#{D7Zw+VeGc8I zX=pr#ncA5buzC%JUAnl8Dk-F-7J21$Rd3w=06>Htq$`70s7TU6aY6l(a#f9FikNLy ziSoa!KI+sEupH$dA04pv+RE(DaTt5dr!fFFb75iOl8qp3Mo!NCjoEfRRaMoAr`h@W z{q&Xzkz3pOoYbH+`S$JFq}$`ikJ)_PU+ts1d-}4z6lzEF3ur(2m2oB0?AYtNAFX>3 zlH)SN!~Ad=UArH+)Q5|;62Y={kM()jf3w27Is}d(9%j4N6yRvq}jPX-QuiKnj7zDcWTPxFElUlmNp^1 z<%e_Oo|jm8Q)%KawqP0+4kd|ce=#n|Ek~6Qy}$2)7_NM1SZ4n)wN0iteM`hRN!q*E zWyzo|L0qRkkV3E4=g4U`(N!ClP$|D)ZI#C-lYq_$A;a{i^ufa`2(02R-WaK|0Hhu( zF#Q%uaAiILiRs+mT9icHnTxxpnwVQt7$9qdLugn^K~xa4*(#_`CW|2jY{`9Q*|C^l z`P4XuSjR_Ef(53k(aNB757~V1zzr+y#&taYC3m1G?eg7kc*L+*5}n(F+Yx=GWSExj zNB4I9odskmFF>Jyc7u`UAdhr=w(zQcgL2vE%~0l+YZSoQ0s~^~=#l+0fgCgjkY9&M zpdo(UH44t_l$|H%8Pjvj>!dtqs)V5k5L^d&`fulpDY~;|eynUA2FS4D z{_z=il@I>@obyF@UL{EQWr~RcCnN}^1k<~Y=n1wnx6!xUhd+MNwg_CUAbu@wVr6mf z-mW8XX2F2%7wMg{k&z-!%dft7@!*6Zzd1uDni?pJjqb}?%Tt5czz9m$_eqa&keJ+^TavvYz0eZ2OB<{Zu{oXvsDH{8&x=_ZOe)%nAtf05Hj zDXHujfFflhZm+!kp1WlRd^yVAZ%kb%Yqi=P4)Pf-tJ zXlOG6r5#Eac~XjYg`K;mFad1hn~1G#3Q7c7ks3y*RuAGNKY>qpvFsOsgX_$mj8$i& z1kTz^p*AOI|98VaRZsOXdjgi^&g?jDd8Z7nt`}DXaIY;%{p>y6#k2!1`$GP1iB0P- z6mfCf0Im6@W^fswl3cQEhk;Rln%)Tp+_8_?pZE7H>4O+UN3$JW#L z>`!pv!4o6gw;xH+r-;CM{rHIRKu2BaBIQ%YmhyuHhXnM!QQ?0a;BA3D7spZFu$>A) z4*lc@xc?&T`c|Cb^tIn0F!Z{pym*t1#t@CON)OjUdAVc9qbHLhrV&8ut@{AjT^KlD z z&_WgcKsWk?5IomuEvd~Kg|v;)zV##8Hfc_?Y2f-BB%WU&(7DPZvwIqW%cd!Eq=a;& zr9@+Mp||Uy-gK=Lu(4kRQb?aRYmhsv>FC_uy}RxGwf?dF5$-Ah+&=JA$)hlImn~+n z59fSfnxXw#sT$M)YX+SzpJ@+j*aKoE9&QN>zia!v?igOt< zYI!snikxQ^=~UdT!X7Q`b`k{RuuBf(MM^D@fatTgt~!d{-=pRHkD0_v`Lu;$Oc9Y= zw=vry&~VNlIeRZ7v0+JSDi5zI5dS|Oe{LSCvYi{|sRX2{1?I7H;X}?)l9zVYwrd|b=t}A)KSj?+m_%mMdYqw-aeiB%8>T~bEZ4qWD@8VH3 zg$1HDl`FS&9k75h0fOt{@lI{Nj=K1jNjIQx0|EET<-2dJy3^Gvfme8|p7mH$SXh{) zm@?5oD9gv8mRHcHx)>3E+BeeUL3$fhj|;3`ngs(ziPv#dKWTGN`tdocVh#M}EX9`+brHEF_wG4$GP{2Jk}7Xd zq{txnCQ>H#+|g!6v%;O8xAmnVjs;o+SHb+%GoLGMZs_Za^`O%;)O zK)Z&$l1L@cV-YCg5KVsz9skDt^}p`wFYQ%UkWhow?+@22kM|dapZp|7U`u%?g(Y47 zcECb%7@5^kqg!Jbv;L_81L*Ot7EGp9E{MK}f!^N!e$QcijV;dugmKSIo&B#T9?reo zN9_Zao;}>Yu){n{Ln|`GBJJbrg1eV_N!K=>ci`DF_U*@P>ZpuV}@bi|G!Q_&XUMoxwXMarl~ z$z9ebBjYBXBYG|N?|{5KUVe)69RT%((b|)XraMJRNB3nw0|I4u8R+F&Uw$re0vpKn(SHO>4PC}?2Y`b@Zrk2htdN>q7+p;o@^jGBxhR}ftIhdtC3ts$`YB_)K5!8(E@0yI_wRf8@ozAx&U|AHJo!$F zt`p89g&$bt&|cg6GuwWY93cNB>kQ-C=j&)lJxpIp{~Lu7pJmE5tsQwqlbn4Wz_uxF z4Q#Z1?QrIS%fZr!$oUa#W}H@He}LIm{n24S{C!vAY-1R?SWaaJW!OQnJN4MB(l;n za}B~7N*MCX@gLP_ZCxGBDC7h}2=3{(k^wB1P zTz3Xc@65v7kNzz5;(+$|+Bh4H`9G~&0BU&OdUk)G368tle5s-%X5fq|@Zj1jq%a&# z1jDh`Hv#K)hZgQuVnN=;frF=G5Z0@S8*755gg=0(uwd}Pn;JiyQ!V!uI0%3-7tH4V zKM#U$zp$>NQWm?BYt-Cy3o^ZS+KATY5lLa{>+Ml6Dr^gYI`9&=1B&J$EBRs}i`0V) z_y7>rM>LMtem?b82IC?dC1T&|Ykr!o9M3qZRzoyE z>cxaUR6$lPKZ9ZklC!hmjv*azb*P;)1mMnTvzQ+2>;)RmEu~BUbPM$2d`Puup&LI} zX_Qh=iIm4VC4l}B&OyUi9hFmsOVH!6Yo|H+=D_H_?hF&3qFV&Q=}%#*Wm1~*KWw*+ z?L)`4UxlepiJ!LcDaRWAP{G)&Ie5K#((w;Ahb{V4WqUW8D{A^X(8Ls+;)XwJs;#s< zuG77{gSUzUXWGzE%&*%Y|Ji-J+K-WfzrNtWncphEOWX1%A2sr%qXC#3EHDI9w{c*S z9yZiJ(BYsWSB=^bh0p$%*?~z5LTQdUp^~LEoe^=Tre&5=$9pEijoC z`=0oKteW{hG=;MJ42PLEzIqGI)s576UV$4#S;|2Bua^nX=pTYwx7z*<*A1$v-Nh&b zb`a%V6()1+rXM}+j9gDY3-|l0^%T8Tt`0zX6W`|uLV^A$(47PtPl1L+Y96w^Je&~2{r2r!(_;EA?op(?>Ddo~YdQDXPXN0P_b7uX^FI#cU>eYbfl!ur z1L%_usMzhH{{sc5#v$2Jion9bHu-MgLiuD^_k2cD9_!&4kp$4+1{Ys;&}PD&If)(% znV{FIN->lnt>476ZSksec>pP`%~VsQ#PRN=^LjJaB9Jh9K=VrpomYfpUC$etGhl_iprEs!#x>#5jdaQ7a*m}@jPF62uPXMvsPfVHb-d#G z9n_B02Cy;oDhv4T*0WMJ?))7vCp=GQc2zCz>4^I*^TyPBjX2;b!{iuMbX7ID_>CTK zmpucJ;~D5Co5}Y*$_9bnvaOjb$3~ncM?v{7}@KI)Vw%|(jMwmNzuQqBuqsN34EOydB#QkZTS9|QCV`O9ppp>PF z?~${h$EFo>Jb>2Y&%&YGQb~VnX2xe5IN1n-{;{8HY+H>d$15js04&B_*GZ4jGxhF0 zTypS*&+-FmMy>i;=U0VvjU?$Az1sbcdy}juR;c5x{CF^ZalSy3W+|;UzwzihI>D(+ z1@tWLg}SfQ?6d-SXbxt=0?wpvY7zVOs`#>A_U%$T3G^a%G4N{%;*Pze=4l0ei&ikZ z*a(CgbBx&Jc?yF#K*!wRzZ*!dcAMP5)X4D%!833&sIlNtYr>1)*Pnr=KbBJN6Y0Gv zDvsuA&@kCRXAXRo2;ll_1Hb#;tu5)~(2}EBNJz-7x0Srib;U%-z`zDDb!~d6^^fw< zc>`bIj8xb#86}&~NutIt~oR!C-%@Ywf{svH9rX zjA$D`KOy`-7Ag3ilhP%%U=k&T5raZf+keb~tgh6sK}JSaITfYalWSP^vj9LA#6Y2f z@5#aF#z0Rsw#YJke|st3jVTo+23##7psf!qvMXT$a+gCHMb*KzETuP2fI`io5`=sV z@G;<7RTkqP*T1n|9s6Ni=>U6l^SzgBtyc_5OneV#eUCE~L+FyT^D6IgC3zKMBv)=r z?T)<)njQ6Aky`pwz>zBhdm6P;6rG!o%UA1QPo%`rG@oxI=h0fYZ_kSFiKq8gw&}-9 z)yJzK(JHmkrGO))fB37RO0@drUlv*ne{7 z4$&WV(DTd>G{=_OqxPN|J9R2ZEant(il5|H{oA!!VqD>%`%g9RBiPc3S0dC06=|l zw|e(RyG;I@H*Z2}7?i-2!A-l7N-Uj#Y!=kr_{B=WB(@q;TE)SHF#U-bMHzoG@yNVc zy(-rW+DmKligtd@cIKPP1k{h`tdwQf^c&e%uPFjcNo^Z$g)HwP(6j3eVkGu1}~BE`Nhf55FEC zjh+~5uaCZjn@GW_pnkYS1F_tGWH6QwG=O?Oxuh9|kv_1i0WLFxa>wMns^v=b>F{d; zk4bN>?+FKL*;3{p)@L(?^$Lpvc!}xhX%NFRglu}Qsc7r#$Ii4T=`dqe02*N2D5%Rsdf;>%M%{@o564R4|k{n?rw?loW$(r5bt<1peh z8EAaAgOfp#$CgcZic=*?CGxp;4{ z-PitjGeag8R1(O#b6hcC|G5nplM90_(w(8fx-kJd77~eoV4zVw12(KEuvUw-%bZlZ zA8qxkfziIs!?W?dckg2*$)6artw!7Ynr9>=B&{zANbj4Qr|6g1e4GbPAos(yMyh=M zVyj4T;K^<+YL~Vh@mS>D2zBsEX^EBsrn$vdTGVQQJbeu4={>o1w7(??(!LRmVP z(V3T|H*YbD*sWHoFyHKV*VNMk%?2{ZYZS{^ueh*GlkG Okcxu3e4d=y%l`%7gFUVQ literal 0 HcmV?d00001 diff --git a/tests/test_grid_map_lib.py b/tests/test_grid_map_lib.py index 92ca67e297..670b357ad3 100644 --- a/tests/test_grid_map_lib.py +++ b/tests/test_grid_map_lib.py @@ -25,5 +25,16 @@ def test_polygon_set(): 1.0, inside=False) +def test_xy_and_grid_index_conversion(): + grid_map = GridMap(100, 120, 0.5, 10.0, -0.5) + + for x_ind in range(grid_map.width): + for y_ind in range(grid_map.height): + grid_ind = grid_map.calc_grid_index_from_xy_index(x_ind, y_ind) + x_ind_2, y_ind_2 = grid_map.calc_xy_index_from_grid_index(grid_ind) + assert x_ind == x_ind_2 + assert y_ind == y_ind_2 + + if __name__ == '__main__': conftest.run_this_test(__file__) diff --git a/utils/plot.py b/utils/plot.py index d4bbe29ffd..eb5aa7ad04 100644 --- a/utils/plot.py +++ b/utils/plot.py @@ -9,6 +9,69 @@ from mpl_toolkits.mplot3d.proj3d import proj_transform from mpl_toolkits.mplot3d import Axes3D +from utils.angle import rot_mat_2d + + +def plot_covariance_ellipse(x, y, cov, chi2=3.0, color="-r", ax=None): + """ + This function plots an ellipse that represents a covariance matrix. The ellipse is centered at (x, y) and its shape, size and rotation are determined by the covariance matrix. + + Parameters: + x : (float) The x-coordinate of the center of the ellipse. + y : (float) The y-coordinate of the center of the ellipse. + cov : (numpy.ndarray) A 2x2 covariance matrix that determines the shape, size, and rotation of the ellipse. + chi2 : (float, optional) A scalar value that scales the ellipse size. This value is typically set based on chi-squared distribution quantiles to achieve certain confidence levels (e.g., 3.0 corresponds to ~95% confidence for a 2D Gaussian). Defaults to 3.0. + color : (str, optional) The color and line style of the ellipse plot, following matplotlib conventions. Defaults to "-r" (a red solid line). + ax : (matplotlib.axes.Axes, optional) The Axes object to draw the ellipse on. If None (default), a new figure and axes are created. + + Returns: + None. This function plots the covariance ellipse on the specified axes. + """ + eig_val, eig_vec = np.linalg.eig(cov) + + if eig_val[0] >= eig_val[1]: + big_ind = 0 + small_ind = 1 + else: + big_ind = 1 + small_ind = 0 + a = math.sqrt(chi2 * eig_val[big_ind]) + b = math.sqrt(chi2 * eig_val[small_ind]) + angle = math.atan2(eig_vec[1, big_ind], eig_vec[0, big_ind]) + plot_ellipse(x, y, a, b, angle, color=color, ax=ax) + + +def plot_ellipse(x, y, a, b, angle, color="-r", ax=None, **kwargs): + """ + This function plots an ellipse based on the given parameters. + + Parameters + ---------- + x : (float) The x-coordinate of the center of the ellipse. + y : (float) The y-coordinate of the center of the ellipse. + a : (float) The length of the semi-major axis of the ellipse. + b : (float) The length of the semi-minor axis of the ellipse. + angle : (float) The rotation angle of the ellipse, in radians. + color : (str, optional) The color and line style of the ellipse plot, following matplotlib conventions. Defaults to "-r" (a red solid line). + ax : (matplotlib.axes.Axes, optional) The Axes object to draw the ellipse on. If None (default), a new figure and axes are created. + **kwargs: Additional keyword arguments to pass to plt.plot or ax.plot. + + Returns + --------- + None. This function plots the ellipse based on the specified parameters. + """ + + t = np.arange(0, 2 * math.pi + 0.1, 0.1) + px = [a * math.cos(it) for it in t] + py = [b * math.sin(it) for it in t] + fx = rot_mat_2d(angle) @ (np.array([px, py])) + px = np.array(fx[0, :] + x).flatten() + py = np.array(fx[1, :] + y).flatten() + if ax is None: + plt.plot(px, py, color, **kwargs) + else: + ax.plot(px, py, color, **kwargs) + def plot_arrow(x, y, yaw, arrow_length=1.0, origin_point_plot_style="xr", @@ -132,7 +195,6 @@ def plot_3d_vector_arrow(ax, p1, p2): ) - def plot_triangle(p1, p2, p3, ax): ax.add_collection3d(art3d.Poly3DCollection([[p1, p2, p3]], color='b')) @@ -163,3 +225,10 @@ def set_equal_3d_axis(ax, x_lims, y_lims, z_lims): ax.set_xlim(mid_x - max_range, mid_x + max_range) ax.set_ylim(mid_y - max_range, mid_y + max_range) ax.set_zlim(mid_z - max_range, mid_z + max_range) + + +if __name__ == '__main__': + plot_ellipse(0, 0, 1, 2, np.deg2rad(15)) + plt.axis('equal') + plt.show() + From 41fec85cb974d650d2ec7965346a1f64f3015518 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 11 Jul 2023 08:02:59 +0900 Subject: [PATCH 630/940] Bump numpy from 1.25.0 to 1.25.1 in /requirements (#874) Bumps [numpy](https://github.com/numpy/numpy) from 1.25.0 to 1.25.1. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.25.0...v1.25.1) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 2fab6f69c8..c5643beee8 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.25.0 +numpy == 1.25.1 scipy == 1.11.1 matplotlib == 3.7.1 cvxpy == 1.3.2 From 4527785222d3bb885c4dfd97df54dfdd66e10595 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 11 Jul 2023 20:10:50 +0900 Subject: [PATCH 631/940] Bump matplotlib from 3.7.1 to 3.7.2 in /requirements (#876) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.7.1 to 3.7.2. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.7.1...v3.7.2) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index c5643beee8..27bc6b32d3 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.25.1 scipy == 1.11.1 -matplotlib == 3.7.1 +matplotlib == 3.7.2 cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test From 32e5e6fd2c891b1f56061f56e73b5d3f1386f1ba Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 11 Jul 2023 20:54:22 +0900 Subject: [PATCH 632/940] Bump ruff from 0.0.276 to 0.0.277 in /requirements (#875) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.276 to 0.0.277. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.276...v0.0.277) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 27bc6b32d3..44742ed34b 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.4.1 # For unit test -ruff == 0.0.276 # For unit test +ruff == 0.0.277 # For unit test From 8c9eb0187e83d0abff9e3d3d5d3af4add6e2c59e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Jul 2023 09:29:15 +0900 Subject: [PATCH 633/940] Bump ruff from 0.0.277 to 0.0.278 in /requirements (#879) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.277 to 0.0.278. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.277...v0.0.278) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 44742ed34b..2f6a441d3c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.4.1 # For unit test -ruff == 0.0.277 # For unit test +ruff == 0.0.278 # For unit test From ba5a1dda753671e5e54ac264c113a6b8f1142640 Mon Sep 17 00:00:00 2001 From: Emmanuel Ferdman Date: Wed, 19 Jul 2023 16:04:35 +0300 Subject: [PATCH 634/940] docs: update the code style test script (#880) Signed-off-by: Emmanuel Ferdman --- docs/how_to_contribute_main.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/how_to_contribute_main.rst b/docs/how_to_contribute_main.rst index 8a2f73e9cd..48895d6fda 100644 --- a/docs/how_to_contribute_main.rst +++ b/docs/how_to_contribute_main.rst @@ -50,7 +50,7 @@ At the least, try to run the example code without animation in the unit test. If you want to run the test suites locally, you can use the `runtests.sh` script by just executing it. -The `test_diff_codestyle.py`_ check code style for your PR's codes. +The `test_codestyle.py`_ check code style for your PR's codes. .. _`how to write doc`: @@ -155,7 +155,7 @@ Sponsors .. _`reStructuredText`: https://www.sphinx-doc.org/en/master/usage/restructuredtext/basics.html .. _`doc modules dir`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/docs/modules .. _`doc README`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/docs/README.md -.. _`test_diff_codestyle.py`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/tests/test_diff_codestyle.py +.. _`test_codestyle.py`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/tests/test_codestyle.py .. _`JetBrains`: https://www.jetbrains.com/ .. _`Sponsor @AtsushiSakai on GitHub Sponsors`: https://github.com/sponsors/AtsushiSakai .. _`Become a backer or sponsor on Patreon`: https://www.patreon.com/myenigma From d6d761bd8a6289f43f6f763dd876018541439765 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 25 Jul 2023 11:59:47 +0900 Subject: [PATCH 635/940] Bump ruff from 0.0.278 to 0.0.280 in /requirements (#881) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.278 to 0.0.280. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.278...v0.0.280) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 2f6a441d3c..a1999d4854 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.4.1 # For unit test -ruff == 0.0.278 # For unit test +ruff == 0.0.280 # For unit test From 9be188feca26a78fed1e638c8ca32ac8dca7d8b6 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 1 Aug 2023 19:16:32 +0900 Subject: [PATCH 636/940] Bump numpy from 1.25.1 to 1.25.2 in /requirements (#882) Bumps [numpy](https://github.com/numpy/numpy) from 1.25.1 to 1.25.2. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.25.1...v1.25.2) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a1999d4854..26e0eb8db3 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.25.1 +numpy == 1.25.2 scipy == 1.11.1 matplotlib == 3.7.2 cvxpy == 1.3.2 From bd0254997d82a3e40bb230db1f137c5a96c8e68e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 1 Aug 2023 19:21:48 +0900 Subject: [PATCH 637/940] Bump ruff from 0.0.280 to 0.0.281 in /requirements (#883) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.280 to 0.0.281. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.280...v0.0.281) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 26e0eb8db3..33bb44ee8f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.4.1 # For unit test -ruff == 0.0.280 # For unit test +ruff == 0.0.281 # For unit test From e7d0a219c6a4c3277a61b3e441f260d036a41479 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 8 Aug 2023 22:09:14 +0900 Subject: [PATCH 638/940] Bump sphinx-notes/pages from 2 to 3 (#884) Bumps [sphinx-notes/pages](https://github.com/sphinx-notes/pages) from 2 to 3. - [Release notes](https://github.com/sphinx-notes/pages/releases) - [Commits](https://github.com/sphinx-notes/pages/compare/v2...v3) --- updated-dependencies: - dependency-name: sphinx-notes/pages dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/gh-pages.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index d5af3b87c6..9cb661ae52 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -19,7 +19,7 @@ jobs: python -m pip install --upgrade pip python -m pip install -r requirements/requirements.txt - name: Build and Commit - uses: sphinx-notes/pages@v2 + uses: sphinx-notes/pages@v3 with: requirements_path: ./docs/doc_requirements.txt - name: Push changes From 5104e2c692ad8c8ffab6eb04bfa96cd9e75dc1d3 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 8 Aug 2023 22:09:42 +0900 Subject: [PATCH 639/940] Bump ruff from 0.0.281 to 0.0.282 in /requirements (#885) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.281 to 0.0.282. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.281...v0.0.282) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 33bb44ee8f..281a4c7662 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.4.1 # For unit test -ruff == 0.0.281 # For unit test +ruff == 0.0.282 # For unit test From 801d43dd25c5bf3f553960eecfbaff7741550031 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Aug 2023 11:43:28 +0900 Subject: [PATCH 640/940] Bump ruff from 0.0.282 to 0.0.284 in /requirements (#887) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.282 to 0.0.284. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.282...v0.0.284) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 281a4c7662..d24bb676c6 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.4.1 # For unit test -ruff == 0.0.282 # For unit test +ruff == 0.0.284 # For unit test From de141eaf14cd3e71ef224eaa81ab4f76336a37b2 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 15 Aug 2023 12:40:52 +0900 Subject: [PATCH 641/940] Update gh-pages.yml (#889) --- .github/workflows/gh-pages.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index 9cb661ae52..072c60c32e 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -6,6 +6,8 @@ on: jobs: build: runs-on: ubuntu-latest + permissions: + id-token: write steps: - name: Setup python uses: actions/setup-python@v4 From bfc91b1bc33372c697081221aefca65e7c7342b5 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 15 Aug 2023 13:04:17 +0900 Subject: [PATCH 642/940] Update gh-pages.yml --- .github/workflows/gh-pages.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index 072c60c32e..f2630df162 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -8,6 +8,7 @@ jobs: runs-on: ubuntu-latest permissions: id-token: write + pages: write steps: - name: Setup python uses: actions/setup-python@v4 From 35f4f61e44ad9c3f8fc6584e3d0d7ab7889bd866 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Aug 2023 13:16:21 +0900 Subject: [PATCH 643/940] Bump mypy from 1.4.1 to 1.5.0 in /requirements (#888) Bumps [mypy](https://github.com/python/mypy) from 1.4.1 to 1.5.0. - [Commits](https://github.com/python/mypy/compare/v1.4.1...v1.5.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index d24bb676c6..7ae3c54134 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.7.2 cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test -mypy == 1.4.1 # For unit test +mypy == 1.5.0 # For unit test ruff == 0.0.284 # For unit test From ff9e48852d7da400768099f54dce90f3cbab104a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 22 Aug 2023 07:38:09 +0900 Subject: [PATCH 644/940] Bump ruff from 0.0.284 to 0.0.285 in /requirements (#893) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.284 to 0.0.285. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.284...v0.0.285) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 7ae3c54134..fed24446c5 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.0 # For unit test -ruff == 0.0.284 # For unit test +ruff == 0.0.285 # For unit test From 637269e0af6128acf5469c057fe6b0564e4d4768 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 22 Aug 2023 20:42:01 +0900 Subject: [PATCH 645/940] Bump scipy from 1.11.1 to 1.11.2 in /requirements (#894) Bumps [scipy](https://github.com/scipy/scipy) from 1.11.1 to 1.11.2. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.11.1...v1.11.2) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index fed24446c5..24f5dd8341 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.25.2 -scipy == 1.11.1 +scipy == 1.11.2 matplotlib == 3.7.2 cvxpy == 1.3.2 pytest == 7.4.0 # For unit test From 3fce78a41e56b3bdb183e581bede2b19ea96a5df Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 22 Aug 2023 20:43:32 +0900 Subject: [PATCH 646/940] Bump mypy from 1.5.0 to 1.5.1 in /requirements (#895) Bumps [mypy](https://github.com/python/mypy) from 1.5.0 to 1.5.1. - [Commits](https://github.com/python/mypy/compare/v1.5.0...v1.5.1) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 24f5dd8341..a0eb41aa73 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.7.2 cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test -mypy == 1.5.0 # For unit test +mypy == 1.5.1 # For unit test ruff == 0.0.285 # For unit test From 19c0fb379c070329c0e60e347a8b41179833140d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sat, 9 Sep 2023 07:01:58 +0900 Subject: [PATCH 647/940] Bump actions/checkout from 3 to 4 (#900) Bumps [actions/checkout](https://github.com/actions/checkout) from 3 to 4. - [Release notes](https://github.com/actions/checkout/releases) - [Changelog](https://github.com/actions/checkout/blob/main/CHANGELOG.md) - [Commits](https://github.com/actions/checkout/compare/v3...v4) --- updated-dependencies: - dependency-name: actions/checkout dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/Linux_CI.yml | 2 +- .github/workflows/MacOS_CI.yml | 2 +- .github/workflows/Windows_CI.yml | 2 +- .github/workflows/codeql.yml | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index a152972753..b9a102c714 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -17,7 +17,7 @@ jobs: name: Python ${{ matrix.python-version }} CI steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - run: git fetch --prune --unshallow - name: Setup python diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index c8bfbbcb7e..2acabd8b44 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -19,7 +19,7 @@ jobs: python-version: [ '3.11' ] name: Python ${{ matrix.python-version }} CI steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - run: git fetch --prune --unshallow - name: Update bash diff --git a/.github/workflows/Windows_CI.yml b/.github/workflows/Windows_CI.yml index 13fdcea8a1..3df2e6265b 100644 --- a/.github/workflows/Windows_CI.yml +++ b/.github/workflows/Windows_CI.yml @@ -19,7 +19,7 @@ jobs: python-version: [ '3.11' ] name: Python ${{ matrix.python-version }} CI steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - run: git fetch --prune --unshallow - name: Setup python diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml index d33545c90f..d3e888f09e 100644 --- a/.github/workflows/codeql.yml +++ b/.github/workflows/codeql.yml @@ -16,7 +16,7 @@ jobs: steps: - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 with: # We must fetch at least the immediate parents so that if this is # a pull request then we can checkout the head. From 4b3544e74ddfd20107de280295e799e0b0385433 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 11 Sep 2023 15:55:49 +0900 Subject: [PATCH 648/940] Bump pytest from 7.4.0 to 7.4.1 in /requirements (#901) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.4.0 to 7.4.1. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.4.0...7.4.1) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a0eb41aa73..b0d3e4d4f0 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.25.2 scipy == 1.11.2 matplotlib == 3.7.2 cvxpy == 1.3.2 -pytest == 7.4.0 # For unit test +pytest == 7.4.1 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.1 # For unit test ruff == 0.0.285 # For unit test From c9145d348c68be78acb2652ec83587ce90d4a51f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 11 Sep 2023 20:38:43 +0900 Subject: [PATCH 649/940] Bump ruff from 0.0.285 to 0.0.287 in /requirements (#902) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.285 to 0.0.287. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.285...v0.0.287) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b0d3e4d4f0..e4792a31bf 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.1 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.1 # For unit test -ruff == 0.0.285 # For unit test +ruff == 0.0.287 # For unit test From 8a427a92abc7fe241dd67f69d17c80c54cd272c2 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 12 Sep 2023 07:35:26 +0900 Subject: [PATCH 650/940] Bump ruff from 0.0.287 to 0.0.288 in /requirements (#905) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.287 to 0.0.288. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.287...v0.0.288) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e4792a31bf..9eeb1f024f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.1 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.1 # For unit test -ruff == 0.0.287 # For unit test +ruff == 0.0.288 # For unit test From 8956c67c21055b9a2c44c1e0d3d20b194e4dfd95 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 13 Sep 2023 17:33:46 +0900 Subject: [PATCH 651/940] Bump pytest from 7.4.1 to 7.4.2 in /requirements (#904) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.4.1 to 7.4.2. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.4.1...7.4.2) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 9eeb1f024f..0c616fc6d3 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.25.2 scipy == 1.11.2 matplotlib == 3.7.2 cvxpy == 1.3.2 -pytest == 7.4.1 # For unit test +pytest == 7.4.2 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.1 # For unit test ruff == 0.0.288 # For unit test From 644d70d0fa3d83ae4434725ff0f82b4f7d4ec46f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 19 Sep 2023 06:51:53 +0900 Subject: [PATCH 652/940] Bump ruff from 0.0.288 to 0.0.290 in /requirements (#908) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.288 to 0.0.290. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.288...v0.0.290) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 0c616fc6d3..6392fd2c33 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.2 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.1 # For unit test -ruff == 0.0.288 # For unit test +ruff == 0.0.290 # For unit test From ba09b4dd90fc49d8873771782c7dc82f0a213534 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 19 Sep 2023 06:59:38 +0900 Subject: [PATCH 653/940] Bump matplotlib from 3.7.2 to 3.8.0 in /requirements (#909) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.7.2 to 3.8.0. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.7.2...v3.8.0) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 6392fd2c33..d1c0592e14 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.25.2 scipy == 1.11.2 -matplotlib == 3.7.2 +matplotlib == 3.8.0 cvxpy == 1.3.2 pytest == 7.4.2 # For unit test pytest-xdist == 3.3.1 # For unit test From a7513699bf7f6f3d6112e48464deddf7e8c22f68 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 19 Sep 2023 12:36:29 +0900 Subject: [PATCH 654/940] Bump numpy from 1.25.2 to 1.26.0 in /requirements (#910) Bumps [numpy](https://github.com/numpy/numpy) from 1.25.2 to 1.26.0. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.25.2...v1.26.0) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index d1c0592e14..836f8b0f54 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.25.2 +numpy == 1.26.0 scipy == 1.11.2 matplotlib == 3.8.0 cvxpy == 1.3.2 From 57ee946537a13af397bafbe8cf54507988006873 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 27 Sep 2023 20:23:08 +0900 Subject: [PATCH 655/940] Bump ruff from 0.0.290 to 0.0.291 in /requirements (#911) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.290 to 0.0.291. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.290...v0.0.291) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 836f8b0f54..d983e22916 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.2 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.1 # For unit test -ruff == 0.0.290 # For unit test +ruff == 0.0.291 # For unit test From 6a765964409bb3f449d94bd55eb0dd8998730c71 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 3 Oct 2023 21:36:37 +0900 Subject: [PATCH 656/940] Bump scipy from 1.11.2 to 1.11.3 in /requirements (#914) Bumps [scipy](https://github.com/scipy/scipy) from 1.11.2 to 1.11.3. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.11.2...v1.11.3) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index d983e22916..b67f904ea5 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.26.0 -scipy == 1.11.2 +scipy == 1.11.3 matplotlib == 3.8.0 cvxpy == 1.3.2 pytest == 7.4.2 # For unit test From 2c4d74507777993d44cbb33e238689d776221243 Mon Sep 17 00:00:00 2001 From: Yuki Onishi Date: Sun, 15 Oct 2023 10:25:22 +0900 Subject: [PATCH 657/940] Revert a parameter in grid_based_sweep_coverage_path_planner to correct (#917) the planning results --- .../grid_based_sweep_coverage_path_planner.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py index ee192e9200..10ba98cd35 100644 --- a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py +++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py @@ -50,7 +50,7 @@ def move_target_grid(self, c_x_index, c_y_index, grid_map): # moving backward next_c_x_index = -self.moving_direction + c_x_index next_c_y_index = c_y_index - if self.check_occupied(next_c_x_index, next_c_y_index, grid_map): + if self.check_occupied(next_c_x_index, next_c_y_index, grid_map, FloatGrid(1.0)): # moved backward, but the grid is occupied by obstacle return None, None else: @@ -61,8 +61,8 @@ def move_target_grid(self, c_x_index, c_y_index, grid_map): return next_c_x_index, next_c_y_index @staticmethod - def check_occupied(c_x_index, c_y_index, grid_map): - return grid_map.check_occupied_from_xy_index(c_x_index, c_y_index, FloatGrid(0.5)) + def check_occupied(c_x_index, c_y_index, grid_map, occupied_val=FloatGrid(0.5)): + return grid_map.check_occupied_from_xy_index(c_x_index, c_y_index, occupied_val) def find_safe_turning_grid(self, c_x_index, c_y_index, grid_map): From 5eed0ec1a6a8751e448a476c950f7342d864510d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sun, 15 Oct 2023 15:34:15 +0900 Subject: [PATCH 658/940] Bump ruff from 0.0.291 to 0.0.292 in /requirements (#913) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.291 to 0.0.292. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.291...v0.0.292) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b67f904ea5..cd38b9cff7 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.2 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.1 # For unit test -ruff == 0.0.291 # For unit test +ruff == 0.0.292 # For unit test From 4adb77dcf71d3dced8e152f861106de1d192adf6 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 18 Oct 2023 21:25:55 +0900 Subject: [PATCH 659/940] Bump ruff from 0.0.292 to 0.1.0 in /requirements (#920) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.292 to 0.1.0. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.292...v0.1.0) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index cd38b9cff7..acc76577c8 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.2 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.1 # For unit test -ruff == 0.0.292 # For unit test +ruff == 0.1.0 # For unit test From 38a8be94bab0baa900a82fafa774b196bd4f1396 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 18 Oct 2023 21:26:26 +0900 Subject: [PATCH 660/940] Bump numpy from 1.26.0 to 1.26.1 in /requirements (#922) Bumps [numpy](https://github.com/numpy/numpy) from 1.26.0 to 1.26.1. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.26.0...v1.26.1) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index acc76577c8..a5875a67ec 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.26.0 +numpy == 1.26.1 scipy == 1.11.3 matplotlib == 3.8.0 cvxpy == 1.3.2 From 8f1306ac01055743a456b08cf2e0032f1942f96c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 18 Oct 2023 22:01:34 +0900 Subject: [PATCH 661/940] Bump cvxpy from 1.3.2 to 1.4.1 in /requirements (#923) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.3.2 to 1.4.1. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.3.2...v1.4.1) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a5875a67ec..46ad6feb23 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.26.1 scipy == 1.11.3 matplotlib == 3.8.0 -cvxpy == 1.3.2 +cvxpy == 1.4.1 pytest == 7.4.2 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.1 # For unit test From d0ff8cc165ce97c473e090e78003a8e5703a7b6d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 25 Oct 2023 20:15:46 +0900 Subject: [PATCH 662/940] Bump ruff from 0.1.0 to 0.1.1 in /requirements (#926) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.0 to 0.1.1. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.0...v0.1.1) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 46ad6feb23..0bda50edc0 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.2 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.5.1 # For unit test -ruff == 0.1.0 # For unit test +ruff == 0.1.1 # For unit test From bde8bda7536449522f3f2bfaa200a450dff41c92 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 25 Oct 2023 23:01:04 +0900 Subject: [PATCH 663/940] Bump mypy from 1.5.1 to 1.6.1 in /requirements (#924) Bumps [mypy](https://github.com/python/mypy) from 1.5.1 to 1.6.1. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.5.1...v1.6.1) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 0bda50edc0..1a89183ba6 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.8.0 cvxpy == 1.4.1 pytest == 7.4.2 # For unit test pytest-xdist == 3.3.1 # For unit test -mypy == 1.5.1 # For unit test +mypy == 1.6.1 # For unit test ruff == 0.1.1 # For unit test From 3a8d93b2a54928d258362b34b31fd8adf04a7d05 Mon Sep 17 00:00:00 2001 From: Jeff Irion Date: Wed, 25 Oct 2023 07:02:14 -0700 Subject: [PATCH 664/940] Fix SE(2) inverse (#925) * Fix SE(2) inverse * Add missing ] --- SLAM/GraphBasedSLAM/graphslam/pose/se2.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/SLAM/GraphBasedSLAM/graphslam/pose/se2.py b/SLAM/GraphBasedSLAM/graphslam/pose/se2.py index e89317a06f..2a32e765f7 100644 --- a/SLAM/GraphBasedSLAM/graphslam/pose/se2.py +++ b/SLAM/GraphBasedSLAM/graphslam/pose/se2.py @@ -136,8 +136,8 @@ def inverse(self): """ return PoseSE2([-self[0] * np.cos(self[2]) - self[1] * np.sin(self[2]), - self[0] * np.sin(self[2]) - self[1] * np.cos( - [self[2]])], -self[2]) + self[0] * np.sin(self[2]) - self[1] * np.cos(self[2])], + -self[2]) # ======================================================================= # # # From f374393b551b781f9c9564bd8b0e273342c8e3a0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 31 Oct 2023 20:55:50 +0900 Subject: [PATCH 665/940] Bump ruff from 0.1.1 to 0.1.3 in /requirements (#928) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.1 to 0.1.3. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.1...v0.1.3) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 1a89183ba6..26a481cbe8 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.2 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.6.1 # For unit test -ruff == 0.1.1 # For unit test +ruff == 0.1.3 # For unit test From fc3ec3cd66f64fc889c3382c4ae41aca26adaf4e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 1 Nov 2023 08:38:39 +0900 Subject: [PATCH 666/940] Bump pytest from 7.4.2 to 7.4.3 in /requirements (#929) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.4.2 to 7.4.3. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.4.2...7.4.3) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 26a481cbe8..4335e42aca 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.26.1 scipy == 1.11.3 matplotlib == 3.8.0 cvxpy == 1.4.1 -pytest == 7.4.2 # For unit test +pytest == 7.4.3 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.6.1 # For unit test ruff == 0.1.3 # For unit test From 8be35b6e70aeb466efcfc76f480a9d734f92f34d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 Nov 2023 07:03:23 +0900 Subject: [PATCH 667/940] Bump matplotlib from 3.8.0 to 3.8.1 in /requirements (#931) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.8.0 to 3.8.1. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.8.0...v3.8.1) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 4335e42aca..3515fbdf9f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.26.1 scipy == 1.11.3 -matplotlib == 3.8.0 +matplotlib == 3.8.1 cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.3.1 # For unit test From dcf8eded0647e1f6d8695cbf98fae690e29fa6df Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 Nov 2023 08:15:50 +0900 Subject: [PATCH 668/940] Bump ruff from 0.1.3 to 0.1.4 in /requirements (#932) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.3 to 0.1.4. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.3...v0.1.4) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 3515fbdf9f..e65db6c92a 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.6.1 # For unit test -ruff == 0.1.3 # For unit test +ruff == 0.1.4 # For unit test From 9eac2c6f2acc63925085242d9bf895b0084fad3b Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 14 Nov 2023 21:40:32 +0900 Subject: [PATCH 669/940] Bump pytest-xdist from 3.3.1 to 3.4.0 in /requirements (#933) Bumps [pytest-xdist](https://github.com/pytest-dev/pytest-xdist) from 3.3.1 to 3.4.0. - [Changelog](https://github.com/pytest-dev/pytest-xdist/blob/master/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest-xdist/compare/v3.3.1...v3.4.0) --- updated-dependencies: - dependency-name: pytest-xdist dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e65db6c92a..6f7253b4a7 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,6 +3,6 @@ scipy == 1.11.3 matplotlib == 3.8.1 cvxpy == 1.4.1 pytest == 7.4.3 # For unit test -pytest-xdist == 3.3.1 # For unit test +pytest-xdist == 3.4.0 # For unit test mypy == 1.6.1 # For unit test ruff == 0.1.4 # For unit test From 3fa8f3e56cf5c742ec19548167bde266ee5e7aa8 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 15 Nov 2023 13:18:18 +0900 Subject: [PATCH 670/940] Bump numpy from 1.26.1 to 1.26.2 in /requirements (#934) Bumps [numpy](https://github.com/numpy/numpy) from 1.26.1 to 1.26.2. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.26.1...v1.26.2) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 6f7253b4a7..f8439d2eb7 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.26.1 +numpy == 1.26.2 scipy == 1.11.3 matplotlib == 3.8.1 cvxpy == 1.4.1 From 58df4be95f7ad4fa67b70cac657fcc2c07e85756 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 15 Nov 2023 14:57:46 +0900 Subject: [PATCH 671/940] Bump mypy from 1.6.1 to 1.7.0 in /requirements (#936) Bumps [mypy](https://github.com/python/mypy) from 1.6.1 to 1.7.0. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.6.1...v1.7.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f8439d2eb7..f6e237366f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.8.1 cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.4.0 # For unit test -mypy == 1.6.1 # For unit test +mypy == 1.7.0 # For unit test ruff == 0.1.4 # For unit test From f7dadb8157cd8ecebb2ef3eeb2e8dc1ae5bfb664 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 15 Nov 2023 17:08:33 +0900 Subject: [PATCH 672/940] Bump ruff from 0.1.4 to 0.1.5 in /requirements (#935) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.4 to 0.1.5. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.4...v0.1.5) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f6e237366f..a17a6bc7cb 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.4.0 # For unit test mypy == 1.7.0 # For unit test -ruff == 0.1.4 # For unit test +ruff == 0.1.5 # For unit test From f5f0253e14e97856f4f6d4016cf4864fce8d46bb Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Nov 2023 12:57:31 +0900 Subject: [PATCH 673/940] Bump scipy from 1.11.3 to 1.11.4 in /requirements (#938) Bumps [scipy](https://github.com/scipy/scipy) from 1.11.3 to 1.11.4. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.11.3...v1.11.4) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a17a6bc7cb..3fcdd9ad19 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.26.2 -scipy == 1.11.3 +scipy == 1.11.4 matplotlib == 3.8.1 cvxpy == 1.4.1 pytest == 7.4.3 # For unit test From df932b0eb25349fd43f28c1f28a92616b9e709b8 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Nov 2023 18:59:57 +0900 Subject: [PATCH 674/940] Bump matplotlib from 3.8.1 to 3.8.2 in /requirements (#940) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.8.1 to 3.8.2. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.8.1...v3.8.2) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 3fcdd9ad19..788e900d13 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.26.2 scipy == 1.11.4 -matplotlib == 3.8.1 +matplotlib == 3.8.2 cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.4.0 # For unit test From 9093d709b5ff74c085f50ab3a1d57928ee6a5b13 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Nov 2023 19:52:11 +0900 Subject: [PATCH 675/940] Bump ruff from 0.1.5 to 0.1.6 in /requirements (#939) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.5 to 0.1.6. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.5...v0.1.6) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 788e900d13..b3b8509b68 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.4.0 # For unit test mypy == 1.7.0 # For unit test -ruff == 0.1.5 # For unit test +ruff == 0.1.6 # For unit test From 0dc6ab42bab4d3e2fb06fc25d86b1abe41d4da2a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 28 Nov 2023 19:59:15 +0900 Subject: [PATCH 676/940] Bump pytest-xdist from 3.4.0 to 3.5.0 in /requirements (#942) Bumps [pytest-xdist](https://github.com/pytest-dev/pytest-xdist) from 3.4.0 to 3.5.0. - [Release notes](https://github.com/pytest-dev/pytest-xdist/releases) - [Changelog](https://github.com/pytest-dev/pytest-xdist/blob/master/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest-xdist/compare/v3.4.0...v3.5.0) --- updated-dependencies: - dependency-name: pytest-xdist dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b3b8509b68..afc244c1a1 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,6 +3,6 @@ scipy == 1.11.4 matplotlib == 3.8.2 cvxpy == 1.4.1 pytest == 7.4.3 # For unit test -pytest-xdist == 3.4.0 # For unit test +pytest-xdist == 3.5.0 # For unit test mypy == 1.7.0 # For unit test ruff == 0.1.6 # For unit test From e9ae79f9204df88e768de39443781a208d66ecd5 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sun, 3 Dec 2023 21:01:12 +0900 Subject: [PATCH 677/940] Bump mypy from 1.7.0 to 1.7.1 in /requirements (#943) Bumps [mypy](https://github.com/python/mypy) from 1.7.0 to 1.7.1. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.7.0...v1.7.1) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index afc244c1a1..f073524c51 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.8.2 cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.5.0 # For unit test -mypy == 1.7.0 # For unit test +mypy == 1.7.1 # For unit test ruff == 0.1.6 # For unit test From 5676da661f09d08fb0ef188f31f71f17be0ab44a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 3 Dec 2023 21:23:50 +0900 Subject: [PATCH 678/940] Update gh-pages.yml --- .github/workflows/gh-pages.yml | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index f2630df162..42ec54f4e1 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -25,8 +25,7 @@ jobs: uses: sphinx-notes/pages@v3 with: requirements_path: ./docs/doc_requirements.txt - - name: Push changes - uses: ad-m/github-push-action@master - with: - github_token: ${{ secrets.GITHUB_TOKEN }} - branch: gh-pages + - name: Deploy GitHub Pages site + id: deployment + uses: actions/deploy-pages@main + From 7585316933cee2febfc0a2cd68a13336020adbbc Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 3 Dec 2023 21:35:30 +0900 Subject: [PATCH 679/940] Update gh-pages.yml --- .github/workflows/gh-pages.yml | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index 42ec54f4e1..17fa1d76ca 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -6,6 +6,9 @@ on: jobs: build: runs-on: ubuntu-latest + environment: + name: github-pages + url: ${{ steps.deployment.outputs.page_url }} permissions: id-token: write pages: write @@ -25,7 +28,9 @@ jobs: uses: sphinx-notes/pages@v3 with: requirements_path: ./docs/doc_requirements.txt - - name: Deploy GitHub Pages site - id: deployment - uses: actions/deploy-pages@main + - name: Push changes + uses: ad-m/github-push-action@master + with: + github_token: ${{ secrets.GITHUB_TOKEN }} + branch: gh-pages From 6dca76ac4b566958080dac7f87f44b15e44a84aa Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 3 Dec 2023 21:41:48 +0900 Subject: [PATCH 680/940] Update gh-pages.yml --- .github/workflows/gh-pages.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index 17fa1d76ca..c50a9f1865 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -1,4 +1,4 @@ -name: Pages +name: GitHub Pages update on: push: branches: From 467f27d178f05474b619f841a93b027707b421ac Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 3 Dec 2023 21:46:56 +0900 Subject: [PATCH 681/940] Update gh-pages.yml --- .github/workflows/gh-pages.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index c50a9f1865..ccc0f5a835 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -1,4 +1,4 @@ -name: GitHub Pages update +name: GitHub Pages site update on: push: branches: From ef287d7a857c52a3f34e7b86765c3467858ad2b6 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 3 Dec 2023 21:53:12 +0900 Subject: [PATCH 682/940] Update gh-pages.yml --- .github/workflows/gh-pages.yml | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index ccc0f5a835..d2c7847807 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -24,13 +24,7 @@ jobs: python --version python -m pip install --upgrade pip python -m pip install -r requirements/requirements.txt - - name: Build and Commit + - name: Build and Deploy uses: sphinx-notes/pages@v3 with: - requirements_path: ./docs/doc_requirements.txt - - name: Push changes - uses: ad-m/github-push-action@master - with: - github_token: ${{ secrets.GITHUB_TOKEN }} - branch: gh-pages - + requirements_path: ./docs/doc_requirements.txt From 331f0877f6ade42901c0762fee41abcce83c7e29 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 3 Dec 2023 21:56:04 +0900 Subject: [PATCH 683/940] Update copyright for doc update test --- docs/conf.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/conf.py b/docs/conf.py index df9b8fce22..46f69cf17b 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -19,7 +19,7 @@ # -- Project information ----------------------------------------------------- project = 'PythonRobotics' -copyright = '2018-2021, Atsushi Sakai' +copyright = '2018-2023, Atsushi Sakai' author = 'Atsushi Sakai' # The short X.Y version From a141cf41807c508e58691c3c42919387e5ff9ded Mon Sep 17 00:00:00 2001 From: Fabiha Tasneem <55595104+fabihatasneem@users.noreply.github.com> Date: Sun, 3 Dec 2023 19:12:00 +0600 Subject: [PATCH 684/940] Fixed Inappropriate Logical Expression (#945) --- .../arm_obstacle_navigation/arm_obstacle_navigation_2.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py index 40e6746bfc..591cd401eb 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py @@ -34,7 +34,7 @@ def main(): goal = (58, 56) grid = get_occupancy_grid(arm, obstacles) route = astar_torus(grid, start, goal) - if len(route) >= 0: + if route: animate(grid, arm, route) From ff66f3babe27d1ae3775f594ffd05264ca173d6a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 12 Dec 2023 22:34:49 +0900 Subject: [PATCH 685/940] Bump actions/setup-python from 4 to 5 (#951) Bumps [actions/setup-python](https://github.com/actions/setup-python) from 4 to 5. - [Release notes](https://github.com/actions/setup-python/releases) - [Commits](https://github.com/actions/setup-python/compare/v4...v5) --- updated-dependencies: - dependency-name: actions/setup-python dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/Linux_CI.yml | 2 +- .github/workflows/MacOS_CI.yml | 2 +- .github/workflows/Windows_CI.yml | 2 +- .github/workflows/gh-pages.yml | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index b9a102c714..b83954f17e 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -21,7 +21,7 @@ jobs: - run: git fetch --prune --unshallow - name: Setup python - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python-version }} - name: Install dependencies diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index 2acabd8b44..19c6612b2f 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -26,7 +26,7 @@ jobs: run: brew install bash - name: Setup python - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python-version }} diff --git a/.github/workflows/Windows_CI.yml b/.github/workflows/Windows_CI.yml index 3df2e6265b..906edcfcdb 100644 --- a/.github/workflows/Windows_CI.yml +++ b/.github/workflows/Windows_CI.yml @@ -23,7 +23,7 @@ jobs: - run: git fetch --prune --unshallow - name: Setup python - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 with: python-version: ${{ matrix.python-version }} diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index d2c7847807..e08c6106c0 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -14,7 +14,7 @@ jobs: pages: write steps: - name: Setup python - uses: actions/setup-python@v4 + uses: actions/setup-python@v5 - name: Checkout uses: actions/checkout@master with: From d25fb355f3c7a1d1e2ee895d009d0d639a37c18b Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 12 Dec 2023 22:35:02 +0900 Subject: [PATCH 686/940] Bump ruff from 0.1.6 to 0.1.7 in /requirements (#952) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.6 to 0.1.7. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.6...v0.1.7) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f073524c51..2c2a6d47ff 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.7.1 # For unit test -ruff == 0.1.6 # For unit test +ruff == 0.1.7 # For unit test From 313ce196215f2625c1f6b20e49722b51631bdb37 Mon Sep 17 00:00:00 2001 From: Xavier Dias <93143666+Xavi007@users.noreply.github.com> Date: Mon, 18 Dec 2023 05:42:47 +0530 Subject: [PATCH 687/940] Xavi007: #903 There's an error in the transformation_matrix of Quadrotor renamed "yaw" to "roll" (#906) --- AerialNavigation/drone_3d_trajectory_following/Quadrotor.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py b/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py index 413a8625a5..c379e5eda0 100644 --- a/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py +++ b/AerialNavigation/drone_3d_trajectory_following/Quadrotor.py @@ -56,7 +56,7 @@ def transformation_matrix(self): [[cos(yaw) * cos(pitch), -sin(yaw) * cos(roll) + cos(yaw) * sin(pitch) * sin(roll), sin(yaw) * sin(roll) + cos(yaw) * sin(pitch) * cos(roll), x], [sin(yaw) * cos(pitch), cos(yaw) * cos(roll) + sin(yaw) * sin(pitch) * sin(roll), -cos(yaw) * sin(roll) + sin(yaw) * sin(pitch) * cos(roll), y], - [-sin(pitch), cos(pitch) * sin(roll), cos(pitch) * cos(yaw), z] + [-sin(pitch), cos(pitch) * sin(roll), cos(pitch) * cos(roll), z] ]) def plot(self): # pragma: no cover From 3efbc94f9cb5532b7a046d4fe79d3fe62dc18bd4 Mon Sep 17 00:00:00 2001 From: flyingmars <55879494+2892510130@users.noreply.github.com> Date: Mon, 18 Dec 2023 21:53:03 +0800 Subject: [PATCH 688/940] fix d_star (#898) --- PathPlanning/DStar/dstar.py | 19 +++++++++++++++---- 1 file changed, 15 insertions(+), 4 deletions(-) diff --git a/PathPlanning/DStar/dstar.py b/PathPlanning/DStar/dstar.py index f8954d776c..cc1d88ed66 100644 --- a/PathPlanning/DStar/dstar.py +++ b/PathPlanning/DStar/dstar.py @@ -9,6 +9,7 @@ """ import math + from sys import maxsize import matplotlib.pyplot as plt @@ -103,7 +104,7 @@ def process_state(self): if y.h <= k_old and x.h > y.h + x.cost(y): x.parent = y x.h = y.h + x.cost(y) - elif k_old == x.h: + if k_old == x.h: for y in self.map.get_neighbors(x): if y.t == "new" or y.parent == x and y.h != x.h + x.cost(y) \ or y.parent != x and y.h > x.h + x.cost(y): @@ -116,7 +117,7 @@ def process_state(self): self.insert(y, x.h + x.cost(y)) else: if y.parent != x and y.h > x.h + x.cost(y): - self.insert(y, x.h) + self.insert(x, x.h) else: if y.parent != x and x.h > y.h + x.cost(y) \ and y.t == "close" and y.h > k_old: @@ -173,6 +174,8 @@ def run(self, start, end): s.set_state("e") tmp = start + AddNewObstacle(self.map) # add new obstacle after the first search finished + while tmp != end: tmp.set_state("*") rx.append(tmp.x) @@ -195,6 +198,15 @@ def modify(self, state): if k_min >= state.h: break +def AddNewObstacle(map:Map): + ox, oy = [], [] + for i in range(5, 21): + ox.append(i) + oy.append(40) + map.set_obstacle([(i, j) for i, j in zip(ox, oy)]) + if show_animation: + plt.pause(0.001) + plt.plot(ox, oy, ".g") def main(): m = Map(100, 100) @@ -217,7 +229,6 @@ def main(): for i in range(0, 40): ox.append(40) oy.append(60 - i) - print([(i, j) for i, j in zip(ox, oy)]) m.set_obstacle([(i, j) for i, j in zip(ox, oy)]) start = [10, 10] @@ -234,7 +245,7 @@ def main(): rx, ry = dstar.run(start, end) if show_animation: - plt.plot(rx, ry, "-r") + # plt.plot(rx, ry, "-r") plt.show() From 1801cd0dfff86de899285d02f4a1593d2df970e9 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 19 Dec 2023 07:04:43 +0900 Subject: [PATCH 689/940] Bump github/codeql-action from 2 to 3 (#955) Bumps [github/codeql-action](https://github.com/github/codeql-action) from 2 to 3. - [Release notes](https://github.com/github/codeql-action/releases) - [Changelog](https://github.com/github/codeql-action/blob/main/CHANGELOG.md) - [Commits](https://github.com/github/codeql-action/compare/v2...v3) --- updated-dependencies: - dependency-name: github/codeql-action dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/codeql.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml index d3e888f09e..878a4a4435 100644 --- a/.github/workflows/codeql.yml +++ b/.github/workflows/codeql.yml @@ -24,7 +24,7 @@ jobs: # Initializes the CodeQL tools for scanning. - name: Initialize CodeQL - uses: github/codeql-action/init@v2 + uses: github/codeql-action/init@v3 with: config-file: ./.github/codeql/codeql-config.yml # Override language selection by uncommenting this and choosing your languages @@ -34,7 +34,7 @@ jobs: # Autobuild attempts to build any compiled languages (C/C++, C#, or Java). # If this step fails, then you should remove it and run the build manually (see below) - name: Autobuild - uses: github/codeql-action/autobuild@v2 + uses: github/codeql-action/autobuild@v3 # ℹ️ Command-line programs to run using the OS shell. # 📚 https://git.io/JvXDl @@ -48,4 +48,4 @@ jobs: # make release - name: Perform CodeQL Analysis - uses: github/codeql-action/analyze@v2 + uses: github/codeql-action/analyze@v3 From 7cca7aa6ac4c6d66cbb46011cc642b2543e5756e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 19 Dec 2023 07:05:11 +0900 Subject: [PATCH 690/940] Bump ruff from 0.1.7 to 0.1.8 in /requirements (#956) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.7 to 0.1.8. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.7...v0.1.8) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 2c2a6d47ff..68d8b2dcff 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.7.1 # For unit test -ruff == 0.1.7 # For unit test +ruff == 0.1.8 # For unit test From b2f866a5cd7bbf3f70c9c247e13f19d4a8858c92 Mon Sep 17 00:00:00 2001 From: Nivid Patel <66813410+nivid26@users.noreply.github.com> Date: Tue, 19 Dec 2023 08:03:55 -0500 Subject: [PATCH 691/940] Update car.py (#957) Changed comment at line 62 and 64 --- PathPlanning/HybridAStar/car.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/HybridAStar/car.py b/PathPlanning/HybridAStar/car.py index 0367ab2775..d7631133c7 100644 --- a/PathPlanning/HybridAStar/car.py +++ b/PathPlanning/HybridAStar/car.py @@ -59,9 +59,9 @@ def rectangle_check(x, y, yaw, ox, oy): rx, ry = converted_xy[0], converted_xy[1] if not (rx > LF or rx < -LB or ry > W / 2.0 or ry < -W / 2.0): - return False # no collision + return False # collision - return True # collision + return True # no collision def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): From e3f7979c3c08de87d702e1d2006ffb55440514a5 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 22 Dec 2023 12:13:59 +0900 Subject: [PATCH 692/940] Update dstar.py (#959) --- PathPlanning/DStar/dstar.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/DStar/dstar.py b/PathPlanning/DStar/dstar.py index cc1d88ed66..b62b939f54 100644 --- a/PathPlanning/DStar/dstar.py +++ b/PathPlanning/DStar/dstar.py @@ -245,7 +245,7 @@ def main(): rx, ry = dstar.run(start, end) if show_animation: - # plt.plot(rx, ry, "-r") + plt.plot(rx, ry, "-r") plt.show() From 87b3aacb8b41e1924319eaae85ef88c39e3062b1 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 26 Dec 2023 23:36:29 +0900 Subject: [PATCH 693/940] Bump mypy from 1.7.1 to 1.8.0 in /requirements (#960) Bumps [mypy](https://github.com/python/mypy) from 1.7.1 to 1.8.0. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.7.1...v1.8.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 68d8b2dcff..ae1aa2d749 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.8.2 cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.5.0 # For unit test -mypy == 1.7.1 # For unit test +mypy == 1.8.0 # For unit test ruff == 0.1.8 # For unit test From 748b9be4e76fa2f0d55b507a30bb578b74d6c921 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 27 Dec 2023 08:33:04 +0900 Subject: [PATCH 694/940] Bump ruff from 0.1.8 to 0.1.9 in /requirements (#961) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.8 to 0.1.9. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.8...v0.1.9) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index ae1aa2d749..bb78ed4d2f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.3 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test -ruff == 0.1.8 # For unit test +ruff == 0.1.9 # For unit test From cc3fd0c55e8df8637ffa1753c6a3d973db9ed2a1 Mon Sep 17 00:00:00 2001 From: Videh Patel <66770479+videh25@users.noreply.github.com> Date: Tue, 2 Jan 2024 19:09:48 +0530 Subject: [PATCH 695/940] Using util.angle_mod in all codes. #684 (#946) * switched to using utils.angle_mod() * switched to using utils.angle_mod() * renamed mod2pi to pi_2_pi * Removed linting errors * switched to using utils.angle_mod() * switched to using utils.angle_mod() * renamed mod2pi to pi_2_pi * Removed linting errors * annotation changes and round precision * Reverted to mod2pi --------- Co-authored-by: Videh Patel --- .../n_joint_arm_to_point_control.py | 5 ++-- .../two_joint_arm_to_point_control.py | 3 ++- Control/move_to_pose/move_to_pose.py | 19 +++++++-------- .../ensemble_kalman_filter.py | 3 ++- .../ClosedLoopRRTStar/unicycle_model.py | 3 ++- .../motion_model.py | 3 ++- .../trajectory_generator.py | 2 +- .../reeds_shepp_path_planning.py | 9 ++++---- .../lqr_speed_steer_control.py | 4 ++-- .../lqr_steer_control/lqr_steer_control.py | 3 ++- ...odel_predictive_speed_and_steer_control.py | 9 ++------ .../rear_wheel_feedback.py | 23 ++++++++----------- .../stanley_controller/stanley_controller.py | 13 ++++------- SLAM/EKFSLAM/ekf_slam.py | 3 ++- SLAM/FastSLAM1/fast_slam1.py | 3 ++- SLAM/FastSLAM2/fast_slam2.py | 3 ++- SLAM/GraphBasedSLAM/graph_based_slam.py | 3 ++- 17 files changed, 51 insertions(+), 60 deletions(-) diff --git a/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py b/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py index 498ef41c1f..a237523336 100644 --- a/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py +++ b/ArmNavigation/n_joint_arm_to_point_control/n_joint_arm_to_point_control.py @@ -11,6 +11,7 @@ import numpy as np from ArmNavigation.n_joint_arm_to_point_control.NLinkArm import NLinkArm +from utils.angle import angle_mod # Simulation parameters Kp = 2 @@ -159,9 +160,9 @@ def ang_diff(theta1, theta2): """ Returns the difference between two angles in the range -pi to +pi """ - return (theta1 - theta2 + np.pi) % (2 * np.pi) - np.pi + return angle_mod(theta1 - theta2) if __name__ == '__main__': # main() - animation() \ No newline at end of file + animation() diff --git a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py index 66d0ebeb23..c2227f18e3 100644 --- a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py +++ b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py @@ -15,6 +15,7 @@ import matplotlib.pyplot as plt import numpy as np import math +from utils.angle import angle_mod # Simulation parameters @@ -110,7 +111,7 @@ def plot_arm(theta1, theta2, target_x, target_y): # pragma: no cover def ang_diff(theta1, theta2): # Returns the difference between two angles in the range -pi to +pi - return (theta1 - theta2 + np.pi) % (2 * np.pi) - np.pi + return angle_mod(theta1 - theta2) def click(event): # pragma: no cover diff --git a/Control/move_to_pose/move_to_pose.py b/Control/move_to_pose/move_to_pose.py index 73604ccd7f..cc29666297 100644 --- a/Control/move_to_pose/move_to_pose.py +++ b/Control/move_to_pose/move_to_pose.py @@ -13,7 +13,7 @@ import matplotlib.pyplot as plt import numpy as np from random import random - +from utils.angle import angle_mod class PathFinderController: """ @@ -71,9 +71,8 @@ def calc_control_command(self, x_diff, y_diff, theta, theta_goal): # from 0 rad to 2*pi rad with slight turn rho = np.hypot(x_diff, y_diff) - alpha = (np.arctan2(y_diff, x_diff) - - theta + np.pi) % (2 * np.pi) - np.pi - beta = (theta_goal - theta - alpha + np.pi) % (2 * np.pi) - np.pi + alpha = angle_mod(np.arctan2(y_diff, x_diff) - theta) + beta = angle_mod(theta_goal - theta - alpha) v = self.Kp_rho * rho w = self.Kp_alpha * alpha - controller.Kp_beta * beta @@ -173,16 +172,14 @@ def transformation_matrix(x, y, theta): def main(): for i in range(5): - x_start = 20 * random() - y_start = 20 * random() - theta_start = 2 * np.pi * random() - np.pi + x_start = 20.0 * random() + y_start = 20.0 * random() + theta_start: float = 2 * np.pi * random() - np.pi x_goal = 20 * random() y_goal = 20 * random() theta_goal = 2 * np.pi * random() - np.pi - print("Initial x: %.2f m\nInitial y: %.2f m\nInitial theta: %.2f rad\n" % - (x_start, y_start, theta_start)) - print("Goal x: %.2f m\nGoal y: %.2f m\nGoal theta: %.2f rad\n" % - (x_goal, y_goal, theta_goal)) + print(f"Initial x: {round(x_start, 2)} m\nInitial y: {round(y_start, 2)} m\nInitial theta: {round(theta_start, 2)} rad\n") + print(f"Goal x: {round(x_goal, 2)} m\nGoal y: {round(y_goal, 2)} m\nGoal theta: {round(theta_goal, 2)} rad\n") move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal) diff --git a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py index fc8280e7bf..2bab3b49c1 100644 --- a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py +++ b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py @@ -16,6 +16,7 @@ import math import matplotlib.pyplot as plt import numpy as np +from utils.angle import angle_mod from utils.angle import rot_mat_2d @@ -179,7 +180,7 @@ def plot_covariance_ellipse(xEst, PEst): # pragma: no cover def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + return angle_mod(angle) def main(): diff --git a/PathPlanning/ClosedLoopRRTStar/unicycle_model.py b/PathPlanning/ClosedLoopRRTStar/unicycle_model.py index 5a0fd17a4e..c05f76c84e 100644 --- a/PathPlanning/ClosedLoopRRTStar/unicycle_model.py +++ b/PathPlanning/ClosedLoopRRTStar/unicycle_model.py @@ -8,6 +8,7 @@ import math import numpy as np +from utils.angle import angle_mod dt = 0.05 # [s] L = 0.9 # [m] @@ -39,7 +40,7 @@ def update(state, a, delta): def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + return angle_mod(angle) if __name__ == '__main__': # pragma: no cover diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py index 531bf91ef5..5ef6d2e23f 100644 --- a/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py +++ b/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py @@ -1,6 +1,7 @@ import math import numpy as np from scipy.interpolate import interp1d +from utils.angle import angle_mod # motion parameter L = 1.0 # wheel base @@ -18,7 +19,7 @@ def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0): def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + return angle_mod(angle) def update(state, v, delta, dt, L): diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py index 97c0ad8b80..6084fc1a07 100644 --- a/PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py +++ b/PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py @@ -18,7 +18,7 @@ # optimization parameter max_iter = 100 -h = np.array([0.5, 0.02, 0.02]).T # parameter sampling distance +h: np.ndarray = np.array([0.5, 0.02, 0.02]).T # parameter sampling distance cost_th = 0.1 show_animation = True diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py index c55d2629e5..4d8fb7d9b8 100644 --- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py +++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py @@ -9,6 +9,7 @@ import matplotlib.pyplot as plt import numpy as np +from utils.angle import angle_mod show_animation = True @@ -40,6 +41,9 @@ def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): plt.plot(x, y) +def pi_2_pi(x): + return angle_mod(x) + def mod2pi(x): # Be consistent with fmod in cplusplus here. v = np.mod(x, np.copysign(2.0 * math.pi, x)) @@ -50,7 +54,6 @@ def mod2pi(x): v -= 2.0 * math.pi return v - def straight_left_straight(x, y, phi): phi = mod2pi(phi) # only take phi in (0.01*math.pi, 0.99*math.pi) for the sake of speed. @@ -296,10 +299,6 @@ def interpolate(dist, length, mode, max_curvature, origin_x, origin_y, return x, y, yaw, 1 if length > 0.0 else -1 -def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi - - def calc_paths(sx, sy, syaw, gx, gy, gyaw, maxc, step_size): q0 = [sx, sy, syaw] q1 = [gx, gy, gyaw] diff --git a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py index 7e57abb80e..a70e30d378 100644 --- a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py +++ b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py @@ -11,6 +11,7 @@ import numpy as np import scipy.linalg as la import pathlib +from utils.angle import angle_mod sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) from PathPlanning.CubicSpline import cubic_spline_planner @@ -52,8 +53,7 @@ def update(state, a, delta): def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi - + return angle_mod(angle) def solve_dare(A, B, Q, R): """ diff --git a/PathTracking/lqr_steer_control/lqr_steer_control.py b/PathTracking/lqr_steer_control/lqr_steer_control.py index 95a1b92ce5..4078ea56db 100644 --- a/PathTracking/lqr_steer_control/lqr_steer_control.py +++ b/PathTracking/lqr_steer_control/lqr_steer_control.py @@ -11,6 +11,7 @@ import numpy as np import sys import pathlib +from utils.angle import angle_mod sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) from PathPlanning.CubicSpline import cubic_spline_planner @@ -61,7 +62,7 @@ def PIDControl(target, current): def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + return angle_mod(angle) def solve_DARE(A, B, Q, R): diff --git a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py index 3015313198..c55018cf26 100644 --- a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py +++ b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py @@ -11,6 +11,7 @@ import numpy as np import sys import pathlib +from utils.angle import angle_mod sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) from PathPlanning.CubicSpline import cubic_spline_planner @@ -69,13 +70,7 @@ def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0): def pi_2_pi(angle): - while(angle > math.pi): - angle = angle - 2.0 * math.pi - - while(angle < -math.pi): - angle = angle + 2.0 * math.pi - - return angle + return angle_mod(angle) def get_linear_model_matrix(v, phi, delta): diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index ff72454f34..1702bd47dd 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -8,6 +8,7 @@ import matplotlib.pyplot as plt import math import numpy as np +from utils.angle import angle_mod from scipy import interpolate from scipy import optimize @@ -51,21 +52,21 @@ def __init__(self, x, y): self.ddY = self.Y.derivative(2) self.length = s[-1] - + def calc_yaw(self, s): dx, dy = self.dX(s), self.dY(s) return np.arctan2(dy, dx) - + def calc_curvature(self, s): dx, dy = self.dX(s), self.dY(s) ddx, ddy = self.ddX(s), self.ddY(s) return (ddy * dx - ddx * dy) / ((dx ** 2 + dy ** 2)**(3 / 2)) - + def __find_nearest_point(self, s0, x, y): def calc_distance(_s, *args): _x, _y= self.X(_s), self.Y(_s) return (_x - args[0])**2 + (_y - args[1])**2 - + def calc_distance_jacobian(_s, *args): _x, _y = self.X(_s), self.Y(_s) _dx, _dy = self.dX(_s), self.dY(_s) @@ -76,7 +77,7 @@ def calc_distance_jacobian(_s, *args): def calc_track_error(self, x, y, s0): ret = self.__find_nearest_point(s0, x, y) - + s = ret[0][0] e = ret[1] @@ -96,13 +97,7 @@ def pid_control(target, current): return a def pi_2_pi(angle): - while(angle > math.pi): - angle = angle - 2.0 * math.pi - - while(angle < -math.pi): - angle = angle + 2.0 * math.pi - - return angle + return angle_mod(angle) def rear_wheel_feedback_control(state, e, k, yaw_ref): v = state.v @@ -170,7 +165,7 @@ def simulate(path_ref, goal): plt.plot(path_ref.X(s0), path_ref.Y(s0), "xg", label="target") plt.axis("equal") plt.grid(True) - plt.title("speed[km/h]:{:.2f}, target s-param:{:.2f}".format(round(state.v * 3.6, 2), s0)) + plt.title(f"speed[km/h]:{round(state.v * 3.6, 2):.2f}, target s-param:{s0:.2f}") plt.pause(0.0001) return t, x, y, yaw, v, goal_flag @@ -184,7 +179,7 @@ def calc_target_speed(state, yaw_ref): if switch: state.direction *= -1 return 0.0 - + if state.direction != 1: return -target_speed diff --git a/PathTracking/stanley_controller/stanley_controller.py b/PathTracking/stanley_controller/stanley_controller.py index 9c475cbaf2..08aa049395 100644 --- a/PathTracking/stanley_controller/stanley_controller.py +++ b/PathTracking/stanley_controller/stanley_controller.py @@ -13,6 +13,7 @@ import matplotlib.pyplot as plt import sys import pathlib +from utils.angle import angle_mod sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) from PathPlanning.CubicSpline import cubic_spline_planner @@ -26,7 +27,7 @@ show_animation = True -class State(object): +class State: """ Class representing the state of a vehicle. @@ -38,7 +39,7 @@ class State(object): def __init__(self, x=0.0, y=0.0, yaw=0.0, v=0.0): """Instantiate the object.""" - super(State, self).__init__() + super().__init__() self.x = x self.y = y self.yaw = yaw @@ -106,13 +107,7 @@ def normalize_angle(angle): :param angle: (float) :return: (float) Angle in radian in [-pi, pi] """ - while angle > np.pi: - angle -= 2.0 * np.pi - - while angle < -np.pi: - angle += 2.0 * np.pi - - return angle + return angle_mod(angle) def calc_target_index(state, cx, cy): diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index bb648ce9d9..a624e8765b 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -8,6 +8,7 @@ import matplotlib.pyplot as plt import numpy as np +from utils.angle import angle_mod # EKF state covariance Cx = np.diag([0.5, 0.5, np.deg2rad(30.0)]) ** 2 @@ -192,7 +193,7 @@ def jacob_h(q, delta, x, i): def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + return angle_mod(angle) def main(): diff --git a/SLAM/FastSLAM1/fast_slam1.py b/SLAM/FastSLAM1/fast_slam1.py index 7b89f52df4..17f6d5e572 100644 --- a/SLAM/FastSLAM1/fast_slam1.py +++ b/SLAM/FastSLAM1/fast_slam1.py @@ -10,6 +10,7 @@ import matplotlib.pyplot as plt import numpy as np +from utils.angle import angle_mod # Fast SLAM covariance Q = np.diag([3.0, np.deg2rad(10.0)]) ** 2 @@ -321,7 +322,7 @@ def motion_model(x, u): def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + return angle_mod(angle) def main(): diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py index aa77aa956a..2b57e3bcc3 100644 --- a/SLAM/FastSLAM2/fast_slam2.py +++ b/SLAM/FastSLAM2/fast_slam2.py @@ -10,6 +10,7 @@ import matplotlib.pyplot as plt import numpy as np +from utils.angle import angle_mod # Fast SLAM covariance Q = np.diag([3.0, np.deg2rad(10.0)]) ** 2 @@ -346,7 +347,7 @@ def motion_model(x, u): def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + return angle_mod(angle) def main(): diff --git a/SLAM/GraphBasedSLAM/graph_based_slam.py b/SLAM/GraphBasedSLAM/graph_based_slam.py index 4d66ef6732..edd20a959c 100644 --- a/SLAM/GraphBasedSLAM/graph_based_slam.py +++ b/SLAM/GraphBasedSLAM/graph_based_slam.py @@ -21,6 +21,7 @@ import matplotlib.pyplot as plt import numpy as np from scipy.spatial.transform import Rotation as Rot +from utils.angle import angle_mod # Simulation parameter Q_sim = np.diag([0.2, np.deg2rad(1.0)]) ** 2 @@ -249,7 +250,7 @@ def motion_model(x, u): def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi + return angle_mod(angle) def main(): From 49ae54ab70f1c30ca848fef215bdbc172a8e692a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 2 Jan 2024 22:40:08 +0900 Subject: [PATCH 696/940] Bump pytest from 7.4.3 to 7.4.4 in /requirements (#963) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.4.3 to 7.4.4. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.4.3...7.4.4) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index bb78ed4d2f..8b3c4c1739 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.26.2 scipy == 1.11.4 matplotlib == 3.8.2 cvxpy == 1.4.1 -pytest == 7.4.3 # For unit test +pytest == 7.4.4 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test ruff == 0.1.9 # For unit test From d7060f60289cc0241f3411fea85764fb20f9cac0 Mon Sep 17 00:00:00 2001 From: Videh Patel <66770479+videh25@users.noreply.github.com> Date: Mon, 8 Jan 2024 18:06:49 +0530 Subject: [PATCH 697/940] Reopen: Added missing path types (#949) * added missing RS path types * modified assert condition in test3 * removed linting errors * added sign check to avoid non RS paths * Mathematical description of RS curves * Undid debugging changes * Added large step_size consideration * renamed test3 to test_too_big_step_size --------- Co-authored-by: Videh Patel --- .../reeds_shepp_path_planning.py | 320 +++++++++------ .../path_planning/reeds_shepp_path/LR_L.png | Bin 0 -> 280028 bytes .../path_planning/reeds_shepp_path/LR_LR.png | Bin 0 -> 381584 bytes .../path_planning/reeds_shepp_path/LSL.png | Bin 0 -> 239825 bytes .../reeds_shepp_path/LSL90xR.png | Bin 0 -> 301712 bytes .../path_planning/reeds_shepp_path/LSR.png | Bin 0 -> 257435 bytes .../reeds_shepp_path/LSR90_L.png | Bin 0 -> 339492 bytes .../reeds_shepp_path/L_R90SL.png | Bin 0 -> 316723 bytes .../reeds_shepp_path/L_R90SL90_R.png | Bin 0 -> 335979 bytes .../reeds_shepp_path/L_R90SR.png | Bin 0 -> 291754 bytes .../path_planning/reeds_shepp_path/L_RL.png | Bin 0 -> 277432 bytes .../path_planning/reeds_shepp_path/L_RL_R.png | Bin 0 -> 323010 bytes .../path_planning/reeds_shepp_path/L_R_L.png | Bin 0 -> 271666 bytes .../reeds_shepp_path_main.rst | 375 ++++++++++++++++++ tests/test_rrt_star_reeds_shepp.py | 6 +- 15 files changed, 586 insertions(+), 115 deletions(-) create mode 100644 docs/modules/path_planning/reeds_shepp_path/LR_L.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/LR_LR.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/LSL.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/LSL90xR.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/LSR.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/LSR90_L.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/L_R90SL.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/L_R90SL90_R.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/L_R90SR.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/L_RL.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/L_RL_R.png create mode 100644 docs/modules/path_planning/reeds_shepp_path/L_R_L.png diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py index 4d8fb7d9b8..8e134ff38b 100644 --- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py +++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py @@ -3,6 +3,7 @@ Reeds Shepp path planner sample code author Atsushi Sakai(@Atsushi_twi) +co-author Videh Patel(@videh25) : Added the missing RS paths """ import math @@ -54,21 +55,6 @@ def mod2pi(x): v -= 2.0 * math.pi return v -def straight_left_straight(x, y, phi): - phi = mod2pi(phi) - # only take phi in (0.01*math.pi, 0.99*math.pi) for the sake of speed. - # phi in (0, 0.01*math.pi) will make test2() in test_rrt_star_reeds_shepp.py - # extremely time-consuming, since the value of xd, t will be very large. - if math.pi * 0.01 < phi < math.pi * 0.99 and y != 0: - xd = - y / math.tan(phi) + x - t = xd - math.tan(phi / 2.0) - u = phi - v = np.sign(y) * math.hypot(x - xd, y) - math.tan(phi / 2.0) - return True, t, u, v - - return False, 0.0, 0.0, 0.0 - - def set_path(paths, lengths, ctypes, step_size): path = Path() path.ctypes = ctypes @@ -90,18 +76,6 @@ def set_path(paths, lengths, ctypes, step_size): return paths -def straight_curve_straight(x, y, phi, paths, step_size): - flag, t, u, v = straight_left_straight(x, y, phi) - if flag: - paths = set_path(paths, [t, u, v], ["S", "L", "S"], step_size) - - flag, t, u, v = straight_left_straight(x, -y, -phi) - if flag: - paths = set_path(paths, [t, u, v], ["S", "R", "S"], step_size) - - return paths - - def polar(x, y): r = math.hypot(x, y) theta = math.atan2(y, x) @@ -110,117 +84,200 @@ def polar(x, y): def left_straight_left(x, y, phi): u, t = polar(x - math.sin(phi), y - 1.0 + math.cos(phi)) - if t >= 0.0: + if 0.0 <= t <= math.pi: v = mod2pi(phi - t) - if v >= 0.0: - return True, t, u, v + if 0.0 <= v <= math.pi: + return True, [t, u, v], ['L', 'S', 'L'] + + return False, [], [] + + +def left_straight_right(x, y, phi): + u1, t1 = polar(x + math.sin(phi), y - 1.0 - math.cos(phi)) + u1 = u1 ** 2 + if u1 >= 4.0: + u = math.sqrt(u1 - 4.0) + theta = math.atan2(2.0, u) + t = mod2pi(t1 + theta) + v = mod2pi(t - phi) + + if (t >= 0.0) and (v >= 0.0): + return True, [t, u, v], ['L', 'S', 'R'] - return False, 0.0, 0.0, 0.0 + return False, [], [] -def left_right_left(x, y, phi): - u1, t1 = polar(x - math.sin(phi), y - 1.0 + math.cos(phi)) +def left_x_right_x_left(x, y, phi): + zeta = x - math.sin(phi) + eeta = y - 1 + math.cos(phi) + u1, theta = polar(zeta, eeta) if u1 <= 4.0: - u = -2.0 * math.asin(0.25 * u1) - t = mod2pi(t1 + 0.5 * u + math.pi) - v = mod2pi(phi - t + u) + A = math.acos(0.25 * u1) + t = mod2pi(A + theta + math.pi/2) + u = mod2pi(math.pi - 2 * A) + v = mod2pi(phi - t - u) + return True, [t, -u, v], ['L', 'R', 'L'] - if t >= 0.0 >= u: - return True, t, u, v + return False, [], [] - return False, 0.0, 0.0, 0.0 +def left_x_right_left(x, y, phi): + zeta = x - math.sin(phi) + eeta = y - 1 + math.cos(phi) + u1, theta = polar(zeta, eeta) -def curve_curve_curve(x, y, phi, paths, step_size): - flag, t, u, v = left_right_left(x, y, phi) - if flag: - paths = set_path(paths, [t, u, v], ["L", "R", "L"], step_size) + if u1 <= 4.0: + A = math.acos(0.25 * u1) + t = mod2pi(A + theta + math.pi/2) + u = mod2pi(math.pi - 2*A) + v = mod2pi(-phi + t + u) + return True, [t, -u, -v], ['L', 'R', 'L'] - flag, t, u, v = left_right_left(-x, y, -phi) - if flag: - paths = set_path(paths, [-t, -u, -v], ["L", "R", "L"], step_size) + return False, [], [] - flag, t, u, v = left_right_left(x, -y, -phi) - if flag: - paths = set_path(paths, [t, u, v], ["R", "L", "R"], step_size) - flag, t, u, v = left_right_left(-x, -y, phi) - if flag: - paths = set_path(paths, [-t, -u, -v], ["R", "L", "R"], step_size) +def left_right_x_left(x, y, phi): + zeta = x - math.sin(phi) + eeta = y - 1 + math.cos(phi) + u1, theta = polar(zeta, eeta) - # backwards - xb = x * math.cos(phi) + y * math.sin(phi) - yb = x * math.sin(phi) - y * math.cos(phi) + if u1 <= 4.0: + u = math.acos(1 - u1**2 * 0.125) + A = math.asin(2 * math.sin(u) / u1) + t = mod2pi(-A + theta + math.pi/2) + v = mod2pi(t - u - phi) + return True, [t, u, -v], ['L', 'R', 'L'] + + return False, [], [] + + +def left_right_x_left_right(x, y, phi): + zeta = x + math.sin(phi) + eeta = y - 1 - math.cos(phi) + u1, theta = polar(zeta, eeta) + + # Solutions refering to (2 < u1 <= 4) are considered sub-optimal in paper + # Solutions do not exist for u1 > 4 + if u1 <= 2: + A = math.acos((u1 + 2) * 0.25) + t = mod2pi(theta + A + math.pi/2) + u = mod2pi(A) + v = mod2pi(phi - t + 2*u) + if ((t >= 0) and (u >= 0) and (v >= 0)): + return True, [t, u, -u, -v], ['L', 'R', 'L', 'R'] + + return False, [], [] + + +def left_x_right_left_x_right(x, y, phi): + zeta = x + math.sin(phi) + eeta = y - 1 - math.cos(phi) + u1, theta = polar(zeta, eeta) + u2 = (20 - u1**2) / 16 + + if (0 <= u2 <= 1): + u = math.acos(u2) + A = math.asin(2 * math.sin(u) / u1) + t = mod2pi(theta + A + math.pi/2) + v = mod2pi(t - phi) + if (t >= 0) and (v >= 0): + return True, [t, -u, -u, v], ['L', 'R', 'L', 'R'] - flag, t, u, v = left_right_left(xb, yb, phi) - if flag: - paths = set_path(paths, [v, u, t], ["L", "R", "L"], step_size) + return False, [], [] - flag, t, u, v = left_right_left(-xb, yb, -phi) - if flag: - paths = set_path(paths, [-v, -u, -t], ["L", "R", "L"], step_size) - flag, t, u, v = left_right_left(xb, -yb, -phi) - if flag: - paths = set_path(paths, [v, u, t], ["R", "L", "R"], step_size) +def left_x_right90_straight_left(x, y, phi): + zeta = x - math.sin(phi) + eeta = y - 1 + math.cos(phi) + u1, theta = polar(zeta, eeta) - flag, t, u, v = left_right_left(-xb, -yb, phi) - if flag: - paths = set_path(paths, [-v, -u, -t], ["R", "L", "R"], step_size) + if u1 >= 2.0: + u = math.sqrt(u1**2 - 4) - 2 + A = math.atan2(2, math.sqrt(u1**2 - 4)) + t = mod2pi(theta + A + math.pi/2) + v = mod2pi(t - phi + math.pi/2) + if (t >= 0) and (v >= 0): + return True, [t, -math.pi/2, -u, -v], ['L', 'R', 'S', 'L'] - return paths + return False, [], [] -def curve_straight_curve(x, y, phi, paths, step_size): - flag, t, u, v = left_straight_left(x, y, phi) - if flag: - paths = set_path(paths, [t, u, v], ["L", "S", "L"], step_size) +def left_straight_right90_x_left(x, y, phi): + zeta = x - math.sin(phi) + eeta = y - 1 + math.cos(phi) + u1, theta = polar(zeta, eeta) - flag, t, u, v = left_straight_left(-x, y, -phi) - if flag: - paths = set_path(paths, [-t, -u, -v], ["L", "S", "L"], step_size) + if u1 >= 2.0: + u = math.sqrt(u1**2 - 4) - 2 + A = math.atan2(math.sqrt(u1**2 - 4), 2) + t = mod2pi(theta - A + math.pi/2) + v = mod2pi(t - phi - math.pi/2) + if (t >= 0) and (v >= 0): + return True, [t, u, math.pi/2, -v], ['L', 'S', 'R', 'L'] - flag, t, u, v = left_straight_left(x, -y, -phi) - if flag: - paths = set_path(paths, [t, u, v], ["R", "S", "R"], step_size) + return False, [], [] - flag, t, u, v = left_straight_left(-x, -y, phi) - if flag: - paths = set_path(paths, [-t, -u, -v], ["R", "S", "R"], step_size) - flag, t, u, v = left_straight_right(x, y, phi) - if flag: - paths = set_path(paths, [t, u, v], ["L", "S", "R"], step_size) +def left_x_right90_straight_right(x, y, phi): + zeta = x + math.sin(phi) + eeta = y - 1 - math.cos(phi) + u1, theta = polar(zeta, eeta) - flag, t, u, v = left_straight_right(-x, y, -phi) - if flag: - paths = set_path(paths, [-t, -u, -v], ["L", "S", "R"], step_size) + if u1 >= 2.0: + t = mod2pi(theta + math.pi/2) + u = u1 - 2 + v = mod2pi(phi - t - math.pi/2) + if (t >= 0) and (v >= 0): + return True, [t, -math.pi/2, -u, -v], ['L', 'R', 'S', 'R'] - flag, t, u, v = left_straight_right(x, -y, -phi) - if flag: - paths = set_path(paths, [t, u, v], ["R", "S", "L"], step_size) + return False, [], [] - flag, t, u, v = left_straight_right(-x, -y, phi) - if flag: - paths = set_path(paths, [-t, -u, -v], ["R", "S", "L"], step_size) - return paths +def left_straight_left90_x_right(x, y, phi): + zeta = x + math.sin(phi) + eeta = y - 1 - math.cos(phi) + u1, theta = polar(zeta, eeta) + if u1 >= 2.0: + t = mod2pi(theta) + u = u1 - 2 + v = mod2pi(phi - t - math.pi/2) + if (t >= 0) and (v >= 0): + return True, [t, u, math.pi/2, -v], ['L', 'S', 'L', 'R'] + + return False, [], [] + + +def left_x_right90_straight_left90_x_right(x, y, phi): + zeta = x + math.sin(phi) + eeta = y - 1 - math.cos(phi) + u1, theta = polar(zeta, eeta) -def left_straight_right(x, y, phi): - u1, t1 = polar(x + math.sin(phi), y - 1.0 - math.cos(phi)) - u1 = u1 ** 2 if u1 >= 4.0: - u = math.sqrt(u1 - 4.0) - theta = math.atan2(2.0, u) - t = mod2pi(t1 + theta) + u = math.sqrt(u1**2 - 4) - 4 + A = math.atan2(2, math.sqrt(u1**2 - 4)) + t = mod2pi(theta + A + math.pi/2) v = mod2pi(t - phi) + if (t >= 0) and (v >= 0): + return True, [t, -math.pi/2, -u, -math.pi/2, v], ['L', 'R', 'S', 'L', 'R'] + + return False, [], [] + - if t >= 0.0 and v >= 0.0: - return True, t, u, v +def timeflip(travel_distances): + return [-x for x in travel_distances] - return False, 0.0, 0.0, 0.0 + +def reflect(steering_directions): + def switch_dir(dirn): + if dirn == 'L': + return 'R' + elif dirn == 'R': + return 'L' + else: + return 'S' + return[switch_dir(dirn) for dirn in steering_directions] def generate_path(q0, q1, max_curvature, step_size): @@ -231,11 +288,52 @@ def generate_path(q0, q1, max_curvature, step_size): s = math.sin(q0[2]) x = (c * dx + s * dy) * max_curvature y = (-s * dx + c * dy) * max_curvature + step_size *= max_curvature paths = [] - paths = straight_curve_straight(x, y, dth, paths, step_size) - paths = curve_straight_curve(x, y, dth, paths, step_size) - paths = curve_curve_curve(x, y, dth, paths, step_size) + path_functions = [left_straight_left, left_straight_right, # CSC + left_x_right_x_left, left_x_right_left, left_right_x_left, # CCC + left_right_x_left_right, left_x_right_left_x_right, # CCCC + left_x_right90_straight_left, left_x_right90_straight_right, # CCSC + left_straight_right90_x_left, left_straight_left90_x_right, # CSCC + left_x_right90_straight_left90_x_right] # CCSCC + + for path_func in path_functions: + flag, travel_distances, steering_dirns = path_func(x, y, dth) + if flag: + for distance in travel_distances: + if (0.1*sum([abs(d) for d in travel_distances]) < abs(distance) < step_size): + print("Step size too large for Reeds-Shepp paths.") + return [] + paths = set_path(paths, travel_distances, steering_dirns, step_size) + + flag, travel_distances, steering_dirns = path_func(-x, y, -dth) + if flag: + for distance in travel_distances: + if (0.1*sum([abs(d) for d in travel_distances]) < abs(distance) < step_size): + print("Step size too large for Reeds-Shepp paths.") + return [] + travel_distances = timeflip(travel_distances) + paths = set_path(paths, travel_distances, steering_dirns, step_size) + + flag, travel_distances, steering_dirns = path_func(x, -y, -dth) + if flag: + for distance in travel_distances: + if (0.1*sum([abs(d) for d in travel_distances]) < abs(distance) < step_size): + print("Step size too large for Reeds-Shepp paths.") + return [] + steering_dirns = reflect(steering_dirns) + paths = set_path(paths, travel_distances, steering_dirns, step_size) + + flag, travel_distances, steering_dirns = path_func(-x, -y, dth) + if flag: + for distance in travel_distances: + if (0.1*sum([abs(d) for d in travel_distances]) < abs(distance) < step_size): + print("Step size too large for Reeds-Shepp paths.") + return [] + travel_distances = timeflip(travel_distances) + steering_dirns = reflect(steering_dirns) + paths = set_path(paths, travel_distances, steering_dirns, step_size) return paths @@ -252,7 +350,7 @@ def calc_interpolate_dists_list(lengths, step_size): def generate_local_course(lengths, modes, max_curvature, step_size): - interpolate_dists_list = calc_interpolate_dists_list(lengths, step_size) + interpolate_dists_list = calc_interpolate_dists_list(lengths, step_size * max_curvature) origin_x, origin_y, origin_yaw = 0.0, 0.0, 0.0 @@ -307,7 +405,7 @@ def calc_paths(sx, sy, syaw, gx, gy, gyaw, maxc, step_size): for path in paths: xs, ys, yaws, directions = generate_local_course(path.lengths, path.ctypes, maxc, - step_size * maxc) + step_size) # convert global coordinate path.x = [math.cos(-q0[2]) * ix + math.sin(-q0[2]) * iy + q0[0] for @@ -354,6 +452,9 @@ def main(): curvature, step_size) + if not xs: + assert False, "No path" + if show_animation: # pragma: no cover plt.cla() plt.plot(xs, ys, label="final course " + str(modes)) @@ -368,9 +469,6 @@ def main(): plt.axis("equal") plt.show() - if not xs: - assert False, "No path" - if __name__ == '__main__': main() diff --git a/docs/modules/path_planning/reeds_shepp_path/LR_L.png b/docs/modules/path_planning/reeds_shepp_path/LR_L.png new file mode 100644 index 0000000000000000000000000000000000000000..1e64da57f2a8ca1bcdded878f9a08e4198f7febf GIT binary patch literal 280028 zcmbTf2VBkn+docl)ANd0p3wx2p0fdRjKxRjXFf%gafh zUA2lXXVogI@6>DI9VTxY4fsE+ubn-0VpVF@wqE#uXsqSVUt6`xK^pz{H`QY3*r~^*)T7WF0Eb-a1oH9TJgo$vkAI zvHavqp*_a!j@kF#ayIQh4PY434JiaRu3 zxO4Su^zlPx_4gRDFZ{n&7O%eg$E5a8ks~A@R67-Y=(?zby``N>J*8mD+}IXzyQ^%b z2G@Uv7)_7-pcpz|E3%2?8~?fKON9wY7)hp z!K?~1TT;0O8c>vM$j&iq5L_6!BlYgl0izmj%9cN7Lh6eD>lxr(nHVg;*9G?!?zd44X6 zw-o=WI$HkDn~AFB&sBpEh5uh$|L_cV{q^J}@AlixK?Y3LUv?EI{2v8ElGpyD^HS1)XNk2ipx_D!xd20_#k{v}d&O|y`&B2WKVgGe6OADv0~EPyLy$e;e>Q6)o8QKu01`{67_8 zdJ%LqaxJNb;y9nNtYlKgv(dq6Kl)1f@1f`u(fg_Rm@I`p zRoTms3y|ywCw6kS=zte|k?X==UWS5y> zBKW_5n;~8fms_-JXFCt+!)3rt>Azr4v-sb?UKa!pmwc@gN_uwP`S5n?aNrE-nn*vy zz^SSQ^7qP$%HN4SoR=40bC-8-y#Jw-o;Y_J>YU#V?g?Z+PGVE=lYa$4PQypz-AR|K zs)!sArI|LoEqyEJfb)84hIq}@B{bjoOUnKy#p5-=<+j!yCll`_W^fROcU; z*bZF{9L*YdSt&cFP~4t=;q9Wcz(N-2;=4CqbkEN`m+du6hzV6NI30G_uYG>VF{3Xr zDK_orLxW=FnJj7&J3&gA3R=*w-QrBLVAWs>R$c4kEq1l1O@^PJ3h+NOmR|p_5fI@zYn+>Pir~wat;)~Rx1bu>#yW3Q& zu2H0asZ;IvEZTl=sI{QHbCtCHo57<4=_i$toK#8FYf{GMlxHs#wZvlLHIe?0Z=N|&vz%VFlvE3^z}LF+pC{YnXCeNa@v zvAL1AP9VvyAeCc(f6~9t%5&dYRa7P3|8B?Pba|uUP5O&nexm-T4}a%+5GCKBW#o6l zTvLVQaB-eEf24Mew|Vc7$d6XBqc17V-(#+8$Nlj5g`VdD@1M!|CT_D-8Io77R(v!1 zT-MLWBKv!+av5{OrEtoPQ~kxn4z5)=N!y+D%uaXsBPgZ59&=~vkJX1Y&NQc{sFLwVy9oxVb`_(`OT?sKE3 zk~G-J3?&eumAw3eeY-GEgnTr< zaI>5;t3-$An$D~Sec#n<*1o%NXM5=Fnxt#CE{wnAZj62uvFUs_JwNPWz;hTD_{MzG zzXi(d4V*I%4lh1-eXQH*hZk#Sh^D^$+krfWOG111dV|Ft)6lx$HJ;V!!yk)GVefqY zSOx!L1OMNN?vOcW#&P9i_WXYzTaPxBc|?qd&)JVnMBDZ$nvH_wXXDC$8j}<4{YubEI~T<@W93c6SG}n+4~YUw+fj5s2$M zx1N0eE@=NbJba}4r(i&lx~t{d7i1If0j)hdesk@&4LK$Alg$}ZZ7y+qA3qKv4{{~) zI(P9*U((f@7xL!muh&**nKd+8mCV&&#L$+@CfBe6oAK81-2ai4w?ys$5b@_SI! zwOHi{?YR9O({FdwFuf0odRnh-mU1YtSS+}BI*oN*WB;r4eS)EdM>uJUc%+2fA+I(v*A&Kl0~cLr%Lp`$vA7uMOY6fkq$di7ae-Wy18ay@1pmgEf?F25&Awri1(F zTmh?OG+P$L@C>#(w!4{F@5)Pbv7OEQa*SQld0g(dmUC}RrR2wS^(2i0uG1sqw_clr zK7Lm{v~F3B_)aD{Wj2rDqNy6r*-D|3ZB~V&vd(-idf|MbX+K7v;W5)2X9KR~J?uZiy~L>8-)1nYK_j7{`_kV{yJds( zeuFT4xq7TWi!{8eIy$TybA+DzpRGhYQEuL+#UNBPe%5)H3*%*vg}=XRJ?$*?lG2Ku z*>qJX`h82dJt7K2&tHDrq@CUK>$I|~M}JCAjVK@2>|@u{`n9pAlSF)DLbdtkDPN^z zH}TOI@mS?6yN6D`zoorf^uV&52`@ezfdCQS%t%GzqH)LQxOlRnocj_+zHrSu`04R&-{G2H>}93)y%8u#R`)Eo#f;J zcz*37JM)U@06Oc%IRar%`gc`C*X(dfK(keeWOj>f<)Ud){*TFu#!mnmB&#hK=KfX} zI1Y>Tz6j#GrX&6f9EB#=@muZszoR_dx&F}RXg;aI{c}!K{QDtUa_V_{r}OcZNN-ks zr=4w1U4F@vO-RMA#B&uEwmLM&to{}AP+vUB>`}4<)n-B6N4MJyTn4ko-%WL&-k4Uh z;Oq*q>b#y4sEYsOU~^p5{(7)`EsLygFU3nfl35>qhK0d0&A=mxBxlC0rWx;V5aMth zc`Y`O{`O+2=W1i|q|eqaFB{!w2Or+1cKB}mFc&F z;X30yl=oY>I4?h6J?&MELN9yKQHOyo@K=|ay{6Q%-PP| z_Wl^e6K9ZVlkYMX>)rjm$s{h~nc_pi>O}P<#2|3c?tM%W{Hd990Fv7bmkg0WUrt4e zxNutqHq*3Xita`M8v z3%@wuzIgiP0QlZ4mB+#{vaM+l12Q1S#9Wx<(ha}m*P!Rv%J#YU*Be%+pCOu^->*cS zzBwd6GCx1no@P_~F>G(X!ysG1V7AW8-qrshaw#x}KSoh%@}wdc+zD2U0_xYKa#cLkT7C8c<09wvwx4X|G*u8$se$EX58)<*1 zT*bkb`1>lS{t1LRvlJ8~+`Y3FQuErVgAY_^Tk@_YoqjplWERI`%p)bm1^ZIfJ==Lu zFp<9Ry;_H_P_dkfJ@R&4-!u*Ua@w5vH!mvbZGU#yq6xXl@M6U2^eO$|_-A?qqmTB7 z&Gl0^36r`2!=TfL<=_5>h?-iHU~_XVy$?hsfd>IvC9^{XMsMjw_uc$n;<1?fJJRJD zEhhqFCP9Znz{#${p}9ga@br;Vx)9U?{r&{OSwExL~zJ<;C*PH%l~sGbzwML z;aR{Uov+vJNInx?WYhJ&y4Y>D2aqD0X}fKuKz|Ak9g`fTK7{r0-yQIfT?i$bKA&5d zDhY5HY?6snj<~ouKNY~Dq4l)sS{~W@89w-ftvGD^e1b&rDEZL7=8+GsPtl3HHa^%a zIy2t;$Ka3TMBO<+ByEM)f2L*vDk}f`J8B0#`{CsD(2Dio^X@%3@b8#y6%Ff?&)Y!o zdyk+kQ)(ofjRdk4EP$zQ#Zv^9+E__aE->HX7^xc)+6Rl~%6x zh2+Aq3gk5!0r%7fF=t)}uy(Fi_uqO=RXXCL+zce=lFE8wotdWxGQZR?wFX7cLhiB^QriR#5r|c8@bLaBpuhz$?o7uu1~Y@lNxzp#-ZoA9a?P48zFqxs?I`y zJ@fNO3yxEh3IS24fsFE+XqPd2z{cu=_J4mqR9Q3hG0ChURlT^K{@?ZpdWHK2-aX0k z*9KB6Rb>WLER*s1$ucwZ;UFHC018)za8hKA{^!i)iw395_8x|BN`?3zT?1ybdh2ZN@{W*B;Esm zbSQVXWzj^vQ>Qo2MNocqzIXu0y?bldZL`K5vT7?-m||0k)}oXR;Mo3A>dHom5!^oA z+;jztw7g$WdU-gxthRjzqBhAc?e+5ZmR{gMjU80hlF2CW3@q&CzlBA+Q?`L;%LUh1 ztEsMHqN04i?b;W~TAa(B4cq(TRwprjIEmjVHMf5#zdv<6s^Fo4dtSwMNDR5>uMBtG z+~_}1uaj0WRe&dTUkuYy=;;*y*V8SjxK$#z?UubKXP{n$+&m%QVS0fGg~T>X3CK1W zQJC_$e)A*PZsMg(Ky5Mr<7z!Pf>f0MqwJs#40qa-ht(@(5&sxxGIqG@$>|@K6!wro z>uc83|0ByB@LY0Xlug5sIq;nUflK7u_itXu;bi#AvNazG-xF6xQ5&bCLeM-w8Hv-k z+wWa%FLoOr_W|k4YEa-VP~l0N|M@1gyevZkPX|o`s1915Fb` zh=hcnt$f?HdmfjQxHNCR-tZ`Xb)?R}fD9C237FtSzm+}dQUWvK?IQ&uw96R%gAxAv zpI>F5(=3n;hzuo>W=!6Sa@Jh z!bM+!Y`K#|C^6!)QnMk+DnL1m!8=H@tUMQx6HXSiWaB>_#ShT9g6Y|mv1q=t$Z6fY z!*%3%47WaD;fo*|WrKo&mx?h%2kx%I=QBBhJL(G6vGj(u2^|A}rXW;^;1>k6@Y^k6 zz^?Spu3vUK#6tl(Sbu#%@+neDsM5osm`3M$Eh}-U6=keS6bC^u5$hG>dKieKp6{7g zW>7lGXCH8!lDaOc6!8cEG?Z1Yd4QJk>wTE%Pm6MAd)vM+nWJU@O`YE@3Qw8Hr^>cz zk9yHZrTq@k*>fw= zbJvP&Uw-a!S^%h!uD_ce?c#532hCzS#c}ukm_I%Rfob~L z+0S!BjwQ2ux{J#;>!=ZqWTi8}6+>;~_w0s5A{EOkPRLyHQ$>`JX#S&e@qrcZ&BXH_ zBFtvw?qd`z>*CKKXX9o8C_f~>oD;;Z(h+7=?EUoQo%gU^hK~tDA$bqlrToP@@AiPR zqR!Kl{j`PTTt8faV|8tl%pyTGtMJ;u&8Nxeo?CvqJEip04mW02J-ajawjB|M{40)j zR?8$NFh{)qP{|EZK8MC=yd zHY<=?+1~W4)z8MKLb|!8An|^BmbyQ!#C@B~Kt^?%K?(2P(IZhICl1~vQN1x)T&|>5 zw!%|V6^OP3*VJF%Y`Xk*-roHl3v;=>v0)dX-aFc4mZq-NjmTp$pq8II4!0?5q^ee~ zqM&pa*l$`Ff2jMINzDs|*XB8`4mS1YuOMj5C(;JT^bc?|a0YG!P5Ya!XiDajCXi3s z*b}<^_J^%t&Oh&PIP<0g+vNoG6JIhUhf}?^JpKR|u0l<~tBW3a&+8P9EjFjvY&`&{ z@p;)HtBcFE%I}R0VY6bu6q@}m3j@{*uq2KTsP?Gawmpl~M?*m#RN<8Czj}OKQt8p* zLMG&P2%eU!yZD9KW8+Y7qX5anRT6(b0r$$%mu2b8gvwA*=krZU&F6~*EJMq#2uHgDv+8T>oro_7L9eie78Oq`>g0$xw3o6y?Li`woFrX$TW9#g~Xsx1rjT{=g z!dAbO>zzA@Noi>z@oPXb;<#)|>}{MfHNdU?sU-_DD6K*PhNV7u?)=|ZwaUJdla0^c zWUNK36FbGnFe}00>CSPksq>ka)y0evmJM_n`$h&v$K*i=qZ|}dNOS`iy#eVUL-X0? zw>QfQi%t(E&SK^ zMD0iB*9f7Q?_dk5{d1}ggZ@nvQ_-&UO|b2}y--vLn|;QIsVjbfnrn6SpD$8UvVLqV zF)=ZU;jaLK*u0_Pd6y6u$@ck)NTu@X%K)Kp^pugn6y^f^esQ2NgQcnlfT7s0M@F5W z4t}|Z>S=FAk$5n}h8Or5q+}{?X3PGD@OS(+AeF!T_^!uvq*eLuYU-%UW z|NaZ}v!@`g^KCOjr`4z3k=<xP-#0WcVa0^!qaf=Xw*GxC}~2h zERi8)+)f&olD3B)BIb?z*RJ0Z zSp1`$RL#ov1}5bR{g~`@i9m&9X*c-JkCt@fI_P=sJvD-J(d zDF#$YSM<#d&!BSze}kDrk3&Vssg(iBX(`GEl%~0d3|NUa>2kIgayx zCe|qXbRn2keH4(xR8RFJ{>Zgo@Ak%pGoHM&A;mft0W#q5w)3avUi2~|`0-*w@xPv`fKM!k30*3DJpQ(CRD)BbR&^W@gOZ;6(46 zzdDSi093oI+uf$hAj8-EVKSJao#lgHv+g~I%fK1V2(z2;Yj3xH4+Ghg8sJ;ob%O^BrSpz2a z?sppL*mCHqs@I-yyBc|ubho^pp-I-s03aB6)$rZSQ$Tebv4mpSp6pymILgmoiC}?( z5w9Ap8;Vc3?KIPik@l1pTL}+T<%CUBy}aLqwu^6J8M)~^G~`!7)a5;3YAz?1rDUsT z*!j-;K4o)InqofU`^VL$fRPty&^fyUl%r3{5W;&eyF21K_M`%O{gOL3R%ry;M{;J< zK2qRH#i#1MKf>AtKU9>x`~boW+-dOLW_&%%y%YE*=J)}VK}5_Up=LlMLjC0EWAhg$j{&{K$J7~w?iqTGyGbWH$-}Vp;@&nzonU!XH%&DNf#AFE2%71Z>?5s<&E$2UqL6|O1$3E{2q zox=mEw;Q&J?MIc26IXRMg7(C-;^_o)IjfHR4xfgYSg9v<{f{c6wG`NOe~hdz=5LlB z`U6D9I@H#8kJMP|5cZUHwOlU4eYk;x{sUdecWj`cpd89j55>AXSFfotoIR^35aJbb z8n_dD=VmAP>vNCAg#%ES-g9E0XsQi)v~uVE6wMaHd`xIdu`L-|39k6nNG}_OJvT}S z?X#bFp+kBF8<#1VV8g!DeT$G*mTz~|UBBa)tM>$Aca={L0_FU{JD&wT{{$nlsP!BY zPTm3*FF$glgjpI82W^6V5lOtoNy4)mm!L@r(ZC%qoSOBYXBJb0_>3$RzRiW7+_3 z(sEQrm-k9|5j_b`!|Y4_r{%YQ(zQTo3Za$h>8^mv?RBxI!*ZuPeT`t-(gasx&p86j zd+h2dMZvsF-bwbuZIYn}E32!SmmeFldAc_) ziePcb*@I_S8*&40a~Ft>ozOO<+M7p@fH+{F7LUbwn_rKwyoW^V{Ln4bjly=$u^sJn?$rLKQD=s&?V?eB(Z3hn&8qRMM3aMwL`3FnOCMEsF5n4UN6D8={k zSnlf;2XI{@%AH4Mzlh1<=QrMlZEHz|c!g1%Z?+!9?5y-z!?HO+-Ktr7;2ATUiX70zPE+wGl5ii(RSB^{(#_}09sT=SU}Cl z8&vBJkM*V3&HwZTKFn)}bgTWsJeh8pf=AJ0sS)WcYM1Dd^IrZ1^g`7Dj%{L(l^%(La|U+7+eeCz zS72ma_tR3S0EI_3E&xIe(Qzwq80>^Z)lVZu`{#u_3Mkmv&~g2kWKxkh0CihULFqL8 zqMCCp5A__rcfPN2`#~2hD=q&cC*kD32Yp8%JUjj`*@5H1ida9$nj)-#mKeB(0v zzw3B?(+JSqPmSR4x=701VTVi}tWoDDkim(&_k(ZjX-G2w4degW)&|6CF1*_P*J>kK z3>q;58t@A_olizp2h!uc=vd!plyk7Zy|dAv(+)8d&WQ!SXjNkdhF~teG(&K#*YZ9m zLrP-vanHkdXHIPoS)}jBz}ONjf5{CQkB9;j*@3=+1VJcyz7C_HqK{F6;8Ly83Bz8rvJo>&YlO9 z$hAoz3$uai>hXvI zo^IgmGs_d@de-u$UcR080i*ZQ(ECBhbX*gCWI6XxHGzjJoZGsLMVJ2KgF5hXCv|d& zAI6*0x&nD=1APqdf%?}RdWAUL^;?Cx!YZE-q-(1NO#iXFsGJBz-O7~xe}@?mK@5RF z{7946%asqsMGK;;?1}GeBx}KOZUhVcV_h3eAiXGkPDBHy^?6q7YB7eYz9%;v;cA2a z$9n?%5Z;FEiHS5TyjUzn+-w`kNU`*tE~Njtc&?dk4Qr9Q^g^anL5iR{I7& zcB{ez;&wf%;kf)|$bf$BKEzYjziXo1NKTzoHPX|%;0k6pxM)5K#OSe^3k~-{6;jt@ zej)?P;+n?VMg-r#3WeDnC>28}(a4cM<<(i|H?!a~bv#?myou(wbc&%|Faz=T-(fGk zD-2G_W&iSd@a;w{*_LCjPUF3`aVTA(gM)a3~0&5FOhnIx(iW}qFBS9?A{v191<@?zrUIBBw@0Qw#P>~DJ~5^%pw zZ_GoDLm>oLj@v|w8Xxl=hdEFWNnWdgUA2r2v|q41^$%V7G}Ul$dS!XTB(er6uprkf zcL|e6bUYPmoLaMXz1Br*LXLV)MKUWs;t-)Kr?`0K zxS@4JvnyEtjnnnJNW)q@Dr4K%wP55V?*_y~$qu&_b%Ea%$oTMq2|tbPaH zXMet3?}I;Xyn$%Xwu&8)x1z3wl$K{3#5z3pxJ%{apTYdrk~yfI0xK6c9a^q*EuD@C zGq2y>2W(YmnsexK8nV;>(lC55!@ExVNu=RfR6KElbgy8p1Xca-?Kuqe0(2NMe~j8g z@IAO_aS9;*eZWH%x99|ksz`#)oH_fTf6+KbytRO|Qx?MU8d48HUhOGOqe4v+T3`i6 z5EZvxcp_r9`HSR~E>z*REuo9}`?wPK`HLR{cmAwG?Fpzo33X43XqPV`Af>%8_%Uxwfn7U%&r!pia3N{R(IkHGTUP$Kn&!g1Z5ji^}3+U>IVRpV(G}wv*bcW z^_fc4v7c3W)w1km&=L{#P2@DGGn?QCeJEMbz)}OEnjC?*BQtfL@5go(K?7v$K_nsD zhW>9!n(Lu&qN*>0zyUKym4aVog_bkTJioMz_iUp;%x&Ir&!5E7qCp|4@-u*c!9+@U zA%fb?5~63Z&;AwI56!xbs2kg&6IuxTU*BB!+c78+Ef8PG-~>$#MyO#ZrydmN9n_5j zS&MidV1`Qg>Ck;3JQ^~!q$Cwy8UF}SO|pP#DyWd0I-${8P@gjb0YO{@9qRSYK()TP zzkd#<7D0af9^7evp&%Vec*QwD$jR(CIZWo1_oKaLhOl94P?PU~{0&Gw?O>NL1X&H` zT?zSh=n-MvmlO@5<=z)+OqaqfQ4HXs943(xehv{%?M3HEr^pz{hs!v5sE#ep{n4^2 zny5$_gp4%++O&UN8uUTGhVR^jI@3D=(|u|j0sUlwHZaps!=B)k!lOd|!H_+1JL!%B z1t8Fy%Rj*^FmMOO!7EkwP;WxZMN}UH40_f5&~pX!HC`t?YFCB2dw9kd)X~hX^oYTa zT~yF%9sNr2MSq1jPG@my0&{&tHGc_#CvuNmEm0RK$8a6cq5>^cTD!pu2WB)uyQ(-s z))GC^1Zb6oe&$(zB-_4_7cgE%ms1({A zbc#*HR4rVLB%a_nAe#LC5li0eSLX$uUyoM@i{4O02U^aDi+LLC=kmTwh@XSN`OWG+ z(L7nG5gtN4LHC|NP~q4reCe)dK^#d5>iRB_9S?hq66yJ=Hh@Oj3s_1L-^R7lqB1yY zDVhe&7Z!8{?)}9D+!6u$!JYtw6O&T4hvEWJv7;Ii30ZC6h#)1rE(7Y`dUh^O`Df_Z$lHx^QI|VO-Bt_aJ6}@fq4|MC8$WCXXA=IM)(exi z=|1baGpEX=7XN;^_s2Z@`{hwUKHr?^nTQW!%I!}rxCj*UXDtorw(NxV`v5_`{BG^< zeVB(upTwO(7hM7P=6v|BQQ_d~*(nT{+$==(t>CO&! zr}y<5+9ol%K&K#NxA$HB1c@#dqWWH?#W_+wl_4HATQ-SiV|_`{*;JOfKW>YG${!T0 zg?bAb$~goj-R#Q!OY@TPnt1-SLSabk!ZL1W)ob$)L8DNkL$gJHmMoM#ao{DPRQclT zlNzGhtMVXQCK+NuiW%quZ~x7?!iPb-IqeQ`!~Uqfdba{V5F^ONv-t+FMugVTf3Uut0*HHjbG+=8GMlp5Wh$uF44tz@5hRY8Ch zty&gX!b&ubC*VUH)V|IWJrI6|sS(CkjVgloZl!y4%*{C&y45B$!$SzRij$<>2CeF- zee-fM=ifG{c|3dZ;spo)E0W_fJq{`2Sof*zFeuyTacR`M9g#Iqy+;9s z8#4(w$*np&jyjlw@^h4Zc(&Aj6-XN#8u}g@ShvC`n}_UuXs0~7b|Z%pA<2>u!Cqoa5%HX6)h5G=j#Bs}R@-4cU9lo>2w3%RGW~ zfE8B%7lkFEqcO_h2$;jr1TwQu?aUt4r=_6#jL^ScC6Aj zy5C^&NyZ?Iym5nH&Cs&U`|0B+Q}S<5gn`i?lg>YL#8x~J{{BG^RH>zvJp@xFcYzUz ztg){rm3Y2z;|qZ*6jV?s-23j_QsfY((Y5`!2c?O|@4mx$LMQ6|f(rF(k{k*zj>^2d zuU2B-i>RPvqwk6MY%1TIA0)QPQpPYQffSv}*eiw??%q-TKFy#w$^77omA$>(QBVsfA6@z2u6w zOIn)7Q!StXbH64r`i^NUYaT$`=U2W&X6bl-CwUwv0L>{*(w(iQAfZ0-Et`9qbF5GS zW2>(OD#gS0J`b){J4H}DTRFqNx`b*Nvw#W2jTLHHz<9iegq5k;JoEGh^R5^N6(`CFoWKucqSSmA@Rw1j0O$K~EZYp+Nz_yM zir`O9KOuok9%cc4+HLe%(!V@G>l%5UGSJ}2j8C=7M+MN>s;<>>%xe%dCGfJQPi}T&yxFfQlEQzFGcpZ4I$U9-NmsXkyKulK9+!d3xr4Oi3&j9c? z)~L#5yfz!gkT{$=@K@`Tx5_SkH+nM_)Yp^6pz&BZ)f(0BprzQ%#{OR;9&)m|kox$V zmDrPoBt8LFFVS@gRMO}ExtMr*)U24`=Z)(7cm+hfF;*<|4gxe1;72mP9GiUyGYwjo zy@)xOfg*nx@y3Da6x^5z9~w_WlQG8D4v<2lk-2Eh?JxNhvaSM5aqfa(y>gSBi9v5n z#;_{<$mqk8xjp(Y0x!JBaj;1QxVDEvDe*ys?=ashh0#w0dr>b#aBnYw;(&uyV$Tho zzY!+;neTft<@j99%tCD+a{wZ~1h}2uLuw)M*FdSnd2%?3Z*#Js?vUO7V!Hr-o{_x- zr*#h?fH1TaC~7Z-I-Ddm5Xb^HA9mgeKA#8eQfLNf{4?3r5%I;KmJ@?5gv!Cc7)c9N z)1v4c&1=Np+CT>c&OS8nbB|>M@bJoFKW=SH)i+r($Pp_4BflP@Mz_bZaD+@u+)8($ zdb;`8jSVX;W98iq|IU*$5Ve8*Exy@Dpu>cTvycFbgr)H} z=HSwMTMu50i*WFP4ud2mgHzk>)!1CEU_|ctMDkKw27xSsj%ZW~)sxr3hzR1_-H+kz zNQ+0dL|rUoMRQ~bp^ZY1TS%`lqE+OBxXYk?{&338bSWERzEKL**5}~qw(8_TFJ@=@ z+YS7;4%21cLDyS+s<-=xbD|j#S8;)Lg7`o%$!!!1H(hK7G6iY6(d8Z+EN-7A`hsT+ z2v&Cjj<0O&2V+5V9D8ZkEx~HM>n5?G+^$Y&ncjQO60*6@`=>a(?d#9;7-*m2S*a$r zsGIak_KBVU&JjI;GY6J(%}h#-=&PBtag3hLkn1hQzaFS+umGqKGGEn7umHRSGwNPI zteIbfzDtVI1R`q??AusyR(RzD`!qpI+~-r2v1D;+v$h&&9XYZWh{}VfK_mTWSkDPK z_X;~m*uu)7iopbZ6s~ytlqK#6+ARW(&0K}9<|9T2AxJvT{1PGUuTldxrf5tQ&#O_* zj5^v@Y;O@dho*Q}C@Nuhq}Zm3b;}XkOAyX?cbx!r)P5hWJE&<)MRcf%6wn=Oq!cce z@yPXkBV43~sT> zGYI~jX-lBx$$TZ)KdHnczQX4eUs*M-Gnx zDS?oF3C-P*-(f;pN{yGqL*Kd>;>v6YEi}qf^W#lAEyV5&z;gpI!D|C^ry-9Q(U21a z#&1pe+*s<04hi=Z6@@F5`!Mc!w?yL z2BFaprOsQ}8xG>%FggL@WrTbT%;vsSGJ1QP-dDfKnMLC*;bI$nGR<_CVLk6@LY99W z-B$CPJ>Hcp43oAp!Ocet(6))D@%3(B_@=Ju7Z>Twr;R+1^vsg?yDk7(s^~i~@yDa> z6R5C?dbqE*Ms=>#8r3jxnOO;DmZXmhEQhzR7hYE&dQw}B4xo|zPi~YvWaOr)XRp2u zy0eey6ucq&oeH{b?$bXGTzq#|Sk$iP>rPbQz1o<5;U~{Q5{6s`2v&XRuoQLD$EmVF zP)fYI6`%l&o4Tgk$($%wiQYo_>r2!Q#IF*3a{;=41_s$!*4*SEYyrk7l)?@RI6&I; zNZ456vHQA>9NQofaX2G(mE@`F2!bX)B5&N0LjdH`^DJV-s(XxMyu=QDGLI*ofO-b; zsQAMiXTy1c%|vZCHRy;9v-F9SbO}8l51r7X0K49Ehnb(9mC+)p8eT_5_$%zOx@5c5 z1fkmRu^=+su)hbjO_0#+X!lrjd+eZcbnq2wN%g@W4_JzZJ(Oq$YxgPteYI1o*KK0} zF_;Ah2Qx=_-(Go!>0GGA;NMjfOQue07at-^(eTjPMt7I2tJS-ZWoto_pPBRMG4Tk) zHz6_uT|aQZzOPPL#1Af0P*V-7C`JZx9v zB>^%|-3Jz`dFrzy@w52F&A_GYcm_^v6so(SPvw2TTgVJRdi^=2VH^kFyR`ivA`8J`%s%^`0#Q3${ohj!4C6Pv;Pf>5svQz znpBc#Ikbn6HsPIFt;NUEayXBqNFK?Ogl=Vks!lt^tPP8XA5jnwFrNtx7qSi8=zstBFf-ut^xy@&KgTVe~z{b{%(NMI{(<3WogW0c+SXs!#DQ|>Ww z@njB_EG~SDYKcJ44?JJG?yi&Y7%m#o6EGLQdnl-`M9&F~Mj{9+UJ``W zlqo_s@$dm!Zzc=dj+GHp&k0__MH#4@2ue}=&dD&Es=PsiUTAG_N6O_dk=x}1=b;^h zca1e_SOz^Y2;WaqQ7QERry)tZ@&sXD0n5z|O~)bCc@Cw|^Zl~9l4ikJr1VkhfZ0Z0 zv(&s;rH0CVnM$ariEct*d3@Jl$(Zp5bf{~hI!QB4m>1@~6u1^s;$Z%xbm@GTtolDX zDwnj@l@+m`ga8D?lW{3fCYbeK9?GJ`BSh~26&-|4A3H!_J;Uz^NBy0z64nuSf13hb z0t7?c!H2G8LKnOpUems zY@kk9X|atGbb;reJOeh$2H5A2$0=w!IjocIu=%5y5G5kUU6St{Ah<74MQ8UeodOXM zFvtj zZ7^~ScMx4UjNQr*tw4bWKcK}RB<~8EbV7GBWjC27@qNCspQv5iC_YB*cp!CZZW1aG zAs69V2gC%ith*(+Qtl%=Am9XGg$5$j{jeJkSX&gz*HI|4bb&wihwdl6T*-h*l>|y# zJw)5s7RgP(b~x8jp%GLdbiKR#t*Xtw zcBUz!lKWen^(8D^$-z@z_~XEsL4ycu(52z5$lp1)3!U0r>h~EG>q5isDh>*2PR~`? ze+=1IzZuN_ZptRJYBePTZuvj^3rf2`1{rsMxX;MQxC@Lo!pUiF%JpaP?PjCjZowOW zIAoUC#_u3}2Oms5@_2(vjY~_yAdFYthbsLs6IyqF>>+Z{1Jez2@YV9jKQ)E@+_G{7 zo}K{6bDE9gdYMR8fGe$|xNzaZ7=&I^{NxUgxidFz+~}N+N$c~bMIZnLe*E}x ztC@abCR&2{HS4HS=pTzQ{g(Jl*-AwW*amKJh1Lc($@hp4i)HGmPYHtyc(pY}<8s0* z`S)&Fx&5=8;1j8wT6{>>#_5UEriN_Q0Guu7>({Se0_qwa8?)64wRX`SpfFoLSZ6$3 zcv=D1mDowC;-_HMCvIau#3hd_vJvFslCFx9N-Ka16Ry{Q)^dF=FC#sbtyI)GVKxo% zTURcN0atpMf>lUA*m4p`(nI_uItELX!`nr7 z{Zm-NtH2owxQZ?qs&3rZpGF*YRDjDCAGjLKu`j^*k=cb5V9Z0_!x8H);tcrpEk}vaNVRBp3I`*?N2K?E3{wF^FzK>q9(lS^& z?&Lm4{5mF3&JNSn6N|65319kP6j$Unn=LIXs{kdYvW5oD0*BUodqxI^z-PA9IdOLb z!Z1~QLlJN^%MDs^pB+1YXITNcG&^7x@4=6^cls?o;O>%3-(MPkj0l}2UB@|U220Vh z!)LfKBgUi?uvzs-0vxuFxa2FS)(Ae|)iNZkzd|cfyO*6z zJ%lN4H49{h9J)ai4>yCDP3Nt61{Wu%+|(vWaO9ITQk1?@?IHe}XEl}c@RR1c&d*VyST|M^WJW_p+n5&_#SKnZunCXO{vEwEg?-oX?iR|!?BL%{(0f6>v?hk&cP=3G$u;xYBgU%bZ!%a$uR zEWMG8J+=qub#t%Td*vU)`wdz1Y!!r3|!dj9amV3JD$0Rd_?NLk~*jhALI9n{gMZ^eU z>XwLu%hVA0mfvhzpS-ufK1H$5PB#G45-xc|DD9n1(H3cyJYw7ZRoUvxLm`6)zq&4x zD0t}y5SU-#(Yj>^PSjRUcG!5qrl=UqrR=AGf?}u-3xCDW%7^wM0@|$$rfso|Y)B8f8Oh$EZm-$J2U4 z#H>CzR>^=K>ji+cF-C7^@-6Hz?_OP8h}SE~t~yb)RVAWr==bj{=i;_(8cjDDe&vUK z2$XdKppK4}O7HTTF=c-U%IZk7I|w^mZz{kJd-@yF8tnJG&Dfc=7Z-USeQrnG%KjuA zT&!~m@M!)Rv@7m~kqc2Xow^lIf@i*i^ZH#zzRgt>-pI_ou$bepS*yr7t1d-H^OP#w z%yq zyPGy`6iu#t04C!pLJ2XC`{~oC`IjR-7OtN!aW4{i@`4Ui(4taknRua=aCU6u$H_bT zbqRxTPw3_yJ9gAg$*sXm4sFFy1tdDz;+QW>CeaRW*khF3J1XL*4UgmD{_c;^kCfJL zjtn!y=oFoUk|OqJ4Lmf9R{&hG|LFn5bWOg!S!T9OE6KC2!Ltr~tp0jz<<^nO1u$~9 zRGFfjA3x(c{QVGmqf>ahE%0k*&NQn(pC#-uhjpBC6%&c52K z5)#vDLTjvc#He=C!H6%dA8g=o{X42Ev@_%?5}Va`4Qqc&!G4BWA>;_ zA!^wYC~REu0df?3i{a)Rm5NXSGoB63SP~dSjqVw&7X2~NQ+*P+jtdV2c}cUg=_pVO zefpKsC1`$NJbE8X@Cc#cCkj25iYEUNdK%CZ{dQ+!p(le11{8NAe;FUod*=l7aPzI(uq_Z2Zfn8nM9im9 zO1}V(>si~Qht{a&bPSCQVGe#tD;~*$OEJmzIk8g0$jIe%Kpjo`KbsP@r-NfTTlID9 ztCNSWmF~!AS}d3^lzUbR+3bt6F$(zwH*VgPng7(#AnJY4_6UjWIym50hitB>FKY<# z`|E`OXpiVfG{r2zc>ZFJrnu2MQ=x+=r;&vw3c) zVE6^ZdlOA+{*?ke}Ec*!~ARCMUDe6Nv)K2&(7Y?60TDKf}kq#V2 zPpkEdvmk$3BxEe}@+ao7#NpFEsHvXbtNkioH{b5#Q@>p@J|C)|pZeUwmPHI$o_~qN9GK4q9~H(LWyx zbz4z0KWYHBf9TL#BLf$1_kUv6y-9SH)LWDd;csW3%hK!VA%?`N{TMJL!n&WCgAY@P zYNUmJvhREG`C{^Nngg5)Fz-2Ws{(Y$6*c`OI5YlX!6M?h zd#Q+8+DW$$9O{XaC+&Fwkc9%ha&!4RkF-00F*#f4WRvGG_~hgcP^nOu(XXv5I^$YH zsg^!(m!|(9Ns;yAXw)Lt;N{d6Zm{$;7)mSUmzPA#Bt#JOpDlWD=+%yQXNcnE%%gxR zRJKy2#CgYA7?R>dvp%+QKaXLXDcw&2`A#5QJ=)**J=f+roJH$?`?GR=H1F0nf1{Oo zD8$+x9bKn$@9~N=wuV&Bf%T#=3uYzQ^EChsSjM!zU?u+iU6x#zsZ?fu4W+6`$$n2p zW@aw9+ARb+H}L<&ppOQsYf|-&>g|BR%0MXJ)s4?rmv&Kgu4^v3)*Z;0qtvhD|NQp2ErMe7=3t_~xqyyBukQ+x z5Y~_$0CJff5Q$hq(1tvqL7J2e-Aqy~5-w%-;;Jjc>J z<|{i}n=^}Uy>^Hh8P91~xIOlBkmf|gzY~sS2H{p%Jim&a9p((q8UXL!$DaA7ixOzL zHM^GnuFE$92y*Y)7k9(O?JF*{!B#7QSt#FM!IYlCl|$$stE4B8)sMSm|+e`>MxN({y7 z>-?#hP`Z{Kk5~59>Jv~NHk(@;&#=7t+odp183SoX{!uf?m*LjAB*~Ikk#J6czL`oKfi`kqIzWnKGh(<4_n+#uRAYD*{ zft#e+1?bLu0a@W+FuoL;R$f3X%8!EX4|F!ZPrNC^>9c291o&h&3m!UiC3pp}C|v}1 z^T(9v<**Y3JtR$qlBmJ0%D`BEn%Na-oJOcA>6QErOi-n}sS?!^cEP`Jap&z9;CK1U z19q@VNlA4padw!e>t#Jix_0Fw%v*8yz`xb_?^$1gj{L2TaUR%@k?VlQCh83vLf5R@ zAoeO~kK*Pd*T-I5stW(Ua@Qkrc<}6M(D2RFiugJ~xXc(=)j=UolbxjDBdEWx*o%(6 zkiP_4+01R1aiL;GsbI2(KPpEzX zf2bY&m-vLz?NBz0v4g@zO|hGcWAM8tn3z0uDEZXlIbr0{MytSSw9^)Pv2yC(K2zB& zXPU0}`B91t-N)L3sUV);v@4WsJ)a>2@#Dt4q?`tvNf;bP&R;su$)y8Izq{d>y%jhvrK;AY@Yutij26yVraUy3*}a_y2MB)=^#NU$n3ysDMGE z2ue4IAT1$X(nv^Kv~)~JEyJSYJpuhl6 z{(Jx1!&n6D`M=}xe+(=&BNDHpmi0R05_(C?hx`r{Hrz-^ua@?b^oHX% zkRu6aYy_JgGQd#!wGOTETv343B(dJh-8lEX27jb{Rky~D!d#Ibltlz6oQcxpkqfx* zV5%v>t+3>U6#RVzV6XuXqK3QPftjIIC^OxaX?i3wFUNwJHMhW|XPUYL_e2?*^2_rs zBrUu|?^na$s@fD`Us=%pG)w1oWNm;TIWG^C{LgVWBgef<)K30)HzW3^a*P8@)cO|( z8=E4lb_w~14<8~H;!dI-tmiW{CiSeB+iNp3`UgNRoxTNulyQzu_~i=ZQm%C3iDZ_Q+wyQoGwU)@kkC|bPI!xv_j&iq|`5xz#TMNCJQ&YkWJAQjSr>&}lkb@uRa=Au#j#qmzPFs$=$1g0Fz zQ1o`ptq?-V|GebGfFj2i0=WP)YV*IRq_5%$jzs2b ztbpC%qrL)ZkgL4-ChZ#+>Xwr)L#o>Z8gjM-0MM3FD}IX za=2>H5sUy<3AovX_9k8dVGtIN814He^ zE2!L;8y5$EJh(@~VpxQX)W9J)M+A9sI5ahn9L8TgS|h;The-Y%hf#0ddzfcb-^FD- zxI6fJXTmm4aCvc{lz=5BUxlu5tCgSO^;1;g7FiIRKWyvUS#-O9F8{#>v%#00?8j+B z#pcNvAi;+e>dR*8gUOhnm*48~WmZ&hgPy^tn0HT_*Y?*7QD>-?heAEYuei8at)I(G zuNxpA*1!uCO5BfV(?3&U6Zz^bjW(7=zB#fJY_E|InLEAqKOcgFd`R!3{9>;EJ&+Po4%x;qKtD(j0Q1H8OlISFEtVmvzTpp!xUX!wJ? z-dC?9KkmN?BkKQ%V;Kfp#9fomd~nI%X~Zigh~NRZuT_7`TLPNQz`H`>M zKb8_D*n~?3fq^e~HWp;X#KaQa zKkqTq(n{prZ>9yM&F;MxNc@x|erUnYlZ&HmEl-5OyWwk50^8hMXd3D0?3`?5VIf~u zoq6`sc-+RY!gA32jrm*40t2YL7Cy}*1YYJPCx?{(mP?OwLptCgM(}nPUVO8&PbWyWGJ-vbo$Gx>WjeyzLpL zwNOnm{{1waJ6M6FQAJ*PBq-YiOGt$s76|u@x_q#ahi8@#U(P+#s>J>GFRv4U;&(2y zZbi@Wn=vwJB3fsVZ>B+GEV&HFj$>G5Kc@wRk+w=tPft8j(hLEA0tQMrXZg0@+6X&` zngH~lN?brbi|-XAJ5m6*AD0#NY#w%@BCgugDo#|_k0&7ImT!w>Wx*q3A*Pdi(cGR? zrxW?;mm+3{p3qsQ`wT~32P&;aJF=AhJMy1I*o?*U&z`FjQ2q)>jCa3hXmUgexqrws zH-hzs(pgS-Fu*N%K08!-2R!CT2lcgU*YI|HD{s2SSk}6I{q#u`PcT|D1=?o&=#*39 z%O9tx3}1wwBdm;$u%v*6*g3ci{m2bq-$U66yOV@RYNpz)3k*d4oHiA?Wn2GL5%cof zS#P@4CWvY^{OhU5W^_u@;B6jBf%IVap>J8nh5tn=EJ!(!kh zI0cK?%0%UZP1ww?2EN66m#t;KV2~@+0(}vISIFTdqszzMNW}oH=$Wg$5M5F&ENyH= zf@SbcPEH0AjmeJ<2m_32*6Ytggs&7w|6^t*UFQ-oBOvg$FH!iCDzPh6Sy54d<6=lf zPA=?E#FFMUC@LZ%mRWLI+gr)=gPqVe@Dh(khKCnBlETA-3`0JeC&8;1;NRgQSKPGo_}u10$j zp4GUoMQJrul3n6lBW~Z%Id|j*dLs~D${e&y9Ga28|Mg!s(MYrhAEsu^2U7Qx>K!Pw z#JuqU1_ZH5FNr3_ZlhBUlAl&o5ErA$odR_ z{XGO;eKue}` zy`Z3=R*nGI^*zMuzLO3sxPw#-G;Wa=;y}%;b;LZf`FP>g0Qu>_(Z)dh^5~pnahCN_Bd7@-?S*+QYA6 z55NAYBMvRK7*y4YGCs0MHXm4@%`Cp!p$j{BG%qH>z_&+7V;uZtatt&9=k=G6MDew} zU{Yr-wfrH1^0UP&xSBoJ-Il224s%2T^GP;gbKOum8gt@N+P4UKf!l5dk75X zwx8M2*q!en&866QR&_#+M+huTpYd|8sMkU#!~Ap&<`?PC$;ap!6l^e)%NTN+tSIPf zYlOx`(;(Wj9d)^%gJ?#3uIY$t>bmR1Zja-iP?KReVjW5(!8$k(XdaebQLo|?)OiK_@|MTU&yxVg! zFpwQFtZ{9bDij+))o%i%mn=znE#-ytE?YU)RJw;Vuwzxqm^Y|AJQ~rVGC~WIE1hbC z?`4Sr9m{AeyJlY+NqY-#O^T-i>Mu{mKKnrm_1VH>`iT9LIsp#P*rNsS$WH7V%U4L) ze$gT5_20A4$rg^i;bfa!PzBvr%W%*8iM?8Ja}uh-JHeHQpFUcqe%!&%|FI!mAstP} zW&Q-L!c!+t`e$cnud~>RxGep_rb?^c1oK`Hm!8lSc(x`zJN*F3T+aui*9?Pt-wUX7 zruC^E6XKKr6s*W%w$J1&)Lzy;pIo@xjaZ<97tR2Rs=Otbge3AQR*Hg^VjMZHJ0djE zx1j26iarliC&^2kGPZfz3sqNn`-&aDh_s;M6Ii21Ba)fBoM8A%-A6rfB$o$|7^{`n zg0hrZL?td;dE+fnD%^8mz1{&sI!iYg(8B6?wCQKdG_ny5@OsA>Rl)xG3aQ2m@FuKp z+5mw=7RcD6AJj^%@AsD4B(JYQ<$?)}MJEH9kefEd+KH}uUQ$3Sy+Zt?%3&cE1YSh> z=L9(Gfn{?ausr}~N=xonKv)L{jpLT3UHT6Cm6Q|3{5qI@N^ym&h0zEZRdLpg&oB8r z9%}{u;ThHUrLw%8>5&6+i_)TLRDb*lX^eIqA#~+%c&ds5)sV#pAQtX)sPT~tuz$;Q zkVHCtj{f)Gun){BkY}5qRv&L_3GNQDRx@1k4^NZh(B-&nS#JT^VeG?gx}mmmt58mh#Pc~{*K5}Im1_mZW0@W?gRkb)cR#T9n@zpJ%;535x-VMkGV zfe;Re=6i@=%4o85E7QCbAaT&wIc|rx1^QRx3srxDP1zwJz%HtfeUgRt3!u-$S0eiLz+tV^E*)A^*^f z<=P@frx4qLHt%!(N^rRhFeb;w#w`7v!Pt)j948+Ty1#0An1!J~HC$Ddg|@a+2xT6N zjFw&5dNJ`vux1l`jbUXE@~)fFE1bQczehWDnDoP${@=Lz`ZVy~Z};7L{5P1d?n46# zTb@}jyALg(5iCEy#ueL-+4^{V!9X%qU=oBuqd~3o4aY@c>{s={Xc$;V6w9!jz6mYH zo-DNaTso3;{C@YX31ah@M<2E%kY=mmBrKl@RvoP!t>12ZHj{D#sS6JC10hh9uk%{c z(fx%_J5b@2Ph_pmS$mGqa$|ixct@-9T0BH`#yTW36duAPSdhJHkZ@aM+)=9Zgqn_o zv4-DTL>Z646YW@b@otSW?NVxp@s^mhIv(F@$2|;f{+~H19(L%Efr!U=yFhC1lcb7c z15KS>#xLdJdEX?5cmumg?}LlxjvG>cLMz*j!QlsYnuO8s>guW@uHaSGIW?P0v4{+6 z!Kl`IJVm1k&wZc_OnVpz$Q$Wx{N;^-F<;ZIa?_a~u8L#iVt zn!U(l8P6|!4_G!*G@h?sU07OO?f9|>5@ih#0jLN#ge59({he=tce3B!5xz>X&FxF?s>*9y)WtH3|p4 z!B=^7{u0MLC9z2bT{N(ZhAW&@%IOVqbi5kWa(=_yDj9qUNV_r5oFO2zReuW%C@YF@ z2Una9+Fe7TGGQ!qRXr;jzLzeGtJCLkSa66pUyUm?9azz%=A=(^*dyFl0CmmZg(9VA zZE6(W`N<5jwU-bmmKk9<-?DL?kl|hVF6qamqu)W_sG6TtDf|ls8Y0$<4xAQ0X5Ib& z9&gVrINm|~Xt%$|%a)92*@(ro#ahD1gqt8sXwaIJ0>B#{A&=#V2WV)k@l)so0XKn= z^bs7=>*>_6FL0Bm-`R6QBtvtxay4}Q2100H)}-9$VO|l`-a+K{kfLhe3h?3PR=2=p zB^iHdWiGOtxvg1doBHWJW5?x7qhA4Q2)uCZV^nGh5PIaOzX4NXaM*QiieNg3XL^I| zlauGGQ|HHx#y&5PbTACw(!9hSQSp15SLmYpk+@Tz1CEWW-?Hz2NM)Mv2dy$zs9H~n z$_Ts~VmleY)OXDxd!t8$dx88dHap?H* z<9(uM2{oX28K+%hc~kY+Zc{jua+2IdCAwB;XXj=>nP?uiM)wuMSYQ0Laz#)?cmv|<;id)0$XTT;Q#->Vwl2#w6*ZPd;y|?yzYAy{LO}cmkbk_?)McKTT#qB zt67IzZrqU)f~_vsrwUnE-_%@g!Xv`X%L0!JxEi6YaZFHW6z0T*AWelk9}b-GC8req z9Z)?hP_3RBgrg8F=a$h=Vk(~5u1&vvDQwdsL#0L%A{Xb zRJr8&MnH02cYQKEa!X$!7qr(t@bQ8DIdoA{RB)We=wH|m{_+b-Pax(s0}M$z=?H<| zI7Cgd-zx?Hko=6p8FZR_ z5#4jMs%liPugcy1;&me&H+ihxm6}u5GaJKp>ZepQ88PVOaJH%xsx7VgSdWw!tL-66 zGB2LEj%sa0t>422{vgI?l<~k)LsKL~%QQevDnlEBhGeCia*(pUxa7G${(*k$2yoNjJWHz_AO@_;Deg+Se*~#+P3^Lz^ zp;U=(3u!+lCJ4I&w#%T)3sOSD`~r~}Sk-AyFxUQ7RaNuJV3@*yA~rVpta^=*XRNZ`Qt!i(nNlN=--tA zrrHSamCQ{m*H9dyZMp{vIKCeo6oNS|n9t*FruOG?nbJB5ZJ$QY(M*1`*R#hVHynrpFK-Ae>4YPSL{CyoX;AkoWTxCK|EC^N7WZ9JcCP1#q{vNN3NOhDBh8PVE=e#5qe{AxjaCkh)aAW8xIeJohszmcgQ;HhKGl>zbLXG zeKLpxgqw!%AX0(_F)mRSS_cH8?C&D59z&LC*2AAmsdfc8^K65ub4$)jI~;&kmOR?p z-u@h;5eJsY38Z+CYwbNiQBVjql%DUgiepw zLd~9U_J%n;V>%L<=OBdoojG2z|6aI}m+%M4uMXRs2Iv(FP1F#wyeI|?pALsxR+h_% z%}NHmCZgGZh%*fFL(z#(=8$=s)6ScV3G2ROVCZtuPo5;nvsZfw#=EjqLg2=Yy$xc? z7(Vxnc^#$SQA@S!&qkmh4R|jRM#HyV(>%(jbrjKs0(jCUp7DvLXLV- zx2P@N0ft+=06TjdK_UO0acIV;glbeft9p&SU7Fi0j2*886o!YNup59oPjm!S1{>6^ zcHM4T6{dvk-Hn$CQfVrjXr7p@_VgnnxNZ@BPp-C|r&9&<$OnIhAj_gcAmM9JylhCC)MuNt)+9Y_yTZfCwu zsTw|W7ZXAJfpPzqaAIzb1#wp^(Y!V?0REhDZTgT)4gH5>r?o2|t3e?!i75ptZ|qQr zA0se%A(Ln^9C0`3Qu8NlVq3!drr$-DSLe-N$S@pI!{E8EAoS|5x=R1E|HcqA3*0Kz zL@^0N>5)`dOf(FHJ3~QRj>d|M6{-LZ*wHtfl!1A3S=}3$0Ac-|^uU~la(?R|O`aPi zntGOY2=sU~0WYpFZW~N9U03=Nbp16!0_zDaTdx$!A^EXh8Ws0xf_Ap6pqv$kSuQ;o zdNq)g;Ya?1DWWAztWYF0P}ti|y>l#o|Nd);3Rfm~enJNdv& zGb1nj$s3u2CLj%|5txti5;kg@j|9SN7m#Eontpj3C&vdN*^h(d;-TDCLTln+A;cz|1No7Xe~sL@@A+2jkgZz%8`l6e~R4qa6=tiRc8J!dQFocID^S ze(le>zjGXhLi+C%Ps_1)rBK|wTW@&CV@6D6BT#f><#;TPIQjj+rFt6HllkG(>fcsp zk5Y^z7~Blw86vX$pyyN;jAqLqX(yFF2Okc-m&pm?Bq4}2@D86lcw-XwnLu3x+(zrs|+|wZ(3`a8bAmEq!WoJLq zR++}K@4XdifZa~eT*fD@ZIvkuj$5Wop~#D07?ml!Oekc2=Vm=t!z_f0!xmRDzu zovDr;xg}E2V7LDAmlcZazwfJ%UxBH&-A;W@Q+M%wl+6?fm^bEgPvYW zaBuT&0K`tGHPlC-V)hak^@`miNLLv+;4brl#@1H%B`@tLeszb!N5Gc2?pCom{$*xd zP8-EZ-@nkHlxp$Q?k}J0aKGWh|4pEkAaeY@)_ouN3T1dOo$&&3(sk?KNH;Sj!tsKn z*qA^`Nh$H;yh(~;IaV=83!UY718x-P%4`3Ciood9RH|#H{Ajjf!jrAniH7KA^e|jO z&bYrQGiwC^Uuob@%5kws|j{7@{ z4L7HFB&iMWufZq6Q~Yzgx6CeGR1ydR)__=H+etIQR*~Php$&GB6}r0HUaLY5X{j#i z%Ki!ZsLcl_S%!L{#C#9JB(2ElaeKQbaFuVGxF z_;hD_@*Vfx%_XGdQ`~v~nU}(cwTOYV9q6B1qfu+So9J|Nm+bTg&os~)u@lq~6_CWHO zCjs{CV7WS6{p>f%Af&}^^evv?>!U8rELLs$pWbJ_hcAS%#-ImXqB~AO@xVN&>`3av zhQuXX9iKKEiXqH64w!r&5N2bsLfIf9^ADTBmj>;)YH=&>^NYZz55(09nB#jw&yH!4Q}7+em^x5X9@Ybo0LC( zDg%q7$oD`LWA4LLa4kCUL6EbW0G8eilT@kM*uJ6Zw4tGO5tg|BaT^%!-_-H;_Wt~P zugGG<&%xfJhpqH=LluWBHgUw0v3l9Efzmk%k*d?w(jI?AWblZI|3;Mh&ai+Ycg$n| zF_0d@qp$#{`v*tjp@ad_wlp_y-Yi>2m>OFE*9B>D*-?1F#99|P3hU8Y%sD2)_&|UE zHj%FoQHMjYKXwn-6E?OPK^`nzTwH4V`|mgp0RrL#GHWbtH0DT&5>nVEh`h;2pmtPd zHc;}t?3PesK0m)hQ{$gqy6d z4Vk}Oh3Zi>NTVVFrkpMV>TC{luy*f1y-6aT$Ezs-&4`#%^6_a=Qc@QDR7+D00f+Ra zoHxw@2f>D5$d%}h?rwWOR4nO!?`%i{jr9y`{E$@2km3dRm-I>^=PutcT5QtM8)}3m zu+}V{GCvOJIDp=Yxv1NQC@w(L8a6xCk-(9Q7;N|o@v*u8e*7Xme0&Ahfgh+&K?9ai z*tc(rI!*@)N+gA5({R;rHA^fLK#@Ws-*G=~c?%n^45Yz8W?C3Liw^N}d)e~Z8sXKe zSLd9dJ*|NII`sKgmmoEg7f`I^A$Ub4d9KuPDbdl<@j|gBvAX^JJr`afmlBKH3VM2& zB;4}5OzQSa{&I)%CCEj93vu?pZ`4CL5&3`3dSpEHNDnacE8MgXD0z?EqxeXZxjbK1%yHE$D3%+l-DiKx`!Z~R?zs>m{4 z`mclB-^(^FU?FP->(V!pqCFE&S=*Y7I^r6_RrL^Yh#58C( z=>GO641*^d;1Epue_h8B7l!OSEyAt}4N8>zyJ$1|Z_o!1-tu+U3ba`wX4;Hir1|tK zQGH;>Ac_E)8ibF70|Pr^-4|<4EqACWM7_mKlgq0H7bGswp$JuV{c;izr+NW-74<$R z)UyCrvFZ&}ZcGOa;YmTN3}lpIS&d|QKSLo-%lLbkXK%d;(kDE!?Pf?I?)^r-`9EKK znga66h#1FFL_JdB?ejZX>EY0PM#x8iRrowQd_vVxP5Wp z;0f2f3BBzwAnhb_FszDtV}_m|Lx1YdK%-}C=n zWD7G6DJe6wL0cNtfEJC#@CWnBq7<^@ve+3=wgW}k?6nkmGj-TZToMvSsN3b+E?lQu z26?MSXvPFRBhfY}?uQ`N)Ez7GT1#s`z^TsdF`K|m_; z-~RmtB91Xk>y?;Vp|%&)Ayc`dse6_z)HIgKfmiY=zJTD~Vd9e=zakX|IOcjO*i zK>EN9ik^rZS;&6;!WIG1z}>l1od*^LI)pkJt1u-&<>x*~2C#v@zli}cH6;RNqydT- zTU%Qz1z8%xDmt0@Do>js$7$t(<_DKjuKO_WvA~C9dVCLrN*cpuuR(FML<-dkJZJ_* z%n#syK8vScc=S3y&W*70kf1nb>zk2fwI8)awvV zy@E1>Oc*d#JU(XojpcqLn8m=aruVPFduUTz0<~S}yG}QPK(0q5aU@ zuko|hZ+#tx5{16Mc|vymmdeq+M)2nE_Rk*w&t4;~08h=(58eFJYOvhYz)49?6v=~* zbP2@a(IeF4i`NXF-PXK!?_COaYRY#YCjv`3@HkV_yAB)>D}1M2;i&Y64>Vi);-CR#SXjHnU<#Xkl*c&cuhd*vQo>6)(O3T33 zv%*ehKVm+ZX~9YuUXtNIvXuS(Es=rsq*F)j8*4ZKZ3asS$Qyw&Wzp2F=dJ@~)@jss zFMWc~l#kig~;ryCqiO4wuD13NKs` zDYz#{&{yqw!u-))Iu8)oYlfmqVMJwRWnF!}r1M^z>{V$aqm&r>UxdfoPp5Dv*1Gjc zn0-GeroB!&^$^R|ay^686ujiZP^V7p+q;sDYxCu;a-TSld^Pz9CD;qrC-+GH``sDH zNtp1Pth({sZaLuednloUegPHuuI}&^C{X%heFLIrwIdp27UAxDTarw(^M5c-1ptj2 z!2*{2Z%z0ELyno4RXb-+dIH2N5@<8zpRTX0w8tVmMwkcuqG?$Uh#8Hzr%#`TTFyMr zfL4|^FGP?E)=3<*0uN7}duiGnIWsMLg_Id7J7l*+oxQ{FbtJjh7l#$x9#DJyKk+yQ z5|4W{5FD%*^vV#&2=KJsN)dFSz;KpJk=ga2SN4M46DoRB1Eu*~etfw)F#}njVa^py za9WmWqUEj`1nJ;%QXWfTXGDh#w8IM0I#VYgT?%#oJ)?&NVNNi01&Pkl$=+ww0y(c4 zpvAfaTYoEQ=+`%RS1)h148o6ML<9bO2moOGEjmzZ>xCLiTE@>{=||=R^nWTgbQ5KN zUb>-yX1?g2KJcUUu=Nho>Ko8n#GifszXydQrHZtQBHVW5;;|)G!w0+<^TR7^>%ja5 zDLx3DXFL?fI-!_0wOwy(jkjEhvkTH6rWw1iU1Mx3lD)@xN%QT zf=c(BwM2OF4G0@`nd4qV{O{C{`HZWr`wjqcU>$VwwO4Lq7hiE7J6pQ3G0eAH{dkRf zILF{~KLO*B)2KcP2VtJmSa76OX&)vKwuTUlPBO^(;LVU1V(bAgn&D1ShD8*_fekRl zLdDr>5^_yyEXWg-Ktnlm@colH#*r)u$iAr+VsA)Ce<6(=h5`_F>Yv~42GVgZ;dT6X zl$Kg`Rd?DsM7jJb9&0;`>F`pVzq$vkD$zlJ?|E#lzYb(1X3?UCQuw#|)s+=|1qFq< zErgrdK7epum_6g;$$9OjUy3Rr**nC~7t+7oyNxe+*IWC7fR;nC`eci;B|@%El4E~3 z$#wKl{$Ft%Ip!Qd55*Lm=Z7lGp}^8s8>7UB)L>QPbR)yW@LHg?)AiN&zem*=-~gxt*n*x;6wrjc;C-L%Pt34(6L0dKJD;swXS}YojrQ%4c=Dlc}@Iw!3z^ovPy#hbvKI zmx*y+6BOcZWwo5^oR1N7EdzS=Rn3(PYe_)zY=-+?xct{i8FgpHsAg()rrcK{Mk^wu z2RcOx_xsu_G%_z=Kzi}IZ@dezVUh_a098Bdeq&UF z(c!Y_fVkz;RSH|qymps%O|0d z-WLbGaxa0men-Xv-a%V}=&8))KlMYd9^!T`=EvNpDo@+1=4|LH&vLF4VdDgSH@eOh z2or&WDrrpu6LY(J4E;znEz&Rsowyhe*QJ z0h<-qQVehV_w1Eb8-GfuW~a4YMMeF9^0lR{ZHq0lIX@dvk(PAL_4SY8MO>rE<9W&usbFj#m8bM>e_=Tml44En#nX@cAH!Il35 zlId=gIY_$51G%I(b=1h}ZnB>_Tpb|}Ss=jT z*?2a9J6qb=sLW`ckvNWZPe&g{qx<^#Nh=Qwy_3cVO=7N@nnLQ205o0$+Vlm&Ow4}! z=8jOcj)3&jeAnbZgO~>q7BOo^L`fgcJpfJ@p}3t&O;oI&p#gf|f#1AWU!B09kEdR& zBi0)MYKgQQz`)+HOTXT=2Vmmk*zT6d%ujNfR2$D}{dyBMHU8n%b<|fP_sseYTsoWn zixX}K2ZOqNisbbe6_u5_Q2o^Y;Bqlrw=&d=bbWn2MXNAvR-PVTX+I#>jy-|>X_x=^$D)1Z)^uj9>;p8hqQNm58~(IA{sTl zR=dCwwN**~o9W>~3v|5`fue$s=0sM`uC~Bn{TSubCHp&)rMM0b4%cD4y)*awn$Fs~ zV}4$_esy!B8xv6EF|kzhPCACcPK9)LlEUR_Oc*tMQ(J!Z9_<5pGJKbH<_gJRIjgNv zY@+JPfUDMwoLRE}dVSRR`d0jUc!x_rc&x(5IkCVd5r7V^I)V8+f-g(ye=gsOTVD~i5yFg7q)c{*Kuc^1p%w@@rZv* zh>JIVtrM?;z3Ge<%YP*eUHv0tV<*y+!t}M0?i0QJy|8#}BOB+^?iKJoPa*wHW3iAw z1#{`6m;*c8+n;KRM2>?Zt|5%`;*BBcPCkYais|eA5RZ6){yaZFKZt45ivGz8Z_ioE z&2^lf4fLf`P*ra1&ZQ!K(AqLZP%3!z{Nd`r-TgrN-_!R%Gr*iGxCDhhsg0&lq3ur}KeD;+xj=RNdgoYRP!RMyhs>8;dDGB3 zXJT*<2lb9Rm~)_4E0Ba!h9<4VrWF#X%*oCR!Ds{x{vIXi;q)y;qNOFj!JOTMZsa^X zt@Pkbkmjzq&|9{3{nbmE-y4O2v}8HS=M9IQ8Ux;XX{B^^@W;krCGo{1eny0On%S*4DnB zOMO?_11*ZcaeI}42r3!RgM))3t{D1KPC_~P0ejjy8H^JU2Bye`NlxcaiNTNO$#Jic zo%<8l-|%I=H~$nAPP#t?J!Ge{`fe{QEDSrcn?dew-`Wp%w`SpADSTGfimvdIqB;GQK0Ti1hvs8 zxp!TA3bwzc3Z_%_ZCoBABVqic4Fq3Zv6wsFj#tiOVTJ0%-MV#aq6nIPJ)rILX9SD& z6@ms%w9$_><6kb;lARC*6|o1;uYL{||JE4BxTV#RhLLPH6aUaGgTvV%5%qD15o=(A ztMHZS;p?4u;JS}o1>xhFIMA9)>jt!I2%gm5uc(<|K6Z9~3vl7`6!5qcK;WS_j~EUe zn}ayv;2)DeMT6kWr$nD^3lRTfQ2u#YV-zia9Lq?VoSGVa^qjh(FTb+5ghbO<$PefP zqHLOZfMQr-^UPBXw}*E@wYliy9|7NQLXkBC1EiNPUpDbeWw}}F?5Lrk5jwgKaAzUwiB@Rw8mhAVNOVTG%a88!aylLOn80r z>j{0?Ksd`CB7k&-!BZO;8NIq)Vk`7@blq0PiW2pI?xjZn$QI}*xL@~H@_8aq8+%`2 zMkXG^Xv6aj2>1jD#noiLuT+$j<3C3&)DfKwEuWc|l~IRE0FIkoSZ1DkXufaNZ2dim z%Pm&*;RM8I9oc$UU^IdV5ODHI)i0p|2rjPsD}JC^VDi?G%=xuynj$mD?r+ zpP{dOH{RE7*qDFzfA0UpC!d2dPC!MPLobrmQmQ21mutbZROyImAkW6iDG|tyb((+k zU*m9{b>!zyA1F8Y3c)}FKUfT)v{&HqGXS(gA3)H?0eD0pLSB|9tf#i;mvb`%s}E$) zlNxvKB-3RW$_op7FqbF@iYyzKk)(wi7y%$cQA`gBI_1IDgi?8t6O6e}v@1JqC zFD}*ig80(X(y{{hP%%H^MHBU+sIL!pUtQ}dx_fH%OrZYH*>kQo<#MO6%Rk^QJX&~B z-{0RaYAa3j7Gj_aHyqhW$;dd!?p!(tvQCtShK8X8#Q_0i*8Qd;molPGVB|3_!YH;z z_fN`~B_t$#{r#IvjDoH#6x*}xc4ez;)~D#-IkFK|r zF43cG|KXnrzeWQ?`3VpLf)%mjk^r<$`213g9J1Qov??hrZJdIZGf(<+2!WQ_(0y;0 z7c$5vNdMK(I|W9bAc^^oyCAw4+BN|UrtZ88;WUN(Kil*P4Jan{kie2P}Zz(W@uWT&81O&39r4FJT52Dk)*bCn0$kIanela5aT9$?v3}E7#(4ZGGjCjI7 zq^G75+FLHbptvj#KG#)xqSiM)4Jq_u^|d3V&z}!OYKC7m*y_zWGj~mp3+tw&1bN@W z@iS-6C}wC}bE=@XcpeZSi?m%ZJ zArMkqr&dcK2zenVd|g8W+EM)jmc_aId?y7=2%db6R+9dbXraTCdFPbCi4*2>Z+MTs zK@T)c#68RYAKdfJ<4PVlcz931-rWTYusQZzh}>eh0+>e-W#2Yu^6~Z_g$V_cVq)k} zDBUC(VX_bO8N{@n?&CM#=*rY6e{gmbk3YS>o{EhceXpj5 z-B`3dG{@xnId2Tcccp$(U$IXM3aDLEuq{3>?@M)=!0Vmgm8Kf8n`07)T!>ok=^GZ>-twF*QSXzy()3eS?Pb||MuPwCvDOpNr{ht2KmL9?6kPEf1f?W zj8#)zcKS>PS^Ptjr#&O;zSvG)J&HoLn?fSBZ^zgpN*Wvi5m|2485NiVJz^x4%9CGa zoi8dXf{E8Byw5gkByXOv&}3=<8qNC@^ow*pvvYEKfxy$Q3v^ttadWFTlbjKOD-Khd1QHNm4o+@u^<7<7_A}X-h@|Jc?@ywB_uocLSOuqo*bs6V?+Jlly*0~HA@$my81r}SwJd?W-qIocF^Vu2H5qO+L z2g$GJ0P3WOT^4e?0SbS~o`e@ek&qY>9Udpks0G8TOki?VyM&F&z-CrMsaDW+RwJ6< zT{lG3(4gG0nwwmhXz|TO5=v&;lZ+y5kti-eh>X{iF-;}3$ATgvePaPA`-*A|Le||l zW_W9Yasv{@M3^%J(Hk$=mGCZQ-t}G3$4KjuHN58h!DR~~`d!jyKWqqEQ?U`^E7wEC z%OK1A8H{m3=og1h#){qoX&UagAH9AQ*t5vVM07M&L=pVUguPJpsGD;UKiD4Bb%UMi zAji3UIT*S(egJWE6Zo3IzD*!_>+b{*cH~zeJ7OpHmz7Dtw45aXR(cy%$-F2bz3h%M zAVqnU4hC|p8?eo(c*?fSdoYr>vy|X27z+~|oS1r$0br)`J2wt5=ZsQq<`?lE26LTp zq2-+gtDmi8b?r@Fb2SDAr?JobM1|n4uB{#u5O@ZO+5C82O!VSF^Q9j@76|LXc##5+ zK^UI?kI_-IC4LPPWX@?1%y8b_-3`qmyK-KMR2L>_)QwTfgUz}B(ANACY;!%}Gw-Ag z-GJrs-7jmU??Iyr{R=X*(T7>%#NEE`8+gP+M*XMV7mq3E=%~o0FE)fUK)xJX`l7%=~{i=3x@6W4*L-Yk`9n(`|#wrz27Q5Y&m6Dq)ItA(0g$mF!p?&1lg z8Wu3A!lXq!!)?+bWq+EWIBNld(AQS&ufabTJlnj1Ixb#{k*TRD!xyHlGD<= zv+r-z)^Pw_p#GEH#BV~t5dBG*T@~54d9eq=M9VA_w&$VN3R$!{F;3~fVV5(eEtWCNGN^B zMF~1Uzy3V%p?I9vnE|PZelSo#3vnU~g&+#|6P7;>x`Ne1L%R2;pa%#*Jpnr9(boj= z!X#)=#|**vVp!q+C&9)E4AeFK>SHlED=xbi#w3EDWm|XKzW->Si^*haTH&%JGB0^G z!L)p{LgRa4$=YJV>}Xb&6$m*XV(_}?I*DSKsu>ze-b9}he+lG{2!1aGcB7@WwQ~1z zR4|qQw)l|Yg^L#(&tI#pgL=iXbkf+eFvKi2a4}hz@*|fm?d?AU=*n4aL`zx4|Crz^ z-7T3Vsd_>t{mv3A+Qj9uygGIiwO z;OLz&0hW<}>+M9QL1;E2JV`-8k)oa*yQ@XY4Ko(&Y`_c)!;8lSg`I#OFjvG6nW(_( zPB{-(-3myVym}czCLQ#JJ$WTMEP;p>-+vMwuQ9}yl1hFl*m~T)46&ukuH3sxnu`do zkmylj+6hN>?`1=Slv6!}mBBoaneLr>WPZ7LZyURv_LhjHRD;j;u`yh_vO+prGh*?X zpi9@QbMfg2Fm{`C`s;%)`FszfGrbo85f%qnWLg1yA9^!ljCns|d}=`pGqXULFWGQz zftPdd_lDjs%-6GaS`v(PoUaoffh_oIYC#Dr2K^%LaVuPzLe*H`KIW| z!%sCmAsZe&`*>COJG8dZs?(y@^fwZGrvMjr%4U=qW%CX%u5cN8t$PRJ6r`4T41F+T1OB+1Y z>+fYI$KtLdv#zc4Y(kQQ<#Sx51o0m0n9+i+Bv5V$@$>s=xt#Yq<>R2)tv2*W ztft(Oh#1X}7leq;XJll2gNkb}g8-fPX65>??{BS*mv(YyEzdVlY8o{D&15$!Qx(<1GUj~6H21(K1Dfa3|2efjORcGPLqTK0YN3qc5VlE3=pAMV&; zY&}KfxVw1`)aO0HOpk)U$@`=R?oKgPnZ|au2RAX@X!%cxLVAe~^WOHFDTtmD0-Rb4 zX8pc4z-t|8YS<8%NdipX7IXJ8E%4|Y8Mg`Eq4t>LR?1^M>jr04Z9lVy@f~u`tq&# zk)ChBlRO)^>L)?yAX0qJkJve2V+9DF4jw>J;J zj%MT2;ansO3gfmIaTP-!4ae$dX=!1z+qP9r(IRBkbMx!QB<^pJAIBVQc*AM@M91g+ z!yTt`%O7axz~7e_1}s6u_X8?OI1ZIKS0FULmI0mKCgnTb^;|pigZ$#j4*~wUaOqO> z6yzb^>FK6L{8l%iDq!vjB31EFXkf&LLai^*NR!FPFFkNPd&&Dn0I}Nbyxm!j-a@1R z^LHEe-{ZGi$ciVO?sgsh-GhC?hJ6~V)kcMgo^n_SJOMpr^47L69%B)1yPU+h0X(uK z3@)>t_>yDdwid)X-)_mtu{kZ@+e$79l$8t~S@**Bw;jSbHMW|0$JZ|?{P{$2{-S|%PJs2Y_tUbODB*j$&Z;5pw zC&UFP*Tg{m{Ic}y#Cfuh?kdSiuYAVR)N+(p$j;fge3C=0bN^a6NrBmN`gPAH{l6RY zqRiu$-bTV1PbwuOFl0f6H1U~eh}xm}o2E}SHOE28qND3&6fwqf1wu;BefahA6uEyU zK6aM)PkVC)3&FYhU`ZJV4~YJ6%GqAuefrdDYR{F2h{@YYHuB@ZM>I$_Uvawdpy^gc z)Xg0a2{|3$AG$LG+GrYO7COOkE3gs+z%C(bk_rtdEaXfBFEpMDKr4bn;Vis=eF3Hz zJ%M(GieuF+Epn_B%P?a&gf`-?9Qez#Xb5JDwAY18jT(j{vAcm+i;wSFtS3GJ*ok_T z%9w@=vw@Uj^$!Jko*zZnpxmMj%jR{%dUa@x4tGeHA46jxE9R${CMw}QwmRF3541CR z5sI?&pyd+k1FuZk6B086Xuo0SSGsWd;zb6bY_)Wv=$IIr>obcvY|&N@KHZ;u{BMXU zmD5`&kkYQNTmIg2uImPwwwgLB$?@)Oh^N@tpXf=QUS(mn6lIVPwqQ0`g29M2P;7*r zvE>jjN{JvDw2XFQLcsqg)N6gArat67a}Ag8 ziTN5@2?$&uxy0mOvlD#rX{_tcWbJLivZRs{eZaWEZCHiMZyCmoR&ubi%3D>GXrv%G z(zk@CTI*IIkm!5Yy}wqMJ`UD9+G_r_`+J2HL-{cFBnwY?fI(8l z!AVM?XyMWD=ln+>q^(Rstj6>gMnhxS4n4`=3u2TD*ihl-I2-3-1VE0y`Fz2JZ2#p5 z%VWa6B#)Oui19b2G{*E5>8WL{Zn6RBR39L{t{*P35C~Ct0?IlHGAq`0N{TU#H)S9a zqY%t<9;mXz=I1i=cv@Jft+mS^O>g#Gh0!d#^Brayx6upg!n4@KqeFV`jrC{FoK1*R z%+UFr|1}5F``IB0@2+y&DLl}jcmh%?)V%Vxmd_zmy|E7c;jiAj`Sj(>S!AlBcbAl) z6VNjtF^(WU2Icj}WT3eF0GaC{1M7K!H?K31fA|A>>h;tCzSyB6A|m5EqVhpMMZL*a z+i1ckGD)s`fT7_HC+dFxuSe5Cj}%=E+5eMp;-gidQ`2>nJ{ZD*+cd=Ub%5sY-Ut(8 zD9=!XO#Pjn-rlLvh*umK%g;Qrv#-`}Wd9;!8}%KN;G0G{|t?-*Y0lH zK9dxS*Y(1(WLEtpYEZ6xYGr$_FF_kPOv+`hYm7zA8st~->-xMgi8~;+HrOt+ONpry zS)A?r1FiJrtX!wDu~nEE_@)A|&jHmO8KY7+2HpGBK<+RwF?s!Cb^o0bi$dfX(_d%Q zk%9|`CH+kO*l|b?)-hKXhOfK{)5)P?mBU@Y^&4*Pjr`&hj<&H-@BU|4N%#J*sT$)i zBpTBV&X)G&Rsx5Y1TMp`*Kl?0<^r$j9sS+E*MveFMB+`UC}?1=jdefH3bHZ9xt1ri(9yzk#@C`31<6Zo*GxCkO~* z5cZrU1VR8mu(*q<5l2S!{EATPkQmjWoiYuUp)D_Wg11pFQ?Chdsvkt~J-p zXFku~^Ov?O3tG&FkfujLVmm6aPLl;Zfh>)JV`z1!oNV3GiS?(}X?z)4B^C}&_?JzrSUr%4K$tCi2uiXu^-FySq zhxL3^qcK!uAo#)!l$|I91Oy?f-;NIV3nJL{WrbX)HGt>_+TvpSXkuU zoncW5Qtp&tw!ckBU0McdaS?Jh{OzET19LKf2v*^9DoN^}XGOP-=mL}E9TNzWtq+hdb4T=SXPRFYa3O}Ea?vgv2U-Qxs0F8}5 z#J35EXqRK*hhG3~#?+eZYS1 zB4l(Iwj{hf`nbgbOqjpXHAwB6Dyed{e_5wWc!t{$SBc{ViCjxr`S@NW^}2|dqa#UC zp?`THUrJkIOT~|U=T*+^lp^qAh&G5=c{mQi>0nknwJJ>dHNI|t1O3~dt36%gjVDr6 zlLb{=X0?|G@(T*0p=3=5sAhR{1a*eA4Jq^p?j8G1 zH0o@>e4HxJZG0qZL*M?Eww;D7*I`LXNkDQkwUw3C=eJFe(}dK!tOVFBG1x(_cj&W@ zrbaCKuOe5VStoXe2$iUUJ5e%amJImQ@C^Moq)DmKfCy z3{XLf;_~UUFe-!R{^V6F#=#b~;m6chMY*XN^eMeB{pG4XzCI=(&-yDgo#%nj^pV;T z{Xd@9PZef}1}tjSalZz8Q&=b(x0$f>V+l0$cNr^PXF~f<2<7b~WJz_PGd3kJn`qnp z&L9FoX#w2%?pNdVG+Ncl%7&FD9J#8wXRKdU^do8|#MR5?@o>-ZO=NxBT>63o3w#by zbC>YfP||H)=?QxrR_Qr>>7@g-1k&JHgBU0mmRTmT#<+IT%*+g_dJ#^hPN<1g$8X)e z%RVgoU>~|~8ldT9J?LyzQP|IFT3cy@QylFRaIS7kLmePf#qdP ze9Rd8#-k_AtfX(lTNch+20e#;=x*n?N8gDBZ3nU+F;=_{H!-)0FxpzY*kJy#=;2fD zGmF#Hfv_Sq4p{fFaKh|6URC0*ZCNmyy50Md5a9Qjg z+sjYpttHCrPx{h`hs?cKq?92s36EN83+%@ebCOP4_|l_qwibX@=Dja?Fj}jSJ-3tE z^`_cvf2;rDrFXX;qd2?OL)Q)=R|(0~o~G9iEL|Q1_vv(DAq92g9T-IatfKwJImRX??m@N2^tHCSTH@fxkBygDLaHbR#BMMcCgape zXBCYO2~qc2URVf&#h{yRO3PA55s}~evUFeRy)JwmvnJcJC7d(yEuo`>RV!EdaiJQG zupi^#+gA5A4-YqLB9ze>!YL@JX|)S7rD-@nlci>cS60r2(Vlt9O9BNmZ76}Bo?a#} zs}{Zg5zbR14I6nq=V#HN4irO!osKAQWfz%}pi0XGPx3W3d)5yHv(m@l7T3326%Es` zMOLl;;m1|(KPkEhBP1Cq_Os9bdM7_m;T1W!)ZR1(=3i&?z6Uk)NVKzcGMDe|aR;g|?69hN#gU;_KjX7CKB{iI>>j-OYfq zk!sY^uTsn~XVoz^6~a_+exTga09B_y&i|YO0uV?ko^AWToB|n~f>s(0GhhXg|LFY& zDliJv!z%K%Gti<5g!nzJDq3#S(uzCVUsN_uZxh|!|9)|tM6}KFJpHM^NBl)dGWAup1O4wN z8}ii^kczqt3#+xmED(7NG1};`1aqH^OYfPLFC=-K>FqCgu$OOGARFm^kovqokkjyx zl?^!P`Sj^Dq|5%*)!xrNiRC^sV&K(}mfCX6gqTfEPE7S}_4dwn*GTAnU&Lw%K;0}! zuS%6{TA1%4A|g8l^@Jjc!@_)PgFIjldkrd{1qgd>;MEu$jb&wUDdQSjnqb~=WW2_0 z<6n{Uvb*f6q%bM35(m>OA4B~JUe7J7vdT(EadGj>`7jZI$znODU#B9u&#MvMxGZTJ zLSV8xg#_W7Pmwtyv{9$eQl1wv{P-l?Z@BV$0xzWUFt};x>QIgQAn+>~{7TN#(UF|u zUR)i?uS)k1yBR=AL2Gf2_G6doFN@O6R0e@+yJ zM9aeIeRyE`#xX1z3mdm_j$UT9zd>fLiuEozy!$NqH+LTiy4nO`zv$!9@!QufXd^ro z6x1bj{$X05Ro96PK`TYR#P1}fPo2`A5m{?}#c$9fZ<(F`)OX$RM&}}o91t30gmfzR z_RX6CAf{si5^lFa$LwwH$0}B7e-a3&azKW6ITe%@NqvrfxJG&e8kXOi9raC{pu+FT zr8mMRC%^L_lW~wmI!N^$a{o1%0VM5Ml2T}o`DHSF=(6O-(+pbUYk=c1fmGA|NzndN zzYZ+OsNh8l1N4E2nwq0_@pB&WLLUglsU1o9MrkwzPriwco>-d-T;fW;(9qSLC2-Sz z@)MKQjUrhZ#tLF;W+!VQLB4m3D#_}vT$V^C*~m-7?``sYBfXYHewrrSb;WFKe4oZv zCNoZ)CyKJG9YwR26WvVa2k!Js>o{ocMIfjOXzUd|^R5rT8c1M3=AM!agk)sQD=81W z5UCiLvBt?SiSKX9^uM~nZm9#o_cYeZM=BM+cYlBQD=70TwNg$o!xjJSVMw}=8Gz-e zh>85Mt(+reHK;fbOB@MP@8BgN5bAd}99(K#Uc--Fm=8EI+9XkBZ?3avc6Iv)KC@+pe|8%72hET*~ z5rHpmZB0w3_B`CG^Sc%Lw!Y)E*lK&PZS3~B5g%kIRa4+`Of_(qKIi4{`k=l%Anbm0 z_=8n57xy{vGMRfo_bdP)HIFxhp^)pUssly<4WN{Z4}_3|4+FJGrq!)JqcxB5OYu8< zxw&?FrT75yzHMcF>KHKQhq~fZopy``Kn|cp2`p#8S@P3^$g;@H9vaE)5l#{D+PgN;TJ-Xn`jyN z6BG^{9Lk1#b^4bB#TYKT8&9bOvfvf^Ut%!jySvYLrtDCjXmEFmvvZBItWx@jo+++fR{J+eQ^H$N$<yE*+cn3&?NeDtGTr{S*n>~Gf#SgZPWLuhj+zd(HwluNLP*GEw z0OiB8zVwSh8Y`of!4GU~LX_voc*3S|^mOTKbC~v`DEtdB2o7(zx098!oI1PLBePgD z@j}P!=-I+EqY=S|{jR2y08n^2*Uz&K+oa)~FS*py{kUy{MKoc;@{>-K`HCbgc_o`F zxH?L=3tvzc-t1;=>|;kIc?oX{1yI%(cP?vrH$tZ|^yaZ{Q?a ze&Mo?%$mHLTb`eGRf50pDf4O(0Pu4P5&U@TmohO0L z?n#6sfPWw0N3cC*Aev=I1s@%WnmM)$uyFo27=8KU<8dru=V6p%eAhH{r^4>ty+rmA8NRx3#dp``}Qh?VK+%h*lm@LM)JVuVr{>|;lXYp zfc!#C^#FiLw~yX8e-Bl|FKmLhm*|6>h)3CQeINfoW<_+aR+`$I+cjy_QJBP3k!fck|M z9tV8>Z9CpQr0@btaMsIQVt~}`#sF>b-p=~x>P|J?5v^bD& zYwTy_vMd`eX#I)w>e;3x(~RB?oAHF%VAYu)kI9<65{u^bjI>#*eUE4$Fg%o74$T7M zBgj0n@@+!hk>}nR$TZP`-IfLUD*NzIaYZ+)t*u*G867vLGSfBx!yg*A=ek~Uznd(+ zj3k_BA8#FBVY)QUX{7iT{W`>cY~;T$o{kZD@*!li#|IQcjG7r<3{EPhmIhP7_~{@#0It;H4~BzCYW0oA2Mp{FMn2FAk|T6nN7A`PQY{x^5k)d}~u z7IIi8t}PFY6x~u<>@VdRw*PW{XvB8-S|y@WZrl8i&+{wtD|=T?bD1?J2y9~a^f8u5 znjDQ?>tzVgFf(7iF3yb2^iMc+bK4g@<-2{>aDSIAmH-D&4s!8{Z`ilm>N1omoBDv& z@Dk(`0##p=G;_zG2}m0SyF8pW7{+GSkvM(%8H(7hL5kKy&ZMQ$1BVoYJT(a)&c8Gc zuV#E<;bv6f<>w{^6l9kk-$3@}OwG*37Z-6gHK7!BM1|r&(jQ8a4CocG$H8WpKdfRu zwpz<9efki&@m^maI6;nT{zunqU?Wyg3TEeX#KCfC2=C&>S= z{sR8|OIxe)@qyh|9D_Qz4*0I(WC0qjK0lM6F-@5Of06fl8r>QEY;6sI z{Bdbv%S(lPe9sKuu%Ee-C=Y;JDAPz@gsXl-AV?L(MC5e`yjBzp#9=d=-#1BHdzm=@-P@>%$&AuwRNTb0e<31JG3gPAvugSf|1tXyBEUT!<1jLHF z$+sa!^z+=WE&I63%F3R-EOwk#b>|DMXznqrCiGcJy&|04`%1&>(94;tLHH|dJ#AUt zo8dqHDs?&n#Mcu%v9gK(kLQaaf<)3nHr(+zC3?^156DR*qh|lGzqglZ{O;bb0Tn;% z>ULAO@Zkp@%$eRbz-dY={^EkaWT3x6`XdK{s9~ ziWq0xqL#1>2G53*w`?j8?Orr!TB_C>ZfNx#X{!?b!sZt_di_eD&-$lx-52+uGQa$m zliP|guoTAo9ZDoa9O$39kpc`^dSF_H@@f?}9G>5jI7;&k>Rg{@FT{QMa;(HhqMd!s zTaByhD@6b}f{>3ne>ehU{7NIzJ;eN9N05a$f@c)7vk#@KSQXpyntn|jr^@Oe1LJjB z)QJ~|&SEh5+gUdsKm&Yb<8A#yTDvlor&9!E{B}1=Sj9Bof7VNkqHWndi9ynG>J<9; z&X*Svuc76eDDdm`+LHQ1Z>+5M$gzEyeHz+DU7{#PTiF`Qr)Ey(8`VZZSjwqrf|gynQX)5@ z>*^S|ZGP_6rP5JT2v+PE!0${4L~N7^s2l~7G=fQR3MGHm)n377Qy zG~bEg@dh{FS$tE}lO~X=PMS6u57tOni8=YzBvD@CHVo){ZNl&Tp;PjH&%m2J8^*0+ zF|@_e=-0J}_f{i-T$KC{W&c2Zi87@Q!1&jlmvQY2rS%vk11@Z92O4f1Jgb2c|LYAwVc~UG!&(8UnZ5fPsR@HYd4LL}YVdXZ-AzEQatblk z*$2cQt$+D!Cw*h6ERZdoHg3p`?tx6u!p`y|N%T)Vgk!V8E=}Q#qU=}fV3wYXT*FZHBlE>ZOG-8pxKA zIw0`J!Hduir{2GR5?0{4pgSXK?f8K(aPmkcHNv$e`e_AITrAUgnL`ezm#@g3*c6N5my}mH4IWSMp@52V+N}?S zbc4QC*?9(j7B|CG>MGHu{xhVnF1$reoUYLd?i`P-H^+eHKnMlP5l>dgL;tGB?&$iCh?h%Dd!Cbq@#sG*B0U0fTNBR-UM_8X)BM665n*op z2O}exqCWaAj%sI`%s<8skH{DdIQTiC zN`|RD+1V=z0W0C;ynF%;ZNx0A29wSFt#{MBgSZlTEVb*ed>s<@Bx4yKo@NX+7$gP) z>KyEWt%blw)bCTtWj;Sd5jtfzVOVeO?(PN{inh2GfD55fPL`XS>qbixRREcg@g=@A z@MT*|112Bx4U$~i?%G${s*^}2JK$vy74l>B?FANAsqHGy#tjl6;x?QPYHIIZmG$QV zfji;wQ%E}eKcfStKs{TLC?0D9Uj$e^KAwIuXL|TjnO!8g|@4to%GR#usC`LK$|R z=I4h*hdzk@r)I`S|GpX5PTWyo-YIWf-(<8$M#kzob^;fNM3KMKV$F1iMSqT|m%G|q zEaIy0_W1V7q;9QGNOZ)*7O_{lCqHybX^)%RSH7)AO(OUmVEzLd{2h<|P^pk-C$B^K zdwP$DS#tLadlPrf%4luy+(`RH{~>O>irPm(C$CCol`2ArqmoXR((N4_GUnDCH&y*1pJ8=I-wz#+?VEr(DV(Zx> zx9>WK1l&?SEPXG4MVt(pSDJ=MsP>tIj);h^bcfC?QQaMrB!mztm#&e9Kzh< z$K!{bp+yrDem4W>LMaRzf*Ggk(F0YkG%fJ}FHWUd%hZ|hfj1fs8#C8BgIWE2Kjjf; z9`37kunFIeIZ&s`eBrfoA0q@0SGI=RKt0{}=-Om;3P1V^K5ath;O1f|jK80?-?H~i zsF85{UG+l5!G;82_QQXRLTF?{Eb1UXb$q2244|Rx7E=FW3PB!l-uxUN_g=jC9B zJdAkk%~KE9j#M%}S(fdxfc)|dditIHW;|JW+4mxC z!($kDQ~^ohWVh~wCvn+q6NEO`MIKE|G)On?O^S(_+!Sl!oQ_Mx-}?T&5lVLYk&PZI zJZiy*216Vmi`;unQq5nSC1#*g)Aw+f1!;`liN+*|CNOBp%DiSuaz>m2y>_3wr|`{Y z9g9H)-KQSSTV;NbfQh}Q`AzrVxEzx7x)#XIJNht=&-af9 z!UnVCCp@^v?$1dMiS$K`w(ERI9{BkDW$m}`#MxrlP*z%^*KP%37nzkqlvl0tKxZ^F z+i~;EGJ~mB+2GKp(=A8)1Z2IvNqRD8G2B6eWu*mph~&y((Ln8l=siviI*OiGoDa}%f4XQt?Y5kl13+=4^v3DYu=&?I2K0c1mF0N3NB~gKeFEJ8FXHUL#lySa=>B7!$;Pmjo96@}BOu6G z9nxy;==boc9^N9KhUTQu(XHxx?0ik@^hAZL-*JM2S3J*UXFU>1PdaJ7#fo>*yP9)0 zPWxntV--|Yz&#+`YDvcw9m}MIU=d))UCwZNqJ}L-HXRBekfBkDZ2>%FAWX{5_1Nb= zvsFO9PiB1byfObo%p{@yEQhS?t}7rJe@GqCE$lir1_jWm z&U3T2_7TeMW$H-nLdbYqLj};`f4rPu{~C#aF|w*~VF&-`1;Qc; zY(&$G%5X$O3N#LL@4JSf39hKb66+5mn;Zg(kTS|$C z8=6FfD?gT(ml53DWBCbJqwc0^m^|Oc&6#32F@*R}kTJw+$jwz%Ah^~V|C zg}zedV>(LM*E)U!$L)qeq}?#s!MgoxZQ}hfYUchjR3_I1=V6Z?m6q+^$6@v%0~_*w zaF{drXIM*hmjHJJMpS52Leq*r))O}&gQ^fJJgO;7g!Xw&^U}DXDe6QN4hWJ2 z&5^wnrx~q@9PQ1&E>1#C9S&fKral1EXTka(tJd?+3fm5w3)f#77NQE}8y$^S1=PFX zXlgKR$|ce2uCius1#A;MeO$yqL!ElXbAiPmF!^(FS?{b$&)=!_0qG5*29 zEeh@kiILN{-pBxw_r<8l;O52Ei!KZSKbM4(D1E2}>uf(##mnF=Esm9#oK*hsuvJ;- zl@#-0FPGcaw{3bg35jdF`zz-ieGrxZ0T1Hg!Li@vPJG-|0{8_P25iHC@ zFLX6E%9hIUc~&S~9w?nK9a*XB@-2v;D4_wn8|pi<*9 zHJvVPLt^(zmpGG9KO!$#D9g;0@5v`~?Fh>IOIT-(Zd6v7x`>8PoF9MVv3VB(c=9{t zUCrUO?B&$a)y*mUT#P~R+Oi3|$fx%_+N=wt+8pu!iw{N!;oKK4K9e)3@L`9xZ$j^WDyu7n7uQW)Y5lFN?-ETV$6 zZs}l8rPMu9N?f(RMDF6q!Etc7ccGn=^V;ckkMEd9TF>Zch4=-V3ln)B@B}ZL6VlQ~ z=V?A|(}x~AE-`UjG-}P}+Pl3wJtU5eYnk^eS)J6*;O8h!Za~AUv0Hcfr~Mwm{l{iz_ZP6Qj(4_^c4!7Rb@(}?R7(ECw> zcwjS;4uKV^)sp_tP61-X>kq-WH$KnLnE&eEiShup3=@{Q;=N05ccUWozPmr{Pm(Bd z|7u#X(Ju2FpJ2A`k72)h6ohBL-zhb{(J<4gkY+#WfP0>S0Tl|lc|$3v6bH$;>N(WZ zn)tdkG(xT~)N`lqlw9Zd3}QHZES$m=`$9Id05bP#@Be(wWdHx)IVq$Xn(i@;A0DyhFotwsI?yx~k zDkj*ba4t5djLK8OXbcP-zxZP>?BR#S0rZ}L@b;^NEpZ)Bh;|Rky+qyZJ;BQt;rL8E za~ns+efdi2%4wG+D)HKV)sAj~^Rm!6Oi#4Cn6wQ*AW27gNsGQ>mayD4nmJgVxx}p> zv!OebuT&sA^Y5;g(+$MTy$>Hr{En~3z8#u2Fdd@cI{BO92nD6Pwfs^bwj1cZ#m)hB z*y{FnUtJjPW&adn%+(E<%84fWu&Snh_(|+vUM1hXq)=+zP$KC)wIQdJ&|ml~dU`9Zi~!=@o!O4p9M>=t)l%vri!G)#Gi560^mycVA75CTPQO@D z;ym-5-XF^343OalT-@Eq93b+05@_8oJJPVI!y*6(*+m20__J(o?gL=-vI%;NZ2ntR zdotEH$V``cJrR9p(j0-?)bph^)3RbNmHTMqi8!Upa79iNNu8H7>^De&X|-SxbVj0kIB;{#aH6h_xg-Td#Z!*Gq#Bw16(KdR}{x7A>Tq;Z$#Z)5?I;|s;sQM z(g z;xtEy(C^Yy*S@hFFZHQz;|oH^PM-?G<85V>iasty@yVPQ(x-A&@Kn!nz zOq|$%f2);Z=F5w$&%Lkmnu*CN#BD}t_-sepMC6*IgR6^+O=}!%piz~zbFj_^KiB7HG8mi^POLpG9JH+5G{B5c1ue`N zDPJGZ)TIE7*xk@4S7TUQm&f{fYUwzIb=I5!*4(IYrJ<{z0&1T1yo!&>Sxloi=Ur?Z zEXROD2n&$WiGu<}yWBN_`te+VX=Q@s!jwVmZonukSM+OGbIQUo@+{MTyF3|o_oN6cYUzzIU( z!OXnw4o&gc#!x)GrVp3n2ptZ^vA-{c3t<%yoaErRChUsuaq86Nnc^~oKBL0+wBHHg z?KCj;H!CT;jQ=rpKP_a~%AtBP?%2W5okWEejV#R3u0fyMp)doYgxE_p$iEG@}i#mC1lsvEwP7sIX8nrpXe$-{F{XiJ+a z<@L->%gHu6D(q6#RdQDeZ||>f3~-fh-1tr@gfB?NS*5)#Ny#&d4ut!W5OJTMV^}`* z3D6BBM;)!ZFOyKv`I*&$qAX^a!46)5&N6g> zf1UL0MC4Y!dGS*J_f~q5Td`C{Cq5pA!mR*71EE}gTNd>5fv?Q#RHhv}dWp8N9moy4 z?3F0L_D++0bhyzuuiE=Y9#34A)p$|p&goN~sZW;8;?%@lm(KvEDS!P3^9;fo2IOh+ z2Kg66@>3-vKeR+Mil4v6O-w}-mENV^&qC5mo%Be$iY27G>V}Zlr=lF@9+O3VRyyt| zkAt1UwhkbwKt`Xl^=BQG+%=^2S4q;;%TmgGwY9Z@s)=#!udM%;T0PL zgiVvFCovc%y0fm8+Gvz=U*XgX08x$cVymQ-L_PaTH*QEqs|;VC$dvwJCPPw1o-9N# z^W}MtFxU5m>u#0h^gxyTh1X@cGV6T+79n|<`wv=AS5ynlA4m2F0x!HrLn-!C$-XCM zo(pKBdBB-*b?0l5`O}b0xjYi4wwiz#pM;lzR$p@-@KW5jGCPd!%u5<=A974A|1h+) z=`HSYaA4lCo7%bU-ZA9aQN6MuA>nytC zihEY{8XyXLhFtZuLqr^#G0ToBZiO!%ED3$}od|fyrg!ZMIX7pyEd0{FK18~EKQ_tiN3*^_Ci;H&2;_y$zV}@zrfQVN*Inqrnvb0y2Fn-4aSEwsVvbq zS#_^ET(D;U`t3_x%xhke?XMQ=ePSyVjJ-+SD*$F*n7eS^*JS)sd69du2@NeZ2R#wd z=~RKIH=pZhI0fyT!K1#S=vJokj+#ZSZMRcO$UL#uc{!!fOZM;}c6!8j~1HmSapONp6>+DQ8^JoQxjN2Cem#aNm zQ+yk2bJ(>L3bq$7_t@nd)^OrslPA<3Jy~-e8Y*9Rd!dEDoguIfSgGs12V#y@U&A09 zdH@N3Xa`zKs`ZylIet*OFW+0~=a-ki5;)P6V^wJSsYro<&3Dv$UKf85n-EzbZ3AeV zT-vpmeo(t$01*tl7$W`%WAaDB_L&fhI`5ePdxryvk%~2L^p)IkuxZ8(zr~165_6i? zm-9hWn8;@}ULGg&HWHDel{lUC5=)jq<*m!S`@FwC5}2d?$3W_m#%n)?=pV%*!ZWBt zRg`D;lQe#6VYvb6e5Hc>{4s^L__@{H*)%0UZ*qAYO~t8Y!_pwl0Q)clJO#XLAw07xKoG4xiiN|Iru7>FFztl;6q!_Qzpx(Gk0ia z50?gWWHuKrfAcQ(t$oO9G-56Vl{r69>h0Hs^0#v528Fa^$9VM1^Oh6Bb-)XKZ zJKtusf~l{-APyIF+~&!R5aFMpLdrd9Y0#-+g)Q)6jzSP+YE2S&iag!rB2GU)A@uKg zf?y#^8kYe4FjcuyGQyAHMbKawg|^IJ2#FE8uSuh2Z?Cb}eZ1+RYh?h)M_$ zbIqP2Hww{l&kW^uEW4w5IV4($^$L$ZE9I4kn6hNef6Asbz(JkOHNE)HtAQi=c`hhu z_mn`F$!^J3{vRnOX*#T%A0J=OH>`eastCNiLhqajb20y z2^7W#G7G>muE6HPP!XQ!#X1dtSihq36@Y3p7P7c-nqVM0w0Ck&kf9q!Lx^QSprNpT z1W-(xL%cU%r7I~Vyr*plN;=$IzSDDVP=+99P{+$!ru6VY6aRuu3W-kV{=vr8*RHnV z{F6KevBU*c3{*jV3Df=<*^Mo<`vZ2*jzvol!*Bv2u+-%#E5cvr@%vy!Py2o=@RCC+zrvEN|-4Bd>Qby?N{D+Hldr zw@-J>S#am`67b45M=SyPLasTK0Q{&iq8kOJgV3|T381}opwXksx&6ouAm6bPo-VeD z&0F`CjbT*E51g6V8o0BSSnL^JzuT0Sf2J z!Ssh_{tVqBMbN8GdNXY48G-k&B-#$VA{V0p>d*gCq$U8do$ZV#7ukM2yclK#_|pn7 zG|t}LvHJws`?dZf=bhizW1?l$AsXh#d0-f9LHW3*g6i5H;dgdaJhlq>lSa8kzCdRLoRXZ&HynnX6GH z-?`V@xLE?kK<#!9giPp~3V>*X8<1*muw1PBxJ7ykv*!5&_qG$otp`z4mB*UbCLQd% z8Okfnf``PNuPj55rw1)6osN{)JTLdwt<{FuVhu*D(1=F7e?Jce?GV1NBje{6{q>Jr z@C72EM)%VP)ES{qOis!*lp+gFd;vfn`W`@12hKX5Bc&@a5e;Ne`LK4r0a~E^z%kVd zR$KA8L7s4x1*Mt~v0n#(CMDm3r9-OXvTr@;-$&1*eYzo?#;*=SEa4wvZgmaT=kFA! z#1&LC+e;nZE>!M)d?9Bim^OD?y`Sc{TmqasS~@uG6GM5pSbu&6@;hBYEZH@f!TXnD zf?p|`lhzP0MeA7k0PkFGafRm#)wkh(1(@f~oqG?<3%7tMPfO`Jl6+C}%ktlRKgMxO z69ZL}1-SDq#F=gap;)FG(d#c)61lD0C-VD{->fNZv|{AFc|BZZAr8apY&1DJ_rp0N zMr9?g!*>|5o9{4s94V|ojOn+BKtqL~>*=?w6ZDrzFT4o97jVJ`q&K~P{qbsU9mt=t z0?zX_>&5%!qTkNLJsq;x!DNUM#OW7@%6r(A0M(TZ1iYuIsIbqXVhYpQjn$zrj^zto z|7y9p@C6L-u_DOSFLJf55ZQ(M(Ktf*Rp|zlO8HcMAdc34t@rr7GnS)yBfBFBw90In|jqYKjST!?jkUHN$Da z@=KUy2F5Vu{jode1B{L1Xc z2+GqMuZ`_a@L&1!16Ir6WkwSh|9K5RFXTWI5+L7Yq36F6M*kzMIprRhxV@zlabM3S z;n2cmMC+K}c7O!)%H_tsSeH-->#I|P zwzU^7Ed%q>>rkM=a%UVftaPzfCt3~hJJo*!RPMUBfl)UbFvq!rRTYj;&#Vl6{q7oQ zu;8qA7IXA(9aDIZB6J|A6E>|c4Cq5fQh)vk$ zK8aF^3i6Y&z$@}WP3p%@S6zv>7p4p=obFV9C^~@(E)`f><{~fU0piLt2c~{G3#UT`JcFe7F!2i zUB#lt8st=9UM3b3)TTpd7hVVK{WoFd>@*RPNx*yH6k15|8UE4=nGXjLS6=RZ60~yR zgcVoJe7|V@0S_g>Oo|ToV;=L0mR0{l+p|6$XE@l%9;w{DTs92 zdFtpq3TzLwt&Q)=Qb-PqhwQHPYPAQUCBM`0k3^1nH2~~L?b#=mzdj4RBnlm5S$YKa5jeDjh`C!#+cgX0R#2+HPe$ri_c|!nN-zWaO1>}s|!D1Y5{`xd&I?OrF zY}lA7qzF4z32}oGQ|2ZvrtrB{U?@)R=>68!W@vaD+#yo%^{~Uf39H8vBt@g>$dHS1 zistOuC#I|(aav$f2i|UIF(wjhnirhK~d6{@v^;!=i8|t_eywXlC-#)*BouuZK+n8u! z(q3LwM0RNaSA;l5v0?;ckC@l5UrSRmOs;0a?nnd)tGe`eVWkmh=+Gm~B67D_KvSLr z-u2ps)f>wX!A!r1UNY(PX=BLmI zb)4orf9;CbLE+7DH=O1Bq22$cpmbv<;2ddA<$C__H5^N|5*XQnW96&g0S3bo*6S8jf;e~f z_8vVWKyk%E-Z)qu8)QKVa5I--8E?26YY&Ie9~!40o~HTS<$H`MK*F<+^YQuCPASrh zyj9l@)2~%$MHSykdZWq)n9z;cqGB^)GSogk6YEP4r(xITRh{0L}o63@Th8CWr;t#fPkDNvcK8h*4STlZ)`gmDZ9mXxyZs z7)zM2@QtG7;WP5J?v@EU&6M59lBVdkJhb!Y6Fz}T10H8t!%*~pJx-l3(vw-K$#VF0 zM~ZBOAQTH3ejFqzIXiLyyqN-8@ED++c@H<@4^{K~8@AQ)rdCi(#{im&!k4&a2>*<* zar=NxugBIR8~k+{PokPNW_CD2_Z-2(mu(X*z8(T3IoR}+TPI|h z+YubqzrNbf6^+Jokxv(5Pg65&kI=)<{;sM~Q}P9k2x~3p-m@kHRA|eRdVBc4g&L*} zm<#1BB)2yO0q6G>T61zq*I#JGL-%*rWA}3~B-5aLtqt~nv+xzj8c_=sb`dI)P=InL zY^@EU%BDqi1JFA=EzNCBt~~ZGv+IvrZ$+J_mf184=|a*ao$&k2b?DzIr0gdGh_E{o zxRN`gwPcp4Y=kWLT=jvrIgR!tI>XoHm`qH_ZEkQ01o z+BVIbKVJAxpF4IDdFG8dmd7UK>JO!Ms|mH*bG5 zlI(of6QR3Qx@Xl2{C0+ypQx=8~Y;x_Hu*gLf+GCxGR5Q{pP9c zI-n}Zh9&senDicrqXHNtUxkouaWH1?RC4B9*F~F_Mjb1r6&xPLcYTJA4&Pn|{rL%) z*@#0O_^1PN!H|0Tr=K2cb-DPalJZxI#0KHlQTjNbrDMqgeKw$Mxq{vReMlZe%yhiO zHM+4xRA5d`gk|p=pHrEX$dX`h2a?owo))=oOt-7j7Iu9}Lz^oyY1d*!9L?2iqH2C9 zBiZ*SAchTp-U3ZI_~`RKJ|689<*Ofs$UY#Q+)T+I*XkXnR*N+>x&JcxVla8%5zo)Z zLVCx6&JP2zBErP{<0c0ODo@Q$rWf!Ukq!1HrH_Kpe8J~Nc_KS4I$-uY{|K;vLgnDm zpDZ;$?X3hRdsqio0uO1Xp$!R;oCRerhy$0`l{?N(0n^jf7g}7EvL3{U4?U~bYh%GV zwt=c9xtsk`r?5U#^~tVLnlW*yeO3x&oIUm=lp;tkdSSyXTl!CDkI4z9;r~X85)Y(< z>FO3gbB`6W|NcB_X((O@-Ve8>|5KP@-t~uPcNrRKoVe#Hyg)Y>wAgX((w%~R=%JJn8_5aRA1-V#o%~AcsT`*AchObA2C5}g}OwvtD~||R^CM$+LVY% zuJXF0R{oUCyB2Xhau&dBUlDOuOsk{wF_VQd>S6{o7S<>Q&N)uEEwcp}{#)%LwtgNw zq}oZc@W0~%CLN(Nq!Rb<*a~R9;}pN6;W^RzHhO>va>fC^NbQDjkqh>>^t-6Vy&M&AVU}?roBkM zmqPvwV)7^4rB=`G?KlS!$F_GCY4M=v$|V?6phV8L+Q!jg`{=^oPLUj5WTjur^JA+& ze$8k_NRxP^GUA`ENx{`N=VL5@{}|~GG|;C3rrcWM!|KI+D^a*Is5u`t9RsVH;bb)nd(Gtv%g%+#t&Sgbs zLtMU1Kjw(cmxz9J>T&42PUp+|*}cklQNS(|wDbfTSir$>M>)OYhlZG69Z-$mg0jB( zqyAex(4hXOsFyoZ*--nP7ikr{d6f9(kMhV)Zk zOsqwEeo-k9XN@Hz|K7khGxP8M;XD(Rkk#2=@qhcMUk2xcXgGJeP)r{u7!9b9 zg+2h3>Sf67n?ymzKE`3XO=O51hhdBjVP1Z}vo?uHu4@TpWHi9XNTi!4;g#9;zkZhw)N7j&wXL98-fxhA?j6PX29w zFn|$(i|QyZB>VNPJHdWIl`|brEHxHEx$-8^e;x8+KF8HTd19|^VI~EWlP`RC`%AzP zL%+q1fS~VdHX|dWW&p=Y7YhMiv?|WmAj>hChXv_rvF>Hi`HR#Yf^*=6w)wil7psv} zX-M^^p~@=Nu^RVWx!euqChpoAS?%CMDHz16*X_82*yoz)%cJCe8s7u^JKdRq)hZi* z7Y}u};74;4e?s}+3-X8eB*DAQk@ZV0+20opegY#-r zy2ir6*?QX-s1yJ1@0Wz;#W02oD$}nx;@5%(01Ylgg&YQVx>jcJs556T{cO-$+@%FR z;>M&X8Q+e^m$dSS0TR z=%lE$z-^o|lXort>h{B>iv-dfNj8M7O}ET0BSqZ(lesrYmuDv+#22|Knuj7+c&MqZS6Do!y5#=U$GdA-! zl^P$|jk?(wLUfvxG(N$`+uEH3zb5Cz+iuLbpfH5c{jgULG{A7P7WymECv4XipK5{w^Kay;ApdpiY{Y3)c z3!5@)z;>wwx<3)Fmegq*dEY`)eD&s6oph2}To{ngjEyj1c7#GY{HgmqEee`G2|`V} zMs;h;Fwel^LxKv7na}VRXmC5Ydv8M0-bNsG5R(~I|KI`tPJZRN_0hCuqiS{`*wGRb zvQb=|j8^(Tq~y4?HXMm;}&P$AP7CJSV4c@p7){gMx#KCw^?;Z!lno`YVK%h4x0_P&4rp3=IBVz(%5;^d%r z&6meA{W{yMjum*O4S!pbghq|xfS2>TKuw^1F|^%^V{DznReI^dLmWXl9u+jR8`2<0 z%-u!v6H8}*G7HkBA(pN+AEbUfYwmQZ!J%XW%=D(>b2I9HBO=U{esqPEImk`6K}!3! z)DVFKp>uUaTDl>~3v)lWAyME91`8^XU%xDOWp2L{a1Oe^ajY%|gan&0cg4(8)1iM2 znf`^2i=1WDHL||K+Eg{Bb{z3d6y`P?Z&#KW72C;Q`YYrgL%Nuf-o3Z&Kd{MuyqFl3 zOv225AsoX<5>N2=&VDV$z4$#?ZD<1oZt+?NT>e%>Kafr1(mR3ji6;)!f_%0~)@Z`aR88<6{i#IA&eMej0BOuyypjU*49hA{q2M*q%3cPwfNFNP6|XEa7w zuMJhFhd}GjeLELUV9hqubVXehc|w1<+$Lbd@y5+0bktGw#ju0(w! zHxDz1rpCdlAI8~Z;-`!2veWemxGl7H8A20@dvee}$=2fALp!o2`P1WLAo)*Wy0D zCTIphh_1Uj{z~3^4wRi!aTiYu^&eP+U$nPdbm4_+W~a{OvEg4e72le=uAWJ(Ej?$Y z@f-P^09Lrsf;K__v#K&uzytm+?wbx(>3W(!yj_YYSe5{wt@i>iO&@zv;uswhul}dd zCxO^zs5$je=j@et$?#OSlC(hLl%1aV_+lU}=Qdxltm&dj(5D;6jRMi6>jJV&NNKI%G!2$bSwu@K zFkuIJa8sqOzp36XEVU;|xkow*r zVc7ma*UvJ`ZsEZntsKvuze7CZoUatl&CY&+RC2({I+t9Uaf@6pb$ZAJBm?(WCo`X6 z7kaZ;45blx*#wKGhh-`yjzj6CIK@<-$*A?=4TLx@?cY|)O21S~6&0+DBK^?Fp8KQT znb9V4#$$;qU%vj0v@r-Li4Qq%P+HpLgw;!kztbDTFMN{nJY0+N>A75vdZ;elclEqS zFPV`F^IY40*l_wCsjd^Spu*XO;?L_so^?5ajpuDuoz3bBmJr4#re0n?sT+9ERSOA# zxH_WPGeql~&!A>EN^ZJ$_n}?O)!&m_xh#eHjVaDeh72WvaF%vK&i{?F!vaqM8h^0k zQ*stmQ^vpVY)>}#+?uVEEgPHkKq%^wpFmEa{LY;_`GEc>K?Nb2)u!Ir#f5)@Ogn3> zPKf%o>rgd@{&35R{gMeb4dcKcZ^QYNm1kawNG(fm|fG`4t zyz~;)bgiT0Up@@<*4l$YX#ipe-fuB_(~8=k;8cvxu_C4uazeCc#rg~P*KKjWJmN$MK~jbfcIZQi<}pIL6K`}2x;O)`q~#(@ zIgC`#r`sM74%-Xre$#$rQto)VFD0@PtX~;kE;Qt>@nZ-AjLNj3A4fSrzHrAGc5|fDxiOZSb>%j(^zgyYI!Pn`Qn(e|J^rw zB^=+mxT?s3#~k92Uxo%puRignrte9{i$`@+E}r&T8O;EZMr(MUv;FJYtoLI{3_BLS znssjdYcPZ%W#{OHwz8Q}u{fPAzU2%h62r&lb(Wk`c^D@X@TtIER=o9$=9TygT!b7H zZ-Nobp91`@n{r+ZndCl)?zGY4;=>J&L2m6UdHI|2^|K||$wil7Ho6Zr-HCGF%b*GL>g8hBKKd-bP7TbP6z>w2k5}#5mv&U0s#mEXgBOPsX*0~*%eY?_V6hH^ zm&h(IUN`Jj7kd`NYE!DUu$MiNctMPWNzWATrUPx9W?WEH>*XIN7B9#ffL$ZUMH7VUMs7_{+-l6vv(bccCoOH>=pf(yN>OKW^7 zhVWL*LX;B#>Ta2#3UL4&q)8BB-n{MovdwI0U#~YLH!p30c7b&Cy@^X8UuG5bi-iI} z?0x<&&NP@9~%-4ueFu z*v0?Ev5q8;y(3dT;|zfD6W+~}Me@!(O0h3?T3JEG%f@!;sumjujN!acA^FkDbn=sY7)vSD$2OcIGdeh%gKO z@%zwXmN1Ns&7?`FPcr#b*>$uWAJg3glGP5|HK3g`@oDXtvV=^CRZB0ox^&-MGAZXB z59+VXeBLVPqc$A0F@BNZloZ#<;`&P>oavAGa(lwJ~cX;PSyDC+@6`S0>`FBmA6 zFS)>WQune17*-!WFw;eoYN;O94O9^^t3d=pIO`S4@(9=25zif?zZIYI(4V(~7f?zL zzz6f3^kX7=lxf47O22ii+mIRNFXpLHm3XfMk=a2B8dQ9#M3L)J71A(QUVqT**BD8Io za1XtoE^qKDnJ0Npzj{On_2`SW8{7FY?}TuSwU(CFUG2`B)yTP@e1$61V=2QY&rpRj zB(YZK_CI6VPnA*^14x{`(X4)p$KxrCc7&{cJ5Z*4D*lopufnGg*fDi# zX!>bE4kGJl7v|9m-ad(VQU zYg$#BO^SS!nwZ|2i^G`1(ZOZ*GSz6547Ya`s@qX!+4B6h7RZkd*3vr!sVMiMCMnr* zaKUsuY_E&}E#lz?iv(U#O?2VWjn!-}e+t zqR9MZUL?m4!R2Nz_2raZXW8s)zI~s$t-ubU)gqvR7D;Nfh3u81-BC=wPyJsWw zNHL97jz=|_op4Q)Hc zF%5Utf24b>gVOP9iPeMQay!q724fKkvp)ox!b3)eGOv{TGL zU_bb~&-iM)Lbh#ps<_Z2&=|8}o?Vk47SyRhEUdLMCR8eQhSbF@Vb>W~eqeuOws(Y4 ziuid_pAFbxc^MYw5hx13eHKw~pj%40aQV7NgdL*yV$(sF*CX<@y)|lmXXo9ki{6k2B#)2{qK!yhfT?rJ_=i&U|J-CV z{u|=h9R>kdJ;X0j6{`8`8D29Oq%*N>^E9k|GvfCnFS?a>k+7B3H&=~onrAgGoX+fI zHkPgHPYnhll6AkIiw)wd48E=s(Upr6hESQWvutM7EP}lM7u>VdJy+vhB~L5?!~n3B4*)hfs_pU);$Tb%OU=lTpk(&y!X4*NhYy>&87k=SR2h* z(aDu$tdlhY83uM?5sbDjdA@jugMfY+p<_#B3hErwy@_PH_qD1$eFbYiV0DAsstK4r z zd^M3>1X=+thcSgsR8$2`cCL03BQ1f&;5e>I`H6K7*ibYbhY76k7f-co*-=Hr3IGuh%sR(i6WPp}>=PI2YQZAuf8Bj|U~(DAdK`-u zEpo$*X%->pU<25S80^j=cs3Vx6gy-AZR_5sGyVO6$q(N2f{(YJ{U8W$N7@c%MjNJ& z$0yv*8>FYXMnN0ZULT&efIS|AbdP|P?!s~sfeFtDvtPwJ>z=)>_?*HNirKhgBf1S1 z|Lce(GmuG&EL<>qtR9?dKo7`Hon^;r`9F(5>@0CiMRLAi@_N`4LsNEvi(elA#gc(` zu>bwCxLz1=1LlMBp19U>M?AK-RxOxn)-c-F(D2T&cc5I|c|l;@57ch2mJOojAYA0# z9ZneOPIvF}E$%HhN-2vJVk6w3tld|C4u0_RCJq*n;hTB&ar&M+!!mrkm}a>EqtEx> zUR%e+{B%7kBum%sE^IVCi*_N=ZFHCs0hb_?%=NLVY~8h%4Xr2;6zeKPz5jJgON6yguQT6aK8mc%{;P)290C&8YTNW9W zG9vt7m+o;cV9}zzpEsR)CI9l7phnNkRe5j-D7NV zA?GUTXxq(WggNkF0L6?3(b`=61e(0-Ic;QXYwIP2xhn(I#F$E+IXto)IF0U^*knL( zQOxI0vfk%SfD6w?L#g(o7l^$Rexfkeug6xFbp?q7XRS+!kkS>C=e*rlE+R>o-PwPO z;d93EKjm{yDtsU>#9Vi%%IR)IQ(W@O)Hin%reZE&AOtNgS;5a(iGkImoR)B;|7GVz zqu$ap>W@(ha86dU{IU8aqBYr4nVnc%doc=|tuo&(ePcGT8)*&QymjlBx{Iy7qo4=K zFQaAM+PP$nM-8Z~4*31TrA*u7J9*!kajO&r_FErTK5*bbao$3hqDLSi>}fiZSi6CP z;g5trBZ`2V16_d@v+p_k#-f~voK52UXOZ#=?j8`>zrfvWUr+=b%?m_kyX8E0UX@FZ zKHKZq1S(-jU_RKJ^w#G5m)0!3${eeL@xdQYthZ>O$h=EfcEj!&kQ2~q$Z*JVX?8*~ zbg4HNEyU=4VRtlkRcN927~JiBi~HL)KcAd9YG(^k*zXeR z{?TGZmq8&o+KPA5|va{&W`p0m`A|GV_e_ro3<~f1F{k)Y87{bSnQrp*7V3uqo z9go0vycE2*o#9~;xcG<=`IaAa7vBt#WqAxAyPO;?RA;fj3wdlm*Nq5rE(}&!V490I z*bEG*#PrtL45^YrsCWFMK?7ii+`q*~k6uJ+C)QZ{!V9fCcOS}ZJ|g|KJt_w&`hopD z6Duy2JE$ZY?Zv1Ge}0Zsx9vbtdz%Xk-*yWZ(Xa0V~l|eT<^;&v3+~)a6;Wx1z^)D<0}mkWIp_9 zH2%*FUdeMbmueDE!c%fi@!|@h;1sMKrr^XBo55&g@A3`KjqiGAnG)3ZNp6QphUI5o z3eY59s^o(r%ZXD?aHby6U*pS6jq2iW!>#b91f28$mF*)}uU;)ShPU=WMa1HCr0l1A z#YWYFT&tM$P9C~i`s&o?%G_o(?yuRdyimPs)p^;|W8^eu?t|>;(ZcoCg$7YKsykOi z|G6Kw1VrdI-!OmHN6cQhj9o~{#l9bjn%OqG-ITmmD>?zTZgt=cud$Pn@mQ7Gl z0hu!=I7QK0A~6TGI30SDckcA0zPAYq7#_ADa0J9w&cfdZAz&=V6pm<;piw9_S=0_?fMF@_o|l9Zpa8$ZZ@S%if3_EG+k_Kn|li z$TnKIiNiyLUN)k&*2>i=MQnrZAIHpolH}o&HlJz!4FP)Y5V-AiG1tuAQa#8(Wi|*^ zG2>s~q?}LMpk7vtg2+7P%MDAV96Onf$|W^52+`qccb)3KefubNpRHSqzExe<2czf@ z;l*U(!3K{O()}R4-obI<@-Kv=_xOxjbjrJuP+6AlaWG+GQ!Xj3v1o0){UbQX^Vk`Y zp|5hMBCUpE&00-z(0-?ifs!8bXTFU}qu><`$VL1NFZG`gi6lA!3}o$0;%A|rxvQj3 z>Hy9d5jpb{xMI*APKO-#y?9azPU;6r(#M~=e$CN-^IM)WeR3j&bbtUm;2>uLm5~LT zrZ;@;iYMYW$t0@;O1%}ZVmNwEKRzGm;EqMj+^Mx(_M%SS#po8dj>_Pynxw(x9`E}0 zq!JiTmusd!&3xYh9s=kz=)LpAmOt-}#c@C&&6ir4<~-JnB~M4F+Et!%|J$q;@TKB^ zGJrN-9P-$Y3^Q!wqoGGCjw(@K^{6BGF$hg1$y;-#uu-a)8OWry(X@6rumJs1v4-_( z@Zs$b?&Oa|3Z-|Vzi~JUvY4bAK*&$lb&%y&WRFu zkJY)3LkDLognm#(vUm-uYnjG=beQkFu1~#qRgX3OrP+dx=vE^*m+v8QQ(UP~Tp$1# zC_RM;SmPx2f(n`gvh2mUET8k|PjTxjv_6$cmj@W2m*g0H>oNnw5&k;aO+Ac98G?C!044E_-D=Pv8SlrSozh2^Fk^~{U>-)&mMB9%02#jf;8 z+dXJI`q)4!7r;%Hzui09bB8b*5XSa4F6NrbX*1SS69(Iee?(dQWo1he93Vo<(g0HE zhCFjKb<%+D2BtSM7F{b=_$7q1kJ+3w__Wrodd+=KQx^Ia8dNn_tF~_ml?v+cR6nBC zRWl*26ZexqFessGjfwN~^Jj+v+k`2}v1i`qxEJ4-tCqs2{e>M^-y>1W-p`~4wFaVT zK!!MIW$lEnd^>>QaxoIiyq?aSHYoWbz^GXEeC@w`Xf1^U8`ZI>ZPp;#(UJKUJH7SW zfF1}|0wH^Z0^0gpjY9&FiZKUq)wZJY>`4lK-JiZkP=MEwnRwoDiof4;pL9@dS55vp z+>KB`P!YqtH^97jkeILgkQ2AbW5I{d<;4~i$bHcm7b(~LQRXFPY?@=WV!e6RaB6;? zc%-gu(okGErGe0e9cFMBS&1-02lmHQ!F6q#{9Ry2Y4CO_4Tar`VVo7Yw`Q0uCD-pH z4+E9Jn1$z(GE^Yo&6QpE1!)rsp6tx@zjZWX)>se_-Nq>N#ERLIJ?p&F2tN5|=SMot zg~Ety18r}hJ?s1s_^6Z@%tiXrkB04_We_qu@5>38l_Q9n#>_rQT8!OXLV<=CS;`-UpCk0zSP@I)vcmBoJ#fx8r&} zAc78c;rdavkftt+RGlK>L~kjV82m6iizrk;*u+5gPW^wXESo5WNApN|T-Yif1{51m<9C;pE*G9{K&?Q8*3D}8_g0<7SqqH8I@B8xH*QV@kX>Edc(dyZ7FE8j`@iy zLNUQVz{Gcv8Jb;lCH)TeqN7#?5x9S>$ATJ^h%V$-9G;5fhYzt`VHnz_JK?1*W{G6T z6Apt>VsU|-lCi+(?z~Gv#|<9lgiS881W)E<754I{xV6nqwD>@v$LFLDfUwQ{{PL*6 za{|#E94LOd+`)cTMS`Kf{44ovMsy69Hu+g~)IV@%{s!nnXkS-Vzv+pB4Fm+53Iyzl zqxU_j$@=e2C{`qsv$MkY=%_#C@F3M&FO-Rza=l8pOX&^Fmu&K#`2cMg@`=WO8 z`}B9j6pZ|8*}@8EVHA~tMip(?;Wy|IT*cZR-sR+9-_$wmd*gtX@x{z?vpkQmYF) zO}Kyqjx4{$J&VEDlb~T#_4B-cf(A-eN!<&EUthSjY>Mb>%H9-}I{5UL^jX>`ErDtR z>;nLe7?&P<%I}8kE$QYBqZDPv*4bW*>qi?vn2cv$P;^cSVYlN^cAHx%;H#4U%M#8Kh%DPgz+*r(nXi1NS z$wz)#RV95e)w5imWICez{pTLBPc%V;$U3qSJ-TclL@JQs*a1@2S#_sMGIMC|&ETc# zKUjqRNyfM~-S>#}O<$7nG|WO#ElC#N+_$T=J$O9pk6U0N7uNFVX3QRxnXqw!GbwGeZ3VCvY=3Rc0L(8@%}T2yHvtdv8&~XtmqE)LC=0jS{58Bgwya zSRT8!=^K=*t%Gyz!!+T}0w(pA03^cZsUdt~F#6vA)xKX?1J%fYn1oORV&_Pm_t)2u z)-^aAG&B^n{>z#9KU=Wooo&04tziB-=Xz7+M^ktgF;iRbMk;Sfl(Yd7IgYtycH`odRd9Wcg*+w}Wr#x23wJL{UV{ywHS3 z`Ix$Lzd)8;o?H2%T_T6>nc5ta9e<%??wYw;M7N;2=5)$7v-~bz^U|(6zLo7aHZ@;P zyB02DRriy}#7?{nPyOR&NkmuOf|Rxtyqj-7)e>&f$zx|Px9sprftcYLw*&Y3@)FkiR8Qgx4^$)V1B z6^f(VGporv)QK-QD$92p|IykmqT8vm$519pv-YWPO!=0s7s{hXAM-26e?(TzJWia5 ze)E?J<3pX16?^cc_maoQ&zhIzSN6pp=yPQeVwSDjsejF&6fPnq&pqgu+C`Ur;+5Yf?JCuu-x7E~cRGIx zhQ>oNRDXkh{sk;)X9#tv%3=|+f3AK>W_-v8qmpl@nXwDt2e0? z*dLd^!(tM4jW^fS6od6OP) z!_z&x{H$?Uht779Gx);g4I}s3Qw~rZiaaT5ncv>3S?lW+_W;R85LapVeZS~6E9z6s zqoj<4KyA%pwT-U=2jvGyJ6#qLu`T=6MF;j3E0mn5B0+ETXI1ms&G6{2le*xGABs1b z49!!C4ugPAt@q;o=nH;}w~1(knn$W98f~EV_FH>8LaCG^c!GXCAj;aB!{dAOJ)r}} zbu!>aUUENAsl>!^=B7CO#`@wG)r6PTIHKI(4#z2a+I~i5MEm~NuDhzJ4|dkw=tXL0 z)p2myp^kpXa4;HInO);kMJ34F@7nb~2y|F}P!TaLgK4l1xE~N#dfZ?9vZz7s%DmMg zscZ!(zU006s?sS|)ZcydK9g<-I1%f-g}hp&zVfDzeRF!_Dvle!ocW6C6L{0cwz@_gY^K?5Q9>YyyJ4Mg5^$-)G z6tgQfp-|3y>YK{6w%>6Gh?>RJqaEi}$$7-38N(yiz0;c_Pt~!=L``fcuB`tp@2}{@ zY)>wg#Mi5~%74~j0_eVDU!>oK$O<@u{H{EWYku7?y-%!-E@@wzT6egv-`NlTx3cN$ zvmOX&i0(D$Zw*(4$qq(-DA+EHD&j9j9a(;?)Dpf_K_KZp5foRHJ5eh%ZY|y{`-ms9 zqP1gBeA-%-xQmb94u5k#SSzd?oXSGa%5)Adx73+p{sKZb?5OfmWof_7KB%+0uYbT- zOe7BD>pef_xmxx%x#8kf2ML?}bUAS7kjQ(lpV}(XCCPEN%6Zl0=4BoI7STgeW5A0_ zI$B#6=U27XhgQn1erR|`;;RVsZ3BaYEcYCW?9T1zH!Z58-FeNYUA*sr$;adM_xs~Y z6+|q0p0(a!=wfusXnUMY;}{EUndze_Gkx+r?-8@wmkNXraB=ZP%USeGoeOvCh(` z(tts^5r3an(!&Twtc|=p$x}M=1y$NUc!VHL6lq zsU#QG{CU9FR_BGkU9iDOs(q@y;JA;_fR;wrt6F-I7=2Az+qONS5g|g)T7G+mKHXGq zu48u3nkTAWw`GW#9EaASdn2q*BSOlVx|Y(j*LzH@j?cJCo$6?Yq6n=|i}}a+r?%>^ z%1g7o{a8eQeOQ@w-#B4R<-Kv$1kdN9D{5*&rwrDr>iT%M&?3_rFz*;KNlkk*r1r`` z)1vL|N%eAp`g38eqZV!7Pp79BeOH-OApFIF0o6VVzo)BmAM0!CN_d+0Grmsn(Yex* zmN8;z zF_-YD=IoW!vbWdoKDnbls&1KtQ9#2)x}2`;o82dkY}I!g2b}9<-eT&*Mk&8- zIcp5M_9fQV+%!r_TGD7{vIf6Oli-~)s+p*2s8Yl>0!@MoHKH%~ZZ+qB-$}mW-rC=E zzD6lA$z|mxO(XY=QmkrOlLR?xy3|ZM^D6Z<54~T0qdISB4f!xDR1ug#CMoS-z~XCa z3bu&gq$EDRZ}$oV^TEfrjZ%Vr7Ch|#xi-c=J|;iAd{d2qsvDk!mi+Sj&YwK3tOk={ zYPf{9-8`W4_-z5N$)}v4qEB(PCQWVetp|rie!HKi6sQr0TxHnGOY{ap65-_O=?sL- z58GT0m!-X2`s(o&lf!7*t{JQfc3*~ib>@=~klRr-X!SHo*%QdgskOPrz~K1w8Vq;} z<7)-+0;+GtHiX4_d-~$MRl3i6-La{xEKuUCE@e*2~7nt2(ciH5%O0p)^lElN3f-s$!)Rt zm@e?MYa1#k9U7u(G<)B9Z{4<+p4035=SnY1@V3J5CoLi0Pt}{-Df|t2&OU;pm%M8a z529t}e?9X4K%&^@Jm9~soK)>444rv3T^(U!SkgWEG51B`IHfB5EA2;s)bMGCbVv+G7|ab?@-_Q!#BhU4!zze?qER zt1g5@hkT3tZ`ITmVZ*kqz=QnK(gBW|w5QRmJ?biU;PUiNPJX&+WcB8|qfv^;@y&9B zjX2&q21EHylw=9;DYXF(+RAwyzjlvQoU{pyFYV7^wkheAH(?(Gf{;3b4-&(xP8|un z>bR*BzQZ-2E}(hT?*jhv^Z@;!aNkQ#=0-F6@%N26yy-{3m4=43Y|?Pk$ktFOhm-sn2JmJ-V?o6 zt0XBBF`9A7@=V9wHM~4Z=@CB>ro8X$+I{5IVB_Zj)<(0T*MC?6Yco12-(Q28Xi`?5&$am>`RiJo4kp&BJjM$--x8AX*sj-i zB37sQ^O|A2mmV=qF(yqWmijRzN#6$!>SmVqnJRbUSQullj^8BwaI52CXy%Fp+V*bs=IqDZ z-7NJ|5JcPlvK|dQ%9r-*C#*3j*UWPVV>8LPa&3y=Wbm?t_QfL;k^Z_w?4ynBh2HG- zj21LW(OCmDp*_AlGSzD63$RqLB-KnyD2&$ES6)nes)*~-mx?ze=V&0^m|V8Zc_oUYrR4O_D*{;67Go0DZ*$eP;0>$G4NG1%NlC7Ww< zS_fzBik6Oqj)D24`m0Ti3y-g=Y47^%bbUc~e`dp1ZekP-)g4U+#UJsfI2Jy(k5B3M z9jB{(d?+d<5ZMor%^S+88y_9A>e$}_YVIAsB^4J(r1i%i@|v0qF0nR$qQ5@BN{{V1 z`ltnS3KcyD-0J);;-$680enP)8&6f@;~Zr1QZ=hnn$#OYu|(l#N7RN2_b<Ue{Mo!GD=YGT>OX{+I_JP|Q7!>97PP z>fa?c)QMhLh@h5s{t(g79hBeI_wLQnSuVgCo%QDBY^SQd22#+->#W#45FkuO|&Cflq28(jUI=xLMnKh%Ui4Tt(t-70n$WVj?dK zB$p(#>sF8aRzOQqL^9qalo%r7iZ+`js_xo9!Wt{++wh?(FG0^{?6)9t*fBW6?M9TB2lK|09(Oqctq^5lf}Cu%f*ruLXg zl}qY6z+Vc=*J^$Fvm-h(%6UYnD?+n&wTO+x8v(gH_YUXD71Xpw+BCFkit+H|s|G9e ze-HQd6Jej!C=Qpjx%}(v(GAIBQ)wOYsR4mnxn29F^S+d2Y{-df)u$t>@p*o_8n3EC0o(sE z(4EkiTH`CM>(gu)+TV^3RtGc}jiirAD_NB<(J9YDQWmU7C&*wn=u`d}pY;{_d0YYC zTbpo_ef1$ZSX-$+6(Qz7?u+jiE{mw#^S{h(>M0T3C^GjA zZE|{tHp^8z%dOSV%CiQIH(b>9SW?6ipZa^;cU$?A38Qdto6yG3(fQ`gKkZTp7~uNt zOS^Qhshodb+nz(;c8;Nm_OAH(FRaJ>SG^KyeA|~V(hG6u#6X$vqdz6{!nqz)nwRFQ z1twCfe6UcBA4>M~=;l9F{v+E&O}Ep!aU@?IP(^g#;DB#vfu)!w+2bYkdc*C}Sj$c2 zTeQk1EE8xB_sGAhRPBD)KdaXEKLpK;8m*R(R$cTL(Dy*;Dzi&?kYPA|a#Z5`k~^RU z$`btmE9XD81GW(*w18%X5vsVa$Nb;MSoZ03JY4j`^Hw=%02-xI^KG4W9lhS{LuNy{ z^jZ5-xKF``4eK1x$92b+$NhKOJ;8e_JHw3 z9-!=gCIwNHK+Tf2{H=BHfSpXO3fsj%=(9vhEcSp)UnNv=2;1(M*ww*Q02$8W$xna2 zB`qB;Uccf{VLnP2>3|2!)AmpIcI}{o0MiDj-Uv+ijzZk(sc+nW*Fu4zdhy8(D;v%ItG{r0_0#TR-_

    okV z|BoCo{ig;+iUE$>iu{l_zAjEuxUlh9LaAK|Az6E5(trge+=C#Iz zX`ZKfA}6^%s2aLRQ|gU^FYcdLgJKvdwD@@Qev6Dfm9n6`q_{YIa0|%mCyT_y#nbL= zGWOzjC|9#Oh80%m(WZ^ZMRz>-go~Y>YMPzTN!9<75rrv_h7~`8E+t4UyZ^|hUpFby z_)d`>!0Tc(7u^07unBb!qfHJdvarY=2lDRot2yUhJf4@Setz6$4vsIt!#i3|^v`gV z9Oe;9V#e))vKdTuwpKc}UvgUw#u!$-C?0@+scs7p*dBbo|IwpWmfxH>4`go57lg{k z;$pPuPan8MH86DM8zbh-hGG);h1hEZ>|gg<3xplFMJqX^&CKFY&!<(_ziIW#S!9yo z_egux4vP{hME~hBD2ZAQObRpQ$M#sy7gh^Ig06J=PRiS?hcYhF znS8#pg$S9iI(-f`^sEx=*jE4jWeQ>e?(+KT7bC~FhclLYkhk9uX?b(2Ck>yG1AdTa#s`x*}f-g_QlO1 z5*mVc>{F=vo0CCLP+}$g?_S6=CFx)EXFan`4axHEx7K z^UO+VGt$4)mZw|+`rb+CDsUc?_Xm3V1&`p8HWIYR<{Q;4X_?N5H01>v&u;VVCP`-O zpVF5>I4N`OTJj?vRVDtbg!J*9J{m|99c_F%%-q4pG7&FgAlR^RGI;-aWu$S>=j$-f zEEvsh3Y+45@I|=?RnfXYr0_CNuNbF4#frAf3ns0EkVrIlP^y=woRM%PoSo!rb=|6AR2zQWT%$(H(^Wok zP~YhVhx@KV{8cH0bc?03=IrZsYGm)5A<0NYVDrB@7l`(`5SJCAo0FF(;I}&#!ZqGj zrFZWWK|1Inc-3XDWI1}|$U~S@aKO)O4=HJT54^hf1K$(Uc1=U$KvX1+jo(0Dd8+3C z?E^d&<|iy-Z#;U*wISMcGw-g`ks%$tG_lR<=$%}yn99V()>FZbCTms6u-E3DRi}v! zf9(PB4ksrkH`L&d=;(y_pb*4X=x28lbSxLn2h+7)auakBDT{2Awwu}8xi=GKfAH|( zMl{q!)6Xkz6B_ZP*(~Eh`16NBWB(ETY2B`g+SABK!`PYTl=EM&viR;QM8azYJ$O-e zNVe|et_G3Kb!#J@MR4eaED!Q4Pd(bV(a}yTIqxobJW+!bN54i|X382FMc6N>lJyhi zQu?TB*fN6Jv*GT&sE@kr7=t2)d8U36F-}II_To}kVQav2_F*|5SXwopC&O$II!DNf zB<%`+Zqv+_&$xjtKW6db(yZ2|^^s?=i-c8vHvI6m3sLInY5{?PHWyPP&$@^^NjvhQ zNg!5O<-~~xq^%m<)%%GW!db(16sdd7z?NrNhtBka4R0{E?d;T-C+?MW>>Tk56*BwL z)FiE>^t7WkrQD*kGKR3JgHTF61*K?|mv$^>ykM%ujFZ=}jZ!I9Y;u&LKE?Wn{Mm)m zhw&$*KMf{!>D-<@th0o$-9%+}gP`!-t4c9UDU$hFb-8tPTyhpyIt}6B85Kaeuid-^oMVaAh25DW zOfQ61wCb|XS(529@yrOEnz#G^wVsk0uRz$UW1M|b`%!8F63X)>l*PUpoxfbPVM5B{ z+%05Ui{btnM4WsoUmWgVAS%n09(RMns>A4fLZ$0CS zOR#%3BNk`Z{(EEVKo;l{v(lN>e9fRQycjuRQVuX*Bf3@DAV~_;4o;AEY-tHSf(a5w zrHcoWch=U!W3Yp>5H-~5>?~p0_Gl?Hzci29+Y8ZeQ9qU2T)$?ytH9h^&%Pq`pn2$a zG!B0KDo>^wXrVFT;iE_FASUmcpgTR85lcuy>+8hE`%41sP8|J%3q0dmckWZj&d%=r z>23IBe5ii;Y}XYmyf+mQK_OI_(jxRZ9sZ35gIfL=-CKE|KR*Bt|Cwk;a=5slIv`xOq4l<2@FFD<3EcyK3{gom!OKzdmuzqs*HZgGup*E<>66p#*wTCjzGKUZE z95m{zFGYxY43vjWU_+XOWh91ZBwb1Ppvof`QmJa#r>-nZa{to#g?v1#zLFo0#`Njhkwo_2j(u zEgv0gzMweE8k{~cc$<6>>do`-*Uj#oy%?pQo*wacgmfb%WV5&vjYL24MY>~krTtR| z5x|hyKHsyGnZwtCvSFceeq(=J`jX*WwGpwbShvpLitWhRECi^GlVW^)#TNV= zkN4&F3hJWA_OD&I2Lhq_0ax+aAKQPY1U&0TG$3HtKeC|}J|!H63z96X{uv9ef#9!5 zbPNClJXju{^;YIA$~uq=s@8BMqiW8-r-DqRK=;o|CSrazP>jE=Lm8*(hu%#~`tfzj zNygfKE4nw>h5Rv4XC6i0;wQp2etv!i@_M96m7S9_=g@i^cH;O-OTJDveoc9~e7*Q3 zYa4Xa5S~w;pQy;c=e}V94wI$x+}ruBc_M20=45S+k`)?+NFX>k7VxAfiV9V`ORKJ; zrQp%WWPhu!J>M5BCZ^Kf-h>i^Y;o1JL|vPzLS)$qYp(RVReqkd;a~2H&4}tKt3kpL z<9gfS^B5H4RCF0K2J*DgYaX=!y**S%iG+pxr)-^B7jd5oVJ8PvDPAXQ5M__rawXVt z$hH2idP8X}rqt02&4IXzQSOAAjiB=^lU^xE(yv6Nso1yiJ#|=S*-N?G1qaSJ?)vLQ zQ$go>Q2*Yj6Q|z;hifwH>cv?UjFLzHfRFI zo|S|ef)={n@KP(gx95KeN2%70L|lOJiHM_kOr)gBXT;#-b_T4zIf+4NEF56*EI+_7 zNO<{)@{;~*qv{PK;t~^gLvZY_Ota>Wzn8F(ijt!yO(&085oCN&yiOA-9;LnP+qUKW zv}|ABFC_>Y{H-e?Kq9 zE;MrseSi6ebLQtgoDNsMXEDh>jVn{LXr%T6dG1U?AMl@SFrnFbd85v;GPkgRG}=<| zkiTGYi|YcMvggQ?hLfEL#w;3-d=Z28nal?zHy}Aj<2uUo??CzPYW5V_r$&S} z0p|SpLQSSGJOegc3!SzQvOJZYpD)N!p3YJ-L_f_L-9wRTxn=X_k8Nz%=AQ&-(qv`f zteEu7x@XYsFij*(9YPvoVks2~5=d052;33(p0w6oQjtyct=}+vqGwLJ0}sR%3+pL5 zX0u4^y$#4LND_HiLnGj$F>3I|n?N_=>aQ4Be!DzeQB!6A|LNJK&VilK3!g1RO!GrT%cpzHS?bPq zlNyQAr7h`tZqISfEj77v^`y>`(=T^#n&x+JNsHW+Jk6C|p7$8(={E?~UUjFUrrsk? zA@+~Sid>0hPDO4Ou=-dmmO&ch8Rlvp{< z3T;?M#ujJe(1tH#UB8}}L>!-DT}Y$J|6ZRe*8XK?C+QRI8C=*_GO!|d^;njSy#dg)x?ynDkl z*;l3M<)3qNV;Mh|+9mvg-#QFiPtuU%;ZGuG9>CvTLBISJx?Rv`MAV@t61Wt|Gg8@0 z`rVK{A0sR#cZI+0;YLWBKtyOzea191wI@YNTkA6=o+ zdk}}Z|Gg)#x`F8Ggab}1_%P_>B~(C4H2Lh?srdN#not_rVQ{tKl1lRzX}p>JVl7== znNz18HZ?V!wZCu=jb;lD!Vvy-G}s!}5tIA)657MefM~Sv5Q3iy3VGaP$ zs1&triTZIXr=pNQKf(d&nAn5k-gCnNBo5o-px@i?2N4mSzK*YYC5cIs2jO%%3 zhtN+O-fRUcYiG}st5+j3(1v> zG)w*E{O{w7QQR8*s)(4>xtYzAYLZ%R9&mjM}l^gm> zz96dDo=lVp!24%MNItkUJI;WPsCAM7TgAo2iw{CH@C_y)?yX8NS?G`#Zs7#IU3H*7V$r-WThM)~&h;PoY!zJyf zI=V=r(AwI{AhHZvd&vEYhp(M{s_+8WCY(_IfBqO*Rf9gF)!MrwuLNd5D$Mo$aXSO0 z^Xg%P7*v*g#q1U_Lb(_>YEjN|Cp-=f3(^<@m6u{^_V>yUKR|G{UU;d;eI-;<5C{i06ayej1^RA=*Sb1Y-2w<$6**gj>Q?f5zCU1PEF#l5wGFq5Fy&q2<0=d$m3Ry;p_ei!+KUC2(vXl zv3<7xeC?XgE9obyO0P&!XWP|_sBskVHWKY(iVu@wx;6^TH^)xcXI@vBVwcW z%2ZhF&77DC$|wROK>7wD@M7R~fA2pIZ95>SzQ{RKHW$T_d1;oKb4Foe)6|sE^oar9 zuqA2V?};=4G<-8$MFt6?0`<_%?R=a%$k|%ZxFJyZqyx=^$Lk>ElQz<}4Ugs;tts{i zAmM_~T~m554QdYP>;H^%$Sx#Q{-S~iWDOnv+%mg$GZ(!a8DulvH_fo$H3rneD;_id@X1*g%2U^iP8Yp#+KW!{l*;C3?Xj~lM$rWEbq*=mL|8~ zVEi{xn0dLyz;5zK|0_8ej*Lo~V4oF3334jCI8vv1#i6q?bR*313}^iIE`H72{J82T;@`zyW2-(~2MeyiM* zuj%I2VuJ(jzBFXFexQ>_VO0O|AZZ;(D%VsveAPHA1L6-H&`x>qX`R*4iIMVjBKlAx zvLTQhC=LebKD|NMi00^bJaNV;3P$&#vhXXv@^2@K(|V(NygT>o&VP;kI(h_#^g0}K z4_dSF+3NI#w9M>GOiW}v>K6oX;rVhvR4YMPRxZnUmcNKJ^6eJ6tdu%V#)TZ&wwnOLyM@gvQojk9yF`1i3=M>uXF!-`t7@M=!R-z&TIdB<}JursWZR5W+y4r z866=~8$^+X@$|(wG#MNxu%T%#QqyeoS@=G^pC7sUY?5*C+uuLE863%AMELzp(1eNf zeK0lmVC9k)-GI8!kG;I~qI1w4PihxO-&)20<7)ijY9>W?O~qt?9$))I*e|OaUWexn zQo6srrjhPI-ezqfe zf!9T*GdytzAD^|An26k>t7+>Dj1g~GEkt+b&n3cACKBo5YA3H5Fmv{}%%hkjp}c={ z)~nfr@1ReONzU8gir-u~Cyen56GL{B?`S@0H@jHf_q(7()L({Wz2F)OIxZ z*ozk(FdSaIY?+w>+qJn*oH2-`AyN4((_eEP$+k@5#&=EXeqJ`WNBWe22;87ZSHW@b z)(g&~Pv-fpp~5xi0csQXMA1&L+~oN`AncQ~Y_bQ?qUyB#Nd$C>Pr~i2IeoW%?jvW` zpJoS48HHKHlq(@#W9+zOm=)q0;n*$`s{z=&Jh-``i!MygSMX8=8`=Qh2;cHMgI-i0 zW`9yH$D;r9Kf{hVe0IAxm;Hk=*xQrgDOMD|Tys0UaWTqlUvQ>^v43}xc z9GIFQ>)*XZqH^AHHm-m4=!U#zZ$f`%93#b*b9Y&D1Bps_rhmhbNXvEOYtxcSMoc^`u-8$ z%%e!b*{(izaN+EaGdd|D+Qm;v7$}hm|5jgcKFZP|`$2NCS~6LQ16)B8di3DouurnW7L4Xwa-V zslFM~AeCsI>_VC~QmWszzJ|T~I`8j&-#^az&^~APJkNdK>t5?x*Sao4+)XY2{IloJ z^Xz3OS}qh8VvW-T558{Y* z--_uJEf)x*|M_69*nzbrdz%Id|z*%lz-UCt0f+f)Aysgg2R4{^Z6SqvDIMs zWXr$O(UAH1WI}wpu(TjuWF!RhkbT`mt9jXqVn4;r(A$@PVG(B5pdS^mOpJU~Xe{_W z353X?Pk+>cof*v#L`(k;q6|`L_#E+fWMIjCPwXUZGfYBhB}yJaR6V0JVb-sxDrGbJ znLn`Fx51jTmN|5VytJJKEhu{c{v+Mom}a21<9H4w`dpeYY%jakkPuSJoV^*tevET< zTpcIf^zLoW-)0gE1zzT%ovC)Nu>d=9!3CW~mad+SuBAUT&OZq~%NVmxGr z7Md3*EMY0*CQR@`E<^Uo8c!S(e%n?2{C)pF_QX8)_3PJ@HbpX;VurH5v8PA`BV?gP z7`M>UE%2&nZk7*f7`o!}LoL!M^Ve%P%RnO7%7hkTFY`1Gj`w{^*3fmOaI!q*mszW zr}%qcB#pc|G39w;PZ)Sj*MLTr8Bo%&5BZ|8-&Hg*20xh7=1LIlE4hxh|)K`oBftA;Tuk-`za2tyqq-_85`lTKPm0B z{h8>vDsaj_gj&-+e8ojZup3uc@c2_YB+HDqOQ%D^`fFHPOl<7DrAtfy(T0dMM4P5? zCw$o$^}SQY{8)2kr2!ho;@|G{K*MXnw_YsudSEObI|fxqMEijTpkqF6CG%**oyZ|H z{FJM7J!Rqu1JCzWIxHQC)@P=}$mFT>Dt&L=nh&kl#GH4KS2BYPobZ$w((9^SPV%%_ z07>V{$rXi;&#6`^w=1dqn90vC)<>$hU*9$f z9Y$}8$7vw>OA=JZJTarYe0ki)encCBSuJc{!_#RiNyT};`J#CWFXjyP8oBR)d!vxK zN$`71LWM=_bcbHCk;N47k~XN0Z0YZ9OK)}j7{9ma^HIDyri7nqYsn7ZZs^&Pl*zSI z#?!gJ-F4*~J+>oR`|&X0>vmYR+fLjg_v=e2OZ&6+K$s{86}rdRP%^Rt21|XZc}hxE zuXeQE{&)t;rn`@GXM7(0VeyZdz;J=Td!b?f^56((@E8b2_PN-Md^TWeky32R(3==& zoj^%0EYA!>x0a_9M?R*tYrCI*_IH*4)sG57$e(eqUczj4>2fuASoJw=^Xu6YamL+! z12Ue6$G`s5z?x@mL0}m(@un2Z&xLEpV#7vmF&R$*gpKXOgr%KbU&h32%K&3d@WjS7o+O81ldF9jwB;b4luL4V8`0pFP_$ z94g~k_y}L#bEag)ef@aW*maH-X&7~`qb9B}P z9Q1jRuY~dQSR*_|@1qMXF3J}G80734>f7NX#>>k)7n?<4LCNS1HghXy&R^18WWZi| z)-#1*Crntfs`|T| zC3oz{PoMOkb}c{rq~?dWkzGrAlk?Dz#Sx=?T<#4vhDm|r!S(fh)UI7%teR|hgdWA^YLgCU@V@1JHT8qW3ezS_wyU{bQ78S)ZWfzW8nAH93yM*Vx? zlu>U9F`BpG#==#N{6?>q!bl*qN+0g3aRH? zcb8hP0wYxnbdu|!Yax90hCaG;`plW>EA6g0kwf*H~2$_eFYV%DPt z-CjIdX$b_RuWXfrPR6b6wdg@CboMRuDTqAW*Lg~L%xb@}tN!GzKi_I$IyPCS-y%hp z&8Nx`!AnkfT=yJ{A5%?*ADL8K92)I)(hx`{(3fAz#j=?v3j6l}Tj`ku=9Hv`Wns+8WfftUxmDO`!nF7ljY(Hpn46FNK7IlF9n0Ag_NEE22< z-4SJx8S$sz`#S>_#LlxfA0EMJ4{GDxo-X?N1=?pY{bw;n4`l|a7}&bdeyorX7)}Gj+(C>&- zHx=8SY9UJO=BVy=A8D6}8zR@oGR@594w9Jd$^%_mb~4Y+>!w)r3MirT<(ds$*hQ(= zG%W8H2{t0f9(Lz^;w$)UXV@PujXPG^(w4Q+;`$tKIV0!+afI>z+dSrgwk`MLUH!`; z8l<(iypg)2k1$;?f1p4W34s>R{*n=naLd~HX?)yDDECXq?SFms>52h~J40~*7X-Dd z7B@!@LDP5@={!@*Wasg&{ik8$tbIqpQrfQ4`fMde&?e&o%gD%(_G_yd8cZYK?^5K}RGe|enYVXC zYf9R%0j$PDr@heh5yuzsBNdRqIyv1B?D`($=@xKCr^6y zQYR#Y>LZL!wMQO&;!f9bNNc2EtW1e`vv?Ock2G^ z{G+O@b3X}I(>mndni2P2(rdKx738ZA*sry0AUb+V@ZLXl=m@q+g{E0si(M1J`~LQT z;D!~8i--3}aRx^d+%V#{IP)8@Z%_@hb^-HO-G2b?mp5O(*6?mlM{7}iss;Bv#D<)Z zXZLoEshl@u;WPV3R!upy?*2|7;dSvBJ$=6~qHow)%`+1JsAJ#^}L^#}w!Qp;dl zuc@if_YSu|>TEtiVq6-N_``=*V;O?34%dSj;KNRwTq@q znPRwPEpVQP2r}whU`ZMsY!=@^Xf5SRK2>qozazl5OfMFTO5K{23KlET0Fh6B&F+q! zPua%|_P(+Z1x3UDxmU2op)IOhGqH;8&8=a3)pZQvAGJJXSi<4KsFiNT3EG*=ms^;^ zK$Fr#*wNX4013@z%kM};r#NAZApbhQJgvkd3O|QW&5%+8zd+57FFRBcL_Xqp<@M1r<*RY1$>R+F>I|w-@9w z&UW;HRf_Wfyq!B=2F8lgi%GHf$$O$Pcy6%oGvCyy^U(RX&V4$b1p%n7L9`s`|DpR^ zmFmyySrFrNiT)_6hY zqA2m{Y~&UaaJ7VaX_0wn<_OsTkfRfBR~?AcH+t+_B!&g3)pn!X6KGCEq=<;fO8oAR z@4FZMaxeM4K(1|6U#H6Lrn!Ru?nka~r*R1VmX6|Mf+V#M*hx$qcvuc7M3*i+d=p1K z9k(9Bxgm@q(bpzF#K(l%Q0&S#%!K$cq~yLP+q_?VaGxD_O4Fw4Z``Xo)mkakL2Yu( zgb4`_=g@b%fid9n6}6xY|4;3epO6oun_b`OJNj;X+zF&XBJN8!6&mQug~HK; zp&~MOk~uEVR9b*YE*pBRU+s9?i}O=r0GfQq&h&@|J*{HK@~c;`@;vBppg~f!*5IyY zc+vXkOzxBBrG+|RcryLkvQQk+T9eK=E!QjML`4h?I$VV}#id<`j@G zPid0%14+G@)sUJ0&|WkK-co_cTi&KQIex(`EL>ivN;=_ES7$h3dT2?a7JMa8cwRW# zTv|9~r>(<;XDyqj$YOT@g2tRim->Q;(ny6>|8Z^pc_&4KLwT?FPXqGLe$oZ}`9_f0 z+7sTw8TTXv;S4y{q-G^#8*01)#w7>_A%-Jc<%jqSLSsQ77)+m}XzRby&S_5uaw)ot zY`cE61;PQVgE4X2|&R=a!x{VZC;cSUl+ zoZk!)*MQeTIJq0y9iEq<9ZgiB$&)61*tl`;A0EN4GwLh}g!jtC zD}k)2O6_K(sjct!{q&mKH7P4E?(FN5TYFrvI| z_vbxBlL{8pk+w8-`7e^i2vk(7T$a?j-)wA~feND33CQk*Jb#5#2MP>bWG)LTY{nrl zwGrY@&;)HTy7#6R*jf&IFJcxf?Z|>~to8~Kf4_@;M+FB4XUv=_-S^^7ZLP7UMjqbq z&(5GfiPDTi$H@I~79RFw0`rLp zRxIfYKyMGYo;0eUl8C`TZzEZYL;mMaK$M%9jA+1Fj^z%ih#}c15+;C&?ri-TY0*n? zz1)^JyRI2+9$n-emfg=W`68+TtuY5~8Cs6gSie5mViyF?Ck+^FW~qc!S<32vlQU0Z zlYYsFk;0FJ8Jys9%?9AwrC zNds11WF&KmzMXR&^;o&TS&k^dCqVSHjaUG%fZSDS*`Q)M1~RK_`w6coc7#hX{?J0;VY6Ky%%TFuyUZX*6| zVdz{;bL*i&5{!b3+*>DI{Shb2<7!G;bL!U@#oJnw>L!qXYC}}31u@KNW(|f?l0goz z%dAH_Wz#!(8u519&oRK9qmJ^C?nZ5&&MzKoNH8Py3oB#I)l~wyV#=y(zv^jv`k!~m z!T@&LMww0ON1xbsB?~ ziCv}11QkD2Y-DPfoUs~1fch8YfqH4kQexm||a&D`d;mItS+4SaKcs zb`Y|d>Nk4;2=d#H(YN0@GUtkNUkDURL$d~wP|a1&i3YaG93R5S1Yql_!J;%)Yf>I( zM#)2P=Hp^}0KBsMUr!6GYjmN3soc*ds`v#APa0v#)LLxOm8zTmN(Xk{ppC6aUh#?L zAaISqhGDbH8tyzy-joa3=zB==X z4;0cH!~{VzAX%YtbV^06>6NY714yHmJiB>00gxK9H?{iY&%QQCxxxnA5s5)>;@f48 zE3-l(Gv(-<@r3pNSnnV5zFck9DoWxqi)2}$3$7$G<5Ju{{Wodt=gz?6PN8BqLnMZi z-u@xG{-XgX!`(z&NLZ&B4pYjbO~rX3Z=JEe{EsH`b6zIC_W|SYkd`F+4o0{2YY$bQ zwR1q1fx7=p;bx#kOP{`l=K2T8S9vu&hfkTJrL*st$^WQsu*x2Qc zaR;)r)mo75NW3i&*yc>*Fz`LOHg@U)UV0%f;^-PXVk-2pb;PGAHoIz>v~FcxP}(LP zDG}TmmydMuY4@a0@MZ_JxBr|!u> zW@e^;WOU+Y=R;1q zG9Mklug>Dvh4=yX$q)}F7kQM0ZbT}`!jsWfKyH~9ccPeuuW7so2SilaAYnM?2IrZn zxXYaO#$RID1(FB$4;EXWn!e(8RNt+Kw&zi>PYv49*U8hcWSY95% zlSUv=GG2T=W!SVy1{bqjXfl}#+D0WI*vwi8FO}Bnztv1q3qnEr5^i8cYo_kMW`;j-uz+O1UTgs%?6U0 zTQHv?e96H2&gQnfRM^;BQf<|V0a~(PZ+%yJlq%<^B35WlEpz^n^!`!2z9YD{^H!{= z6x_IXGcz##`7gH-$Q5VST8>EgBiQik9bBdG{7)5_$8CkUKbu6v!|(vxoh!psqJps} z$R=c36rc-DY47A8+iOv=dg9hAHE_b3Kz>(*sCp_@yKAK#Q2~+JB>}X}>PdKqK(t2J zv<54D2-ki5ETl2Ag|MayiHE42+RrIn+quh)KmeTbdDKLBE85k+9qRI|c>GxAcX6ST zGDMWFc*=?VJom~A82Lw)9TrOdifl|g!BJqov?a(-$?p8-<lR}E(1-w)XyB-xk+M5(jOKQ?jcLJVH_R14}Monug#z7z$clWD0Vc#b0md2DD!5-4lyNbolZK87)! zBzvKw<8>hZ8>9oCm}rb5&ZW?#rS=^U?=C+U>TeDpi6=>+;juT`}a zSYcJ`dfy*pd3p5`!8@h%{Qc~qb$$aRhKtS)b2QNjYZkb2@vjF9!h=~h z$|9`>A`6SMTD}1;ag{ zEg4BDnGrt(>m=5v1eCpmMS#(MJtO=VJwKMSz*A?HT*3b6U$@0)w zxk7^P5zZ6GV!i@6bGaOE3G3WyEw#&xKAIk3J&z|~qL|X=%Pm2r^a(v-35kvHrk>sQ zwDYnM2=ne62R^F|i4zoo;;W`zUs{#n$tgR!i8$iyJ{#f3mWBea`B2Z*RzLZ~Es-$?JWZkj zn7+;!Z|sK3b|Wf$ZZ|ST!^tzaAJCTi-?h)aHJ*}?rL(OtDqI-6{)VL9wuA3NMD*i- zGEM*7*f?70gwZBW+520b{m(x;zK$V@y=uLPW<25GOT`&+JaJ=KHWYx{Jjdh*ly9o( zEBeo8*AK9TDX99beEt61U4yep_+Q)n;>qbFN+8y|5pC5t^O83q`P)90u;izXZO0z&z2V8$Gej?%JJq@}`S+{B{F(Hk1sS{P{ z^=#6bdZ6DA1(2~-*WJTulY%7|a3Mr*Le1G8Yhoy)U-J>KQxXvhQ}?%UOrNDMzVT~< zD*CAV&|N!%;B~(GP~C+Dl;PPqIkFb*L}o^)_3T_Tm>L|67$&h2R4u0oM!nL!pm!(gdOrx;-kRAQ{_^lBGAnzu9 zm_VMav{`|QGe0w9D_g|fDp)H~CkSX&ylq7JX0=*qguijKP{!a%_dS1PvfOSJc?F=_UaO1BhIbpwh?=E$t6N-#b0<-Jb!e8WHd(+B0rG zp1W((G-!O#Fo5o6WO{2PL=@lhN$LuNaEGECHV}H_Ct*sCqjE7wq`golT_($oOo36) z?k#O7yQ-z{yY>zB?wMJ)L}}+U49ZDVK}d zN0Qi%0TL6zuZ4P`U8EzuGObKT^?N4ITD2_%4>-(2nc$Q_ng6+3pfFx zm}wzipN}dje)Rc0?;i6IMFJ*?$W(irf2k^CGviCim61}>~>&b=iEow z3%EwzJvS6pNBw!!lP5ihzX6`pk>|DFp{xSl(qsQ!IGKT%G$1AxL^kts2>;uV?6|yfxBb*@NYd8#Y|{`Zib> zG@EBh37Foe62Ts=XP}lF$yEuFchRcWgz|Xp%I-VAv=l7W9xn%v^SrCGuh~so?t~^4 z{=l1(dT)<+oN}-DW9srd%5Yq#Grat84@>Wn)V^?r8UJjf=wrf;oQ)|Oh1+plRhdN8 z)7jvqE0ndCUB(X>3z_pERlMI>HRb3{ff=+dOSWT(O_V^pchska23?lr1m zu}!@ksVjq`gB1-Fy>t$gZ0Yw)f5p2`Ir7hh&abs$jK`DbSzTymK|@BcDbSjYT%bm4 z<}BQvDQKC6glK_)WWsx(ZXR0{r^XG`stz1K-&gMnnL_=l43KsLVHfWFRMD$-6I%o$ zQuA&>w3&0!h8*U)AE_0j8HDLb6$WpYx2V*$Nc+AY^`A%H$EKw~YLaMXO*PYU@FZm*u6X|S7cc%fE8D@HSd zeTe#tDSvG;j(2PCU>5N4ed?vy?uSJYY}@B_KJAhR4NS{RXJ( zsuI+=<7O$J(1r24$?L6@V)^uGY#d|x3ksenZzWk~ zg@?<5#vs)Ts$Jgl;AT0laOdY~27fZoU)P|jFs{Lg^+l#_tfz!`HhRH{Bx7d0nJq$~ z61;`)CFz6O4WpnCV0yZo6nSh`MWfNgwe+{v<^IQQ#JZtbv@6F!jo1kI_8pRwg700K z58~qFFPg{g0(*OHan4+q$yrmb32$d-3I}%eMk$|PIkFWpxHrLr=F7Q;#yV<=g}zVF zKWJ}nSN*sbuGqsLzLc6J($dmQ=Ei>@184@}7{Aer)neu@Am$pmkDoppVRymNB0!Z2 zCtLLOZn?WEG8O+wokKC$_z=f0Ak0#*f> z=K+Gky~E_Erw3Euv1f}&i_|WSI_yxFO^mZ2)i5^veYyS4n#_TJr4)Pq#T;1Zfi$H^ zXrAE85y1EggoE7`c7*G04S7K%I=Zwmg`mWES(!SpV$zr+y>pe7oB@JEEZt!9-KD$3 z<&-74(7=^^x!VFCi3^7gY`*cv{N1N3<3m$qbRs@0ox}=ueV(0~vBB@0f4XT`uNwTQ zES7!*=MHR_sw8PqQT080_j-se_$%901+NFBa?6}^tZ#7(GxI6pm#=LSc2#v9J6>>! z1_qyYHMCOkf?0KH^o|ahT+#E8LA*IIUeN{Id#oJ3OXS#$0k`8v^j@EF%^!0h#4s#s z7Y6zF90p@ee$|(Ra!{;j($=W)*b+m9w*ynJzBovPXwf&C>!HBES#GcLt! z?$AF!7M>suH-zr4*yeBh3*k}0N^yf}eYt!E9X3jQM=*yZrwc0{6R*o9Q^Uz&1U_Jk|53+MkavtScQ-1T}_{$+# z!dx6&Qb)N0MsZy|J$LAHRqsUpBX8Dk&RJ&a7n|N>f85xlExx)pcEXs-{tEMaA2CeE z*lB4??%l`69V??7t%}EJxEg?(FY|nh!x4D^9D|ywLq8hCo6$m1FEB`VR+N)3^}Tvk z7&rPNXWOnV>ve26M~xD2kzU+jgnq%-&d%IMKId6%SH?D|iS*sZ!G7{pZ74DJfpNyk zZOB1QWj><-z{mKf!o~VG7vR4OYxNjmkAI}xU$nw%qQ303yZi(x#0B=Ik|=Ma>Pkm* zEY;7ViJ6UR4U_$^FRbor-p{5qua}0WN$2514y98Nd@W2IvydliqZ>~CMnt)eBO9*d z!5jX-kLhE$xUy`yku8Hhf>!4JVBOD0>vO&Hxt=sVpFf`C^;|2sc+bg-4Cn#g@-Z|H z(~akq-(~z>(SM&lp9%aM$eoNqzwp5^7gSZ)kmfVXRe+Wrq=F+J~ni~=bBBjcHB^jm{%)3nTbLTrw=>EijtD~3d5IW70SjvXsoePs8i zsPoGf7pnGSl6{TlUKgty;#%t9QN}KAK~C5{=8Y>V2PC?lM?zTk);jsl)3}Gtut7( z9YBiQhV3r>aUT=OtY8Pe5A-K8Y;2YEjK9l!?!txZfIBX@A8O&QszK`Kw_;Jn`q|Pp z4;Vnw>ydZf1Z%!(7t-ZWYQFn%r{Lq2AMZT#V5`3>8`%MHj2iXisF-~Ci67sreHP2} z`n?xi+SQ){Es%$}2r{prLzoh$Bib8I491U$Elbt_H=C22TB1_NFJmO%`d(pdrQ$uq zS@i`&d4HdZ8cH$+``7XRdmeuNsXiHq(F(DBGc4;X%l|6S zn)DS(V+Z)?xioqCktT5jE*Edn&s>DQJn_%J`gL>YD1AhN)z~`UbMalCf`$E1A~V5h zpAZ#^uBG*!6yJw95BJ#n7OSTxAT8a|b(l})Y5Pegk*R-%hC+w@CCAEIT2HDNV zC4R@?`XgQB)&0WO(NeddAED}+M%(*D-iCobr@(dBW~XUvWW|QLboH@U0u%i{v8GX0 z=!f0Yq}mf&n%q`OJ*9iqujUqpfc8lq)l1o`n)hNa)6sbF8e;Oxa5DvEd?uMT<)I%o zb$yt;65M^zeHn**r7~)$GK~6Eoh02V2(&3X>L)C-bz2ZKnedOVJRVcso&5@~9!DNt zW!njFXWUg`GnW*0L$Y`Q*tHnP+w+cxhexFrDWaMMs#oL2Cb*I~nnXGS& zIvmI2#A?wAMN|z>^TfO`v%$*O~Z~^bR)9oBH_Jsan77M`>-i* zSCfE(8OR*g9;0NT**06Cz~q*is%G;H1ctoxg`j45qLUG`<5Q_T3#bELKfXmi!dDJLs&K!TUL#tZhP9*PnQRcNyz`Zr8_GFiJVb3)Y#D zWHd(9>|5eXglzrUl(-$d7ii}+J*h-Bf$2oy9mgn{cj#@s7q%>^Y%#k7dz5clF2ZOh zSHmeW0UyW096uVg4Cs|FdhUdI}Tb`kbp!9f!`Rv*)wP;}x!3twY=mb1j2aKsOXLT*&0tpA7 z-GSq&ff>a^cbB$GsXcEIaLE5QM_l}i^Ef0p*D*l4zx=wj-9FX!{^ZaAq!Q)D1mgpX2insJ_u;)(AhvgyIt_sgdOOz%|gFVQW zs_=U-7!`C$Kkx6V&%yasRI=R9f8>ax??PD;C%PKQ0EtZsnXBD#L%`c6czwM$dwa%p z_1B#WuARB;$lP2lv%G3gnUX|GrlFi}9TVlO3>Co-xh-#fyvMxuQD_T*L7UDwTp@y% z8}^j)1NCtSqO~0*RI`!)kbA+xcwgJrmO7(a!*u5_*s%BgMp@y9qNbSuG?yo#HVE1rTsobCt4^Qodo?CzMfjM}x zU~Z#0>yK33?_9EDoiRoVWMMQ=_u@GjfBK&2$UeItE#rhqPYQRuB4tZDcfmTF(ZOibJ@=l-B=S%CbCc+eJAr}@LROk*`5RAdf#QC)!)%%4*$}cMp||Z}AHJZg z?y&x2@q$iIP33C{n9A?EKqnUN8^tz?-IuQv$paCMZF6ra+C`E)MA5uEwocqfnoh0h zYa8dNruK%&;S!v8y1P1nr;+@LbHn-ezF1!qKW$ZmS;oa@M;R>YVl%6{_}bmQXz@c| z>!nj(my90KwbGrzP~CAO|L(Bu!o*xvBY|RnzHr5d<#_RYQ(<ZMbdGrpCOPA_R4)q=y8D=uuKf{(g$yDf` zqMa9#t&u5`9Dp_Uq5J;gu;o&lJxjBOBuJL7@M@B;d(_0)P5BcCmn&@U^Iv)V`0*gE z2DPzI(v%G%ROG{*+e(u4d>mO{4pCo|V2Q2?(G(;8EtWAbGNvKhNr2b7YivI?QqUoW zl#H%zbLofeZRj9g$3-Yuf~V02S?BKXEpVBWX7BC6DxYE09;`C3ey}NhF!wVTN+hSD zxE_ChVXEZFk!`nMU%%#xucyC`@YDa(|@)w8`6HB4DeT9SZ`% zu-BZ&i2`&k0Y+HUEHp#z%AUJ?nUCA^OMzzvlyF1|3c$eMdEbT|81Xl&NQeMweiJ)8 z``tT5w=ZHE;K7T<_*bg-kp1178b=Frl%yJH?9c+zopFh-} zKD2Ye_7G#O0h}$GFTOv~{>wD98AwTQ+>@@s$*9gvZ-YE&J^Aqjr7^m*G7Hiz7vlLD zNOGC7w^TJv?&98nRHkdYnNhL@kbS7=>&iDostwHm)rG99~3b}D^LL?i!=hU3s3 zY{(qI9eZr@AxmJFj2wZfp@r$Dh-Jx4ES8}oEG4yxTCxZcHd%5eSv-?PjY+6)vvBz%HIOhmEn#->b(e$Vh4lN(qDZ!W!Sfc|G5%7c0;Q5=H|YML_P<763f%2 zns=9qkRJ@}EvBc}Jhiv^-n46|@!iv2X?+qDyS3=~2c^>$u`jb<;y1Y(vT>WyJQsLM zGsdm~qvL~}#3i&<)*%7-2$kdfm?~t>(`ys}>|gsBZ*VmcZ?_Uf=G+x4R#=MdU&0Y1 zPFZN(I|2wQDwkol#U5hevCHOo*Gwr;IN0z!5r>q6MKR`AaMz+Cke5rgaIkEBnQ?^C zk;5}I1HCXZk%bH(&?Ni%=EQI|29r`eEe%vH+qQd{^_%pg=qvc_b9M%YK?r*#CS!MN zn=6kAf*1rC+e_CdLD##l2r$~}I&PE*qxfMpg287?WDLkE6k*Y4=q zYc8xqJ^4{(uug@D@|pRN2#QW%Kw^b%)+Jmx7dHVM?G!xwTRQ&tMfLM=w=cpvDklWQ zv9M~<&;w_UlA+a_KH-2GXnYVd1fHMQR6n&Z;u@+-wpmN5ub9ZJdzz=dpRVXUk#Y;9 zbV*VFU~bKO%ir%V!2@{0zfo7?jIEM5%}_r=sU^12_%LSr2$6?LXnAWlS~b^ETPiB? z^MBf`s%hWb+nZlCxAK3SIm8A&lwjY_{WtE=odcGf(wPJRD@O+Uj+tRhY0_i@wJz#R zp&{eu>eQVCz!err*(l;_(z)6XY`c-&LH0XcmYA%uTDJ&vKys^j|EQs66Fa02J3t@L zP9GYuoUY=0BB8qLpP)C*A@Di9IjH7Wa zD*1O;D^?~cC7!Irc!>a zRh~BUO@7qP8sZsnxNZH8r0k(r?(FQWr}=DZ@?_A@uM!F7-kgOCx1fb8H8?n!tbgjS z?27q*S@Quu<+FsR5$yJJuR>bR!J&`TFECqE(Yfamrl?7Rqt4_7iW$NZ^Wv~P-XQZ` z@V%b|J`+%eLy_L1mA>Yy=;MtW`(vQZ#hVEKyFU{T^=M1^`;)S9&12ZO0};J+EGmpIXmuNK87tFXP~z>;xkNcac)zJcB(g3?}&yu}N>%I4$DPf{-l2#AF$ zd-=C+=rKOj^i%G&RDurcq&p>BpwNVBHy0XPBn5N?*S{X_m~fEHlhR0`_;`Emibb<4 zeZ?+mfFaE{xirqq^T&sYE>@*q(Xa{x|A=pLfVSpX5PH_qg^b|_+uVZmv&82?Vfs(D ztezkuH`MX2g6dcL!#C~G0ZjOWByX(+WTDO&Kog^PhZHnK;dxo^p&iXT{32oI&#pI- zKkqb4{6hT5|Lj^uAUhp>AOMP~nWWs)yZPQbEpf7FtEP1Nd?K-MARqF?{mjZ#S_? zh>=~j4Oq-vS=sAa-b$%k!!36Rqx%h&kAuCvL7VR_z*V&RO&+_$$$n@bTynVx_Hg#` zEH7fpvW90@*D$a>9W_;_Ry0S5eO?L(E?n1Hm0}%NUT+oGDydV&W zQ%Z}T$r@j$9z9cU+s5T!jxMrBt0F}8$+>TO-v6L%CL^<_XP#FVTz#zU|AG`_KtRc? z;TPiO4r)B#0)hgymfTbmIJ&`N5x8JATvkrIwme{0?5SIyp{~WNkHS%du7^<0_xpYoUif2c83QDYx9q z7gxSfWxQvn-VkWwWl+O-9{3B+oy^Ny-+1KKEH|MsB;0a8IM!4Mv;K>!w`@mCNhmLO z)8Ai`dD|)B5==FX3i)feJP|mgorJ{QB(8{IUx2 zj-k5!eunYd2S`$(^Q)STR!U<0+El*D)QACH=S5H*m?P`4ha~5&4EvvtqDw84W4*p_ zSkC5uYGcM@RV3B0kI-LYS$(MYJ_sq5yBlWg;ON*UEH1vDG+;pioe=Bwuk5VwKX37uP541l3YPm{(mi_2ANi__E{+o z_+|n6*8OA=1!S%wA`I*ViUeBkH5R3bLs&(a7!AmMQn(w%TQI}siTbQxbcEsea0U)B zd0-LimVjD*qvIK-j@^Noz%EEp61oFj0jGg^^lx+QVwv+~7KF8;NVY6a?w`)O%bsq+ zhfHjl)(x73A_rg$GLVq9tX`3ldlUX*DEH?h?6=N8yI4|^2eYKeczFlPs=3CFy^fYU zM3K_yuCL(iYMHj;?uQvEA(q#uRoURP>1ac520)`D|D@R+8fobF^fwn^mNrXLLWlOJ zqFIYSO&bim?qAQr=Ud^pavnb4Ot)n=pR&LsZQ*+uZ1U>Gi**==$kSSQ^V>sL-*=H> z2~F88J?g+f_5nWI_GsHYzh=K6bhr)JF#&cJANRa(yEjJzb-QFRShTjMy*d`LZJ7W1p zY#VXT%`mNX`Su*WyZ|-ZriV9rulJfNJHa*6=K{QC{K5nPlZY1OCZsgBR z`V2ViaVep`#gV}YaVY-4tw4$qJNuWN-cL`}gG7@x`lzcd#QB_1v+`>E>wJ zBY_7ZeTs^TJVs}9i3mA9z{ni|sy0(M5km0S6%zz0EQ=>n0e{Ozfnw-Pb#O~;uW%N+|$BAW^UbWOc*!gm(CWu|J?LcorM53n%I3+T?0!;SYm zw#0idjojeq0+!ZcXU$m*h@d~=l{T2RjP;W+kB|@|^5^G&ZjL|CZVNVICsA9%#&xw+ z>>!Dpl<^pGybjXC&U@zul_dRx=S-R0-7Xq^;xY#bBj9FEb+Lq$+NIHpk&Jjh_@0z) zz|?)lRbJ@tm^lfJK3vN6FPv=-Pk;aCH~ss){=b~=T4$OT$^nt0S-LXGdheVY({W1; zKGUVG*UseFtpi29N*X~?3>0yrYLSm&uF5B%c`1UiqeM1w-DrOr%|HP>n(u#{s1fW- zsD#_{*YlyYNB3zV0!1i0aN+A96_i-?<3M@iKY{@(MzKfoP|-*d8nOr9%|GcEIb#3j zE8{?@d%g6%V%_nd7s!dVwJ0Vjpr>$ijvl=casy7mddvSuh~deS!*8@#&tCoSC&D(F z$)?num#?((@mO{~k_Y-aaYV};;P6`~^|5eT%i9w=O3h4*X_Rv(|DV zpBDw95?f&iKR;3`RxV$5_%BW^&SCv(l(L)OCH=*}8;8i0$Pg`p0{)7*1w_HdG+=Wm z!Ht6*-s!^bt{XYhespa74v~wNH?U6JLW1muG18v1Yt5L1W{@sT0RQ+(pXoN7?{E2F z>G5`d}ubSlQ zdusst4doGa7%{tsqT2qc`q*|uHR(fuq;*`7$WUmp9^)wf}WkkBFf(Yr<$ z7^jS?T-@MmjoNZLo1Ke`%Pv!YmH!n0#BhHoy1l@?IXr6V(x}!{yL-NqqJx;VCP?+y zP*IkTkSFJ>Zy!b%*3KBowqq=fc#?t$4p(}*2Cx#+q4?+X=g&ETx5@j`>LS(1q|Do@ z4_0++aCl}i^(vHm9d2qs_^ zIoif0;RYX`WsJj>npm*EXaPGPUjuFiGJoIRS|YWegO}~6lAddB%=+(U{;Ey{V}-WrEyLMtc&3>&8oJe)52K+9Tx181 z+<32DAX$figk80TbK}qDGnS&OZ5cLVLw>Kiv9Ukt(*W)>ksAMmbtZ?-Z8QeG-<( zGWGSntyLc%1^aerObS1!&o*%9_|L%WO+X-G-8^AoMqKx{Y5ybgy7p5MmVf8w@UM<@ zumH<%6mLk?Oc`^|mfZ5tpV)1)19556p(u!jE!khcjYF2d6r}tg-BB(#2?xW_FdIL+ z7f(UrUbsJ3H+0i9BsJy4Y~*;7#Av*@uB!)Zaku}K47)O%@Ow{8V||=|i6gZa*})cl zn`~oBoVuzW!Yim5f8y~mhmNZZOyHY9H7c_aklPJRTCGPv^la#EJrXuD&7V14$)QW_ zA}1&3dK%hC2YXxScJW@`XA4-*;?K3MCI81%i`@Btp>n+lWp-EO!T>)za?(^J`PQT~ z&_E1|>sG0A?@#CmlNjQgdlEhhmd+usuxAC?dNCB%cc@L?-PQSC73OWZS3|pzET%`X z%ooy5VWyQLQA$Hb)U`daiD`XKZ4;<=TQ`_JqmnM(>&q)O3jP!)n1rFR ztH7eL#E9Y9(7k#b1`^SLbI3$EZ#H0$4luVb4!-`K$g&(l4k4Vv&$0iPjAhqk@b;3P zA}}#+0~2uFiV0-GVL4PLUPET)WNOCJ*lVllri~q)ot}`6S&z82V!KH0Y&aQ!vY3OI z3b(vDOD;AL|5VuhW#4Gpl$dH!PY ziDVRcsMOdl8`Yhl*b_OPtO!+j%3%6)oq@sKsz)84^JOUcMaA&RR=jmB;|9BgPWV-{ zV9VbHO`MpAhQp1;S~rq8VF4})X?icb-$rzb^9&{b3Y@e|_2-ESx7%bg%M){)AdkAX z7V#M(#@cRxyK*4q(3}t@Hl9QaL*={fon?n+0~p|>gJ>#+{tafjz=Y85u+k1%#aO`< zf`s1LMfYoR69(G)>^6>Ke>1khtc5u90Eee1g8jDvN?FS?s`OMNS*L925+phyYjqB@RH(Cst9qPWGs=MOLI{F?>VgBzYqQ_P+Ia z@KY@EKi|$k3Mu>hXRm>yM)DPS#`!EZ7sWCp=xumz4MdUzsgjiDqC zvNNCZxF>E&%W|oMtO1?jfdEl;E^ix>#K~?b6mmgiIBeI7(LkCYZM=T$_PgcmOc0NMO%|veNx9gLirSLswN4I?CevN8}CaIJu} zpxP;H{tM2<>?21?HLb2I=J|$@utw7~f2sWG6;6Feu^}Ii;xPR5hyj`gc`*Pk@~|g@ zAx1_a&2gpv%W{psXCZ+NC}UrJs+h8XMFmck!HY-S^q89$ab+1#l5Gnnx8JS?Y4%X7 z1+d3(y;$`hKYkopD3>TKeEsfSNf0}|YMlG?MAl+-o*1(y-h5-|t}=#(#Qoqyra~^j z%LCCT@mlD=zJ#lxw-d0!dJMbl?eej z8Y5N!qaXr?^ELsFyM}GH0hL*dg2;|J?L(Y^xkU&e0w%v){tJwA(4H76#~~>a?a+Pj zJ8-AD*TD9e(AZSw#9cg&_FSZ#)VYrSZRc)_Wxrp_c{D*(duy=zw z-3Hub&D9H`kWIeCou1b7*e7zqAb2C%{itHgjuj@dAwW1B1ie{;tKm`kFFIjGTv%|j z!r}6FW5;)~$b$bqnD!v9DqUH5o1}7vT@AZPtVTj{{VXoswS;1Kz@j1>$o=6v#f+~* zKk|okN1xi#*j65+#UROdBe+R+Is_KJ_16qZB| zyYTTD8!Izc#riZSqI?<=Es?+yFV}kg1!66zE>*`#L_8CBKzHMB(>Qv8XK5FU7gqkvWOnW`{-^%i)zy6xF6Pwt+DfNvU0p=q$fEZhh< z%;T&m!g)(~Y9X?{Nd-}l;9I&Rkz@2|K^IY6b>8>BB=NZ!j3FEwqi*x$<+oGUH!L~n zkJsvdwg*E9tCIJ4;&#@2!SxFPXBHdhBi9k)B11c7=fDo;v%+9oyqEw_wxu?oE|Ezy zXfNaowGFzsD{gzQ=V=#pL-!~f+4tcM&KM94#AR3gZfv~6W15t|tK_Id)=WnO#1ipp zJF(kRlO#5<8c@-B|9|7N0#_pmMQ2b!!onP#n!s(a&e<`$=$2FL$l?7QQ+-oy4IN<*QoGLi3`}w@beP8!A zEL!u;L+V^H9`sD&0%nA9$UM=%EigXfu+_Qx;5W+Ul_^6i8T~+n)D9k*wuwVs`$i6> zukBluk9b2}oz`X38DVVG=|1TDygZt1hmq2X=ni*!YKwnZmHisPWZx$;TfC+HTPvuw z5hsrAqp}$x2dad^^s(=*1J1M0C{<-pvi6ORBe;MtI<~Y+_++gh14&G`iV!^KKT&*} zifX|;a(=^9ivzan4-VC*napvAb3zFYPBWR;879zCYvOb-JG4P)Mjb#3C<*j~iz+i` zP%gL$gz$v7nuEH9`-ZRYdJ~zJ?&id`}q6)GTcc1Uyf$T2<1Nf%!E@x z=iy=B%WnH=hke@st-i7O0Vz^3Iw3aH0BNxc&5aJ|VF8c?gV&y%{q!!|BZ1nz4fHUb zhA70?2=gQhY3Ai6PA1N{C8B^}u*6>B{2PK{4Mg?VJo)#B!^1-5H0>b#+B=$u=8Qxe z2A%v0=8CeisXd0jMPuE!mTU2RhCOL90Ny^{YJe}K!_?BI9-1zAI`&HZU?CxpFhF?} zNF)wNK#e~+)H+eKQ?7&#G>n8w&$bKeI{ z9(6U3x>OFU@nPdt{Q8%g@?9D~z@WsG1aYPcto`ZO3G3uUm?*hiEp`ZJ&zHj1*nd6u3ewbgVOr=rm;0D8ns3Pbmb<8JM!oyt z33|PQ4i4LA(67i2(;>qyFJZ44BHyATY>Qi^F$R`3=fxHgSwI{d^DzJpR@QZBr^W5y z6&!zThb|K#Yrn3*4*wu){(1p*7SnCwYuu1leEa>c9$yxXinY*25so%4cM@R^)t6aJ zy{8|vN}ROwms-_Um672n<%YlU602rtrEkxS{k05FGykE_aQkw1u`?;pct)Js*Xg=` zi_V=I@3rHGe+*da&8w#WhmIW6Hhs9_Bz^wu@9*cTUs7i%;&2}xwjnSLS$T#p(2fu3 zNwMq@pm0(mpRa8Zes2FELwd@yI+tXzt*~I`bTWOY2 zu5z;I=|DxHneoK*i1z|32sm543ITt@as8W@{0<_+$0%DF7>J?&k^4{gQG=d;6RuLz zu6m%rZHT*igkft&A#nOm=wKgh<_Bg?j0%7Ne6Vo)xP=Fr$Ww6SxZ=GB2S+sEZ2w1h z94VgyN()WgC@p_M;MHBV~jg&63$jMgyce`+n*ZB6%v4tghLu#tF( zQFL)1a}kef(i+k`MHOPz>jOTt26{4Kp9^|W)k6c>jYe(!G-4b#pjjGAoUI`bFq1Io z!Zu%3{@d~R(-nT%3d#qmN8DKJ8Z5K-7bXxQ1_Qm4;Tl|5zQFH;(#<{&MigQ+K|Bzh zV$VT=U5vYH`>BTW6HlsIHd=L6tc9WfEr3M?U^aMiVO~o;%`(j+gt=qg-?SsRW%lgZ z(V)`a;?vzFn_Ve5bA`9@V1?%y+>4z-85hCjYA>+86w`U{LR^kfAeb_N$Uo#v0+|Ub zS%_w;Kq5Qpo)_^?B=d6BXw)G5<_&_I4@Jx}!I?wvP8_Qsw~0RW{>9r&FImRVA*3q$ z)R>_-ymaj9d(hVW06aM*ZCCl*B%ug)FV6n^X1J-i3E|$;Jl)#EOeHYyB!eR&%!E19 z5mX>--k=|I3 zp1x_?@JU2j7h!(|f>QGNhrZz3m_z@@PU5!5gRyyUyqd~~?xfl`cy_1Vk3s86av^<` zq*sM4uk>VtH{N;-hK_9(cOLaccj1_=R5x9bTBQ=QaVMtbixY#eW{7l)40^Jd$+nrX z+pJV@=%gOenvt3I9Gg(n?5XhzswMNDy?9Ylt+<;9yx&LnO+d1&irl|oiL&hGFs4eM z2BaVI5kyJ0a@KqN*l2*pL~;DH0@-3U*ddK1n_JyWAE-b1%>@{{K*Zz7rCJa4_^I*( zv6-vdO~Me%`r8?b*NAfDpRwIhY7~9`xCa`xwB9|i_#4n{apmQ`K?jK`&~&sjCJW7R z(Cb`X(hR`EGBR#6E!EIG!ej-Hiw`HrR^3xd7bIBdn)00M9dbOw>J(zd7fbvb+x&0m zVRat8mB&d*OIO8S!x@g0QTz8&r-3(8d1>^{Syy5UV z>RlU%Yb>&5)8$pEsHjMMpd)yfE(s?ZPEGU7$%&1k)z*Pr@K={KVif!FQ(8<;KV}gm zK>7W8^R-S_MzQhaRX5Up^C%<+wPen397ANvuo`PUd5f3wcK`X}3VX@tX!bw+XD8cs zf>d~2C&aUI)~;B^WMMxh^^k?SZh7U=#>O;b4rVLhQlBQ^1E{vT=t(o)=Bj%S2HvK= zyt5Y;QwGm2F%n5xvfntd%YSutDpd=;uIpkP!giwax|xK6Wnp<0jCUXs`r|B{e&^UF zu(w72NDUDB-2LAW@c$p6nPur$Obw&(n1nZ>1tdt7JgC2mZqw2dqj>ZvOps-!Okk0b zSYz-@M8o}aAb2AkCZT%|$GUVsW!Z@>{aJD##ve^6FYw9~^*)HF1HhQhyg%RnZxcN7 z7|lq7(sA^0>Qmlh2E>@}zsJZw1TZ~gD*C~E6rK-ldsS9@PBVkcZXYvdjTdG`5F*6H zu%sWj(MD)c=#!jyUSn_=1rB5+mHk>mGbGA1Vi)v7KC{_0qps#6G{qW3jFKZ%ft+9X z56Elpe$IX)fZD#l=_Vu^q_T+y>gBjY=&$)le>?Ge=YQUMkMPG53CYt$RH1;*L4nAp z20?ay9peV3?CN`umZS|gwK!OJVm@1pCStAsRuo~xTuMy+cv5}R(R+ePHf^Lx*mBX~h9JP{(rq{CQ5~!m15H{E;Ds5&5F}0>`14 zQ}aLP-PxGh`;>W=r$^)D_wOCB#P9_ZZdE~^MKd^%7R~CWJTcQ$t5pX;*+Ja5?DQOx zAsaZeN5e?k=v7J9nD@hWvaah-5oY-f6ww|lyl`0tvg zA>=dh>tpM*_kAC9P=Gt~pI@hN30{r(or)j`J0%p&>#H;F-o0zi91e3RGZ1T7VJ~e}b@g<<2U@J>F##wNicu`&^y)Nw8$_Bb;i?>eYI8zWV)n)H9k9FiRHZ|l+7fE&(`d8@?+%IR3nYm=3`_p@|_SN&-n|9k0T}59M&$hsXS}Z{0u5i}JdpJ8IEx z0=4EvjOn!6PH|Iy)_me%9$+8P!tgm)0^$UH6#l{&F^VgRJ$zS8mu*?5QX5tTQS4s! z_Vxqp^qO1YBjTB>uG9GB9BjiO&yVwH8rGR_nK$B3qU-i^Q}{Ul3u@dTtfL*L-}6%L z$uqDC%6VnEjecF*Hd48i3cM2Iz=5*3_7G-iL|B9niR-m5o+Pb+Zz8c;f>b=GKn(|T z6bAH3x?(H1VM9R6lHnw$hq?GeIB5rujPR_2JXla6@qeru4F7M=?AP0c@Sx{LE%2}> z4z3C$TZ6UN-;QPJc35?v;y=50?-R+bkSy>6+{X!c+4wQgUpv!HW$r``*GYVnL7WKY z-u1O@wj;bxQz$p_?>#L?kVzZOy?bUHOeC0R$EZ6O!)GCP7{$us?(an5CY*>!Qp>?- zOBBCqlnxKMk+Of`+MP8?APl?W1Qjf{;r>7lB}t5k@`{FbgBS zs6YZI39@;=#}npVm*DZx6U?XnFzRIG;gMCQ5{%trTawi=%xHJ=NF(bSkPk1Uh?U9$fy82tS}h$|=~SvX5;w zHTaR%fI#09Xj%pthHG0Asg8?#PqnZ$h0&knEnh;Cyf5d|wxPov>vBefhNGlZSU3OW z}uyVp&z`E;}g}SVwNx_)a z3s8s+AY-trueH(#P>trce`;Wfg?;Jr2M6c4L;7|QL|Sk@WWWJB7Shn)6%aghi%qI9 zgLZf#Aph|C_nW{2{bCzRITs=;1Qbg^Zl?^FQEshVlAB#`zKWJZ&%}NAWRK!tM!{rx z%nQ=#gHmf{6z&Us)$)f|8#O<$L z;8%MqD2NNZ^R2GoRylkwOu5Mc08p4M*Pet*aBP|4bGl6RU;Ht1l|-nZmhx!Sl-H)L zp}ZylEX(6#*EQK^Q{pOYviJw;OvE>J`(`Wfu?Qc3JtwEQ&4HWi_Ul8Ia|G7)8;#!a z3oIbYAsiUqE~8^(0h^D;9K=d2*Rp`Z{VG*5;rLrpK}hTIU2(q zqr@WsV_xE!ktvLYjM8DK(#Z+@4^wlKO142%WZplL&PoxG-ghsG-p?87OpH9G&1i81cNX6%%O&ZfO8P1L?LiE&bOAef!@okpB-)!>s{?gifO6iF@nOHzaxor_MIj$4Wlt?%1a#U^jl6lP|e>qZT?N#JsMg9sv>7ty~(Lb{QOX&b26hS0! z#?nyb88|#_2R(MFTIHshYrKtE^M@TWnsMvpVn~;>!i|7PcxaozPS(iua}CR22H|dvWszvq#Nf$ zenW_PrjeCGfB8KBw_paG6Z#bNpl@SRP^J;}_ELB7L6f?K%QJ3W zvM3jjHk=_~2Ko52A)a7Mu5(Sl?KG-kt8Aohg|nZ)Ny7Euttw7^@7itTxO>HIMKb?- zacwQPQ)FUZdso*+sEIv@Ma~EAuqzCox4EO_u0Wu(wd28r(&H zI4`_OP=P!cBEaj6PxKuE2zibS%7%@cpSHH@5<}`&VnbK$g{0Ey9PSqaKJN(s@%^6s z$oPi~MCmJ=6KRH)jhJcdKzxY&9(H#2LCi@5?;Ya$3#M^K4h!qL`KCU~1LuY+4xAyG zTaFAVF%qb8F$>@nE+@_fI6o6Fzk99?F1?J+z;K71v!vo>WZ|X34(O#z1h^v#LfKreEm9CRrQ&b+&4KMEKd9`?v%k6mA$?-@_?qifcpWLh+ zd1xAPMGT}UZ>lrI(^t`qL!PaTar!m{^_JM{Ely-zx$@+NXIM5pH?!3Qji@1RBkYeX z%%7X*$-r&+yDJ<;Dwen5Tqycir$08*{aO;^zA#7<;U@oSL3eSV(>doCch0_oPmsq9 zm>eIdkQNU}+pWa+-*RjEch_j-oYu3hHvBy|D!T6$_9kg#2Fy=(+TMzdjSW#Kbzx!n z3g`#)rp>q@P3%X=kwo_hMqLfFYagr!`1S^r19;G@fazl-(H;JhRF7!A66htz=pc{A zLheM3AS_^#g7ECWwW030s7=GhV#+89M{bH(kz<$5qvp|wt*ZpNH-~+c_~by8({nRO zO>lx5lVo3T9}YTY?+P&#CDBAE^n7qo7@W24#~mfMM6JLz59Rieopzr#L0Dd#>KF*3 z$&{)@tKKbN-(d#N@bK^&a#K)K>&>V=GibKQmt~Ar%jTf}|KB;KtxE~p0nk_pRHUpX zDWDn=lcsZ(IuH9uC_U!>+Y=sPj>8WD!@PwHhi_fmw1ld4`9V23UuxRo3i*LZ5V2Qo-x4C~S8LBl-$l6o9Rk{w4Ii0WdWHM68PWuAcDH;u6 z#0Xo4H&wzdm1m&XEejLZd}Pu5F{R0$M^h$zm&-oIM1!B}x~-R(8a%Wg&D|?@zcElcytpjn+pc;c)pa|%HiruYuIdqw#$*n+BxxM(8rtA~G}8h<(KV{re3JBZCWIg1v#B`SWfM?K78G z&IH|l3T9XML{pxNZ3pqWuhm5H(d0@JKIR}M^Nm|Z;dgqolsBhLltJ#HOyZ$V_yaD{@n-ZWn%Z2V#wmyBD#JrH5ob~Psx0c{)kNt%?w8Iq} zNO%Z!ADPa;46KK$=yeYfZVgUilXZ>r3M)>20n9h4SBT(ozIYizjZ|#*VJVl_p z6^ZM$^0iMrUp5FP*-i^Kr#K%8SJ(WLoRcVF528ymKnqtDK_wd9d!eM5Zu?=0v$~+G z>I>{e@quLMXO}su|56?PY<_o=eUxgXPx&F6h%!J^mt}*eo8~;ZAVKNnyjmv(?vW`1 z$91uHDyK*4ib=QuG8%|gQ8W!9%ObG6UQ=34gxZ3Kgqsv&0?}7-3fE+0cr|%Z)6bsb z7q?Ydlfhr&9%4EDd>_Bd_cd&I`Bax|+}&2t`TF`E#M}XeD35_k{IbUo@^Ay?8>6Nj z(>V@YMr`Wq`$*l=3@A|#CFPB3jOolul`Jf!8RlI8HZ*VQs^@zn?29YIX9QUM{*kE! zB;nK?QRwy{pECQ zY`{UK3`XHD`sO5|j3RW?oe7uKeYgCVA45$cXzq>?(AS{+=Ga(9q}aIH`)tb}&@fKe zSbKcb5rqmjI)@MmY3a*=>52%czf2tFZ17~|0}ectDHQ1Vq}63C6r!+7wd1&S$kdn# z>D(VUQ-x{76v&lF1T~FiIV9^Bb7NUZrd}pqp2wkQNJXD!q_4kn^$}eB+(1#tX)M4O znEn@4oB{#zY>v&P+D%0@rB?PS;<0`h<*E*XT7JUYTgv3+}M{6;4Il1Zh|>_Dhr{S8>PA8?xQ=~PH|CQWNj z)N>Lto?}g2`LO@lmTo;{Gfpw3O3-|qwn_k`&sD7mayHrI z7w+{Y$j$`>C6C!(y;V-0uxZ^Eau|x7N>QN^+sn3NhdSIB%s#~VHKw1NncRxk5@AOU zy{;GPl#A^)!S8$cwk_Bfp+G&5Hx|}pQ!Ov-(gc@Ga7E&Fj+7S*Eh&2SDgeP&B;=5; zuD?#~n$x(EO z;7{on-p>de{b{10dV7TZkcd0UEd;h1RMd=jdnw zOkfiJ${ml$$sNw=YW{q>76LbMT|0ife~)lnMtt<=01Q*rgV~ZbVtU>iv9q%?F)|(# z1IL%)uj?in>qg_rshQD>So9X7+-2hovB8C$0b1);!?`(#n&!I}?JMM=!Ch?td3t2QtIkG9cZ&_#Gcsl5sNJv74vS|(a0W{lg^19N z^C?#<6MwW8{!}Gn|9DDv7*#`tt76htpwvSV_`*_PA>YVF*2kzGsHL#81CF1ARui z?fdmGI3RqOhT+6Jy&z!kG?3dlsjY{aW$;t#D;b=i+DvicLvnixPt%ZNotS!-Ul?-eoqJ2CQXUh3{$?&fxsh8Vw~iGJ8K@u<hN$BTTb0Jvc~h_2{8P{={U71!YU-dm&uX#rh~rh2z1kB(n;g_{6sI#Ef# zU6gm#R(Cw3C0hIZF>;|nZ?}OE?R&mqij^_ZrEvS4s%>C+I3Mv!0_igSiEXQODGwRN zC0ieRKzDnO9%f~O@a8W;GwsUM$|;$d_4kw^j8(!kHd7(wgia!^^pC-_EP1ZfF<-{l4TP7O|7|Hi=bJ zB!dle@UC-jx2*?ME;F6a0za_>a~7@HgbU41DPtJIEZ*gtxVSK1X8JNRV*5qzFTDxF z=Ph_!VYYdgvz2DmL=v4d3!i zu5gJ-4xXEK+!;ye&C&?`DFM7jhP(X&#)dyN)NTO_%vy5QaebF=0%$1>fkvKI%v6A4 zRN_?msu?@@0E$BUs0}WZC5Il#72c42dkg$O=WWqQJBSITUUef5Fk+0li1~R=&TD!a zAl^Rb&Qa$ufG@joDv8)9CM=e=;h_zPfg%a~{NYN=(;y95Yp zu%+F{@e*`cORiFmrrhS@S&bEXz3^qUdME*p+zuf522z-$d%;b$yqF`nz&X*i04$vO zE0|eXEtSj`)6)y>p2NKl)*HWiZJ)#|op7miB=NFu;qFd<)neAw%a^GZQcmXZNg{&q zSmNhB|2@U~r-*R~#%`bf!0si}Nq?Yo3eP1zd4ppGKi1~&q&owv48-PD&3EobWS$s8 zCeWE4@;tm9qDL*x2>aYhQU0bgL*+`AcD4KUv}is`>)}-%(bCc~OapHMDatP5gd?~10%0rziuO&@g>;wbdmX9O6NC)Hg_45Eg}|lTt<}fcu&!BwA*=Zt(r$2!?+SYNyO7$xR>OR zg9s927@DMUX^t*o)76D7qgccU;zDGcCLV>ULYSwE#0d6T!= zW41@s0$fCQNC|^P$;Pq>Y~-e_#~14_-l06;B??o?K)i0`_#=t~ScmI#;q1jLA8$$= z7ePYM>l?*IsZMfDnv7#{Qqr?+`_-P4od0y+Cql?6RiP46xQg}4K74Eo;$~*fOS^<}9#NQI zh*aa_7Y?|%xZoOhy$OTu;MqtARI#s*VIPC6qBhXS$~kmi4~)d7CGdo*l^RAg*Gc)~ zCe;Z(7twQ0%*TL1T1v`e>9S=cSS$W}-0CSzEo5220U629Bop0Ty z*5@Y+dR=xc1Xe!65wW@!Re9;c82h%5U=vKrxgGw?PF+lPYWs>CJrp!A2hZtYBVJ!s zn(@(`1$A*H87)rnUj*n6+k(|!v2}#SqO0PtZN8z6n_DUk!G(YVr1$LN<9n5Pf+o?# z-MsOUH0WmWyKZn0%O@OVg!3=M3Wtfv>kw=1EQV*7w33oiU|~*Y!P+lb_alpqSN_1i z<4<^|NLjr4$`qV$=g_(*#n>J#)Y+>J=w_6NG}j!ry!+5O+2ieBUdjk0TzNmQu#im> z%U@j1wE5TVsI88g499?&X#*SRgzD{sz$-!$s4O?d9U&1=o zUgpQ5@U8Irl}Mz0n3_t$a)rCdv>3goNi*NZ8GtvuO_5aFteGU(OTpOQ>gVPmCnR|1 z&QbcnR(LR5BbS0G+K8{^2Ea?n(i}t0@0to>-BPFz;|p z5z@@9R8g<~cJgFPeZ6Yhl{nX0&oENNjV-Cn+0$(*`%M^Pj=JDN$a2jSDy8GW9cmks5L@cxX!^IxU0z`X7(P zYy`qOCrVz_$n@hdt$J|c0KgFWN$PEA`5bcH@-56;a^D)R#jQ=|t=Dx~7yMadPcQEf zV*K#-$&9hMgb=)W`aKv5g2q;jN_rGBWAIs=yI3x%#z0 zvc<7$t$LQVLEvdYnH=?pSWx^K6;#ZC{ESs9`)01#QG4x=r@ zm_ahv`@)FR12>D|ltpO)tx86BUcZtU4=l3wTs3KFB-AVVN^S4J=!+|tFC(X&*#T1< z)t)X6qjE1-;2mqI$L)nCMT2dtbIfcp#a^>OA7*v`)B?YL=e7i>hA3k|66M7aE7OKs zR%+xly^DH~M;0Uo8a?+fUc5*G$q7Ze!;3F}D|IXLu09M$l_eX#=RRt;qc=0DweM94 zE%Z=135N$u?=EAPz28!DIKNta8`^1GflYfzN<#7t@u=`7Vk6FV>!=gw(+n?KhQ=o2 zEsg#T5+!Q=n07^*r<*aYV1&i}iloPOF6EnAw;Z#hPZJd=(pjtDo04PkD77BiWOg{` z`t6?ja=i-Z&_|n6I32V_lc~_Qeih|>j6ToH^XrU<=)Ils%?}ZepxTUg2PylqIBewc zVaBCPl?*=jpir}hVlvn@o&ThP{OotwjkwBoR-paU>E&``_O17{HAQDcyy9+a?)PgH zibxttu>fUAdCn&Re*O;BC$$d~%J<;t6N-C7GKIHMVzKSxAu*H{)j2y=MuS8Y#gaV?eqO`+GshG zr7lWMr^IIU?%BN8-esM^Ewt+d1(%9YJ_~FgcNsDc7^d7-K_7hxs*9+@4%!?JPe#nuMq)o?}KVA<7iL%*;%Uq$g9xU%q^?2DrGo zb`JOa44i11HqCYN=b4$`#3mT)=}1mim_S#zoc^hDonS}IF`?#_ZN0s{3HK}cs9E?T zsFV^F%v|i}Y1jP5n!k?JzNAJ6Z_=bL8GoeLv>N?QToa8F>(KFqG$HJtF_T{Xcr-07 zjlWrwE3Mb`a^9gVi}A|B%n`}+pT>8*RF~hqp!)=1^cQ!(ha|pCUsSF6!x1oyw_DDx z;Z%8iz)&IWaY&UHFR3ip*wY$NlJW8T+SgD0OKkq!Ib91*x?FgeJ~w3d1`gcVve;fZ zzTuDm{Fi9N_80EVO=|6xlnnP1qSq%ud{rm7<~!McdUJU1-o0iO%^8;AP3YgGx^qG0 zlN!ODc%S$Ffog*mvI*F{-*z_tyG&`$-PhuX;%qFh`h#zT=OXv7Zd;mC{hYb?#c?N$mo zqWCFk-oPOgDVvk?MuUizczf_ot%q!L_D6&if(he&Xo8pyec!j6+c=`R#b|@ek33Wv z-kuh6)nmt1g(uC@Apw6aT7B}3_U?LL%kdq>gX*Q(K{>AdRaQB!bFzjiMB|&fyGm^N zg{kRk!ii+cTt^m4w|yc^*dc$QB-4N7!sxmpm6B8GZcWW>SW;4Q>(i%CRR_#(2!b zW}Gj&-(7w`I8tkEi*1cY_gpG3x0d}?&v?oThWb}h{;)ZMm{2t(`vfb4fypGypG36&kF z+D{3TkOvhD6h-vaB8rWhyrR-1(tm4?YpsM2N03JtMzSi#s!%jX-my(|NLnm@pa9YB zUUOKt^x^$V-B98V({=7khf6=x-JLlC!2(bFgaR{k!f`_%=AJZ}%$o|dwMs&XjXb6t znVj9uqX~>k+^uQnjw`c^CZ;97_w?{!t}lAMdcMiKClBaqJPW}^FwEGSGqp&0Bu9mH z=mdxyR^D!NvV>};kj@bh=w@(NL;7+H_xM?Pkv?_mzHQsKB?a27m746i7k)JzVNK6s z0?>aH6TZO!-QBr@2-GD6M4F~PbB4I5N~9qbJ4n1&2=`Cm#H48CRNi$;og6_5^mNG+ zq9l?eFR#2&g#{mK*cRLNL~^nCbXE|Y=aqHNPTF$J8u;{qw|z9O?!Mm}o;&vRmroYv zJ@ohY-+)q8*b@_-m42VOO_{rEt#YG{ZC&ZJdsST+?2#kS(`6Fp1XzF zrrxR`8ZoS@#33oJuP%J{@W@c0Q5bun$rbKb>lk7~-7KyW3()f7>^&)Q1*tU_`zk02 zDOez7(>}HJHP3*1Q&D%mRAO=TJH=FQvU zOjPUA=4Yt9Pm&(`@@3nTUjJD+oMk#byG*P*UYQ9k!SQ zn9nZYzNjq=Fa!G@quISBeJiwWZnjS!6~hXP{R>1tZqT1nfRWcsoG2D!Z0B03H571F z8x=KkQb|z}1ATn2|gAPM6x~wX$}YXOF!L?`sAtdw1|Ak0fP(uyJbK0C*tPr2p+r`@}8ra>nKCvcgF_@(SJOxkEi8a#T zlLdUfQ(7XsO{#Nt5b_6aRtHnEmEO%6Ro>5X*X=GTay5LXC@vSRbtF5cxTNIasvPIB z{^RpjD+@kA-MV^NE|2`|Pva>x4MI^J-sK5?ji$~#2r^tRB$WQ>Uce5;a35xy#fuk< zxN#-*D^Xve1?*tf6dWm?nmg_BJVa3l6|6|RgKc(0MA-G~vR0eFfQ z+Y~oYysv*MdWT4$dy2UxWfXo&g;FFKa1gNsZ@)Vd0miIT20U<;gf!Yx$*_Lzp7*Wk zbQz7iOw(i%Jtl{5hK6bz7o~3~h{?Vg36K;S54t|p+m}<_n@^0s2_s^?4&sl+B`YJde)sMIx%5#aKo+AK z<6FDaX6u6slhNf6v5~&&y(hCt#u>XBw;yQ2xo{uo7(F@nN7>}w`h)uZ*~3qs^wDJU zTG&h9hDACs(N3V9jvf@}TV|e{$2{m8xk9^e@9RSgCj62(!+|x_wzs2)3Ct+dMr4XfV~ow$!ygL7f8>3xOvn ziagZ2$^xG{du!^5Z%|(C4%nrE?oscH-R9#?hw#@2`v@c^Nu_9u7&&TI*FWEO;>F5= z9}NldkB~4`*T0r8xBSw`Uyh^ctUYUlKe4P@wHXAu``_F`+}(U=1k(@^@t$8f$Tk+u zbus8DT~UXdlN(`+o}RWdHSevEWlIy?qXP#Hj0*WMkEvY>8_*WVh;y2WfjZacAsuX-MdF<4__+v4ADmDCH)-us)xoL8-vNs^Md+)r7m$H|R6&pFrmdv8ic5DMig`>y#TugifGEx6NA^@)x@O^lEef$=5FV?EG2(Y|-hzov9*m{;0o%vyP6=MIQ`4fZ_xx z?Nq1NGcG#FnwAZjL~_otZ!Ff<)>m)jc+@0@58y~z!O9vgGdInwrSkmnH5!dRZC0_? zwP!=S4^M}K6T#P^Tv*vyV;C3|bnvW5I&)47eNN=Fty3JbRt1i5ma_iDe2-sE~O@63aJ6`>AJw!Q`JaI6fWSe@jYcg z#*CR9zbP&W;d6cCy9|zAC>^=~NkHwhd-Uz+L-FF=HR0rmF8%AO6 zu1rSfuDgU3c?TAC3cK_{i9~V*#>4PkzS_d-Ci2c%W@}YDGq=ANSn)STdPD+tQWzt}^}c9DB}0zK+w^gBY$flBdbgW% z>_+bR-8W7m&XUab&UeAxSArbp@P`A;kNSXk`}x$!+{A={30D!<_0Cx|N)jSR@zNUR zoB#=d5Ra?b&6_e0FW;iZhNWy*AJeXy*d2EJ_Q~w@RJMU-g78PvehLiH&AI6j&%a zkjo*`dM34;odoNW)I22zlwaGZCo~dUbgEl}@iQ)|s6?~tEysyCO2||8^;z$)iALdw zHdIe4--(ej&S$vQ`+a+RRyd~g-Sz85Q-TxrR-0OHDn6aVpJ~4&a9dR3GmnYjI_OG z8$-%QVfSsToa)P_;$*&bvePcHNJm{1O)3QC1!e3`*F2hp*1Q_fO5}6DuNboJga;tl zMni9n_V1vb2$wg25xO2m(s5SeF#84C{Ury5=oV^Z%Exa(q?XN&mgQ#k7fsXcn!BUf z?ai~k?H~MX>fAZ0ThhY5|7;WQhJ!&DzR6m-UDy8*8Zdc3%X-7TPueWZbHA08-d)mB zrOTND zD8tjsOoA)UqW`{ib{NJ-rQl(mOuc{zmq4UP$Qu|bYI6@sNzmFnttK`=7)j2#)WW#$ zX`jF0=#{=~g~_J-tGRf>cQ2?2D3bSjRP<_Yh5yd9OABwDs!zYQ+DS@Q|B`Ot#_KH| z$A;Rsd@JBP>yvR-W<{wyEA@Bg66fo7K005HiM=JSG=~~9Pm%uosPLRb*73lQzcucM zU|A&kijHDqc+Nkm$A#84Mlq3LEzVAwhIEY$<&y+v`ymu(=E1B6Yc}Wf<#+54Ro-w$ zc^YpkHaAc+Lbt$m5bQx;^(d7IMNC$jp9nQgKs|I>#z(GLv0^pVc!}_f?l1nWLZLn^0|_ywt6oKDWHnc@ zXg^R?IWy+`Mz=AdMP9$BNFnmrNL+)esA8#jshzZf>&;Uqy<(*vx{mIzie>Insl~B6 z6YiQ`^SSDv$B5{<)ct8KrF2x{sWkEF#$WvIY|i&gYwZ$SEQ~dxwIy$Aum?rx2|aG^ z*a{;LYj%?z-U$g?pxV~+K6g%IKmUdeFTRFGJ0`oS@U%i5v&!wl1sY-~viUHkN}cfc z5{gq_%p#@+88pk$B%l3`8HKQO?m&RVHU>enq}ua5cZT4fDh)8ScVSfcHya;ck47H( zvjxM)_}W;OE?u9UB_rA8?`UlMt*NPL=d0&Bb35Z7{czeOJN{}SeYldU`EFSAu;}hisQPunIwKZBYRDHSQ)x9@AA#eya^W7vm#Wi>u=<^ zDh{zw(MNnt-%Tb~`-z#QaBWk0ROG;EurzK#2;L%BdYp%DCH43O2~sNskNE13x+{Ge zoZ7*}{zs>NIaFCRwTb8Z{CD-yHkHn8XTweIahh9-@OZ%RJg03E;HZrj#xz$e3(puRqoaeseJwj zXI~rB=gpT*PMdF^k%sbXccc)6bO;md|DKnHNriwVo->(b?23S<2#wtJpcP;(i`4J0 zi_mj&ax%_*urt2;Mr4aEyRfi->%>R5z_yhxVQ(6JZP0y|LY*X+vKQ2_v3bOl{~@IF zC)%^sA4EhHe$^4-fx#wR00LBY30fp46TL`UlKlBT45AIF-_><(=V(iEw_961IBq9A zkZZH1KGWU^ie*G61Xi7RlnoiG`c+hfQAC$S1Rq?9H*;c100-*n0 z5E9EsuXlyw!g#ZcM3OZ#n1R3mt6yp%KEOH_6K5-8{9u>$vgip^1q` z(3?BJXAq2g+1o6;#k87aYtB$Z{PP?tNQi-!uG61~iI@u8?%ld}pT6pLzkG;rH`X51 zpT@MZ*R|P}Bon(nzkMucCD21LS_9EFORtB0?S|~){RLHJ8$Sb(DFFk=Z22QV8>^uF zJ;0;Jt<0yEQb;$T5Xc|>gzGg+`lbzD67)2HatMCo|LK$2`z`d3Of$8Dr*uwc<|UOM zebP7nt#+qULEHJKgJajPtt`F1Xv9a`YwF~gWaY;6syvJNl>@et0T!RD$k6!m_3O#p ztGXz72mgFaIwgRaq4y~4awINN&t1$S7-yy-LO<7dSreEQ9dbk))3M@>i6gUvoV>hH zT!+d%7+V%u*baOQDc#o3^BEUEv0*XW@U2eMvKXV*Cg(wwRJ1^$ViTWIrM4?K%8N7; z+1K#xZvuyD*05v3!B+${`f5@dQ+B7tTIN9_3}qZmG9B`@%2Cm)ANi37%i_@>xwdzrnn3Wo;+VvJWJ69OR=!?iK&bw}c^yv(Sz0ztvhlxAfLv zw>cqO+QUlf{DXtJVVNYn=(Uw17|oC&A5CvIQ@k|4PBODumN%`If8-iHv-NIp5u?2< zt7E*uG;(6Su_D0%{2YF~=wLr6Laq;b?*9ImgNCF{S>}I>Dc52>^LbC!XoIQvae6r> z_w4!I&Gt6uJ%yV)ZUzLXHbkqK)tB^LI~lgrqJE60IqH7jRDfNv^X~Ai`2}3tj_9y9 zKF6V8`!SU3+L|5fvTw=;huu?deERh1+C5UNe-yC)Zs%Fl$~ca?Hvbvo;&4;q)Tsxg z^9R2P=JU$jAwh8N$4r&RDYx74xH?z69bazu4{hsX$L+Z6G%Xys0 zdFiPH7IbUd`)^S{zU8pUCX81rzU~qftogbY z_Oe!Q2E{iwCG|dP%Idy(w$I0}^&ayg?e}~2n`?AljICO=inQGC1x^D2Bd+QE##QS* z9bY3Z)gi-ePUB+MU1sO4zzQG`iv9bPpY{NMUPdq>7ge15=ilp~COIg?=0)%Lw-{xI zU_s;K)>Qtg#3(=APoUM2`C5(1Bj)j5V2FMT%1TQG&WWzjvT_$hRzk`99fdA5(Dtfp z^u6WhroZsf`SM1gL^XVMvlB->EZ${9G~W4QwdHUW=T=o36Q0i`!HlT*Lz2O=3-(DH z|C(N}quJ})7uvlUVs%zljv8`sZ#hxC@jz$s*rHXfb7{XGtlB+(#q#MKDb7wJuYeZD zM9HFHqCck-19|({RiWr<#^!fxvx8V{HVX&rOC!Sp7mXBjdjG!Ttv4kuUpjQ8Y~Kps z=u9OPcCz1At@-1!whD9eI3!e)#9n!Ew7GQBy=Q zc-PSW2o-AZd3_*JTh(O}+x#%=FgG>s-=~Wb8JJVB1E;(!N&~ zd_q(DGK+iGvKoFLBTnQX&kCK333na8|FS7PQblp4!roc#PRokQ%hM+UuZVKg_8RDI z{qL8a{`#M1;Z?F&-Mo#swto+DwnIy%6{fdu18nXzW~UrvICX6(YU9`n2MmD> zQ1rjpml*#D4rHCy&9?PB&QOIhS=3*|kkUV&rQ^d2Y0oda4?cEGyvJ!>%DHXuQ<1`p zF^#-Q)*oLzAG|dJs;3;ZY`I_2iblm^q2|bF_UNp*;dirWa@8evpTG>g+#>=@fjBXi z3nr}n<26oy=S^S%hHm`RKva*(9eihw8drFKaH&Ssatob|`{CB#+pF36WldWs%9^~P z?0VZ;j3LrA%R$O(>9*!DSGZ-@@#8I-P~r~ zHF3tA>uIzYb}_D2rySQsb;2K`n+N+}^}HCH%BSz}x}O*Ip7!yJvvADvWl>$$@J{hs zN$%Jp>Bidhvw9+9ltZ7q0(Z!ZkjV8@orK+;zAQQSpOhbPt}KF$lA&9WT8{GE zf_S3R^UXi{=j733-61WlE#SkGw8Yl~7#w|o%xG!iLZr*7`W)L{M?5Z^+xI8GzXiqx z_r%yhM$hw?FArqf^sF2A`;b3v7=hQ{AO~03V&Vyw5%`txCvyYfvB5yE3T8q+P^Zs)SNs(w-Fi;BJjshuCQf}_5Uz3Y=oaVhs@VXBH9 zA5d=X-^GzJbs{I^hvml89_fCECpES|4^o&WO%W8dpW#^ZaQb}^FFvTT#s9mF|M}fN z^2`6;WptS`67gw32@)H0l&fX@ka)G>mmj9cHyvA&p(s3t)7TJA)3ME_4pOY zyQ`OVuYJ2$Qj&B1`lz(h`<5Guy>!tLP>mp%B8ZLD9Ibj}t{G6_ z{g@GJWKw(*!c_13-7yDbmGxZsSP?;89TVGb*DPWDR_q&c7=0}~vM^KZBz(3Pb%l8z zwdqdTEXk{t(&$%il_18X?8` zM65IG=AT}-?&D0A5l3WXu7qIBTEafUS|n7%vV6Hp=YutFZsMdn=KIKXNKI|icx=Uo zpt3T#yL&AG1ZjJAe%F{!gl-6tGd(>D_AEExbz>gq#0g_mY4K@zB9$=$F4vvMd+tR8 zFS2F5#KQ1d&m9HDs&K~io(%^RZzNG!CpNf(mABp8V5f&i?P?g_Uj0H+1u+3PJ<|$V z8vp7e!$LYwKl|%B1B2U^LCmmT)*r~!e)-xhZ%z|NaaT_bE%54WuOBTD-5uSy-I#XF zkdcaMc{jJZW0%2MjU@dKVSJ~xuGifeY?ytSrZIGM%iR-%RvT_KyvVFhUZe%-bmdwL z4E_?-E3p=jte)!n(Ld*fcw}z3<}?VUMLmuv37UH90IdSl`Pum~FSl<%%Vbftpx2|c z>PkN7I)ZWZz0Dgm;76(97pzi1jndy2v$0yk%E^f_Ss;}k?fHMKm5=`c_IsXSnyDod zVZCeNis21pJ-@DP5jC@KP0q@b)!sM8HR2NCJz(8vp0UIB3bT?W9KpI{WXv`0=K+O! zF*Y8k6rbMPo1F)yhZr$QmOZPa+dfMC@leliQA-R2$5lJ|udbx_e)h?^_76tTYu&CZ7AH%PBixq3SX1SXtWl8P& z@%?mg7{DUV?c3i_anvL%aA}=rY@OPmQQN9h9aoA;)-AZF)g+v_CI#tA_?f}WWGM9_ z4rzU|B6}CD7M61w>+c(`HE|GMzy8_EjT{_LGkwmrq)P^?T+@B1f4O`OVc%rIA>eAg zW2sRS_FeCUcg2A&XAF`{Fve5a(57=_-9uMhk2CpwzGk~ZIOkRmU6twU@{(DfdGmVO zCA0OHdCo`c25icTG4-Vx7qQ9an++OX7KuJ5c1MPXoiY}buH`ICKdwTV)rG^nMhm@H zdHMD~xn@vwC*oH17D~}iHcl@?%apbLjM~7;g=&`Mp?NpN&#kH#a&f7y&l*gGXUhxI zU{1lF+Cw8LUl;J@9vc1h_NZYLoXF-s?W_o?y0%u7$dacO@wd^flGF#Ak2S@C)e)9Z z3hN;>ftaJd2g%Rg5LS7S1y3t1#x($T>M%1E0DRYnHZl4sBzLNWV-H=s6z7=Y?nxzr zBT2&_2IJ;S9u4W@(07nbtyQh2v`*rW;zXC%+L-V3AHB~z-V#~cXqnkQ2O%V}#;X61 zuIrA+dTrx}Bq^zckWq><%dBLSXdo?QtL)uEBs4V8k`&>INSWE2>ZGjf6-r4N8D)j! z{ocwsk5lja$NQ;sdfz<1=l)&yb$zezSVk6@H9INce%&bSV!88F<2HU=IiqS%fs_SX z@o6=VuhX5OeubO9u&^5WY0R%HC@6&2`lW6Wz;=ja5~Qr2Xk@7%k0vJ8iZ2Q6XLG>Q zBF*JYt{*>qxXBTT8}=wdrUkDWq>cM=$rfY#Bs@R0%W$XEw|Hlvd&^sUrqbmQQ*d_k ztasqA6^>--nqfOO^fV%D8~=(GJB1h6I1Zo?1sY~MX|2z*SJ%yUibH0ok$rZLOj}0& z_jYljExi@r4x(FO(6ZV$Zhi76zZMDl^@0j;AKe_-Z*fwCyPlhF+fj{MY`*}7%Ng<` z(_%_O8gfL=oQDHMp(PfIy%qc#{R33J3886CznzWMa`FWX))AJ}{qJDBUxq&CKV zNO)k$r**c6^L`|nzL%)p`oJFh&K-PsTmiUl<;a&Y>#Pj|Qc@|$GXTF3V)oWq?VLyJ zC+q6_h=?jK{f&@w%Zb1a?xhMpz8#J@nw5sNeeQ8lthWj+jJ9dp=eOU|-#IH1NfuIt z_4PN=c@}Bu7-|{s_r?2RBt{8yAF}6a*T>D(-EPli^s4;pj3P_g-vVV)WnP{?6g1;; zcrsd62tw7&kZN=BqPHh89FW@=m=`zuvcbb;vE*6)387zeTsG6>@snc?OlCA7aO*dkZ`+UA9h%2P@y z;*(b@A}gDI+?%r@zPwC{lZ|=aykjr>9^e-EZuM|W9|N&FEQV=;cti|zv=?9L=%c+p z1t#)>JL&u%5k|*na+=1?*|b{g#fuloC(FMFhOz!e)led#7CJ1KpHa$(sTM@g5s?BE>VKbQu-wKHc8BkWd7NjN;fCGSKF|1$!TU1GlK~yA(qW zv>EAlh5f%yC5oSHX*pPnHN`?Ee(M9tNo<^)LY#Dm4)1PB&;zIgGG}R2M6i9<4iJAr zvY2;oX4boN5;WT+^dF2bhzib@ZXe*z-P$CF>W0UUfv`f}t`_&fdp$S_GCc9tumlcI zAWJl-2O!8x-%d#QGB#SjSH)14r24zJ1|0X9>!vfOe2j9Dm zCy$o$wYydpM-pB{V`ionoDR zI_mg|>bD0Wisa9Ue{v!uto`7f;5UAod0k_{V6JekX|7K&76+G7wy@s(;p_OeTzK`1 zwa~RjOIM-1x!m&1dqrkg^Qy58B8XN@W_xD)+Y9{{jUY(?TrARZi@m~QQ*=w5}$$Ee=0-WMxD%}|oE%)vU=BOUjB6QCtRpnLWrN|~;7#ahIM zK5nMjF6(1C5AM4%eif(LGy3wzcPih%Ws?146cCPZ)&@_qK&(mkwEsY2NXrsIS4yu; z%=`4hWkyAsI?tYR0Mwi>#1t%}etQuiG02-Tr2U~?I9+%vw!t6H%oFS1$invdG;Y0? zz95$YUn#nfTeq~=&}cQ=OwQkcO>2rx{i~?6+jvfHg}vea@hd%dAJ!AomO$bs(<8fj z^>#vp0KMpFN5*k)&qf@%OOcDSwC(HbBGuR{<-{tszHw<|I*Ha>ZB5FSoHW>BjJBR- zCil`>B4ra>)R1E3UzR~)qCk%bEWNP#4_}ruxnt~g&W%zbES?ZAo0^#wVYRul9?}V$ z?}weRB&%PVxO;>+!M&+}!DaCv;1VOEpHF@ zuE6R;|7@s`;vf#Q1T-p-_umooI1Z=*_vwY=$OSA9_>&olcWlGT@E+XXkz4`^IbU~@ zTBaLl_%3TORYgN8F}{z6b1Z-KW3XD^f`f*s6S#$?dzVd_!5FL}A<}DvgoGqdnVQ}| z!oGsq&SOY)_lgxvU2eMzf3n{xjAYbNq5kInqG4ymRNTPu-jYEO{|ez`VWQ%-ue#_cb=60-)W>SQE%|7u1$>9nu$(it6=fcHVfe9OP}0M<{Q~ zwg?Bvx%cWm!XtUbaGtwCxfxFT)F$ zG`Gh}&G%yst2kiQ%DY0vV&DDs!YY?vMeY3IB_6rf{lSqOZ3kXJOtD6}uYILrVd*gQ z5dQk@TC#B7XSj=P#&m(eY3mduv8>&q3PMg){M}A#n?mP2{LxQbl4lOniD)&?V`TI- z$@X4qCC%~;#`Eo(9%KGxJBWQlGuYkI-LXO2uw5i#@Tm>bM~-Evd2Ca1cr1~vzgvJF z`bA5*htpp6FxQ5ordGG#Cg?iP&9x2xc1}9s=tJGNVmFVuDT>LzN}5Y4X4&w6cn9d_ z%uw(QRm%&gOQ(qp4O1sKWEmN`8Ii#1NHB2Ytzy@ltw6H_4J`dd_Qhn_6i8yMTPghL zt(oP^@3^VcIF7@=6ow)FVI}$FYR9b2Uyx+wDR4f5`?GzYSB_GM2|e+YuW$Mc|lbjl#U$G_8+4^z9)fjGl<1@ z#2n+}VRR?*BeW&g6o1#)mGEPt88AsP1Z(?ZPOtxe$49AP6i+|Ip_F09(?3MR#KMh~ zQ3iIc8mUc<@rH6N!iiG9jM;{IPq4DF6@!EO0R@$aR=y!JnvmKPSftQjXtB zA5^9ORISTtk@IpL1Wh$W1)P^$Fn|6{a6)$~DS2Lqy==9jpKzKsah0wnRPsub=t#^g z9Gh(&m=ETor;)I(SskqQ1JVgK#0fnb+TW0IBm#*jZ=+YnO)0QZhPAs57GO)!HLs&( z(V(+N@QI8G)PkFkS?|y1msQ*=9D5Z(F1O7ZYLBg?3`L#@J@QfT>dwty1r8r8Kyc2; z#*uCC^!h_XO#aywqLX*o=StNW{Y4|baJ}nbG{NYq0%U&j&2yB_t_sq^YoePFI}$G} zEv-eeYW{*#WF*GHaO2!muy2ojtx#re6qy|F%MZkrtzDF4UdE}5?If`Jn;XDtxfkxG zPrj#JCMa)7mX#|alykYxE2Ol5HW8JjUjbFsC-cIk9FZyxt5&@{b z*6J8-nH&VU6D(Gns}}6I6QY@lU?~ zG5~AHt|O8jpkqnd9f*44Z|*I#!(~aL+#42xGa^nH9XqWEP<_rCdf3lAvS!6gD(hLu zM^P=<*c>0Gfn7zKTW{vJjVHQ3+}_+wVRzSX1&#Ud{B{VhCuuK~Mz1~LV|q$z*Wd|7 zm~1R}hnWVZG=`2JdGrVV^yRE49?JYnI%j}5Ia~My1-GFQ*g0!!VfYYlLfqvVdU|?J zR>|DVu>_q>966@fv4r`s#jR2TlpEzmtkzE$T{OHdKkXr-H`HSLli5cUZ7V37zv63B zGYLGn`0Ir^%Ou|2cxtd=wCjYbacyHx+qKP|WaYnFkitb<;&9smIkE`kJM<@GHp)8R z8(&8lz5kPJ45bGGAC6+c+i3<7@d~_E9m`EP@fJm8-W2(JC!eI`z6Hoi%G%RO6g0S~ z6J%Y1g|s_(j0gLj^{#7cYl~@**j!0ypY0y91k@n`Bd*(~zOP-BaK~{dq9d^*xx)4G zxqRox+axfhA)tCCrAKQ)a9L-q^UggV*OAr3k@~sGGMBdp4;3egNirJY{d$N62 zWtDouJM)ZPvH#&Jp-lYDjvn@%5sAygN1@3D7W)#^E1|n_+6QbvXuzt{t>7|NinVwJ zjogK=42pPRGtWgc0w2Un7cch57Rgzqp@%1|{?~)?0lnfGt!J#SW#!H_qucFHzA0j5F$iyqG49OK>j0Ai&`s>bCtF4730M%^)0wWieNW+@(NBt#Yw)&S zeKr=!j~kzog=!rm{QSsoRiZTx|0Z{+IN6@MPl(>D^z16xcV!x83|&Gt7zCAaUq(g} zk`%H1s3tJVYu3Yg3^hh3(1DTgnTF$(;A~iY*wlPMZQQE-5Owi`whxO{8juAmI6lR=_{Hwu*l`+9`95J!jk zXT!pH!@_bVEMku7~GkA5^g;{Ye~f!1p$SfjoRaqudx08ki!E>P}Q6|)wi zOeQSn=Z`40$~u?_Zku$^<+k5G#a}f0$j{bpX10g=>)Fjt6Gw?kpDVs*&BMfC3~qpu z)D6Ag8PGKoOSUHC6#@sCX>Sz=arW2Ao%l93R`)D=Nbzs*Lx~_kW>&YMI^Y;$6cMh~ zjQ*@@ENmG+%sDv7F@lzNu;J~VmIGt2Z4!#mbgsf4>p%i9_V0~r*X|APb$PM8{7jCW z!_MJCc2iV@@a3*#-f3m@0s>G}S}G!W9QPmcMY9fV^!=S1%#aa+TAiM~QXRJB|2Cio zYbdoRMZGxP1}Z#_p@e~fSLV?mUq7W>LLOl^r$2Jo3zTu>a*KuB)2=}lSgsWKP<|GM z*$>O$Iss9Z*|8-0*CVheB@~(W?+@KkaL+;|iEujW$cAFQl@x2P-Hhl`PtTdZluyUt z$a&?$=!9Lz+e$%{6nlGW!0)b{b9`yy*jo(rQa?nZUxX}f9)Gh@Bc{VP$uwt@vLviz zp?g{Iy2Gj=V{OD$my$+1*4TxY&TLnGc_3^NQhRO;{QIH)`PDv51G2U4rt4;WjXGXn zxAOmOkzk#zy|;RI#OcW8txV*ldnc4!c$qFmuOAlPwx?r*@4im66UKNO^|bm?k6v!> zDL2v;;i!qa8`q2w@6#$5#rwclZRms;(~XanNmnHpE7q$&@{WktO)hk?Bd=E3r(S{= zwjY5DcV+pf*WupzqD*JQt=CsgE-3$Id3Q;a{dMd?oc{9xZc#7&v`}O$>mf(lhIKrVjgE6pvuafXq=%DYb2kJdE1obewlI1n{XIp1o zB1)F;7!huSgowgFtt!<1 zqgI|y>fA%;uZibWd&-La-|#-#I|0KpQFNZ^8)6YVwwQy%YTy(2LJ9LZrJ^6%k8Z$; z-%Nq07>`RUO@u|aW43+PLCdf1&kL>sTj}(Y>x*5>eIi=^=iOdLhyt|xug+vHB;1q?d3o-my zVIATz(QWMa_>}vU*P5zXF;02q#3}4EaWL&pDFXc>;Wj#kCjtyVnlCITAl1o{o7{~8 z6q>#6eWhh(aYI`sIA9RX+$LWi(u9WFd9+j0!#ZvD1P6RpjfTcKx70HBjSZZ~%%vgN z4*NNK`c+CiA)qAbv(=Ta}Xj<2(9J zX5M($zWA*uOV`1_IDBpjJe>Jo{gV?RYu`B;!MB!bNbtPC0FXehH+RJ7uq^6M5+uRN z#h-O`bqQ@Q!Zk{UDQ&X<88gp{0-4Xmo9Ior@24xYtgNggQ;J>ODE7qYSmJJsq3|4i z%bji+JBpo60DRf%Y$sr68NV_2@A7iZ(9>g9ZTHsT_K=Dz0MCOD153W23an+dLmDDr z#*-XdQzOYnUEfKcovvGZ}X+`Up9zWZF<~ zc3<%<=1nF?dscH(Fx+co&YrQv$h>r4UPU8#Jcz-vGu67K zHYTIq85^3MoF8M|;eBR5%N-piCzBj!9fvVb*P)SJI=aH$|Imm2x!CA}ws;ozXxw{s z_tybxHK%2DZS@O|yVJhH({mLKlc%7dUV|XXIfXiFnSH>XZ3WnQM6+N${tq?kXW`t1I@6nXSOz<(}O71TM#ev z6U+X_r18N{er50Z*V&C+HlsW4+SPO@j=?3R03ljt&o8qU@<6wJKQ^}Xo5O^GEcRCq zdL{@@=25r}>!FF*I1SB{#MH3kAsdLZ$Qk3NB2EF*)`{Lh#cwx8c+^#=aoKTL+B~bS|3;P$-Fs*>w zz!ov%JloF)lx6g|t6FF;rnbaGx2i#s3fr3W&Kt%&u3l(~$#%Gq@o26fGQR`mlRWoJZVc^~w%RJ*#O`Q(M%YOwlg*+`?NnKDXZqi0Z zMyf7+oS0Z)%Awb|N4UybWrwo^-s1f4z0UcPY3soCCVPWsceU8JvkBHxpkXpsYz;+G zhm=JmbFkHa>h2cKbsf5a;vZ<>(H;&HbUv8xOFa_B2+y^AI7q7#WL*2fduW8Z=Mok? zNi}XOw`(8YV__H>$niF=oePx`GZMTrE)$PS z%l^W>)vbQH!rNq?=aF4t36_G^>J!kX7emq(bcmz0b1y9`r=(5IWrlRw%U6Bm4V0d> zLSYt|lar(8%*oAdcW$HM+m;1Y90n6F>1YzF~4v1Cp&c z5HxZQY>v4re*1*@f+uu(8AZ#s&OGIt43vb^jq^@5ng((vRkq%X(Wy)QSl8_MjOi;v z$E!OYc}0N>pnHtNePQ%I%w^&W>ACvwnt(qnk+6D%;cMB+GJYlnj{^oa2Bm@a_ z=G=~Dde;r}2k&3TwsHfqmDi>J2-UXD2PMZ8j;hUT$j9>Hq%|`$OM=T2seE-x2}w5W!xPjzkWCmk)J;O{G}C?JE=Rz zF|4V)sGFkF`pL#|J-oiO(dLB;KwP7LKW#7nH^M3GJQfkME;5Zrw6J;>WqaR%j4` z1QMe^NK69Sg;bt1p%^Qryoig^v2uBfQ)#txHuzk=?3*dw5KrT*AEfOCHd^kNwU%bv zjS}kp1?ic2Y+-oPV3dq{u><#+0Td2A0~OJt_JgETw`Hxkz%5>zM4@89=;Jff^lRdVF{Khc2g)E}QQ=(8ij05+yzJ!=d&;WQ&rmYlX>*y{sJsNXmN_dPKz884p#`YYfLlW)uY zrcq>mW6Z&dQ7dd52!$Ud8?g{{L|z@@Q^z6*=Lde$8$2Hon<$MnRvazT^u6Xb6qWyg zIe)OLwnX~i0b&&28cyrF^NPau{mClZwy7Zt+b2HA>{m0Rv~S+RyLMf21>b*tzpb`t zMP9L4C{RBJr2?9%%n=ag3YY3CZ|6*m72Y};V?41F71v}iOw!^CA*n7nz^a^;jhg42 ze>OIM4c)Kn!nCWu9|?DnYWqZ9+}`&ro_J@X-Ui1l$3_tin;_>Q@-BWL+o2u2aVwyV zX*RX7I0Rj}z6rz`S|0X8%U>lWNwl58Auz=9;?S2v?&1~uP7`)mCF4_ReY0pok6Nse zWZP;YFgg`uv8$rUyW8-#jsPA&#abHo#16oS=Ik&2{(HNlqvJFBcA*&`@F%4IjDS@Q zOlERahutMc$;c?Qeo{H{$6*(<*%`%*Ik$|M(fE=XwWz#YHZRwzT7Zyv)ANouICGPe zeUki@ac|<8IjkTo30XAXt}E)Ej{CKTuD6A-O=8I1rlP`8;syZ^;k^l{q0x!6YJ?#l-`GSscDMi+=t!ywy#nm7JE7hz}s{Gv>h$IV=<2Y*swnWl=&z zozjbbe%GqBXtsf`FG*&FoocPydv7i~|H$9iK7Y~rL5}`rwSw4;fL5J_8R)Kw0BMRf zdN3`i_`Yy#*&Q1ahzrJT?d>WUq!PZ_9T~fzqQ%6z74E}d%Vgg!%};pp0M?Z!DneW zdje-pjE(tx_5`ZX!zslwyiC@fPIg^2jN9=wLoV535#z|r0y@W9}7)~_5hF+AItRlQx)gik`bbV{Mmo2dq%1!{hZV>Qx%o-kFSE% z_=qvZKKC)b*bfNl0!SK+mJT=t`$_yH$tZg?^rOeYgM~@fx|+WnW`z12QkJ`CS+q%L zlJ!Za^X-X~5k!NS1LfIN-UHsbxn9~wJb=@d9>9wn39ZGOm(N2NInE;n!bSL)ma$rz zR$#84RvjJ~@W-XWIhk!9BMO%&pIw0G*B5Qp977v}Tc|-tNzo_r!GmBX*IF$dj=rXu z1!?Le6NO3+J@qYB;5S<;C4#jn!65Tck`FqzjQx=Y7K?3MIzh>wO2-lEcd+__HD3`D zDlIb6``pdk^zkSOV7GUAc0i2QZz?&5*v*(nz_Nfd;0@SJtwFSU*WFRG3)jpe;s_u~ z;J{1h+uC_K^`Lpsth}&Ny5?sO>=>(LW%ck&>-8Ucqi?~ncl>KnNoUTf|A{n;bI6B2NyDBy4k={EsPLxlVD>FXy5lkd;2Br_scLJsfTXTg>5<{ zO%Imu4n#FF;$>KGq{LfM)$f97j7$2CwoM(|!i5#BM+QF?0${Rm$_>4ST#}a7Bbi9@ zTP99S#4l<)*88&+my~D-#ERCu!2*)3L%(D?f^cxfc%|gOhv&b)GC7aGQ}|lP3?0Zc=Q3F(%$;2ZiQ3R6IzmxaG| z2kBWl?UUGbSfY7s6AbjRDZ7uJMMhMb$Q#lu%*;6I{Sfs|GF^fTqdx;Y;VrRCZ!vf3 zAqJeVEq6a#_yN77;}uVZ?+?9(e0_cO1Z!B9o*t_XE9OVq*j<%%^MC-{Q#ya~wn9VI zIiG{p)JNf;nbVdyYOt_}P^09OHM4=|f=O1d4;XzrLKxCw#CVhW?*SYb9GOWEXZ;t@8QKRK=# z{GtsxgNb2Nwj9rgvh)y|32}Bj@NKX<~)%Q zp{_%Cwa@nGJJS+^0U(T@u$e_oey_4xt}Q#pM)&GD$bQ z0Y~W4l`Bz)+}dtua?+4GlCyd$okkO`bLs*Wj3t~~nC8zkYS_|pN*h_c5#nUAC1G6pfz$5A}`DZgh&=I3_lK2@KzL) zudk2Nmosn$n?}wDYYz-uQ_r1M_4{t_pYKMH(7GkoS5xCVo_1tDJqmZA%4=66!S%GJ zBU*J64}6SaS+lKlkLDR#tHs4-&-8#rz~*MH@*19-dme}AET&yR!Up&bc&ku?JhhFd%uR)u85k_D zl@Y2wnz3*XbLl160XI>O42BbeG(dj!_`c@MWcaaVJvn@IIc^$(emH0pK|{DL*~goi z*M3v!mZ>?7L2ZXRr6UHXjR&odK)$fWjzxep^quw&) z#x*dc$qE#FqL@jF(DIOwfy4HzxQ-m5VcGzD5^3uIfL2xc9+Rqm_t+H?+Cd_7l8>YW zrN9L%;)TUu=njp^@|W;C)_~j5O^j~{PpX^u9M9C!C3bI+@+>RYg=#L_uVZjhlZuqjeS*Ov= zqQ}|GZF+wBpVK(~#!=>ik1e}gVIMU!$kWUVFExot5Iwz5IC!YD`a;*^92dCopqdEs zNzSG{!Eiq+s+d?UWOc_M3#!IsY>Iup`2c|J$s3sV*4uHbpYwb$m!y6Yx3W|6gB8jW zhyK2}G2I2u`BTYdn>HDculw9<@ThyOL_QOXj(#C8vOXr*P^de0g$SxJYA-OSuDw6+ z6t6Knqk6%=N2vc*!9&_RckU1$HJ@W+qoW*8oaEDj(VYDxoE$b+qR3#gwcsV((e7hK z@v%J2;qHMO*RLPkuUWtFX2fgoN62Q;{8@rt>P{Z0`nPG6WH7kgSHfJUMR7+#)N)&f z3%WE|HsOuD$Cu~qq-lm%;;$0w=6>S;nlO@qgV?Gw=shYrF2jG`` zeDFi+Z-ip+1t|hnjcE-*k5k(_-4%G3xD{*pnRH&a-V)8;lWy#m}l1LylU2-H= zZQkOY*Fh1pov^>YecVF;7=!Jkg=Q9x}Gm0G7VBdl9zPfE}5O2 z0WVj&!FSIw0Qeg%U%tHX?THHNA87je{(sl^7U z@U@EKoaeUhO4ig_{0+`8W)MP!vxcRDXGH?Z=;q8R!QJ2&cAoQSA8cu#-HIc4yN-i% z^N|Y(x2`*Q3_w;WA7%3}X<0G1wPU0^Vc!`QZ2w-0PBWwPGdbOfo0U9dIv#G~bWHeO z<>-d;Y`gS){2w0kCsf^$?{1|FsE!HZ{c39VSMCgy4*sD`thDYXG5akZTW=;Hu(@D} z=u>{kA37hpDiJ}fgn#--MvLS0qwjvmaVWv=)9!mY@NN>x$W6P}vVsqhAz?)g^#;fM zNFKxTfpx2Cd&MXoGUWQJ+{YekH%6HnJvPPuENlNX7Bil-*CaOXpK7NL(e!_bt-6Mc z7+45s*>p8Lj({6QRt+bDi+^TR^h%A}T6?y%}u_h`6V-?b9d0$B!SAWUp*{v^=~w zNrt^`DJ-=S-j~#EFy9-{C@NEi(seV3tkHy1!?4UH_z&kbNZZU)yQcIUahQ9 zYPxM>Rg_KV46e?MgX<|vLaz$5UxohnBP0@f7VGxon<-u--Adw255xj&+xijp1-ec# z^dx?LHi~ge?H*c5pTLbIJ#3jj(c{qWHHT*{R~HCWfm{wbl|1{_($m^6r#xV_ZO*7< zNUb0KR9>Yzxc@v>7bV0<9UZ^@V;#0XP$;I0R}9es1js$v`0p|J`76hD=v>5{ln-2a z!9WNv;E1dwUBk!{;FY8(;aJ^1rO3~(4Ae%{hy}JeP~kbPtKv)0z7yX_93}~{^;u%h zSw09uN$x1IwCsw6!xQJdVYqef3=}hr&AW1C#v_{vqV^LpMGhzR&xVUZk0u!^IzmXR zIe7=+U$&T{?Xx*__;!bRdYc7eso&n-&X(w@lHoMl&=Z2`-g4QRr*jB5q-!5DQetdBM)j4l%(mryKcc)DuX8iSS&z^%v z_P`1$36dvpx1vu}y7u4+t(29mKNN=T-%f0txl%h3#$yF|sBsw)nTqFq3*U42*gE38 zjO8jsM9!tR;yhkSRVX0JiUWgfww=%ab=bxImV_U~aJVj!+OT4iS}Tm-R1sRyB-Ss93tsa$v~yb2)2i;%a&9*UN#1gMS{fTGtJzdqTby&8-jJb3RG0E$ z>EKXbcthCSy-{_WjfI6DN*QU6a6qky6==A9Fq4fYa8ZS#GFl}G)0fva*6-KT6LPhF z0v&?i=`jms4+U%ZdvE^D#)jXXX5XA^Ur4I4HHB%_nq0oewwF1eG^>R9~O;rOSkUQ%GF5v4q7z>1*=G)a%y2kT0^&|mz&j;Vz!8* zQ2^P&+Rz0kb}4+fQ{HER6C9~V{3v_^k+xC1etG0Qc#Bw(5V_li@$Z~$9+k)*H;Pw= z_19QpAqH#| zkN=Rzssy*671M9Z)ctc|9FcHYy+%`pT_#UJYV+4S^b_(XO+&Pu83%#3i@+uP8 z_Z2XWRD0EJF7hZ55;?ee+l1ToE)C7sM5%M3?`{wEME9!_G2z92vsN~KhPwyXY=Yr? zW_wShjDGuek>^QV0GajxZsC<0$V(I&S#;p>q4Tz{Q;KY#j7d7e@I>PDcb9D2kH8s- z==n%2fT`^;*s~4Yrd%*Nogk5e$_p^g{GY_eS$Yb0Y7?6J(_Id$#SVdz5Ow*-YQojG!F{0{{C5Q`*z3e0k2>}gZiGRvW=-`q_cV( zj$fQpoylpOYy)f{KLn9v7a#+%JQuDotk)x{)tGxoD(rQT=4&>zU_m90orJ{LVBcF~ z)vG*qbWI>hFUwUgoU*#=-%EUbHXM0>uCbTPHS0>CM3UWaO;^7J9<`Cvv&P?i{_4;( zq-$S3O-j{!`1F3OnD#4ux?m>zIEl@8CAkdRo3qh@;>!aA}h zI(*^NpM0zM(Mr30uru5D-@950Y*Dv1CJq`Ji+T5voA}&^JtoQzaoRu)WGp!dFT-+S zhB@qeZi0FuZK*D{g|d#;b&HpGqjXIkmZ$#r2A5xX`~9PARg^|>q56~5pMOJxmXhYu zqF1kExQ=0NeBbtL$2F(t=F~UU&jZrG6pxYTm~i8?A)ZSdK)`;7gGO%SjqAx2w;g}r zN{yMV=Aw#3J2-Qd*ggmk--60`KO>_dx-Q=9t#_K@_jk-+v7IXZ{1wW~qO;5j4HXA7 z7tjRH-W8@`NB0_y-l4~1cI}=>ArQ`(;xb%iZ|ytN{E>|~hkULHM*pe?D51riS>z8< z%#LX&;ub!V@Y?>TJ>U^>M5tEVfgY^d-TK8EIceVzOv9~LS}xU)l9IBYc$A$BU=ueI zfzCIL`8`D#HD{}GF9_3qLGNI;t*Vq~jy2EthxGgjyNJS%hv;G#RdjvUd*}}Hr@gR) z?pp;|I1qQInv#;zKi@inAO;5-z~(B8!mOG6jiaQp`{17_nLp)&A&01~moqX70D*oW zdS@YwO~MGMZo6p5o^K(-{LdJltECi^id&%~`dYjlETu`d?bWu5wU2*n(o|EEY-~b2 zy9j;irUjl%(w96H?%vaSElc8F?9} zpw=KaC8b`92=o7am_L8zau<*JYIdY8H7yufR6~05*4eHq8gZ>W+}s-N>Yv^&FyC5W zk6PWMTBO9Y@)|g#<(me4bz8>~%@^5xS~iPm$jZ3 zTwRI*kopSsjJ>UsasMkqqK0Sj;zK=V(?9P!TIjm`G0z8=Rb!(;vd*7nVbf98qRag`Ei36DATlCh9o%Amt zSSXOe_qTY#`+H!zAqi=Euw0jt`bs9H4Pm+B>UfObgxSkRvKV>LP1i zEW>K+D}G7ZEf{~j!(~x$jaEGW*WHu+x99!ac>MZR^DcB*O)U~^RFjXV&0OqwiZQ&1 zh+U3IGwe2c%!zF|8uOT?6SVE8szJWAgkx(#)PV)Zs4u-==jCTSsXgmFD&j2wHtYaaf;Dj{pbTH_PFT=% ziw3cxsj9^(iHi!42%OtduE3N8+pwi_2t5hJ077zmTDELa)`r||?Ne=l905QR>a*)W?)uH)0V zxz6IL#ju=HsqGF(R&SwW$N;{9HO)U2@YkpNdhzW}F93uS3D&axvztGG74z=e3sper1o8E=jgSy>;s)6`lCt6< z5)GO@hn>&5QUE%DC>-%3pU+1ByA$HwgZr)P>sS3kd7YQ6hhKWfEJJDHhtafYN#~W` z*ctHo)Em4B-lW+U&D)%)HW{A#W}`P)3A$DK`Ul#lYZ()fk#mHM^m%+M`f?1i9OwUP#zBti85q?V^{jUd0cs^en!D0LSZCRNgjt z5XK8r#DLciElYeDr&`yR>50a?X{nUuLgqPH<7H+Ozdu<={QV0A&8aKTCN*-mr0k80 zG%*081Z&Yt+MZ;37$-}ONw=2^I0ahmSsU#dBk8aD`}=E%RbEB}mvdl6#cm&EE50{- z&yNvBC<*T@85|rk@j^X*3309o6Z43L-n=)tdN!)@pEffl$TO{qKwGtO8EZu;lqa`F{;^TinC$P z`$&!iY%>XnDS}&PeaK1#*T5C1?>Zf6aUqa6>_A>l(!7nE=xyJA5xd_zE|$_GXyo4V z`!(D=L9pf|=d%TKexzA2cu%{qnht&ow z9L)7?(9;qefhD~(^tS?!_M3Eb!h&b1CX3d_Y08C9FmT3*Mdsmn{-5whkKA=D+SSFL z;rQ+hM4ZM1^nb;fWe8A^h){m`w8UNr%_FvPBnHgVvL#3cn}SA|Bka&&nw*56ZJog` zUS?Lpy*P!r(>xp51yQh0d7|uGmiF_9i`Flw+Ofg)eCW*xX0~60=*(-Wi`Zxj&oJJN zU0l(Y!VDE8=f#*t2*$PT9^faoKtUOa9WS!CW?zrsj77Hfe0ztYo;WaN*f2CVHA$9l z;wKmdhcYZ`5q8qtbTY?jl1PIw=9dHr>!{Bkd~yM#+b1@L4Ww1`^mLwgSJA_0aKNmr z4s574nw>-yG!3Cn|4ONaeBtM*|GB3YvC)QKdFeA)Wf#J~}-IxdA)?9*vVwFwk4%E@@7hI(QKe;f%odt;>$AXt?s z_}g3d@3-zqLEkjzy@V9i(+=g^ZDb^dvFsXN*yJ7{Cd7hM(AHlb-_vY-o*a=b7ROIQ znI14dGesrayXRi^S_iCTZld+rVPaz9KHq4--JL?h6$Qp~VX(AS)GBm2g;~nJDNQ3~ zg$Dp*k~nRj^QF*Lb_6QF?Qo_u!$BvLa;3lfA6bO|90KCDB)iqmhU%5;U*QEBQ>M$8 z@aNp!*I%Fek<;^s1`#Q3vLZkH8_k%#f`1 zY^U<8$!{+d)tj@N`@~Q=j(@ZH#O(3yESchO3*xj$soSY#A8o(f47ssZ;3oL!kboL} z@BWTF9KQs{)G+X{tP{wss$+CA@=dPI&@i$BYMZVunEttcZ(8BPJPa* zCP`PzH=GpcAR2~h$2{TVZU_Y#v*&?`3c@tse8u}d$O;ajR;;4SwYV6FoVYz*sI!G`B%=BUb1u0ITs3@9}32iGg+r&`-088LWn}6`ON! zTN^)IVQxaJ;&#Wk(`o35jC^V&dd@B`_pw2e2d@h@X7kY!QF8_2Z~1+!KHn*t>z&j1 zmoE7_rE#=oAE3V)TCfSbI<%U*awmS?E&r_%(~r4hJr@B#^-+6F<4Q2aU_i zVd>boC&NH>eB>CR*#Y?zl#1bN+_I;*^x`I3pPUVUkX~aOpg2jK?}(7s>MN1J1kZlM zmB(13v)JAtqXVO%8D2%zNGE+gz&50i6tag+*j|tL2cAT?&AQ@!^%54z-{P^H2pI3Y zm!8TIpdgtJ&NeHtdk5UGRXDw{u+X)RzLAM`!4eYHLbAYjg>G7d_r`j^SsUSFz&?F% zpLOb)ub{Sf^;l@k!J}MV`66KUV0kMxzSc}eNC}*3VaJ4f6lupKCkb(T8FFB%(jAO- zQ>_CwL4I%kc56nLtS|`dJ*DfIYx7%bY~e~&p2AWp>MDS^#_J(hO|?$x=cSpLbSLQDdt|`G zXvYyhrNv8@(6LZe`RRAtlW0cm3c`i|`|pP4TK+YG42GLfgYN)9hLL0+f~s0N9J9Td z1_lPqaDfpOxnAHsR$BcuTiv%3abpSrO>u|9{pT^BLh&IU4wcp0L{iBb5_tE+Xx)-r zcxzmPf=B;*eBOf=ko=R5ecI*U*F9?!76m67V!RyPT2hEqa!U`0VyT@xxFSoy>Gs|2 zhMUbU>lP97k@p1qA@^u?&Cib-r)-l4ZvBbAX+k3Cy5lYLOXO2H&CXF zV6MD^_w=`WInXrtF{azJcLEgSj~+(=hEY8Djjr_vuPy*)aPQ^PS4%1s`7vzWgkxaM z#vZ^SW`KC1L~JXK%xp10dANabDmX41GYHwy5|ir2k;N=5kr;XxGzz~P&eBcY`x#Cp zacT8oYXa^$#fhl>L^}vAWO@px?}YVTe{$N9Gy|%I#;*eL2K=6u@!kz`GYGkuIw%Ds zun^&q;me(2kp?4zlM&B)u>Vj!VAO;ODH86j3!0yJTo7pPU1BcqIKtDr$=J1X)hI+~ zB3E3oN4k8vvWvaqf;BO|fXKl-grvBW4cRy@^iQDYC3y7H53XfSFK1iS&AU5e`c9PW zb{j&C;YwUwpG%r>V*1%l3vAT%?~99Ip5O5(Y)yPNm-f$Z$uTU`*WZ9M{l-#62F1um6%wpaWcJ>m|a08O? z$2J>eG9E2SE*F-Xe(+1ob;M!z@&lJ?&_tg0iTbsvxxwk)O#@%Q`d$bEc5jL)WGG1i zv>uWpJqUe}u~y_T!j)VTBBz-mQoEEq?7Ke+Oca-w2mab!aLTUMp(Y#s`n*O2e4ppA zQJ?ByQjjLhR^6307DFEfjh*#5GeVBzrExpggd736JBZ$T%*WJa?O4B;3rkn>3RZy+ zm@N|Om~FU}fn6rrMYd^Nd6si&KpMIl30H0Mx+?DDvRQydlthiTY*6vT` zVF|ATf3(H$gm6P!UC&sdG5^INgVY^Q`KLYTLa%M(b+2hq##cr-(j;4g|L@QnH&*oJ zPv(*Ft#AZgr8t5N(lo{=Fx;7;%QmkETY?M5o0$<)rUL9 zm(%-_Tb!EgzJiL^=stjRjFsh-i-yz-OkE!kE}4*381SrTj3=I%`R1)#L7%^zXE(a` zV`98Mvk$EUL4}LFr%UWVA9bqYX83qcOh(oiI=$LRkf%Pv8Z;aUZlUTMO;(Vl9dtNJ z(O3Z!{`*$!=sDLw3pI|NHqqrs3r)75$z!{k2E*eWT1tk`y7b!XU&C8R2wqD%);+s` zZ0;D_fIVhXw-vt>-t@KKQ6bC^+A#U_HKmuEE`p?(Nb|B4`95j98^&L9;FM@1x@rvC2>DRmuOLxD3EdQ?M^!RA)jy6lCnI_>7PKJnlsShS?G<8^G|JeQNR zX*6tdlou|2H;7Lj>P1{;X-7ogY=Q$!;G79<6np0sv!=7d#Ov~9#*;m%^&c=(eueZ( z4gD1NCjMtSjIbl*=!Nm{=>e|Mi9Qbp@4>4c-<1V+-L=%&u8)(tZL%U`y-AKrxxcSWeyZfyATSCj4p7u;-%A)s?T>cr`S>jF5n=`P>tx5t8 z8q_~Hb#=s^W-mGr!!D=9rBvU^U2%$*qokxHsm*AT#I9ezUImNQPvYk|7WMC@vG8t! z21|g*F^Mi*WJ%*fqo+Mgd)hd+F?6iq$20c_11fla!sfTQhc_JBS(w5{8QHAq8f`n~ z*erhf%RJ0PYdg6?RH!QFx!sF;u}^w%LN`B3{mu&Dp3(j)AV7n6<2M|sG69Gg`r3)XTvK?nbaTAm zhyC8KYj-t)_w(WL3!a#I^PbnK63{DS0*Fr+pRQ=X)4s^L(Ijc1Yn*Sm|K}UZxKD}| z=b7eQxAghE3ORKZW8jjKDZOy+{BniySa@s8`we47Zn=d%(ce>>o+#7^zUJEjzs>!m z=}oUzpT956Q(?YyD;&LZRhx+Tl2;+R5&PN?nV&*q9M;F=_u0Q220FuElLsTr%F83t zO=$gB3JDc=O;k@C?iy&eV)}!rG9C(XHTS+NF&`FQi9u4&Xx+2wmTfty{N7c%jh`x<>PPwIgWV zcd-Aq%+S*(;~=m(BDi~@yR?{-I2RK=Nu}1LzNXJ=QBmp4<5+rq?MZ*DCwW)Py?J?a zyw_x$emb!K*Sk2Qn`49U|6lefw|d(C&Onn73!e4TF-e`1%r?ONNeT_#e*=dnvDCxg zuNT9SAN`R1@#F(SGv6mqn|YRrUvS+E_?#k<<1qKg-E+?whd|(Mb=PUmGZj(qE~3xn zn4A&~D>KXQuN^@i^ifz4?EplV0xu1s8?S7Q_7)`b7-ohWFjQ;qP{f@Z@ibK)Q|wxIlgHY0)}Uy>^s%ZH3DZxaTOUkcKA8wN1NzCHSc z^RafvabjkzG>&?!@?0_NZ1F}rs? zxOYU+i4iFPsLFO--8%?~R)vIBgcy1G!qqQ+E#{TtA`=FeyPkP-Iy+hPQVlfyqZ>~T zCx;c`HT<09pu-47dR_}divA;Q<0kW2w6rS~6y7kTf*J8bOkn=>J*oj800CaI&iU%p z^Lhsura|U=O8;bTN^~mBS$AxyeA&FR=muZf#;ssmwCEsRB?0#S!Mui-zdXJ`K z+Y680@YEKsEf@wHUEO>>Bje&Y`#10i7L5D*NHtWiKUt#VxP0S6k<6SVR1>e&i#~Gd zT(th6U9)Bl5v3&iLCdNJ503U9T&91pE>vQ{s>9(uSHU3Fb6u}YfeQxlt59!;NdUNb z1YOzE`>McV0bTO}z(`zgH_7U`PG5;|VL$#K{V`AXiNN?h4du!L#&C zN1wI0jNDK}kVPgg{j!DL3%G@F*Bn*5>+!vfH|c2m&X{@_ksl*UNzfnv1+_P6wt_&0 zbe@>LU7D6iQjGazcboeUeX$0#KDl!%?kuKS?pQGHPk3$QZp4%hgRQWxo>w^>rRPB} zMy*cf`eb=4&&c;Qt|yVzimac%y{~ut;k@$g4#t5s z;-WeWE*VO8ll`2F7A+6ic;ah+OEM^JmcB%u(s9JjkQQY?_55&2pt%0$I&>pIn^-T} z3sAJakua`gEk(GD+Pf(dD7hFNzUh};L_@9`?T#sn_>#(I>x)bq{}MU*=-}o&)Rfx> zkHTiHPkpYfG4^lC6C74go8|)ibI+yX_O)ew0 zSVnOEQj~t$p*kFTa+{TeuqE5n zi$TJ8AmpX%(*nS2F~c=*?B}nDH-=ftkp!;4t$$swls&W{FNZT*)!B|^rs7`k;|%us z&(%9s(tg(-@Q6?*J04Ab(@VBeX+~fK^P3I&fI-{{EAzsN!~5C45h^82Sj=n1gvY^o z+5tlEId5;;Pu{d+1y4ylrLo6EYGc=1D2y}F5Cxyo0jZR%^4elzW7VOVa$-UHihZ>#OHg9)oOXXAKQB8yL zrQEP&e(@FZ*t(5oK$cArVnX(YrDp2_xo2aUM~FIcWJPIP16|EafKTFbugsfv1G6Wp zRIAEXNp66NDlB74qtF z?K4%t;xcdH8=PiKCa}INExn1`>2{AXuV*)|)B3E$BfnR;f<eCht`sI+e9pWAg7nk{)}W+86#$mN-0|s^14P$Oy&-Dgu_XQ7QnP?bJ=X&G>)Bdi7*RP zG+)Lv4)z^LasA^$uYlO$_gEBdr}}9#d<%%@xuD<+TlrseN}#UbJhUkFL`V91MmSQRgWvTd9Z<>OTe=)14=Y;H%&x4<~*wRVymyTVtcfiwmP5tnK35j=MsZ#BM&)@nxS9 zL%+X{N59fvw7VN(J&Gn$fQ44-g2I>cob2|zmN{o-uN*#g{?L&Mzywb$;)O!x zFIU)EgM|S?`ZW8~b&4zjIwfSGUmaQ<8R6sNa!$52*died>J0|6&C&YkDcr!yz;4ik z(+zPkF{ffonXjsQx^m7>)#fJ3nu1`@d>tdD z6JGf?Wd=G{dwVO=ixrKQ%Z5)(hw|rT=#gmWaVW+fgrI|`?w$PhEe>Q67j@l(ukbS6 zNoIk-bt{Cd)YN<-oTLE${^_zKlY^LW+@DmHmDQlC?8n7cjeq#!{0J~5A)RL@X83@$ z8%eiTQp7ez;=$b7YCeV4O#M9*c>LE;a3m?1y;;|?Li;5WyW_{JGjD+WRL*Uus!o4R zIT2Y&_V^i;x$EYwokpxgv(gh|G2z$oyZ{Gs>+ zojT2lck)$G_h&2mI+(VY$MHksHm^*;PxJGj?#9%(87{fk{tI5qe?-5RG^dg?s- zF`wksO-LEb2@0`E;1f+%ajC>K`CP!GW4qY!9g*S2CntsX-JHM2$MChD$AR#82#6_x z5le36Di)Ty`gf#5Ku>d@$Uo_}Li5Du;sYcy4E(hErta3%iyT;;o0msNn~X~R7#mw( zX>cxp#dpvc^ex@71%43i>E2E~;93MJda~XiX}>|{xM|n>?${c=Ty|Jdk(OY5 zr2lnZCz(Es6yMBXh`(G_zLrNwNC^n*#haBku3!Jjz5K@PiTu|oU6k~YoV{d*h&gm3 z2Wpy@m0!Vb<4Wbn?A@RtmYU-}h%{Lpq}?6o(0@z|nYtB12CIgHz4|aBgAAs@u6j&z zpP@ob-KB}%+z7&JckbPLLR4;Eeip^DR_gtNjsJXv*$0e*Bw!6+*OKs=+5{&xOP7Ln zWpGf?2au$tqDVsn6r{H8>J%aKGd2ec^(ZMos~!TFqDn7BjOPMz-^*3xulRv^U1)CK zg{bC6fUw$$Yyana{O>*Z!v_5GppN2z3qYJDYtrCP=E80MzlsWm4fwnL-{3s0Khb=Z zp|dVi9fYXegs1`cU#segFQ>j!$w#Yk5Vck~1IxhZE#W<_e1|SkB1<>xs$C-;`l{;S z(tqi7&Y&p3T)FXYP;HWrSuy8ff3lvEmnUQf0BjfhDAu8fOp_-Rnp(>z4}cV?s@V=- zO2))*DFkka&58jVs}6=lm5K26LVXZ;Fk`Tf&Y^s1+AYQ1~tTq;Nl9nBhpuQl<*cuq4F&BVV88<^(x2Z{%oK2 znGKp&TcK|K6kOP&+S)s0{`z-K{ZFZXv>H=yWG4N*Y8STX2_)fA2I6(xkEW~0=M-k1 zW{b(v4!9<|vS%s`Qxk|xAZ!*kk7TT*qr1r9j!<(J&S?jwR}j5Z)%O~+-yO^J#54w! zqhB2uAHs=EfVr}?ROg=@tU^*wis)(1xkpolCRQhLfy+9Kaxc))(Op9KBO@=bc|ZD% zFQQ@Y?Uk%d+$=Xz62x)TF@RG9cX0=-FSrzcBG(_vWI?-)@2B5)`0!1ZTPRZc#kK`tLt0P3zo>{)hw zB}d*%(8EVPR^-=zbhOO(mdqAIdQ^RHQZPk(9W_mRKFdR8^LI`pNAD*=F;BWIohe-K zJM3RmK|tui#aKXk9T7Xxpi!j}r}SsF=1Zz-(H??XdkFjA3+^(|5T<0U&7kVnWaALI z)LI}T(BY_Tu>zr3$>c%MNyg`5AZ3pAg^0QKw^s<5GjYxqL0A)6*xvWwbI$@O=o0(P z5%z!47PBmHC4ICCPRx13Uk-`i&}1CaEsyZP&X_#p0=I+oV!F<2KYpS^8~z3h5Cms< z)|b*(06|%0Q&h~>jw|s5A36`JYL}PY02f6Hvm?!XGemN>pmKKUh12(5I|337w=gC< zhKii%_|h`qWQ?qH`kUHeAF@dH_HE}7eMcMfIHVcpjCB1!7E)Ps3*hpw3t+%DG7Z0w>YH$nefw}R=kv|hoY9tf+cG{FXjc#1fpjW2`|_T`+?K2 zjeY_{TC(dB&afBB5di2`Y@{5ns~hh$o*NzUijTO);42$ zi`71B@?zJ?tmnH1lbk14?mxI%L3V|JVcoOOYVo|!tg9j-;>sfOPh2iLY2f-p>Fdq{ zUiQ}oCnO_xNpDZAuJ~MSCiRZ?wCw5?{pk~CUHKH6_UqOjY#nN?vKxQ z??&a%Z|3ugmo^qgP48uom#s(-BAsJr=A`Xp>c)t*(*>f);jEIuW6V6~x6L5Tb57Y1 z!H`)}+;{!Kkh2CCfE2bF0U=gV8!8<RP(Kg!J+6lexKw3_~5*kNY=RgPPr54k(HSQgR#?eu< zfjmqMYuE0;_T5u7k$SEJeG5NFtE*28eP2#@6XfUFSNe}X4UqGe{FC$k`cwCQ905`D(~7HRQ=omJ@4y|q7|1B;?K zE$PcYDolU+ji@slJc2v>}w+=s^0g$vJX4z<>Z zshKw{AY|Dtv~L>pqLu&1|LP?fC_yRwB)TfB1#Lw9SX^=3<*a5C+O8 z`}5w^Ztuneko5{Jo?q~%@F-Zmpv2d@=NM5_EGSkgQOzEby|Vju_}jU_*=)L;xl-b9 z&>ZaEYjt=ALY%3wvRG-pD$ z+D`wjJDh51J1i63;gl4uGXKfnPlUv1t%#JjTV1t$=5L$*8O*rq%@jrRPmaU+;gDFY zE=xTHpmd2#~ZQv32-1P`Y2j<3ZNUK`H9sthV=P6(*w??>C|8S|)8Zagk1&N9R z(TJ2uuelhtn(lYV&l+9ukVT9WWDou&C2XA|%y<5NcjQq|b(7OL!MJDs-%lwbgI9h; z%}sy1D~@5*g@QMExz5^o_4YobU&GJ zc@8uL#~qU^LeCr_a+@H;1X!k4sLE~oy&-7dOrsrd8d(|D70#UqOUR>lR&5oz@+tox z)9r2vTnt_GjPH&Cg&9dGpsZjZuoSGFG}VPqYd80_))`tCV@{aQ=0LtBTM*&&ZF&gyo-<~ za*t5dHa4+xs?G%k>~ILiyF6cC_;Uz$uPToD1{^K_K7eGY+;o(gG7)FFb}KD7gDuG` zWJs_qc8ebdl;pkj0JFM#9qPSCGD?iofB)cO4K5iYf5^K*ATFykJOT#+dY zr4C{VPcWI94{LVH{3m;@qHaBJ5&aO%<_L*-+h<=Fm-_C5tgNh&0Ru>Ld#!y#m|w~@ zp4HF1_!BbJk zzUj9yF`T_jw zr?f1I29t+ zD$?0+UjpLZ2b2Z+!7ul}gGi`l&u0(V5>8dcMVamj(Q2-QuZ~KwK*NhqZyW4T+^`j0 z@p2Z2AgR9fuv>slo4qeZ^^3I_X^@mp?RKl}Dv ze8f=^{RFkLX$61YueATuN&LQ}BFczoTIwvCe?~9$A!J{|4Xt#QWwz zLsB;*>!gY1o$pg2y}T4OTWG^`FwR@HXi=`}5$_-T4k)WFnmn{X6W^5W4onS)nb0o5 znyBGtk!EZ`nfBa_CCPT&(ou&j>k=84_QAIDNcOfvvs0s=G%Z#%HS;`?w0aHk^+>^- zHC>&HZ=)FBeRU#wmGqK7kxqIAVi}EsgW#MR$>rENFa$__yZ#xfy5px#tss}%UYRr& zx4v$@L4-T|I+^3H)06$+2nY%SEgfLm&TY}7QL?zR^7)GwkpZSPxlLV>=xd=nd3Whj zFw}ZL!*>tss7&&DkSQj4R_u2|`?|zi#6kumFkRzQ=g#@_Y8Q+5sn33gIqihK78;;&Z0*EQw=!EGAFJiovKHn zWzcD*wLd$-<)(T=~xUMLHQ28)nB(5=Gh@%)x@WpOtN%{iivX&cd&wc- zA0*M6f`USnGwWX?(k{}>)KoZs{gWw&{BZ;qHiCM}&t6)kxp3ja(fYfjJu(l&#OQh| zx8=eqZ(K;a2BBOh3Sye;-(t7b`E!(Nm1V_p+D;~6(-TlTKVx{W`^h7+Vo~y7QLA#m zfm@A`7;#~f3mdv~z5Ur&gzqy~`D{wXQ>p7vxJd3O=x^-%-B{R5FCy}Ixau8IThTzh z&Ca&D;Ij*$^qkN()yj2W!i&tXHc|XzU}~?hm;h~2YU!TmJ2BRg2|2kTT4gz@xx0|l z)%H{vAoKO0YR`ikvG5Vz!kYZeW7?ld60{v^Sm;G> z21_AK>ROMiic&?3nZbsh`*rKJ50AGJCyI(?hp)^8K^{s-g1RA^Rz`#zyt7K?#bH{% z-(&H=f5AV>{(2M2k%ec+CG?x*UtKtK=l=b^l>R;EAuVb^4o#-*!6pF#tnQVUm}Ybt-gN71WH8W$l9rX`TXcI27Pug?FXL!}mh32eSHBtS zUD}W9P2R+kCdTpc!Mbhrw!=M_+NlU=h#!)MDy{Owal0eh{;E}|1`3*q+sE(-X76qw zimu5&kY*@LE2a0+27$f&s~z}t!JBPOrNZy~37efX$Qah#shSeU5LL|+GKPNWBT$IT z+Xm4X+%XvVv#YU&Xks7=TOLX4lbZCqn{j1_O46RQf1dr%pVSDgM3QrL=`2vXqT7bd zwTUV~!GZY2`lwL4=Eoes0o;oNxWMcfK>`tp=xAF(In2BHxg#D~@HjR-^CccI@^M4& zw@)_WY{^*o`5|JS9dz7vu>lveXsrB)3MlsziyF-Yz=}`6p|Bicvo^LgZpvTTUsO#D z6D*)fYhzpzF(vtcc;B;S1q;h=Ogmli`8;irbhcuCE^TAA%n1{@ zG9&l0LjzB- zEPI82=u(C#*;pdR)SADr)WVRi22ryN+U&OJ$J?k(QM1t!b9-a0G(5(Of0WJ}>xm_M z`p@fJsxwD%9z`8Jv2umE@RwbuuJ}nE%`=M@W|zo%LXK!p*-Akm;GqXSp#5blt$phw zsuPc6(TcARW9R&EZ?gPV;xrwE63I7xqdoontzu;yW#0LUy60HgMhp3$n;^nc0rLra#>=HW14Gj-Cs1*3O9!+?!_~ZmJyp>%YW(@ot+vT$ar} zSgH1ooj-4N;5eR;QzKdZ)CxSjYIM|k4-lX^2m=T+=1mpzwdp_VmW6#F{9YE6P+rjP z6O^zc3r_@fYqDa@R|BLJmD5{JS9XLwPVeP7PVBPXtT>kB!eglaf>-}baYOIk;(kiY z3I})hwO+LL5QuR>adR9(hXwwY+vnF*@1Ly@=RD?2xWn}oB_F~Jq@LN|YQKCjaWR2u zqQ3m$AE#N;zU-o**iF`(D(?kt(xdfOPc@ZV%)qICpcA>WuxumQE`eirj<<5qae6_l zF|THm-65e)q#A$_;{TqX?;uOFMAnecH_->w>}^DQVwZA4erV`3c7>A!<>8#J<&f5X9}+tN2JvHa? zXRGs0@&!0`-p}brHZG)~{Q%7$6`|dypWn2`_^wI)NEM>)iFall(&6zeqSj|oj%f^Di&U!xr?>ZPs7w&C z&3PVRsji3m`4QSwkHrHI`DrC|4jD#%CiLhd(%+LPS4=_dU{SnYr#Qb0FM`i&9d-pY zI#2o2SFy{!JSRFcEwI0`n0R)bgoRq?xxlW-8RGh!l7Aj$2BF_2Mr{xO^MkuLQP8H6 z>a+OnS;&5wgRVS~ruquI$*pDK&j@}V%o@oSxu1#lr)hh6L8t?Pw22X3zF=aFsTVPz zSM-gh7$PSNU#5VIxE_jNl5z4uGsi+=s!H5=8uzN!ob|^Z^5-ar9iGig2<@_S!!jb4 zPrSpVV#d+*%Oo3JdhKv?rsT<59rfN{2Dsef{i=QU`B5!)6r?-1rY3brFyz#hUj+NELN zkzzk4I1`0LkgYB~gnr>IqB|bSmHwk1((@l7adqW-;eZl^1x~yicT+atGCLAr@yuRL zj5aptib>n&SHr$$k$1n&5Gr3&TIQ^=k@n7L-C%**@i4ua7MCFN+){h7czw!k!-@}- z_F6{~Mt*BJzH$E_4M%cpeT7?zKnLO6qi^Bap#8E&Mllw^S#X#J3N)!=rSKTxQi76$ z?{>9mHPC8*M$CQj{-C|n#I<*+_MG~3An#BQQvcJOkJW5+qcP{7TmYk_}q*t6DW8YvRZH7y~yVfqLR4M8n^! zmR|C)|6uMn&hb&ph^@Vt{JwAP@>a z6>Yb_kwg2}NJl<&rD1L8Q=X9WiH>Jsm4t)@Y20Muv`_CucBi5mGj1<|h^Y#Zq+wd9 z3oHNyGA|iBBd&hLtvTk9Kd>mE5N=HSua$lP1^VFVO!W;trxvR!QuqQ} zLjQ5*F2nB5nk5$o=7faVNWTtAtoPQ}O9GSY04etAxM1Z?ADoI-o})5=5ka zPIz#?vs3}f8M(g$)qn-u@FE=s^I83bOpcQh8H;8jeE?$4vcD4Mmwbe}Ee~oL1r50U zkDy$(*D|cinQ$hE#R>oSu+wOmszq6-`<6OjPZ=WyyC%Y9+6ie3wDJ-C5^}&J$fVBWIa8Y@DRBZ z(}iUpyHUjQI1}U*)A9@Zib|TJ0@rBW#!X-7Rl{)0Wt;HU@Q6btAMyI0#`h493t&G|g{OHd~#o`y%%C3%#p{iNv z-Kx)EA*5Cj1HlFhw2Q_+kFbB!+oTp%ya? z3swBqvP$5hdcETiAqrK9_H7xRB1`^n+?+YP)ADES4HmDHIX6@I3UFx7vh9Yh6S_fU zKzd(096DSvOjSR-Sr6}PHxb8~q{Jvil~{rxgp|+!w6F?GcYz>ilChrV@X{f&>ksa4 z(^cApkjxu7h`vFnn#+xwVSPx6#6eA@vfn!>$6I>bQeOgl!e19?gMa(XfdbKDrJq;xz}n0;0xAZ7Uv2R$U;HXxhM7ZwEW6qz3setu zZCkTjlw1>Vl^5``PMvmcQk=E~I4DJi+16)K^olo~OPyHC!mV+e#$Wgoe6x2G!epeA z?pEWxrr;yY76(y3w;vT?Hp@p?J>jn^Ksi;Fje&p2ibU3%l+3fKh@rS(D@Z$W9xYIc z*aps7!f-~$Nv!=|I@6)L{BxEH@CDOjwm5s9~dbHR2zv zZSjpq&?5=1x;nRTh+-)Im<;o*gw`Z7B19UgSbo$QKVF;@(R*_FWelr{FddzC9oc0P zGGUW=HvmZ9gRMoN+VIAiPnZ;>wm2o&+s`YpPn%f3W{u|co?2NsOQH_`IRndSq;q|^ zjQE<8ektes-gypvlrvK;>K~9Abw%s)<=v-(n^TamXFStdMn*P#O#bNEY3=GXl2R`L z)GxpD6pa=t`=_I9ofZ8LOy5M`TQ{3>=6toiWK4gR{o$OdA}fe&`hl^(g&ake5fc~( zU@JW78j}#|F3G@aoFy5V|FrFRzXJP3j2893#JrJx@_7v;`=w}ijW z7jI>Bw=`g*`6Xha0RZvGHNQ@g{n-+1EABo*9H?6k+iB`8Fr!UyW)TyW zUjKxEUnpc>KMZKtkk@sc2*SdQpp{12X{qsTXkCF*eNR4)U@RMa{itt4!<5A`aTOzF z^2(Q(RRCAto*jz8k1L5kRW*SBf!UUHaw(;!qbW`HSk^rKq3rKb_1U~yLy=p3?V<)w z^YG+WPNU%U|G12$1os)CzhFD(%TE16R=e1XIaT!=FcR@seR!pW+5PxPU$R`X)Lsgy z4gk`YB88S_KRf>OS1)5q@O;1OWjy{fK;Or~Rp=3MWEUzH$8EVM^>QC7;Ra6Vx9mXu z@DwjWkbET<*DN>@Uf}oDFt8l7$BMfaO^BCF0?fV}O!NiMN*JT=Bg#DWGsDbzRNy~u z!vbQAaIAs;k|j&n?G?GU%;FJ$uATUP6n(oFnY^EKHm9l#OpeE(`yls$?@I;(d%N5x z-43Prnok5w0PZS(yiqC~D$6r$tmvNa&gF+bt_PGFuw7Gef)&ki zm~80dj;D85@7xSNBbQtyBD1`{!R?1 zA&lk4tMloLGhfjbIu9EU1?|F8uie6J@(~+`a$NSoD0i_Wcl$q zvztq%rFOR(fHqg6Ui8e%AZ2IW<(|t8*M7QErhM39?2--;l~~C-l|KR48}?stCi{&a z2Wd-m+zWdujbBPEn<0XS5T2CpdDcrK%Rv0xiTygW6zP+5gQLSFP0Y@xT2p*p`$RH= zEoaY3o5O*a`ipb5DC}qwrLmU=o|#_cVh_>W$c7GpoNuVA_|AQQ7`&+$jk9|I?@@!$ z`%z_$PVk^UFc_r^mggRa0sL#LWM9cUVYWbLP*H3%5^NlLD&RV=LG@YK%5;Ub7B8n< zwxqAKMwv*GczrjKaFjPO3-kfy8%qs(gQsXqliT^aa#aMUGq*Zj@n8V9h+d`cvhiC- zPya(tQgh$Gj_We~AhQ*Bv*(;tLsxMlqgcRmNnyexq`L2s%3^ujfr-;IAVrE`QR|02 z3W5Vm%&p?`r3hBd3lzy8oh za(4$>_O`PDl#8c8-H)Vx+dF-~3{P!D2u{n4Gh672S^F_mbNSn(|Jg6wk?&X3UKsZ0 z`z<~t&R(y(gqD_Xli9ced%Y4{@0$A0Yl$Oe?#BA|h5@410F6m##pOm)C`8If(RS2q4AqX0#_|_(Pay^4| zRC#D8@t;0mI&!5cI656z)2dkG<4>n4Nx4erz)5@FCEXDZaI;aDZhP&&&iubHRjlsF z60v?wHymcx)h!Jb4_i0YJ5y$?HK^EAfB<|6-C((7m_s>1i*!5Cm9L@ITh7RvE6cV! z*G;b9G`%zjh-iV2Sgc-3IWF|Q9}hPH%z6x%%Hs@guEDT2h-gp2H?5RI;Ybq)i;L>u zQN%+c99A$`y0DW4p24k%bo-6C5?B^vQ?-if6PC&hh|*9gQLr>QUo;;UVz>K*<8Z&{B#{Br*+Abuu^y9VCdBnVUHa8||J z4*WMj2&n|t9u@outIeIY{_DliivmyH)?LM(+;qX6%;vE|u5X2f&?2=r%D!V*13RBCI2^|mr*+^*kwEiJiQpyp)dtX7{ z^Vsp@v7$^60VW^=YV_&`6Ep=CJ(xy&h+boE3zQ14$$9^N&1(AZBLVgX-9vbTJP~OC zgPTq+wYWU;djBXi;HPRn@!AE~O22?~f0<)K_2t4kG@%z^I-jU_!zB>T%-toCtX;{ zxm3rDc%8k<;qf3)R*skeZ68hpU#$mzpZ9*WUpHT@A(uW5$4>6Dp#EPdKXd>^IkvV6 zaRiv=%~vY00ZyTrPUMEjMq0UH$_u^H<6lW)5EKFA!x&Q(<(c-v#+Zq+a1mJ;Bzj23 zcWVR0!&9bgbnwvr_4vUa)KxrJvOasX9_CJOKThaB(og@{sF?#ZGIdT~ePRyzpM{E7 zKWKk;U*t5w#O|!99*X7NbltZMNAK;<*x_e0;6W4HzJVLR?9$t6w{xlToLv~6&}0yS z;BxlB^QMxAdJvUAK(|i$oWgG7e$(-N&%J{BMj5GMtA}5JE-n*%Vx6A&P=qDUU)i2#yWw2d?@791mj*z{`bRNv-6AB!$cDF= z^_|LSy}^~y_talEJbT(-?*I!wm`5W zJr~vaNX`^ywCCE3)FVG)#q11E6J~0}>b3mWz12G}gdNi@-D8fxrou0vCH$%Fr`W{M z3t|OK=2)svsPllL7gUfW4Zu=~<@Nml=Q{K651J$dWRss4c<|)t2D!OCm?tgr>!#EK z3x)efSQdSuJB#Ge()1)BGy*lA^?ST^&|yD?5lNxtM}S=$YORNmYZUFgVXM^Eq3c&5Hijb~Lg`4Ea&lJTOG=1(J5${|uwyk>N$1`=p!O{Rh+6erU z-kfT(lMUSlU#oqEb9$;Q8VXve4vf>9?nAdi5{!25mOB!pa2Q} zKn*pF2z@}S*-UnT!<}A;QT<#Dj7ib2t95yCScg)2jfY#6VXDDh53Y-jCOfWo6uvZ` zIy3f}i@f()$rE8KRZg>*-e>GZQ_7vw(PFytb*QEpI+QdXnOM6j^2^iY^xi^YVxd$0 z;p*I#_>+tO%gNDNv`y(`1zRd9onr--k#&h4^(^{^0ZZ4nfhT2O7HE`4sXlvsOegs5 z=pEzGb^lC2hAN{9G#)_Ej^}P+I*K7m8s1i+sADb2;`OOWgGsJCj)g_n{Vo#@z%DB(vUW4q#hxC_r_?VIrF3yl=oAB8Axjy*-x2M1cTx zH*XC}5M{e(I=4p0Uas-07&gkdvY0G+%14}ibpER45pR?>g7N3HvO7|K9Ta%mQnVJv zcRt^mre7Oz1)>{YL__oI3{5Z!fM1xwzG$-C?cMGqQnA zrr|j1<(4Ng`y#saSgKmqAKK6ZEYRyBAGw8>0eAD1Re|o;eoE{iQ{binP|l7Leko&w zS+E=k?Wiy{%MCnU@H997_yRJohha4TxQ*sIb@pbx;%BH{sK~x7C>62mj@zwyx~p}F zdY#tWj+D@gpsrF?)m(M>KVAd>_m+XPdorszy90|gk5PPjEm4kE+gBo%Hur$-SVT|? zrLG+s>(sk;1SWnDCUt@Dj`~8w)TqffG|HDs5~w7u9w{~A?(j%i_DVa;5}V5;u(khc zz0m>e%BX1HU@oH2&r^18H;9M^aVb@Aa~z(!R$!T&xHXiPfK*N#V-E^6VX*fmv@=X0 z+TcKkwAgsundao4bLo<`sBX#h>{@tcX`D{IEjEFonC@n*$dwTnaBOjWl7AUF;uGdl zPCuAv6N$^Z=;%+L>mAGTj5hx7xBpYR)O(XtfZ3>?1!x!#?oRBNoQ(Oy=te!TkqXx4 z7Ys6eGIS1=xUbD&r(^gpZ5@1q#uTz@8V0rp|8yC)^X0D}Ok~^r#P_8S>jZJP&Ufc} zURK1xVH2aueiupVJCQtY{G!k_A3_EvOq#$q?{$&iR>9U;$t%meetr8jKg+k#nGkVL;q&o|qRZ9&ecOqfOGF$!Ra@x;ClZe$9dC}oUx^_LOu2aR(Fm%eP7yo@4tQE!U zoRw;qjPwZ2;p+amFX9szq7~U)JUj=L$hzqda=ZpBI`B& zt#)D2&NeZQA|;~S%7m^o8G5by+Z#$^aB=J;Fw0^tDtj{4cyUmAJd9{Ipk;*<^If znh2;{MQm&Gy#>$kezE=bAB}N@t#r1SU_3$XU`)#a{*Nmb8+U?alwG!muih4eY3t}F z+oA6B9=tk_74OPFs<6-nTgFEOOb0=ZM>#7E?}%fk8r%G$66yfApJ3Ek+c5EZN#f*i zvmep$Ua4<(_R0Jy0AuV}JyM7fmegKr*!V@5g|NfzM{H$`{NHhgz&i{$M%$}9zlE%> znQkp`#=g)MXO%(K=Q8uB`U@ELi<9P2L}sH{c85Zg+B4&03L5Q??)B7!J>kBRy|cvI zQu~qkaEhIc&Y5rxH!@vv!|+*|rHDzt;&?NWCMR6?tx-y^zRLKh%&&ISeG2|BkrG!9 zcMV}VA;3EhstRFMda<<$)#0j1Vv7*1horO5tAQ#`fiE4QKI2|isjNv=403wiWycjy{UMs3N5xi zzoAOHWtn%Bml7Ny-j>bWp_On&WT^T1hx)qmpD`+V)zmTjrd);3z=@iJ->;n`JO1P2 zAf5i(EiEl7Z?68?kDiB~Mx%eBI<49otOa>Q?IoKKhF+9e*AdmSTI>le&j5f8vwm?n_B8oF*O?e|+X9{JGVVjD^WuL%U@FVgYNJE3YiT{R*vYUAiTwNvYn~ zs*@}FUZ0dY9j3R}lBBH~Ol_n9aF(R(55&GYaXNAuZJdo^8^fi>QZ#ME&Su)$ICTj% z=ADd~UT>;nC{AUg9-81*{Dc16D=)C-uQoV6hIZ=*&NQF8E`11}UU?F|`~7$5(hM3K~ImHqMjr(n~at(9rsyrD|fju#ZILh{=f-P^Pz8L14rSa4ry!BBX zkQH=8&Hf|DrSFb7HHA%-4Wi(>jF9ybeHLBXc}xbGD5QxH3cs0X5^-uxs4_5)Q-1gx zvB}a}0Mf%YShO(ECWl-Zsf|YmO4y9A^|a2T= zUVO2?#d$kSaLr@M`6~#2<`P_{pWT+ynHO5oD0?AHf1lCmZ-v2UcN*x)$cwfpO1_nt z41E|Smjg&@JGL@osN+D1GLaYs8Rl8EH=xV}`3Dsbj-}}600|?OQhM`LxBCZFc6WF0 zY9@Y1m=mq+FVpQ9@N~Q$x16>}k62?75o!4-6`hPIa8AG=5=UgzdOrzHe?)_oPZb7e z1#2sL&9C8NACr)EmDZ)Z~y2zZ@~lOckhq=^=cC>?Q?@B}><`6>whagwRZa2h6D+tQ+(L#_bHdkQX-*Ok_@O2-;^>Ddt zD|f{Y9To8nyRQmf8&B8Emph0NLC*Yv{&0s zY$==;ofx`EVBOZ^U8nY76{VzG&9nn#sitMLmbMxifvlzV)8hPTGFd&s(gNq&d~VK+ zlKvEU}^%-v8rW}vh|bw0@#u2}Kn z@up5H{q*UCoC$4eoAoZKa5>#uruz7YT8J-Xg6K<@*wUfE>q6C!`5!mjrP$JrQhV#J(MUZ1h`OLSRZ{NsJJ z4r8l_fR7QLD!;@o)fC>mR8|eqy~auDNJ%|t0+j@!TJ*Hwo26NLo8LxF&p!h!Cevqb z!%_QEzOsg2>@9W7_&t#@d}eRZV%GO?XQwCK_t}d+=Y*P*jp42|gM2ce_?^wN@~9@p zdZoQ|lfhMa6ec%Gb6L}%`qh^_&ON1vvW_gM-e92c-g(06VC~R^{mKWss=C+ zhQ21;7WZe2^+@*i%CbM!dkIXUb2uy$YPrK*c9ZNtf!EMF>$%jd;;vYcQg|plQ7=Yy zey3aTn`=H^j$N-u6#dHn<6Em1Cc9Iwte^$039{yXsC7Wt zs}r$>w)_WBB+iSX>=9RQ_GIY*woVjJOXJnnOTIHtKMcwALg!7bbQIxP(0cn(DBKmd zk~k4H0{AgJ%4VEogU*BB^=p6ULQ5yAJZgq?i5sl5<~W~o?6i`AZF_A z3iqcxp@Mx~iEfVrZXJ@S27LMm0Fu{=WNK-m=BMTMz5A6=IX1N}0UG5ut0_LYORTit znATOVTdk->Jkdbq)8Y4v@!j`AJK2pB)^Smpze6+)1w+e+JWxcc%G8-7FD%;W?%Urb9 zf#}YIz;&6IY>U_Yd_?EU+F;u89gI10!xuq}My?V!bF z#-$bK(t;RM3-?R3RTBTe4MNxU__d4hYO5oxmC&AX`_8xaN+_ex#1JCi9eLmK?#s5g zy}=)lQcqO4#n@o>M0Od6xtMG=pQGPvJC=0t@ZrkaFtJdnweFR23Pjhcr)7D>X}Rc7 zR@y*3s*w{!&aPeW6q12-U%zH_YYo#i)}_;BjWk0stv3v#;zq5?OPdSF{^wnwkWNzo z8*WfdSo1e~Y)(&?v3T{tr16?zrym`D%REdLFmP@;vMt`#ejb-=37?26HUjAyO)n|K zCXA+_>&vTbM)~+Y^)&OVdZ(&-_W9&tt5nK=-{#E+$QCt*aOlbCpHU^p@7|!`Z*&4 z_dSU?`|9nra0;86)&8Pa()-=Qot}$PaW87olj&-4N#56+&qJ1+o#MP{67`%w6mUbw zTv?e|8{`kdMR|0;2_dVuA9l}wLKdNtCFak(E&AfRXl#D+uV*v)9yHMzs~_C=S&(P< zObjD^+wUWUB`&g)y}sg++~2ph-iX4?sj5gNX|uqCFB?OOLOkQED`W0kmt|%QtK9es z_GGY3a=53X8lQjIxMmq|mKtjQrOS_CL7+Q%Yt{zbGs>n)-V@<({HpnBm+I6J_(v6H z>C+2fqQU1)tv1#6eXoJzJC+0)s+CWUWy{O_s?_Bb2 z^G+VIvAr+tH^Jc_keV;Xf;c5gXfzUg3LUHBOOd1x!%j-0V-iW~G0IS-%#(1u56A-e z;3e47u4pIUk~U2vG555eSXL^f#HgRhYvatgetq7kkaX(Vd}zMSzM1JiO=&Zka<)M` zWC!H?x$Vq9-8FPm)*Y?y*ZRAfS){QOKpBd<&3UH2uA6uUKh)Aa%eRhG8XZ&c%%$a; zl+}SWpgcz+!zz=eRYX}bSlW*h-9ka^bEBpS>=zS`F`?Cf5PdHWG&Mp@JQJ$oMP0?0 zA4wM6jer{o@dPc+(XE$bFLiQs^z3S13&IhfpWdNCC^$EM8N_s0NsG3hK9z&-llm}J)2k1(XqmCHn;c?(7OWaHAj>T z-gYSYjFVky=yOd>`YBTotrz1#D#=pXogmRDboGx?K3eL9)e$E(4J7b ze(6)f#*$L0oHPv4xrIqvO2Rr?tJV+ZmUx&6_cNB5wM|)Q7UcR6uo+V(}P126eUiL&mQmi=KgiB;hneX1sS{06bC?l~_yDtpyX#m8Q< z9u@BB&w^P>i?Kf1v~|oV4j(fK8vVEFRW&YjFG@>d1`Twk_I{9=`dWT{_op1AnSK|E zn2#wZqhmz@*EGX&@p17w);1sW*pxGmCpsd~7RtQDJlu2h_kS$k{1&oVNpuE>=Rf5i z|Ngo*B^5JjGQ5BuNY8$-{=Y}%cS@)yL*JD|rVR!QEQA^R5pAkg*o#({ z$JiU|mHqbjqPjX=?&YK!xn-6Le6%;VZQCZaTE8N!Ky0l022GRpj@pvoNfv+G@sVxz z9s2M3Q8su8>h1sy^uMK{WzYSrIt7n76&ZRDypa3OVbe-IhNiTbi4NE+@_+uTIZuCo zJ-i&Nva_={v}JEth%3ljRdE#r5sS!aNYn6{_{lc|F)@3Io>*2cG*qY*P#QXXP?DTwe@s zQ9i-rK#!o&(5mSBMaGrOCEpny;p%ISsZEXqyRw|^`$Jzn!ISg*r)CJcN7d{K^{miN z9=su5$dCGIMIu>9`HU&kSJ}rE!F9%gtH`GRZmbNY3pR&__&&yw`Oi8k3fm0@6^5gz z@JW@dDH5rH`+dH*3#tb`LG|WT-mA=!RT^Ct)LseVuidxJrTG{~h<&QOjWbjq0(bH- zOhs`P`r?AX6fW7x_=-gdqb;|z6#x9*nLpV(0r+HiMEqGMwe^$Lpu{ldk=HjH)_1S^ z0wK==mb>w6SFq5}5P3ZmDw1N0ffYxcFT#+7t~SH4;lM-J3TFsTG6t%_O&FtA4`U`8 zTfLz)Y+`(h*HcIaoYP~iC~&!QOXgV5z1AZ)s#B;hEA2}Mes^*(x`F7sk?p(ud8ZDW0Iv?8RE7we5)G5u(2>McNw&{pggn2U>6zOE!mp(aZ_7;sXfv=i`b|hCO{9?L#miwW5-1YUST<{ts7Vfr}0M`rq)`WmQ#rC3h|AZ zAWa7uQ0BEoiH`X4^79Y)6?jz~+OjcI^FZdztNK4tSz~qgu%Q)X0viUZKVD^?#Ye?8 z9l*P-qN0gcig9Eo)e97gk~UXIQ51s2d2d2bhcT+$Kb~4Q?tm5I3=z^@c3Rtf1S@4v z0MlyhRg(~e8smr9<&l=PFHf_c`5+JCCZrDabHFJ5rGkR@8@$G%&75ruZs*Ubv ziXb`(x@W8@aiIwXU3^#w>-JP5eBx1Ze0*!8Bf+~4rVL3yRV#_(QqZjQ=uCD8K*79% zI3^)2(89REa5jzz(oMBRvs@&J0Jov-#*G!Z5A16XH2{ZuEhs0T9GIzm(O{%7+L-vA zrM%i69=!el5zb zc&M;D=KS|xE=DnzX|FdoFCd;1jcAQD7x{!Zrts;DVnaiPc0C${uy{SON;nd4su^fbc4)-W?3T)?~IG+d3`Pai2oA{m*7uS(a!oxMsC}VVz}rq)O(Rns*j$pLYtvSgEEVPB-dO@7>gMIWXhuD=3p`6P?%b9G)U3Q-``b@fq4;_V+zB;4-aH9Wn(7oLE>P zEJH96b8ZI4-*R+RlIT%XeTuAe2b_7#ha^$B*O+#oc-*42N!5$G+a$7*u<`+)8(T7y zZPIE3n%?%q4utI1cP7z5^((AX;-&fGZ`SvF5$-U!37$D!)BVw~N_aesA^#s=*BwZ8 z+x{aYrKk|HqEtviLUxHHLb69>uZ&}5m9)r8l8%+^kz~(OHrex7A$wFt9qV`98a&U_ z`+NU*UKP%F-1l`~<1^Y+TtCjlg-pU&LBGffkF*hn0iIJo6Ft`FPdsOQr-=LnchOvs zFOyjB;B|Y}YG`rt)@A}~D`w3<=vQx-gXnel#g{8~ITTlqG;jO;Og8l&Jvo42U>q%z z+e4+mjsKIRQdDwAz2yMD0Bwk{nOLnqjLNQp!(`w z2^FjAw8v4kLsx8k&i;*3oT`~Bhb1_sDrK2nQNE+y4fv`$7hZwXYEWS20v7|`-7D~e z$k-G*K+}yd=Df^S(hVSDvr~snnyaVs8H=Rp3gcMSZd2@g(l&Tk_iV$+NiVdk7qee@9J&Z@cIm4NVCRBOPG=ZBK3xk)o6D6we zn85jYEE&>y@MZeC({W2};K-n3Bm`D|Ef@a@)801H05wtS8MKV3a%Bq3C zfud4@phqoe^^%~_lin)*@s`9Nf+=!Kmw;)2jM&M!er4%eEK!am85Tir+I4@?xvm}A zv_v)*i+JfF6wUS6aMM8}G}wQ&CY&-nc?U45Y{f7wo-k|P);%9i*V1N_Nz#0X=ZFgJjVaNAPM>L@>o#c-$PJ)}*WS<{)&3qJ$5Vqe9 zbnzAT!a0bX*?wpw3z?rY1388(ry>5@A#*V2i)FIF%L#>pK0JLsjRjny)*Q}yDU+a^MbNc!@bzR7@dxdQi6oaSmya z;7U17H);hrJ5m+I7uCL907fcgp~|sNUp}2QZDQ+$h9GF+oz&DLHvmNu4S&Rez(D~0 z3PMBb$ziTdRCuWGQY75S?afbXcf%&cPM8{{^`;$0_$5#i5~~q~Rm6otIFf}q@S=BtM1`{n*Fs9Jaxivi6k0!2S$aWb@v=+R-11zKlj=*xdsh>ID8;Bk z?D2qFVtT2#j8cY~NJeti|Ks;=zN$+YV`F2CF-Etqf_1l|QSrAQqQ)nM3zi~go`b8m z#K1!HC1H7Fv^scy8z?H1c85k%H-ziVeWv`?gN-JdyUz?_sfn5Qbdss5sp$liHzR~L z*68dr;7^k*kPcwd8IoEy7`W@ZxIeBG^`v2nE-lWdRRHLFzp!_qT$+bNwJ~8J43udU zf(L!7Ivl`&r2Ac9$X>p4NY&_Wi~8Z+jAu-U#({)+fmLf}I8NUR>jw!&{#LJMBzPYb z9&TP>uYJ{;Oh)#H730NuH$dU-T!RymPGEaNe0@K%V_{u}RPV*Jsj<54bS6#n*IGsK zqpXM$k|9W*xs7m&ZjN1?D!C}&OgCce52G?3lFYjdb5PQlbB2@3e+-0)KVsL>DwzLT z!W0+8t%E?3yeQ+IPW-sMZll(V7(ek^A}2QS+JsJuf1d<8(BkPW?S=66vh49@b8Peg zar>P5y|y8b+!YUjz@WopKd^_mN|IxTvmaL%nfpZ=+?6wX(%9L-pO8jSBc9A;0ZrK# zloq|P3o|UDzzy$y{e@n|<`avw#?M($kqcG336cbYHP&$CO2vVvsmstDq|SQX&DR1y z)hy)YknF|)rg_Ny73p*2KVYq?ixAN?s(pIdfRZ%Fyg~PNE*}&^4dLbh?p1BZt`?8h zF@n!P5Ejez;lqb=g{f~X+u5HpgLKoEy1WmyNv~fwIVqj(AEU+#8iB+J_S#D(v`M{) zs5$^;0Gixoq}d}wLu{i*Xg9++fA4kigFq~_*5lq|rQlr_&hyU@cmL=s=omNiR6N=9 zOx{#RyR60wD9(v*<;ZJCBaP(S8$DfD;`E)!-#||HA?VpNx-pwi`Gxft)(wV9$g{T* z_JGDM1-3}^SsXRYG)@std(q;g=Hr*v{nG9`yb`fFQw%e8erloMqU^>O=jrv2(GfP1 zjS5;r2FE{OCE|$YPNdn}tT+>k$g!yy$YaoH@@#Dd&=A$yjy+VCM|pI0J>std+Rv_c z*S;tLV(65leomz1;r1n8@6~*l6t_N2en!8NhFJNpj7%k<61y77zPCV9Q#F;LEAy+Y1llI`# zGNV3`+LPz=g?}#P?G%&%`@JyO%bn@+WpT(!)b}g@iG8H@x=?&ekG9>9b4$vqm$9T? zZEr~KO^6c9GOl*K)*U#P0fnpcpr3#lCt>DXA9S@5idQE8nmW-%V#1N*E8ifphJebn zT2L1pP^g+z($FyDOc!{0dVa|?amzMpAdh0doF&NwBhb4E5&H(jo$WWtIsBtwTwgF} zxdP?}77(ok40vdX5_NMK0US<7MrH`(Pl>hF;K=1zBkJsgMM8%4?`I1U&$<`O)_RYY zldy^l>1`(_B%HYQi0*94N-*xEFUaj2q(Y4gq-gOK&VKrl$3Q>TL}0oX^uhxe?EH6- zlo4pNcIY+^d}6@qVKc3)R6NHJ_;}wSUix;NkU?HZCo@0Jz3NbCrN8?et3melk{sx* zRRMI$Pk%H|lwuS{pf$rV!F9apWX9lR*{JB+U-5;!bJPX~1YcngKyPm5NAM8YV%47> z+(|F;nv8IbDtGva<`5!t;&57dFeb2U92HbHzF`gMgVEp<%Pk12-JN5-`O@7XOH-b3&YR@_5v9c+|dPgL0${7W>=R8dNq-)E` z{_NGJ?V~%RyR+Q{GH*=9WqO-!d5qFwH7ck1)~my4+5n-l%D`X52p8Z6?%#CD=jp80 znj=>YYgf~_79V%VHkO*FJfVDpD|WOBs{TYS{YqP^)`<5(yG|l3e_LoYSAj#%yW{2s z38z!kR8-hNQ-Ci!g<7Z}{}e;=Dw}dQK=+oROU&<+QXy3;X>BNT>Y-uROve7?UU6IC zy3mI=(Vvg`VF6sQ-n}a~t)ZGkqww;Wn-$scI3{MoNa(W0_AUkPAsh&Ao~b|CUwRJR<@CMgb%u5M{-D5}AIFNM_%NOJ$nx0+>ltbF+xH z@CO!8&m5w;&y&E{K&2Tc6d1w4!|Wi-@qnIWOlG$EY0=DYi?N+QJbcZfLJF={7cWZh zcLM{iXA#|e7R@it?{18b(zba^eA)72GDql>C)L3UqNb0p3ggn?he-v(p4A@{(SJu| zP?=RWMWbyWsDt{^8Hg&ZRYBvHBt?(7(N91_xchFYK@$NkH`=^OX( z*K47EWIbB(^|g?>2J~RKxS7UoY2>ucNIxvUBv!d|QN{_Is$lGF`@%Fq!gzW|Ywcvp zB)8k#YesV`{sN4U@P+=s3G&vs=xr-oy8Nj9ux+XHcg=)&pSnAb!>>TvD*AG^-_&x< z<4Yo4Qtp@uE!9KVeD~<%G$F>{VWlUHLF;69ad?Fb9|rHT&nnxHKV9Toptf%2JWjN2 z_kq*>hItP7*XHrF=_1REV8mQI{^RRqkE~< z>O=kH8GTHTsu(VgUvwld z(tYLH^Z9XJ@XSo@yD8N)XC(Z@>Wyv0pROvHQ$O#6F} zY1`I*-=iKq-Z|3szq@FZwzIMw?Emj|_AZtYePe3+%39PY}`*qboNF9Q6AQ-Cf8sPX_%+vZ| zdseQ;E4q1TuJLO3_JzrPU9HD`;I7D5pLZ|%+?vrLqR`>ye{E#>TK1#h_ClkT@S^iK zk}w6B40n%s1?J9t2Xn0c1i$ZU+5&*o-p(9>w|`TWc4lTKXkZ1~$zw6Rg6%Qr``BKH zDQSLXoAM3o^MjHKKDGU1K?P=IK1J)>Gq*+4;miv;B_)~WG<6Q)d#4*a)H`*p+&yT} z)eU>+E$Fw`SFe5@Uv$KzcRxSrUtT}$x-Z@=$DC%uy!Wh&hw+C?73K@tS@6v*Up_4? z2@9kZ3`rzgKUTc__!r^9Jn@;Z1?6QJFtCUz!?DHb*C(PAr+_GkHm9 zEH+?bEHnu~4ww&G!dd3=OnQsZAiJau#Iay#*|#l=iL}i-YNaRlkmgMATPJLZcc(~g z_n6l#z)YRp3eZTvG@oN~o0jIyOfF$4GHNlez{?xI+~Jtn5p+mSYe&6CM)RT|-aQ`E zyyEe0JG=K#OaB;Pj&RHZ_&4UEp`q;1q~4((T7R+_z-d>_a;~*ESojFJIzf6W)s_XV z22?R~WWinJSoaCBP-OxkM)JTkNfEH6+mY^0)wEj%pP>00*1?oxod-WCr}5&Oc-nRu zZX=wDJ{6l@W_71~ez^f&_N(-f{ErhQx((*_HUqXRBK)pgtqu;8c+raK+9^DNa<2K2 zp6p_UwxO#e>pz!qWDsqwaZquT>5k% zkIz(Qn77FSo6FbWunMoMbqW*n#EdB{#PL*}qOPp2)WQ7B1!tQmRN-Y$ys=SoGRZ@HR_)Jhl`wPo1 z|JC9NV_yyHevQjq^UoQQz<%VUiS2fdOu`AlE4m6jW&;toS{hspih5hka}?#%b?1c2 zQ3NmkNJ{gxaY8!hu>bwfMK^L69bL$y+9y!B$GdCv(fgR;S7rLx^IG3^^3V0EiB&YX zQ747D9iM4A9h1>KamS`z7w_z;8BDI8f$nbLu!z7Nvr8o<&F!IGk*yPsbS_*J<3iQ7 zm(pqHc}o=K#TJ`B+Tb9JkBu~EMOs}~jqDuxddaV>da1x?a?aJuMu1>qq!9n?vvlS) zu9A zORR2@`;zz#jTh~luzk6gG< zd*%|03!iSkFb~9$e1@h5-zF{k^rR+cry%)EMAB=s3Up zaz|y5*ZsJl+g-tIyM;m_l_dWICyH&-SNM{h?shwP;t6i%He_f5-%lxL!D2Yja|wiZ z2%ZC+lH~|4jY+8&$iVzW-rcN%bSYfs!&3Go&^vve6e;`Mw)&{P^`4x#`5qW{$hV*p@%ESfRb0hkW8W$PepV1I3l`i=0~}6@1e-3M&Ce7M#^|Q$sB8rIqYG zRsx}H@JC7bZFg)6@^%bh>}YcO`Y7Ss*x~O#85#M(U*~m)@xyPQcCSx?f9Z?=5)qIU z9Ui(pr{c!v1)t-uQwlrsoTDk~7`!nvL$>2vw{l=GGq+fAjFCHt-%Z_jjMh7}T&itz z2}@NnQBkdJTT)pAa4#sg+>NXDdVc}s6uW}n?9xOA&!}uWjd?f%c9!$jpy`@ zSs$InfPz-JG6tC*53)CXp0_C|j%)F7@r{U_!=LM8<*{>}WrPQ`stM3=+?}xQI_;F& z$@TyS-kkFb7h>DB@obDmZ(HCz?i_oX*R#4LY-Hs>`84}AAKWVk54vgeq|qCL6{-zS zV)Fwa*Bu^fj&nGvA@D4G{lUBX0>R<@N%-0BpU-I(3lFVbNEEOQ9*O;*?+^|weAhaH z{%!G_whcT!c)}uL@OBr$?SQhVxh+*Xw@2#E9kOxNON{GiQ=58maZ+WX#euVpFs-&^I9r$KN;rSNja~_j?u+HaK@ZbPJx6eup(1OGH z6KToOAaXd8Kw9)DWYN)`JZIuA4j7lb?vZngorwtZMc+<}9Fup_@g4bORdm3r{na20 z$mtFQ*T+AoCp{`3h}STBIVK+(=xzk>PphpiY$c_zgcWBse9zwk@HL+S6Y$Ts z@{bJy?%29Bun}@Hgu_yMzo)c|MQead^JtbQy&t@&B=}*=pRaVS{*H}n>fmjgf^XcK z@YnJyH>2SbZ$`qaaWpkqxWQh3O6Xyn&XBhm{#%!j#D zhjWL{cNKtBm^($dA0IYe>k6dlfgarJ8Em*;G2gPP@V&hs!@37i+8uU0x1X@P99{=1 zYC)!ea-S8F9@KIk4&i6??zUv2BTsu;Ie-zttbXzLkO2Vla7t#qEs?_34&eRrl}C^1IWHI(cyQK_meKQGC+>(nXR0q2}fyCm?)K$b>a5b6j)HpsWb6H zn8_nZ*6Ivj0R~oZ*l809*v6ze-HVnc^6&~z{{0oY-t6rg8%Z5F%&HE8dVu7Lz2t=t z^LLNimoyeU102esiz9}i4WsfIoEqtb)`E@moMYw>#G9GgacB2u*KRI+{xWKWp zz8mj58l}3IA5whTBWpYv(XMgrpJ!>R1)&!0bs1aeyj zejtKgo_pUr?f%h=`!%59NpJz1%B9krpXDx~0fpcl+1ySMzGZa}j8J^Je*5ufE5j;N zn5ns%(#grmS2Qo@x#O@&!gRu^1<~BRTj$4!pK1CNJt)7l^~S)n@QQrMcvp7PlqV-8 z?ZN(NNHtniYyTFr`sl9f*3WGjjF90lj^**IDBEQ@zQ}V+VLEM7>i61DbgFACODdOp za1OV}tgYE(+x6iy`bNgXYVCu#RNCkl8JVs<)Ts`7D^PJvb3=V{%@`ALqQENIV;~*X znRsa~TwZ0p(_|NvqnXMtI)&Ut+u%I6gTk^P#6YC6w-42+)wrrfN3gI61W};YBkOHr ztKLl8I$=Q6I)mmKThTekDy9Vis5zbH@7n4uM4l}Zhh)zYD>@H}W={fSDL1*WAYpL% zw#&qia~^5Mcr#Y!7RBa?0Q`)f!-`GhwozjOqsVR0Q9nF6!aOiL|4abK|F|oxNVma2 z1UKR9{$v0u&Xtpc06sd2bJ*#%SShwVuzNU2?sy_?_OxB*;tq^%%{ym}6~}^+`zF0F z)Ka-{w(BMHj;p~T9y!+*L4vw^#(hzEaEt;P7>OZPWydq2WI{OKFT z$Sf#1cvPitaFiy~sAR&$s;y61ZQF~#dR?ayk*96$I=Q2y4CqQ;ofQs8x zx3dtoJOr;4Xcw5Ib)%{m+p~CNeK&-BJXY8H;xzn|Fgq+`<3N}CHhSW$G2?qKQntA> zLxcu7t|^*7Qks(c)*tt{(~Tvy94LFI)h4^t^Q^v&JJP8>n)m5_(czF*qywp%Sg2#n zbm@=EX~#&oYxuAS*iOet)wFKtKm2@s-mZKY)rHXTzCILAJp}dB+&Z!{UzZf(q57RT z6<@o)Ha?>j`aJiuA73X)O3lc-f`|_OYz#O4^)$EAD=wrA; zC*5z-2F8mb50pPcWt_Lm1~p4)>YxP1t+=F|hkweiJ8GBX@4(J$ezeu<8*P%FNvqW`Oiv@%q ziq7e;MphOawlgEqexv?*=X5 z&KrtIc_g5c5PvAA*Z#^{oGb_L#lx?682kmz@rf%c^KSh6f_rQ@(SZdv+}KXq-;GRh zW(*;e(=qNMc&_}rj|SjZ&PI~`)#XH-Ssm~f>@^Wa&wqBWNf-CnQZQ5O_VRf*1#pow(a}zm z6xsL13AcBU=Wx75?6!6t*VO31E8pErg@zWh4U>`|RY!ythu?RFA=cMHrnL@Lu}f)Z zb9-dvUENXvzmEp!DO$ofWYts|C2@Pwp<08qMc5Gw>2?!{R^}_+M_zdudAX(nvzY?}Tp2MWfVKF@i zDECS6zZL~4GOOB8>GD#qz1j<)L0j%-v{otou1RNo@#4pmEwvS3+#zp&_&aE-RznxH z==8;_=1nJtLEK^p^u}0nnq$uG7;8xkz7b5e4h<<)_X6hnebK4Uz!)OO)YeJYKWpCb z5!>jxdV0XCT{70ad=ys1Pq2vRZeq+#FBhl+?@D@ZQ?T3d@S*d^OQoa^3hc=6i4fom zFnQSno~vI$@Ly;$hEA)+Gd>%qJQEP8tX z0?VE;55U;%B@6(bw8_7@GiP+Ph(J00id0r@?Zu;>0= zBnOf)7XCG3RNHfex#*ld`fh&nL&ElI8JJu**aBdxJW?raNKSN-$SkrTA2W5##WEx^ zlAD&6Rzhw<{)~{av)&U-QPs7D$<8Ji9>?Zz9X-lpv@0zo#iHRLIM%~FE*9EhF&;k~ z=^cAdgRtn0dUA)dqzL2ro5>^E^?3`=)pz`fM;o)3(lx-rtd#7gCD?f7cZvBfW`SN@ z6d4c*>vle6?6rRE1CQw<_^GGmebzY2EjHKFpxneJQj!@v>=^O}_e3erG4+exq>U_j zo#4oGRs`UH5+SF;BeWJPe0A<=Q=G)0c*pm*+nCrc9$4!MR;0S=IGrzDT~kvc?C>&H zMn@-t()MFj6_3$}9_U@7%+3ghu+P4XB0|vzViITiTClODg1uXa>2~khn|J%>-pX2U6w-M#kk5Mmw!qR`OY!0+{1&qj2`vC23TI+NX z1@*#%Q6ov9L0t*{yuRWlQt}^lL$z%0Qy!VW1{LvIQA|YxC>~qy3knM}t?f;lLapyx z6)@P}_sVt}lE+|hlBoi=rK=z)o?~%0CFfr%9OwdvF%#0v=qKP@j%TCHr2V>=?Dku9 ziMzI|g{5i>ylj^NZ68Xvy5BN!|6HR1lkk#)S4j1ie{V~`f0I3iOdoKYx3U|HTpdl@ zQo@qE)*j}QIdEF__3PJW zM$B#iF&Wf7K*g3)3gkmS8@&|_m_XNnGThTwgBWv=qM8bV-O(EML0fkReqoA(?)}f} z=HrZt+&bzf=~AYc@FYB(142AikB4|y>vf> zUE~WI3ji1F5`?y>B2^6+oK^aB>@Hd4m!kg@r`0aN5pIl zOkcUDsn%LRr1ms2xx8$1>Cz);hV*4=0N+l+!^ z`T)`_=irb9$^fEA%WIg?2Ne)fQBjpIttBNTkrXs^cFh|(77+yeHTZ5J{EQaG$$u^i zCMjgs9>ryHIssnXajUR2^lO*kJEyuc;wnWJamr;4fHfbSLEgBK|Bx^eY3+Rq_@n2J zz0MLVYs1_gfx4?-L(?onA5D;<*()rSrvuonpxG6qss~5PYv{o@fB7aT-o!|~^T1yM zBeNuMVkvKBY&iFBAq*rPHK>}enez4BImj*|((}EsWE}^Pj&x|pBfhw63mFvDf;PCF{l3ZqDrXBy;090f_ZRyQ?b;IVCIdXl&Z|s7B$=ggjQrAVX&jX2VKo zJOexvcRIo>1XOuMnxd7b1O=!WzA1dgJ{#i}L;iQDC(*kdY`|jEIIHwd^VMc2lAqh} z-hP5cPytheXzLen&B!Q@QgQjyL+&#(U=VUR48-d%8~4W@Tv-ByKQ$xbPMTI^fFel*ee?&j1oqwj@uxcvlr_p1y5WRJ_mj=0Xv3+S~naOrhEa|dt$ zajdGTvGW+TSYNUMo;p(Lz(Y+)h>9w8GSj?3)~DobLUS3+uKpRM;g6mb#6gf5d~p+Z z{`WsRT>$cJJmzltgGPF0I0TJaQWTCg(zCt+G`Jf=*XsJ+xwdj>7H}Um2nVDx2TV}I z$^e#CI^W&NJuq5H(afoT^L6l%@T1NLZn+9aAw91phBeA55+WJd-mQz-{bs}doz)%y=F{E88fGk6JS*uX-HS`cB2qFItBBwtk z14?AR@k)P3Oo*3?z=uzFHu3)ZK^E@=R9sEZ=ld}L#5$)A1eeQls;Wq%RxIy4v{dJ287t1MuFW z>y0c@J+xmxbfA4`k9~a#K7!)B*UHi&5d9}^9c$1lAi@3O@WvOdqv*$>VDnC*mQ8=oUF7@kBt zBPTNAW8gChz}ePtOvjP@hD83t2&leguMoE-3_yXzZ5fm)o*;028XmWuL6CiUloPp9c<~F_yoZC>ae~A2RFd z_JbsB5SpA^+6D;47zy)dj>KSga2%PzL1`lkeLlZ-Is|C#Kjak?a}Z726=ea^hrErP z6IIOq!XgFIl0K>&Ytsyw|GmjhBcWT`3d4!(Fe&~Dv5Bq>nAO24DV&2dfFpVF9OO)^ z%HKK}aM}!qT&)&^9;T3HtGdJdVTNY{#B-k$!6mLGj8fe?4jA-U!27slnj}eX@rvD> zke2oYkma-rgxj?SN1c-Z4JB***7L9H^z@g@#f0DQEM-z z<^F9ap>rm5d$g~l1d5)@zO8coa#UcDwKM-ncYZCgxNZ-97W3wKCe*UNQBb<#Zg^LLr+Cil>gz%Pv0lK%XHOc=( z`}we+M->!1i(QOg&Wi|{FBCd|^S$QKhQStTcY|KqL1$;@)%`?Q@T%gGyJo?Rr8RM_ zmiOahpaI}=3@!}4gPDRwt@nYXF~PG^v2^wzIU;Yks~oPFhq}S80eSny#-0WG(p5Vt zorIGqBm)L#_MQ4|xd3~UbvTm~Bk@6y;3&3jy1ef!!V_$jH6B=4YTW zQi!0~y-ZuE@EQp2I%j$s351-1qPCb(^B_%ndnIaILGaR~ixZ`ciHbs2y;jeSkpz$D z6)#XLqvOq@p`np;$g0m%&tY)H-6$t_{$JPX1J_|axh-j9k;v$IB_$nG2VQ0ase?}= zye;%-><;Qs=KJQJg$>%5q9wzU)2$2E-raK@1!XxUPE_q7oKpxlQA4ip@u>e z>$#N$VBFP!OLfFP5_iVf-si7CVFqcwztlH0Hg5OEaix|@Lf7ogdK!3f3Rna@dJTL?Y7XO+=RR`x!nZ98pGDj#`X4rJ0_zkN&PtUn1?ewHvKBt$yF4G4!%q*G^_ zp$yixTe)U>i2AqD#HIy{4m@<_1=4aA|Bh?lmG!_!`75xRYrv`GY@}$kz^BoRI6CHe zmu|qCUyL}@c|>_@n+tE?DF$VI{pj|ZMN2oN0h~~DN>uu); zB50gIRC5@#+_onz9S?H;jRmj+JPuB4;71XSRzKYKb=dewMNqC4;NkmO9IfcG-hYrJ zWqVT!{Uk$xk}GLxal+ZQLs+#)mGj7v05qO!|IMMIbKk!`9Voul1$5K;0`K}+h{d`?d2P&O0v;rDQJmVg5TYY zss^f|N{_+T-=ixYITt1H4taPr>CN94^-?U*$^2ibTR6n)qCDM%-|pYPAG%jA#Ako{ zB5r|YXd)CGR!fQI!H(&6!)|8*M%LW$(<5EFgh;{^R65&^;z0!UF|>J?%$ZfXqdY~= zot2sv;;a;2glWhN905OnQGWzM*rX~-(hViK)s(ZWy zK$rP@ra{FcTbQaIq9J+V_plTkf@7i3k?1a-NGliuxPq^oyanGW!u%QjAsyGxM%XM7 zR#sL+0*D4NnWy3WEcGCS(m5CikaxMxoKP+(7Bwlw{*S_T6?q${ubkU-4?nLw_xK5z zRs4WrALZHQwNHhXvg<1mNwA=J%0%GRucEBckL18s0%;T%^xyPkx{G*0MNkP?u&aY> zKtCyW61PAp~kJkR&{D zD#`10sc%)gwj=hr^XIS(E}zsxFH3 zY|n2n9CY*JICA8K)hB4xc;*m;5RcLFu8F$Ptnl90n34)Qv%lksJw4Z;g|pivbr7P6`hxx3;7yQ4FuN5aWL{7YT|anN zp^&(rEg^6bXZ9@xf#RX7CHN~1N-i(tAR^34MLqHq4Lob?oZbihnKHqL2E<;cA#m)2 z5k)MlLH%STQm~JTineAf>#k21wAUFiBGem)^*_E^L$x)>H$pd-}N0&T}UTw*$ZY&!b4EC zB!BamKl~7%i6^}4*=vGuB!lpcMOETS~~SX1-xM(cm$?5{A)0uPY7+5%ONzwe2%Gxx@eFT-wAar&iuFP(l% zO1#d0OGkHE9Wjex_}w2rq7-=+^;wr!5U&NO@txftl(pZHZp38;s9FtyUa*~4n&gvj zDG1YEhf+`ii`2gI9cQL%rAMI;$GLr!+}7or<4POoS&soX?xm<2Vki8*AZXMnavi+c zH~c|F>Q{96E)M~)Z(;xZhPumlRXsQ}U&ACN3Lkc~DW~A^J4zWf2#4DX%o!LuP+_PZ zkahj~by?8B{j%6?RUm%}1Xa%GoHK?zvmyB^w>l`|V?7uFmH|V#9ehN$i0sRav4=D~ z2zhfC;dlgDA3CK8;IkvOLQ??Z4vmbo<7&5pjeQ4=8VI8`1n--xqK8=^#Y*shqfQ1z zf81lWBbnqIsq!Xnk0%!z0@3;_r1#m!$zXZb`PNS7qM~h<0J1h6vPY^dI@;V4W)9`P zpSq;MAs({t;)K54=f-zdqE0+u`1cQ=LQzy%DiX-P%x@LMCf^e!UXI*PaeCKQseBlS zT>td`{`QlSJ_A0bz>qS8K3mMl$s&n^THS@tnHe{uph>T$@y0~|`8Ps=1@DR59_P1s z<*yHH0f9@BF(0WuEp*xf$EF}h z-$gp=iD!LmPoi=>b1Fn^)%!U%@ttaC7^2#xYRF?-koI z+Dr*Jo_ZRy$5D!%R?gUo%oE zPK-{iy)9OD?-=xbJ1(dF>^ZW{@(~qXKI;+scLh-9032LUuQG{mWi3d||X{R4hLo9|o@OeQPJweGTEd$AK`uL(* z1{4c{kUX?Lj<2|T3VVGXWFlwHI$J_K2_auB9G$_eEOZ)2(kf6!vGjYF0$$y(y-enr zXrrXDEjS9VQndM<^}oKtY%|)x!dhDl3D7ff*Oh!2^l;<%VHKxfbCqX3tDn2{mjV8I zJRpSI5~SV;4HWmHOJT?o`{vD?dg}Qd9xIP$L=iCQ zaU6%FRqocuAjfIxH@kKSaL$6tcMY@*{D}Di;^2;oehfU|Nb}s~^>jOE3rRyaj_FMi zQlo%U!$5T#{RInxqUiG;_88NGRH*xzS@Q4?e zdE>BT?n>de`n@aBf~)|P;J#OHn8L-uk^Fhy92j5V;Je%Slq5H)8bt&BF%Xm;6p|Yc zCW_h4qS?XukS)lnSFT*gJxx_O z-XO+t?AXDs7{&=mX78IYP;VGJ{RzwKH=_bpR}~w>N$54~Tkq>lv12D>2}4ka2?)u{$|i0%!a#csy0R0K z<)h?YCkTm&iOZdnFv2hcyS}>oql2YC$or=y}`=-usrQO8ER!mvg5c-gEN&?0{TU}@()XgF5Y*7B{2f-iR7_fHQAB$^_}4NtN!?sNNhzP~;y4bVb+-Q0s$f!nrY<71meI$pq;@bjpzuYc0gqB1yB@}th0)Wo*qy^0?6 z$KnK3mVXawcvA29u~1Mn*v!Hi?icys!Gl*P;3VgjERB9v>_Li?*_SOvEzT_I1$%{F z!02rA-2PoeU0d6U8|NzWH=gf5zk=1jd2d|foQ0-EH5^Ri79r=eE1cM02@+9|g0mQQ z>-&p(kl3SEGwoXJ06%D7O|&M{=wI6v_H@UY+0w0FK_^z!qyRZhJ%=NMC;cw@K}B8E z#~~%3@F!`h>jG7_vU)2}0yGl@4;&s=45ZnI*xAq9+S!>~9hYSEG9mf}qsc|0QGtkmKf3yosJ#7 z$w(UGq~o;Kixb#$r_qFJ32|fv!LGRQ>ItetZ%VI+Y99ty-yL)>d_4J=<)ljG2wk*D zjO@9&xdkqmgYw7RWGAm-n2S_O?|#h^(l zI!?~m;%V^Bn%#>b{$J@UQ4Dmd8HpK_H*zUvz4PM6#XTqxC85?BCH4A5_Sd+wzi5hv zimJ+c``*~3r0OGSaA5GC69q>F06);rP|2U$&ZVfPb_Aq>5_roIV+?lG9v9rs`ZYp2 z(Y8+9e0~W4L|C?|0QuSFqT^_T*SEB_-Nfh5N6m0MP-DoGw`oXA`v8+%Y!U;wRZf^z zO4N)66B6oUtmw#UD*syVK(jXrUdJ|`vCTC*2O&z1AwZCDC1rAtbNZrw9CI)1m%*ZK zg*hwGEUp3gnbp2HULdWP3k~}64uPe?tj=4N#|?x+92q{xCvtw($VJ|a!nfs)dx03{ zgI+C_l6f!)h1DZa69iM5?F4lR8YGD zXhM3}MY#EF&DuJHcN9r)E@VaY@Iiio*%wPG5JOmY zw8RsDN4BU*7#M=dfIO3AT5<&-mMSh<(|vtJ7P7flxUnO|PeR8;A+D%S?PnS#a{@J) zWnb~|JRhP|1I1mHs}q-(`{FXQCnl%<@piISAd3}WXPzIye&9c`brObiY@lmakn`Z> zvsjA#V(x`E44~Z!qSckJ^vi*@0xdRFG{FgOIV?cpYn(ht}I4Fcp*R3k(8 zwB4>?)uf?lArdm_CrkPg6NGe!+ruOHOVb2ch*ncPcyBKx2rwUj?k$UOyTNsk2$QHm zI;=ttuT~s>eH_SiKfmK@l+RcN@fL)9*vI5txZlcz&WZgYV=q~xc~UR_32Dw4hY zy4au4n?opcJEQlAT0s_ATA@+Z(W7U&t8#>&ykpqg(02z!8&9|Ct~{D6k1L&!kfLv- zt!!>?_EWrhk`H^Q2(I~XZ5j)PU2~?l=#YSbfMIBUAOG3(>3k0eEl>DXFKIN>{5>kX z*M*_P@*)A%#_D8?E`^|U&X@*(MW8^2zuPf~LgwZDyIYFFp#6901=%g`l=OUaX3m;vf6)L*(RI+uWb; z6B_W|>q{RYnFZay_T|jgdKf#&02t~e^s`vnQ5~XkOk(Erocb-RhcY zzh;q$^o{zrLHykRdI@Pf0XY_X3a|?x?SE~?B?1Sww_RmpMf`4q1-3j4Gp$zAp4dbNmxjka$#)))2SlmBOz=dr5>x_ zm;`}ka=Uz4Z0(!aN&R=;v9I-Bk)AymH6um{c~{9qAAc!>X>))JScXZZ#brJLJGb|3 zu2{$b+HopWrj`RwtYI<+0-P*E*T_ZmCt`yyk>y4Bd<7L8>NM|rYa$#Ra<;a%zIp}q z@Be4MAA~g6PEKAgU$-k-Pj~tS39tmSfNkJ6Ds8Q(5wOB_d50q6mhJ3*Cdne^O8|;E0=ix<@7-P#5?&%jmYFdU3wX<>SXm^YAe^xs zFV1XAG^dpwZ9$$t5$RQOm#k>QH53xryL?Tv%b;d->&dzU=07i$a;JI5_)>K?2oLG@%R4`m)? zYB&7{=jo1Od%MW_o{eOwn5JR&9trjOr0LfX=6!Jla=b!73yaerF-Y2F+N{`b4WNMz zn)lR{-^B=u@+5Ch&WDRq#)GB8Y3RglMf0Ax=*8;l3#fU4Sj0oBe9zNZ=JE28%Z*T& z2TY`ak=QQAGoz(PZUHjrqp;)jf!8yzIV)itbsH3U#vR)5it^SvZQ)Pp%>Ymm!t=M-^fIYy7{tSxnl;} zqXI@j>n}#g^=3kx0%vETvt7eM=&z8w8oaJoO&87DI_bsiI@PWuP%a(0@u2_lmH0t) za>W)^sr}huzc!W)`1=-Yy(c<-?RUF^2u2kA`o+L-sRWrZno}*KgVD`=o4lJy#z+2?@Dhza?Fa?m@elL))B9W+XTyWTX}{{{SV zsId-LHK)Ri?vm3VrqQyI`1tz;;Kh75sOHKW+b?RY{9EH|JsNHNhe8KlffMVKf8RfI zA`u_1Snn-iV=2Vf^Dke$QiM?^n1>vd9S*R#jr3xCSJFU$6oiZ+ga|;}*EPuR_7@k$ zC;{4Z*L6^11slY11}nlcT6yqqPZ zqrt=gg`-fJzC)vfbmr%3P9%UoAcf2&f}(9l4+-9_Px$*0#cYcfL3jqqrbY0GOhr}o z0?c~9*uf03ajm|tE(8Lua6W?&>H(!d4=(3e$mtpp!0W!Y>Jc&!9~&F{*>!g9TY|u_ zGJl^}QTmhS2JUSQaeM*z^mQut$lsuYzxNE79j2ic4C$tI^ojEol!&Y?It4FdV=JL( zG&idAv%7Br0EeK9@P2KlW&sUe4cczzB-r3!R=iLP0MlqeCm4E(r}D)2r?L}6&Lf0e ze{Pv+W?Ul{Aab$wzx;Rn=dYcrrvULpM4)Zc^tzPC3y_;N@aAseC&0d#&$6o}W2yo9 zrs*L(z?GwG+*egq4fqVL z!%|+sylHj(d!@pIDTbr7KJd?yf*9}|k{v*x6uHApCje^84|zhTKqb5iz_TLG3wUry z8AhH0B+mgny*~6RaF{r}h_h4pDtmiFCB6{HSO`@Sb0f zq*Rws%iz1Y$7QZfdx_LZ5|#!#X6v~>Pm+|a02c8!Hh%sqP^$)GZ+!tO7mhe-cxBPJ z^6wGglMVy%Y1UVOesqS;yI(yZ?bx7y{#`ke?j!&=OuMsFdFf+lh+_7ghEB?jGTr{| zTfL@9VAKh<)}z;ss(*z*{n>O#HW5K^#y4O(Ki461J#+}$Xp2C{f*b5jLf*ZTtoryd z^r&*&`@EB}S`1IMKrZT%g^wtj1Vpm&K)xAO3@TVU z&ff>_GIWysTRU{)$*h0nbRM3V;{x%2s@Hz-qs}o8fZ9U_N=Y_uZUulS8$#bNBEkP) z%w8wh--cg4eUN6SGXqDDY_N&10^IXn?U58e&oaW2?;p4g-+6DBC<3UW^6|o1$-6ny zj{pAx`wJNS=U$zC3Qx>`ieg(0DmI2dnB#=YMOoQEz_1P~SRyYn5Ue|$%bzdF?BWG4 zyBZ`$#_eMjf{+ej?8}$u&=~a3^Z(mdvyb5u6sC4P_|H38MXi#O-M9q3U&y~U`&8cS ziQ1_y_u1P_l|c6&FE`?vSO3}X2@vSJsf@^hrVP{zi4K-xP|w^qEK@(gDl!(7)8pL()a7L!$U%@>^*DmaN8aYt?pF<*@YX_ zlS5$`Aq&G~BzU2usK^Y_v8>`QA@ZNj5ZfxRtBg{cwZZ`(`XOK5`g;=zd|G1Ae|SOi zZt6x4RYbRwKcfg5)H;keeQQLu-^bPq5}O~*f8SR<%!3`v19di?CpH)Rff<32xd4rn zepQs8uK|LFTu?vQThQAhK%X}w@kj(9FrW1OeoLadjtmZQYzLVXA3eC35G@h7>2RyZqdGVm;0nPtE)YzaYvH2VO zO*yfrh!=VfFb2kk@Zakw@$hhEc#Y&aDWc)slfFHZpIe`w{&oSHd~{Uf7E=Hy$c8}F zNZZWI%R8tlGO&=_xOA;-u);qSSV%;zco1Jx_SwZS{*XuUZ(@}j>rH$Jwi2s=0gQkD zY(Xt5@VpBKv^Kj5Jpv7Z_;Oypr4YI+n5(#6JFpEp!;eNM+q>YQo-G@~8@ssV`_l1W zfU1JB-K!on;htW02d8adw~)Pf0*gVnUSv^ga0ZP;Ksrw_jsNwR@7uL(s}7xn-!DWw z%98;TCV>Ax)YZ4x;J^MYIFw$2WG(G$li;QUCUD2&$B!#vs&{)Gmj>Cuxn34?6i6x2 ztdyem_Cv4^xEgl}tDzkBGej3aCV3rT{t=1zH_exlw-1y6?i1d$&BqpLmM@eYprdX- z(I!9lECEvhbCcVIGhY$|QvcsbL7ICAnr&R__)W!7X`DE)Twu90Jgv*d)KpakLa|V9 zl%9g7foe36823~^lsm3ltfk{N-}@ zHCfVi0KTIWPoYJI^8eop(`YYLgy?L_SMFWVTfxu2h73MR6t#kdmX4#rxs5U`$?*K? zg(AphSvz!qL1iJcp8CfrY@y{hdptBeoTqu#yJ#;wPR{MrB||}S7mZDj4EObhC<$5S zQi@F<@@FCaUQ%8|kflTvE=2^g{@JlkYEiklYNueptfK#GD#@7k955Zsl#rn;*>OV= ztE}TPb_nTP@p!@{RY>6M%A~PaFwA;f|Btlq4y3w$|1S?^G*OC@vMCxyWSoXdWmS@0 zR5p>3-DyWkq(MeQiG*a&N}>{xy&6;qkuCgQx2K#_eV)F5{Qi1QoX7iq-}iN2^L4#0 zTky#!rfhw$SAt_Fw28p0>)tuHs#swMhO>T4t;o;+bwL_zB(rfx{MKqZK?gJ|048SZ zwsBbR4;xIeChZ;jFr;}cPtm__|Fh(I$v81pWFPCjGrl8UB4c!)W2)TQ_d9m%@Z00Q z<+)3v<;;chJ0-FQOf+Vkg}>vnwa#Y<&ZPiUL= z{~g7@M;CyiQinBNPX;xfKyi^9) z;WuKCft;}%dinC@Mbe;=gK>jPaxnV}`K#Jb!kF94%bwlw1#rY5!YZ`ZbO62QA~@9E z-YOA-F#ki`Cw`VooJuS8rF8Zk4aTH<51QU7Id-v1=o#7N;&ukCrZ<7YD#4mY65N3_ zG#tcCDodZDf`VBiuP>q0%2@lYyIVnd9{L6vRaS^=#@V3+Wnkv+mUyxu_cc7+E9H+) z{$(Y6=NMitrOJySH^xm^!%6c(}jK(Pe`1vMAlxQn`; z2SJo)WY_^uz0&@DUNA%3)LM*<*ONmVZ04FtfzQ>IM;ytCp7nM`Ln;|>-lsjn*>;u! zs1t#nImwe6D#7MKn|=Bhe)gBc%>4#IQOxlbnKkhueAP?<6p`HA+G*T9Vj?1&oq6*S z4@(deFu9y60rovH%p0{-)95|cj+yB}=sc;SE_<5n3+8MM)JXPQ?=%bb25Q_?f0Dj$ zMlNJsBdw=&>#^2UD0|Y)Yae%>;V-MgUYd~djB|xG%fz}SP1a{1{ZR03&W!42wA^c# zcOQpp9n^!xDZBByU)FonV-R^&qcW|LJ;OlhEYmUebn4;pSw9o4M=2yI&cB2)zD>|t z7f3t<*m=`=@9#Gs!c@)BPAJ^XT6gftbSK+7X6s?3e*6KUTXrcje%a59iG;&pK8JN* zHcp|#e~pVFr4;UgMvY-{E=`Ml7l^n2u(3MB#ZI#j4Lp~?>#RKegdRv6ref2xk^-S9 zx4I&7u=I&uWDO>r2(04KCw zye}(FCQU*owWciA8lNWgzb?eTtK-B2Z|0h6|9la$!Q+s2f(R`6C^b-yD(CK?N6xUB zs^kWlZ6fDKI);Lewoa`@^XB0+oNm^R_@XV~HsgoR3SwfLyO}iJqHz?QB9ei^8kas6 zh17ltD*w*+^|^RlftqYR=gw9*%*|*#?0GUPYBt?r(kBeZJA+GI)~05vt^w? zba6n>lktq`x3ND|)`L8sst_&<&zkRKfFtIB-MW2c=usa~>%$J^+B&W`cSlolZ%^P2 z^z@IlbN>g??}R5Ia2Y;wQ%&R9xf3hReKr9P^ou~Pz4V^$szv9|mf{$#u&W<(HZ}ZI zvaEL(S?9d>5pM#t?7a8&oku8~3}EcOj3U$)_!OZ=@-7`q5z)W>m?dJZOJ`&z9yXyw zzLH_WIURDXv{-SoJQc9-7celbXV>uauP4pA=ql2XpE(8Ye+LpuF2yni#VCQ0`Nz6I zYZl#byI&bj$p8|%nbf8#=Zu{@@`*`k+Z8?%z8`JPY)`Ijf}npzlNhc1G_f0WnS{5Q zSkEW57WxycWZZRc_hN33m&L`h4DD%YY4>e>QM%)ECB-+hM(}_^qnF3%RC4-Xy(%hi z;lPlds3H66G&~ zmg9x$fw3?3EQhtrt0lk6vaAyE*^oDRvI<30e@)bYXfpGz*Os9%mAh(VDz3j`)wW8g zaE;c!_g=@noK?&zYV||Qw#~8Y?>@g3u`-H}{i3V7LwHu_RGn?>)~!~3^;N$(@Ra|T ztcu~$ijQwT4Ud{FWME{T#rIX2K{bBl#hw16iz!Da>zSETWRJHFeY&RT?o5~>2qZ0u z3%%4U0kp0dRjj^@#)*V3-^3-F%KT2^N0)GjHdtGx3>KCftoth=S^eVcU1ZsZlbM*auS@A zs~9b~>A$=$@W@!oR+;vV9py{v8dkes^5EXYZn+4ZnKev-6nA!O4Tg@w&&Y6Jb1YR& z0I9uj%~y?5WWj$3 zGcK0k;FGbIuaOZRMBG4S&Zu@|EGAn@j#iEh84p(6_xjrdDdd6i23vl8AnRK4KxbDZ z;4Gp>pgs*UC|X)tZhG#js)aS-AYfm94igMciax%_7`*!}=^TL;Ox-dEB|txn50|xf zx+F}uW52v4^DJ{q2+{3^$!#1H+gcDo=A)Y?7RkJLd-nDcO2jNCoPACk?2{3U+?Jh{amF9nmh)4W&Rz|Do%a#@0unbx^@wh)elyEXU zZdbc*t40&{`Lh7bI1SSxFg;ngF>Zc{^#j!}2=eFee#FVh%o&{v+x7wa^E41vN}gqy zKJHms(gGF()}UKPp2Z=ul8Uj4EIs$<7mBtQTC^A5ZMVwDS}uoGjW)--XU%owpf2Tt zCia?L$kJ}S5P!vsI3T)4S>1oxI_~w@x)m2=*G{}b1eFmUa_DZ5@CQ`~@>v3*$8D}% z#?I&8$)KUowE;+9A&^nzkJ<^LD zbt5Onm~61#I(y>B1rKwP3o@;^r>lLt9&PHT&{8jY96s_>A}CNbZ8@(o*WHWT5-{55 z@__DLR;Ns_o&ef4r9a+W641;2Pb=mLMWMHn7 z)SFQ_GxrW1a?o=JPr}XA)Whw?=$!48s%ii_VY+d_LPm$3dl1pw?e65aXa?lhcl}I7 zsZAN%W#|_0+uA6%$@N-hsYKg9zopCJZ(UjAVw-LW$`}*hWyz<}<8zPWmUUCW(oIJw z=h&E2?5d`WB5vAptbM$*U)HPlVIL}Bt6QUPn&cjt%#(a1hNUSr7a@v~%@NOH#s0JK zfu)~i>`?m4T7<}2?pn~Dr5YbFbUspbXq9_rj>I^}&ONG7gKCgG+cjir7J4AzQ@e!n z1eDbT?r~>7V7v;$(b+LV{4j#64BNmA9||vvK=CNfM=$aw2pgp_+2^G~>rPD1`&CZp z7RDovZBIDb@tf*$6~d24ryHX8irdn=CGv7b+H#geSzLb}qSA(wd$Wr2J!wUsu` zXJl1-3!Lq_IL~$~?Hc5M4q<}W;*p2*kNu_vC&UsTa=9nJb1r6}TMJoc{5ja4qM3Q% zkPDkq`{McYiZl_Hhr)M~yj{N}RT^1Dk=l0O@!2A~sTdxx#;ZT0QM+Xf37vCjDd4>4 zo6qu}ugVzBg;d7A-+$i*k3z?j57lf=68E7&*EQ7m(#4Cngdd>wI&Q=jdF;}%8kbrd zS&g~WqjLc;T#F4~gPu0Sr+d)|{u=(((Z1IT<8M;nM16i*9IvBI|dZ(>{*uoOruk>jkPtP!4~=7^E;lPp*ZyTk>WClc=eb>QLN=*x zEMRaDQ9^6t`0)c%iJm5{IM=!jM<{z)I89JysujB4hmwhQ^_SLl?a0FT;C^g$Sedl; z2t}I;eEzc?8j9M@T!<*nqqw~g>}#~Q`|W;GEukJ1=h1%Oy)6Q`{%j<(udFgtUkc(d z8yA#7&f?N36{nZan9MMJvF7G?ePjR&nd5Q=BXZ;~q9?dT*hs**u-|H9w_Xjz6jT)6 z4?#P#c%Vp??-LWRYtx0*?@#kb_q+yLm&|Lv0dGdG@#d7@7DT^R?v2DzGAN??PZ5QT zyW)%%qJVK8fwGh3=Eqmn?d%@dBrK<1W8eI^9XioqTd2HrK;=cGo9?XbFbi`Px-%4Y zx2kD61$;L?O%MAJ@1{Pt+RtvTp>8$SU3DPDrc`qnDt{p~%`3L4YO~BmsNh+9N+w6` zA3}LuK_cVJgOhp{nY3N{W6`dB$XrhiiDIH{weg(IkAn*fVf)qX`tQx+)8wLpICKem z6F9sFUl^NUmUUOGou~NpRAR23(iFwx2w0li-1uA2@xB}dBx)+d-i$VfW1_C7O_X9< zJ|AVz2m?tDFL3{ope@mgERaC>MgQ+9r|H~3-93HrEZ=-!0Hi+A64 zVcMHiu&&Oke*ztu&)l>l)f1GbR{yl4bRYc~MVo+=HG#@G3S{ik$r{qlUM4U2v2zrc$ z4MDn>CQ+@q3Z5PuhH9#qQe%dJd&}(AunMkD_yQIP6y9+&GQZJy%hNcp@hp$*{pUp~ zbq-svfn2gTI?C%E> z+Lxp774i|M@wqR7p0{drvRv+g?rT!2=P} z_jj6&{qPO2`uT50=BD^ujQ1`L+!?bbD+`q|Ouh77(4pSK$Sif7VtT5UYw7M;@F9JH zv={(SSQ$r+Sy8aIm6hrqXSFEB!3{of=LGV?j#me2x`X1Kc~(ItrMq!H;s!K0*aj5_ zmJI8fg$50(6kW+-C_FV?+f%N%(aUM$Pm}(uA!lUXi3Rp+(p(IYNz`CKr4{&Pg~;qN7vUk@Hc@wlB)|XWtoN80io8snTkD{fMf}y=avMkz5-IC zm^Zee+wFlv^YfnKIIkSw33n%3>k4>F7-gm!P41J<5)e*^gUG$B>Sfv&IOJTl_Y}b? za$BO$yJ(e~34HMA+2EG3aI+jHbPdfZg&})M>$ELRtY~NabLldh5xE~rHP|+>`+P1; zmhxFy@RUdyrOswsGvfnIJ{HeL@3E0CIECaMl*PNCKi>q}>P+}(&z%Hh;A{_;pIYFs zITJBOQiDs$+Nn>$o>i+Cr{BmVeWDgjrd3i^*+RM5TD~4F9|ck&9+k(dD!*sl9+a(j zEF+l~ZgY)Mk~?0d?c>Tkt7;Mz#D7bOMG|xQ0w1lbbgQIXlIK554QW<#V$nZ8d>woM_xcDB0Y>j!%hrt!=ZvlC z1M1JoM-TDRG+u?(hz%CPtuQgbKu#wy`N6ysK>o^!iHq~g&31)5bg#^_H|sOH!cLPg z4ci~+RfD?D!X>U8FM;068dBG7_f#$Lj)_g)l7k#}X5a8W#bcAGU*>E!;&Dce(NbCM zJzye-7TD*_uGY_d{+BmTClcofA^IaALpz_&_;^ zREX^A1SZ;>?z=;nTTEba+c-fVQ~Mc6b7G&?`0koRT{`!QqPsI`xQzXpJ>207oq99h zGH}Ovg!H9l^?^GYta!lmsQdv9P}?N8j(XnTop7T@pUCz+h?{kK%k3n!v{#)#ZZ3lT z)*nuUnf3q%NrC`m>$2AdO9=VrFd!3o4*8DsnkmL^Es<3i<?O(}#%EL>CoUDRj=S9}0zlI~QA4Vw^O3Etq z+Y2s23}=s6`u>Pkcm8F`oWZAs?L2ucCJe5knp#@38)3>nkRoo-Xn<@Zaid?p$d*?5 zX*nhYY2rgkDzvg+n~gN>R_O}*A2$iy5kWe^F>G2_JH&*!DL5A$jPK*0%-H%uU0tyg z^bdZ^1QrhnO!F>P6-HXL%U4eyv8$!Poh9hUjkMa?zwu(s{dBR>;;}*H7K6f;=fu5_ z{dPYMGW}|&gn(u|14e3CkfAf$Lygdh{DY2X5SC`|v61?l6_JAr@=`bW%)~K}53IW* z7HinXv9-N_>U$Ga`UE%@6F2*XO^dYnu6vtvD$WWl7()tGjzqe<(;W7@v3jCX$z6k6 zD55|`Fo||;;Y&-A4<7`{lLVl$j~}mpz2Xm+(P1b^kJ(P^@w@E5h8Z+UWFh#j_3U>%ao4S?649(;MajrLw~EP1L+K&i4+w zXU(bK%;(KGL$RmiFxahQq%LND%t9F7a%T%&cu%`iKh?;}#fV&4R1W?8_xLv`kJyMo zLN7q@$wz^KXJ@YY5^t#%5Lh1A7C^de@+VJS;J+e+1YBK6pl$#%^aH*e-Jkimz4!JZ zerhI1DlFl9T)BJ6ae%3b%|N4jW}EJMnrZlBDQdz<<2v^3qM3UL9aRD9SQeQw2U2qC z@-_Z`qoxCm|6I>_-K~c*NKpD3f%{p}1;`VxKwpZ~?r_F0ZEKKl7XPHgFevEn@pyxS z{4i{5jMSyfs~<@#v6u8c9wNTx1_+kFzFXvnnXNQ&o>-zB3F`j|xwV1zJ2g>FBO_ix zK|wX$qe(1HXLEZijl;vPz)$NRKB6QPx`_uY z%)Q_>M3>c-8w%7J*~!bY7w}MVMMZ%aFt$2LKgn_qAj7_-Ubg}h zNTm*sBL3P0$F)*D8I{8UylLpDB1`rdV1fF>8BJA`X9hZ;!CcvOs#dI zV>aU5RbhwUpXnJw5=|Ne+u!|agx>Y}y+5>ynmKE;QAR-J-MDjLHdgQq^rNL+{?wNd zi%Dj2UHLWIdpYbzKhsjh*sL2jOhP4+t4w@9BZV`=<+dY(AHP3ii3a9~O1(6y->k&+ z4v_D2@F-%xwZR!8O1dnZpp5N-+=%-&3?{@C)3eZX_b`8BKuJrGj?vZZ#rsW99vsg9 zoOYSg!A9afl9Lzn0}qIT5p-sfU0&gcy3>Rn|MP>t4K#aoGJh+o-#-*qNghFAySlME zI^8rY4totKqtN}5ZpH`35y;c>9)3&hVeFr&{Czo0!sBH$~{tVnAw43!L6)bs3NK8qa?;+qRhbrYdvOEd<4r3We8u zbQcP1x8?v@^Z}eU1%=t1YCjh>vAT&5{ybQDT7pKjz{HPAq8N7E-gX9nB5mD7_#-G_ zltv}(K0Aq;PqNS+hs4O_i{x{ZzSvD)MI>{?^fo&NR7 zqS57LTZ7L}7>7SUAgX!X&dW^GKaA0HNOIu=z>jB8Kf3jZRM9S=qDx9_Z2N8|slMGx zO08W*c3!JU;2US;A1$OoxZI4j3E^l5uc>0l*^XyT{V*-)ApnXNBU z&=Y?H5{w=RUUYZYMWxkkJ3?`0Be91)x@~ksR}OX_0kgB9GwQQnY$;CvxsQ_>T#4P` zs*PfydpWGo-<6o_kl+gx8P?3Me4f`i-eV-<59%g!hCoNCCUYrP=-2;e;?VJdsz46t ziCQ`PFYh<2;5c4Th_h%d-!N15x6sZ!Fwbg6mcWDy3^c$O`(n55#Q)D~lUWQP-YcxD z;w@ir%Q@`({`Hjd%jAIa^|T%R{doPK;c#6u)AVTWdda-;I{EhPrSrDxA`06$7qYtV z;EUPj`>4c!1V5@16~_@oh94z!AyiUz=Zu%cjiN6%?M z;BE4@*$Ptlcu)pNwAXpFfo~N9j6=fM=V~X2f_s7DbDv=q%qs1>1Tah%de{_A_|$J`BylMhs@8 z$nzh3E_x>q1pC^{@=VVw&OOEJCL-|PXFZw0PXaE(=cc)|d+%S%Kyr}D!jtwOthk5ar?1+HU)mQg(cEWVe`8C3IA=>i9l_ElNeLp7uXNK|lsrPN})*8}~Cl}mgcWNaw^ zpG%84Lez_SViGOM#J7V1t?K8`a0u^O14pI(2JFLCz2^$hB~-itM}&R=g`e2~v64Na z^<5dI087n=3|sQ=-22;|pAeJr57G$#+~w)yI_h#R8JtJlnWTPO~cq8u2Q z09!DM;E8L`oHOwHycZ{0K#h||`~XZNXrat@L({*!U>d3oVfw?7dbH>13diqxbo4Ni z6)~|^1djmYe!#E@C1X^XR8tk_110PW`}q{aHJk)`gr1Zch}-3a4kDBGY`)nwEt~Sf zVmo-4o0aUJ{t^Gu1r+|%aZJ_mY?iby`F~(QR_HVtvXgoY6*fir^PIqETUfg_SYTSBj+o$A zZR+*)r}6*omT_dU~#%2!!j`Kik ze6l?xCaie`&tXb!(R;;4h4NP*QKF^0+{Y`XCQuv=2QP80iT&?ONg2g!eQFGAJxzP9 zK-NrXwggC!rPXI(m@zL(#=>*1FeRb`k8(Y28^->U&V5B^R5VTz4Cc z)&>U$YgJVi1t?4dge@;*H@h-sFZr4nKC-j}8rjm2WB^E+q;=n=?{O|#q4ynUPgspV zKTux+>u6R{W=(gx-_Pe_lXyX+7E>`^1c3pj!rRn^#t3WXxuw8h%$|x?$R#ZCI zJM&5Nk0nn!jQj`S249>%;PjVxP;(Z!feA&yG*_kM;W%s-31AfvbOL*pYT=t8PhOfi zrE*IX1B343gQ)yOhCk4(Pknoo?LFG)ihbng{N*X&gdn#s$l+pG*Y2p#T2kZA63@3*_{BVZuC*)UY#LT$6-=?dgxbkc2>dr^w_IW~^yF~-d zdcL8~HKI_^-M5YXW);jKm#bRTX|7N1xYrlzte4b|d}ac1QP*8B5&lyZ{`?6g4DR2j z!6{a>u$Yp}M(U>thr8ZezNiD-o^;s#_NrOf8B(J`VI#&7 z+Q~f+G4gzb;VLs+q8$Gw9b?95H7TR*!x2g#tH9nYls}(=G^^t7O(fbA0CtnLu$e2Y z8HK$(k^XJyl?*kd!A<-eP)!40pUjN8SOITQs%q5F&V#@9`L3BiU+8z~z;mc>c*n|+ zSAMjUW8SxgZ#-y`zEdinpt$3~$Hkh;*u|l=G+&Ak6LB9_e~EvxWbk-kYd#9x9}4)- zzibMi%lXl*|HmUsny^&0Y$jH^6Xlz|`@ud{0+GTbQ0@?$X*c$+hH?8_{>PAO4xme)Zg~22DikDquc%0Q`Fpp_hU+aS5qWL z6{s2o$FPom*^$ZryeFc7BICVi-4%aZ_)6jvi>iM6^^IuDy~Mn8;|8rzOF7h$OTW4~ zAtLQNjU~&=09znm)chByBd(1I{1I|37^GQ94x4}pb`7^-{MoIXS_u1OnuVe}#~+urzzQ;w*oR}F+CYw4 zkUdAgT>RF^ZkH^3lol@YleH1{jHE$%oVBOj1g^~)l0HFVx^eZ>-8Ao<_5wd&kusN{ zjvfh#P-(xT_Oc;m(DbJ7sV|p~`(7aMOF8O7q^(W{OrlOBU!U}vlPK`!i#y(vDo7WZ z@tTKmv@b8v{>aY!6*)J7$^A_|eNCMGts4R3DLaCm5Y-NuyABMx zOZ<=53U9kI3#!nLn}30YDA!H zMmjnO%oG6Bxx7ctu}B@sMb+Rvu40`1M_`Qd(7aMNNjxNA;;qL&yiv>LInesCNsM+m z828Jlc0{VBbtCfmrguV}*$>+Bd6&(-1kJyD)C^A)M*K%-38+Gnd`()RrM&db4KFh{r5)O*n27pF_sSa&{YFZUs57+ zi4ST0Bq_w6+9cJN_)0z|-}O9l7xNU|9P=xsNgj%B<-cek@CY31ilO{_>5yUuzxzozIy-Va^^#CsZ;Zj>SvTNc71}s+q6SHVdM=HMvAc(k!{pPc(mXln- zyybf+h_>0J8x9XPUw%d|<6e%8;Qw*5Kc6>YhAvNhiE^F!UljvX`u#Eos9aL#!nNNn z!Z{=m{|H8hXWPe<40AE5(U-KL07a#J^D)}M-os8y>=BHmCD;Ev<){#7srqXMbZ`pF z45H#mVlhB)YiTQ)&4X}2eN2jZR+KLBL)S*wBEpO!^>X4@T4lb&TsgldGuGU*$#)MWy71n_t=DaW)D)gM9wbYrJ@7t z&eLlLAG53g0x%VD1X2U{ApmQ4pPejJAx@Gx_<-IIKWM4)-A}FJvgVS`&XD*mTmQDR z1&R=wy4qE9e*F@4Oo2J?Dcbi;-{w;N9^6)8-j_khD?dP;-cNYBEV*h42xB6v zU?>u^=Je8u9nJXt^snUcn0vMCOmtr=xyV2&nt%|3W?y&5rM)%?)Zy&Ssf{?jl$}6| zuDP||mEQFR=_!H<7{|2Vi2m>P#5X!bv$nb?4nqbmV_&nX(CjgBz!W7`XJd3} zPT#D86;ueqQ-JF#cNuQq&Q3fG(C2>IE&N>2{|A&t)P)I7-iK?4UY!BVIyPS@du*ih z8Fsi#cGG-1eKMg~CO*7DsFgM9+(Ao%Q1~<$kyztIvG#6q2x@qw2LogDlr zEGiHdgF0zxI+^s>qT(6Pz-_e%^DK1D8h91m^1#m&{5omdM!w51h=(jv-UO>s_dYrK zwE41ec7y1tA9YTl%hFswHP?hN&^}O)qAVpjuxS$QN0S+>7;ggx1{B-Yv2-LzHUf_P zc9w`a)^)UD^r*EL*oy2?V%y+gIXsk)hJ7wBqr-dGa$EdWYp#d0Bzx;oI^RCjH4|3w*19DY+JUM7nbZRGFZ=mBbf`hModC7DJ|M&4}M(T7Yk^;*0@18e{&;DOhO3Z};)}Oj9oD{m@It~D zKx~t&$Weewe9`LFpH^~?n{JE#(3wr7-9+6k{5{>5%*Cikp(vo$lw@!TkV&cu-R)fD zU8_|+?`e>cOXDCvbe-<}uph?QFD5Qq-fQ$*_>;fA5rHPdjhtM~PIpC`F6VYPzc59Q z58BNWk`tDt)U6~iB@r>P=Wz#|cKBl#n9|yr%6m{8_n%UW2D^6d;SSJTeD83{@g-<) zru{c38dm<7aH^43+>1jM^c(q!F@W+fb%620LY5p1EC9ZO#70nx z7U0~g?2`5zBj9r$yUZ0t6BKj0(aPh0NCn^jYINiaVLI^Y+I(bfViWR^Q65K&+BGVL z)N1ljdm%6Glx{6P*F&X55;10bx1BrTl9{$pUTP6b51rh&XvQG9}07n$|56!@%_h=&L*V|By5+3Op0Olu? zS3LCur3@-mHZ&_}mE>|lPY7=EC9d`NEfxT{gWV<-TglwBe|_K^I3?roOS-+!O&`ym zYS$ew1TZ1Xk4i(B{14V{B?Kt zUBCn9+ML`@|3Dim*mv^4Xpdgl%>0dTbxn|{JEI;d-|UUTsd(KFEhJZumOl$|pI>H&~)uIA5K;Yi0W^5@k#g{yPu@VAR} zP+f{Mq0i0-YrqErDsLJN-iRK78>l0_Mmx$E>kZmWC@C1l>xUom%Ymm)=y3^kZH4~u z;!_LQD~;T3NPF}rx1G!B-sJZUr>?{6O5Uok5U2Z+pP2u(1|{T$Pz8SKR=JEOQanjY zzO$oL;fg0-U}Gp0{X#HD_l&aA^BvZJH+=ocX=i*T(nYxRekX7FMdANX>pXoNaUJf_ zt?Gd|QCcGK+S>+F&=M83DA@i|E#eg}x6^Hhy&TM$;8eEQqlm^HPg4*l5^&WsBn%oD zwe@~WrTnTQs6+7RDmNAV68cq9s7PEr1M+?zgg4s349I;GT*dm_`G)Ed?}(jvRq>KX z*#CHWU>pkm<*T*2-P}Mrq2ll$LnE(hwVex{M?-fr|2<@LYgnuNxhcGK+sh{@VpnIaUF+|A)N+4*rZl|@1k2^f*V<(+$C2n^%t6MCRvEDsx-tvg-t!cCh#~-%^HG-uiYaZaI ziT){?L|d|7S-F1;F3m<#F$6*+Vgk9hN09+UBcQGs6qA&U>v|5lt~+;+l}B^NrT|k2&WSx-NwVZ?x9y-;&U}FY zFFz&aXL!zWt85UHo1R+ee9*^TD4{6n9EIIhBOggd(hXvdRst0yu0LSnY^}&$Xi6ea zOI*wHgD+gm%z`SmeUoYX%9Bd6_S2IPrFa|Ltpaqw9{2AVP!^pJ`|28<7yf#Q=roPhKp8LC#y{-rT(9A>Xm3B zB{#d&0$?}NP~s{Pk!3xrz%g}%G=8B?NyTBv8L_~7s9Cj~9CY%Hm(WTcaC55?jDtPk znokL%8;YU^ozb;6DTZ$E$52M8-dwIrm*xL=XX5P{Py>Bvzay1~sGvN8d&Bjm!s;4r z(de8O!7x)ovGeg&Xh!lI!nlh8Oo>^Jz0GGRLQmRN{YL_}N}Rz?5_I`{1j}xu9DVl< znvXu5=08`!A#L+U=pcF`Za?Y+(yYSS0_~7T+f{Sv>y{I~*u;m4YCX+QBMd8`n-d`M z5qdjLlP)ci~>`V&*lPX$QSWyD%gk1%;e;G*Xm`pYJN-@4=wL zZmH3imHZkAPm*aV;u43U7k`4bds(W6KUNbtj+|@p%>>gnQm9;mh$5&3?iZk3m=ZAM`*I{B#cH~ zsIcs8$wo1lRA)EAQDNJ;v9@&VT@E6M?L5*gGWaIDBs+8 zc5hR5E>H?#Cu>MUmtKgf`WFlZPyBGj^qi_j-(UOeW{DW!Dn71v52e3~rx-x+eijKZ zomyRX?r{nvQsF`bqVUCN>(#jh8&W+nL6KbkJCR8UNTw@z%jJH*qdX!yioUB`Ip7SZ zEPxFtd4{99kfHGv_yZLnboOu8(6D}Q0A7~(e>uKClB5KHne zpHvT;5^9VdsGe*>FEV@6f`nHKh;{$os*|(DyMnmdEw@7mWRWNH98d7Bx7Sbc`T#$y zXas1u{2YgmSIzQOxC}Y}uZ#P?sCv3LjCX^8*!YU9ol&T~B@{omLuXaOO@H^$Jl0P) z1nQLj?SirvDAtBG_|bltxRx2}>@1r^DjzBAD4C)ZQ5YhI;2A)YXQW-5lya2MfhXFo zL|(#H9xbDX`KBl3fa2Im%mleZd$e$F>_+93rqliuRcaiGD23>+7iqsyttEaQI%*=+ zLj@Q2gN@`FdIAiEUB!)NA~IIC*60BoehfK z)V3FSf@i=&-?@?cH@Wa{`cJG|e zS3g(T`kpkn-*9NG_4SJn31bSpo4ndi4>T|4s&wa-rIXV?Jd}b>5N3}$?TLztgC-x( zKOS-gQTrImSzm@LE00q%K6+PkCBT2ULfjkPTZV=q?Q6WizdcvT>yk6^V)6)s4~a5bcalo)dnAp|p;RSKiqvmf!u+y6 zw{&^?UB4-*dZ+N?!Qp;8IfVl+Ll%SDil@WtzfXpmNu0tLHszf3$5$~2(89AM;R-*3 z)a#wzt3JM~THp!rW?WgX#PdbeZO3cvfcGP$l0FX*&*lS%pKKIC(r*Yi1C0WYzYSdO z!R{lATSt1^2vv>@6lhph7wcdyc&y?Xk+rp;hj-?rH^>{O4V>p**Chb5LJ`?Tv6=8%FtSAu;6qEU9)c=Z$q8U)@P%`;d4d zyj)%_+-4}RNI6q!dZzGArFVTNUd+vx9QClsTM;ZdCa%;X4?)nPbCjl?}nnQGD9LJq;}W zW8ZkkLU`86tO*IN{_@JB_*+w#CGwNs2iA1g&QBPMO(;+yRnIk(oR z>TOS&ilU7qBiVv34cxPLcw4nrH}R0)OZ`>Gj!rJi=J*&&d|1RSu4|HbrMv=MCA-** z1)m?gIVP(!#o0r@ySczDSu!{->Y~`;yMvAC@*`RNyt53G41MpvX?WP}wEaVXWq_oa zm)xPgv(|NqTG@Jv&+hTYMQU~&T{-xAY|H4iLCMxFW7YpOCx+(-k2MT`^nQ^iI2JVB zU1p2HrPZRrDN)yy-1UrdM&^k6#~fK8XTKqPw~Q|SOs#d}Efdqh${-iPO5F^{Wo5#w zbZpcAYfgdDT*P+GukUpJ@=FRg1GhtC+Mzqx*NtG+6oOu6`|SAj?OF~W$(>RD`wG{s zUd6ZjqP72pgYKXO-G>PE_9@^u0!i~|R730Yci@+o9nQM=p!57Fh;Gi!O3nC{+Faf#Jj2 zSL@dl`FsxPAKCBK@0Ov{e4Be&V9FZLzOzz?)3myCyldO6M6YF(sPw)x9?nu&(b3}l zQD@t|%*y?z4RlAnhXJ0FTcA? zFD%yo7V2pGMwK_aV{KumV!ul5%&_76u;I4`JKI|uB_xwO7M?!c$p616q-j5UD+;3T zFm79U-+$T31=s}6Y~Cgy>z}+BUkc;E(3%_;E`8l3!+#2eHNvDe!VBHJdHJKmTO8RK zd2E3x%IayWluRpwdG@)uRClEaqoM9FrV0k4N%+c$EsVmq^(<;{fst3Afr!4p@sc>w z1YwRHb-KK6pBHZ$RUY|#<=Os6=_hV0#wE9l$6D2YNwHD3*)6dCL$3q-S~P?o>z1K0g#nAIjEdT(C^d@b(t=zLKWvV#aa zU)p`NGwwuO6nG(8A*~p-?R^-BEA%ECqkdjYfkRn(Lxrsc-u@uVvwxUGpER8K#(8ON z=#%fX*H3BL7Rl*~=uHLftUN_2kb)@I4W376s;^*u8r~b)E zPdlkelh1=-y}#;6nc**A%T=f5^wH z94;T-^Q7G^Gj3PWg{L8x3i1_snoA0wIK1y+kqdWhup9GkN!;)t??Bqye$gkbl{-`Q zPBuudHdKDxzBklp!L&cA=;`E@kCjXueHZb1-!GfMx1Es;;7oTIzPidx!hHL>bw@9X zXf4^Z$|=Zh`r{o-w(fz8-97jz`~^&UQPr-PU1~m@qDu%k{NBk@?rKbkLR9(aJ84Q3 zxqx)y6-|sVk5Wi{K2*)COm?#gUmovX#6iYafzcj!p1Zn*cnH$d4eTPkG!Ht-R4 z-|g|#BGLe>kGf@izuj`_t$sIJx1=}>d%h94vUJ{e_L>Y zAJdJL$O!YhdO8E=&Y#!lU!J~X0L&7CD4uPP(p+2^uAGyXKgH;Jbw~1!#;5p8{O-Fx zkGYT`7+$xxU0ouqzI&#{Wif3rxf0$E?V7S3iZE#}cgtS$3EOu?G?B$9}oj+dIX1VU1wFpT~07 zTFSdV=U%(ZT>Aa$F5Q?<^<~WNwfrwZsGMf#_Xb|*@V?bGy1q)3 zm8SXAaPsF^lG>gKJh~_zm$@C{df;gL5Jgqs@)P0n1p#VXn?CvZ78Um$TO(m^3rX#^ z=+_X?NxoJ%R=*|H@Sh&p8L6r>7AWuO%eY~%etxN||GurW%{5#jVuw?U^46n%8FVHgem$#aw!hp;209;@>%U+=eh$X$vrvoXlb2q}$Zr;VA znJ(yEdjVkn5Y1tbZU_(ecg~F7i>9s%sMKzTcZHbBmSsTZM1wzaJQ-F zPepoGiAdo@t`DAg(2p$WKA>R=seOQrO))ft{kNMH1O#u$E9&o`Gg`fI%1c*aS03!Y{3`SR zm_k1;QhY~_gpmEWkZNK3b^iq!&?0#UPUX_i6$f5iQUk=mY?o7|_Fd6e<3sk!jbo8| z4nXhbIv6aAUFMBh?k*+M3jzdv9lum*jVnR@lo@VgFYDe_-8E(B;1ExH(7Y{W{_wf> z%WaM6kE}U(IK;(=B-9!jwxoLIoxi!Sq;maBrKBz87q$AmTKf-!x#_Y@XL8`O;S>S8 z^{I-h%vhe$W^2&txQPq%)dzzn;?7Eqj1QXl_ZxgWsRFaluq3hfZF=j?K+F@FV2^xP zGgzkAmYHACIo6TAXvD=w5$D%#zb$UAXR0ae)=I02rB{``vp?5PTe+QE##&^VezMf{ zK6Cv@&qwKtn*FZY72;+zof~RzI#E#^xi!8wSH?my%CGu1A$I=7TRAcv{|u5EbI{#ws@VZ$=nnd#aH7`9xhTH3v?t)VozL-}3ro8~WR ziQRQv#V;yz#yHIFv~Qm1vFfj33Mp@|)pT65Y-CNQXiFu(!e__!uesm_lt)-ZMmIloO zjx3@1(fsT#rF?_&ol4tm^{OB5zoiwX@aq#qJgaXws0LQ!AIbaeRG%|#bfc)VoB z^#AEy$X&PCX-lPyx0Oui@K#5s{)JOrHa8#Nva+>7Bl6p(v4GwT*(>c<26~3+M&&Aa z$}+#_Bi}UF#)IW??E6~YMZ-HCGU7xkH7zek3vNT;88*0Bu&YzQt z{C#~^2-35Ch{6tx z9(b54T@qHhetmPNcRzL7*xuvU)_6GhtWtviMcdKx*pg$usi zF}pIBJzQYhqV!#<+N%UZ$%x)~gb1WkyR~+P zjii3RT~<`6WMjoM#%|I7IX%}ESiOkjyH-Q}q4 zF%Yl&S}|)o+Rh81>C znJ;cuSX%UA-;2>$hk>TOstO?@a_+$%WKhEjaecs-$d0p4@dOokqYS(d9 zOiq>l(jXF7T8QSWw6euTBs=?mn0(u$G=D93a=`x?3qOCaMV=?yqYEdPx^$Hz&~gq+ zuMG%Nb)LOgm0o+_yzE0-Ixi+nwj8o+L>h*8t&ML&Lj+t6*|o}wv$T9Rj{lXhgd4jG z_QEh!TOa-7IXvKf_INwxFtk#<<-xlUUw8{j?V9%(R3yI>C^tmz9_|h5*3Z zZKq_{K}iX0@;$^~PE!o`zZRfQ1AGvpS)eXtF@uPcbtdn{!$XwZulK+bo!QGQeF1|& z+T5oC?2|+%l)Tw5N4~zUcQditaP}S1-?qf&b3O1Tv#4y$co%4 zp@rsXB9O_{uqv>fR@HlD-XkOKV4nlsIW%iM+{=NpHUYHJ2w+>*V_s$*^j4-Uo9^09 zlaH_0ESF}1G<=CJmz6hR&L(>gSJE`MUQ& zTG<4_dPu_pEOfyuGlE0MFOrd%KHh;gL*YoPwQJ(xOyum)RNUxW-|EDa!L^mnJ+cZE z_g;?H%aU6G0lR+Q%x_~H{&mm%VYmJ3XC3E^S;k-qqvaw?evQ|O@XzPpe1C+ZsaI#j zT?XY^daSiqqS)%KjpxBuXlZ6MHcahCRvhit9+!XJ4}zkP5YQ{DAYDNonHy9&6+pI{ z0SS^iD8HW0g(IZ_#gC{dZtcP8Q`Q%-=pU2kfqX0{)PhReLb?ViC&oSSqQ=+s8`Rn? zzvX=loCwki)OkIbx$rE``+A+84UedYW={X{%=~K<{}|brj<*DkWBsCG+{yJ{F_o1v zFN_!_JAXdtQQOBb_E5|Rh*)kxm9dkWAHmDK1=;hK1c~gocV@hB9OnA+5+G_Hw9qNF zL@T}a@YDffoz4+@k+V<{DHvK!3_h7k*UzALg+zRz`?dpx;pW5szFd7aKQab~98oN} z584kV6gid5%Ko&V`X`eV`QI)D7tK z@J)d|tOzwYC*ZE&H-RGYwwI55yhQ%k$s16HEMaY4D-Aea3gAUqJXoqI6ejrVxMl}; z7k9~b&~4y4)jzoa!{Xo8_rYX!ggB(AyZHlInm`^UF81Gs-6eza?hBs+4wm^Ytek3x z&YRp9aK$OWE#15eB)#V%&Z}34dzKwwtl6ffHQ-utLk;(dMLYW+@aHGHYtXc0Y8q-h zP9@MN_Z=j3^R|E0!!TN#AneFB;qXvXa%*+6#s3>6hc;aBaJmlCC8!6!uOX7omdG6c z*1f|OTN$j)rJ-jI{?A-Q7TYVOK7U=B0q8^c@0I%PPtZ>>*GqWZA)R#px2Onsp@q}E zosQs=-B@wYk0 zFTN+t#g!fEmu87?a5~>^%|`EApUr!$79$F$sIU@)c&U9=#gA^jPrmWz7vw*JB<~fH z)FWlkOd8Xl&Y7<9$FTKh?8JB(hcs@U;|uo7_ULQE5k5P5Qv&;3Exfs`0L(x<+0O*k^;nda z^DEouGus_bjSlBx-Y`rrlNSB6ohr;S1^&9;Ql#=_F26s7Yd_zoE)CZOsR{2%rOgdW zM3v~sJ`b(m-nxz+2mNYjGv&42=$>k}18M2|w`mOR-9m0S8)5c{=K!?g5X%&MaicNA z+P(Q&BTx=%LbX>{Ax>r>aD@Vxr4$u7d1iTX%OX3%A2A^7_#wwaCw`3B+IY0>?a^I6 zcw+w^_+`6Dgc0-J?N#>J+i`?G)qCRO-@wSnpt7{8*xU1r#CdkXA$$QKp)-ZIp)hlz zr#@&!nECGZh5=GCrT;?j4m!jpde(a9e520?rFC z1;KfI3yMh4Q$mSB`Io3XuEoL9QsgPdkV{zw+oGhb{Im*)7+#FV*>#XaIS+619Dqng zhyw2A#xzx(Pwb-xrU6@)Zf-Qtf?p4wSRc9M4dTd-Zg;4HtN_6no$wJ#S2cufzY0%? z5-^$DKpnz$AU18c`tkj12oM1fe-PcHNro#smKI^iO~U)N{DW`4zA>a}3SBnL&AKz6 z7n}DqEzM=M-NtpfU@+Ybmz7GJa@p{0_f%oYL%bIK>WJlFa9i=_y*I%7q52aY&K@ol z%L<2@t4*M)wWn25`0QC4*+JoFO)_ZQ(0~&fX`vZ#{;}T+AWSviiveV?eTucz#+g zT73pMeJND}yyBV!9NL-2(dm*CQ2bQRoW~4x{E*1kHx$Wavq+I4=jYGQE)c2&N_a!r zf{#GZ;)1pnp@2_H8c3%mTL^9r=`kwE+|dClx7y z%u^2R%G*HuT3XHzaCK_S*c_y>%v1kilcimi+|91_9)IA%c_#&R7vDjj&o{m>!YUjj zemC_3{;QvUqv4;QB_WqY<{$9Phn#VU9-k`4cwFD^J*K9m@wQI^qQNlbWn@CaQnz?L5oeV@*~jDqLq69sOAM&tsL zYeM>V71AorCo4*blOUaEAZ3_sYVG|%f)QsY_U=$w!H?bT>DTjnt&+&+mTe8R+__avJ z&l#$W|1`EB(0GWPY(O7xK?N|xAb5FDEqyAIgL@Kbl3e=Al4Gp|einF==bcC}^d0lG zy4mjf9v?`7*XMctAL-H3X%E*9)Ovg zfu@MyEvwK|sVq%@{qz-hp^NP73IGPMyt>;L7_8fISb%7K;gc3raypIJY^XBVONve= z<0r;HR5E{^sC3X*h3^;B4<3$mfY+mpb;1B7e82VG8-rwFKrO2x3KbSZq1w*HYec4O zxJ3PD$d$`P9ls5k=s1uTp|~_Y zUZP=<#-`5(Xv>OEj=j!%Ap%LAPY@mGrKzFLBm=a+iQh?5O5KE>NeKTGfC}>`rc6_v z9nd_Zc72(tkq7-;chxJ-+$&{qjfh|O$5-@{BRE9KaRzqg#cJqh zQKOx$+Y<5yN=vf?G|Zis)orsrqXDQ`X`1^dA{_i7mSFB7LuSt>p7jgxDmT9RYkui8 z*Sv_5bhM8g`QwB4{T}#u>#79a5{>yL+!_AFrFSADPVI~7$sc=oL&(<%A%lt>_*^WI zyN$plI3#aiFeDQv3>iV-;>q$3VG!hK6$}vKbEGglpl9@gp2@pAqtkoPZ%8}1i8!3a zv(@e7OTW1NGrlk7pbmg=Gv5AL6ydrEkW@Kr#t8^qWSLo6-{JT1O~gY0R8b!Keb zq4yF@PV)Bee)v!4_t$^rE5TiY4(ayUHzg9sNs#y)N@TD@92^R0N7|=QgK`@MFso4X zfNK@>akBTV%!Gbjv3*bZ`BCBwT;D-&G?IP;d~YS!0ctP-m}D5#Le)RQAZGDk0qB3B zkPJd}&)fyK>1h5kdi*bUz6H$Out>#viy(s6+{d_>|C+~PmK=k217YA`H3ChY4NiZM zFKY+k{;B##J$e(BOB&77;3%-R#Zk;@P~ zsIl|pE-{!okO`(j3SdyT>UkhVz!&gBbG?w97-&2=|+mRL-j#}V!8 zYNIKK`982TrZ z%q#+N$)M1NiJ3mXjjqJ|d*CRq0u3#|V|S+95s-vb*ibLT19D2hmg%rBTV{9$K(TNx z=;9;LM|uNFI6}9oaFF(DR5&hk3EE5$(fBR=KiL2U7QFGzi^E)xd1PIhvNLIV^Ee2w}x3Qrbeo&r)+!f4~^3@&`(9bPtQU}LDgI>D|6a2(bS}l8KG!d9KZ9`rK*B~su zB_@!2ynazPEOwZcoxSmCAFx!qM1sYJR$vEz#3K_i)|Ud?B|F>Xzn-2)*blgRn8}`E z1lM_J!f=T!no#Sz*omi9gXvUbvHpVBW$Kok>jlFp?MoDtB=S@c%}$}+tY)o5h1Unz z@GOueWOUK4%W_8CcIN5}0I;kStuvo&UJ+>t zc*%ko??$;a+>q^29`<`3p;f%l9s+`H2XpYhXqT!T=dqvy}r2MO;*qUm*2s`u= z@rjbU2ClA=8!nL1xjFgg?nKAa&N}x&vei;|u{UuIIEOb|hmqFWvmGgZw=cVE)&PkP z$rb@k%%Ea>HgxSZ{`7f)2c+jozQ0qFS^)V@&=B~Bth_m#rw-HdH|KoMk{R7?FS~#9 z<3@TZ)3}5F3AEl5Oi5CL9$?eY;l-Lj_H!2SR30n(EvQE|0l%EzDl$_i`vsyH$rMmp zac>XTVm%l4IhNyGvxX-*+Z6G%wubn5?p!?R4v`Pl(FLYNwxK~sM0qP_+R>%@%4mNo zS($mqJR0i3TuXlyigyR&rL`u_fQUTeql{+VgSy{7>#S@IFBhT{9l{+FKV0f$N8i@y zT)+8tCYIv)khyzK|QqX&|_9F6Pd==gK z9cuet{`D--L|DaBwj^7uL_yj(MISQK*6S)?L7v7Hn`(vQ0rj+p9b!e&fKEag`5eA z_WC#-x&S@h4{9zGkFz7kGr>n9_BD@0qw0D*F+iP4wcZBfYGEmTcWeb3*fJiNYsm^v zGMpb}t#$&->);Ghl?hNj@R3oPLx9VqiCRjPoPwx1(yxTqH(ux#hEs4ZMq&N+Nm90} z?)C0a-_+!lqi7JxaZ5)Qi{ti+ZMiYLW;eLjhXCWBV#@7)>&TT#c6NUAvhbmC2jSzx zdWe4bEK~-%*hhjepjuyRQMs=a!?iZ`ZUs!h1#sbu@Lz9ADk)opJvuP0txN*UYQ^xT4mBf0Pt@#fJK z%l^~puVYK)n$@N4q+*d(_n)~QH1p0ZP@P&*5h$jc=fDhkO1komVFF5LaV;tm@%pNm zT`u$F-iNY?&%_GJa@5`XF6G-xm0cDVaO>WNfW(C5BO;La0>d6Uce z24YIxj^RND5hr!P^={!NR|u8Hr(|#mS%D~lV@)t~dKKFq7@kZ`x&HaVBUL^(#U}1-yOTRXg!mQM+VMK_mBD@D5;o#IqVQW z`mi#A?gB3k+w_xVHw;u%pW+)oj-Nwhz1Qx4Z16Il+V`3dLxuVhqai8TkLRjQcSIIC z(@4f0Dxag(6VPkE+mE>-4@Y$qv<~tRi!~jY?-m)4Mun;P5}9K#A8MS}OehRChbx~Z zPIZKxMLaeZJjy36>+W7=-_3yz^}Jtt;5eZ-^k|DlJxZm-bTlBcWNzy*i8cIQFx=-} z$s5g2>i1Xyp+GZPnpkPOK!cSSVJ5Sl67IPUTY_5P%a<=KD2#y_zhZ*`4bhh#{^yrW zqI&#+W@VWFvf$LX!|2;wC9d)}Inm0Jbua4x;8VV;gZkWc1%Q`W$C7PuLz+2UD$Lsf z9AgIGM!smR<{+65@yq$SQS8NW$c%9T_ON!u{P?%-P3!wEWG~X)`qiwO?V%XxMEo&J zvZ(fON+8fOZjtJPfH>kVrku6K16zL;3=B_p%Qbd4hT`Nm{AR?~s&A|Ena5y;Vw?QM z22)wA0ia#;GM^Jj{9e+twg)h2v}fF4#DKp2w0wj9t|N##oDd&xbzcg zACDkQgQHEY8}%ISR2gbjU*(065w=dhuR#prTrQq+c^@6;x}N|#7N~HBexTL4-u;a{ z-S~_t#q?swCDo{5ML3jwRot$(Qr5mhSHp-Q>ju)PD)X#0+5P^-gh28Tt{E|s@8!0gQZ5>p$<#sSB5B?;~0 zS@9APf2RSE$9h;E=G+V8G?=PD@u}LibmnfHJExJ}aKhpcr?Ffa+6Qe_vy~2ErAj>X ziarT|RnFCddJ*d+ws}7D?u(r4^K_|(DXI34`m*X#M&X_wPzR+yJk>fY9In5gVlGZ`5Za)>CjV`4+}&xu+Bxm6lESozsQF z64rb&ou6s6ttE{*nPHPe;RiF7MFrEH{;&K48Nj%tP{3YW5mjPTg!O;;xwdhEGSbVpy6@QGK=sN{qSVQ?|^6#|Kuf3Pq%Q9Nv%?C-Z z7=^+(Yv{dMDrM>s5P{y)imK8}fAPM&=Pknaropr6%yXqT{o{g9)XLo05$%$cS zPRFklK4{{XH3m-I6mB?X0h1(Ntso^SL9jqnIzL(tMm4HU8Yr^sS84FO`U*A4SJ;eE zb%fV9iDo$O*M9#@f<#9kA$n)^e%)JQXFEB;)}^RTvEx87hA?Vml*>I*9c5n&QsG?f zM*btjrunyE&#i*ZjbiYWVHksgt}pZy^sOR&!Qt}bm}%W{pYACrD44pDy33PWXx7DQ z>#g|_LUox@5%SCx_lv>gwWS<&g5f&sR#tcVkkdH0_91Izo=->g;Aq+XlzU`cLOr^3 zEh64eTSEc!Q2_W#rJ-wEER&3FZqpy2huem1f;Q45)_WI|{n&2MAP?ET@#e5uw}3R5 zmup-)FTQP>i^95@Zj(DFUuhi_z0}O)*a;31UtX}^`%ua%Fj>js z737wH)wLv}h19en0AP<9V&|-MwTZqu$BP6G7O6=SKww~#GR>?8Y+>sCsES25BvbON zD`9PJ!$zBGFo#4lBph!NPXag`0y@=tiszAo@*L(rD4bkH!+R$qL{_63_d3tH?JDKQ$x zo>h>5vE|*EV=}2Q*QmpIJ$u_wpm&_;dwmnscFA?lZ!`M(P-SD&<%r3o!X^+28y}I< zDu;s*I%Z~W3^;WHoTc;T%~%%~ch^9|A->3$RvC%60=?q3=3|Q17a1#}Yid8cp12|& zU`Oy?on-u*I>B)H9s*iI#B4&TC))NE1;KUHk6xM`)yy?^_3>?EMkWs{9WPssY|W98 zRtys5lukd_s_wgc5UC!~5~Bv7B`c6}Z06LvY2V_WjAKJUtpIAX4vA4DjvDFB?)zdd zGl}H)1Rk3?)kr@%#`--%*m3FXi{x2VVz_kK^&ETdB1@fIIVEGVF$ED*Cqy)B&KV@w zEip0xt$H6zPu-7;WE+xu+FTI0u6uuke)jb7lZ&=C@zyPz-0vTy)O6Kb$)R)2-Mt7=vFRSKdPw?{4Z-P~V4zl$JjXLVbgm z+F3WUj_|JrdST}B^3ppfr8X!})4XH{z4Gk??!lkI*}Hh%$=!=N*Bycsdy2@uWCjy?pR<7yhT)n!6Vokd9G?mesc=Lgv<-et zdhU?5>g}UVUt&J-sa?)k{VrWtzFiU01CfvE$Ve(#$m}#GoISq-h*vT!)}?0ZIasAhONkNhd$H@%KVlZkSO;;uXgF>W$jR?UVBr~hPXN$=&Jxi47RpYRWzz=`} zDZ#F7ZlOk_KP)A)-JvP&(2?OQ{?W|S*6&U)}jhH;Q>_l~jhE%g$YR$4^g@&uRSS5F3r>NlrzJ20=>OI)91F(-0Ht%KF}0=TW5&+k#vS3;4UM5Kk&XX;LrA zF98J?zSipj?kdLF`7XWQZ0<7CrC|qf{HC5+XDKzUeS>(Z z2}HYh(#%V~M#AxkIN}7<6Yg#v_Z^={i#f+f=eahRD|eYXJvEb+0O=@%Y^F0boNR82 z#~uvcCecO*$2EaJ$*yb*=m^GtolD{A7I?7eli(=w=wNTc)%1NPrn##x&&)G8a4 z0x&#oEBr+1JTHnhX})?&%RZDK3J~zaUYL3i5=G3MI(*F%e|`KU`kDA?ur5IT_YQC% zy;H|}deJ0djNnQff=38gz088J5X^C}72didcA~O|5|NC*7U*uHr^%Tesjl40t?@Tx zFi!Oaq0!PP(CFPV0JQp3=2a1yDFkT8%r{FB8aR$8(cv@f9?3)kMPR zPbK$a%KdWt1~jSa7dyo2zZHuYO+y&Bcv9{{Z@n`p%-~oGBXAt$kE>-?L1&I`8Bxvm zpp5voF1UXzo5KE}9Houdtkrn$F1CIak=pTaP>*ll=C#%YFAfo`q>bDguF!ECH+5H$ zmi6g;apawBAQ3n|PyojAK?7E(8?aF&P;b&1ozj=mbqVPP&(gNY@7ORdWW_KuYO?-f z#B(Gq-@o-)Cp`MWYq|zS&0|)$S+E2P@oZwxtsf3vF%C_7RHW68z*?lfb9aVWA`FmZ+M27Id!ka?lXW^ZsTl{#>X}3V zf>(&956BRfsGe>LUkM;TNu!p^p`u$F06HF<7JZmF=Q7FZVek--zd71D5@zlC!55P= z1}$Qbq9eEU0 zb`Twf!j1{uP{J0hD(gcMY6rCVthy;~)Fn0EehdzgyAMj1VTmlaZ{gH4z+axe(;)GT ziHl`(GdjHIB-?Ow)aeUp(FY>{wI?8RT#?!6JD76)c%0SEGYASJB;IN%f;+uvNvE^D zJ%Kov5j!_27x_G(ujiB-XZtH(s8#6Cm6}b)2&%!01C=V414LDoZV8?%5m! zUW!1&Mf!A^IVhBNkt|+A`j}4CDHU%fd^>ny1tO|w$}@cZyU^6G5e&(3HNAW*rV~o z{fP{xaG|rqGo*iz$-@c6SU~uF;YSXco7ssG%qmbBVr)gvyNozOf$sqwz72e)!~|Lp zH}aAxs6f^17Ez%0b3!$D${kEP+2&ULdr7*fWEJ94zvSr=_l?+eNgu+Hu&^`#WQ(-4 znqO4gqo19x*+}9NCK)}r*ll+Q9jjGtYp}Sa^YglN2#R-|>#{Zi0ZsFU6Iw#nYHD^c z@+?v6@eeu9$(tTX+FC(gJ{aJ?c*(D22LN6b!#U?5ehk4&&L4U4o*&8RE)2Zl%rv|^ zrZ~zi@ikDwqz%@`XPeZ^EXltcf z^q32oB1qs7F?B%2dJwK-;Nt|Kj-AKCFHGT!a#7_q+_jJv;&&%61*<^(+^6Tx%d?Yi6jP zGA1WFOKx6#{_!}wIM6M6;0MiE1I@OgFcyHp@pUnRnZ)x}K zJEQK-*7_#9cLeFAGZm}cmaslvD=`VNC6)X6AvpPyps)=Co@7RO z!1BGbSQ;0!vmon~XI?mo-C+-_1h3^Q!8PHss3z5Urin1>fKGiC;Yi)1mSnOY^#`#d z#}coL>(PF#!v2o<0Co+@t+&z@R%XPO4xXQD#r}l9 zY^L3aX4dA)RR{uRoTgmwN-%9K_cs1Y74(pZCUc+JaN*p^wv8w!-EAk;J@q=eQm zI=ml3Dv-+R-1k3A+jiK#en4Qt!tY;-AIKnXX-Ha#@P^I%tSe8+h!+DNiVapa6l5$4 z;9qdP)McoO6mkB^#|Oq58$uTQ(%yY^5*O>JgvU#>+ZA)(rR(7XFG_Dfy<85DYNbV> z9ip}dp@trY4_T6=aB_l-_o=g#mzeg;X}$<3R7J3( zyp{jZqZZMbvmC4;yLRKoX%bw>Q%T&Qu=PoU*jn}mC^Ue!5Rj;IIpa|D(^Hy6GqfRg z4~qb-i%h%^J)gvg49<+b5s88z6QL_jUB$NBg81-)5T@qR93%+&_J&7&dJjiz;+J{O zR9|Y74+7-c&8YczTQhXr41JrvWHVw(k@_+F zzBvR3A15i^k1uV^bTpj%eieYOq7T>R7G|L-&IGiq=AAagPFW8JJ^;@OGSW|Y33$oZ zpiXk+s9FA1R8$Yif=ibR7$=k4x6tmoN)R2la5NrYCO%9rauu9N(KTbAM>(IreCd+; z5Xu%roU-lTdaC+zB4_b@>?$RC>#Ecm4Sr8Wf(OYzya~8mn;-{qXLecB8J<*GhcVk(p$p$L$e6XtBF`*A^4_ydjnH1>= zHLp&}L{M1js*{Y95%0`Yy?(8aR+lFCg0QMfwvx*;th$gXy|SUcLPZ4K43tH|6&%K{N3de-J8pB5(B(hr_dPY=dbU=~w{m?C#V^&1^+_Oe+Hv zPS!n_EC;X}ADPsA%%u&X6IPTfy+dn#`rvPqfxpcS_>rkhY1d31ZUWqv z(DmI%_Zcp6zvu1Lf9vd;8l--!_(C^=3w}5uSNiJ8sAlG7FmH?&6hdAjG;Zmb@n8J% zK8U)74okJPy6IqC8r2TYEU>1mrlLfl>-P2fb6BRCycvHl8s4eoiaY6V2~PEdBgJIQ z%GVIHdi|VH2jvy0ba}Ua5j=s4#CWiCBffO&IxM^XhLN67q^T^^(iwlKI_Z%y!h=r~ z$|6HqYq6f?Mp@(}=wpv(_9VYvhg4j23#1tTD@fbxrRGW2}+SQTLb?@ET6-Ruue037t# zWl^XaB)p`LUKC+W^d5)E9or(Ih!id8f8x8M4Lrwql9`7Iz#_5 z4#ac_jL*I@@>a*?&v#KX2Ftl)+(H2@c5FgbQQP0aWP0F(z?4b*iCBRuhNRu5>#FA z$AiO!E4t7u7|xk4e^oe%%xM-cM;8(w*_ulOT(EG4W$3hZ!XmD*M5~dG<(P_oWhm9t zvU$k8at?}IznI#Jtqj}iqeWww-{r;?l^elQp6pKRxqS;+%Cu0XLlu;;lmzI+C)deg zDRX`xOL>B@>7n0P)$l`~If)2vA&8A<>WtNI7kY^~CBYfp&e)2A3n;2IbbjLzaHHc0 z6rwn1f!uTF!9RE}Uat6Mc$4u3scb)aTt`9ZE6V)HTlVK)ryd`3Wmv=c&wL&fLblmh z=@i^gw&CVNbe#?hPyUQv^y|;as}78R8*Ayu+y86SfOoO^=340_or_LKGgi)LpG-kJBae%yb}#y>WK8obQrM1Ggq{(=5JCtWao zcW6Wp{z{(%ElnXZS>L|53*iI9MkxPe_)YP@ep&|n55nh_cYfh>!h1?*!FE1->T>j7 zi=+@8?0@{KR~H*k^TQCNv1A@m&xPR7v`<|D?Wf+K`R?N+P zGCM{nAOgsRX}&4P-#%mv7gmPrgmlHP>RuqwQXm6SPgDK-f#7%|1EKxx1^;gjMB{Am z8RknG{g%;Bf8F6@u`qkn7Foa6$AQ_-gvx02Jq>bS_LFCSyV<-m;gr$aOUe4||0+=s z?2whqwtpw^MpoAo;qz1czK>O4!j%vI{j7Rh!`UFq;D3+kkpB1>Mt|fY=`ill{^iH} zzV-8C9RaKi`r>1|-z*y&JVQ81G48iT+rJMEKzalQBJjsI`1x$c|A_-pIQIMm-ETwv z!_<1OfUPDA;*pd5!w-@5`5%3~@3Rd5`pAXgn-3&YN%n7}%Sag&Vx77D>c)MOhJ0LM z13Ojz|Hw}L>&^GQ@c+SqNI>;fD7sTdN&D+BvqVgH$dW z-+9^N#D6TdeEZ@B97rf#bNX+O{{bANz|kPS!f#@WGAO52IVc;p`|CUY^85aAuRcEy z*1qt)U+;b^6Kn>T3(vE7yuWuw;=!X_YP_D&wf`63BbRdji=bF7-M1H8nRjn_7D0oGmJ!o_bM;tuNVHGJjvP{tQ_@WX7qmJ zRYwfZP|ef?@y*{Yt(Q1_wVCv{T_g{FpD@Mm-t@1pd*Kjp&7M*Vt0q7*D{EK$!?-H@ z--YoQ;+cKUY-j!LckKUaT{XBcLcibCPgSR3T*5b1)b{&3`+W&Bu_xqtVf$3LBfNsY(hb=dDy)RDk5 zsxLOJAN||+cua@9G7nYp{tL+aF(^vuH5w#u?jPm8Re_Iv2*|NR-X*zzQn^9cD|*v% z;UV0IPO?a-C(@-a^y_7b&r*j-$LSJC)vEr y^c*hHWdu9G(SG^g@iIW@6xaB_{9-uF^I-{1fHczpZ%a_{^78s~M+^E}VUN$X&=Fm}|zf#x3*e#FJ;2FFt8gDk|X=-hbvKrB!Lto)i4J_fFrW zyHdPsKU(R8&C_!y=x<1@zxd3$A8qqFJ;!Q(GJ!!NH$pU*b$X@pt()Ysq}0_9*z8)j zsB!&Xle(AwGBU35&cX=%~sq{EQm(WtJju7$DI%=DC(FJDfqt*+>5 zYT^!~DA{pj|ND;?YG7cXu(Hx`Vck_KBQ^EylP6D(i-<7i?xd9ToPDFNu3jHklAiwF z%iCM1@ql^|JYY%H)XwfxVPRqYE<$qhYXd_=enG(olbcshZ@!?Kk)pT4+cG#f*v-Yo z+ zXUq<|nOoJrh8rgP``HOOuCA_bD+~4-A$WC;|2qlF?sA;N#qrK?2lL42Xz})NY8o2H zO3v7(Jzx9!iXJ?8zw(WcK^Ue5p;f^ycQ2yMmV1 zgZYJpBkg30e;1hYseFG&o~4_I$G$v%emuZ3{ot?D@C6Gldx5+|}A(=HcyU zZm5<;yF-e*J>OwAWebIOS}OozV7;jhVTNV>-a6 zs1W5Jl^4$Il2r*uSowOx$B(KmqE(6;HusPk?6Wy2$&j*GA9IN9y0ddnx5D!6EkiV* z;9%&I`SrNr>!H=AL;CjiS-y+z{za?56V^+d{ph<}#CM$z-T3^&y_zpm3B8jO6QU+b zci-q7uH@nh#3_ zALgRqppQ8Dg>9^Wz#jIJ9&QF%k&Sn4j1Ju`=%jUJ<(>4x$(2C=r9kJp$^BGRQ&R~V zBy;FzBggJZc>FlGtH?3p#7Mk#5)ZP&juiPXEWNxs_4^~v^FFS~$f*19;X}Astl1Sx zP3FL~?HexpsY-uOnY(&;nH!JlkvgN+t^@n`pKtBXd&!#ZQ6G;qyGjF+zL8B(}uTB>Tz#Rsq4r62M%PFmOkNHG_Mxj zPJB6jC)NG#_`@FRn>N0&#{H~#kD$r@3eN}KRzuP5)1QQ-6p$4x*2iaL95pmH4i&fd z_AYadcuX2QI~Jv=sHooD^5KKZ1vT(yqRNxt{*+l8WdH5jW5z~~bCZ-sB_)q_6lZ_^ z%F4?6tfHzKAs&BoW0U$VD3lzk^d0MOg&~y2@1ORv5)M5hxcof^Go)1bcn4q-H~FCrHBm2HlP zVSwl(M0rk}I(21P;sDEXjJ}>;AQNeq^_VUi8s?3TTDMe$$tMM1RcvyyveaC7|2h_! z9LRR^Ti{LE{}vKL>eum!~m1 zuKF=fU{-*iKW?>%aAE9hw!p}bA3r!qD@t5eOd=6O6gl*iHnKk+T)+&R^dOn|6-ukJ znf4r$gjL=4#3wN^S*fYpg-CzO=1z>W>8tcTP;@Ug_F$SyER#;I+53WG&l8(w+pmJ3 zpLgY{Tb-GixwHJC$5zw6?Sw7CJgWZqP%!T9u>E@#2cTzhg@!wpE6{muEMqs|vZ4PbBu`AfUT{q8M8)T{qp?wbJthq|9G56RqkorB~Wp) zJ?8g}$4o!D2$QeS$DL@H>Bce{p}30DRHNNCf;>AcoBc{mOpNWeZQC-e;?E$T)1w*r zQR0xShsEkUI}0sJUXn6&K^BYn2&cg6-ro3op`qe&8QIxxy^1eIn^~RZ1nDrwlAPSl2*s2HDr5%uk2K}JD{UQOa>|nst{yt# z6wxZ+1TbnMHx<~$@F^*rX?MNN%u*oCaV@fk68+A`+Ev5a?eLgo5hrcG0Q1+5j*~r+ zVLP#LE%!W8h&hE<12%^f{A9|EcjG{)$|dG(nj#rWfEjTEK|w+3#uitv>ihf4NRXHK ztc|cC&&0`~l^hn|NuHwK+%Hlzgrfl7U)D$c9`QJnp{`Nr^jr)|d~j{LS1L_~9uL3v zkj1pN!}{AhI!<45S5;NbDl6-vkxLBw_ii@2#!#7tcqs|P^DMnr8SmKH*vwY*j&P8s z)5{Ejc*XfW<%X${UJa&t9HQWD9$X7?N0yBHmzKT)>hYDSciE{Klz8C4fmG_Lva+(& z1M_zk!`O18yu_=m8OYJi9Enxiz@b{^T>i#0Ix_O&?%liju@BGvgO@jWUX+*HIXgS2 zE+!_u|M)R)2QAwpLJ`Bpi0}J><+M0{V)>r|`3PXHmo@M_`bIP!^Ya*yaAsy^du!{u zsoo0Pp`js`@n946=V*5U5Y#!0v@9rR_GiQPuDd;GcyZqO~B`rlfTe!8R$relkmbt3H- z2ik?f^YZ0aB|!%Xr;RUOv|60*dq<5tfjtqm>^(ElAtWI#F3zAy@flK~%C`pn zHW!*sDXqH9efoS<_k6t2)=DUaXZ5YEHPQ-1}{?|0f(b-2a*H?teJw-_~ z*@NQb zI*sDdy?giSubf9t6ms+g1Yw3lpFPm1c&5hada$X~X)!Ue`U9h-rQ&=s9$vbmk{jCy z@g^0ZNyFSuCqLqsWvE9|XI{OM{nFUk)dircGfd9nJd6?3kB&s2mXfju`&D;U?a3h} zh9py)c~ZT!RGgKQqv&cFJlECP`TXhAH@0%gRmc}RDI%+i%gSseBqY@F#@SR)1onRV!P*Ct8p-bEDej zo`az~jXrwK^viZOG*A(T(9GlH7HK%Sp6Dg)p60j4pDlKBx{*7OP@1 z<8I%+T`#aVa4|b2rG}4>uehpCn+S=O8Q}s!4V)=4Ah%QMF@#y7UzFx$1$H|(U+o}?rZ)jN9fb$7G4>wY+{eSCj+oeY)12ywU|KA)6{VU$drom-5n{8%ZHRV)cpnFnf!CXEw8M@|UA zwnON=Cehu}Vg^B=ci-NM&8!HS$|oJW3sH9-K76QFwzoF;#tjsFI4?Y$egfG)47C-r zNQK3@+k8ctHze>lSf61}90r4SY4Y&!Sb9yEg#1R=*qDuu>h@pn0%kJ?W~otel%JFh z(9wJR{2l-q)j7PCgd-uY)-OJt?`7cv_C~tHqw!-RA`f{G+<1Qv9&o_$+k$Yv?*YbX zIwf)5Oe~L&sNdamTkMd*`|fTZ{s}L=#c$otVbs;1=XI8EH=LUUDm#1oj;~)Yeo6nD z)nduu`}y1bZa*~)TPRKst+PvkIgC?Iq)3M%fE3G9oa!v)&j_FoU0&$7fek}$q)Wv0~=6!jAP=dfc@3Ci{Q1fwaqFi z>9~IVIz8)$>3=?-&Z&SHB0qh4M6LCf#;8m4Mj3q%5}Mh0QC{{w%X8LWoNR4uV&nKJ z(Ols08n&TP>`pE&gF5zAR^utz*>I+g(cn;WTXu}y7px?$Av&7$p8M6AdO3F9-V)Su z%J+Be+QqIwIU?TQ-*5V59)msGCJ>64!hHvFtd-uW21tZnYg>Q3)>CdV{_~d3K_b6F zA~_C|SMan=DFAiC{A2tUtwLFr^^Oz>AGG)GXCvFF$E+zZ03N$uSd--ItGrSqoAqEU zD>mXRJ5kIuRv$Sl^h0-6h*d%c4;0D2hr_;wcjZvM-(Xvm*b_fg2^yE*5m#yTJtXa; zG`~Q}g0<5dT6k||WAhT&l6XhN`4~{NwY9~*abxTaV)okA&cThf<01Jh;wH{y;@nO) zJDe*m+#?8dWh}*?uH{D zQ$`Bk7;&_V%#|xwUIQygf5ybf$R1238erzkMZ_|Rz63dGw5ZI?%zBPS;7yBbwC3F= z?Q{$b#sV)BDVhGWc%bNF;^OWtv;Gc|ynGgM1(z_@!>H0A*QUaRt5>hKwYCoZY7&y% zd>}m9;T%M)m}@_d69@l_=??Z@?AT;eL-0ijF~SF5V`JkN2}&Vgugx4MWMmuxeNc6^ zF%3YDn;LhO2oX1icLOLoH*RO+$af6ZT3GB=_o;5G{d)!!$nZGI&4Xp-*jH%}d@8w? z>7$>BC-{xWg;C@W4bRM+z;^jczT3I$-(*=~{AFfrBSbm|w@v}h&J3cD*0yI}E1uy^ zOBZ7>Yd-dUGDw`REr@1)7JL(yo#lJ^>jRPe^=5e zrFv>AJ8z&9V#KE@>!Or}1ve451ZgDpw=;=~iRJQW#LE}d*!C4z`?dhpR{2C|!8WxAl#Y@1pNsyEUd8IGn>$kZrfzj89`fCbow;FqLsAIN zY%7X^fdT02=ok8vT$whLzkmOx3L7HZvL83NUgYNwPT-z$HOw?-+xq(YUK*xsj=<+~ z&|&bF4e<*6(e0s*5aVbQx66g@1-@z+jgn@(qgPN-RMZZb(MSCH?Jc=%^=HIE{rVA$ zHZ>kNXG9|wxgtV2p~W- z<&usm@Jsoxg-)e64z^HPUi^1RSdb8u@+bBnab%{b-0&g@T9e;u0`WOEg)d)zx3gzs z>8#Ug-%j**SQJ4ZgU=Q)yOvtpmoFCqv-g`sXkS&6`1i;)VvfPjj&K36r|Yzj_HY1p zpTrS#6Jk4G&v|2>g~ z2?kliP(4aq1{4owe&MUOw6O41aC2Hacz>F7Jwc2C!-sepyDL||Kd%Fq$FoO~N^BDp z65ZG(V@$A;Gq`tY&AJ%{1%=ewHRSL83izxnelY9cF)u^I80#jK7?decyy z*;d!CowRY;IJzxbLdUn5$|)YmG=5Bo3Bhx4m=hG~y=>mSCgmQNA-fpf{r>ak0z4jX zDy_dy7)ANi2qThQR8)ijS)j{0#3d)c$NoJJ81@kqpI3%aWF$I=OLJ)39(W+G9X)4& zWT)v4?QLxafM42g%lT^~+09*9>)rVCG;cCH>!Vp8$FtUNl9MnWJsAC}cwPt%vZ>Xd zfn{*iD|m@eOZ@z<&h0IoMM#3m$_mTJ%8Ve^;tmhII#1-; zBQ_yWD+Qs@^18052(nH@B!KG!bg{UyQ%IV)oFde>^c?k`y##oinUkYoGwvV~%ERa@ zE-C54SEO*8@2H5d@U!oG^8uuh(`oLB16Hc5qazovddus>o2Z)@R=N+rC@HZvm^s9v zVh2EycFuK=`zN{zB#)+i!)H1>(v@dQ|6-u~AvnIMj0;YU5uI|nU@;3nKF9EuLOeA9^EmbNAiz*^BwKc-?~3Zr)}(m9 zu&{v3JmIs&V!96}mM22ipokUwQBfxGBM@Q3hA6Hu&bD5O`}60|N0IlOK9Dw*Ii`l= z*-g)gh*$y(q_wy6c1c;;0gf$CqEm_hw`hIinf}Hviz9K_yT)nV)f*Ya9hP~v?HJ{h0 z<~@q94DXI-(=$+D=R{5SRyaEtXT1C{Iy$OFet+Ed3n#DEy`gI1wd$Zth9QQ||8fc5ukfxUxU!6yC?+gw?;%J*472q!ir6 z%*0fG{iYJiwS%h(SZ*Z)Ot5P{r-J$EGiM9{zBf-gC9Wfgzc2O_2l~A7low}NX{iky z@3xkfo78{p4UF!o7R1@p-v*)3#|&9983ZD>{yNK%e-k49lmQhDDdEuk8yi#AWB%IJmDkkNl)l}8 z1Q+xiA1NYk9Bo|bV@*J1w1+_rr}|z3`M=DLy;E`?4--=Wbr2Zp zw>LL7nnKv^J+zM#-ey8s?!8#wf#-N^#Org?bo+xyI8DkYuhDJUZQ|nO!e$P4kgNb# zh7Ju4wYzrh=kxCx{{B^E;*W0ke){xD)GRc_eDG-XrWSx!dI@(x&Uz+Q8GPi-+NyU< ze0(898K7~T3BvSSm!EDY{_|%w@6~13FQ!<=-{3@{Tu--?@*FXp=|2k2TuRu;h3UU* zRDBPDX4iB_7?9y&=qR8}_~L~r*hs2*y{3zsn}MfiNsjW{w{K(Lw9Yi@R?;4lo|`Xb zIf$ZsL)=^_folu9DFClgP+0hSOEC~}u#Hn{K)MM{+PQ04eaqx4Zf|X+z}!4cOawiY z0agosX7b${B4BV%&tUzsW0}N>$On+p(9qSGCr|F~_q4XoaCLWIF);V`?uvXvu=k02 zLlDH8jE{`WY>bHMQ9=ULZc5U(!SpS;xw#v+u&g*-1I6y$yUz!IbIoEmj*N=Zhw_m1 z1IdjYIRJ;>z2`N>qaTW2mP#Ou+6)!kC zR#z6)3>^^k0P!fYIN4?r0yp#S`L-;>w)S>QLbKA}laG9+iXuNRj+*>A05n!Bb@kAQ zeq$}IZ;o{50ufW~M_7NUlWH#Xcq{U(Y@fA1CBJBTA|aj?jg8r)|Hs6)!S-2_#c6Nk z)^eu6!2w!M@yi^ygv6s5nSUkIMScBTh;-U0)$+#d-CS8q%Nf=ETb?7z^CCC*azsRg z8=xA!b0vz96CA%i^qWYB+}DEP2z_X%+f!Ux4HX|X=8PIn5s~%|i$|04Ia41t>e$4C zS9}*XPfu%LqY(O35hG$92s8`5gliVeww~|Uu@>jE2FR9QVoz+B<|go7<~AN28tMSr z@j0ACii%VkSfRhJ(kTL|+MPLh@-m1~u4x!*YW5Ev8kHdJ8RiJ=S;H;yVfp?i2mxQe zs}$5L&ivLiO@XwBo)l68(B2GDaJ+xOr>n$l>u(XCjyZ*b3$q@^V zGtaB*>qGB_g~iZgzbk<8M|`c9LN}-jvu+{%*tt;vdd>(5F}T0u8Dj6L^zE{-vAJ+v zeLpcr#PpwnZ813)Y_`WK2v>-0TlnxGiCV|YOnJ-9aMhoI5A)0Gjs2G>!C*ff#ii6r zGWQ5lE*?G_U`eypi^x-_^WvE5rY3>E&qz;qVyYW+ra+eBsWzsp8DKmlL2DfksUPMS z6g>NtpFep4cFsurqzet+14%c}$jD6VBv6L|+59!ju&DZ976qv00HEX5+pok}x4e;@ zSu<)u#IaXY#CIUT0R_me9g3pc1m4bU$s{oB7cevyQT|UU@|MMPd6_fv@>)PSBa5&U z%|}j1O4>oFmuUC9b}e^)Ztm%1?CA+(a(AAhaYu`2@1G+qsK-oSzkYpDTdU9#odR55 zy^8XGfPjNBlGch0hitJ6G}hGC_G8A2^t%?h9LJ7*+`oVS^W5B~IU$l^Y?{v-`o?5^ z-?w+p^X-x`PB>;@U;swATM42BJ3q?I%q-QG?OT!&C!3U4Wc075^fHR>xb7(j39mq$ zEjnL8Q(b*`l-?yFPM0lJBr7DQ*uP~F+_Fp}f{7}3A>UDNit$Jy+$FSSk6HXDc(4QD zV`=~u)Dvp^x4|!8o*Mpjdp4318AlWfOtvsTe{btxO&~2upai4RlKE)?`cC1MlY_U+ z8L^!y*rcAGUvkqV!=A~j{_x>0#3FrJS^Uu?VHuge--Pt^6WB9g`PGL|gv4}}yM*+8 zg83hT$U7EvWbKjLxh+dneUD~DyavwnK)ha=ys(H!pGTi4#QY^g_O@{iclV;G=x8AC zLj({CB!2Jz42JT5Y5=F$kwP-KUlvhk8x1ibA?M4C!$<@hZ2NMdWj~6AL38L$P!JW8 zo_&(GIvE_^2}UW@rlG!xU5GDOqZ1Vsbz*9tnx0nNr9?9ZCBcRpUjFBWQ!v$76mZWA zvqK;Aq(|pdf!WPZJl7Xw3SOD*`EQH-{~4e)Xh5WPrJvp)^!B6GH8g;;Xzl3L?Xv7E za~IrYS<-Q&uiTTN;A(OB!jA3R9SS*-^$3TTUHG@a4M!Y zHXouNK5P(9d$Rx~PMx?LZm=hKA$&vxLyIe2#oLi!qoX%h2Vn$Xe>IG3Juh%BF0cc* zrKYnc89M$nb-GF!eW$COu1p}LcJ05g{_!&Y4uo_jHV9&sO5GX*+BZ`7%!J?w1z{l} zU%!3(7T}u=@c?QmA3uDU{q$&rcZ)qzdMF|saEG#ra+Mk*R_Uzf(KCYB4ZkLR_of>G<4lq>VGiOQ*!(4VE!L!-~4$_LP zG|N2=io&9zxU4hzaVP$>$Wu^W?(ua#8%7!tC9~$)k;caR+E3 zI)&lJhi{vp0zmk29)hbsI#OwNVbahN0|l}A*9WIqmMr~PsJ5(+-yV;}sW_oX!y<>@ zSCvADg)XQ)Z$wfj7ILgn^F5IsTqc2V-9d#B$z-Yio5`LA032^&`h*k{*eOti?riF* z2T24oH8r)PqBkX;Xoh=(`%uoAdbHaMk5QojB^|;o0@}UMDR6HqECB+a-sAV|v&re{ zE-3A0fl3Vfxp_A-UQ9KFEZVQPgf2}}!9H{j4i1)tj(;|BcFtpDWb|~z%n>UP8!_$> zvb8nJSCxocTgjl=yqIU%ko@-9hj&oot~?;PZA(da<2z`F3#JwpZ<&~x8`LwpQ=udh zGl3c=NltGopg!zxcLvPp`oE6)c2WMFF@4Qu9bq5PGOlu zkYulHt`=A)NUrKIVWQky42|*EMtQQ6 zUqgX{HXipI$Ig~moroo!Gw zJagiNslI;q%ZgHgu&ot@0x4jz(M!2-!}*9u~WxS2n!GGMN7kf#+Cj2 zD(4p$EsHH<*N#9oRHbZRA5hJW2Eb~6`SRhhJ@fPPP|3R<6fL@UYnsx`4-+a4us%dW z-CwBEKZMb%);NaVGVq`2$3sE&m@7{TH;l3$g)b-&j(PN`xG}Y&qKA-~d2K7mAxBFd z-9Wm!pi=AU>4`tME$$o{{u6cji6H98TY=Q%GJbzV^H>KaL|_$H?p=32g$`%v-)?wa z{ooc0!AO!DNv^iYtZJ`}=~a#CP&X;i@-wZrIj-uiG=cUp(pZNZ=-f?x0sS59#bluC zKxR}Syw3}iZ1H;^fr1YzaCw!P24(bJkZ?(fv59Z097xXj78>#ukWsh)Mu05-BlSpS zw%d(6JEivfF{Azd8 z(hAxcGVA#N67g@T1TDBA_wbPtDejQdq--5>8*tNNtzDdQ(|f?djvT-1>}_S+3rS^5 zbon=vZc(?DPfarDHEe%trd}Z^{d7)GjEtBLQ^p@84VMIN=|mA46sc5o7qft1>J8JK zf`K@yV|L>{6SfJyjye$%zzobnJ4!#kW zkeK|HuwIT7MSoA{_^*yH1PJ=P(w|It_|Vd1ZT2D1h(n#M+$F1>w@#Dt20%5yGse)r z;T))slhDOtT?bZ6CaBWV(m*M3bnJ3xd^=6u?}w~{?>PGv$$igh%`c>;9+BA{MsgZ| zG5R%%v$ZmSP~zgABTx;4f}C#Qdu=dpNMYfb%!~~3qkpI4j@}S~Yq1KDO8?V4Z^e_6 zGUA}_AI3NME#xg|tj}qHrpgl81%{~D)Wt5s*KGOlgw>7&*UIbzkTvMt-w+Nv{X!9< zpA+gHB#p`No%*)mvASHKT_Po^Q{ZcAT0Lo$29ltEi4yTAIwx}OoH4)8;M_R1pfG1- zWTbwX13<PTboy!e%tj>SLp)e{!y|pUYSFvOeNsK5+t2>&ep1i}YOnL> z5LAK2y7^8eU14wteehsUS6`n@do5_(#z#l5ITwu{Kvgm~au`hROgfN_Ae=*j+qSqQ z@Z$o}}fBIQAhHWfsr!Oc6bo zYHwvVVu!tw-UaSXy%riL7T(J@lj`@dfn@j)YTj4AAl(HuAmcC8NZ9JvunxVdW$en* zI~fQ6nH~O4lWXDsoePvE&PYkIx;jjfIj<~ChRhx9i13?hQq*eS12#ShJVV`?SJx=n z?_a^+yt%C^KNiunCEjE#KjVZIY)g~i2IGV8x&9A&`u_}ZU@GOC)= zHquMX6beD6rU!f{vby#WCM^$yga zE|nd={0Cs1HC|ij|bLy$wWtvC5&<>Eo~Q2*vVe7*^W>RV`HJ{*|MqCJt+TqJ^!m!OTkqm zI+}lGA66ZVB1^Ri_A<%lDhjSVUHX1~Ju1hi)(<|_3hDHO)%mL+MDk zm4q61A5ifUVJ#2C$Ir@?8AkV#fKzV|IR6ffGvR8%l z)S2U`ahT_?h4*`rG>~WvoPsLP%&}FJEv7 z$h)-U+1WKH!n?MeYTDVdih`1EeN5qd-ebq|pfbNmi(}h*+^>*hCp24Y8XpR{j9GH~ zgBt&xR18}tmW zT#t@k8&Wk{zVPXtO%s7B=PeC)yNv&ueQDPp-+ge@FTD96 ziiIxG;>z|$v1ij1SGezvZzu2xl%1RtF=0&RlxyGPD)j&kLJUJ=mBMOF2;=h3#CH1d zlMW8*qC^I8(_A5gASF0vZlVC~m7N6n_-5-9M~FBxKTXuN#ygsd!1$GCmq`~w=L zvi0Fdd%WZ!XHanhQJ{;~jh$Pd3+^FBq*K=5T%-G{Pm_NjeMi(CHbLn>Gd0Ck?VgAV zhxON3>#>!%zTd1oCs(~IhrK5j{nr--FLkT~j@N$a^?YeAO@{T?Vuq4KyIX8ZN{Uum zmGf{YkOj4@i(kJ!f+VL_>PY0ApVq9m`6(ZdE0T4h#%s(((i-qny-BFpTq?!S{E_ONJmtCb_sI;_2LK{ z)o*Rdn{RI$W@OPNGXAfP zfs=TO<4b60Xpo?qSXOc6>b$P5JgX5eDJC)5Ub!H=($lwUly-N8N9MQk%4FZ#)w#;15&CT0w|pOP|)NYYs9D5df2eAqJUx7ABP_s zJv$rBtfL%YzBF$2>mt$d#V|F#K2x!Sl6IB9rT(Zx`L+F-gpPrCVGyUsQ-6ydLg5)2 zy&bp<->p1P=}85i1Z7!+`%lh_&!pt~C6)=o7T{X4nYpNP|ymJ7pXJ* zOT8I^Z^}u2YeuJ(TRk!H{3y$jQy$vUSFE1=17XGaI07z{9x~V@YpqlPuD#665{#$5 z*MfLdOS1xx=QI)9eF9a_7*a<6acUa_(XVfV}Y z{75^!*nzbnleOB)nE=73TqQRnLAOzciC_%5hBe8t2b{1tr0!9pn3zEG>B!X$2ZSa?;I2;@n2tvb(<}Q3wRxec@?y-{njy zB%6|Abnjo_2<0Pc`sOodW4{G`o7;?_xOWt1quOe!#w~pVm~@Xs9M7WuPT*o=QxVs_ z?peN3Wy(LwCo8G-`n}-#tYDW3Scdq!)#aS^Qs1s3-9;{Evo6H!9{tRgBOI|I!W|zwLR*P@0^xSt5r5nseSZFSOR*^ z4;y^4;EssyUPeZ-ph>TFl`U=ovBpap2z8%dEvh@RhNJJMp{CAu=U{_;Ae(U?3rkRE z9UgTkJ1#rYJ!EhpGNPFs^^l=)jDtHHn)4pfBW);Vq@2Qrb)%zfc9@P`>u=zmgVNNx8-F5 z4>9K)s*^OyH%ce;-VPKvz6frLH95Y9fbovfTzOzpnyz-C347XeCj$3z%;>pABMDhZ zTxPv4FN~xxQ_MN4PdnG-^eKiy&uMeU{^+Qvq1waEmWUJki%YAcP*5|kKWm0{uHtn` zNQWf#TXs?Q!Gm#U$)F?ys+dr|(}`zIY1t%|mM-p|sRYyNO^`d+&xv1MUCrZiFQi*& zdUI;;=0p4Uqg0+!YM8crzt!Ye5q{#zhDd!uh7Rb%9*O8DBBH0dEOH)L&+eB0f9^$1TwJ3?c?4+?#Ke`{%GUAJ~co>5bP zkeF!myOW#UnD?+Tm0ZS7siOR1*`O(}cgIqA?#Vk*Yk_mfq9enCEoFSvbI6=W~% zmw|B6DKM#%S#Cyc<9?JGZdcx@t_xzZim6dE={4vgR+sr6!1RDirB}mnhc$`6!mCo+ zIXFBaFe%*bO|U+>AFu4J5O!_J)03hcZP%ktNNz?4vYiF^zMvWr?;dy1Az zIx_BsR=xmXXTB1*ww6R>;z1P~4OPVpU(@M-R{fHw`gMUH_#pAtp&SO7qhdoW>+>JO z!*OqxT;xwN9*mdt{I27tMej4B8l(bs!_g7?4d3Z>6@M}KHFQJ#E_1z#WxG@DiH9-= zc;}$HdrZ!(%VM80AXcVRpuC8 zk7~+~8ms%KcY3u~byv{fg6g$rtEQ_5w8G2ya&J|FpRMh5J8hgc=L3j4tjm%A`@a4A z?~12ZR`vosXqL86C&kcRtd2a-d$}Spk)1EdsICH> zblvG!C-wFwUSDDSCh+?NcTpgHPZT;QVcv*F2}vd|+t%sWb#!*V%+1YBe+SwsgtY87 z77!GaSk(-0_Z{tHC&JnOL*zZDd!Sg=+KTP!?#_p{;gG7fDx|Aso=XzxlK(mIZVhkA zMQN^tS^weMqElvXwAUcEyQxXGS^oBqz?LmJ0<0fBCI6rHWV1>0ci+w8nJJgFF$ynk z2L`5WZ}0B5gY0dsB%t)prWWAf=@fCG#N&8~od%mg-Q2iZ4l6!)*r0Aq#jVkuyWj|c zI_qf{D6@EnpFG(Q8Ab4TRb{0E;T#(^HeQpFn)~^&AYGGXedPjqq#)W5>pSv^ka|GH zt=*lw{MgTmtFDfnVMo2l9 zA>}hnCo(aXM4@l+h>@*sLg#xHOJWhFxjJTj4U}x(%8Pb}b#@xqLRa~vccMh0+vXgI z9a7mHBb^e9?>sKB_dDVpeFhF#Zu_D>#5V$L$*|9!HKg#>_v_=xR(}PKJ4t>)^Awa$ zY9eCJs>yiFRA)r92?Bq_6m>A^sXlkZTbg;QJ=qr{v8wDsv2wUgypmXL8v@F8?NpDD@kCy^JE% zTm+>HET0LBAXUEG`iZo72BbA=cJ_LU4Z_xJ%&}SurD6Lk@pe}uGQ@I?HCST)nOCUd! zUXbW9?u+3;klLcoN^S3NsI6_*+S*FRjCq#%u2Wx01u?!w73t3Pdid~hNOeU;&9>4M<2%&C^kp`{BhCNbq50I*c zbyxrUH#>Uv9oV;Trb&tAZ@}yqz+Yq(&~8%Y*VMT#(Z!N_wx!G-?60RpRiUB4!vbM^ zPN&ogE$d^Ya}EGdicU!I@3HV8l0wzO==_yX_cPx6#alaArKCbA%-MR7hnki{ijT4XdtC7NXNKL&M$~X@ERn z{P*vlO@!G@^Y@xyCAz39FCR>BjDS2+B1cuF_{&2!#eZ;Ho@S)tk(+em$|;KWA1BPA}b|fOH*u)gt?GT9#Ur}F`f1h&5 zmcfQIXhsdj#j)~O>+~5K7{rc^{yaNf1B&Hv34Dh>sx17g9Mz<<%%g4F5WR1I>K~PD zZ4~p3whxV~zVjD@q~is^jN;)Y+obTW8o3;OC?-;wFyx#jWBY3h9y*xm8bmy|%*F<^ zM}7Uy|5jo^T!eO6HIi@-V2*>(i?mTcNEyn>us97KN*jEIuXygxj}@rS1s7l69$j7C z*r(gM+2$4&N{edd{?_!I9#l6qJ-8PVB9E1Eu(EmqUDd@>J>A_d0#}Uoc6w=2O(f+& zTM+ZTC)pmdh>q)1xWvl7_=)UF{4@My{07GkXj~dKvz`;$fY7=dN9G-2S)EWh`o!vNH=#XJfkxfrr4-uNdAO5XgF8s+K<{zBy%{2~{?~(Vc*x8a;&4;H z$5j{qV5>uCav&*Li!(g8MO}uoM7vzJ23?CXFQ{mPyQV=~XUP-$-eYd$!LP$-j1L|> z$aS7+e&>Ex*C_aQ_LIQ)g&b0yJ%bMln?UoHCV4BNyHKTQJhc zn!~Y#Gb!yCu->!*gogaW!nd_S*b*Ju3*3uvUYQPZ8=QV~{O>_DrYFhx#6C7O6irPz z@cDRJ&yF1XTOr!?i0BKLvb;dCs2rIqB?xktj~7G}gTj&?`6P8d(6l;KS7i0m{Bn13QnA-Y9Bjx;4ZZRyluszZr1=2)s|ng|}l_ zMRnq&X15J1#I+R8fB^ISS4ZqI-SB4wYGy`8ZprvKEIolZ&lgx zl0S!Qm6Q|PiLz?SWTeU0Il|f1b>40|9F9bcaa@EV$NdXeVujE?1i|}Qg>>LY>-G@1HKlTR za1ebU8v5Wd?CAXYtitMhJNXMICMVU(@V&OQyLKtWr9rK|qxKHc>;Of%iPH>oJmjQ1 zDE{&U+3bl85i0S!`dkeZz>-Ug7knu+*lu756mOwb+}C&YQXb!*lP6BxAJcA%4+isg zZ!&LW{2T6}DS;Q{+{0XXj*yx9RXTvxiW|OR*c>>MZx7V8y0CJL-8F(=O%!-Qh1Q`g z*V;YrI^LF*dAi07*+vb@a_Dw^e#P4(a0PC0l97?gGHV=PeE(kQiW=2x1R4bwg%Vh-x zLtJ^sGK?6xat@S=KBY}qZr1fDP@ZS+=SD!~X~Q|;OPHL|Qug$AS6?Id2jPTb+cI4Q zphCBu!_)I{Kh-Xcs1~fOR9sTr1099qr;s*u7{{ojusvtL0Xg@fkv@eHsStvjH4g<- zSBcw)k$wL;#{GPFxPk|6duUr#_pSVL)<)X0)TVO;=pi%){5#qCQ*xhTt2;ZNsGUC_ z>x!u}0N|+3ErBg0-9v>eu^=^X#wuWs_AxKGWlSHEfx{UdPWF#o z60L>_+M!}61A;UWm&xQrw7c&V*Ouc+G&Uu!#PR-RpA7lM;IlLt*jE)VUYyXr<7$}#JqapM8 zh#9a0FE3gZ?e^8!i=6smQ{{vRR|cGlNYLruQULt0$PH?q_8}qh@$vbU4fn9Zm2i_s zJ_9`-a~~b)k@&$Ym+8CptHA6UM47zlHiyBBKfNDe zvfiExBi=7j24D6P#bR%?tF0`(X+uCMNRZAHLn=6oF&vJDO{>&Llv+>aF=&7G&TtrD`Ud zquNN9E(s)F5@bBp)6o(1+cOV3x=YqcYTKvCMK^QH&0aVP(CgXT*zl<&lB5{hj@LA9 zpbcPbRYJ6qODkP+k32TA*tm(uhF67+k~=?7IHAkp$=Xxo#sinJ=0Zb?g~i3Vo)3{T zl@%5CfN|Qse%)78wk(lip8vi-@1>#TW52^VsOTC@{6d&OkOWAC{+4Nw{lyDt`IMr0H+o@L91PS*kQ3XR{I)a}= zT0W!=4R#mf1YV5)@H6iQAll(aY^5SD%PIcEyJZMl)Vd=)Lo|chQ)Q$C+>-uPH|_%M zlc!qpKKvF!Zg@%^6w5J0M~-CV$d~y;`@vVJ(CZXoC(mKKslXFfPki~*op3OFv5C;n z#-c)a=EdA#2BB@wAu#fQiwmsUOSUUQ2)bbV&O`83H6Wc5pn|R^~98yBIE1 zp?G@>j{qbQ5c9041v^(_C~t*VaO?olkRxOp_!Fl0H;lA@7ar-^#Fm4`IuC^0M-Em) zwP}IIhxtcXP-Vx{7y9lvF$A0Jul4q;WX` zm#$?GF1**Qb;CMn?1kGY0A!5m)EpHMP~W&$t(h+oZ8&M}0^Q=TlS^2lOT)ZmKFH43$ zMiUYm3fC$be;L3Q#C31WRvnjD}u%~v{k&iw)+BugA z0Lm{;|80~y`Rb%rbLrYbdh@mNJ4LIuva+xAlORK$HGxu`&xFP%YEm;a;I8FnoAnD8tGyQMVZZT|E z!j!ELOfPt(_iOq4`{VZB5Y~aVSK+>ph3)8b=g!%|O+RDjOOq7lTMj%TBeH66sv0PC zhTK4;tZdc3c+oH~a34U2ajqq#=3xvA&@!$%{)(xwuMBSJGTASy>_~`C=}}VhDLZ|L z7Gf0Frj3n_gof@Oo)3iIeWc+c+}1NTc32j9iwghPHM_yxbaR}jx@NU5ns2fGv-P%A zLPx=T4`1Z%LQV51G@iA^o2Tzdod&;&K922edl{ipzFig<*tM=m zD5D<7veuL2gw^vD7HzvH{a4D07N*y)zUpNi|L*zS>i?1T-SJfZ@BcYYaVond(y>LU z?3rVetcZ+*%AVQTq)0`GWM(C@_a2oZ*<`Pz>`_+s@48X%&+qs9=ll44dpqac_v^mK z^Lk#->$)?~<>;^T&#t7|+=*DK)u!Do?(R~d*z148IO-9qfpA7xG9V4X`WkwiI1HD; zze5Jut!^7@f&}{r?~lUB#6-Qr9esVE zNXy$tK<`OOLnblO4k$rC>M0TSE;CXQv3|x6U(D~}aL9voBWet(l!Lwa*{f){+@N-CsC! z5#w%TIOsX`OxDt4^^a~b$78!$C49n-@Uh-s8*0(|Vg>w9Hk^KMyZ_#(Ud!p)UZ``M z)v!MN_VYbVP}Oc7UveE8G3mACskrYZFCPG7KuU>OFGd4FCt-)fq;4HoSE{CK4>pco$>rOe}e+Y zzZKro>=w*H@f(ZgMDpV6&-Y+$0cGp3!i~DNAeMDHiz7WRPuAw;WmHrQ$P<5ERcC&s zXQ3hj%&Z7UyrC}h4;iS}{nHv8*d<<(fY3R-%RV{rRe?{0mknjnrK#vc<^_S zHt{GXH44_0-R(ji?6Cirh1RU4Fm&awcH_r$o-c#H0?$FzT;K>Kc(< z(=kQmuusUjb6FNekbT5-)%WB@J>3$ENGIv9bE$uMvU_RtI#^xful9pCvzT$brKXo+?Oik;< zVrc04q|HDk!(1*o;kdgrG8(#=R8^bh3 zUY^@c)59);S}VoXf9mOm&&e*@)$4SNGcWnP$`%?<`esn<(l0yJ}cVfL2FV zMT(f`tj-PEJ1Jo|A<2~Q{0yTok~45{Sb9%0Zs`${fcaLi2juR_VKovPq$O4EKMm~# z=2%yECPB6R26_`Ly}WunqRmBZ1XkF|+jVQ+3)TH&x?emF(PArMGngg@>dSuEOQHS> z7KdddGT2HtNcpPv3&|QTt*+*`@>0-MuZDSV8>indKk|Dy>$Pdq&)KwO>00NxDt4`x^-5~)yr;?!b+7-~BXgfIr?AinM#EGI zyRtAaK=RIqxK&Qxnyl53yK@OMaeo7`W=sLQT)OYS-T*eP2DEUqz%QoE=SqYdg|}v* zD>BZrw=X=EfXV_o8dfqBWT^3j1-u!d12=lVkBvq5$Fu6Fx&VFyi8pM5ikqqz$%QF_ z6mLBfbz313q~HFyBkiVCQa6K@?HTH~M_)xN+$K|2^un0>L|Na=V|-ivGrVoLmP4zJ zbZ@utulVl>d_P*1jIE3F{3cf1em}GifEtmyXJD=I&nXQL9CR@Ir_vWQ$J zg7iO*2HhXh*>?$4DO^#XD@e9@R(6P*8Zu16c+AAVMVsEZyJ+=7SW|m^XRx@dcW0Zb z@*TAZaS#_e1t6Xm7LWB|uKm8YKSy?AgVI zh0MpUGxtJ+k<*YVZ1ezn0P)<7pAYEhgAe<_fM*Y^SyETCw2wTD??a#zvF?&<*xqW) z2s6Js6u?6k>34Tc&p1W3nT?F?`S-xfnue8-!JSPn5#eF|%>lv6=BHvi!UmU$QGBqqT(& zu%Y$85y_Ir-rI3v9_u_)30GOZDp|dKxhwqRXI=ocY5&mB73VTgLrl-lSEq5_r9;Ek z*TJTtDv#*`WR?sBmfhyhi1ybKz-sPKCst;v|GcX9>}spt39noEqm;HGtVFgKZRA3{ zf7b)ny(V9JQktvW>rE;LkFWPdbk(mw8>v7^>0@DU{O)+2& ztk$gGPrz4ltaI;7vB9|gd90+M>pz@s+=bXw^9o#R!~V>83)f#QfFAV?0E;g@Kr#kg zMa!VOT+!i2PKIe28AtgTl4K9~gkhlSi^>x9ligdIo-#wr^8i1 z5bd;g@pqrqq_2r?T-=H9QncQw_M8myP>_vu6OvQjLk%Sa1o#%!w)^$4SJJ9GXb4gQ z)5S{y0;VvTDYkmxhXLD3--TD;9ox}rGXEM?*kEx)5%0FW>7q{NU@LL*9O6W8kUxvj zlzE7g!#(M_VXJZD`3+{Ruc6-`26d1;si+VE5b1cLWYPqQJSA_vuiTl)m$_%UVSc;^ zOMW-s`$Pbu677+85_4Q^Y~$a<5?L1!gil!g=b{P8)>*L*o3m$At2{px>}5UgI&|0w zpk@WubDF~Ur{Zk2sE<^M@C7<_A4K(8X_n9V`9D572&2shE0d0-Av=P;CKl`t;_rTb zM3{g%B=vMTCm&!b7TQ;#yGOo>raM}yoc2ycuUF5@zK`$SP9!Z{E@oC z@_!3Xwom-|W8-P)`+WF3dU1A@V|I9FQ__p>!=8I;%qy~SGtcjqg0 z@_ukecvZ3vvn55gEqT7G?8?aH9gq7R!_ibZUNt`GNcED>DyrkwAEMq1i>pt?2jY<4 z3Km|sfjfXA_db9g#l}lNJ>;LAsXa7pY40qRk|=%vp`DNw4EH>=!B zFX$AVzinpa{XA7U+jL-rQ9};C0?UD!*p`T-T{7=0NGr7H=FIX`dU@&H>#P+rtI)~5 zLJQqxTXJ-}B95jGFz8IwY)@`dp;-sZAU#s}{4sZbnPYmUZfQFR(N8j+{zaq?<3NOmj(StWSNQ-2FSeI}bGU-)c%xhltWO;} zIU}R7ugJ^}xEZVZ((eJO^5Ieqg+t9*oNi+A!Gj_fk{hq~M zHsR54XHU8n=ISWV7-vTFU(Io*CEdIJdL@)Vg~@nDYkDKqOI{0&%w>&b;w_n<w8!&%jqvpzig6He~?7*l~^Fd-8!BFaFHsR+eXl!)29z=Gx=u6=T4Otd)ar#X>^u|cRH$& z@7fqPm;-HC&u9PhTEv#}r$cBoc0nIyKi*sjyZN={!l<1WM&21TNP@*J-n~wJ-IaKz zC-*~`L=2ec?oVU+F>-fVRLf5g-^K(qGhtQ#pPR!T^9iKk7YZro`cO-0=WN}P5*Qv4 zQD=9`i2i`jd4~AmE$JsG4lc_nP3K;D*(o%ZEdTue6s$I{bZeF0cZ0p(iN>7QD*sAa z@!c)GudKr{-%~WdTxrtmBpsz-w8F=fGftDwJ7&M9?UZI`X|~L)eIe?j@GaGE{wesz z2Js~<`B{R<*Y%Ow&9jfQ@a1_jv}dmdHK?IrZ9AFkPd&CoD_@DY*s1u3 zM~X+r-wpsmu|Mpb+I`YVaK{ZAaU8Y-U1Zri+EsVi_w&-V)+_s`?uK#aa*T~#TX?2X zY45Dax;im5kR|vw|4dJH=iwvf!;4w{H?6)`=@^l1+lOQhUw z;BJ6nQUQ6D{m;hBMhlD2U{XvNe;Sr~i43iL7E^Jot_NjavH8~qOoM~H z6!JJzpCCq00^#X23VK~mSqy!atS944CA;bET)U2ZGbrd}Bk}>iy5ixQIqZn(hvfkS zThiwfAPc=wA`wak)132s=#68+SoRk+QNNqmkf-6lwz%D75UVCoypO!53X@mp{9nO*(X%H^am^ZlI%Cti;2KEOhAasbEz! zyRPWpfZe@ZMkiU32YxRAF8g8=-yOx%J~c#YRge8iX#AdQx3j5H?Ek1OiZU?sX6}2~ zAES6X&r~vzDxglgz?5Q^KFs$3T14r9ZF!yY0Y5Sy0bJEcmKooUa@W#}Q? z4PfKlC%{s=v1DDq`o%fxcm zrVsek5@%$-EppR)Ws~h*{=R7bk#*Dd2!RpbRPtO`wxsRtKzkmzKp%I8c(H`#-)6X{ z(kX0+$zvquIw?!|t@@6sAm1b+3D;+m66M441cxvGQ6Q;wlJY-O7dL?IqeT$EUJ5Z1 zedM$1yLs!@t!s6vrw}88$BAScJrpJS>R8rMZYbF@@=picCL%dqo3egS+@2O~_tKm1 zLt~5}w<$XLb@Mm*Cf}@SVTJcjMkf}?UirE`XHooZ5O$PcFCHE6QKz_Bd8@pV-!{|Z za^-tt&VIu$9L4=9R>GO_;-VZD+6I+<$9wfe6=q(FYHPi6l1`gCv@Ee_(0Pw*AhTJ$ zyMK^=BY7syV}0rJTyeg6!^BZEHdq3Jm>O}!+r{TN{7K4Wg65VrWA)v03@%5XxS(wa z3eq5f1Fx^ye0>}4_HjD-R4&C~Fj^Po1Ga8M%9jZr;2JP9eT82z1I!M?MOHd0ZjgQQ zS7zm_<9-Lk6A&BH6KpBAMj0A}MMQiLj(xcJ<00pyutisfR*_jpO7MrTrD=_*f5*D_ z1a~tW8z3HVH z1&!e7THAkL)hmwUOjS#{mX^C~g9V69L8Ki=;K{tfV69swCzBS*>xEFz`cCmb zWoMzmHk;9PW~`Ztb1ac2?OGSf3({Td$0y^dsx%{TEXh$*^Etu#} zUN4R6Gq@O1PU|A%G;_+9xIvfkRz;R$Soom?Hz~toy9vqX6tP^-73VqKVir1f*u9wv zFNLsHJMn)3k3DdM+eE)NI%hLbl1o+cJY2-HiWUP8P>i5iQAK(FP6@U)}n=w=JT!E-J3Xxuv(~=fVK+F_^b95|J1hsC84CaVOw^+#^ zCJLS#$jL5T@~I&i+hz-+#FKUP-u&^6>Ole^nEx>Xa&O#q%!6_=%@@C+<)8CTB&{~> zDC7thFxz}HzKJ7ykp}q;E*9-H+h+v!T67~_BQo!e!*o{@By0xC=j2r`i$4c?WSOLq zYo~zEQYF;o!biA>&uit?mR1nS^cPuWO8S$2HoY&j`zUKZpx+CAGNTHAFncvn>3@^% z{`CdZqC&V*0f;ubE>9UX=!IZgu10IaFC0$Zi$fS0TkLJDIoRyFsqBi528q>kDLdU7jbITFxZcYm#3soa~*kg^XS=dODX8EEFkQW=KeodQ36;wACLBZdbgXtv`Gkk87 z%ZU+)Uh1qY(H%ue_KLf%&RM|%h{^d=7yf_O7m>kHHyaVNet)3SmLN%F(O;BVmwHJz zo1)d8+-iyV=rxMP#cKeEkhh`=7Jg`=9W=0H#E_SNW9}&RPOT4-LihHgzpE z*c{vMGSPze#^jH{eso|1gZJ;Ja5W;)Dt^y}P{K|#mrBo3{QW+r2wcH%E-bg-K=c+bC{koVM^PlrAI$^2IsZE-%+pCn7RI`Cgf;Q^spr$alW zDhZg0j&6GG`?x4#%b|*1ql?5(0ldS;N0%s9aqdYZ^5T=tSl?jeuq zIjmzfu^NEPHnw+PhM%RQ3U=|k#)D!EmGhWve?3RXercuW&NGpekF8wLe4Vzd4n3lq zY6^J4ac)463ZJC-_ZGRNMn2Kl6ci78_8T|HXqk{LHEup)49XGPnpCEqVs6@Zs0vve zO-n)7G1KJuLS0d3oA%^@)%Z)J6|C`v9GN=u#c7(phe*t~V^@7wM-EUFyWMT4wwpmi zA~Mz~vP^S~-xeS}BgC`PAb?bq;Qb@2D9SvG{FizO*P~^phvrn>kJ3O4vqN%-`~3+z zh!0ZnoZTxm_rbv$*;rToNN6M|;Rw9F=N=j+{tG)o7NkZM3GZRy8*9EHYVln{A!Z^D zuasfub>#R3?Si|_8UKuG2z$xpw_*8A-j|v5?5elacYS}(W{N+_>dLuc1A@As*_*<3 zP8wUzR4H+>)eG;B@EOz`u)*C9+xN<&RH>jUhotp&Nusxf+0x_;{|73`MI;*%W381B z%dmeoL3}Vr{yED*l3duph|HI@NdAMs$>gopwgGR(cv9!TmZ4Txl1EY?iC`rGdzcW5 zAO~$rl?p4uz&!h-crES^cu3q}KN$uoyd;8elL~%l25lHePZe16Xw0wj-mlxv%EwO$ z6xUrLqE+Shfe~#WDyAh)sIc2x$^FYh3x|9*=BtOTtJaM9d;BiA>HJ!-&$yLdrBR(K zLR{1Q_D7M`wn@=sd7b$cx8I*xXYU{3TsU-I1~3Ma!|E^jz=oQBNH-9J8p|9eM|CrH z)5IDMQsk9JhC6cS2rf)m+!DJK=6QoGj(GP|3!FZK#u_cy69X^|sgCWFlgY&p2-h(?o|#N4f4t@m|G| zM(&n^llty$j(MgFX&NHGCGuTE_yshxqpWYd3Mz`7K3RUJP{ZlZH-D2=gUK^{_yDU+ zY}u3Z&X7rV_XJoG^kBwEt#Fn2{LLKf7~zn(?;))unZWDqEaCgkVHfMo=P%DxXw_eo z>UaJ6^--zoSHop?KQ0X)x3}$@;0BXd#&uhjd8U6U$rCa3F^ zD96>5SKfRgO;Nn*KlQ5O<7?KJr%hb{J;-`56lI~pKo;BDxmfFQT5lX0^{eC@!SQ|1yMfZq(1UpT`PYT0*7r_zL1z@t zHSa#v(rXCtX`%Cg{Je>=94z}9Fu=jio`_0n3TUvdTh>)CVM7xX`#d-w5<}d34c9zt zcegv`4WPiAP#fiymM=kO*~7O?6s?Zt*?N@&%jQX>j2UAlWVLwvAN`tI%a1=heP)j6 zNqTnWw6iEJ@t&dWehA9f2q@F$n?)I)-LH9ZLC3PMz)YN3r_lTd-2mm^yte7@UB%68 zuGx@pDly6`Sooao!fEX=p95$+A4qAsFPYcjJ8LCy46CmdB9JZM>i&fQ*9A*qZMDpe zI0^Cvb{|-g+E*JuIUIP&Y4`<|`9dLeG$ zhT7$`D*Ya6IQ4O8ROh%1+!@j;9O&Ab<#Dd4ouw=V_uM;i!#MA!Q{cWY)`D6Ikx#3V z;|AysGCjT*QPU945vy|X(o(!US(0AfFr90wJZYv@cI+1}1geMa{?Ql{e2buROr(`pJ7E8b<} zfpDJv)@_~D2CXbQ{La+c0i=ei$w$}MkM*Xt`1wq0ZEvnEW+o;krU(O3!tlYB?;5EG z+~<3Q>cyaZgor1;c)Wjr5x-vv=}H?W6h{v2{o=xTB>I(qG{p=sKBN^cG#vy+Nlto= z7I`>IRPb;*I%LO@heHf=6J-|fU=ysL$XnP=xV|z=BN=$?q4z3r{WZyy(>{NZ=c@Om z(SlvRZqkPLziQ7N9p|}jRz7n7NQS4X0*BZg-S(Ock6%*#g)Xs`TPyu5u(wOZZ29^= ziE{weM$x*sS!zEX^;BU~(l1NUU)z zn%ng#xRf%^?|?;jmSd!Qka!?{a(0s5%AmdwKR3Id`D@bAOtpW0)ty!3C-qU?^B(@$r&c{V37Qm_t-)G+Aq69d zg$si8gVJ=3%)H|q8a+X0gm<$ZtZFyp8naU3QhED@62#l&TkDqBT2HI8AN41hNXtK?cqwR~QeH~7X?GT!b5bGhZ&Z!+w)S>poH+|a zwkiJKArI@xeCPqEeFiQt*A`&X10+9V{8ABzW>x`&-6&cwhKCQ11Cy-FFN69x?xGl< z_4FoeZ!I!ziu$qKL#?}x>HN{z_4WqG^gyZoy0FxfztN9L$^a@&&gd6A3d5^a-JpJp zEfMWg5q0I%>sh>O;k00rBzpdKDalURhoYv9TF%ljN;g;m#`xmRUi5_9PNTo%wqn__ z>?=Xta5s_GZzk|C67C_bN z{JK5N8u(Utd$frGiLiBUPruLuPBgio1`YK3p$=yZr}VRQLQBYbH1D zPOn7GYB_n&t0JrZvTHZDa}D01Sap9tJ4AB2r!_$`-$-DI@d>8>p(CUu#}$=x^}We) zAF1TJcP+H$Inq0s&)WIf7F!+?!&Kj~ce(ZfZU{X69LaqAV7wtfp-C5%!e)tF(%vV!`0eROEo3`nu#WZ~R z!Wg7$^rKzAEbmb&8-(k72q8)aLm^PZg-YO13YZHX^gh;LWEnte$)~-#iZoo9SfT`M z6DPkVdcjnM4zOkxTb5weh#hE)J^%88>l!8bBR_AnE%?k~_P$IV{<+B{0y*k^^9{wA zE+*Dak#YuQr!^v71MOk^7Ewu0|LM~mtLwu%Tl(p+gS&41NG~Br$8u_n zt_O9~mloHKsgp05L`LyC?3S}fSW8@a{Co(BSaeyB?>Yw<47r#O6s+YI_df;F)ahen zC9ogR4s`xyS7Zj_z6HpuE&`8=eqnAO?S0~K*lB@FO9t{}FZUBKu8Jbq_e-L5`=3Uc zzgmDN*J$AVDeV&ZC%X2?kVitYbMz?Qi}W;4J>H*^e1Vc+C#-e* z`wLV2sG~mCdbM3Eq%1cJdJ-?rYhCZ~<~woD?a<#KkNb@|k1y+V$mB;@zqzcPY#`wU zvlZ@gswzQTwtVHWg6S_A=&atDE7vw+x~lf`xJQJ-%ejlDt0!~6#NM##I?k09@<^{& z%Q2?qN9Ec#XPxg^8_Y+IHr{7jZtZMjLSfhIAgb{9Y<4L@RY0Fq%rAB77_D0}*Ak1( z7~+?Dss<;kSe9|}X`bPH(fc7{><#YRvJ_)Rr%z=p2sm>-I_CRGjfwuu< zjCDh7viG9AYaM{kcOKV-7NTg={dfDEA|-u%VEL6_We@r(v%d%^c3avRtYSWXD5STK zlq3`7NqtmpfM0h1_3@;5^R#xk=AjpN>7DOY9t%9pi%i1+dt3-fTj-4wo+|Z%6<1f` z>vhfqw-4>s8m{f!0V9|DD?8YSN;;h~B8~V5?)nB&bF<{G3jq4qzi+rZ<2l#my0czK zZ@=UA+Y}K68XK8VKod`}cp|8PH!LjdCTNkVQX?hzaZazS0ibObq6n2Xpam=-^R75X z(IMn%Jwn~*-@QIT3AD-$bV0~<6glR~=D|6Lxhd01jp#h{vWaVZ96^fmE4_5yfS|FI z%tAS^9_5Y)_mZhI2`BW1#e}_O{hBZB|J-G&R?)_>&(CA!HUa%O-(LXUGAir)D2dne zNCXN6eAzlU>$B{+KKVvm5jx|a06J+-k5lG+DM*2;&B~C2jqUF6TA#o<)pGP7c%MnC z{e7|lhm4KOn1?)i(zk~1Wb|%#*9lAYFAd%)a``=MIqb1oc(HnuYtB{RFTw1yMAhnu zu{bn2uJojh0ub$)H}2;imWb*bhuSg)dON+fc;jK$q; zJ;zMcQggH7o^4=j{Z78TmLg&KlNAK_q$nArzSf6_DWyB0sQz7pvE1uYEe z!MN&sgR3?>uhukqZr46~v?{r?y;>dnQt$RMNVhD22bsKLUcI$qpXi9`UCs*pkRUO- z305#rwX?l}CAx>{-sC?$Ehr9qfYVdHK75zBZi=NT$R$?IF@h|y2egLr4J0Nc$f3U#CFE${+5)|%nXKmln@HJP{quPnlMm9IjCpd? zKyKj8MVoz2B-jQGJSTpNW%m7wG*rBU@2gIH+z&)Z{xXyaL(CTH$S1A9>p{6({>WgA zy#(5{j}o6fI<5+N?kfCUkP_{n-+n#?@LvG{lFz8&Sn(|t(w}zjGlS*Dq6;;Iw>H>R zH-1Fu&(ZdKP+YCZYMG+U@wYI5D!bVVPj6dRJH1}5rybp`;1Ot&=?P`&%KCIR>;n58 z5zmQ!+~;vnCWzKd-)pPzPBNR|@71oaho*rc--3Xw_bqG<%y4N#{h*Q zId+VNz-p%b(8bp{D6%uZXpGMHghnSNb|a45E(ZfuecH0RWS-R9bhB5t>4kx7O()m!6asR+kfOl8n6MzfJ$xJgj^QGf-5P;{+!`m*m zi0!!dd}ksTTc1d>$ojbCL1UBp>dN>sJm+$^Xb5b=n(C$5tQMkr-GP*;UW-lqS?O2C zowtO;Qt`8Mm8(NeACGJHK;r)%6vDBosqgV)doX#&R)c5EA$_=D?&x@b#AdeD<_bl> zR&LE1dthJsIkGD#FR}+gBX$>8V4KhmP5F1fy^q%@q|VXGH#VCiX%dgOMsdBvgx`?w z?yOQwTKIAnVJJ*EspUhVlF^>*DmXH9QhQ(mW_Uui<4^CW;&tK-{pu^D@2gxHyPX31 znJs0{hgGd5Fhh9=v-s96uSyM>0B|}{5bI{VxT}`+F!@wdmP;ak8na473I2AfVL<$K zVU)Qtkq=yk;5%)I;)BBbxvkz2WhbFo#2QejnQ`;m(3U>st+d9q@mDtBQ0_h7uB?qc zU+L1ZIT%jOZym#H-pMwT>rZR<2(&US;cY^$c+y!ry^FB?6UxnU#}#P2X#wdykPfxR zx#0&X%N_xJ%*Lx^wxI{u7Rpq+j{u)lO;rd_Do*?;)27(QO#WcYH1GL>Ll??!erV_H z%Bgt6YuVfHlo6{o{Ud$knb&3#-fgz9)N{SfYwt9?O^EB$@LEHXR-@0YE$3VJ&sw}Q841StfVs<_PPE?0<&ee>y@&w~w;E+Y$%5q`Y@4|(+MbQ@=+_GX& z0qQctCp1lhJQ1;v5?0+$bh#9Gz~*l`B_#s={j9c(hEQ@<4u2HLCUV7Uj%rcsZdd6{*@is10ZluFkK%K;H@vag*_ zsflkAqifH^wtE6Pmbch1S5(=^f=5EbtPm)To8!%~gDqSXWu(BQ!`ivRsEB*``#hCZ ze@2h=SGeSF=zb42*lFO%E`S!T|LkwbFSEb{^JKb7KlUXRs+W02H>*3c7kt3Q?4EdE zGbl8>qHcNyioYt$NUvX~_5ZG_gqHJU>o9@c)pQy1juXKKf@Y_!v5ocDyYjIC|1 z&T$hwd-ipNULNGg`o3Zt{dCfRKA_mmMahEGH-KW9t!I2zke*f6u)Z`&rB+VaytCe2 zT?CG%16kr25}&_LyasDu~| zcgD`A2hQzR$JlUm7+%IY4r;?&(WQ_otN`_#n|!R>0Rr-GIgT7(CKdSy4JnP!eM#f< zmXGnMrI0NlxfLRjH9zbH3p2xhVSX>;-MaD4(n36GuPkPF9-h>LM%AZYAi;D8p(|j= z8J-|DTlI-dc;-?^VN&hHuTPM6tSQ$w{9~r)D;AsYrH={hIVR*$=(sSNEApwEO5&jy z$;+s7sDn4id{gh$BTRy~Ou$aQ`in@wgZEvK{KWxuOz{V;0z8?lvpJ@|rklX*NXt!g zbuy(Rl8^>PWDrRUOUySQYt0yQ?$nWvpJFl@m7`ZxgjOiLNkZVd>J@*`69nhrQL8n< zFXf_ziEStmCLWMPiGFh^2}!KMTqvMiR{)NcD>_paei>A={r2!= z-{m@5sv>+qOQBQfV}z%ma(lzox$3p~{cIK{px;AFjk!;`d#movD^K(4ovnFav?1G~^r{a?kBG3qn(Fnh+1G+LwsX7n+l zXH@7{ovcnUVS~@1%2*>o-lwt{6CD{9(pmJRM6}R7?aV)rn;eG2Gx*oYg!`$J@<4T` zXy%oQa9G}&pjlX*YUGA*$KugrO6QBEUn$%!ae@M1GVcWax?=ZCt5P0jf#pr^H z1}dQL1trObo5_VP ze*SaiD}t#{gPt!4>dLuq57@Uz4;GglzFI#7f2x*peWx3;+z7@ zr#AMHpP*$oA66vlvF-p-zQq#I)k+ip@JqgubB3nh-2zWteqUP5;c#}0s*ts#@;CfR z5uygXBRb+uIO9iSEjRfm4Y^Syo%$?MwifzjiMe;vZf9C>dq6RZ|4D~JMPhSqeK-^? z>gJ@<(V%kdT(mmNxO)=K9u(y2g`p7L;Uu^n8u!Xkyt*fN4mF zj#n3&;^4Pf0>Og~@3a$#@6x}^M$dgdW`Bu>T#nfXk;m#$7H&wa-UWulJ}b4sfczAA z2N$M-c%I@VG=p!bt3RMEx&FX{#C!LO35X}6w7Of$UMzU6>2@<8{q^ikoGW|cht)`v zI5VF*>F+~ZkYxLz1R%G)?y!~A^wwu|8KEy;eLkmdF*HdUxCRm3q3LQ5r%(B4YEn=h zX!`}22iFiP%zCz=Z|VuWjW9Zk&^^&psvKQ%XD`_jw*-BMne*<>|dfj1q4N&x-OyHG5fBgG`4PC z*AAZ9M{r;pAsEwdx<`6IMf2q5P0m@UG3iNMq^|EuVuA&L8V=x2K7{;K8)YjmtWE?3 z5P0v=i2_H(rw0TW*bf`N#No9{p}ZMK&u=HP=xY)kJyo-%=QnmHP{@-W1Y(^g&+!Xl@4(LuYTJk##ZLKa!CLcYai`adJ}ayY7=1gflCV;aOJkwZ zrzg{<)EC(2$uK=`@lMkiSvqnjMTOp?fNmL3SZ0kE3cu_+%Fz@>cCLyZe9Dp zGj{d#x6*03jh}izOC4E=c1Hb2sV>IqL&geFRaIq56QFpQD2MTIIYD%iS2t2Vojeo`Ix)! zG2+rnBEO`BR|o9X`uM{CDv*K&QCz3mWExZw8im@K$jRkc39RN~#k@RKo_lPpC{D_> zI0S_hZ7UqG6*eJ6H|kCa1RMl#KR`%dX%X_*tqchXN^78*7q8*EUbfC`LNh28dgwfj zanKbwR6VHC1{Ly~ZbELgWQ->|Pq~6FBR;gEW^u(Xyt9mq0QuKNXM`FU1Pvv3sja`O zDI-1ixP4KR;naE(?+gsDb=#RQ7pCwYh$TxqQS{o{p%eIXTunc^U^{)f7qlDx2NUe7 zH-B7IJ2YL;p~PMJ{v+^VCa=7>K!9={$icGhK#!VPRRhGtXQ^Y`=9zr5m82kXRx!Wu>xRo%+s2oWWMlIU`0 zeA=U*F`r+oC7u0iQ?;_V=qbYna`rG$rD+W`x?LLAo0c4lIoc)P!Am%4MP%#d>e8Y8 zf|7XIKO0(+ukZdKP<^3vdJxgigRGyDpKUpn){5a_RW>w*->+&gskkGebF4HXq$586 z6={q<3iYmKwiC>l7JuT!+eh99?Fu%Flv7Zy;ociz{5O-Jl1Q=VQ$KCmKAU1=%{3Sr zbIZ}QGdwL3#BeG05BI|M0QQnuJJZHQ(zAiSY(DcW{pumd&5tMbpZ;0hTX(orv(^C|SDTMgNv@9=JQLWTDcf@G6jW@1Zt$d!_$b74} z#nTuJRln~|D(rU(m?V_Unzgg}uj8tZDw}I_4DQk=l#DcDV%K0fi$YCebAbE|rsgbM zd%k$-40rGlAKY;Sf2Pqn0@2ORv(+`HK%U*_RAF-NblDy)P0bL0EWgk8^b|{5wSt{- zh+26q=^pqpMCirF+&8-pw~Y>a;qYtpBYkY3#}7nYNEt{@UeAXTat8IQp&h)VmB})6 z1YsD&2c=tM9#aok882T~wUuyeDAo5GmXL-YkC9OulcT+xmecD5eyy}-%oG)!})+YwK*v7J4Cj6uYwElIZfk(qlm zWuXjG)#^Msae-m9!*LL#aEjA%un?rMp*vl(C7=)9NH?NQ{fSqMvQSnin}IJ5M-bb8 z67Qg@LbBcqfprmW{!`^|>ag?i=Id`k@aNBKMj;@#tCpWof|tLeH8Qn-bnOt{0p`Jw z=Nj+k(avWjqJ*txTpPsKVucF3vhFRbJW=lZDhb}X3xO1ILGG?t%5w!bIqT$&Xh4^Y zm|i}jqj({fiG+#;Rs`qiK$H8Nn!W*#d1rm*>O#&#dzJ`dHb$T8IHE&ouk6iEe4n2N zyl4d|o1UY!4EKyqbTm7LaW_n3*-@026$Us6+)^W|#RIZ<5ulc{yuI*&jL*C?HJ*!7 zZXT+NThDF`4!bWZ#u_>6) zWn#e$y?{j#e{~R{rwV**8(&`L11*Pu>&qy~rN&X>Z z8X&4EAwhN1J9jm1ycjYXTuzcE=SC9z^Vb6#<+RLy!Dv z-g9qs0wtMzDicMHE;%%HP7`3J!qx>ZIb2~h_)^&Ww5nP=y{pfAC#rDX6w?>}TPLl0 zpAL+z0byHAPtW)#I>i%BH?>`+Gm9Bch=JzIw}IBNQ`Kqmb%cz_3sfZY0tCr^=V6a= zp_eNy?6-Ul+Li^z`*W!ReVIPuU++?J01XFjn#|? zfZ5G62=dwp)#TJvHmbpdJ>l6S&<_c}K^PC885V4tJV4@1STcQE*2uf&_C2X<$K)7& zU@TCl+$pnvECbP&4V2H3B?-Ri=(!Pfm6E`!G31ULUg@2k19P-asDT=kg25-zVF%SD z97_!?&NxEf?N;3~5P5yypNYlg<)+WcWrc$hD0ezNPPXC4^?5)GM%=~?#>_6qm16|j z=-?#-nh9AQOV`=bn_=I?jMOYtw;pn;ZmCZ>K%JjEomJi(B=Wm{%rP`-|7-y4KPHw_ z7lHq*-OKegjK`^rPQoIBVL|-}0U6R+eJ5{H|2N}~9U>S!X8t{V{+k~yeve6l@hoT- z*y~LkM~>kp=1(5mXA-Tf9+9U3;n*JlKMcuRjh(Gr$&Op~734xUnk9*P3h~h3MKsVe zR+OhLNWPx*B_bd%8$`c)4W9&(!(b%UIxs6`lN z#SBEO#YRF^K6D4n`G@W$&B8&gkp#5uP7ojm*^LGWH@N;VuO;Hei=WFkscGRKso}A3 ze~8ui3)dI01g}}~C3h1P+IS6W4v^{}spjBGgguSDn76AngupI--t_D0dLj$in zNq!VfoDo7qIC3X_pyKX@Ho2k&@iwyH5!i`m=K1br>sN)5(@A8`aa*-U`kz|o+(#XE zoVRqnV90ZH5jZ|BODZzarC<*bsEHd5-TNMx({0_*W#2B(`Y=Z8^n zQLnG)pMH-_m?^aMERb3>oMin zk1J(8sTBD2lp1A*v?mnf%@Fa?ZUnHQYW)xetYwt-!m(tE)s?lH2{6k|P@Ib*yDH!q zhZwLFFdd|3k=4B=JDezegw>iAVI*KUum~i5H$ecKQidxxV~K}){%2zvg=@p|ji6aO z_$#;qLk=Hig%>?A2@|_fhOVZ}*cj3TqTasPYwe4EAC$S&DAb@;2*V7D==A5`kl$};`#GWOI!2=aTWv6j^q{`*%*y=9?AuMSsw@SfN>zS5j(?d zrRiC~=GRFhUT$?)Zx?>fjorJ&e|8TtJgB^$1yQ~J&%JfgOE~Qy3mSgwqe6OQDWHrw ztyzi8Pk@p3N<;DG1PeNm@)n#Xz<<0cdOYv^nk>XJd>3;i74qys5hRolMr-MKanc@j zhRcw6{B{`&{gJ+qBNrM3W*Wkk)O!msGz%};u+ldpp% zU$lBaOW8JY1(;V?%#k|}cc19L+YLSjR{s2c$kqSub`Tjdpa|2@d<_zuu?Jk*6D+&` z5nGImw#=?2ts-V2g+q-(B8jZdHwAfL2B3ih_i@@7xyB09w#0Zo!LuDgBw8IW(MixT z`VzI>N&$hR8Z#jz*F5b?LMPHQW=O}$G#6eXdb|x7)^cdKebA@`v4z|6S53TF_&K$C zJG@PAo)LSQRP2uI2;i+^gpSR$m|iyodBxl?mkSI9r<(|TuH4G`Kx$8Y#2uMn5C+O8 zCKdmaZ=crOgNn%Y*CO2^_W=Ru;qO0kDMehC8#1NGo?TE3;|ok5tvZ>`L2|A$6juDJ z1;An5klP+AO)x<|cbgeoY>9adqdKC@%>m(5Kh$J#)w(&%cgZ3j zcjox>6p(O>FX&fQbdhJ5O|i2Mkemd{xe&;D0cKN}w!76Lx~hA1Dy97orV);*;1`Zs zW@XsROL+UwcMIATo6;XAXhdBdHp5Lmhcx_5wzzE66mX18Y%@o6XLC^lf{5E(=^MPq z@>drZvILTg4Q$CKr(xRIcHXk;iG$OE;9vh{z;cJcC`@k3$4PkL4K;6De`;HuU#?_* zZO8su2uVNIS0_};h$o&6BJs<&0h;M$(Rcs$BiT`|0?9P|`t_o6W*=>>l#km^A!Zb; z2cPWt65WLyZ?bO<%+L&?T#_FZ=_b4Wp+#+@ArqZNOEFYKAL79Nv6F{-ALVn;nzl3O zR%m%QmPN-ocEzJva2$PHaJf@$7C;J_+l<1+N<-i~hezWmjEX>hT4;~&R>+!m?QR)+ z54-A)ISrVSamN5 z&UGys%o#oC2z;c7ufYh=uI%k_*EK5osKGi0>z28-1m|;1j1{)*icQocF@{@)bA0WC*&nwzpm>DSL zj@HaK)cc)4Q|7fKNMR;I$uZ@5y|>z7Xp*`6n&>H}-HWWDK{JtR0nNXmv=Gp}HSCcX zf;&waFH0Fx@1Zk%VcWJ6K#zbV-CR=27P3V2Ldl%Ebk z(b7G9`Oc>v68-`5qIpJ{r2-8m-nh`Srh-TK)S`e{3?arY8q!8%KM!orqskS=R){3fHW zn;h5+C5Ttzus)C(dSE2TJRtb>7n(~3ICWzN@`pG)nnf|n5VUlu%eJtm3ASvKn7SaN zSaeG4l8=MD+ZD3$<$S3NAjeu`2qdN73)EN{R9QerVzu?aKC1fP?tqUe=1=y;&*#OT zOoY_lY3ouHw4u5QncTjA`6GzhuiejsMPH>GS0C2SLRwzsOQogrfL2aFc}IoIA}!rP zL@pMpi1XTz#B_Ub&ipFicbd65Jyhw|BYClM={hp_mB|IYfqdv0U!1X}VpS>-+x$k> zY=mbpsU#B0t?L-K6k(wnU0EIW8ZN!hO3Afcwmy|km6rJPW~npM)|=a@qqTp!rdzIm z@7qD)>5Tk=7BYd60|?z6+OAi|9+H$wJ4u)XtFYo+eo~tR{akLHcNwWL_nm)ov1-DR z=jqw~u;z0B#bxpmMzrNPxekQc5)$~_!#rqkN^?`CZXsVoV&FC`OnDqyQ()F{jX`p! zRk9w0?9y6GP0HMH-Qy%V3>h-j>9|ap~Apew~9%_aMapJT_;( zdgn@lkUJ3>4PRqHg7`0>wR>#q&Wvwoj%Su_fBkgfBSh8-T|xVEbI?u-j!_c)aZLF8 zQ*JvmwsVuy@Iw|zjhW6o8I2fZfRjbeoz6rm>R*4tb*&AjF+Bcq( zw+i(^d3C=}!#D?Ew{fyEPn0&etlF1|zWlHn;O~4-Om^OQE%tOwFXXjkqRwBhzUs*1 zwY?d|^BS0K+jCBPwb}v;z~-SCXBiSi-|kKOC`BpO90VapG2%geh+qoZziuZf8I>Q^ zfLziFT8q4nato;>$L$z?54ttH^QaG|#}s~eHwmLQlb`~8`LpMwYifEmbzcsmv?*1@ zQTsA4eD!16(y5-dD|UTb=hacYm$)+eCA<*Sp}Ot=*%S$zwMoqPjoM z>U%7Q&%)3T>7!;UtA+)m=WQ)nC8LMk#zJHV#-Wo)CK{G!FLeBP3#2FOl5c+TZ)KmJ zx>da~IDfs(Q0XhRIpI^jaZyl42=bB&{aqu0TmL_7y>~pPAtPJJF4;3=(=-d&n(aMZQ1{ucJTUv_L>76(Kts+0Xb2#1XJ=2gt?l5r(efm&g$w&`b-a!7O~9BS zeMTA{eO?JK{{)us>GsbeyyG4Vg^y#yAvZj>oMHo#?k(12N0}$@-Nf!Xe)7e)kQq%? zU(}S`b44-FI6n4-)X=d%=D_8%58D27wp&1xZ_J-Z54UI+vtsn+>Vg>r|qt0wnVzj7pJ*$_~Ap7l%M<9|>Eam6t2 z`S)k`40-ly5$EFG3JK5AV%ngpG24qB?zC8AUhUfSypY|$QyO7Hp9w=`?h}RTmTOea z9{7bTQCbWaaYw zB=nwc($cB6NOqmJ!h6>ZB1-D#RPm8&hht5tp3639y1e_7OjGP8m5KXJXV&vg!(cFB zwo{+XZy7QM>5U}f%B?Ku=}ELb|IUyOGdOVLMIINmdR@nVAsV8C?&dxWN<^(5uo7?@ zRdvPA@bP}T02TC6P5zr*n5%m#)lUb%J;eebuA4-g%VQ%;$C(c^ts!ED+cuoxLgj%k zwt=}poqMTENG?bDIMco7Ky^Gq3=_{tVa1%!eb9-AdzL-Iu|i7`$zBt;DY0bh*E3lx z43%ZK>nTt^$jRomlMc3EHr=THmG20Onb9mDdp`y7Z`DazugM~GnA~*+?0IYUf_T;@Q2|f}3 zp?dsH2d7$2z*TiIPo1-jCb+N^>=yW25rVZ6SG+}s9v%X+Zs5<|jPK6bk#s*vlhmLH zYB!CV7hZ|3O$dU9wETF)97h2IEZkR+VyJ>vzqUN*s|>e1DN)P=!A=c7@)L^GtQOrQ zr%99IV`D$`-M%!nsYRjcD(*NbwTr-cKvshD?N9FTU=i2?pJjo@abrs=36IGX-j4q_ zlCGwU)#|p!n$!VLd2X1j`KAqCe%cQLWjm;p9S3DC!kj)|9>9r<;@H(zq@~!rM&Ps| zI5FXEEVJ3&-F>Y_d5D~JHLuDWelxd=zfU%~vw-B@dXH>$QC{9FXfFHk+bX`ALm8>^ zwV=1iUy512@RS>Wcd6otbMo`_j^M)-QsIH|YMFZo6fnL=2|#uZVwr3mrm%J{Be zUn!Js%}w-^62c~xg017?IZDuQq&RY>u2NO1me8pC1bSQhIjxZBHh*EXyLkFrkcJM99h?*RKvqmrZwU&!ru7Jngphr1S1d( zavGFh$mxb6SKcUA%|R0>zu`H)it_t#RP`yRlTFBbc|dc=WGfy#cwk3!%o`o&NL`#* z=4k-SD*>J8Ul-MO+C^g{&&ASau*s=V)uWHfSjJngG?A>G4i`;cu;#~h^5nmugNGi= zAK-Hvkp7aZDYot}KsEf6-H<>i`gmroJl$Q*JjH=iirgO4y>u zV>>(sO*7J;KF&Xf!C2^N{L4B-+Rtci2MMqpfWhhsqGc$0OQ31V#DOh^mE#^9G8?g7 zpP#5)Jn!Ipu(xIV==)C{;DN=U*4T+w!nU7tVWhIyP%&6=e>F&Q5cNbWU(ZMM42R1t zA?}viErKtPXht-}H}qoO{4XNZLI?D$oKJ3Tu4im6I&H2$ONI0M1IeFe>{PpRKhn+_fXd=m%$s(eMmy)% zJrm=M;X?12NUt(6I1Id>K!mbB#QmqmkNGmeFI=i>l&ALi>l92yc!O{6$u`eP@ENu6 z8Bk|W2ZIzyB>wI}eE-3>cSW60l(0Jt7`*?Kc#*d1U!Rz8{tJ^#>5kg-V#LRi79Xo}dO_LZ$_{&xPlrz ze&=Mr{!XTATfqYxblbyFwzg;^T=zA=U_s1|aD+zy)4ras2ALMzmz-`!#EjG$O~}eC zD=SC3kFi?B`xz&F#s||6$Eje}niIc5L|5v1ywCMhKtpjU#ie03s``S%)rq*$H}Udc z0YEKg+Huql6$LKS*`6VyiU%1Y|5YTwd1x%EV@e zF?^NI{|)WiyClePz%WwLdaB;#5edAfTt;5ta>X!CK=vFni{rOuk{$H{L?MaJtF2-W zUd2gaza9mo$r0$>nkJ^2N0dr$lx z{cyg%Rb9AXJYf#@Xys?wU&xi4i$UYfC~^&viZ_9C!I;wq1?CsP#wcIsLfjoF56^Cl zl9;_)Z>xJ5!9sJR-q33qQ?yZ1b$l^mScJi1dRDdj$EDzP!7t`%?o$M{+f$*&m%)ml z1W?nD7CXP%Z|rvq_j8o<(f6*nW=h zrrK|$UGMo`QmqFck7jnbnzsUzh1&8SIGKb)KgcwM-a;QcFGm5!?HcZ;ATv@>!bQ17 zOgf$WD#M8eG}CF~(msiWbq-7TrRK9sxyK&M^+*U_E3}!%(%{_6Z#`AH@NDT|-rfGKp0xd5SGrvWs*g);fr3s` za)OV5W#4T%7|M)h%zafAwo6vv!=)`5+INf(=JI4^UUBd=9Q@-t59eJxjea0`|cxZsk7L!zbNC~mkJ z0YasF4X1u90|w*M!SN#RArh^S@f{143x(;m<00Fhm;~%49Jz0Qm0^SRRVxl4?xtgS zuZ6Hgi*Tt|AC^2OcK{3*J^uy3P3mu)St)y@dO70NO$UoslB(`q|MLc9rQUrDAfkG< ztn8JcUg0brs|EEVy+507R@J4?;A<)nJVr50lXF>JICpdI3*&8Tcoq4jwaYc_;BmDw zEdDK0b`grZuo~juCRz>yZ4BSespJ=K;O-T{OoJ7x`sY%Q11F7eL6skYfsAueHt{KrX&zT|;>WczSBAe#!md#%#P+DK~R;I2{-t(u-M14k3C4 zGixY?qC$7{>FaIy~i%_ZPEhSbZ1|F`nI)lnzC<=s%h?R%k(obfF` z3w<*CK8}R}rL|G+WkE|k)?YDbm?Ck%JpiOl4C?kO3uO6azLoHxe0<6i8_I7be!xaN23(1ZZQdxMfR9+U0?WyQP zSE0#j>2w?hM#-}4=$A@ylU%EGNFl3U0h_kq7-k(7`col(MK%`087GEoOmyZNfC$!* zr9M>C5i9`LFaE_Z@W3`ML%6^4s9b{T6Et>?yuj2E*A?X_RfFH+^cyvdS}uYUUS+jZ zgj8_))09V_Eq2My0>i(V$w=MpTn;hzPtvYuG9YIg+enge_(oc};Hfpy3 z+|R2?Cab{bSQASW zene==*?XA@1qsW_)J`arN zblOGrDh$>VZLew=IOlG7SicB)wB&zMXX<&yu`>meqstp*Os{_~7)3ACEQ@>bOdNc7 z+ye4iV4>FXY=%H;GQ2@I$lZbBnVe=8iMfo*S5Br? zz|?CO@6;R=b1=Eb^ZuF7FMf?AY80M8y;Ohj)95jLhw9JQ+Rna+lsYIV>j=qTXrs$0 z@Mx%!sU8c;+lFG9mtgv+>_m3k2UcxSYT4;$(N!nAH=YP6;3`~7dO3AF^5MTEzeE(EIZ$D1Ua z^>j_*V@NUH|5BBTPQY_b&$Jg#Ipry(tg1a2LO4!sLR#ziw!{1-oi3}5`RW70mjeyU zH4A3WA{*yL=F%UkF_dY6btjPqQw^#+=rswHS|0NXXtD~vEAgT(yL-T{m=8#4ZMp&3VplWHIi0@vyjdiKMx;yED`0;zyg-k4VP48%yTr ziKTHYememi)f}77xY0@uv+Z zDF@_+K)oi%6C))>R87XBhM$)U%T8+CmYzML%sGr@&T)P^A8%)vOc4B|Afot{=ChNl zdXtN9^^LzLJHu!_c}Xlk-$?Ge;ydc=~OE~vO{-a2~d5KfLGf0 zcom7F6+{(TxlfGsuh^%9ILYk{R{;!oGU!@JM7ocTA{BfN?cV1qND1#>*ITrbCIRp_ z!c?%qU-AB)rcBSrx2IOcunK2?5_aa|0|{*rF&#;lw*P<{=)|t!M4xwv-&XCICk;!60`#r~Z~d<} zjwN8-mqalt4#V+?T%A0aIN0^o(28*Je0L%D5CfJu6=^;LzA0m@&g{|J4{4kU?vSiX z68}-;p4|k@P63zk`qXBULrrV&5(Q~Wt8!m{MggHmRn|h+8*A|4YCjv2R3X@T@@0Di z^y4}L+mOjQ%w__U?lcS$;CN-YIB&0h%}T@AQ*=v9*^0wW1peo+E%(tU3nB>3+2hTR+{>7f3Co;LmvcpU* zER?^o0&w+PxHya*2TS-8yS}OE`g~tI7~Gw_i23=Ji`dR@x*uBFn=xSG4ZR>f6#o0~ zi6w=!Yh{)fRfy==5p$<@=9z7Bm(q_o=3h!orz%-xBFqoZ7mYt$+a#lrqq5X_BH%k` z-7lN1X-xb(Hnkd7M6#1Y0i)W>?NrNCZc|cZTa+UbHyyCPn>*3-Cg(Lkv+9NQ1Mmi%PuP734U^DsuXn)+*RwC!I7vl)N0LGux*Da`q!uEn_$ z0<(%E<+>8@-oRNh!ObW;TSpyBsyzx)$rPyPJ%FnCugr8?C+(- zh<-hRs97#swf^UuKLH^?0r&iwDL3Kb2DoQM;^KNT%TE9`{c(diE z&6+a&(3*WqDorQ6SG$^V;xGiza1sZ%X~IA`lV4ZF&GLEQLYFM@ley8<-X`Q3>L(S3 zvwm+CgjB?AS|KdEa$%pf#pH3m)g3^Ijn}u2LUQ%;)8|E67yup}ru!OFGXZVk*_`+N zwRLpNfWGm`1^ak0H#Yy-$lp??*4|>;M=$1B@xX~35*1wMJb}aHJWFhJR;mXB+g&1w zyr2_qL+ZCJBSUQ5rLrxJxx-R!WJ-ZmdvIk+T{?uDPprdLCB5*5 zX-)f{!2jp@>0P~=M8gy3)+ZTzUoO0>!1n&a=upYchplhfdCinRC+Acd&z!FubyofC zy|ur)a--~Kmton>juV~$Q=Jz~yP%sRFhZ8dia21iRSnMHRdk<9*6%i+6kC--)8Kb* z>wQ;mRDcdcBInbMgPp4}gJMR>pbRM5vzB!*m-y+CbI)l0IkU1b1Rz6vYu)61lVgF& zf{3kb_k(2*UpBo+*lQ-y3btO+xE(^&C|2d-xDpp`bZLEobZrZ48=a9CufW^6g2u9i zC=BXFLs;JJaQuNu6Vjc3Y7zQ3tn#;GqGx>%onX-DN3?0`(Ye2AM9|;j@rWR(yBQV3 zFI9^s1F_c)65%77b>?^@GoUn;-ks}ui=@Dh-U1$b`uw4Zhtz3oRD1$0aUgaMNOJF} z%Z{Xa;=~5)Xzcrwv_Gtu`><5gu=D=hz9}ffU5z7Kt`y~yPI~ZtkRC|&&rsh479*3s z+gVM*J%>l6MGICS-EpQSnJ2XGs)8}``^`5o10`HWTaO`x5ssGhTC;=@Kv zI1dvk3S>-4e*9GI4{w_Gf{|poGO77{3$o7r9ni?l_xoU*L)c|uJpJGF@%Qm-l6DsjU;o4A7oXu z=gtAcGswk$z${R15t#N-Py*L7I8y_*^6KRE1aMBLP?6;)-HcW+8Z~3%jA0O#^VSo_tVLT zRN~Z`BK$hMeJk(&+#(o==K=9%Wi$2PkVn7xl{7nu^bOpT4VKw0$Dc4(ekSm9$7pav z5Mz}YNsPl}FpyOXAi6wF2P!ElPcj}oTln_)8GfcIK61cXoyX%nJx#-?1yA0*zNtng z{ukf)MuD8#YV7Xscb@V-3ZE|*rKRGgc2fqjYbB=sHr}I>>tXIdu#O_mlIsA@ZEBgW zVlyU2!imL~r(b=3g{mCJ!_#m1vym^cKPQvpTU@F^G&a=l{O0rHfL=X(u~TBVfUFWv zBthkmbD#cIVJo))xn*ZXy{E*!10!&NMjYxl`g4XO^zfZLnPmQQTwCesv9gVPH}(|W zBm9ai!HnqCCCA`fz+X8{5qa(7((vhRxVl52R=?5y(kRiHyJ6c*Q-o1Dhcl{ihLIO6 zc?zL$)BcPb@SK%?z_mI%n*o?%Uj;q~f?$bIbT--Lc8K+KLAdDmSlz|+hbL9!D|3(= zwNyW8*Tx($B)*#%_}-t-&1NX7Uq}#knHdB;w9L)OwZH*;cyb%Dn<%=3(a7iU+<{$r z4h*(nlpIh19l6GG^|`OK*fnWgA}@WdQ;a$zg8v{9yYKANC`_LPP>!k;gCbV~d`g-V zAcGcbf8dWGkCt25xuli5O@BbBFa(vi1GvY!{UC}fDuI5aLtjmXJor^K1+WX{qYteZ z>96CgA8Ce%uDmN;y08Zg-|LGVLX3-F zdFoalpqlH;C6cR&2&1;AA*2Gt!|j3FnC2<;9O^(n`}9u3?<_LmU8_$*zyn)?yS2eU z+8OpcBZ%%5BH8u3Z`9|mX#V$}XGXsP!?Lj*JyUCSRa@Su_JGH5%m5m{{voWMAKH1RG6YP_r2fc}SAHauD*t%8s+V33lPFm?BGl&?#Dmg(6 zL+FNS5{Xt;G%T19#$yydL-Jc1fKITV7$q3lgYtQ^1Zg80q<9zPmX2TFMwuxt#KGIXuPU|tnE#|ZqzyYrZdoSfxWsrQ>=`yRAtVrTH@ zAYOC%@38+uD!EMQ1^3%hsj4Wm1n%w)fxnBMfaVyuLMz)YQuvFtO#jP~{?9?g z^#A{tYs^3z88ZWg^{3g_T&4D)!zqAZK@#y2(sHD3AA-c&x%9>RAJ&mDD#-QywgxQE z?+T@qQk~kp1*B-RTlkRBx?!@dGl5um_ zF7kseNV$+f#208q`z6i5n`{Mk`RkkxCyMBYhF}nE`(Xi@jQps9Q9)pHXmsxV&iN^gC({Px4Zimr2B0Q-J~<^VDWb*oD8I8mMka&JcnLxnPfgT3kxX~+dTICxsI9a$L)xK)6~+qxE!S{>}TT!rJgWg z5&U}0eD;a7G**1WI!pc5FJJGKwNDadF4;@VpE~OANi+`F-UxLBw~xBcDp8k}l|Lu3 zwQ<&64xqp(Lws7BG+>zy!k?1Xf6~nH_`|^&f=jHG)1$(IfRa7feiVu}?fM5nQ^sjV9QYH|Lvf)0!1GxQHQVCkRh)6_cJZ@8n^v)+g=ziMAfCn|dV=E0paLZJJ<_F}}N@DKbg} z)^ARV-jqF*B?VBjkJI7Qhq9%2egNT9FfteK;sdAlQYfq=RC;Z^mI_SjhjR_+xWYx| zFHCU0JAmmQQS@L1nO{?8=}QLSVI5n5QfV{`DBjFTV)tJyBmftLW$_&t5)m?&0e4>b zt1u0GQCR(3=SO+D9%zZ1AO=WsTT)^vFH>#w*(*SX`ZOJU5)@t7uj}gSWalR zQ&Fz+-wO9T*aiuWU@+YN`Say5JjPe5^adL~1jxE#s5%0_2o{gM1>M7DBeu$8y^nb< zFzG!r60^!K4G+PK9%+HH%{;eXPk;@mi$g+LKshl>BsT+mtm_Q$RG+F{dXFBL7X5NA;s6uFU4iRDSDz5{--AM-h|EncZb#2xj?!`-4XrCASt2%mEV@7q$UjiLE zd?iz0Y;@F@fJb#R&X>)4q~>w{-sV4Z5zGE6Fv z#VNgUBEnmI|SAvy5hY3grBZu1hsg$BX`j|cT>kPkHg|6oS*B$OUKWmXIJ1Ct*CFz z7yF31@P$gql?SyFh9vtWT~h&&468*7sv&W{_B}S$lY0BAFc)n>D4^r;ROJNO@^-KPFZ9r$;_=i(4CK71OIfXxLp|^BDMX?l6YH z&q{$D;JXi;fw&aTqr8nj1L0J^VNLj&2&nfbu@Sr@flpZfwU zwmxOM zV%qjNmuM-(gUD7-Mvc;~65Mj1u~P-*A!X0edaWD={cMetNfakettPwyZY`&zWMfz7 zVhcB<)P$rTbV-6W57Ch`Rd5z9#>O0`VnP%Zm2;j@cpOPr`J!UVT*s51IS+MgwMd)Q z_fMTEGb~r8YW7XG#7O1AI(TVsYa+rkVfYMiWfl@(w%UupuBzF*C73q7zrULO4(khP zzijXVr-$+-!#|=ZSb*meM?KKH)EkSZ0x0hUL=RsVnk^RAxO!&-U@6vWW1@}n)0z_% zvNhwLr!a30J+XKk8C>!T(=_~Wzj5E&mG6N>`@0*%Agr3i^Yl4moZuHd zvT;f@^|&NvGT*)-W&7i*psGB*Wm%`8-^T zsGvh)*RB@C$L@ji)52K`|Gu%503nUA^M`89GPflINNLYtNF_mi=JZ8ue==D1=&0M~ zcX%dNd4#6Z_vauZPto#n;|(sR}jDVBq%`@#Z90Y*3P zH14@sy$xB8$+_J~DS$#4y65E^p@Eou_J;=XbYJsz92|kWCq;>iZc5_UymwLmBJ*>|tDJi+!KMJ|H z5>mypyf1&3le_D~s>kAv<9nF@7oV!jikG>H!(Z^qh3i*BLzR1^o#bu93-X9 z1e`aV-1d6kcY?1=+jX&19Ka{FKunaLCKp7YW6Mq^t=xmZBxyOGDQ`9PwMI8)o3CFs zTvaf4xbFsx8A7Q&8y zf9m?9n|XPUw)jcFJ{&Yd_{=60e;-6736?&Q5lAG!Se0i64NLBTezAhzvdtnh!U(-E zDd<*kl^is$gdDCy=jTcvE7SXI4c^auwa-78FjrkIG`QR|_I*bivoi_SBHn9&b0<2x ztIV2WfdnEky;+3gU`XKF504ZN3t<=vjFSmUQn7K71*s{^l(VW?Z zw?82E#F5_6C(-TOSmpU_3{rWWZiy$Dz=>lhrM!elbciI^;k^m2NuSHfH0!!nS`iEi z1ZjC4&ypK-VVG!)LJxl38%PygJUl$}8gVtnJ#Y=*Q1eRRJm7>t9%&U{dLErpSW$tL zIf?8kxwlQrwfH>&s2XH%d$Fcii8aKG2`P`W?0nuN^yk?nbw#g=sj(+%+>d62gz z0x1Xg^9;5?#y81S#7xLsLkt4AqPkygazQ)u6B`}?Oyuj@8@Jxyq1&$jm3_}cb>=h} zv3_@I#+WSvhf2#aYR@0&Sv+32mNB%tSehHEr(cxktau`Dynti>j7=C zOkFWcU(u((3y{$tEUun;rn5vuC5t{P=JQI?$6%M{RmO~_wqE}_jGw6h zC%jjvn-Ikv_~uM(>GOUNc%IxZfBpD2bV6nI0{)nz0J z`Zx^->Qb0?NE0bg7fHyRm(N~JNtg4hGS3U-d>?;zTRC`3Le}c}s>)sc0SG>6LmgB< z=M7Gso0Ed2kJWwX0HIsqZe{bGD0fhjBp6) z@1waxZ>*bm*K;p7feSy>oFvf8l5)ab_gn^u>0U~avEi}fr?p0Jg*uw7PCTT*dMNw1 zoQK!We<9rr7qqw~*3wy+I^>DTNhAZy67icj{iSu6h z?)G=i!@n#NhhP{K-~NXOt$(Is0AK~1>NcjF}hCxBRey+~P`{Q&wMe-$Jxw-lyXHMYn^@fmt183bw@4kXT zRl29^PItZSc<7GhG1Y#}=n>VK<{>)DE`e7nna7Fu9D8Kb4JvNmubOo|fdXfi-|MP@ zPD^_N3c9?ktip`H{mvf;+ zXm*c9QgWi<&o9;4KR>6NM_@icT2=^P@-S4fMyq`Q*F73o>dTK`NC3NIw7F)cYL@-? zA1FqZ2YvYQ<{D%GmnZa2fe}M%vccTxu`;w<7!aG!)e%OZNoJ^gOK^BT$gfH%Q=`o! z2pt7Y1*yPVkEY}h;3~?uH7|U``bdG6d_AEN?!H@Nl7?=YLs{~F_f^AYAMD{$cCSk9 zluX=s_D?c6Hy}_>b~^QkJ3^uG8b;Cs+andWR&Y5#8BiSyhZt$0BPBQ+H(8{zoYy@L zdU&h$JO6GG5!|A!Gnog6pUqu09c+#^w;B(|@~##;#2dRM>dMzK0Un@d2p~n7Euir| zcF+K7#BHp~x$Rw79{b7%24=`6Yg841dL1X9eTB^#TMzQqN;QB%eP9nlY3p}4Z5Dxc zeV4g7D0;}n*;%K7EZM6nDB1D05GMZ9%VV<-zMR-qu^ULEAQoHo+nb_lRQf_;eawG~ zAm{cj2yVWLT=yL)HE*7}+;;u&!~RPP0gdeYBy>Qydkt+4(-3yh@9QWU!p4{gj`X05 zAmMSNePRDQN9tPeXu4OLqqvR=Ie&Zn z8MJPfjm8A+(c(;Aiwz-VhtByQ#G8{SIf)$!Ij(;~r@|ET`srOz)SPYQ$;2=ab_85rK+Vk20kXSeN65wk|G{(H{%M^dk`Nu}%$wU2N|5!|3NO zE-puTpHC7?Z=FO?8T8)s5euB7^JSKL-aUA4-%jj2+h2?uT0LvJLxyceI%^b|DLJTgm25YRL z9AgWPjXFyvP#w9!jOL^G73H-&!eaJ)kCNUhC-d1|F#k^Oy)1-}dC&fKBxnsOz=EEe z@E;OLFOvqiz3>5bBPnfDBV(ih;w%q>MttVBFGOfm?3WwIA2tjSijCcP_jRl?|oe2YF+vmH!aplghZdQc4z1e zq{qQCrgJOhBs$eTq(ZK9k>6)$sR~@7Hl`R6`fY>#g9CH=RnX}tU_7kg-HoJ_x!5m| zaK-le^lB?6(s7@!6{>V;rE3^#c@$#)pni9V=T|U7O*9vhH@|0+SzQs134B`8t zuZQ2gcLc2D<=}j)4~aGdO6rM?l^vHk4keeophO}n?sBMlt^tyvb4&FQ{K1za>)Q1L z5<{X-=YoU>|Ig4Hf8OnEt*k7D$R6g{!>UN?CoZf{TqO5+OlcsOXGROfg8Nknc`F?! z#5w%^uFS*U^O3#>ubcW_R~;4-w{gJ3%L;l0SS3X~=3WdlvD@4-9EU+<8&x3Z)JTmn zXrodv0vhe0SPfvOi{mov*Q@7CqQkc_G=jyFq=T{(8~339;#n8IPO)^b-7ML(kp@cA zF`)E!@WK94fxXIQb5KfFvn2{%h6as1yA#+D<>zGs$(hPHs>KZ%yk`AJM~$*osA^B( zxNqw3W~uo#H+P+a^+?z#R7Vdt?#y#sJzr#j2x@fzk=Ndv4NQ%bl4^`yZ)fAzt1#{xA;5G7(L_1JLm=@t zb9gZfcQ+ptNUc0_ME}1}A@L2UUXuelG6*x#nqruiWfgcAU&{PY4sJ_(m82hDh?9r* z0a4a=1PFX2_pS}I+y^#V2OnbHLi69xeznLBMEI&_njy2NWbQ%}{1%lBu@wvPf#qv& zfLB1oe1^TW9yq+C7dP9Px>5V`W*WOap66aPhVcym;64IKU~$s|XBET$)R0p271&>v z@dApv>h8P1Q!}~EqXda7k{{(T1!Y+i(#I8rkMo#H#|q+ag)~55o4^1!zkmNOx;gi? zB%1nF?oQIgZ1g^+IEqz+7#RKA2~&*u9pJ2+TEmu}=ez zRT)CT(PaM${??90@MT)zB1c2_(%U?KwF+d`-L(iQPAM$!%dQvIU z-i@6Il=a0_|6)w(#`fip?LbwoyrEJ%p6oVk1Ig4ah2{TzMQ?0&(+o3;C~cS^fc}H1 zcIRb8>Qj;nQP3hVPfc3@1_whENORNkCV-rfNyz=0Pne^Et30WXrC-?ddOV}+y$2Ud zo?dSB)mpX2!(Xmc4L{Dt`cfJl39NJYInK3o*!TI|76-qIm3Mo~cx#Bm{B_z*x3T>I z*oN8m7oY<4dKXdv#G!nbJ+yiUDW*VSd}%49AA|;^Tei?W2|z29odO%0m=;xodFD!w zK`nxSo6zBW@?o5JsG&!dfD9hC+d5Yz*;wxEudC&u#&|;D6H64=N$A?Gn(5 z41u`9m?~d4I~>g1`1evK3GwN*EZ{YVsx=Y#oa%b*JKQEH2Gj|2NK9L@TR#}l_ZRi= z>NM6D)&1zE@4$Nay<1q|hstbTpTWdB0P<2n2a?2R9=HTzp!6i9#M$$%OSotiegbx4 z+RGvn9Hc4Gtl0xw*>3PK(3o{+uHpUoj==I{frW}(V}3qY;gv#t|`0GW(03f0TdhXT&iIn_%1s|y-hI}d9zy1cH; zwxz>B=Ydmh9+>ypz2f!_4+Zu7!>j!#0$zC?>EW+^%$3eSj@lGOdm6xS0zXeEdk``WM{Y9#E zrT}aYB{Gu~W%Y#&b!B#%mnEK;{?89%A^g*ntj!Vg&2?Bn>_ds{Cwoi^4Jrzt+3a}8 zpf9ZdF;i=*CVD{D_X>aAejR9bWcIXv{g$UPCa=5$=leCrE8Kh>oac0ZhF;593I_E9 zZRHXa#vjy7ios*K?H(U;?`OMdl0i5PtT3M_vQi|#9RfF#WC1Yqv&|;-5(ro(Suk-b z?|RyEe!`CbW&!5i@L-TETxiAjZx?s?(pu{L2yMQ7|DL#f zR6zk~$0@r$j|6e_fcQFIpN0E=r`zG0+$I15sopNB6pZ`GOM2vUU=aJI3fL#j(bP!~ zaR-%8>h>2W+x*Gl8AbNArDOggl?%MS`(9{DqozEpVll7eOI2ypVvR`g$b0$seFm-`yA1yK79a04e=d*FEOEI5)K91o=SL zOuoXnG*hf1S4o6Dvd?fhfS=MX2!Zs5$2zw+z^-AoZieBZ%!M;)XGKt+cQ=vR`UuT8 zV-oCb1Xpo}o4%j`yNKK#3Sn(`$AfABE||rFj-Fbrd9&iPCE8O|?{Uru=5n*1z!64^ z6W0HCLUc-Bs#dTFrWPA_hKDpo|JYvY*Z9`POr}O?-HS;w~wd8TIcz zO1x-Q)0E$*A53Rzd4lvPLYAUWX}$8#s|9?m6Ago{E;IcLT3_H&&c+@7>CFMY7=%y( z=oMI_#AC0~+PnyoSJ`HtztYH>;u?Jd2v*#ndG~^bX)|FV;qQRVTUdRq=yN4q3|xxC}N$o!++?FeeK^9kyg%llkeC^=#+ z#F8PIc^;xCh|OFX6f~~8a6s_45eDe# zh2Jm2iuSbeEky+fhoTDDD<1Kl&?qe~zZ`rSWu|pDHi1Jc;%IIuRf@iCABo{43?zS^ zi;U*=-TA?KwRuS5gRcv0ypw{)3JUNNTp~)L;3dLBKj`il4fiY@RH`s-mR~dc{MI(k z7jaBkVupbxa$gl?QtCG;>xsz(bF+(O7*oWJ7U3y;k?C`boh({uMJo`|BDQePZD;}Q z;8$vVyvytt)Bt9&@r#yXo}=K+XQrY@Ozdqk@KBJsJV@ew(Ec7UYF@$N9S7p=$`Ien zd~=Vz&xseCD{8ZgvQ_>7nyotU(uNAv*Ke9J`{$8zzzt9|YjPmvlmJ@z+ug#I7TRzl zDBqFFRfd(dY_i<_>NF=NgTg=3T>-hd@tgOH%zeJacX}dgr&ie8_QL80S~bEF)8f0A zv09g2a&>HUbEmTtLgDLboDE<=0Q;Gj^^8UsNG$gaq`4HqUpsVkc|tD)f5|J0t+HW_ zDWLzT6z``=)y48&+S!v|g$6T-gA8ilna{M*!u|v)i&8-N?-Z0_F%Qykk!BhRuR-OL zp#XOf4trdPTAWqWANGN4`{!N4Qy*y5;?dfdAy}M&I%MtQ^8-js=}_|{t9<<}@srz8 z4=F9>0@=lEq5|EB>Hp>o@-Fe8AP}!%$CGU`q*Z7W)6NNq*yi!t-h_ZQlN{<6iWxym^g zKp2zxZ$`Xh*ux(8z?Y<`Jtyx0-P6PQO(|}DeUpnGI3KPH&55Z z#H3fAV%WeSZW&WmW8s()c!63LrODd;YC!0-jP>wwUMZ(TelL~)P^o@))EtnA_=g(eTbL~pl^BK z2t;|V+m*2;FF&^bWH4Y*1wz*%@cW;5j>7@CiPZLh+1M*mjBb=DwJrjjPNUOa z1Mi;$^Dl`sV&jfTppr&9kkZ5LEr1u=0fl*z5hIr9ZE(n@T&gIRCm)Uq|Jy;Q`jN5~ z)h>%zIhkBo57VY7$enDlWgWqRI_CRXXArxg0R2gTu<0KU2#fr2oO#aZX)Xuw=<_r{>?(u~{zvzBsn8KN(N}iEo4ZBlk7H`Swcrx(qi$BI5 zJ~0cj+j}R}Lrp;}Jx_l!k?(Ng6)EG-cuV1DAo+u=muwW@y6V;HSAxUfrwyPf>~=Oj z`-CUma{^JUX+PB0FM58*lmT?xB(~qfudF^&3?QUf1g+c2KZ9rJA?It+VCi4%>C~uq zil7|ckWnUH^wFjLH?r5U_Ln4 zc2xPG^E@LuBHicHX;oP@lIOgZCK@M9V8)maUHPc04T3A$3!n`9F-L08FiC{Pb@mSw zQ%m#UNU>Mu7DRtTjV9$UG02~RAm`M#cL78%QeV&>sUV}*u0j1{rM0~A1v{gfwaI|| zsL|zs>*>U76lj~r4+VX9y+VUN$lf`zCP7UQ-u&q?I(q$J9xo&4Qk>yd!2&xJc;UYx zy1?2z=1-5A(>smXKcs&HA+$guUBdeEm?-zP0=Z~Cw*2nr?A%SEAmtUJC;?wmyAx+G zIkK04-N6Ufw8G3%VBy5579iRE_nDce>-^W9_QBt8lIe$hAl)VaU5p&ZWghmP#6zx4 zPZA3=%jPZLnCfy#mA=&r?KWW}oD&}a=QBGfssmD~O<<7h1{ON8W|~#x*!$#KGGE^K zA2m*C1l`_Zv?}+{+4Q-~hqWC({V91gb$bnU??7X3!Sx=fuY<0$5m}e|OLPVVg*X9S zrXtq!-FJR2fD5y%{1&q1rQ)bg(g;m@LA>o+Kf=h$%E~qHTpQ)bV(c2eT#ATN8N<7_ zo@*eD+P(XDo%--W=|HJn->Yz~brf?;#vTCD18ndDYb@ zxQTzEu4BfO(2Y4EEp&n0>$>kT#%6|42SW3Lq^S79=z% zVrpO9vxmKo8@_c=0t_pXDCgxpd0uXr0{~Husdr;`P1||FTr^ExOg2y7bK}5Rd4DiZ5NAqdasQ zyhQ6*f4?ZDQtV(+VO%-3e(1x0iAV{}sLdELq3;i8dYic9!JjhB5WS^;3tB4Xf@?xB zLhwYc1hNNE^IE8khf^Ul3LqyHwAk&4Wy_6gRcye_NK}7d!`ORMr{H>76YLVCE>oQ^ z-ckQRc^aHYdovkRN`XpQaGk!y>?5I7T~r3`53p8R6pLlTB07p_ar?0sA7c73 z6lv-qMW3=er4S@VfUEb`b#?M>(Uo=K?@$)8-&{yW!x0R!<_=U#&x)#Ii0x=Z_9#HP zu5Wj8eWoRf5vWIM1Ab6t&3+<^GKLFbHQ;s809_9(oMgE$>k-!=>+-2mxD{7`QC5!m z_mJb1A(X^Cn&L$#=LO1F+)5@_NjfFZW26PT)Z!tWE z$S2sa>8uhY{3DlL_ZnXu1pRxlQuNl?!?=0SGD%ZEEpB?TyAE@HmyJY*3k}bjV(&iv zwi&D4{WtH9Qz^w>f<4~$uz>Y4#pgQ7xb;)$%)Bv&XXa@qGlx2^Q*giTG2|Bq<&^+a zuB_#j3X?CCWYekHdEW%bTw@jz!2fXw^`2X!An1WHz7Lc$Dz`dYTiKj%)ceRhmmk!d z2^N2djMxy|s!gn=zhzx4S=>k$GTaCQ$02YEF%H#Q=Y0h!Ox`|x8dG$5F{E$ZMOZU( z#&82|MyAIY>~{wwGYup_=X0lp@%`;66QI)?1J54r2Nsm`x5}u^6%XSee2ohYZ$NeS zeEF6NR_IjH&TqBokv%cbb=t#Q!GO=CV%Pcka|JvpiVXRam@z!W&qxG3Uw!FT1$w4#p!CTM+(*tH z2ty`!I}fK)7;A~)_JZ2$Mf`*Tus zy*JiB9!3ELd<9|#<(_$m<97LCA^d*bMU_wci%OWy+0z-+_JS3ysr_-{htv9 z9=RwaS08ADh(1C2;5zO*RB8JkAt->|#!cb0$WHT#jkfOdu9aqBUjuE@V?v4E)MH4_ zcLYa++#gx6!1eyV6W>hd`3VU&&-_ah&~CHAFd_?#Sh#wNme**(R*J2W@`MMBR^3)Q zNyHD+ZMqyblo|Z`_7N0zD<%vk8i(Kf4GH4MVZ$$rH1P-N$#`xX4IKanl@MB+>sO&Z zu#FJ=rDPy703#u4u-hgI&@ISk--RNIBepyX7fZ!1BJM-V6!&&fHB#2@jlxjL(-5RY zD^0RNhcz=k)inTaVD{djCohti>BcOP3^y1S*xsNN`Kcq5j)Pe<11{VheeWQu+XJ1K zO}ah#zf4&_DOZ1l&cPhu>fAXfHEsdo_lT1SfobnxB>*N24l$;O1P;Guy)uX8Ua-_& zrWhQBnFP{nIYTs4bx;DV{FIkJ{G<@UJlvgo4f!gSlvCg_#Cp^DQFP1NuU~}cf0TU! zjsIyX2RO*c_K%Y2D#Z{m-A-+AXjg2S8Arwt;^?I)>U)qwi~S0E{pVzglL_YGrHDKk zo&#X*(pW8(=wX2MVoUcNK_C>M5iDZ|AgFl{R3#N#s8+jY9ig6sA<{{y9baDlRNwvk zZnBf|mBE9FxF!>n!#)e;%T#Km?|~2NeF+07 zL@wU?RTDj2T^TzRKL}4Cc_2DZMyFJK-zXV**a3W{C~gfs1p!rrgY{v0ifZkz8VtK=?$;npy#APq+sHZ(JFAO_Y^*EK zq`n4T7JJw9Ek}3=Qes%lRh?--l9lxX+{)!eTKtK_kI075w15NzL#C2znbqVK6 zS+hrpuTRvJ79VgstS=07u2b+p_hGdY64nSw>uFLF_0}i=4Z?kmaV15#4JsbpTWxV1 zRF&?AkVx!G zqCpuFWlUk4N@f|Fl#+P}Nurr zd`Nr&S(HwtD7WQ!oA*}1P^0tkmRm+N$Xc37_PB0iaPX7Y!}=zv6jaZlVX;waY*wQ; z^uJ&74Qxh|zFGTg713R=P?h{d>7P@@w-F~LM9sM_3D-Dg1L-var7d>dh#UAo^c2ix z!tFQ4uV)OSzPuvK79sDmjoBLIl`O3WXkaPpkuF^!5Gwz0h`izP|0#BO<7-E5(F4z~}j=$Q|x~ zi6dg%mF0m=yql%hwtJy%jsp7^8Q z3Xn$(pL>V^*bcyhm6G%%37?qrIyUR?0)W}CXJSBICH^JuxcIr|1paeYCyn|$?p%+d z_tQV|OA>FEnnm+=v$Zs6WhSGBBqNjy(i=)hV{Z}R?f=*+yNV>Rwh!pDj&_dqK9Lzr;{I+qn<`ek5pJwIbx^+>@Rs0uz zYkWHzcS;$iza%Ct30}wF20upI?~zsEyrBRUOngIV{Q*N_^_D7OlVmOK7V<;+l-%q| zWYm1=WQexm?y1XHy$`bf`0*oF{}i!4=mU8pK%P$6v`B+jg9A+b)F}2d5D(vk4r|j- zX6(mxq>I?K7Pi>bCtEkg>T@cjOYVdtR{RCK3>X{udV*q1TU(XtOlF-W_f5M;xU}oi zXG=7%`J#za_XDz{xGMf~0d^9(VCC3gs{=9~eOO-Mu+`#bK!EmuIUZYQp8y;{+5Z`f zu%2|EH*o9nY=DQ)f%rKltc-(;KZd-$2jn*bo2m;!&1nezhhpW6&(6Cmq(;IvE1(#( z!8A|r)Z9{4e?ip!w{o_Bc*i`ClV1iRlm*lgn~yn zor^24n^H|UJrjSpcU3ecb|YB%$p@mQQBE09FfaZuA5zILk&^)F!m^^ID8Uj2<$BHn zO$NZSG|YI#^+YK_tF9{1yt$jH@5$Vq)hjfGZJ?##=d5sgGPZbY;czqL7e|6{2y$QeYtTttSotDmP6dWe5C}H6M~=(|Y$eaO?~`TKUf@T~Ws+1~so?hLWI~99K^BZHPdUi1Jj`;f>I^ebr%jRx z_3b=D%SaQGQLL9QI!huUX+f3^c5%%accc9!5^i4dm*nc^t@JopFt4tBci-ob!zZP( zHJ$Q9Eqx3B06R)boR6T}9(a1Teyn%5+oAVye`v1z5s9X@pB!0EE1Tb?c+PEfbZA#^ zD}|e~(*bMIJ_=(9+aV}=={2;zc98aiVVEMvWf7!xZy29rx8M{*aw%FL4`0WZQ9tH{Ja^aOFYdE+QR`V{^miCnw&EZ{NpO z4EEoFlSS3C<}1o=nC!IkvCU);+W^JZ0rPHs{bB8|V~02_P}Ckrs*6uElXCY?P?61B z8tWeuQ+Xj08EL}Z)|nr78psxP$5ZT!GI>EvYWu;^DCL`5LPUZ8%PjeiS&if^7H;3! zfBn3bNwLxt%)caK$|(l|;B<7jrMw#>m_UERk|&Cg-Ey}__u@49}SOMw(w zyZS_B60z%xO?S>p`<%6Qv81^(#hM()X0m?bNrWY|0QY)&K~hvV_Oe<=bLJq(rP?Wj z^wY8;S?_W&a=D?Bp{4Q>beIPoJ17sP2;X`aSv%O#$6tlDjXJp-mok!&>h)sS>RA#+ z^@?6>VOh9rQ!&c>;P4Xbe=%+Lsv#CJuSdu-e;7z(e8HbaN-D443huf9wpTMAS8QZ- z#~A4S9V@@6{t4}(kMU}SgyWzh6dD4O-iW2-rk;`89gjYDgrST?+h!FxB@Sa0xSs{- zsIa^1f$_xND}Oxy=V79;d&nw6SfFqH`(xO!T+_>%VDPoS^tMjI4R7Ln>Wg{NtSaQT zW2!UP#$>@<5`ph}^J(-b4nZnlfgKpCA3XalMxdR)SsSV4kG%G;D`ouc4H0ZT@t9t& zNM5FQ0IOc2I`7997hk%rIVft%Xkmvk@g)i)ckYPtVFpLok)FE$yfu?GAaGldRvf9w zjpk%E2?mFW4X^TbeXy{x%B;H#o5&ZK!v}VDs**W~=p(+)#fFN=NZqC_c8vc;p-&Xbb*nSTf zR4~gPz5KW5`15`Fw2t^e9%XEAZ{L1V4*50^3Mxf0;YEMMI*<{aGRWLVwG;gFDxt;$ ztW*+_bRxSL$ACSsfy!oD+BcEfa(z$T`m5{XT5d*yNSPDA5#`BTPX4|f-^j8GkVixY zaxqTcCe*sk_Cuwb4S`8Cx5?pp`mg2cU>_t~X$qiB-Av{8`t6txU3lG+14P5f`zDFj^awmg=cgGQ$hE}D|d*I6=>ghd2nf)O_c z4xZq^!2Y$%gq#$954|w#eCa)VbY^dfKt2oLTyt^dTr#?xXoG0}CdziB{w#?K zaVmYgS>FlcJ(d4OXgYa#3vX%mO+WX`sdJubuG80hyjm00ocV|*7V-$r`u zYxMGGxnR=kiHOWnyVf$w^Tb5hJ@r+m%QnlRgd!3&Y2VWeKq4^tjMCvu;8oDkKx4;V z1^I!TFAASd=lyLA=Es?t1BrOJ`tbU_XRjKKBn>J%F%y)}HGd(eqDPgY$+~<35)Ay} ztnDIm?gsrU?y7a@T9vK`J;T))o8R^RuKkMiWLpgDv^lm7B?u5t!F*8#oK!_FP36#EA7j6{pKEhLAd%mE2~!{wl}j z|5PQ8Q@5j{274S4O;eEUcCJwSoeIwW6Ir*R&pGpm-l6gM^WK>Ld!29!{jE?x$USh? z&9kHn;#d|nrNJ*DwbLkfYp^ybxVG{R?TLK+=<@ls+QY zel5@?^!NPVJV66vwqbaosm}NlgvG#bN%P`=Vc$v4-1{DPfN(D=7g(E;CB6 zQGRi4U=sQY2W*j^=-^E$EaODbaN?bir?W| zgY(cZJoWG*Zm)L~E14J&=`jJyZmg0EJSFNrcn%S6hgv`STU9rOdHBzYSTcrh@pH<}Dv*L29hF_p^$@^p9kd~V^(2KKeUp-t!6IC}H3aW#@Di))2f z^u9HAya8Er9iSGBE-5ufv;LErsLI8IeX>02F1jk7iq|n5f+ruN-15PZ&7h@O%_LkSoWUHD;=1h-4kyD^CXgl9t zudT5}>%7MtoF!MR2g$ur+iL1mDx{WCy!LO%RC1kP20sn7*8MAzBM-{hHOa_xQ8rNu z22G&mNn+(?s@t;W-yJOL8r5QWS6=tE+sVA;)dCh;^5X5MK6?*y8Pt7!evxH7`7GNe zEk^MY1&e@z8o&F^W57Rh0vq4~Jm|j5Xce89yMuN3BPYHPj(f64p0hM;216o}3Z~^i zF8LZMz+)c1bn%=%=zPwxq*xAzYyk~3@g_XP*hTwzgEQVKKcIx1Q#>RjMC^J8mJt{m ztENUqwlk0;o)ydKA2pAgA3V4^0%dO$o7K3Wq-exWPj?-~h6|5~^&|oEIu*C0p?}6# z>CxHx``fnE-93XuCu`0bSvA`v;QFX=eJJ$ICu9ki%dYu4qptlF)t7vg!=n9ye1=+y zX#4aEJAIB}Qn_yaCGWu91Y20aVXVh;)O|S%v*G$^Nyti(98 z=R`pk<`lWUQJ$H2#g>gn2?^~$T+7S*U8!b;KNa+*zg?iV%^92KwqMmBJs*K|(#KUf`Hg^J;~dY6z!N?pKU}uu$sC&Yzm7wVz3cq# zfs-n8<#wtuhc}`ru?34jllR?=~*j z2bw`4Po=mr)wbbord5o1aFe(x@7KSBo*~k}e7YNC+fzl_)0Q$+ah7z=WZ%k(olYI9 z#Es3wzu7)tvgdX{;*jp~>tMmWw1W)OuH3_1h~emcOPZt(Xf7VZ1dqb>milr$s^WF$K4$fn)R zJSxqu#trOySabF6RxzqLA~y!^dvXi+wQ14s#>Pg3v^(Gp8E}4rS_k2k!9jfOKrY1_ zJ&L>EGZ2T{^-M|88)T9w98YV@+{d9H0^x@Mj0E`z%9@U2s%T@f7m8fwYk?!yi0LwV#9*aW7* zLcYIQXSTgm;wF47S;ZQ^1z#m~d=%J}7VQ@B$7_1Jfq5-gZ`*!6d{SuBmaWHxk7mv; z`dATU*`B*5*AIm>Wv1lti~nuSKbz8QHSMEhj$JgJsW!26dK)5n?BxEao)*6!hbl5S z!T{5@=N0Zh-`yG_I2~H_TgbkG_^A=bbMGDWZ_m&K@Q#~gDq2^^U6Q7VFF0tzDf9?G zGi`!e=91khQZRmIr71_f7#&VV>-O+1<@{AtvLzoEZqY!;>8Zkoa>B@Z?2ZnEJJnCXK81 z_^f>MOKeoE?E({lx!Hd^x92}k=0QqTX;rhuNjY&j7wfZV@%AeZdWGdO(q zm0CM7>)%~B`le&_-n~_3!tTO9zM@qTkZ0xYkA6tWLMKQjU>W1i7kBLYeG(3r(a?M+k=b)Av0}bZx&TXQJ1tyMdIP0%3&X-Mk)p zl1V<()Q`}j4BQZ@fwN7*r-?;Fg7$qq=MY))99!oTwjCcv1*mQOn=B=NT35yTIF#JK zL2v&J_HX-GF8E#AgZEE3ML(uzNf;KX1qp}st!N;VvvX^s<6Qeo;#3~Pp6=9y0t#NT z#qjxbQl7voD!26iV-x^LMoZxEs4MTOghP*yK9?oB!Rdo23=S`(acRL}M|u54vjwy} zhv(9i1XzzszO6E+ZheBzTOU}8(v67Sv+0D3JgkdhA5&jC2>Fs!JMa!Xo}$eC{AUI2 zr25H8O*C04McD2lYP!b8;)}IH8Zzr1(6N_?#P2HBj29&!2-spor_E`FZX%6uhPXD5 zK^P%&Zvc>;h>1+dqgyBM3Jt^5=#zrmC`%Y^7%VGGvbhb&q7!_3#XnatSmD=69vWg<`;Yiiy| zD^a$bEyUiqlCOB{<4#n4cjZn$6zg_C3V6tVg~H17A0skNy99k{_(+N^;NlH=zqGu4_JE z$)7{ngi4yTMB&7gC}UEx{tLWTGeL(sQNZ~hVZPG{ANv9;hkA3=ehxd%!*HG%biNb$ zr|*O^7EA+q7^B2um}iSB+_7^QhUR|ZJlh@HU*>dnpTGqAa9Hh0p{m_I$M7yv(1&V{ zx_FAMRhgNUF~{v!+Vwi*Gk@dT zW}Y;!9bNnW+*eo6YAYjun{L=&mb@U1YZnJu7bt7{;q!{;;FWfE9;rGbHGgRM8OIZ@ zJ3FoJo>trd;{x;A&A;sOhl|x0%$dE^0<7dxZ_M=sYG2;D+cU8pAbZSU-fmZ@!^zsA z(ZSYT1GWJeB#-be2jpY)oL*pKyse$v$G+Mpu>QU${Cm#D3jaJq4kk@zenNW+cgm>z zdTBkwL>+2Km9Y{3xzV~2~7li-q>QL~xjWP4;g{{-ZXy{E#gN&+}Nd~#4qhTOU4_o=a<-0_j32!`ZDyXj1&NV{Y&~MP5a83pO8ctb_^>j znh|}J)LIsH!hLKQV7b__hC&Kubqla>)XZNnXYQSKZfT$%@r+8hLFPQ{%>`&rc<+(X*?ly>`l! z)KK28nOe+=g#?@-bE-NF#qF17UadtdwPfSl(dzBp97NV=4)Z6n^ya?Syv&-97*!QC zTf6@QsN7V&d-@-Xd;#7u1`nRRMQ`4}f8dnwd-%oSF80#?!*^IGw2m^_Eq{tcu&4h~ zc>K#`89Z4rZY?2cs^C>VchRaWJL4L@PR4h^(&sA!$C3;_e$U<%oCLImzAUZLpt5Ok59 zzxfXc>-i1iV>G{22CsPnF@rJ8Y?4g-UnaKZ;#HFP)hHSr6)^Ej;p~r&Jw7^+#vLOr z;Ie_6P5`~XSq!hklR%fPW0FqpE^_tzLrf=UK5)quYJq9RU36x*K}J>(ufK6ay3Nq! zKar;_d)MU_u(;jpSo)HEy2NKPnfmU;PMQG;=MiM4xT7V^%>d>ILuVv=# zH^Bjn5k3G}Gd=wgsO--1x$PlQdAo7rcN{Q!8?BUKXX_GlaMuWFEMPJN;z~AJw7k4% z*6q+Z483~sU46pQZZ;GDUdPqZF@{Ljh;e{=UBjpgN;3IU-k3X#>N!w8cMANDvF998 z+d~S2Kc25Qv~0A?Zs9va!IQNiQbEeY0u(u#b)!RRzyjrj>}uwd!d_{JbpM|^QrouKD4`gb0ZQe`X<3=9Ujm3{_r~nJSm+ zzcMyN@kH#ju3%}{`yWl6y~{E^u!*b?jmvk0L*56|Gc6%7+Ps2aDp;8Sp4nh9@Y=+p z_8jZnHIpm&-ig>R;ya;?bYXsLS$kR*5?hBJ6mI)#o|FznUvaFTO1o9-t!97F-|ynn zjYF7agwfe9?|eT zsq}6-`{J++e)`KoOs+1dxRsXG1EuZ5Vh)MzGL0RsEjb=2LfQ`>MJ5}YnQomqeWS`U z57l?fjJ|PG-Yv$%zzvvLLfRMT*P2wS0oxil1um){H0^iRF^ZYY&I@21m6YY5cinD7&|$5_JMmLTj>)VagWoTua%x3yu-&P3p3_ zrXpakZa!iL3EGLKo;(;zumybmZ}ui4ms9p0KIHu1m2IBLiseK{(p^CLtGh6!UviI1 zKkLWPNZCnyV7^ysHAw!Oe=J@^Mbgu zeDN}jw=3sjwvuCHp2`sQk%?IE@$9KC-S6t~p)&M(f!PtMRQDH{0yfHX(hM z#Ot$>+=sAlxA(F++O~*G^BG_UIl+uKr<$!~EtsA3JTI_5urUTEDu=CC{y@iXZ(!;| z-97m|uvtVSyhHF&V*7=iQByz)DaJ)s%NRdRQ=f0OIV_NmTAGf2JFII@%t`UJ($XL> zn?q2Z)jQ~r*DbsfJm`HBt0+zlS!JlzGm$PWkkMZ&4>1s?jpoKAszXpL&$7N$n`mQ|o-;g|lOKay?kg%yHL=7`8#l#S1KJ z|7Y{eFR1`*DNr?8#V|@?+@je(yp07`m-bV<-9YoZ_x2$v@^ZS&rhhCIF;qCbV1>+^ z#HPp_+lf^;lrZ8}JM^7AcBE?Dojo9KDoSep5G!n>uGC3z@<8~Mp61#&1>N(hwGYv7 zR`8$ydBou8ae!yG<@e;43)O8rBba6B%$@`Pj=0@QbvJQ;06|F~_j>|q8Lk%=J8!(3JH3}kHDCGP_y z81l^idT~m{62>><%|&JYM%7nbswk4E4WQ^*b{;6@@T1?6$ekkUn9&n|MrW`4zoHa5 z5S*-!o?C>rQ_oRxq_c8-sE183d+8U}7qg?cLcU7H|M~?n!!Fl_c_axrUq;ZlaRLpGRDxqduNm|7x!lKP@@1&Ht@E?y8E8)6v)xn4xk z4|89QSL7SO-(~S3IK`wGJ`wJ*8i5WLT@vVD>6j%g&3h_t+cOw>?uVK|Hf&|A@CM8D z&g7C1#wE(svL15dUel}B*3C<#JHxa0p{e65-ttaq25=Xy1Ypl(P|QV&G9LGTFe9y& ztt&DjaxEnLGA`HMGlX~>55Y`1>C6g`*wsmjI|TDWPT=m>EKmnC1i#%gKH@$j2@9d+ zaaq$iI+>(;{c!Pw^X&7rcFAo(v(6eFpjaKVBfLyc_?I(d0sOB3>KBokR)h+b)8DR zv0$p)4$QWa%SONv_i*&o-h$xhwI+mY`GC+&r}9W|kM_6pkXP;|@_1xuM6L{K*_VVD z)$5K4`Sxrv)zs9iyj<>vbEU+L-p=Xzx7e#2)4?=kwF+MFk3Ipz3KY!_&)lh_g76H9$d}`MDE3s;;)Qw`di`=HX#x+^YFec zJRsFM@*jOduPhp-RLq9k`D{ejEuJnxGd0V5#v_52*BoZAYCCdG`>(+qn478^pfA=- zSae2Jin?3&L#Wfic-`Jg!mJtB2Y&w=wj)6JHs@VR@=q*w7;1A~z%a%1%0BsL3P0Yg zFQ2@D{KPkr4KiMNAt;vWI!>h6!$q2~P3Wiq?#p}aK)z=runb~)7M^9yuuPER5Urw& z-(Rli7RVsg`s&zc`)U77%*`E2#RJPcXt4sY|QgE~=1QpuYUc z>HIp$>f;Uy_x&QOZ?Ocdi*Y1JfEel$b(3I@L{$N-C_=!g3&AN4EByPl@F{_835RY+PN`guoMIh)a^L?l&S5~gXYEje;gg5MAA^(x z!U?#&aW;=aEy!@%&0f>PQG1HAu@djt#H8Ei zGXp01V7>d@-Mu4TDcKR?#r6_9-mt|+OR0d|^9-P_?pj{w_3Y_Q0+0Hctrby%%3675f3 z=x_9G!+)JVHGe!yN-GQ>vJB5M0{6S3pY(h=#-VF8y0##>8WZ;-SuB!o5TO3ErJ2qB zfoxr2?HDDQToZ+vR1CWg#x{gtSyUR*>SKE)n!8ctn zkrdi`^H6C&pfb%&7th2AphXiv)e7R8#wKdKIcTu=W8H>Q5F z+_&#$QeCLYbv_^-TVaDnJ*Z!;hIbPoMWs}qnJONqyb^3(zXiqQ6$vi)C1enFsnkX5 z&p1uVmdQ>n8zPnqFI|MLkr7X&*Zu?bc^!cV+SA3uP7>JV*r&6dt2K(-;%-3O>f9BvR}jHH4xOjb5&NGH@sdd&BzDyrz<1u=4tB z8aHJ-=j!_r7R2m4cuae+n+SXD=H@a}DNNQVTBSEWf^{F^T_&wDO5Sp!Y#B1CQOTt0 zJaPq{=Wjr|v4^R!K@AzpM1T&|og--XZ#rlw!WG$*Es~+kBQbX>4oZ8J7`?AcNA>V^An9C)m=*(;;QiteI`R z@D!<+Jqvx3WBJVB%(O%P*W1STZ2GX2$3@%s+4tFODZq7#h8QfTB3Heda+tIAh-O1R zMh|^pv!B}N37f_y03pSfDfR}^xA?#P9jM{>&W}6r8BJm)TrtD-?{$<|YlNfseVVy70ZR!gdld zitehr#|hZncxj$v4*kElmDg^?uwR2=&hAyxe{8Aov0#%I6X7&yS{7}Q!IG9=dowa$ zo1Gu}yn7NH zo}k-DwqfTBSp)gn&X~82oFv@`E@!=4@6~tr*p^i!XVQ z@09y#Pop1LT;huilJq6Lxvq%eL`f~eiK4S8JLM0?-)0i{%*G`21-|*8mUzZ2Vf^eTF0CJ9 ziSdy(#2wdHymrtwq&W&tF6+q;m!_}~$*D}G61jcB+ikY?c6 zif(v!y1S^g>9*C=yFA93gjGVOW@c1x-wW!vcRzOBg;ciF>*goN-uYlUM|>_1i;A+g z_U7j+wD=Y)7pw5_9J(OD;UBo$sa& zSJ$Y^?L>!B?>U1zr}m}F$&sQ*k<=?NW&3_>KJ~xVXi^2kH4W|pSH61n`fQ=6I-f}> z43rCY-u7RSN^W+py-e&i)3XCe8*pKi>mVX@?tN}`H zN0_udqY#!qBCN;0*U`I438%Pf=H5O$z9g1UAQ2c2+Y0wdEAGVU9%FXjR z;}1-%PGphvvDfT+U^luIYrF?0=^ce&2`u1@2MJt1R+-Jf+O+i0j(JA(^6@Fuz?M1v zr}|Z$JaYaW|DRlyTSK`;F8T;}LM0@>E~p#bwgXBxit7guP#ShZixW3UjM)j2XwlqJ z9?`6K{IJ>j#XOu>E{P+zD7mwY44s3wtL*vTZt^fBYYq{A*}d4p7@Q^^#_H}mkvV%M z4v`HI+RK)SFo%gm?~pEIDpzp0K?G6)T)fQUmtssdFw<(uWMX*nFf;NnC2w)}u4U9+ zu}w~8QHSSxE8S+dYCJ_vrFOi(+mIo6LrP8RfPBd_#<59PSK@8P_wT-8_OoR7?I+F` zokzbGj~MiKt!d5o#14v+OHEGg&Ku)Ae#~@D8b)SRO2eQu)x==59HmbV%V~{8qiIhE zPU;>zkaVG|Hc_`9GXzLsR#Idds{5Wb>3Pu06AjE+wObuSlpeesEe_>w94!DP(|D|J zCh78;_pqIjiCR7Jhj&~*zbo=W>gx+W`dNv2#1 zi~FYZh0>k>6G8-Tu0`{?y> z&R7(uJh@KAUoh$EK+?;Bq>`QR!D=q@@=AXgd?!RFu<*pklV6v>XS3ZsO!{~rJ!LYm zk%Lz}Sij+D`;?oeeM9HrC@(YT!A~uR;T?TvyOcBZk)&`*=Bs3v%X`hWK}JnWZBN@Z zAXNEvXMf)Z_95%sRT<|%R)Iirf4btx^EzUyHidxY|!;EuXvn^zWPf{O9u{fw>=1xth3K7cL*Buh z^0TZq)s<@6;DG^`ji~9hMmyLKErn9xCQ&j&Nw(z4m-&4;UjG0^4Xz59IMP`?U0KX2{QE2W@{U}##_#0K0>2zf}|_5k88p+^`!btPTS>`w(!tx z>tXLFt&QQjXth>~O#@2@m@9FO^MtY_p8cDJ{;hxnl2|kLjF(5qw;V{aMtXX$=q1FZ zN(d55zM}wTygnXQy;qi~svmNc6l;BT#phTD%*M_QG%QVc4rZlQZuvnxgQqC!pNVW$&p+@1}}@5X1UY37`tNAs=W-(k()yo=Vd>#SnRYU);*2XA9wYvCNi z6fAfOBK%MmFI3#QahBA1Kp1RwVu!(k)u>bAorp+mjiP@f_4b20pBy){($7K%ZeP3l z*ouqtqYL(hD+5w5I!DB5UAV{nkI|-TtQ53#R378Q`;pfxAJc#*S; znVJ%8rfO8OP2<2(1J?gq-x=I8^;{qXi-3+mHl9LEx6hD0^LrX2>|#}wwpGiVJ%WDI z{=)N@eoKf%E!CGu0N+O{%KN(?Fqln*SL|tJ;p%BD?~!)aFW(0tN*^>3s$&Jj!i0zh zIGa$esy7sp2`QHZGY+|nT0amiPPs&Kb+bvxVR!pGKb`HX$qAHwbkNAEUbtW;bkGAN)~lhYbZC)I3)JOr~T-ZAAA~g;>Y~uK-2;^s*NAhFCpz~5t?AN!ho|57 zec``$UsMD*Sn5G|4s7Zy z3tQsEun;!UnLOJW5t_Cfa@|>ht`E z#d~&>RE`YHqYE)2Jb0@ghwZyv?D6^tGQ(_ zed)DqE?g7oQgjR}9h4u|-d1jKMZ()g4K!F6$p7}_@mnM_Hcrqd_!kzXou8RH6KWMb zbkLqSd6=f_Zcx@2%$8^?3ssHOUhm1z?>SO+Z6MNi7d3=BdWfo2dlqA`t4U9bFt`~H ztFd9GkEO9)2;1toZo{1Wi)SBhtdco;^DIDl(TZXQsrT~h-&u9>?=yG#3COC61QF|W zfKH(Dcslgt=>^T~O({O#{*rCHQgV|_w@$+XMg-VMBeQnQay6FF_p(i`0x%bXg-f3_ ze*T>ikfv`o#EQou1m*Qp+sC{dl%F*@!Pip84JOb_o zc{%0NJzrDy?8YMzTHpP0Z?%Y0G|(djkZEZaY82_S`SUi zO_a^!eSkUMaP_!BZ)303;j!!xCcwJ*E7$XnJa=gfI zBa>vo()c+q16Mrcdqug z9(k|2HypXza3sXoU&F80NN3|A(eDMA3Z`=ASv#Vo$yfeqwUEj_1%ow{@!vtsAy>38 z6}RelO+PQ>?vy`WQq6J|WD2=Z0!XoW6~e|TBh#+Ae#!yE23v@EH#;8g7Mu-wRf5s} zop~ZLUoX$u8`MXv_fj8JuWXVUdRE12V6xcR=ML7gJR`;c6>I+%YT>^6frY7aWNsH% zZoQCtj15OmU={Pk*&0x3qzEbp+Wc4qlBcJNiuS(*uF!IrtyIz^# zgXO)w=YA;7z$ivMJp4_fFQqV4Joe;KeHmp6oaGh1U#d&cUcVym&WSbY>v9#}YaVZ( zyZ7>f$5_8qx%xYB}3Aeflo&?aoc~=(x!>g{|F%3yE*x-AzaKgug-ddW=Wu zo+Y7|pjF*bDYNp(9P*5nX;@H5oX^`Djh0xS3u!v`b*_@>UrxJZ#CRm%;Roa8)JGJa3OLFEe%N8zjIIbFxTkt#m-(<(`3 z=J3S0a6z}S+3oqWr9;+6flkrG)y&qf+m?i?uLi6`pq!RJMWpXTud*2@di}2gwSAA4RK-xI;gW5HLdz=FAjL4cX>@{lwC263r6?~(WJI}doxMws$ zz;2wPS~gqQHX?j+XPAYv7(zwpJZdO0WmU&JLoD!co+Pd00cmEExKR43W-EC7&DHA3 z20m^=Z|2Qa*A7I^qzCAq!x{Q8f>X0>Q)Dz)<(Ry}FfYm6FCiEz!wMz}Gp z2Ol=tfaw*`q`UVu*A*isMK@E};8gbHEKj+{mwE94(Ng@!d}J|H+e?!H-rtryctqmd zu*dC!&u1;`2A;_cHr`S(%k6LwijJq=stN5n3?nMyRGz>5rcTH>%x`K)6EqQD8fg@( z$r+uR)6Tx_?k*fD%ewIlSCk>?Q$sH}?YGQyjDc3$-~=1>`T_0l=hum3SAY?p$ez!w z9DEA+`p$~8hL4Z>BnkJ*R~Q*-Es^*;R#GieqJ&(l4HRyT?>u7*La!Z0aHTt{fP(41 z`eI&%#jM2Qt1~4-|AZWjTk^BHm(in>d%iPrnSXKB{r&wY{9L?V*z9pO+KhDtlZa$} zmsi?vnrh+ea|p?3`s|5E4y7jRG`88?9T@((AG>=#7HE@eKYPsuPP6EUe=vON=9q-? z^P6+~h8wX(!xlPL8&jcTk#O)>sUTEAPM@-KJS?Wt<8^)Ts*mcliqdX z(gFHFYN$Owb}E(>JP#Y1Cff@k_%b`=CbTWlPDpK%e$H~)#wBOeJJ3!XSp#IVhRjUu z-rQU(_SVe3`@tAM@7!^-vtM~@((C>P&p0!shSRtj3yrR;1qrw;TxP=@Kf}JEFp?mt zrVewj!j$h5b?2gMe=EgybC~<}>T|GP8xj5zZ+2A?$C{sIhTZD9fy~b)CTV%>BWlYwLZCH$|qj-Jvqz{$`tP+{2EZD=F zJ-_owi|X*n4Uk)FXMkC$JaH;x&3=H^ud7PcYh(W61vfX-$SgOE_G}O5Rq)-T9$#)` z*!Tzxu)?#21F0xzrRDUufDgGY4(}@Oobhxmh>$z~21+$%vg@Z(7Pq~fev)(z8{0ey zySC>}6T#`k_zl1%wM0>CzjCH$fTFy}_5R*%yU(!=;?kd9Qa~71Z9@IQ3sQRSv$sUQ zxh;7&Y5N2uLC4=nNVrmJJ6siWYAxFUS=}&=I_UXL#~+-FkHqru6BOC$@`F2C|K}C> zMM9G_yrChfHxcxVT(yfam$>)3D0Zz0HE~j_zLZfcoALDV`GAv|d^1*9pofN5ylX9W zlR46GWXL7wlt!%VOr5t!PTTgP5;I5Fv@P7#TQ1toRKC@kGk1Zi`SQ!eFHzaIm@vAa z1bNu2+j?NveHTyFe?7~5i%6o&Rt#F?;;i^i!Z6+9o6Dv3Yj3KMNx@1xbD=tx$*wXRK`OLDEZQW;0r?vy~*i$3%Q8@5%mmkXdFyj1OQ-<Ox#HS7of zfPi75v{Zn$i9dQze=}>Gg2Uny7%`989$Y@jK&b?7K4La1cZ0Q8@6o%Bf%dF(JcjXZ&acz45YrP41nDXN7IYkBYYvzE5*a*{+IoNb zJ2nLgO%Vxji&r+h*0HJa&e3MdJ$LYaO+wtwF0IdE6ySRV9)_jG2T>+#vmwk%vfy_gIA z)t5(HN~0PO7jTQn@Q&>OmU*tb6x4!XSusic16!PHG)fE8)B=sT4VNsLvzN1OPs*kW zw*CLn7#5@%cQ374MzJ-xAkXOZ{-1XJ1jwYmz#@wGYJ*3A(?9UY6{QVC#q$n3=;X8pfn49f#E`$u9TT#vq%md~}!jA(jNf5Tzg?1DCs9#d)=TIS2{3C<4N$QlC} z+^CyT`%!=QKU}$rLOCdjvh}#T*b%Wq$H&bl>HbzgO9Ht+g;b80L5<;j$~li;V#s9lH0qy6@ki> zde)Qb;y$D5;FN#+#8`^(gW+bhR?bn|sOr0#1#jT*?tzVa`rn}F>jR><&}BHfxzrsL z7VGo%l&(4y`T9b4_quRJ&{l5|YpR`?kP~d@w<6A%V z3ih_>bzE0TT4*=CUr|aX6?5=@W7x4NNBjk>UY_^IvTP8_n&ckbW9QpH`|~%8u>`vx z)=SQ2d)cT}_mBrf?_PFU`Tko2OB(uUA*!3fg)`=&Y?Pp9zh8uQL`GgZ)1Ov)3`+r= zgEU4_RHtrqRNNHIm1@&EVVc}wFZ68kcJ!{h9j=l!XRu4G5mljjNXKCQ;LeJi+IRq1 z#(0k@2sNdjivCo)10Jx}jD@;O;??O`|4z!cA411p+BoGuJs0wYOrde+7XCW@0eu7^ zU^P!;-1`Kkabg{wjSOp6QY}hEPp+c*DE(;zZ0PfJT*iw}QZ-B#m^6w!u+cVZ+~44d zBqNyREiBnc)x?iO{5+FqDSlndk+^h`$3qD5UL+&&mB$J5As~gywpq zSeqv(t{WTWQ|51NGu=j&xuqUs;e(F8q$VTv3-J8`@eAT>DQewqSja%NBfMmj=dSJs zR=KcBvV~C%>TiV~R|pg!mQEIm8G&&#a(-V>bB$9#$0S8Zcl2y)Zr!Epz)ZJy>?M^F z5v#ngORLBh*6nJAJ?U(38zvR)uaQ?W%&E~))3YN{1o^jiN>7hs^N98cd#1Tgnci#y5`J& z`2U4_Z85Ur1x`ju@eb~bj4+=_=-U#p2Q9H+w(s6svgvv#{5O2<{5=09cHB27it;^) z54b^6k+#$(kn^J1s)!9$k{Kzv+~%JSag_eTo-bfrJOLxM zNGvPH;xU90LIrECmiD7&Ixz86d^4%vyQOPfsF*nf(HjEbgB)@CZ>cS9ro@@yY}&cT zXtgDVl8LV0u#tB`UbQBc5faX+%cKpn@n_1eiSuZ>VvjOgemi+unFW}NBgJNBAb(K3 z!sZ;&`{YA##k5DDmqpYw(q(Mb^8Y=u&&8wFI-W(gs2D$EQyixzbgiT*ZAV1l^j&9X zk?4Ip*95ppJSU-4U`S|b-Man%wh1a7WfyHU;QZmK*1FRNUIC3b70b4Wl2VUt5Ow9j zGtcv91kBvpSYg|Hn*K%KrwArv#j6i)JI3$Px7jkmB5|Z-YlF#`z+pI#TEUaR2L;Mo zOt7dIp*b}|h}WoV%=AC-Nb6_`3iqgydQ@U0h-zeY!!4N+ji{ZN@(uNTqj1XNqCv;SrcBCKy|Oq*U{YJ z`|caY1;?2ustBOV>k*R+p!Z@k9c zZ?dF33E5y+Ep$|Dtzxa#(c5En4a7yXz(()cIv~C+zl>Ute|QbP_#?x z7~|NOQ%qf{Ro#FuNj7e~0w)X?7e0r&(%x98I*D>5`Q^>Ed;72_)VU?($!*!PHyV#H zF%Xh}9qw&{i*)EnbkyuMetFG1@STffI#^m~uIm6VwcxxGtVN%EFdd`j8Ra=<7=G+2 ze12`=VIA2I#!is)LY|)|kjRtK@>yrSpNr?dh8Z07_`8*pgv}I^t#cLDH+K&I?G*m6 zSicwH&7MTK2sKx@-{^{eb8+3T-ulUXW76|wG@n+zJMd^*(S7n-%3>5x&|7L>Im^_d zWD07u<*E(7D~Abrl+Rt{a#|?U4PGtke!7?`P;_R{cI&hp^x_nK77H$xeLhfkVIjklTSW?HAWuF7 zT+5_AlwLUw8JdPd=%`H5{BU|qs01Dt*&8$@}a* zlyjW=yQgUL_*L`t)l#;F^CYyk(HM4&;HRj+=3Jn0;y{J+%OUGZZupWuEXFw1R3~3N z({}}7Ny9+YH&3paLEToSc@Mnr-We&ZK2emK*CU?&W6j^}02Y7?F?-N-HPdQ138?g- z`@V1&#VzB>`VE1!-P0%ZBSSvyk}d6j?6qjgc@|2zA>@OvcY6_IksWQG|0xMnvFPQh zFFm#4>|HC%$nOMgs}hN(w?a|%DE=5g=;M`fF!ly>Mv};@rKC0{qF?#g_FZ7{} zDs6F39LPhr4RO+11XX5oQ0Nn{h)7qL6kgjvfq3}wwC^WFB>U0FL_T5flB^Yrc~X6% zu1NL@KE?y*GG;ECo=74-6Oo$42vo0jRsWe$mZweuHb`aSSUENQ7>X~079%za)NSqH0h8OM(t zGHQFMJM`Sfdv}!OIo*Es%gV);O=%6ogs8^Rys65j#4m{+8*|NOwDZL*47%xIn~z-n zQJ(lKWv@-E8^tj3VBnmr`(d_&&L+%;umy!|F;P`TYed(%_Ije^ZbUZZ++uH-o0Q!> z6*%}Pu@}GS=? zoshR>!*Ty=^@DY8e=A_Cd!j5G7p~*UHK4iVzs;|`y|bQ)c5i8U`#snOkz@)5l@t1b zPq1rp3u1&MmT!#<_9bVQH9aH&i77I$!$Pa?JyKU`duQ?gN`+QK;#HS@u3N8c<HcwD-$3)-T~`|H+y%_z4aORr)x|$f!kg*YFKt2Hn>>t+(BlZ!&EX)=OTgI}yDV zKaz_<%r9xd7TQ(@-508?hskUW8$Dg?3zD$2(1{D2TMzg~{747U7?s-X`<7M}+VrSB z5%zdQjC~Truh>9i-*s|!iM!*c^j-$CKfBz#v*Ps=m;pXPgh9@N8vw&T>2S&30o1Xs z2dSH9y-X*6NZoO*CoZV;vxUi{5Lk5&5Qss^At-x2T+|*uAZr62BxTaQpr5`a**2%? zhBQ1XjFW$VtHTW8hS4A4ta6s6V}B}9@arXd``ho|fuBfIV!FvK(;z$b*IvCUce|)o zv=aXkAb?CDD?D(?ldbJz?^?QcCVP()`#Z_q?Bag015J7iEQ-ZgMquNw3Sx znRm(~!l+~Y8`t*mnlaoLX%K&HXcymjQJJ}qRsmLDH%L0gy|1UPTfV>9r9I#l*5-B< zWoZ~8Z+B3)agBB*J$6*?<=<8`Wl5tu?U8y33*L$6`QKj$v|lWlt%}GOabrmN`2;8* zs|uKC_tuo{|CWqiUd~2-mFIlgz8fo^viM9!u1*2h-|Ko`#RA+1dl_`Ow1)I_)oN6! zvp*?HpSrB-j#b}6lPWSx=yM~SKf}Hj&cx*g5mZ|ARPA^oe+=_U(hV=t^3p%-GH}hg z09?UOfTnXwZ?KmI-hO_*-*m(j5F4@1TI@ZD#xBI}dGw0iAHjk(!OU4)Gi#JgNlgLs zbzFH|U#OHPTjZ=A?<^k?F z3UINcTGdOhX)#Ta-onr8{1)-NKrADaUIJDaBmw&~BlrF(n40L{4)28Mk-?nHlXef2i?&i@CPs{NrKcq^xuKxu@KQn!+}1hBtjThP$)4_dz4W zkx>3yMP{Tr@l){9T#r#GA~wi453SYS_XZm%fXn2|$}{4apxqBQyZ+C-bowVGQTYQJ zw^=mnXv+TuXV65;!>;QN+BlfV+7Ud1B;;`UB;FZgZ&nYJwnlw=KG7lZbo>^fzalvW z5ajGx_U`ZMaqu(LSm&R+qWl<=D+AO%4~KLrHqE?MPX-!-VDn0xX^|(o6LZ7DEQ5I>@qZ|NQ=OtK~%n z8I;eVd9sWOO8r^4cUd^OEh^e7{{tqBk&t&=fCs;O;+6Y?)4Dzq%RiJLVQnb;8(;_h zY>?GchK&ghXb*1vpXQE>jr2wv2M&AZH;;xdxrikN7+_FH(`A=+HE-;Br@gM{uLEGY$lYD z_~*FK)#Fg(SVG9^eZi9WR0|SnX$1&G8zBXDd?`8QSk&Ce}Ktx|0gXt8*ZB-v4Q0*Fkz0A9L6%^w1-AXgy zynr4(1xblvN8ldJ>ImfZnzXdc9WstU_>tGZq-L_gmZ~cv+#1*3mt1Eu4=Kcyhq%Cn zwI#In0n8{ZXjGM2wuWpWPZJv8)e^AMLv82ez8%6`;!R&f$F5nJjxCOo>z0FAOj*ZA znGs{m$`8KYpAU^rl}g>D-&V_mHsuj}Uf=q_z^(wC?)Ax6u@Akoy*PBoV~CQg1oFFWfFY^sX8s$Q z+tT1ZQcW!M_Yn3Y;s38cyh#+^Ampkh%r$_@FRNOxk$T}Wt!!(nc#C?61%at=Gk?jO zfwcW%aHcX>Qj5T;6w5C#rSVNYg{nl~jWe6N5Vhcu$)ub=P6mMIJiqG_&a+;!!B>Wj zno(D+bx%-er*X4#FWJ{Xzvw-mxCgz^ZJWawB_)k z??h<@HoOrYm|9JM)(wct8?pA91?46NwabOeNs#4YZt0z}^!Z)KrVhw#^pI+E;-t*Gk(f!z!z1ZA~Mk1|P=?jbe!n26Pz8w_Kjq&a^Jg4~> zlkBUJLw7>!GOYuMs6T_oV$UIJuo?Sg;5BKC&V1ZP_fI}*$WwRCPrO*NO}(UVW@D%E z|3p^;MbvNOefji){qtVih0znUR--=^Q|_hBCtzYgRJ6gLSeGpSOvWuEe~uH$Jk^-Vig~SA%renZh}352Opm3Q(=e6VW9QKf($Q= zbD#1DRkz}4IR+ZR2d>BN!mRNe+c?E-qWkbk%ml({@f32iH;ufTK6hAl*9B})Z$Or& zTGEd{B$_R@w4b&GA=Y__Z8^5iXDJWcTnbcT*)W4^1ole~4eQ|xFD}m`A@2SSRdnSZv!3_+>Dt$gOZ!Lm?VL?2N>mL`2gOe@-xG}l|$RvwQfBiW7b z*T9$wOXnfc$(-ffhk($Zl93BCAUZqp>9FFNdiwI>shS5ytu5M=Uu*PPeTm(;YCr3O zMd4ITCaw$-$LvRmdF;*GUZ{KZqZM8FG$Vu>8M8opp{`>yK!(P>y2gR+7`@t)A)mbL zlGQW(EUE)@htpZiR>KZ{cp$aIx<*R(pw`d_vs#wik*MyuVwTC{Tf8wo5ww!f2J2S& ztoNfT^;4}HU%)aXw2iy;!2nDal7Z}>*=cxvS_QP2LgoNuDAuil!cDdI(tocj_VS5W zh0K0q&%?H9z4s|o+KIxFHBRv4@nCo1)j-f{Gpnz2KkG;`9g7Uc=^)z8xd7Jb8Js^4 zFKH~us^%^Vo6xkLiKi@PidPwd-mug989{xp|BBb#(c8L@=YB~qZLQu=HR(OBp8srv zd84wjtU2n7T%l-rXBU>(0(p7p4CV#?r!P0zsug= zRs9VGsoXJ_uUva1Lt2iz?T>7HA^Z(~bZkN)pcQ#V9Fu#>c_~a!+)g2ICJP;7zyY+uW}JjH6FVN>w+~6$D2}bmpYLtXuut7Hhi1h=kRogO z=WaqC2Sg^#@#qcn)C!Jj@YG;jC|la^y;3@fx$YYjPj!TS!S@(A_BZql4Et6}PzKhg zBIRp@ZJR-K_Dx5Zn_-&t1NC)MA(`L`pMiG8SMlb`7g;uo!UvTEbK+j7BVAL!-h`uN z+xpYMxQUlJi8{~kLb_JraHF)0fOI1hgYY=!h!cG~noeKoG~BS+VIs1X7i;3`e(F3Iua#t4H6Vj_5e72rrw7mdc{> zR3`bpWRNZ;kvG$>d3V`YU78S@)c)n_si9pW{*7~=>eOf^8FFkgmDW`jcu%1Iu#-eF zPDo&h<0rUIG-v+W2Mt2=xnNV=4;d&M3{hbn9aXJ7H~oT->QhS|5!iRTJC2=3fMr*f zs1y{OyCsm)@wuQt1}*NM$7{KrIwCV2e}IOjq+kZHR6Jn<(;La=Woja;B(2Og+b zctteemXi~5!;P@gVpW5W;*=d;V?3hgfG6?oG6-3x08+^PS6czZ2$PLJ%cDCtW3c-4X+{bD zRIGJ4PH2}C)%a1s#3dSeJ^xUiy(&CG{*Ag{U2(van1Z3AoH5o0peq^k{!T%imo8+m zi3w`Yqjo8~voWFmYw3HPO-Yx^;ZNz0(|KfEk3VjKLB)_LXL1oRAq$M$RJ4iZTqZ1o z1RD?Pe$`Jl*rOXOIaD`?*8cxWaxO0v->fE7v6XfD=>qSF|DuDtL|P4*+_D`bd=(2C z{&yKMg}eXS2n6CJVc7@PFf$%iL*Z#4b!>1)d?BonRXH}hMy@M$BB3wQG3SmT|f=O-Z%)9qnu5or8(^o5}gFmLU&N`=h_xbfKJUPv| zqJwd&)TDuq$q4@jSCK8 zqD))~$IbPJXD$_nttgGc*UGx=48C?L2gu#jxzE~xLoljwO4i|zhNsXY10|IKaEu!e zRn>oSoaDXWqqN?dLrGvtK3vcukX44nhxX`UgyTGk9>z$Ub#{h3UGq*CzWg*YcY8ft zSngeFc+HQ>6GXHYF&X;~qco=NdSBe#S8{naQ416-Ja95Q;`O+(|U?|FUe!$(izfKZEYYB{#8j8_+2<=jf(bBY7LM;m+s} z2g9U0{Tqf(A7Fi|bpxhsP2d0p*)G$)q*du+I9~K{$1!;xF$R;Zw^nX>3Gn>xr`SH% z31?iDfeG?Rc6-#sa;eaCcH^u8t6ZeJmgCO0qH=WCPKT;XJFQs(Z3DTq@zALEf zyJ1>4N@@FL+}j2;lg6qMwFpBuJHu}?)(AX)^D>)GWA-e~NDHhv-`8Zldb_PsgB=Nb zAj7NvR&@1;z(3bEcWLw4kqrJs*a%o=YN*eQcz7bo)3VIzlp)hPv?j zGuGL9Y^DvTf8?>vVyF|QqE zR2Sa_&Yl;Oc13sHjbrTBXUp>~g13uHdS4t26ch&;Ro?;c>BZS~A)fT^B(9j4LaFkqB@ucvXW+2uMXg2S$n9!5^ZF}hlp z#k7+rkYw1os|bU_BdDnlnqMmNb>B}Nk;0%mq*XYuVb3zj$C!ZT5gSz~(S-h~17_Y0 zcBrLT>X|mh#lT} z486AZwq(qkzC3`QWDt;0IhK|YE zag#x6gwf(%`H_Kvfwj8PN=vm@Gg5-#MdECsY(L$3M&KO!^_cy80ir--v|R47Y?%JM z1N?yR=40X>1es@}WauRfi(;=X;B~~VFROc6$@muUIM3!eNE6Ww#WQ%_fbB!KO=KXL zI6gVi?{B>VO%vcjB7cHxmq0ZW~U?-e|wYQBHb|Ca;2sy#I8Xb!%heRW~df~1V-rMxF zYG`k5GO=7DGE6;yz@mL?J^ue(y*acC92!S%ppq6?-LmV){bTS+&Osp_Yf~qDI}MSx zIk)sK>G(@|^>y-^w=E)rjXgUZ=_m3|X9h91d|2y9UHbbZZi@gH@gH?Kvu_$yV0%m{ zn3~LUg%&Z)n@F!x36smzW9{8Gh;Dwx4Ph{mO-$XTZu_@_LNKAj`pD)3jN%xZ6>CFI zD0uZvKF;+2#wTa!OUF3fsbh>Q_&1uTqOnea8hC40lTt*4Y$yiTonJB4K?gW zZWn;JvAV-Bn7D1bTKA;>kRye5fpe$RV7x0}W@6g{v+h$NuO2`o;re&rts~Bl1|SUY zSpu!S(-@{-_WyPZ)BP0pzOVBh)x~co>>qEV=na{xGW0B$ENWJWcGq#@uisA3Fx9`= zOGiXr3PuQLJulry^Xb}?5cG0Jy60(0_IN!A{=HnSpt@L-*lKB3nZ6=LT!`wOI8d6s z zN{js*mlkU=2xQsF6Y8kH;Q5ZvCcxjTdTKGVs5G_~`k+`xzw`dzUzjwhx{bQ|U|M>_ zxFl<|!2%-o=t){6uO@nG<}9vk1s(-p5tg1l52AFbavHkKhMOjGf+qNPZ8t2_yE)u_ zGgwne+IE9Fs|Fms)YYAVQJ&?HoSBBTnow(#@LuD35&coGff~jNrNps$0V~JmU=jY= z(2b#KtUj#bwPi+0PFUjcu#@rr*Vvm8!5su9bXWGw$yLEqj$}3B{}d5!;M`@+q+9SQ5UW zO~0t8`^ndkAsxNk`m7gzing(K;67~UwYu}+0qu>^2npe%3X4a}gjpI=O z^vsXf?%WP9sPz#G_8PJn)!fn<@Z{heEvBC?{QiZo3+Tb*WoQuzv?MUv-YCz`H2)^< z{5bV@;^M|n$_XVKMb?tsvl@!dk5w$dxhn1G>zST#Q0o}Q^LivgWnG=phtn;~`Y!&A zUJPQeg^C92%|Yopm5srZGopg+wrx@C8Kd@n0psIrlFd9a#O{f?Yw8_jSIIhk-$;o5 zglwh`RKCvo!=K;51nhd_@%{hqA`&EZruC|`?247S*(3-ecXy1-BO>F<*BLT-YQjkI zTfqdkz?;DjmUTWVm!(*4hzOQP$@5b(iltm-Cp^h{#)xN***uozo|C?nGuPZpq0>Ee zTeNw{0Sg9X!K{))TlYNgc2bA>{Ejy5LmNhPm+Z~1npY7Kt}dH|jj(KT02k!ri8-h&XCG z1Dx2U&Gh;KUFrqvLS?;tlPL?y^-tl0erAX1e0t+{`vL{PViuxqFU*$(jD^>4)JofY zboSBkEMd$njXIk~;gcC*m^-3d=>o2N8`Wd|-aM*RNpFQL%b16Ia3~jw{8hL10gx4Q zoBX@-AH@U3W)=m)oo5pmV24e1MrwgM@G$$cL(dd>2)*i8?0PnSHF47(6Mkm%v?#Nc z6#L>PxzV}xIIU!s=}IyH$ZCl#she5PU)eNjh6;7XboW@Joh%8deO+3}f8k`rcwFwS zRiby89tUojSZCPjoM@2pIdoDJsy?IVF1u=EUY*gh=F?^zJoL#j8)iq=+^4{oi@mFN zqqjVAu5$0}%|aDrUWBrU1ZF3{Gi0`ct};z>(HNr4XKtJ?8*Xc*eHl#t!X!jFMCuZ~ z68omqg+g3=GJGfxQ8eg1IsG+t-L3imJ7~yc5oM7LB&-9HBZMOjA#cd(wbvbak;3K7 zcqSvhlME#Va>s?AiCF)9&n0$hq@bfEKQ9ZElN#>%&O4LWP6EP)M@~$-mBSi3(VVA+ zG4uXuvu&gassk4wV6kq&I}*0TbqTPIYGBKRLc#CMUhJ5r3EdRY_H|=2qcFR?(6DOP z*=SJk#aleN)bBHQ7^;^zjTsTTQfv)VrJ<(Qfzvj++=46SX^@Kgj zCfd%~$`7=Rx(v%(&B(6}Q$QNkd!(oZ2b+8~;98Da_sZ!l*^Q7Ws(JN2@9Kk;L1pWn z3D|<2t)WgRcxmHtsoM_{qK(&8RCPHRT0Zg4wH7dmsTZ229ld_w?(gvX+q)lJclA~> zCub&%$I+C35-07Xy(y*lpYMbu64H}TI-MY~xay>uy@;L)ha}Aelk>2)N!W&G!Q1`K zgROJDSs6G=Dhd|r#tu#8L@;xW^~|_U@+TJJA zd(I00noKyTQ?T{&AZ+NtKu;1n`f&WOxo*GCz%UxLttJb{_v75`!Re-&Wuy}2)|2*D zx-mZSk^e&1O#=Bpz>QA2UOav6MNz4>w}Ghq8f?dIRL|aho4tl}lW9-=LFVqU{MH*J zVFp}3>Bi0@cZKyVaTIjs6JFFM+(qV%iKT?4lWbn%uNk4h$u=5ZNX*Glq!5>)s;h4b z%ZI7~e|7UgmoT`+I)gBYA^Mje)myjk&UDJqu%~~6^o~TXp}tFYdQMH;lXc!2X+W7URpu2 z6&=FEle-=ywh$cxVQMv^qR`p_TA>X}6wAbBl3qdkAe&+-_f#dktVMEzLL<)Apa*b-EIFr$)H< z4T%|~7S0WTJ1*{@?Pg4SQ?Oh#olkTafY06Zi2wYQ5JrgQrTe(7!*LhzOi-MxGVwB^ z-9pLqk9AK1HT2SfVLD9Ud5VT^s!>~A<{MW#=&m+|{nqOI^UUVm7$twRk!p<4x zzTEB4JECqR!$~oLTT^);Q8c7N!#|I`1q9y{WBsHR%G@|i?`xct_Kh&Tpi7 zA_a2g$dGdfs=Tn?%qS(u3jpM?=$>010uOqkvuWc+P5}jYmmS1Uh#$iXu>_>Vp;_NX_&l5faIWKSW$*Ps~ z>h2RW9IZF(Ns1;OC7+(VI@fODSXZ83RVbtp;ZDp8tbRfaR&SO z{&XY*6NV9I4=T^rd1%q?#(KK9a@h{i%v?z@913%Qvl5?mn?|s(baNOi=d0TNfyQo%g7qqLayY4}T?$yF$CQUhcYnAk zc%4z_!C7FAdz_7lk57U6EC@ZRPOaG%ryAV4z5)!-o1UiRj2UTqeWDC`%eE>ki_Txp zlXl4Xg*-P;-Bn{g^p=L_CwOTF(DF!&tMus#oOpwa#ulw_*hyiXcryW&J4`2>Q2H1_ zGD1`ZWV(sN_h5N1VUr^3Ebm7?I^PGvbuNZm)u`d8fayVFl#y$bda&bn6FkKcx>j?X0MQc{Wb@&t8q~7rukvN=(Ck@0$<9)MX;ff=xW6oOdHw3NXG^WPWX_< zE6$cIpJ~C4-`~{w_WK;dUDeD&bcQ|=X^cLuu`#tpL9T(kok}yMqeg^ z3$3zl5jQD&9X0=7y2rujcnU^yaRv!P6GH^##$kiN$5n|Rqub&=_n27)vI(qO#=1)n#|?pU^l<)d%GsYDS0^+pxtl+~!x^gD5Sq z5YT!P4UEAMM1d-o&8xhgmkUl8K;R8`-Ah~(U;ld&QcpD)-ql9sk25#R!8vVg(6ZzU zD%WuIcFHj-E^=r*lw2gO6sx-LN%GkyG#niDU+y|pd}2U~F0qw%=Ot{+byZ7tjG&^tyV8m)N8aa~y8O5EM3kSa&vW-u8S zN^r$ccfCLsuB{J{s#*6o=A2Ke`>$*5>|x8x+ym?d$JMdK*N^W0%K59XPh6*2CiQ|l z%dvPWrb8Bxu7=gOuGthtfn}tGK;``F+!4{bM}(r*K0L$7ZcJs>-1es($d+C3VH5s; z6L#YWI7Mtn`D=da#LHNJRdmEmMt2CKIc9?(EjK3ACqySPag~bWh^`Z>Ud#y8LF$R^ zq3jia;LJhvQyb2ne8j!g;%28MJAJUgCPS$;Isd>Fg?!0wod_yJPDt1#i|$JaeWCNO zC+gi5JtQGIx1!$%u*$`TE||d$^)~JheH*cqkv|nz7ip+}oQkb>ko?n%`R?fhR{zIB zkUSDo8b%NI^okcQ(nUMm}^tpN+ik12T-gx&7TGrVES?uJ}z(?QLn*^15$G)-EPc z4=}D=qdZfXC@FjaT__!tk_HGvyTg*YW1RhVv|QkG{Ld}KlZrZ`EMI1E9vY^;RTv;- z;DRW#J>$!%$sqP1(qotwxu7di?>~e-9=2XeZfrjEW-`ssW;rv%eH(12Als_b2BGIO zOrZ{}T6h!VjTUZ~pD%RYN&{sj`^Z0A^XMTUEXhbfQGSdYO=ChvTyEDQ7}}((L|_x! zy;(A41tRSPc2l2`p{9E6Jr$N=fpDna$|S8fu8HJ7rt4YT?*&_Cr;z)yuDPUrSmP13 znDKrgI%S*O$t5d*bEKn7Za`u5uFKEGbh;V`P*iJAytOU6NhWQ_1dT29IGv_9U5c(; zO5i!9#=NdFQoEp|d4xhsCgGzZ)w?WS(?jNo06cC2lM*BJcYKbt9|JYG4V#Qaf@vIyjz9~ng!T~@LP>AppMG?;Xrr4z^re1 zIb$&i@u+$VS%DG8h*23;gVW|hQgRD&PBv~=cgCDF1C*_6y*nkZ!ZsFf`qqj@ z#eAwthUe&>)kAT#u=<3w@s6D+@9b;GZambw)`kfAr5kMmC6-b*G*=sK!b<47zHpiv-q#+cV|8 z(yQ;)Be>r~^VaSg>2(j&#|*ID?&-}LU=?@{qP6f**T}DAJ+h?D3jH;D1fLN&gqIQ-FC8}T89?U zRa9|tzOvn|kH6&~6SZspt#xwTL32fvEARd^eWp-f6cAnb!NBzX5`PP-^amwa1 zNCX}O^)Cx@k3SO#hbuy_sEXwoLbqo@0Z-=l;c}mKj(n8MeEo?1GDwJ?H{C7z6Day9 z%HW#j;cV6SEL zsRQOzeO!GMgpfzMQXDO1A))iJAr%=N7PE_f?I6zd_{LJa4>gYX5l|n;jdU*>;kR}O zkupNnl0I_w$H$YP8ElhT&d2tXxx>B^ius7}hs0rK@Z!wakIM6lGS*0Uu3Mw@IS+zi z-p>p(qYiozDnP+dEfZ=Gq-TnJ*7_3&K+1mCVbH83IWl1WvpF(bmfb#2-f>q>w2rYmnC%~gF|*ijXCYpAbT>Zohf*Sh89mhv1^b01>l zv`4NnZI_A@z2tYNIxK`?-)pDAj<223dXy8Ww;axgwaj3B@GQQ+WvflbRbMJlYLenmI$%?jU>hNn+E- zH+!mGd)TuT602hpjSS^?ZZ_Dm{)pU)MQf%nqN@ZOTCXm3MRp;>gjnS2IF+*_`I&>? zfG%s zmKmkoTe?!kNxx>aFuYS(HXUPG&tb2kW9rmppTiJ>ss7d|(`xD9c-jtmrx}Ni!G&aR zOD^5AS&}&gW6lb>IZm_EIVY)ZFc_YiyC7sL?+^+mPZf-MSShL~fA&Z;A>mzg{ zGuMoPXZ+Q_We3i@B}uxGB%4?#FGA%fhUo*gzfmc_K}{Ca^?WQ(Q8|RbWVoe{7isL8 zk6NB>1&zes5U@ktXe?L{Tmb@98Tc+sUfO&`H+>AiQ9wT2O0DnSkw!RFnH^*nX$ZyK zHoZnJAi5wxP_`OJ7O@j1ed~u8@nN~Dev8>=6B~7sadQ0gRPK+> zlYTPJj^KUM-u>ZaD<t zXw|7AZYH?&=teo%>mD#SJzFA>&=>W36hy+xj1SPSn1NxZkT?!GN+lR=ec2WMp_rST zehiHEY3W3 zF^@YC*8kbD@#HY-_x*eVt}G7=iRCR$)4rA?xYMg_Fa955ECVAiUxcz380LeL2eejJ_Z7j{Z0mB6AaEMb@7c3F&(>jQ<{Z;QDkURS+gm^=T8fTZ?90W(Z?cDzyZ=G@fB-I0`@ z*B{ePcX2B|K@)lWtP;dC|K!yncedKrZC0<%l-P$)@UrE&ns}vF(PU(aGND8KU z+xT@?O8C1Y{rrn9yy+yVWvlNH-s>A;ZA&iNJ8kwehPG_Q_uTtzNGTll;PVVOuxQnB zqAB4CnfLMUlw0!ck8B?-JrONMy*dw5g=1SSKV}k=Dj!h=fy&rns$y3wBaJOXa-@>V z=Da1t@uM14R?(p^5(e?~xvJ-IZT+tIP#k&?Ap5)8L3HEbS!5 zKO|x_?3k62?rGNZLVm6oxx{)Log9FaN-)Ly>(m6=FS^}DpIy1>3YL!k0Fad$AhfX@ zlOFXDl(358nx%=G<7m z@hB0MJ$@k(au4~~G8XD4cO386`)E2H?N~wix~%+)icIPv7mXM`p#+nX-r0lVs{R+0 zbbTZJj|(PGzegS)m@TtPcx(BD!vE!{6lO))ftur{;r2bdO91nXzAWXp=FLSy}ILja>W9~ zw*=Yxz_4q|RX?o?#*YrR%pK?B1^v|S@2r5fBJAjoZT0dZGP6hv+XD)0`?8SaV;S~w z@!H*zya9XI2 zdFq$Nd4I9`-Fcs#KZcq8dao^;asBxBkFJ-$if%?hO)ZqCI6c%lWzgW!!e0}r^HG@B z&?-T7+Gvj!L3a{egpjX0qLsj7FxFGoc<-m|iPVg|ISkz_n6t_i%~g0#EHq02_*R!D&cF<6rYNu0;Vl<_nqdXq_>gmhLnP>=(WwDAPaZ8oFoGZP4%f8Z zDhuM}w#&&ze6Y=#hAVufaxd}x{;;de+T1nu zt?Xx2x@8BzsBb&h0v@(%is8iz*a?d1&P6uxCyioV^K>=(3@?)5{`Ckx`woA`wzf6_ zaq*8ANT_ggq!oCLM+AR@ zWYGQYis#q@*V2A3XZ@OMp(=v)jcYEz3viYz62LEG{_ZimqBi!6~$UHJ?~O8;z{mHUzD(4Vc7ZlQ0sSyGRzCz8Df#mHcpDy9~@iO zP?!vqzo2^$guO$FMJdKToXys}w`-}rNphVBR~qIwPv-isI6yoa2L5~sAAsW7+pZw_ z45()Zus)ktT>@CYoi*&luS@Y9x)lYXu?HUrV|3!MDl3{m_89skKy*ojc2wRa7MWTeg+xh@?t+Lsda&QL1XDaAti9P1aiOB%`-b zp6&x>RXi;%O$$9=Tbb?J6A3ws0`~FLQqG(?Q`GOCTmgjf4@9!|&2c-HR3GI-zgsN2 zJ8DM>>P2ys?ULsnGi!qw_p>Nfd<0=QA9coV2MK27jd6Q>dfvtjsDu_&VE68ZZ}!w# zUL%t@gR9UuZr=1@9aK^6nENbxbU-}7Q4i3>Y~@Y)aU4m*O7dd9zV!~10V&ZGbGOgv(qFb?YD zJqMHWK7~o0Kj?7Yki9AYpqhs`8vZ`sIn-@nmk_Uds@Bw6_utP-){n0bA;vk%Q1Y%GIwWV!1 zv+=VFn&>txyAJ0le&~z6RVFC^mdU`Fnv`WzS_&Px40TRbc4P36N(rsyQu(AF0 z#ouo^6V1u^(&P)&tLbn>-{m}1I3+XcFR(PV{hj^kWSn)%9t>m4 zE*#)$ga@lVw|U|rCa6(TbBXl))DLgk%v&#%qkxMg(d*64$+-ay1+^WMv^Tl*a{=O{ZSZ zc%3x=rv_#lokDf^`yjTK8)?fA!{eua=*YvUsGB!xK;_!T-ogxZ|3MPkr3CqyTEIBK z_jVkJOG1=42nZ;jIFWefWHzQ|it^80kDnHcAoS~sZna4!|3-VgPZUlVas`p9!)MTN z3_@CQ+*mowMfBdUi}Tnr^F?{)P_R?)pmnUfX$;blHBN>(7O!sq?}gLYl$4ZiXJ$%< zM)L9UMuUSyySL;RFAqMtAi12_iuJx=z8w`fC*ua%_EkIhnHedW8aW9w$hOI!z>qMh#T_Sl40%U@#0C*kPw?ci+t`!XH76M{cMHbbzDj_gp?*ag3 zRO9`HtN$C`VN{7G?yNw})=OcpU>P!kI^!FdzQbt^Q~k0{=&P%$j-!7~N0q?^3vBH+ zT$eZc=9Ht_CC-q4hs$YIUKQj6(?9jUUns&{g%4J=r(X4c3bjc{QKb6k(vt) z2Jx1^0QIm50;(Q#TU#H$U^##tdjMMbz3bdRJx2dCs{RFjWw${OEwUhq@b92Ji-s-J zWTvD7N-WJ>1Ro=C4Al9`~UU2Bi=)0oTH*V|2x3VuU@ zX6IDAQC$2W`j0mIWAp#L;@K~bchB_9{ktm(2FY~FyWXM>#$IOHyQ5e)Ck5l-+-zdg z?s41)S{YAMZC^<&cJ!4A`v8R{(k8=Ukz3sF<`we ziNU$Q9w|N76Fz|ZBCw;`L3^c0h6CeYzK9(WgX;rsK0ykrIiQB99ifuxf~S8tDuNKP zEQPJV_ukGkQRLjKPMK`^1Nbms=6*uKX(hYb2P=VZZ-k-AmJ~Nsby{F_g-dNE0Pu9@ z^}qk3n$7d&mJx>CqNEye@?&4U+GgzeiqZ;`qrDHY-`STgU0U~Mvr`?RuQ&E+H9(+sd>b0$sB6oT84==2C(T5RT!MA z#|%yd$jQzA1@>phu}k;L<@I5VVX-(QHT>Q^A=Fb29u#0&r5m0`o&k(J%!y$%4xe(x1xCk)>M8}p&;8jke(8N#N{^FT3;D{g<>6@06H#<#WJ}F0gwonaOeN#G zV6x4(4wyCXG;TpXzscI#I`|~0X+gmqk4pNmA+9G$MC61k{SCXC(qO7sqZ&YU(q;- zRmVP&=axQCp6rCl)Xi63u-m2*>(sb_+ODdQc6@U~4#fgJj9@y?NFoV_5rCo?ICt5H z5(RV0!sX(U9vXxS=j7~jyZy6;nP?3Vw#7tBm(=p~eJvyu!0 zi~T%wiqHnfU>f`BjoJ4gz~RmQaX!lb-3`>83p*T7gT=LDsg;(t z<7ZY&5x0~F?T&8BTbCeAJfINGF|lPSvg0*mfbbvVkZ-5GLo#7qQfDltaDGF@-Vt;U zT!)8ZI9r(+U#gj5>qF_UF7Nl8i!&-1aqbU+r(Clz#rosP~HBF zs;&f|$rk7ClpKj4KOQ3lMcxVTvgqP-hfaSNP`;w14)65F^~L2is&itbzR}C~KXl)j zT|tZBEH@uQ-EhOSsy4CL*YR-8czMGoSwOdUpW2w0Z@R|}kARZi^=DQc+Ix`V^y08c zXGahh*QS&2-ng{Dg=}_h>CuUx-%!?VeXuB5p@p#2;>8M24-UeY#qq{Y%IMEkjCO|~9g=$` zxM9N$Jq{ABsHyEKmX1}r8Fel(oP{AV9=*U!8XLTmBZdwrTVrrfe!ceM#9WdFLjA+lR7=6! zQ6l?O@v5!%vm ziWKtOm?OT}5GRCvqOGk>c%Ol25cWB|v)UiYx}f8S+blB1R-8h}(CtuNNUWX2-!DB^ zYjU^IZr3!KnXH$>mlQO1{y{+&8J9u4SvBt(Gvi+j%kv7Nxi;`ncAX3$j50Xn?4^Ex z9f3tlE&A{}`FG{&NX(^zFaw(3=n%|0bJqOT|AHN?$a}+;<857?0VXqR4qn2Ppt`(^u<%kM?-9696f*LS7#qarX zq4ta^gf0yYnRd{o!*(ZRA#vJ>LM*Ad{NqAw3}*&Eak5RN7$$afW5g~Y^2{diyqZ&4 z-NpCZ$#8k8go4|{7ZZZJ@O24o==huf0d$9fYj5q=R8phT9jl%RqF?csI zY>*>cZolny`8lMP$~kq|;@tU^Uyn+j=k7}sDd8j>jK9F81r<_)jDh}oWE-j-O3Ft$ zE7eoRFo(8m6ery`!n#*8gHg;c1dbXCKQ-YzGtj#45Zv)IZE8Pe#zNJ^CHLEr@c{AT ztBQ6sdDvIlE(%E%U#+pdPZNZcMg6@0_RY`hg#fwtE<7F`7q^;~y<6N5$2a>#jy7)P zXImIu|J?#i2CCG@x{xgBNsdU^p#8kr-L^vNu3i|b6g^qz_ss$f6APYBtoZad>YSIa z;t`$*&iFw^LtMchPMk9u#{RiZn{!~=|Ddpe5>i}?vcu zcNARAYE5&sdeec9diR>)aJNZ67`?XFDNcz!@FVr;*imP_!w*V+_T{)uP5wfC8O$~) z(*StWHlWd7Wc%56B`;K@ytwGP&;U`xsk=cB zcQ6B3bmB{BKK$cFj90}!>%#xk;XECTj{PlSXyUei4@5=;iMt%A94~t6g=*>@KBTHg zS5`kfoPNX}@ZD1=hH|{QH7bo`UixI~$K6vn!=3(K_2-bex0T|{h<4_LOFWKbMva-P z%xo!x8e<5Qxz^c`Gx^y(dRoMrlsYM?Y?m{+%X}Vq1>BTe=V008gnrkSG&w@97l@zo z6y~^EsUGgT+PCH&9?RjZN~x(9$Njgn>zSJ{OOG`_<@(tAr31RLtx1B%)xLa8iI&6p z>Pu=KChtl8w{Jhjm_e-C85qD(07-w(>nF?0gWK_1}Sya{^ zeS{}gIK?*#U_hkS}fzE-yFp;KaaFa75e|63>W#?%`kRx#(s%WYJ*Y}xYEZ~}L%Ii7y( z)rq(GpU^}3lZwRv87|HBx5EeK#zS+!w@whNbGLty6`W1Td7~(C5*<9_)5c`CucUPeej~WR-cV0`Z zRi5XI4R(O5nCcV*=g#we_ld?=@)nv&6$b~0!XIz{`;&j_e1Ss#HaWj?EB5YEyT|wc zvGv~ZT(|xEc*GUDiin0?Xb2T5L`q~=vO~)j*;~<8L?l^-kjxU9Z)u5=nLScuWK~v? z{EpM=y1&2AKRvpy>$-WpU+?pLj^lY8$J0{;?`Oz=4RPS2i}MzEIt1pOt3~bUDR&Th z(p4X#$H9b3F?~dSLyS-~eH#pDw+WFT5CVr8Wt7CC=S*LBI!FCRk~MD0u}csi8~S*R zwDRxnwxe}W0iYv)W{2s;Hr;+;R&aflE>_#SkUak9Q@hZPNRDDuqte4gRuAgx}(njgQ<%EhE^MvbcR3{2vvv4N+ZH`bLaR!AUS*wB}&I(LK1ZMuFb?_ zHrb9QmLYaQa-F|CdDCLZ)&TW%q_js}f){RHJX%-`cIHPnKc%Rr+p zg3kFCfz~mJw(#t7c79@uQ}6?W&DFjGnt2S@YD)P2f9HLX4-Zpi)Sn-nmRt}QZcUSK zJ^+M=Pew*Y$IG6H`Z=KoJ&L67`gFtxGq)=1?HLMi0E`25O@=eHdeT;xze-XK;kZQ$;AGTi0f*Op<`9NQtUz{kaIU zRsm;JMH&gJYp$rk{`?UJqD`4qNdsg7xof0AdqP5jGS~;HswFMcg3+w+VXLdd&e+QA z3d*=W5XfsrLuKSd9Lu$rADQ+g3<^NWr|ZzjYgMfi@KOD@e)=B#sd=E4U~Q%Fu5Z}p zJFPZ9pG+c-lWbEi7X)Nk0UrHaTT*dU+sU|Xz6X=#p&?=3!GH6q<@$^KCtv#PTJP7Z zhTBhhsB~vnn1EgpKZtZ_QmdpGv06q?_26 zbi-mBF^DAzEaq_uj}dL@z+O-LJ8RLSFkPe$-yKUo6y7uV_G1n4`>?pemO7TE^^xhZ;f(&hF7a) zyvbIb`EbV5Pg8zZ+G^$bM*&!Ep@bRDX@(OQIhQY8PLCHN_gO51&Wsv2a;ME|@Lt5eHtGO4R~I)W&asz}h<4{>xh>WccmJ+`YVCwX}OZ=uNxTsP(gc z+($sG`AP^103lG9({^Jvm*CXvp9^ea$;f{2g)|B8I9v|$v;BfO3#u0H5E>X?n-D41 z`&(Jn-DJS=|9t99+iOOmnE@CLJP9^yps??Acn)0Cs69VK(}0 zA5SOk$fxCAB`;-0rqZXm=cPoL?CFPT?HRXpB6MnB?H{Mx3M3dECq9h?wG1vXzD(ZA z3r*SJW^A1m1{iz`xO;2CyNl1HgmA^9aPYapOg1{J?eny0aO{>-a}DtKfB!o?;_R+sQ6He< zrAU3MQJxU*kgeYlg=a=Poee7y5%+U{eiVR7=sTn+>BXbpdi<^^XR%WX>nI*Bz5xN_ zk93wVc;);SiO%2OyEscvZqLU85G?=P`*;0c(M1j)aYiCba35MD0LcqxVg}w+UlB`FW^+Hq6j3^|APvSB3UGq-Lekd$GGJ^$J$$Cq%IW5u`MrNY1-v?jh$?#`RkVq9_{9uw?V>s>TBOCTg<>lq~f`~X+c?3b6O>`=&vCh?m11223FTyS5Lf?y3cf+~*w3lP3oSNk^tU~I!z@sOZTokZIR3Oe!5451!R};uv ziT3{fglU~Qq;LOn>|)}ZkNt~$cvvbe2lTUAWl9YmJk)9)4ZkC@?~NgFt%rSJh_A`_ zWTyKG8ISX^#A>rc4Cb}YshTF-WY9=VN4`Xct)#w7*P|xwWmzt>ZvA?HMlnt6@%^Ev z79jBXK{Z~7?qONMK{&a;S9GjTpOCcgysDz&hIAN@gTB0ZIk$`f{MW5(6qc&_!Qdc% zoB7Bz@wT+s&2gOj;GU_>qgwA%dw#+FsRYEbK#5UQe^(2|8bAIqjbd{p1@3Q5fPe~` zkB*^(G37e<`=?zP%&`a#tf1kkPHIg;;$tmELp%3w+HV(OOXhlvAu}bq2!)DJ##7Il z|E+)9J$x`tEd^$#y7<@nQiG)rjQc(BZ1W+x63Sh#XSND-DoAlJe`H?ijuo}3V-+@N zXh_mIHqi~z!sQKg$;+`W%)X_t`n+(s(20G2K0J|~d;N6YxGq$(W{NZa`yQRSe4ihd zvFE{AQv&$cdtG!V;=b9hJl!5(mf17oc^DSwFPl7$jib{JGnR`@8z~x!#lHkDd3>x_DLA z`JU)dUZ1erNYw#3<4ao>BYe+fb-HC_fJ3|hGbm44xw+4D?wi;y_RuJ}Z{TGpYll}Z z*Tizd!oM)hv5nNvMb=c5-jv$9ez|*hY8Wgutz9B+EncWnui%Oe|1(ok(wPwc)~N&g z)toCD_|*lEN?k*rV-~?wlj~sS217LtkhfYaPd>4+NQPj|^3wM7nk<-LYY=kRk$i+` zWk7zBTxV+k!JKlXS3@j@3ifX}U2-UXn9s2*4X(wu)KJJLb3PovJBo*TMwq`k{{!z| z7?Ouo@!&x$63Dw_iavR~6rk4XIQN#R(RnVw6I1<#5aY_gfsHl|pQ>aCdp@-9LEfp8 z_V)H&-)`Q#3E+0c{gTbEFTEU=?(NeGZW**XF+s8fHBaD?+A;ViC<6XkWcn&_Ic=Ib z{dT|EH}WmjTicKVTUI4WnUey!tp^@Cf^rT@gq{x;N|dmlDL4^64Msf=(x_uj8aP)P z#2d0vLGTq}MM3xM7pna^O*=IlqyCQ>GJ~oH+;n8+!Fyi!Vcd5^a1Z2N@-kGL5lc&< z@bUZg^(9leGkuB03G9RqMQ&fS2a31|&NlOW@a5v6o-ba^x-ht5T24K|bHZ7vAAaz% zPnCu~9e=TQ{&M>qXC)@?JuiKM({keIedw-{Irpc4=-^hX1UGpZZffgZdeS=@(@W`| zgDY4F;@HBn%jxT_!%FXEMlPpoTi07h&R36gj8s#q(Y_{xsDh&At(J}=RXcw-zc$ zGuz8Ec;_R(nXwSGCpo_|Apdj21URbPP%y-bKf2}OpuP^peYA{WD15}`3(YsYKC`1) z1z>2RZ1~;6L_4)DKzi&Bab_-dev1`DW~561Oh z$+_N!iY8@a^t}qAjI8-^&-F8XFJK4O&{vTQ-+$oBUD(@VXFUqm!H&KfPGOZ>8&?Eb znH~mfxZDF@HWM8$)f7|kojd0GuwVKW2Mk2hnlZ-Vy~gb6w-wlm?J9(D_%KX>vJ=if zjh}wEkVdSP=KkDZU4jnGAwq|yd_96m-1LnYsx5ON8fAIBwId10Fn1t&@ zosSo7wN^~7wj%sfkM$o83mRB_1Z^`AUbJXeI+I5aD7Eb-i750 z4HFNO0d@GQg!+F8o`&sO%-r1E1}w%q=v)sY6^fj!X2q#sGAA4IN&$wc)kIr*L|6RV zF=ijeJO)D^LWsQ| zXW3-;#%~x%c*Gx+obA@}@>7HZYewZL34|z;EE4c*p-ABsjLtVQ%CX%G`W$nHmGOzc zU)KsBu+plo9~#?RJH{mOd_D>6q)ju(T?Yt_Wy&v5Tx_p7ntPiu1qU+(b19b3-8%dE z7{RziC1yh(iAB*lbup~`*{2)VK^C&A^?ZHsYH`b3q?S=$7;e@!sIfy(hm^pD zhKKAite=QqKbNp%i{4UCtg(OuFoC}SF|GKUy-wy-*&8D?^H5& zJP9uCS!P7(wc^I`?`C4+MnMt(+_^U8KVPM0U=WF2>-CC*cDGmF zJL-eQl=2EUIKtdqG57YnIEE&NU1@BM9qO0$rCx|Q#Z997SXw|;_|vkSTk{Rs!~6sI z-x}6takr00AETk^cuqB1W>YVB#$Rq>4j%5t5?8Fb z_`rYDtVpNb!6z<`PXcjW3`Du^QU*xYfN`rHuypJni1covx36!|$i+`Jib&HgCeA8$%XA0kSG^#d5$$g&NE2!+353P< zgKwc6AxFkXmawokx)m?GBa0cCc~F2CC?ayox3{c$Z@bRahqty&97d) zT7Be0r?Z;n$}w7?q#3MIf)C=nc-#g|RR4nIqcK8MLKV3>Al@%G+XnRe z7wEQrJKWbl0Mb>g5>WGEEhah@yN$XLVnsl%+m_afE>5&w5SoXKp7(M1WGxmZ69$Z* zA1sEi!~vo^dOVz<{f=yk(^06qvS>Ni?u{%0s(}Z%++GQKRnItX&J<8iR8xKOvj$1-sIA>`4Np{vNMezN;3#&~*FiFfAI``QmvanR1O>DP1M}-vy(Dx@H{$Wy`5yO?I0Y zM<(puzyG3nb^ckWm2khXHDw*`Z$fpqMYM`=(YCt`8r%=lzE~fzC)XbZaaEk{GPV8H zd@h2Q+UUqKHo{UY7Ei-`>m5P}#)Sd|JqieoWgVzJD%fiEu}S1_>f-s)>hiG^OkTB> z6SC2QQY%i(lk(wp#14pX`PHuNI9m-n7rQp}K^X0CWvwTd?gbRB`Q=>+4j5w*0UPfY zTF0X&Q*Yc7hhkeq|4TRtsssg0I%E+frPZA3DG(+#R~zZVE#EmgYTMkakR79TSL5Hb zNeLal3A6#l_0+TsSG7%CR_a^)Caa%)wX%B+3tS&pJ%!ez8ak!W8x9|OFfQHZocy70 zue(DjLrk5%kY;ew2a)w;f{9v6^baKDPc^W?D&RJDi2Xj0SwXfYj$~7##ec7%;sQA}|GTKKy;epHl$i><#V2>vWFjbCc9*jS7lo{&Vix z#UED@xqdX7SW7VUI6u?>B8g~1hJ76(i>9zh-r@rj9lZ~FC}m?~W5tw9@(aOKn+!!5 z%zPzgv8Hw@Dm7tlkfv1@gZ9QJS~@|N$-NaXMP0V0wp2XxYi`>JL!F|EN-)CgJG6@X zlatI=5xk$wdTy?hk3&4mHM%A+fusI**I8J|SHnWbVEnbud<2(GqzBUbx*?`S#yquQ@)hS)%{@d+^ z-Zs}`4lb2wR&JQO`=1?t2p2C<^NiW;ME)kNCg?m3Mgrx^xiFrry3kKL4_2g0!qHT@URNiflC|`0aNBUz_c<&wqW8r)Cz- zE0Xg80Y=5%J_BO?mpPAvzjycNwW7m80ZL$C61cf;{C@V5L?R_6rJLZhz5_a0P?w%9 z=?+b7CrI_ePODg0PI+qATE?!`4@&}zMp)-Tb(9n!hDeDz022mlLlyq#p=O>8f6yo& z2Obv7$lY{huzEEoCugEXSaI!(7kQ^*z4pt?E1^0+Z+chtRTExaU$As z^r*m98=gtwM>%ATMx2i{cMxj+baxwp*75)U9=s1w z>-V1^YRUSX?fcSwEo#R=5Oe>Koy}MmwJEFpKpk1PVP_pATf~m{;30QY=D%-Ykq^%* zSK!CiNjj#gXhd+x?tQZ0h9H(goJA{nt>~bR1U84<-ryX3(e%;3JiZc%UZe4B)s!328sRV ziS?lYbW{hC8kr2K5A#Yx zzV~UHzKJ1s+6NlX)M74n_P*-XYy2@Q+zgY-47c7pr1Zy2P=bf2>DM!ugI2?uDZ4o4 z|KL57m*2U?7OQU>!N7dzGq_m~DzSehgob zS3*HWWmkjz$rzRt%iYLC88q88To~9Xbfz0M(wGKJh_ za8Yv+LG(6W&WqvR+L>FRI!qM0K6>$L5v+LjpV4l*BJ(}rVBx%Rp11dUACM|a5VcNN zZU;FFJRc!fE_~&KR9shPQ!A4xHP|B|V84@|;;_~fO56|xi7x%UE?opmcwBQ&dmq{T zRiy*P+7~R)v27TdW2D-<^+SrXy0&$CqEAFgMMboWd(E0Kw*rA0D-AE6eJrC+r(4q+ zWymtKT#V@!ZxbrsU$l-I4Q_yZ*ITi9=wspI^Q@-Xak_!WT}{}k2hH}F(!$v;h^HMX z4zRhDyz}fx{JBE=FV`Lm3H!)yW$0OUpw+ZVW+dSx7`^B1-j>a7L8GEMuSh7=)ejDG z*Z3JIc{0SB(0tLv9OiA!i@4b!N2l)t6}>8;ZM#!vaeHq^oGFy3cbLK+0b?9)h1xM7 z2g-n@`L}JW`Z?sce>_t1o|H?P>Yc662Ob9p2Y-P>Yq6c=jke6{dMxVT%R71~+L?AO z>XdDTUWubXzdw&jN-W&r|NV9|R-uKu0vdNq*A@L&7g|)>wzZL}hyB{f2|XXou^`30 zX7L9pZ&|~#)$dMjx4XBr=L*%-q2t`{PY!*2ve1OLUz5cogzRtIq2|;bi;~S%bK8fI z$8x!3cb2EK9{X(YDqPV6RHQ6oXGIU`4$B~V)SsFHq8(861|P%(lv*1#P|6=?z}+tU zMpd!?O$&e&3Ne8xH#Z#QvS`V9{FqIsxDxEnXKcomeUynu-d>>pR5l0@<8zzzkOf@Y z=MXE|&2e~<`W``(0+@2IMXPZ%Q8>(L!G{9qPdi|!3~WF@5`gjZD$2AfPrEOPWIc8% zUuf->+3F%hhy&d330+z9nX8a^H9kG%Xx@A~sej!>d@kp;i~69DFD1qVQ&u7GkX3%2 zZaFk`r*rJko|h@J1aGR3n62FP>)TDZBv$X*@Jrue(Cg=G!CZ~8b?exa z^z4+%B(4&IZfx*#&EF!nV8Pyh5$J_YW(s)Vu4(#h>!^h>;MhW`a)qou7Y%65K)hj3 zkigvQU{WCdnn7f5Z02V~S7q?6z0r2 zXsh`6_*_%Z&GxQy2|lC1LQVRdH~Rgja%nyMUPV%5V-W5 z-euxmOc_A<6c7qC1Rj}j@<~g#D*9C@T0)Xn@SY=6IZykt%gUx~8PA713miGogN^?z z4%IfVu<1J$buVoouP<%*8f(--;jO(Y2g!bada21W3fDN`4Sg?*vIT7}oh21zRUVA~ z$|_EV(-{Gpf5)GT3tFBtWXY|+NUmOP;Xs{Mr0Y4hQZM;cJ_+n|MKRVoKc8^u9pn~ogUp6r) z{sF6+wQ>ljUmIgU?wxt=pK|k(m{W<+T%8In#Bfg$&Lr`WOBSo2Mc>PsdihpXUf$WW zeYhk#2|v-7mw?JC2u{Pw)U#)?mSyeKUBaHUZWfpb6T1H*U!cLN$J4&)aAnAq4WS~( z?*96<<5877o@w>*T8dyr*hrp*oxyhGxtH^t8nhgGvgs?FzkVp)AN`SR zW7<{oXwC}_b#6EHrcIkNu+XSxS2$Ce?jH!K|S@v0%UbRPA71`g9koML>nu_dMI2P$0+>zSm+9Z61CXAT(-P>Ck)ho0o7Ku z76Y%5xj<@ZZN)8ksO;p74fzD+p#`{RSZXX~SiOKl(QTrlu+>A6QxiVo0j!(uVOGY1 z>pIUJ8pj6~LdD6)2JQnV)=1HPd^|j@CKunVJhZdcHR>+zr(wHQbIJm_7d?~Pxr-EH z=XBbp#n`*2Ms8x|iof83H(E}@iYMy$h})w;VwKR~PdzoDG{n$%=Q#vvcNahyyj{f6 zRVvr8{;B;J}GXZrRIMKisQKtE-RPYg6m8yF57=lE2nr8UbUr24`8Q?Bm?^@43 zd0KyEO3c@Yg(AL5I^ULGLb}fm^1E2y!8J-l;VZvv*-KL14r{}do!>CLVt??i50 zvfDJ(bXUziBTqXck!C0tr(M;1BM98xF6y0S3~jMvz0xEZ#6Fhe_mQP0Ln46WYnk`&@C$TKI_BJytjq zXR`bC(0c%TO>4IsUj;g>Bj)oJUlw4Kc?~^JHuXef4@~TWVVG@*SWg7axdWSr zccs#00Y_i|(D3@%T?`Z%IHum~(xtT4l!9;t->rj$IZzWanE0#7DqW)AD7a_IvbDyR z_gT9~9pVcK8P0R;3FA~F0(KlKss5JUUZu_jONE6Gf{zqRi*+r>HLWZ1CQlSUpQA#D zPBPrSeBcJhO~9UE38!9f9(jK9?e0I%kQ)nFUKq(vXXt`b&?~YmS!NmQ*oKw=(Tj%C z7`gZI6EhdJW)!(4aM|LY&}-n1Ir^cOWfJnom#az#^fyJL_l{-EvSbduQ3W;wdV9O` zYv!AP-E5Usq3|WXjeTql9fgkL;gD*p0LoSI3PA>fJ%gI>wQKedDf#{*!;OetTPBL` zx6!<#L;HJW1?Ow93;2j)tcI6ZWD*?vVJj*z6GSGBTziuTUX}lS1Jeu!RhnGW%S-3o zPuo|Kg$8fQii%Sq!iM^=8W{|gaP&DU^REma5}=T^KIdDhPL%FV0i) z5#pd;?N5f8&O-X2yBJ%9lE4_9MMC^Cj$Ma9hg}uOKe;ZK0-E0s)Z#NV;NUv|!sQ{H zD;K^n?{g$dHFcWU+pZ>-*PDn5@AqybP8IAQjN-gIP?5EH0)568^hyr!bpd^$8dLV% z-h_zX+KmR>iY-J{kCm|4qO1>kSIo;%OO4-9Gew4*zxJ41B00*F`Yo*vc7iKfDI0g} zsIxdml;r;dLCpM598uiVMxzJSpUHZ%P#~<`Py4*N9=w(y^p5ZgY~_h~c-ija_BtZc zYU&PX^iVpE>eU{F!I3lCt%EOBwm7mJr%K%%f|mHSL@MLadA^;u_fA^SX4gZNC+g$| z{eCIRn4b4B27~XKO9#R~q?HZ;SqdS}mWfP5{*u%9%_PwXT30 zH`oU5{hwzBP>y?)x{FXIBSoMVt*oz~-$?ORsy?~&W0vYiAFV2*Tg|k%n=G|7cx-nl zk>32vT^y~5+pot~$2cdXKH*a9ZvxTN;zi82%)3tI)S|PdRy-rLq!L>Hy;O!+V32m; zBUM3I%O9+*c?XEh@9TY7sg)UAM>yej@8MlYaBVdm*cC(3gfAa4f>t`D!VFnN!PC=hv z&HSF842I5IErY5SKoT;r|3U&pk0%Mm6)3Pbp`&<4Yzl<4vi0x7p3GEW23uegG1}rz z0nualB)T&EXg>yklcPasy(A29jh~pH8Va)(D>XcZJZqY7l1w>qM`S+x{(Tqiay}nE zXcC_%|LFQyF_D{=-7>EpSg8;ye{ap3PRgc7#N!6Gc;QaX2*USnIG$ZqwDGR2UZf!^&mw_-VD2ymj7p$pz9BGuqF5+PfuKjV-!@xx_Jy|OCoLA2vzWJ0+{(5jZYD}`~6D? zO?7U?qTOO&FvX|yr0ozp7d}IiNnlo zJ&M`kda>0@=EC!f{XF@vI9i|gfDgUv92=c?I!#DMbOHQV{##E2a}Dwrju(%@{CrhPgYQKHj^n-Htel$fx|{6Z}lfBgCR z<)IBgE+kyPMXN>RO%g6mJRYP(HRJhqj7lx8>ReIt6&tmq7;!{0 zeT(oeWE`C`=hin&hTMBb6FPf@WL@dNn$T@KH|^CSa9dyuMo1cId0&&fTVDN8u%Cpo z7bb(7Y@!Ol@sm`gbBKR}QIy`q_>joN&=o+%`Sx_y3y;O_(;|>9b?N_h%NBqg$ z=K+P3V)UQ%w>Z%8kRvo2P1jy@7P5_HZ8>%FBuAm>!6-?7l;vBqs#-5hj1BaCYnYox z!|XgouV&YQ@NY&l1McBx%Vtl)ZDx2!b@tJG*%Sfr<}l9-nZn;cR5~Wu{#N4cVMS9o4rp+R{-cd@!`vTa2CVw!1u1@n?|UE1o$k7 ztJBXUrDMmD5a+ic1gyGrZ+Tp)Epq6I48lS_;iAoEF*nF6ky=#ozRWW}< zyz{9iY(JvEolv(I0PB> z08h)>R*TYBh1fGZNTpW@{}8-lVi*QmtChYsdR=~NLE+0@(jny|F&{lho=D3t?@2pr z!2aX6SFF@;bCVQILBb?!I>#{gSDKS;-(|e5#)!h1ZK|x#f8&t^RnrU)K-m6!tiFgW z$l7e>+hLnWEI-4-(ZhWF9|=RdEYAb#{JiAM!G={yF}Y{Zwu>8qFJD|wRC@q0BvWWw>W1iNhjyN6I~|^5GnsU>8q8)5k~d>_HuTF)2cbS0`%*cwAY`Q3-%iAN zxU0EhPqix}F`_hW259{jx1%+!NZmePrA2H`Urx1$-h4E{FK#pv)(N3|D7$14NS2;rZxP9KUI^{KpiL`x?ml$pDxS;0$ZJ&VjH5jF z+*xP(hZ_EMkGJS&mYBxt8?5Ua&E9(axbMPEsHYWsD3#xOe>D6EvTB^H5491u=xWKb zhl$Bu1r~$sKDaA0jyaQot8}w%qTnW1Wg4ZwMk(8!pXpl&nS#lG^q3I0>RA$j8!Oqu z(5T}Odu+a>U(id>pNa-r12r2gf35feckKJ_`K#1>P~KQRkvpUis^4x5hp6JGm4zv> z@r;7#N?#LuuGXJPJEf)lF~jvOLr6>&D#SrndD_1adc~@~D82i$zDn#{ju>;X5xaza z8?HZ`IB*;kvREz0?fdTC-i)Tb;%V$?Mbc{i23oj(uOo+8?MU`25N7os9lZBz0o*+y z@@=l_krz?LMuy$}(u?M6)p2lNY^Hne2gCsgLMr}p_6^4g=A6O2zD^9_#Jr{<$qhvv zvG!yA$qnIjg8{p2+r2?_7aESQPt0lxk&4l3&T`McPX?3n!IM~XDh!NV+(>_$>Y42e zHpoWQuqsRFU3>eiKxGv3U&4-03w`9Cb8U%DHpg^vN(wORxezE~lLt|?1R9oQMsV8l z?>k6CJxDl)X{!h1jAWDR&Eq*Jb}=HYXZ?xroj|LgaMf%D`k;`tap88!^5hVq$KdeG z{@D!o=sanN+>dO5CdhR~+X^Bu>%^|b?M?}$pC)*G+H5}z1UWT#%3jpYX#${OnlTBO zoUlBgIgaOeFpQ+3gjMhy>Mm%W6R6oIie5q2viPxTF(Lorm-sAVAo`~t=+TuztM>1CNIfA10V!H{_NNq2&{vATH!H9_nSr zkF-6|4ryia*vqlQ;Aub&;A>r%FzyBj;@V~rIQ|H8hV_s4tY=syyd`{E8v+>y z7n)zWON)DNws85GT|&H-)ul%!xjwiW0~V@>xO68>o}Zk*u8*kmg3G`@T90)}TbY|- zW@o0Vn5^?ve#tsBQbf7T)tufGZ-K?rAdmilpP{J$Z?;vvI+m#15n_W;n-?S5R^EK= z3(;+P!iMcnl&bK7nu?+De&PaRQJWO<(nxHZOg`Tjtk2h!{=RV%=1AL5yr3aom}Klh zHc)uhuBsPtfJxWCb4OrlPdD}C=c6DL+=f-KV3Fvl1+0lDlXy>W1kW%gE0IIn0sPFW zP=U<8>#{{Gcx>sa4qY6hA~~w5MNi;Mc>l-Yy2{i5c5zGN(>{Ma)c-KU;p}k%CiDrP z43u2I*K=HO;sE+GTDFzA&f_RTCU%q&|9(h8V-hr=(*jH@R`8iYHJ17jSO9j)NP9>d7zi$y)h|I#2_iFoeKMMqM) zb{g@(Gtn{lh(`^3BoX0xz2TT88yxxpFy|4#g|+|X zx^^Ct8lokW%Eo8sp1qePlXDC{ex0>dn2)Qoj~Gds+M`50M;A@}Pdb4ZC9E;eiUY{- zkFDvy^9lLW=B@BcS5j5Y)GO3xiNeGl#&A3adXZ@noz4&T&w(pE#sr__A?E01ccqU) zRn+eorBCrfv!juux#<^dz2pTig$f<5gEiW>LhnKS5y*ogBnL5Q^u$!DjeBc}`v<;p zSR!3{QoZCjw`)69fLU6-WL5^LMLmqB4R8|!CgT^+K0Q-Ol=t8VS8zTeE{r~ZhWXVd z7f$QK8p1Ti?*9o_aVdx&5fkj-v%h-%+RZxh zP~TMy1*Pt%%=L5K)cTK(1F+g|R?a~dT@5eZ&$oHA@*rj02v(y}o$o>qwt0;k>S5iY z=l9pEiYw@*893k&_qn6v3u5t(#eFZMkPto(r(ZohFol(%!==7e*S?dzTrJ>j$@Jb+ zpN}DCK3vl7B@p#TH_;Kyr29}HWiKBkz zi7H()Vq}nEK%Kd$O|8T`yD0;%GU#L0sX@gA1DrpH6BKpvu~^D+6=(~7mZzH za&xFe>VY#h78>~iLtUlA&(2Z!`S=tevxdirETJiMn304c&p0yCL3oey>r~3!0Or^a zzuy_r)rS3}5q&QDt%fX=P0GAMcEj4it)fOm3n{2GviXw7_tFjb6rp6~;1a{akC#Tt z{q?Dn(+&BI8#le}AL9E#bU9L;|S(A&YN1nT6*@)xsHirqnduRy?2WyuWyCoX)_3a|+y>uy9e|u`@8xY5KjqkiQE)SKBE15C}tWV{O z_6`adl~ZI)a_rbGeXH~S6%86{30ATjmaNTj>-7m-hv@k*NO>;L;X8a43iRZ=6J_pF*BAfIE=<0J%{~!pIz`p57!8<-o0D0WgywzP~SKQ-`4Z{@J75_5JX%QKju-M*4co%3{yb|xmS_j~qE z&;!bN1ki}4hV#uurS=dVqsJf>=jrD|YCZ7y4c9x(n*|sysE2s1dqfs?Z4YV<87aiD z&&=h+Naa4CbJLR_&$3s4W*o3>=j8iHJJvl{{$(&%cDG;=T>hV*m{DUSl}EL(vx2An zfUHzKSvrU!{n1#srt6#lZISX=(UfW+&A!<> zJD1LeGOAtkS>`{bx)l}cR-2! z6@9MkWFc&w;YX!Xj*AOW8K|gyE*jq8Z;q;h zXK6>qPXN|UI|WvjG?o^|esn;ofA)cXff+JWgPegZ4{9HeWtg9dMW%rdV+fYIe9cw0l1(R?!47pNK z*3fU4OISf{E7r%Ta@)aJWIt-0w_<-V$I=Jdor+~8c2Xk$-1zTt_(YCP!QD)f*Nl&~ zXNG+#{nH!i>wRTrsZp(MkihQB<` z8_38qk3HWTqMiGX_%K#%1fTEJejcV2f)gv-8B{ZvNBrCRs_ttHq3K`_A6$3dccHz; z9q>Mb*X3sR>e(Xt=ikpQ3xgoI^K#LhZKqD7WLl$^jfE}Pm}vUovxE96m?e%uca$4m zHB|!GsXNoHyyCJfa`0))?bAewMv!PoQ-N3~Y&O`PSoV+2@`F{2JAgDq{5ea6VR{Ci zMToWnGK8|j>7-m_Zq?G-BHc^Dm6os!4xT-sS8084LmI)l?Ogj7l3a7xks59J_vW^R zSZ=qT>_Ie3S^0MABmdE7XDI{Ni*dE?i%1NPqd&ov?nXRl#NSP`m~0kS<1ibV-2v5BQ#|9l1WCCjF@ zNy!p6MW*GFK_F`+%z1$`#)WReLoSv#Y^o^PUrOlapJVl3=s@ho5K4PAb#qxlO*5Z(9?TNip@$jWcg?^>H6`HA3=;)quw=<^fsJG zII*>H2eVxCf`D<64-H#Go>OvsLPDM?+>D0(T34{RPN)j0;=^B|4>FzoG;`&)&wiE$ z@Ffx7-b49fmeg~L3wztIMq%-i?~YcE_g6Z{IKJC$pFL?SR{TUacp9Zuf-#po5EXJJ zmoZp_4+R(mtKNHlwTJF>Q)cPI@O0XL?j8oH{2l<0DRvU5hx5}Vj4lOOns%b`Id4lxtn~kUH#0$rrwOZ6bDanD>$gH_M|Ou_9sAa^ zM;%E&Ab9EPtt+rHj+U6ny8Y;Uj3|}iWcT}+y6GIyuR%vVyT}fUdIM}+I0;6&tj1~@ zDJ67%A)j~6{<_%pTjB5H7w25Dq5zgo>ik`bZve$bB~>UVjQy)6g5r8_+!eWVT+~S) zra=wLQzd@XI9UH`+ii@teiYJ~hIS`8G97ZI(kfN#Z%y{@PImXiVUAQD(&yQ`a7Or_364&##hugHHZyPOto7JZsDKW;$h1WL93@}u33^QVAkoQ707czE=R^RGqU7~ydYbdt z;v&78f989$-x$4wSJ`&_2D%<8t-J-4i$|N*vEvh2Z?r5O{Xrc71YJ(&S8u@QcvafV zH2YBlX^lL;%TEH95iLK${{>ZKGyHTd(GxJ{QVyvfy5vl$o(vPS2r`7AHcfy`To`43 z9^a_ua9WsdH&EI!kh6023&Fk`z)c=&yuaBebhFmxRSI&!RV#OS{(KbtEp7AAL>{K2 z`M~3%&h7mDnkXbihE{_OY_Zhl+&0S(8@pq2*;sZGK_&t9(sG6mSN>qYqP)D&EqZ67264uj#JuQtY)iKZITH*1TD8PO2?jBpDP{P;yBxa z$_n@(5bJ?|u{de|-XFOX4KD{>_@+|dWl38M@t8Gf!K8~0$6UY=qZu`r!TW<)L}!!p z>9Vbpid5rDvI>pt9Y%?L=OL}uPt5rr4{sHf1_`x`Z+G(7?9B&zr{sAE6+Z$q00BBJ z_ep@@LI=5~18lN-6o!&V5)Z|kf2epZsC85;9hLrtzwROPXDD}LbZZN&r*BnV_)&o9 zQB1kV^WKZ~yw)eiWBGdjH1b{H4@1UQa(*6WQ%@|O%+9aa9F@R<2ha6(^E zmr84#I1UT)sxm%@J!R0NVbhay_bzZ3HQ^9$vM7_%JRH~=HJyYdHM@pfOlOA6Ona!4 zUi?9(lJI?v%$s>#IB#QnI}XV~D~KhEI$n5rGdG8{-{lf1_;#MGZmfNe$-|0}@0UCZ zeJk6@K%3k1n~&9I{dRyk=ej3Rb=zK8Uo$cHH<#Tyy;Vdok@ut>yOru`%mStr5 zlnmML?QP9BNu|F!nwGlFu6T{vA*wx%A364x-@}@$m|g#pMR<2Mk8OO|D(c9Ri)6Zp zm+6pf$X#L@gWzl@^IOcS&hOF+s@h#M$pwF$+}jQU)UaMW1%^p0QeD?BWz+Nb=^WE7 zl=NFRbD(e1WQyJmYJw@*@uXLGxi+u+23r`~l&c&<*KzqGoL?ygpeASpTGGDu2G>v9 z^lkb&n;f2@49_C#GsW*T4Sy&^7GA$5$R^J!HpW{Tyx|8r`)} zaMr}qpZks?BaH3Y#kKl}Vp_AR1@rr?phN z=cU?y9do4t$+vDb_YW}EZzbq8NOt~X-%iGYPkrk1_N_A^3q{7E7;lgpC6xw}ZVd=x zTRK&K`}w6O)%Vge-l7{=BkeKf7-T3d$LLgDU47E#cj@kEFijg#K^f8z>qBwu9cdIV z(h)PSEFy%6GRHFMh?zaaAi$dp_m@4ec+-e3)tIlK&+FkO*|`B{)297W2m6N2CRBX? z<0J1aA+J)OqSp~y0+X93r|zBoC_ufmzcs%eD|giu!yn=W{x-HzC0s$lQ2@7Yw?jB%3eN?J|6c9@)J zVZA_j($vrEx~XkxoxBwnJ+*9~eN9S^y$GgQ;~ZwlZ?P-Nef|iONDB)zd!7D;H*JUgm?xF$XVy zakzpA+;9nnzYDyZGl@a!W1?{su?OfE=6qar4+RDGmbHw}HLh=>T=(d49B@sHVgwJ2 z$k-LH?m18-cN`p~+u`9~w^v=*kYqcoy8dC!e)2?bDFf_tcHDz()2X@SSu%$ zL*8fR=!$4vZ^ms%e4lfpUepg!ddcYn6|%%1?c1)|AaV5=m6z!sWO7k8+3WW*>HccO zg7l7q3z&9(<&WsVy*)z=tUvGUIVUq-w(miQ-!vRqrOwdO>|?5YT10k4M#a?b*Vo$r zpZY8?ky<$|2ex7cHGK__@3+E9z*ll0x*MsuQj=r08uva%#qXpJTm)RQ>(RkYf?7$& zm|E}f5-!E%R;A~L9)@j;ZlHx~6K4kaDrt6O*c}6KpY=$G*;Z2mm%tgaLH;{tz4`!D zqLO|ml@DvK0cE(d(o?8BSA>uL7H(bxxHYYdCebqUzbfrqpQg zYqTGzb9Uz*AgBTDdreP9-w1MWeD1KhLfSTfDyB@V7*&-AKNM}C2?%4GeBa{G{i4r&22j@3}YHXJkcjd18PbHo}c50LWqWt$CY$)jK z0~VFh|1}}PW;^Bgr9YgoU&%JSlKA2bSRW3j)@II(Pnc+Z4sd&Y7%6KO1!!_29gNqN z3UZ+fCF}^T9>$s}B=n!TB^pdj|Kf5#sEQd->sjxK zWzUC8#WJ0pnF~@H6uV{g#C~vx*Mwtz4(hYpBT775!L#Sq^&aZq4HDdtmhDR8Rid?9n@=516kZeC2&5T_3Dtk{o)6s3#H9HhSjJgk0yjKg0Lx64cnAIh^|v zqH`M4`m|F5s(0E?KOYnsk-E7#{kym1iH}CA7|}5+9>?N}@(TJ2VwX&|T+@rGBrL>E z8j)zjUzt+(ToT)@;Y@ncCcC8FjIDLOQ^1S-K;J=;l3TJofhcBtF8*|&DWDnID!20@ z`!FOEPlD;M%Vv+{AU0mm?h$?y6A1U~=E?W4?=X))@TG52`AYi54N z(@3jnsH@ea#ji_0_yP-jf7>c&`n)C9S*n$7S!5&3iMDgUeq8qP~x4n&tbSJRqy20Fr?{ zn{52EOsNj}Rfa32E*SI8pDpjf^e{b}Ab(`QnnR=p}U30TIN=k zuIlY8X8Wih{dUOe>xdjgr-DwPk+D`HMg^tW>&7C9wxu{_=o{mPj?$Ky&{DBw1y!qmxPwDl0 z%j9ws>Gdq6nAhdfjxdp61s{DMtnYh060&fpKI^q(w2?{dH^eW&*^A%l3pG}#|1x~v zFcZqw34H^jBX2P3=UO?~?nEjNm_^zt#9di^`%gwvXDg_T5qr)RCI>)PppUNRW%W+~ zi#oDW%Mz)xTuht?x*jfx?j8S)b9)L5*zb+GY{H35|Me9mnKgRcpMdkEqVFcyMl8X!{m~(F-D&{=|y*tMfxXcG5#b$tVhGt18 z42c`PnOmMPXbm3L@BseW5pE8yN!sSN&3<;h@uA^^BJK)6RlQ^suUmQ3uzP|_H2}%I z{d-G*pw95BH}yORDk@e+$kf|`dGEk=O@o8~dE07w8BXbo!ayo5#;MK$g-B|ethJBbWC4 zx$|R7NM+h8AK8s0cgMbdOy^41Lv=~p){R(tt13yK=8h~l6OzIv)AO94+cRj~>-qo3 z)pvkn-M0Vdj-o|`B$AAxVWhI}NGtJki>1ko$U@w%iOc>&q?tIwpSq&)U!|33UT__ z{Ty>Mf21(n_1=rRk<`EYbT6ithL9Ym&pUmDVm3*F?&Z<7KbH1^?N$F%!IpaOs?b}% z%3LbnG>J4%XJQk|T_6E*!DmdB8(X;Y(sKMc3=a8oiY4C-bb?ve5uQxkD}S5kDb#l- zF%u*f>sz!VebmV_6(gE<#4}t_J24pmkwNt9Qd^rFX9@I z!6}Q+Cx@#i-ngnHVNj*t#ux^LX}7>1Z>tt=8ex(`PK-=#yZm`^NIuQdvpBBz-isEU ze$DYE*213TCH&8Vn4(O-*V$vWKU!fh+!CMUAuxWw>%~i!`_9MG@9f|gFKt}016jwX zKcBd!!|uvD>SbVg^im^tJvNwoTMUj-LFVM+!*=5Q^dFU|MOvTyZl+6s6I9{&gTDu# z$_IL%gMkiH$x7i%Hsc(AMl%hV`xu4vayOf6e;R}&x4VAcbWp-s;sr>g2(`Ah1CUx^ zGS(GRP^T!mjo0fwMD17hie1+}>JMfme){PJj`OaCJ=fPLTIcJ!fc9w^J^4CVH8FD0 z$9{f^#zdy|r$}`l#@d$E(bHANc5c{1ex!K5(^Ce{DV`jTP-K8@PcgxnXNKzQT609- zAFINj*E>N!7IE zPs0)gm?XDsGN|r3I&AgeptiOpXqx!cC_Kw$WCB9fw+67WnH^qKzA&QQK86dYEO;cP z$SA7*EAh4+{3Lfi_IZPv=7>L-@-u5kw%_Zf^wJ!chB_!E zU8E`%{r90(FS!m3&L^k+UvbQOJ9=$`YA@i0eyO}rB z%KmwDSyidg7eh8u{}+fZ6A?3cvBVAar9tif?*2hA);Unh=d0_mbly5*osMsm|3jU< z5bBfgSBqttz?c`EfP2%IHQygS&x8Gd!3J zoD)NnoJQrOUi_s1=~p0wNpg@so)RAw>lTIzg~>%>A+EnJ!Z}1p$qU956V~H)a@zs; zwI4v{MyU+l@QqE&QHT~ky5!*i0LqY06}LIbNYh`pHy{(NFt06}5B|z~TyKLm0tGbhScik0o(1TB_SipWu-E$umX zEh+1PMS^K2M-HwGDzNLafb0W2b$U)&F11N5S#kzRZ zj%%u_iqpKB;VX+*e79>JtyJ>J9~_)ctbWo7(Z*pA zz?~)~{;XarIjh^BBTHU7WK#R!K}qEqKpird%)UQ|TfhPdzlK_pb?r@K-p(}FhV!~O zrxNX@$?zm!K@zyz2yv~!?zfs;bA;p4kaTj~=54WQE`N2h!o$p!%BM^QyY{!X-$wu) zq5PEhmZh<%9L4jwIoT}vRgB5}NI3$r3iMCIZpOYzf2;bFYW3vBNa}tH-s;1ucx$@{ zuNVIlBm_3%>K2|DKk0-s6;ya)%ro%i)`+wd6U|JyTWMN8z$syE-AaEL}z zhrov!0|RJHoJAZ&)03tJ(p9>ddUs5sYyR{`=URWS|B}n6i@eD)V1G7aDJZTbx6suj47P4kTs8(>q9P|nJ-1&FOddykLM(cgPTG$jq@1aGr> znXJpb2uY74wy*y)f*Q~+&Xo7eQspz(-IwS8@8ucc6{h|_q0y=|CcQ(^@lB<$tHQB%4;lE?}Kk?0J?;B+E zorkUAVLl+>qqOGO3au>D;W*)ZVL5073D36DEp7v>Jxl2XbAF;Xu533MOpY;hea7{l zp;OpDR4!auFpT=d*5EbWhP8aXc&QDr%;qIN%y&OZ~f zFFoMs8SmE!6TRxwMP%;81c=dsWet;=F4zBdl3=+aD9sf%xRq0cFoy0p6pYKvbTdPY z$#QLEI4OfL;IkyQs1Zw5(lMD~8R14^cXw@BDF0gu3pkmu5=54IpHhdqpvUrA)J7Bx zj|@(A6HrRP$8*Sp1aD!b<$z6^_t?)a+DS<5Ur7)z1Qw`(a$(YY5Yu)lbZ_j;Is`) z%la?`U+BAFLf*I~lX|qm`=jS)9UJm6ab!V3)rozpXl)y_!9-1B{m6H*-+A# zLe!w@k)M0+IqhK@v(EsD0LUx+&lf)R!ABOn$6@AyU%u2vIq2q^5hSs2zk(x#W5`N zlk&p;sq$f7Gqma*kq69Qu!Qkc?sP#O(50RT_0u+b7$@V zk)EsJXr^_aaTM>&Is{-q`2H-AKQZ~KwI#wMIPqG*vkh8|U;$@iLW+nxPmOjdJxR^P zz3MQYU{Q{hxYS~Gl0I>Yv>?>&#i-gwP?krvdh8KeQkvlDgxS|kW`-9VGcEAsb#jz&K!WJQ&ca_*!`oJ1&&^t7hwSu&}ZweK`cWK zc;X(5_N{;GP^DeQIE^YRUD`-ey5(Rdr=NK3Lge?spwnYWp6!W))Rs$l^L36+@Y+Oj zzxwM04BSXbTG{hJ#1KP}$nY7}r>MBJ4NQf|$x?dFGl>nu=E{P%KAhov>K)W!{diOv zt?qo)!Ka=lJ3~=5wjfKjTjpT&y-J0d0n5x+8`AlzLCK&=KO7&6ShyYaw?UxvIr|Fl zkIF=05MJoI7c^xusOfaEJugUu%z+YLvkArmL5==<7P&W|>lTyKI-k`nM*@`GX3 z#>}aR(t1zJ)t=On#r~_M-+nWEDx1l7>+ebX(U9z~%z|5~)$$Q&QD4lg;8LWhl9?)R z4J?GPNIr19>YslA9LPf;Fdv2jCVrn&;6d26#^(Sf7eptP-Z16+f z-A!}*XkZbUtgNaNhHT-gex<@@nxn2@7W^)o3*HOOp0#V(mhUA30IaE2VY+wSe+@8? zKLp^fI=nJ<9#O~R)+m>9r&;SVOj2X5!kmX%`(!r4kwwgYr2dH!0^rT!YeFYzXg=u! z5qt|anR-ae{7XNqn4Ct#osTrf?x_-cEBg4eXc>=J={I|N)_o+0=n)E*6X80zUOsJmhn?n9i%V0esYjn! z;yBv5R7-V`jIzuE%#zqCz5cWp4gu+qoU81jrp+~}xQZ0mg0db|AWdb!LdCBFK;Xq4 znhfU2K zS7PE-vunU5UnxOz7skJ{Wgt^NZi|~J$20ZYCv$ZFO-Z5hGxi?6dd?Y!fZLKh9`8=U zX2h?4O`0!Ihg`_@pG+U!SV1g!gP?`a#v~?bd=K=$d+x-v_9bm34S=MM&>XK;Wxo9P zo|@;?1^=LYUdr|iB9Vp~nrVYqkT$}?x^*lXKDzVwP?DO7hFNzvdajJ%;9&LkhJbBt zGzmvf-rW1fl;uSf99cf6Zd^1YQe50XA2zx$uE_r{*@Qi*G3E7ZU?|KEtIlJ$tFBLj zxnZX2{0|cdCtrs&wPR$Q6EsaIRko62aP0`xB`vtiBTk9wM{t$LJ#Gx8yYqLCTwtpn z)*wX{3IY07Tk%{D=|yz({AA9AKvtjV271zEB>&K^SF19|FfzsUY*RdeQN1aHvLPLs z|G*;wB84w=d=f^a@GK7~uEzENY{Q2Ry6i>0m<%5C9g=PJc+MFFV5vA}W0N#Aeu9N` zRJ~mhXx{+jz;DLn1z88%p2%+Qsf_t4Oz?D>viLS)DQHBv;EEOXU`7TJ)K@vb0Vf56 zSlkf?Q7Jp$OKh<@_c3|jkpPHn!mXFE%-s*ae+0Ua z^#QtqRvdkoISa`ugP>UKoM?9FvUYbU7h|*g6}zL}*OmHF#mM%XUlfWIGO0s}kgH zz7HAU?WZK6Ee*ReHFZ^XDEAqu2Uf=!ULCgpmRWq)Wiv7lOMQwF#WCdWGwzSI*X+A| z-Ek97|9=v2f-Z1ZzF6~yo+_c<|MOz zqA{VFF9t60MM1ClbSbsWAI|-Jt->4cs;RcAEXqyH!%cY3M6fORPMB4wRph z=YN{vM$bZBxWm4vD`;ObYCk%j;Etn@PLz4Rw5391)q5Pu|7;9TxLJ^t_n`PvYEll! zaY;c2*B2-MGc?5ufAfuMzP6w8^LvltAWX1!*GzEKyhBxxc>OvZ*-L#C{fLmLk*FUK zHa&F0#E)i-pc>}1fCqA-lx=@*K;JJxd)aUv(W>KA)<-z!LnS{}14J?V26=MC-Tis) zh626(vmZDS*zPT_`E5-huP| z(tl?%zrELLHnIB9BLemumDB0+_+K9SI3$!&p$#F2$@-{Sp=B4wTKTvW%`_2nDBGKl zMPBlR3VWnPH)IIU?Au0H+ggq7P0&PMI7MM3`|%ydls2dnpAHc-vl;uSLy*aOn0hsJ zOaw8B?WcfB){sh2#uVVzJ9v(YdQj=qautM_3x^YPq~FkVQc?{n2h9`5yM3tTjANf0 zs#G_A@t3TUtL-TX3FX>4|F1>`obk-ucFrJVvKHwWUSd?DNC?7E?>+P+h)WVmwG zWvj_n`|D2t364r}Dc`WHBL4MQ4=})V^mx3rNehuo=qVy^ugnQwd35eE|5?RZMhYO_-Wczfv|yh%4uS<=%@TKaqOVR zeQ!!htCq-w!s$7z>ziw;jkXAdYbVXg@LSA_}2A zFrehQW4T$h$F0t)l7-B?nPgiX*^WGmFnZ^=t zK;-gdy9B;Sj=TYw^pik-LJ`z(eF7x_6#_koyRZ@Er=*k(_D;A{0RP`|&V_|U7NF1* zHAzI_;mGmkQOik7qbJbdwLp<2u~d69H!Cgd?}ETrW1*iD7av}v<0arNB>gv{SY-#D z;26HtnlRqrQ*L%v2cr_vc*h+*+)W(dO1d48qNE|zd4mZHp*ns`ZPf&8dyj?(x;2N}$hgL*cO0rks?k8B|oInH+B z0B$>NCiA_1kmVHFzmva^5alZJao`x2R^hLhkXjiT_Usb3Ygnh#6`)0lN zNlq*NJqA5aqS*&%{jNuBd}b#uAQO*8s0Xw)%d}}oVEjK{zy#H{YTpsQi<;?~N7wc{Z(@@_Qk3%1vuXz{LssEaAkAJCkJku#iyX}@Uxqq6z`S}_WC^2j( z@~qF7VI98z?`dR?52KDZ+ow^hNv0SPzQc37FF7c8AbJoq4PKnGhAe7!lpH|~}A zo-|=NhElIP zG1mc~V&nl!4o*K*T#x8Ed(6IZ2N_y9Luv;`?c#=sBAE~?s|)m9Vt*QoRdlpl&`su? zE`--H?dipZ!guGF4KkfQjFFDm&>VE~E(f${yqVb4LmF#$GwG?hyc-fy`nXsQlE7^z zUa>SNAuBN_CTU8zQ0rs)$R7woDi$ip;vTauW7ERl`h%+7v<(V^f`Xx@I~L&M_-^n5 zn*p&WY&0)aU3E(eSU>FcL$`+rx6bcTaaAVG8}>ZEqEnF$X-wqd#543=~#&h6GNm+-)&uq4Ge0CevYQD1!~o@2i0)ijT#a zlB6_^>s?lL5Pk8e^bev111h}6*?wO)9ooRAJVl*C_p_phADyV4^v*0EhKkF+=Ke<= zT=_S{wtnbVfLDO@U8j%gf4@&ZIpCApf5_tM<=iIrPvDMx_jsXCYJyS>hWZC3GoZXtuKkE9>Jw4aQ^ID!K` z{mOj0*`wLe*EOgRZ`6*J^1JHRRRvD3E;C|gO zkLz`GPjrLyZ0KC_ka@knHd$wb9#eSJ()YSYA(-fU;M_ag0H>k1fl|0(s*>VxCdW2` zX@Rgc6kdwj1(npHlvFiWMNAg8SHk%;04K@BXDRUL+zRfwpF@p@4w&DFb821t=a!i( zFuzcK3|%IDDIOW;x1BX6+4PT+3R8Pth-}`+*8%QIc9@BtpD$)`8H(oNWCa|J(S1KL z>FyY6R$uC{!}85u&`nD>9B3FJy^dqu?hW##0{{LFiN%SF`gX(0cAU(38y{@h{vj7P za_+v@-sG(XG63x*)#e;Mk@dvl(6zp(5;R{b*2@md$_SsJ397NTg5Dc;)>6yohVT9J zO8FR2t40n&N~w85Hb}Q^gyrRf#ZUC&CGSP0r-#|e8Wn@X z_}xVcK*;@z8GHF#;YNtRtg3%EQ1Sc^o9+AE{*-Uj*2U&)NhDKbm3ma{-P@3DJ)iyl zSQx!+iJ`WTH?9r(O)+(9K2~PfR5M`5?!k)+Qu9znUK!Q+m8J2Dh-Ztc2@j z)+^&&FOAH-+L3B2!4o&5))pOd+$7$gKY>CJI6SkO`f^A<27#u(I`Gw%G4Zlj;e}nR zrQ<%GfCj?Y3utQfSaPK#nSup4II8{dXZt9HjBi%}-eG=%Xp`XzM4uD$-j~zjzM7D&#r=sD%2d%W1 zdgR>c&u54oN2!Fi1I`zjVR2W2PsDA2A<2}~ARb8c-YL9Z_o040+!Du019jw~^4E_i z?+lZ(1Z}K_k^Jr>-QYYVI>zOQgB^@onS*tfMZG1u#-^1^6L1m3DjhLX2v=*xR-M`R zBoxJdtNSK?+J$(hu(4%N)&OoOpZ|0U2O^pG9V@ zNEINpTky?mvr#pac#n@tzaTLK-kWW31q;W{0{xxHI~bkHK~mvy@MVGcY5wrEskRLLkbW za}Gs^Rl}PN-^w~veQ+#|LQMm*>rnG-_>B+-j{1m4i2>Io%qH z35DUJ?q3RB3xaY^i1jH#^F2A7gC;G%vhH{X_&&2cdo)%53jRWuzdGfZ5E{n#uc^e| zq(>j%qANgq-b~8gy7>k$%DWu2Sx;{F%M>-`NXSy|>)VON-hKN=6Du8Ia@>GgALmZf zV|LP2rZuGCxPb^$vR0i;B{$=o$1l!s?&qxY>Gr}Wr|l44opqnp2IaTCoGp#F4F>!w zCm>O`Iv0&f^YSevTflZR;W9Ih>72FqSWZxCFWns zNe1m!z*b7j(qzNCZo2nQHu5w*Wk4a=ieyFO&ZoQn$#ZJ?ALsD`5{Pr~Q$01d%f;&914Aph zJD^RrL0L~t_}XK;Q7gk#qjvYWe!ESvq)J&s)@JfEsxAmh;-& z5t_>oJdlzEKt;rRdX>5Xf(M*X0!+y}Kx{FAgq{;J@gyIkM|*ZglaD2ddT7sjk_Y7E z&cuGR^Uq33rVtMW$H)VhWM`szfNs@N|JDA|R4CN@6&^UJ%@}__THDGijbTHZ)Mub8 zMTAiC{q7DPJiDz{k-JKx$hD!qCJ6attKBY|DE&F#sS$JF4s9?KEa^6&(cY?=C=fN< z{Fe~Y_mx*MsfC)ijpL(cBJbk}8X~)DiG&xAsE1lUC9%38S@goH{6$9-b1yl|K`=dm z{%c|Vf`!i$ijnVb4tmpRDH;4baac;KAft|Qg8V^Ie65;gh+X0U1VKq#ObH2vk_+I>uoO}ND3n-}%P!ryCaa41>ON#I0 z(mx!pwqK{(@8P76^;SR%4S63DnN^e0?pkhs`1`HuG zmUSAi(TD?ZdkE8dV}ufB_7y68CABx5X!e47x`oe^J)OjfarCsi{>rZ~o_J@)_^=A2 zQtq$aWs-=Vs9Z*zG>CjP3_6!2oBnG={fM@k& zBwab(SD$ulckKmXsPQxJltU6^$mqJi?+LsEPB5K8q69{n`Pm+-fN;a#$`&k z>G;TxS!F|;c9HUGrn=SWKOMxw)Z7_Qj0f&y=5&|u^}T*ruzP(*l1u58^wP&|<)Av| zo|@f$>S8$}chOx4*T*BU{M|=iF1HNpnqWL$J2#zK2(sPta7JmKtbjbHnHVwBKB1s& zBE};%OCeSxDg!fu5PF)I9p1x?$b2q`(Te~I^--xA8aF?WhdjWKIjl?45}8_k?cBp! zb|$&b9$JpZgS`Es!F9-&8x<&8rA|<9-z{_=n($QH#P7^O(tGC2)gp+~vyhPDk+Pdi z*t#*0;_W=R>sjUV(eWt8m*!cG{E*Sy_YeP(g^%>XJbc^VwP4AVsFJMk%=P?4eNO{1 zY(3D>yrSWSsG&DK!y62G8Xq66;blhyS4bI)cA(@RAh$`w`^V63N`q{9D%|~r_)iX#vL??Nn zP#>}Hy8+!$FZjHi@$TY*=BzgWDtagfo=<3T>~M#o*9kOhelxTwR}2BIdJ5+j!(2T8 z^@?MK9b^?wD42a5ConQJhfG;1bXCT1sDpWt=Q~SYYnYHlowCS0J&3g~=S+Ll{b&L( zq41xbkS8=UhH+e6WrU+#qh735^zqHE)hoEc9sQ{vy$@6O2*OtLlZ%sCwl%#nzd(n%b zKUx4jS%7QyZ{>P~LaB!)M|M5*lm~WnkU!j+sC(uDT|!sYj&e)^L?h-To2Lf$6;j(y zy}g^Jc(>le?1?jb^GRZ$wQR3wA^DczljRfMYVOt#y?rN^-YGV!_&jWLR+v&^WXIj&neye91RVPENG-}FM7`ECrH$Hx(9r)17(ZcSQuRh zYvxArTF-cbHm({XI-cg`TUd<3lSq(LywErK+;*uclJiF`Ft&^01B^KXvT~8pMN`ds^;v@hK{doU_b&U?AFz{r=KWr1a>K7&XY~_~ zF_duhparg-r6HQ&V5NYUXAYLgV_}j;kmS9=R{y7-o6nD$Ls<;xsCz%exj2T^Q@qhE zhx01`WuK86#?W6v=aEN;&=bTr7BJ>25g zWyTmP-ozo`$wMKQ1+aa$_r<}Ha|m@nptr(Q$NYl9>=uKb@8Hzl0YMFH{@5|Kf~3n1 z;D~ludNg|Nmb|VYgRm9M7wj*EC=-x2m&FCNS|o!G#2!m$T*eQp4F0c5Z|>ynA_P(1 z{e3NrsMRnX;q%(0Wx640I1!F>o}_y}(t?)j^opeNdy5SJ$^$&9y%gvTvT?_sh)AqD zL~I=-J0x~Hhlv^ZL=#T$59AN0BmSZA8^L$>3>fA+q@ynizA*o>{c5^RFKRjRnwzR* zaiE?eVHK+V*eE0c;EiJ?$NdPU0_Ux+68c)LYP~;nUzrka#{dR^k|)6!+?U6=5V#sYc}kLLX^sPpH7U6t zuXw(+quMe3mA_^NWe{jd;srPnOJIyCU&r!P%Dw2Kv9T@kt*z=mJMRPl~x`X&vJuk&Xc}yI}Iod7}8I1{lx5bW8!1mcU zasA0~**tBo}9!gwa>aQAVHH54BFjMI5U(1*KdIk zq5_#V8r-b4e5J}}~aFn)53{`eIE!n$bLG9`?K)^4*JCRa#aQH-lE9JOw<^A9eJ;m2GyOl;L5`=BYMr&; z6~tsn7p&8M9_b9-^%UUo$jOD211qX8Hj;RYLRTMak=|omH2XMvTX$NI_8vdfleQXh z_Nu+?zaIyS?^)7g{$LfS0wrT1$7?eZ&MaYbi}${rjCi1wkudcLz9s7GI7wF1jr7Hy zX4{jJ4GHKpE(gJGbOBTH(I?@h4=w#(^r%9VA8BY;CYbWnd9b;@$%8*Awrl5;pJQi| zb}-*fbJZe$x1HsHn^&&tw*0f(i?0(uj7GGe{2h{}Hp|G-Jo;|uJg;Pk z4tkz=QG*#WPiFImpWTa&GZ}o$0bau|j;Vv?xQx&pZ~V)^+b%Hqk9l+ zDmVd1rkOYq&L{KmH2Fy9wV6ROnT})ZM7RUdRKAxV*V@h+dueB((_?euGZ4{P|0fv? z=95rKvw)@OB&42UFU}ZreLCAgx=S6ODv`|HHx*>>Cl#>9!a-Cz38-Hv&D zD95s&A`~kA+i>f*EH~J9AQ$b_KJ(#3gS=Fb-@9Y@&Q6Qgr`TgfV@?`hv@15t>N)kG^>wwi{VL)5fr}O+i z!h-tNQkKhmK_%XZ4#aT2Igr2*OiFg0e`ikdJGar0?110;i&yd5u|lil`JWgC6c#b2 zF?;&R)mt<>cqU$elj5bfoTN*um+7~~E^3B;2R^IN-YdE*ULc&;~4poeVL^fL3B%5)7_MxZHNR z12WJtzT`GCCjZQ{v^zkpZvoh2B_eQxm+0IEmF$?zIoGmBjW1hNDbz5-*Vq))%A366 zC1JuDq026TH$3oENFvA@^zyu6XdFK?Xk`~e| zbQnqiBu2Nte`e2RE?7>1nl@J+8k3YmAt#b~R{M1=ufAwtR4^~XzEXMu*OStc<2e4q zoStbtihi*tE7RAIA~VO9jj%QrIHwY4;?CiBD?~cr)%~|lL05T3*MEs_6Sxh}YG zeb|5xx3!JN-~SWe=|m75)uhE2)y`?f9AHYS!-p6hLELeXG*DEu2Ck>MyKm ztATB4XmIb>l2Y?_RD`{kj_Kh$ou#u1Az@)~L{lev^l>&t609eO%1 zrnJ&{SN)|BPfV+AF<#cQl0I%T?4it!C`Y?iUFPk+pGdi3KtU;yMSL?-eZT#dT;l!^ zVuk-$nxdC}ymb2Rx?kVm(Ylzf{{SVKKF(yjaxUN!D@KfM7j&Mv3av$0kkyzvC^?__ z{u|&KQb?o`k@l!Li=Q0;hUIa{d>A3ARab_@rI{A|8Z1DXRh9e|!GMz|nGZolORNpPQf=)p6G`40ft*~*Ce{0T*7ER8RQ+{P6CpV-qje_|S;vQWIk zpC>=GnQOlCJg=3@wfHY3=`Lhbv(Vl16x|@b{f?J>ERq!Bmq1xi!Aldk zB4l2gFT4po|BjHg@(*?s@m~tP3%hYHQlOHdanN*}9Mi?+{&Dj+Wj`hT6Foc#a=uLT zF}B|WjC<$Km$@IK{4sH6*d-|+2qCqWBlyJ|N8kT!aYSsYWX6xug&q^4lP~?6wXf^9(r@?T-^I7JsH-V|NeyTW;&e-vx|=D=5)%3Omt_ru$W8WQWk_Dpi@+iBP%!gvLIih4$JaCS^- zoLUaK&+ZQJ3-L+s2;8foceR3c-%vJbIb+u?Pu6mBbi>2w!0Ik{GpwY(2eS>0Nec7> zY1*>!WR6uSKg@+E7%Uo626aNm=e)(JmQ2o%`2P+m+_AiRcqKB)G8KPJJ)0Y6#FZ74 z??H2cPNAqGOj6jyv@e=z+&>L;$~nb#B7W!a3@QWU)SPe?`yJfz0DF_Js=`XmqtXL& zlLnEl{Rp(&w*jQ5x#L=v<=$ZvYcY#p2%^^E6qD4pnZLOHTFd@!7R421Y}(iE>BlB%{uv_Bwc{m|Ba_<TQLn(RTPhj4`*KUyPFf_W}#rPrbUBCauOiId-K7MN3pFugP5P6DseP4G~!- zMxT5XSTwVkraFLmNMAFkA@QmWK+z++t^#x0RV>6|hufrY!uK2ASQOd9DMT#&IiFzC&=J&kD? zwZ2_ayeQMg2%>|PF1o(q?aj~isi}FSqrbJ;u)o|emca^)W(F)CTOxMH&AChPC{?uR z*sp1gGFDahEZfw(xZz0_{XG+X+yYecJoy<*Lp_ridb_=PD%h7E2-%2F#cOg$BjSTO zx5Fj@QYwGdHs@A&uk%;_hd=XQlpTH09;zP?nng!ee)j(i?EJ=u+Z8*;LgWBY5J@x4 zF)Ot8Y@prxvP|A{aZe@Pv>O59PWH#+66K<8eI_m3e1+KyJ&SDp@h6>l965ksw)fxE zV$h|fLQ`b^LT`*phLdaF)BSbydbzMxSG^+vp~(NpjYo5ZyP`Q@kf}F@-v1Kqu^;9a?|L^-~=p zNw@S0ILb#yNu9pcdAHjAD(9A{hvGKa#&buSz-7-b$t2Ft{!#O+^3{Pks|XooWu_bO zmF3kQy7zJ_`_m={l$q3;L6dKcSeKx_Zi^{iwGpLjJh|Z(X?wa3?YDA znCq=9MgY!w*0NMRFgUb} zdo)yzHLZ`;@EfjK!ftdp*Cw`#XQ|F$7UcYg52an}&g~;)I)JNWdYxE9Ro!W>1O|gE zzNF9uQ=IbCc~p{tC|}RMltt4wxpXYg zhddKIGAK`TYzL>8!3r(M)wE^%uR}B=ORFS*{?#XMxBgy}a|`nXv0VL%M-mA4WZfP- z6xhPWR)1-;lwF)2-#uCiUu19r*Dx-I-TQTjvO; zLJaH4SA1b>do~`BSnqq`%c~K3h7~M<5g7t|&Z<=MGs@X%7Wp!&EGXM)S1G;tW6^{M z=3_cIM)YaXo>b{SSrD4!RyCW{msE%ytbJE2Ak=?EPz>`s`cQ-}o2PV|rSP&07!`rW zc^^0OHD0{4@glv7C;3%QoyTppcJukskC&_lv(RN<(8v{Esw3rxEeKL{?~@3I!Zq;w z?4#x3F1Zc3 zU+cpDc^9sLRc(=Z;jWC2AJW3NZAen3_!WJJHj}XW`Msz+NZi1IaE(ZrtbHHSie}8* zUI?TCkKX_T!)EE+H$-B|qPp7~7mR#DUa{adbk{zwZmRzNOFcy?iNPc&b^P>>s}@6X zq%wzS5Q(^a0@t~>r`WA?6f~c#6Wex3GfZMncV*;*q;D}AjP;}bzKt08Xi(s!G5ZZT z)h%fBA1EriPidjX!U&S$ahyVTniy*taXyVUL5&3 zkG{2nz2oo#cGH!3P68dwlodHM7x`QGyymfZy3KRSLtOg$c@HyGe?R44&zg_!JZntu z`{=Dr987_p%bALgRdbKN1lV^E4e#s7g>e(1G7DDSV6f+>Ghzzfcvu^d-SSUceJ^Y| z`ndP>LAkbF^l4!wP4Uryijyi>Y`m5_R$tpxr|UU;bMAeV1{2@GC&X)LS2SL2xh-{C z2ub6kd1o!X{e68$T0Bvz+`4sz%HFN2NG;Mt2$XhU9u=KcOwh*XE-4RBMKy*+W3XGy77LsXAes9v7IEVUOcKW77Ui|hDf8{=?-yBl<8`XW( zHn2R{J+N%2LUYMvDj3!W?jI_VOXE1+gYuvZvU=KPEQLUXU%W<=8N+c&#@AX>uh!7* zJPc?0i15q!I0X^_JL&(}vDL~#ME|q86XkcgtZu$~2g-fB?s6`} zEiOM}Bv>!f4`9z#PR{?IZTM?Tdah-Za~)I3(>}Iy*_Mq%D5dv>9Ny-N7cnMU`W;W+ zeeJyE3zP;??Op%4@!H!7lzdyC_dMFt`6*q1#hilG_#YUFJ$*v38QY=$qdHeiEY*y` z*O5R!Wq6Av=-V5|`ZbJN$5!l;k&BjHP&$=o-*f1K+@Din<+XX+*p_i`Q@?j|i}g=r zz68&E)8eTjuNow9VJ3=$#pR(vo;HfZ?YGU_ZclWq#B}4`I|bKl(yC$DgBEz$Td2!Rk z1;yQhRlhe#$*p44gr5MJ>2&6B=3su1&X?|r&+MG7?R=ImXEhh^$THzwth{uBE~gBH zu*eOWLL+&X5o(9$kjrW%W0q6`4LQktxtPXNl7?pGH4K7xA@J&-#J;$R7J6|hwONmE z^E2D<7TF&>Lqk9zd~`d%bjP5@euWbHBsj6Rz@E=&e)yk9xo%{v?_kyko~msDUS^!- zZh|U-#mDb-+fep+ew?7*$TBThk#pp0zMT%9{!vz{s-ZgTu}4g78dF@dPL^A$x{v*R zEBJ>W{3LXx4|a!?Jm4Fz6@Px)f8LQT&1tp@#-{=58J+k)iK+JEUjLso8)=I=zxlI>>x^v6(fNs$CVK}Y(hA!<`#_on7#m(qnGHJVZw!j&66BXk9c-z%> z-s{K&!@GcmA7LV*SIiPR-3iP_m9998tFXTncWcrWksntO`1=YbTKf1EM9W+hep2@D zBNBq?_?x{~$|A+cJy4O=3sDy^x$G+r$>pg^YZdsg>G_Csz{iP^ymzZN;Dnt|C+Gh3 z@Kf=(@fxD*vnu~wGvwA`o|e+MAh9?zZtzKd?s4 zh1bm3bh(F1F0=0K7o{uTaLl?)e7*H#$O)I#`)%D^49o)FUZ5A->BY26JzOkq?>x4> z(9yn&T%vmkiae#%15tbC&gWmJG>a95WgpbAdz^oOY!g7!S7W_>rLcA@?~>O8xLS&h z==n8Ag^zTnE-K(``a+_Ih?^GV!og1_TdW~L3s|w`XsbySOm9~{HV5R1T3zH{{SNxvExD85SoLm0Es-1k`GRi( zB7pnb{Ca4uM(Gn*v(drd|M3HFKdF0dCgI2&*%QTIw4a;N;JLWe?uVV;WtKIXU#0E3 z0wLC)kx=5@_vdLC(@~~|u2)!BQtS<@4~eT3>rzrm2SY`#tx+sYtr&H=%7z8^ku&sJ z1}~lZW8<73s0{0u{h%-`N-SIAGfa;GksX<>t`KO}^9%pEl}WY0mrH-{+b7O%4Mjih zea?hbO&i+84xvtyGbpqe{V${7@%El)-~=LP1FA{;4QdYROZcw>0#yZq?#O>7aLI+p zAnI182w7*%iiD<@IC(|ZM=xKCfNMrkhy^9O74-d#ke>C}=wWo^2p?P<68*g~&@L#KLg z?pHWamCBNHx+;jJ%j9Of2i5XCiq7%r>_U{s3eiLAIEgt2oi5t) zKOcM=Q?7vjENEk=a~ew!XM?HH!k{lI{R4F?unq%T+Rz)kiDb93Lb9Df zlwt4%55C%7C-ZA8t8Sn|^9)#OJdq9;To}d#TigNIsh#g|Dxu>Br-){!duX^IjxWry zxg#=LymJ;PZU18&)oS2^LyCE};MQF&rd&(8@ZIjy>*tW=JVlY9!>!zA!+B@tmlJ2}QD?R64ME$&$Z+GAo}~HB0ZihqoU-&bUQKZ-(NH zId^2E(7O0sd7&|v%}jyR7{(6SVSMNlz*e(|pF~Z+4idZyeR})DtFZ~&rrcP?R(YY? ze*;>@;ndD0!O+=yCg2J)xE-kWIoZ4>js)g=PF5@{-#Kq{50robLCIXLv&UXha!{$u zEa-k`B^}W}2NPTNw3~woZea`cl|LcgiECL>weD~4!9~}bfZ&y( zt*7PKKDeEW(coA2@$Z{fna91aDq1mBRunXHe^Z0Z&P^$bDT2=jf5g1nroyK}4=C-S z5bNr7Ah3g=a^pLBtioDs)SGG3#{8)}I?+-aY)MJ;`xlD~1;GJ20a^icIU>PO)uW`Y z6Mgnrh0lHN`~XP)fUPc{pK|#fzH5lSe`O>5J}1X|Yb^X-cxxl-)62x6O4$4|z^wsBDL#;kIE^uq>5UlZ4@b1YnR_xOW^TlKr!JVA>=w zbYi>*m9?f=YBpjh$NgJ?B^c%B@LV;kg8*WEw#~Z}|884OI>zg3soBhO?bOB;tLepC z_*XwvWb(d_ez&e9XVaCIXOqqLT|xr$Mx`QbR?ojmZ}a8Y-``FC!Lw=ZutrIez`fx0 zp7T&3`0(&PAM|;$73V<7ErQ%f9P+fMr_`*CXokvmMRxKIo6~GIS;nm8{T?NQfKy1y{fBzs zuWE3L9$v}y;9_W7bUy9;4nuibUP8gDryzXp!9o8sPq@Xe<^NH2CD2f|?|WtpMz%p& zvV@RSB4t-2LJ|qB$Wq!YV<*WBLM2g@rKq$>C6!8AjHSrhreqz27NiZO_+M}J)$f0f z)9HL)X}s_A+{<-c_jN1Dh4y=kn2r;bYZgPU`zxeBuS(uRK>4~Z!{KMUYpQ~a`<)ks zFC@QLnK%Yo>}AO>4XK3cLxq?o3D|E3++%@7OtM13AboIWbeM5Ww?TPpgtpuurg~=G z4t{_19lxx(y~%OYzejHmwJ>EEvbmf23&Mt$r)#;7vAGF9ZAl+4<4C?~5k4xguam!$ zkH;DXIjeh1j|w-6qCOeDKr4xTt*gVQUWyI)^ye0q7K-mUY#&4s2Js@wW^H0^eiJGyA+ znq&Rlt^|g=0=0LOc5&6KsM7ME2Jl*W7b?x4f7z{Lwtsh}I6CdGAAk^~fi#Smp81_v zAm8*;g0j14@9x1?csXX@g>3Ef2GIoj9h0yI^wym(g^FqtmOqm)-@A?!_-qh-fx-= zxHG&hY8X@JX*$PpSLBBXNeaQwDBs#p6 z5-85JjNz)I@HCa(gGu@(3!`z)^`zWq!H>lkY_nX~wgV&5D6RFa2W=Cj_*NNN&MBx!YUt}oRQw8qZeq=oIy3(9 z^ii4d>THucg!+iM*w?#VfT$e>QN{vLv>6)t_j$Z|lH- zmFkzJ+>TLh8PC_PMdYfWO3dhPhJ48No&Zy>?WGv~@Trx?*Ozh&46d4OE5&SLa2-Sl zsRFSt7H8)y{xNL!)#$Zu#EAEU4Yh(kp3h`lo4NbO7uG#5I;J*Z8GH(O$LI0WYu6s+ z|8p@|Uj?|YmPfc=o7iSh?ndXRt#ssNCZb#n)SN9X#n~K*xPMLXVbF3C)!D$-U0lun zw0W%ge^>Qax;Upq+S&kZ;T+3+cr$HO6pvRl!OWJSe+0U*GZwbUY`%b6w>4FiMe7bJn6YkwyPo8?KDpsLUl`KA-Mw0uwYHzs%S}sdI z5xG1OsBKdNc3Af6@d?BVl5-syv2*frljR!?!xY?q#FNY&nNIh@KcD+hPW1r(o4) zufKL?BNI~OH4WV(Vq#)SV3>1TKPS&f6jrpYGNzli7nd&87tz+&*kD=*y;4B$ao-tq z_RjYO(slqxd`cfWI}r7Kr_$4SMfol}f1}vVd89M@IBxIOb_TJAM{vQ6dj zB~h+=)&m{qKW9Fezc~I^%KV+XC6!scw;<}>WU%4u+h>-mmdY4?zB(4Sx^^Asx~QMr zZKko@k}jq|e`spdL*<;vlbhyxd!$Tj*fgPj-NygU-i~y+DFV{zq)Isq{MakMLcE_n z%hZmnSBg5&8YrZ(d`;&O)>#^7@DmWf5^YmC$CC{9$)rUD(>7(%hN`f|Y%7g69?g8< zsE09otv)r+)&T0ujKz^9ZZRUt&Xt4oN0>@oJ$jTA=!M`?@$+)|$KRlCY&uD<{OaO; z5u*TT(t2){0vC~7jY+;+^;i+T46aY7jQC_xEj z`a16ZRa5cCWmc~go{mj5HzCZ>BNUHtVo9E2fS^MRHdJ&HTh(F0sIHxWQWF;``+RHP5; zTYwf1YI3L4i!`bMI7@meT)CRgjgKI}Xs0$)mPGc~RVS{22Xmk0yXg<2H+qz%b8*ey znQfi(<(B-)sjMggMyha?pPz2|QfXnSVFopk7-xEWb33io|4QYkqO>x1D{!i_aGk2T z+UCMpe-E(gJGy?lXIlawB!PTt$rSy&6=7tGetx5mJL>EJ}%qUFzcjh2|B~gck zXff*E6Q0QoEdlPm{!5vv8X5*`R!{MA9jHyGs{88o1-q|N;iixlzxl}iAl>YgV-VbIakUq7Yo85s(t1%O}c!>Y=Gdi;9Rw4c8^T$5zqHXc}{5xR3QT}MrUL- zD+gf%kqq=*z`U(Rd5!-5R@D8oVd(f=8!OB*F|Pj5#&6o8+eDH%PFjapU{YE3_1+r`76X+&7GvmS;-qVy*(|)(T)edwMumNkixiB0!-Zg_d3RAv+fl~Vk~R{G%haC?W7$BD)CT#{ai&jM7YAuL=BZfGPDAfc_zng z{38;@t`Rki9^o82A9B4H@?`!UsW~r?Qw4BWxl5>+shmZhV#MdX_!;hLkPUs-m5sM- zU(U~tG&VTMXR=;To^NSefsYs9u+6F274~f+B&dR?Im#D`7GHvy$dd&_PDJwym`lT7 z>7n4(jlXe3#ur-Kolv`aAMV-u;NqPEBAv{UkVN3C8vTBu+HM@ut2?27U&L=13GNIG zQ>*wXyrfHd|2Wyag`Ef*tQK{Gqg1oo*~?cvVoqF)5UX57&)a!UDD3{gliYZZgL$Bp ziQ4n1?u5Kg5ARi@*g<-kXT79P^Og2pb9^m(n67qMk+{(q8-EVtUd`DW{^d%fCDk+C z=rONO@(0bEEB_?@J|&iL(ul02_IzHpQLsbb?KmuH3v?cv=$6h)tPB>pzR6{>-_HNe zWX82+; zKUl0)rVF1_>3KEtTuK}Pou8}ROwasg_S(Wf;!TI%KnAsZF9UZaIFQ5~CXkQghCk!5 zQu_#1PM~-}Ea!))kkV46fp5bVqP&eWlE`?lgU^K4E}(aZtnCq5>mLEZ-WIHvF`Uc1 z7e9XQ70-w8gwaK&N|N)gZ>d#7;`f>{{WF0&vRQOiMX{P|m0d#0z+{0za_(n5$7*=N zwDplc&vL8`Otf3_(~-zNxB8PHIeP15QguY@W%O6wm3NbJS_GHwOlUO|!@N`)G<10d z+LK>k8gXF>=#J-uCX!7%20l2zgT=wae;$!;=-p$}i;vP@>}2mezpwK{XX$)c>t6dQ zq8$GEXV+>+vT*Qp@-vQ5u=KK|+3e{n(mROzMqe0??7;4yfu zf1%*%zT`IgV-0?Nh1J-R9WawDkL&d9oFZ95g6ZU8ka{54qDnwY(2_khASp4?@hq>* z-|vRsoSMm1_q7c7roEEqIeW%FThov&-Uij?RDFv*7{U33;&{BR4kA^@3){yTGA8=0 zQ)h1cR6gH$@H3SNr%Y2f@Nx@aS@*RS__7uHlU@v!Z6zIGbkgZZNv25gX-)5`im0a}x!FNKe0kpX}Pz1d+8He%+f`Su*X? zl})7z%L;wxyH;f$y~S>H*qZfrps}jN1N}wN$`|Nf3Nv1~%w1Q=;EE*e8IG)UE%Kee zIbN_tOkT=fSe6n=)isOeC1&H^^=c^2t@?iIrm6Vn<;;?Jl03UJ>dO;LxE!p%qB%`B ztjshDElrKPJoy}`#G(neULr7a*)Zi%o$-%i6?-Q!Bg`NM!`>+0H|DhAH@7k zPM7SsKr?Rki&i};zt`??R{Fg}H!a4LlaVq%dsFUp_l45mt{r*|;@qU@$15X&%5+jq zt-IxY&)EFBfJFYOT)x6>w5}9S&bR8c9#fWs$LIfjRgq2f@MmDDrGHD%ib>;5WuX)vLG@qS)VSEjg4G>z#6|1e3Q7`H>l-GJ-Q}fs4|_go@E_e%EMW}wd&3q93F9Zh z6GEZce@drcpv2e_R&KF;cRlnN&25E6_qpkdkfU-+CNQ9T2J1<7d?Ypge(CgQwOE!QI&bgDs{O4o6-zJ!T=H!NtwS+ECqn# zan~f--)!QE4!R_vthIz{s!!DKlv}IUvV+ZO_q!h++-XEjI)YQuBoJ7bA?|FSLfu*9 zCVYgK_ClU#>4Gl@cb??^RDS%((X8`37eKLEc3i6AdZ#wQv&f42!p@v$;w zX)^}5z-b@Y;UiV`DeiFz6~bENt!nr2b^!5{M(g_Ot?+hqTo?7(P(-N51#bG&+W62- zo4JNixgEW4LRbQ7`Wjk)FDHJpbOk4)I1*~39VrdktE>%ymb$7M0~}QKsw!8k@eai% z=?|*cCO=G0*dbuA@V~QmZ7hEZBTSsL^)aB(E!b2?@z055e9?lV-dCA&M8E_EvbUT8 zjG;MuYqT+4D77qc>OFA{uQJm1Z$irlI2oLN<6_@u5yemFr_PpS-!KvxBIQsp%TO55pz7|(Fq8&QW zY!CA&=_6`$BQ^VcVUKm@VZ!@!CVJ(!Ct!^oWE4X4EhGysxxq0;c)a*La-&2-IFA-Y z5Ub%Hzh$-8jIoA<(bRi0@7@`~{aV|!q@g0T4uLICyG&TYv$s#%uYm8+A3Y3vc;-og zHv5dYM!~MopJpZ=yJrQojqMXY4bvQ2@Q#5_7Ey6yK-pS_JBMtOE@!gKF?715(Qwz5 zw3DB2xLlM!#J_NExdC5o$A&@cK;yp=%}bSQ({>-*sAS+D>|@1zs)6Q!(Z%6G)9b5PwQA1VW-?GXoP`mb-7!kOK7p^DvZ+6Rf41+az}h0wxHnHS^q+cXDYcPV zE7qEu$DYim{6eY{8KlOyd8C+}FyG-X16l#Et#0@?Ee2?LK40hd0RU{vVZP_Na5L>v z*O!C!reoVD%XdjtEFwF1VlqxpcUgBtrkZk<$pz>YqIbU0R4ggGe)b+mzA9JV`q(C9@H~ zpN=;qN_D!qoT8-2x~7f#^zm0Ay%n}zKlugKcEM%$lqXeB*e}*zsrb^s;s5G(peXxU zI{rpA8Wm!Mmt`uty4j<%{djx_)ys}6no`(2yTQ}lGimDY0X8QiW2Z>2l?X$-9#9*j zqgW}NO`!-lX0q1pB``Z9^46yBkFAkCnyxd{c__uGwBN7hY&Ay;HOt7fi*#rkk|@|V z;|C6~70T40{+`=65nZ169-H+GE!CG`$=+0Rjpw|Y*t<12A)<&i)^>y>pY^7{KI^=h zAvV&O-f#sHYN*QuuMY}J6?{#*wpp*J^lrFTPiLn$@`R9pGF|#JBr%!P0h}d=>nA+ zn7>K^zw=nT%K2EM!#= zg1E2%I9}oeNxm(n4&-xhhGPpXNnl+XNki_A_!YD2q^-Pux#*yxHKq@B_vb`~Y}i8B zQiFw)ywxA_p~EG^sVrRHBeacUyx-Abq%w98XY&jX>^Irsfe*MVvQ;POa1|6jn-SL&0Kx_gB^1onT(Xef0 z$_l>JE`W(&Zh2=RCWO-$2Z8yVGct40G}bA@Iv>Sc9e&+ zSk@8<$f+oIE(Cn)Fei}XekWL5`gl%3avBf647G0zwSiN~Stx8KtoII5S)|I>II0e^Ld=}9QGM!= z9+aagsIbSL&w1gl6jUX+bQBoQZQ~i!C|aX?7b{(Q>D&|fZk744(7yf!RGWr{dQpxh zo71E=ZT}SZ2ls$J)=}I96Xx?^v+8T9L5X zLWy^K+LH8RQ*>srAB(e!<(H14V2RgFnH;%~eKO%NlMKFnvcv{KLMSCyZ~2&p?<5SV zeI!2Q2AuBE$-1)`%Oun=wP+vj7RbO7-n+}6EU03=OqpqUI+6cFKZ>ut_0IFDEOn=Y zAIRw5dw)J%@WEFkmU>*G7$9?it0k}NkDSrhdy+nUXL3c%Ii`^Sx_q-N?!(k+Rk_k# zLK;fY+P*Qcdl59>;Qj0nmDo`63e$-@#Fhs7n61a4+!;)KX}=Q~ok#0c3WyJr_i3F> zwC_N6Tc6h(2`4gi5OU8n!xsPdXjuXRoPoDMUvJiE=1tv^8m=wTy}1TK zo==J4f5%jl`V8V*F~&C$o748s71Got%@#`WjCZ;n7C%k-Pqjp#B#dE!g_tP3nf~TN zsQ&qRu6LV5nqj8nD6>7G)xON?01`gUd0wQz@k1dV;{Sp3f#R%Zoxmu!ATF0^>?p99 zDkF2jd=Mz*IjhFw$4;z2!YHC)rJe&s!KaL*rg;&*QkQkj{GY-P=?oUi=kGK&a_@TX zLYVnHg|a!A_F(Y7%T-kCwICjXXStN_aj75QU^3iMZaj+e_4z6#>AjDePRJHCWiWTE zxGkgPg~X0m;vYOMBr5yjqrn?Z7_k*(Kj4{$yCv%Q%=;yY>K3;sWMEyIz>tB~Mg~K= z0~^SBHor043y+x^;3Z9D=KlC}1$(SDfm$``RN&TtzhwtoiPbNoe{<)w?M1G6@l%BS zZdwDKFeXs=LyICnanY36P#MiRKck9c?gS~BS-Q-fzY=pr_OL3Q=5Hi9hQg{(!f}6V zWch=b<%$CWjM$iZU8YBfvlf$g7EYh_Ne5`63i~ZdD)b~OcU|_9s6FkEOX2fK__c0N z<{Ak4mTYLdAGz^%Q^^!>{Wk36{Jw~IR(*)o)|ie8p4HXS^Zt5)pGo}0Hky!)*4mO9e`>#Sa zZH*toF|*jR{Dyp1*+1%{YZ=KRXH4YayVDJn#=B@S1m>&D%|lw-Lg=J3Ry<7#K1>fuZ((41W7^YWh9%xTM8XK|J#YyxH2HG`XA(l-#^4GY_07h6MkV@T|`ZyRcL za)HykgV;FKX=!2gHU3!foaK3^N8f!l<+?bo32p~tAx~M!&lM6^cTS$Wy=mtw)7>IZ zitj)_vRAyKm0vgZ)P}4(45z7WmM**+CR`meiHoh1=C*X6>(kALJ1s5Vi8V|%FN`B9 zo?S|X+P9HIEUcY+qw8lP%}S<+KS+|_*e;qf=Xk5VeBDcpxHwrwiN6%;a0Um@J+1I3 zvY2h-vZj0Rfq11``K^tNG77*H9cnX^N-0)5S|Tcnp6gqCF-BO@uwQcC^yAcK!T*8< zanBhvH;I{&7tG`l$G=Z0j3V@s_zSggKWPi0nTkMRFjbv?x3U@0o8>ORDC!>w=WS>k ziVe4rqid{!3)hOXP@B#sn9$&dVxTZqoeoX7+yK2v5?HBQ7sJ24b2{I!1H4}f;^ns& z>5q~gs!d6Cuv{O!HAQ*Z6rx9aWbq(qIcJQjU>tTb_I+LryHWAd`E5%+-Wx}yw^)=y z3ErBvVnFsCR#yykmM*bwrRPKhY*`XIbo|S^rrN&Z0)s0RY2qRS%skM!MwBoM8C~ym z##FwSA;q_LJ^|4)8y4iJNZpe)DEggj>9;%sEzm$w(?lK~n&Fq{oFVkzBVlj_!e)9m zVoEj z?!5?v3lL}?rE7ay@tgWbSbe-6C{EKL>v!#j^*`m~2~P&;36vyd<>X(D!$JztEhqIS zJ;5&PZy1JK$-4u&!@kXi03M0j4XLaadW6lO88Bcc-a94kAOqXQSM^lLwSi{MO`Ilj zVazyKlDT>>N8BF5u6>D#&*kBwX?gXUKd*UPl9#;n2h4`A{F=Sb_8MJ!DOcqDwyor@ z9bkP&{gkCt4G;15JQfWu%h_|f6I%s+w$~T5;d(}yQ1NaaWKX=o8<8$qwcZ&~O zxxtWYN3KG7$36M1Ji?*qP(S~BlH;Q7aLV@Sk#b&lOhha;@5( zujdwuiF|%0Ag)52q5ez2t4fT{JgTiRB^0^htYHDsuo3pPBMp)dtq%QH-4PT;I#rSR z7F>zuZG@W|V#Q*z+RFc)tsz@R$EzBxme0@fN7AQ90JKw0q(ZDHT~;IyV_LG}#3C~{ z+bMzvlAa*w%fK~ICeE!^%yT=;E*L_68p_Jbo6&9`CPYf(VNlaGm0yfxSP6XI_lD2> z%Z%N_ra^XkKf+ypaC&VQn7B)W$x zB)wIsaeF>?FH5CD>ZZC0YZ$GLKwx)f?3IDQ*j^6!gw$Fl>P=PHo%*)k#dJtORZNWL z;$z%_D&o^9kRAQY0!?wjQt1ss%As>LmR{O9gEwG!DSj2%Trtk> zI%22@*T>dqZ=rl2rN!B1c!8fF|}J$IR^^4(1zpH2)!3K}msjy$GdyEe;Hcqb)2 znSD`IZFW~eZ2ONc@pW!SfqjX-#bJ55C!Ol0`zE9!z?@*zxT(g z#jW;jzGm+HRsEvSs*9z=%BINs)#}kX#-qCemfjS%pSvp?exzqP^0KqJp9rlI zoi(oP{PM<2uiQU>HK^{srh8y~R$uVP$it??KySsI<419g6{rgeXG9@ReX5nuTk>gLJ+j~HZ%)5;mv4# z8aPJvupmZx@)Iw5a%38hL`2l>>U)Lb|3vlV?VCo~Ga!jWeSX0AI@v^Ysmk1^=*A7K zmk=B-_f?!JrGdtoHe=dSIijR^3ZlF)I!<^CHW4N+DD@F#i43`a4bl4QW`DKZ{;uz2 z=#LI<#A{`UUIL7K^^Hc~JTVJR)ayL*ME7{-3EupGZPCFiIp7^ck1bMjD1DoLcP(|# z#J8;(OQP-@N;YBH(`UP{TfH^e5fOR$?vuz2*TA->2|CZ~0je~S_|?@|urNA(?XhEj zwL5PGxE-QqjgU6z%L~R1K4!_h`cn2qip?`DNOrt|!Kl1~%jmH#ZuR3sxII~X;)8&A zp*|a6aSiluLAjMwtK!rv56b!F>;`zYP?dcDpOPW{0I6*Qrs~cej!QU;frfWZCmCdv z&$iWk5cvKYluQs~NBw-i3A>p}-?W6G?K+Dk(b_w*W}ze*%i*BhB1YCq;=0-h!?MZH zH&v2XtMi-^9%m9$+Jy1oo`Jn9*Y6|QtT=Aci2`zHuuC$%^FiFg2p*{jKBiy%0izh| zQbfv(f=#6bLZQPB7xNC}0G=8)Frn2!q&PTYoZyTol5fP9^dZ~1^CehYR42*Ut|Hj> z;-kcA$`7I5Q12Ymk5uslGTGZ)4mAS-G2Eb7KEeRrik~uBVh9>?F)wmMHOxmK0ldup zCdKZ@;)n2MKW{_*vKkH}Zx+>E{|oTgSdu<3A3_04uRVDF+?`AA8Cv%xCZPZ*x!PlL z9PD7>=5o_Jvl#wHok}WnKB|a<@wPyj!Wq8B;H^C*515Xy1-dYr7hBfUPyY);SaEhy z70v4b%y014vqqjwol|CP#nGeCWlSrF)Ke?swiVwBT-v0UZJbFYkM0-f&eY3NBBfv5 zaH*A0lVHBMaR?*G4%qiAv(4MPvywVo_x{Z`-ijm$z%#-epV<9GSle-g#yj+6YqbuK z8CH{kG@;eSQN$)EMoUc$Eni+*@9;7hB>5S@4s5G^K8IPoG;aVnd&au>7ilK6->{x? z<=#lng~sG&7%{4IbF9%3e!9O?UCy&Pous{{dk|B zqiiROgxfCC&kZe*cU6^@%QY%q>tjx@J7h`uW(O5FM@m6k>$5Yr+9yYj8#Ox*C~|bp^5BScbyKlaz)D3Mbnzx)_1% zCt8vMU7C-70%Em)eZIuf>ihVZ>ROv^q1vbcRrfq- z;m?=mZbf*e9F>q&BhL{h{FMPIISUJ)Tc7DKnID5T%fcj-Z>Dcsu@YfGS6?jjbBD(W z5PDknoPWIQi&@N}HiKib+h%*;n)rIFn|9TnC(tk{MQ5vRIQXv1`kRwx$024ygq&?l z@lta8(2?X4LBCmbXh!GUx0XhBbH8w&@EqZz8t^uZZ&U_F>=Wv*aD3ZMv9~-X37gnm{`s-RO^}VK!;brfZqS-ZK zz;}-zCP*(1Rg*TPfGtT`9Qpl?ILFx!?B~*B>k=Z)anPl3%G;wr7MJV|ab*1jUEh}U z9c|ZB)VZu=cHT|QzaGXdWEC}9;6hATa-m;4hJUPOg8Y7eOWXp-uIS@)Jsb(0!V~}Zv`xLaadLWm5AACB7l5VjWMsW=jO~;9649dLrytOj?t+Ht#0L>^ zngoSev@~2)|3-XFo{5d-ocQJcBWQG^qtTazk-e}u-TrJV>`oNvm(6Gx9TqLgwZlEejVtP5RBkA7&s|6AqOLhbfD5VWT5gQ`CH`On`G? z9%O_ib0faIQ34~PgL>ailrjoChdTqb=q~g+{ENj#=s}d?5qiPS`4QSiv3;4(u0?vF z^gad#`gVOVq(spxRg=i4wxiZ;%N{S|pP@e}b+&2IN5efWrHZcSja(jgE*?mx8jCY- z@Leux0M6_fylo!0Lquwn!MphU@T;RrW_+rfuOc4H)cLZr$j7LwN75j-lN?%POER7OpELm(V!sLl#95IC`kC*`*>MWhnn+%KXYDl^SY|Vep2vB84 z0Sr@xHhHRO*6@kw1-+0?*%!R0hj$y;1-ez)MVz{Dt0Dqhj?bcm@)gB8-ZY!ch08_By&FH|xvJUs?#>5^ z2(6SAP~dYuZF&Fi(fs$M+!^>^TE*3Jr%%xs&yyxY;ffVt_{1+~uH1)*N%AX3L(E)E z)yybemM0NetW~zmpqnCaEd1fdtXwR{;kyim+uUFlwmwnThCYmV0}-D}%8KJ4eHZx$GS;T#Y-?G^+kjC4|As-TjtM8uQe> zMRRsG61~=sL&QY29)Y0#|F3n?91umlMDW7UA5Bg(Mg|Avi0=55t(0}co9={M7QYek zKIAxb!>a0MYhCn91NB41X(ntSqctotPtZQ&h!Gq3nM!=8X0Y7_^aFodUPH?w<<0f@ z5zhia7|o!yq5-utR#Ik;kNEW76{!loJKT>jv;rxt-3zYfn_gk2nQ^TFhzkh&hd!+s z#a^AY{IJ@}eAhA8eHyY*H<2IhJBS}dI*W8a)Z;!sTi6j{MD_x%+DrtaPpzcyn4%=? zAqLCj6&eOEEHF1ZWwI6g$eF_YOoES(KJ0HK{E>d24*u>W7I$cZWv$pb7cMQ zDj}DrL2b!f&(h z*xhh{tXt3}8UvF@;H5oX?<0LPAKR#HFyM8y5&=q>@(qYnnZgL)=VLws_o#t2W5486 zG+3MQ)9&HlcTj{LOSsg0@VRb^AA6?+=Uh4pqYI|p-=5!pXNwr$^zcObLo|$ML1299 zejwPCdT*zZ`3LA7m)qRo5<1-9UuvqXd`+N{3$~Bg{E|I-KsGXx{;}tkikl44Jw{l= z_+{=@w{01M6$CK)_p4Zi3APvT>As=SKk7xkG`RhA{-$$9*1Y%h@lVzY*d`_8}W7;b} zk9i2&YeqdQ1+$`7?W4PYXvrq>zxUWa`)kG-|APhnB37f#@w61#UV21}4@%YXz+NVm zx< zs>TIDEoaxU>;1g_E%(R|J*_w#s^WA*05#&Gui`WMFJpQ@1MtTa`>Ouqvu1hnY|=O< zNhJWhpm$GSfJe?S3iYKgaFbdylhwE;;rWSuFF*Qa=f6gbS$TP8v7kQP$k%4B{pnbc zcddiruzNo2cmJD3s0|EBRnUD~7bopkNKziz{OItDfkH zKTac6ea4+G)&H~rzN0#;bS)`f%B1tP$dXfz4;OJZFGt|ujaIzQZ*I%9D_CC^#&k2 z*049q*Ci_NOQxjHPV{w#7SK&>Zp>~^jUm)fn`@7*JT{L0>?~f+IXQ_VA_{CFnFV>_ z&X~q2==(JNuFa)q61u{7;kxufCb`0jtF;?5lIKMR#zxaCQ8W@+(l_hP)3XPN-KzFU zfIm|)x7RQjj(#u=4{r|H=y>yu97x3uF0U~@MjR#&8&YEcPV$Y*@|NrfpnqrKH?{cd zXGH2b_IE=L-3s-&0)^~u9LdEus$%|SJv%N2r2;TGtm$h|&15$A`5=_f{Oc z7f89b@UwEB_H3Ow{{RfyJhDwJ=U%(^D)AB|c+(YdJve#F%TiKJYx`4`U!ZJfkF&50 zu?oTEgI~(;QzZV5zJMgH)J>y&;CaX~=-LfmvrI(u zRy+ts@fp3+^xpw}PiJ|KBT{>(S^GD}bL1(T_ynklq;u;$c`pU$Oz*h9_0Uk5qZg9+ zJ-fkS?l8E_h%x7#NzY{|eBT+PYVGL?JXIr@#nksvgEsiEqG@z`h}gByS6iQC1d6q} za)T=WrY9oah_E58qftFa*pHHt>#07;NHoHWjIL=Bdyi^>rJE$tn;vo#r0U)YDIDo0 zBUbO3NqX6VisWqzf@H=8-o<&EG&6zmDf^{2qk@V4Ue|p~@IhR(^+`y4KEWmU?f2M( zjB>qBOsI|2N6-s`73sqyf zuD5#F?E^46s6Am6n)=z$HOO7?d6OGamX@ip`W?p`-7VQh8eh3O&CmK3>TVZ?uWZfp zn!kfsWqVRt>0e22NLBQX2XA$ku3OMwol+5yRd6}5S6@6zjCJY}3X7n6Fr~KjvRYOg z8AA7aUy-dfi^WT~SzyFhvjDZZHk#FwKHg`F z+YLX=N>T~JohL||TIv+Zxq0S;upkh0ISfg*mEuXNVs+5XN4&O2$4dSBR@bkqtV5J# z)7r25wLRqYRR8Ybx5J$STT5tdURM&W&%e^r*aM_LMO!UF~nrniM)SVM({ z#XQ)ATpVf~%HJ$1r@so;2^VZldBu!BC>O@vhX2;HHFFkpGyhN#>4tN@CJIERdM)x~6dsB< ztJ3PV*Zg9 z@e-=Q@5`aT=Q*keoa0X*qY0CX*Yw=E_cKm^bF_xXW9=>@nHcIN8|-r8uVHeuA)|eF z^<7HZZKn4SVdxY}LoCS*yY1f-mt>A514Lv$rxLqdHBmq`F6`7?Malub;|Y4bs#~7^ zc}qB!+{2{oQQV$w5q-}@>az5%2+8WsRez1wGsP>!!-E1eG!?Btgj^ZWE}!0)U9>6Z zLqdH+6=Yu%7yO(O>$cq7PX>Ikrs<7k9yzZFNfQBJn#=Gl?m^|SW#p9hq#~Vlr?^Ks z40AFBG-UdweY%VBo*(Pxo!Q~B)W?xYi*ZQ5!rmb<5*-|&WHgc3d1s2>{foq~B6r}u zGz6V%hu#iRI%5E=cp1IE@zT}7mosuY811db?FGLJMO@ZD;|kCO3gCWJH=T9zzd@BGx|12Gb>NrBR&+u7_I{ON3#9jW>%kkc(Aq zguhw5(e#{$qDsotp-dU;!z#)w&;$7X16`;P255_5iRdk2bSJ2H`>N#cq#xl5ZB=a3(#)K>Ip!$!jkesq5<@=^- z4mES`Ap*Q@yM5hI7bAt%Z3REWQSe6BC;v~j5@-1eP(mGj*?Cg3DKaW_5vtp&i%urj zX3W=}ta!{O=mEl%j2CBEnfdM07OZ30pTrk31uG-%Ru=w0Q86Lch5SMlQlqD5Ut(+s zgNn|aXQ11-39s0XXz)icBdq((2RAUB7h%cDp3;S{Zfq`5p$k#a2?f7%6}c5sd~@gN z9Jklv)r*Ni5zMbV3npKkC*@CB-Z9-LH}es+Gr2;1<=(V(nfqd_Ttkgz+)4SG(mUT1 z+0{&lv+pk&s(1oL!Dv_zqC&3Rk%ik=Ux2Cm^L(e;p4-G5#FwHz)vb`1eW&kXlB<$$ z{G2&$Z8y}Ry3H?+u3tf%#Do^OP>*v}>RkUEMo6ZuNuL??8yinqyIYxF3v>`;sfo3i zSE;WnRGgfj{?3|DZ#`t@wORL4AT4m~<{cUwv88OdhPG*Kuk}C3lepplfH5k66l-qY zK83FrWt74HV34g=H&Sm-IxvcT3UqyceG3fQp2d=3ujwLzm=&gJk#~E+>t~%)TVNtO zUTbu*JjYFkGiSiW`D9C?=W&yWqfHvop)xkD4(Nq9!!NSr$45D#G93tV^*bu$g$mv? zovWfXj+Yg7QGLS;%A5E$L|u)eix<2b@_^us07DinIdm{uE7$#ZVKsj4j-2JwjuDX70p* z(-xp^YVz98{w9mZG-H^#!34xy5pUj>h8+YJZjaq&&BOKqF;tz?bxvX&Wlltlx^*6b{J`$LXa5XRlPF zVP;tS#4PhcSabFBEwQ72iy-o4A&m`aV|I$skP=P*Cd$GMtCnN0Tl39v@_kvqmZIfu z4V=H>S!+HUO7RQU?$6g`j80$hnIn!?Bo^^>iS;bF-3g9;_i?j)@PY?2;}M30*SLz? z0t!lG`y+Fb*!#Yr@VYv1;Zeb?XSgnZz9*Zh%!DTrVdUXkO;5pDoqG~9tD@?zy1uI^ zfPN&4r_O|j|1bOn?cJ0%{a@NH5~ZN#3DnZ7Ac@#wU=BZ$-QA1>PSBkX+A&`}-^ z`9T6nuH{794&a=nLeg4_7C!OsHhX(tmAbgIJNO4AN9Vqu=wrUusKUw@=Z^4x`CDev z0530XDs>I5!#8VR6Bb>IHAVL?#wO&ciNUg>x4hrxZoyC4oWP}DeLYHlMG9leI={Uf z`B5gV*?)*g=K9H9RK;sq|MdIrWo{)dYlSHFY&nO zl(8jz?tL%{Jp(fph4z>ByY8VqAT~_wZxId<&fpV}-p2ve@fzK0bfaWd^$DX}s_kN8UU(db%7U)_s(H*!IFf~69Sx-hIQ)ObH8ZD z7STsqEdk<{{RQ_CF4}`&V1i49LZHJ$JqVoOJ1nUik!{SR}l_ zhOj#zIqez!(0OHrDppDYpq@VSOtqX4e0@S>-`RE7xz|mP$3+K@U2?)ha4IVF-WE$>{+p3+$g;+No+E=)po29@$B=S0x-u{R zCsk0YPIkcwNY5bkWhw>)2hFca=bjn3JoY?MNNbbR87naZnB1j)S&^!)gk+}Ilbjxy zEWkM{FWWdU)4e>Fq8$=+(1fWeS7X1R-9^qQ#75wie9wXT_me^F+%b9S6nyqgcTBO| zfgGlLm2)t}`nj#CwV$~Qad^UymBx>w(?#_D9MS3h$C9aq3JFv}cDTFx!#{Bvoh`hk zTCSEMn4dY=4amW%bDD&Tm0JN@dn48uk$;r>d+j0-8c6s~Pb2PT2mUH^IjO;j+2t=} z)7FoAlzVPV5r;C{IzyjN(hxFwx1yj7(SNNf)Q>b`z`*Buk!V8Xsv()CNQxM8X|zVG zkS^J#y64_qEPG|=9)~vnCm8HE9YX?Bqu|O%-^-d)roPyLJ0a)7E?BPx4^CIi(oa=w zudcR&`B2gNIF7NI)k%QDpK!U}EGUN5xAve?vsHBcj+XbJE$k;IU{BzrCZE;P_5hRs z?@uGX*k0U}kcc5fGIa!s(M&nHC)zn!)U~5sFv~4kmG5rEXui8V7f+zq=5czD^q7xE9@!=dl<^Gn}l*tijPdFRoY~qOSF00qw#C1Dtz5gE57fO#&WA{1>@IOE^umU>iGmw@8>pIO6 zI{f=Ek(Ej0UaYkvNFLaznqApt`n3S9#|r2!gnQ1sbL#%3elMi1(q0vq(QtI$M$XU^ z3m$Gw_&B(AaT%HIxao)3G`FOYXLd`{pvZc6tz6l#t-wRP!_i>6mKzIe>etRQCYEKs zg9WthjgR&3*!BAK;w2Fyb-k;~cx1`{zeW4?`CllKOf~ziIP-pSXjV^}vW2)D{Z!|l zOUhg3O@0`5=}96O(kQ(CFcsF*i|NJj5mTwcY;kJ1P2~X|=XN>_?J8XkyAJm#{e2oL zZqq3Ab^`W446y2?&^|!mZeFvrRahTFnA_tw8c~NjsA_%hn=Z}*5!S7etH%k0qMOx7 z#k|85c9%G+yJJL2sn-UB`Q;GyRq&dvI}`|%>KZ&nO_v9@W!W1@O!BMQWe*$`OxoF8 zc*y)zO;S5 zj>Io-2x&2W2t7AguEeWLZ0UOR_h&h!It*$-Fp)Og-tNTRb4bILctWGp;lxDi>=Cv# z|Km@vkNsuCFo7dByq{$K93vND!QSekG7VzCp)pTj;`PM>a9*wCDL)`MYf`Z)|fX+SN zna-l-P5U6#5$LOR;Wa;qpnmq1b@Bb>`o1Wz3sp&Ca=O~(?b8~AA!FCxJZ+%x9z#z5 zPYeiKPLj<6zBe0w76IXW_m`ZvWE6NuF#OTR1UmMwP6X5Cgt=LZhOsB;E>@}s|6 zloNrrFd0=rs5v@)7QflQ>!ac}myqhb-=&q6N1d+cdnrpl=mD)sgs1}4`5*nh!^2D1 zIP}(77ak;hNJhs3*vb1zkyocXX>Ql0D}U#pn@c(|NsEIw|AKvP+-|rp`;I%`^v)o7 zy#G;HVCkRT7D9boze7MmEfu8ntA+==^K!%5U8@z~@mcCGP!*@>Y8*9jH=sRqT3&SK zyp6g_@0q*fnRWPSx~vHwjA#v$4Q`)b5eA9SDQ{kOh#Bd?Z2SG1&&?c$N^MGPG3v0u zOr!iDIFzi17R#&Ts@&&*g{Gqu~RY=94Nj3^jNk{UQ& zB&sh~Haq^mivRbwW&;ZRRewj($H1CxfvVp(t0rejDKSPf3~37S$LRVLfDFl8AwtXEh3tKP6rhsBclx zH~bTU(f2~pR!h{lnKOON^Iq@`+M}-t=YLeUT#-s$^;4v=ws~Q+uu8gTjD5^?gQxT} zRhq&!C?I(@$(^$RS}aS}?;}E7sJLX%)AM#8HhMxn`M=q3w<0Jz(ZaB8j|EQd-T|bd z>C7ol&Z&E_9}cRfeRpz?|Ml*;po=I{c2$j=^#jl$&UU^^4Q@l;U9IVz$zv4zo<7^? zsAZDvYOu17-GQP0-@j~s`}kDM5MeE31x-a;b_9y;ULj(DxZNK;io};jnkJjDC4)Ny zHSk$OciLLl6flLWe$d-$%R7kAsQ89T1gkF-$59&-X1)v|LVN%FOG}gNxU*vPD{3yo zl|epXa5BZ~Wz~rML>zc$}c9YvLrGqddE2?WSU;(v-uH5!Axs zAz?Njb$Cwp%ktq z(Y}J&pISJg1XuaM(Gs2oZ$9o;fT3scx#opk>+GN3pH)15s$Bgy_6^|Mt1){Xp;ir! zG24<2kBzH-I7%lN%lB0 zvR7s)TUL}kLbCp^PviT1pXc|#F4y7@!!mV16iDF&g^;YB)96^E-b4*DMVy(u`o#DkHv6=vuR4?63QyjaubK zL*hBFw_@xuTj;fV{XuQubvXPVp42PPE!2P*28+=oe6CBD7Zg@W$xQC;>_CnB*HJEf~ zJr7~ayG5GUZ_-^ml7-pe{CoBUax-kD&?rzY*C6EI1UI-s-h2SomSEN7j}vmi{agOg z`%2grfFV%_q|J7&pzkTH5-Y|RDhN~T=|MO+07aU988XN#SL*Rj!oas0#P*t@s&cSK zX#V&?+88E#60{}E=>%k%$L=|UXpATa%Qb6ww==iyZ2rid+InJN5e0H|Qfn&Y_BZ>; z(=ATIKC9x%D`Ry#`N-m^SVP8&OdEpQ1YMKr0qp~VS7epy$S}dGSPHpHuXK8WE6TN` zWHk9fj=*60N|R4s-sF)4!zMW{4jt3M9m&sjE1y3Mez@|YG_A&?{qYBZ%PW3q)^A=_ zxX*jclg7dW^T+QzpOQ^>8>G!$zWnY~(|)wmCNqUH#K?W!Zc0`7VM&vco5<3j)_sb4 zN>r8>~|`G0){`c;Cu<60(TPFvey1-XH>hLgs&$58A9)ME|V(NzuUH*rreoRMU7 zx1gUaMrIb|${mRMSovTWSYV*h+VY`lrPY!YByx5YU;@4Ve#vIgf*)hR765T#{y}5A zN0Z!6Xq*{HoU)X2kFbZ?rqw2%Bzns7fq>g;<$-BsNuXyl06F=9B1i~qVOy-DyVk`N zI&z%qB~<1?xZfS1R>TSiK+h(sGIxW9sR$UXMFO?xpczwCRxZqayS9GeH(sO5&9|eo zJ|Wn32bYv|d*bmG9qPlvjUcZ`G-DhX;?a17b$JWD@+Al$1E;`O!PRcMWGnUAmEHFZ z;3nXNRq%rqn@jI*N!>kZH=x@i_Ps-4u;lswoEiL2RaR8yWu}{rY~O@T!*tP#vgnhs zUbV9f?xrFqaH_k>SuW(NveHX_m(z`!2`L9TYp)w=j5U^Q70uFQ`b--B{6AmkA}S$B zA-mY+b}3->K=MGMHW*zcnd)+oqhb5J#0E&W6P~=L6YbLk2_}#A+C8mj^(B*uHUqmx z1VTJK^5&avktx9^lA$;Ub1W3u_fKGqbBula3(kl=aXLh!C+GjZJGNBwAtI@#%^R!V zh6P`BA8)fPt{>Dl!X2su?`vz&0oiq&0_5+-h%YN2PXP{~(lOR0k4`8`M({5@R`X0QTqy-@S0h5dl3gk>SZuwHV$D z`%o&FE{|3mcIA-UQB3tg!7_*-V{a(pQF|R0RxDCF zP-VO~A(CT0EJD?i!-it44TU1{M!zGcOpp7I+El1>996?cX$(D?R(BzHuk^GCG7dUqQ zg@*h_%WGuBWZVI5Rtmtr#MAPBA3vd#644xibx6Xl>L8v(D;nt^rbd;j$Wa-7ZiKp$ znx|Km=Ym#Ocs_MiiKNqn2I2x-XgAmgWa^iD5gw(JvT)HZmx60ge&S0qxVQ%-$??vR z)2~9wb@WG7Y9j_Ng1Q8(-Sk#ou4lA2fR%`ey_JdgcD|%M)>mcl#o8EbBnV1VI zQGe!lw#9=F1kx4&JLm<-Dqi={x2|44I%6v%&)xMp&h4&nk8y)2D4%b)V5=J8}pHk|3U z4vw05wKk>>!Rp77t_^$SeKhvm@VKwgIl0SZ>`RY87l8Gw_Z>E7``14bIf%wuwLTK8 zLF5nsnVs^Tg}&m}Kr$TR=~%;F?BpaAyQuBNY@P9wWDbJ6;DNm?A%o4~=!SC@`dgPj;Lg$d?q#TM1kRYh&RC-6wr zcygfszXbCl+HawPbEIkbuV>YJmW=LPZDr8jpnh7VQ%?O#wclatq7Sm-bquZ?A-@w~ zY?V!Ewt>khR0KRUxh#L|`B(rZIkWeass-nSYG0-$TEn)KR-?eU$4Kf(Oi z+Msxd0yjX-N$v3vW#pTh(8Y;&nO562t9{LVDSgrQP%fzb$ckxty2JLZ( zPc%JFjoo1~PW$&e66uZ>=woM#8g}>hm=kIf7Y6$Vby&OlZkpCT1S;GwR#sv4j*{NpXI|+-j^OzywmF#x~q%N!Ms3T}M z`q=`QuEGRw-X0b=LYCg%=vMVD5FpbYZ2T))xHCazCFu;pxMCQA0+O}cG2t*fn=*=7T>hXl8B;JI-d-Me#XWoz$! z)YGS!Z4}v^wE+j`rK4`@9dg>bc9yg9$nPi)c`WSo&{yA^+d65Q%%#h15?mc>EZ9;Tj!KFc+H(-yTJ4 z9=P=0ENNOW%l`Jy`3K4##X|5r7%p!eLB9ANHZV@+{(h}vOFvBel7+ho@e zgu%d=Com6G4&RF%__ksOf&ly>o%^=;*8?DSu{*%>h<-qnov4GG88@X91;LJt=M)Vc zsQ|2aMH;vvG!%ifr`G9+^|5et1sIIzf8!DW4)Gdi8SlBIN@&4sLBuE5HVcqM=#SG+ ze&&C`AgP!jM2WZXgl}fFo$oDukry@`+TJ8D=YDt%e<6PKg>KCOUxF0c$O%+CI>dG z1-S;QgvibQ&)XIN5#F4e#Z3JAz(@@0PFoWg_Zs5k5J?sQC8y&n)9P{jGzq>X#Ss$`%qf>=-*7&8rDi==48gBrQ21F2ED+kWPk@Rd; z8q^(S?XWHjhRLzc^flLpAbeK&cL+@>>f={((Z35DY2q~ zB6JRFIf4-YSs^xgm1j>6n$sCM$Q7|X2u(cgX}`_Qs_`I$AE_$7-nQ%;7xf2G|1Fzd zCK!Hxg`DIN-Myr(_3wlT<-Rgf?n^wookSzw4qTyl zw{CXV%kGPI&scj>|~qc;N6MGmhtJ)E@jbQMZNs-+7l%lvqzBZYQg7d z2{l~3B_pxp5YM-h*P6}INigX?SjIZg4Nxkxi*aBai3Jl15y)?V#!(k^dfr1eFrvZi z+@&KZXx_T7*!f=1!@Y#ECC}~GjT$J@bhbe*d&9WH(;CAIQTNc;l7@V1g`c>Nz+bn_ znbINYGb|ri4lUbMY2NaL4&t2a!r@=J1bLf8$?<;qy*JouXtH1Mpx7h7KwxfPqLuwX zM^wa{%E4%Ap}*Nvx>%uA^r4`cOSTZOk<Qt@2E*@H1ffY+K zjFN5+c=ro*?2#pC;2SLHf$RtETPEP4yfThVpSCDwws(dKuAkqpGIK18RQ=}GH@u4` zfb+#rZ%A1^0Y`?94ASV`?7T-^(8@rHzJ^ju>|WTDC?2Hq@fdZ^KBv;G&`maW#w+7E zxHDeUega8D#b|J6Ox#N3fjtV8NO`bl>`N)L$nTm9D@BA&KplV$F&EVEro~@{7uV$b zzU%6LQxuVeBYe97hE-6yOY2jphtD`Fyz>9`>R&_Z{gVOmyKux7_DY2V+3^`WEpGH_ zOBs)yGesExegZU0mMADT3qj}A7v#nN=Ib*_Ev3;_$rSYsX3N&NYoO#lZR{AthAjev z)`1i00XJQ0t`~xpm`fAa!`i#sP{rrc8M{@9t*{Gx8F(>%RIlKT%k1H`?e|ZsAV43U z`$5w1Am$_F7j?iTB&p1x1x^l=UrkSkw)_l+-!WTRHe5TQTb8YK$5NgX1$QvN->&q; zjD?Yw@0qv}R{_d{7~S>I)rkBy@pnI0XP+pv@UhvXa>ORg$J|;3LCx;7iF@O|MVdw@ zsGRW3pK!7Tj^F~Y++*%b9SSt9CO&BPms-uUXcLf63SOV2HcU*fx>kJonH5NO}v_6zsd)728iEjEl)dS6$$wm zkjFNhCKX0x1Odrqc!}XKzj56Mw&1)k}iW&^+0hhfgdzs+|mSywAbMLOmVUSh{b*oQQl==)y`VF z%}k&4IVwX60NL8PvgNj9KD)PDE)p9v`3f#)mG+^}Z^IM`l^Ne&sO6IZH9rMYWy!4o z37CPgTW~??kd_e2s2voGjSn*e((%O7Xp{FdveqPsFV~g4%$+lmqmD4pgX{rl+c(cY z-VrwV^QJYTQ6K|zP<}$RS>lZM%ZPkP>GX-|*Q_L;P;c;ey?06iz_}0Bicyn`(U2U2 z7QGcIcPh)7qc$MJPAkqrR?w{GxeVnpPX^7crSYedV|7(hPrL(|z%=CaoYobm)L%cXPT5&>%D5}VSpp&Ii;Y^}=38$7Bt46PgWV^!s= zoq$RVNWJ*yWC*trXMdn9BL25=z;tz{b!_6@k+06A-kL`&1wpT%jsIAN)za_FED<5N-s+nmGEJ z)=RWk`XFr)$4PcKrDQii21Faao1zN705>cbUx?lHOaTv@#Feh!Kx4|orp3W9hQ(}M|)vj$<;(By5*ZBHxR5HA4; zFARbzXGdkwSbM@~;|T+sNufvWG=Ea|9gM@^J8@h#(Qz#7^wFr}(vLm{|H&T_Xmy6fuJP&)M z1^UOpCD@d!O1o>|*mT#+u_v8i;hQl1W`}09<&s@Vo!&zX9jHb3x|hNepIa6-TDTnl zxt;Hf!I)P|yN(L;HKZHP-el!jb!&it33eLJRMrpn6k+rZvSY(5f%_O-Gcc6|{}&|8 zRlOsiGIN(puzZVO0y)AREKZgkMJ~TAdP&PG*mme{fu{}F_7y=YVVlM`ENkhW_?zg5 zFhF#5Uk~5x9^Q57nYT3rqR1dltG^WlOZ#Cwq9QF6^TH7r@#mL|*F*m0U}%O!spTp6A2mlALhivWs9aY@Qb| zZ^YKTz6+?cSp8H`pOj-K0$PDy%5{x3@SP)t%0QbGrDLZOU9Z?=e9XeSGOU|$INW?& zlx1`k#XEKP1SZY0Wc&PQ%u2Z;l@XO<1n4pk`u|N z6bbh+KOWwjm=9=|#@8Dx%V~hG-l3#NQeEO$C$>fZfUuEgP;txcuiHE!0|p9L)}DZj zS8AbhSBag%5-y1%(M@XM{#x|q!BOb(bA{R^g}~|j?&@P$9VmH!|J(X#Z}jG?m>)Fu zuphdDGwT3Tk${okiPo=^z|fi449V?nz;R$9a`~_%+RP%YD}CKdx4%h3x?J~5|$W62-X)J!>8{&AjDb^}&WcJ8x&1~KqvMiY&}>@R5h_Z?!;7>0(`L4LLJE9h+# zT>7pHwj050an$pf{YXnR(otV?!#CWR;e)JB>1lGNz}~s{>imVs#N^gtN6rxEGWNt; zThUJMCabzxz#;a3i({g3+<@BO5)!CEMYt_Iaa*9h*R5;%O91)w_c&4Y7S7Aiq!iLy z4*VNkTddvXjCLe8zPlMXTq7q+(rY2UyZiMeOJHN1P%ig2>!vaNDQBrmClftpy3T9u z3kf=Ul$f;ZPTS~B7Cu$elCf|J@7n3aT^>iJzxwizQH4T3)`?v|rbu8y+};cTsPH*e zRXDh@O8~{5$e*Csjh(V$Z3$dv|v(EO*S-hK_q& zdHD13V9E$2Dvc+Rtx40zf>VrGcYW-@6VEnlIW%6)6tcM({yVNXCKSv73Kd;m6$ynR zP`Hb%2s2Jq4+X=!H|dg|K7(pPx=Pi!zP(1>mxqWr`(3;Dg(7_w_s@MH9w&IE2wfej ztmHZ=#g1_&VBS8b#@Y;f9kG0~iRVk#Se|R*VlPARQGU-yT)p*|a4M+G37Tm99cCLk~#swZSKsKN7g&4Km-hExPXV zq5-^lr_3aP6QiqvrOi^eJ>fvzAbN zyq+FAqDR|o$`lueNo64Cl{vrV6=l8-6(q&J7>`Xb(Y*-mz`4774=4S}6R9HPpU%L# z9hM^NgWOcQ+F_q=u)QW)EwD$vK=@o{;UxfvOM{)DmU;kZ-WmPg1>Ws-?i{c`R4~QT zi{4@On905E5?%G0TesfgSslmv?q|DyN5$X&-5W|K9|;6N-!?##OlGnR8+|s}b$4u! zI(iV9oA0=8f}K`Bg6JVLz|4|v0xBNyJn^&x`EJB~UmoiQwH_J7o;Qg=Ta{K!GA?zo zod!~_qTz5B5pD(P#QEkGUs}z^P9w?MS;_>{&@c}1uf6$c{UO%Wr2e0K4%TDe#sr>q z*lZUa3#IqyoM4Y+L8rR}7%-c8L5rl!bPHOT6{>VU+BmT}SiIM+2b%oH?TJ%S5s zjWrPnBc$(StR{@u0M_QF_3s9Vun;JzP6MIk2z9=aTIru(Q*J#8uYY2W$_((w_c+h= zbf%w6ZM=a3D_KWxnjOW|N(PQv#bFk8{5gyBA7+q~AxM%R)sEpj)U5pq__I%iHu`J` zxcci$l|UY9Xi&OeIBs!1dgXR)Ze{?&fSijVvpM*b+Am!Cr&aN%S6HGIRGlm*cx{o+ z(;g*>c|N0hM1`TE><9jxdQM=wQkLhisuQ3$U!IH2a{L>e=0bxJ(p4l4dqpy#;)NU9vtb=$z;J}9=z`E-{OR%w- zR%@OWF_J}N1J9pj@1Q2r|E@aC52(zl-c#9OpC=yaqBA))nGPe>f~}F}F_6+53beTG zTU=WK>!-gZE|C5a7}LmgcxZP%o*Ii_(J#-E zndL&(6tjxte6f&umJQX3htlcdxjs#JhJ5H#H+rz|7rm%-n!g@`3Txutkt#-mipLb( zEa*SQ!Jo@OIE@0JqFidV$4t&1fjh*Vrw-7H2KAd&>m@Tr92RLtjP9WoZ4y*IoZkOe z3jn(@Ncj|Rik%|f!<_2mch**)85o~uknw%%v7yG3aDekj1W%wr?QGyB#}tHvvBx~- zw1b(IH|>7RY3IUiAbR>ZIPo{#JwjA{xaY`GLDu&CbGCIph>c|Y^qaM1;OZFm>w&Iq zf4`*X9soG@_D#UR%`MH5k*knqPk}(7m~#5W(}6sLhLQP@?n+tNrq6g8Nr&U$Na4Yy z6BrN~9FI;vDOX6jGc0t>;kEjJBH;k}c2?QAyugcQJedE0&o!?qCQ`LF}(w0JM?E6UOk9yk{=%smG}>jiA3hWeHWT zR#T(pbH_bf2+mRHHI7REcK1K%L8BeYD8}V$2b*e(QHt_DkGYb`tKJ-r9vY;*=3}5W z>P5^)oH$l@6VsVTxIuh5vnXc5eq0h7&V8=-zU`g$09;Zpl6ZDs`>e2EtafX_efsqU z@Yu3?5`4WB9u0rlf;Ut!1DaARx+bjfcpCh+0JFL2Gz}Lc(yEJf1}LuUpYJS(ZG42d za>aGfSzlwIFc&lakW6n5RX4r8Gr3in4)EWiD-$2Gj=prZsNefk)%~q!A$)sF`E6lg zZ(99D^<+|jFDu>*dgd>_Q+Hn6mUl7Uim_OF$9-wl6MW$m?yWkoa85~ZTUO{S-#A8BVe_^@nE2W8~$zwkTg956N7D{1de_)N4lB<;zPm zC;J~;Z~wVD*dVgGwt)up;kF<14O>)ef&=XcTL0dMta?@ZK7BfgF=Ou)_m(p$$1#96 z(4n1Icu|I$UZL-x(ezD~4eEmEYA(ih*5og6jYLL6G>iLJwkN7e zvnMV%N{sf{WR=vPUemx8=bJVUV87rI+5!k8&Td*uhY2kQprQ=j9ViRPGe&t*ik^d)s7HOK}D{ zLvAT|!BV{ldW+-=pl#{COBhw)3X5ShI?Jp^?=~P~S!d(JrRdy#R$UVrilTGeC|?`0 ziFM{0WwT2H`7i)(A|~g@+z{^gwzW?!1&e#6Mnbn$Z{Bk-0_V*xwRua;iEytqYI~oC ztkw7wLOSqIm<1fz76vdh>7&vT-J7ieQ7^h1UHs!lW!+;mi*bbb)DeXrhxvdX{XF=e4(i&MTL5W^Fg0!Y_z8RK zlg{g;4R%h;XUP1^Cp< zs37(Vv_p^dh%asE{JtI1Xz;O_1lOS;drRvRV;F7R1k8W!i=zuNjB<&Js-}c;IPMTXou-Z|VpKn17ai_m#*Q7K1<+@o= zaaXj9vGDYR$sU(=JpeIzV0Kh8>sWv+6HFP>XMC}TT$;Zu34nibx>X={+eKGLP;1Uc zJzHZ4>O-kL;{CP|8X9pe2jEq{I2o!m&h4CsbT3)RFsq4q?FrJNK#iFo17bgHmg{-@hFv0n@^RG{-`c`cgYL2-Y4s>MPg~i1|~~sT{122 z|4O3v#*xK61p~&7jQxkcyLG(z=`eV9IjltT5K-uGnHo)&e(Lr)tpal6D zY8`6~9m9@kR0990b|ry1=2vq6^_+k369)#IaT}|1gAzwI@x>~BympMa!*{1&7xw`l zbPXf8#SxpHux2Q%AlWGRlaWW{+CYu zMUC~!B?AQ|eI@(!81&dGvzx~qJ#MzefKaOs?(8?CSn$S)OgXREnwZnO6Ncb!Tn~+| zO2Hx{cd_$|KLAyBuBkE{bkYO)#~6YXJNo&Pn4d=LZ|zN61$Mtw8v6-E1|Ngz_*wE0 z!nIFoZD7oUpSf;U^arSWmhJY#)N}!8g&S%gZk$7JW40(W#EhVG6D)ihMyu`>V3cSe zrCr;$qY%`{5ftA-(>*(h!0ZS^qVMW3o za(sF8{c+y!|8wZQ>SR^o^^}=DxqMj=i5gi@oS*D_^SG?4c@o{8Ei$RIp>h$?#-WRS z7a+1K}kGjF@} zMrL;O{z;pYuf`QcRBaCkA;O3^)ADmZqQ=w(i)K&$?b z2om&7&J;xT(zI;$we&JbeJaJBtn=akWZ?5t4psu}k>zMN?dCe$)aW6iZ{sRx|5KcB zHDQtZ_Z$Y!@3vY^)QT(l&%acAW*B~)9H0e+txhuyra0O^AW2;q?X;Bvfnh0NhGE@S zO0%5r*qcXt4yL9LJ{dtolmLLvy&aOG+Nm#L-m~V0bbVK#z4+eBxEq;g$PR%`6^AuH zl6uF++j)Ob1)Sm%uw#nivT#CI0CTR%?+1C*!LAONR_em6cX{4Yko=P}P$o=@!!MrL<-sJC;#uwsjvL_kMeXXww2l!gQVA3Pa=JD* z!A5n5AeaYn&9&sIpF1;V2r~;T>40;gQFKKK8y2xHgp7HdO7j-14t|FmSk$B^d zGQGz!Fxq$E`-((b3CPLg;g?zw_pkJB=8p64B1V1zXgQb13uJkp`Sx;iw9rh>OZ05Z^X8|@n(zsI%7#)|)gY`=T zxA)FBJ`)c5^7Nj=RZp;ws@Xf_U|n@kP=N2vS9X07f|0}AQVG^Zo0mLy??)yB$;pp9 z4LkFkpNb00F||*~f-WI>2>Jvz0MB<=G9N63Io!!PRs_KN{dJqei-?_W zCx*8caCc9X34SzYkF-Mz%q7cTGu0Les=fWc&%{f;15lltp+S3kqMGBry`EDq;4XbRff)u~t6hpWxe_n;14DCwS<=rV@x z0cgsY%bx< zi5qk7B@#W%NIS{>M?84vlk&~y+kl_j0=Ff1cDc93+b!8@a6@KZX?Zx1oC<|!J?;mjEd;xwgq|WBwriZb>Qv9{ zcvkhdRHYY z#VIvG%*i5rH@0u|5%bq2Z|y<|75=KL02{o!ltz)$jc7s8n;>icnbE2G=f$?Mmv-7b_B@)*c_z2v&6L8g8U{p8 zx+znD7;0CaaGHYZ0o3;532AA$e>7#X&DaI%qlOPHn6u$kyqKc-I3VXCJ$pi}2$b1yC?{RRFBDIGcoKobmdCw%y5_(M>r%+28(? z|78y&rB#uSuh5CBAH`s3pa=KRC2I>;3?{`NR7D8}-^C{$na#jYcG~F1hZB$9QSp}z zPt+TQi;iMWQ=s3(N^9v7o=pz%o)*MswF+6ZIII~yyzKJ0T}N7HOsAAWg-mXA-|2zK z9P$CTu`rhrKRSQg9cWcW;_>Cf^JGNvxB8q(mGFuVOlGbzyvrpJWpy0T*dh)G8fsqy z<8!)IVVY8DCy8+BOW)6L%T;&6($5qY7fwgS#y=rva05PD%DUis!N}W^DVMS5SE=km zjAG88cnMQ~*M({J=^^iyJgsRt5xoIwq&Mwi{3L!>uzi^ea31}04zlqW2UeomH7E-c z$bX?g9+=~o-*j0954Zlzso9?othfaYx>Yy}>A#L?if}`BfI(qS!1sw}b4zYec!Ge# zC801K#II5ucp6*zKX8O0@)tGY_A~(iQv^<7^g9#oLsXtRrE3!L9K2@Dg?C{RZ5G~? z@By{G_Tc;}TAZ$x^Jud5EqEKXiHJoJlUZCX;!iuyt+GtagWiDWPQ&v#xT2cl0$ncg z7=l3U-2~Qf9y@5AJnVZu;Tnt`>kc{|mU9pSnPNWD(%#sR+4>&iWLx!`66Xxg8TeBy zB20<0>G;l>D)%!WYa6umV_!#aueW<%1OnMdy#6jDo!zgZvqh-A0H%Am8~SzMRGr}O z!|;IXf(2N;R7^d_7pbU=lozK|2dtGR3<-69{iUtsAy4GJ>4}(ok*t-$-O}|Ucjq(- znO;G3XL*#cim4wK%w{^LnEU8^vPUYT1q$|NHX4DZt#~36ODsd)O8%|_Adh9=W87$F zcS+Qq*xmgII-1fto}D9xd8tm$2xIV{FWEc}>`Nvnj3e&ca)+pZe2|I5Jvq)0D&glm|Fdae-CT^fCY{3njCgW2`$1VaHzXYJS#+-7{LmGKGwo zf^?|Z@42A!lqC@m9RLt}08Hal&}u3CQJ{P} zOqDqRU+lD1zxEEY{=gi(u+JWWHZ!x?nM<=#m+Yyv*TdS!35vot|0)8Y4P`>rW z^TjC&8#<$nUl+PEiR`19n(xSR^^VZ4Ef#TUxE_AU5kGx#7dhfH!+=4p-Y;JfSEiO% z{tA-{-u2#?7cg6@#+)MlU*aA+;7leZw*%8Yd(2DmBoBbmzthd{C~|5UjAgmf0!(*{ zcTa*O@8q+MTjELAN!{6(OFx|@*SU@Go^N4UmS)Wr5yM3gSN1}+KJ!LlbE4$Uxo~E= zX!dzD)@7Zl+p%nAM`nKVkR*NeQ!%4WsK(itS8;Wx!EFPx$jGOgqVQ|A8Ej zooIoPb%?C8?c|Dm(a4csBD3U$k z?f0oKg6bkY`xUBgR=4B!Xb{hUbG++d^;)3*A{UpOl{SUEDM%Tz&Un!UFx?Ei^rYKo z8YRXw^=r@$PVDy=$QV~VK8cikn*6+76?YYQ$~*qNj^DJy;C7ock!xJQmMq81DT^_< zy2YGg3+j*YzsQUTOzu~L#jP!f#w((Gk-P3qg`RuLG6$;JD&Wz-mbs*D{qt`izaUt^ zq3`VJg|=`O_HaAc@fkZv&7bhz;P>U2sm~qB%x}xv&n#~4*H2Y_Rm-SFflNzxsKm)q zq3ltn0eBXM0s7_KKwsup2XTPJxl73n6-bh-63;4<{JLoD*wkthd))9nQqj7&{sfOd zkB(EK62J#b&r}S^aNPP{JKdy_-gu05_MrialSKyy=I7^*?t5a;rBf_zT1ke8@SJY6 z|D>a&L=cq9O5(2BM2|U2cMsqME&%hCUb!C956%4zn5ufJ<6JL8y707*dNNfWO{ny- z&N{ZMj;~A~La6KO`OEXckNy=Lk*MpAt&I0sVfUQ;QWI3(d8<0%Ier&>>)Qk+6PJ3%6lJ&(h-qC;LfH80rA z@M~zv)t=M`Ff^95g zcNG^m=Yo%AsrHb%947F?PJJ848wU(uw72||$aZhSm`@)iPkf{_ZKrC?8L#nbFpt{3 z(zG%SRWs8^gU!0xZHahje@+1uu`GS8O>B~>^yk#86zlVh*QAN?o%tOsb0`l9@c+CUX}#ijgSLIW3NzFoM+sB6P|>(kn`L5xW<}}+D!Q)$9&fH+-I}_N4(_S~}x9n=7wKxg(76lN9hHQ!H1GIvm2D?tW3A%;Ir$-@LWG-))eiwz%+j3DdQ)-71fT6a=VU^fN=>C0%A zlL}namuS+Y#9}RNOkdjHut~hd<(13%(ctA09cb6S^d;Kd`R4_WLtbF+%vE@S@ycFQ zHqD8mER3BTFp|*m3ghm2V$-Qd6vpg8BhTQr-XrA#|_0k%!0V zS5WNjiL?b59<$=l_ex={$C0tNhX&lfrBg6bILIgZq6R^Ngli|7LIGj;fj>>Z=c)(( zbRvLv=KE7Be~vP(Y8hQ2a55;y$x!lR$i^5{n4M!^N!QcNO>deY$TA>js!Rry&p|M$ zyaWZOJnqL#e*26!6(7dk21Lj%kib+ZT1^Jp`levoC$`3R1JLkOS+0~>myrQ71e4FO zwTfHK+Gj|g(n!}?{rM}nS%xGdqjk^*PCq3ePB6?T7&&|!F`RrS2L&1{|UEy z<75leUKzb}I@@0O&$W)01K7e``vNPxhm>qy(<4xmd-r95GtYfkp2c=IL+4-VkvK!} zdglhvj}Ny;GjCcCRGp09H*R2y&x?I~aLFz=Li%ST>Cl>Y-3_MHt%SbvwI5qh^V>3u z-)an}jXz=1Hs9Cl1;a5SC~r!pU;m@c))ATH zx3h<37KN}6vf&DYyLu;_Fm8llSgs+1Znb%Y>5|PgRXXJ;iQ4X3G;qU<)q6^l5eC z2SX|zKc0WGUub0eH?Z|hT}T%x@aB{qt%2J4u&^(}Air^)XZhH{9@KvwJyHV^eeTtr z>NQriq$Z8F5bKkD>6MsB>US%Q*(2UI9OxGS5+BdW%`gKHu7yhgT-B3pcrD&Z@dudz z7}Yk=WMlCs-eS3kR)c-O0NcTwMfXpOSfj$ZO3t7VEz1i?6Yvg2sMy$@$kD~W7d)y@hl*2Su@+^)TALTg0( z89F^)lNGL`n7$)?Xj1r?G>T_Uwfh!{G)DGK4;%cBtSb--kqfj0h7#y&=bVlRs8-Aa zLv~@ga~$a#kxOu~*ri2A-~f2F$0z@p+m$84OlEmy$1CJT~ZM&OnkW^*KzphNwtACk=4ttgV#XwSAw+a4YzhF z%?>>gB@wtQmYR>{Z)OJB{nV0PPeqcXZRiokC}c?>;^`2WMHIc^w@bk86?)5K&e<}- z`2naycuk}nh8*73N4O?UY(3GBj)v8y)5)npR^lskYJzsCE6keTjN^g+RA%_;AP9q2 zjIf2c-#0*brk!Rohsi2M4By9npAvoH&6vHPBK5rkFSW?J&G2}X87N(Fw65noT@GJi z{{=;WXqB<+I}k{(fsxd4W_V3Xs25dP-@lS|4Ox4QXV-hld9=$gAJ^@{d4Bhh78)hn zgJ6;+B+J&vPlJL1D?%*$f6Ys28oV31*sMOKIdi1z&7Y8z%8guum+$>9mFj;J60uCt zfwND=lP4ZqdR*ni-Qsm?FyV{}Pk95oqlY`IOqek`FRl{E7o(t`0BMM)$+VwcdSn(Z z7{B2V{y%;BJ?xy?m=vNi#O=NeH_* z3gJH2PNGBZ! zVyX{-WKK%Fh|L4qw|o3|Za=tm(yy2%d|45oj`-;`x&c~g5cOTzXpp)G@e2obd%hQ2 z5pZE)tpo%;8{KcW4|ef*KEz-SzSQ!X*KcR&XPkwy)1E^)RCTM$##fCe@{)Wl%wWvm zMN)!5`d84fCi+pcYJg_1k30)*M~^(!SFCU&NVJ6fu488NI~|7vccY@9K=^XxEbAJ1 z`u|Y_+&Wa;o*>apndFeCeBc`^45H#_i*NM4$M&h!9@t2#vP`;bfhbw~aSzWk9SZ_= z)*Fhq=5;VMe3#vWY247E)^L~L0N6bz)F>ZWb5Ms3MfF_rPSqj_9&e}cQ(HyC7$!$k{^|wOg|%nS(ci@e zK$Da)?@`UTf>@G(seopZnpLVAN97vtm(g85sbbk@)KjZ!kJ_b`BgF+oS}BtcFpcvR zVW!UMyUS2fM(V1b{H;bh~NQ%#Kw-0dSoM{w9QUCHzwp5CpuwTpLvw_ger4 zHatc?{1*$3jC#R%uBv4qp?Ebgy?_W2ii|vwb_+(g<&1u41etqtK4QlrNJYHAK+} zN=uu3Nqz7k8bzffT~wyo;Ad^!gi9 zORV|Ud2&EA9jR#$A+t?d0q={9{Xl1?UGeqRbzJmzLa?*23@zK(yJ&$|BObvvH4aFr zb6=pn;)8tj}u=u0kn?xH%VR46H*)b=jzfih4Ff`OWu(Q%~LKW|)1%v2WulhmFk|6GUhO<8NI-~vDLmG`=IRK(~m4oGF_XU{Q7(~m)ob*HT^v0oCk2Dj|g z=YcMWuR`Q3=iEKd6PF1%Ute0KpIA4L^3GVdqB-u|(@KwG-Sm|5A4g5_L6hQ&lJo@M z&P&?6bf3mD*bbFgx9%bNcbvnLv>(wQtkAx6Km^wX+3lVw&OU4XfklIN!XHSvevIJ$rc9k@s zq^n!OMQ0xJ&Bk|^oE|$UC%NV*DLcY*5%&R#;yZSWn9=e8{&vabP$SuAQXPGKV-Wr| zgT85J4Q(bc!L$oskYbcH8tncK=egG->H(ND{qqEV4AFe?Rr0O{6*ul9{SrhX$E;o0 zgYMG>oU@&$KhOUXz1Xa0&Y!1jq-tZvbFM60nhb-ZI*vYc+yI+*jxuN*W>s+!2x#kvcTYOOhu5d7}Kpwq>5c`|>E<~G6 zp-k4fn?}nm@LfC1;?7hYFTt+SunaFfZvtcLza7ReWSrAm_Gm~yPUbB*HTjcZLd&xl z#6ced2&Z)rhYed83@C!KlLz&%PdFcHw{EcsY~Wid9F1K$nq4pc6BtB)QJe|vHsn+k zEpnc|pnv9&UWlZrb%t2jL3uShxS7*=1 zqrt-Wme~?rF|5a{6tzFd9vOxPmHR^@W(U1(5vlgTfp`*(^0_k#UR8A0Jd>hHPoA|$ z{b`( z&&PIz{w@MenAZfAt1YEXfYPL@}#l ztK>No&y|IB{3zzk=2pl(Ag~(loxCL4XK4&`BO3}de&LR zr*^e{2_8(f>*_$w4VF&i?rI!K8=>Yx>TS~_W{UxumR3w0|I zZ5w^=AX*dNJ;~58nYEzr-F0@5I=9CtxDY?%*Tic~nLi}a%LrhcElx)G^E{v!*pqMw zg`kFY{3lI7Jkq=%TsDv4N|A>Qdl|H2+j|L<<@Po9Io;8AvY8ks$6dpPYfFP>-YW0g6l1|a4_cTB|rqW&kZm0Y<*_8Jx1c5}x4f$YP?zvR|V>N}7aVCRb$d){9KVW{! zl<+x0Bsp}R<9DeMG(Vu0IA;0$!I!}LcU>Zh2FHlD2op)~u>LX+B3SSKLrzfcV zFBR<4$KRxTCg05jU#K4;H+a$s{{*!K*hy_d=U)gM4d6Jy0?MGTkkOIu=0y`thQExk zjFoJ0teD1^-s;yQqIJHq9an*W?JJ~`GZ~4b=`I34py41v<(@G>M8!|9OA&KMV3d@e zj{YN|l2pYjvhXgph!4)Uwzr8165O3bFJzlO)ub^bBO{f*?#}4PY;%#ouo|RK07xu5 z|1|Q`$LTPpl|ujoeNSWf426mFAdHU-aX8(+;k`PP_l5Ae z!VL;sIrH6pLW+{R{&Y}Ch}->{pd&BrBbstc zpeg?CQbM)?y0$$lKnch`L;y73VeCm@j= zZFOQCfl}uQX|~3yqUsC$p$6SeNYIjWS2?NfMh_#GdK`sBR4UZyY(+9gNbOuQJh6d8 znezFw$zgn^Ri!QygjDQTne!GZ?kvf!ODR4=hGd}cL6ShTvM*8m%)9=3AOWM(j(6wq z?D>H}0J5pb%HGG?_2*A(Y$6O5M2%H)o2vj%+>?w7gC?t}0e&zgCPZUthlfA!y~Npj zHRQVxZ9!OMqd*+8SM$MJU_?X@<3zmpD4@Lt&@z^YVANAhoeeB5(bo8dTuWegnUXz2 z*cRTHwanIZm3*b!pB=Sf?3{wm7hKv^i@w=vbj=k*6QhQ zT$Jp-Q%x%_&AOEKV)!7`ZW)rT_w z175-ys1>6PKTyUxA!H9xZ^?{Y7!Mvj*L#h535eNDDT8chp-*0lqzJbdwfDog*P!g@ zG0Jk!9K_HCelm~Lm1ZJXs)cu{uB1a^5qv(J+l49JFFOr$MS^H= zf6NXfrk4;D$}BYaTjo{8MZFNP+^m4FncZ8Q(nFuWRjDM_pSiz{MqM$E?)268`X zOLu{UL4sRgU!IhZ;f=uhTri7<$FY6 zPKCypjO(usqx;FFisf0H)ygU^yBA+Su0Z(aJHvT#%nZiNe}`d&{f!s)J0umD_s`={ z^QbCXTos6zL*TS7-I842{7Q3>HGV`X({v)a6I8aZ85RWgP$=7AnG0+nNs{DrX`#6> z1l7Du8uET#Xp`9!+~3?kHaG$VA2~uvHHr4o}T}>@Nq4f1mJD zbD-6``YGC7Ah|m2^!x)`ZUauSWr^4vlf>H%hBU%tX_22pHy!^h;A^OO$%>hcT!Bl{ zh2b@?8#A<#b6S*PR-(^E?!dpVKwFFtP-M5Ee}I20(l+D!2c@Xd)@T|_2)s5U?vmQ* zMLv|DTO?#~zTG=ifbhu*%DL^gKSAK8 z8w5R4f{cV1kE6!y-R{OG#%iXgox?>jq^h*PrE8$J7`#_K6-2ZIzh8SqqW_OZ3MiJc z}Ti~7xo_u$(e7n0>lS4yq z-svXuf2TaY4~@O=1`N|SzH%tAx18@+iWqe+ID~#uP{vhK$(fHdixaVJkD=uNT8S6A zmb7=WSwF$lvW#6HfZ1qwu1LOOQ@RFvmxT<@G=nyjpseO-0;&sdER$2V( z_ItBoVaF@{W-~sV$G=#=QWo)i3;{Fv*II^d*n!Tt`NUoO{?Q9(F}K)JUd-~zSh*d=W&}F?IzrP+K3S+*W`C_w z%%VOZ`)Bdz=JXUrvn|_xIcPMCMQb!Mlm!z6xTV*FpfR zS#cmVGy(BVoVZRI!gd!$VGNxd)=5IX0binfU0U5;!1xWj>fC#kERozgt3>yqe|HgF zYu?$w>XoW9`Ey*TuSKTS2*2Vc+}9F-wYFNvA|hH4K%Z_4C0`d)%h=zQj`h}FMlez% z>`tt_lTfMCP<>J=p-9>E9a9JRSd!T*Szct}&1{lnvvbs*aRJ`M+Fz%G!tgQkYps|U3N-7|vtlkqcr)6MIYVG6npC7@>w=o)}WaUxazfQp#AAwfgW_1=# z54Rq*9r+{%Clv2|fcF86<6X#~nu^H-Hx9M_>L8l5yZ_{#5?G6_Bj|Cue2;}{wzHzn z@ANTGI1o{`2z4-8D&U6Jrne$;ZxPP0=(HyMjbW;xkH~nxFx7@7Gy!r z$C4(TxK8nZ^G_vKL6}fRC++^?b_w*EhT&N<^A7+D<@V~4&kwaM<$E$OYJp3%1gWV9 zt6j*jS#f;~W_0oay|cthC=|)cpmM;KyDQzdKXV{A`$UPS{b`mbLm=mjTgK2q^Y?_k zmSmwM@>(v3dwB0DW7RB_u4r1CD{X<>&8h>{#o4Cs5(R7~3k2)7rL5_y8`B3K6JD)` z+L^P z)g2Jwya4gRx?8&s<2WK%`aC!5FiMbrapW4vJx2xiDAU&%+?670-t_T@p50|27-To- zWm@m9O@Ea<9V5kprWLit&h?q)DB`73kiYzHu899sML9cw(6jv-=E3LKf3N_EwD{nU z!kH`e1WMyk@^Zjy-G}z+FodWnkAKjj(sdrIC?_vw#I2M){~KMhN8{Lkq0U}Hn)?lB z&k%NA`L0HN2Qp{Y_=_l+j*N5uewWTrYaz$=(Mx*|(p`VBa^D@mjetgaPSdgk_l!CP zk0*25Lps=7jNw1kp+7+s@I6sEkoibbX@>M;PM*hO-2vR|D8wFQ$==i`H>G9hMCRD1 z)@Oz)Y4$uBH}CKM75)MVOTGhIGmzi4WU+fj+5xZv*V$9<&bWolXKmc|>*4iOBI9o) zop!cxl99m`U0(A?n~xn^3#JoS^g%Brm`rR)lN=qWg&?C-#$P#2?6j!nqISe0KmL~U zHXI08gR%mxC^wHILKNzHAkw;g1VoErh~XGdZGq{32_&?-TdEl;8gIM1tpFV24o&2u zD`Ea?4|Jeul%(OH&iPPtHEQ+J{g*ZN$8OglQn|jMZTCRVw@ctS%H-US%nGP(#9vK} zZuUS#tl9h~m3uSANCQh@-?_E#OdMclm{*Renr&TV)qbvavluQ2e~vG3VYU(MxIy%ypyVk7b>FMJ@#+2mW#;FYwG-I$&+FxfvN~@#7~{!maGi1X zPGR)ax{4MKl(&c=pQq>!We~z@-w4!><+Wl9Z>{~elKRIHO=FNo`ZkD=E;wDh@$0<$ zWuX$q?N`eU13}>2?O>oh;V^G|DuQ-)@osIG5yYCK@ds-lz%GaEi2aKN3;qL8YocT7 z4wJ~(fL!eILdyKR-R{+6%Dd~d>?=(Yg<(XD7^m8vGFc*9%n-B_5#?+5BOCwwDBb3* zd7v+dhQJuT^{lpe(ECoRR!%#nm5eT=!?NRfjxqXf>TnrFQY39}DFuKRdJbNNXNf;! z5KQKi+jJ{u4w_dI_CEb$#gd>T4DK6EKPtUQDOE>K@jz<|(Jdl-vyn-iwiG{1AzCeu zs<0e)Y9t2T!cF?yEH(>aVbOtv_YkO14B!Wn!+|C#hMn?GY#Oc4PRB*<*cQ>11SZaN zqrR#KltmzFgP;wcSfux{;!myUO%e|089Ffsr@_LU!p*?YEo~mx0y4vtEcW!bm^=yG z6R-T>L}csey0Plx%~L#zy_fnP>C;aKKhAk_3itRqD)pBv)(5tp;lXEu{X@vhOU4l; zE~ps%AavZ-eF^$(Cf#oi9msJ0i`v39>&;EJ%ddZVsd~_{ylQPfJlWCzRxymqg?Rs0 zy_s}{Tjj5xEcY6*d=cMfB$6_ruPm&syI5*zPTXDM&zxy_I zMt|`?T=36u$~4@4PcSWY?(0kw4A#>0IEg)+*+vjOPm92mqb|E3u%!uX9W^_o*nq^f?8fXi46W(v=()8lOSLF5wK z8i1Rt=2Qi=C8p7al_5=XJpG;xZZv}~CX+gDZBYlWQLj&oWYKJ)m0Hg7U|lktQ-9om>$QKi3(}JRS5F zb%vu^%649pjOQR3rnD^7#hw=my6wlLX2oRx2(L^wq8!rbtnXQpUfMD+Z|5xp@~8TX zb?eNVz9i*vsUBZLIy95xv&xbCk)sGPimy*4=*14XdO(kx99LOZ!llmBpLU_JZmYkE ziT;bI$P%9Im%o1=VXJPp&>dC2wIWXXCfbW}sXRINtD{;QMB)$3r6Cqg6tUf6Md8T@ z6zT!LDw=0KWdRMP)%&>Gxb$3Zzxiu_Owq7n!1qre7o=3?-Yv`6!^Zlu`38}67hsQ= zw=gg{nkzq2zXld6r*eTuAg219w&WE-J5+yT2rwwdZ@S~cyul^5i^LQ4{pbuvF z+}ukc3^659`-fAt~BoOCwL)m0JJvgT0o&V#p$*Z^E z!6E)7zg!=#w+9)S1Ek;D^?^jv;DWwm_6p4A%Hpudn3!v=arP%TbdDX<@c}+dv1D4zA+8%kp`DfjA1c@rx0ks6|z#xDYn7aTYnj8|@uMs#Nt_n43QLFM2= znWy@D4C^^mukGqYZDUpm^ryR7(r=ja^|kB^w40Rzi@Q_R2uA5GP3k?elR^bt-D&QoO7*2;B9k;Ywei^T`n`-+yUddcK3{ z;WM3svfE*|yk3@#QaMX2&O<>QupoIZb{Cw!SN=el))CGyacG5pj`Y=RQ7m@^-klJ- zUi@6*vEF0BlU}TzO3Z?tg=W76j*=Ai~;s=wY735cRsl(j2HBC}jg>*n8jG@wVf zmM;zBb12JBR}FG&FJqFi@gkq0fGDvp#g7RLdb@ujPxFEBJzF-D;zhkHh2KY)3F-zuZ}FwnTXPr?gpZI8AzU(vn}l10mNewG00qvL3@Z8UGZ*q?_tQ8YQq8Tj>KI- zrii2os=y}FOL+55uMIl>obm{^DFYJL9EtR^2N35~f7ib4E8@(i_xo?LOep>M79SSD zSYXeG_b|?ipvvxRAqDiOk6%{)<)Hk#%eQv(f3$NV?^d3NqdRP`EStD{Ayr z^@>zuyM*rM^5|fe|Djj;uz{he_3hfN%R{CUfUo!tQ|(6a%S}!pEi??uOqcvoB^fVQ zkkj7V;l~$9CKs}fcvbszM#5N22rpHJeHWYoFlo5P7M83T83QB@vLQYLn!*orZMaZJ z7Xy?gpm0v-n4XXe(wLW@s8bqbMWWSLqvSIPEiQko_4bgSjTTvgOw%A&E#qgQ2!6;laO-_Ir*b0x5{T?vJ{dEf~E2pu`Y(bX#29*&ERE zW9NO8ZBgO-D$&%_6YPY+XwqCH2Znq*eCQqtlVe2q*tMF zWZE}vooafDibul1cddb7Wn&(I6HaQW&>H4Mjk&PM%+#$P4M~#-o+;codbjyDDf9_% z?GDdz+7q@8+}tX?%=tP>qGUoA3Yrv_6iM8+C^7v@*w+Ww&*$FD=H@x|K{vIkgTFS_ zRO*+1UF(s<%ESZj8!KbTKYS(^Dtq3qbV{!N>>PWbSGVB1zH(M1I#bYbrg}J<;z%3S zjrD}~9x{QlP|!-ZKI5ct>YDW83G)<16pUF@;0Q1?KTSm&=fLLW<&`3go;JN_A>0yRF4FlPG?& zuO_?`3-j|;LBvr%04#U8|IKS}N2vBxS;nLAqxO4|87M`{pQFM|0gR=^rp`QGn~b4! z=Z~gzSNY0QED_^M*?Zz1;O+{$)W0NyIIp&uN#X1YobF%pYY8Ax-O0t zFF%xaoQ!$`jJl|ARCP?dSryhcH{*-rLl=}P06p3x%0tV^yEf+3ICE{V(BRCcwkl61 zBehnCXSY24as{wmtgjJ$%l-`*mvY+J*w}sSjccr_J2o1;kdz$*mb8Lqozi#0Hb{T- z*T*9wam}aJHa03-vRquxb`NX`txga$Hx@y0^l2~O$DVRBJ~sT+D3Y@GCucL9Uf+QS zOwJchhtN_JkfYYEd>RWw)?savP`(VmLZF1gu2fySJj7y$)ABSOcq}R(QxC>h{kWh? z9R2N7NC}Y2iT4{ln>w%XDYf4qusRgEjCqrpD2b@jUClvar*%~K1S?kVc&>WhcH>Dm_5z!2< zJlic_JEUa6Ir9E23Dw)|THEsBo&J?-iiMjS%p+Thrk;%F<%1_5Y+YS95x*X$MQ$@l zL?qz(tm+!|qX%6~IR`3BP6GEPA5Y8K-4t*(JsWr|WWmN4lN7u&3`Jmr1c@U^LV2Ah z*`%a*?Lln(+)pUG4frDxm|g&z>EB?_kXE7s2zq!Vc_*pY1Ye189b)y}1_lfCE2eiF7vB4)hTWd$<*Y>#|DkWL*7D_Sltnb^XMt zURv`}U}8<5eh|4+aMi}cA$sA=o@4Kc1FB8SF+up-8imX0PUqi7LQRM2i1t8blWDxz zv!%tRXI^#Vhj!U9OVMcY+y|u6n@oaY(Kc!4n!KC&j#a-q+I-+(51|h z23M?WUHfaLI#xiwrSas(1)Bqb&ED~Ejq>%;zhu*CVq$uq)t8)3uavDT={R|yRe~ds zw)37omhKdZbmzq|M?0|}J+@|M(kFYEWHw$#E3b98Na5~9TrnT`FeE`HtyCuR{gq`F z)kdvj8m0TlkVL89=0@*Aw9TSN&e4~YoSv9NOHq;QH>}MVztb2EB1fDcCwy3nvW15F zcEz=dRUz$2n}nfeDS@~fT@c>78cZ99Rx*^VYVAh24_|Xc+c)=~=s6ipJpKme-aI_M z7t`W#dH&05?U*e)ab8CEkBMnrEDB6GnE`aCdWMEpYHIYBi#txbh=0UU7C{FGGq&)3 zYH3OM5XYVe`zDf}DsE5E)N@%$f4#WmdA0Dy__xWI#UiwHt&gkUe0w^|K5xH@v4 zd~f&i=l%K>aE6yQ>JsK#+B&uqHV z?#ftNR&V@xJ@IK|9mcxGZ`fU6$sczJGLqbnKeyE zO)O%RuIj7lUuY;;wXv0Smo{GF9(qT6S?YL#lySrgcS!mD8TZ-m+RoKNRA&+wDauFv zQ728uN=xAea(eq1p=>@BM^gUDH3jIgoW^uPSUT7|06=+<=ma>rafm%nb< z1u|m=ix{=#4pQQVf2$=`5XfCN1P?h3pSg z2X@D>wG9B^l(~Lqld9vq;swaGFF^3(mlMz*i*3Jx87mESaYzqLyEo&mk;cbF;p*(o z?u@WCirzMU8^dKZ9t0kJRHOJk&#E zNC(2afKHg)_Fk=o)i1nMsJ=*k^z_kbM{&*vg){Ci%XaxK$R7>kvuySVohy{}fWN3S z=XMmISA?ZWUCS0}Q@1Q_z*%jeyImtR-zp1h)AsLQXGe^_l(U8ZWd0Y^F5uKik=*neFqsIwC&5&>3UA4!gTk=zsUs%aE8paDVEmI*M znu<&n@}s4JCmO3H>P{nqKbTNgj;9f^mD9Ogo7-+%l}3Jx;2qdw75GL$i>}Zk%_K`` z5O(~jubv#mSUdX7)ws7^aad&bxSK@Qx=L@;>tdoDTEBZLX03`6=-AzCb32N5hS?D( zof?D5ON<|4k^rf4^IOZhP&7&KebwgAM62*1G#;{Od6y zzosBHsV|R?_Mb_eB7G0Vh|4}^`4zs95Flerx5`1WyB&nY9v^BsS95fxkQ{$g!O(L{ zQ=iV-py}zIa@O$KnM-4iK2diK#^itp40f)n`(}6+G8byg8y4hM!DREY5mUW19o_5B zHx5RAYmseGp3Th?f-&_;faj1*(bI}6WA)3f7^kr8Bp4c}wy?%MH_*IH>kzH>@w4iK zNoESd@e`V`Ew|K>3j`lp84@|VZuXv<*XNkzyu#uB!nubkn_`85uxl%DHeGTmU|*08 zLe37ElCyW-;&K{OXg^3_T~^M$g>Cz)c_k54PcckdcsqdF}c zo1AJ|c)_vN_eq4td&2Ya^rxE(APUOlJz=|+8*7tOJ(Y2k5~|DaF z=5)GeD{fK~EB7!VTee@Qdd7V>JDH)tKhopA@f_Z!X=5n!x)PHIx+?q%j`)Zw_KFR|-x&SBqonYf{UYP43YLvVfAfmc^rE_e7Fyx%eRa= zXw{%ewXgkSWk_E#%+ff#i7X}T?GB!Sq~9?2C)6jDYRNN2&&&|Orm!Ds7{j|oVhr{J zgmCx5vBRvv>bB;!z-cawD?;vUCs>-lMy72Ui-89CMGz6t-)C4Fd}SWtaP_r}0=(m? z@;?U*&U9xeVgwW@%7f8a&qwH4=l65YD46Srz>2)9g>r}^^(IToj&Gjjc>fFKK2ynQ z@ego@AFP}54mN&hSp`rg0O2c!2TYr1%u6lFbBr6SzCcOd^}8(wI{@k>qgt@j)FAct z&MButcJ2^=ebk9kjgOb8Nn%?@mj zw#~h-+$OVYozYL$8M*PopKsie{odB+HCRwFn zwQYvJtzQn?`0Lq+r`mFU`WpmcHd$g$ppHMr)Pa|JhxQ{cKX39PF*^Qy3@QK6zr zVAxnzshtuq<3$7^)+@-~yD9nibaqmNtD3{u?ip@&KG#$n3#oS2SsMM_23JNNwcJv3vSsBXD#S6oY4WsVoXqjuKkM2ZyZR!!5jj42cvdkK zyr)KlWOkO2V?D?1coeEp0A=1&&39a;ZA7EiqLO^4iPnwsgs;Xor`B_i81Wt|OPylC z<26$f(VT;Lx#Ak>7%#D;)TTRI*@H3xMtAA}g(dnf=9vNXdz-qZJ&)=oK?TzEk=}f> z@R2diuIMmyCS(>+<0*PR5Mv8+mlBz<$UYK=fAyKYjCPKH>5w6 z0v}QrY#er~CuL2OQTuHpzqF?IH65{ZmOdJ(El29C^9gTMY_}NB`I%tXdB*?|@+3s4 z_r$7hIqTb&#%@igpauU$74~Ptqt*ly65{DOJ&Tv^ZEz`5^5NShgc+KZa%1<|+8)4%N9%DHn?7(SC0hFT*kM1oW4`}~%z!a?~ zcTyX4pR_t%;6L9$BA_w-WBA+1g~<4b?~eT>3P;T^n6TeHTp?j7G+n%U)B0$|yNIZ~|yM7qV1pPjpo|sFIKJF+o@%GPrEtmWeK&s<%+Ga0__L=c`Yfs$j`OS9S$*I0qi>XLOL zob%he-77;9pS^w>trC>XE=RAH3NLqeJp4(q=V2n=`H1GF(7lqz*Vs?9vQJ_HSzi)x zcpr50S9{KXv7BaHHiCouR)o%cI@3FNV9u6-4n^zc8^EjdCRD(q4=ic11PrtuH<`g3&G>-4O z2;b?bz=y@^EbW;UwiWh$awL|CL#qa$O;`gKt*0Ln34RUa4%4Pa2NU~*{DTEp@#KC; zcq}77$~qp0@ZVR329C}UDXvvpJc}@B1!*M9LW@TDdK2dK6<0j? zx%2Lb4^e-jGRY(1#~J~X<}Q^2H$aMTJ`vMiHj%#<1Oh%pxg%_36ftPkdKwfIo0{qR zSpooVns76o@`jzwX{bj1`_jhB$8$NPkPtiCam;3uyOo@PY82U;Fz#cAw?h@5KENB5CSo_4&b%4S6P--^Y{D`JL7%g?L!!(8#?%*S`iALe}+ zE^q!~f9*5&H(S`kk)ozEG=#JA_ znyAzAIK$=9Z|s#i#2%u$Y{=mN{CzP$!GN%;Zt6=?Vi=TD$xMfVMG8O%spHr`ZBrt* zYr6|ovxnKN*Q&|o17^0-@-~#PQY%Bx-@je7!aeseK zz%vYp=${uB5pk14!1zCa5PbK8q0}sIAgIB#!wmSG&n=$J6?q$^U&hJ^HgZg ziNEcbj)2GGAY?xF5%e}(jj#>1P!w-c{%?EPr;ec@6-)#i!graMmvVyAUs=0eXEIT$ zQbn;(Nd&%suL#w~m?D!-Jt*i*uJ0K!6WXG=9T#fhj7(icK@IH=BphUidSff29cry= z|1M>{0m{93*-1Sr$++qcU%}Zq->ZI%d#jUkyDdL;VbZcONEE#k&X9|kaeo%kVg{K@ zEwllHNE~1eY#$)&hKS~9;Ni14oB-KJIs6m?)vT?A*q^~Tx(EDM-)b)Ko|>Xj?q(YN zSd==nzun`1sF&%7$SU*LK&R{nWJu3lNF~@A6KePfJjn?2xB~%O{#=Vq<#U~{cLB)0 zM83`FVnu4Jzh8m}LPv_GyuDDHU&uA8 zzkvqLbY{>Y*Ec)gf09oX9P$(3!pPYZj&mT3eFMXM=@V#nx`nb}2p+|B3)-A+L5@_W z!tW#1eyW^F@{SU*ouF|{XdcXQ*-hbK;QDW)^jX(HK(igjmswV-h5JQ@f9pkR!*_tC zK%~3cP?#ZN!sEd}zm+jdcgPm@&hJX3HiKR(LbxcZ+q3KNtMp}teIpkWI0AZp>d~)v zM|uRH)NaO?Qr{BCB!GSY5x&L#MVuga2djp8&#vNvEnXQj5Tb+S zE7}+)FY-z2iK2`wKenJ6n42%(4`_qn<_pLg>#i09T3hYt@ZhKHR1B;Ka?5COt@=mn ze5*xa++|;1pXPUC0HNr=ykc+@CqX@t-0!pUS`8?Y*-{Q-Wnx|mJHP%x~yxKYC zfuj5h=Q}K4u@=Hr;W!nhgYEMMZs&XV2bV97mE4G%o1agSsDXS-xAv~vbLBOOf35_w zV(5Pd zw4M*j2h9=86j)>&fzue7}Qu;Jr5 z`|+wWz2*{nWQ8!izYU5TA1z^pTEL9E_}4cM@c#`7*)_&uZ7-+_&^j8$w-kvkX+K6> z^gpjW{y_hO@8)+PqNRGq8S}XhAUc#paWyI-ARBC+0JzwT%DSP~=mUlD&^JM)PQA`$ z6D}3ABT7qjM`CBl)Y|O1Vz=G_zsR!UgRST#^CO*JB=BmN`oMSIIE5Lw*1@v=Z0~t9=A<7@6HP1T0Q&;+!5C&Z*P9O_rR9k zrfUYd#mxEW_sYvT^jHVxE8EYrg)OW9n)Z5oxT`xOlsV_%aHbH3Xz$r^vD}ej&9A;0 zM#6L|FNcSRr_TTs`@J}vZXDMUe}&V*`QPQ8BbR@K&7DK8kaDw zGlT;IA%YFhf7`iEkW1tV|90Y2)3R#JFOd3SpOm}{cL7U<>k!#G@5$Eaje5^eBVx;L z5hicT`QYQmx!tK_G=dfZnXF#1afI0yr99Ux##=Nx_3D6m2@UGh5UZ+9A;l_flp0&W z;=n`k+n)zsMU0WQBVI>sBaSjLfDSE)j}$Oml^@^U2Qa@n0tLxWvHs)F(IE)XT|aO8 z{rmUfd^Vfg0b?f|IRAL)Rl-YSE59__@Z;s3ko`Y76JB!<dO=-q;5yL@xJ2I$Z%)?LLg`nw-6Ix>dxkgz z7A*iFCn&>oUC*bdBk8ndwNI8R3aQ{izuJ&s1{g%~z($S?K&ei_4<?I6_^ippOLRehfp(Sj4>r8g5-vSHYol1ePSnh#=i z;AIgNK&j(x+YmkBNF;Lcud56UA+DUSfF=$o@tzS7 zxCk(O>)oBrO;?pv)iwhQj=!G>T~7A3sjJ_=l;Mr$iq*QFPWV9iK{e)s^%Jl04}G=9 z29>#2@44R89ni6&D3^{DaSCPm;i#YxXy*ZV@_`b_+MR>}&NO-GDO*E-lEY59 z>4sH8Hr!0lM4YTIZCLvO<~v9w#3AW%LV!6TOrVhmesi7+(}AUx*m-vw+P{0)q=@st z2`j^HB2HFtqO;3lmRYz+cuk%+&x`l(JJ_=zE{M3%O$!%>p0(Jfi`G=CptMvpc|=<0 zUi%GAMLJ^;uO6@x`5js!cMWlx#;D7nZeUlFZwcDpe7Ex4&)z`e!XkLz3f3P1&pVeB z#;B{M(&P@Aohi_F?*K21fDms~9d-Kr6r7x(%H#Vd#C>{R(=Zjhy2(C;4n%xAa6n$2 z;W>BC9B|K5N|d~f7to+Gzzg6}?rG2!h~W?yAH47~`#C#S1{E3_%0q6HcNYKgA^MH5 ze7pfDKTY9UM)_(@?XJ%X`|LUeVuZ&0j($ycz)kQSmy^2q`|ettUjrs1E|s|l+>k0Qu9D)XTzWfg2*H$@1=W*S6i=NhVk1sZ z7r$M^db9WMg8W{V3^pu}<14+|noY;6=M8rsuqLpzYIn?=Ua&rheNX0p`|`8<`#aMs zx=$1zRAlB>$U24u^5GB(BKk3Q2um-j`84DS_dziCV}J&!)mq?}=6i_&gM=1-I2#n< zV~$pkbtQv#gI6uhX3qt5{J|__AOl|e-O{UVZiA)^k5fJxaAC49re|iF=H|md!xjq4 z5yEpu_;B`R!Kd6FeX9lT!L|}dsp4K61FpX<`xF5RbXuPR%JRMrr~k8LEU;upZlkVV{;mu8cniz2oN=}9 z)a3SWdaOI|m=7zhynAzV>?E{I#NXGSicd^r0|tAI-8tPUR$}QT(Ep5wA?jy}O@^Gv z*3JZibhr{l9*eLMM2iO_qI=6a|C*eIaR4A8b2J&Z(j6<6vq7Wp4G4IVHCx8I0`}g~ zp#2V902Af_tvlFCCJCqdJ70~w1KMg;h!39L?g(9zCv$p$Bj!OuC)O$0*b9;I7sGdZ z$sLTvo`2$xbL8^!xLW;=Nqjx|x8VApiS5_csebfI&KEgFoVYUHLZ9bU`mM}DEe4nK zD`bbbhws7)E0H4*U4Bz8U1wzITyGJE^*OU5ojXw&T?mhnCJzwi-yd8L{nsF|$48>C zQX7s_x4hM!qP$f@uwvncwRJlX4=8XnPuR_df^;xOSROg1 z`{$X(#SQu1&>91NEe{f_!<#2$w}=tTQ{eh-y7wFCW$_~bjoTv%7cyBsLgBc*qvMQ@ zQMu!|6&Rsz{d!&a7&3L72iIBdAXwBdcVCMI5xccf1ZPW&lC6;izB@WteFIRsObtL4 zBoUHxdbS(v{f3LMPqCn|WvdYA!MLcK)V3en48liVuM4oT1t*Niy7GNJ4rlZTBTo<} z|Ed^PPXqP@kEUrYQ3b{rK~$KlTEYkm-Ad>%R-r@HfDVdB*ac>($ta;-dPWvCX%Zc3 zQ0sWcD%|(K$7_bo;=))g?K7X0XRH;Ceb18;m)h4a;6JXAt+S_@D*^Q-`=20jPl<}Q zEN!ELjLR^H0!(MXIgCZZS(8hJUMCZ1=26rvolJv$ab{*PXaUL8zMD*f%!lYLTK{{r z=Y$ChdmcP^@CI~h$hyFNJ@bKBNkRF&d!oELwwUeCAleie3r2|V5OPFlb>l_{OzeGT zj}g13nJHxe$;{l5${V~t`&)#qm!1O>V#eV!I&Y}wzdGQ$-Rqx|#d&#Is+ZygGh zRz%5E(YTSL|$Hbo8+L zS-4kUn5Z!Ro8e74Bl+$t{vjUA$&u_UgV{EC#(Q&>&gDrn+ZCkvZv&9>Ac&Gb8HwvE z9#JvkT@h)vw75+qHU{|;qYO8l*!~YQLh;Uv@+GWn#Wao2-P6%&Za ze+UZpLm`O=sr)PY{Ns`j*#qh>YHMrjFOVAHB#iVPUE8MhH@k6H3-S&vRN79P|=SKRITtkZTXEO%Y4^^3&(Sq@W=B0tmd4SJRazbbSt{V_pnpq|$b0h+!(VMy! z4~nPRr?^l+&rb%RGVSqBLGi$@Wq>>X&`Vr=PC{4%IuOEuHqBf>1R`r-a=e@asp(q{ z9MTe?Q|QlZBHpiVcZR51`G*Xga}qKM-@Q_1`xA1IXhbevgPO-M$@|^^p`rI#Dt%I zBiL35I%2}6R^$KKqA7cnd((2q9TJVBXDRIwdN=a)Pbb8!tn$cSZFwXXH{)(TsjlXB zh|~iipXFgHraop5ykVrWsJ0cAoQOl1MqZ!$4S=mDs0>LtUI61UD8dgC6fFy2&hQAY zg8aI={=jR?3miDvcwsnVZIq`@rPw+_BL}zva)c+*Z+tZf)IyG1@O;ewXMcv@D7&vtygXA5gMVWODeVKpvx6{>)8rjjB>%eS z<}18$e}2=SVhxt`%*?ikGHX~|*8MH%yjrX*p z2ilUE$O}Z*@S+Z|@9lb_vA4ntYGN3660vmjzGA&YO`OB6whkxQ&m6Gk z5qE;O*dNFPU&)Qm5g`kDfgMU*qInLF;`Fc{3K$0L9^oVw;kh@g6UQMpp#Ivw97VqN z1G%oC4jmh-2zj`{y$8@N#m~S#{2eVda0DC@iP?+8FbIjo3+%M;-h>w~cn97EW|Pr* z-~4kFR>0Sr|`1$2&P*z!iM5>-bd zi>B`D|3s)rswwY)R%~9r+@n;wUGmT{k)X(d$9F`UORDBu;d3kS<+_(HF@x@GD$Ko7 z1?f`aPmWi&&g!)CnN(a_3sk`3O(LQ(nn^@~F9~S!MZ4SNAQ)6`p80U*RT6w}f)pY; zZIl_8MM^e@R{bBP$Jjh~MHd_Mj{)?L6AGtn zd|;>ou=QyaL2g#T!XnWZ;%UlZnu0E{*D1pZX31y?C6p~7#tGWNer|ui3?c7*ghpRb zXms*VqID6&Y=pDN{L#a9H4IL9p@Wr;JBR=}MhXWvy@TT)AJBouz96(zg(G_(3B&Wc zs=$5Gb2#m;T}yVPN-Wxyj}Crhrmhg0=@32@%g{WH@BjL_7Wo?(yBYdlo-Ti!yqL}L zwoyqCS=r9=eU?<$B913pdrViG0F@HTx5fp+J0=r88(Ph{z2Ax}akg8}9qJ$>hdt%c z@+dRT_|(*AxsUHX9KbUcD37W8nTW&c0=@Z53;Q4>`33Ipj~kB{-89kK84}kjDm;Ow zw|l+OS~KQL18i?B)(GI0k?)_;eC81r7S00+s@S9+Mb#;!GzY<@3PCRTMqwx^qy8ji z7-rngFvUDZ$2KeDB9lrSvTKQdll1^}Ck8sFD&hXf{RxyHq?dA4Ro+kvDZdn)&(J%1 zmPI3DV9gb|#D89x6M>hUy@S&!^UTXnG`?jzXTVNyT>Hbwtk+=&a@G#W?L zM)B952|lTi6)ewuObik?7ry}XPv82wO!gB?$PkWJ3c9Ld#nM9)jjuW+J~72b_*qDY3ZxT$kXvh9}Tl$Jc+1XfB4j&SOulZ3^|YT zEfR67glYV0oC&Oh@Zaprh#62qc&aiXNZK{S5fHkXk&!WT9cx+#0j%a0jet?spR@+4 zHmIU~`AEV5b6A3c4xJ@WF7KUbKpMc?9BiTVO9CjH$slpIm7>@ZHfK{{ywnh!9 z!GAgRT?-osJcH+cN&oUVsaSOKK6S?KjR%(u;n5B|bK6eo{z4?1I>VuIw z&XjVF1}t%bngu+;n_Ht|(<`(6HFXY@f0rv>egx|){b+9tTw{ws}o!})G%Ruj|B4zI&WuvD(+p_~2 ze2-WxTB2sgu4wE*F~F6oCgYgSnSpw{#&vio_DezaaLFTESx1;Y zrUvFmtDx4&XYv@7}EAn{%6K@7g?CIPi+Qg|7#pn>%+lF)(HG> zg#YKyKFZ9D&c7n`l>63-LYtQ}*TYWUQ7%6*x(sL%v8wv4iaTG_y+Hg+{}(BXPSkF6 z|1zk#lJHW&h9e(PFNd4waT|tm&VBik%$*0l8^{egRT@g-K2zP8p`G0e8wE8uE0}au zXL~G@9TK{ef#7kt6TIP`8;GUb;w$*LyT6snL%c(^`>g`#IuwNSN%C2~G-D3XYyoGI zI5uYD1!R1$SDw?k9|;iqi_b($xEqSYnhRTFx&YRx?hI%tZ)%7vJ|jkj`wW3f z)c6C0+k(VWV(N3hTdmoUjfjSK)7rHuC1+(7g{;tbtQAEl;q>|dg+g8a&m+olIjv18 zaM)dVx|f^FYHE+Ie++F=m|l1KQF+n|a@L^qXwhj1TB|eBjSU(xSfpR14#Xdjpd>tu!zOn>5kRM{iCu~dfvs92}KVl2We*x`7odgSqV+r0MWT5r9 zK9TRA2ZW4~`NJM`E&B;JIBbBiCo({Vlpjb^I;u?P&JV38%)4AE-^8% ztTbTOF5x4u`af6z-z(U!RM*?UjUj2?s$@Luu+^i-4t?RGiZo~)Rp|FlDC}CZP zMrabHtYa(LE279O#lf+aL{@f`ot0#hGLxN>t&(JwtVGH7W@fKS zWsj0d;{SY3<9&bs>*{sAS8;s5pYe?Qxu5%)N9r4|Zo(KR?Xzd^%HGan4dDYvHo5;0 zyAI~Q3K=E`dL1aesn3v`{)oIGB6$4gS&fNu_jhVa;YyDn)qC(bL+anyfjeZ29-^ks zaf`jzYb!LL8JAX6X4RSX>Zq-`>|r&9!L%<}D-*j126!K)$aGq0uwJ^822D4T)A^Fu5Q>BFR(N;Wy ztOu%LXjaQo;MW=^7wI&pZO3U~G>*}^`&nCC>%2Aul#z1G>2*P){h~ztI}~4`KXE=F ztb@`9LG*JU zgcJi+KS2$lC768MM*p65ZE%s+7<`4wJXtsU$^O&QwsH--cMun+joxhi-O!LJ#$Yw_ zv_Ww$h75|14*3qJw__H_76VIQ=*@;a>81uZQ`*|u&B(~UF_{2W#Or>?zn;7acIUqT zg&`RR4R=iH5p&?66eU9{nha^cdchZs84CBBcpfb?&_JS?Ir2N_`L!>+5N{b@G7vQ~ zRr}(^d-1CaQ$-2K1^rRZIcD72ilzU`mC0=n05~qqe+Q#r6QQAaJ3H-ZU5ut+@S*K7 z?R1d(zhETpaT%+YZl2P7rcgM(I|QWN^n6#Rv*p?9PCxZ2Em!tQTEcbQlGa8NWa$$T z(}6Gm`+Lz*FSr-=Kd{_kBM`4Lyx=(MDY$690=eE! z-nHMj7-(6Me_iGbSK~>cakA(6pvi5ozIJJrb;I+Y8DX?WM805mj!?-fr=dP6<6%sdqO>#`Yu^5VOZdRpt(5~b07#PzP2TaRZ(~%ris^lxtYM54pQI@ql zvHft%DZ&qZtQpB+&4LSTPvG^en3$CSG2D@%#eAhqr)2P+vhPiHMb& zjufl0gbe3JZ0=?8pwAwegQBcWaTiR)nu2#UNH&Bz zn~xGsxdF5a1^ajPgG0B{BJ-qSdXi@ImYkDc9Gd5u4@r-LV}U&GQ{;}LcePg-Dk1u{ zgMxuTlu{;Brv%9x^Is%|FOg(9tP^bcr^plh}!jakG?N% z>N<@)4UR1Y>i#X@_9+yvQJEK; zn;_y}WCsJgpO`_DiSXcCE7=*)MUMl*S#ogKeSM+Uwzi!zY)>-4Wa?wZ1&4tl6!oD< zHL6i<&m+;Nax8jSFw?xdcI`^Y$TW_jBj%L;6TBok1^XMPVJ~ezr@-N0Eud zMw4L|etcar%7j4aL5wg&9jBK5vA=o-1}EJ+*zce>T>ibyir&`gSLVX)91i9x&YjI9 z!ht_d2g6h$l&CQGFU#N$n6WGkYZ4Ifo#Dd@vV{A~$6%nKW0zvLhC_&~J6kCi{MHw@|c_m_uA0r~bx_pnbtjloHV-0RQO74TMzJG0j9YRP%=m?4MMmed@5?6a9~x+D$qv3HK~$?Sd~3`^tT-} zNwmWF03{PVeYz|ubNLom598+Spl~fxZj8cys5bA(T3eET|-nhK7bRxIBYi23xQSA#dxOAXCrdL<^x>Sr8k@-{H^C3U#eu#_oG&;j9mqZcv?`C)iEbZhoh5yLM_Z&@EvH?tF&e9x37m^Vr{ml2AYVq5 za=-C_%3vj8Ft%l(1OVrq#toohf4B-%s<$mNt6ti9`&mXk7BM5PJ!~(FvCA8Q)>|UX+ijtdFzJV!|0utU zs8UE7>3txKF^ZC<-*|r@$l6rB&ca}QfgKZ0%aH&A3+k&Cze`~gkHcdVKnWg}O<=70 zLSmwjZi?Ij(0o!LK$J+y@hJ?aMsQ ztG$IF)pHVX)_e+QsQ;rdM21a;EtQnIQ{!!4rK=;W3t&zL*|;aNYFxGERA;wx@k77-8hJfE? zvc;dM%Mkp%7p>B_aUjf|m(x1%mUkJ5d+clSaHscIjCyFB*?qPpy#oU|@vf@jY3JcG zhN*KmZV@ z*?ZqFwmL1!lboEFv_G?^Q+vtS|6L*YpG8I}rG`TZUya-5YCQ+$EKwRpnHT>^t~sFs z5X%(I_`aAuWyKPi&kEy{Ph3-fNpOjuDQn-K2pOti>WM)|1`RUuh)keju<8xcN-z@j zM%glgqo0ewxKSV;KZ112;$s7_aNg?%t?Qo*IP?A$J{8p5R+lC$jRt?CKwftleknaD z@R5~rH_dcYD_<1Lkq<1hWV^{CbM5Y(JKyK`XVstwhtjK$x&!@igRJ$gOQVk+^qH@v zlRy*r$K#Cksgz51PBc{F*dO3qAXfhG;*=aCOLWBhhO_rXsTd>`Tz$R>qF~8!6D{H` zjaE1Qd<^jP_#lhe0J-J zqmZt*V8xhsT2Uno1=dnsBsmQNo^tBr$9CvM7n9|9aqUF5{FOahDqn#N&<-sA{ir1| z?OSWpCzr-;$YK!a_lk%x5Dk$yeN<1Z=t3#mxNd60Z$v1JVJ}1cNg~4za;*M8ZEZct z^Fvf@^~w}1zCbG92bHtW%oy9Ps;LC+RL8F854=~W^^|PQM9p}H zRUr;Fn6df^(UrOl%t{uL?uDz2et9O$rSvwaDIyAL|H&U?(DN>7m^7 zm<7YVD{Sb_a)%gG&I5bo)2B~f_ms{weScx>@X1FOg~Nj8DX9E^n4FpxdL@e<2uVun z&khtX`TlGzs&{_#>{p2L&bFp?{XeT^M`{1o+xf_7#raGI9bVqAAUmo5Af-ng~&SqEdPbt%QkItB{ITG)mmRqTPGe2TlC3LHe-{@ z{t>fFatc~c2gY=^ZKqxyyBZkC2ftUN-UXAI*o9s2mNkB^E|!KHKl;th^Vx_|?0e+x z2;!7hoE+peFKF0JN;6dX$cs^j%RZyfKooKbB1<^;iY6g{MD)FHoblkZNFQEg^MCyr z1aDSz%#BonG8} zsxrB?xwJI}qCc+>c|ijQx(bUN>NAmI7}+teL;x)wysUz95i@bJz_>K$;lWD~xIrwk zn>>P=$K$&CG_9b|GlZ4m&1KN^KPukGBhtsZ zitK3Kj9xKM_|*udQNNSi_NXd;C?_X}A)HT62LObJOwZ3~a9bnHg3Zwo($Yy5@~2+( z&yV(nrsPm1J{mN+_@QH$N(WPA&4sU}W~9@F4p6wKjQDsSz?dl+7yuST zOHBG>CIrV|E+W8$oHzfhot^Lm#J-lI``M59l&sG5Hj@yBNmUG<-ws$zs9raAxrD=W zo6eot#s}(|44PIj-~AIfr?~=9k9`Klx=u51Utzm72BaP1AZjTk-Umj5A${d4daI(Y`1@j(#P=b*(&0D7j{+R^biG>U{D0GUe8{cYH-k?6C=xy_?t zH?4aEAPtRDJlp(v2`v)xLoDRP^8+$JmFHvkE`n~06$_yv_>tKN9EFN&u|g0A`&=R0 z9?d3obvH{1@ClZfSs6dkROn8nwCc?h^isb&s&Q6z83AhLYWl!RxevHg z$20!V*a%aI?|7j1?XYao(@$Ev6#RV-j-4S9;O3#Fr04hE~{H{kB8hEd=pvzC{ses?ck zZ*Va;TGNP88IgFj;>f!#^3#FP^$Et{2)x{3_?9*Vh}L6Ir$JPe52Wy)$upN3pyP}q zBVUy${SZdie_E=!>AOLK47hiZvROu6PVK(206JDGdRpJh{y|EuhTooFh}+&*G?vUc5SC;t^`TF!#n8j zY=Jc1TG6}J7GFUj$lcHkHNN&U~lByLntK7+F*Qrm^iI6Yh#?L z5MaAJ`CNF|Q6?J8piZXz3dF41A-$s6XZLdLr8!mqlp+Sz4GF7zT!AfeJ7&+Jo* zW=Dm`P$xLd0ECca`1V9RX?Y0@xXGay=?893sEKjp>J2o#IuZ4q9A=f2lziXFYMBI- zJHMfTb<&ILfv+QfE|fC_`yjAypY}x!D97CasFwflk%faBXN68Jo7@8c7~C?*dM@)E zGp^*BO&a2Ued+wuQ*VKqVG9^0eY#^$UZkz9txvmy@81##0S+`+!|VGEF=kf?C)m>n zwhzQM6~PnqK$?N|sTa}UzD<~YpB^ij~Hp_X$cQT+71_}f*ViQUEYj7rxo1G$~d05?#C9Rx%NH*>YUtgS9WT%p( z$N!|?xtA2 zG`Is{1)Dp?Zwh1`h{4T$yR^RQ@TJrV+`++jE@%Xf8C#VxzHAbE(F)?MVcCxuxVXOcnQObN) zY|K}H75OBFUG~*ON0a^NT*;}Cg|42EsOdhN4)~)symLU3!Fl$ZtZ0Bmy3SBfd;@W+*ErAaQ{Zck%wDh=Q^sBt@4+rkhDxO} zJrPi&XNt+V)>H zVZtXE(ZYo5w_AShs{_Gk?%{1pf;rFBC1WIblES+<&X`Ds+w{Wo`~g6BpnyRq zO>A$#7#3nK5RI)J~9bdXZ$xv zvnc3|8_*zwWWZ56)gq4w+{6k(83JZU^jDR@z-=h6YacZK|)2Ca)Ah z@9;?uF55Ga(pmHv-fPfeTH-D>T2wtNQU$EsGXVFa02Uw{GB$`_hOef`((zUH*Ki*Sr8Ka&Yc0 z4*=^5SR~hj#=rfIZt3-~3L8aS!vWYJaF#j}|XXNDDvza%n>uYHInAuMMi-q7FE^(_&u+h&cc##n6r z!mzR-SWr9o?-L?fXDMAaxC~qa`q77?w|V4yfU4GaNn^wULV_>nZR34`C;OVn10@D- z8H{nu)xi`Lq8|x?%12wO#2GIN#g&(gpSo1&4q5VOdtIw9v2K`xdc2sP!aB!bUh`(S z)1ZksdJ<#a6HxgQ<@nyNX% zmp-QVfLdVlh84+hSS6#e#z-Bj8kEW5PWDxe~YI?VkU+ zRJLG~f6OfgXK_%On9Ae=kBRl1-%jR=+*7C{>KLEkX3h|V>vrH0XXD`4v8p%KKsb3Q03u0`m>oqs%r%Z;QdQ=_0To%JU>&;g?pa*cuT+H$G!CR3 z@`+S)uOA3O3&JRO(u;xgV_?5D0x*NlH1RcSl$JlDlF5kaF2j$z(}Amt6Y~Y z*eWImfwcJlL}>Lmf(~XyGhe9$HQNWrN7Pl}mryUr!m!F=N456oOkr)(6+`DWk0>bjnd$ z=E`YL)X!aHlK-aazDu?Co4b!lFfe{E2BNurJl=|+Sf;Ze%ka=D_bUt(7cez3rh8Gz z8n6sakXlF}R-fY+(S?_O@7}$5+o<{-Lrn3Pj^46vkUuDDD&5h1C2FWVn8mR3qx)}f z6*miA^o>8HN5#Wmemz@Y8L(9Wl>049l_%gm3B-ki4X%$)sPw&rMwxis7_73q%-}!c za4g?WCrYq1Hv9(*d5>U}>)Ouz&fy>7tS6xM0_hik+E1KWp`jmbpjiB-m@~w4SVUCH z@dsQ>>*B(chI-I%zX+~q6^34b~U|0Jg zGo9Q*!D~QtKX=t~6r~>h=%ISgxAq?CX-n-MJ%&8LST>pU1ZTyHr!S(>3K0aQdyoV zaKitdr@e^E9yCgCoTT389Yb#wfxXsPrh&$4n!v!dbxFYuP!PzH--IsU1ZbNnIHR2V zMAoTaN7V&khsHv|OKb-tc9~Rpyw8IytwZE2htPF?a($#_(o^Mm?n@w*wC(a~=mVSi zex#lqi;uhrqap=vBmJxQxz`mwUA_FP)QYr9I$kcaP1yA2pT%E;4CzVOdG**mdS@nJ z7F@nu!NFJ0t4I!~M1}0#PHZ$zx+4=1oPQoy!f0H`Sa8=nV(XoUH!>WQV)ua6tLqT@ zlPJ^|W4i{L{VstSb5y_&g~Q(+Sqw%Sj$z{&b~@9W`ue>(LX_a+;pN1dw>x zr0Pl^qMv%-S9?R~D`=??laTF?Usn1c1&11balI$DlR0K!<@wcH5Z~<6Gn0ybyck1G z?{hXaok~xhx0Wvv`KZSgh{MX%}?Aq z+5~&SqiF>O21a^YZP2_a5cFx*E$kJL>G3$(UFN~CEI{t;-A$bTcK@fmmx7LyF;Kzs zAiLEY*(I!U8p>EvlEiNeOzHnEi)$c~0OQqLC?~Dd|B>K`M=>NX5z z!sH`T!p*;m<1WBR!G}36NDBk~so%n;D)&KI)lbal!_9LBTa?jNmO($uO-rs=twY!7 za>gU_ueff=T8k}scQ*n#YhN_$0Ylqy-#M{eQuZe(wFbXM;=Hr<^xPlPmvg-JVJkY6 zqxl@#&F{+$qAN2GOhzWmMgOn6WnBw%o}-gL%GU)XOy+6sK5m2OO$P$EM&B(GTM;j0 zW7epyhuN+#(>+Ha<=39aRbx@RS4bDf%{Y~Z5NDo*^~k3|eT8VQFvFghbm{IIL7#JO zBHGhFcuKkBgy{O%FILA|0yn<7w||+GkHO7%Q@{IBSXjsq&YenxEP&!B&mX7t@bFRdzfL#xYggQtstW5yfL z%NPgAqA8@r#%!eA<(pUsiR_%&JL6q%h??Zg5)a}3X*j`>GlrJpEnk+4NOp;gLhO+= zY$2Xa@@$OGZ8^P*(-5%Pf=@S$nv~GwC8L)=h`Yj0T$)b&vq{{B7zzrC&`v}?-SOg- z%lw}E0P+|z@6e7aS6J}D8tr6$_HM$|TdKwmHN}Nk;$H5vx!zO?jaPS5Jv}`7?y^J- zSB*RWk`(zHQ-*=XO0U3@g3MqDjZY|#zKYyFzUSX0508?(&1w~HqArTTA9HGs#!jDv z(&qr>2z{$J3;-$U*0^7E$54H0Z3mbCi8#}nB-{Z$A&{rUzMJCUC3TAN{l8#X%Bp`k^ zmzqzfopP7&ImqYer$;|-xg|*~Q%&JxYwO7wH23OO^#I+~<~hzzp^zlOU{Rc1TaxCC zOqo0Xq&nhMPH}?DU{u6Isq+kM3jUQ@mJE)AUg1{Ee-alBEJD4tf!=QAS;=k)y-)h? zKY)aD%JAINZ4zqgPh@r@MBkbJ`4Q&D3;s*X&;1PmR>_sQ0KU8I(&w|y?vp>R(#@(H zc>gz!g&Pfxhu#$}Wh4Y1ha=bF1kgj8`=OoWzoAJMKUjdD7t~+!xo&~In*tRZeVVHT zBkjc4XW}_e&e__2quO385Q1fpyD*!CLIN>=@VufS(vL)75hXD|dPss6=xJJZ#lWXA zFfV)FYxAfkc0Y*5l5*m{ak#TeDZBnW8nj`_l(Mj}6wqNShjnot?<8#1B-ziMAAYQ9 zXWmOqKM@~a2_ALD;2%#-pc0itqJCWg|Io^(;Mw(lzPu=r@r>ugGx4iH87y1BAFzD% zUpW<@G%}eik9YSfis@?~p{wb1+lT4bF(oJ0*=_Sl{OD10N+zvj8-ugsd;cES=Lm?Z zE2=Pe{{g8M>c%?RJqj>_6Mg;;YBp{oGxsZX1fZK~aFY|00g>1HV1>^oCp}@y2kPx$6s4tEEkWqVvFgahxe zF-1j1^(}QvI6|q$ty$qb(;rh7!VQ*S%+hG2s4@U>lrlgGUK{5HsvQF5tl9hd3px$+ z#Xo|_1!Ktsdw8C`d=Zcj>iM_sp3uF0qY!2zlChV=kY7HI2+*2pppswqyE*75wD5zHXt09d9oz z+!M5EURsW{O*L|a;)+2bYJvp(ZYFjHTD={J{mlCelLie!zwg5hG$=mJymanQWU)2D2-Vb7jW7+zv1?gO^A{d(TeCAML$DnSFk$Hs)t_w=L;d4(zH6Tyz}@=Q-`~0 z{;VH4iEXHGM#u?h@>@{Yc@Ks56RuXJbX37;c&9O%6q*+;8jU@9wH~3VKy(VVcUOaf z8T!xxW7zii1`Q9nBBKv9Jt5MD? zZNwhB4EaryzEtNIHblzFr^aT#y)YUS-&9>%NtbYDmHACR%K|)FFhZP zRVem;e7Sv!1WV_ClB#+m>?Y_)X@K3-I#&y+=Ib5GMAFD+qXk^lqtd7mz)eL!Z^Og= zmgnk)^42=Yj@zN#@^WbG0)I#%?-v~{8$I}atW=bp)FgO-D%7;qhNKzmS!eB(q8 z11^6>_SH&d^Z4=B3IEU6Hr5B~`qS58nqCW%P`{^<@e9rdlH`Yun|w&;qsXph@SyXc z_(TPp%^9rqPT75F_MV=e6rpyq)R?zGnjnhp?tb=lX`)!B>r5=U;>vTm$Zn~zN|Btf z>A_%*{U^dJpP~!Bukr4}a$uRh1<*h!iL>1u(-!JmPXXW&c_8yQHV(#0VWuBtEit$n zma)h4Qu@S$+qHNqvI>_A1fn8lgIjt0#U<*;rrr6(^ay!-$%mCv{V&&Z%q-XoYh-B< zweDEe4E{p0ps`Jf%%OGwNQb;J+1JAwHAHQIj4`0*aHP=%1FMNhJ_uxW<>6&l5ZA%R z?v~a9)vUQE?V_1je|1!g3cbb?UkF#f=jkQSFHcd`$mcTION9Y5&ujhwCLIn(V{@uD z*XL^A?5#cVmsADCwH6ciI*MOt zl;beDnhUKsb5pRHMdBsAhOzvI%NQc%g@n}c(nk!Kt_Sh$J~zE2_2x+6`PJtWDnXg~ zE4$XyBlhlImssc6jGf?{-5Yo{FeWg(u%}z}WZu@VewVX-o@1lbA(sjupI3dzwa~cT zqwvBzpQ1}OpI+N#|318N3|L;5HkGVh9qqju_2(ge_&UOzTL=G2Pf0itW`FWc;)TH~ zDE}&X&@$FfO#^Vndv~mX-xOfQ)WB}*MbTJN$bv%X)99!BzleWsDyZb33P&SP8LnF^ zF-Jemjt&PtRrGD(&!2t0vc!*ZCL>0|l$%Q0?J`r4iNwbJGUghDvws@VvBbv^a?l;&DRkjDm*-O)> zxV7=9XdNmJxH4u{N$2qZB00TJ3nk9S${d`>J{}rR;CGvg<*zR z#+|1Z{1B3~$xucPOSqdnFQFaiI^?L-4%GDEEHiFIKa6mLX2^J+*=@X^Zr)k-d@jvG zYUcX2C6qi6qA82Z8){Zoa$vqd!P6pn3k1yCz{Ew*DO-MpG&TVSyP4jhX#Q}_7`lb* zz=_0ue;KO5&5W~pu?G`xe}DLpjP8|v|H$MWB*(>aYwct;<@qEWrUArvo%bJp6u2O@ zji=u~qzU+|aqUp90wcIyAm)|wD;46vM4bEy%A!;UOQ2}LWb_G0gtvAUkFB(%-Lcto zxm?wso9+6lq!~BULuuR-ig+KX=%j_6X>`lSub+ida&)C2>w))hP_!UJ$zgc}dBY*l z`z+$JVF}pt^$n!R?=DEZ{SL|B{#Q>}XR<)MY!>64U2A_)Y6O_0z?wR}#^ID}x~6ER zyD>5?6#H*LgyiY~5fT6#r21{#P{e27<9f&Mc$84S`0-N@njU8|&YXtBfy8I3&Fy2T zKQ3MiiTIw{5yc{m;Slgj{ZFIKwkwfQ-7Dv9qhKJOn&v_ES!3PW?DoyEQFl=-2-JcoWd z(_X576Xp;cKsd^o`$j>J^#re^ z1bG4!2?5!=_dpfVSam21q5F#a32iy3dqL)XZKmo7G`{L==Lz+b`_aV!6$LRU>O8Te z?EIDLlQKd&hG{<&OOr?5*JgKEmr_NWrS822RKXp!ceEqwW3QNs?UZL(69Vb6`pJtC zEwQU_B3uD?*TwbdXCCrYQ`lHm`3`f*-vc>{;gP*pA+ExJFWYSjk`%PWL$Dw z#WS4j1Fg71&&$qk$LD_j(7;fw0xgW3uMhQwOuuv8bx`8oy?g3nD9<&PMNA0lj;H+iffBlg@RAM8(Wkn!C`of zK?VkI+Z)H|nV-{;KU|A`D3}#0AH{92RB+PeLBw0vMv8VpUe{CFGID1JKqHSJu6->VYz8l_3uNRs>{*!iY<5KT2S)OPznE6JC#;i(aIeo0*<^I`I2U*X&SH1jp za&}64CBy5SM{OZMznlN%uzF48!2$~c*B%cJ$bpg}3N{FEBLP$wlN*-E(sWNQQ|;)3so2zGMp=uUgR_;K#; zhaa^zm-z#%#>IU`4qIn(upDPXxL;zc0{TZJ~S%WmfkI=9^@dL z=dBWfQUWdL(ofcU7sny=^t7ptZPC2w9Tgk9{}mGAYihumJ_d0h$nO&Y0y_bB*UszG zz=7)*UcvOe_YoVK7;;M-NR;l*{JFXmUX#tSyy}^G?=8mi<%``o?#a_3(0ARYeW2FX z)L`pjpZPJiQ~S`o*If6oIaC7P01?o_;Yqo}zZMT?aFfs)`ZYmy$u~2%kSpEj)5T$G z!je<^`RSjsVFx3M?h z8{fK5+DP~kdS_2;0w|Q*|X@)~vN_h4a(fA5*byBgYb<8A3IBUpel@SeFe> z%=y4D54j{3Uvi^9X!A2y)oPFSF(m*;#uwI_*4kcec5lM;X;-ewG^oMk<>d`3DjocN zhDitc&zEJ>NuWc6ycTWmMrtY>l5HHA6Q?KNw-b~?8Xqa^paCw3l#A}52B>ms@uQ`SE%*=NF zug-jZ+;-@*BeviqLEgtA;LGbzOF>&BOihR{3=&AEc3E_B`GKACfC@+29tausL#jdT z%SHC*3jTR=xQtc|gUAO?O{JdfPrvZEn{gYtJQY0m$4Bb(=(!syRxw%?1qUAFX1em^ zvl^Hhzx=xf^Lruh=ja>`IzvlG$13*n^Pe z0X=?p<{apQ&8%e8b6t6P5Kfyq8c*B`2(6BKSI#VS^sTS7h%RVOLQ_ym-R76#yAJEi zpyzt+NbT(jK6GK_PFO+8o^bP~Fkk~0ti1EW{+u0jmF*~RAN4bYuw(LP$OxVJpj9C;A;Qzu<5_cBa6)150_GiBoOUd zKte*Vz^K@j>FHb-#$v%t9`q#~21~MQ6Zw6y{@huab1*#h3s^UT!=Vr?@c2ggDT(IvGJWsSg`J-~bk*cwy7nwIIf8b^;FOJrYG=4mdUN%HRS z+aTPyAI%MU3=XfXJ!S686<&|cqup)gdlE_C`^U;?hX5q61%2HPPsSU1mulH?gXZw2 zHJM6p)!`$Zx#Kc351>|1P}#2N_OQ0QoTw4;`>ISD!gv07Cb4>T0@3Mx9~P*{o7l5{ z&2a}dlm-~j`84i$zR5G>3)`zeB)7MKl9G~vi)-m!Zs{Hj&Y-*=G&4j||FCe(Oz*vR zAWECOenYXa0??-z7$~viAOH?grCiBL`7QiTf;d%2rlRFIl%`K&k)Hna#~~2j$4b&v zkv0~#uP5!8=pQZs+>J?}5ODU@4;y9&OLM!sB13}5DByDc*u@_Rrl4LBGhAg(HH!32 zL~O>YpFuh=(;6!NXMsX`&>nu~$fh%Y234v?4hIz#745O<-q2@g&ZXp`9JTuEB&Bw6 z3A@yBl$7ycDm9&*3%Rbh^njrDDa_s{dd)~9!}=5Loh~B8-`0V z8nE!snSp0W_j7HfhHosnO|Z7kp6>65{uDK5@GVRW`%eM9)ZVB?_`PYt!RTcA<=WOB z0_J}~sY?xQEz4_K7SsF(@8D@trlxG?D2@?v#zdq(qegxVqT@Rdzp_L|iNlf&V9s@B zB*R0ne|6WQ9h)K6$szV|F*m_MY2$d61lDR=TW1%`$z_K@E3N0>{U)Yr{_Onh34qILi6-RzW z#fiPf*%8CL&tCy@C3HI`z;kK(_*6=V^6rFBA$?vJhE!xi3Nzq^V)oxMb@Kv6l6I*4 z>?_%QfHExDbtvQ3EmQw|kR@aaIzA0NWcv_g+1psUItQzNDB0TbgSnk_3jxMZD=4Dq zm?(gl(x;D#TSIS#P9HcrMz06bnH(s)I|7y8eyY?6((m37%&HNdsq0-AzeRF$Uh{+9 z=bO)3|9LX>c=@K}wd!?1E$ZH$D-gbT5(xR{IK3VY_cn9~AWKLmVX_nK3y&KJXdQyK z3cao(MUW$t!1U6-(bLoG$0h6~)*PF;!VJ&*>xD}m5uloR?X9=iYTuZ{s&yOS8!a2( zKQG))Iddim)X~tu=EmWPiSD`*YDlY21XpkmMdwM9nw)SUM6=8#D_lm-GIZM{S60g9ISXc`tB<-=IX{xZ z{W<7+L|`2Pj?aT^kHAFGR)BjwJw1Knz)jGXlsMc4MEYI@N_t_80+ZaOPkA7|YJN+~ zffwSoFK^mJuaIH9S*Jms66672BsGD6yXwUfYwYn!$Ui+!zbqP%^F7u^Iwv?<@&K!m zvCBj2CAEtNEL>b%d+@fABu5ZzPVuNe%GR1 zP#6FifFyW7R$Ej1Y!#}})8&o=Z{EC-X$wB_`wZ02fMq$oMSbt?-Q8nzQEK+~_V-^g zgDFEYrY4H?yu^AsG@POgOvuT7PUl#~+y?6QQNzI@EVX-0cPSwueKrJTnE9_Xa#Ltb zg2YP7foI=x`np%GkB&8#O{w^i?+kB1ei~;GQV-PQeSj)d&$O)nYz0qv2N6o~%;Cg; zEelx)feQ4FBF85>U%g^+!Hhs7Mr3p}l^5F{I`TS*t`?0fSkxh*U~sFT&_+-`1O=y< z8JflJAvHk(KEB+(2ag->vQ*A7hNDL%eRTa!^rmk_lQ=FrS=V^q**_HT`B&6h} zBpg@gSHbk*qxLl!myMJjf-kJIx#Cl(I_y_4_3g*T>50o*u;1J$lE80a*mty z(=aZ?Ugdg%N?qk>xzmjx+Li*+y-Ojn{D51o4k^83)Es2n$rGDv6)90StbRWZ>6y62 zF~E|buf1115h8(iL&xp-;j~k?qP<&a@Au&3?!^1LiAz^UNkf+51S;loNap8W6dFL1?OFv8_i>IiqpIP-9lJv+Ude84I-(PFs z2tGKhzi2@pkr1_DQia2@09+oh|8wZrB;naYAjwtrU7HuKUI2dwm3R}lEPch6TzOl4nyh6{#b$;GZjYs=bCQs~j(zE^jGN}!o zFW^4R+~l^}h3NK&+$MvCGvKV19xJwcb#f?V+PlrvRuAeujwiuOKqz#4RrlYJnF4O#mPFl8U#gun0m@Q+%4JPh|K_g#~U8smeJ z9$w!}^9$rNXISp4=7J9bwlozb4b8*Vbx}B(ujng*%cB}SYt{^7H+cY0@j9Nv@(;1* zOUh`#-Mt-3m$$cua|POW=Tnk0l6oV|aEE5iBY+Z`9#4U+HyTp7@;ciXI_Lho!DQsx zU`kyhdkJ`OPfp~u-5*`G$Eo&L5^{2L0|MmwKVPngILZz{U=MH~XD*0o^t=j*kB<+O z+pW!ut_)gUW@rGawQ=3_e~tKjpm)$1?k468qS>TbNSo9l<@C$<2};Lf=XXhK9WOFJ z?KswDTE02bU3*S9a&heR3z5M?CW?LzAwQr2OtnT_)^&97-pV63h^tksV2t*sw26(T zqz)+Hi6EI}$%MylEHHK?33WQ~`fsc>zXu+|Be$urtLT9ysX~BeW`bIVdrz*PZ+IEW z7~qcU|8>j$y~Xt>(S4is!c${#-?S#-yP%z#rPl-6d#oSWTJr3$;#lC#rxS)8ge`p= zu+7R6#TqI_Kp@Q(aYAl8MuA!G;@hzKT}Mri zZ+z0eIoEIhS}W&qSFO>3+{xM_DvByjMw5esgP)$pRN=VswwPMqFA31?)1CAMa*P8N zSC*8T-VJyu0w9Lk=yaN4W_r{p$od8zm5C+=rv?uRj*bN}(Cf}b)X<2~0U4KsgoFYa zLM#Acq@DTmC727LeA`4|&j_!nAj4<@GKfwH!eZG2P6he4aXg2}X1dbSRodduu7&`g z;V8asoC7r%eF7YmRo7e08AR7Akf_m#4~9I`@I!<4vbJx4fH^ackcI+H;dh=fsF0^%Vz=A@sw@D-iJ z7w?70Yh!N$#OH9q1*iAGP)v~{*^cDK3QVnr%IuIRMCyxt040%t^{V`VzfXo%T<-KF zgp&-MoQw1Pt+eDQp#J;>&TR8ed!c9m^>4K4p8vL@ns!FFYI^N95K5c2QJW1O`g$aB z*RQQM1Rq;F+j%u`$g*s3pQtGGX7WaDtAUe)`V1eg6C%mTxpvO`%}X4rw%5C26f-}3 zD#!0j!myEr@axl03YQN*#gk)0bqO`i&p>AR?n@AK(X2>sysX=zxC=^drrz^|dX6iQ zjkLnR_YF^iA!)zzJ;+_grJyo~ux;TKqzdO+`=wvxdi?*S_4QjAsD?AR?C*w-yU1(T zq&H=^g;=2z#`fyqAzpkQ1}MZxAyp9WO5ukTcC`@O~oR*msUA?_={FVV*VDmK&1YBwbsQ^dtq(B2xSk1lSg`a~gNJL;a3p4Zk(WwV}CB-(-$>d}=)hz%U@!`-5D9(E69u1WNG}J`c;1~mH(xjm6r~f@)Jz3*-Y$nAMNiPX z5IbpXZ2a_=!u>%A0#RB|7hBKp=XV4n^YdUaeFfs|h)pIMFg-9V&Ah1cZBzkO93LN^ zEaYd<&j)+HZ+K>M-d9VLIa#C275VIw*8QPpwYmdmVceYC)qiv4o5K2cTR>j@V+_Ao zlBx+E)5aURptu_rzOBmf3_H<^2Nz=@R1ksO(EGY?I z9KMmB?h;i3K>5jHi=$NP$L(H z6c=Q&p#T`=+G_?G<~e>HmftUIC5-NF(BW0VamYjLpr+WkqZn>d*ww2nTNBVk9uEQV zk>%&^L~H?pJK!y`714|K9O6G>mgDzz|9)?}hvp*(nyvLns2V~R=#DH03)=_eI|Dem zrq#5)dsbx|WHpkihe6hO7iewL9ONdVR}1;H6N!kSF0S5oNRS&YAA8?utMDKDD#P40 zwgKs@Q9<{;yEzl#7ZyiN9?uAEBNqb1YH{k3wkr->70e=kL)1t3tv$4*cXy|~p+>SI zY;+R#@qQ+NB<=2j6W*=3>+c3108ruUox2~)SF@X7oiq&%QzT5zk2+ZUweHxpR6VzU z22zrbjj18QDp;?9vX~o|DP5}38yR}e9%cMTHY+EtH;_a2G>jQmeFDHo(|+HgcW^|K zLFu4rm~v3G8ZzT{_zRaPUq}f&fSf%n%Kn0MrI*zR(Z)zm4z-?6zbaQ%xj5g2`4<=@ znJY_fK0Xy7a-G+D3^{E=YU;E<*+FVw*rv;yVq_4pupn{c+h7h25>T48Gkw=9`mP4r7%~nZaF`u5IpT3*_zH%}0QOS89FQCD-KsvktgP@;9M?~yBHCQzA zqVCN@o_7NnN|o}4>4U%)-{HL$6O#mC6x)FEuL%6(&S~1l;l_aO9Mv9B+SmmL+%r)C zP}qOthP?t=bhVrc{)6`4l5X5E+NgoB&|Np;tJVpKp*WfD-Q=goS&%Pq-$}34rd@zp zerK8|Ro(4Bpw6Fjot*DpEc&a+e-+~AFFAT$WnxDjWR|eqgeqpCUTxAv@Nrv_lP}yVr2CfgH2b0T71$wb7z%F5tMjcllYi}E z-RJgU(I_&^8e`X(0q89rL__ZGPv++2#4IG72EC%XJkj0mW@fiRPwYn2@rn$KM`y38 z@(GHPUec0k`Xbl5l|J09fLf_JQqo6?o#FD+U}L!yU74z!T#{tgY`Gz1Vyf8DU?QlF z4K=oc%8_eydd&q84|}9C!Rjkf0m=Hi(4xZZM%{G*Cy0_&m^DaIDfn&-5btV&?tHO+ z4TriFxGzz3c>`_&#qYd~?w&qhdkVsm4-;0#9OThB`+F8Y3+Jk}P4s+*Yt3sae|Yp& zuby;RTN`<1mQW67`vb;zLX}JO$8_#>otsCX@%#-z#3qUHQqk%zj$X06I)}|jq-n2LfHRW>`%(}Z`OHD^l<*LzaQM_maFS3L$Z{6X|3#vKoK_RrP@p-Xjr-vi#@U{$P_ zlkHf+*oA2pvC`5~mdFJ04Ia0(c@xcJ$C6QFY1Pxf)`GEOfCr|o4sSvFwAC{p3LDINfDuCke07n2;D+s z9#J!2o7k%d|AmA8gnwx5qfsHFn^DCWK8&4Qj0_EgagY!@>pEIldY<-$ND9j!%vym4 z)!VX7P;HM^SUyokm47FZSMK-jm&CyCKRe0{kg(*=5p9dQ8R=Ur3oI9cu0=;DqSJ`z zQzMrj?Z&V$cZEN>2o-nW-P)<;%b%QiWl)sqPzK`6JwiJ924~~VYqZR?qFyeGYu?#& zNdj}6xr-OMa|8?jF+1&ayz zM57Hla33>FO*K5CzZu<{W`h??bsQ?YLsV7$egJO>MvwGj z&6G!0yHrp%)B5U_%x2%>+X2g%cWn^Y$UKf=@cEc(mBfIQf zC%Zv}>_U-|?9AWed8u>yyno++&h4Drk*?SEdOjcH{r z@)fv5Ho&E3G!|hohfK96Ez5LY*e$cVsbCB`zpy8POIEg`JlI#%IQrTg*~D)4wO`}V zFx&939ynk>jb)^#AEo8FvgN1YJFgMBAg@D4PAyF_V0HEkSI}U)yz5V2;-FI&!1Nan z*zi7E3n?WINF_&X4{b!-cD$3~?#U3SRZ2HPmnrKw9*kS}uP`FD0FdQr_IW>>J?CQm z`!xPZG?WM@c@lf#DB%uoF}J5?!#w5D3Klxed(dEqGKB$ZzVoi}3-H5cKUdTsd+2v< zJ%)79#hE|YS5j{p)(1NB)=>8F3!D}b_!{38kg;Bl*9Rh4XYciAz~(Z$;t7j%ZHCKT z&E6{ws|a1~!K}#mk8p9m;&pgVh9T>{fMsu-?8=Ts8xzmbfs=@IWyBN}efT_OR0`1V!dSJWn3*?O*%R{kdcEH;K*7E(~cGOEuA9>fYD&sjIG`_TuF=#=tM4cL z9;nLT!Oe=c-34>ESsa(CP$`F;W+IerNYzjQ%;oPJm?Vw=k$ahSdwram`@bAOx1+#eqTA zs9yRVj$y1%IicHx+BZK(mo(K`S65fFx<_}&WWb%?Gc#F#o1rlO<-i-pmhFmvJ^Ku?FNi|HQGYl3#^RjK^a0!c`Hzvq2 z2M9qMsZ)NLm8E4kX=CdPtyq!|hl&4s=`>k4aGqC(K?Y?}jTUWT0Yu?t z1uqo>XmMJDNQh2DOH1J6e$~f*+S=N=W3APPcFvA3#ktfyosY=ZIqU&^QQH917gfq( zP0v)Sefy+5+dA@RRMQY@4jR*n>E~_L=1K8nGUrC1f@-|NwCS5FU3lck5&xKMru-ki z8?JoKEn<1hUj2@A+uN0bkNe8?#WVFD3^>;S0+io4T**JtvW{*kkYJO8sCyTfn{>4TN;H!8wOg*bodGIs<#) zl;~GLsA*N?k#^p2Q#54w?=s+@F(Cg9*y=REpbUdaJB-0S-dk1|vf*1XXnnsk49Vp{ z8{DeAe%y!Ttd6{TXz0ZLq<9^a;{8%lPsLCIKsl3MH&vH$60H0=zp>qkSph@CcdK_o zL+7hSC1}X#5Ugnjr0DEAky`c5*9CQ&ee`_*pyg=S2QeE-|Ff%W1LpMxwy4?iiKQHk*}z1;LK(95U4yt2i~(OPK!-9 z=bPTuofX?$yPnhr2iN5mj%fm#xlg^WuRM^GD=G)VRdz=;K;5e1#q7=sJkCt*$BGKO zXkExwFvVJ5li{(pXrb~C0lyMeHov(Oip=XF4-Nh*VG46`$3l*~jos#}ef?UcY$aqP zp3F;eBfG6{9I|~)wdEUhpJ>Q@z*2xp9jbMe_M4&;!<4&rUN=;mzZ6ocz90-MVC&Zv zS#bUNc_USMsJ;C(EjewpvK>@E9oaQ752=o)Av=JF-3Xt+=vqZh?O^i$93NY0Pa&80 z!!Oj1=NpZRCB69cDMre_()w+}xNE*{`xnodFKnOk5-%*o1A}3i$s2Z=kHMfzoLdaq zEwl(?I@x4b8sfA+bsnzGID&@Qu)!pfSd@-xr=R)zy+UCoLh$j0re3>k%F7Pa!ZF(c znT=Qu8R&Yb-!15NlM&b8oF-G1V6rS3z(VFNfL8c?0-sq|qE9eb0rEvenTQSB?+_{j znV}qL4V-=1=eD~-hV$#Td^%pGSsb)KeXc72d=Sq}I(U7LVSQF|t%|8+in?d?<+3jM zkRK%lg*7lA+<Upv-8H2sbRw6p?v_(9gsZ56^h#$>;(>r zEi+S32eAF_gohUkotgC--Vb(u$F9yjJgG9;NS7F6>F!2-iB~YvOdFBy5R3LrqV#)) zEi`F}zw)Ta!I|dDF)+N9`NC!vK2gp7zKX{oj?Cpzk=zbQA<2ge(VlR zk;E!XA6z{!zMl4i6Vr{*vbArw$!M|lY8dD}j+xT@hIswliSN5s;ykT9W|W`FI+S%l zg&?QkKMyYL@O$f>F>7zj(6KcQN~y+g2C@-YSprvo}-QsTd*m6 z@o2BiBcJbl9k2Af2qX0orba}|w`F6Ze zi%B?)@yM!RmzfT=3B&vB((-+TIKtul7R@J^7zE{OPh&)t3@l zm)6Q5mOc0THP0VaO7=$_`veHZG(srWy zzuxhD;LZvY#bcp~EM!S~*fOFID^Z@YLbBh%o&jzW3H9%T$^J=pb_xbwuJ4KqYsQvN z>t}j~_6cm1ez{4--22=n?5CGn8KcKqaCgP9KW{wHz_OR76drxN-FO#j5FvN!OAkm1 zk?T9Aj|*Es60kPOdo~Mg@ReViNIS3hr1cA;R_=JXqVe><-yGZ#a*(zR|m>OQf-D8K?s{gFoxAF5}HwIwlP2w!GlVm+vR z$3AF@FbetkKxZ|c;E*r&6fx-_EmZ(XZ&-l(?Am$)nhk@+ z!`+CV@O|fBn5s-nZ!m%qG8WkEX{XH#gwWPufWC9)63%-+`I<&Dvo>0}9?kTenX%-- zhWMjYPk|&^%PdWzLAzIpmLAUE3~YpJ6_-C#E5*IB>m18%(>0uppoh-sH8-yoq|#cd z;3c46)nk6ttUM~(9XZu*dac;EN_zY4UYF+kG6P^lD~xs#^D+6ipJpGjCfw#;tr6tm z4HT;f6vkfS9jxDBk~w{EZ^yqwW~lnGPf6TK9rDbtu^P8^0}n;B;61=)NDZ5rq%lwU z@}asiduU(8{D&j6#XASyH7&5hIGoc?sH@}PvDrot;~fRj`mxG{$zwx9;lp6?{@iKs zc-rVV^v_qyM3Cmj_5yKo&fsT(<4NZR@{^~-DvKRn)=srwGdR~}Ht)qya$#}spQ$8H z7tn`&8B8v=i2ZDq!ok~g)aAX;wtvBG%e5tm;}vQiQ(r&&LEDB~B3``o2r@OYg4KSh z^GN=aH%HVZrt;6X4qCqqBFQk%$}|fDiYA<&=_AOM={gj_+C(8CA#L#SykKBfq9?9G z08svPlZv$MA?76~a;Dk`&3=WC&|5OOq9tEcveD^;Lcl@?592f#s7LA#3;}VdBe8o2 z=_aP3xelJA2cV3jCHb!lZBNz7r~qh<~S_oUU61`=LOi3g%;(O zIt|)u9_Qp#1|1WF35#_Yjug6v>jZQSs#9Jfp@*8J;fW3YCN$;{u#c-gA zQD;U=3q-oFG#$_aG$;sjt15GH$`i_0Lp9_W(kRsf+$MVpO}XwN2*Tau-I!c06Qg+-+77{IG4ncWd(Q{5CdF?t>VNeybNA|D>a9I2Fwxhy7rG;# z+T(ktI7Z0e>t%I40Cav-hJ|8m9J$ZI>hsZ8=O`Olb~-oW9KyrH%t3k{?BotK{4mCuMT^8rT^6G1aRoo~4$cd# zYuH4CuzsmV==%0Il&`%2UlsZ^rXpq!TQ4Eoo)+-jh=Y0c0qVUd%c7#>)ybLeeCjvl z2T=-wsxgsmFZp>9z3T|57SGg)ec^Q6xU%-xbB7CQvAz(`9^D^bfdcL@Q4LS0gHn$x zB=dvRq~Z`+U`I+bs26NFug_L|8w30!gfJBV4)7XHu44VueJ&v+QFnH~!@S z6TX=X$i(JUCtuH#l9NCPzf_Uv`ioz<`vhn-fR?iKhK8BYIp>iS@3z{Bn+R zprjpjm?#vAQpkgyKl1OJ1dDT^epF~b;`CVSJ{C5TxZ<-E^boAYd*c}HeD8jn z^GjP9DQenD_m%ionYC3=&Di=v*1F(`V>-TegPb0XFEVbUEz;5hF2OfBxfxIa0&r$E zYgW$bIg4vx##{*P9-BjpdjR{V>XZ>IE`jQzW}|XiM>J z7`Bxq06TcTk}{87*+yfhz?~c^F2~2T7tz zs}`XC2GyAadN^y$?eD^TMk{iiW>ggcsg7#Ad$6;lCdm0=wa~?I;aN3iq4{!ULaS*S zHgM!mr+F?9$25Nz92XdFFx7|vGs8akMSBNwETCi-mQ;k;qwc3_?cL@tM9^CpDYLd+II8dQU^*Jordb znSh={_kj4&LPBqkrpgVs&lUl1F&047{v%?kJKV>5QVc?T{njQk-QW(iLI2cdq93^O zpl+k#=mEr8Z93xcIotC**u6!8E~Obfh%S^B?3Z;*_X8u14{2)Dzea+oDj=FujmG$8T zK&*y|7yHJM)jud_6C!@L@IFSJ%$G8&e!I_5VcvN6EE%jNbNoy=z|NMu+mv|XF^u*Uj? zuaQXipe2MFZpXf2F^Yb`$*UEq=xNFJ5N*E6GCe2n;n3sYwRy;>JFqV3B|nWU(;)@^ z_|6QC?l+uFXio^Zh|&y> zgPY*3Q=^CAfR+OelZ*%;#K|}&@``mjovIlqmAEG4)ny7XYpS!rdsOfYOb_$5cu%?0 zXOdOpJh|&&e}YPwdWpq1aO9FEd14w1$;XD_y2G~@+v|1P3oH}hvxp3u8>^A^Kb-gJ zWhtcIL2k6G$xM|~B^Iiuj2dQu;UmUa=uoxm3R;42D1f&Ne(OE`A1rE^{0k7po!BOfLv>%?gg6KzKlL)gR(NFNJN0 z$4oIY;7N;W^60N&Huuv93b#Vqi&X#|L?H3cH>XGkgI(Mulc_XM_IVL_HeF5-6o4%Kw~qQS%z$_gCH5g zk{GLY0VOQoJHAbNspH6mN4ArmshjOWFo4@GLRUJjor38-4jYY|U2_LLLDeAM5r{J% zs=S;F|IYk`z8Ykf3}p{?hk>kew=CVYIyqg0EPF&ABK}OzlvIjmsL1z>WsvL`?V)Bfxs(ygP{z!dH+3Rx%gZRx z=io!8E@sB(Q;%sGTz#~f`*lu@U85V+k6%YlMAE8yPFgaQ zH!c47;VMiIh4MD$Y=(9;T)23ubZVY}`4-+S>iQtHUSRDP+jhKSh-X@N=up}jGxiZ2 z!uv_TEiL>)irATvJ5>MT4!;oyO2mzL8LO-g-&G*djQ3a{xkltO=>s*BWZ$>RWR(la zY(vy%zM!$`LPqXIT4)yxhZx6@T7~#QJy`6Ip<DpmP=w^V+j`AwqzeM{jCcOy5q1K;pR2~Y+k z?pUx7ijR2KzkLkqt@;iZ8RD&eRZsAdcLNMy!Od3xE>p?x`oJZo9x4MH7#jm@>4rpQ zP+?4hT+sH?IvBK19s9VzSjJp4g7|naEl>v7_6ozJDJq4vA6c{AvCvB*s9ACp9I|X? z2P!hYECWOOoUNnK84-Sqo}i7GhG~ZG^S9%e54)J*!93((m1>+6&`D6dE9Cp95_7%3 z6aafQX5mE^Yjwki`Xl+t|J9ePYDl^i1ICxl#pO)iV7kzzL|QWUtg^Em^1_u+7es+8 zb2cY1H&IJnNjV6gP=^Njy?_b(0gk`0!ktT+g#+Y)5j)BaeG;5Dn(=(OI46mMWRd-3 z=Wb$Q#U!v?_pAEP-tr9ksH`+|2+H=I1M5I0ztnXW2)4={$$02x!vixtq*DM^)&wCc zTK4R;?Y;@l@NxRh?}U}RWeQYiAAwq5 z;flGvJrMaxg^P=UxgtbG#hZYY&gJ102ZmwysS%h>4FGr=lh@H+!q zpaK6up;O<126IxJYhM+`#5+viiFs(ipPsP=r~cQCjeSx=Uv^k4_0bsQZodI$4}?)f z^C=Y-79dw~AA{RIeKUCJi8!uLHmPdFW0PnQEYt4E}DcN!dF%^P%U(6}=AS?Wic4;a9+Eg0qg( zBVIg_2XDQnm+zg&fNK-0+f-iJ+L(-B(C_|%a3PlI+TT+k!7lJr$*aWsrv_;AN}$Xw z>;A=Y07jK5^rTe z{^p3sNf1L5z{9JXBwATgB_Qg4>i)}nswbTCAsRWXxfjqyR?HrUCj4BPliAxV!2CXE z#vvl|eqtzp-%*n$gk)?8voxY$b?cy$=+kF6LB7A`BT5r>1Rl;p3y=0iBUMbOsgfQt z(UBK)XnUdA{@*2sUuXeldkrOuFnx?$UG)wf5P088aROwMzBG^A&zyn+l*0A`mynAW zD|A;QsX@|rY>12NPl@<}zedYjmw)kDBnyCC?u4zcMBa>zPNpaevsecN)QV-o`DFVh z{?d$aFHHv`g-s^J=AsHkfnp#G6oZ(U9gOCj*$7(SpvHFnb#XiLI)>Ddvq5yV@YTPN z=^3Giha_#IeshxnV+N|e7J_N)NV|bsqye1hAo`oRf59|lZbUPEwE%C%1~FBDiGX6W zhdMic9?^yrMJ^LY`NeWwP!Z_tmjd}z%qm^~i7Usw&vblAhHdax4r%S}?IRjV+B?58 zOBu@U9Gb@`kGQZA`9G8e-#vG=bb#gNQjY#$k}b8qqdyjaZr=e~a`J5Dy(2|2%;8^kr3dRAMry24dL++umKL-k4DYl(*da&vOq#zwCU^jwS)k4Y&5zx1R zoNLA=^c4t@qr?Cx9x=7_=S21Dl#5ga`ool2R~pG%GlgsZ($ zAd++Bv>DOhFLkep4-qq}!HJFI2JXun(|U?xz#M@67uu4~wV2^$W&{TA@P-(f5kbCR zxgHXFi`cd*?j(jse zB(UqmH5Qm_Wq>}AG(7LSDd|n>Zh3Q+akCMSH9v>2fA)b$GAlE46H|A!>rV2SOM_<# zcx_`x%+C=8J|v{nY?3u+D|8at#tplzrvc>;&lwKM2sP~VM3jg5( z{BNy#l&<;B8-_fM&J1~X$8Y|4Yy(8Rf`8W-0_S+l}lFt9f-T3emwTjfAcF>@6mgm!(!*X2Eqew zI=`W%Ia+`P;MX=fooc2RAikp@9pL*R{)So^57#aF4NMNg6GK8wWjU+d#b9)>mxboW zne=d6An_J#>TU&R84F`SfEH7GOmq(+#$suXu=wv$;VakRG9i?osx8WW=l2yp zfp!&JGr~9Tz+lhmHe8ASL@u$?2z^qDhyeY z8n(;f5u~6?aM1K8Kx5Gmj^$eQQ(sc6$tludHE)| zTkyN;Y2ii6eUXg0ag&6ClJagyG+L7e%;{KQNFh4wPu|^lEZL!pmFE!OFE;1=b$JtS za{3#bjDSt&7!Il(_nMt%DMcbT)JC3FMDCF$zB45e zEwL)-AXHJJRk2%hAxbQEz=FE~d=gGnHs82$qgO$SV1M%W`Kx~ppY`H$7Y#^Vi8WJF zQm|;^b=(AKQfTEdo+5aZgT@7w_-!E935(2O9RQ-vcY~%C9BCWTPAD%#p`1xU?8Z15 zJ}K!?+C^Wm63_O7+X|(m#sy6g z1Ees2gp1E$aURX!GAOb-iDB%>4}%C1i99%T8bC<~;*X4w#}2y}Tb~K9eLXI=A;<*l z^-)t#?*W*-T#w5#ttz!`y0`~pa5$>WDnx(mkwjo^(?20MZUTwRm5-0^#1%b+Ql+Sm z%#;n^hZB*AU0a?J0CLZBg)W#(av+SAk9r2P0b7gu6qN|ZLNKK6G4-n0oV5j|~8YV1YfS^h_ zps;TWpkn0TdL_)l!PI?eSEM zl$q3yrTpu$$LZTmf0=ka{>ZrkkE7x4?*5C(3h1ikz`{(HMim$br}1=Rbo3>Lx$lu? zE}}Fp&v8uqSY=%5Cqj)34JX7tf~ywbigZGrSAHLVaL;!qO@ZTw*2j;5C|#nIYa6gZ zlq*C5v}VTmEI{Q{6Z7D~H&;(+Yb71~&Y`7(2n0em^~z%nbW?d021hR)ffN@yUCnhB39Efm(9lfCtM`kE;JiB00wJF z;_iE8##9|==Pv4KF$7dE=YsQM=k!zr400Q^IuRXKJC z=TB0cdG@ydKfG?g(@J3}S~8^a<6;F>&2T69ML3Y^xs&xmt?79%S&&f3LC!G8fUBic zXjpOYU?&+hwRG(bkN_=6-rI5a;-Ha)3rqSoo2NsQ02t1Mee6#;wfrr0n!#Ht%e5MHwhxV1;az=*7oife;wxo z69hy+JOktL{vrf4i@S_q&kmqGT0QrQva~G(_g5qL8#2LL(8>UL7;21!4KI4t};NLIKAOGr=veo(&ba8w~kIu2UpppcR+rM@dFNGoP7uM}=9*#w$ zzt94yr9j^U#<>p>o3tbuk7Ff?*j!CRodECo{6&@kNRqGZqG68>-7DXrG-moBEiC)1 zZNR%l;7KI7x4^x!8AiKTNmE_*l4LpM10LwGT`PK374(+_(LwrDp zKB6a}@k^Zp)`$UxZX8&jY!`C%({3S+9oSeXytBbzJZYM@rX^Yu6is!14F3=tXnvOr zfTGy$J>H1w9i(A_*a*O6k7s+`L;3{x8qCNqFHa^P_M{k9dl&J2ML3%d@ox&l-{}sp zLVBq7<3M7Qfa&}p1ty{vH8^;bMD!>N^y;g>A4Ll#Js6;YE>xZ^71}f~E)xNqYo37H zpad$T566=Ck%8O%O>}CJ6C2wDihcX;-MB#vlzlw9AN5X{Z@NiQPznQA{ifNp2~B5N z!E4~qKuzhXbXsD5Y3`51Y@$u_# zbi(?9b~x?I26#5A#9R^}k?YE(jg1O`F@n7J+{pC@4xnTInUc;_E&dyYYDnyx-h~vHo=HB2zBlffspj4FAg~$-*fjC-x=c^be`!R_e za7*xR6uG8V=V5lj3)W8Ke%zgZUmb7}0;Y|qXO;&mB4>UhgYdqJ-1mkPpL4?3ej1Tu z2HM?6u5&+~CkKx7e#$Z}m*o*5bfrw4LMN`c{5Z%X69`|^e%KW7lC#HYcaxJuz2 zz5X6EY}G?sY5E!aFUN~xH7qStp_WjX!y_^J>5cq@z*E z$wJ6i21w8>RX5>7H{G#|q5mtZk)6Yi_zho!4I-ytOQQka;5s>m%p2J+#nJ%z7Y0r3 zmYy@`lM@piuF@ZZJ^-j3RGO4Ar&7{!0r9!X(h}n0+9aC5R65n9^BabEiQq8NM;>m= z=j%(-Gyt37=Ht_Vn^j{Pbe&A*497aq+;f2n2+|6+g|O*?PyZE|Bj@lim~2HWYoSgO zdnyBr`3hJrB=mUgCbOBX{Gx#y)W*$FBTmlS{Cc5=0|3(+kG6qB%XU5~l_?7?k^b<^ zK!7(>$La4fbL1v&DD1=KsQi=c5#tiU%sA~6DM1hdFVI9hfK+>p1R5ajzNcwp?Gat5 zg>(8~eG4l~ve?oEz$CMI{nYt9RIqJUz1lhW91n>>8ODuVDr#GMRSmfc-RuFCbib zD*C=QGlOu|nI~P6Wm+)f4z=TqvQ~%Bb*cDBoG*S9RIV_SZ@FV0xTMa2++oU__8s6l z>{mJuAm=wSB#m?OYC*#uWEu^yj8Oda_U7<*i_-Qly|Y(=9dr*!MjbI?^bF`_yW^o7 zX@e>KWzDnfZ~TEW%f-XfI7vJPZ}h*@ZbMkJ47U9`bsvAI{$@e+!YOA*0Ob*3Ex>UV zNQy12fK_se$f<>vl~o7kM3?3;A%~qqpc_Te zPtHUNKu>#mpVoU!EF~$HH^Y|<3Qh12No(G8H%@3$J%Y&d|CXaNCy--O>Y)1rp^KL_ zub}xU?E3C-v$KB#r&oGYt}k7K9^l-tqAGF%&cIQK0o9`$xOg_hQf3{}?qsa{g=7C0 z=*+}*hubYQrk+ybX0(ksko1H6IaM{h6}&V^KsYRR<6#8Xf*cstmo(&rt`>kasKYS< z($Y9HTH1kZIsGqz!{jfzvW@iW9R?yNgoKM@Dm16C#I2PXX<8cCRatc!s6nrvff^Kr zt@OERqezSx(21{VhN^h{m_@~SVO2fU5#zuMk$n2ZTsYsP;)8e8kfs$X6aLvJ{ZRRU zxb9$BfWsr)5OA}}P1?&>-x3pL*zWp(5qtM8Yxk3+k9^7+8}`WvH5*}=$KoGv#YrE`z5TluDdfTH_33b^P= zpu*3Lu|>y?xhlfr=F~%|36H2;`1W4<=^O~Ungt4~Ewj;JfESTi8ze!=0|L^bbGgL9 zsO%2L&8ka*?N3Lbo=Ma17K41x9=E@qco(=B!7SuC*wuC@nTB+iwX@tS+lRrU#dxCc z4v`RwL10-Sl|G1O)!}?!Xg%@R7PSlZ2V)3Q6{Nu{g=DB){7*k{izdR;n=$Zf*Juid zx`YlO1}98yz+)X@e5!cS(NgmcM?^?1Rpb*jHwj=A(pF5YZ6j|^q392gItK!N%39R#>cIFDt{B#W z1VIvr1;HxG#ifEa0BcMK(D%~6>i7$gDvUyTrO4`qg9ORGBDigU6xuwoB_|=e0=4Yy z^n#Y>&NpDFo08RRD(83W)-9iKy*lD<&KwwWX#k+SGs;4-#Q-gEFvz;5ZBAyZkEB8> z&b_xnLc%=x7v0}Jz3A$5jrCjDsv$&&0ZMcopF^<&RqfNcH~S;C3D?o>xe6FF5sF@2 z4ES{AEP^2z@Orc_iI`Oz=GU%$=hyoNdE_40!`3r2rEA1m19`-NjhzVn{V%yvNKo&{ zG$;!x;-nf-zNmSq-2SGQ5iuhd9*})jfx5J=%Nf`P0)TDR!(qapqGwl;EQ->oG>-#g ztZIiVr&*1!J{=r_TmGYH%?q-y4G<aRk_ZW!K7_T zve&djegXPB4uH<`%4Z{XbZ1g-)PpMJh;#MNTP^8ujuEvy+hA(j>WAV;TJH14$j2Ht ziIvqc9eSZ zZQ5#q6>njos5N}TeI)8m&L^*C>_D=+hX(9zC&__N$189+}qUxQ7 z9-*?Kri>bxy<~CA3%Zv&r0JcWzFPI{$P)d;H6j1l?p&X$ix^89=qeJiKl@5f#rU?Y zEoE5UTAsMXRo(=CLQINLVoRyPD+so228=t>{LrxI7qk;R04%!7`Z*UB?t;T|3!r8P z8&c$+UWGaQ;1^3v_{%wHNETlWp;8M-L4)&4-@pz`pW}JqWx@yh{SRAZEPely0_$K) zDag@e4&$%~;S&!vj%feM)cNF+xqY(}WIEL!h`nki!^jCE_Fb46KCGLs?{|r^cpOj3 z#k})JvIm!6olt8!Q!}U?w@y1}hTmWm;Nlh1;g=BC4i0BgFt&_|<@Wia(pl?{t?ws6 zu6c!(skz(z0S#&4`OTxPqK>`iO58Jo;#v##8)0& zKef1d`S<7eD|UH@>}r`Aa%H;>Inqx(rL^??V&lPNMfVS6A9+cNgW?5RE+q8klg}Ez zP3H1?EdP;!w5;BQKNR44VAF|qtx`3%&tqNt!lMg(SXcJz`mI+3SI7M0V0lh7*^2n;PM5oL;V zyxo5dy9vc1u8a)sjL?-J89=ZcNRTR;k&*H4mnq<*!t$0^4puy(#2Xq|5&jOYm6#a1 z2lt=07#iE1D~tWeCG`7HJYqn~3vLOCv+hmNAfs0YP!g#b#lcBdPq(d?OokyVJ3AV} z=mBXpMsilx^!E=Iug59|a%Lx!GGVs(PH()Gw$#yz{jxNr!_3l`7J|lGSM8q}zIvs- z-bqB{Opn$xpfypRmj;1pf?Pq$?8*^n4k@AU?RD@n3N>SCx%tb{=lDaA2V)GeN~0As zrTx>yK|w)d*_n@GRD`D~N7P8QcEqdjhIS&*+QRFa!Ebw44b>ERg zU-zCyFP?uUp(}s5>ce8t;F{)4{$eIIfCjbLt&7eYy2c6T*yL?1AKvar+ zj20k9RL4_c9dF!Y%(9rkPhNv$Nv zkQ3vvv`6{*#rZ3knVGAqtq12X#+D(kf_X9bopP+65xyx?{nW@z;^O1J{%3q09rLt0 zZO{1nKlOY-l>z|5>OHKZQM_Si=UuLq%2v(J5|4P%m+Eejha?({Mc@=O;gOv_TK2*G z4)wA|mF{+lH{%l$_`zi+bkGmXBJYH=E7iXJV!??Ha1@DqW;m?>`Vf%<1DsUm!;|Zc zzpvNM%Olgq2L)k@jPn|ubQz@gy=mH&v+RW4=lTW>D?k=_+(%w(T4u zx1(ri;7`G?(||#Q?enS}o!APPo^uNezx#M{f)Ivj>M>AiyAk2PJ4T69FHeH z73`6%l)Urhy6|A#5htsJOG3zLH9k?u?!V=EJq4SXipx!gK@&dg%?cdw%W(| z5-#hT%4)X-gJpaH37}RR!cfp@qA$Q@JmuGeFIB3;9C1**6l{YqlIN zixc_?Al+E0+g8{*t7C|?P^(u%)CjhbggCVeLnIglsue)Yow#T~tpFsEC+bm|Y|Q!R z7#F$*!lz;(Xs?gi9kC^*v2`F))3cYnMYMa5I?QA)hWz6PZ8A0`HB~v{kgVmoFWGr{ zjvtO5J9b`I<}>kL1pOVO9g*@$6fK+Lg3vDzSg%(L{VouN+$T~rd=rXK*!1E8AMV28 zv@pgmO=AZH012F77xO9BZ&CQ2Wm9U1-OI|Lvup*_bz1o$Q0e8jR!7VC}h2zq}1Q~EICGv?k^ZrcI(Q|rD4u}(5QfQ+JJh8VrPLD*MxUCTW6W32% zY+QBTvFH0tX&#vM(1D#)X$1?IAsGupS8hD)Ditkg%{WO!N+7=>!>x zelTa{=ii5sZpSnEwHn8RVwN|6((-bhS@{Ox?@>IAb*s`#;;GyBp<{}nX7zk*-w{sE z4bMSAh@$dGPG2+=?&j9wy7JR9J10vtnah5|8?j!R#jLc~KM>)UY1+9OfgvZ81eNfSIzbi-n5JG98}sZERU+@ME~L;z=1+0kPJG- zj)1I+!w1BbUiwMq9g7MK_hYxA$*VTD03ovHo#&O@ZvpG7Iqnp665@koi)l`UgMpW0 z!t_%);fGQ>p*`EfzeB_uVs$5J`Y&7e$qe((lT%T7+D)|~@fFJAqL~^qCa-(wTq92G z!r#Ie*9;Oa@zQ<1aBi92tS@YG9?x!Y^CT>1?#A%9pZC~XvevE2Y|8bcdLe>!>PB!I7U9d_6CB`#83uBF{*viB05eV*pG8NF^iI1h1bwn zu7i|82i1{f@0$Q&MThkN{^Kq4Q9eG}yf0>EW=;$=pvgC1ApHzx*K-fyJ+h_QSirwZ zqkxU{#DmYlf8Fk!dO9SeK(Yx{K_4+K|4x-6fEV|dL5$iq8wg`qRmCMiyshFW804Y)}fK=82ik!M9=SC6vm{(~?ng~6;bvy1wdj+=I^ z{sguRXS7x0!{w*DF^`zCa&zOz>3N!g;$tWM5$awvBEIH8W<0Ky6CiaJbUHDxYxLA{ z&*_Qo3YPzuRSG(pb83(zHh<H@2rg=op&%Ut z!8auRH?yseT=q>Tvv9SA?=y3y1IG}?{@$277wy|o@q1!4=@16OFoWD>=fZvh;clDyH^XFOVRYIETZ#2OH$oxB+G77{29`+}Ha=(?KQhY#tN+X0=U zoN(42f>!sDOb4O9yMf!%>9%fyTA^=W!TU*YwTL*c=i9jd3d^1OeTiE-$h8gVp=CaP zdv>n2pbKEttxzIG49kKOUIq9-*#K27>VF$D9FCd-E>1A-U05iU;!grDWdZV&C5m); zuVn!9hv4osJo1ngKp-Blz!5Y)Aq5hs#bDbPrQlzgos}g@*DrNl$LrbzAnKnk4G{J< z{5df0*H#l!@|jyFuiajw9CxSiR}=&0Y3C={Yt6;U`AX=Xl@4zjA}5XT;QK-;iZU|8 zq=ab;1X3PMObVDs8qn8E&qxBhQHKjrZHd-kLS1VfS$@0xoRB zk%!b)3nn4$-}7kuyRLr zWE)c3w+H}n?phs8%)C##F^Sv=|~k-(RK9B>IggE@z#JOEmiPD6iK(v=Pn2@(HGC}?#c zR{1Yf(@J5;iqo)0M)AOpdn=65F`F5#3zR$6*hR+CZiXR%4LT)JQBk8G2mblzpMC-D zuLPWK4u|p&b}9Ps)c5b{z>fp;Zw%0#4E?5thW#H+?BHnQ>L}y<*7L^FpK1Uyl%cgx zM_u$8xJqP%atppeEw~G~W3jw zSDQmb{h_3W^w(xbQ`m!~{4nW<_mGgZ+~Iws?r~W}-u%W5950D`)lZm^RLQF%Rm)q` zvf9*ysih{E7kvDK<*&?PUk$s`GXQ&z`wmXY&VUgd_9_JFN@0{s9TakbjT5 zTS0Hxd-wgcX{R)_VRE6DWZUTsWXy4^$E~HhyYqu=u5-iHW z{%c5w9`W2DwOm|Ni~ds2%s^!P;Apgz*BW_4O}tRebyUwQn;*^lS&0OpW?2``OE92$9)4 z60YmeHQ@n94F?h9DbPRtEHlX|Uf7de^^Rf`T~#u4RrMQcyx$(^{NVg>}3XQfQNUT5jk#l~=U(DNps3h*ss zyQbN4UiCI zPc6W`y6)eLPf)qb?tJcFaL6_S$MZxE^wo7gjBEVCY*{y?3WVQdFw!WVdg0I`3}hXP zYsybV{$GVUB}uV&G!sX$V}diXnCwtiMWKZirHyYUu#;^k_O6y=0kVRX*az>-a&vQM zwdAQYv+Cp#`w7QlQ5fbfHE+9P%xn!%x4OuWql#8ffJZv>s8@) zneB~*ad3~Cv*_CUzhEpX22YFpjtTB$AHabzO`R5wj-M8Ux#8pHDnQI2JWK%Rh^Ca6 z&ea}bubm=dg%a&BLPom>$ln`(j{WM7shmRFr9dMkyYHQSNh^fZ={0w7BF*}ce`jW= zNnU}hw~{<2XeQVoyuk`dZ}tD<>%Zf<{{H`QJff1K%qUT2h>FaNiZU`HdzC0#_Fkog zP-J8$*)w~qM9AJ-AuD_D@9jL$tLOW3`ThQQJ}*6=<mOVha%DhhicMUjqYxCO-U&Jte$_1lU?CD^EZQJrQ)dETaD$@MWMK#K3en;Sivv{1_oNYiHeF=M_+$d%yK^l@{VAL z95$Yw(!1{qj{0L92pzsk79Gi+lVK*FSK;1(FeA+<2&N~neNRfW&%y0p!5zR>3UwB0(pl=ocBL`l`Isw4K*#XP(k8c-{tB;-G zIbn&3joe3pq>A*pUY!KI*##vHt3ZUW^5M9&KLW&*%&Rf3(#$DI}B4AEC!!te-f3<}S#71oqNay}FD#(V;|*`1KIw4b_Jq^&puYK$R+gpq`Xw z2QBg3-224(}uN& zH?n`KsH!^5a4h*&IUx=_aUY?q3dC2;;?Ojzx=l%=Drmd3_M z&R|ma#$)iV!`#|#X;9JUO}2ur!yBN>=G-N@gHQ!Djg)RRua2Qm(|_7Dgpim-XLq{y z05+?UAdLX_-TNRCi9|1YE^4qiLG}6A9IpDaWi!y&2?VfkciIeSbc_^Ers0bSwxiu^ zdk5N?XJ4aXijUBvAEyd{2r9tEzANUp`>kDFSB{QJI|9dm_~LoJ9=Hy404uMZ*?CW8 zxqk$4!#kn)ufO@%MPl}@8(0^M!5B$nQI$6hKs|zm%wJHS%uyar`wYJ+P~L$bCs>4< z$d&C&{WgU!QF8f&S$4k9Mq8s;+1F_+C-I)%jV}%2(}{`Nc=#MsGKX;}kG8hAOMt1@ zCIIzwpEXr1gHqn+YD3PA4Uq7gS_i8ZNl-C8f)OWk4Z{JA@C!(NwNKCfXA_cDgt6a~ zmOIBVi;0R1^nj&wd)?Pud==tu=)$rA@NM?v$O)EzA8giDSW3$0%@ax}Bi))PAjLUx zqG^Bwx+EDNj=+2bdd%`Ma6qBae0A#fVa%E7K!?7rnyQ4EnfVp-8K`s2_`(_DLEof$ zHLNS+Imp++Y`gE|(Oqe_>`dX$8#Cw@x%a2*A)f{2dJJc63SfALuE*oJoSyT4vKp*c ze~#TG6rkhovkb`e?uHm65@pJ1gf7mn?l$gD;?dF~2@}61AHP!G(z*{t2Z2p`F^Ht= z)Q9teYQoX~AU~yrg;=^lUmGR!apdL8f4YdT!Ubc7E|^UmB4`TO`UyMT0Mbk;2`MRs zOthtU7$9k8@chN#(l^CPN=_C{7pbqSGk%*L{Q5Nw;Qq`Dr6GFj2=#d-!#tr({F?huttf zK$?)8M6`E~#XZMw#8momGlMZB#Y2?Mx8ft2FT~33b{jLC2EfZ{yg#8v`aQoJqS#mZ zY^Yyj{%RAVRaiJAL6&z~YM?_sTknnKL~FGa$7OK0+uP)@8&>@>Glh!J4$o9mHIj1; zm#pESujZm|g46a(7(Eq>2uEESCuZyc`%-p*w=DZJA^g^+f-rkhQ$-0t$|;}^J-)08 zc=?k0=oYqM3$>f7sL4>TaZ5{Jd@OHXd=S~694x=}QBO!cAyaeGA0uV30A zR~?f1!GGH1#%}&W?N;;SP9~emc{|hM2c-$oG_;=utS9c_N#5a{k@0gSZ}j?u+Owd0 z)TOdHZBrKT>C+YDeLXd;228_nxTdgX4x@cONPt!H-42qdN{7f?DHms81Qa}^to%cvS?K6s!88&IIWg zRrZY{hWtrGW2J7OyQr-JDybm4o|JVRy;rs)$nm0b(y*r;qz&vKs{2rt>~6=s_kKbd zyYTB4Tmho^#GPD6Umt3J=+?Gg2CsbE#aHDVWX5lhE2&RSb*>a~SSMwck2H1*TnUN7 zy1F0dv>V#u6nZC#`wG5vDO_C#*aHn74DAIlpf2WRF>dKU)M>$3c6KRfE z;Qa(~@nED$@Uheq(?)y321z+163YFG|7vk%%G7z`G$=wtwB4&|XbvDO4h_1}ebU=0BqMtsZc|U3I;XRRASR&*NnX3UV3b-|OpxpaY!q zlHuC5-h|(2)zdJ_xJdcz8Txn^VmQ=mkMAYx>zyxB)ayuxVzZ8VIGFYY0aeXFEZL+P z4SF~iYydlGYZTr?9k$%q3QIS*k0lYHaQ7g)U5IW_lLmidAQ7A1!2-WR$xj~>i7<`h z4xF>#5AcxtSPvHxS%>RN{j@uv0r%rKe7p^I;esh@iayUEIlELOU-$IH3I86u6X?&F zkbpznhcPl9)js6_p{2O$XcSq>)o?i7WCQS)M58p{$}1^##569}jIN8=SjX#~Ja-tH z;8Ccd-R;>LadRS|D@V=&ygHOw!IImHuQd6kqG|kYC+|LsEV$aE^4np{$|5|P1_?KJ zw*Eb##L77afp@}r?!pxis=fij(Tqs{|!K?<{tjU#` zQpjM-%)Ty1raqYB-wD{p1Ofd5B!~W^P3;zDzI5l}mNq=^V5>^YU7Nc-*8 zgn@CP{X2UTOUkkXM?}iHBYk})C>zj8l908jnKM3W z&s{(Q_RagCYl&nC`PKh`j^BBZ!aH*8h$0eC>ENg@3!kj$c!wHtd4_zU`(oQ@yCq$G5RI0lo62cDk4x5j^VV1se` zYdsHvt=8Tg8K322YY*m=Wk#TeuP|BdK7%4P(-9~%1&4O-KHiY;;#1VA%O3M zVNkv)P*4JS4WL$HJL8&-p>r)ld_4Rrs%KZ$zjdgF(Bqrr2Q*>IxXr zp4pgSk@snIcaI9_jh7;pR1VR1;aiO_2g8612-Rk8h9+RhUIh}QO=4FF+fe6_FoEO; zj2*p8m$QvgmtNH6aLfOBjc}Zwpw3meMV-XosFHV7@99G)1)DyuRRB+LQn>&J+}iVv zeWN&I1l{%P*W;?784fF`h~**!qTDHOp)K1pS5;YAgU1*?xR^bbMh$Llx8U;4UD)VX zqyAQb=#w~c!aqHzB_M}=JJYRu^u(LDbeDm=D4_2T@V3?9a-dJV>PUSwRl}10_Hh&p z!cOmwY&wrzgSpTr^AQRDV7P8;L6Xr8Bk>BKi8*CBA;NZc1)1JYp!I*yXoMBK>nG5B zITIFP?=EOGz>=~*#*uhGq1q?(#QmP^r$vfRm^fX^Iyh53WpA>N0h5*od33mbyMtw@ zFwA>kvs$&aX=~)(L9xQ(Pe`IzYrYu~%*yvJsO@u4Af2og+MXi}CR+fwX$`58`cFA6 zKFl@nGE=e>ad@n(tgO%YU7LRi48~ZW5KCvt({E`p2 z>vklt7qOuSvRuwLfTCx&xNu%`wrXmO5}AK_mo%fBKFo#s(C7=9y;_@rt*9EHdLk<0 zm2@XlL2@CcdKP-$Q>ACI(YB>Lx~gjK03-7=AV{=oT<(h145?T=qXIDj;-YmtM#2MC z^Lo1&1%%Hdq#`o3FB~pe4zUWx`7gNIhT^KHmW(T2o@@qE7nkpgarCz=lk+&PW&j+q3-?#e z%s0@*J4KGymIoMk$S+MpXQe+mY(#0D7p7^%Erz34SXg-XN|B~zR|d!^gqln#%gWLK zm`>j^e4C)%`|WvJ+Jjr?25~1Dc`Nayv4P|P_x#)K*=NHb&H~21&6c9?=jKpT(yS%U z^P3JgOUvi6!9Z+8ln-~DueQz{Z;+6XK>o|tD;kzfq6j3Pu1(*5yJ=I znrwVS&mfOA?GsQqI(5Dz7JS=3KKFdlE$PU z)xPFjeJgFL12O2+-I$`Q1J@rYIMG{se>)GM;L68N@G!ZjsL1yx{$VFW(P3QNcfR7N z@+^z2{cVm zYF6w?*h*P>`psJ%x`Nv>p~J?tG?9u&^+bQ-;*)jy%maw2FQFdP)+{|ZkQsnE=xFAd zTN5DU;ii@_dnxd)J4Qf0jcl~`Hbe}Bu7{6d zyU{{>axmOb5%L*h)@VFY)LAd&OO0N2k;P#fpQ#!%Gi`$)NQdU`Z5# zPrx!X3Y{Bsn0xaSGdb+3LITv|2m)iw-oom8{;DIc-}ccPmV>7PNw=lXKPP{8G+Hb(2)LRcbWgEmK*^&=oZK0gJr=-L!Va?9MVrWeQxI%WWD~2N@ zBXs3q=gfq#v6vgXhpkKWZnI=6-Mc3S)l4`uY|(1K+Js*0yYx=OCY9!0NtgQ>%tm!} zz3EmMN?EOu`vZo$7nrXocu{goBecyfSnvH7Zlue$9l}^lVIwLM(orTjh+4I8zMJ%* zvT|s&u$J)u&HDECXn6s=o@+PIe-YyA1;&HwLr-0drzo^v=Vt#LL!DV17~&LlC|Px+ zhrTvx2lViHxQQ&gr2>BEFh?;w0~+ky>P0@j&ZS7TOfyMIJ~(Q z#16Fz(E)mj7#<B;&f0T>{y0tJK79|$sDF>Gh0;4%tPst`HxZ^XrHoWTe{PC1O)onwaR#Nh^%83a@8 zOM;2@IcQKXX0?4nItk_cxSU-j01``htFG1M1SRRM8wpu)o>QTNCOydE=-jz;(td3< zKcFuRis?uErAihaT)%fDTU9uq2VB!wkT{0*By@fQ!Hs0)lU`E{Lsk30O;i9E4Fuww zEUrkHm`u;r{GrRrTPL})m#~_UGi{F1R*Oppm>+hTF=q4@lepsF`+-r)+~LfzPIEUv z*VRC?e(F#@5W+_wtLCCoChi;nd`*$F>XuQ+mwBsB!Pbh1f`z}AK z57%EW4KJg}IQ#ErSXIH8J+h5IdOkJ_1_b2*ofml0Aix65cP^4f_ZpyxcGo3T%RqKv z@Kr1X17V5Qj0X6d7!S0K%)LH=eZ&Pg)2+8{`Wj<#9@l}b_I7>8L`~>en%1Og_(@o3 zDuf4ZlCW6kf4`l~ATZ7*08mfl@J(B=h4z zh)EJB5TC?{%fMCmpj)?UCY#zLx`GZ8ve0G`;8|wM$4d-{Tn7B(po-i4ym=G;dtl>J zO2sxTw1bxjW29}2{(*JDXabSZzc8nEI_8Z-qhE;CI8{2V`y5CU| z_d;ta=2XuzI2Lu$=NXPHgWFL2b)Lc}w+6~vM40!x46A;^3W`DKj$Ua~sw3CU6oZ~w z1qi4qYsc8R*xN!ox=J5A&bSEr`@;Z0wz8{7tfsVr-;^F(fIzfE$h+EyO((HTPY&7( zn(`8tl2;+B^%`U`f3Rgh9X3AFz9xIseI_;J<=@&69f~)o!8!I=XI(|zspY9<=%Dm8 zi5~@I983s2kJ8L&9~??eyUr&yP_I*5x-a~{g&=JlZU;uq5QN3cv|TxXF$67-8Owy- z6DVsD&#`W3UZiL}15_Ndqj^*M3c5c#_|BW$a#jzvn28Q8TvdeWT6aV zH}Ug@eKGZ<6ciUg{_Bc~dgqsCq`TMc4k=S##&u{_iM@GNA=snfQCTGkh@T2jW(flP zi0E8%U<9;zKxi$hQ#8JKg$9 zoE^bKm)XyUkyaZ9{sC|QZ&LFcAE=aHS9^iWVloNDUq{7uM>$`Zh@jiCN51w8tY8ls z@rvZpnbl+ocjJ>>Ehb!zs>Chy1@}<@35FDPndjrS#vLPf~^=%ql7T0|Rx*qXi#3LNl_L znCAn^2sK%w$*s%a60Mvj2NGHpEz+$UX;(8{`t=>}KX+&Eh3Mx$vxUPy#04Um{$5@x zgc|lk6vZLN*RueQ$-{vL$S}a!t*@iYBwL#p^8w{9NcyXriQ-EHON+Y~xJ>d=$py^j ztY<4a$LD-F;EMQD93@COTw}2q=Sw*r63M>F>d`?6ErQB1{n^VU+J^Oi{59Ou(%A#S@Jy%E%GT z<96k4E2Q!1U0xtFZ>m76%tf#$1s=3mS~wt;v#Tlh`Sa%#J(Ig&vCZ4U#OD!oHB2#~ zIc%FM0f-t)=i!cEg^7zbpEQsw0XN+<_QB;b)J8sGns+{G=^t5r<~r^B8ax=)zc*!! zFEBgx@*5U@kpAjrc5$wew;6yjh&BpEE>d#%9RaB?t7>)v{Y~@z!4}SIOauvL3shHP z^U6|w#XP-R-=7ken9926)VBKt^D zjH$>LU~dGYy)nZ0au(j)4i1Eca{yDZ#&4k$l~Tl%c1Kq8Tp98^7>ha>OM&{sW!R+J zmITH?(tb@5H!Q18^u(DGgeX{aJiK}1#w$9F)L79gj#<)#5o%1)cp~dA*NNMfl7TMN z=X^;>NNahzuP0_y0oL{{%+!KE0Av0&kcA|^rb7yb(O6htnxtoBtP(S4Ea=mffx zb>e-w5thy3aZ06#;ci`Z^^SGAjD1J?@v>1bdsACZyT`}YmD>%DL9K9_A+y6JeTR^e zONtKU{_|UK$8pcAUhKeW*KT3ZXDg(M1H zfR1;gXNUX{HS8^~t@Fd8NMCXBTl6bq;sK6kiJIgVsQfUSOueOUz<mR;nVT74@QlEUl23>sNfPF>f$cTa~dvx6~v@?lK^T?IEpf|y ztH>9^Z&i}*ptF*?)4}|^FzZ!T5J<;ttjw&Ode4v-rm-4Ne%#>4aW$B8A3Jra{Gr*^ zGa&%Bd+=zlhQyYRX69E*kqnlYo*(&bm(*?mXK|rA+F)%(L zFu>pcPV!l2beb+(Pqs^CYnMPlu(r;v81Vk;<)ZCJ8>U+Y=}NCVlD3bVt{=K9ztb*a znkqe=GQL2RW7x^*d7J&#llDckxFQ_eBv7sHO-Pzf(FMg+Qfd_3tqc^Twlo_o)Hngz zb>kiHZd!3f-3@m2x6nv7(PYJU=iN~nWB#c^DvB+L?2p((J~wI`v{F%z!!(S#)Ps=P z3lL-`pGcZG)h)o_aDMx~#ockJRyFCPXGlY)c*Yd4i1+US%&O&UpyaiZpvE_p>|slc z5oQwl4i&$G@D<#wi5gi*u8zxwG5A@5h$0y2_FSNh!ywIt2OqnELWHEEVo(*2^HQ=F zFO^!rZ7!qE`yGt?C!rI(w40J<>Wo8ij5C#A>F8}ujKz^33aLw{?&k~DVrOd9F??(c zY9hBru%((!Y+Kx|dR(||oKROdwLA@Pg3{${ocJ&M%TKf70$BkC(BJ!7eLB78r2WR> zUvzmzj(p?$=3S{Lm^N1*X0mCr>aty1nFx7Hha?gO^yOF{9ZR_xCSkJj_6zdPfi#c6 zgBmpg2BlHm=y>-&pdRNzbFu~@o(ll(2l2_3J@TM7hQ@~i92(=`E-uJz^|s%g1o0_Q zk<2Q&sRM(zSuEIAPJ?tO&%@b^cNKisax^itwVu>-+s;>o6eSVf*q|gX-fo|ql43NU zyliOF;^lz~la{ZR^=N*w)Kp?ytlmaXrL~ZOKGVTN$DZ)1gOWA~Tn(i8u~bh1nBon@Yn$gidf|ZolLXJq zmQ1JsF=?jL59TRD-8C3I&aIk-W~AYb+qVqc-X8F9cRvM9vN9n!X`0lcxpjv&YGPsk*%{T`yz_+HUuNyp;b#%HiGWW#A-JU$!_Z zmYR|j;;v(ArM)1Naj9kdIDczftJpS}A}&@l%9TF$Yb7C*5Hm`#JjEkhsA=vg5@Gh@ z<+t-)egco^`V76xruoLXEFJ|c-22nVvSwO#ksd6C6;xE@D6MuxBPH@O3Q1tEh26L?Ge6o#y~!NCsaEk76( zDVo}}dwF~N5Ju-1JY`7ga9IkTm^kaUr7P>-BajH95xZY+&`bCyW7JElIqeG;83+BR z=0bT8IadV6E;WsE#yK_H(0evNOdj1%c*1JAt9hezgKqM@$16HpV*!&=73kDY{Z2?u z3raam{kE8UfFv>1it?Fa=*&Wci-gDLXJLPoRsl9WHscc9?N2m12@$zs+Z~KRh~|vd z9H8fLhD9ljlR2MX;s_P^_<`D`Dj+-6VQo>bxm$7&q$RGfea|#jWg3LMM=w1i1Qo}- zyA}NjF_fi&C(HN~E+xTaqYszf0mR=?49XyCJ{5Nua~Z0}YY*pLq-gPGBQfN#;c6{q5&PCZ>d@ zhNXdAZYdGdiN|NH2xsGEq3}V$1L+qGg98W`k>Bt7h}xjZvrdhddG_KI4^alDiKH|- z@(x@7Mj=BKAO~A?v{E}uA5XOINE+oS$JVaSHIKiQuV~Kv0JuxqwVgG;%UZz;4cwI% zKsRd0uwiY1{B{#dhAtx_; zf3ay|@*oVCX0ZB{+|Fr{0^}ro1;?}amL+c5PA_v@r z0h1}vNR5^97jm-~joM%ugM_~&pa>oYoVdx7?XmqsbtGE^6Fu29m^7!|7CeMFCwlaXU!M?n1ZL^n;sF3l#99IHr`>Gz2}Ooufrev|yj-kf6~WNxo3ibk z@Y%%{Km=z^25;1`+{&>vhDh`MwVzPXU_!#Jt#1ATjb{aaKGo6*2=x85Lrk?^pnLru zeR~!b1tt@{ppX3t*po%?Wca5z3jlG}bMAcHKeWUHZn-3Tqt$My#ODPs022Iwpg&!| zb~OZ~uP_+qforBB|A*r+C<>v(p{bgN1Wo}>Id|FYdk)crBdd|Z<8e~jQZm6Y4T2oU z1+yJ&JjKP|UR(crn zf*p5C{)F)^jBY%8sxtgEQWFS7i}au?PcZVMida(Wd)ZN^PZ)TSfrXyU zq~oz&)q=fZwx1=MdZvY6_rZcD>RI!5XMTeFk zE26B9@$E(#^csQ$Xdfm($EWuKs@TLpiM;Q%YU&mU*uDnE1{>+BT@2UWs~#M|4qdSv zEXTS45djQG@>3sw zx4o;Z{3f=-Z9gvgcMec>mR?gRl5~W*;**Bcf-4OWh z!qtx-<&^F=4X^g4<=^;~UXt6i)&I6P4awQcM6Ql#ALx0$Ic4e+0P5{Mtr+4K&|wkT z8L)bCKL=N)z+ImGF?Z+I*8sCid%AkNYib*XxCuCi4?Aex7lDR~AU%>kiC}vQrJD;` zqfRmmyE-r4McPXdfA{I?hjNJPY^cjHc3Q(X)R|@*GTFQ_sSKDPREiyKmN@C#4Hoyv z71#nF@^6y|Itb$iFZzVuLAU0*FifQyIBFE(qev|{ZUs2L; z1+!iCF=~j~rqd1MK8;q4@JAS9Rq5)Ne0BgUj+@n9j2j|NSE1cVFI^vXCi8x^x$W@g zP}@*)s$zBi6ju|pQaH85Ogcs@UDjKoh69x}&GI=@`_mM9QKcd5fXAwyFN>_$i^icH zF);j%cZxK*qaoQ;MYgedQid4oU)%|*SW@BW8Bf+3!B4x&qm`G0A%{j35(vV_zlnIL znCF{iaRbF%adY!eZ#tbJNK%k89|jp)Rjg^4o%mf_?tCbxp>Z+maYGQG3o}&=QQJ*4 z`5UNtRs&0j?&?(qa3*C#dZsX4k?036`w!=fo!gk_QjI}_NAdO0-lQcu6_>L>0EVI$ zdI}Y8{Q4E!088ijr`xx5_URd?-xNa*slWSYz+mrdk4u|^T(Na(Qv(+yM&Z12#U>GE zTD>2GCB7_mg!w7~NdA-Q?;k^3FVZzwu2b<-?xZEBycI}H1mNpR!^&Y?@x_8siP5Zj z|BU_;dZzO?SdTNi>+UQ>$t_Bnm$1|2P5J{?Vg%aW!Dxb|0vu9F)W zKqjF6V_{Ybx8zD9E#LlLa&t9#u#FT25b&@zm_0AKz7&iF3t)&(f9;w&xKGeS&2FJj z)<@>_#U1a~jYeQjvLcT9hoQxTt02VMoSz^YFxkLAb1k^is@-#VS&?{u$a*9@KzO>A zU9#V0n^s`7A^5x2R?W*Vg*u)(LfiRsC5jd^Wwx1fPR8P%_Z~fxIDFXC+W};6o29~D zIh!Q*ZZCCw+6gsuR&1)76571)*cNyBvB2hRgUxeyv8XEQ;QEJETo*#@dW_{}e|l7I zmHPLlWjX`NpwdF&_P0xmYiU4C*ziEPTJ%NS#a{~`($g(v2UE*iwjL2i=%CryEFCDzHL;w|Cy?F&R38&m%D1%nsb%eE*3MtqU&R7p zpy(jNha3!7kxMV~2sXJSB_{+^oR0v7LHaiDxQs(3iQAQoJG_DrkMs6`-Uf_9eY}aS z4xg2(^z-ua2SY$*5as$Km$J()K(Ds=dNeaM%hd^me&W!E7lR4k*OdWN$AJfpG!$SG zTDj6aI#|aoX&WVY%imVa=+E4&3-|%YUZMTEnrCdj@xExneYf#X z_<+j3GTOksj(c0QI)lCJn)8o-N%lZ!fBCrBl&orx1DssCs)yS!2oa*2s)GG{uJ&Ul zn~5^>c`76D+l4Mv6C=KurlxjZAi`di8Q@zG;_-{~}y7#e&INbdV0JN6 z<1@ST#Qh4um?hfo4osZLw+xE&np4Bx44bU!dX(h)yyyaqh%CYyzvZao`*)sv0E?Z- z7NiwkF$VzQF;GTuEw=jmS(i;S+QbqN{+e&PO6I@TYdvY869yyrv zAA=SpV64Mo#DVzzFlu&{9O9i6F?UGDqu32Put#NuSuzaim)E(*QuBP3tkQX{?<6hE z(_OoKmyYTCnE%T9r1@&;hVKfbKCNmyT z>K!+Yq0b-(GDVvk?xT?b(q(H>0bZdmqwK1vs%BQc4O?%`t`;xU2O#2AY8C*h=D}c^ zw->J(pIX%&-N3AWQ=y~TsvBUuM)ULMPr+io8-KGpbkp3%2E_2EhgAd+UyiHkz!rdH z=f;g2t|+QrI}f+`ZDk6Q{aa}_%9g(?hg(@x=#&ts8H{M{tSbd*XxWXBBI2fx*O)3r zUrJkR>vu?9Ma$r745*w!Z6y9X14gJ6x&xGFBe9~59KJ`O{5iJ(j5*{&8k>@GXMTP@ zp|{^iieNvQo04_{V@eK2#qJ$jH7q`19~40}t%$8yHVLwLXE@qL{d1^Lv73!855J zkHo$l=jNQy%7?0V^V5*bUeVhT5d;GsO1x?40a<7IfLv$i6qBG}|Ku+Q@YkIsMD8u` zz;5~8rul=rUlsbEd_8Us7xh}z4HevfdX)WivhkwW-P|-689qk2@ERc5SFotdHFf;~ z<~+_YbSoN&R3*bCMKqeTB2iiUTih2H(SoTRXWhaIA@vVnb@5= zbLP+6?C9unv5<~9g`X@eEND_52wgh~2tc3^N;qGBknlTbcKf&>XGApWTWDz=w0m9& zI#UmZPC4C7FD`~466!7ljB6EOB(8-l?yo#fvGU;eFV6wS_ekUv$;oqDEzPmd>J}KJ zjD&2rmgGK}M7T51iH)!~ya9j&dGSV?PQP9JlsOGgF98)++pR#lZ{&ZCl z|NKyYO@95_w(SS!cX@pbxZwD@new&V?aE-FQUwuZcY@5fQYZ5#{nrvdsnXjw(^Wf6 zT^-u42Q6JEayFyZ4swVWg8<|e2QB51*}E3VOB#6K#j7Vp5eBdpTL!9$OxjT6Nw6Xq zbNX-8mHDez^$X15(5QR4K{N~Dv5vy!R`QGU1kOLN3k<`Qu@SZWu7){W_4AOBau?W2 zxps)y8Y95a7?($VC_{wdd_gYEb87&S$>{0n=|j+jvkHEX814IsV0>f$upjjmB`f_b zd@pj5Vi>5iyqd6D=kV{TTg>0@bU2De$7RSm7tY>DTpO|Tqi4NSxIJw{WY#PmGoS?B zOkiA|Yg0_V>shi1W>uX^S`@Vwkgf|gvlsGPf`_)ye;t8=Qvg8V*1!#3 ziscJ;&TD`{ia{iSw6`*Z1)K|!MW|r!XeNfv4j<`!PBvH9`%l?&_YmH+FBvIxiRhrV zGJi6yUR6DnlXL$1^~(2FIXV7Y(6;PnNk0X{4v>Ts`}Gu;h=_bNL# zX+M#LV8Hj0B+$kPD13!lKKUxbQLGa|Lg1OP<5$9u3!rB4oJSIM@#cblyl~ zcdZo9r0$dxHuv4jowihPnOPXd8dqD1Tu7vh8yB>amS;jx>KMPT50;MVC4$RrFTpDw1@UqIBW8KlDg`0=AZjI)nZa?bj?R|Eaa zKmj~IR7W0LptM~ZJBgzvQ9hoImi8upwB5q*W)MyCqWZB*oPa-3eh?Q)p4kEM0aYu& zT%F|n0zZJ$eVWn)O>Ns~VP0}+5;1)l|kt6|B2{V?}P=UQcH&8MRl8VKU2G2ix9VHpJ!RD!f zms|vKRCq`_0U?p_YZ>1oJw09Bx=UAX)Wy&81vtm-{@A6^a%dM0n<)(5i}y9^D^vgp z>N9b(K#@esuwcz{i{(Z7_k6Hm%3+%U+tGO_F8HtMKnv{(NJ~uRK*85S$Y&) zr!NW;>MgguYX|I37-CD9dbv!b4 z)LjUy8Wv{sYj0aYD>U`5V3NIFmgvIVL~K2 z0(GHSU}1S6r2_Fe`? zlC#}M!%43_UWS?iJkLROLL5MQz#dVVOwm+Sj3XUFqaE^#vk<~1Kn%A%&nJeZ*DHEeaB8ORfQ-^@BH9_Txb|eLD@F*J1v)sy7ctj;p-86;zhA^iSp@@%LAf} zGBs}JZpMzaUg-OCQ?mOG9a(lpx)MB@t+Xp1xfCy zXIx9~)z;p(%i~@H?-8LL|A|f&Rn?@eJo}^d(4u>9^(5W%x|xF%)2Dq)CEHM8aggK- zyL9~%mr>(!Dbmv0cOqGx6(>b47UbkAxJ)C%HA+-%dJ zV+!-Mcv?sGw4lw4tXH`SXrBuPGTCEJ2JvnbP6^SLDbMc zYA<}f=g0*g^WkU$VLhU9hjE*dh1D?t;IbKXF77^`LUqd5>_xAhw(Ao&c@-+MfF*WU z=1X;5U7O%5d5vGxAgQ1aFcY6QcY8G-zGdBq;hkkdcd_~MPT7UaHXGKdryW$BOIz`d zoG7dGp^v^zh&Mf;MY%X`QT?5xBdyJ=*TQ8(iu>lybl*2VaEGp_7^}Z1^Z-ydNT{Zp zD!yMWDgIz$7;PON8M|gmiH9{OCAUcm>B`Dj)7O;o0BC=;x*{t_9YE_7oj%QiZnD+2 zwYKsk)?I`ax};%iL^3@A&Izy6diK{wa9_R%bo$6sT$d5D^oVTlG(BS|C!mg3u_umy zw124L44!#nfSB=#qM_IwC&5P?BC$mPM3@?Pd$>$I5&;q=U`!glmi|cyma+Bm$-RuH z)i10M5o$!f*jo3zDyWJ5A;xkv32)+V_XI;Vm9T-J^q;ETq-jTx@4yH}>8GsqNnX2hHc|T8$IlMw7_d)-nS# z4((5`#9=7(iUC~On(9x@f#_|=(YHZCHP90I2z17JVJCeh@J>w6IcK&X$)j`83A$*v zybIGhfJKW>(qp78DM8e;xkf5M%gLqqg@~wv=%iWoTGpew=A#_7gbJ;t-~^Qj44~)B z9P6=A|MQh}q1)~)Xn;`&i2i~gM}7o=#9|=0cR$Y@fPL2%esHjLzM=p3I*I1Of!!-2 zpr9gvRj?^56%OoLJ1=?T@Keh$TJ}cH$WPH;KSuWi?C^Naez|K@Ok{ombNDN=3C9hT`-C+ zZMvW*cl`J0Kx&xs&@VbVhTky--sJ2-aL;s8xj-IS3y7-=+uPfPhGF_o?bjcsYnBX; zM!8srw9Cr~(8IiuTfSx(^0l@Tt3dcUvmMd+QIh-}pOwK?#ow~~`vP4+vm{swjgkKT z=K+UKaB~7Af;o*k8|A;y6Tt78!M0%1b(;*(dcunX|T!UvPN>lkqe(w&{SunZs`a zap{UdD^uUn51yYe-E4*{5Xl>TU4-+_kVMOY4v8%G#Ecg>uqx$l&D^4;rlx)e4hq@E zJ!H`2+1mo}r!M8Y8pI$o4QQtlZ~$E`7(RmXn&cPQryO|TA{&<_&IZXmDH4_cWHBmT zr0(S8lrudwp|l_FVcz2aZ_dV#qi8Q8xUL)_iT~(%@q##udHVMwK0bjFCr_H!4t}<7 zVK3V>N9HF=HdIJP35MQ0Q#H%L?NS2NmDWjv-|%U{M^OHYVlU(dfdD~v5O0q~bm0Au zFTh10Kj23a1OT1CIZo=d#lhEL-Em49w)@wJE7&Oa6$vjHH)@J`&S~0z<{#cXH$2od zgI@0bU7Ak(T~hp{ns!XMMvesc${j7OcMg9-=pqF#KG)S99fdK@&RZ9_qYJCToW7to z6^v~xLmmkWy8@*^4PZS#>V=&_fKeQ)t?BZmOBw#RFZX@GZQT)Fx3zS~!B~U90f807 zc7sS(>q*RbChZJRQvo$gvNX(q7I9DO37i{WlYewwx^( z5(a>n>OC8L-~V+u6I{WakW^Uvuh)g_akn3)rA>wTqb7jps`2erSGk{6O-@14oTkB# zdI}$*J}RuT`|6JBB(V3Tit7e%Q(*0#(9&`E`doNdx^;hzF-X_Koa95HzAwIMH$`^F z8u*-o-*k;f>!<(N-4-^H+fiiQsC0#cW9pHIhleCwdMx=z|B=W@qJ{FnYLRDux_lxb zU${F)R6C4c32koyy{WD&xyJOUYa5>r7h06)-T;|qIy$=VFcKKMG?JWFD1n^UO@Gqt zI(6Z^x*)uB>0u;y%x-ZL9fSjuHPnNN5hP|3x_8|H`n;_OQ4sS`4R-lpGc2sdbF^&^ zk$$hKY3_FqqIPz6R$Z|^OQF+9EZMpDxc8ah#2&XQJhJ~qkFm*y2QlOh>!f}!Isd;v zfA`IJT$DT{;YcYJTz}giq(LvB2zjV36431)j0F#8GpD_@I-on910aO*bazPd>+6V~_74(W?d3zB(HJ7&p%HIF~EWNV;RN)-o` zX+0DIx+uQ?9mej*ftI5riWJr;h-Q2%a7~+YH^l7$5>C^by^oQdUmKe3p=86v&f3r zP(2(H8e0J!@chd*=~D$S?y1IK5jOpAPSW18Eg?Q|Bt+ppfIL*+*J{}G>9&(p132h! z)Ji910(=7$2Od6GNWIpt(Xg`qFmw_-1J^t3w<5E8(l=T2EOjedZNqd>js|?laV2BOPu)fo-Z%YpiScGvuBzAf4*|Lr)%A#0Q7pH zGhW}2vA$M4Sm`tJhCzyXn2ho?%L6<-ZO@kpjgB1B>rg+8fYOLXs48f!yT5o5dfCeS z1{im>`mjJBrG#k*?3L6VR1b=>X*#I9-beVsX&1+l4(B;nJNl4MWt|aL3;jodP$*=!ZoPotT>+v(Xw0pPO`j5`~w2 zaYEpoy%5*^@&nK=AmD=#D207!^+aQs^x*=?%+_%4J@}n(HuQ%GI?WEc{rK!+>)?L6 zT(;BpeAcj6Ipu$woI^U~n%yU8!u3Bem`Hp*aSIzFYRJuKn971o8gtSE>9xy%UqKV^ zx;IQJdp8IsAb-S$Mnnu>-steKI^Bs=rEG>rN0A^!T*zh3@%|Oef|n43TPo*uqI1ZO!bG$LSbX!ht*^SmrLpJ_Plr6JC{5Y zZ6EJ|*CD6+3Lb?=duc@Uh1<0$C{=^Os9t4uH6B(vu`!BAF=HX@wK>qLZ#CPoX;@f`2NF#Sd4Q^biDp* zi#tdlB2b?$h=CHcNQjBO26P9<$2)9CY$IGJ+S5#Q?)LT6`hi>~@)DY~Vxar`7r|b7 zhwDo%lqO)MOq!b1fKcEaFo8wmT|M{M0(K)UPKZ?D7OS7KQ zMdu4h?gZKJNH+cIYV-AHgv_xd|Jn0*UK5-N*cN^*gKeSNMuE<(kRn9+Lr9jRmO>3x9n~GD6#e8MX zpWrcUzvgUx`MXq+R6fY54?^8X!zxgGoMnZCmEb!ds`Sa<`uX`414|uU;|)hc^!`S{ z{m@lDiJX|%B@Z0f|34@{h08e!HnFAxukYU&!psQ1)X7%HGGM05{{$JO09ixP_A}a| zK_N^9LOUrAul}<|LtY02&_et6NhoSUq7v(oSm2oxvy^UV8V6#r8l}jZN*82CHHU;_ z{?A*49uBgk^|45M`F{tk|EBurFy2>nLrpJq=I7;~w@7I2t6MnfURf!j zeB-I|`SX^ely+Z$***e8ZL82Pre#|UFgU$r?p5LII*#k*<%RTr5xG8i^7Xl!Y-?p^ zEkmzq_O}@9vqPkvV1$G`B=_R+p}MCT=;55;`!D%~pxXYFqA+O=wUD!VE4izI<)6;G zlw3x7osJ-hv$sWNIpGfrOuag>Ur>eIz26)wj(VRxA5lZC3zSHGV#D(s@)U=iAALL8 zx3o#gO*R>Q9hxLz2Ze6p>n$nPJXqK0r%Rr{5;m4FwgDy2lN`}D$e|pP@9#YF&p-e8LTq?n^z;#` zJ14nR%=Vu^18D;>{6}~UzDM7bb=SJ5`iV_vh-0lXrSDHGe7FTguTGsqP2NM;8iTWh zLjGyxjbsoBErvQ3%gSYX6ME+wM+L_OH9@JdCfjWoAxF1{NjV(}+G%Mv^9`9}tomck zvwA-1UnJw7>e9Wl$=LYFXuI|v-*d(5{t31iwfXk{jc2^|=MrAU${H?~+5WX=MThZL zZ18#H`M0cRB|xX@2Rb7oBOMRFM@tfF^n#(I70c%DojYyxw~!f9e9|HNytpR=5A_!x z`axTd(EAD~KiJS?D$((d&~|#H?@zGTajyIQ=yvgGx&UU42GaM zxI>gTrmH{zhzK&nn$NSPuU4w-G4A{E2oUuT0H)5$;ncas+=ZD*Z2(EU-Nud2g3X^D zeIXEli>XHMDihf~cS)64^^s2tuPvON4qBnBtE8Q)2N*{#8(@#{Yn>9BTg2|6C>fk( zUxFqu^G!7LDbj%ird>87p*_A8z9UW;h;GU~!+&c-S>c@*?S>N4jtM~T2kt(6_Ke;C z4zK?;#^wx#U{O>MBo^sIl4kN^T>R&+P;e-b9CBfJD6S!9>+AD9-S#_Oky4xcCa5-c zd%zFzBgn(@O2TMoiS=OH;NW29&12lyA~F1UJLXKGmSkHwGX8=qtOJH-;+5dbWt?^y zCF_oQ45M3Xb4Zk^Sx;MKR!f)5TzpB0AXe{4c%bLd(0#$W%gwj4i)`l_f$-&dt67G2C%3rOwZ3-Wa^$nRoR70Fm-S@&FGTzuW`bn1zhT|+y+Dqc-nLGuWpme^Q9wEFo(nTGz+Jp zQX#3k>v!#{_jS7Wx4r!*K2Y7CHor%E$YNR%?vWO$6pA->nY6~O2L+9=X@seS2Q--* z&BhWwD5uVT{{LHwopAObG~1IN#z@yiB^9nUq%z&L?pbM=$mQJW1Sr0{&O8IhUZA;?IkS zxr7C+N%=zK@Xq}k;ici}A-!`EC@~TqfSHRy$lL<2F9+|7FiNO`7&EBxsn;gI2NLU2 zBiBDG4cUa@RA$`&+!-fjQOU@M2=0G`rTQGZa9!ly8;ti4QJQ}ypQ+@_dQh#dXHpu( zkLLDqaeyIpb^iUAyq9>6!DCH6Aj!|Yb+SN$$&JRbqjC2Cbk}CQu}b2|C+FTRS-NX3 z{yd5L{MLT%_UOlE@&hJ0KV`**fmRbhTC08F^s}zAv0)}8clqNi-SrQ8!_Xf?8fjROBX1PX(mGO^NzvM^Xco1IqEkpuoI9n1>adV9@lhYLxI7vqa3>DP8@ z+y8#dd32+slh>U4=wj=_nIkmoMyqU^D_k#JAWjVkjMv=0vgVr*rs>{WwyN1&{H5k- zG;P)VW(Akv+O1nNZKYi=)tGT=YV@8#yuyA=yvaX?f%nG7qVh4P6lS<^Jjau<~ z#N=k ztd}q{-a#bokx*t^-G(r{2spsW{OJp&Lr!4}(eG_V<4_a#C z3{Rp@fCr&*TJv8TeoZ~Kv{|4&EyR)WV&(6e$)6bPA3!REUiOw=GAQENf@*hv7|*4- zs&VGyelzp{bb73p*Lh;t^dlnKV)8=~>Qso$EG1!aYVN0{j=eYCT7yuQmD4Wt^mjfw;L zl*t;Cr!zG*g&pb56=F7(|8AZeNZ;4S={*#Bd>ie{++O#i0%MI($m&u`r3jWzqyH1w|PlWO+UhF12xddgM^cIV@y?NDiv6H7y zoCtqnyIz9&%xC^`V>8^uqd8Lpc4chMLEjB`X2bTS*O5TS8uOf-AdkOL$Oo>cgQ>0! zaQ%%NHrzpqgIP$TaLvi0`j70=v~AI{0#}qC4PnAL=}Ps{L{45Ke*(|zY}i7?FLRdaoMKJF zcaWxmi_$@-KEX;uv!K8Fd;0I{B$&6KzlM*@W5dTtz-DBLLcSg&5>&migJnMgWOi6K zRO_8gqScqYCz$bpmCmg=NK3MiqEPHd^;0bZ_11&q=?4~o3&pc$$y(PUcIrv}?pC*O zt>|tYq_MCs=Zuo9yC*VcK4 zth_jKA15`(n_Mo%v;BaTG4^7+tQ0x?ycsmkO=2hXIeZ@(so8zviNRk3D^B#v*{77> z&y||O{G<@e7^ywp{}}l=MGYzDiHkrd-E13Gd-0}t<} z^H)^YSSnYjdE?u+f3RYx$h}ddN;qj-eHCf*9&+Jd@`0O6v5NImv124&$HzrZ07p)#E&9Q%c8f1U?mN&dqr{)#|wGtY>(rIapKeG)vikY%ZLaoQ>vAIhH05;s`i zj*68FkVP2-xg5?v$wRZp4=JRu3zSlb9+^dtW_EilMvX2tO}pm83e&qE2O9!8abP7H zg2RE^3e4TBWTuXi?xVHxQKp3Wja$piWiL^|miT_A!JNqiqK8p_eIEfzQqUTttQMGD zcVdGFab=mfAj8KeO9Dd)5#t|Dng96)mUNiHHAm{Gs^@D5x#Cq6kU(f5a8jcr-!B6eziT!OpANBdh4GpB}BeN!GrsAszlul-#{lnXkqbm zwO3DVj?<8_X;tKPZ4bW((whL6Q>iub@|hV||LS;azk1F#_YbawGq)fHMt_{O=3USp zKbafrSVf-`;uD!tb46KWj9hY!ZQXjrArwAglcc>7yqm{MHwX*Y?oO55WTDN_k3GGt zCL@G;M}Ko8wSgE}fBKtADEK(kX?^tQ`=fBO=x^TFGy7iMDIM7Ti4VAvX-jNAzcm>O z!a2K7lyp)=hgrwhG5GNjXGYj~-*&wP|FaQ(H3Ws1bpvhavzr_r>MVgOLiKp-GZDHg ztc4(;?O)@nQ5Gs~&NYbEy&dP1m>duN-*c-p#+ZDEnr9?D{bVtjL%effZp`lRBIAvi z8>I57JVk6EPHdY$qTq}vJ5WcnfWXY{FZTYoP@v?#-Q0_*Bcu5h+FG=meTW$hF)yLF zn`Np4GKm8+Jw5$>@o{Ej{}F`#p!ayN<+$DLZ-Wh*PvODL&hbbxEmeRFp0`2s9NieF zJcSF)!1D6D9LDo6^N`NOi;61QI~lCJA83EPg>IajtG&oxHerl$2KQq0TIRu;O4Zek zlJ-68(YlP?aKBCt_-~>(u%!DuS^p)A%*q4Udg1pk@A^|U4R{q46fz}OjnXb%`hPZ} z;#jM)a_=ljh_Z!Qmo|H5Bm{tR=`r0c3SXU$N5lHQ{%d(a{-gc&|C!I0MK`>vLXNNG zAVOjw4K|r0Bv5iIk8ZfZO5?ukc@iF|z=|aYU#^26VkRRAW4s!ZtNzzHj}ORAs!*MG zql!Q#uiUe<7`rhf4~kz)AZb3nQavt7C}FJmBt|3D$m4Rf3xti{ce@ijlLE$)aO^_50EiA?aVr#=pOqD+?0%rjDOi+ zV2gD&vWZ;G6d14;^y{vs{;UmZxA{l6kI=XPa45YN;yJ5dClSDy;3QInT(Dsz9(X81FhA^T%1}oP zOJC~j@V80t;a_FQhWRyX&k~|a>7^diU9lgo2vw^U?3#mb=FNBUAaWvzWlYBM;XD7R zS+uLSm*qGEJ-AGFUc8Yj`t)4hG1aXufsEy;K>ol3Yto);8@P7Zm2hu2F2qE>nVa2Z z4#AmyPpU?wL^oAAYO@0|=OVCLj7Z8Z&Rm7D;U_{%NeemmgY4%AjD*z$UW&<>8Gh)+ zKtGO(`ai$T7llcPBCU?XNHq`lK@`X;U^oTEugYiMyGNyqWW?B?`D@5hyj=uTK za#hGedv)WJtS86LYGLQvlKH~GkRqX9P{7pqau;lszFW_z!}#Ds@dc38%{0MzD@nn1 zCHXLIysWBDhf~@9r)Tg=tMt9K@y7-C?Aarh;-?+2?i09?p!v?9q&9BaTwN-SDr%EW znw(r$nf*IYs6)%28<(z#K8~0@T0LPz;CMW|Ot{Vu6}(V`Fu@ zQ`PJBw`dVEtO$DXW)_v*8_79SMo(P-!TtZ&;MR>BzV7bxV4p|(=EAIaz$JgW_WOBw zxBO(}`?^RGZhvU9vQDvVEqOwj!ie&&%iHKMDA)d{G01Yhw0j!M%r>($xqQzi5L?gL zFMmoS?$bUsC51u5W0H^{5thEmVr*n2el%z^`9=`37eL7Vwus!<6>P+(zusbJ)-ewc z4|Ew^zy5zdECsn3F9!NL-ocjMs5SpG=W)+toa}`SNqd1vub;fS#;$Yn?+U4hX~~|S z;jnA`+`SV=)gAD}-qoB;+C#^)Has*5F52yE&;D0QqM;NX8R?ln8e4geAUM3Zec7l_ zUw1vRD}Z<{0D3^lKrCU!0|yvS(Z23Hx@qdtoqMtsT<5_rHv*;Bf#Y?4{)chLv#Cy9?@fvOA`$&O)InfiRoCZd3KzqBP_LaN_#`B(e z?M3&9)c;5Q>D$C5P?}GGN|E~WsHlI}#E-3(75NclFjmn!c}4dGJH|e{rFp08XFFfG zV--GhAZGUSwm6d>>+Jh~XaD(x1-Zu#U@R>!y(Q_F>gD(M1eCTpT;kzzJ*eehTkw1M z*Z2`F)$o;;XDps-wOd`kRuR%0%Y;+g4>h=i-V_WoeK6h<-Jq*FpwtzwAm=)O;++-PSxf{78Vwf zLzHZZLBw{`FI>1nd@JAF5o)FijAF$b!;Q0BQZy>>gNn?S#N4S&Ju6({z8FZG8Zd6x z6}gjpHcYEM^m})7X7K-6&ZqJLPa49lRXHH1^~%b27)sk0)IPmViD$V167A^V=d)bz z0R4!7ZY$;?c1B!l%r#xd$06=PKi7E%jg>Yn0*TrBr_o#>^`QImvTU4e~XXsb20URvcK{H}__XYnQGC^7JzBauca0 z0|+f|4l)mNoF-dBpKv^aO1;$i{j0B7R=wy2>T_XeUKLm-6&IC zN&)*)bYD>W-wUagzL+aDOpzCy@`kjtDjr#_WgF(h@R5x`CHcqr6tFzNr-7!ayINmy z)Pe?+yv1SIyu9=JhS{1q?>AlSc~>xU9af5)RUaU=2|OYOmUyieVc$?x>;tf#Gyzcz z44J!8*I-`6&zIlbw2kdacc?wUVSkwL?rKg3nVwu%%|CJdN3&492H*&kB^tcLln=(a zJYh916HM#((5{hr^FJ^X96rKI!G4EE@_~`i?6%jO(>4h|2i_BZj2mPnsg*4~_g5Q7 zJx3o<;yKfXK1RROW0~{AoEH4{ZjIXkzk8a6-?H9PA3OzwZ6s$dP!V6Q3{_njz$QqN<<}ld8uSnakF?r+)0qmXZJ%t%b zZ6>vs3l9vG?CXQ4A@oBZgT;FVdj4ALR!T~Us=tb{?CWluoSYn=urN5O1kstSPGf$F zbm8Z)pUIMjiEH1tLG`qS?~G@+6m`MyB72A=h;H1Z-h5R~R#x^!zQdZZpo(1wQkm0ZcEJD$CxO_<5GmJe1tUwJB{IJ%l+==x>=_O{Pv)n>JDrNA7jp(|XscS* z(aK&BQw}1a2ACnCcL<^tiGRTA5q0Q03ScsYWrWBxww`{wd@aMNzg&q5R`eMjmG(d42Eq2;E8@B?oJFKw= zOCH_cV-^sJ^EKwy0N4&u8S@X{*CR?Xw0<`_O6-$|SXc<_3aI^;wsK}~FRw`Wd;I`Z zD|yo#Wf1g~+Rf>K?i5RAYQYbsVHRsoO`IU4E_abN{{Jm^@z4QtEnBPpBN^|D=8yw? zv_lPU%cF%+4*d<>G8?y%r9fQ|LTK|`_+QuF-~bCfc*V@tYK(KNLgfZ_ITRv+H*7Qhat=Hk{Y5kkc^r zxM5U6=oAc#mh|wfq}APMQbU+rCx-8q25iWjhWNGvBFd*_%T{^2E7AkY5+HKu<_1JM zM}&H+rCI3(^p!;Xy(@uoKu*_ia{{|FV$bWA?t|2(4xKnI9_~&Ls?zc`BeJOuqf#*9 zI*Xb?-u}?3nY$B9=hJ!|k>VkiHZ;t@1Q<~|lvfcstim$0jrOYZ0_+<~%a&2G`f{Qe zYkm*8N(!H&qMYYIQ>=12ZXQDjW0aSu96IC!F+i+v`8mewbc%yRs??9dbrC^DzH3xu ze!m!oSmf=P;oiUA0&DtFinNj`3aHM{0d-H*_iLPf2Qf+vb$yr}!$a2DGv9&~$;(NF zDM!4ldz3DYS3WmVBznrqBYgU_Ul(4CW?MV()&knKBu59Xb6U*5Z#u3Dl|h_SK7OQL zu5%(^gL!nY&Z|jN+%db=B*hDw11feu{8+nt1eJF&1a2WblOTH+BNt6ADn)|PBWT%q zum^~=&Y>jLyiVEp{e86$jn9yxIQK9aeK|-t95{$-x%#^_JY2Ac_<4EfZ6}}4LuctX zDE+pveSaeVPb&5NiMda$ZZ?l~wT6fDLRsV&^Y6f1*NMbTG)ey3$;6Yo(_0SnZr!SO zkm2ZvCwNQay)*-XX&b4;aSeAb}woRq(y}eIa(PBN=^Oz5|MdI zawSlo2N?bqF5hQ#M9U5QsjM5Q`-3Y?})OO>5-2)`6zo~Znl$vCj| zJY>)E_W8mx2n*sR*;#i0{V~s@>cOh`yk>Cwe7|;dD}a6$$C&{_xLv1~9pN#9 zg`kE0dSLhthM-hEeb2d}e~6P8%I_kWo}NjI%49pBckfqrcUkf){XdKAlfa$3ch|z= zXz9qH!v1xrNOwE*72cfq+;;N*R`%FLQNQ>{aZ6)iRhZJpBA286(2D|m^m-Ag4VXxS0cepI%K z<4(+L1VLVDINiz3n65+l-TV_raJ?nRs#R2uQVqY)TwzW=otTIj( z_a)~V)Ipyga8l2lSe&OWe)YTlZ$uTMRsbKw(VE`H5l^}j8;t|9vV7ED|ZyKHe{e1%@@XDPN6BC4O9f=l=Q|IxkJ>TPrCt+qDV7>)-;s=JQ)Cax_9omzaijX1iJ}J}5s_yS+bP^->}+gndzcp3 zU2D($>yv~VGmsQOToM@Ee6efA51XpA8&S{2^W+nTIx15G?L}|8Pgv{QKO|%kQyV@u z+Rc!67eA!SMLS8i(2^cq1 z@*&fR1iR^ohDN(x1Df3}x1~pqri`|ppcmpJ%fbn8xlv1=2Pp7kUaRs+)Df-FVT}o= zpajyY4-E?&{Kg1(EezzNkjKHPdw0eGXX+**#5ng>TogG4E>r7gU{(YmN5b9@)S$HEhDI0pY zlk?CvAS`lG(2m-&?vteS3C|~2?tQQ8)JMz7raDbgmG1{Px- zQ6>;mE;5+W$wNG$9wb0^=6EJC&g$aatvUO^Pcy~{+#p>7isq~HG3L?+n}7@>#1&-a z$n@p>Gb{-G3qKB02koZwN6tjUdnx|7%XlU7J57mV_H5A{Q`&t$DX7?@J$PqdDI^S} zHY3H&zm7-Y^8=DVhP9*r&Mb3YzU`8^CiwcRz>5!`Flx3F%nuhc6_G ziQFA`?%WaTe>G>!iO)us^#DiGM++M`*F>+Jn4I*EJ+8(uTN;!Tsp?QU8yjg6uCS}# zb}U9TnD@t1&kn#lwyVV`Ci!5}>_S&n13I!vs6c9VDT+q8J0CJYk4rEyht|)SL_CM} z+q%c{?|C+;T0>0^q^C$QvvT}cJfLipNK`)BErItTlG+5BkA4^1b``DyB^?0<`cWei z|L2^`8==dcp2~V4*q_xR;?b{WB!*mA6=fZG4WQb5p^H`y z@d1|qF~0Z9mvw+YB6jo44NW~7I5u#wg{}A)3fS$WA?;lHc4EF}b%Iyp>YH5p=lAMg z_%6TXR%pcy;X8oaaB)rLxMn_~|I-cohb6g9U(6s_+t2S`ly7T_C+WwQxI~F}%u{DU zU34rf6jMt9sEWkx6W0HcnW2MYL1J_fZjJTZw+}_AYN%xiS%D&ePrh6Q<;|Cn?R?~0 zOX*X7zdi|^lxU5(%%Nw~YAKsL#NHES3U?Ww1ob}z<}XpOFu}Rn^EQuu zaG9#OB7noMQnEPcQ&z6S1o&&SsNr7#xjPF35`Boa3-`bySFK9$-@&|cXuY+WO4V;U zM9{z|C4}(c&c%WToM`vuI5Pv*G_CF};9B@(W}b*yDu^czvPAuhX_zaW*cdP8SV7-q zNonlpAMoj~H`33&=t|;uQy8I8haqd3@r3wnwJ`;ai@*E&cUdri{1= ze1Re|(c5z$KQAT_`eD2S>=3>W@{$STazfK@8tgK z5K-gjO8 z(1V~6fXn-id>a|@LocjxN~n^dvGCtF1LJg2PEN2{06h_?lKp~zZ{CE^e+w~!sPTkr zVWTaP2)sn954pDwY=G5NIPBl; zav6P!A&vnW!F8zp8vFqzY;zg42sP}v#gWG|`|0ozA9LW=j{PbprhVhajdo*~4L)j9fm0Gh+PR)spggD`|&89GO3)i1r5SQ)+(yyuU}0 zoq${atWBEr7G3=|b~k%DNJXqptdWjPOIPg%o&&#`*x>ZA8p6$qFKm8ysxo96_*04N zShFA@4euT+;4<(fhoj>b0o~2vUK(Ybi2)*pBErH6TZKm?UI^J~%fwb>!)Bl%5w%(T zGwEWH$UPixq*sS#k~o?vV)mt*%EdCX^=ICP7NH5oC;e{9g(=V(!Uo%Ep4m<%v`{fv z-I@80Fqi6dMLmKc$K9-T(@(1UWPnew<_fc?LH_l8QuVw8!B}08G;;2OjWG$woTV-|qar5nCj(I2l zB+I;H3Akz9IACM`u>RcHu(HM5j;%AEeW2;8El^>d(|Nh)!cS{b^v~Z1;utou59xg{ zpDZe_x;Zzf*0mYHrDpj4{#NBqUDuJChH3qTmp=|QOP5OR72B;=umS2wYn_S&ulgEj zu!_bnIcNvR&^eBL>FtgC-4pXAOUNf9sUoC2Ue8tQD9ucdyjhny--N--Ec-$FO^FuC zXe&~DK#Hw-^UH~V*tU$}F4>@uxgh(k%6Y$Gx_*P-`B{r<> z7WY|l;@8KI`kh|Qn)9@of6ag1PQ%_%f~NmAQzwvbwaMAphZd8Nhcdc@SX93@ zf^!EijDl;LFMVN)vG?d(bFl(#SI(re__AqXy*InhCqdl2D%THz)`M|Nzf`}CA2SGd=g>nT@b;U6gFwvl>UAEa~z$2@eR0e67Zq< zcIMsABl|cL;^-!9WjZ=ZX-b$f#Dylt>TV6Uf$NB$*3*kW+7DU=_9kR0BRDFYv;Pee z6k%VtN|@?;5vv*3b>!IU3ncB0whVmpGFIHHs8GelfAe*;2)EE$;%Sa2bO%p}^VBIS z8Hl399QpXMSI;5!i!oW|S@yke^-{&Im+H`Jk!2{Zn)BZiekb)vq?==CUfm=!T(M6_ zyEUj!qwmtvqwF4sm>z&qhe}a#DpWf2-Q4JBRarB!Mwq zoUWlZdAYfIb%z!zwD{xW=;EJnJ`;!2MhE>ZuTM1+b~~y+yYvj1X?E%7JaPf=7&bwn zXCAIdjVb%#$4z{gNrt)3n3GrnT;iNylKbM+7)WiVb-pW#jSzgv4)llEj^SD`a|^w5 zhqM@eAAK_ZEGNe0Iuv{B&g(W;_FSe`DjGUi8;9E!+kb*Ub#pfKoO|q&C+_BaK`L`>XqRRcLk4}>>@70Wzml7` zL59pWqQBo>#hCZRPLHZz7Y@R42570Tp>fY+E*i|(_cd042dKn-@S-I3qDh(EV4ipo z7h!q%Mh><$%^}jZmy#n!ZS@*7Pi9THjz7!{iOW5%vDNW5kF*q@#0d8Y5g+2nmo$*l z-y^EoaxtOecayoiynMq}?CCqm){=$kaxHT+qusZbz1^R(voIzxQ+yIJiX{^w5}pg* zY1wqh)7>xP>}ym*x(Ej_a5_uh?Pu$vjITlFQu%jiJv4P)dAU1_=uatB#XfyKlL+*c zFmfJr`aLCQ*ljM=HE-i&lUS}!_)w%3gx0Tr^W}>m;lopxEQRSM;9p|+Oq_~9o7e}I z8zS*2z1GDuKY<^U(xce>YB8kUdJ6`lb&g9?bm!g+0L{W%zMVuN{QJvo`+#pOi#c%> zQ{^l5rN}R9;+K38XZ3k{qAr*Cd}g{h_0XH3LfRnD`64dt$3D)um`kIDg$KGnCP$B+ z6;N3XrxaM?L^Qwbi+Pk)EYFz{7X}h?5vslv4UO0SL`q-%`AMwx?<4!{EvDP=sl3=o zM6w_f%>Z!06rsxf?h{Ak?9(-3){Bd4BWA@2 zHKqd(F57#kHccCL$}$oU9(DuTeUO&{2>Gs? z>Vv(*Jy?5pMbv4Yd+AJC^pfC}T`H1+$=lx;5*oyk2DEeWQb#VanRX%_xekta4yQOnr^Suq` zHn*ofHv-j(0|Qrpzw=5@Rf1Oo^j$1hxxE`o!d{X=o7;Y1pPgLUk<3jsw}s9m8sz4T z>V)laZTDEjlOB^bIXebx=mq=b4ouM7BkXg2wy}(t7)(X{J_g1*T(|IeYD~I&ilRIF zYHl95<<(^`q9gG412UdJqOWCduC3R&dNJz5{)NZ93);RG)>C~t^VCruj#Y2p_dgj> zcvd_jSZMFU_~>Sb{2n%R!~vqwDy#INx6sQAC>*!q8M1AZx^UE@sK_VB@Or{kgEKK0 zZG#ybHqCiDhVC2j;Kw;Jt@{I~!n+cLFGOTrl@yFQl@&W+Wj%*C>t9S>H5g5`q*i3eu~BADw?TdhDmwm*2Ox`t1*n-T;T z(bFG*?TSN_Ntmlc&hk$ob&LL{s;Y9&ADJS-*+-5Z?HU%XNg={2uI#Xc_dM^Z^?_&@ zsUIby4Qal1w7Xw`)B^OSJ7@n{bsb&oi4^$HKZi&lYXtMNaL(tcXDTBUMo+QPzvsJ? zY~&3LGUZ~n)uAc9%xm`FPC&9DA>&9a?($*zfq=pfUocF*_e_^`=X}gMASxN@ z&3KrZ5+EY?{V^`Me~IA_DAQ-ApJYbIk#ZWK972}kwcaFL)JQuxVgk{{JurTBVX6A! zboJ-l*v8Bix2()!4xGypnkXtNs;pJ*>>kJ(bQs}(H8K0~$$rr|M#(ln4&9yRdtt)5 zNx1f^a07XVI%{++mSCkGDmwrd1b@}=0T=nNWd!p@hGMxl(QR?CU^utQc$Q>B>1UCe z>`RVdwp-hd^Va=~4$?E8kI4%xmjMJjq^@qi?jNsPwVCOQ6y!~9>(I=TVLGaZ z=I&#?ZVfQHhBnjw-4GLR2~oIUVOOMTU2L9Ui`z+s^k=y(-eEY5NqO5l3&o_{EuRJ zZNitjkA0{P1wc-S-esEi`^5+4d%19OJrb?FdY>5al*B~7Gz>g*%Uh1!r?{-@zC3Jo z`knpLwg&pwGrRw}F&j9KbBOma{qO^O0{r>=e@%U-8LP3i6XtGp|K3xpR3hh;hu2cx zCjGk&eNU)epgw$oU5c{Eo}7uuX) zJ1~J@N;km>q<>*ePpzMC>uaS#1lV@KLe-y$T9KpFY~@laR#%7$XEW}~6wA+_nK6-J zU2J9kGcvu)qJ1LHjyR%3;r&ky2yafSbE%%l-`gGT_MHM>77>WnMcp)$$ygKMpygD; z*b6fFA)U$iB%$?!;w0`ifC6mu@zlPhOR}sdiOK^xHJ3jMz?zVdsdQ4zUTq(-F-mT+ z_w=6w9_jPtiR&+3zQW1~1 zkZS(3@cEK`o@+;&vPY=9Tf5ltI4aCI#Zc0j5CfwOI)LHFeggL@+*-wLwJ#!<(bJPs z_M@XMX#4(KzCquc^xm=WcJTE@go)XbRcDM3)=dW>ZuOkxt?lJf>Y*+J5*gsL|F^Ri zg9j&!DdkM)MTB>koB~;?=<~{*78_u5$@N=W$Ghx(4jzcj>$;?A7{zD~d=`t$K}h;_ zZ*LAg?k_knci88EW9K7derLbI<{0P!ibfq;M(V#31|*L19p)p){Z^5EPR zrwtU^@}ZaAi$}9z6~hGW*M`!=leBN=DoO18N>P4zKmOv__40%VQ^uOl>6NJuBlozz z-#l>j$dUKn{9$fW8I6{ZpUD4L1GlF{%dAgYg@uKpuSQW-2P)ZX*(^@&J+!0%8EoZ# zGQV1veA>BMZA2S0WDs^m#03^dt3XQEZ@8JH7!Z_67#4$-#|B3}rLO4RJXjziMsU=K zI^Ti<_4MDUG46qyM)C{}+lQ>Z2)7kBqtX+!Lt{RDzBf$^x&OlXL?KACo)UTVJP&+9OHE zY{^Q2CDK6Bf_Ijl{teBNZ7O-8E%oZ!l>~c+()|2-{_khZ+RznP>(yQOCmubXcDu*tbMo}AU{ zj-!1aBi^Zdk9NYHTiEoSUbfHtW zmb&u#_3K0=fBojo`1c9VsrZS9CKOt4FuZox-Ijgu}Y8CM=G5sIJk9#(FE23OdI!{7X2?!nR2KVTp4nq9|+dp_u7Ymcl z@TZ^9ZA77zdZ=*N?ayk9I7~6fujafWl`X0R_gPc;RXV-$B}Ral7Kvl&WLHK|gP|#x znY(<_g#$|Zk}+2@4veLgDr-DkaMEOUFS9t`VL?$GCJVOONfFFg+M^?Y@m1IF=KR7m>yQ;FfytLF0 z$`?%t6-r07UO8mHy?*=l*puI?%?AcI3JMAyUuagnUQ#kkH&0qnaQ^_tD-wtl&Nyk> z^$R(M4pO=y505B`Ej8#%5aEJ(hOP1F`RFL1cmiFYVA&ZRtooM^p@%z57xR7+!R0jn zgV~}L#%IBitByY|-ZB}zmwM@Uv0@Reeix`l7SYL#;Y+m9Fq-&VSk^w}K09=!LoM>d z%(IY7#mQB;C+EhDx4wrpXML(=FtKu%vJgH#yoba(L_){Yx?5`ECgmv8D*dE9Jdv|a zXBr2Cxb)WB!dCs^k!0uNmUc+2EKwB6Zm;=W1;ZE)i@M2pou`-jQO<|$I8%|A8rG@- z5?6Y%F@46TB_0!ZprQ*LtOIR= z|DCv@L^78&8Aa_{M4ZucYsQ#18)b}OF zo}H3E7y`f7Fm{VNUV9*J7L!Y@I4>+tBav~>srNXnPov?rQYEqw_nW7%*7o+R8tHm6 zHd`+)_PhC~fGK7?dbv>~y@f6V^6{6c6XTs>C3>H=4b$}`UqWSqob>Ikb$(Zapqqff z#SiDr7BiQyyWhN4hdneJ)Xe{f2l#UXCB1q7uAQ?Ty+=4BvFo>i?)rGDDLW(RZouOHsHvX4D~le+FIJBQK4+ndjMw|}r~#+>>3!sqeD2<&Jlcgna=nQ}sF zPaBB}t)wWeUuKZsj|gmEw3w-@t|kcYhKUw{)$hTF{*zf@VFp{Zz%2$Qwsq`BS{-ut zA6)R~br>-`&F@E9yA51^A6waIvvR4S8(=85`u1?HwyNWNh{K3qM#g}QKk*xtvs9#K z4m=A6#D0isvE6ZV2M9 z6}Fb|xi<`hB5|>r+Aos`iXZtsX*6E>$lo3*m4?RW&H`X9svGP3c>2;dOzO8!`v(LF zBAk-nAh*qH6W_$-C6U(AMLg#zqXW&y%Z|DtebcP*OZ$sUJl?R!Bn!SWQ&<*h%P->v=`k1924<4+ttz3HTn5~e}ygr)oUcMGew0fT1yJz_Kls8O- z#PI{cTE}jgW1e6GzO7u-eQs8|yS%Et0Vc-hRKlc>GfTZM)0e8v5Ds|RVN(>!Ay~Y4 z8m-;-`HqWI&NvazcTmB$XEvqm=}H)e&HS$n#Q#tiJjTY)=p!IncV)aAq}6n=IsSMK#D zRAdJaAAVZ#JDJMPM%#YP3X7uB^%wW7pUOkNZ>XP%!Pe%iM-RuKO}czYo2-X)SfnSv z^K9Dw$)&t@!=rGDadcGCaZ^*Dv9Ng#-8Zc=I+me{PhwIu-?(}6j(h(t4L}^7s-3`( z10p%7Ba|ElKUwN8Z+LFx9TOeIkO|X`11V-Tk&qfbHqGz%SoU~!@#1KDL4W9K&J5_wI1KQE%oEti!+t^sjnyK9+x#FB&YSZyG>N}pq@XS$|9GpH~9kLcD9QvGwsdc zu5imTEM{htQ$%sdE!yX|lX`|+5)MDh(kt&*W}&W&8k@xCL@e2|fwti&@@SG18I4A1 zh-xT3tZxLn>k`AdiXDs;Ny!iV#VA#5k1V6-T}qiq?tzI15vVQEH~7Lu&dbnsNTeoDO))v^r$# z*MrL#_$)hJBVMPbU4$I?9|Yf3*A<%G7~xE`%` z^}L-23ROE2PkqsY9K*qY{%7BgYf<8-MgsPHTOwC!ix}st#c<$}J6rtt@#Bf+%{Z=@ zOsNA2{N)$bC$cT-eS8oZ4R=6QJ#>1B1uk1Ze(Rsf<%bKU>t5NH`1DzD*cj-W@!e^= zXnx``4EFdrE;ZSGP>R@eLSY}1T)K3<@`R7a!lscGHL+dxPjg;IKIEr;NSwpxS$zLZ z>n)~Gb9#YN`2)Yb&)E~L6l}b5y&F#N(&VLtpL+kPZpINZmmhL;%kN(iB$C~r{>%;; zI#Cc@w=Py0q%Mg3BRB|-^6cDAZDW%NLSWtE&hPnVUZWe03s9yIxt&98_6X%2X4vzy zWkDchw;hV+4K5+^?I3E{O@@CCW&?>q9m)}lolF|(+2^Mb8|sU`iO5wuz+wLO_;@w# zMy0>7tm0}5a-x%(rU+CG%=l;1&Xs()W>}VXbb6bYtvW~!oI|DIT?r<(dcsa69X`^6 z$`6i2VYgJF5afm#8vvH@AB(j1N;6)y&N`CLlFqesX(53E$aDlidCH~g`o(id93_eD zDbNru5YyTYbiV8V|67`Olse}slc)Bf-9=>w{>+fs8GCaTC zr-|9a=CNj2gaRbrn{@OH(P9H!Q6x7C)hLuc{|GS}hV;iUqdj%ciwf@RvD%3|{-+<& zN>OiWs1pWrxMmcEGvo#ctWlQ`VrXPkM26cWaX{R3WNprs43tu7addLTA*2PAgf zm?Jn{J2XGedJ+T8cDNAk;K_{W$3;I_Yg`#2PaHvl6F(yt(wIMua=9@@X>po)VYXc* zlPh?9TF==vGX3jimj(91=n;;pk+SF3{o|3_Mi zmh9dWATNCFpu}nR+sR9Ybf;m^@UTLY02A|<79M++@7a{hC6a0>CMI4--^68T9C}3C z_T#2$)!<<;JLm2;6xXZNu^X^gE^dFJ03mM?ibgWt6 zOg+n6qTTfiGjxSZv|u$`()i}$#B;)!#J_vRS|M5sj;W>W*W9UzxWJQdV!Qrx(KAaX zm={8woSOXru5lyVHe+qvTF1rjm#o~0`m4@owp5-+_mD4KiO;uTKrR zgcf;UBkTxsCC?qn0iy$VD-J1BGnMAjaK7G2`hC`o6B$hnmN?z6Vd|TJwKbX8F>!ww(~>2iylVKcLCEAw&Atcsf@c0mjca)%EEi|+9S9D+$_}+9 zkZFWKbwY{3MO-8LW0n{x664*u(jPY3zTYRJbXjvB%J3g%yDl zBH>zbeOWWLSiI&yO28?m6Tk3qD4vX63m8Kx75*DAQbZROi3{_+&a$=df=*IlJGm=) z7|C^DpZO95%3aJHbYL;DyYkrB z#@Rm{OQn^+Wn)tgq}UkYo4j`~lNvhAVJsr-92(o|xCQ7=itf1rPJV--rB*Vi%$ZVq zZ+z1k{&lo`%xUAEmwUvA2_x#77I|3C?cBuKh}DDmDH0FTlDlGODkvcJ@pwEkJ}~n~ zdPe5~>RCrXU8Xa?Nwk^dHOyk)yiZS%*EZXD@%~xy9&o$JX6zb&g)5sMB*KJ`>sebz zaU9)uP~_6vsjbw7@LwS7zB;L>ths>%{967D_!DI*D75w(w zccYEXE4qV4#m`qa&D2{Lhhv@uqfaNpPgJnY4vp3^Etcteg36U#k^7>a8szGKx-g{l zVfAY7oTPYp?VVWw&-XCM`dv^TC>kHDtH`?YdE@~x zn)Z3{K==86$5scu5q*POb%BkFTp`OvHQ-!Rs31l@xyJ@h^k-3vLQj&Ndsiq4c1cB> z#lEO^pG!sb1%3s`lYJ($6J<|7_bZ7Qz^unmKLCYIrR8U_d5L?^Z$US`H2Zr`a=A_c{`;lasFxnDp{N@KUqPB>6mtI|#Ix`34EUy7$- z8PV$CTBt-YBMsgU9X^`KJrVOw6D~%)keA$m# zq9V52Sv97X+C3TW>z~M;ewtjy9F1YA`(D6xgv{SxE#zz3 zgA6;8jby5RcE?#5NDeDJ6Xr@Rar&2go1AeOZ29y0Xe*3Q;RL{Vfiq_IiDaJQ3nFfi z%W5{;7u<|=9-Q@4(}_1zbBBF)=p?^QZM|`cE--$R0p$PsYIm8Oru)yj-6IV2)W$1j z3}^HE;d!id;7UP&h=DMX53Q~Bd+#-9X`XbQQ&M*1-u~RV62g3bmbDAaGbI+)ab8CK zB!E)Bext`23JGFkqhi|BXq^?Rl8QtSv)ZRcCuhJt-bmmbSBG04+LH6joxw|Py+EGj zl@qpb0E6YDf^DUCYFAY}>ZIMtftOp(JyN9Z&r1IA{Ccqmg#;)jh_%@M(I<$Io zZqD1iy!*-*5WXsb&I8%>|2q+-$eZ6E)#w7^qS43aMwrJ6fD^N>iAQhEX@wbG1Eqpt z`10<>NhCnAW3(oG?}Ey!_1Mx@6_c<2#oBwxpoJY9Ssu7<@mSxp)d$S15}49OewO## zC(}DJnGu-BVO3z7{u?Lk*ULt6$F^*8dGCDNgw$ekPk$}r3FC4mS}?gRV8dso z=|wMMz4FR3*f~Ko;&AL%0yOhY!?!EGlqFGLO#c2B$ewmC=^9apExXg10JlbYeS~*I zzM38Q@J#}E%?I_}e%p`31plnnFaIr`js5iFw5gA$Pae8Ti!#fn#b6(5TS@#-?UBT^ z)uV#r=l4L9$P-f+o&@_DHD>UC{3y_#^Q%h@Dzt}97&H8cmib-ekfj>ivZF~K8F!ec z6Npu{=i)&FjMOZ&_&*$p*AW{!lHw1^!_frPJ9qlFhs*)Kpm(*bZ^}WtUD@lp1tOm9I)y|sL+EXio%-en!m^t#c{TR8IoxLzl;`+XD1 zNIPPC(d3c)8O>Z`bBSAmNX?vxB^iJIn$tf5atlFy;};NM_V2R2B)=LX=goKg0yl2L zWSKqpw-)=*kY!qMuT9Z$;ebAgbFvAUJwl`xMWAv$9#jnL#@10>D7MlM?%g{LJ`MZ( zF}IKcz1#btwAo<&VTK@0{hBN13*wZ{Fu|G;=nU_4$t=F(j~n$6FeDADB@S3D-}RE& zz(?x%IWw$d)k5>~y2rZm81=tDOFx`1A|{s7ekrjpm2ffeAD;iP-hLLV<)zR;<$M?2 z>cPExJ*Yen#pZx5Fn_Um#lUs{Y7QC}hh{Ms~)L?UWW3DwLgUqOu(; z4Iz7PmAx~we~;^&qu1ws`~LpvR-JV{uj_F==KXPhQ01+D`F4q9!i_m&&*Y$<_r|8C z>K5dgqJ)gV>jLI0u&Od<+@b2w%3SE2xRj>dWf%R=@mh!wK4lVNol)=&i?7OnUBbFF zACw3aG_aC)8Nx<=G6*PfFm{nN=vbWi4{07-TA?NeXe&%4lH zTLpBFK2Fu87=t63y%4&7HW77bKvs-haHhM>6S1$ek8{ap^gO(a({uGz&d z-#O9I=&)qhWlqdiT`*4s*t!N{TS|d$f=O(M=8@;+lgNg;ozf3@reyJ_IWEg}>^9F{ zymsi>)qnX57&+^}V&__*KMPny0~pkC6>NBV3m57mWx)cXiUKkk7|8h_szv3}|e zp&tl>Hh`e?n99@ORHUOdT zi`6N-3fNwIbDk)`+OGjHOjzU=Okxs(o_kRF9cDUw6;X~Rktfc}rm#QEMNMIm{cFC>^wS9XbnNHy+cJMVcC#`|PzohtiQd~+P zuLm0u>C&oufiC|4z*I2QqI>ejr509vARRPRWDg3Rft}sHFpj@>Oi>ClfJ4($kOQ3% zu_b1~RS%+6flQPaAyuG}Uj}p(Tmk|$6WT)a00~of+^+L8%H$#GwL}$Eur)l&X|g= zrs_G9%K0Ny&{6u>E~7zl+9RWy%f3M0@hAJHrJ-U5xGV1qht%;XkI1DI`p8h*J-p*Q zAVdLlBA~rFf2-m`rzJ?<5SN2MAzun)sXNTVD%m$?9&${En3Hq^I9nIxFm?7YZ|GL- zjtEGS%ziXYo)7dUT_t(&uW`-s0_Y~;g7(W_y?Pe62zKrE8|KE#{Xuno~@ z%$9Dhmc~`v9_Qk!d~FeZi;NO>IBNjBOxqZSZzQ`sKr>=f1j8fH0Ew5Z6LL`4H1hm& z9}N$_A~a!%T@cFXQb07@G*l>d{CMKc^MK(o)(rGtQT@P9&~nJG zkS^d~4fogyV=@6WeH8kMxtCNGD(>|V6GAA$pLyCrAd<#BqJ*aQJCSd=WeXKV2sZ{) z$8L)Kg8Dqb4D}LH!O*j_M)!a-wi?0^Z!)=~42<4Ai51YO#~bwe^{u;;D<6$I!1EJm zaC!=Q_zh}{)krSugw;3pdaAQb^xES4n!EMg_yw*~dn|=QE?vD=eEdY0?Oj~}Qz!uk zF(;%PPvT<0xVDpb0~|~DV;4w&C1f=(dVgDNREARRv-FiZrCm?~6)|n1G5~6YZ^hHb z-m#WjluUHVvZw}w+6JM}ksZ&x^3fD%I8fFX?8r+t z%Lhc>U`!A>*m!r8UKY^v0eH{=kmS=eM&CkV*?Z={w^p1h0rE0tZr-V7_&iF$-r}Zw zCOzi>9N0LoiDTE(9Xc1Zcj*;6-%R)dwby^@&w(Q-DoOyg3k=@>k)JP`b-g&_t`bpqaj1ba zdU-6^j1ag1&3%qUQ3c9luRPb6Nuwyyw%WR3OCSPYvv8<_Em!7 z;ana$eU2cwG2~#EZynyP`tP$z@OqTuHCkLh^+-{~sZTu=?@%bWo$1cc`^-0?Xb@_< zmql0}!h7cW^@alw!SrXAMZ-+(>L&*qjRzIG5=nRKCWN}(QdTb`Av2TPMIKiUv|W5G zWI}rGOH%@XO!DBsUb|&GQf$3v1ekInq~NlK_d!gVRPy&mK~0)w+Hu5v3D$eH)A_s25)|$ck;oMv$dTKb zPo_iBs!J1dG4Z!Eq4O5b2vmkF#_0NaC`brfH9va1^jDvFM8-!j`B8zS;d`6(?NB5w z@NJHx)j?DbEA{t?fEl>$`HZgsA`kWAPvkVh{TW$9Jc|RC<&cw1odD_q>qjW&CEH~RX$dc3NC#8I@ikpZdAapUjwrZZ)>V0af0G+2T_N& zq-3#vlgxwN!F}Kk<9f{!vPB@sT!zxjkCFu`?4N2fm{;M~3;=btl`qQwnSe+dfRi@Z z+>I`6P16o!?uu%<#)ux8!ymyC8a|mP6UsK>bRyJln(^gMP17Qp3xc#RX zU&Fvtt$8_Xbjw2i{=G9d9AQ_e0B9t$aTN-})j@yYs^}5jCqz{Wc6L*|heW|f)O-=! z%0~RnM6iTCgvYri;9= z)r=pzC&k4SAUOb-zOU)AAz@+K83OAiU3gdfidD)5e{kXHi}$xcR}5$2uZN*1Z3o@D z7mHWtX>lj_Kk5#9S^hV+-UW%O8u`2@%zUWfDs`5-BPnDHXw~L)-6q=@RP{Yx#j7{( zsoWJy(uHL{pd#mP5icL+i~gN4IZJ}6f@;vAEnnZ)Hv#R=R`X8((=uphx!Ik6J2V18 zi;;pkb%w^{_eBH9$(_LM0gljJ7B$aTBwRc9o;WL_UGg~KMX%{Md5~^_@l2=&0(03B zfDZ)$&8to;K=RHWv5!iR2LuwA3j$DpHGOX@UH+~dFt%6ojgD{yUreJ@+>V z1{$s2gfmu1eaz|tG&ehTS?oz!n(S(eEDaSXj4R66md0NgA^hbsUG!Y<*OrF|zpqX!?FdkitJ>=f9;(fB{e=h0uZ+!a2nm9^ zIr}NLamjYUTGQ&>OFpWc1P-q>`Ja{Q;nvXS0x9Q~wFtwkkiGcJ)HAI1MMqLnQp`oc zl7|6i>CrR%ol8sd2f2R}4+#m@1!H(LG)k@tw#q@#6+lh#Q15si9DL1=;thyX_?(Vc zFjT$@0l6kR*at4o53#i9wyoM}|0dk*IR)Yu_DhpN>ljMT%;hyHOVsE;`mc_p0{gY> zNs<*`MjR?g15>Te>1w-CTg1bNhCu+OUY&w^GqSnmiX78lsFp{6K1>)ZzyDlc$FgfF z5O^x5Qqu;$LF#_#YE+JaQiz}U^ZG&Y6s^3c8cMfJH|!LDD)7qp9i_++aP;gdg<%+0 zb9I2=c!7G14tvgA=<<4CdLJ^*m{1`jyTXh&e1|e0ya9}IfdkuKFT@%`(4rT$`XSjC z3PcmrTulp_M4sTn~#Idc+1}+F8v`#;~`;53pbRP+G zg`r1A4bk{kO98!%c1H1HXV9edA(S&DJM!LV^17~wnZK|hr0WVGU3W0sE$il{MMzD) zxrI`r+>%lV%Ysc_jqXM`o8AIeL2}Q2xnISG29u`H$z&c$^o4+q;LSi?u8zh(nV_5D zA<(@;(&Fl&D1-I8G=f2Z`|U`*b!Q#Tq6E-aL?Li2(eJ5bW?o+c{s`#l{a~v{`UZ~c z$W`%l*Fv0#F%S&*s|)a=m^$o+LO&uVXAMJfIG7q9XZB z8Jw0iy`=X}W;ZhO?VQuEv|1l&75$AvT^Na*uWLT$v!^*a4%9(VT-rL~7H|y9I;GAW zpgi<=e4+2PErO|vbUWNrne-dG1de(zDw<7czPqjoFqfK`h5IQGKi#*=8zp6w!T6mc zV=*@>cF%!)Lp20wyJA+?A%+ad7&!-c!`CAA(RGt(un{_v25?*@JD-XE{?7p>NC4$4 zaIbu?HPR8^M$bJ1sPsyxc$kW1fXiG3bto-{OHcAYo#BApEW=?gc$avJco%7`E|n%I zUkhgAKk>3F*PeM#e#JR4B`eyz4(qFG*mGm0B{a{4Mua-d3#wb!a{BWw~!too0o49`$n!UEeo@7K0OB z4E{|NLhRuP9{o`K{_hQ7D5*r_ZO6j)=Aks9W3St=nB7DFEy3AFHb_wjtXYL>%FqZj z_~T67d;|~FHW4^!jv+3W6nFqL0<3fKQZw;-#>#R45E-f}e1OOUMjVU7vf61{dyWv* z7TqH?c=I*){)6X;r+1hfpa>iY91X!4k*aWpY%C=`sO2jP)TnZcJIal zg6sL~*9V_u1W03n6_c;v&0vNTbj+PQQe(W28!Ntg`_iRvy!bX46-qUlg6L!CC%+jp z8BLD0zT+2PeV!D@{dwxJ-Lk}CZYh{><+H$anR`TeYOx zi3k7%D-4ViKRuuDJQE9@2f1e&Q!+QCsk9nm_@fPF>!)c~yy9#cBA9_daiRSkxIy1R zt=?^P@tJ_Igd4DUv+Y9bZn4tLu!(C5brk2BT(LkkGLs*b5li>u^&ZchCRY8)uDqpo zSIOyyxfo+6$>A0!BUib))%mqdn+DcfP>Ee^e+Tpditg_2s)bX51^^390E=*VHDP$! zy@dVAuP@4(PV??b&JC|y3SFnCJ}5yJFAOT2yWVysUNxGuYReEn!=u_W!KLp2Rjax( z1s_pZ=*+gc)mv16kmjbP;A|WRdQWWg5^5$NIxxBrYsbvW$`5GP$LE1*A+&4N)b-mz zi}nnbEMSO7^wDoiJoG9bN44a92)7LSqE5BA5S57q2F%7(P5wYHX^67iIOw1J3XEFR zTb)kPfR`mC){92kB}16_waD*vXOE^u8M2O8)TlR@Jrc3+Wy>y+C@9JL*fbrm;?u3( zP*-p`%Xpv9#QbouxBY?!qJm$Eb3Ez)!rIgo>wY*^x~ZFK-8-YN?Vcv=9hONpW)8-sg>FuuVu{B&)O2j(XG}pDsq{D^WwZZUu$c7az6A{@a#3sACG7uyoFsN zO8(;X{X2Z_(wK_Fa0azwojTKPqf5tCxZ2xXOFBor)QX3PQ%1amiXSpQQR}n=9>CMC zQ~HmkCy%DIOn>m5$SBLvJuO|*lD&ZMTNjLF3>i5?g||p_?_O|EvT3mJiJqFXTK`yA zdmcBk{4x{)13>v&SSKwlE}Z|S{-N+(>#1?Eq@=iE1NRN4^j`xj%G1H)#j}lHE4|#j zqOUC;#KeC485kvXuinBk+TYLuYE7iQE9niRZ5D++W4<)6`ynZ=PHCY~T<2?>wJG<~ z;DT6=ROa4Ge=3ycj;*XWs5f}}wk)+^o_vk5HZ_{A-WAu^`5+U!;&kN}JCA@=0ke@%z2r}$L8TyI#o*iNXRzb>`ZMs$bNzLx?6<7D6nyjwd{$A`{q z$5f6f+5?@qSpin&Y}U}gO07X}U0b(iZ2i60x=vwuYK=axoH=e+rbi{aB(lsy@YJ%U zIeWO<~D^FFw(9M!kD-?e)RC=C?UjmlSDUh{4xvo&U?HfGdQVzgNlq&C!J-#c# zt!pMtS+endZefQe7H=HQLoTt_pJosr!=r)yi(|ZxS)X3Bmnez8DcAM*?#`Yb$+89- zar}(aDCh8i?57?DEx8z;m+N2X?eaFH<@0+wzgAv#hK%ZF$<+8&XYTE`<&&)y)sGKB zX2iRdDi6POtlQ4^_pvo&v*Cg5Qa`cQPOxTx4zCtp({pn4x|}cheo8sxDOKLCR(-v> zh0gZ2U4MI@7z3gTp<}AAI-l!-BF1-9C)A&V)e3XK=P<&zFvHIXGBMe;d9bi3Do>oc zXcc+3yu-(FSB`$>Qdr!J<;FB^p)O|3Az^Jbu6>^;S#}=)gF1PVGEa{YmX5vcXnQ5U zXR$P@jS2qi1^TZe-FA}~(F3(v|F)#cs|!D?WO(N%#oU^a(X-te4Vr%Q!-JfG=Z~WB zq`({w=~8~r3L`-LJMTN-SEmp7b-lBN@51X`{mzmcb6NSc^;E{RXR*+E;~K(u!Ywj{Xffb z%P8oO>pL-VSuv)y-%MblQOnda98Lny6N2bfYI!s6;t%j84)6Vct zHgAO`vR_9h?$_1h!_NT{C6nJ%m4MKoC&a0&;VS=N`H7`*bFF?!{)=PT>G|Nz#oK8K zZ95w5ZSTQaj{RJ$61xVUn^cDF<7zCQEPRqudp%w03AFnBO<;D#eyw~=_7f{1H(iR} zVFT?Y=2S(-`(Qh@TDTI<%F?By=L+3=F5+6=8KCo~`#-XSB;m}E>h3%r0I$pfYnUGP zy3YgDqZU`4G`<{`bTMCYMq3d!;3^gAqbbP_9uV%!#^iAs2wzHdJ#gT?J>}^1?vV0G z;WJKn5q^hG7tD@9?9#o3k_gRwgRr7Jn!Ir*b^B_!;V5osaQx5%0K2pFTbBZDE^%3| zn{QJ90UgKhQpi7*@idA&8-6nlJOzcm#>PhFTV*lbA(NGlKU2FK7(hWVFy}1BaM7)# zsXIi9^$v7k--L2R+;AeZfphTZ=nieYk2fE?N!>wxT9ES9x7z{U;Dg>)hv!RKh36Kz zV<&Cdds^CC#cAlH5grNy18X-V0?1EVqv(lC2uGaDuhA7Cwp zZ^~)HUS9S`8+#^iGY0+$Tk-S*Mb-4;gybn9J1lhB zj?!Y^GLz!$Z;aBu120PDW8{hA!?%87C3lMJWgGU7Jbn35PH1Ey%h)ye0$kOmNSI3i zaq^zl%V>j|7~tFxK6vu80>4DmJEeP!(bTYshkPbH_gL;4V^xNcL$dZeJ@~Xl8WtWD z_vSBYI6ufkzC>!;VCSC}Ws6r$ta#A-e_L7mKk+C}%n#-Cei77*BBf;;6nd`J0kKO+d2iz8!CR8*!?=B}~TtB@*_4J=N&fougv z0?dY^SKf`U{*HK*Q5o61t%AlP$5os-@ReO+-7Q`^?0g8gM1=O7I;(!x+<7q*uZlS1~uhF%iizrzeCq%;)c}mtQ+SL`aVa+te_I%zo8G6V3!6`jEn0ZwNSGWNvv|e5cXm{A%0= z`;x}Ixp4>UUFB6X?K&h$H<|6!oO1H`R@QqBDD|WtviL8|uYZQGe>HJyk!&)vM1w9J z78WfrBIcJA*QYn{apk>#Cf41w&Ti-Ns5e|XN@SxJ3O>i(_*nW+tg32`kIU@ZqjraH zB`bSErUr9phtGuYiHVev0;Tumnj7sYc?JiROCOHZ^rP5k-pNj+>wa|FxR}RDe`#z< zbRLBj8~BV%PDsc`TtWC%WnKsZiA^a3|n|y!e*iA z{4MX-!`2Ob)>Zf3p=pbvJ03=pYX#u=m8`nkPSl-MfgjIfX!-a9D$KJ6QQR& zh}K$Co9}F%di|hR+HvKIj8T2_W9^A(Yo;a1$e3FWUKZ=8_O^^mAjfn}+FI18Z`o?N z4m|YyRVUktaW_4Vm3Ov(O)XrXGE7*olt`5l9(}5$bJ_hVL$bG%mxaKnpeqxPt5N3D zo}REaCxIG@k(}b*;TEG6vU(tyzfpJ|MyPk`<6e9i&H4oNo#Cm4jqh8?9|gbCom*h} z`Z(o~KlZ3vaQM-)ROs27LvrNqCDGI62Wj&T18)bEc~$M#JEZoy$%}y$Yp~ z&3{^IV^(LCSIo50%XM87D+BZ68||>FU)lC%<6rlQ74!cZKTMXtHzTZsGh`dT zqJTXzPkGaXgoc%kDg(kyL5Pyi2=$I#`Lm*Giu!zEs7`X0aTzh$A^R3h?7Inl6`?Yv z0Q!(K@`LV6$f1cczJk^Vw`x&E_qor=a>Yf}jH-17a_eQ82)iO{jGwi{s z6O(X+9Ej?6SAM0vhtIc@_rfq+wK=jkrE(VKZ63P{-JfOrN7?W{X_GRwvL=QEahXuT z?a5g-Te)ivN0h0Y`e1gGxXyN}ZqKT&GZoSs4Vem)&b1vdV>hD32=c}PQ0NU{!(1ZP`7m^_vR(9HiGal~ci z>oFNf1;6$^x_PFI$UGdU2k9|1&!KJLeHWE4Z>N^kG0Sc zM~<;mI4>?D@=Y6qO`p)e%~iqn+|_?-jN~s~i~|lTwG;zjp_~g`q&y!KA!nG;cpkuhD*{Kd&8`>VWkDkCbXGR^v12crry-Y}Zdly8Rt&O* zl6hUZ{`_b-AcBu>q#`i?zr!kk3e~VyGqJ<8?455(<-6@mNLth0(%wKrVa{4LW40vX z=oMoK89oBq9;H=Z$RYhXwFhYU47%C~s0MR9uEPvcfm4UQ=C1*ukxZ5F z(snwX0>=b>hffq-{N~3O4;(pL>$vF{JT?2J)u%dmIyyM+?(f812tWzk6Z+5C#EwF< zL-u3~un(e1#+(rlS$#9kk!~X7a^lb!upd{Bvc~%H?jukrV zcBny3U=#*VLM58Qvs8F%&P<3Js7SN<_%&V;Y zamaD@ySKWEMN1?g(x@2R)Pagc2(oL;QR%Xolc*=&-6#x{1`}tjiq;0+T;}VI#_?w|hrvh)G?vL|M+?-g^M5{ge$KgN5t4)fx$lObx@TgHo;UX? z^@*S%D7p%dwg3mcsA|*uMBu->Y-|tU_}Ovst~#iZ)$X8|k|v6}Y%Ej`D92<@J)A*&44Qy(ej}ia6iR*MmuBy2n=(U7u7Gt ze!@n5Ee0&n1(t&~|7x_9qd|wHggiEG5}bE5&k;(zhc}i7Td9d2+fYT;eEI7 zm`I&P)oY|(9Dp4nDv-onzI}haSuF^!X@?c5WpsNlXAKdW=Zi5zq&E|sWgA4jMEMK@ z6mpS}^Fl#Y^&!iVp2~ZZ{qxVX;B_FV5(RCTuJhs7OC#ug5y{F9+h~D4rp#;3T*^?F z+;PoJ2^2cYha2Wq?j-IHIu$0N_ttHKw+r+KvHF1Gfqhwj{bg|AlyL?MGEJR+4S^u^-JvR>_XxmK~e`u zxFcW805o3*Mw(X26VHQZ{{eC5WKZA#4doF3-365buB0d|i!os-CW1jRF+yn031o>I zbh`tTh#&^8AD1sLk*o!5Jp+#4V;p;~)u_N`=N4 z0IXvG@GOZ=00nOZMi#_VGU5_?m~`mAMyPoA%hZ%8E*F*iQQs`E7+haWGx_`gI#6O> zaa9m8`N4ov_S*lj8}QfhP=(LE#}9@8g36B8w`Bh|%y*g$2yBWTwZmAM6tx8ZiU;#w zzXEFr;6AR(exBSy1yHKMT7SBAj}ZBmUQv#GehMLFxUmQLQJ>@6oC%;A5a1$EN>lF+ zERbZ<0EZy6&_ZX`@d=>W-=R`A2qm%IJ=^PvjsKchz)n7;{+u>L z1O;fBoHBxm@2G{JFU^Bgm;XYJU}U4Cql4~DtgLzrj+tr+ijNk;r~duW8(vi%9UeI0 zAI)g=QSOVY;ljaCw|+RpF|x(BN`3`gvNE1q|G6K8C*v;XVYH=VypMWxu2 z++@qQ#zn;E@yjVg^*QLowyQV^)4$O?(a-KroC(~n91dh=7Pfg-x-wI!_Yd;$XYiK& zBe#gU7F>xd7@5hhXL3BKbC_u(I=VO~c9c2%|0uyDM`M-JS~3juz>3PmUv}Q=1)Bi3 zrHks13wgOtti0@v^88I_P&I5oS#$z`PD}QBZgn_Z}lc3*q`kG1?PjVBl8 zO?CkZ9O2O}BCp(%o!y-{w8l3I1MZL+B!6J3e=DR3n1?oUBf{N!mQD?*w{lAF#F6Y)Ex%=a@1^Mjr^_j2@54SNi~iV6nEb=>gaY`K84m)up^F|kIIjSE&%tk;@#6&D z#3ax^9vKZJ#K#AwpwAN&Taq&#vajhJY7M)duWz{%ZDfU~3o_*GwCA~I8`IiG#)Mg{ zG7XChdlLWk_{QmjZg}al?SRxjrvVvcU*ApSiipHhke{dd%W|k3k;T%XF+a!!wd0jq zoj6kf^h>eCKDgM66u?Oey(3qlY4=#+M+<-D;-E<;N&xt4lTNCI8* za!p?e>YwfdBd$DXG+2Za^PY6q@z$Ei(mQ+zvj*4!1!%Cink*?OD7f#TTntg%F&yMb zL-${JLu{?2yu(o6;W=Tqk7FwWVgglCe51I7mH05q6waafz&%;;PRhFVL;(c z+d0&=RQ&rlqM1YxUqG`@1)W9!q-{9){q?LnVZ6@%V%^y4+<&3%W%1F zVKNO4*PT5NdPzYErXBI`M##urCirJ@2AF%3g*Fkj-5Cj_#DJxR$r|a0kk1q(y4#tg zJs7s*jSfAwFBD@T70IGdT3?F9b~D4ChtOT6$SKb*9nmGc|4&cL1fbI6nwXvsnr zWszrd+euHt0)rSF3iQ=rq(`0?xD#P(;2^`@3<(+&i6S+_rC^}#zCgtj@Zk;b@uAS2 zs{o!v#c^jcrYKuYALTJ6!5g{!3dJ^_k0%f0K5%AvH=-P>smY?8zU0Zm%WBehFC&XtUP6AbCTCbQZC&xyx)M zlgL80qH4&Vf#-+nVJNT(MV~aXWD|5JK)vX;;UMD_j=2uOt*stR+zezBcmCeov9*UA7Cy51L`0u2CIPg0riM3`$nxe(U*GW?QKV`82KwzV z(1EktqU&e~f}lY?;x!1+=YXA!Rr`y>(vK_w&sF$)mMy>Hs0zmDQ4Neat|E@?h52Xku{ccEzqtn;EJumf3Zi=s zP={ne9i%pn!{p8i^Jtp#yW7x4gXVB2K)@(U(kvkmDk_1p9K1aNlEnYIMp8;jiZAMb zFj1EVABz>rF}r#5m8u8O#J_#xGS#gM(Gy!s0%2?oG8%L?5JrC5pXf!rabzb@bOOxF z^j_7ysUtf)qCQ3WdieglMdA*kfp>eJAgcD{^Ek-0C}f$}bYuGgL;D;M^N)8flKP-! z(=b+6seqLG@n;5{v>!H8E@RENi}w8Mb`>TEJ{v{zTWuCqz59ww09o`#Btn(M9tExg zVpfiAXe1>iJ~7ru&=WND1rtr-{@x4&i3T&XtyXus^XMtE63mECah__Tw^;9buFYt! zA{u=FdG+J%wH1VLierqzIfOAP=d84JA3u$k7-TrzkB`)z$S`cUhGt-cHK1myAN~e0 zTwGetowUj%!t!**Pp(5*&iLI#sgp9Ai;;7|*s^Z00Qa7ccT#ky*vzRa0NKlBV!5nBg9*>whw~5eNi<%gN_}w zLm5jEXaMhu#FlE~yM(O8d0MPCg!yRdnP2DYgyI{|s64jxTR(DLp7FmUDkC5B4&N`l?AvBVZxp6WH^g;^kKI(w`CzwW zIJ%2L9IDbIsfq#@Dg5Q)$bN03q$c~hgI@K*8>ZbCV^zQLJ$S=&bYJ}bg&letR;sr- zPQhG;A9LsHL<;&k?OC-FJ!%Worw)31yvwrV@R)X;?(?qPGrUnZryO(m@?p1|#nme_ z52e{qA==pE!=cCpIu494rjlkLZ7BM#(?d2#`ChNq*49f`uU_r-7Dq2a3-EqHxSK+Qr^md+NbJ2hh$?kMpj&l2895~#hw5Ik^2tF5|3&y5{128 zY$PDzUTPEuSdA~xCiRLQeeHI#8V-)`-rbK9iT_%lgmGSH0THX2S$A1#Huw&}kSMx( zE}*Z494f`w*jR7MP|2!CE!2U&>&cqIg*pW#Qh6L+;{wd{qM)s6CM>~`3~sGI0Diy0 zJhP)-2h!`4;-D~fGW3Kl14!xjlF~%l$YqWWy9y&_dQC1@37wO~#lH^&i?4T=@F*|e zU{-K4)cHx5nHFmFqhw%bv{TO~q$~3rNv%FJ1oEnJA69BoC_Ue)&5taw{NfkY4^fW&k0lZ05p~1 zeep+oMm#rq{V21%%7G~1TWax{_&nHc(V9G2tsGhsH^WfBif1%njhh3`E%|21ltW4xoz*EGpT0*v3U1pDx7dYwPc8f z?w91Wn@X|X+S;%*I|LI(*-%G}JUBs=q?biyRU!PQKpeR`@fKdVJ@aW-*xCm0IH6q< z)-E})lI0?slqV{tO$=MT2B++S++?DOi@xWmEsUg6?z2j`p`|?qC2<2r?w1~8ok&3@UXjO z?{r8J;oY#xL9}I4+%`UFLx>AQ+jIlAN#K(84Yc3MCvjAa$G^b(Hr!pkpr`vA01ov` z_;QtqkEzX}8D{_l((%+&qm^+f31z)NOgn351q2Eopoo+119Z~AV(;x`n5|Ar+<~?& z`vJzlz#yL1ECJ);-qPA?UM;V}tDwSP*#ZmR55>w_srrzTKB$uNLsLa3OP9k{v=Fq5 z4OEnQ%ss(6bm)8NEG2OoSIZ)fzZ;&eLT^xYhjk~onrmG_OZ&<_15FPVkoVW0E(ac# z)O;ZN@wfk}B}-U1<-TL@;oDD)MDyh?fkGL6WpJUiSON+pQ&F)Vz&t`-n4wJg+1Lc~ z#wGbyRpP`^CANh@*3|l zhwn!o-VE6;OneHCQZNnPoRY*R62t*-)+uOG$#%!<1GD9AAe*{yjCd4$vc{Fqxjs1j zERV!ry|AQFBdJ-y-%}$GO6UoChjW^boKiG79bRF8~V6SEPf}lkX(op7w{rTBRxc%ArWh!tr zM1MayGge#+?b6I}SuY1h$r{M)8iz^^Uc2|@g0 z=#Cd}j1VH~PmUnHe()*%fz9+L`|b!Rms2r7H%ExB1Pj;)V>>iOqP9M4d2Kt zjpnU3$)dY5;9<#YNe90$> zuO^GXz8B2ONMizxKJiyz#pVojcJ{~Rn~2L%+pm*rqYLAoH=_h#KHLcp&oqJ>B&XbW z9Q4tv7lwq}+(8zz+C6*&aO?|5^<7#tZv*MK#<}M`Bn`XDBp>3^mT45D>1+hp+ve8R zb2?UlWIN^1U$!&w3_%pDv^gYyic5|b9ua`+TX(HVDYp2C;|j8s=z35y)7c4iE2uHrAH` zV^{7v;rYPc9eWRbwgjr-Mfr-{oA`l(0L*?b(X|MYLP*Qw5myLx^lBQ+WmeEyv)vXtL+F{ zn%X|mjlaKt)B60CDOTEqDhiv==8}(*zh0I(@%v&a$s1QYc?Y6X3!(CFTgngZJO*rD z^9^p=6862&P4mH&&AI+UFy9}|1-%TQ{x9e(?V4X_`D2IGwn%2K}j4S zlXPG8EcrDS>`H%0)Hpos+kY<3iYZB;6_MlzmZpV7fa^{e!3T)juLCfQB2ZVgx)jqu zyc%d4D4CnQWOAEy5k@Id=03`QigzGCZDF*D`@!ym&z(5o_CEzK=AtI<``s|WYd_RD zs>r4ZS8iWs8T3fg<2MUpv^t?`DLR(?c2-b)y(6Y%S3K>-$<*5D64Et;RlVbe19e}_ zAXo}=MJ10FApD(&jaiRya?gaZ0Qfde2Unr<2d9+0O%WH*G5>?7z8 zt$jfLfQ_fsneJ)al`$vzm{ZeTMS5-m3_AZ*S;9YUi3K5bl_p8n9tQaknnabD!!0c> zr*3?Cl%R-s|H=6~LRMBUA-2ieFH0+0W+CMfw&wuAmKXs1kL0wL1Se zRlzf_ronA?ikwozzYIE)O(Ai5O;eKzSg|S#CXoXRY|e|LXP`1R0y;AxsDqnytg$xW z0#*<4*!mF;I=iS0jL$~|aO=tnNZ{Ma+dmbYE?_@RO}NjIh-gAK{&H_(6^6GzI(3zB zsR0SfG<^4+Kk*yhm(A5lvqN4gV~LMD(%~WsDXo8MzS^>8^(S$Kg@t$47uqB zB8D7Ur;ozs;ECzZAf#MJ8e~KE==t`d9}QYR7+F36^NZ^Y;of}TFaSmtQ)ulJyKiM} zZQ2;GusRQ1@RvagJrUfJRm@|!Qeo{lUE=>(3gG4wRjG56swVMykXyKE&yyfBLDZnC zx5!{xxKa`H27mBeo}Jj$G5Yv8Z@q~3+F!-D?~Mp|jt+IZpdk(mik>4f?EYZygCUG1 z2zu-Yxtd8Bs2uYPRT{i^v{^+RjN_AP2dsE~mtok!WCI#gGELrdzb9ZSU*Hiq#|-Tf zKT1|(KH)=OM<4eBi#TN9!gmpd77nEw@zsZ1{KMP*f8{)Z3l!@0VY3|K&$W;@zFlkN zTpzPe8N1+qPo5~WA;;iN3Q4w^gdI~dhIzHOVQ^||*C6EK>ZH~}$aa#f8YcD?1^A)N zqd6cvq60xPM>Xy1TAs+$ifY{5iCh`vS_&w&^nhC829^^>USV2?LOgS;t#>{9AW7IidyO zP45T_EuRF*b{lSieENgkZDH_jT%19CDM@sz8EsI^V98m$7#-h`{CE#?3+_ zq3Rnl-gYVA2pIty`YW$azPZR`6M^=SPtF)p;D5l{od=T31^2wQx9saYwc@9k4g~(g z0;DS*`9QSu5JntF!!cd?_KRF@_ab@>m_oE@DjdwFxRl!6+ujO9o08=dqcJ2;36@&5 z50ceCobs#*i?2UH1_8k1eOAe7X-9e$fMk+p~ zRV}cbh;=L&o?_-cI(;uHy6?O}7sp0r#7FBs%)5Z_-LAi|Ymn^>Ft$zH+J8S+-oaDY<7)1m{0XE{z4FOmaWd2RZ)mbI1D4bX_ehu@?U5+XQ9CRljeiyR@e zq;`XT>5bpgzo2xPlE+{~ZIs|YdHImbKGA?pA^k=aGSlnr?kJnIHr}Me-M%=DNEs_ zGNQ=v7>*7+}k7Epf=hMG6Ee`*OeJy2Mk6M)%80$8<3ns%&4J9~aQem31%t+$*sDBm=OKVj{vm8*315 zbVzwYPH#}A=BpRK&Y>+e_P_qizK0n1D?h>6xdBC-1wo$T6e-WYGZVpnL@UCx3r@sQ zRL+BNg^DQzi)PC20NL>PeN@f=1$fv!Oj11(1mS}_)=IDQ-uS`^5ayTwb_k%|HlLll z)fk`r?p+OjX5O_}11F~Wysx;*1EgT?Sqp9(Ziq?#$l^Xjl}`)vothya*pn1S$q+f8 zf=O$U>rHik&FiAqm1E}TisrM5g$37jL43gjaiM?XV2}`1xDH`WYz`9oRdW3pf^~VB zQU;YOQ|Q)Mm=e_VI4I^AKjv-bzL6^j3shtTg_g~jhuoBxd1X-B{0#|{K;Uml?S0w{ zG#9tW-{pmh`1NdE5=9J$rg<*}y}(#@#3R8+Ii$-eXP=eI&&9;-eb^qOksd~`@Hndz zxJ`P?XLKH3p@24f3Owlp@x2hI#&gR!gTF?TLz9g^^Uu58o9*kcireoh35$RWbAc@7 zqfF|r=+uJg9$+7c*0gUUhy;e02GBVo9)3#@-Ln922)WYc7s@=PWd#Q%^@u)tUKt{? z%!m1pzw=7hZHrlpVJ63KC8HHJH<|W-Xa0l&v?;57={h!G;^h5a0NS$vhk|AB@>RuH z26FJNqrEH>xUR3*&x0njeVkIGuw`a3u^r&=Mm%klC7yBF200{@+0R(i{z$ztVFg4G zRTq5@8%#$NV=?A@7#Z;k<&8NbyN+In{KK6hN_|vEF^gBF| zGR>u#TU^&3_`NpaBq?&EqZehxgCBo z7vSftV_!!g6!%>1>U$RGIlx)=?;cmlaui#Xf_qAE14`n~`Qzb4V_0`d-N)pqxxJR~eNP#cMc;hen5`A}iG-tI**XdL|^#oA5 z=_{uQw?W_8(&!5*RWWo!k$$Bgef)v5i&k4T?r-is~JAfHoH12 z#e?UU=kO{!+S4?;(X()N-F=$QBZJoE$$?WxA^j9S=ME!!%t1St1WF-~=6g7f9EnDRi!xq>MxE=){PBF^qx$Q@>#tNQ zI*~wegp~z)&%cGc0t`UzcmqPf@b>iFF=%$i{#Y3Sun)4dRrvHJ)CK zUMk|AW&i@2(4Iiv`sfXO<3GWs)OZd72v<~YF(I3TW1s_1FaQSE%eqh8ayNYs(^ikINRZTKIQLa=h<};{H?0 zS^_4}WYxQ6oI^5Gh*io4lD{uOM`Rq8qwZFLsjV*m#(ONLBvBiDZ@n7|Lr=b!kEE$^(b)oZ{8~=SqT)f%hxF*Nh$8Zle1h z+!7U`oOilHBoph4p`waU%9~nO^kJ@PLy*~_@y3xpp=0UiA>Rb<{<2gXEKx!;KL)ZP z(C#%91>(POcr()5e#s|H%DHfre|@8OQ*hmBWocL3WOuR<#9dAhKpykGy?!)6jEK`vI_$l~Y-vmVkeG21%izNOwTH1RL`D#TYJ2 z6*Vx73vcBz;F#3F!x#Gc{}FcGaW(J%|LPX0FNKC%QZ^+S5z?@d(V)FEQnX8jR1Pvq z$|zJSNqg_1fdzoG3)l=?G zPtgc1^Yz)`9hzr2B~Ng;Nz&oFmnSV(hs?Kx=OIbAU5;tvn*{pV3?dM$(mf=(SpWKrEA5~Bj z_L+g}FSM!{9NcStM0cBt*M{R#;Q;Pj*M%(YM{daC)|=iQHNfF4@seo@nj91XV_j>YG=6$Wk`DGgzs!O=NCmgyhaOjSS z&TFID>vV?ECY{k0%!xs|a&{fKpRNE1q^ztqOOAgG(N}sa}@!53rn3g)cEZByyk&#m~mz73eXu_K3w>@#fr=zu?@>pqnMd=UA5K!mZMkbHqK@)c(7d`Rf(; z7d>D|VVb;}fRosydFf@2_Orzoa+>&T)H{GGFDqAcvN;;ytM~ad&@>ms9cek%4uAgk`AIcwc&~#tpM8|6?3Hi3!Z1+WJOnS*Gm;IClyaZHJ6PYkYjP)2PW>pO`Z(M#K~(cj&Co zjA`tH8@4a>V%;Lahz;jD&Odb!hx+>_`^etp9zSd}pTV^Ia*y1XLEjjjapiu8P1=3y zdv5m$xj9MXMx4hGk&UDt({QUwrV~jzVG6IRP?o;<_lL=-&GIJ%&>JVpe}1ZyG@oNl zKj--<7>Zh*kovkYlX3}`h3omcZq?C3wScizuT)ML0Dp}^{vbFsG+%qogN(LvDmB&i ztX-E*i&ntgpC5-54`ZWs(v0y9mj6Z<@^L@V{DbzqTWA~n6d1SmdHs_)_%EyVDG-;f z83Q>&QcS)d%10Y{N0*pjpu5G%Xpx`tJ^jOR7*}u@2M4;>J{p(C>#Fevhf#RC6?K5T znAWk2<`L4*4TcLpqse*$`J7iv%mB{j!Nj$8+~(gHc)BCx^fVM=Qm!Wje6=#!O0mD% zCa|_|OaXbig%37-dSoARo(htNe_-IsF4ggP#2a#+3+sN_zt)W9nnG;%{Zw2Xm z@O;p=&g4(Po{5wMYUZo{Zc!H{ossKI+8V=*4%>Iw}unN+O{jm$dNF}ABL?WU_;`*F2sf+R(xD3-6B zT-*4^Puo&9g0r&Top667V`d|HD26^{s$H>2Z_Gy{nl*`f8Z6{I?>&V4J>&`QAS=B> zKiaD^wwZQ#p*7k%X_)`|Ne9}>9}m7Fe$&C9`r;qo%}?B?J971P0UQKT7PsG5d^Owgs0{&X0OU-;M8=}dJ-a&oE~zC#(|JLPH*z8CwC$G^QP|(3k&;% z3G+@M9xs6t#$`GC__QnhkBy1|Qc%a=zV5)dun1oxQz?(3*fR#taz3aHr-W+a9jJCK zUvyu17TGT0xU5Y@JMKDmfy5P4|4?G!IZN)JEIU}&1eCk=p`0{ZC3C2>0uht_wWoeM zObkAl|1jsFwQt6Y4w;XeXhS&--12rw;oTO_+`m&N)7fcb|Y()=!uB~aE)6Q{1 za3+33DMNzBbYxRB-MGm4&87oy^9I=0QbX!G2Pv;!&J|rtlCxI?{-Q0ZK(M<-Vr*L> z`f#qTuz$aQRZgjj4iC}hATe(t{cDp^8u%nJam%`t&v%lMTVT!@M)>#<+`qzR8D6uY z_xCf{NC?tbM7r9d9J%v4IG=j~B%sZz&P{Z0Y*sfC` z--X(Irm0etqdC@UEQ@;gE<*@k}h37fNM>-w4h zTUb1`ur+2tjPpp!QUCdO(0VLU%vA0SCe zbULg#UW3~Dhe}3rNBhwyccbm*#MwzA%7rwX(crpdXtw?L0+BpqmfCnc_!A_)y;}AT z4&Bv55mTP#xRRPCOz>Y}Oj@_Dy*mCU1E(xFg~x#@9ad3M=@OpOFoA3CZ}cGV@mw8^ z4&eh~nL}aHyz=M2Jihkv^If?*{akQwq(UXrNLIJFKSa)sze}m4|01r5I5!zCc#_?u zzZ_&S*KByOAK?PKI-roPP}J0p2RX!vLtx{JKHKxLeYYxDZ$^c6Xa~DHpld&zur<2M zTL0ep$=~FlTbK4T{o{J$@+P^A^Z{iB=y0>Ds_Ohc(CfD_C)?mc&r?}X%for@ZXj+b z$*v)|AP&|$crqihX<Z^iI*~S2JmJdUX2vLCXh=ev66#GdZWu-B%=02m*B>L-YO)&sR*d9$J%hN96 zYOG>T;KjN0px5k{H@g%P23RgM{CV4Fz#JnX^FaHo`+Ux^+Ut-3?J`!#G_>iAov(p$ z-6r$CLj7dH(cKNPh^B?7 zvt%1E!|l2QHOavlxWST){`9U=+eY5uhFRv2R(++4phFMeuVub4I@t0F9%WJUAU?yCB5EcK7mLT4p?*;fQW~}O;`4_*Vy*8&!z!Wb1!BQB{2rW$4>T_8*^eM(^U@57+||1*FhKq$W)7* zw}L)%LUVm#(74%ohl;PoIwj#oo$9{uqGQg=aT3TkMuMB)K>ePWepHE^gcuQntxzE6 zCV3!}SM8@%>lzd>4yVmVyFC$F~DtHs5AQQ{wENI zLd*S-E{R05>2~TN=yQRx{9Kyt{+Dt?yqb?26?M}x@!+_qHaIXK54HdX`Ud8GwI8(r zS#ck5n{DJkvS!RrMh({|OyIde)K&%zN4ah358JT;*Rh2JtRau@qF#$^U)*{sHun>* z*ex*j#ou4^^o)Bd{}H2^ffFt$)x%NYCO5M`{`5|DRi%8@}+P*wLC`-v=bCXjt&Fpb8&BhRr+JM z(O4vA4fLbmCB`-pwx$6vg<*`Eb44)N+5Zs_cJ$d$YZ%6+=$|+`a5Y}*`2b3SaxmM2 zbCu88W4o`41V@?KUQRv(S5Y#DX?UnSv+z>KS6dCc2+)|#-v}n1kmCknJVaH1n@~l_ zb^E)|f#2{eKteYb)kcns2W5;Me$h4Ev^0XuMDWp^8K}B9B;OGFezdlJq*gpkm4F5~ zdDkD=E~1^u%P>wT{F2Jht7Wd)Ng2Hn1Xd*zk9#;BdN>(ejivM0#4n(~>aoFZO&j#` z?_s{07P{bV&voUkcRTfirm&b;2Z9`if(Qs4+hy3BfLQ^8)KM$Mi;5So3;zCw^#K#J zQJGv86RRqCssVh%nAhtMGU3H}spL`Ef$XZeS7Yp(nQIssZ`uM{RYGcyGu6 z`g`!MdUWQ9^2ipQHc(SC*7c5NfQ9&#F#AC89{#*a;)amj*MmJ699EWA|07+t*}f$5=IE9%2?)qJR<#4^d)7Ocw)*TI-(Rng6vAl0}jLv_0&K^^kvwfgro=r zg$Jq6Ch-X{iVYarApN{gL3W#7W?VU^iJXIpuXWX_IqJ73Z`mJCoP~;$TmZ@rI%0B! z90uR?z@;v$-eectip{)5#!&6}y)2-N03s_oDYC8e5KtIm)TUl$rYJav3)k!ZAxds) zuo(sP&J`SMRarr1zLmGwb}b?g4n+0N2vXu+=oyjZoco$?)3H8NAZvCNp&1_HSym-7 zB011tS`VeiS@TopNBaR$VCz!<&?{wzA$a|_TqNXA{ScvusIAw7rRmaqLV`97gXc&K zyg}CE_k&*h{MV-oH=R5LFm2V!Ll5N7b4SzY-3GB)b3|%bF%(au@Ei$A2us@EVQf?; z!)NxtBx&lAnpVrBT`aEyf1YiT5AAJ|uNetUA; zg!&#L)(m*T7M6w7$tMAw!2{3WGW4#C0TtK0U~_pkaVRhrJSUaCZK-?@oju#(o}@qi zApifL&V-YspD?l_f9TDg_#*`Yp%hapFZhe=@pgGOx)&mQ&Hq;k(QEnarx3;+*v=sc+7mY7(KNCn{pJUX7$F;G1I~}s(#0l94 z)#GFrQbrTdX|*H(zKLeP6=m09*b}BR!ru})sdEk*=zB~=w^&v~*6h_aW)0z5H}Hg0 z3w=t!f&)Q%5#zs++|OuK_iP(U%K{g2n(^n%J>VV1>Cix4`3&L%+9q1VE2Y4L3?9MI z)0>D{%A7Y5lAt;j#UL|&uZtOl37kDcHFfeW-)KDK=Y7bgKPyQ?~%zxQ2H$-Q(vnCJk zB-;eKbk_GTg{D5rpR-OX)zH{Ct0f>f-$WHefe~e`qktcqOTu~LT?Mejm6ao-IuFAw zElI#b?YeXIyx(1J8c6?dnZa+|U^i>$OgPJ|1}iD>J#rAWSrnFmhqo2I>7O80EjXh@ zBP&a80OZ8^a*ZnCVR`B_AiRDXnn2hiueJ@Mv|!O#H_I3+W<^uI9Oj+;nTYzQ)mC%^ zp2NVC7%{QKf&%gy8r-<1E}IR@K0lL3>g^b^pMM=~CNlUzU7Sh6>0NUI{u1~aOFX?rFVa0pP%4ex+bnbXN&T#$3 zRw&-WBQ<#^Jeqi-(;)I@j(?`KV#563-sw=9ypP5z2b+{o{4i#ppH5_Ix$ABavpe?+|1`^BS7-0dbIi2SI& z(X|PY7hoi5Q!oG*kUZD9Ud0?cbQB^b0?MjS#|xemNa~v3UCy-Cz<$Db^TAKv;dk)n-q~Q22xs&qMCAa1to4>g zD(@y5N$-eEY33@es-2cs{l{V{97t`M?$lJ61bVDF3DZtF#}2{&wxe*O=9AJOl#|cp zBM-%v0@=9D>(+#&^Iglr4A~JV5eyNs+-~=I8SjlK``$1D`vsSE-kLyer+wq(3TgP_*RajUga^A;a61NFOIoTR|-!g<0`ZZ#c=ZI_~Fl&S$ zMz{>qLKd)?U!~lGk8%PB`s`c&7cis^g{pghZ>iZ)V4^)Q&*<*NfyT^67m&4}sRlct z*zhJPHuR&A@1idu(00VyZs1^grBy8jUiU3m@KP)CV*eO6&*Lf27qG^-pJ_{*ZiFQD z;2f%yovRicUzhwIvM!RGLH~_yD(<0s7N7fkdvCnOLE7cf!WVWD<9F|B7GhDJ`hi@L zZ_0+eTZ~k1{FZM_g`wCV`DT2no_$v0zKfD-j2Bu&>t7?#c)dTRDy7ATTcq}kLf`ZE zaJOSC(qtws;V)KuKnBYGgY4V$<2z1?WkdG_Tf)a7G|9YC%!A|sZ9wpiST!LwPa{~Y zRw0Z^Tz)dyy@g}n&4ss>3^PC9IY^M}ru?HizxcNC-KN|jaM6w9vC`xFkNI_^tZgEY z4h{*qfqr~@;Z8p_suw3KwZKYO*qq=vbWzfgkqjq?XC<~`jSBTgkOU7g4B^LQgNPvj67!YN+;iTlT*rk0yW*f9D8Wufh6tdz`A*LsT-Mq z8&D(idPd5ISvpGgOOOwcbmL`dembx}0LcvjAs| zWSvi&qC=}OD1)p5`%}=|4zvEhzcwx>5OsL@`oGBbe1InI>?F}Z8*>ffR#I|B0<^-M zXMng0c6A_zI^8Bz#q^u2LH4*0xMgSVz>89Fqxu3$|XVt^iJy&YMde(3Az$DpSQV|2|4e8Ju)e zFq_mU6gOeSTyC^H51LT2zOG(vs#zz`D(&GS-&bBt0?xS14QNmdm(@pr|+JX zAanJ#sFlUO`|>$z>p#u;w7UXkDQZd`W-3p<#~_+aK3?j0zOVcU(&pnn%yj3seLmqr zah#Tmg2UQ;h14Hh0KVyJdf^lIJ6x>mzZOs0=dU0v%B8dP9!|Um-X5W#k!!(rroMEj zuY;TL4%XrpYWb~O8k%o+_i2m-wsq^Ou;qvY7zjkE_qY#B<7x zSHIrYCV_@o2PR$1Z-mm^^*wYA*V77~esQKBai&5Un_`wuUX;rWqO>xe<}o418WL2$tD5IwXW@>zHRV()^+FnbZCdvUM7L&rnQITk@QG>H4MYK6c8h$%K2HtOg#%b>go78>( zG^u10&XM4*C8dge;=6TuDLKxZdH#EyzvUw~SVbLBZXcTkY%L@7DBrLad$<08XP9FX_2H7ElyxSmB4yJ)4Y4|jA` zS9In`b*2mY5w9ePtKiTh+7dz!e!u6GjYO5i{h7csdChjyR0(o|F_;tbY_~#IFsL~j zbh9o7M@CN6VJbS2jrWeXo6lFwN+E#xt6d%NL=V&*-M7emkEV5{o_P+t%AU}gNP?hE zE%om|D3XFDJ)bnKNgup#UIqHzqS{3W2|YKJRSdU|WTiu-`A;{Oz6Txr0D6}b@GNIm%XuT{V{9hpdZTTjDfmRuwbw2R$HxRWv5Bt$DO zly`VE`KiAUvU~_l`fyRj+{ve#!$DY*XhD&UyXB7*cMA;~2m8OW!Ehn=j$*+|1Q3L= zb=r2lrG!541N9d^=UYRzg07Q))Ry%0pj@Iy^S3*|^^ps_G~|l(1FgdUi@&o!;&}#_ zcYniD{{Ccs8xd0peDdxfF%|h!@oEYZCfUG;{8Ft?A7&M^VBM!B*YE(tB@*IZq2yRk0 zI^M+O?>BH#SQLFA8cmN4RbNUl4is7$c3+qYJw7djq+DfO zs}}qDk-Y5?_2`lg;F-4w$>Nq+U&XG}w%yZ&k+PC0pg$(ebL+LnzwO80nqs)^%i_Le zGLJ5YKN(bVac6N&0?VPC+KJ?rmcp`}M9UC0b^@e!lIP`bN z$~O~(IQL!_qPpW?=k*Xz3c=nJ{UV*gmi;b9#{QLnJIy=An zTI8=$3m!o|oWaf!tA9u8lLCl}9Dr=r{qWVs4?@zJu^m*~uJLYMj`o6aom+>Vs%XRB$OeLBEF#J{PyN`BJ>(*7nw5j+DUt&?Uv{#OYqq zg{nQ_`;wr{%iA&~alQwU_0<3^-UGK{Np0^$ko-#pB~K8!orh=z`Lw4IR@6npH3k$7 z%rwvgmYu!{)jy5zkZQUr8zh0%IgyH|VAs5lgyyy$j>p;$qo9Xyd=>^eI`AP#oSopH z&wPOk5TqtK?!BNl$XKry&9G|N9yI-02T&9TljlJJ5gg z%_Qv0Pb)O7^bkekW}7yWB>5o05Cley`?w!tV2tlC6Q5DOihMtDg_#o^NX-Y-=VzWR zNP;A{$G-VUs)$IXdq>oNIG%q{0tuUMZ_yM}5A8lkV06f9OUI*gq+*nKTqM=*v$~|c z0j)m#)F2>Uj_;O30{yZ;KKftguJEjEiT2mr}dg@%POb3Ivr+vjX9Jky)Oo{|Hh9qH{i46 zfwJJ$HoqCSU2-R##Lzoe8mnbEbF6=isnvJ;BP8Onf$=4>0%vdD`j1DWS10_G6;=fk zY-^flz-FO?Ruv#SCO5d*hSvGebpqXUW;;vj(#-fENGw-k4Utwj*zj&2ZvlV8ShGmx znuV=MK;J-J$5L8`J@3nSVfL?gr9l!GftOLQd`f%_;T?$AvoN`=+)pb!cqqd^Iz)OU4$3BQpE3sad5l z8z1-O@jC24OnI2K7@plH;&KtA4<)4h|E!qJ8Q&b^eZ}hMHy_Z2!>IO3Old;|DI{Ms zQ8pEN_&XN;2SpP~qmu=6)KjKzkN|Io zJ|ij3)g-?tzh(s4bU9sQS$YUX1^4_oN|_jTKSFlD=c}BRg{!oVzVCUgYQV#_g@fK{phF`A!U{}H;MH{@}C9oR;57$ zU?F)cohCI)J4?V6Uqgz4lN&BEe-s-1CTuN>4S$#kZJaq?0z{q4yC<1Wfr+1w z9$*zPP1iU#?&19}?YjcrtM;9|lkcX~V8NR8`i0)oN_G7vq%w@IlSKQigy~=kO&^>^ zXc7a+cRpaKPBN-IQXCE3J$=FHE-)c?9zXM6E~R`vdFBh}%Va05V(|$ISa1X1ea997 zxwn0b^JdRmWO)egwa6gXN?7I#P)Be2jXG|E>%UefV}}oLly-MGONoTEMnbB!71|04 z3SZVkG=8eFf7;!9&v4OR^FE$4^&a89y3pGjPzx%(q`y`JG~{DwHzxD23hoC#$$rz# zt>l<3yh~Tby$?L1EeOSn`^p_g%6neR*>7Y{fCKut_~_7-nwQ3Ua%a#S&l+vAaSQsRmlZX z@kDey7<&JKAj0jVl0HrPKgGe|N)|}_#}FMexFC;h$6?V0Micm;<2L*NA=V2QzUH3| z(S*`ab4?W+j^p-Xbp=t7!sk4&5nFNc)80N7Na~BVNvJ z{Vjn2OT`QeKq-SiIwmTF@SFW~xY{v5L!{ZYkkPL9OQ}jU_HwK#2}6o-d^I_wlgAGI zqbuk=ck|iFjXh_vXAL<(CFHW1G8h_DycJcXpBDHI?D0n5oOj?Q&vYq&_*>7KYy%3R zY$gh!$jg(gv~GSDI*8;54SMIMK&QwxpGjjnzAm3 z=AM&rh$*=rb#7=}@u49GAdXqXFX!Ltn;4eFqfY(i6liftcvM8BM? zFqj~}c7&1b#`M5G8)KlHPAGZoyogQ*_JeP9kjVXUU`GGd_{>4C%-7=2EN~f5$Z1Y> zVEv_-8fasmn|p<6G)dayQS9iCMB9OEqIS^)wtbu9k*0F+udXgdC#IFf-i>{x2r7Hh z>PI?xD1=T*to-~1F`9HaE4sm=&y%zNcDKE^x_&fqr!)7Cvt|Kfb0yIFF?*JH_Y9>f z?tq~GyfIgSKa0FQNNTYsHcMvyE0uzDR5IP(b%qqemzS23%<|o`W9Z0Ru&P+Iu@Cw> zhY&guj(4q%#B>glVju-KUZ&4aE|s4_OCA#U(A9UOUB3ra2dU3RQE@ZcMwIqP^wDxf zfAh^}pUs&1)~O%HeAB5H@A&7}i;r@D{A2gr12cDSJix|w|j+Z)vUn$!HnAi;{2Yn1V6O^Bq`4`dG>vZEc)};HFKRzI?;YHN`3u z;H0HRYoWO0cq9w61pQmMpJk$!DP?k7y>-%IME z<47Okp%h;v8l`GJ!mrdQ@)7HJ_PsC;l!5oR*B;w>QgVD4!^9|=@yDF@JH9RGB_A`m zL1es#J|6fFx(&?jRS9pvIxyraO$RKvWMty~$dS zw2`$jMc21z0Q;CIGtv%}*?bNr=J}v-DO#5+Pko-W83izBB^-Jq-wWSvP!)WiO25G* z#7?PG_yS4OwnuOb_ZDn>mN;1jcV2Tflem;zO$D>Q{>y6T&X5 z20R6Q+#0u_0@m1&5O&X42ht`^P1~-&Z)W$Q2ET`TXA^}v?$yv;slIDVJ#0JPZJadL z7ha&6em+4^Cu2BTStU%_<#u(6k&a)=jTLylk(j*2amcEsUad8IIj0QM47f2wl6n|2 z;H(7_>5Wpe)0ZU|F_7L)JO(PkT4T53?+I#@p@pq*Kd8~X0&1}*0-SZvPkr5Q4!HX; zpjX%AwOrHw9>oAMn?8ycwi?B7C1^cKnk4{0AYtiVC)FGCS3Ha4c(a?YgW=emq$u@- z{F!qX8O&l?93LLO*7oC#RW&VE@bJn&?e8BOy4f~1_`jf$P7mcjxNeVtp&WxQe8rfa z)F!^*wg;wkwPD-?_tSI$^~#v#AV*4^Ghc;PZNf-OZ?o>gSE{F*gVPC zCB4FA5H(Ec+qKRf@JXU=zlp-DD0Bwwyyj*ky=A2&UvL&+yNMj>~! zH_D;%FMaQMw`)KQGS<1!T@Kiyb@ zu~-`t|4f*6KeJRQxK$@znRp7F*v^z2bfOwP3DV-YiMfQ&&4W(+O7$#Ue<)omd+;|M zt=cPk*1thwp-6n>heH1t#y}*YxkBJm5f|Ax6tpiYW2j1yYw1;1_Ji|k_4r`s6oGba@B)MHzr4v9;4c~8 zXzijn(*2S})DySI7NLR6qk|Ur(Qcy>fohEd=b9tgiyel|#a%;^cRw}oLP}GYjC%%T zS%@-oZZ8Q3dqqKHrH)5{P*4Uvp^*G&YC6W>x9_K|>WoUU*s^8ITJ<(8qYL3Y7&hpc+U@`_f#e6w|qg3 z?UKqu?Ix&T>nF+ztkQ}Ua2=8*sc?3TfGi~<;QmzOCN1te$PO!w7Jwe|C57#kZapmic)^)0|TW1@t@EC@1G=Vu=#l| zp6ufTEoc|fZ6O^~sv%pg>g7%doAu6qWc@TSa&-O^^AB_sy7}_g`%z|S=6emNz9n28 zgzR%df^yopk~o7WQX;IGKXWScF<@>h;A9`pMUmy_%3fnc*mpG1rZn_ z%}|L(lV3)?MNG9n$Y9dTQENX^Nkd=t#N&k2Z10{kyc)6g`*&Td&MO@H(0ReZuUhv? zb*1UF`!!9XX-C3Wi?L!s)Wwq2pKp4v&ew9i6Qz7N^8FDA5Ct3DthW-w2lzbA2yw$G z`}(|FlBRpVAk85^*G`Ik(cF6)CMh|d7}L&wC4Sj#h7XOqs3#iq0WTd+@`vYydkA#q z{VD#_`%k`I6MZUgW!vzp{hgWf&wcK@Cb9Tf*KoH_*s4bBzN7zPcBE~fFTQ5XDy9w0 zn=m`0a-?5vqWLGO{ssGswHm9S#2T+lsx$B5GLbNAxY*lOU!T5rN!5G*z07IgH2Xh# zG{|~gm4uR&PvX#TvOEzD+OOZgZFv=|(Ey)T=4c9zxNJ`aN zVUaviGp1?4tSo5OyS%0_g#bk&;G)Vash=~q8 z?jJsY{_qj#vcF`G!`O(;oBaG(n1hsgp=%feJS77f`#|BSiYpT5Ua(tA>Z%w3BW180 z9(cTb%SgYVIJlimykSnjAg9W{u6o`Ds!$*uATXjeWvUvg@rWxJ*tEg&H1k`HZS}c_ z#wr4ZypFyRS({{>mZb6c<}T%xaq*>*iq%y-R^E>)TmL8O|90LrNzMMMIeoSMuXmbf z{I&l10euhg6P_cp`l?$jGoojI&rDbBFf?kZ(^B>~2*j;1k_i(@^eK=_xHU&s z*lt#flCqKdQ8C{yP4-GbM~u0xN*Jp%Y}3-W_ULho*gT7ZTki<4DmL!MfPGbc+w9^O zVS#xe1YUaKbAR?c#uX^}KBnL&*8QY#f6P4$ELR5}(2>1BE*{xb4J5VCR_|NucWPtQ zu4Wdy9oeJ(C5)l~y^EDO1vNjIh&AzA@1%Z@3vymrlVR4ow5`9eBk|10d$)Y1QVHui zRsjY7w?|7%Dl(p@&i&drnt8f%nXysk2J7Bv!;YYO`$C_@y%EP}CtXuS_wV0Z1!)y> zEmE6KP4~19GZ}$u>GCDg&lVY=Lq~gc^_ueC6LC3SuG|Je(t7pik|aOl9yIPrIPFe4 z0f+coG^;ToaR6u+&XK7gBZYO64jUPqt0Pa5N3! zS!^DuOtI7tLkl$1j_Ych(>c0-a28dB-MyM3#mTSuDs@ZiF+oEf!={7oNm{lx)vX0# z#>3B|jNWAs$&&RIc0;n!KUu1foH#W^m>R4vVs zecg{1o0e4Lwhr%>LJ@`%rF@Uo$Ag3=DqEEz^;bCGkMBrJtPGcEu4swNj83Qar=DUn zbLjcj!cx7S>*>gqS)wUpQSzae=4>6Ao7Pb)T9c_Xb|mM3dV$mCj-Ky}6V3@Vr!|dq zB(%ld|DHWK78|=FKh;5HjYiICrQnC!+`eT?|9!(Jg;25zW18itT7S@n=h3thC7!j| zFX%6Zk|Qovk?*Q4IT%VYL`!Ww`>_bd0Y29K$s?#WOccr(cv0$)u9jQSeeU|{c*_=9 zG`jZfs7tRdfGbn3hL~=d`pgAENn{qW5xkkseMkEwMhBLybc5rOvOdio2L2dkS~;CM z_tv|PF0HRKw$Ro4#E?Q$2s5uuW8bsdMltw(K% zp`_27bL}Oo+Izd|&SZuurrt?6FIXR@9@%=dq;T-~Ev+6ji?^*`+@IDWWLG8|>@d8f zq@yOTq)NifpPCu|cCF!&h!{bQ%(showAmYKwR9I<^{}dG7|XnAJ|dBHK#je`c9mc6 z@?vXW=B^E-vV@yiFPMpNo#o&@0lhvgG++;Lj@nP{*L(-7eC7=FBh)c^Ryok!ol0X5Y@E zCiY>z9TjmeL){}zC-pxoWyt??MU5GC_wmIs+XR}cayz`j<=QrNw92Y9rxn^t)fn>1 z@P4v)uurq>h|C<`#&7HQ`F~;hCr%{4YphT0vobt;;_{CB`;#Ayj1NSe7CTMb1lFyJ z7tKU%>8E@D11qBexN4-H2{Eos?RB&I5UTWM7sC<}G&Iiy1$fE#H8rvowMhjzmyWYC ziqwc>Xf?O^g=CGpeJub5-ygWQdR~vG1GPgW4Shr6T5M5e3sw1Y-(R=RK7R|X*s2)7 zN+m7`1ndcNheFNP?C=TIlT3^;A<2@`cUN}%Ydc;A)^2s(vTv2vJ}^Fs&=ucsdPpd=2zVi zFZr)4wH*_&%cylcGGslA+=VBS`<0WSH#i(jneK@>N4FhGu0X39in0&v-MT70fv(;Ie<%B2^ zX^B<)U44w0?7|Gr{IFj&_R@({aPfvKyp4VHBpeL-U54T;55K7rG^$X#W?$bjH;koI z?A2&htV)K}s+z?;C-r7dKlgulXVT`->}xV8r?i(u9d zX{Q&RYHDhg5)U6fy#2N?o^j7ws2Dp?BKzR)>qmV;7s)M-*PaM2Sa~QK>Gy(y$gCJC z3QOs!$EI4T^5s7G9O*GMP1Z z@zxU?dGgv+Li9V@5|Zw6*;qXZYEgMHC#g#!x}HdQI`tDZ(CV7Ti`hx89U@hs?qMEX zOJT0V3eNnO+FM7|p5DO{*=Z+#M_O`OqL4=7TZBa?XU$#2b=o=MFRsdTtV|g_7F9WO zh8Y(&T3gdaF`!dMlhjESKdqzIE^j;a)+h$MZ8oi|*?#7WF6z$jpxbqc%dp%|zIhBB zk=iG^WX{#+7Vwz1B^kepbDHC7q&s3;cha~uQM|ps@oIG!w^gRgz~IaFLG}j{PxcCl zhFWOBE4j(OMsqpUM(6G5`_Yl6xX${SGGN^kGqH?v*ZdG5pHwEJH4 z$j3i;x9f{`P^uC^WhbtA1gxb`3Pkyhc@bP6f)J^<&Fl zed4lhyg{bTy` zlzk#5Ki~;wC7!8ijUOLrId0vTbI50jv09h=zPp#}!mR-x{&Ha|0+15MJkLmUyn7dZ z_1t?&>;RY130JSJ$8-P3jgG;6ui6DvB7dBj15C#HC>gF@0q4pTNxV3CsAp5>a$J?% z$=nWGli?}y+=qKihkE=IZ{+qBPVUiiCWEi|?}fT)rJKFzD7rA{oj%+fX5v%DZde`c zHL8!fm4jP)9A^tvI^>R(kN9BkyJm;;{^~kS{O$iOr(Mdmd2?Wx@q%=yzUCZ>$VO>zN# z{&wQ0<#9N?6Lsf5@J!!{xeF>#)oxv(^|&87aNdnFm=C(ysA7GvH{CZbt!*|4+?`56 zW3i%-MQ9wiNxA_5*{iuR0&f>H#`EqtTWskEDXiR(x9B*kQoOCczRzK(o*idf_?C`Y zwIS>IpNS@I+ry3o9(d(hBQdmus+&JnbEe!Tt#HUXWxK5p4zN7a{;pkIw}wbj>7&Sa z?lc|WuI(y_m>kZvMp+YJ5bJdFx;Fb)H*4~Dl z`nTZG72Ze%JIDwTWrpMz+dWJAz~)y2Qz0C*9_27)K>-k|gxZcjW?X(LYmRA+k;IsI zX!>Z`I zZO4};m(p);JezezM+62-V@35n zw2g6=@fEK{Am4nc9h;J{;-JSs)lDeu6h2y1i6HTe#L(Qwd~ULIEH~{d>U_UZ3@yHM z6|{e4_KkN^J7=@jE5*n|ODsNWjeO+Bq2}AlVaFnjBJZ!vI97Cv>Pod4;qPsC5P4>^ zuxZSG@u|!E#2Q93&)z<^YNhr1SgB{vwR#eQn)YYjMRGW7o8Q{#`1 zK82e-eo^_xMYtyNFOB;0!oH6B7LT5abGyU$m2`fMe|<{eUzcSHxnSfoyN+So)|0ct z#~lvzZblerj3yP=hE3sGM4;MZNre6A;F#+dE~8_DaythlE5y3{Q5JAjbJl|8w=TZu zApSPMj<@mk2BLkPwbi5?K09Rj=Gpw1+^5cY%y+w0Xo2^(5|>;M&@NQRwG>5%`|dTp z4MtEz@0WKkUGnR~)iz0}v z?ycTZaZ_)T@%tC1?HI&hl4|KHT0PUpzI=(X;=++Y5!2VBnSH%gYH!p9jow5GmL(kK zG}K6PF|JR4DQg>h-?*x$g?nMX`&#|`K4vkcVHWp{YZFSF!yo8B33A=QP?K=0Elo>b z>*|>#V3(<1iww+DAAJb$;!*39R>?DX(a|E|aJv8?i(u5D8yow|J<`KZ#N0`=>$grz zZ;99+QyaYezc#$VolG}ht~N2Yc>GES+{{83R%2K_6ME~B5MPo+L4xFRqB&gJE#Uk- zSj2Xo<>oh^O~a96LCbGtq0X~K>YLA2bN>hgk_N$ z(o5{Mz8k&@B{BWF(+-b&MF&ro)LVKW*jD$|FG_gYc7JiA_w)2wDXb~^{h6b>BAKN{ z)*ZF(T|?XXMjpIiwKl{Bb(@M}( zqQ=)haGMFz!hdX7z#S-d#VXJE$r-z}JIV5~;WuDYE_ z>Z!t>#W@HsO&fIuP zMYR9m2vX~CO8BnTonH{v9up&1!Q$)?|H#%x{o&h<$^gdFQu18N{L5l0zYD5mW?yyq zp6X@NQI?<_V0Kv4{}8*OQrgpA6RW_@Vef=(s{}=pDvtY#AFW^KX{2Fe64TmbSW%y< z4G=_h+u3BT%jx=`wMtn6hl}bS40{MxC)YT!uRG~}P$jXi_g37Dp!&bWxfG^((Er}w zH8AI53|p4|j4-gPlx)^w#yW@Lo@;B|TK1hnX3Bl7+Qu*bB&uS1!6~F&GxB+HPMPcZ zr*AgapKIYs1BEWuOM@5)cnM13s_*z!B8}jm5P-Hi`sih@<^nff?=IV$M) z?;Z2Yty?$sfs$MS6(jR#4%-Qpp!p+XK+)~AY&soPg5{sPyp1Y431bw2{K~rG$ir2W zgPq-~=*C7`84NWeVyGcUQY}u4c$7_p=Kr?L#k0Q%enl`G%Yy|CuDflPwy$FC%)i+R zMn;1lUr4$Pwy>rM#Y8e=oQ4=Rt@kQ=s7PY$!mHD4XQJRBoT4{B@Pm#dyj*xh%LFAo z;G|kdK6jG(MwA*dvpZ~KFVEU+B(&lIsV1JweNL=Jx}7rj&mP6K%Ha=~V+?=vVj6t~ z@giWTV^Qol|AcGHRb8#|%fH+W`m@NP*I$WW>$Rt%(yR2_n_&$JY|0+TzfxW%gy}c; zgCrvoGY6Z!O#Cv)Xwv$NqK$po71|%@rZ4n}rsR_pfzOfAwtNGT4qf$`65$>K0g;l% z(f)soz@KCB3IMHq$;%G3n6)%} zvSf$Bru!y7&{x%HZNJo0qI9KlmIFuxCZDZF{$h;8YLViqg0Wmi~_H^2CM15#|M`q|IvI{c$6hY=V&uBZ|6hU^pOZc2)o#oYr-hRck7PGHZvYVLzky9+Fff&1RZO$*C zqT5qSdHB;~hi5sX4NS5xC~;ModeaU)vWcO**M?za3~>AvgY)pbVt2QrvdwCVbvn;u zWPm!Qn5L8$<4QN3WU>Ao><5&hSC(?AeLC$Dq1GE%7HDGlhTn%_-S1A?gRYUjW_D6g zQ{>Jk(|{65zIO~Tw_ZHwRT{KVr>PW5ACdSXJC*gVmZ$KkV=E5aW8B^aZkSfGxW^sa z_^~Rsss1A&s0wmfE-T9Sbkq609bS3$<+r7wk8!T8Q8^7$<)}?_> zgJN+~@<}5yFeXWcWgA)6!q5==sYN&c`j}VMAu<#Ms_bGSB#C7n_+PUeC zbh7&4C6oVkJbU$&VHX40f*;L6=6~~qWl1?!5(s;|WhWTUF|+ft-8+WDW)Iu=vr+A# z6Ip`Ptu9>QiBXe;aep`6tDR>Q&C>8Z?N5Pgi%$ak## z)8VAvhK;AgbKg#;gsw5~;WjBs53pGACiQTwm$Kn8&%M?1a3{x@O))a1jEN;IV8e{Efe0RO$bQ|burvX>{ zSIaV`8KyCeeyIObV#uyAv&Cm+H#KVu%W#U`8;%m!U9FxHmCk*Sy&qdyc@!6cK-3|1 zOrO5*ME#2ov8lSW#y@U6#QjUaMRwQ#Xsm=eUu5q4{{7j!Y%~sX;IB9ro z`MX-5$GCdE80MuhHeWY7;&=zA&3h&g>DSct)`fQ-K0JlXHfOu9)CylDu1~NtS+=4y zx)R(CWAIfIAcl_HRJvcI$nhxB*$Mu7PHF|43~giIDym+WS|zCb?13IfQT+TB2UHOb z*7#P<`td||)=#m0M{hqgqF*1TxIHd@b3|P>Lv8g3V`D+Xgl@Y>;XhN|fB)(FeM#*Z zHk>BDC^SEC^D~E#blK&iCg_4d|ujR zcT{Ut@H!07Q%c`ea0W3b%I2%vQLtkEI-DCt=eo zG4Ji+vk3p@fBYZwd0WqR`vE!KH6qrn5BUf`goNd;ThG!_?bxoz&@2eFid|4$*dUE9 zxgJqyi?K?v0|GFUlonry4DP)(&i?C1(Fm)JqqLza*F!DGtLgk<5s#m&H@7Qvwk%bn zo2ea=4f>x(mmAS5N&S7BCje5)8BWYFb}sM{t44>7G5zEbG<}MPnr2IW0}5MB@L34U z+`;@Ix~R46*VD3)I;fSt#g)E6KtQ0gP2cgxDnGsw)P!i}@GA!EGD#d}Wn}z9-Br(B zB^2)Un1}< z#;rp$@nv6ltufM=-@+{ed96-9WLW0+E=m#hNF3Uq zUu8F9&`m+g(*N?s1@gsv`bXmBu5dk|i~TXbIK2wj!~D?xsDj1ThB(ht=jZxa9)5K9 z2-bzdVU7~Zzvc)B7^*X&*CbubVzdt3Fei8~5FfYiHBXR3Trx{z_qrYiq+0cGeXQ86 z0L+AZgXe7u!Hvfx?J9B1G2Rox(JReLAzlHxqZ@E)no-aV)^7F@fzZQlbnq+^;bo=r zqigkZOyX2_D?M5}d*%9*Zx@m@m{OE>Z3dbk(1-Dqt}&osnss@dJ=IuYRwkxT#ruW5 z99nRw0mTi@f||+2sF>X;igKy>;ns>ld<-9Y9>a%=WFiEXQsjF0!tUN_Q_h<|61?yUFWwQVcZV`;fVifG=Lfy2k50rc55R&Os#6g_YFr+ zGcQ8dxInkizS$kzZ1i+=TzYY+tM2p#-tcrcPg?F0x~PnyP%-pEF2g~$Cwc9p*LXKW9>Q)1#;I@zy_j-X9cFLqz#*C!Yp-PBD}r-`n2>)Q+f`cl(b~ z&==(8OqRv%>V7TXK|4HqJW!()=CzuGrB?ez$77fG=a`Ude%8A?>5-YO!ILvSm&|Op zn~pRXLq}hrN)`HDC@i+s-E(dvWUOeg%i94k$(s%^7~%j&JzQLM?(m0_3nbhWCR|mRe36#e!SEU3_Q^z;Ty|}1t$G=mdiU(v$?7x(D`7_?4&%$ZKqUr zC5xRBc@)LIs-{!G^oWqRne7o%@p=Kd$$DrNSkeVrS2 zwo^APaxZqQuuo>t14*nwnMLM*&IVHFp}Yw%!wPuJkW04SEC)&9URGNViQQ8Gwj= zrXhy!18#J+onUyqtQ-C9Dv<8_s{MQiD5sx8wr+ND&H|J26ylg?1hphxd6UEMx_=hz zu8-1=Zpr*+&wWqua4wgMp^@Neo;JD;xFfS|QA)((#ow`Vd5w>?*AD-g3rt+E3v{ep zNqZTNmn_a}1XnGs@$v8yYnQ@HFMh#Qc=OMfwExTHwIfP5OnQcxp&fDkKJm3(~b;j8+#XYlYGqHy{!^}59lSX4lDY8(z(Hx4TYfE;%GJNrT4GO=ES ziu20(69~WNKn-x*3h$00 z1|e(0-O9M_mQ@)BCA?%{EO?>afSpuroBwTpBoBw_K2VKh-bcX!5M_H1*`2WF6(umG zn~*RbF)}mA?<#&$8zMS%cYQ;Zl>6m`z6@>zuhdC+w;!|p7t_*=l~ehu_B z@2Wd{_EssBjVv<16utb+E|fAc)toC+du^a6M zTsmcI;5zEo45ARpY3PKizHp?Yijf}t+pdAEr$i}`xfkhuU6XJzZYLech6<5g#E9sP zISpTQq&5{v?AUDHN+lSrJXmC5rrV6@h5Le8`6=fx7fG)I0~8c2!D18I%iZu0&vn&9 zwrqrPYWn)dql%a>%S?On8p-p+=4FX5_qW ze3T7B^Zj{bwvD{PKY&vZ<;$wbKAq5OjM7CZ-IfQ9c)r8b^k`$|>8`cI3Al?yu-A_~O9? z%ZeEFGWnCnnZE~hpZFD=GJnVhmB&D5l~!2NM>E9@bE7ceDlyt<08jW-D30JbfRag8 zi)vG^{3}r36(CxP@$HjrQ3J3Smb2vIpso6N)HqN;YMrMB58q4zkiu`}S&EN0e_Bg!h(;k~Q z{c*y>oIgPMG7a*IkH1VnabT(fkdBuBB5dXx^)I9=pBw4ozw+5Xhv@GgqR__-Yf!(| zrMG`aD&W~yvVloeHVfaG9*6;NK{Mrid)llTx6VeD=~hF%0E)_$b^3u5&px8-9W&-wQjTKDId z4%$_(Eyg1&<0AaHq3AV4)I9)NJAjxFG#h6Cf{Kq8H}B(?vKd~C0O?6<2!{w;2P#%h zg5m7X34R_ao2UI_u+l~hK+OEeMAwe9_zeJo*Jg=JNzE@L8{i~UVS)(gctO0p4tUr+ zoi4k8_<$@%h{$5BC6N|mnx?{p)z1n;;sj9b>Otk&%;3YV%pXh$S!D3eoR-IqWxxs? z00?#mD#c}lO9MR0*WA)}D&{Yc3>CEX)6lJ>7+5nVFm3VyQJ9HE6la&gay`xBlw|#R zh4D17;R?}$1OQnM5tIz@z&>bla~&MmU#@)gF$7bhLx|48bVFJJDC?pf=~#o%X5S@R zpJKOgpD`5NzO?WF33}QODt2jC3acI$Q4o4Pq^OfI>9a4Py;2Jh$4{2-4Dq1*wweIp zo@0gJ_sCUL>9DtSM5*@#VHxwWkvIkx4gJXLOt`8Cb#4!*`w(#Xnc;Ig3AZ{Is9?)z z3Hw|TKrE)fFdbNH1;CnO*Nsd3A!}=)TpcDt*oC86PW!-ie#*Rp`m+ck|HbFktM6Js z^1sBZ1cg@oEH(>g;8KdnNf*KUrx#9f8})n@>=Yf4jqGCRCvWK^RS)7`jN_S#<=Aj1 z{q_r$L5vwMm&Uy8d~q4v7YF1f!37iHWX^#MtE|%yf0+E=&RO$`S?JW zN=nHPtnwhDpqMASQ^`%{Sfgy6Ltfm4F^bS$@>^#(;4ADMNp5+b^gm*|Kb8bj4~YkOOV_6%9%Q@ljk_{Bdtj zGB_8j?`bY_=4dNv57hKaJ-}eN4wCk=x%=uL09F}stQ9kPEzoKbj-m>C=%44h7*)s7 zro5k_2XignnAF^b7;vtl;xph;!4 z=|8*r^=Qy%_wKzi?GR)~>ZBbj(yIb;=rh(WOX?EdtYJe?1fRoDBVtZNzLobKQKEEu0+T7pN_opP9BW-^cN0l%VQP} z;vm;O<+ti-Y>j_Ajj|DiWl$DVqg^H+X`XJG*_oXKuWczjHj=z&4n%rL@FWq`&#AWt zlHh@}St;psx0tcEzT9&9yV4EaSl7S@Z_mZgCfF=GY9ks7f)x&wY+ZgCyA@cT_mvOm ze+jr6tJd5V$`;ro&AbGW+tk^9Zq*fd^E{mFb#xic`RN{*y1mN(YyimCl>auq0`Sv& z%X`59QqnJcd^ruy5G_)&2Y`$>A|5ySNjODY3)P^L_44#=B~-fep9a;2F^5Bo#J8aq zGT=fItTe$KX+yp>P)V9NjG!k#3@Y1ca`o<7G0h7Q2vPfC zjm!gzzdOjj%N(-jR2|+z$GD0Jf@zV>HF!XdWPUg7*}mf(23t9bCmLII(6#B1t`H0ruzVO1QX=`T3kkzj~g!M3$;SIAri1e!d+VB z7XWfG<6_?1>p)e%rz2jl7H7bGX>V(**F8v=m}hm?yQQjI#L6tR27MdwR%#Z95$P$^ z4$2kowV3>E9&39-Grq8jq;go3DaAp!3z#ZrcxfsMtf1IHS$K-G7kMN!+#sPk#6q~6 zYHvu4pk7`7`P>Ja7=lxEo5tE(4J3C@v@qA|>79RrU!mskN1?<>@`2FGs19?PL}W1! z%C2K`9QT%%Ufh*bomuZbkLC2^g(Y;Rd(Y!mmo?eUi5IE_F zPKePJ+Hc-L-ItU!qNk^F9GXKZ8d^W3d;vts6|am46QS@WnpZyy1>B-_n`Q2A<|A(@szdC3 z&ke|1ieMMMCKmtblh6s@pKjd|8iM#17Swthtp_uwD(}{*FGEQqRdV`u+3@$_0lD;O z%ws-(bTv2LoqFP(grHgP53MC|s3@D;5$Nx>+WpR<1r}_?$YFcfyPx~I84CGM&~7C= z4vRKIJm=Ssij$s9{QzzhW?#+lmzsT_$)o2~lN}i9YkifKhhsC=rU8gVO)X%-h88`Z z*LQxt?fki@2?khrcabB}KJ)!Y_l?cdC;_z28$CalyGh8@wKq8LOMGp(ivhDA((Im< zu&dozyJEgQ_UGER>`TN>BnVoQOiwO6OapAbBIx6p0*y-FcX+E1a8}~Iq{?5I42}mu z(r3}WX+gd}wVQn9<2|pCh0Qjfo52QEIA%UhzK7%K?A2#aq3HR%*AP7ma(j2)FDJ4^rVi`TmZHggB%7 z+jJwZD)5@St)(8U_(gUtf0J^}ziaX*1{lsW$vTh*5S8YFenb*v9*9{$T>1u2J{9x;SFtrZyiGQ%QgXM&Or&RR93YEZba2LX=x18tvoa)IllUMc+8z`)je^X`r9ah09^?jXlfTwc9k#IPM%{ z)uD4#hop*$QPW*v9Ctdit(kY~uw76{=cGP_md09BVD|H|(50^m)iQBLaph_4p%ISI zkRPDcEgweVn|GW)_AOHmHV$*)37~_c8$v2WS}tLdanj&6)FFUs%J*+)Hq4*9gitlhHs3xX?J%*~yO4&7Ilk!ho!9gGlqUtMDJ* zvKGj6*ZXEaWkvVchjfph$)baz{GibF{KTu{d(80lgqzHce#rJ;tnL)wvE?qN&oJvF z#ODvtJ~a+M3%aHt4lv@|TWmhg!u=v1o~a+N{(Q`#fpi_x+EXY~?SGh_5}~9b8dn8m z&8BVYp>rHxKUbm1P{p9B5*07DR?I(?Fi)=MMi$3!C9Xx%pO)>5TqY%wuQo8vL<`OS z`V7l1w|7DLH&188;A_HrJ1FMrbh-c2BNyF-7*io0R^Bp>SLN8Y&0WYkPqVH;WG z=*cdR+wJLlvEcD|0+%lHeR{s(tsOeyE@Jv~RK*B2(-!mj_r-4}Jj2iav{~#wq<2Zq z%QR!U1Sq^IhuRb56{LUOl*L!CLY^~lG#R6tA=6?r>ZIwy1a^@%uw%}OCJt#Ct%;*q zU$(?jWB1wW%3hI~1i)yl*5>Cg-GiZMpNz?lH0qT9=2w&Z???2r`wV@fc^l?;33~!M>U`*_Lc>&DSBiT%1m>Be zm94nlKJYoa-gd_a(K!_-087k=f1jW<{VD;U#Er`7U=DT1?wsc?H-GmST@mwk!Om`q zA9k(K=?UYbtFqc?JO!W6nf&D^fKEKRP`0o|)Dnxr1LdYdP3PxFD-*J0mwBrX{7z_!Tq^yG;N<;M3X6l6R}IvpIyx{+-_a?>kF{E2(oL0*z2=+8i!>&lRJn+l$&d3p8?+K z6X{TJA{VhXCkzhum2fMbu4dc2S&8>DR6zFEM>dDnVozYhgiwB?;#Ap}-H5V;yzp!E z8v1gcbG$m28h5d#jFH=ZQe&?d=bD8~yIblS5=?cE28#M8RfAECMBrZQ=D3?qRm+(o z!uV&OAvrEHHkr&kMhsB4-ScsFp?Bw#B6$EqPa~bo^VC~dSvXJO%*tI4Wt81v^>IZ^=h28g_&hWY2OD4b||5ofGZ=ELRix z&C_ACV-}obIVp-d-?{Y6Vhb*;luCKI+rM^}dO1fsE~<|G>s)M_zx@27978k$!_ldh zKmN52sD+DDK6$~R%<061Ga7arng=bGI+Z)`53L*>HY}4j5G%J}5sZqh9$&VxaX2Q@hR&P+bqVo3 ztk;S1AwFrH&wkd4qoK=US!?xRB-US@C`#d9(0n}{^Z6Z;uWol-StgFzgtPn0Fy-in z4mReOY6`zCbortQ))pB&MS4qiv`*}}2m9r!a5@qn#97N_x}S%b7#w|TS6NohmU{(4EeYa#6Flybz$&+0`RdtMhz!4L@oU;Cl!Q6J#{1j4)lP}{y0wL`%%I&&N$1C!<|>MQrO>D|AT?01-><1MQC?;tCxi|KZS2#QS)K> z>X}l;PCuNnG7~3d_OtUx#yfaKfkwQkonFM|c)ZMkuPJVgU||?+-kn8N$7+`l9+EJ2 zGihNjkP0QjuaC5obl6Y7dNy_%g1L3 z4Y}hs1aXq3GWRicCuNHQOMhAs)_xDl^vKw+;q&=)OS&B524Cf>ttI{P;&0YpvV^MV z%yR6E?ZeXrmt~7TZ){ZOwDL9 zlLxTGh2dFz!0SP|W^9fztSa259bj5)chkF( z$C1=rjDRH|I2l)4Y%!7QTY}EMHBC-svCc`_GFnI?(3KmsL`Z4E(<=#4Gg9L7QZ*11(sKNauvo5kN#6Cv9Ka!cHT!t65cnDxXB zC=XZGw#LcqA zaeNct55}&?H)8Ajwb~C>AzOpm=cMJ6Njy%jdx#o_BOZy*aytYC<>~2`Iy!ZIz&EgW zNwz(GVX{M$g*&S57 z-GtyyYY%W)U&iStTGR3GvvYe3fJC5S^_zDdz`;ha>L5xA2psoZ^ViM@6Q`0hWF(R9 zughJkPV~Cjx;KH308EvfY+And9`D$~Yj3xD+$Ldt_7xwo)0RmeN}gM_J6|SWG9AZAxjU&P>AfH-=!`5o6MW?@LYxA6<9i3@$c-Ds)?GiylZrz}QR|}#lFp0U&)Iz% z_r;u}emI%V{`F*VtT9WOMW|zizKMpf6-Z|ui(@) z(_f0G-7wG6=9L*vKz(VrQg)sjYkB?S?8X+xZe{vY_wnU0c8F+85pC&k|Y3$sL4?`xAmCv~GhbX2}8lA@GD9~*p(DEI1AEr{FS#9dO z=IF{Rcr+D|j~hdG=0cJB0rY2Lum>dfyOQqQQz&jIvk4B+`-MIbVk92XN_Tn=zD5gE z0QP$-=jenHocGM(EXRvXyz`La@|#w$!B)mLg)IzuZc>4(@HFRiY9oYnPo-3|-{E_cAH3A5XY zxpN5CL(@@xr1b`%rGhvBdmR9%r$FR_CdM_Ip7k79J#*_007kei_`wqZo?Z4ZXM;KL z%qkf|UumFtAr{UvCs_hG&P3lhRdO<#z%B+mcd(RbBaK`#h2fm3?TIRaR z{W9dk|6DdBpKf_$A8;7CU*#oJ{GbCb zP3=h;&*wg)-Yvk5k?yg)IVl7HmIW{~ZB?eBdT0s+5X!J5A&b-gPzU=zri1H=r0OH} zCG&(m7W;)*ybmZow))}uN{77uLQ{vu~@pY$hv>lgjnR(6j zh3t?_8-Y{+HV>S_a>*D=<>J(A;N!|FbmLFk023olY|ru;c*Nm%j!0q+u`xtIZoOJ) zFkL9yySD5P)y`N`TX_$y0_w5}x(;%8Z?$_osj^QKK_aAhrz*Kt6F{E$sk3KZ@##bF zS+k9rvqol%=rZTp4Ag#DR#K~~c#4iQXlHVs`e@FfbmmKx{zah=-h!2W!h_6pE*DAJ z6sQ%sae70f6Hql+040A%m0xJ(2^guH)OxI%eGA^E+N2Df%ENkmTs?kJ^yPT_b$RV< z{r3)~17m6;36j>@Rb2Q!KYs`Yzq>%&>Id}I0I&hNsrH^6+D8dQ`>5B(3bl>vpCfS) znN(zY-3HQjx54GVn7uxKIxz60q@)8B&`EhMpikoDx@Fup0fj6Vr!C*8oQb-I!hyHI zE+hQTO2RfPAh{@=*2QJo6qy3v>4J48#+_Nw9X5=$I3PLy-aSwodgqR9b#CidaoJNl z-SjHlrefKdnClu1mEyre6U{fgl}#*E$3;+AN%Ey&^>b3Ltvv&ooOI*a+&P*~5*>@J z<}QPCIs?ZC z3h%JKa{p|x)6n3+hxXyfS9@k6>P2Js&iP_Mi=Q@a82PDloiG~PH(pVVx zemlcSRf0AO_-Dl1J3oBC{03{asrPue%*D-O;%Vp=NKz zFI;PZVqobE%{*K|cbR2q4|k@I1hR#$F1_LtA|KLg*dD#AHq<@ql9WzeErn!F@hD=S zSl;4_!tX<@_I5Uz14>jyYIj;N#53ncxE5Su&7{1SUVqY678QlWm~ zAUZQ*^Ze8E<02fh^iq2H2a@M>qy;E^n!;Xp@hdz15=}=9M&Q9OvJPDO`Z*Ty(JtG( z$*m=At_7LeE>l8;rO}23DipOS(gh(FS$%*sol&G)Qj*q-n`zQxJO8HDDui#?)(1f* zmv;&rW(w4l3aC_TClfg#lJNAsDlZ)!S#4-R&+2*<*4fn+)f5Iu{1Y7}&tItANc_Xa z^wA&YKgCAQB_*g?BbwkO7QJB;C*=->1KvBc#>Jw@tZnL8@ARmWe3!k1yJ==y1sCYa zIals4P7PHL-7J}(qCA%Aa0!=^UgX5%5EO`eMY+Yu6Tt9$(caGpTc41YA_fmf7&B4y zyJzQ*;b8;I*%p6T?E7~F7Ls-k39g;?lalL-KgyhBhkm; ze7^*27f0jIbd>CRVEpaUE~w(?lqPnj+CnJnn1Kqt{M?u%%!-I~gbJB=Z4Gd&k&;SO z3jx;4j!J^M%q@;9DFQKXU;{Fa2M;S+BG!W76`de+rL##hbyP=i-0OlL?^4kdh0DVL zP`k;v3P0jc;iGV~s&Q2iQlQpnniRdAzN?mnUW6k}$4B5LQ1&ueGezLHBD4^T-ik0S zXn4@%@gPFMQY(GsXwO~^Ci>3{)YA;#wxlbbf4w7nJs?`TVnKFXEDO?R4^43h1ld?T;PI{NH?KLsv&*1|<4A#!*N9@K5_cbTQUJ^=i){fl8 zCatC-IYK9(puFUcVd$66U4&NP;~M-;^PaVrhqr(Gj#U2`s^sMJ?;U7(^v3cz*xx1% zK+V*vOQ!9Wb~SlZAhea5FET&&k!Ld=35+Xy#TkfE8M{hBa87|Yn4PT4W##=N-68=S6=YT{wp7 z5vAw6_mJhTH8%aQE2@WwJAD__yPAr=aeX};yf<6A8~bg@&krxrg+ASSb!||Iq2kU) z+;hCgVPc_=D4QvKEVHFs6v4NO9r{nT+S$FyJv~$Qc1^tJppr#t#FyoxDVqbO&`*?F znM>>sv~9W;MP}Erw)O2=AVQ0_O&yjB7Em7cPQCo~!`Gi16Qo*;nClOiG>cNEA`SWh zsduQadwublKV$5~tCwv)eiXr=J|n9Fpx9EZNM_}&2B zrq)fHcC%=xC>p?qLgrZDHtbQsN8W{sZ$99=Ozld!tjA%M_!b#95XI zMD2CQ{Q&?j1Md{X7k0@x{iOL9su_GRCtssxJkx#+h;ofe=lR}HXvG5tMsM%|(} zwIAlpMRk+oLxdlR3?tNn6|hC=M=*(ndPH?GgZXj{Nf3M(DnoEuZsscgSWNuq$Uyop zrzHR`f1nGU_zY2VudM@3;q`jbWhHX`_RaVitdA~N%t-P*E=85jFq+|diLRo!To*hZ z44{5c0FVnc-T?i^7DF?QEcWYzXa$sixhu(pT|c2HKV}kLy*BNHl=`tCoT{kS1TdLp zG+i;(ZODvw@7`Cy8@8V@0_w~FQB|8alhe+)Yyev;uZI`d?kLBw5vT<8k45D5;y>2` z|7UFL(GJNUNI%$>=@b405vly!;Vm0cs?V_hw!=B6I_fpvghRN3mvuOkY|Op{DR`bi z+c6z7{}_122d!k)Zj#$_9m@FPZXCkQyQwvaN>u7Jr{l<&W|BOBC2{c8+11xZSuwB4 zEm*XnpBLo`3zJXKsZ!mV7w|c|iCr>5tDg(LpD4#YNS^v*Uzd9B57&v{GmrvdH3(AJ)GU|b_Rj}fxdr)CTEk&3Eudo76VH63C)XjmL>EzE8-v+|L?4GqD zpr1{sUCk6oQUJTufkjgJgI~DE+`bL=Dw`SNF{$Z%l~xU5#ZZIbZNFzZzMs2Ty~fkG zRSMWWp{oOcesM+Jh2?q*9AHZn#zR)s7%rX3pU;h`RqJ~QY6)kV%MfkdCCmi_A&@Xf zf>z{>ZufCe4HkcpP)L7zobhF2bF_}qqi-wV8qoW~I%#sS3JvYY%jO;eh};9|@<4fp z_ae>v2%c4g4*$vEg49W^mWbZtgo(pTD5KD*ecD;VEtjtMAGp4paK7SJ?KJ7VVCx;y zMq+rTU$#B2-sNNCthayxFC(%_CJZ&W5V@zkRhC-anse{D0kP~N|K-U_!|sD9F498o zOf_{?wOhITG*vK6$Gf{O-0D4WSn@!lG;_tU|7thUe@-{CI`{MaMK1FWQT2?{1jLJ$ zD5DZmbT(#%Dx&oCRCC)~&w&a?4)Z0qsUFgr{`eklMgg7qHN3U3Kid@LKCP476Nm&l z{iJZCI+p}S%<(9nFMhXQ{W#VE<>I7A6IIzsA81~_Km{vIuAbNzvX#Gm*3fg#;Z6zW zOjnu%c5b(?HN~5jFMeik-sss&kIwU&1j*2OZ_V9t2?(YG!wOV0-n^%i-|FQ}V%R=l zR13!KQ~O%yx^kfvv!~9yq$MbA=@O|<-;ukuhCF-&+?_p4cHY#A-iL4vAfmty zD`wXmqI)%lnyYxOjRaanWx$>J)ehW+5Vd^-U>6n&$pb8fxbcWn_?j4}9`wH@iT|*5 z(_zA-J}Zpj<}@BT$Qk%)OL{I<;ia(!gXZux-7>Mt83N5S(WC4#6Do0$B~*KlBdN;x z^^GR9kTrpxU560^VVPH#rp)*uF$=yRvH%ke7U8|0BT;VUjJ1Quhn6Yf2Gs6 zn;tbXvAH0oS=f`QM0qqjjBmpJwCKkqV-jt5r-^pDVr(=`6s7HZom`)_cj7cy`wt5|)F|(}L zRh%hw>A1tS=e>CqFvO?k+7kHZ5l^O2=G_{k(3nb#M6RZj?Y@0B=f+6{KqrjEy~Z9d zBK(2T-g**Qs?SQTfEHo70B%OjMxte2X+#SajC`7X7ecfQj56fd-y|0s9Pj}eDHKB= z0S>dzCayZ0fo^pr6=#TXGPowlY5q*qtpFTamfm}EV!j&%X)z3od8hn zo1Q~KJFwGI{;~eBu+I0>OOO;EYsrWW9>;6Edcm9#`D(vVZ8_I_;&-~tr zprP}KskV&hJ*5u_Jpq5c^=Mh1_XE`CE}l*EgeAb8YcYB4E|_+#ZW4Is&IZtX5kK|g zPras0&`XJiIzF|nQwk;EN%>@5MJ~u7eT#V}PvF@^FQ$39Mc@?f@rmL9|DHa;ylsMW z7TEuQNl%%p;8ejJrtq;ESFxX;lM8ome$byDeF3+e zCRfVnK857(C3pRbL&suSsonzB7*JtU`5uX*b)s?SfeAK(qWLZMTF>;Uj4VPPe;q>->a=k)BYAAbR~KqJG? zewFdC3o#D00yaYA-WZEgftb%KWlKus#xn~>b9cS`_UpTJU0KpNAGY5XF>PYuITcHH zi|Ph>-317R=Uxvr&fL9VqI`y4s_pS08>b^A={SQ=T3IQCq~{Mz!2rz_h)pCQHg(ZJ z4fd$QftYOqlK~A2&R{mmleTIF(y~mSEUIPJY(B7@9x5tS_B=f+#@}V7knJ;hqxw!C z+WE?DppH1(abf@Temm$0Xyj+L=8!+g=>O?Z?=nRB%uZ%;5C0Ow`DG_w*wo z*72h0F70L5Yc8#(@Ehsee;v`<;Qr6Q{@V`}rr<PKL z%lh^|(9!vrb~`RHM!x$y8y_w@0}mc5^8<@T`~Q+6{H4VB%VY4LANuAr4C5e>Vt;4h z`%8gwTT&)Z(yf08ME-X9zmE#?15Z(Cw4krO=ig6i@pBe(wKxQFyp* zAF=n}|2`IQ(e2vsfchL;cA4bWx=#{PL@7jU??^r;42q(C0-}IX`e>}j+!=S`4FOiy7`Tg8~ zJ`v=nUqSa!kxV$o^ZQsG6oa~S*1KDo5r3TfKOLS0)!fp)*mr+Cz>F%G9OR+;qTRor z`#)XOo4at^zjzA&FtYUL;DX8Vi6?gKcisNRRU{#HmOC!R)G7TozWxTtgvvFIasT6Q z>a^eqQ?gB1|Nlo;ff=#m9SObA@!P34(}RYnO#W<3-e0yG|7lGB@x6n^$osXp`0`IP zYUkasw{N>)^uMeG-{A@C`>}T@{4ues;oK`?AHV+(6RlklZX0#`W?%5{b7&X~llZEa ziR}L{9C3)1>N6HC$v-}C6_%ozWU&js3#~TB?AO%__lxwKHr-eFSWSx)?r7NL@qqK+ z?RJpHH*KtF$JyKYBEPk^dP1Mjf4<=Qzj}rL)gb5hFAfS0QgZ literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/reeds_shepp_path/LSL.png b/docs/modules/path_planning/reeds_shepp_path/LSL.png new file mode 100644 index 0000000000000000000000000000000000000000..6785ad3f8cd182b34c8639a93756b4f723b7d263 GIT binary patch literal 239825 zcmeFaWmr^e+dr(cK?zY55EVrfrOTvc3-RO<-{yL~sRHZiLZ73T|Kzfb=l*BOY!9li@;iriNB;2JE5F6HvMVlYj23%; zt8BGR>By6+EC;6vr8upG+IPpD*Q~{mkWn*X|N6r-HaQw2t`JMm_v@%)=Uxk)@}f-W_*qg~M2VQmu_?3%w!p`i4eEADrfDov!q6HsQUY zPABtc_SdC5o6O{X3`9LFU!FXBr{O|l-dy9PpVO4zK!wu?zZ1>Ebi%?j2i`VErH1&E ze_og^&Dq2*Y379xar4}q!)A$dwR!Uvv*o+zZ(F%DI57o_&ge-_S&VDaE|CTT}H}~CmVcZxqSlF_Q zX3Kv>mJ*K@-FrO_FT%-;+W#6{1tnR!U#`nm;>A!6j4?%8BwaRpQ?R3UevZbRGB@hU ztI*gMig`;|?`zJ8x^-r&wR)nc=C>PP$43vXop4YT#;u5Q)emw)Yrl?Hq@H_2d{8m_ z@PyOC#P^|v`JoHn^XA7AI(ozwrZ_3CdnJjdgEi^k3^=#FpiF<5w z18R*npg8X?-F7~2TG{@`N7e+=M#Z%@U&jx#kTyj|Mv^vq#Obo^CH{Cdh1eMa`t|)n zzyl%yI8BoAEk^4lSNjRd1j@32q_{?PlzikkfE5asZ^RC=alFL|5~t#nx9aX%`HeCywNb*Q+BkpW z-9H)n?<>Pj!12L#sJ&9`VQSL4f0T{r!~Xr76?v5%25Co>2RtR-f%Aj?H*Z=YWz`S3 z>p=c_{DO+?ij+e6fEE{hmlLb03~Ce7AY)?+{25e0s$*wr8Vvq3+sTyF!SgrFrP~sB z?SiPxIZoOWE5xk&LGK}`jAEViS>he}GT`hcNKoXhvhC0Y*kScxUNuoW*boi8sP_CX zf*@9r6!U|985&WuLiktr0+pkq%}*zT+lv+9R3T13YZ1AK^g;DQjHB}Z}L zzXUH{!KQ*T#xy&{u&$`A+%{P5ZOVx~L}FI?@futNM00+Z=5W-l17KNJvVXy_Xl~dc zVP0KyMJaG^VLAE;I*L6j#H{+^usCQa`vA*+;vG7X&L()fzc5O<8?eLc6Rmwj)1U=M zlfxG$N47%Dsvknxfw$5Z`Por-2qPvX9yOKKtGNXf z53WFR!>e9cCAGqq0@s&%feyDo^;EVD32GqktlYn-&F$;^o@NMPrB-fTb zW5ir1>OMGH@f|n(|HQYpe9YMWs9lqWtXs9gGfavq>{;0r?ku>e^I>1M{snrnjsc$( za2qAL6Nrxsqk8xkygw`rkJcY$VIlgswkt>+MJElb?BxIA=n~U@A4k=c5DVX`8E}QD z8$Sh-au;;OV6>crsNOzWAc#@!lr^g>9quIMq-x)Da?M3$K8wV*zHxRGl;{V!r_1oh z{Y5}Gp$3O@J4%pT3wdU&l|R z9N+vGkB$JJ$nVzj9(8Lr7XV(zpOQtbOSGsZ;{OluE^7Pl0I%Fpob9QqVwDuz-wJRz z3p^Yig}QM6=iyd0u0>`0Z>A8HmY?7_76X+eUajMGO-+yRRzp|w{2XgqTeWY5Ghc9k zDvyNOe)_+`#cE*uBQ>Z@#hNIN(jjTEf`Xi zDSDD1)vn3ekfjq_v-r z06uqdsu!R<2#QdY&%hpseNZ-RLxqp1XFx% z)`!hYzu-Uclc#_!c){u7ccb>Rn#cRU6n9ZS{+#0Ceo#~~hpDvuP+qD*M?(!wYfLzQ zn&<;*Pl3#s+~n4w1hIGyTy+#xh5cG3FiNk*>6?#|H=|ej`;tpvP2(+;f)(E zCUzDx#$7}mrq~ZkA7#mgf`Y5*x``oXVyM-_-+%kpaa|hz&8YkEh@v0=8%5t@{iE|t z_~)X&zUyfw!s+K@7F39lDKrsm$mNFH+rL;zf+I00X>(;|<@dHXx6j9OHaUiW<~dD_ zZTX1%-o(*^s)!SJ{pIM$uzdSuqg>||uz_;p-Ve)}mRv#>9K zSq$6*)2p$FxFYTYWmW$eS6T2ag1WkTCe8Tx_=m|!>zfu98WIAk<=-SI6D+cwhK9y;dbF2bm(Uda=_>jc|AT!WR$(I4I1(CC z0d3iLoYKEHUS3}QZD`1e&;#WKf?Es`S}-L_Kn@~$VmnHK&`(9Pg)Jk0Zf2sRBuF?x zslKLW>$`XF4jevA+dIR*>n(xQIQ9o|yGlp_lOrfi=8uRalmf$V)O5ePy4vuSzTbFK zQqs49fhLRIw*=*kL$O{fv|!1hS}j$!Z$GL8jbi!Aeel7T9zmJz?(Q1*e0_bN1_!%8 zcpRl2Oz?P{lTFC!#@6P$p!^>2!|C|LNNlQ=Hy?Aj?cTW$qLx?*L zhs!Ye`u2JJOvGcCMvuTMQet?f7JypM%<-zgzv%Vq1?Jb(sA%LlidMuEggrdO<^@30 zY{DN?rtfBtbVc#PL=JdyyI9Zz&CTC4qf7wTm~LEnd;KP@fVQevil$RPx|oAhGv*`( zH6Iawj=K&1ako;54SE$l2PEfGbMjaDO_wp$6Vu<{|GoOWc8-d=ot<5Hb0Z#)_lPz6 zI?nv!<{lJJH$oG^ahqt*pA~{+2P+>xKYem?ay?0^8aF5~Ju@@27iLhx2B>=(VSwg= z4)EZgNu}`n%ixcD)ZwX0&`Bp_T~!ifA(H zQFM-k+7K#xkh_RW8JQj(y&1l%(TcIBB*+y^E}|bw7CEF8C=+6WFo54g^b@Ehel=zZ zUb%$YWn<7aFz9!qsk)wOI58d{AOC_^XZLwpqt^9Lo}-94ECU|LG%fxd(YLQ6I3>ll zukY?1IC6x}z`!7L&F$N_P3LE)noQkxLXS&Qvldm5)F}l9*hL)tbNFLQjKNYQ%gV@n z=qU6sf7#H`aLL+Q;O^bKdmUOopUlYdpYBGj+vb84PXA)Gz(fES7Z>+5D9Ej#pdhNY zKa;+HXvky9Nq*jCxAPyURiCWiiQ+>i7+lX5bTnFp4b;{^aZ04l41~z|3Q&oT*{PB8 z%F4&W;{xl!EF#k~QF8iEsrO&Dup+%gCmgG6@Tp?W*!cMF;HKv0AVO73V`G4D+IAo| z;JFbxBxoViL5iy?0dZU7Jc+rvjDUHPQc`^E6u>WR*tDsztV|BHqUrmW9UwU_n-P>J z7=|t_o&i<3S&d##-o%`oT_YnSNr{Qny)(`3w3l~p+jbubnBTq?7J!)?3*FPL#YU*Fl(3#Co_UiB%@B=mgfDp*u%q;899>8a+Jhd zDFDKq&zO4h=W(Nf3rvKDMcB~N;@A}k0d(8;?GN6(c@tHA-7Z(lYaPYEAe`Jq@Rbz& ztrdSJ*n#}>moEha1BR9|6t5$(GvB`HrKG11^$UqJa5ZVAxJMDo!C0h+!r5T`31u*= z81*0~_DRM-hiwu%yU}bvLE{yrLFaY+PIcII_{P zF>zyK~!a>1c4p2kcuP9T}>5yj!S@nKJgM-6%tQE9sURh@ymmY#vBmf z3Kg)^4PH6P$%l^3jaEigM^6}^{%YyOhWa(z9i-;d5K4xMc&M*YdeOFx6cmA4QBl#$ z@}kq!wq3j2yu7@0W5c&8lBd(Z*c45?SI!0mR@{nN^ZS*ET*h{hC}hly6B-lZgb5A7 zmd3L9jPt!PL7zr;^&GZ`1J!7&183gar?)|tO=ShtRr_CQBR+fw2cMwe_KCq}*ZKMRZ43;qB_$~@mDmK+8TM$v~-emq@I@DR=c=$QWK z{MeKfCjyG(i#NDIT;}XP;6vC|b|SY|_v85xbC|oBf<^6~xJ|X)-qhY~)w(}zJ;+*= zX*+791=|7gVlXyDkNfdN^L)1l30yx_b(k*+>Z#6RZI;}=5 z4dMRVg4^hCx2`bdw5)lCy1e`=_cJ;+HiC_D4mWOaTYU%)4(6(I?EdWEl(a4z0@z^u9~MV_ zjp7Y%fp-{2f+cP47JBUNc?KT$eO;aEh7B7!-H)^pfW*O#C`U-~w=-%=S~>;>oL8@1 z(=|0c&^I=!_db0$2oG=>0?!&68##@wRKc&mqYw%q@)pO83>$Ab{cB4CS4k&*D5D<{5NGuI>xgXInMnI(b!H1{^tOJ+Czpbw8&w*0|M{AVl zFf$(CfhrF)^>0rU1M{A<*)C0FBK9_7E+qZ0|7b4xxgK|uivh#t6SdM znwQYOJ=+SF%~9Wu>i%Q@LA=KO{)#^@8%(Nl{yey32Hp?psi_5k&j6-LOt+K^z^WhW zv(Qd`h8jHQuNeOKKoEP9l!cYGqb0|#ytdYlP}2gng0d-%+5e!hzwR^WUBIO<&%C?0 zDS21ji2Ii>UsScVJ)qjuO*J;c3=>{rC(ikyre`7VhpE(bbCwlDU+u%NC5~1p#NYp; zzCEES8uMCP_+?K^!#qnu1LvFZ9u9gQjr%yqQb6S`12Sv?XE~}DDN;P#-9NOo=~P{x4|%vZRqKC^ zd3Uf44}X0(IX^R$%wz}4K6-SjA+uRt1n6rYJB6Zy1BOerKBlQ3{u5&bJoCrLExEY3 z-sk6IZ(3S*Yw22A9)+T4`}+qpnYvVZ!QjeA2EL&3)O;ymve9~!fBUb~MXtc`f|Qih z0a4Li035(xchmD~HGR_m;DZJ9Kq9TMcZD__2Lz(?&p*}trock<7l=RF$dj0rwS!%I zxbx%V^E_r<#lGKqdj%(5f-d}bQ1ZVsjVllQ^@DW)s_x2gFHq2&#qr1EkTr&Dfv;Qj z!uAt&L5~zJseB7NLcFv}fOvtJ!i7*#(#G_(G|Qafmr{Q15HTe9GdYj^@5d#rd4|80 zzj*rW*+WR6y23zUA6zKu?=+gfd?*H7{a=noS<4gQEv+v1j69R786bw$cT7JW*AVot{(=J*TOIRAjM zjbFkw4x+y*^M-wJ*Q>aq{N%5i^;3t9=~ORVc<}M#M^#PDFUn_yQ#?F8Bp|aIRQ;!z z6O5{*do-rixFGNw-FZ2>yJ|(x$P@ zBo!M8%gvFdPwDCDg~P)p8>pzRBxvu716S12Fqeut_3{!K{FaWPMWN0`Vh*2agIwi1 z=mvdqBolV}tj8r;d@aGUDZ^A(7T=cByMz6dXRbosoOG*|l~rM;dC#-(OKQKEFxz7U zicL*T4H($j38#-jJr_wSAgufMvO|*zEl@a83{%Y(@iLy9|$kyWn z^{&IyBTRPFIsChZvPWd>C%@jqm%L6%p%t4QerKS2Z2H>^0f*_)_@1K&n;hZxjGMg` z@gtFipIdVsW>OCfq7!o4Mrjg7sG4}%iK$k2rP<%T!2k7bY5 zkEH3^Auf?3A7DPQ?)^@#zsb0bt|Sy^R(uN zXtCfVTdKQi;?$F}vuBH+D$U3`O;>7`N{!6UPvo^)oXaX1Nt^-o4vUOrtj@mmFzy{!BN`O$2gGf^ z$nzYi!GFZ7#_jdIRmpA=l&df)NN@(BwnXLGjCA9kwAR=A6IkYFISD!wvooW~90)YH zP`8IrJP$T9m^GTxVNW5kb6oP`1g)79qowQ{+w~|eK#Nq1N%X6Mt*y{tGk&7D02Ewz z_u*qA#`_cgjdyVENDDWCmE&I?KaRumZ3PnOEH^tjhMU;gb~vOnyCgX+%(M;(v5;0* zrYcwq%{{{mFeW$-3$v5%+q!k@Mn_zFAhZylxHPk}u#EN;S)g?h$3YGbV-u8mM;p8= z@3}ewc2IioR?Xw@N5%77ND)moOdk&_L@Ys4*nSA{-OP}mB=6Cm7^Bs3n)k&JpiW@N z`@Tp6H;TK}8Dv=x7w7R>2|dAhzqMj>y|QD5ymB9imdb=}RnRS!B zBv|y5JET*08Yc>_@cm>h_9RKgj9ltnje2pZ-`8<`G?)k^!ImVgHi(=24wd17tgMs{ zyEv6k7{aZAFZj(`8?zF?Rjr+*z0+C>b$Oce@f!7|>>qx~J@XkzA|fK%L3jzX`$X#p z-nvjis{GUeGJ~Oj&*&2MVPptvb96i^u|on~^q$1jR66#X^N_!C-8?2Fl-2)Mky?nr zkv;;&-;bi{JHom&u25u0hR#5O^jf>Nrp8jU2ok$T9v&cG0@k{}CQiV-``p%|#10+7 zAu455Z@EkrH<~pYlaTvx)BsFByjC4r#`O~$F*8WjEaB;QlwUcF3>@u=<@r}2R#Rch zxtN=sy%Uh{g~YijQ-INvosVVBYUjHAv_HWAID5eF@T^cJ;VPuFSN32)OwG}7?AFgc80B7#HX(pl; zYk85^od1(D-o!3*`Xvfza07;Fc^#MfuQRzOY&btFJz3niZBDRVPKuO9!-dA>BnP>Feva*2)SeIgOS}%p5BvC(+ufs-f{2vrE|H`}gnL zcI;@NLtxQNW)M}gB8mhbaUBN-(TK>%)=43eoU}9ebgP>;eXa=haV0^Nd=LHm7VQUP4wf;lrgUT0(CtVKid;xI3-k5M-j}Jtez3Z}w1I??Ebh8BPn1T)ez_ zW@3)x_1DVl>oa4NC_Y5WNjf<>ZP>W+w5;r=3+P2@6_^|ZtQ;MWf%9sgT5r*+^bOKG zjSQ3Lo(6JCf6twhl;OiB6e(i%lf&3rTSh(E=i}LB-*GG^3SFcMwQC;f{+tCUo141F z!=sty({DP`{RI%T&4EFXnb$2Q2L}gB^U~@=D7201*kV20c6|Iz)9A&K>=#h!gZ%p$ z|L0Qjoq*Zq%I@&2r2Saue0gLz#U;#O(XHVwkt3skvEE9{Nk6Tm4%GE1DI7PI5Gm~ap z(f<_s5Ci1;sm~T_^ZXrRikqO8(3@gG^k8fmAk#Mt;r|*{GI@_lH*R%LIoag65jQ@k zx4n@I2NNvQ)uzRQKqvvm=(#e8M$gi=uPT@v*`!;_^5+|f-*a(n92-sym_-` z+Oo`&c&3Pa$p+GL(UyThe`3iHYp@9V>?VwmHW!Rr4DKxr7G(geia0F5`_uy0Avt@o zm3wSVge|Lzp!lFPImX+PTvR$27oCdH8de1d{LeDOkJSxIu zvsVq8_SmR7YN_B-0_-R<#jJ;Qw5244Ga^0lkvj)nzvvKk#doXZ?iA^SFOXqY&J5#0 z-y8>s6IuuiDF;Q{TgoGw+;zoxg?0^A;<6XK=8y z=P|AyY0QKO>#;s%AN0?P=#ZKX^igvU@`!G}e)Hzxb?erdmGV1d4}pCLyfQXIZBh$7 z9)3HK5r}NCHl#2Pr9Uwq^rnf1Rpx!+Zl|5lN9@uJEGFOi7^z=z@$g(->oYo6(vdUK z;+mVAs~i2{=ivgx>-k(@%8^;2t7>NOfcwYX(B5@kqX5}vi9!e?Z@F&4=`?8YH6+w6%$9JTFYO&>=`D9 zD3Kf)0jSXM6hRT79kJu1N4IKfY9hW$4mmIVH**CrXoaA5OurwG=0hk-Xd0Zuzj2r$ zq}LmnSo-l?7N%1^fs^oHys~Ekyv(+3+ln;b5E|2y%g#=lKb^RCbm9`)3(K+Ly1KeR zCdHV+5Xb3Pnst=by9$0+j$RL0j~HJN4LP-d3Ni=gZgKkYV*eQTWXrJFOYUkJSN$6} zsK#9}ej2HBLr6i+(%wEhmHvhW$ypvGc27?CCnPIF1*iZjJL4pzkkAxR56gbNG)LmhM0JOX!3|P;BEBbE3U2)(M(PD;T<= zooKo+KUceM86-ULT!XtsVL#Dqm2gK>!5;=M?oYJX@j{X8LRqvgI>;DdkmfW*ZX^S_ zSKB)nq=Fn$t1eNaUkR8vZ=|Xgd$E|PB?y3evPII^n-}WGv$L}dt$ebsyI>rJlAb4} zDvSFrHik^Z=EuI=sqTQI;WdDk@g^Zh=xM(i)ePRc*Af4$^w1{#?P8 z&L}|%&;4WtU}8P|-Fbv~82Vfg|hxpXvvF=!MV)*e5 z0n`nB#j_cE_oE!`um%!Wz7x`0bJuxmg+y*j79vYQ4v)lGRH0mv58{f#-4u_maAVP; zU~Y9ZP|G7yBCux{x~Xpk0h$X(Yk6k3!Ucdr@~YFx)4h=)r$Mes50$A5J)MUvs0k|Q>S3I7kMkkK(WKSY_z%gs%AH9q=u1epbbnbb<_+ho*w!B`4> zxL9lNnGL$fR9J|UrStiSd}UY^)Y`n*;N`(U*4X&vaSSz4iw z;Qzh`!OfGHk@1u;n4OyHi?6V1v0;Ug!WU5QfbJ~`8Lfm4pyuxG?$gM zSE$|DWi~0VH2USJa7fj$br7-aL)S_=d2ADoPc~6*$A%)EEK+07KThiE-OW$FR@x2& zAm72_ntEje1-x7u0MY~q*T6Z^V(vufNkIsNlnj{~Yiv{>Bz=WC4@yo_LE~4E_YTs< z*VilW6(?w9D%>jem29(y@aR!k&xP{korrf9NAVF1Fu$BKd{^MLYu7p;wUtk(wF+W# zQLlXQW&OH!VJb1Z91g@wI%A)c96frp9m{5^a}RMvho4iTY~O?yI3)4>+YS_g@O9e)Nku@H)nLVAHldiq|%w#*Spr%jLC+zOyOCBBdAG11y|ky)_U zn}T_Hcyh;X_W-m+Mu;U7%6F0c_4ykgEhfST5vcJ&Hk@f7=rDaV8yt|Oeu?ivXRHCa zi2WpA?!x?xCcQ;p)vJM_dxL|6HEP+YQlr3WoZZA=!ROEC;B8dhCARakHoFggQ9cM$ z*nrKyy*`4%<~Xog@@L_{0%bOr{Nm!XP1!c)wQ9mbLP)(BdJt!mSj4w5nWSKPPx3u} z{MhTnAbuCL*-xK7{hC!cdw6TNN^L~Lui1S!;XLc`3G8KOmavwh~sAc z4kAAKZ*ObSQJiMVDUtCIcB=Gh;o7}>w+Dc)idYGl2R(cm>REe4d-u3BTM5g6))Lws zVZ`PGZF@9PqH3p>bIgg+!>J$@$VQ8goqLuGZe}cD3X21^ZoAH98u}gm*nXJ;;P> z#e|K7t#`w6$$@Ij9ODap*aVGF+{E|lU=JX^x}IM7S6^*I%6QCvTdUK8!`2hh7pqce z0vR24E#_s}{v+39*mMpTI%5+YbZt|Yfp{%(2%5N!bo zc&NREb$*sNfTvg{StbIXps;WN;b>-Kc}q($sTq`FMtFLANX{aY91oAOFP%A|mC>=V zI0D^%-78o2r>CWyv}<@JnsXY~NW{ZDr!eYx`R@8lavvpR z*two(kUciJ(d(8V(&+|)d&eu)lgyuQ>oS=ci3}R3?M^N|<|;PdA=Waa|6!R6`)T16 z!RO#1`!XV>t zLr|%8^P5|qTNCYL*F?@AB#^!`EzY1P5Qb32C9E>=85ACNli;Zb~rVr_lh&V@Brn_e%QxGAM?7 zLJNZ^rHppLma>kHP=7428_J>YHSIy5-A=#!h6c5*oi>pBb1DWyZx&KPkC+W3)B*~y zK6BU21B*^e?m7+zT9Dag&6Bo4j&svvNCyibjA+nfJNbXesEd$#CK-`2WWTRx(yAg; zUPjGXzRGpbQ31nA)V0ISygZDF@+ETKCxyXI2#Ox4R zK>I;HzQiHl*)i<}3z$JB%!vG)ocTg0nNV11S1s%TQ>n-}CTJ=lA>a1YWY6II=SM7w zCxNfrf8=Za0ZN!ox$JRF7MY)iGX8FJ(g+xhh2c~kgP&E$hG zSZG1>-fNt&E;e}QI1=GepqBxv{;$ZD;00kh z&m7XP6N9M>V!awtw5S7kpenU40yeqM^3&?beP()?-IVp7{B7K+}+yLK2?_qd|<{^m)FhyZDo*xC4gi zAFVh`l#vh8#YXCHxP`)&AZH1cCl45%Vif8pM14hrURIvr<#MOA7Ju2CL2vW4-|TqR z@wMNJ?{Dn8-?1U%Yn1ap0!*Lp7xTSHbFXzXrClpdt#SI<;LWUL*2}FEN(!%(ntOy# zrUwO{jrOiGd$KSgGIujz`pLwc!#$>gnd8wL^tfqLbC*R^Hfd8(NRk{2^lWcW88S}+{8X)7X8Nq#V8SinhdGaJYAwjmP^;$ZR z@G35@dFuV6Q)_TfDdd_M6^*u@MA3o!Lc(U$(|`~}B#k;T49i4a=9m;OHMA%ebx*=Utd$^O|^Hv!V>&VPpGMv1k<=hjx}Y|h7CnkRaFrk zI~W+I1aGQG-#pFah@nj{EDiSEjCxud7f_$M6ZLH5%UG7SiJ6x%F;W2Pj!JV23#&t= zl36CQ@_O&%O-oOS0QNN>Ru>Ol((YIqIes57#Ny%M#Hi9X_0*JwAU!?3l#Na1jdPN;a2wfqEFB9s zFRv>HHf#?yC6KNA{PT{br=L>Mxq9`qaGV2x$j#J*Pr6AFH-+gs2$x)inj39%5mbNiM2AbDr^$8;7p4&2#lGN#q+~VTmVaHr6sj>Mx zVb1}&A@|XH{zNI)WHiOiavUvvEU>5Vy?}Dv;F#_0?tZh(@U*lim!#D-sP;WrgAv~R zjX?1I`0>n*C=RSb>mfMfXmyZImzqr7xqUqG)wlbLYKUz@d<{%NeSH7^P87r5^y_^+ zMYnEY*txms#smZJuEBI~0Rd{vh^L^~qN)O(;*$~ggFU}`ip{EOYToYd8|Cv%Hr050 zdtU~G95x@Zc-J@5yZ7#;-g=oFz;Q16)hjO;!YHD?{|tmK|KiG}rF~g)hf>rR78Z)n z#b(s^5R&OXe*WwOS>>5CXX?iq0NG)_Bi49qF!tdh^~--SAhzMXsI6s`QIF4CpJO|} zZb|*fo}NTxm7J_N>*!SGT+Lg}uw%!*0|&}?l5gG*w@~Zi>gz8MX1-mGi;g}k?C=aKdD^cOUl ziybf#b8~ZZz_G2O+}zTfhO&~9iI?a1xxj-?oxnEl3=ejMI(lO7%|4P6&}T`m!kt7` zuiH9on^V!+%G)<$8P#o;`JP~DAjTRUIbQ~vGK*-6)25F^gITjyiVQU6!Hs?7ziNsl zGG|gzQSn;8rO))6g@r}?O`#jtPQHaF<;##%^%DAMC%&lZ>%UUTK1K99i4pl=r=T4! zz8doKUQr>NGW|ukc!c)o>;SuxPF5yC$-y}l9Dn-wy!Wo399&cmoh!JcqyvOgnQn-G zfRRT*!II(tStH=RDGtlT1QTipMMZOZo1*W(g22*laA?oU@3FI_fElh_zI^!;wyNjG z*ocmqnc3_=EEp2%`x(IQ&8$~Wp!Zq#04@s4>uy+CVNsgS@+43YyrQGic1{55UkaL< zH++WgBgV)Vgw@s#Id|@y;SQ_g$8k!^%KkjO7{rG!dAd5a{Go|YP#-Gj8R->*fr{(m zgg$nCa94@(@Ti(*^@BuiVe^#`fn3Lv{S2+k?vm-gv#nv4t-TN{g}DvlOT0GA$ri}T z7S_d@GRt2ML}JgU5~(b( z=x6xopn&0QeOX~j5{!bp{N{sYU0qk=LPgox*)MAg0i;O<^G&aD^rk{dErJfbPKvrj z+p;Mn(%_u$3s@fXJV3M!vN}bbOP5YSmFcLo7M&y=9bG-mz1S6I+@_2Q=>qiu(LH$g z)f4(QXJllKT36k<2W|wMnyA)~*q<mOTH1 z3^2W|7^r4dG&bV(P2a8RUXNjLJxF$r#~NqW0HbUXz{0Vjgz(UOYM`Cr z5(63Lr@1Z3x=noTSkX=8I+&!5I0QOU+jzW zC%t6KlMGWxwdQ~LxeBGu-4vc^GEcoV25p%`tohLal}fl7uwuX`53|_YZ`wiGq-)oZ zwM5Fh%Z|%hMO}XE{BAKv`{o{lvCOR4*hj2`CNA(aIfQ7wzatvjYFG4)js2>tm4nVK zS+_0{RG6r*;oiJCzJ2?4@*UzAFFsdNQTZTv;)%yy=Pc9XbTKgzGWt%vQraA#w|o3- zp<9wVFM^zoL+9Z9;7f z-J7`B*uW`{0&k7I@O$SZ62Q#0K}B(49W48F3G(}12%2@?&z>U~*G4Fb4<^`mai$;1 z;fS4qe_LSFjdPZkX)vT^Xdn`_Y}akFm}4Qb_;S9cfV^tA2Yo$<{XUU0!>$uwA{N91 z&sZ^+RV)as20QmU_r;5ofWY_h^2$Oc!MCXRd{42)#tG+SWUk9YosNOul#TzPOC3E$PTeFb!W^V4Cf9S{e%! z9ojANgyQ2ZAQe*J+zaPoA2fxD4sbEu_ygIpUMxEwTpbxCO@zZjW0ZC~5H)l@K&phZ zyLvUEv!{pQ5H_qKHQ%mvM$2aS&HB`UFFg2x*P35y>+9K(e@`G)5ZT z+mfo&P(VnK($;RxVht1wlBv&g%7Z-N86Wcrh;_`6Zy3GT+{1z*!jKJO3l)Em&x$)m zeTn!1J`(UcR{-CsmGbBGN^cen(xyv~**no6kCz$DTbSny3#CLTUxOJ(#{9kJ=NvfmzZ&itjx%0=#GlROUuX zJ)+Y@AUre_3qii1%k08_habRJ0VMa6uzx~?AaGHPT&}64nyA-{pQsIR1qI^rk!dwm zRg#vLma%@Xi;KOdrfdZ5Cli&FlumJ-v@pX9y_p+tH1-QH%3{AXa&YsKWUkW6 ziSbe`X0J*`!;iha!?Uvk8P=UVTMoqpOGx@>WU98^M(fsQB)@A9Kev?ltbCLBz*#6W zJuXg~(?kTH*=$5O(6@wL49KG@C6q7D^fEkCvgGlTLJBd_e6CmRaqzCAPY-BVJKs|B z`at3TKB;|Y(PsJDd($(ZoCfc^uk2l7#OHmX$C#01x2WiTl#_8az$+ggA4%}lQBI4& zR1d&9Bb9PDI%UA!0H~LH1r91NWM>@0ahxiwHoGb_MnlKMv~T3pR^ghoMq`#V?I`W*_4`^y4m0F%#sJ^ zd+a=I7%O8iVVkq(UCF0Ul`;mh=gw_dl6Afj1ol=pMqRXdKz2);F7e3w0XhVLcBfIx zv6fS9+_;Y56&xH-Cs?ugeeC|k`ic2FcSs1d!;tA4>^FR4m<#$=Jkz@1NbsqX;>p~% zcYE}L>~vBg>}3`pxP`WBqVgJBupmQ;QI9~exFi5DQ|N}?$SAh3l3)VfA&m> zM(ym`hgFcTD=2txez!k@3X?bW#TXHAmCVDOf!Ck*9Xe!Qdm4sbe0zfJWO!iaZwk&G zQMCvK69Lu8Zo$F}d-;r-wNIXMYN{cdcF6~LdDp`rO3UTuZ|r78(IGvy7IS11Z~ zu7dmjl5O{Xk(?FEw`oI#{Q?Y+ush~y)5pI1S|(%I)2Y=l#Jm~tJ;HQy1?n&a@j4@e z4Tc^R)YUm+BHMp!hW2{EK>xsHi zeYO3DCI6Doh3UKYTrpDS#`gH>M;b~>`ydIZdTg{9>0=?C^GFrwN9FjTBvsPG8`(<0 zOE-ts{!<%$od0ejS`l=FF)%f#c5w!rM%l$9M~(ngOAli2UBuZsC*U}cvVUNp4?qf< z)3Qa{Q^n^yk$%>Z`y-`d+8Y@~GIV{ICEWG+g%DTuqfl(#v~YxvdYQu%hW24!>IE-f zyCx+r?y`@SHQ>OJORy1FB<1yT+lSVN&rr(4*IRi`qIGx8T3w2$$F^{GMm%V8N9-$1 zA!wZLI$5RV0F)@xHkRO&BLc^f8fxQnr~7vGii}k$R+N`NcT68=OURr;}S#O%b0TN%wp>>M24$*sEFethJ6oSk1GAidghGZ!kb)gVb$ zmYvj9VgN>5d^QQZXDn5*@ph_@4{d$Aafm=riM2~%)=w_|gF|dU3xro(QQ>_w3*0w| zj;*)1H=v}ZxtUv5Y%T?iA+D5)zljN;ap^{tYh+80{Xi!-Wd7pCi;H4GhB`Xfs>;tA zJbtE+_a20V8o_UAO_tuM(3fwGAa-Nf`(#Thux#*r$B%~i1vwa$;Hcip1o;WN5)YRL=bA0@@$oK>pgWpuUG)gS-(VaCqG)6&g#6A|Jg zW{|S!_$^74loL~tU9>oQ|0?CZJfSj%=ULO&8^DwZE!Sy{KypMe4andW{HL-qPZh3a zXepnGSl3chAF`m4`#pE!~%7O76rOeQU{c5)&(YdWGfz&03P1z&CSwl&5iCB}>yGUu$tGXu8WWF@iBuOGV}C z1CcX}=@F9|rq8ExaL~vI&YEY(&i9Uj|Ep>S^g=< z#uwYAbS7Q3eLgzPq=z1-YqfqstL2cIgkjmSq&i{y66>$&AQ@*%Fevv+Uw@=jb3Yh_ zR-Sz2DmtLl-Gz&d`C*(WgF&oAZmmV15$K+Ej#hI&yrbkbWSsJg;T%>HP-mhh(<>lE z3mEDux?Jp=V}_BO!?($}b_ugI582j6l>4;UCwJz|5!O9;vYhAL&&5K?0J5A|b+-Nc z#gVoKH#hh6+C&UInff9`2<8pNH&KjYN<0J?t-3$3q3K=3i6k>F^S$R`#&JKK1?O4% z`W8hL!;2~^g}&3T+@$I5y~0>URz3(`OOh3zaYBSu)@a9>sh(r3f(s)~JD3zsEJ1Ci zqe#8bto=Q?JpVwZ1`m{jeW5m4$5q0C@PHPai3f&5aTy6OM%?^yh!?H7+nG_;fGjq@ zkMF>NJ#aSR_!$6q;o;#V%XFpDLPPcm3?hX(P*6~WM@Lh<5uiNh&?9_sbgI;NyLh#x z)tPQ_`T{|PCriepGlA*r7Pjcn6p;1YzHM9C)|>cdZ%@y}nF4>neAM?}fWS=OU(-i( zW%4mx)SyCh4|EE@SuU~)dIbFuMTV_CH>8=|}4tlvMEJ#u3F#Xn1mahh&;X71p@gL}cPK`V(%T3Y%vl`qtY*5INL zct@wgB98L-I07L2T+IX1zc$&(0=YvSr^Fx>KwacoZs60WY|xqtR4aVBn8{G5Iopcq z-?#x;DP8k63yNqC9;vfuDeR8TSZug|pP55{ll_m!2S*-<+zG@F7HvMGuSZtzf#7uz z%{F(|fD7{Z(FjI zIey&VzH0}CV4ZIO=a|^E*S_IHSV_($+_>%JV#h2MFtFivxuu#41G8QjqQ_xe05E-U z{*35Q^cLDWq9Uxezq+iS+{7A^K=1pM=;q71<^nq_nwq#EX-y)3-yQR)*(&5wvy+o5 z#hEKtDu#=gFOI!L1OoENF}@s7 z@QBtETb2wLrD+JA`3lImaYaJ|N8hPxH*Qf;O(^AY`zCCDe8I@ruOvN(d!S5V$Byv9 zBCo`m%FT;g!&#HTi*c{Z-oK!wwK3CPM#dd7F-d5t7UkYV9ukXmRFy5gMbK1a0u?N+ z*tfriz2!UdZ(*V*W8s}%VxyvpZe3tteVMz-QLa10{@{RfMTwxqxP1r1#feCy zk^@XgqD5*3kcIk(K+nMtz&YUAvsbTP{Ye80&`@pZ14;bKj`?08G&BpmMJvo&l1p5n zjJ3g@p41)67d9^Pqyz))80a~~F`EblfmA-9iI&e2h;SPIXM6To&5bX?rf*0U9ENfl zcbvSoWCLN`p~nh0f=ue_o|0g2+!-MtP#Fy1y8c4l5=)-^9W~8Js;EOA|Sh?&3buxZ6giI^k^~Ve>6@uV23o&&_pg zG(V_gfJ@C3)X(eOazS0SZmV+5*LMmwGXxZQ?1+nn*Hs>Oau=}ER4&qzlVgI~Qy4{) zKClz2AXRaqUt3v)hMkts3DxwNO!C`CTZbaX?Sb;rV zX+C$*+8+tp-`&I?_Al+x+g!bKIeXPf#~@iS^iGYQ zL2=<#bo7=n{>1{5jsXyrc>=|r)r$Xo+3<35Z+P!!(T^XmRqBGDJ-a^nlzeg1`D%;4 zv!Y^e-^aauqt##r@}z?)&E%s_qc0B5e0za^7XIUt_LJD!?5pR^mn*FZqe^4o{6|@Y zJZlOvc|p@;B){DQ#%Pc}x=N$;>t$|$#*%G250JNGkjm@V_;H$6jMRW53Jw`KgfobNhMg$3&3+I4lk&`h;4}zE_vN zHeGIp&he7^j4yG9$sRcKEv z*zVOH#*KTaTX=c!d*PMAq{8=&t$7`tI~Z+Fc^4O3iUi}9xMxWF^yyR2=g;?C(9{$i zQGhmEXJ@DLQukv&tp9@K6M9~ODNz(IruT>&qnyky+VKz*ouNsW8FR@>d6dz}d>_l% z4qnGS z6h}xC7J=gc7DToy^Z?0X$X@a4Ff}AKH=f}&RH_?Ep$Gvn0T|P@AOtpr<~7_#9O=X)}ByP5O+B|J6R~K`e4s8 z^LgN1nCvkBlC@D#P!P&bl#3nz|4CNBNdZFz`UM0itAcBz-MaPRyRV6tqB|G8vX1=P zkW$vZIYVgfDt&E)zAM)={hO6LGW&V_C#P#IT&o<0?7UxJ^Y|<}70x9x=A-g0S4f2G z)y()ALV7M;bLi7u$lmjx{6EItJD%$PjUO*jMr4FaWs?!5j0mSF*^-rA8OhGfJ}p9& znPen0GvwGb6j^2ORrcPS-}OF@?$h`8`92=s`;Q*?E%!O^_v>|C*Xz2T*YkP32w+0; zz^rp_SF@ryXwZTpBhBT>u=v7l$fR6(LvA7*fWH~UWdwT<^1-FeIQ#b+BvLzzD3`88 z^>`E}#K&JVHckLkUt7YH8VlQ=!2k#A1wwJ)NC#~7T-8K(ktWmwHBq|$?+!VaG}ujk z%wE`-AJ?_!@{Nt+mnfA+R1a{zK01#y zXNvD~0f66?kejOpjT8l{GOCBVE>jmq3zoD=ik;)8MqkbKtZ8s?5lzJYu>)nxo*1c{`pzc}xo9K4F4 z#Ml!D_s0??NKZqMYA)zBA72=NWv)yw5R#RbmoZ^e@HJ4YeT-XzM63D_ZL0J)MmLqK z)1^8X-Nnsi`ES+wbg5^wus~+{9|FL=k+!>$5t|VQoL^A1umhNkrHjCqNgF`$8)3*n z0Fu8?@ECFFBiHPAT5Y)Wn~?WZEa{%2!b1B9b~d)VNqMPdNJfnHH%4?RgVl@Gq-gE% ztQ%3u>k~OkmzZuK`+(LXL6E`naxWNF{`8H^iTnhs_l^a+%GBGmEr z48`;q)(qR@{%=jZHlbSZf*9`OqOkET(U+{LYB%Ab%nI~M`l#-bQKGTI5Iqt!U$zw< z;<=QwgvLF?2@>dznJN2GEE#1zr+J^03gjeP?e&0oZ0afvnZwe^nt<3pOMvu1Ua8pQ zn)o=I;$=G{A(26Q(!v7Js*aRN3hytM+k;4-}ynT8?EzlOC4WmdV6qg7n8+25BKX+Y$4dhFK>F8!m-3NI%U?q;(K6i<|Q+5Yuz=^>L2b}O<7 zn}&ZNmHg48FCo01{w@-wG&yR>&dwgUrHFmeGYAvwTQ>s>?zPcABsSUCzn+R9MxR0= z`W4+o{Fu3y@Zc#VCk9?gLsOGcxeo~mZlU71vbx&2N?P@KN=HW>s*OsPKB|J={g>|R z0&D`Ka0;k=@1j~tv$LrM){yRM?h-i84to^96i>)8ewQ7P{%ewmp|Nz_838qQ+Rcme zHRs;^{I33QRMgT%MRkBLJKSsmo)EAdDsninZQQ+Lz`!v64sC15x1lbXRQSNRoHFg9 z`BY;0LX^y^B}TT6J-iRswB^VuE>7Fjw}m+*@jitQ3bV6S;RwPNF+dte^6@%-N`w%$ z`*e9o6Q`w9dG5a-ff<}b17j4L$IZr3K|w44K?yZ7>0x725%C+odyFSe&@N5`KNOPf zZ22|j`H8YslL#1xyQMy!vNuMvO>w4uBEgupN8{~-WkTwL7lS{Yu1 zwR(=>l-_xMtjBnrhPnzfm=}yAj_*8In_3?f#2sd?3`im%EzTFc6aS&81#YeM=JhL+ zrWh%2if7e>+1iDjb>BOC`Nd%iQ(0NZznK&d(5kxkx_3qg?!|sw%i)<-Hwck&u9D(W z>A(v6{P}WvmL6?B(vICrSOX4JbYb~uzzvvO8 zD<2>jBRK^c$3k9ElqbNhHPL+939CcM_H?bwEZ}XA)>VXdYr+1E$2@_fJl{^gJf?AqeuVwMee=sMG0 zeorov3l|bQ%pYQbN}mjbRNiv~8Vk8knw~cxnbVi`EB5^n$dT{!7MA1eR}(IHd?ptH zwO`WpVG-Eny3G#JCoO)LmbJ4als+*?I|jH=V+7aa9PBY^#5%All9$ynotERvKVPU| zAt?oJ*f&|>fGqrdL#V|Xo!967JrEWM;1Y_Egar0(GHBVUs;KNay5kgKbSl&6u@aj* zH?FuHICS!`_m}9v$B~=$+aX(lp1Q-Tz>rg&sdLg^d(CtKc{lVnoywI-nC&0{$?*E} zboke=UtgT>r~B;v22w~18LxR6%)2WFgpPn4t_O@B`Gm)G0UHJ(#Q--Z zceQDn7$8C?abX&4Xn2K`r1MiJUj8*Khzi>1@ys&)lb##1iocT(UZ(smFLNiFlqV95 zB@O}UOz%=ml;3K;F4mhSkh^s_VUSwk*XCM%#O_X1c67a2C|)kfF8;)p@b=Q!!^6d7 zNeLZO$Cz&cOp=F^m-mAyj3Yr7_wEIOy3U+a*%531kr2r1D*g$bXX%}RSeKBVZrNQ3 z!1P=tYv5gjclqK&I-ein`3%&VZ?pfPmd`L8>}el(FiX2>ebJ51k3^e z#rD~=D_FxDK*M}FN$WfJ6Cs2alS{T@;s25(4c(C**5u<-fB%Eyobpe1 z9{dga8FBH`08)z5I9yH_O=(fG1eTG}fWg+4@cWx(+eK`xEgjDu>LOnXRcZZ`u?5Gn z-puMUghqm8Ju|T&4sh|J+cy?yU2*g9Sk8M? z!ng}?saT-fM5X?d031Z{Yvw#O6aM=AXXi}&5qeZZYip7Ym$0xVNJ(fO5f7Ao{oJT5 zKYc(VmMp%Hf9tZG#KPN^1J`y`8fT%Alb0GTE73mi+fBFE3(jJ$&Ve19aEpIv^E zjQ4F>Q4kdJI`32en-SoCqdX6BjsWP@NyJ!3p}B{|oM&ReVyZj+d+Y-JJtxfzFPbxY zXsIqwW8Ajbe1HtKm+Ebeudv~LiAj><${_#gwis*D#&n)|tL`tRSnt}y>gT!f zyKs-*>T1JE+nsOZE|D*d9!!Pg#wC}Gf~(=T zdpdhK5@J>!hu+{6hNmviMvnasv&pf|$q5Z0lmII`tTys1_S60+KH&&h?>fcLBRh<} z-Q0PnS`nttES6>tqT+pKg2}4j+)QR4{xcs%YeTORBN|whok{|T# zl?8I^yL^Eg*!U%_jr5p+4g>VZ15q9QHrJ5CGd^D0#cT+hE@mae^3!!|HQ=4@;4NS`s*MRzd4Ld6lpeSUq+RJ9E)X#3 zqTLJDh}j;mG|EU0pA*O;b-@vS0X5Jm$GR_#kg+!mTKn|b%f znwCJ6F_~isoRUG_YgirzlPIi@%=gfncxH?;jD#Or)A&#Q6HmO*L~3szt-Zl~7#tp! zcX0TKX64*PeEH8@yqHEyY-IttysCx<-MUv?@xWK%GA>qwt!%5%_eE1dHGX`)b7KmC zo&vv@0cMvxn9S*cy0X%&>Bco~Zf-WfpLVMdPyoVK>K?-X{{IUBSX#Od)a)>SI6g9U zCuFi_?+@NtUPIcw4)=;gOWf}O4t*cQxYv_4 zR>4CGqHm(pN4j!M1OE&SX>$w?<_V1!3>~`}8DkKBqosmge(;2o7Kbu5lI^6ifGqEd z_$?!Qdo==dd6*g0zCN9kVX%|c-LH&8H`x%KTKOx2u}$Mm@)AHx?2>%&yH=e@*Q)3= zCmhPSI0TQ8l?7dlU}*io*+&`p{hhJ)&6`}n&ZDb)-GuXkf^taC;D(Mj5h(Fdgxktv zp;_@z!z{RWE$pCYKUtwYx5V~?Dv!p* ze&Rkb9k#TH)(8=J?$#~D(r|<=`J55JFJ>S|5y8@7uTVj{3fd-edd9stFy}BDX-xwl zqtO%{6m&Zzi{+Ti_IC-69LenhtGdMAjjM0W%&7GIs<7Yb$dQ$s%La6XxGjq2rdlmX z662zquI$v7Osa_G%LP5aTNad|Cj4;PH}DhQGyeCq;PG#XiusF~x~Crmu5fU)R7Bv~ zi%$ch`jF2lB8K+EUFCk#X6TCL26xQQ&0TgFbl6$?JkZ>%=T#l~`}W8u|4-^P-nSo- zGF)5l4gaLd@&9vbA`Rf<6ot<4IcXE;~EodiYWl5BWvR6M| zUW3m-orkO;Fp#nXQR(pFP z0fL7VGP+8j%L4y;q@lXDHWVBfXv;el7o|@kZ1JxqV=H`9`&Xm5dnWw1sITP8g(dj9 zJ!k0$P8`>zcj~w>Tp4Zc_C>9L65+QQI>1Ery>KU@c(BR6d+(9fF>HVH4NghI+bpqG zCv3kOvC~~DFNT+jbei@#zT;!q2arcBKV_2bDE{O8=L4ude=pGwdQn}a9||PrsH)1w zxZ|-4agZ$w`2N7#(Uu0d5XuU}*b!o^tg9R$nRniTCJ5fw&>&6Ehl(uH|Cg^ZJV5X$ zX4PL|d%bM@s?fzbAGXlYNyDp8u}fefQ$D`<13+1TE}yEWl|rI1_I2s;u(S`wP{VQ;ua#6Ym1$wq+#W zM<%cAV|?-1JhOX~pa$zelxl{coCm>JF2l=us~vU5^&QtP&w_1Ya0Esk-Zr@+){wc$ zfrX-Wf1VZK#T_EzIPr?_ZCV;{N@gZTDb8podqEu}g3>C!tjqv&TTd@)RLPog>odL4 zoKA1U@Lb8Xtel?SLG_!+3jh?xZ8beH(ZrsvWT}~iNxgw>)x!cFfo7Z|>lEo({PmGS z)+c{7-XGr=!YGe0GSV+bSlvlYOA7%cL;lY->YXs~RT~x6lo9QpjXQT8(!R8>x}d%6 z^=+Tf@87@w{Q8m7?ngnm)$+?Zi64Ur zfjJsQ_HVv;CaK({f*Ljg1`OC)ab4fpZRtKp90wL%TCW7Zc)>I#-qLS#gzZQAmsi`( zneo%#7#yNVGfTC7AGviOmZied`dAQw9CU8RS(N1EX&lbocX26vCcvzQwQMnDN0PcZ zH1QngAXL~zXkl;Mp@H*Ov?8MY_yhMe6l$Im5J05J`M4!5=Octn9XTC^r9cm2MoKNS z)z4@&z|i}1P-T7QOHiTbHlO_wY|o!E11AZR18R6kXsE2dzJ9*cD7Izeh0;ZcaAabB z`2CmitFT!G9Qg5Z&)#{GWC9ZPQy)HrhKI`ov1pZ=<@U}iK;!@(H%!%NP%^6rHX7iH zz!IVYG38C|<)R*T`R@VgWUcBdOwY?!p4?PrQiA^ts3wqhXn%46GDPJH4CgS0M##GV zkiDqXQWB1rHVXifc#l{)64d`%O)M;5-IM?R8~L|a%DYGmno-0CB}V&Vx0PQ+17jP5 z;8u|vw7D^L&i(DC3CnBa4trL&hqry!e>3);IQR~U9Fe5SNu~&82}_UJo06K^*u%Mt z^T>iZ^GtFS;5~)mZCD}2;s=lap}prF1|r@4g^}y&u>%u880A=Bn#@Tc*_}pF9z*zT zszmeKNoSOd>b&wc+okvHM6p6iJrTJ^K5SLY#n3H zDtvPdM*2Z>eDXtz>CFA^ZIqF>qeW+A_5V?+F? za2XmKiVPVD{2(9#@^>gN6tu11NpK4(UINyNP||(W$VG{gL+rw$l zLt@h`HBk|%FHq7%z-Vz)bqBAjkyO?1+S&dB9Al=(>MFei!E-R*B!ciW<3xZAx)*e=;YS)K zLslg32ccuDaT+N%P)IGg)Mg(wzo{s$(@1%s*2ZqFApMM6jWdHAUR#-cj9da)Tsuq}*7YZ-v z{GAHdN6=u)ML4*0($pW?GvpfO5CLj30hA-Yr|K0nPF8ey`iUh zc^~^<5EN90Sjz@#;J;OjArd`m^Uc2^q5i9?*Y{%aySBgGZz!?k!LySf%Zv1+_(iB3!HI|9+ zJsi~5JvPl{D{K7ena7cc`jlFww-x%>AiurVWSW-#8UTB!VUXDr4mZx?0E|?`lNV2L z;49J;5Q?I#knb66UW1FoAZi{9Y0Jpqi;@EQh=vU=JnTVN?zUU4ZmW-sI2N&%^--8E zP#nD0s;*hpQBzZRRDi!&<^9$yqmxK#fj7DPQjWl4$+Vd)!Yw}x9P&QrO{|X@rwjBlv8?|3B3|h@uauO)tQi91I+wJRbSU zoQ7LnCSL*=cp0a(E?#uuIK_qGH+Ek~?XTJn&LmB3uY5ONlH9%_91CNbD%7=(Y)R9N z$>IbuZ3$k5vRa!G7O7!Kevon;D$2Oh@3`t93*mG-b~)U~!|MPJhk$BxgLt=ZxAO#T zObB@rlp9$J_oMJZ?zZGnNBP9 ztw?cu##_L-`t;h0#M<>L&+lRbC-l2olJdo^7I^)=n28>`^Vk2?V+tD85MudGUZ@?R z))_mg`@38K5N%Ng>~V^J@=lr&=bc%|fC0Krm4<)XA@ZcSgN6_3q1hJ3vOB$r$F8S8 zlxu`Y_B61(-ufiLmj&*=Wmr~Gzg5I-)7y3o^sTb*)BIiCW=UZwoU3y92)@ydOihKs zs6SabxgaZnt+H@J8q{$lQ`#pgkDn=d=|e=zAjOX#sPYwpddcnL6}M6cbRw{A zfOInZh!Z#EgO>?cyN(M0(u+u0p|bGTdAc=dJnA;CQvqZ#zNby!uBL1*VSdwvQ_&^n zcM}((4gzBUA)oMQX(~4oH^cduoOBy1-|vgAPRSw)X{P+NRq( zRQ+)(W%Vmtk4g)8{!HX}keW7kM5asVpOQ(-AT3>9k3bo1gIQ8b3Ypt+=eM_(b%qLN zYR)0d!|a7FyMf5p)Y}7bBIg9yK4hsh)QM|m_s;B>mE7LQN<;95M#-%Yyqm3_RdNO~ zX|?r!gakn^BDktRlDE|mF4q&YU64;oCL9$A!+?@UAA6YrW?TlcbpZ(pzA+Mp9bTwe zhZ`}jI%Y*G*2j8G`|)>+5)$2injJ`@3&TF1^&;&s>3JgMuRDwKO2rU{jDVss#jhAL z0XW46!hZd<#8frCWG!4A4>`zy|tPwWhI#(6D=?-mz?N-mze%p%%%qIl+@=*w`BwJZW(bGB|{u1s0tMWb>YwC0Lyk(vgl)0b%r+D^xhwS8gCjF8O-yT!XrE?@JZrU+_ zI~gI;d|s8>n*Xzt&aj{1@Dnn%(A;Ytdd z?t*wri(dzBr~lNY{b6kp9n6`qTsUrI>7nnM(ib%y5=2inth~Ias3_aX(0gicrsle8 zzhLXNS#sf#c`cn_bfmRJj#bB}N7=(~z3n$4My;|}JtY3BfSc~-FrLDxGuc~a@J7kB z=JqY-9Ro>2K$K9&;GI6_&iQlZ0~iQL&&A9CQvv}~-AIrjGJx7xiDNbG;w_ddOP$7Z z{oW4M?=M@c&y;*fp=n>&=XG()*KL^j%_tw&dE)%UGce?rV$&DrwX+5stv$f z_G-x-irJEF*q*2tGJdtSwQM}o7}KKfl$an3yw$gx?uDnJi}lW__jKu~*(^Vw+$Ipr z3qP+nx;M+tPKN8w^=>zUsyNhXa41735|RXimuaS!dl!2jOjr-J|4@tS0g?+`^P!;; zmfYB>{!(nWTa*Vato5bZBmcBwuOoy%(qx5y(3}4ZA&dsDoDPPuV0!w{4N_H8J3Q}J z)H6#l`$pu0m7eCUx926+?*7!mX$XGlSLe@MPTBhI*>&E;!NsMMJ>25K{q;7@GVZa! zdt8f)s>|KeR%Vo1H(v(R>#;%TPdBKbFJ)@CcK#C3t+W-mZ9Bxa(g9?qrp@)%+AFr} z0cJ;iytoLFJUBIVysYd%Li{zT1wcm}$>NCXyOk#+Nri){4;h|&MvuAjTyUW;yFr792gE(fIv-1?>PtGm2w!%gvhA4R-ZrnY6grAI5yB z$0b!^yYGN@j3Fmx*`se?_RKeZ>a}YGv^lSlF$M4seoaoTs zcDZ?ip;14hblaoKxxKo@AtB%Wd+tGLrVM1vPEbe)8(%n&(Qy!M0HL1?F00yQt3hzO z3_0@24xf|%?FnQ>`@os+c-7z#Bb+<$x-F9-2|6r{4&>!GVaCnbeCW9)u0G%Gf(kyO zeGoHcKQ_~Uj`M@J-MzJiKo7P@a6e7QjA6y3rM26;v;hCRnc-WLy>dOlI$3p zWXbmlLV~iBWt*K5XL-cMwe^$8hN8^Of|gq_a%=MXEYB(`1{7qeY(?r8G>NuKpOH*@ z?r!L1CMFiowM;D|NQPnlBJ|4XW7ZBfwYA;#$tS^)1d5OpBRq;j8E+2{B0Bz0!ag%Q zL3ZcNg+4uY2`0V)^u-BtfAbueXPrqccx8M|dDD=?>8p(4ty`Bsd}r?$js@Io6&@Zd z+V(hFG%eAst?ty#9zm~{Yj!Z5-!)=IQzN(a5$z-EG1uNk zeg5LLdt9Zn-(F1|@&kb3?%u@`weC~73j>X8LJZe$++c;Ff^RwF58#f`|Jl--fFX-Z z-J}Bl2o5QI0?L7x3gG$}hot?;i+tUT5#AqZILFRP@Pf<>QRlbH&>FmFsnN>q0rB_~ z(-^(7kVdZBdI_F@)6rA+#{@H}dKYqqGH_;$Ip{R>QpTvydh6;qOvGegI z`fF9nay>dd)B>AGGbyob+dbW&#oT}=)Tt+BvvYd3vP!c=j(|V9N7tj%GRUrqJ+dxI z$=@2p>g;{j7{uG#!#lIM{wELm5mMOC zkh5IGGY877bd;-W5p?r2t0iGT9?TuMt3yM*bL5s2;|TvPPY@w4;9h|)&OCa04G$`4 zsb^eT(?d7cTIDO~%kl@;^fYyuAy@b)!M+_+vhEd-t*|ZOk?`^)H9>sPPcc&N46R$1 zv8PB=S-6V~>8Ttn&G|El^u&DQ@{`RqQPS5nLuiYbN@$2V;=S2kTwZg{aE)3u6_7Qd z7BKp;EWzphq9CToEt)H&*G?SM#iGYwl3TGw&J!a{Yt?J_h5UYBr*-X-4>uC8eYV70 z=-QqdZA_TJ^eU8DL5gR4&g9kfp{X`zG5-8=myK9j9yTV?!uDBiA?vVQt{Z8AG*(X6 zln)S!s>SBzA^1W~MbYA-i*W2vB#ex=A8%2lrlGmAZ)%rWE8<1~*P6u$p2O=Wc%jJP zhYwu-4f<1DS&oz1zbLPLp`)c`hxy=k^+Y+`JFD*|Z3r|4q_2hP?Em6jbkXN#mLd8N z5W%~<#80{^hz6eM95`ADm-}*UO`L0#Ssy!FE12$6>b~KeQdf0W?=>lAxITuzpkC7Y zSa#>Uyk3wO;OmYRlR!YhN71iq_Tbe%FI|GXrnkxpGkH>H-dytSTi zclP$U+v866KNa7F#8pwf{7{VY2zqvzy-iS*zIyfby-8+f=92}QbUTTuR}vYe)$+o* z$~8RvXNG$3=SlthEbY6KL9s9I990fi3@fO&LBTq24g`g-6&13;>TI11CEr=FK3M{o z85y^oanB6y>W(vjP}`7lgEQPJ;nv56r!?ei)1K_HcEfbTd}}Lr+Fg6y69YY+^AB#! z$OuJvOFL7Hu~y_ci%?ZN}Ta=fZ5mDM>ZI(RxKc zyy_(}``c2pvyF-Z7G=gU&L0Rth5kp&xNL)^2-+m^mllVchNFWkgO&3}d$Z=;FlLQx zRxP~Y(G2^+2Xyw9kf}qbvpb6K_5Fq-gOOglIGy}E`$}=)q0a@DAVb*XpBm2QGTfg) z^MCT@yHKdq{8peOtEjwSNPEh@V<~+_1V}&pts;4@_md|lgnY&(EZQIRKT&n<^8&H@ zrfzDi*u9VJ?AewRS}Cc?XY}6HUyum`#C~IA(~?3w>wW@qTd%x|Td~?E)qpj3SH=M| zEq$r^j)#R#;rf}S+)=8k6Je@LFaZRSOL6gK@Cj*M}L zI4?^*UGUxN&1SC~YlKs;C3nTT_fy}1)YDr-kqP5XDMFhh7%`WtGa>{TRLN;+=ie@Y z_Q{)OWqn;9cq|1zt@ZWww>)=e1$mhh!L;_4@Lzb=f-0AVwNkqLYd7)5KYt*jq8ve? zKVy2sCcZObbS^c3f}!TY@P&`r#SiA$rYq>v-KF*)d@+(!AExx|nd%KSwgkxyrejR4 z+%r{&#M!jD^mXj|mpU3$+Z{#|R3oCT)>geAzncC0^bq}a)|nJ8-jD`H&yY24l&0}rmj@fKN>^y3AO@zd?gQ$=yK zL#M|Ze@yJ{@29@tlDh)es`Wc2MN`{fj_oE~xZMS9%U?x0O~Uy(m+ff2e)|Ug0}b=Z zy#4!eEGV=T4P1|S*W)-|p|^(sTF3b%QA|e>bp7ArcjrHC-lD#xW8|tlx9$jk@!~Ii z5t}bEY?6^0T(dqEJfJLLmRF`>p$r!(q-3UtLMT%x8~QxCre$gS!KlllC}eBHuG)NN zIh@aP)sL;qF>*za%A|SKBSui3!fjb^-h8}APc_;@`?B}Jm%fUTY?BT0>2DuYUwY)Z z@`-R9_Io)bmY%?yJNA+zc`n?20rRk)f9YQcpa(LI_hKDA1w9Pz-FeV6NbqC94}M-c z#FSP}evRcU|MShDr(r^LPhQUG``2fQ)GlA>JQjX6m~U-pRG-i)Q1zud9W+PIpdcd7 zB%mtF&MDt?)bv`-W0Ij|S_YwO9me4i9|UJ4`sV9(-Xtv~#cXNnxz`>`sj3ezd~~2z zRUZrEX=FB^IdM?rs*??EDrwr zcr>oT9TKXc(R?0n-%<-%yov`A+zJs9m6i2k&cl6_cO$(tEPC^8-+eK31^;DZXMd() zk%Wu?Uaq9@s`c}q-{W4j+>dZ<(f2Zc$040d}?{MBVuVwN8AO(tUd0 zp*Hd`oApU**V&56bF%NQ=RRDE9?uk(Bp>ZHSS#Hwl^?pLLP$B|hAu9?SXEhh_dYAM z6R7FwIY~%J2BxQ{S0jxN?0kjuhdup{{1OEg_>QJb4R@%>n)-djM+^U!CSG3rq((gs z;VC9P`HMQmS`S^9>`7#|QZwbI-dr%5s55=TEPm3ni+%pgDFR~WQWOZ_QhEULHqMEF zOKV4ez4NvoYpR+TuAJm0V?JR#$jXea>OsM>BnmTIp|IN$XYe1WvnGrTg z!*R_)BaHmgNZ+T1;Ym!CNy=%imv2m?U%szVNa-okbg7Hvj0y^lyjWVAr{Spdnk{s6 zbZGXg*mMXVz5d98u04EwFU={COM!wpXBNn!aK5~R%gK5l8GgsDP!_DvA&CdP_{|q< zWQ7z>gG=zO7`sAV7_z2jKR3+BYZ_Lk!(tpmt~uH!91hixzoH)X*qiX$a4D7^R~?pkxU|NC*) z6v!X9`um0MG_^L%E`2#vT^cAMAbH5g=fz$Fw_B~5>NJf<_Yz*zh%GMeQqzag^7i@O za0Rm*T;PzPgR!E($)_NEb}7T5vmQmGfu&UM*p`-Bh z9k;Z!UOj&L^tC}0NpSvbo))k|b03v^OAc2x#!S6DabZyDIbGj0=kSR}#i@09#%F<3 zf11wPLrfbc8XFsn&(3Zbs_yMI2#QR3I<--mC%!DP5_|Zx?p-J67^mLQpXhx$f)=BP zB(JS4w)!grmYyNW`29b}Z)c=2t}5d29OJ@-R9VsTAq)mgo?mSbZ>dhOd2SxmAL z^~vK*?6iW}tVO!MKi*reIZ%*=v}PP-;UxE8(k0Xg@M0jHX!{_wG~H{RlMN)%3j;o^ z9S$GG>co_}fiV8<;8gpKwbS}ti4V>fmoB3Z#Al?XRs7zRy3E#JC&oV1W!HKB&;ght zW=cBpL<~1YYpn!O56PpV_Q@%KyBd3^X~8Z_hQp%pvdzBh5LCp+>_6;`*ue$inZ4-K zI(gS%Zoj%odXEI$tjgFXt^?N}d?Qd7T)e*(Y(ChUyG{0!!-*t}pmQekLr?; zcT=lhnye&KrbiSP<7N=&nyclfOIz71(=tDPmApe;-Gg?d{^_YxTaPIjk@l7tOMa(7 znJeCb4&^bfuZeJ!awr-gebz`iVQKNPqCz#-`NQ#*E!UK;kMa=Tr8hR&nYiUHuPwZs zxf2-r>KP6D8IHu~=WLEZAbF3no3?~&Pa2Yx8I`-~#&=s%oP@*}F|;&72SpMC>>oBI z;Ipj^=WtvMTr~Z84E@o(RSx8>wanlbVUT&|nH+&xHeTVx8=JM0b3;EY#;rJxH!2P( zFx>q-7SJIaxm2|fE+l_*aJ%P5&>g8i-Unpld}zLl9*g`=g+eJ9|Aq_O#C(~ho?e50 ziYSdGmtGw%UC-#&D%oD-Ct)}nr#EDXNbzIeqSVzxExPirkDb=66m+)fD@RkGJV^mB zwvz{^AYoYig9SeRr3_iXl$ojjB7PY55{CHFT=iPed?K%{#MKFjr^41zCCpwZ8iKM( z38p)Yo3(3|`TcsvpFT>(3lhC8>&Q}0yjb>0^xFj2rcuX;bTJhw_5>k9p$2xhRlLXM znyi}IdKdex;Vbl2pDa5qhKPOrf+42-q7XAgM&rhsp+O)~Rb8Fq3X@K*Q&UqL?zEKm z?Bz!cE`c-565rs=5QCfa|Dcb*Co?8!Xw-WH-qU;DjvYO~pG#H=?vYesYojyLqyA-8zKS()U zXRD0Oai)QUK<6OX17%U2G}>J=LTss6FBUo`j#FJ`nA)BaS9t{me;CQP3Cq0?y-6!5 z(3i*B9Qb-3!W+r-?Gltc2C- z3+&i$HzhB`6IL^`^pla%ih;xcSMZR)1qfB+Rh}IwD>u1 zY;H!4$#deKW5x~6?PyPmc6_?LJ~N!#JW8yQ|2ZT48$VTLP0jgcDh3Q|;KhcNF<<@9 z8q(RVBQN1@?8^~La zzej=d8W|f$h$%L;ZchiC0ZA<=JZzGs>~=ZI&Jl~4KsUD)f_$BN4C++AFXjg8Hts0VQ`c8~g=Alo<- zpUqB4aTCS=Vo~hR^&@`+*4@xO{Yx4MPKme4lr|~laCuS!2pLTRAT>EEVB{k|Y-|HN zDv3_jZ|C*%tQ95`bGS?YVEE~+Da|GC&|Z8H z7%e@_Dj=wL(M*1H;E+(!Te!ylTBd$U@trRdyF#H3ha^CSgma0ixR%+IRKJ71=V6%?@kot8m^2Qs&?9F}@dFekD4rf6cmTfm6osyZFbJKA6Tz$yN9MhuVxSO;D#Q9H9zz-q$2v;=r_PgZX zE7F%{prq`}+MT?JDi?-`zy9rkNjRSK<|7dwBYA}vH?4H%N!_j)!d0G*MKEe16y&RG zF9>vinnRnv`h0S3dODl@8xZ$U=YH@I(PYHTCwPK(xd3-Fg)2{EKX>Zc#B3@@N>U$_jfZ!7)=~T2{^K=M<^uO?05L&Q$pY%2Sf@ zhG7x$N+N2_|ETKP=CWfX<4UbC^%0uik*6j)?hxhAJ~mg5+TRWYcD9|XK29jn(a_x4 zvib#pi8uC=9qfvga)OU8*If|XJwoAe%1v)UG)c1%0kiu-+-&c#GIN8}F z-unWqHFFxBDKrtxRd1bTwU#4xweoDqJ2x_PH%lLyz~zHBfH*+!lv7brNp(_*3g<*p z*g{{@$UCgc5;s*NlZSf7NJNmpdNnpV`5JAqtZ7+04J#h&*=k}8w&EaNkVgwRgD*88hHm%q6 z-`~p}O0T@~Zs5v}r;)xw8=9F=jT^)16Zd+~_!t_C==lsF<>%N2q)2Z0KH8PW7U0p zXLuFX?NRwr!?@_Yv#|M35JMFq=iT+V9aDG#2uXW^T~d@Z5M|jpIQBEcLSI6s8nm0y@j=niR-C`eJUyTJ`%8mT z$xX%Z%XGs1wJ)g&Q=S!_idpXMCs^57zOKIL!07lI&E+t}4+UO2S(p{5>#m)B=w7xl zp)O|@T%T9;>Epd34Qp$~R8SR8{{Aix5Jl}Rqyj1d#+RTJBHk{(7Mqcw1oADAfypem z$|!D6#X5PCQcyTHg+gkE^DYKBp)NAxJ6ri_2p&ZhW`pLUJ@l>y{bPx<;^BjsdLU-?zaE$@(#|_dE;;9I)jFb+YfENF9Za!W5~l1 z_iQ%mB+kETSo>Pg5#0#4#*Vh~A%KF^NW4n98gw`>MWC!;J9UZ}v7PJau@09T z58MY^SW;11HeR~!_kwio-HI2ctXya1-AgJn&DiHYheu>vSfUqSg=8>iFXT~CGj>;Cq3$YjO8pjh4$`JTuhKGX zX1gd=`izc}k_mz$5*s}{bjydtO{1fB48>*zY>Cms&IG@rM{~e-%;)az*N)kBNyQfU z`pYo7=eqK~P={2`n?y~cwJNO@Q}x+kZlWcYwu|QWLw4@-Dimr>l>u+=b8%&U7!{5) zjW71-R(Uvi!f}5@TPKl_bq_BzyoEZU@gK6axh__=SSZ>qizTz5PXk79zIj%u|G^la>K6p(*s!qXS~%9b1{DLA}-m6&apgi>>k)o(vn8 z_D^PbM6t(FvVR={UMLnpe4=Uo zHGfxPi{4T_isK@NIj?}wT9tL{OV=HA8pNos%dw^Uf4nCv=3*9~WOHnKP5ekb6WU>Z zZ=C%i8!D*iapljG{r5Yvv@ZPi(IT1rGfg*cLPhMHgM#aD4%5>!HkhvT023yTU4G&f z9OfF<0EBrhlftEUBI*zHcrfEg#(THI@$WRhpFQxt^WZ?PJs0j& z?7Xafu9ujG*wkH`q1`hS`$WC8FlkrdQuDV-(CLT34aMGPZXS~4U6)uX&oIbbooDZ= z@+$r!I|6~+iaEBq17p$7a?HlM>nS;d$yAs0-?tN$gY;0Q>Ks2lV$ufS?J&tdloY&e z%GG0n5Dn+Nxv*ExrREdC9J0pRuWM&7&CUt{DBD?jDgYc1L;KUl6_&nx?e^{4@lMk{ zRz+5HyF!Q_et7Zq`m+&|`U8{9S3W%Gr64u<{vd03l?yDYq*V!a9m zaq;&1T(~fz+>QwNW>>bOKHA!GbVWk}re@J&VRsj$7IJW7h++1fOU|$am(~RW3PKn) zVBDCfI5b63;<6Z&m35|O*C!y(F?IFyCwUR!ZHAW@V2i^Kuo=<6f53TJ;Y%xEQgg)n zQQ6v9>iyNhaIpy)NI-0q(U5M#5gOP%u>a6WUg-YS@~!pdS!U12`AwV*j1ajVG*!|n zE?f;rdhAUET$uOd1MLprDpM+BfLKx=Jvy4jh#S}r5%>$7sGByj=l-F}<(`6Lmh+!- zXXn9xZV`~t^M%L;b3~vwSqtU=%;vB$B_OJL}%#sS+x{+y-ldLKb zu%_zbrinTh;^<29pX^#ZvGZ$)(#m3Y((py_{|jvK^7>A4cktV{(;^~Tq7Gw!Y+Y}G z5|#-eBmsGdx-B8_tHSGEUfFhQvUs;ef_Z1S#ppr+d`~pH3d{#6a-7W8S%AgTN$V*d zxAqL4`)F<%Fi%Dr1UHZSl+mcih|51~X6bV$KotKVOa#eyT(7VN+)*9^Db94~d9mGS zl!+wk%}L?4c&8+UHGqPKbw8-$2gVuwz3EH&9-A&jd3pmVznoh%zY&UwNE+^96Z8AMMb4( zRm{yQl^0_d(0wQB`}5$Fff8dSS`!BWcW48!CZz?s56yo92=?tW9{Kr}8mdWlF%t${ z+~`Ak@$UV+IWl;Uco79*{lFWxuz%cLpZ}+BzW9X;HwOj=iaoY1DEC^^9Fg=Wc7t2I zsBOCrlALfvf0*MR*zp)ORjUq0y&0Y_JQ+W^MlcJlU+?9{x`wyaN9vPj9q`+<(|4NWqPCz_eDxltwP@|ldf z$=&D10Xp6zoQuu0z=dS|5icA3M)WCiBAp}v=|i^Nuu@UQ!g#APjE{P)YqZv^DL+~- z*(okGlbXqvWv;p0b_BAUy{TRv8RiL&>1|WVW*?V;d_3Bc9=Wn=oA8L0|8F_BOa&Gq zG5jzTFEsQuBFn$Fkn_)IKpPr3Ypw3HXzeGMWXif-L3;F@iT}}*&QP8=CqFokK39z@ z(YSr*&fuS5$Q=R$68ePI+!6?S8Hmr%Jf@Q!COgz~Z@U^A#=gtA_*YMmABAM! zV(h&5w_)@ihF6Llj?%-cP`$idNubAn2xg9way(`5tODk=Ce31>1Y`=m#kmEbd=Kay%j4Qm6l3GWOzD*atvhN>r1Pq%fz|7D*P;6 zLgA)=)%!O2gh<*atZrkIMS?+2flZwjq!vHp?KaI+gp+3J&u8o}eeyMq^ z>$z(2AD7wr`CyRx&71#5QhwM#Bm!1n0ZOPg)oTbZQ&^};%xNlD$6x;qgkrPhdGT|m zKcEpXxz4Z04PCkJJ2xQ1WTg8k8E$H1bPZ4+DWc7sLJ!C9U%!e>$p0-u%exV5V*TiC zcYKTYf!$!d@XO-g*^S5nsLP^aV89>axm7@tXTE4cUSKxk2GeW?=nr$~@wv!vNa;`% zPj0VWN>NzvP;;GZNbn=U=#;+J&XoZ0j{D9x|Ff5tFFo2{U}Sv|jH8YOF3zaR&?}k{ zJ#^#@D)+VB7Y)tp%$-V-diNkt_c-Y>@u9)I=i)F&JV@*ErLnjvOcTq`Z|h${U?N6F zen5{#a*~P$nW_QSVK-eM8Pb5)dV2y4DK#+>ZCe& zTtwybmoGrp-WW{^deExp=>FTf^k$(_)L6Cu#0fM7O>%mAC=z74 z$o~?=dg`xJ2O?bx+a!M?JP+uL0;evSFV5z{i$*&yV-tm#aZQY*LFx9^x(Vk682mW+ z+C1ZI;JS=`c;#Du6I1O1?}F2zJ;04k*)WgUB!nUP_2UsvXm z(}~~tzXO7i42DYP_@ygOt>Q#Sj_zeZfBt+~R#_Qy=0vks(YwUVVYrN>NK8OPG~hq%Kp6>ET&BJbc-@!2LFBzQ z2y?{$fA4iycrSUmJB-B2zWa*>#`E2??Yi~lY1L>_3?EpOt%xTy4pOGvnnBY>3* zwHT}puP$^LmmaowFGy?8c;S9LAphD$dLsyc{C} zFa13eoDd{D!}O^G{vmw_3BePObN>HC>$}0_m|hPaGCE$$^p2@y09&dTMjHoT-3fRJ z(AW>;h9OYAVtz~GQ`cIQA+7>HGT!r31P)`{ium2URc@rKWt7B6gf?Y(d#>3%CqjBvUvrJ0Oa;la^w1bF~uqZ~zu5ixnh5M(DK~crgT|y)ENdi6eOCkR<&_EN?DEHRbsl(c zWOD;a9b9f}(czaz*nPG4@zS{7IyN$0vK$SUF^lOwdioZ)z<8ElHju+-x6+ z1gIX!Yk%gJLuzv+6(elLdexuO)6;YQcbd$}m+sSL)~!jc#Sf_AaQw;Qg%U#mpI7yB zP|=;cclT~`!Ck+3Y2eVCbnF z%fd#Ll+OYK!vPYZ`TUX4mZ2_{cA^#9TAVR%*$S`E%U%sU>3*tuK#QBdE=&rUs`fZm7hI-K3SP? zR(RJI`<7tuy0;F0K;iA3n-qAf^&3;ie-u1Z{8{enju&iz+j%)fV03HvIju`+IYb&ZZyI5IRYK|N;vDSK`{bkm5Y2rh`yJ^Mm zjGo2FRe%CkT_O;L9bKN=OP4bcEllws!y(#Vm(m4ZoVzxkqsZvVySUtKidkH=wVmtC zx^@2tSCY^EewZg%^3q$J*+z>9V&)ZoZS$@L!4xMQ5@KSJwDDWJ!3dbs(0)6e zk1n~@^Pb)8@q^f@V_2}@=NrU6cI&kr{J_hVc(-{=_YU0%M{U7(f}2DH`rNU!o#Cf- zS_Y<+MEVIMge+g%Pxo}QlWOWYgt`H^U}7PEO0TSyd)B~h_DLh{0BA0+Os~Z5b*R>Y z$w6@j&w1MJmAj8NB$y~CMLE9qKPLFY<;~O1;o3+}^VST(|Btixj%s@Qq6Z%ch$4ao zQK}6K2q?XSB6dIp=|!bV?|~rA0xAM3(mP6%UIT;xHc)yG5JHh&0tlgnHs|B}s=PJ7 zS!-tgdCNx$`P|%l?m7GHy^s7V+~`x&XYTnl<@CcW?BR_3hBpAH^wp^&$G!T2J!*V4rQs#Waw|5FXbak!)uY%}M_=pcEj(U8v@cGri;9{$o<6>eO$tp3t?=A<)Ssf{cZGO4; z;k=yM5-J*zXUziql+l(Be{c;pOAkFy@*XN)>01;Kp~$fAJP z`SZw)CjC_?5GoIs4KnjL4oSOM1+ykN)!9U_P&G0)`R5~6dqmlm6Nn0 zv$BpOHz3IuK5w<&a&vsZN=JKr3fR-Y`Vr2|x~e$ceJOyAr%`UzD!8^ezJzXxe4PLu z1IMn135fQoMu{mKxRXRDUD<5#udqc>H8#&?COyh5$7dK;^vbyO!4!e@r9Rt{O?<@$ z4|4fhb>)3!dudz7Z1!oItwH|hmwm%9r!r&^W;xrn2(eNNur^`Y;l}8!YfZY&x-V7V zZN7f*`~u#^QVVRcb)`^6DO=)B13ZbztD%xJl(-;X9l}%cR0gU@-$sw zv~H@o$ad3y){(j9nRw(RlU&57<* zEK(7Ou%Rz5^!6==RMvXO&Yf>yeD0S49TchCEP?Hq~BbCma8tSP1hQAeDs&nlpl`;pHvm=n`~SNWDczs8Pn9!v7jcE;vv6pwVmw9 z6f$o*JlP3M#1<^dcHW(F&jIj?gC4~hgEFm9K|=u~5Ape!94UN$3G$CfM~Aha)oRVe z0pZ}?v4?-PQB5qC#lRM}TzWzMxxkqMx3Z2t!`(8J)U`7EcNzNFj_J;k3)3f~?H=tY zss8%ajheyoB0^9XzB1$RKJGF_@|~BQ&A1H@N$lLVU#H3`)!SfV5}&|#*Ma6C!XTZA zadbg^QvOYvy}fl2YIAMtr^Np(?{->bbTj1BMT8Xq8hK=7dbTTd3Q=3LHtifjW*O|? zzdwAI0Mvack%HdH7`U*{7l4~KETSJoiuut-4Er@jPgpg+T+7z8rF4dcd&`PoGv25Q zU^gqrS5|1)VrYIWXj+5%`r~$Pkv>cB4T5b&VS^fwUBE2EW!`h{`^ghy<)-zKC%Ez3 zbas|n7JEV_ItOUtH6-g%yl6<%a}5MNMc=*AAW={Ulx3Vnvolj1Yo>Zg3YE1|QeI9L z-2@xv$XT1u$wyE)iLY}y?bSz*9Ww!Dr$aYjx*^;A&sVZgQz$K1_VJiIXHde;Ze-#2 zs&R5z;cw3U$>`z`n6xz|u6|3s+;ol_nHZg+mHWxmVSW3(TKS!u%Y#9C+1Ux_{4Hhp z!hT?@-R`pdUT9>=?K){h6iN|vZiTWiY4#``m>G6w;y+q5=6P+dFNwuezdUqIoahuh zNYxYX=UZi4JU};Dfj3`RfN?WwPdz5u(vo$o2a{PkMaNR^IamXlA56<|Abe(X5mWIU z2H6YF<9vq;C#<24tY5A1rrKr+%dZ1%5uh^sdIk9*kpVJO0wu zfrdnn!Nl<#`%mN#re?F*gvqT@B$CE}%gLpSh&%4@C;(?(mj(bo6mgmI|Ob`&DW zSFX2)d^yPXBBvzG8aRLnZZGqUo!n$sqG8|hVg&exqAd8r2j1%q(lZ6R2}yggzJ`Sl zl$@{MF_S$ZE{<2v!6)BIEc5~-ZDrlIV*Lct!d{UBW(&x~GCrb6=`8*18nw<}-fb?v z|H`6~ZD7qy60-^2*~WI|A(X>IkV{zDe*6-bI?XR%qfoz84TxMa#TP62;EuKt=T7ybO|XQfTnjam(aDd z(^1)CNn-ni@Gd{Uvev?pwl2qe>O3XhD$e1FpDAB$*ss%MSoon_Bc`Y>^G;@;*QSSB zNO{sC)Yg$X~CLM$jN^baT78MjB+b4?#hlKFJAn4sQ`x9BOKyxHQo?X1G@^kQFtT0NqLv+6>B71P(vOHTW;DZTcB5i+5Y#JfQWwHo44K6^ zhXODqA@3bUMy&pgYeV@>ML|t>LL}X~E%g>MJDHGiThS93=6g9ftUSx1JtYanas3j- zF_Su*YT1{xI#Uq_&4%W+D~}(6s$1hEW8!2OT|c3lY_mVRVxv@2Z`*U|QjWOe%u@_2 zJOMd*d%&+3cr-n3qcJWXBHmu>3wVsPHiuv3y*cgjQ(|35k%JX>&dXpEo=I#hsa!T&)Jly zpsxOQhffRhtTVLe)_+!W*TPh8alic(DG=JDOj_Pw{nb^iz`8UoJ%Lc!a7IZ2kNOD& zI#Y1IuGRPoi{5=3AszjBZ*S=xf4DNo z8OgvE_!1NPU58mB15u)!XxrFWor&_77isgTI%LMtA?h?_Y+Lrz*ZirowMBwqHyyMr z!wfx3>RUtY93F zsYpzA1Im{ox;Y@o`PxBBCBP(0ex>$#qFc1TFXw@`7r;D;6-8~aUU0#}wYIj>=vAcg z5@m5)>PXXW>U2=1Uodb7&VO|CJCkoD4ENkF5C)0PJV&Ewuea`;1{vZAhGJkh9HOZ+ z(`)x_pAaHDjAwl?u781T(+!h0u+Tt*P6@IhmTJ$aG^y0y{ntGKIf_1}a1YP7ZCStn zN3P(d!!QXKT>7m=3ieJu+jEThLgh(XPs;d7H&P)UIIz{Fn+-A2wdvXA7Q8I07it?C z4lt(aekhvEX4{EaaGN`i_zRYI*2E9|1i+`+|9-)PJ3ZhtvG2Af1{812|6~+pms75( z$gexiuQy-j=1$DU#RoOc>Wj`VYVx*#DGlFsjH;bCURnRCTv-L zJxxCu?}dkcLU|UyvLY!rH`ig{DQgX21OyW^J~{?(}{VBz@MvRlWqAJEZ)Ho6uMug3rM^FUWUO zbPUPHuR}XW2e%sttFOU^EN|s~@bTj0s$|Q1H(rvxR;@4lVJ7SucQrMS3vJ z6)B=NK%GA^)M|QXH~F{^sMet}6*uY1GvW8`|3z*+=B$hAx|W8~D~jkG+A0nN$8vHj1e`-j#bU8xdwU(afZLW4dBoRLP6bY zzgYL5^^MS9U$#mS?$}j`LJvCnme4HA$X>bUl$ z5SZhD04!-=qJf>V2?5U-&UEtTlO6kR+%c;y?l#;uZEdY{RR?deL&)Np#}p`tK`hwkG^ElJO@Dja1bv8!ytRVLUz zxXax<#$)ytjB|34KQS^Muxw?}F$J6z)8pU|{i<(G35xYk1t=64WUZ@Qh{ByR`Tm9{ z*$bo*#$f2s@l&tJj&2c6wO-aDojW$4Y2V5qKo-6R-Zfj{@Lb4nq&woe{^UUrUi+C4 zDl^O08s;CWr9Djw<0JJ^qyulkSwHi`lw7(A4|LDG>3R(y0DP~jbCLift&B9etRu#T zyFSJ^cW8Gk(K9mWd`O>cgl>&zdK}!C{Wj-H`yVk3eP)su2}0`5#5=Kuo+~Evt4|qN zYrxXcwj6(#0w9AG?`LV5(*aUv49oS(mwzzKxBA{8V4cQ~B6;Y=ix&%AzG*Dr*ZK8J z+nzWuB?WLuwmj((oyuZmZeq5(q+l49ektHhPR+Hb>92eCw2VGxiawO6>_IN%0$>z! zDa#c=MfWn6SxOJTRU3j&qsZV?3hQ=RXvvJ^LLgD(@*v-u$Mv%Ocn?+;GyA$>B9i^S zhbc$wQmMhV65*cdTMj*k0TrWM1@!-s>j!{u8+(V$OBr{%5$qwN|Ag{TUadfI2%qLPW8?Qb3N4HE z32?BK@3>n}BnRm}dOVTA`rUk3kCc5+&sx~D?vSFu?jy9x-qQZlW)9!((pvmiGv}Ul%EwPVD%q5X&FW>NNKBXlSUc zdl9*(oM@w#gf|pSGm9hT)%!kus-2!Ud7Kj2+EiKujKo@N4AE2=lOo50f%iSk0~G3WoT&?@IgK4?Ir*kO`{+uEaeFGEPyDKIe%>Hf~YJ4ZdoX zT9CK`nM!@5h+XQyVihZ1!V(Lqr`uqFcm`2a#xg?pF$pb4OnRWT1ZBAB9ipgJS0s|2 z*FuEuj8q(({7Q{9jSS8t5@cM7&MhlJ(yUrV9*2)#L<{H)3DJ7QC@CpvZ${@BRqr0} ztEh06%Ph-c>Eu@yJli5~Xx^%j*Q@l-eiEM@2NzW98VH;E_IubS9BI0#5O*1Tb`d#t z@8kkCeXYL2tKW=6kU8kVF^+Yg22$$Z%f^X&)y@%IYFE zW&KdjMqMM(Jd2VKLC8X9D96sgU|gd|T3Nf)Lz!dcFxCe?Vqy zd3QYq)%*IiT5|XbSvLOX*NYS>jEwx?j~^G)8^vu>q8(n8{Bw~2*t#GTXK}S1jg`Ra z)YY|&6$b9}$o(7FTSxE4$$7|F3TOP9B>F4ZRjPQ~Nvr6zQJY5jLR8rS{9VjxAJqWer?zBYw9WuzUNICMHGMaah8x*hHA>4Q+n~{A=EZ>XbH17P7R)AnU z$eqTkaV4gtVs#0ASFJ{qpsu?RLVg;*(&{vRjO!CGI-B0Mplvu6rnsTEC zs6)AT{HTOPXW8Y6QK`SkYo#zkpc!#9YX5uo=v@((WVUpY)mE0|FQ^8yciC%mX7f2+ zZj=SM9fw%L05g#M^;p!$=7onDps#jhXd8v(?iy zdUGC}LTzrWcMR%aZ5i7vbM!You15J<@>3CjtQYYLhbe$Je-&Ct5`Ki{op_xUoV`2n zv6NY?BbRoJedQr&X1t1wvMnO$sQ@_hyI5JFp{oL=hDlAM=I7Aqv}he zcVH%!PKS>EgsYbyDX^DfBwX4|sc?j9&_iUPcIB3Bf*SIwm6cUg_3+6mI;_(fhTT%r%knqGaMjy43|cHt#6tT64Hh<&vbr zvKfm2<8MBkE|ytoaO>7Ro+dk__o}=t2Ws_>7o}|9+Rv78;X4-LV$%`SYw9o4AQg%* z7Fkvj!w@NEUHCagXuXq))}i!U-utwXwBQFiu2j%*5m3!Ax2i8qO@AUGn*`xza#D3> z%{WKDC)Z&MK34{^5v*p6iWul@x9pX}NXw{fgEBb>#o<-x8Qh4K(Qbe)BbN7vO^F?o zRvSQWg0*3S;(YCP&d|o)!2t-dZb2S4y&Hn+$?KtKa(8pHu~{%S1aV4hG{|p0)Kn%F z4Sx6zv?Nl8IOx{hhF)LR(L>$3_4?uL$L&I3bI~l#X08=6B1zpBhyLIMeKBpj0N(~+ zK0U&^IFDZdpjJKv>mfmum>kZ}Cy}{$Y-s0t$Ux1L-z<#smz*0Qx&N5&H zB&$MGCJmi^9>0xbQ$?JR%zsYat$-9!QB?SPeAChJX`{%0HqMQp{thc zU#^N+3U^Gyx}ZPS0rl6IGU+G?^O7%IxX`nDJf~FgK$EoBnAtPWqLlaV!<)8-jwJw# zR(mDQ{%5lDYqg4#V4*NF{Aae#LW5a7`|4hY2_oIV;K^2rc7&HEljoip-{b{mP9 z&J&5#tJX&mO+I*P-nnxXyoP|veaH{Q-Zi?mIG*$8&yz-Ay4?vTnOSdV8BT&wc>}6d zS^TE~&ru}xb)M{q5EQlFzkj`2e&Yy4&H`yw1eifOP(g=;FNu7);V9@62eZ;Yu?iIE zst>G;Uf)d5k~-tx&TylkyR@RBB4XwRU)HOY`O&BuRhgd`wM!h5oH_ZQ5*BbqL*HJ{ zLAn&Nf!9aHl+Au(@H1h$(Q*zkrbuMz1RyAbp~*jl9JnvkKUB)p1fin;-UWM*8t_7l zRE`i*0>G=vMYj_!mQ!qj?FSAXJO!0XUZ4lG z6T!Fb0=9mbZ`-&V7S5{@pADw%=+UD$nmj;IA>;y}EFDN0zQK1 zq6_37{NXQnU_H?}y0WLl(FC~Src{jS7)u3b zAjq|(Yi27N^Z?+9XnIUJ7{7~^#SZ`$_6lrYIOaIYB`Sd{cE914Wu$>t{P`t$ICv+< zdS{P5?s%!#r?{^(EaJ5GU^Rj9P1L2~*ZRM?0Iv=|-lTud-My=UJCn5nlH=!qX-JMi z0{u66ps$~Jdr2|=9ZfkDp%KDn zfkZN!L&pS(?R_$=8BCZm8LSHUwPtZH-475-AxFz6F3;tAph-PvWFBHJI~vNINoNW@ zX~!#rt8*V!<<|=yLN~mJ>4Ea>uN$)4z`xB)2yFP$*=oGWq|}HzHXc_W>=eOD0HbyXhg~zMwn! zfZpkSrLs8jIFK>Ku8*~*1ob?euWtd!C{Qo5u@Pt0B~-H5Z5f~lBtsn&q-hcstRj`x zehEbNb8GXBwIJiI&kcA?0*>S>$a<372OYeBsX5kwIW-5_vzVK`nq^tRwF=*!h3k#1 znd`LV-F#@O@1<#KJc~-oRa%{Np%oS!t&H zo|~*Ccjj_0$OR7p8oZ-GHAdr1Svekrfx;;y@Mr z`7xsT{NMiQ7lqS<8&S{Ov*q;2=)&D?7ALRqAMm-C?+-bVu8?i!^<}PcT$HI9*OB4B}?nhJfZ3)7sC`c}FFD=+F~6N4%Ovq1%5Ie(DDTrdZY!Rfl%;8{3^ z-V}7yZnxZAp|QTr>9b-$($W`+Oz$_;(cwksMvF0?9UU5S>ePwoETpFNW{!$Or=B9$ z+wu|+`jOq|d)7Y|jz0bCJ^BB>=Qw-H2i%|bUD~;Grx1&}=*15e7UAK(-h4D7|D>ER z1__kkXXM0=l(>GRWev{}uJ@o3c_jxTHcOKcUzBO*5{E*80L9}J4^5(=~FxKN7wsGFn~I4*?jb>e%_bq zpJjmB!#D@$)M(#e(aNms)~fmlJ8bU?Ovt+dVOq+G`$n$|Rc2FmdpFD%E|8@bFi{SR{liQryYIux6L=a*rkDmTbXOMr1QL|lYVSb>X@Q)CEv3h_1$H#Ni z*qNF)JlBnvX9oalUMh8xqeI~;A!NbW+%#AC!q(u^@ucjsG zdZs=ZcSZ1ij`}E`fgQp3@U~A5S<#U7ESmHyfFS|6hn4*)r?y*{zi(rbX}VtlJ{fA` zQ6td`AQsMT1V8EV*AWj;H;LPru3(IUoNdmsF16q@=|UGSNY=)k)Y*x_x3zr(41E}) z>Knj9QUrbNe~KL}XQ4)WF7&PO@$zzTB{ec+wlzEr-ktXMFf6}><%pAPx7zd>2z z5EIi@J8Z12b(o&Ra|C_ry0bPazqw~UPlWM{SVlwNyUR=^z_e%jED-+bbtN3w%zI0Q zUhD1XJ&KwlJj-Kx*XR8jkO9bLdYP@1IqSb8$1Tdy1dQm4{X3!hwpDYe`_F{Rq4FKt3-0|ac1;kALhfun`OaKJ;!xT^RU5I zE3u>B-x)VXOO6T$6C=9%qL1`&Jz)vr3mmNOMblIv)g6o zGns`|>B!Qze0g+piUf)Q)|do&4CG?mbAY*Bxpe7L?+i#iFM2s#2Z;-!m!%Te%SJ?2 zc#i|VvUGzV%LhXy-yqf$brgea16dmfd#aQo?B-9VG>l`4Vt}Kn+-Xq(Y~74YLE;mF z^8v4zLVf>+DUh3+n=UP4`6(5<$6v0l*s9pKw}*!xY>vW%l5^cv#OW`x5dR*Kg)s7g zyX$}V9L$vk9N+BnuY!5Ye-4ZMo0Uj9CXY>(nJPUdnI>rEi@D;4Xh#}i_>hFtbiQ8R z9pR*vL9x^VLXH(^y3JG1b`Jtq)##F8X0UFl3yBx_&Vnmc&D-J_>SARH#RExp%_I+q zSCoeyKE3h1#}kF4%yx6~n#>V*B@SK_P`kv|7&#oKSg_XyAEkRjCHfSfM#kCRZRGEa zIxvfd3(-Ou2KuWE(?d0SIgms0$6G~=(L*p_&eUml^-B43nm}udKys_U?dX4fV;S*! zsp#D0^k1JKcyIzusDM5%3{_@{N$AQj|HlTr1X~gmx95K-<2p<&#kT|)V?gf+Q?a4l zN7~ysv@@vT8rh%2_0kq8|BoA@KnoD>J$U$CQj`*lDpk)eyps@!*w>`?}VqWc>G& z{QvZUOVE;|y?}|52Na!Fs!%>n6&s+5f!of>BNA$vl^^1Lsv!kYQi+qZc9Ma?;I{u* zcNe_A7Q%aIvq4@he?wRCb*cPWBgebeGl}Fyprj&{DqVz=LM<+7&JJ|tmWnAgVf8)X6jSFHOX)`V zasvOs0wI;WJj=l&K^qIM&qi@gZ@d;=7>h901PwUh$7N(>Y-jaLon9N@(8IKSkJX;u z8fI;}I|Z^mV@TC5{R2F_I2VTZ!b(fytG1&IgRO$`uS%3?Rw_ndWy-#8PddKzCUKRk-GkgL2%dXo>mVmt;j#?6Y1Hd`T=r#E|@vm zc4R~#Fb}V0mK6$PW$X2^n)`YW!B#rM%&RrI#o`kU0YBri9UrntEHDE}l=2;4=-Ho-52Ekk>-DJJ+a-Bnza?V_Izy4?@J z2WoNtx2M&r%mt4eInU)jbuPQx^qwU(dfU6+XHI~Ql+lteJ=Vz7IV8?;^M8>5`CxO@ zpyY@tE%=Z9c_>^7y2*)KO`_=!-#kh!^=_iO(2}zw^P>x6vDyV)h=$t`(V{j8Elyv2 zx|3xHAmOu*lB663c?xJmnmi%mNteZa`SRtU@G>GjNTB^>j@#RGlFC($e1hHMf_FJL z5SeSEl3!SN!R=9-3?n>h9z3A!aN|9CVWKYj^gYld=o(JxH6sWU=qANA5@whvZnr+D zpKk8kmsO-DmqLQPRl{G zN1>4-xR*6#E1>m{&)z*vj^Z)ritHXVC(<5C+1qt=BmXvI$ObT2ow^c$1m;iIZ`qbQ zARm)_l81M;irw~GqLTkh=GVZqjK3a6xZaUq7N+f zi;XcW63{6*CKQn1wv~{)HbF>bmNJxr!@nY+PdMiBNfiPeoi{|JsOuNnV0376= zFZi>p`g!|a=7zKXPPkOn{4BYKFZ(#nD0h^f!C~eWYM?#mfmT~Kt>|J%Y@W%@KQLeC!*$>3SQh+xCdvi zDDMc(lZl`EZjr+UgoIk&D&Uix2L}iF+r_P4?cDNywE%y&p?c1{WM-B{MWC7$b{5~SFM+v|{Ahr4(Hy}G5?-lznyVA$LH8rYRD5&c49EPvG%TBr$Qp2Db1cgjZm>@T^(X7%*`E{}yGXDj10ZP!! zjAmWN7cG33VdE`V4>SE0s+jdfDDQWBK%rIgRzP3saP`HM7=|(BT}aFPAwa_pfNp$)kd%OQ z<(!j)bx zTwBoud<>Ig~#psYm0z9v`;0o zg#C{vK<*_bT?(?o#g0N&d}5Den?4c#E&vD zPKXX7?0~Ts4awQ!d(4}=zDq;Y zjLv7KKzb8!lG!|7-`~^J5NIuLUcVlA1M8!6``x90yGh1+e;=2M7t&`1aSq~^()@5I zY>DlJ112(me-0+{)lo-@+lC^A)xkvH2Be$V+JEOPmZr87*s{i;7o#<`Zsa5YVR;Bz zKJ=jpLc8S;G)0*smI+2hKVBcZOtDuT*Gb(;o+c9RjRBcB*b8p5ulB0=>n)S&z2mpSR219P^W@=bYDN(7@UXD7VZ3qC`v8 z=41v1Haz3EbK2uhkcbC#bvSc3GkZjA>va*zV}GERX9bAqCjBetPmWyeDw&;cVR z4xDs|OIt1Y#_dHudQZL__a&PMaoboB`!KnAAX29Hfc|5wq#h zx;u+dJ`k$H{)>-)N(rwad?iZx2i2-mdZvxB{Ez7v-waj1_m}$Vs@dV|8C`0^V0OHNE05w|?>QGy((u-2WCFR=^@^ww0SvCxbaYSBbess6qxTRU>^WQMM%C`BimqW1VNNcEO^iwU)F2^ zlqH8+e#}85+*qRjjU^rw`}&vX`x3>kn7aWHVi;s=A{&P5pwfQXxBx&|Jkj>xU$&mY zT?he8Q>4o?Tb7KT4K~O5{L_c%sgE3fm1#)pTPbnqPYT{|aF^6w=rFCPk|Tf_I};CO zwogMNt;owm?Ch4^wQ%geBPlY5=n{n(4<;|9d3$51+3s?J)yGdslROJyVaJ6R zyw7c01Ny5no;{Vt0Kz~Sy8*aIUbLlohV(aHAMUJy()$b|QocZ9vso(20M0o=G7*`F zE95%7^?)d5D8+Erk;7Y_Ip+>+lgu)a{~QPnr1}U+!b5GBA82YxSncctO?FWwp^BO#9b{Y+bK3Nt5Z_PUSW~e=l2GI7Twrkd&n;IdEu@%#@QGlUf}#T?0)89zMR>z%2G^Pg9qMhJXbL{UAIsgiLly z$)8)XIIJ-h9m77k@;dfp2_JqL56+BbKo5ojPa(-o(&Uf7JA&*~j#=b~# z(P)?S{=x{@X%34E6OvvQizkjyIdF72U8ro``XY|Vn6Nd zhFV`FuT6t{RxmWX+e}(1G0}^s^Bfe@T#4>`4-7Y(HP8O$0?0+#PdCv?%9({X_d>_a zXbl(cAsFw0nUp?D>@~#)kt0*`2bpo9{S(r)Ju}iZs~haoYy+TwA0J) zrYnbwSIRw8C3akkoq}3b)4&dd)D01SKtq)vi^G|bm z+Fh1w3B|{FJw4?hFZPj~#+1kzwdLAdd_nx}!P8KXt^CMuf50BwJsxIk>Z2?BJa4kr ziqD1e@m)|ppB}mY+nLHVR`rKJll+98Y^NZanXr+YtFyXTY%upzSQ8nxQ!o6`g6Kz_ zu12?DO==Gi7M)c|?Q+K3sK8_X)slipmLCmN)- zGRRDGnT(SHhtgsUu2=&&NNAtz^Nab&=)qBhjk-%-Ki_w9Co7|P1TlWpB2>s0=j>)X zMXr*|j|wHvS7!NlqSuTMkX=kt^3Rs=p^s>Admu+hMety_{+EtHE;Dg;ip3dpU3ztS z)(ftsVL4wBFV0`DmcmLyDt&O3Br-K9&@)}rQ1j9o9i3gh>aw5D1s$s*1BlNIOJBmcm3F{07uo8TG6U7(aa zi+inDv5c7BDz#a16>!->=D8sE6@ zvTYhFmWMxGeiSgmUvs>%B#Kh1U@j6azBjzq5D`-@80m2&eYHfNN(I(o{@WReT(@~s zf=wI7!DgyPC1_g@u`FX|w8Te1+Qk)lyZ2;$?Ld6g)(~||R#v=YP(PoYOkVz)b@g;v zZtMK6{HXec;^r)N$udcCG3g3NXE>3oxD*$(oVD1!z*z3CLmFcFj?Ok2_;YnOLXIx_ zz55(-v5D3DSAxzv8)~9ZasF9TWXfyp!>ZZahnR}oT5L6IwQ?O@Y%&b{C*c6xUs{Qg zmd5R#1zo4V=ZOR5m*k+6g_!9O7xiroaxJM3z=KcoZSpb!VuYDC6=hs0R;W# z$ubvWnH3Tfa_IyX!dvy5pG!Cy&KHfj`%hyu_3WSi3|{TM`)g$&08u=A|6S5P=}6^_ z_|ZdIrqoL=x>}OrE+(VnuyaHfOIs=xWl*p0Y z*Dw=&!&1XfI_j^@Wt@LwZ{-JGUmuH4*e+^+z~7savT0j#&foEo?AX(_@u3=Pir+TZ z_dZ+PJi=r9ebcZ_XWNDVS)4$e*SfG-!&~Sc62B$uxswW&#!CsMps>f;2MR+PJb2Qp zc`C@%yN89yO)5Lo-s)%s5xOC(c6Db5yR@pKX88n`McQn%3ht?g?WljFO5#j!r}lUK zt_X+*+I- zz6Uf%0#}QP3tR_a`X>ozP+cRR<~Kdb7VW%5%L6Zu%U{dpG#hXsib?6N)`ai{ykPrs zhQkKmKZ?koF`P%isK(C@>&R;Olu+o*c!M?e<;Q>jT6r~W2>5d)CB0V?&!g6xm&U5etkgWPBD zdXGQhSLzbt;k3cCH$WzBX7w2`S61ZWfZ0H8;a89$D6rGB_oq%OD-bj}kM~ULwRF8t zEEifL_jE>i7iCjaiisu1VG#vfOgmr_n>eftg%}8LoE?@*{~G#&hUO?L)*x(&ECJL2 zIZ4oKOkc_h%b!>9v2*{I`{~lB2NyBA5;OaiMcoO`^yo8 z80=ZcU*Buchi{>_eoLQw9*y2ZY!#gKaBhDKuW%J!VJSyp2gXu@e>2$1;WKI4^gO)5 zbX4eOVX%Bp)_I`yEnh&25NbY$12%YVhm)$YQ;Xl9J|V=|3L+2i@Q@9vhz|Zmj3^L68!hno{5-c4%nobnU!~ldpcp7%Ha@q^^ zk5TN~WEjm^(;nOKx}$Aw6cgw9`vYP^dRSnM2vsjQg)#2shSIuk?68)q@cyik)i}}< zJ9wd3wr}HnF%iS9)g2kLedn)7!7}Yfz7Nm-dujh&z9avBVRBIH?@Roje+2nBkl(?| zjqt!PnS#_56nE3B{$)ph)T`CkQFp^B0*4GF(VV_8Tw>|CNL!vFtqKz5bL{3e-x)Dj zhBW}0)Cmg?Y&L@Wr3Huy><0M8u!bwkqte!ZhS52ek%Q{7_xnj^MIk$Y^WQ%yjcTsU z>gtQ+lUCi6}Cx=U4f~8&VA=I^z=Qto2u{O_~ zQ9RPqTWG1-%xxI@W;X`9RcZ!a>(0$5p8z~lYo@pgGGe75obRqf_t%C5dua+h+RvN9 z$^DM(NEzHYg}77A0N7%%B!G7=#(lE93@fH{CrL zx~(xH#R-O?UAN#$mM&!%wHPY84pm<+sq(hw6x3G^x0m-kf4Uu+#*QAvK?aTmNHa?A zgo;`J_swE)!@!U1(zqN}7M9^6X|zw;>@iJ`b}v=ZuQExA=>@==lfZQ@7=+ZO81F9w z@AFhMxAY5f7i8=et0h!W7|V{GvThw7Rr{o6$9FR^p|BYZ<##okm&Dg~`9H+?-XYt! zO}{9|48;xC;*FXbSv-QAG^4v7oV{*)1#Wd&{XPQe6h$&C?rLo3_zrB>;AI&7U@h~b zEikcK6@8}vxqk2oUThCb?HwPH9a%^f=(i)K6TJP zcTCdPQw0SutobzPCRx{iobj?ZNtqF(K;AZ%!Q!INk$*pBR1#etTrq~!U+U|tZ53)* zD3Q!YQ54A!aVgU;8WP`A(f?aDq0noI)#s*P^v0(M8+YBxK$77s!;13odV?g^MG-w? zq&AxB(GoO`)Msux+zWT4^<_+em~0`RVR_k}5l2lZg-=kv`XLn%QnKhb`{$qsi;@2& z8aho)zlfVn8%1_UM)W(VL`DN*x+Gt4rA+=T{rv-;??yylfv>i!&4Bjn+M^?0FV+b~ABKKLW`{a@d z0_WHp{O>3Klv{d8xnOpMQ z_Oa1&?V<~Pcm_kh_KnGMQy0?p#$d9qK>pxy)x{%xP}oR`i%kZF0MNBIuR1udT~Rv$ zn!<6Ejz(4L9bWif3!>FY96|EpG$>`(Wzp*=ERw7zI4D-V@Dezal z96OSgL9V^V`73+T9uEtVitTm_#^$vM=1cWG@T;ZmEO3cGMQ}jXzjWdxhSLJ$rjU+hgU-YO{UER#*mFN%FLFjZ>Ke znz)tA+wPkNA736dr%u;o%UeabT~J&KlZtzt&H}Ze1cCe}Z&M+^A8$-U-oXKctFszh zdvq0f`xc)P0y#Ejg$5V4gOmXz$uV!nMJyMdd(&+!jL_ijWtug{CI`RN)=uMkS05vd zPX&#~?ZGtutvm#37&+;F*ouepdnAG&wGq@go3QhH3-&FQc6`%SQgb2SCq!@OG#s??^2l=gd5OQ-+$7>cU9P z#4T6ms_{*S`P2y?h`co*=YLtKq@KZ-8zy)9mOcN@jCFG9AqR)9i-Rb%T70HBPSo{@_2!?+d6kBQqwx*wV=C9r)1;-hOE90MDFv?)K z3}>luxA@PU%dHI9fixq4FvNcB0aU+EQ=QF&w*Y1P&LqEf_e^#^WpZlcKOYY=xG~=9 zG-Zp2time<(w$?ho89uX2;r)1Z`1q;m?@|t_Fdg70J|GQw-%Z=`+yUoaQG$-3@tJS zH^Vtlz&)qy0q7lE0#wc)4yUOCjbM=MVmRT*gMVP;cljIWXKeq!==utGfc6t?Y0VQfLp$bEqFW6f(dKfyB{DEvXA}ZdO+0&NVVB(Ew z_KwxGDsFR7GxA2-YPsMz`RXd+)D`=3Grzi|rxmuHh&o=bjSG6~%A56r4 ztFTZ8RGXp2k6kpMpNY8hQw7p9cl{ejIzA^}3K!1rav9kryu1bFoAN9D(*sg_*Zdw% zyFI|3{1)?oz=eNU8LX`#nCi}0WPSXv?ZDiskID^#RnNByaWlDQL3iM8o!V~N>t3#9 zho`anBf31pabmFGM=v4ev8^m%x=tl(m{pdqp000}f#-H$-`9_uKLHshf`PEM(=%$o zHrx_VA_ahLsmBazHc<*d-x&oB9_>ex3G*m^|L53VJ&5Cd%IL`A-}(u#v}+~Dd)oLt z?Yx`m_J)e-y@Yw&E&b0NLP8r@8K|H@>+1+5`E8K9i)*}6xS6Pd?q5x-?Dq3pVab~t z%QhDf$~aa&Y~N?@8OUc)0xv+#uH9$lq6}z|w4=YFonGjkPYY<62a1Mp%VotnZRGZ{ z_wV<_ra^k{(#}zEQWz!i(Mk-#4NMJ}zfuvfExfgnQfE(ch+;BzJ_mrm`#QA%Ll9%OgU2?vsvRP>jN6=-g-6!x`fKDWNq%c*dn`c?zSx~c5SQeK*-&+ zE)uHkK>e3p**v#p7E6vg;PQnF$6S7)lJc@DTCv>sWRIvoTXU|H!?(o;DH%Dhcj8=s zPG$c_F#=^JE|*I>-JdqhOUY7Of01w&XVWnRovtcg9vQaaC4apO^nQqz4@kAb?hvDb zJgB8U`|^;z+gjJU;r11QYSaGF*Ik_Kt$SO2q@{YdJCxrRTO8*glYd$(#r{wwMj)Qd z@7QN|g*F&tqq)G_VAwr(Is%yk%axbsdIZG(C>%)Tm*d?{O)L&~pm=xJ??7zhRNW^} zN)2S{tLjpVH1H*_d>ex)4#+$-Qv-5^Hs4Db?ONTIv|-4y(rTC7lN~7EBaKg?RQSvG z;9r2myN6A?!ftNyf~?o;>rzrnJ3lZXZd-K@5!Fv<6fG3=J=GbrxDIj`>|{9=M1!b9 zJgTWNSKd-l5=*G>;OXY*YgElkngJL(H&DwYQ@nj#fW6D~Z5{9xt~9)R`}V^P+$!rV zOs6fZz{~V`=fNOm8E4T^Hi&v{N-wHwJ(V;29@FOi6#)n7{0Qp+6`Y;Qbruu;%r=!) z?7#jhDb9UtX@btj$BBnhSZ9TJOEK=JoP!Teyy%p~y!RP{Q=DcZJx@PB;WWm6chd#t zkq&9sB@-!YHbKFZe3cR(&Rw8o`C@c>vG49&>`6Ui76JVSmG_`G;t-zPc-C>p1MY1X zBn&)sr_Z#$fI&2VT68$pWp0*?Wyf_wy4F$Mpc%fs3!_I1+rit;TZr3Z_|vBch8DRY z!+2;EO4toPyKD-sG8BsrWv=vmcY!2mZP1`% z7ftTLZpUs2)_5oEiQLHhTHRM+NrJ2UX9ga%&OKL&kN_Hm*#%n|)#-J}Qr33a%?u2R z+V07W%AfS6nUoW^OK*Gowyk7!Y=mLu9chzYr#5_kY1@mCa|U3s30v22MPi+t(~U51FD@|Z#ZI`cg5BnS(;#`$jbt5RY~C}^BU{}J0d6NL z7=R=e+HN)L{J3=jHTzwEYhK7tRr(4UeP+GOBzW<>!`a;&teB*OM>+V{TKRpk!%+S_ zj^AxP%=(PFZ%W_0boSeWz26gO*0cr7e7oj6Jv6(2+oGMu4}KW!y*ka*S*w*7B^`3` zX>v-4xI@jW+WxqOQ4g@(rSHuU-Jl4#P6Nw&!{;M39X zY;1hkGWF1~r?^sBfPK(f63p(-6a%L>ca$p_>%roSzzP2Ew{VBNeOje+lw{L|QzYc* z$&}3dL<^`!mri5xgNWe0hfLkFn6?^KQy)yq>e4Q%99iH-MYV)}%cIjzj}(E6v{{>| zOLf(!a9*Tcm*uLQ-lTBzV)&Z~)2Qyj)@rL~&MBXKr*dYbo~Z5B^?4Rj;$_e-Q}mUg zUM3>xw67oi@SUh~-J*8hxJN-ZPkNlJpY8qDA#<}}J=Y2u)00?TeFX2U%1I)-hZQSO z!ynzcMO!&}j`B3Qg%ir`6NZ#Or34zno#e{A{`4PlHGEqQX{LTKD=b2|3QCPn&gkwz zX_c%qBY>^)dsLId*HOQSW`BHsdb|Ig3sl;jaLo@lnhueG`_aQI& zAaA*;legWIhy3^|Ru2{%-)+C=VW`wS6>A#rttqsLzx!l*&;G93clGAJO!N;_J@?gdZA=clRDnh%6ul|59J{A#}sMX(qkMyqL8x#n%5N|5!$wMUpJk~yhV z6O>z#Aqr%BiTG^S6BNi>$r@1XQ5q})-^~Y&sSP^G4?kdsLjVfNQiP`Gn7mEpKz=xR zCbf}1+BNTMc>GG=7yG6-oGi|BY2el5mfWFNHpAOFs}yfP_?Oj4Q`|_$NMYNkO%0<} znFlZDvJgYlQjINlBFe`Fle9~&TLPKbkRx4rs)RRTBIm`fTls51jeebMaRu*U+A=k~?`aIe;urX1OjSYgP_#W#AJD{cd zDjNJaUkJr8Zrz7^@R4V}A@mUmHRya?SQWHCi6G^PNd6eXXEgg)q;aYk*hdaK&dAqg z_dmLz6ejyD#x~;VIj*%`T9dWG=em9l8hjh`DUmL!PYil?PTSVazP>r4JpRF7m-IYa zB(0pB80(UQOM1P1xCJ`LoUePJ3UHCdMpdxaG;cmsW7hhA=S6CxK z+sAmR5@IM=I9~6M9kr-DIeFklIM(i_?PD-mJf6@*FT|?;`*9sqLN7vV>gY~EZgQ1G zoEeLXJ)lW(-S8(`=wSD81X5V-xJ)!mapz;7fWcmy#yNDskhn#mOVuQ7s(J&IGwty1 zd;lE&$**$dGiL%i3p*kj3R<)mvuXBe?D+MnZ;jpFdN5xhT^zOq1QCI>!iE*6YM-Az zMA()DG7*65L3|2gri@<&=Z-_(-?#C7t3IFn9nvIJ~7L9wa4S#rKL_`smhB#0T@asOd zQ4|npfQLv1tc%$8XSZ@?q-uRaxKLX28U24%yk^T8b&joCey(KJ^sX(lC(av#K?bFf zukSqC(dY6EWZj%ik)Qef%lr}&u2$1;lH_E#Kl}EvxQ2&vK=Zg$68rHjA-UE12lb3KM@}5QIooEc zd2Kd!%bfbX$Y6eFaYJpxuKHJAhZt)5#dj-uD(g(=%35AG3Nm~6)@ZbB(&_78OJAG{ zyDEHWFhD2vdc(+PBSM%1E$(Rxb;FGAP{nTv0#>pMdUN=@9;H9W_jB`@B^GZ>d$BN{#bx?5X&ObN>To|& zCM(L~;NX`F+ZtN>wzXf}rY0IJ;>Xscp~9x>^~qCIv?Qx+G&pbh<5vg1$CXW#=1zUG zWvu0Wo!V>8CtgV#9U|(z_Sszb!y5DB{DlejCQF>_%w$bw;*SP#h+LR^^TjbXdaN>N z?EM;%VBZT|qGLtN+TI*#H)g&mDP+Xf7+1I-&U||^6Tk) zZ{h0OF(u@+B=crXN2+rA3{WaRi1IK?P&f28zP=Oi#vwY zN)$EYxKBRD;cOxzbz$=8na?EazE-~E5&exR(*-DmHUyO;qpOs^L!N!dW-)7lSQ*q8 zB-EFJSl!#^Xb{V#bDv_sspPiSQmq+}xOTU!Y#BJ)BS2#Yl zg5kV3{bJ!X>bdWY;)C^pO-IyMlo;x3=*jmFHqzDE{O~+{{btdad?0TxQ@v!v#1rus zpJv*tk7$NJeWTNqUUnu?_SxHgmNgUK@ALRn4a;8gom7ao_EPbAs(#Pr*M*Kc{B2}b z-Jm$YMlex(EtgN@jRvA9`t7oyyPf4L&y9Nzf*zc$#VGpicd}STYldjGFn3{>1jSQ% zjr9R>rPLi1Klkf1FAJ1#QUS@k^V9)7V^b_*UcY(MkG2JC{X4bc+t& zXJ%HpT3lM}t8r=0OF`_c=VYaO%AvV^gu1{O^QI)Ci=!KQ; z(PmSCao9-IEjW-Mt|hc<^Y8xRAhgUJjv1RQ_V{yFT<73?GuC2!sC@qA(xf8|{+To8 zS1l)GAf~i~ho{UhI;j!+_rR@Xl9Q8{ajo63VJ8uU$I6ZrD6Lu<;vCytUFVjO6H}*4+WWV66_k_@UuLD(JS!aEZHywFhWQ>I zg@w#^#`@S)9o`kCnzLU|h&Tz!y!`7((a*Dt;bCJ!BNug=&oUf4cfChKS>yJ*JCz&Q ziY`@Jme9u3d>#X`@;o?K2HY>&LqK4qeXnwQvFs0xK zig%6&Po8vJ`dS99&H*rK^495m?U&;@P#QZ5k;SNNX{dB@5jn3;m)%>pg^mfW)4a!j z_|%N)W5^Ql>2d*FORdO27k51BWYBc{(_waY>X_2TS#UR*r^2#64TQZTvG+M&s^-;3 zi_4B0BRvH(Y$d5dduC^j%v@8H=2X!#M_flfJg!YqsVO z_2mVxhjj|&6rJZ*coz;Y6_R@*u=IIih4SwpYB(yOG(!_UMVrWq8ydx7(+B5M}GPmj0Fc9BGzu8qdOhNI0s9&Rx2(_fnSck!qQeHyu2W&OChQl2-n$ zGOc)*hnJ`G^2}`CZ2PG>lRW_$KSGxWWY*dC&i19W-^jfyTR741T^pRvlp{Gz>tz_- z#!qofyzQMRRL8c&i*ql$Ix8(-J%Wv2`s;Ar58+K4SD*0pT>m@QhuRV}DPGv{&lCeO zhyf3)PH^50bo;paBkKeR&zl!-+Ps+?w8jDD=hI|E*sA*+n)~RVm(Kr##PCt|VV*|I zvoI&@JHSwmRYv8Tzd&|40<+QAf?7wuF;GGCw@0rM)$Etl_z-Rp*6k8?7prd5(tF?i z#_M%LXZw)vPu=gZbBn&4xcT2Mb-^c5G%=e9#}fFHefW)WIQ$>+^%PlmEt~_O01t-!$wl)SP_kJa%3| zyE4~1od4a;o3|Z@K2Lnw9d@-n)lng_uq3)YUR;E~LY}$iOq|JCX#!1bxIfFos9g66 za##LiRW!cm$9iABHSce`d!$J>rMUP_N4=^Fj}piF;EWuCx3S)}LdQ}d=KEe2O!F=J$bcSOv8we7!pt71E z8;Y-t>ds(oO?;bLlJ;%l8fs}hKHZK2$_E3=vZq4I5JSCsv=!SZ>sB~^_r-lZhIZ3) zY>Crc7;CG{LYpt6#5;E}{gxlrRug(#YVY)~Fye3$Tfh7*{hV!b>G(`&McFmQ+J`QU z`o;w#AEr(oPxDhOsq^Hz)8q={el(pe?NdW)Lqg=Ro-EdnB<2Lw3Wzuu<`c5e{0bRL^x-tkjEb8pP8fjyUM zetJAPXSwnFzg4<(OSZN0rBthAQhpA8Zw!>0_TlC%>7Y+3R^5TRHA8=xPUMMw*?7~d z3*7D9LJFl%hP!(1yJX5qD5tmR5BW>1XlswRVVnz*Gzx*a6G4vwMQ5p{l^vWLn!Hrd zQ{K{eYD?$o!l;?yv4R-)2CGeAgKThmB4t7Znmi*rJw(eA*=h=Y9b`b*~-<$Ufe_fBRM*}-AlR)Kcn+c{P5g%m&F zo~qo@HSSLp&7sbr*4){0c+&c1U+OZ3{VB4en@f~OOKz$bwR3Zb#fCWZl+fNam3*L^ zEfMFkHe<@`$;qDPi9Y*@E4`<`r9_v= zjl#i@>j6PHI2vj z%)>9h<=yW{FHP&Q9ocye)OL02-eUjVd4NR=K3oN5bNS+x1%HO!tE5Om(7#kc=`?m# z8OLvrsd~Y@B~sdShR?Z9S*X9>gh8o3uvK|TX=ysrktyN zwU^^>%(m5yfX$~j(9^HY7`U6w<;s`F=Q)kpnNPhFq^lZ&dt&l+77_Eq!^xuC zx9jPSpzFGf)w`dX+#x&?toLObywY<2Zj@E&%kNK_-1nR^NlToz>U~*s^iV*6=wj6y z;kcU9_WOlM&cxo}>(gjsp|z{$89+}d^Rdnkr|GMgt~kXBV{HXYFD6DiFW9fjq=Is0 z5<-5|0#S!4jFj3cC+-hch125-{S$*>;ziVipsZnS0cXX3E)J zJC7Yd{xHX34DQ4BZkelBuRfFK?DRruub%bPqe@1vJr{3Rv^>AHN0~o0d9P4(M2Q8b zw&9twES3`o6I*l~Iy)7+T03)Nh`P~{dQ7pnCYqWq zrY!bKG)Nr=uLl9Da6j{OMx~? zf|rzoCYg-^`-Qaq;F)ZVd~f#W!L#y~pNiI~JMOto^pnp_f2WXwI$lpYF8> zpqi17;Zhr92z)>@Qo{${jxFS$6QcTiY-yaaN15>>siX~4Z9j;me(37(Q-3;FUjOvd zTvK3q#rKqw;;SyN{Jy@opbyAY*5wgn|2G784Gh=!V+3wP@W zPrg(D``|!+p8WBHMMYy$BcnVr}(U(k1t&#$#2& zr#a-l{LA+@TJ^^_F8lX_v__FK!1C=!Zi;7ekmR`M##ajF=eT`zm~tFVHE!4mLC6%6 z+D`cK1Tk20s%1e0f@mH+T}fyT122cQ%)--h#p#n-!keE^PePwsiKk&nQFF8|<9eYoUd>MZ8 zuC7vfxQi3EEWSkJ{6kG}R^uz_Zj)rZcqEq5BmMN5UXgVNu8Kp&B*`nllc{h2PECls!X8iX#aMw`KplXjZV1T^N<-?1184FMii4IK@B0=hkz;aqm+Z&>N zoP{x7#!EhV>IklDNu=e^ZCET#sl~y1Y6m{I^w)4c%8&iO1e6w1Ppe8@GXZAj;fM(~ zIQ{$$G11`*(?QxPB1Q%6C92CZC&oIvHlrHya4q{BCx4Ay4V&6+)ry)v*e0HkQS7=I zLO1-Q?krY)IzEc!9JmNQns+rQ;+lBnol`$3wfvI?8d6PGq(udnJ#bbxIN=zfpVm_c zb^A@CmhWj(3qjh$?!?_m0NjW5RBQK4dVMHtm+ZM$?7}}VXxl%Df9!py=1LhF+TYSl zc}{MRi{*T3qOWDA3}A~C|9}6N>m1_UScvffdCFsO8INOY&IIHB-#e3ina5DCZFs?(4fc*<L_H(*2Xx``Qr9wJIyc(`Na%jB)dX3gyUciS&R2`i)Q${W#|N7pzS^})X(4o;n?%m+ zlzrU#F$M-2E(3gG-`iGD<+Q36b$P2C>2enqA9;lqzp4-sS^lLH{x zK80HxO1mzKIyj)=@TlK0a!sjKa&F@OFQ?$6`#=r+wm4Rc6R437NOVPsmkQ~Y%Y_)N zVqsx1dOKfn<`fm)jm&}|g?aY^K3dkJ^F2aX_t6kbB3yvKH7~*OP{hb)C;A)<6~#ln zXq|k(xF8~G3vJGxMuF+Ni|TBo?A~C$)9IGoRmX{~-EnWOwa=*h)UExw;EH>}63P+2 zkeXm+KN&F)Nkg=N?Ew64&WsW^0DyN44M|75`dFqWq@f=| zLR<9J*}vt+!fJaf|HKy(HweP~v3b^$5@F6GoDt!GtM}$JCnVN?tgE>R@RVr-w;D9F z+rYvi+@RzBd^&+~iheDSgoAdTXm%Wbc9u$6)V0vPKnq0{24$%0nemc1t35sbb8E+I z*JX6X^~t=5&2Qg~(G%!@{LEk|WrO1>fW}i=w=g~yG7#9Udot|5sX)xK>ZO7Vs0Q73m$)c)4DguSh-FzHMQH#3QWA~UjuW2^QY#{Y6^9(Br|zBJN|enD zc@#LkQzyKvDT6^iC%yuWpNV@Yj{Yx|N%V3LA-?q$mRxKsK8OeR?!$f`ZAH89 z=g&$nuoU))L!sER=@*S_|9V@v*^(jQN)K$(sSmR1~xDJs)mWA+5rLg?}n&;5!KjYfDB)pN>&nI_kSP=%ICw zmd_i9AC!_>WQIwuH|C&3XHE9;o&ykA(e8PloRow_2Wi|05Us=ccl}CVSv24%_46gf zB&Y4#vEy?SP5sz*x2*o$hVf}mwfZzuUfAs{ea{>RvyNI_7z7QuN5~&0yD2P1mFp?b zF)dLi4SSWs$Vu@Oow*P|?hCI}pBIj)XQ9+O2>-tKm?iJv=H@P!*0V*)AJcm>^JLHq zaY*=$S|w89Z)a6(g+JvZ;`+Yuu-nKew9B5l2ww+ zoU;g6^jDs$e8DD%IAMiLTKVTv-gv27q}_VB;=>+_r#oPScRrhYqmzZ=ozt?inj=SN zfaKebPGsdKaM-<028q5V>Z{a2`7p+8gHo<9gsX;{87x(6>s^N};!#>B>3(3kNka&% z2*rst4_K-`u}&ee5k8VF)1ByWVXqVb#|Splp|zI3Hn#{ILqPn4$B{?bjg2V)L)6WL zd;jh3p<2olyTHwnO4OnkJ5-xxzkd5has*JEdkiEJTmFv37u4R3wA~3^v?5_4Tsi;F zr#)DNQO>qaBs}rIZVfNKi?%gN_{I7yQVuh|~>`|rj=5r()E?=ENwH(7dj zdd|+O4G)S;f2h+?E@{~Oj$Y{^D5>A zRH;ji8q-e`K_ra$B71BB$`GYB^ACcxk88N&=$H;R61sPm3ATN9aB;OF{XRpdgg&YeP=2^!Bs~5t;Au(8UtdVST2HLTRD4ldnxi>o^>?$)uyFPZEdbm7NVKL}q}TlVtSnP=R` zPTxrn&F6@_6`Ig`@tR-wr-$axm$JROK0IA+m1jCAe~eGQxU|jRzu&1WkotRYmSf*> zT^*P55!O~&H;6zLqg~W>|M4lpWB)+@qR3BzAEu}`a4E48i>EMVW@vYLG6@#@21ww2 zzNm>~uvboLZPj|A7$1Dy-Cf11-H!6ZO642l88jXFaF`-yv$h@sRMt;F{|9HNm>g9> z1|=4|XJ92uh5u+HwryEkQ(9Igv^95pe4NUaY$0IxaO^GLc96?c@^SmyvB>U+H457i z2`4)Xa(yiO8tcwUZec<(aC;#slZ7b zo%=G2g7%q%S^oosYT>{T8~qjCm@*#6zE{w`?T3Diylu0j5D0XjD?pRVh+!?1aec6S zRp&0nd#=(W`_;uPg`uG#em9Wrdh~Y8{}(5aqFF4M&XA%!%`c%@ynG`o_L?}&{orde zy&`{f@1*81dsEk(1ouBr=O`8UBHl<)8|rni;K>K3u_{$JjiG&* z;)Pg10^#dBq7|ZbOHz{A=N-dV0~~_vU6fBNe*=|@2;5um>2hChFut;b>kqpFK{xv_ zD>%*&;A8{QE)janB8>`KTA__l^BsgJq>PzaLg7-VNow+75w|lFX9U6I+|P9JM6F-{ z;xSq>VFauMj&r-W_8#6 z81yIvMbKcfo-XA_c@OpcptS!e`Z~J(gDP6|KWf)^M_+jY4&4C7iYJy`sk}uh2*X;Q zimYquObgKU*8MVqsUOX7OD1Fn9sTp4js|1UMIYx~8K_87WTjP=U+h zMdUXDavF)afJ&rITpw_|N^*lgenBmo1mT2(eoP<}Avla)H%>SLAn??}*w7rP2v5Lb zW;ZMWUJ_#Cmdv#+Dx*Y5oHPoSmGHIp18c{R`Bw8ovLoa>6!q*G%z%$RBRusrYcAG> zP*}g!LENV}l7<`=kyglY`O`fhi;d$M}K(hWkagmJD7Xn-b_xJ?d;`RU5LVbeec&ae;z zNzA9}Pye3&3exi~gde#+V3MZGXTVTi`Ybr#lUe!BUEY zvVdv=?aPq+`~Y)eR{}P%{9%qrusU;B;Cv-$vakzRkQ5(fb4*6Y8~zQ)b#-;!VyUUA zZ>bPz%F48&$<K(l4906&pt!?% ztY}}Fc!M5=m=?07HJW?qXqtA1`q*OgP^r@w4$HFnO-<|Va*F(N0Qx$+VJLZ;2>Ls^ zFfuW5z-{aPez?z>)yYalclW%za3h7ZKG;Ag(RqiC*c`qbR2EAXFD?d}#%b@iVSW-B z(8U{TcFg=i`7%9m89Z?F-5H8DK`Q?|6@aK*N9>wzL^{=3ONh;Km z%8ysm7kI{P=MN1gIV0!KR_7qOMlgSt(eQyMJu)w6t9Nn^sizTLvbEEUFib91Z6#jn z09l@R+`<2)*j#d9_8>Kh^I-qyfjP`zJId=a;elavcw-ZSJ3H}1=y{Ic5*GqnTic9y z51QXW;@5lcBTI5Cb-vF#x-$46zK8#lFYm1T7#e&&tU6LbeF-u-Zqd;nbHB6+kg>gd zea}C?eO>{32}~OJi>3T&1RiW+W>)=vWn;b|m5RFNwO&L`jy-P98;I2)Py8!FOMsuZ zFY|uefza#MuO9<-M@Lh1{@ZKbfj|~;(i;bi)I-1itMxVNH}UZSCDDIhAup%PYT;6o z;`ka%&q)5V)G@fl%NA~DdZ;+{B3>&>iY=nFDn z^d&8+y39}|QJpg_>t&Fb%}FxGK!*22P|P%7D)>!1{dI%(Yao~vvTS9hcy{?>2m}s= zB1!WW4b1LI9XxpTm%?Iq~YgMT-_Wsonl% zFw(sHW1PBJUACP?SO7%dYRT-ts;I!*+gp0BmmhtrXMab>E|L(jnwp_4vG_mlPaW?s zDulI%Lir$HhP=O`14;8vB)d0J2q%*aqH+%^5dWpiooN5+B0q7){-9D39K#HqW-;B0 z6+XBm$EBpC>ULeA{&l8Rms3 zRbJ#uc~@Lrg~`Cd{j4@U#mlyCNW#4P4yXS4vhgdO4UfUFAjWLF_mq)Z1Sl2v(D?F! zykF+Li1Kaboi`RiYIaYx<>g<0T{GK9?8*|Ig0O&Yti(PH8~elo$qRpv=P1sk^LSsr zD=0XDl{^`-74h>ikZiKrR=b6pnd0UAWb)K%>=IQd@3Glk*V(iRh-hH4E!INKlo<>M zQ#hHV>t1AG7DNSx2e@5jcOHtsGf^iuv#iz1LZhugH90k-IXCG?Y@ML~Tx`fF!QYP& z8Ij_+(Wls7lX&IZktpZI2*EYy3}Ho{CUDQw^ARkeOPv36B^@!E%!&`%H%0Nq=SSjp z7~AjR`m_3ilCY6y4>*<}KbX>$PF0 zR0!)u2Eg$pD-k-uN|Mp=q~3{E!1ofo>z;7@#EMqZ51A#D-zTXiQS1+PCEHNEY(yf^ zk(;m2P-e}19V#X@`en7Oj#Kt2ZwTZQ~ZDqhK(j;uA2n3qmn{!Ix~m4#`x$9<;OwmDzFaun`r_wlQy)W6E)#( zY0!^YZOd7^HYr$*lN;+4{pLTvN>_>q2%HlT=;|nxR8i@vKvJh$yAhZiI4KeNXPGi< z==xqIEhRG|EG4LRvVz^|gGB3Ra20E$YYp-yhq4o1lf49v6zu6eJ!kQA8|4>{M8uIc zw1pxcEm-JBw{GqP+nZhvjpJBE_bP$fAc3i3#=3qw)Zp%CBMhq)H468hZs8Qs( z@7(v_YMrFcmem4M4Y=|RRn{F34{riYm00&=_A1dd_`xEPUVQk$*$rm61js8ceI0J+ z4QlW7l1uy>CdRKifU4W%?%qz>w@U3saPyqk)ox=Lj%MOSr<9A6x=WVJ)kI%>xr z`RbVyLtJj)B(Bx1(sD2|;;J4M?-^I(rb=B;7-cvF#rUU`DTU7#XFNmoFDw-hZg@&> zeQ(m9XsszoDDcE*51vT$4fv-(bs9<5>~92D<#f!f@1jrhMgs^z|F?kxI`co`8yEE} z^XT&pX!&B7ZWlFB3CjUUU=EJI$9a<|yGSCFf(Gz7V*Y-MMKMeZsf~6gz*CWU7653k zZ=5-Ft+$?_&BQAUxRz>M!%B}Nx>Pu{XDY29Sc}zQfKHKAS?4cCQEaV{Ec}_^@8V@{ z3KUPUbqH_LX_kAz@46a4nY!V9Y3U=P!b((*n5?a<2r`K|JN&ijm(tNCjpQnABDq>> zf)@6E3SfAh?c6LysJ#B7Rt6JXrQeec%w~u_h`G9eZOnu87nXt>sdOE0t7 zx|Xt?!Oh4RBrmjhM^cUIwgD>@)J*AWk}~fb470hT^h*EX^w0Y)!{V$< z#A-YiLPLOE;PV+P@pdZ}Z6CxTA{@3WWAi`;zDS`*B`xu%rL|8<`@Lm~I7bo#<&OX};ggEl03pU4cEUx_k1*Le08L*AD2DLXA z*ICpf63bQG3^dEi%geLthRfO`=FY-e#M~AC#fYbk)a~y{JgcAF9IX;1229$;y(< zN!AMH(GOcr>@is4R+(gabOYeVUKvNE`9p91?Yo4Knib3@dU> zfggguQ))4(>~;3F6P$#;^B2?x;O)a_a1aYC>jI8*rWw+VMXMrfqd8@8*d$7M=kajU zkKoW6sxkgqG{W&X!483u>sprcGFjSEVkJwMnC$`bU!9q@gyWKipmuf)paS*wWVFR&E-euBT!6tZY zwHpx505gY^Bkj>?n}KIi^|`sZNo;!~w0gkU&4YpW$*C*}^OsknZ@Jf{sANeDrbfyI zfLW>j3>D@tCrK2DcA};uql5~NwncV9gW{9flbeN%9upCy_uPikV{q{jZW*%Q`$WUC z>e+Gci>JF7X{f2!Me_zxK52YAjYL<{sit(Eb>~W?o1syPFK@v@8#+u*Wr-;gFa~ev zcc=mZ_S$yfzyaTxPDC2KKQB^iKL0Cl`)QQH6$=dEb?HcdbMyArLsUJr@xo!&v9!Ty zmm{p5+Kh=j1Sz+yYSsPvVTjl-Ap&uoiLAix-pQbS&9ag9JB#hM5bUn6OuZ9f6REWLHewY7Q6p`1<60cb#dz} zzCJuai?{DVgMCOSdA>b5r-QdXc=TuoK%;WS7b5+|Fv8L2SZeq&2vB)58^#SQm65zA zHa|$a>|?zmr6VW#+Txm&GY&|=%cPZH8VKDIiLnfHs${PN8^?cVzlN6b z4z~YSiX1`c+F2E6bD^l=6%*lYy(sScV7g&+9w4v5jc+FUzTXFmRMskjlqKE~qqLhM z^agVf@P?>WV4&8~aMgWr${n%Sm*mBj9b!~D7xy=$$qNK3D=k~TTwr};#v)hoG7kmT zQ|A}Xq;bVo&61eG%mHhh>-8yAcFoq`?g~HAa=;9G^U0KN z@A3fC8(*usR3|6&q{R9>36mp?>0 zwPydsi+{c(>g+QJb&6X!11JY(=c$+k95GXFL!_ap86kWua4w9ZN0K&{uSG4hccIOS z)D1PSo|vKZ!2%seaGJ<@lzvB~`WJ+U;hg0>mX^FUT&}3u8ZJ4+WWa0k(H;+*2rji5 zELpO|BP1kbf{4nI9q_SCZ`d^X0fa09NbAwqK%^o~b4GmOx%{~NO3tnPmzPJZb1WAB z_v8F8WaNKBDEK%`xI{*7f~Zp8d$GwFrJUdJ&7Vre2@9||5jRYv4!tCHK{%EU-xn(j zQb}+nTzI>f9Jv=8gVVZbxD_?4!X>{k86YBC-F`Pa67TX$e^n#O#_9c1eZy1ENG@z! z%FB2^7LTbUHl3boXqnv!ehA^G_Rq2sg-Bpiub)Rx3^ymy#Lg_={QVj{p*{hEt9P$Qq*0oPpMRHJE0CC-f)Bg7V!q;%m}P! z`_Al7yjDZMlf(GFcV%l2ct340W|!t+M?a1U$Bu;y7mg|kL?h^1oWA2;54$bHgFi&% zIA8UIq+E1pwg#+x>%3ttYbt*Og5`G1MfV;uP#Db5mm2z2?SgS)^ZlF&vkdR@PDork z4!m9>UH0Pj3?PhifJeA%6_R!3&c=!t77Wt-2gF;Ikb`5^z_NPT-)S`8n`S)kjQGT` zk{DGVI5K@ESH4q(dK@Q#;W6}R#mI7cLhGPd1`nlF8>4&bws-R}#cKyvE8TaLlMgk* zlK~D~*kVO3govG=x3I8;m~O@CW45f_C3rnHY!qksHJb-9aw-iLZ}5z@v84qtqELE& zlgPzBsc?m_;xD?Kv9hl-i)6ck8UE{Q3B+4G_ zAV!MyFQ@zt|5v}6e~J3cnKQBqwPaNUo{odD4j?2Cl9u<<=$nI1hopG_`Y2^^S}uB} zVZQi|9e)W+eP*K)T00Itr`&V(erm73(~#lw{iZ#{>$AJ6s6C5pcmNbEDTRnHJF<=s zijl`z_sM=<`;eI7Rgi_q=#U3_oYVY0K15M+xkQgyG2-WO4AU|oWJp=q!*MnUNhfDW zt!_O<(%C}lhHv*gX((6$manl6BGt9^fwT|q=h&ZPT&S-?TpFfuCp zMhwh@u5r%kN$s}q=3i?lioF3E1dm*^;vcL3ln}Ul`U*`zvx-2p;9kPC&ny&(e{~Ye z=2d2CuFY0j0Dfrt_J#H!AjKV)mdSSQMcpx+(!Nskpu}P|-HuK6rmHEP zKC9ZH-pL6Z!RP8McB=aN&tFtELr28??I*gy$qeg>L7imx?CJ)Gk#067=QLF@th*CU zk@InC%59(GGQKkrljY8S$=DMvR%fTM7f8D6hEXMYic^MY?YazoL)I$4Fp6(UDs&u2 z(!*3*p5lr*N@K{%qnz~Dx#*nCt9{jr5z)xJ_Jb_AFg~TwaDDwmvw`3O+?p>oH5L!u*6Fdl@B_<>ImW z%}F{kWaAa(UBmYU!xrSyhBr&6keNKNPc|rO@bU9Y_m_ohrd)n3E-I?>=FJo}>+YoZ5Ub3f9~qRkgz_1*(Gsb06b0?Lw!UZ(RNf#_otPZ!H@#{mK)qj1 ziu0(Ul;EB{A1i&!>{kzLbX&XYTh^MKmAjdYJ$M$FTydk~!TGp6cqueOGJ$IFy>wTw?+*0|HNm~ebxs2Se2XhmNo zMK?e$j3e2AG!2o=qNs}Uh468VE!J^Su$bMO#yhx%~T!y`OUOrSdj+Oeq?g@_Kiz??zIpGZZ<2qY3`wfzu zrmXqzotG$o;oKZ4$85piJ*dy(H2iRBs$sj;QMp5K3jHsb^}nck|1-bzlD2Hkitbnt zBwk&Nemi&eZMi&(Dnc8)e*MOc45wJxTT*sQ^{u)9%K1x~fd3YOz!ZK#4RK=MhR5JT zPSjOIN*{ze!{H3ZXx0TnqMecK{RmWk@g7V6bAI*%Vb1CZ*(ydEeK|?=eYZDhDa8dpu_LtFBE;@HqX>jY zAI3*(Bp-s9~q z%O)8QO{k@}RtcqZT>lDlEz>+9lk*!+~9P!+^74gq{ zpEZItVVs3uur_A0tbN%FOu%~b$;MTGvNriuJ`vt^Xz@?lPVo)wC#~kuEzBMiwRHY& zDnP#B1jEX>)Z{qyVUSFSF@ro?ptp*8zdF%xHOGQbqcJr`7C?0l=Y7IopO}w?rwymo z$g|jIAcFzN`1OB)piS&8;gqaH$_vd@N{r-8s-453|uh(-t#{F@B+#hiBeS?{!`d?qnPuGkB$P;?% z(A`CKoNVtG*Ee%=8C_+)8Y#FM(n<#tS(BTGB)Pfab2yOYAFef29(6p3A>q8Bt`@KB zze0xQ6$PK?;pwrW1iUptp);Z?+P4~!m*zSOtbCs9=&)g_oTB2#b@2%nANMVE{#sH$ z_3%pr70>zC=g1sG5a8XiWjSa|DUkuo51oyu>$)-kj_R$fXZLgv+Ly?o>&yIE>jIJZ z-Kjdh|FKz`yzq8QOG2et4M6fv>_x%xIneYOyHK#ORcJy%XM+l935K12df+7^hiP$h zljcI-Q$Fm^x{>I=_PqYqc*=UH;}>|^D_wqmuX)so!5^Xg?#J8TKYd8@Ij31o=k*M6 z0Z2m+XUFi+P~*ROU+U{OM@HQY`vo#+A3Ce@0He*HRtkN7Qfx@s`)3I3rmTl3IM97lUVTkK$-@4jYZ0df6!SjXRGTL`bVL)f6LDmEuAkb7UU?kGg+zd<@MLhH z*mXo}WMnY20ETKo##YxD=qoGqz1=i@rlZ-PAh@9Bd>owYU7^3lg~_D#tl;u(Cccb1 zFBjn#={(-M>tGP9^zHS|&kCB2QC0bFNWl~=eejHe3-0;`5C%4CS=@{2O4-N+$&}Pf ziH{#kAih{pd-38$|F+JhoRsRRBrLf}A}OQBs87Ud=A-$@G^GY+O%;t4jZkfR(lHE9 z&ig%fqb~(U4!*znJ1-SGaAOY`)~eYpzo|q^k&ZuJ9l}*IU*1fOp)0g6EJkEs&(CnNx14l<|K zy!G?*JJw|t(&@L~;yN;km{prT)UQ5c{T>?_nCj=|Hld#YEGbzM%a?23k+qZpd6}a^ z!J=kuiOQkiTHR9%QKe}yerAyT;K-jL61NrF7wwHbR{l10{05O9jHo)z>emzbzC+#h zDDJ>eMc7P(U}VpPj@emJaF)AAcw*G%Ur5llp=R*Xe9M+Cx3_n#Vt3kg5F9$9@p(In z2r(0kcMxv)9pq(+UPw;d@kYB}3%s5tp({ugzI;&OE>c&jd^DNqe&%@rpg{>Du-zC` zonR`08A4=!genASj9mYq)WPKK!6{bI*rF$L@P;6wGsqstk#2*81w^2>y|({^s# z<^}Gght6qpU{EPh7ccYlte%*D?geR|TDmm*bA>pXQ644hM(ob6yi_I47I(V$FflmS z-{yDjd#+zi2%ZqZ@7ud*YJ}2o$5Y{0SI|cub}T^=p9}&5uI&e7b=zaYan?s7wFUqS zR;hGgfe~G}0~}7T+H;bn?htZ-ooF$TmIzb^_Z4Mgba2YaR__`}SMoK16H>S@PYBml-C~X5pr>c{U6$NJi z>JTl~2Vcl!B6R!u0F3wN();>UPpN=V__RtsK0@=qbKkoi(sQPRWfR%8?zgj#m;23X zjxBY_V;HIevD|i+EYIp{7P0~|_bJY~np-5vGQ_@h!fBaXSI!;Gd*)gfHM<%966nmp!IgRC`j-?^x z`bs0;kLabJN#Oj|xGL&3;WIc&`jz9=H%*Kxa{?IXq*QPrJp|=|2kwriPp=J~d^(*B zjEeXa&2N38)MJCq`fmACT@qyWWX>GaN>wlt)buh$%Sr#^=O3l$%m8lxM)!F-FqU_i z`a;Ig5VHKjB-dGgkRR$6U}@98%zw{1QDLDpfp4yPO=Y@<(-^-tobkP$OYhmq2psB} z&muYbgtvj8k#;l(?Au!ITtsXW2N6E&StJ830*!0Q^XJdW*>V%%`UzLM(sjh?>4h;{ z+FqOmQeUC2#))SGNGNr@eSFkn^(S@dz^1wQpjzi|0fm-_X&C5A=8??!5qE9ANqw9NgE3hKAk;XE58~sX^HTb5!NuAt9kYZqhPz^jqG!ax$mzd=05Jwh zhiE?<<0SfD_Vo0FoC+a$X7O>X#|3&Hd+40rGaZZKl&6I6)`$T%eU~KBys~|jTeNl+ zI-pNv>|6b7$dHsr27+$fIGQo5d~(wM6J#xz#~QbeRA>}-cw3K!nB>%i>?8)~RgMSq zfN+amS3Yy*nG;$-`_MppXG(&OT4eknZl6iT;}cYtT-GEGDZ>njAGM8OdoDZqZC`pi ztVTUbn3U8bd6V~Yp;$zw0c~-e72j%n@6%`H{UE0_{5#JgcH#YiGmrNtslWDIAdc*) zKz{?s8TXOE`H6pkRu}0viXX+rXpdF;Y`;VOPnWe89k{7Jf^)zMWxhr}nQvs~lEzZ+ zq|{R>OmPRFvy})2YnuWTA*dUCy#?(JXt8O|H33=Q$o@4`^K7g=_~$R*Zzb9TZuM=h z%y^??$F@U8aLAy0Z%>VF@q2X*r5rq}7}2@48uSJ4ru9>LYX8=_;V~}2%he(xA_Y(d zQ45Buk(zkRIFqWoB(u&kAC?*<0|e?yP$_uL@^Oy@3~P{`!Q)wsS3`-AjJpAm zF<DFJbVywe-qm+9BfW%w@UKvYdKszJu@bz zhi^i~KXccKQmfRFb;k)jKD0A_2Zqw#0201&Rfxf!RE${;!-%yD>!VIt4I%Ywgr$84 zj?NGaltj|jQ&>D8emB9y`e7SF zn&kQrTW#0W)J&0b1|~^ne_g(IO}auJNu}_UCr_G+xDafIDn0yB1u&+oUDooG1WL3C z^RHQ@F6CLkvhXCB2q4^ERj+@3OB{?)GB;SGWWYlFQ9i^5=tKr11y)6MeE@we0+cB0 zXQh8*&vIwJozR1<{!Q?=qUi{%v!}e;bjfW2#|YR(xd=rH0S5sOdS+@``rzt1_z4Tc zxFW(D&PO@rcB+($$6G;1oG>zf?a6_5fNSKg$8|hh0KpWG%j&;f<_T=-1h!}2{4XOG z!YfhYz?zdzU9^Pd-diPPVb0=Fh|^9xge>KGV*MWTEhNzt-B}098o6|O?OO>X1Pt2+P@#R zk1*~JNUTKpo)n!C1n3o=0#=!qZ2g50AukLl0>$t6n5s+99sIt`tXO23oW5t$fp4Lt z4b|lPpL|C4XjJfu9Di%iG$RwjX60lpW}e10&AQsrkt7u16iyk>UDb*E`V}e_MBw9s z!m%Bw52;gLJW6c;c}DkAc(~{(sS7FGR(G->;zM*!2(wt`0h(4L0zM%cI#K?}x3uXU zc&HFIa2vRhKqWpd~>3+PK+TrLu{B1ab23nt=t zPptg%G*(jPZi=wlom?Uwf~4IbSt}7-n#M&$N2z~!DZ-<;c$-?L6;8Xy>a?Ncg|n~D#( z8BZo%ipCPi|{sF?ClA{3zk5b#OdGmTXU^~ z0Uos&+o{`q5B;km_$I+B5r*BzH4M9x884kb&*B;_`pek7sr3^$jsC-PfgJt+dqE7@ z;(aTYhnRKsqP0^~-UKQ79}G|Tyi_iT^taEB zri44zBMX%U3A8NB6qH!mqd#cqQ*Eu`r_*1i77RLka>n(ztvn2}i0$YZ&_Mg(HSTb| zeT*^aAB91vmQ3Oz;Yc8NF)L<-Wna4kuKcOc9AY~eMl2tOIDMy68WRc2`kQ^#_eA88 zm_(&*(YW`cJ;DZ~SC@F!3ues%$mGxdbz>k};bv9sMoZq#T>Z!tfLj#{PzHPeL0IH!+RC***vh+(3^m7@!F?o6ibPRSreAIp(+&6A*|qkc zuh!2msQbg}Iv|GXw`V*qdGP&!9h0(G#Io?J=W!89Ky0OU%M_8Fw*;Y$_N2E>j}#qy zMmgf1K2<9p2=KBxv<9`gl=7N$XV2Dc3aOzwd&2GR`iZcL$9cLbbby+X&c$VYh~GX; z05H_m9@IOkS3~tEWjG&Wh$RQ_@jI*=YVhd;KXLznoyyquqsETsL_v2IFNHw=?^OM5j|{n4)SnW#>nDZHPf^caXR&2MbN%rM81k!zAC1 zN-|kB=?H#2$QQ}w9ooJrOP}q`hJOtXKJcwdIB{C>;bKSR3`DQFsry@P5&_OE^<<2TZV)bU z{GC+oR7@y4itbfXU)8g-8^)RWs9y9(vu!ac?YzHd{DtKxRgtrwUUUx0Fx3Fzf2wp3 z0x9Z)82Kgeu`pPASCCVmYRRM5#FJ!|vd8~O&`GJNvw{rjWj_I=Q)jHN{q^x%sW2PYm*b(Hwk^-PDa47e2t^8z6vX4Zy zJu3eISXpAYlsJwa_K8vUQ5y!mb!;os8~2=qy!tcFXQkX$7u^1RFQO470kgRBWqa`I zhUm^9$FA$d)HV&fj`RmptD#80ByQe4C3w2wy2?@DLruf9=`m*ILXvA-A&?A z{pLIimXCY(;>;{`JSj1saqdH|P#XnN^S;epgQT1|bEEm!ZxYKCBpy;;Qyd_7WZ}}N zrs&iP_b%Wf0|zGPSj?L^HM%`})(?`$amKZ8>JAB&gaiw!Pd1g2<<%GALu;M-uO2;m zbZyPW42{&2t%o;u?o0T{Hy1(zYnN8Ah-_k?PhZ3ucCS^jXVF%5%OM&<-<{kZNs{T>6Af0w_|f=8u@!oc;mDRtM5j3e54F=x(f--2n+^ z3PNl~&vCMl&Q21ndTreVy;U^MQ)jODd}>7khtLT1)6kjjF%}?0-9!lZoVo%%u55D` zR>VG8kJPc_?NVXkt+;rNvDZ9xF*4kVM|8KcQlu*h*NV~6^m31-YjfbKLR+}e>o{Dh zXqydtkReNG&(Kzk?=a25sqH*1_L!5gyVPeT@YE-VXhNoEJlQpJl&w`>pJg89?V=&& z?<->rEgvNWqfs?i_iuLgTWy^>p9^`_HAvTAmN@&@P{Cgd9&H#TBEOE$FcMtiT>HN3 z`^C*J{`>D86;!YtTDlGI405$Nh6BR#oA(hSKPY}JHB@rG7LU>q*wtq1BL_R)ACdF? zq*h0i;Sr~~2Me5<63c$?ckv51w_sU>l*661;{Pjbn%T2bDglcNiTy^p>#V#_-1~=_)d18B6#1e>w{#(Yy-uKu0Z^Mz&N8d`$YEJ9V&^>$Z zTq6l4K~B1C5PPgVI&ok>eK}W29pEL)@NO?E zD9P2+(}Or{!0_9rB}ynkZ{a@Eq|=Egp-*YFUx`X*$DmE^Q$(r=JpXN5!Q2?9kRqs= zjOF|^hvke29wfu-64(AUi)m0aw-UJwt@n1l_1QLPoh>LKz{f@_$Wx7V#c0}7a69=Y zBXS$Mtn;BF#`6Q%gTmn7ay(<_;ArGZHLX)zzC50_ zQ&bcZUUKmv?_RDt4L%t4M4BkJTcw>HG<7X49{!2Tb}tXdJdv1>$N*jM==AWT_s+E zo`M#|?#d}M#b!AEW7r+ee>o6sQ|CWKb)DTkHxl)W9eelgrQ9^(_%8eD^d>Zp9dfvP zC#V@(mn5ttEV(;IJ#(4ngZ`&vBH&=jN@Dn}dv0d#ES?;WdDb-7C>Tsm1vrhsclYO$ zb}lkl(RHZ6@IJ8>^fO+!j{+%9k56`+CUrrE@XK)nHH{%D@}(l}HPN@9bwQ#%u@8^9L70U5}# zjW{SXG2N>br(SBmHl+1A(-llmISloEp(r^yX0+*^cGc>#Xy3jBaJ;u6by(1)E4>Z{ zZOe!^-_FJbET=N-e~h4Pcpd0^E|QKDa0N5lp}-#q*-2?UjK+K~gYD91Hht(4W-onbGEAH}Ya3u$^O5JwG7N zhjPpc!<*p#l1%$$rGC1xxb4)!=JW3pcr%L*m4AJDKs;gei@<1Xn-~T{$=)3>4tB0U z=NH2>jUBR(uSipOSmubcSWe}v%lI(xQl2LB+F0<-hQ=9&GDf@|B0v{vY2F}?Z$gJ= zO`@xC)@tUGmD=01xOne=uK5bvp>=^l^ugC}0)s3CV zxui~-I}EoapK10bfM;7pRQr^zuUTqwG}}s9hxc$$U_FiFRNs|3IaWQc1f-_*X3fJB zVO41N)?MiG{SaUBJ(><#rkl&OhN-FTgLBVFtCtqLqoMwy{_23}Mc*R#gWJDZ`hiUu zu}C=SpYi=iJ$EBQ=DgGYx1 z3J!spB}VFxgxodW9%YfHlfW;zzlkquZiVqRVsBvKZ8Zunhghp#icQ$Dhr)V0VuqkB>uvlg}a*Qu3W~t176D5iJ40Y`oFdw6B+l9Xpk)0JV~wR8ORA zBW4?Zn1!55Zu-=4)7eVR#c1dPId0d7yZS%m?cQk)$Db%|02jy4w$*q9iGz^5{D*PR zh#k&|zHvb=^U5N5Wy2X+nia~_U3J^RPK2Yuf+E7vc~B6vB~4NY2f~1COWpR_K(hl@ z7nR}GB4)XMds$pue7>A(_|Zgr4RbKrZxE{)lR09NaskMZzveJez#T7Os5^rnkCr|5 z*O;jxr$F>y6t4~omN0v1v%=WGaK3?}H~+0on=D~hY+7p=q&Oq~Dirad_p1(l7jwBP z%mz8Wv6D1%|3{|>FYZR@W~s$@ZZpi>&B@0lHz?h_QWyg24>DiJ^xI4m9}<#_!HpAaQLq-9%=MauWGX%$pO10gheO3KWx*qiCMfn8;xSzyV~(Wd)oIU4L3T^k(yi!2*uO&osM4KYjyv zWs6LiLt9u6-F&0y*LS2AqhMK|=?Q`a!%ARu6f}z>e%qami zMzZ+`A1Je8I-*0L9@L~>pg*OJ!vR@=;{B4(Mm0aiHoU!eOQfF ztijL^u#;i1(NcPo&Qbrx_e;u&m#hMB6igc?69tKJ!F+2IITaXYqg<~=p~2n%DQIx_ zIKi|8x&GV1dJkeqS!!lZuJG99r`Yhl<*rF{=qD+XpXqUs014Fr?XqJ_*fsNQaWA4Y zGTe}>#<{W07shZ0x=9)VM*DeraSuw}KtjvD=k^-Z-4X}xeqMgQP0KD^ z_ST9h|8-yAZsMIWqoLn^0`1-(6rmKaA1*xqA#=D(p}?q>!vsjjjnuAZ1>?FJ8SJ}b zQ_2$)7R#Qd4(nREVA(tdKzCrV7lK$rr``+n`6Om?Iglq60`ld1>C$8tb27;J6VNxA zz)9v_NQ#(OJih(UoRyn{z|v;4R9wa+A9FZ~~~w*qb{`q4POSBpN^=rXRmpht&RK(zaua_Zd3} zI99NE7GHNVmYOW01Jxe`3qa&8RRjb) z7$r6A1NzXwh4n%vKxE%v%B{+cCaSrnS){F+dXxru_9AQ~ewNmY^bw8W!eyVH98no} z1GN$rv+{bNM4%znd_F*mZ57qxSLQs{+(@zJ4Y0DA9eI--exES>u8N~RIdJ{Tma zz(jhKvl7`R{q>I**ab6F)&r$bl%F;Bu9MOA0%&ukb^WWw&A=CKhy*+Bwtx;}QnbgI z&?cDWK+JZAJA-W)$}x5R>hv%9GR5nb5J|s1L#`bkId9x3Pm%6Q+R&srpPOg7(517J zP1e1BrT68sb;VlldxyEbHb|fQ>-uv$o7oH4LPaH8HUu=zOd7mZ6OSuI#mD%z*qlqNfn)YM}#92S*;D0689KeU32Vj)PeQCdu zsf^%NxNHR96DGCBK@ozs?O$SFPTLWsJ@%txzrJVc#Lokdo)qh-(w|09S+JX9WH@tF z!R6-{0plMtEQ*Ia-wBdu$Lk0hv)MKkUYaEh(y6t%55cbWRi z6DTJs4a?67l^J|`_|18Beu;{}0t^tj2EMYi^TC<4b)mgG9z)rem)jy{ceVKw=3n&b zVm`U+;8tV$M-($o=#|QYMjb5w6SB5P;NPqpeRW?`{$6-%U(DD-24*4hn}c}C9VyNO z^$%z?Xu;V&*TL;>SJ9_%=S1hA1qK!zb(@@{+6^A$1K&JZ%y5Vg^)D3ccd_Exf;YTQv zukUkg@gFNcMIE)vy2PC?nQ!f`g^$(_mOrAc;zYLE84#S=RRelBNOP7>zk0=wn_KX*(}~_9ay=6z~gP0ogl(ky^cIM!%_`j6&l*#6ByI=6Y2jXHIlo zd1~w>7(camWAew+v15f7q@-c7i#^QWvX333NTR6j9vPD%za9a6;W{`pT}Zpjd4lx% zxX9Fs_A&>DIl7X+c#{3Z)f?TGPK1Cwk)*!frLw?xUnI*<(7sqR2u8H|Z~Cv0zjjz8 zSQErw9l}Xp9_0!S%s2@Ap5!{5v=)=qR$fDXeau;%kNy%f`N{l&dYrB+x&{tQzdcxT zZQV-H2j-F5nwIIz|GcZ%VmMNsrK@4d9xLnh@yz6?PJd0^GUak|kM|9mC(sUrvNfmB zXTmmwaOu(Y%e-z`tDX?u7w*G1U*fP2)>##Q!2MdISg{=VLvG6gS0>qd$2yCa?3N1;EmN?n*J1WhMWWW*D&-UkCQD zWBdi>Cl59{IQ=ar{UbrOgP=~WFv`Di8X3U7#}Y#wX`?CLKKp%Q9gzx_{@deB+Ze&= z>|N;JNCpq}3)FdcbT&PHTI5c)db;cPm*ZWk1v9xVYIn&EGW~|2W(1bPH~+-)vCYp=rqZS(jHM$jt%?_Cqzq&`?n^s1 zfI__n6SzJ)wQGA|GJv0wNZpvi6P-(!E{*s$1wYE2cTs-m%L_gV<3dlM1kS*3t12h) zG0hepAHV(O_>8gNHsTUmlnkoeY0$~EE?NN1Av@hGJ=!N7kwCtf+{YSDbkqy;nP@Bo zqe%Qz{YU$1NdS0rkt|(pNcc!MbIe!F4TF=GN_fNa7g=kFd664io}r~ZfVf|QgHsQ+ zXI1mZIN#PKTlllz8wW1{$w(tgmu~MH)a%fm?tzVXO_+P~t#gb6uFFOIf>Bc+$4ck^ zi=SSz=PJ`3yJgvPO-{0uy*+R2$MtyjrrMiBwrDkq{&{;L+?`?z&Ba%EqWKU9@kIUB zC`{lSFKyWrgnN*i9NXBbq4;f2+XT#fIQ_M~Qd%md!F#-OW;SJVlCf5070XH3vlo8p z#hxiN%RG@yk4IEo+@p4MWUx1D()3rT;c7J>$MFXDOaat-rlraaB;h4LdaZJu*mivQ zMoc&{E|?mpD*lar6LFDG~I9V|=5@u@rM|9acZ zThJ3Fei=7CcwZ{i=#QzJD1AQ9x0_+KQuy{lLQS}AJzCt#WFKi`h>-1WM`Vge&~Wu; z9G5)#{$vE|?#y!_=*5rY=I~_d9r_7;bSo=#i$^`k2bUr6t!UQ>T>Oe{v7&4dnrOly z5@C`~cT9q(*wD#qS%bF7UI>@nS3iT(VYIPRWue2-alDsuG>(_8q{VvrxhA(DQ49h5 zWw>Wb4cGUcz#4!5>&ojn(*{16u0V7?CE;Y@ikw$SdKaRk6``5FnD(Cv%CfAh?%MmhSq(>f%Stn>+C(;gPOQVmv30N!k3|)#1x>=B zVq5t0C4m`oX0U4k;OaN#w#Syx4toAfXlS_5R(nqblDOAMNBEIAs*Q8XtIDyisb~H! z)L_~Dtw13d_utErf*9^K`U7IKU!iU5(hjKF z3BfaKq~7Ic?y&aWth`R`)BTcxG^1A)MzhWHWThZ3FMywRhxmW@JC~j6v}H1rBINRH zpttk$Vop>dDwqkcZFB%aK_|j8Sk{vEeYrbG*i|!2jp;MO&tT!TEsLXW(f>(MmUv7W zFD|bK)^Q8C;=4ue$k`s7k5`MZW7^L&NYSo1{OVFN4z(6Z_VvDY*DCd6GgKLtZtT1u z-qXboJAItv%p<57t*p2Cd*(4kRjTzuPykMErOUplw55qPWp&j%Cm9FY>A(-$RjxXs zLtChW7unZX)XW|o=^kB(^6{mmJN)i@mORu5-Wg8X2*zD%DJ*rj!hI!{rQQq^=57{m zL^q0he6wXO4iK1h{}nl|!|ighoTau27SK@deQuYmK(@y^s; zoGJc%^;RF+qQY1xUx&@+ANp(mLfU(J*-;wKSE3`>Y=s8Y8;+oTSuePjoqm)&xd`{l z8Y*J1yIlrT%Qj3?`q}fnJjP`vHe~xa_eXRU7Ihn$<1uO}@`|7$T}w517 z!}^VI$I`F#OJx|RnzERD^g=B`h;DnDsYY+z$oDUX#nnLZT0kS3Z~cl#t~>ku*tOw+ zD8kCS11Ll;nI&xyu-y(r7GHq~9143f-fmuyK*X7w`tTHUH@Dy}8Ep1H0fkp`=(41! zmY&3K;F!!Ag~3;?f<#f&tZIz84>dAHYiIe_J(|_Qje9*vPzAl;DIQ2y*LL zEa1aeV3PC0YHefe9m0TXu0M}lS*R!vi0pQmst@0Xm}hN|TEJ$!apTg$hiAvKNyaa^ z!yu*~PkgtL@yX;FiEx95x`VsuNm9q;!aJ+Q!K9vnUioVlfYTQXATVu;Ldd? zjQ+!DfxTV%wV_lyKXtCG#eA?iu955qRak#tmw&c1%`n|A7?T_PX+b)R>DWk2$ML6< z^e^5vlbW2u`}Lv?#8RgkJb<;$0k*rl8KKX`EGYRM2GzV56P6yX`RZZ#b1^dK8Az(e zfg-p?b?~EyKkBtJb7jqg_)(6;Lm!sX?0wwg9z?3IkfrdFa0ZjqtUct&5K{CUUmW+3KZ z-rn&xwIcM;kYOXW#%?qaoiXkt^bQ^cH_AG~ytj)%o=cmWOKU*V(-O77D5`41@&6;BiW>|-K82C6^ zRU6ClJYjE=5jx4lwA0ZOmLpFwhqZRJXY2>}e*(Wa(OBy*uTNuOWj)ZWt4N{N**#d| zxppy0BLHDAk8^|iLGap1gmxNgcUmHf4PKi#|_NR z3Dfq8BEk7{sMysr&qpK&1WzsFZ7(_?fpG-|iU*8C3ua{f!|IExCB$jOXd0vzi<(J5ci9?Q`I%M}1RZB)#dd5!jEnR)KC->lN3U}Bg! zpGh$I?roZXFF2`5wJg~)b?-Aah27- zhx*a`JK%0O(s$Fk<4KNA{gr>|Hql;(iZFnOR`>-ou0>BJ;{t5KrW|g0dlyVY$BvG& zuKySq?rrPuJu@>MjXV1<^BE?x$sxHfUXk2NKWPDzYwWAddm*hh(w>6$%{e4zSb43% zl%F2ND6zrJ;z|+0in0gZm3;sV*Jq6W>K@OWa)*<{l^wN*8KVe#ZGoYasGoa>zKlj} z5R1Je9-X|H02ev)ZFimo-`-oRTAyZalt(778>l*BowMN7s~ytmH$IeciUe>IOUfmc zEI97=4v=Iy^R@!Z>gS%tgUr&LO1G{@)dc0PI(MfJdXhU-)Qe0(3bkq;7#1r=bcg)S z^;f&$5$I<3LNRZR-8%wlKt4s6;tUz!cnz@ zDCqCnw{I@pT_4N9s zykXT&k~^Jc?(LuFD|RZ8tI0;q^b1rKsvm~}s0yA)_5;q}%H>*L3eo-70B0I_J}WTM^)z})wJb40 z!{}?rdl^jly*1vi3Myb%-&?O{MFXqJn+6`trw3sHT!n!OveD@SAKo;X<8+X6!v~bY z`dxO?eUaJzgHX>~VOABJjK;#l=t6JYjsFpUcCwWhLdut6Sr5?z9M(;}fS*p~uEm6Q z#xeUjiqC?k(r?G2$u$rG=)I`)a}jRIwd9Vtf_jWyxPmZa<8l3K)PEI{KbeT9T7Z^$ z8fSiYrBj8TaW?dO>;DG=CFtdh&Fz@y&ypcirXVuVouEp`IlWd>ux&Ea6u-VL>%A$t ze-xgm9=`UAr%Z7&OtIW6Fj8;)M3F6;9uKZY@8w5&hDkHM| zBn2=i6;K8@UQItAI3o`VR)Lk@_bg+LFQ{jUqA!gz+&-xMH_PGLd>(_p#*le63WA0l zFxl!|N4rNCpa$}>X%EIydLph+@GjM7>@#N?glks7A)Q8Ct>v$P0>?e5Pgu8x-DCzR z%oEI=I~~XCXVu^Oj6=;G-iK4IJ+f>9J=RsL3%hCH4jf+EPfGuee9oea^LZ-|*s8%5 zE@Y&LKy?W!0gHiJ{B9a1K`t`#3nKF{4lE()rG(!Zdde@qh!KJRf$HbFEAyTemz2B; z!1{q_EmYu13j4D~MQMA~n`6&OdGX=``@P59VU)AcOD=LOeoO~*dYr6($< zyY!rE0c3u_{=Lz7D3+k+1gru_tm;0d-_x84q&V`0)cz&Zv!Cm!Y$NZ;do~s4;Rp&$LQ=g)RNJVP!AGu7>U_D;3TV?N0O3LjA14z6f?X(<82YC zy&#E6K>E97W41wg3kLzFL$llZwxCRHXunZ_Tq4b6Htl}t4X9pu;v$luxvioT(En{M zeaysa*rsk#oU%?6L5A0RpbkRw=(dF@dm4`aBq*>+KmPSj za_mVaP(o1^lKv2tKq~=x&7^vH6qM$nG#k7-rxtCs^`x?d^28Qo-CFIZj3|J6%VcHA zcXUjlAemeX9!1l41UY{4zc~00cyT5O*p=;K+%v|H;SWcK@R?tw-y0qVAa{JiAa6_nt&B81j5?Z1n)60qMeo%-@z6eTDfP_0J&Ws%(vcf9CO z4Oiq$N~M0wZ)VbcKYk#2u(FN$S2M1_RXjKI-Ac2~29v>YUxphw6N8I;b%sw6coL?7 zz%l&4bmBQb54dlSAdwDb<4mwDrXw>2Z(Gui6Ug~x;GZj95bCLb3eJG(vDSmU3H z@hm0hEhw`Z%&0!jLtO{KhisNo;Pg}uTJiko0J09S|8RmNNC5*{b9^|HbpH)q zL0&*mfWuq%!PNx{YxvA+EBs3{-VYK8|J>ixJt5-L{Ke)gohZVzj)GoGN!0v&t{-z< zD4k#`)UKBlg(bS0f>r=MlB!ndHfHVzRNmI7G%h98~0;4=696%eI3jRNCjqdts zY3ZK_P-qcyL2Ib7pAC@C925Zito6>2EQ%r~yxeu8ADA=MLE4Y>WbWy3#OX+7F<| zD!_YXI+sq&BpoKzCN^`sKr)kA4M+4W@&}$rxtv-~BQZbZN9RDQQ(gZ%WMviruJJ&2 z5XPEN#vWla;@K5y-+xKp*pg# z^wmaOG_RX%S`T(!1_6Jyx5gsXRAdhUsD1$H*)dKnkE}8_Fndjn4J}M2kI@i`dz;a9 zC4=mro3aHvLD5LNZsIKoPJ5D7LPz&%&8j#LV@PS3gDOzh&R30=w^11v*fWcSNFwQN zjk?!no9z}hoJrmFZ)6nl&5y!K8N++%zHh^7@lF#^VM#h(0z`7$P&1rx2((Xrk@RP7 zXa?L`bG2v7Me0WlI)ZWu>EtjYA$=pxiteIbRP2j`%)da)O( zX)3^-*R;1l(4gr2r&Ew~+%~e%_W*paRq0MOa_U554?aIjs_{)~$I0+?T|tMZ`;fWU zL+R)ete5r%$sNKh7m)UB;o(@bEn#I$AXd;z8}{IF-&`7RWyX1Bo4$5H+5xQzh)sJ7 z3`bVNr3%d0-0l1RC@=3$HaA0kbSHa~0G+Uy(AMig=pDUC6*j{ud?APyAQVL{LYVrF z^xxoi)NER;YPQJB>2NL`#eIS)ZF}wlby$la>xKiL-+$v-H)T?&z2gP4A>&QF`0%&^ z%l&EaM+YxO$V-3sZeAS7oq?{vrAyGbO$ClkJrV>tr`m%>4ORMQZm3`&&#D=fdy4mc!sSSGuUP*CsOYKjTfWk00G<>f- zEs_^UmmbwylfZu$QuM-*yc2_v@7$FwtVv5_5;xT$-!2HK7y&F5_Q|e}^7m_PUHzG0 z6&IzYun-JF!cpyhVQA}NvO|)J(e!D+)Q%2pR$i;IJQ%>l zHfOInPJ=Z%VzWS9qN1GD|kZJuG$L>!)1vVk~0k(FH-BlP0Y(dA84skI@prfbmTcHFKjj+Dun_}6*^c-%W{>(g zs&%70p8R-Uf*2{Q-&*f{2F0BxHFDm9RGwin3Z(Y{DeJZ7&^cULo}4@V*GK{rzFBRJmbP&LNx|5scvA)O78lxap{}(UV)*pkv!`yPt^8sy_V-X4zfHW- zVdyAF*v6wfjKr33luTMB%6XQq!~4--yAqJ=lQLCc-gPatnXUxC91oYAK*=ZcI0@A+ zjAOtp7^_8|C%gF=ZAXEsd^){^;2Xq-w9QA4{Tuc=Px-cRMuY^EeLW=O8Aw0Iy>`9A z#l8X#m(khIyvqL;Hzu;Bph{aDmYBjg1e3X|aNbfyXw1P}X-Y#v3dF?;!2e+{@dz)t zq_1GWi30G8>x_s9Y#xA;WGv4Lgioko%0?``JAlg1e`Ci90Be9Rh?l)#R z464ZybY+KXrU$7cT$n45N^B?$dkGY?rj(1*k#3tM%fSi<$~1okFdBN%|mcKQ?!=R4!ax=sp_wT->VLY#GN4}nQbn1bk91p z#LKB|JFkg`K|v`&Ws$h+>f34Wi(vI-V@@siGOm&OEj8Myp)Txio{v&9Md)GDDIkIP zriAye@;E#5R69k2P9FwQt08gOQ~Hlq&)ECq@D>t$l3D1{dk{l}61pkOGwErKV8PBA zKRplcl=gngRpvno|A3X%b{vfgA`8-|RR<|Jcl5{@-HAj%72rJZ-um+e{;k;A{-=lZ zX?IObY&ppEgatu#q$AkCptAU9{@Uf97~?qp`q}^y3o^Ctr$0K`$5=!n_8K%IAh?_a z?oii{K@`$!oi0 zltw)|G`D1i=(3BG<}PfO08WsmlJTy{6kQ^v0lRl_hg)C~cel@=uTu&i>C+;B{tCd+ zWvbQjC-_K+y-@MYxEQx!Y$W`^sc+M61v8Hs1(|262piP|=SF9t2lEKJ4SHb#jfK%- zJ?4P}K3=}6PJ7Tjcd{@X_%H|`)DM3CV*>al1M1Fnxwp?@ zfg#et+m+u*t~Sd5U=xe|8#4;Egdl#B8MXaE5Z@w3a;BEjhs8R&ryxALnGl*!Hu}-R zoGFHN05ClLEuJkiaA@=`%l=vSx6&o_yysxH?(OlAB{${uU{*ALiEg<}RyUs?I4tir zvcZ~Wc<=1QdlgidJS6NDFz^F0sf$OV)U%e*@7dBW*DX8SXkq#u2TCT&PlTCt8VVs= zlEhVF0?Q?UT3cbgwb~>1P)3zfwwotq|9O=z00A}l?s%L98+G3ZUm%)TvY0H2;581& zqVo`@1VYuL&&+@-3bR*2E_z+pK2z#Z3~A#epDSO z*Rr>7(V`gx8`0&MNlm@O081mD23fzJv*KWu+gju)<6kAw8899j-!F4!u7;=$K3ZIR zuz(7XJf=F;V?_aTGBGJnd{qwc%6mv@XFk%VpV5Y`b*D0i^$D=wi_(9XI$3!Y^!e1s z6-bR+8B-2<3%HKUJm>2U+MU4ahHN7_^~ocW)EpvCxCa#USEM|JtTexn0CH<#r=P9~ zW>B*DZ^;;|6NlTCIXY7I+<&#{EK&z2CCLAkxVtGY!Xe|Yk8XwLJ^jop^N^1|KiJ1h zK0)H{@J0f7FKm|i8W&`r^(62Ci`B@;V2sY;E8^wkoe!d6J(!$V&~^8?hTX(8jrueZ!%vspvV&>39)*(ltH#ch8pC&z7A~V2h=2Ej*tbPb z@4b$tB1mapu$0w7hsx=@Bsc3c5{H!!6Hv`iuxldZCMy0f;OaDfo|7$zv;9x%aeASM zyu7Hua+2}6n?<}j~*j97%lP7ypAJ6i3zZ~E9CPoS_7T=ebL zQer&Cb`Um!m}%?_fo8DOufZ{9!*FZyKZOoOHbLL;TL%~~g~~6$bfYU&h)%=t9+{y; zIOQu&_tbqaI+fv*D*R?Vb6t!x-fy-ko|#F6Ji<}aEe}kxAZPFUgDfzmk6`dgFZkG7 zq44v)b^!DJ-mD$0vHb!7;TldIg&vmoZL32=MA7*V#)Y@8e<+7PpG%sL0<2zejvri) z(^vKzc?mrcz!&+cy#d#q0__)IQpxR7eIM3Rdm0!+RN@K(Xf1z)o%ceaUim)}I`;op zE`fMn=;6~$LTv;)KL>>rt>)vT-U^;LDUdS!0wPNSNKg?ufItyGUC?wc0T^ERlBF8R zxWZXY@DM>X?3HFve&fstUSvZsd3CHQz}OtV_kc~_(q5n7pF-QWZ)eG1sC2HT`vWLa zWJBY1w+MQtED1Z_TlO()xXd_iRRBOgKK&nsb`D9+Sv(tyFT`CK^UE_$1_}C3AQLd{ z_TN3Tg?2dreR)^*lb!(5awY${*k#};u(bbGkyQ>6BMErp$0U2E=XM~3Vio_pGs#D} z&$1wdbQqenjYXySUUF$xnN~=&|GGstx#7uKkVbllUqP{FM|uR(H0xjADpepz%DjEF zr=u@4_oA9EJr;}hdqNK10}r(imQs`iFc( zAA|oeq2fOxJ%vStyqJu9pq}{REAL?S*CIo+KfF1K?vGMtZF5<(V7=36(wewSM@OgY zD=H~S&Pcx_f~7*c$R_%-uxzEE<_+B2Eh$m6n3o#H7D77Gb4@oy` z(sj%^5J4r!CqfTs)7Q3g@&0e(t>;c+~!ElI;bSVt&jk&5txl6LPbd>5Hxn zW!Tg5wN4(WsvIGG3Eq{jEDZ@Yi{#AJG6D2XW5FCYD1;~zzlHGawtPR80D!9b|8^SO zRW6AAI%RE{ErgV_vtTYa3GW@zcKa1+=riiKF2jM8F(V$nl{Cy)2Tn!Og*>#~&IUc8 z_K`M}`s=~F%l#UgaLpm+ij^a8KAE$e;+T-|$;ZkOzC9F`4UY8UJA@a6w3td}yuL)m z!tNcSj^q9@ms2|5nb8(AOO^vBN+}z7Gr4K%7gSwdtEro6EX)(R^oKdliYCkrZ+)2r zJyM%kg7=ue!Jo-)%ZldSroLqqo_39+(8B_quaD5X5)U?FO&{*jYvk5RTiyUrj(y{H zTIxk7v~!J}niXo7B@IG>AqPeyFYM*wQCKytlpc#fPy=_zdg5s>pfu?H&c59ebVaQXoPkXtok zl`1wo=`~5{YU&S^{c5p}FAYcL>KPhC}Xl z6AtUW8pqN0%n@A}6W&?_|O5fa*;9urkbNPDj z5ywGVqi4tjcIXc-AW$#do@hcflG|)diV?^wzBC>h#cs1C_Sffuny*H)Sk^*J)a&QD zpJ=WU+nfH&i1d~fq%Y$xh1qPdri)JHJ%WF5)3a?nB__~9p&_kq)D5=bus3no!>Z$iI< zletoM`5O4e1pgyo%lHx6pM3-5Is|YDJs)rnSetb3Y64(J2&-v#bpkn24RJPpQ9b&r zb~KQ4ns6n^ptFd&vwgzPHzAIFcDzy=3eL_D047b!mTNQ!YJ^#ojYWYqJ~gT7x`)dE z#1`HICV0KDky`TnIb++WJ>QV7Ws^S5JpU)&T2+68@)rE2ZH&_TfV6)vL&4S#jVyM0$z`+3#>)S8-%d(J{4#jZG2*8>Vufk1*MQHy-2U_lp3Qdfz% zuY!DIo9;SaNxqy3FP*GACuQ^Ldw}FIr~ptgMg$=R=M+M$5wj$Ahzis zL@lX}OCa85jJ%39zv};UX9dbHv*k}7Zxiv--fH=p5p1yh;b1k1F&8k6eBWk4&Ql^H zAtDpo8yb2WwvSNKaT^=$ZM^Uo&~Osb5x8KQ!9p>-5i$Ll+nL z{jhF9Ke)Q^jNk*R%JQ6BU1uKEa8X;B=UUtx>Gh&BZ{8H%?uIv$4Hdmd_2J={y;>lD z^3s98TZYS~&LfpP4yjnc0=MMtOsEN>NGbt-NNWZEclQKZE1J6&6%`^;7$V?X&$5nq z$_bO;gkX*T!@Js`3>2hbD#HXBMRgB;esO_xkXY{W38)DQs5AKV4I~01wjR~+bik_| z%k;N>9x$KiD$@cmCfL$`it85HrSD&27C>@nBb7FCPz3$nOBIo5k&e~Pef#d%{~`z# zVIJREV}6Ix`HTqj6S}?-0l?+$2>eFkfCF~r+6161ll6W$?ZNM{6fL}=Y)42Hb8`12 zCaUsXfC94Iv9mUW&x`WG7BZJ5O!dWEu*%`sb?Zl;~>H!f;Z*0Yha|dQ32=%Dx^#i zRYos2QRYt(QnC~QI^SFV@V2?>kA~(xD8J>v+!I2UT*tdT%#+Ow(af%)LNjnYg2_eo zTHNzSc^CuBGNYr>UJ-9vDOKK$T62xW&wzmX!1IAPy4_`tTIl2Lb-s~)XK*IrIj zkQle-GLbD+2gS_FAO7?XOW;nE*%N0TA02q-U21@t1=?Ni&2Rkq37CoL7RS`Ts7Fe( zWyIXn)P8~2dD?LDd5pT9#>Q^K4Hr7}tuI>$^Dr+J$p`V_v9{v4u>@;}~T zh-f+p42N)yU1tg#-!`^RXu%e*^FC+;#&g>g;vOL#qhX@2EgAj@G2O@RhLoEDJ)@l% zmV3q;QKfme6``_fer3z^e@!@A5aiQrTCLD253ukaBFWnt>elpIH$>5rGL7b6{%uoE?4=mw}j>r7A=jX1dG=j#ce!sGYJQ zIsLE#BX<~8*>y^ZMgnXs3yaC-kr3P#SRw2!2s5CU9u+reSg|=>J-%l~?I!ek%HRFS76UP!U;W<9fOUr8CzQ2MpXo3A=)(By5% z^GeD91{r%OwKkz=x>TNei7|X?+jwCeK{D%!9muH}Dao8ga zb+)7GC%O@QG_9_tC!7t}2t(Y5GohC7zSKGaBonm}(rMfH=2^r(dcQLRMkIfj;R(R@ zbBC`wqmXYSxZLtn+Fp#Ouzw@;HbehFwZtronE5&8SNp)E$%f_LEnA6-hz#Z5 zC2|RhozMP1!mc|W%eD>kyu6{_kSLLiB!n^|5~-wQugp|db_zvSdudZDk&-=9_H4;c zWra{kk&%)j^&J<_L+_~X`{Vn)zmn&EuKT>sah%6_obbF+xXvGdJuICJI)6Jhw#B+g z4Jj|P)EshwzOr1`Q>J~70^y~oPN2>3(%5p|a_39TC8XZpxbd4yjC90G$a}a>duHL73z-fJlW)6eSz6jV zU&(8e_(z)7%3}%$xHjXX5^%LQtM;L#VyD*oYnl)P3*nrm4(kk0M#(0DGgr+l&vL}h zk+R~2FxwZOj*e>!o3E@qcUr~Uc0F)@rQ}vVPtfNGmDg^6A0f;qZ$QTJqyg#d*s2Ce zxkm^Tw~BD9c?ppYb&Q?1b3TZe;=A^2r+VHMY+q7-jHJw6;bDV5tWew?C{8PKIQF9e z{YAobd<`B|;qz0m$uM5VKJLJfG=-`5lS&xmRKp~}jf#;T4i zW5&pY;I6bDyz$RNjX1O6FD=6b7ajGU8nhTp)2FubjeNEa9zNAEywT(GDDIKiN`FvY zWCVu6NHhGxM@*uDJqU`F4>4p@)cve`UNKgW$(F)IsBj9_)=)#gd zS;+E>L1Hk6d=Fl4uL~Vo0^_49hL4V0k#4y1=Y|^-DJhz_r4bu|Hnny~Xb};It4JK0 zlyC7+uiN|S3*EHG=k`I`+!(%u`OYxLnn=j_@8&$y>=gK^4}D1?wBwG?E5f{JI~3Yl z?r$a2gsA)q%SJnR@N@pXB>)K7OZ%_8`48T!Q*0(Y@iS{??sOb9Q2@d8+!o(B9?B!Z z0ZcYLwDf+N{=$Rs0*D648-s;Z))XWyJ$uJEEBz$1rB-xk0kYN>MAPMK~RvbpFG_+lG zw7ruM0R83SuYg+9FLDnKGwf^rU9f*ND7Q*O4(ciHe%lr-_%+`%N9fEjB_iPaUW|uK zdx~tK#>&3(GH0pNC{YZVe3`1Qj1Y01i>Xp4vd+!(_5W}3F~o=BNjV$)(-u}69jbGR zn=nn)4=f7>nt);vIaY%?*?`|jzPud`zY>NfCop<^PVcuA0zJp6In%qYW4H#LkJkXT zk3mP^Aq|u5Y9a*mr%~JM zQ#L_>I8{Bw(K$n(&3LJSE^^N}7i%2x1CeBllo)d@ANY;mx8`YNm}cc`EFUy4*Z3^A z;vE5=L|MpO$NP*X*GJh734*HDS11T0MgI#trb`(bBf>M<0#MlM$t*!V}N9{~mTHTVEGTJQKyg=m5AOYK zqsWeq&m9XLOkR<%^qtS&myv*8B&`bLXesoYzq@*M*!gAvVupVO5x5kk^jwm~zjeG9l(aPM?~C<$SgP>h`HwDI6hQBlE7b-GzDd!^anJ-=N3*%kdLq#4OPsP=z&DF5L-3c6Z!<-8pI%GkPTOZ+xgs zU%ug~Em*N`mVXaAc)}HqOcUQcQks$A5=4rD@V??6EOIj*-SVR+z*gJYo8~G1_MWYM zK}^Ur*+gjN<9~sX79v1{(UP6WFht@$5`7KQ@^S#6x^PP_HCJ$RdMQ$P5!pfBBhgCK z0|SRIyl!$87fd}=MBqEj8l6HgitYvmy&Qpy3ykb3{V&i7BYu3dN820igJ|u`-<+|L z@ktgIhJ8DEEk61`F$WjIWp<@O#7rH*WJ@J!*&JWkcFhY*nyhZaT|NR2C=~DpBhl^S z=SdHDacxKy;F7fXGQ?wiPW~pEgw9Iq^|V2ifJ1H61*(8g)^_nFc@`-^PQmw0d8s~z za}nj|bw>&9G$2AJ_nbi^mMrnMj`evz-{|)fQHpkYh_;>Rg8S~De9-qEL8u~%QBkwO zA8YqU!$Ca-KpTs<=$N$s{=|?|V~cAc+R+uFeH&8q1tadJVl9z|e<7U6V%~9?Mk2ii zwC6P0EWiWU&D8?5ZK4D*vhc|L7u&)~wyDa=o&{vE9a9*m$uL@+_^S4kGErnY5pVLp zIigSq`0=_j`l&qNa8f7cHXH*47p?yNeCPPrvtdbd=}%XDkrD^67r$ zsX1W1eNkSjIc<)l#Tm>MZg6)`CEMTj`T12oo9D+Ls5+lQMB35EE(cR-t#WEzbu^#r zS5!E{NN<+1rVi{-8yDg&vLR6^n@God^)<)!z6Sy4LPv)UH!|{!P|B3<@8A9_QWQGc zSEANQOlqbF)-oJFaY7gZ_=fz+*UOulniSrx5EN8fxpHOVa+N>AbU>K<`uQRI{J0}l z1$Y_ah4Qidi6hGV($de^dzXq(m>d|0R6ci1dW5pCu~P_ykI_rG2(q)2lc*|HG8L z*gG?@Iou@cuGs?(e$-e#efm_|u3|3HLQcLALH&@xa7JvPvH^ThY+k#&9xdFHy165} zR?L|^vA=I2uolPr&p2mmG5PR8W|X~q_j(L=Y>11GchnV8P-ys4?y+Udmf0^M7@o`H z;-#!9AtiMY9sCViT3X?p-MxQx2hH&`Tj=J|_HlpUc1FO1LJRf{1brU;29c)=nCcIo zR?C}fNtOIpl?a0OA^WO9gIS*-v-_>CP)!R|tX(7+$Cai3{eP;vpp`9ea%OZ&y?dT; zq_*ReiVEk{x~3-cZQHkF!I*LIyz_$fWU-go=#ElHkS$KOiq!D%&C9{gnUmA3_wV1o zBpZ%X>w zAuUib_$xke4yV=FtHI%6d2MS~$iSa}-2Nx^IA1i^V%B4$v2m!Op`on8g_M+(hmRh? zG9pl^*WP2)QCBi@oP<+eR! z+6%Zo8m==(-=C)9{m%z(SPPTW+RQzhy0`*M;8z8G`?e2jNVs%#bg-*N+JEn!J#>cy z+3(I(aE}zYZU2OinU!_@qe{k_W9P`aTZjWV>0HFF_N3S?-~3;{Suiiujgx-J9ouqG zp`UH3bj`;>>rfNoNMcen?bW>(A82$+*#H~;2KK`ku6MQFT1%W{eK@UzqKa0 zOf|N+s8r7pq{vv)Q*Gq_;>iw`a;nV3?Ym-bEgOgj1_%ot;wlZH(|WPf$KGOEnSOz8<6 zP1&>$oIEG$H-XZOtNa7W>d6g$Z4^rPS})GP=`&{R4ysLMSdSm@KA5wsa_^f8Zavn= zvDGeq7k$J@DYN2hYj#Gcs}_H1zz=^ELP@+T{@*srgBTG5O@|hSmrp6wgOF8M^*aqb zQWpijl#!9qUoBWjBY?)8dg{y8*1}~E4F0yP{HM3vunsTS@>1B81ixj_<;(N*u6H19 z=Z+DE#+0RD)`jUox3HPiE&h^kor$5L1{Td+2nms6V&mdkgk*;eH+cBqwpu3H)npY4 zfGgv!`IyRxdRSb%e5>q6+Kp+Ubhnn*Zs_gyC0Dueoru-%Ce)i1u?T%!fJS*oZ#!Nr;P7f z0-K!6+F+5hJMLcNrAu>dsI~K>$7_%u%5E)dbmXnzT%RkR>;xZIH#e>Yx|D)nG%`qw5 zE_(IgNc7#ick5X4^73xtWq*s#=IBonG81X;WAf~ZxDy}0(Zj>zCcxj}Y+K!-k!tSu^8)&6Er(kJ3Re!*7?72~mZB6vL*~GPL^? z_>tKn%Y8N8iJdGTAD`<%4P|BJa5sV7@7>{;X0}pd+#;i*)R40#=jjRZ^Q!__@B7rV zjUF)}l25Ivz%LhmQVTn5B#s?B7CQ5hAN4o4snQQwB0^%mtJdo}pRVS{jpx7!SpOSW zNOq0cHFNsVTo=RDO{#~^867nYKT~liFdC*H5z=1Z#Hf93r6?Kz%l7yB`}@-gw1rXv zFmu@fS>v;)1m^XeK7RZh;KvgyoHA6_vuI)4tOYEh*2u9x7}0xgKvOHx72>w&2k`S?&l>dB=>6ruFu$A)c` zKoJfi`4C84xMGDVc-dCJ&i?}MV2h1+#{3&wXfL$rFs1uuJr;+yKm5F43sAMQZEe;( zRTb4tM-gKUtaXCAyB$~T`;v<8?}xIx-NV^mzU=uhIGAQH4)a?_=~gm7)N1A1D<`^m zarG$>{#Ce@yb{r1)}FHI1|71HMLpIJ6GV+0uqe6%+|~1#tNbu9P+e#6OUHZz5yQS& z&PSb=O*r#MYD-p?l$-%6*zAU{udgQd+Ce#DeacS=kXSlUm6`x)ph1=O^Msu@8{uGpBOVxU@4;8up zv$lspK|#gCUtyubD_1uAYe{p^-swLcxs8sv1y%cvlc(xTK~(d=DywWPNY77Nr>?$n z)25Rz%wiVIA!)VRl^ui8u>;j0&~?9;mX$Tc2J=k?l*U~qugRV`GxUMNRABy(wx`+`V;5JJBKu*8M*fOY&m4K2Glt zIRTns%p=KHX=&+M6ihziwWW{XSn-bci%`G=ZFZewwPS_rEW&WER>ExLho@H#9wowpQ!lHifC92_+Rd9cOAu*O!uMdyhkC5?vSoTxcmJP{ z)Yc7`Z0UEzbTSVd5F#$7w4{X1)5pTk1Z&=QZp+Qgl=ot4Fd{i^c36d4P<*@?aXJI8 zu4^JcOy+-k5BM;-pfT$K-+U}0VoUq9=vh>AbCyi?9d;F}`3~^dv5O4Fti-^r2N3k1 z;0W4vrCD7wNuqP#%l53L{z>K>-Jpt3pLUCiizn2p<&We6t9kwE)vM1|bPZeZvtyNE zw|7vwW#ai}c7qPaN+%b5%5gda3Q_U#qIhiVL3BaHv>9{xyLZ=P^VW3rPA-}Q4A`1`C;) znKQ1QyUm_@S~d9Sz>;XcM3M?ROX?aLE`(TW9=o&D;>8Z`tA@HBg9K3m&q#{t<^93T zwChPrqG^eP{cPOdley|oXx6C8!GK5{Z0!rz6Yd>nV6EiYy%2pL=lii21g-txNbBTn z*Y+^Qa@?)$`uO-F=%_pQ=d$GN5~wx|x_@7d`LDlfTW%HPf?FX0(Y>>{GEP&_(I`uz zMYeuT3YhecBE)w>95Ypt{_{!Q?eUp?d84$XoWa6M_0a2Q&!2Y!q4!KS%KvT= zPRGN``+ksXN%c1zX=UO1zJ}{80`M_4*}L7`+}dS(0|V*2Z*HyRVv3zsh2SEIYCHtw zQwyv~aJsj+nYOI>6c^DgB5Rfh>kGddHI<=W5rdm3e&A?9JD`8KZ8{2B=IJ9OHu>B! zvlmNA$!j|o?)&NyKIXf3FZcBdtRs%GSfG`A4I#6>$-rc@o~LK}&RO;-9rFt>0vR-g zQrRn(a@)U_&&I&Elnp}hxr-O=D_|?az;C&R{3;GnKe^D>q z;KbCsYG~A$ewd)2dU|@{CpsnOCja1e=wq29VYUzpU*hB{K!~%&^{$+MjRsg16;o_& zZKVUg?;{B#^1bW#Ueq-C8OADOpTM3=!P9ALhOn%C{^!m_fnS28#< zzi-Jm2QSLBr;wG2iL5&Nko^iXAmo<^9%D3&^m}xi)8os)R+o#!Mlr>s30;x9zs9_n zYOt{~TnF0(Cmd#56h-W4oc27)B}?+s)HtIIL^2Z2cVw|Gy@D5frYfOBQTjLr?E4YVr+gYWo4-h84KY+pR-x zQg(k;mgA5qhB}?|lf1iYjs@n*xF!bsYU}7+#9}wAuxJ4H(yq-4JL;3egYE71P+yV5 z@xYNPE4)!MPu|#s$uiU7XzVA1Ruf#&)557)*bLhQI8eMvlu)5~ap101gA09h*>5@Z!5H~aRi(Zz{ z)zcFoPy?cC?dYv*3l{0c+ySx1jMR1APyBv;W9zV^&sAAdoeI(4q{s>07r(8Qv*Ip} zSp^wQ)#H0F7zPIi7s|_LR%IBqZD0&H%W!_@TprcBhzXgtUdz6ZT5*YqvXq{jgu8bQ zae1$cx6?8^YkQ(OchrZe7evs;Fd%NudBL3*3%^DGx-Ov$x`mp}Er;9t=ZGAL$uNq6kAf+vdG#mDImpL>zCDu(YdeCE`3TlWu=t?*f9m+MiR-%XP1Mt z1)Y(m6k=3lg{fD6OVa%H`JM#CB&d3OZp1I|WYKcGI+ymcSenrVRx%zxe!K&4c5!LZ zw?{dZ**y)Z=f8ScT1q43v$EOz* zIu1grpah<~x0OwXx(HSEJfpOX%=qTzo$czq`Df3bE#@)92#ko8l~tn;E&r!w0h5lF z0mCj?`Fs7FC%3sOtc}FmKx|kS&YM6vFQ%}e=%s-9y_?2}a<1z(9Zt(twX(X_@#an4 zij{c!My(b)5&AJ!eVG_yb+-wHo(f4-91xO`9RZZBv13tgx!Bb z>E7KBysLJ_X_hSSchAIrCT5kS>+Z(wqzuj_vmYz3@|LsPqw2TJ$m$w zP8AdF*yMtcg+60SFGS(dNLGc3qTap;qT7zC#uF_JOupmPV7RrWENL;C+py*!*#*+j z*j?{Y0&mdJVB@^jp;p9=ucOqS{B)Nk1@<+^^SH0237BjPmoMj1I6pm>!&2V0d9jH0 z)oQPJzRj0pcbxk$e=?H3VK1qy3_)wbv|wL$hUk#{<&jkp@^06@eEH%qm9zZ&*}}=Q zy^xmv>DdS(2^~a36O%36Tf!-c_dOY!T-2%}y-2e}#NpQM6RN=BuL6UO&t}SKI#ghK zKDPA;=^(*9)SSBU`QzF3eB;T|)S;jomze^()_tZ7`8TWOhWu8+XTNLCzB6{&X3@W% ziW*Uad~hHiUrol>tGeV$oZ?d!>z3;MgF+!S_iGft2gR@3GJF>zQSCqivyHvIroVr| z?ZgS3ba%RNPK8g+6+MC+kS(n>H8rwXl0*5vfaA;02&_?fQER)3e#tnRU1Y>ibH$`) zLoc%YaIX#MmxW+RvK-pSzYC}hq+>aj7)EpFY^m|2U9c|SE+6*xy0_P*_BQtn`U%)x zaaW@mzqq)jnwr`|l=^iB%L*7NAt51Y+aJ$-0nSNmf9+vOR#sMSv__y^ps%)Ojl`v3 zbE=6K8UL*Z8%{dY=dNB|QaIM@_M1Kz6Rm_`r-fE>sNE>Ms~%J68QzPM9T_DkZx>2Q z=_t7X5U_>B=&U(&eoAKFi@3jj$V{qLf^Cd`<{aV*2e5)%tG#`D;i9Q;Kl#3>&m6e{ zKHo1#F~`(D%khzp7e5AXJLQxjn1LR0}n9PlqTa!J@vY-=8g%evk_zO?f+H* zLizm+EL`sg-}T&Eo5HpoY^=TVBx~~W|I>^r$Y$>5(KX&QkA<8mi`>P`7mi%V10OK1 z`u=76UJQWr^xgn2E)DHC0w_ExFE4*J_KcdLGJRX$2IhvGS}#WYqeE@0BUcY%CFK7z ziA!r>5-UCjNz$G!NSwT60)QMlae_ldMa72Aod-FL>z&#qpC(H9va)jn1MVm~9zC8( zDcc9I;PB{aDNdUOEBB<1FLUPQbv~kf3GZwCm(CL(z|0&v{R9>9EytjP2zV}+$o}Ei zukM*Er(6HB?YW5DPTG;F9_pRBVAT@jyTu!BcZa+a5D+NhZ{xyyd%5k3X@?vI z4Wi;dv>rWr^!nX9QL&?(Y;1w&=QAKW*`n)VVwVHni47KNp zI29$i-RaIR^szmWAK{&2Xb~3;Yxt+V(9w61#l!o2)gM#eT-$vDwCU^Wy4xP=KDdH2 z&FT5A;OQxsqXh=saEAM4HEXHn$F(De_rUO$xaRPO4`-qLb!uXCsoT_7!1k{K}Bs~B)Y~zc7k5^hX2zvE5Kx8tyOrBna6wLjb z@7g1@L;I6*=+L3!(%YVv-A3JF9VLeX6OfmA56!ppt7qW_-&qpfzv=3S8p(h&@W)6w z{m5Il)ImuV1}Q!#w%>5*&3TY~H7zVGgw{vSpxRvp{{XZ`k0~aNff4sS<3>wPlv*!A zY<`mw(s!X`15aXI4DI2f2x?jUE+6@Gy7Algb|KQQM}a%XQn_5MO$CmD9M!gaK;urPP$=DZdF$)*|3VI3VE7IKG2z9W^r{ixkTh#JTmbX4<8 zox%S~Ln~gf)%jz)Hj!vK2<7YZd*@dBn?Kz2lUw*(qWY2~s==3!O`B70( zb*!~XY4>%WZog;9hE8P21Xv&EC5W|E)$R$}zn{VlxvcQjStubl zK)i`ZWo`)dW39b|z*aArE|tfhot@p7jfgK*IQp{xWM;GbF^%A(d-#KBF6if{BR(t? zwpHJ#V@zw%YA+%?*l{^MyE!VCV zl^j~*ON2|o|63N|(_2-XYuByYfVJ!#DW~e#9dhVieZF;N=QIk_H*?kSz!YsalbEao z&HS+rj68%ugLkcG1Bdm)9T+;g^PozE&W9B?PNoI@=j7s2=XJS zKC~+sXeL)wOX-&Sz&c-XA+djlZ)0PGRDoB+%tOICjI5Wv8CMyFA~_c?St6_LIUjRE z8OEINu?z_yPgAVfaoX?or;x4;25~fzk$FAC^pXxl)tL*Pr|bXH`6r9w_sb237*P>q z0wSc2y?%5eUC}UQv&lU#1Sbw}9Vey+ZN#u%XYLnr47hg-0b#g)P}Vaw6~!p|8PI{| zwT3-7!g>*8yzFB2G?s~2(yXDXeDhXI;vjs)4imrUTJojf)^Q(q3nv5d#Yg%R(8MJ5{#@g@l9`Eh-lKxRi-P zMW0R;xQOanT1w!an<&ra1Plh`G~;TWz;<98C4dZtB_xunzPjZP8HeG*tnt~dPYuit zR|9?c-R|vYOv9kJV(aG5?Ru0y{;UG%f&B zRvsStV(T`pqtw5(V~dTAJ%bGQ7>lTtZ@Rh(I3=31Q)N$R!e8`Y_RU7PHFw zzsE#Xi}K-bbL;)@m{Gs9dte|-cbv7a<*T(IiM)Gy;|Pivg-DrOYl|#kCY9+6cDL`L z9~!%Ue=8D}^vim!Jl&&f{7x(MMDu;~0qh>UrCUXQcbw-;zLlGy7cIa%bEa3F@N@YI z+maL=08l^g`e#HOr}|-R>NEsJzXM}0)ph!9Wt2RfmJsiY=~Jhgb&D?GxOb(WtCw7%N=kX^^odK z1%$vc2B0Z$5w%Pi2|t>vJNx^kFr;xF$|Z`m5vK2BN`Dn?=_vK+PIt*n2D=8`HY{U} z(ter$nPtX|3rOQ$xZ538FZxQF-L2Q2-X3E}yK|>Uxib$)0crdd+AX;xin0Zi>%}BT z|J--x4BK8z64(s1-GfVwONyZ-OYcP@)p`LzhmK?R^OtQq2t6|+S19rS4sK@p#*fnS z35__#Z@q?qCwf5-A(U(pwvKTK<4pqS{4Kv4cAedQ6~akXru}YbmGO2qn3CbFo8mb1 zYX2~>o3WqpNkFcYATAVJE&sfim!IDWIqG1d$r!~)X{QCgk4$;+=EXaDx9t0HC?k&O z>B2ub?@QS=WtjhrdDVvWF)W#A{;W4J(NLbO=qZGKr+3eiQ~P~Q-1&ot4uwUEo2gFT zrR}SN($b_!-@T?LHbALh#F5H{k=07z^F}g=O$Eh9tb1zf+jIg(4509P5&=ET?k`!I zO$kC5;tWFLT-Jnl$*^vrnpJxTZGOXo0VU9iJnEg(G?x`9GaV#Fjn%8^?FO#!Gi?}Lm!o0i67VKoi5s~sp=N##zIv?tuo}S_gPqY+eV6wlV5N&8 zG!~~UC_I*!Jd$%y$*VXj?Jpeq5-8CwFzhNdn(&0J{-C=zdnlSrG27wgedzVUNg z4qxrMYuh4sc6!cvAWHW~$H&Ll9Y+ZgjaJ9ZE$=|M5$&!|zX;|h^zha~2GRe+@UZuu z2w7V5_y;?Ybvda!3MOfaZ8j<6Mn1j!ZI6g)vjO~{oE-Pxpu#1j@4IZie9rYi#reu4 z5{3}q)WIQkjgcW;0Qg=W5S|hDgC_nKh`&gHTsyNjxRgq{X>$xh>r<$vz^-zhgcfqe z5A%P3X0YO$%d$qhUy`-i+&AK~X=l60PT~p3`+7*%GGEztT?S_f_#5}{-#0tI2mB3y z8uR%SMlq?~iJ1{j&I}WQEaWu}TnC?0p8`My93AQS?8Pdgg(@nA_k8{K?Xv+CGKf>! z=}BdKSL-#y&_fM-k?3W9p_4?S+%M%MMUS?1>!AY8ut45yas`d3qO-d7i`{a z)&_AukAb$;?W0|d;wx8LV2;hfGXm(_UJRz6CXoTGCNrFVPS!7TRZ-P{Sr*tgG^EGSMB&pq`d?J1e^?^Bjmkl(F2xgLSvXYBw^pe*@#vQT|E8&g9h4)RfupuToHREW6vN7udOL&;9%C4)LUT zIIefPsE`rZLv&VF7T1x?%uK9qx$~lR9l)crxPxVY>{2RTb#;kgMCp8L>e38atMIC- zYIt>l`zy7*7^onT}f99-`^78Xw4w^ZA9vC(kZwJv$TB7S|1Q;+FRSz)@?zFBMQOXC9S~GZdPjMjAxvmHYMV$&N)`+X0T%#vb9P{0!0td2n(pZQ z_}TJ$ru86Gu!R}U;^l3A|ACu!EQulm(0(b$AfR}6L{1Nu+Z_AW=UsRn(|d0>eqBKe zj5HreyR9IvPzf`%aR3u8U6B{pKmme4mF?Bn$=a#HZ@bErsv4aMjng>oBsRkmRF7QZ zTq074bV^*T%{4e7HB}c#m-WgDGMs`Hn6mpnPFC1_LGaF{n6$M;iqv=u1p_vL7al6XtVKldEVMd6dr0xLCFS@?;HCt*3?yh;Mbg~k2M_1PgwAKzDJSgk<0tvjj zbv{!4#t{f5)a==lfYHaPa04j|uJeO~sCy;X<#azwTPGrKaH{ z#ScjH{(PvL7vXfI<@?l%W(5rndXS+@TQGo%ncoA!O|_ZZM?2qX(_;-9VQ!t^>@{kW zl}hE9DitNlo>RFcwO*NeOHBN2i{bZAowK+4`9frYT&=W#iNRS)*T6ssnASOHQ-2@jV*_9$DB z>1hHdWsB-l+O1_Ja*1alA9wxyt^N)rY{JL9oZY0#@$+er11I}W z5hBNEgN}Q~j{UUp6ZB5Id&NOHOmluAt=HO{qZ$5em3!F*!cKaLv*DiUjmF~(g>-bP-N0nIm&O=7oi6SS#uriMRiC#;+|XXEI$4A z`9PLCDVDj$WIn=4-P0_WCF6%X=>zm-wa)|(n3Q*MYi`l(Dm>69)rWw#n4>AJtgH=uwNP3$2qC*X+p#;(fcHc%`RSNC9m|fp>sCK-!f62re;78iF zN5{q8q#a|Q3#>UzPZ_XnyI2gc4YPb!ix2g|FzF9cQXETZzCZl926kdZQk+9d)40w%TU<1F7z z?IO2mEW|{y0mAcws*dT4>|HTl&Cup+VM;$ecbVF6vztkbiWcVIka19HZ5I=f7As%S zjkI9?E-im>@V9Bh4qooaGUw-muxAyn&+@Oc(H~)4R z3pM+`s!5utNKv;WyhDmdT-Yv&!>;V^6nf1Ey?J|!nU`PWN)lTN62b-@9XI!i*x1F~ zz)_obKi4wpCag&@4P-t_z|c}1b!Hrf*OS!@l=^7*VdtHX%wYDR%WrRQ?{p<%<=!+r zqlO01p}#-U&*gWZIAJ^=vb6b&=6^g%RlPw|GhtWrHDzB9vum}FxY_90@o)_SZLXB= zR|%-3YrfjC4;i1G#dlxy;E>{9G?+TB#n6PvVjzul92bWHrZ=C}wE zEaV~-B#?$7;eJ1SxRzVRe_e-iEjvzCwy<7;U>9Y(M^CLr#9x`R2W8r1ey0xx; zZctv{N}<%2>uaXDe1+)DqSdQcKf@TpRN96D2xM&2G@E1Wju^bl@_LO~3_?BM-P>sN z+iRFCiTG9PeQAga@2H+<=vGR%46jSZO^nF|>J#Wf`clOqdf{tG^_JoKQjAn%Z{IqY z-rja-m#p?h>Q{9SDZ(7t$>)uQ-$$I1DiAMR4>kg#iJbySeoAL(2?n$cn)@V`DivwP zupZ?I>w-`+{*X@PzN-hXX2&clHM{e0rAG!1fL9PwF_&l0o^4@Tf!Sr=S-ZtWMb8EX z(jlAiaNSJp2o+UPfY*hP`7^XI(q$5+#Tdo<{ohC-1O z6_c0@jAWR@@TyUn@sJurKyu9$V{2UNLCA^JbW1H+vI#}jc81E{opHLOrRPP~`OS&P z!icD-_sb-9QDgY0@y^cIk6q5Qq3{K@q~OX?2}EiDwsn^u*Vmf> z=(GL!70Wrs56XVl7c5s3C9RxT_uRhYAQR%>a2NgyG?_*dAPV*xQfRaR<1CmglWWcRSySd^i zE3X1Sl8kt{jbQZRvMt}W+jXLG445B14gu^qYBp+pHosK{X#{>#)8VFXt5G!Td6{)U9fK`wFase z9a!+ZJzU@elxQ{@4pb&yWa;bzIO2#A1Py5GIo4&oqn6zX;}lSc@{;82>8Y2ux33RV z^o(C9BJ!JI54hW)V!)DaS2?IXBz{m@P;^JB`H|wBUoX6|CBa1M!{^UluZ-@!U^wSqR@!lg^APr5v( zPL3IKkPMd)0udj{2#-QCP^wLrmaZlpYm_m@JwZYL5eFvTaH5E=kRV?j&#ANTNnv%W zVH1tD{br7?NVbWw@o^Rb4+JGYQ1qJWue`V{bq4d*Q0Y61wQ#-GVhoumtVvduQK!d< zVbQZt=%~M3fPv{*3l{XpW?Z6r^efYejR14%1Oi=Og)Ni1;~E3twT(NLq74jR%(X>c zEN-L?%1}*k{6@RaA@L#YdEz8x9DjTs2$KBQKcBX6k^n{Kj-kYJJC@@KPY#%Un9x24 zAc#>B2 ztCDJg#H-V*`Pk2wdXlz#ERe;o5NwJ;&>c3wJ$s#+$ZYa3er#p#6uKX}KV_JqaZKmn z<`zXW&~C^1RTJ;YAvDmZ=Qv9`RvlR>of_ebkhVQuaam4t<;p!lNn9rMG-Bq{R+`!Ua^xWh8M#H_Tzcc&PXs_^_p5egKz>7k#cf(f9cIET&Sj zN;3L4W2LKSB8Gt6jn8c#4tzlkUUc+MB&6S3wB1xwHQc7aXUOqIVL+i*2^h0`A&k}u ziJm!}e|pzph5bYwFa|(dW9{05cO*{~jQ^76&8o_GhmbXwgV(Vb5M%8|D1EA(JAXbJ zTWWqEw~7cOA*rX-Vd`N~K3<2vC0*4;pn+7S_XP{Jc~|Wm1ii@;=rDI+#cus6IqM=ip&EY(R{V}f4AX8R z&4Xa^8&tM=;08uR)u&-P&*enLT?DK-aT$!a+MKati9K&gI(LM|1)#=peQwzC=Uy}} z09I<-R$N*}qKHe93@5MRZVkhtAB{cO@O&PQP2suzTTT*Qi?j&HPMRel5UVp4uLidW ztv$?aPbIul3I5c7S)1cIGKOqvaP`u#BBWlzXwia!B@E9ax$}N<>Cqk2=ug0Tm~VO< zY&^RG#9T5?rL@i2IT1@~^?Zi=l9D`&_ha@Ssvp`(b+yCxh_f=1$F5Dh+qJ67S3}O7 z6GXT>7ZK6g7LQKNM2`?y~9Dt6cGSrgrXQP}r_`oon<(0kOZ~vke z$cbXqMt^#-;l0nO&CNU||6DUQo6(@&2819KdG8jvEX5Z?$+>;!NF7R{P@H9Mm#SA* zR?4+_dGvD5pD%%-sYN}ZUgKV<*_5nFkx}b~R_wLV>$phLej~fNS9sifu)t8LIr*jJ zui@fmU3f+wS4GWv^!CTQ6AVv7ZHl;5eu! zIj#j??YNbF?tZw%>YXDdCe{JKEIl-F|951tULq`Y$BBcn)(-+{zXW$m3TlMUyc$r$ zg@GpzeMEC0Eq8}LFNVuwwe5MLCnT6W`kk-GcbOnH4g9&9C%+5L^!vS9oHzJrfP+5K zfr8j!u37%*=%^;9bFO-5$p!}|kbYzOe7PKVUy#K6D}C<(9F2szLiKhEL=`v&b3SHkU^!B}hear8|}N;I0ZtKQ-}5!^g@TU3b} zJ*Q(pd$4>5wD3Y9)j+a+3Et9tSA*6tZf5FsUedySc;R)>|EE06-2g}Bn)6|~)n_mbJ0ZcEB6otNkhHy4Dl5A*(?6iK z(S*mRaaF#(Vg)-)tUbv*#|eF;@lG|0&*U0e6_IAw%Sn;!KW9u6zKxn8aFF@Kr*_pW zKN(mbDGtNETfLm5L`B&>eE^DnFgpKbbacF*hGDFXD_74_V|0-qSy=!?={WDoJ=jhf z@MAatgmiPad?RzG3H#z;(sOPZ^RzfT}r8||$4@_)_Xu_ogXCmOOQCrQZbN+fd( zjZw+UEdUa2&@%)lH?su&|MU|mjbGpNN}4sP)<6i{Z=OU*5hbOL&dwbo3qaQ)?oZLP z`(~2o;r&Dc=KGh&D)W-QzhVtoN*NupL>)3~-aIi-AJmzFqBm^y`DIW{CE8xXj?FY0 zinhSOgDoSOAPk8`=60z@x*YK zt9gkzKc1*6R1Fx&bdD)NkA2|pH8%MVC2T1rt-#EeURN^e!dPnl@F`nu*)1W14q|NP z7zV^GT=R$O#9`uno0POt{(YmV38xm4+?LrAjx>vnW0*i7bU_IMFSOzd=iIq(4V@xQ z8JY=Rs?_WCyxz>%*zREADyVwtiCp~tW#sFV07>+>v=&@YS~5#F=6!sBJs4H(5!bF= z!yxBk$o6mrKh_$5gg)U&wZ;>3q(TAOsOAnpV7LVIR~ryE8_n#O=!&FEZB8w67$eGw z0T5&wlH3lG8WDlF{JMfDknEgNAoBYBKMyrT6akWC`AdiTRW3)o_Y~B z&}8O5kd*fe7SqT_XKpWC^i41&TIj9zykgt|-1oUi+o?s&S5*S6AZxfTyy1I$0@5sK zMm)QDd+~T^c9)_b`W!;|=~(2EJ{{vo7m>o1LrudMHELa*l2Z`NmsSt}Od135!pP*b ziNt!pt}0X`1SA1qSUjAX1IAuYGL3in?^hH^2*%n+Cv^}FSYijr=9r`ws(6iP{o3a= z{PoqXlzy~{i5=lxJjK*%rF=O?kFO`)h}=umREW4`?YxD8f@)AwuFkuc%`=|F+Ab1}i|9mv=SF?smj}I7JvU(< zh|6G_undhz$J9LRMfSkJSgs;_4=slM%b~fiA+9^?-4bqmvO8bUJoXRn*Sy}<7*eNK zbQ5B*TH_elSaCkl+zf1A2x)#5vkDV#YAO1lHbjVJHs;r}!DuFg)H8vBbkJw0@6UDZ!AWCSyx0hJB&9l#^(gTNi8KmQHw*7RUCd|1w1JTchOYIzS6qk}x`NlAV(2 z!1U!rrUm@m@}!H50&QZ*mo05YB(|(yx9$*W;}UfOz&y`p-qdzlfZPq}u)4Ws&=4VT z3WHr$7YLkPPCKk~g7j#OxC-SStiLfkiN0Vdew^rpHJX`7=myL*j%mW*o7W5{DqgqD z-RYDi=RO(5Vb6xXAxsz0Uw0b1MKt&*IF+tUhFF_+G( z>{D}Tb9m?ixKIHB0jTFaIFQ-b5U~CdnYCMbTGiDxc_msmm~A!dkyudg#SMWIFhVXM zv)zbNaWB_ukzYP4s1CZYshOSj9#m^fJ*4UCLjJW$wP`Lvm_1@_M2Y0A#C~J^dn+6Y^l_?_d9qRnsq#6@Demy~ z|MYZy@bku6bCuuWr*uIJ0I+m@q@Av$Fv&Sbhx=1JH%7v?v3IdNx~^;+o4XtyJvrmX zUn%SJZMPHVIQASIAIZz*CtU7RF5M5UKKmH`4Raj8)z8u|V#)-s8QZN;}lD@Y77~Aso zW5ka{%coFc=fGTB!Sf#x`J;5FqZ)sxeAiN&$Dqc{rYLxD=5^-9UhKMtv-NIUtiHK; z@f?QPY;18+l;ceMV;csU-mN zO@vhdY6Ms7oxQy6RJvx+MDqR_6UGBWDw*^ z8{OVmUm3fKREt;Xo5G}VdFLQK2s!dugC>pFCK?173g|G1g@7eRsS8W6t2w2I=%7-;S5XM1!8a*O=2nqL<`Hm&- zjmi5yt+gNuG0>?$4N#hE#tij|f+jG6sUkw9l__0nOF?tSW1`CTsi$6t=%4++hw&g+ zWf_g!PA}x%QNj+`Jo3RFET5GG(nc?%{pWtwNI+ezH9|cK$t0U43cy>4-UX_%PUx4l zXXmu7WSA>T&J@o=iZG`1066&!<+_i_n9~|h&F|g2moXGayOsZWLoUJeyLL`JO)6%N zR{*Aeum`J%)@BJ>pOXHA*@jrkzTLY{Nr3GS7-Rdv7rsN?k6y}A-d1Chu@t=m47e-` zRDYxka}3%q;tuUGQkoN(UeYShfms*ZyV^a;J|+FAwa4}!d32PTef>KL2g-B<=Ac}* zVLSDS-J=;~7sn;AbQiwRgr2Riq-5Vl&l6*UfvT&J*mV6-J}u!IS~07>wEYoho|z2! zx2lXIWHt-Tj2Cq`_Pb4g+v5ry+qWNTQb3)&@c`RpFQEC~+P5-)JaRAPBwnTyayYa6 z-0V!QVW+B4jTLrAxa75o2r&)kW6r@-w*r%e^4A#R}Cyp!`jH#(65uSq#$$Ma&QbVT3Y4A0-c=#KSd zWyjrE8uq$sTxkqCqp@p#>}I?N?%}9&;k&t*!6T#VKa}Sgr&vi~#mrfv2m1CKnl-|h zju|ebf7-rp`rEQzLi|M2mAA>G>%u;RG@^m&{)mB${3Gd-TNM8y1og$->*I7Dqt4;~ zG(KuL4%8%R!nW-+UB&^qAeHZ5)}V0PwObs5pHRN>OG@}OjhtB9-eyk=;NKzJ)Ky+u^4qo z2*?XWAxU`o^16U&Yo2_RICJ)_z@!DLW0({>T0Xwy;~9T}d#qIZcgvw)@fAS73r}Hp zd_o8Icbo-X>cv!4`_FgXwgay28dtP3HKJv`r_8GX^Su0aD+JWwUHWYMrz@ctu1BoM zb?pk4Kr9r5+VcVSgLlLUDFrCSMo?GY#}AIuaaOknfELAjV>(E20Q)d?HnUn!W(j_I z(J-TS#3~8WIwnk1V6GBMiQX1Zb8pY!S-xpwh*;<7fg7~B?f>%NY-ez3{uoS^UOe%r zETO9KA`2HSvhx!b5zz$ja8o~eBjfb_PX*h$NO*0h>ub3EfT;)yf8}p=kvKEeyds`QqB?SW+fOd)ZT-moj>Ma2U+;C>?OWXF+T^?cH~FfT;dGdrcsCt z8#Zo|#+S3NdA5fw>8a1)RjB?yCl^!>9BRzN@eYlLH2!cU29c_Vn^Feaw|16=NITUn zA&M-vIv8d->63F@i7_aTfz0Wnv0D0}Co+oO}r(LXWZ@#d`ufbe|y6Yk{$u_vxB6qIOJQi4~QJ4Si#4 zIM{p@d_O0?Z_a+cbqU!t1`jyx;aqM8^47#D;IE{Y?X2<~~ zRI;u=w(6%BtBZxlnZ8~8*gR<30+?upds|@d%(9D8QmDE^AW1cz^xIKJ_T-}aIkkld z$3o4RZahhHU!&SzFo;>H^4$IcaqP7K!UXNuYkS{tziTZlG>p}~7o49qo{`eN{nR<& z%c!u}9A(nH_ND#ojVEC^mc2{<_SZTvvElby6+AkQk_I-Srfrk^S;2K3X z!~&UekPFGEYnt9)X_+of#b;&%aC5yefAoK>pMDGBbd|3^Qb6McUZdb`gd#gr`c{B`Dl%;54n!DM z5~2dCk;l0tzW0G5T~jgE6pN8pjrcMi39)AzegUUDKi&k!RTe7I<1AAn&O~Wuy~EFI zTl_Yv2sk>iK*Akw;=*E8$AgU#c;)}^I(#D02HkuUUM2 zr;u!ZA?@>F)<)1V1f=o?_S>$RC*AkrPK>N`L-pAFXB0~IxS|X;Z_Shh_IM#7IfrG! zD^3prrdoD$!}*ieqafHzBte`#SU1-n7kZ}2L`eMa`@wIGOE9hCe~f*1JeF<$e?+&2 zQj$8(zLlKD_a90tEG}uLM1zqnR(gV4Ta3IXGQkR$o{<#a^F4Q-~HS@ z|MZe^UDtV@$M_uY&wB*wa?Q-s<(p|V3woi#+Bt9avSsT4noe(;Owwd|yRZ##06$oh z5i&XeAv}l~1!3H<-wftz+(P54d;jUvr@=P9m!2~hZ=8O;Z?yiG`@!|pLej#PpWOh~CMn`fOfR^P22L4%q;}{p1aSp`2Qs@r_W!tW@2yg67 z?2Ie;P8}e`YE&Lx=<5}AUQ=Rv$y7--_eafJ8hArN`s1y$WFO$7X2TV9Gte|42aQmL z)!fON$MV40JA2LP%k%nKE#@F_)}efPfS*X{HF9(;D?%fs9nH5T4q-48b?P%F8#;&WCaQ6P?p(=wQn&A(m0UbHSzHHf-*ZV!9XI7ua zbm;(>8t*OY8%W*~rf6kQ0(w6TiBi4UbANXlpbNsDDZM-V&acfaDV($Xz6X#ZmK;wo zF&FQT$EHl^86%&MKhK}J5U~YxM#=UlV+9eFVFTuY$r3v>*h2s@WbBnT%a}~oBcbJ7S z@hCdLu!=IXd!J_6v4NPwVTH>3%?j=;4VCtq*8PwAerfwP@{&irx!v@ek1#V_vlzpYF`cdj zV5(+uCKhwTcqbFluUWTK3q@MNTj(-i=gtWT`Y#^fCa2uH$%hx5bpE& z=x_^=(J|$BgUBs@ zhM2dc3HZ3itcUjoT8{ea-V0`K-VYxqDVLhT36geCe9DqKL8qIRtiC+`I(h7N)QW#R z(~O_MDsp8!uH_;-_HIlMI$FuvOdv3Am9fESbQgPNpx+P_xRf#dltbVSH^)JDR_jMQbjvBYmFz>fY>W!KmO%5UXIQncQU<>xgLjd1(kws4F zDuugrJncYg5th%GZugv}@3&aAmGS_Y4(jtnt%KP{M`q6ZwT&^KhlnLM+Uz`VBZ!p< zvTgB1NaJxpie`UZ{6EYB+!g6PD;QcW(&mZ6GnE^Kgvj04=<{KFhJj3QFM@yBc9I!H zT5EC#6b^wZsf(lbiLhgVSH_dIJAdBQ$ZYhXn_%d>b2K!j2KKN6RgxdKqvNHJee&~A zgO%_7A?9)paW{Tt6{}T~V;PgLE8gZcy))ib!6xvD^udWFGKkqCvGv(gJUr6pd4|(E zrSfaTk;2D9`$;AD)$UanMd$fxW||2f1^8n!QVqOj&g5Gu-2Ys` z*QnDA*xj1@pDdNNu|6QxEq7Hx>(_L!D!WArh8Vb*v}q@onN0zXA$?_%Xi~!+u+WUq z+aN+b{hJX0`)pKnnEr)Fj}5ty6@1AvGog~x zY^2uIu>24hcqw6xduZ&_ks0+qP&VV_9u<{Ge+=(CiP_ado4LlUq9q=5D|Ri|nt9do z$UnS?C5nx?X26VP<}{2M{C{^}GOOn}kI$#On4E!N3!?xb)d0!36 zbQb2rG(F$3r9b5@0yd{}aqu$Dl_&h)3Cf&fH>*&Lgr5QluJH0W_dUgK1U`oepyUt=PWMGluE?v)6hm+3=rwqK^P#SRlVW0hXR!5JF zcMsfpvTUOR6T($%`Fq)$h{4YIkFV}KtBckc6^+Z{P0A$;;)Ki%$~vZ%wB0vqSYxEtx@S!c(>=2F4AQN7xj}WCxx=vcoyqndmS;U?C)Db@ zRNn=kh20EkNIwQ-zn*t$bx=i6;LwMdPVqapZf)P&g^~Gw7cbj3Z6|25Uvp2Cwj9d% zczuX?FsYi7*1(B4-Gg7Jc5M%X!evbrryG~{hI?LK`jHn`&G7J4r*62o%q2R-CZ^sH zi!nluIyOeoCifFqq?-xmiL>%AoxFeE0h}(-(yTU9zJfPCNQ}=A8n<{I8d2v#6Uifs z0+`9V&0;NUgnm}djko7R`|^q*w|Og4SiNuv){1qA)j^eh$0_ae&={}jLr$un;I8j^ zuXjA_IMN&s9}|w7hZp$Jfn1P-tvXt54@8?(}uVK#BV6m7kT36XGT{O z?~M?sl`UN8Sc*Dmpi9U-5Fx8<-UC|T{?Uh3H|zV>0U?A?5ql-5!TX2z{A?5@^EWR1 zJOmsw4>^lucSnQWXy^Kjv3-z2=#o$vmce1oGyhr+&!P2O%J9P?O;8g)=+lQ3u*^vR zIcTj%t*r80J8Up+Wh-2lZ~DTfsWwYwb6?P^sVe;FaT+5 zbwv2knx*WUeYA`>y7Wlos~E2nutJTvufNvudSMVuu#eU zvpnoLH?fgkzD4a5y@JT>b(=3Z%XLaCKc1EGT6>2mCeOH5wy(vQ>r^$5(ByY(uBel) zae{-l)E09c67hYw|G9~X10_&5IdV;n#@;Je`x!%-O)0i*JYS!#8_Vm|545tsn+jG9 z;SL2c8wt5aFG#}-{F+szY;KPJ2|@5ix=&I#fE2CdVVo|WFCA}`zg{CX(!@*-K5%ZW zwz^1kuuF}y09^kL{*}(Qbf#rBD>{-0YxZfb-jf~t{ErBFY=e%Vrn26lpQ~o??QFm# zJg64;*Q9hXPuCMK0D#t#3|9j)In-^1&TC6~vY*V$;PGmXQ z1MfoL{C9YlboN|YddXTp!?4pscxSe$vff+sjAtiCqx!TV6%<0Nd~XAW$GS46w7-oJ zKBMb#u@kR3m*hLSTdy2TPc?ZKxytg0-x#Nqx&L8}AEA9?>g`?+i$=?>!(%{#yhnQ1 z2#E6jYO@g`cJJD|s#P#$ccY(978kXoC=U~O(wKjOL8*|EMFjy`Q?Q~xZTHsXdDUgL zcc%TC%}N)Cs@?4Nh`r+!c8^1`XWp8)5NQes7h0?WlM+>1VospNjH|~{1Tb5isn5@f z|DTt6ht%bw?iY+rWk$TddAIDDHOD*8QX%n#sU~`|8|v!bq@%wzE|QvZYSZfb z297%}XF}_yioEsXE!b{}`vq)a{~YS%L58tP8P?Hg1-B^}DG`S}ec!9Cz8e!-Z}$)` zdpKj7JdF0Q0e3_l;v~SJyM&rn>Q6MIeyl2Q62h&B4Qc_wg^i_*suEZ{4a`v}n zpC1cDrNtPQ?`cH`NEHWSC>i^tvg7!OR|*iPm5Olu*#Zdcd!%sG&%>&dI_<7L6J*sd zHbo(z1ZbmGsm27jPv+W2`Q!$J@FKDmXE>3oQ&~%j*94 z{K29gm4ZMc^cFWmpZ!Dr$dQ843`y1~mDs%l!;g8;?*+i7bFC3B=e{|IVfwV!itGeQ zB_IYSl(E!8w6g_Ur$uU1I^QxgYoB}bruY4=SDi#(cOfui8^s)OgueI#Fy;zXUSyyh z{W~0jt8uln6C<@_fvfGpuh7SFuL}A+gdRfaspGHth>tPJYt8B5#3^J1u3zcg3K6pf z;e+WE*s=!~yce+W9l+Q=WEuxW^bap5{@K$1g8dnz+^}O+Vu9DMu`DQj^#h!zCNw^Z zwtrSsHmul|>fnpaYD7pFe2T=Q1VOUVh7SQfS(3?tw_b=hDjAkyFozVXU2T@kw(th0~zw3O{ z0pe~JcahM4Aj|zrcYwsF$Mdyai;|vr^w$!00>pQmSE8h_Tr++9AVc#LI|KZW;^u=m~2*Tz(gyXcU z!_nEj>mSQursRH73l+g7j;M4H1$k#lX_q`24NXMia%KJB>jI7DCL2t-#lEHU4R;y3 z!TE4f;9i5p*fUwj++_11_PH^unAc{x8*bgRr*P+@2@~%R8dk+&myZmdRo%9+{s*Oq zgQza2CVCv>uO!=2?yI8H*?d>L`yQIzyQti}Muv|lJ-b5)?M!96(o~tYU)mmVc-yU- z6MjiidTtlIHZE5FVNL1d6L;f2rcIAc;OyZO`5JFtEdUhb2U8a~b!>S_SwvcG|Ftsi zm34MnOf|UDQF3W>Tv1Bk5Kw1KeMpY$QX_LDN1JN?J0!@U;owZW)GTW} zvU4^RVfPjbc-TjJy2VqY__wq#c!%fT>*zdw?dK67q0f{if4&iZ#yAXD;rfQ~UwCG6y~rRW9st$#0-rVz7~6t7S= ztcTfy)yjQ1;=6g?1w#d3^vHZ_gOp+Lc=F)G?X77~9(t)tbcoU4d-CLoCG~kq)*8>y zh8lenR+gpfICv9;C(8(6O{^$d+oQ2ADI|6o@h}!=0qY^grNT?0W+nXU&sv(-%j<&p z|LjOkJo}>uu9eo*gGu|jv}iHLKiDqPHw*KSeRTG|fE*w9u>iWxtr9rn$Wa_d^u8+a zgAD2=GMZWqtu&j6$)k!5;VfZSUu(}m?c3-&DN(0qq5l7v2HBQq`9;^nhG;QZIF|`5 zX7(i#ho?-HP?WZ|ccmPHf6dd%Cw#c>CA5V%YOFbrcp1A)ZJ3f`HhY*d!Tz2xF-lpn zV!j}b#U5Du-@}N<#Ke004o&t&YMaPrH|02ZpS}NwTeDja8su9Lvbxw=!+a-piFiLO;Xd?TolMwA_B{3?z8%`Qg z>^mki)oICb^}TyGF{y$j>kS-P-&w^I(;dPa!h-qxjgJEZ!2YXP@xq@s=jGDMH0zl4 z>(@7h0kkCDu*$Vg(oPIw9A=JvT4}mDj*HoYqt$kuP;$$ZyV9Q=e<%7zCQ?Sf9(tW< z+5YK1hU+2BTemJ3$4vF-0utJnwL;G<9qH+PuKI+1Qqpm9T(4vTI8_rq^Y)>TKdl&( zjR{{oS^QSZ)g_Ym&~DsyCm8+7ILN*81tqOcyrf4P_FFIY)UyLiU%*iB&l{%)7`W~U zIGblpC=n|dsj2b!E~_nS352P8^G3}Knd;{T{r_)$lfn>}?45}QEy?`(QRP@B` zkT~y+qc)2Q^SrwN8pN2*jw&4V9-XV4SJjlItj=krwZrDQDbF9bN#_yh!`3wG9xt3i z4JIfuT{scs+jdvltUnmdF=Vi-n%QE$^`E8lcNL=WZ!Et9mjE;m4K zOYr>~mrCDa*y2anC-g4DLWp-oY;@c)|$aTjS=H z+i0En8V@JeJ&uL!fCR8_fIHYd;zEsL%&h>DeAtp7F-vJ)F%2-WlorU#$=%rgcmv|^ z9@p7K7NUv074_MU>U<5=OaQoY2i&hXNiBR-XD>T7iITLn=ygyJW|W>YVQBz^Z-x@V z3vAo`jJ7vhGHP;(DjU{^*l^DNEAdh~+Xn+TY(o$Cm$9_MmFYq3y7+fO!ElQpwEX_ zz!&{|le^iTEX7$}=y8c(3<55xoTSqUf4bdU0~|YSz3&01V)OVgu=NmDIh@QBFLxc{ zeQ^Y)as!1+tYmvE1YwJj^6iN+SYdYm_N3;}NDH*|^QI!MO-icYTL-YTOu@(sx+u1+392az_qjU8Sjt zib{E2Kk3sgS^@^jm8`UDSj0eWhob#`;1PR`4jo@o zsPS(@&C3Qg4_F>6uNGH)1Srey5qEK!Dwv3UmRP_d_kc{Lh-Bf6RafibwM7Kzq?&X+ z9(zWX@VL%VSNy7x{B;=4tU1z+pjIzQ*U7v2%hc>WL~4f?=#9|rImht9s8K@bli#fX z8gWf}5lPAVP)*_S(1--%lCmbK!`*s%QaiTlgxD;go#YFMNa|>Es|~?<9ooG1nAbrK z49hP$uh^mnvP*Qx<&pj%Yn@{4w5n$;8T@&u#${zX)z0YXG>7^-2qyVJ^SsogqGC@( zP!a1<$&qKo8YahTww(QC@n9&(Up~tP_ytdO&PHE$&7*go$A4{FTGJATU7S5iRN4Sp zJ9+}C-FfFUh7Lh9RH(+z4FqHQ7pv%(t%f&!SUL|IcO|!4(`8^vK+5|Er>G+hRH$ze)x=Rz(1;hIEl#_Fd zEyhsd#cv2|`<{)}%7j{Wi$Yi=8g^ZYzu)>Au!2mC{V4f$Mvhao;m^>IiYy=TZvt=< zShjrmdP3dSz`;oFo@PFty;~1iD6pTa>WC~%>=00ghXGo@I~d=O306YbAD60}Y;pSQ z7(S9b6sYzoH3N(^hlqwk@49xpawMo<<*OHPq28EUdI@b-LQdVjs}|i}AQySoEv%bW z2>3~@i^fVbt$QH`|GzEf7#0zl{<&3bKP4*DL(+klMDwtHPR0jpt{O&j?I4_EbU^|= z4}dh%mK`X3UgkMCo$4Vby%aEC*7xGY##~x+C)Ggaa|>`p#Yvj#4m;QEa&ua6)@cw2 zwDZ|vAUEP7?xD7tV)}s%{Z6id8eySezq5Mr6%f}0$c?rYnL?ep5q!4?AOLb$3kCi+ zIA&)4EMJ97pl?wTnoYYP8Oh=YpFG6-4k3$xn+$Uzu$2^&Q{F{@cp_|wHH06?($)wxFwu3Z_54;j zkH(*g92mzzUj6~{BLU^fH`=kF!)X?uUH6{x`ackIop(U(m08J4bJ<}m0on5jje`Je&>uV`PR(fIuB9?MOpX{3 zcgT`LnI#gs*Q#SuzOhqlLjJX&z%yrIs7^koQ^>Q#H0L~!(i(>!NT*&*L{oRYgzp^( z43J+Aas&@d=6Y{GkG>Q}-AyI-`*HSTRxW(0Cmu%A87jg8Q~(|4A^C>7*ofo7H@Zyg zaroh5-_|d8u52sFg&>UTRfT|ct7|`}-7QmG2jn`DgFuX8$FMmc3X%8Roc4^L6;aET z9Ca(KJB4+XaIngEXv;H#{$p_Zb+xiGO~F;HT9;ZHA$mK)iv5F|t808G948+jN4JKf zPNW*pj;KM;Tf5BE;TM(udk+O@TVM|(qLD8C>$iN6qGfhxNUq*+8 zqTKn^Cepk*A(wxmTuw9bqoOMKL1t9~j4?f6-Y4A6RA?J>tqnntyIgY4<1gWw@LqLe z368og8QO6nP4u?7m9nO#CmhdItq#53H~OUA?aQ4ybf4p{q*skKw)gda5_=j8+gEQm zNwrjl*mfi-ky@o6%d8Eu!Mc)-LftP&=qoh?P7GSBXq`{0FTlnkPd1&K`r|~{KE?bE zM+f`GXTdES z6(hc_8pCXhTf_NSr?iW5xlh)*>Il{P+qgo}{Q-?lcIUpWlI7$debgs+u4P=IA*(XO zs`abvlv2j=+Srf7ZdUGSTl|oL`(l$@G)K=wXXl4Px51QBlm1(N-}NSs7_YXc3@V+= zDeSCOnMxYW$W$!JGPjrbKK*J%hXz;Whqu}Z#LvIxx6)O}%Ep&N{JUBb;8K_QNBvr< zNuR@g7352e=PSt;Z6DBht^QU~JfmBWdSVn3gyzHwiU$TwE~2Ab@2_pOJIumeCX@{HsVW(D68O!IHMoR>@gs5O|isy zzrJ->@2Bk+Wzk?r2esT+nojeAyW~;J9s9+*E87|<-#YXuzCvkRdtNw;=@?j4k2Z_6^@&U>=1s_YW#4R=EmQG+T1S=Z^cer$tzGYj_Xu!&JQRZM?8EHJx`f%2e!v zS!aa5Azr&><)}kd_>Xo2c3ZR1mQ6};Px>1^>UzCe+#ovN?)!M5BAT4|7(Jg9$#=Bc zK0IN6j7N9Dp{3~Yj`$19k4jK95-+sif=9dCQ)0za_>T_MJ-+ZYz271FTl8-73GrI> z)cdMJQYWJQ@RxV@>KD}3;+tza{L%|KE@IF&^Vdq^2vy^H7%D}JAKJ=Sd2#-tUX~mo zGzD;f2R~haKjJ{{cW@EnOw>7x$sQo%OSHrAkJCwsihlM3A_1F_9#rS|0r9CMWdN2Z ztsj}y6OZejT>-=MjWMUbRNousQkdFbu4$wH6WP`8&x=oN`vGgGP~{JaC9n~HE%FrY zDEFP$C}zo@=aK4HFN;_S5h_}GskQydNf^$nCq>cRfGucw;N8j2q#CpM+My6{$^(G? zwjn*3#~H0I&3J-o*rY0kng&sB4yqMnMU*^`mZm!M_03$Bs#DXcVH&FG>hU>kTEY5}i_ zQP8nSQ1^4oi)U`D_R7!QXSFu#!@R-1vn;kHx$?N85EaQ^(*qzz?x>Lf6#@mVv|*0^7bR z4(v_Hbjj5uRgz7k^BvBVriQy2Aknxngg_os1 zt@L(a3ey_Zc*N#arlZIDK`rHc$ZI+c>L2}%jIGz^r484PK6xNM9zIbqEM>!D@9=Tq zZuZfSw^Hj>9#e{RIwc>Le-Hdn)+97moo;i1ZP&#xp3j8RjdP0MnZlC0)ud_QWon!p zj;(01<$!^8y-jFy5=vuc`wy3bTW`Oy@?hzY`}kci?N&l+e=L>uDJa~c8y>2_HO59( zDN^Nr@NI>|Hn2HdCGznd<=gtr6WVd8#Ok?3t1sp#C_gKdNa^!ZH;a|%LGo_&I9tG42RyPe?C(fNZ=c_76A_8!e{Gudib+5CA6=+X>Ufkw)NuY70Iw*c@*4Z zO9^eUR+8lvZ?n`j_XG={u-7*G5Q^C974;?G4dX9#buzZ4xYg}U6aOkGu2op?r?7EH zntq_v#|}1ZFNX%lKXHVhA7exLnp>+yv9g_bZ$?`HQe=0ccBW)uS9Fvirz39rs*ARF zjjXl^*zqtvt<+?`*m9|Ld!o9=UQUh_-lz`C6B&L6iUX7BB zv{@SAG)9v(G2|nfYL6v_htL&6MwrsOD4wiJL6+JCq50Yv|U}rA=?mIV=ofcllDPU=aYY1i@TB@ zgoHsJP8r9aVuMc7_dnWhcRJ$jjf+<@Df@?%N{kt89gGwQp02Z=BNH?D*nY?_WA#M( zsTgj%h}Oh;5eGYLDF$Ari~ZXMcSrOCp3TS7)#VwDatziRAIGoy85>8x32)t*M&01n zVJVO?si!#bIqU$?qj^WYyAcOHHU<7~V!FR4@luBPjtPp}D2z zK=qR{%_oDlz7%S{=752|R1xK9%*V5fb2(&LyI)=?>3C+FA#8nahjsIdbFDj?i2f=r zh2+i<|E*P)wYi!$;XSrdf0~^>nUUjZ7kkh^(3s?;5&fE9yAd{p@2k^VG_?vM+YBtM zVyuCoc*3^&$nr8ei}FGYTjq#U}l1aI}6od5bgK zZ0#$$ClVYoqy6JswvNW*oULx9gEM0soEDB=EDK~b=p10LKt;JK$#R2rbHRrv6yxGm z4-~iON2YkB^?%w^jGN$k|Lk4f;V-X&8?lhVL8L)79gNX;U$cp8-s`;1O0lTC9+ASY zJody+yg<}Q;eB|Mr|QX*5%eMwzN*}{eq9?!+BxVEJL`zfaDgVs+7q8T3Pcy+KXvn| zK4~y4%Iu+~iI$w;EH3jsa&{ynO^_WeUr`F6&Az7lw zKp3Au#Ow3Wl--hV_zkI>rAyWbztOX%W{jt=Fw~ZryM=vO!UA6=vm*EK3zqm`;;=89 z{$P8N!+hN$EoI?ns|&2Jx@@w{n9W3~m*_p6=}U+gP}G;eKQZnlC3`;cfo<06bi;yQ*%; zCrfaeFYt|Q@Azz`X({#n?*8rW0`~%5ZVZ*PYLDRM>1x`llNeMRk=lM+*oq%r;!P>a zo#&0-DV!?JI;oja7v8#h%lU>^n#%1j7xcBs58Bq)PV`DEZ%s(O;KE!d9EA(gxQmbF z8v42`)z@@fiQhnJ!`%@6y@jPnMLB&Ug3+s zZZ4AfoFL4^0&F}yAF(A{}@Eg zx_jr&hu9;a{%tllkMx8CRCgj6dPAD8Tkwht?csy8N^#)K^ZN3t@YXHLfK9ffzDg8b zfZL}y`#A>6b5r{h@V%jQMU1bSOG35LF@F-mzy|%QBkg%b4X+7OKWZCFwa7vjm%P;$tPQ zG=7la9f)$=;1{*qg?!E593HkvPQ)-fqRkUiS;DmTr z2KVJ{nT6e{QxDsWKI}5&{+{^Qv!J6v3tV;NJW-+5Tg;=lpiI&#Yj6!*&$1#^BPh$o)N>zbJnm zLU55Vw-l#aYu*)rPD!=Dtlw_~ggN1)S?EJgc)|Js`MgXBbo;UCN z$9L)NB1WGM3>?W&B--~?N)m22Z!$5iQ}@K#BNxR~%Pq4fNr8XXp%7G0f|UetkQ8uC zw@{&6_8~4ED9vlGsYhLWE?y?xh~HX0)PU--gegR^q)Z>-H=UlDX*$-B&)%faQTe7u zE3(#0NYwG$XQ6vwqHI#eqJ!wPhdNX2-(cI7q31t9*NbcO6wXud}&yDWxmNrxTnHC3~Snzo_(jj6B9A#&A-``Bv<7IkwH z%*gxXsBR*fiTtW@&(4N5gty+#!ErvgVzfJ46JpSPQV$dP*!!!1i7Ssr2PUC82O3w= zmeExnX|<3E5Rp(y7vKY;+@ZAD0cqp`u+5VOTMTux&_7!NA665@#5eY1#R>Z(1r(?b z`Kh(%UG=hrlS6tO(-k!mjf(@EKSilm#Ho)uoNTa8RVQ9>+^blZtEtFK{#qG;om?740+V!|Byp`|EuG9G(Z`s7-FX-4WF|(qCwN#DzDI7u@VI1~b zL*!Qa?i4Lo3_f|{#QA|eQ<;{uZi*u)A&GMY%JupeK|p4`Oj|6?A}5m6HOElc+=D&f zrH~%zqdG(hgJB(8@x2k$VpF%-e_+y+%GCwYCR3hc+o}NF+*Mgk{rHv{Q-g4G9T3_)4PA+Oij8P98OJa7E%24rQ5;A)GNo{VH6tgyLM`ex#XP~z|8slt z0DC+|Ad%0es;!0AszNaH$CrgJvIZJm5&Tx8YSA%=s$3nsv_(q>pux&{HLsozk3(~K zAbwRuP*2rBhL7lNhZ{KIN8QfsDIL~Iam}16FDj0_of%U;`~gRpsz8Sut+#z0>LdKe z)L6_jTP$-Fib@7Fw%C;v-5iWR6A{$%(U#H`^(EZbFTSeI^HkB>!KbwxZ&!;Kc(jfL zDwbS!qAUdbmZK0u)0P-e`?lNOhjO9R_$WSzA4kWIvuSCr?I~%L@86Zql|@7TkmS)b zIGR8S1@MKx+1`=(4U2rOC%~t0UjoGp0*cX@I4mp0`JOVqHr@-kk(5EXMuDbHd*2r$ z{Q_V7E*604-yNu%hLU0~>KEXT3a+&p)TR(1$$oqMH-+vzW_MQ8*JU4`%pg3g#g#88 zPs4UVx%4N5zk8=8KS?{E*t3T%MXKO@B2Ut^D)X=Y(^IBm*ObS9w(jML@mjXppgE;% zB$4w#>60aQ8aiCUtvK1mW9`DZoU-*+6idIDmvx?%F}>zUT>1x1J!_BxT%2xH@4vJ1 z^fjM>*V1XXA`15!1?=UWlInlY-48fMJdJJemuB2wZ~FK5XjR~nGlx^-24U6z>{U3$ zEFgqc!E;~s1>603T<=+HqCHQ--jnnBmYa=l9&FV=Sl{odQ9Ci*o|J0qSJj@Gxl3{s z24+*t#hxu6l<3P?ws$GDXewyk*bQA=YcYf-<41bd@ zk=pUXiZrDG!GDT@gYaMIO zA#?`NL_Yw60FsdplAbzR5ky|@Z%8Oc7dy%e%yZ=SFO`PgI9 zNZG!SiYB2N!gbc~+*vgzH`6w4-sc-jI4QjWE4M@DZUK8FVoE2|^Y!aju!7%AD~`au zgIp&UNZ_;;G=@YzjVIjbNCr&$B;+s#WvhSAg`6o%mSNH*LafX~K1F#VFeT@L?!5Ex zLVyv6aC@EoaGjt|&Z14~Ns&|Bg8!11K&F{HjN69AHZlHWW;lt`5vy|awB&lf5fh~> z_D7qvGSfw^_Cu*_!AAe#RTuaQ_raulKR)t3-u408m9pYmI7Qr1B!*9oW3;J8Y0>q5 zX~IUIZl-PfG5I;zg=S+wPsol>k^s9t-r`Mh83)9i3mtk0^1Yt36J-|sV~(M&HH{dA zzBSK@X0A!c@qe|rkq&5t5syIfJHPus-7S@AL5;bOu3A&;g&9A!!kC;r2H+PR=Zdiy z`_cE6h-Z))NueH9G??WA=md90P^kc$(bk>^?eGuhY!GUjA+=cy59;JtI(n8*c1l0~ zbPjf<;U!iaXhnGeVL1ti#6Ua~d@ogurS*V35~JV?upUWO??fF#Btud{NPB(N5f~U81XVsGRvcj^&iNa)SI?__hvoApFs>x^fY3#Y0J{1}Wfy(v) z(P}~~X);VY%)}w;Q-pHSZzZ=(z0Yy)%-c&vX7Al$ZG=4$d7jJA#b$jxnIBXq&1B8} zqJ&P8ekpc)F-D@>n=TKAy8>q1iRkTxrU|H6W+#i*6fgxY0R4s z_IlAzn?`0*@RIoho`U&r#Ssh|i*eJuWggql)&VttS(qdQ6C9|Ukb$*m3|@83pFh7J zdl4~0baU3%%E-XO$}x&xUc{i=N=I8HEX&WZlGb+k`Ui0V-3QABC>o&98(qV8ag{b} zYBDW-Es0T+bw?BgK)8a z_wH556YbR@pKn(>K}v!9UyZ!4uV8Wuq8_pX;r@-QI7f3cCDS6N=iEvSn8d?_h{xiO zg7-|xccyK@h=CO`{J}csWw#Z3Hu19{k&-19M}PYnNiJN)U51HS&izSe5@iEI*(wKR z*eh<*NZw|ImGB)Q*jnDi>GA;~CayI7hA`B?K$5pdI&+--#g;-eO81AS-o3?1Uzcc4 z=E7W2Z}06XPKunxb$aLlbz!9=XxV;>B*K`Qr&{-HMKp&unA88q@-2G4#fF|I9O}QY zn11rLNFc%PH9u>?Yympr&jyC4RjV;lMu_lDAV-=Pi=+mZ)aN0bV%5-{@-90D=0ylv z&L<*OwsXH!hRe?*{EiFVMV2<`DR&MW=t&5mvBsTB-mncZ@<@2RL+l!o7+dMK*}K6L zIq|o&bS{e!5ID8kxU(mJI*4R%nkG=9R9e-p6rprP{^7>Yr#Mc5jMK3E{ZUMpVn{%$ zK;%6I{sK8)6ZuFsyYN{qFhhn4_LTC|EeMlForCu;J3a8zBak-y)yt(8nncu1iroX*l!RhN1)X<)wvi*=+z%9)sP1pbAsTF7?hx)#}ovZtB(OjCIg(%5jCy90D zmI8Y$A2Dwv@uxV4x{3SzM*7Rt%Zq0_c`>1te`cMbSK&hFsEAo@E7!3Zqs}eaf{Rwu zOtHQ<$K4wTD>V<5n(iV=$dRDSaO;7`=Ari$lo&QAW0*oQFE|N!_V2n9q117vl2~w$$T!_QedE1hkpzyH0?i5SFa|n5==iKWA3-`w7^2eP zV|fs6X+wj>YepOz-Rah>;GUKbFsL{~7fa$|k&`3?&|>qu7tATsCde!Tl-=4#R>IBd zUp|!dpGXd&^xoacJ!2o5ZB9SbUB}NpnoHTccQ1TO>doKndxs;%8|Y_o?{(oDIZp>i zkk)J7Fej>lo6`WyAi6Wh%zj$u_8QXI*Olg~nP&`o5#oPRjArUZ$jX7iQ=<<3dj$od zF3B0mTD^UA#t&ASW(7$pM;h##Jpowq5pbd5q_=Vx?c|n5163v;SfIWD%>#3hw<`Gedo& z6D&mCscWy{-;DS!Br* z$Xx#tZAms!v!|p3pH!Dh{6E3%BVG>GzcJy$pHC7ioCbHUi5cI7fI0IaO;SV2-L>rt zB#{Sj9$avbPDU06u(gcTh#Xjh>wz#l@6Nm$p`LF{931@QT!qA`c`Mk1r#C*3elg(K znB(*dpKby~?WM!8WQizk7fIwG(hq@mheCfY?7t9h|2j00@4b%!hj9G%an7ILjehjk z>OD2<@LDcl1r=uZ{7dU<9fmqpiT$N4@1JLJvKm8P-Dc2FEn_@PX0lD3IB4PW+K`?k)-MqNhYeqy#leJiWgb%&{F6HFD5#wq_4Y&RuNnuST*g{ zvS4eO9>>Wpn_WRa&8h(~+e{1}y4rVCXmA4`e@e*azaLuCTo_tQ-UR18npv6{w5M0m zI||CC6=g&!(&#^Z?#GGirh+!HL*9N9%Eb3L1T}-OlV1_A%es3r5qf|?cK}N&aaGM3 zA}IR1HFle|Ophbkp_aKgt7Yn4y|1*gqVEK!qu?^GYtjrfv^2EW*4{XH>QtD_CWVb+ zjR&G+neJ^rK5uQZmy;9ie50jIu?cTqEEb@rnL2SweqnX^#`V&V4E8?S`(FCnl&wNT z6JyF+-q#r^E%jq{#&vp4-SNZmQe)@8)(l$@?L7D8jp9{0#K-}bVMwjG>lLB7Pue{1 zsi?W%Wo)?5Svq?7Cp5(%viz8N5nJ=Wov5;XvDKt~?~W6h`K{Vx+TbncgbxfTGrn&- z_>%pMDFAtnXfK|%jcl|-i>MtcpgM}|?W(V@&l$evUEx^N3xJ*72)L)*0HN#ng^|U^U$6 zJP9eafBni0j<=A58GIBD!?aAeR{_B5yZNp2%cUj;JPPPgy?CIPv&-y^oLst|_0kBe$b>qg3+a@XA_B+gK zRe%?s7~Io(%So0#S|jDmc(*+G&d~HIs)bBWvcX>F&AWHg*=4Eg^8Qiy_xBUcX2%j1 z6}#lrFIp6*cMCdes7Fx=t$+OZanK%XMk;*g>PS6&>&~6X*nA)wB<5Z?dU$APt3;IM zQBzJ(zi=pu$W+YP3-{zv|n z)d~yUWX(gqSYO6*A|Ww$bTx-w-SCCo<<#)hq`$B7Ym4bMp?jT0a~{j%9mZb7MH*

    dD{-s`w7zwT@YBvwCXCxw+gH7L^ZLnuzdWtBWGkTk87H2 zIq;4{f+glX&X|Qt_e_KIkT*db(K={6*Tp+Nb6^Rh$@1mP zb;lCSDq_x(NcIniCJ1=uU?Fy3emhZ>*hepDsE)DPG&xjBdiXG*u@-(p;0ELOanpAW zfhs$XY51SmRpaQjP!b2m;CqsWGy(3%)L-A}=koS;dL&gA@}pN3b=qYyd@^+d z@@YH&vBw_|BoT-Qsx(-%XwGi6BZ(=xg_7d9JX#Nt2NG$xCVs8~d&V{%ExM zTRk$8+SXBFLbs=x7Sajd92$ZEjvilND2pS11PtTkr3V-K>CqE1I8rjeg+k2}ZRwFT zBsZOrJFDPpB=@f2hlg_j!PX793Apc?9wGI_eKb{uFLMBh5$F*UX`L+J1<(57HPnUh zU(1UU&mVFauLdDy8Myz|W(!Y{@eFD>f@N##JczJI80mUiTH5qusT-5MLspM(EIK?j zuFLu@bSc{6JnHe$O{khaIpvO-LN+uU5jx0hcZ*n62A2IqEvtev%rKpa^^dt7NU>;L zjSkC~&Y3hkBGc$%1K~vk|LX={sl|+z!XzR^#EQsb9PDNHY-yu^MMn{c!D*J6sXFkT(kCGx>Y=G@DMJ z5@lC`THK${7XHN~(=aO_P9bVpIj7{%#-u0VlAcS?Xz-WMqsr~ANTKQ=BkGyAF^U}w zZs%UmZlt3~$$w>4EeGOmOY`{3bLz}{D(8J4#?{`as!&*${Ff~9as9mN5EA2~9i5Hil4Pot6T zCP4W3>`RLIe?T}rjnqJveVeksDq@<5b1@Cu{!_9jq-=j`SBLK>1J*-%o>?r7$reP< z^*738^)rS&oL5Q7Q0l5TGU)F9K=T(Kl9xX@(J~cE;xXQ&fLdN(yzpbVlsVt{MisC# z!OaITYi~pWM&P7tWb%Io9PAA%_X@g9y=e^#k@ench7BHJX(iq`{$~UG_tGya{xa*W z&7(enP#&9ei4?{>o_{AkI@0fNUBCW?p~3VDH-6nL;nXX!8JQ+38X8G1e7(Cj*)+=G zb}|2Wihc70$yo0xFxcGM4CmY&AuTii31B`IrF|xMapIF3oq2V%NYx*qsv|zQkJIfMK$m-4C?3&W<+G8s($>si-kV9UCfjfXTNz>9*4LjU*+g1408PH6^?3$Y_8b?7)&i;=4Y=Z{3|){}45##H!}>IR z_=2U_bOxHkXDud5<39kyf{XYHliaG~XC)y|tM8y`d-eJ`U6nrBNkbwyzDMqJsY$Od zra)Zn%$Pxp8(*CJyHJVMF)=YURfB71??=pU_}_gKJqGidCzz8%K|yk|RDi_hnpld} zy(NB*B$s(Z#<|Ag7Mg*$Et7?vZYhR@DhLZz9EVF+tmu5SZ_*R7ZC9SH_T|dfphR81 z9vUh*9+qg)S#r<)=}yQ28oH12{_!Hnha-M6|8M0tmY#1Vjq;@xM;MlD9{UnZLV|SU zGtNCH5q3Q;s+p5h@uiVUB7~Vh(ujx7EmJO`zG2{S0m`wDTq{^ujx-Jpz$QWkEJKUP zGyJ$de^A%&%mJ*#G?9rX`xbfe$XMVLsw*%y7bo5%Hatl-0C0xV-gRWY6=Q>&!<-!e zVFlbFS%M$TY1ZDaYrSUY@!5ky*6$9r^Y^;Y8LWHb| z-ibVBn-ta1E(uA-rufXETX#zy=aUYC`)1w%F{W%TD`R z(tz?V1ianp<}cjaH%KKe9Uz%lM%Nj9Y-qtnP~R*@8xyoe+PXx(MhSf0xZ7$O%K901 z0QUQ@mfK=SOg<YxOZnYj<|sR$c#K5@@o_iEad@ zkjLYQ)nhNC9pT6_-oz7Cs%^#4IG)$@zBR0cF3P+THq~r%S z6A7W&87oH87puBXd^~og(3fhy=Z;g>e25Pn zAN>Wx1gDR`{uXxSU3ihqDF9V35W}*Pk|dW%5c)Zvj}#OXEJ%9$hZ!Lj_e!j#@b3wG zp=+6W$|3**Yb+!fGO>A7m2_ryN>F1FB(mxrmAF^gRAtm}0iyRJsh_H7p4M0+*0mar$5I-|UUl%F_xka9!!MnQVHy#MjAOYYuXsW~nYp~Imv|3MJiV06$-yBEi5d() zY6c{Ku1@5zdAE4hTby2?l2i&AIhR5&%qh;^6Vc^*-BSwW4cF3{`Hv7)?T^>X55EI+ zd5NhP-18tXXaiiTxd4Pd9;kY7;4AuGSD;hKm%D@TrVoT&H> zTD@LdZ`;7#5MJxNAIz`R@ZRN6M zT5XS4VGA;{t`!vx$%jTarsY+RPUX@_Ux*EeG_A6b>8SL zEn2IHB^+Yp-Ypy6cV>(>)sl>Rpi7MZaCAO3H7K{ucQwy#$me65b8=xzky3m#U8Kl+ z=8=c9VHGKbV<-i=IR6#VAdlQn%rL9iMyN2&+YU0K<)5Alz$-*7|Chr`MVE(W5|=-@ zQ}yPBgAM?Xbl1tF5AiJA%ZV2RNt9x8CPf&j1g_NXqN-sb_Nlmc@2zE53AsCUpYz`{E^x9c0crAya&rS>gd@&z{R9 zsykJoh+xnU#RounF9Nrw|IsysZ@dHGos_@TrB#Q@>&IJCNJ$T0m`5T)^5#0Wk&E?T zp49B6`7bHV-GD@6V-jPo>rW)HeN7E*Y5NfK#a7O#O!i%)fWvDx-Gk1YRV1R+Ezozt z#};%9{*#@ot5O?e=KE#;;{yWl;^2#fC$0FpRu0 zqRR&1!GEX6P$w^@)qSGps+k9L zkqkdl3inrY>^%WNi63Bf6#mzIeSNbdi@wkKJINQLOIA=qap8$MD@Yi0xzZkLs?kM% zY3J>MY-|mavF>g@iuJ?5fU2hmu93&#a38~ESgee4;wv`vb+9xT`b%Zi#MiIC4xhw# zxEwuMeGU0r*HEJkSEkGQyh6g*mq@(TTnc4w^V*?EE-Wr)o&0uU=B4n@@maM8xfZ>* ziNC|l4_NR5i$~P+``V@;YLHj(LD>E4j~zQU-5oZv?&OE^6A;<7w4M;5l;R(%-~7lfWi^5pP! z*o1`8cLoZhEpYx>0}419I7W|UlKB~#2FAesh=rM%2N!<`WMZppk4((^RMQ_GR3r@N zWj@o*`icR30;$jVNqf&zZ4n_u)I4}%HJ_K4mq={X`rc0NyaDOz#0`_3R~7-6xws%Q z?WwCXKiVncj(p+r4~SRd-v{Ly~eA3xaK(g0J|5#9*e8H zF4sd=_Q$Pu;ghjfKYu=2hdS}4MxryP58=^BI_dcS^Ujy)F^KSP)XPs=vzn`dFZ zd!K~5=+rH8<|8vbr*9wkNxd`jCJ+H}!dSbOPH6RVIb`})WaT~qKR7b`bDKDG`kyLl zX+RAr*Upp7+L?>_A)zaG>s}pCT1zU5I@k|v@1k*k=qCN3E`+-NlQVXh^1@b-7=&+p zC?^`k^|*+W*ZXG~3P^a2SRF!y8b->#Uf&+S{enT~(*PY4xCPjqg{OqeeNBUZwi}z8 zWE?H66eP%_Pww=OLHBnR{U$@-xgc^R$}$Y_Y?M9ybk&Si+m0i^CeL!)&cD8WH+A2s z-11{X>mi6lF?tjzo!EjC?&wh86&AAe?l826RXKP;i%-z;@bD3nMHHB-78Vw1+=RS_ zgh*h4bT;fbQJ34~PrB5>E9mij#^-Q}G6F(xUBR_ahB{A#kl)B`kZT@ncQ@mYxZMBZ zk)tA&S4#^SUUqb-0UIX~K11}xGGX?YiGTGA!v?Iidc`tl&9D;@z;}k-W1-8){fv={ zLKQa`m-QKs6?8wd3ou?;hlKkCG96X9(_|>UzAjF4_2G^m7boNH-!FtI&{5AOyO)ec zkA-CXaGjvw-%ga;idH04owy($7C2I-4Nh$2xO~c%sc8+(+>d7g)IE1ZXVq+$5|8md ze3$IGcGs;>QuXSb1k9A<1$rV;i>=R>mGPx`!N_ccTz{HdCbfE(jgNjIq+(PE<6^H* z3N9lC#a{p*NF6b`eg+mfY~?=so-jmX^2ZTC5c9na=5nPk$WY`OhCvMdz8_{^gVUe$ zZz9D@uNazvd zg=A*+1?8J|pT?9;qgz`b@hbQ}*ybZJn7y2e6E}G=1Ni4gL#DTXkkJe2ltkj z-f4;G@HM>N_yzJ2b08v6@*JwzwO=nGf=hTc$K~4yt2DCGwXe}Ewk(^*6B zv9CW+fQF|S3p<1nYDHi;$IwPY|K@ko>5wp&spn9~S3T!5AbNfaKHbSRvp*W$|4`L? z)R9{RltV8{t$ILU~|3!VTKyPEX3<*e&9QV;A->FLh7} zhY>lu;*wtOXlE&x$Z39v0dCh`EwBuyowp7O&mIY=i$-f~aod0YfjG-+USmG2G{Ni@ z*XR15aNy_3_9i+s7W@N%-Rcw!Lb+N{*>$0hx8BpSg67#aitUe|06mS&Ye%q%5Hx&| zs3wda>&jF}P%-W!?q=XRnSkue7=Gy~F4Hb*;ykwrPzKXrcS{2q8+G+;xMNBSv&J=u z9DwE|as7^{^bgNYI+n2)b^q~YqB9}Y$rFYmmpS`<6{(gIC`7UY>BYl`>vO09;@tyl zJtkk0d4SE2F#2%od`oWt*YG5iDa0Er??u7pM3!>quOxFDgVl}AtKlrq1yf!woLR&y?dsk4!ro4fhy*I6{g0}SPs4OKV% zKa&rdLYjlL8=-;IlR3Qnsf$BI9YOY!E&JMa>#kkdJiZ$k4=YJnFuSRySW5u11xvWs zV_+795-N@bEj`B?R^Gj)e((keSdb@t8G>X;XyOMwZ~OXc)28xgxR}*4J;LU3C>G6l zM|%G1-n|*Dv{F09Fjgog5j7A;rQbr>-4~QT4xd%kp=MxYE1&1_y5MQ^nHV3}Ec28* z+3j-B3$^@wSc)b-J(~DK1_W%3Onv^x$x2otp~ZK&OLER$`4qNMzL4YfvR! zW@!hl;o5;s^cjk0uc?5m?fW~Th4>m~kzN@sPK_mu6$=ukgSN2k3c)?twaX^aXvgxZ zB*SPNR)@OY6CSN%|FcTkM9DSNblaAf`cQz_g}FE$h5@-@T$>x~A_$TVK2%ojw0)Co zVRlmqcLPl7)idX-&LOXmCwjIW-H5BfE|=*&|L+NMPQV82_^tQ8}nVG>rkzI1E?oDq4NJwu}23aF?P9nQz+_Kg1;> zl|mP+`Gh8CK;Pd76F2)!bB*VmDLkzTWY0b|IWhZ|@moY#KEWt>Iepy0rsm{o6uC_D z1Bm<)Q$OkK9RD+Cq&@<_J57IUp5Fp`tCl=N2S>-=cDhB2mU^kq2Q!Vqsxfol3Cw>9 zw|S_)rKP*!j`tFJQ1*%;+MOOyvYENIq7Sp1f7U;lv6yeKpafuO)u<-}WOxPQ*rMw@ zX@@3d|K8_KelERN0t4Bw)B^ghKbd*6{9O(80G`VzO^ew->v4c!g8LLpZd=e<@p`;j zdOdaR&2(LR`;xbB??ZqCW3%k1kp--hRMd=1cY{IzU~#1*TpkJND`nGo5Ju}2(I@3s zQfV$)2CF8bF#m z6t`%==dr@y$k+5^%Q6s6F^c!Z#c37`8%c<3yakMItq_c70WhkvZQC|s=?|1UE)9t#wP5-4!n4GoBf_-^ z`I>>H6&#x${?s1n02dQP?~=5??y>0oRK1U2MD<=ZUlv*4;4dw9psP}&_#~4nh_Div zI(o|1jW4_X^XE_Zk`jnW_WJn2lHq(yV?olSzoot3cnF>h7{!H#I8LGSnqG=dNc1J3PC;J~f! zKqp|<>IGnuDUPU398lO3iLnV_J?TDO#UXGTwLRdG(ugXh^H?`157vh6(ljjG+(vC2 z1VqAhWbH>#vL~>f@YgVaKHvw8whwwZYW44<>J{7sZ7(6FZ|4F+$L`e&VlSWr;!E)i zI6PCpZ}9FNnoo9QWvtLi#L4U7h*I#)fmaEf?spxJ9*wboDvc4%oTtN|u@U8qQd{Zl zhRauXk=bYtEU((swzq&>S>1PF`!}q(^kYUy{~E(zg}YKm2iXPIqeI~Pa^Cs*qYe8k z6fC>mJ^DTB0(=CF2QcXV0 z!MZ1!A?4>Br@|q7U%W!1fP*ty^#B7=vczmzt}R0}J6Wib)D5@1=54j6cAwufW!k@| zATgoz^;AADzY5((-Xn|XnR%j5h+I5 zELmyOJe&-kwP58%%#d*2)LAE_M_kFX?MG~k+*q-8rD|_>jb0Y+-1bp?4sm{Y{kuz{oK|W>G`2VIwcOwNoI>FUW8IFzpph>`$GYs@I|<=OkT6yL zs56aPd7+sY9sL@L+hYCQD5*TTO~!^e1`+xw)2R6e6>V+paFGnyXB+?ws<-NJ@XBGi ziT2)yPfI12PUu@ac5noLr{LlN`Oy)k)m(TVRWh)z`kXeDo0^EI<@7?P3Md z<4qAt%;VI8e(zDmF-Y(tN{`@DBung&yEn}hU+ro6kGsXT!Ps#1+uDv9MbD@=?9pxc zG~{v9+qIhY*&mr)DCSIV`bJjd&sRogDoDE_51M6Wghqvm}1rCGTetYTHWrp%mM$D?|C{d=abq)j4^ENjIGyl$#^UzTRa zr9eBq`?=rO$qq|o)7ug=zqpceY?B=7aYN!1&2*Z?e3G5-;cDkTnpuF;bVt5_jqGG| zLYzxl`qsKOzw+5(jMJOj*H;az;H2D~4agBxBkh;F`BrYyg|_6M7;folj1<3rk1IEp z%!uymrWg_C$V!#3VUO-tSL$0J?1O|_x4rv`-idvRI4CaK0RrBdnF)JXXn#U z-^kAUEpLZ%j3Mp*?*CtV!B`C6LP;9;j@cBTpIVf}D?Jt8!peICYxc7Z!ZEEFJ>|}0 z<%{~SZ2EED?6p(U&A1EXRN-dm+A=k`C6MMEsrWHw`*zJ+^R^r>4%q#MhSpj-)lqte zc>mW#M^Z+i1})&Tp;W!4n ztUtwW#d50c6j^RjG-tTmId^#f2#$JZ>ocK$hIt^-S7&*oykjg$LE~j=I&-Hi$!6I- z%!4{;Nrno{_LH{1_4)a7H8}zXe)$f4JVK>(R(-1Tg7F^-=wu;VGF)x6=^f^GpLMSk zY;DE6Q+^SzL$U2$J^^>47`Cb=>#(&+gOAK14$Z`4vNq#k*MfpR2YgyNpK2kMl6)(f)xtLCZI_B5AuYiTkw%{8mvFRDlR6Rz zJ`Eo@{Xt^|o9OYQl8&I(5H+{3b z9DiZXSYx`HEeM%c*t>~y_Dg1*_CwcWF$k_NyDfk0{aOWu>}ugi_g+w78rH+pwEF5Z zqo{&ry^w+S2+N>WOuoO8vpR_0>zbBz&6knTR_VGYn?D(fFk9TWoV+^~o*3J6w{VrH zv__bwhK6(I4%ux8`He3rqh8KezK__4fdB1~*;K8vgp136g4ry%r>T!K#jL_Gzk<09bil?b<5k+^O=49 zE|2_$vwvEscKV?(RUqJYm zdbv>y%mdd8Q2r4cy*(mFYOmZ0KS#P9+?<0|kA~Vr{1jNs$M~;wa%!RLufb8~-QBi|mDGOgqr-iNC$t7#V4?jEE}JXgNyXmG@fIg?Ar2W=S*8Rq zs^Ai9d{K`6zt&0gB(*>W=+cU_?}1ACPL^+&%{re~OLVh5YNV!d#jf^M=lG5vHOa1~ zKN#58Gbbt3*T{h3#s8qZ=|mj94EF4E&d$zBIxjGbXEPjZPZBLt1-roP$0}{%CNIAE z6W+RU3o-3{hbDDCr+?kV4vOq)^Wh#sczOLD9#uP9GGOW47o53*#xI?&^MNAf;khsA zSB(Gu72fhoIXSyK0bY92aKKqW<&|<1xa`Xiz>%qq2(Pg2^iz8#+S={$=yGC|$nfBr zKLV_9Bow&gVfAfG&d;)`rlwG?=xzag{#}Udhl}-LPS1R%ycgaAHJs#|n7@+h>W0SD z#&HwAs#^&q%ljHKG_mNy3|c^bjMH8h?wV~{#(meq6aAc1Pff|syJe=9ar0B<<-``R z@Ou-d(Rq$TgS%$SxK#!7K&)@14spCBwR7>2ZQHhef#FXmps91UvbJIiyj%~q5}wJm zcSbEl?sjY=kM>1H^`byJIks}fC#5p&v2k&Td*ZVYWHIx;c*|S1g7tx1NRa@;j{lfC zQWnzew&|b8kuiHaG&2LaHQQ}goA6{-2sN3=K??jdj5$cX;~s0i}Z#=KHbQXkCrBC;I=XT zJGs*9em5VW9)Fe#zWfvOO2M}447#EKMlc){02=?Js(k3QuPzOtDHB#U(H;@koeGVW zINAqp`+6JIjM6lHtji=&Xm9<)o~-kog&`De?T}7E1Fw|Yz@Y5!1>tem9>X5uuZm{o zu5Tt~-Nc(qvwxGhtXyDZd{J*$V_!mq*GOHGpePrJXP6M&gBiTCw6(@T!HO=Qohml2 zzmIF{=y1?0j^FOwSh>IQ_!ry&I#bfFn1$R)P}I)U|N0s6ECYT8ICaPfGAZwzA*o1! zgxQ_)T~c#~cN71>jr?Cb#qxe0Ept*9$Fki)5lQcHJ>RaOIdyZ3&t^SARx;C*=?CB8 zYDv1FKIeWuc)2@n+(wT{1?q}^WsfgpDXdNnJ)Z_u^_ zN8RY^0FcevvaB^LFJ92Qr61K)US2-ZSd@k@%Xb$|x>X$?aI$BeC%APrWWU1jUH8pp zuAXZf{>qOo7^emYDilK~IrT5Z(g35ALq4b2Z~5sQ>o~qPU_JYhKbQa*)i1+$e)^`< zZ2P0krE5h*Sd#?fe1?_}^;(CmdPv`wdYS%eWAlcLH}K?5Q>)Kj`LfPTZ>14y)9{iD zeSIklm3Vw9#njo?tYEkL1ln9+d10E7>EqXX%pljB?vrue80@6 zYFY-z_PZCSay+5Ocy!j+txs>pH$eEkFknf#XPl%}i^RUJ zmi+uAPfz)kK@CcGlftDg1_T5y>SJSLKL&K1`BGuAow|kLW0y`Rmp|DB@OT*Faf2}?BpSerhehOcUJ-JaPoJV?*+^{ z`Xk=y&$%6%QbAItrgFTRg_?&hFHiUe8*+)DdTEx-yBfiLsTZven+9f3EQkgy`x|~HA%6+&`j~nAkM5J5*;2YVZGAd`^sj|pO30)YGiI5Mx_li z;s%FO^*ICczsiz*Seuc=0HEL&CE`5I)_=?HR82yrgmGTI>w&w8@T0gyb6CTow%bXn z3~QxNUd>dg+P1q~xDa(UQ{mdAKzx^BR;pw*G_sZNXa*@;z8A)|yOW>&P`!K91A^Y1 z?e<%!W7*4Dbs{}~s1V`nK0kLj0mfdw(aJ0lTmTo=ujoK5mj-$3!hi58+-btrX*Ilx zX%QNla8ip)HXC-y6KXh7c}YIk8@L6dG}gursK zxDmU0py;*^iJLWvj*0Y2{Duxops2+N`zmZx)b#Z9wl@-g7Q!D04O{q}uXTwZUZ@T{ z3OD)RNy+@Yh)lA#Y756nI{-F8Pm ze5eislv)d0pfAL|piR@v%q+3i(Qg8GYL4y4Yuw!;*_JUmf=P0g*$<9^A0u=h zT}W2w)nFmbB6QM$3H1WJ4Q75`o7lXzc_Qd*{BtEnj)`=?2%#YMhpF z7l%bKNwY3d;*FW3jF_G$4BW)K;J$m0e^!q``2v@gWl0K+&$>2@4Ab{&nT<{cZ*$1$ zFA2XAAF@Ka&~VD^hl5uDY^gFcGj--~!h*MdK~?x5Y5$?VQ-tV&183D|ZUv`!lsE@% zHq%%!`GLh$Os3_C)Vd1YR@JJlEVR^{najK1k~A(aYwKph4cBt&NUL7R@SHi6ZH46V z^Y`N7WG@_^D(M`3hKu;1i_r-NgZzz&j+oj7+!=%Ke z2g{Awv(s^Ez2PS~*y0tGj=nmtBLot`hP&gp(-8*((ptj%G}Vr3hTS%!!nQezwa3{t z9JYA>%3O@-!Jio)_KS##g_1n98=dWB;Si;w+*owekM?I<4+`B?-?SawZ;#Rsa5F@6cJ_q-jgJEW~efwL8JH z=i+a!l8uC;gIE&&w6rua#i|3ILykP*_M49F!TmXVP2wJ_Msbr-f02bqjsE@R&mGg< z-fK0Dgd|({W$ri+^;YF4BoxW%7>cL|@9hY_Z&AsEO722o>T)78B|!(DIl{?p7xmLE%h_!y$ zS&g;vFUV`gGmxk8TZen!I9c)OOi_a$I}L~K1sl&pXqqkwS4#EZY_!RhPP}qZQ}bi4 zN5)H<)Ke26JUvw0z-P-BU9ISRZ0}$w%73lyINkv`92de~Xs2w{YZ!6Ch-V$ddjN)13^ysAEes$#)N0)>v7YIPEOvFdhyZI!_VUG-MgyZVQ#m2XqQ9I zlB>B=I}kzweud&t@&)m*R@JBel#?g3ATfP=L{cxy5hk=FHwB({UiFPUPw4Z|ep?1l z2&v!XL9x=eH>&XrC7KSXcu*Dh+JKTxP3#AO^4h=HI_N^&({O(FxJ>!g`*~;7Xk04Y zTqY}n(el$y74vMrkpF^)e8~Ynf7V;^W%WZfqJjX3mn~-1#n1?ytbVv>$Ejxu+ghFX zIOI6j5~u9=PE^rdg28f_K?=ypeavR%cUVZJVN)wG`bHEtlrmzPF=04Q8(#n~&9%^J z-ma`GL$I|Nn8EWxj?_>8osr8{fMN>NeL0gM8Oy^D@`js3yls$Ux;@+O}_AcPrU<(I!&!gB( ztufLJhk_e$+yyr^WEXw`$e_Whw*T4wGA~O~#j{;fYzc!fVof!V4tgKvgo`qkXTj|ru1JREj z?d`)=Bp5PDmeNMkQi62ZGHJ9-zXmEEJ7Ne0*Oyf%#({hm-o3J!1AgogF*d3=-)#dT zT+s2!v1rI%tNddNkS8+}qc|v*(ahWfAB`x%^=W*Mbgop!7WU%uuo+(7rI)LOwKB5V zPhx9O!~7#5;idazX9G`yv&s!Rhn4lP9(bG&8$FzVQ`=>7_~+{IE0o=sV3uO&%z%1J zB9v%U;j0bJ`n3Z!ivb;kP zG4;lrF-bb8QJ?k4WJ}M5m6&J5(C-V>NA3ANOykt8{@Pa!{N3~n*(^I{!wG0FJDrq3 z9Pc1YX^@D{%Y(+U!HWBP$x?}n7ihdEdk&LO0xmvxye?uYCwQ^S{SJsVE9m=%`v;*_ z@(g|2EV*<8soxJ#O(vA(Z72)-FcapLVM7xZ%TSy;V=>b0ph78qrUo?e8*Jg6Ibg|M z_#M#tcRrcZ4K^v@$#j9&h7jRKb#yg2VXI%-@%=~+o5(*T8W6CV$UAd zhGFNetW6J?o2l%UG!cVU5)9cXDk!K7u0Z#leVuQjsN*!FLWLsTw&kHHIVa(b@^^Ce$jdYV*)3CJUQm@nk5CRm5y`SRPmovwX9emIbn z6I0(E|MbIwG;42^wf$SD@E{p6s39rKX2&eNl27@G1%xHnp6MAHHYL!j^d>E>8=($r zu+B-f4m;=(+~{1X28AbwHhsr(KkHK?tvmHZ(_&&?+c?}!kAYhSkhVS8! z^}6B>S|*9j$PVUrpjj_4Kp0d+@+ueThJ!mMB|{2_wge(j$H4Df6+4DB_5g36X!%8* z3#65(KBHZI%Er%;e`+(up{*Vt#0-})92Nypk ze%vs%AKfTbYQOgX!v%O6=_~j=7jpj?`qRn3C!PD74I|yV*MaPt-b{001*{T?jVvf* z@ZEdK>!9@d3m6;ij!$3LT(@fw`uA$G`EUm2XD;>^udwcE(n|K}Zh1RAsQ?E=uK|Nu zZ{we5rf{Oxw4J~7#{UXU)J-R8Qup5$+!PuTlD2Lwwir#s`Sa&x49j+o5GW+Fr@rD) zmkJ)!Xz$+gSOHg!%-)v#Eo?6p7d87$NUHy)e zOyHfuc)bS^_eNyw>wfcL8Roy@3X2xZ>Y--_huwCVxV3dPkWB0H@YhD2? zH*P0u0J0}w=p~2Ta#GyLm%|cTZh3rSVlZ0VGC9$^Co7LvZ<*}Ud}C_KLG7}%oRKRZf+wz6DR@SXMNN&Z zR@A6I=2+4Hm3Ra;IW=c?b$rH^MJy6N9(4LIn&+R@sj&r>Zed`_>6$N`8qX@aQ>19Z zFb*r-Si$ZGO8ecQ9Kjq#OLx9Ag8k*5LeVN(r8UPu)rX#{J%_U5fgyF6Kn?Z~`91GIy=BTu?fQr`s3Wxr zsl$;*bs1gex&hP_g)kHEELTIndmQAIm@VeXv_l&mFk*fD>45Cb|E~82&fx-T-g{qj zMp3ISXgus?9=3jzxMp&nHEKbA*v??iiJ>n3FelaR(QC-@xw&41Y+Br&4rtCRrfPOr zc$M54)1e$5^+AH-F~)9vlJtdqX|%MSoQv6LZFm-QR!P)@dn#DoNc%W+d; z0DFbddZ%k1J<5z4I-jz0=UMe|8I8-_O5JvYXiH28Ck;+SBd+hc;529qOBcx#?{5l* z$4WyG`5o%~qC=(;CPBNsIF&)z`10k;yGKV})(@Sm&8XP$Uxy)u2Mq-G`NY!OGpbsN zYZN%L1JOxc$2WO4N5=yBCzh4N24^U_q&sBDV+MjBggIxMv^9cmp6Q&VGt}&lF3Rwi zP-+acX)ixsTUAxX?!gUx8$k9O_YN+ZsN|w>$qC({`?cM=dLb`}KMaWxv3@&H0{M-`0XE z;egwCcx>WPv1EI7G?C-?AzcajJesr6p ziSA3AgsC6XW6SChGCr``(??@)=+HW_w)PttHQx)z`9>V46%8F{EvtVoSR0&PeKNdU z|Na2y2gQR{>dqtvh>UNaTQ2Pc(t((+)LcV*C2H%XJYdwQ8+8uG~#JxBnW zJZWCO8K;4jDCD0FcHd66T^RX`TV>UgwNZYG;M`j#C@aPQ!aPAxTik)ak=g~+^BosU zP$}IvM)Yh@NJ#bZcK7{$dF{=fgC#Na4&*6feQoNYjnjL1K_Jl79-OE`=$ew`H^eaQ zCho3xEj+->eEAC}hcI|D_LR&{j|>}0aWOF)dk}_3LcAx(Y0uCH|JTBjh{IBEH&`As zqXaKVr`B83hi$m0Ll%`i=3fEU9i^{+3E>)@`ZoW_agCcr@83J^o>x`7(aZ2Iudyyw z(<2us+dv5m+3*^4pJG%hq$*85aKea==DKfWDX|8NbBt7QPH4mwjq2<3<4Ga|UxGD@ zNOdjYhZw_cNXfQpx{${Ig!9P)63#$ph{) zpUqE)2KsLC@#5h(8i_ef98&LgU%JcNYEH@qQB|K3TB&`z6C2st*rb0|lSQ^^)2j6} zR-(~twzY5rz>t2UaMrG!JL}x@)S3J!tZtom{J#LDGfS1zr=q`Z+k1; z2Cl)|%-eHyTFIh|HjM5w+(#I9X=msme2oUA_E!t_J12u zy_tc8@XVu4ebIw2@qT)G%}p=7)Z<{8E#=_g@a0giTaII3V%x0^pfF{cnwY5I=DKg& zk{A7xLXln8*-o8sX?$M8Yi8p8{rK41aq)S|Kp0c#&5nK}nNKL%rQQ(#qW1u#$Q&Uh zP~|Pbamn@p^;OPk403p_yzy=kO(v7Cy1DSbF&qYUJbz*&%3IaGSJEJr6CK5m{jU1i3GMcXu1B&1uLyIt8I*4Nt@+WfPFXKY;N z0Rl@kv&Z_(_#w4AIY6!Vh*hcP;O?aoeC0IBi*2x_YUNXDKjM~xzzaajDnPu>oIRW7 z!r&u*RBOp*44gVAG}_o#uO`0IE3(!R?H#fI`EC`99PeXSl$6)#%4%eBQ7O_9My&&~ z-Rh4BzvuO(X@)^;R$q3{suQ=bUl&kx?Yj=Vy}`WG^&8wFD;TefrX?HZa9rrMTAbR% zUvTC>)|EaTj->#T<1=UHH@EYMi)-Sp;Ufc8U|^0kJD1U&r^7wB-~?;Aa2RUSYehw> z{8Ae0KLoEwId&v{uf}ps+|0zbn^#P_s=L=ZDah zy&oVaq+mLAB9N*Nwos_$_u+dLFD4(nb-HB=rf+iTJnI>1_<_zoKDY6nxwW+AVRHhv8rKY zBAfffHU6bJ@r|M(rJ{K5P|(XxlKB2mKciH0-%0O}KrK`>HErb>-&NC*%6+rYW2&Y> zOUjiQpYY!cIg*ep24jc*iU^u6@F^6!s_JTjkV8h0bvs4pWG|{TikpOrBjM)t4b!J~ z3X6#B6uDw4`8YB5!Y-`+m`2CxkfVQN_MHUy#QBY^J?WW83`55TI|B0F z*2;P@lpY2I1i!?cj@nSd6c(Of1)WJF}Mn_v>@ z9awhYv|_`z+GqXc<$Ga2DbZ4_bav0I?(iR2W;6Moh2AfoF=+SArAbIgxb*5hHglTX zW1#*j=m@?^pFDBw?*=A)iJmMS>>?k&K54NuR8YWN+Ewp>-^GiI_|3^8EO*=6I$V4B z2Ex%RJMD2OIlSd^-3@8Y!d=lKxV*!Cy@kqa1Homg`j|P4aI&krEi-nefAl1bFwETT z&yNFr3IQ^WJ-I}xxHN-U8Ml=O*nGhUyYRx9eV zpoj=jy@(3!N&#YUeBsiiq0Wz?-_!$I795gv(5KaK$Vm#V)CpcEBC=72L0eZh=k^Ue z*D1x2LhH1l*oaFuD}FZhdkcZ!KyH+y_*rjJ}79e4*91sB~0P4%@6_+vI&{ykL>f)!udi&JwGF!b(ir}iUMP3!Na zq?86d;#k7Q$@zbDU3Xm1d;3aehBBg~=w4>-GDJ`_quu|GPN-8@tlC(68h9+rm zD_SaPPc)@Mi{|foe;w-lp3Xn#)q{uc_w#v=`@ZgL@Z$1q-Cp&A zg*wYy(bxf#m%ij|c-C+|Gh|tCf-Z&kD}0TLi4g7a-&WYfX=?ozW#{ry-;^)xj*17< zIbBKkN!XU}gW=N#o#o*|7*d9rBe2Y*<7JaN_sPtkw_u1-pW1u0mx$A)|Pf?vw*Du~A$3UM;IToNQ}Xc&qxjfd5> z#tEgXR;*aCo?4BT1Zxww8$wnrYPGoEL#C%=Q>tX}Ce8U6hRu3Uj$Ekp=luXKtxh7C z7wV3x>*!MS+E5mf1i&{v!z4+PSjJfOmn0

    HZ%^o8@O?Fi7i)(6+xT`u>W7g(V zdt{UAwuPaRcF*fLwj6uISUDOmOY|4tG5&d?#M4nYSX(?zoT1v<+GLL$#sh2HO(aZ8 z2tXl~lCXWdqR@5uTEJQvpJU_N(HPnPDEYk)Hi|b#M1@nu#l>CAAO>0_IQ0D*I@bRk z?4hc1!Ao)3bHi;`5%~BX8T76J6%Plk!CS#in~D`#xr5$aTP>W5DGtUKA^W1l^-0?Gx#Fa&>kaGD z?U(>{dw|S6nT;!H?dO1yKX>=6oy_<+82eTG;MR|SB6l$Cxk|0yp?zaVQbK~0)IzOK zIT`aD`^0d9ihc5wV>POZVyxyUtZjErXh{q|F{glsuFeqPRCdyq!C6D_h{e>wO?hDP;{I}QO=a&&%vW4Gbfv&5 zqMg}~6kYEwaK<|m3z@xe=)g!k>VpwpM{#=={l10PJMCy+fUa0`)1i((;K;(<=RrHP>=rVf7FZjUbu7#gw>|?P_;_kAfW+mI$jM8`k!)piC^4;b*FFAxa22Z zbf0gGJPK*3H)(C^Hw~8Z|ml8JU~fA(^v=dlgp* znuoMmG0hz4R+7GzIIc#t2G-PPe#Hs&-b!DA@VtX;zEO+I#U*uElo_u-WL|JOCPaJD z&Ni=oo;2EMY|Nhw0f-~nlm=yECJ_3@s?eUq>awn^Z_=>7b9}-ySNA%Px&{44bK~=&Sp-eb zS2Umxkp`F$a52MpsylT4s;2|NbA=h{1ibFwUyq)~F)$@ejyQDmpfch4Th!MEhzX>+ zOab34OkCZ|ve6(t^06$^;x(iB!V?jFg5*hkuiUdvEU51J1qLat=SIqXgY`|=CEtgt z)VKS%!6CXBK+fS}KYg&5eOQjy$@UMvzCbl=(fny(VFqiT{fgDccGhoxz2K?s&9G$2 z$g6!mUY_bWl1J%9&IM}98dr(=ZmQUHasaChp>chWH)%`z%g0qtk9tg}lPIkF-gb%l zaKJNpc9s^W%8_@`zK_v!SI`j1mZ<;ML?y7jt00Sm8Dq;6OmX#0XjM8aB zL&r=-L%oY*^JZ1{(_jB4-C^KY0LVNz_Qgyt^cCo??R|@(=|m)v+bv$o7j%*9n3m8Fj_~&|C*C%(SF z&SzJ-D#fTf$!P9wubgJfiZ>A8!B60#7iQc%Qd0H8-p&0BBcr2BU<kRa}MW zqzNvTCDdc9x-i}ez*j66-3FHP{qWsGrh`%6D5pu)+Bx?)6-_Ws)VD0N>1>rJm9_ zhtoAM42gsC06GLK!^=W=yM-{d85`-d7(2ztK}|=KMuBG`qIS4KaKbCvcF~*_tX`mS zmtbpru&He*@F0*EF$laUCFZ*}6I)KpPAj0|X9j ztI2%T|L&!*>K2O@(W0I3rpG0&vhx8jL6TXq>#lx>6OfVbamJH-9c9S$#j~Dv;lhQ- zK!^p>+rju5O#yKtTzXkm=eRN7)7R->zEyIMbRw-ujT9`ErbVp@QBevg#pUy_roTtE zcMSP~5ZrzoxVh@z3ADf0Topm3vv@cWV*LA;Xr#F!==*{f)k;6f&2v$;^tp27d+DK} zBSKW0Z7rt^%AJG!npy+}1=GA`2mQ8xj`qKMR{%Eb;z1_8Rgw;!K3_oO$5MfUac7C9 zj0esqN~j8nl80lSjpaT{*RIW60a5I;X1#12a3(1JwS$*D8Pk>ZD}3#<>ge4!?{YTl zCCi@~&2IfEx&HNsq1y;kEWM~vb(i)b+xrxKx1>{7^WXgD0vP2^unSTBK_h0>_#B6{ zaRQfR3BQ~**!EmNL)iPpePsu+I~J|oCVD7##MSebpa2+J*{@dI{JLFW9|&UvazID+ zU}*wl1GrgBMop{P7#J8rwHazCXGyY3Y8%N}P0XKiMU9s7`2eE?R$~SUi6%#aL+n@R zIkY53F-9|>%loUd(UB#72yF&n)h?fvj)A3uHCEm1@MqB&~)2orJ-%FX&s zx_Mp`6Q>cCE6&V@I*%j0KO7zKF(JaYR`wXa_wi&8%Q8!kL72^wK^;i4nmlH zy-C2SGZosd?=|eO+aE%a^ooDjab>ds`-4GJ{>EY7tX&61ep`5`*d8ZI+3zHinAsf`UD*B;RrV4)JZ~j-j|n^R30>>mGV2~&D~==Pz2TUM?&JoEW=B6bx>OFH zOM7<|oJ~Y4UO5wGTP+&oUf@ZU6Fq*~Y3^!R5R0SHgeQm;r@t^dS=ohvd{%p34rU~6 ze=S)(jvN(Pq^SJTm|m_p!H(8%2t?=M5P_4ga2*iqBsDH|HXijy#|WCm)SL@&%nBTag;1zUTH?@;^u`~MPeyqNfMw+&4lFXrmz$#;TFTj8Kz zX&%>NO&oV16c=BG5wScne%HgzQ4AoG(Y!GrD^(P<`g>#RRLu!#g4qF64dK2SJ5TBX809L{Q*@Ur?&^WPQ%!HIn;WVOQ_9zqI;7 zm@AohJ_2I~e#s;ts9gPTLTH^p#<;|x6zV=Qu)Xq=Y*dt*F#6bt{2Vy14@TIcp-}I%iZh+M& zW(olgDHdnlPz(|Yx1zx4o+_GgLa`tXBM6__zAGs>6}8qOoJ7`FrNG{p-vv$I;)vYLDwI z;Ix2`I+3}tcfpOzmv7?l4}bZbgHD&cGyVkDCu5Xpk7#|P)>DhK+3E3OREe9TAKl&N zbY)Xgi$2X5kPKyd;tWoF2k*vI=7f4o{k$J-SV6t34IslEq#Hl$Ifj^0XeO+JTRAYx zBq<6jjn&nap)W$#z|YO>^D$Zc_o+kvXF(!a4NfLOfA)f>XCIBevSn>?A2tBg1$fP7 zn?RdZr=d<@5LK(QcNU}Xw-OA$wCbNEs z`tX%sGq3!LbsDj5A>IOq(D#Q9Xy$P~jzo=~W}wYG zQ#~A#pki+9OS@nCnw&S|`ggy@Z`!wS9|y2m=T%b#xCYLt9U7+dX$s5^GBY}`fB#{h zLD+>C=TDF4yE&KoVj%Lj1J+Ueuv*l zLyvR{q3@4sO>;qSo&6l8tbuPTqdrIWl3cPR{!!EY%O4Rjo%Aszy(_3)Q}Kwz|9T(_)jc z*(`uRYjZ9Y{MR5<-U|rjt>+{sCnqoz0RYiEu3qwDd>l*QK0~RGBhj)J^!=E@5U|4I zVt4fuq7fp-qhLjXMdAxImG_f7{FlDN=^$nG3lt&zn0O@^y{7$jq|(F|kU%-2fPOJF z{In3L{B94|EFAbsXpA9ukZ?>G_(=w`z?I!xCCBF8{*XrCGG8JfI2(Wrphl4E{nrn+ zTX3h1+w-g}Swi;R;pIW+cG3*FE4JP+Nd1R{vr}%cAy7JF`GegjxmKH{@zP>81u-dOp@pCH^s(BN zh1NYA*Ncc;*suS=5q?(CVtwk`AS05aZPN@56cM=G+ojrG`*0MxvrK8N-8KjOps!cJ zt@v?YU$e;mcMQKa%LpUstfzn6n7;Yti{&Ny9=9HFyK}@VK`$XLxK&eq8K=rEZaPx@ zX8&9h|15FO6$CY*-efon+G@Kl3wB_)(9cjbi_N|rEq`XzZgON^gW9tU?IbLb)`g43h$vc<#AXa}a9D_wTC#PIHMU7rPAjQr9 z9>zJO##mw3gQ&{WT>GN^znvCY_Tbm|YjYyRA*qvJBi>i{Y&U>X<=j}wBw2+rOXkZK zSd+D6wL9p>P8!inL%*g_G4~tqGFWvOp2IxN9q0XnVtjc*FAc zlSYi)5!lpg&s&sOeG#|1ddn(N3KCBO6Najzod;c~@d%4H{4BnOO%QS+7K(fqE6B5s zEjSkJiNXx6iPh7$D&R9SZh0V!A~y#h(RavG_M$RnIs#?1G>+bPuuu@WsG=fBEcA{& zKTofwE>Kn8N8%#NzhE@p0W&wiCB09#uKM4=GRiyD2M!s^NB)`LZo_&Kwp*Ca>i?a7iec%}fWt2?X2#oF)0Tp$ zK*d(?p3pFM7*Y#le3SrM(>wI zSTY7rkLWv^Y1*Bkx`XkPY|18c_o{_mXxo=3v{=7F?hmH4X@uKz0Axb@g;^iI0H6!N z9zJLn{F0nGy83No@DB>Y z$3>qRhFHrg5|o9^!thbd+UFFf`zeTz9|@-zn2im;%2+05pMM`H2rbe;#Q&E*?XkHe)6qLjJ_jgGnVTD=l-=*Q*q%WBHBko zCpi7r0Lj`Vr|JJ6y8qM~zsH=j4rbYNvL+^xz8o<-Q;8}BmjV+Ai%SWql2b9u?jUA= zXPf$8Nw4iLjE9k6rJq843)z97R4%SIVk_U{SC8{YZ52e9)zL~5Qm8y_mWtLIHmjYp#JT(V0`Q}eR+{p#3Z{l5c$y#Y3==9TeD<)RjJ1PBg0 z)wwGA*$!k!l29jSv-Mfe)Z%{DR`*1!bg8z6JAKN~wvC>vC&FV8BYsFl&Gu8Got_cfHm zSm^xv_3l5uey~(|TC%G^n(|Pjc^^aMpNTW(?uZMZgc9Pn+y4Z3>b21}yd%~D)YEZ` z*rfvpYWr9_=QvQXyeIgvDLp1vA=G5nla?)5K#rPuL7a?_y$NI^0DLi}I6f}6K%Zv> zH?r#SCfIze0%D-LEbyO%?S2OM$f*(|iAq1U;B+Yai_wflLebc_T2Ugv1lWc3La10Z z8c-reg0a%~IppfBJLb=x!Wpmz|9r^NwU_^&4atm3-|QU8U_wZM=EX&;KBg>mWy`W1 zXHMu}y>@M%^G?WcZUqE%rK}_J;a_#H=QOP(Q%Sx>1lu!SwYwW&z_-Nf{Q2{5h?W>f z!l{sR@BI$I;2J(Ak6*drLiRE5L#(D%e+a{Wd`1KE87*Wk&;Rr23Zkfkb@zj&K3#6)az%!tc1uMJCGE%Jb_VdFt>p4#($#v30*=4uY|kVu;x9w z5TfGxq1G4M<7SI?hzF4OQ2yK!1&%|8ScM7M&hpp)^dpCuyt1;kN!hk}qOUEE;fVHj z7p2i(7Q@2yeXI1?O`Ht-)wb=5P^BK5BC+N~&t#v=8wToqlB#=#o3FK?8&+cnWb@0f z?cslwXq2m;@;qz1YHJmgX{JNZw2@7iq1oDu;<-#eU05%*uhpMK+>>nxuR|LU%POa3>v0Z z3;#81}A#Wbc~L)PF|y(Qf^ugP@izc)EQXIR70a&Vh1685lIRxd4DH z0uV!8P_;(mH1XL_YqWM)T}r#cfWrgYRUR05Rv#LExXgX25I?`gH~mTJdm%O3oIbxd z4>$Oale~s-30C*Y-~N5J%%es=18LoCT8M~b+f?;SDi zAA5SLN?z1`-O%wyRQ=Kb-PQPWjUbaJ=Je^8)Db!kTx(n3o;X@~RJ8VO?WSCU5mwZA zzX9njt|dLM2+_-D-OfC#wRT#UXbG-Yv|Pu4csDL_?=IR*Ja9l~OK-@}ONX_G;t&n1 zjw(w#kZZ|R30kUxvo`w71v`h!SiyQ~oPs1jEV|M>wT{H_LLUQ!#hcOFQ~&lrmvD$F=&T8?X#Hjw{G>dO<-Pyv<;x$Ig22+qkjvNi zu+JkUTa;gZXl33V-Kt4^xBB14mV9Qb`Gc(Z*Y!OFpSRug7zwaMJzbR_B4%+1d4j8? zmNF1Q+8rU|{uCWmR~P3iSK=5ktLgymxWpqNoYT>74O^jf&Pm6)RCLfF<7klhaG#NR z<_k>Hz`ypIamDE8>Z_X^Mh+SsKSqV~ar0xv^OrqW&>}a+=X?g_|4G*f4S`tGR!xa9 zsq<%8@ceVjjMDxQkS!SkCbcr;x>*?0$)3o7W2pPpwzI*a_Vm=xuEP0GM^a#2rHr`f z7n{dq^d+Ld?Py@%oj41MnDwx;@URcM^j%&vbJrZ9c1>|bkM-(4uK~>$LLZc=@zvwl zCloR8NIys?E~5phCsAINpZoM*HR~ZYAq2vaAfVR-G58`7!FC-r>nF#mO3abl;g-p> zzu~W?1tj>9Al>kzyVL>@-vlN~_LaL=q`Gm-3|oRl0(aKUaJA`df9lL&|JR>K_viM& zfmK5o9}T^GhUhpL4^cafn`O0Renq$p~^00UCiRRd2nRmzKi#f!UcBUdE76zp-DY9=TSvG$T5la`pSWk((Ij8ace5P%1x6=7&_;hl znNbXBj8MGQNTb!DDY zo@Gw36GUkifg<>&vQE0P9+D((35nVhI;+!pGcZvsV%b$mnf=K!P!q>OLP1hXq8Q_@ z98>-Bn+rg?{RHEKw;By;cP4w>Zu&Mj^*xSZZ129C;~K=W-2`D5g4^E_crw?n5g8zw zT3S*~5BwWb&u;$@R?8gDE!K1do+5s;t`+7_v5(eR4P4xqzP@cS>45I-4X4WxYKzS} zg@Qf@yfReDA6OSus+usY5ELCAPt=av42zAxOT5Fl9ekVmr;f@m#RHZNp&>+n2(oN5 z(m*UEqgE++2Q|FEktAdu*0kfyF_)fdo)o2(9o4A^PRA-FU){tV7xA3)CBr3`fN1Mg zg6`Q)6EAPJA`E3Gp9}1IqAW_qo!wkQxH?LO(uLSUYq~3LrnSD-Eo)r z^#{&NE`PFnKGX93`)T-W%{DIMdvBVMs;{|h)$^56=Wog~%gJ?qo7RgKI;GTqv!^A* zp?|WkoG<*4!`l`MkI@e;A;}{Rpx54zygP-Lxrro5mX%{Xye2Q);=*WMovyl{F#Ftl zKhOXh!%v9u!%V{&s8gUPRXjR!USg-p}kY>}{eNz>ebXh+aoXVEU=n*$ zsI*}qcQowu&yIk;`F%JLvp;w0e{ce6;1)qE2knyxh->b(IJRNFXiy-|zJRm!$93*Q|P(04`5YVzS}#7ZCL}IZCSexurWcxNh3} zI?BKPpxQ1e#15Dg-`>c~&ffpLQl`ou)n;`=MuuehqBk2T|AaFw@gUH{1hqLF48S6E zFAf?-!=jnFCd_epn{JOAHCAtn?(w@+GE`J#82kxXyJ;p4l(k0Vuy&Ga5~%nV#lokC z;DLv*Hhk5fR|X5EECQNHAsFJG5NF36Nf^9oO0Bo&@9v% zkeetJ*dckmt6SjUYY%nCUSvMGdtH>Gj72i^h%%qR-gyP~EOh zx~!I5{#%VpmuZ#s+&Im5O?5hWz(FFqNJ!mfBD)vD7Vuwn6s@( z!p>1Ym)d~a{4;y#pXElWGb31V7@v}#^-JCNiKYV~L(MTNwNFkY8v>YE;r3A&{=F$! zpJA+~(lmD&%nsbsE(EL2+T|YaDsx(w$^L->p%n(UUUxD1E(||+_AEENkoaO>XlrWX zl;Xa@L{2wPHd?|)AX2)mXSLb$G0XKS(*)jPy(V?sFnfKb;hxE#EFtZeCOZ`7>4b{w zhUN2=S#KF*7lm$mT9VJcm?@%Y#oimqhVH~6#AT!C`A+0bUr z@cIf&DY+N=`_qmxELtRbt8a*0Xr)B#C{=qQ=ClT}Rv}l)CBItLVH%+ModxCGM- zlCS|`lyy$mXYY-hy<4n=7A;&Te2Y=+XX8OwL52Dn=xJzFS?{HyqJq)IN_qx{!8?zH zDY8;8>xCJcGTn#M_jJ59+3r*M*Tm$*wpULZcMHQ_28Op+o4XNCM!~Tro9p!0U{VS& zH6ui%-TvRr!k>>HL9w@(9boCWKBCA8V`*`n6ZeCrxbnlp*FjWx$R2x5HBa_@mjiWh zX@d8c&C&P4HY|dbKDW4dTD2TYZn{mYwTnYNnGu0HWAw?H^qYYHn}3pkNsOgxOZ~km zxU!>qfmTu9z|`R7iQ})-j(%;E-6=IRG0l@Mq@SWlYW-0e7aShRz>4V?Epl9$VJ*$J z^~iYu1kN`0bK5rIMb%N>%xw6Tk1|}w3?PJG^qveC*DlcyKETX7i2`B5LjHUnpDhwh zf_AuP5jq43U9M{u0HeAtcwXy%MgCwn4d&1@EfwW!twMMiK1=VClRG^?b-0kS5H5OR zcZ5$5-7FpZWb~liYx3-|@#i8wJ9{ra1?pl%CYuf1>A<6m;YPz1J+KQLTGFt%HqiZ7 z8ESh0XH??8hqDyKNy}oAk^&H7r-ZFrHUSbQ4`}23U1bj$zbcSY)J`kNPl67{agwV0 zY^<$WW&V!DTvK<+^qDoGnZ0X_$oZrr$nQ5}Dq(wp#K3f5iYjh+BGoyeA+fp%?hXI5(&rNBGi%_EepO6y(sv1bjt5<_2V*L(~jf{m0wpl*-8;^)c?Rh*%Bv? zxasQZj&5s5f8MQuuQYx;{F%Ev!Dxxb5%$dQK;=6HK;_y%qS=KD7jA`z+oZ<h1!lKqEJr_lqPb&N(vJ_}hlXMH>jV0dP^JulJoDxiq;x2wp32)&|mk_&ZAU(R^ z=i%vmH6CSe20xD-XJUVhdz(3pAyZA0C{A$X7nbWJ=$qVSfA{3V`SWj}ri5KbPE}y$ z4C?gnpSrK%OXXI6nl&6vT2^tizNEO=vXgc7YIE-L6RF$K!0Qs*Ba4I;mHNs=#wp4? z`Gw*VMIeI!l^Brj(`;H>1if|$3m<@I@otv>(@!9=lp}ZORSna(8*{AzEMSphmoVzw%qp_c;M}LCrd~Nznhrf=z zM6{FTlP6CoF}9w^xA6J z1XVsL(Nx(OLGQ^XVV&Zw>i0oAUiU+CAZV}GS5DE`z+#3 zqhG%XkGgI%IRMY5Vz`S%lIr)BvwOZOhSkV2zfl(8HCMqyehuZ^{8_)(%~4TTw}G&% zK+jK`lJ_eVJ>_%JGif22+L4Nd6ygwA`~>;VRpnl_AW{aZdnQRflr&n1P@`IZ21V-1^{SJG7oiTc+ zwa*g-JW#!DdNO~S4+3^^aV^4+w8z<^j7iL%zxu50-At?=oKAUE7gLiL7ZEE~^Pcm= z_bDGGW|nVBqw13e9(cEeMbeI9+CMNb(0TCPsEw-S(uE7Zcb{H0mkyh(VpJKXvsd#1 zYQk9f#c0136tq$Q(G5HadQma4BCJ>e(gUDAUs*L^Wj~G<pt?M(ezjk4s_x$Wv9xq*#kv6Gu~%x$+NuULD-<%C)fDOwZ2r;!F97-W`)` zUC^N>!$sr4Hg^m^dWXl{Y~Y$PuuH!I#fF%A!GZ)LSt>=jdkkFzo|vKI{%G=5q-vs4`pb^gb^7V=JeK(@~=A65}zBX!BUZNmFT1P zfL4^&Fs>gpls2&bfgrg0xaOuN0djtUY+d~$HYv%b?|@&^u!skadY6kI5Q6@vaG(8C zK_o!%?Av}6_S4Lt8DPr5LhK;x0aR=)RzZUegcq2DDDvFB);5-ww~4*W!(b?V4b`^y ziQe!8hQxGy{8{wyd9P0d^Wj4oP%W+?+Ke+unxuLdY5^FGp zXZtD(L81L*sBFzdBGsX4Qv}y49<+UMy~W+tE2E-4{$uPjk4gl@L+k$`C>5Ni zhMj`~?dv<8SK3F&a0_nA*950A8$^2O**(YM^Svi<)yu0iz%(}z9q`?|cWd-cBopt= zm*oS~n+k&Mii2+(>*{U*LTF^@uIBQJW*^no z736Xz(Qr}@{Dp64Y z`lSk0(c$4?Vb}!_@WCoRkuDxpq@r!@!@X{*ESra&#H6L0mcRIg&w8$gM0@3c<#yD(!p2Ct;2p&DSWU~wwVrGKBD6SVk$ zj)0R-vHe?evPx%)lY&PDNO+c?e&&HzLQ||m@9zi(YEtYFJ>jXYi+X`zE0gSFBmg|xR>%9?Byww5Pf$QMp zQk(y}x3?Pw>F&i}#85D=BAo^T0?f1N5Y2cTS^RDa*(#DCh-`IL(+r!SbR$qJmHf5`Gm(uAL@W`Ph%to3bf=!R{v! zAtg}3Tnk5};Lq=P$u1Tx`m|>tJr*CeY|g4y96CipM)2$gw8IU2Jca1sl6aXnZ>@~$ z`wxz(>-)$-Pj1Z~MG&n|OspNKBUTbGt!-@d9~rSUS%BW5rX?}B81`w68w1zj4Yn~+ zP0H94_ZR%F@MgE`4b1w9gafB@{(QlCHWW?}>VXML`V5Jt1*oQ87UIyUqs#_## z`gYAJBwSycp1k2P@jxYT%e|74ZxHdmirL!}gKN-auiy|9Rl-Ot+g<|VT)TE{iD@Xr z0pLv+p5QxfiOF3u(m1p4L2Ntz(k(kNoHs)Ug9C&6NM|p>fmoJt{v~l|)!i#Aam<`K zJJ%UIFU7jkvFjlwNrZ!V8^q3*4_lB>ATAym85NcFMV{N`t#{tc>;3naCyM5-nWs_E zMI-uCIWA2?RJ5+t5aU^~6DUmU7Gk64@+SsAbS+$Ex^nqtT!PNfVd(2vizHUQRCDv^ z7qiphKX~icSETX+p}8`@)-~DdsWV2PMa1zCJnd2|kZSHbm^aGF$pP=wThGN+wkE6O z2wp6+6H=QT>P%6Lg93j!KR>^u5Mv#j=e0CLE_<7YhJnM^g^uCOYX>Io#8yJ2gXM2r zzhB9XN*X2!hs2%@0iwqceR+St`#%xlg=8Rn*#Gjcm?Y9R;d;bu{eZ5nS(Pb?95PY;3_S**RSz-1=pwexVw%aY?)Kd=fkdW(1Ji;CM72-asAN4L#<}*Sw=6Jt0R(FTMfxjRq!_V4xB+$h-M;}iE-VsoWxkrk zXWe^Z`Piw~`>Ph_1-Gg37z_O@DHBC+s*b3TF_;VVT~7!fIOhHSm3dxy%#z5DLFl2PxrN0w zkD+xU$5o6kJkOxhl`HTo>I*Qi_l9TOL5jikPLDH5?)V$XH}difGx!eQxXaqZ&hJw` z{!Fbk;wM5jEu-8+Wy4S3w&c2nCSovX!OZ=u4>qMH*+`)ARP>j*QWu*97}h+!-q6PT-7#)?0;Sp|c2`AfFsF>v z1KLN7Sl)TPq9y6B2sZM=61*e=Mv5P(U{C8yK3X(yorsOyglwZ5zTIX?#5tch;#=0J zkbECR;f2vrtTQ1jD~mXD=1k#6`7B?>kgzTHy+5~lOy}NpZa5)q_fei}RkL0di;k#L zUVMD%2a_z$A?$PFd{C}>*Z1G2%%3+!B|&BYyt-NcW^3fAl5assskCMZ0R2o|rT{3(5Q8221?IQ}{++zt1a8Fxx=k^I_& zfC%s6GPeictQdz*Q~zti6^agXE$-J$5n^qHicB{5wFXE5Wq$~%;CA4U1X-D8h~3y8y3OU^0c(zL}f;cKi% z?bN58Q!mV`xLT|icK429G4JMIWO3Eod#h3TuYxdF8lHA^|}sRkR|~aL^m47sivhsyP-*Le|T=Id?yJ3$1s6A zprzIE*hBUD^ow;<8~~&ZuRp85fU@PhubKcaaRer2STABU4jka-=P%)j=F;^kjDCSp zfajBEX6OVy4h#%bv8u3RdE2HIfGE;ILI#2E5wIHY65Fox*E1E*UR1eV;Pr@EvTa(N zRg8V-hQ+Vk9tsYyJu3RCvmR(#AcBrTb@zVp)lnm@a^;fWT!03gY9?U2C5BN?&apIP zSU4VJn_4$P+~?PXhfw^-%P$w#gm0Y|ypHMT%I=sJ}zkFM- zKtSTcqCUZnhay+$L?t9j$fOe8bl>`s!9hRxBdcKVD+E|^JfZX6pE`l#7z)p0+)KvH zt7@ClqOE?!{xwLnkp`Rhp-os}bn>2WUCX<%@SO+c4!rGmjEP;Rv$w-V$i=l8zJWp{ zixH)nT2cohC;#84{q;W!u8>>QuKMx}HzT5i8XZSrswQur@TwK-+x+n-+&Yql9|_XI zcBL4k*3Bqy3abG?6OYs&(Gv$&^pAuoJ5Euwk_{wg3B7aMi$v2}kXnw!FnczMx zd^bTN!i-vkmvvbH=l%fc&1a~d8HSlTxTmi17%)1qq5i0YI_}7JqGrI0ZI*P}EfM#h zm!b_ZI$_iCmzsH3DHP7g5I+V=u;TQ^d~zL`{-`jNXWkAox`q>X^>QP?)(t5q6po|| zrNVDa5euR0cGbIg-0Rmr57>|;R*UUgpXm^dDMK-_@ZGQ>=HRFUB{}6Pwd+^~t`(k- zD>%-bnbf;Mf5k}3_~D~_!&AgO1j7p-Kb?~UpSSW$%+hv|9rDl7;<+2+-}E? zk>bxZa+|-oem0GUE21Jg5xf0|4n<%zr>v=YTWlTmeX>%dIktFAo#vu4JlL)`s;oN} zDZ`$c*S1G$YRbKEGPo`eF$6H~?2=DrziQ9*=TpsmWKyL5*8a|XDM#gk{lX#a9}@jZ z2wB^9tda4z`s43ZT0uGuLPhe#?rNv5tVA|u4XU4ed#waliyU7R((CyqhT%p4f&ubvd~vFrk>X5EC4nABGWnFiDge7aNj?^3#c zd+KMc!p^a*(q5Y+B?`NCj!h>(E|=Y`SGLSl@>zUsG3F$B(r4}VG`CPYF+6i4H0mWn zoGd?#Das9E8wh4X0xv0nh_T*EDJC;(>pKYt(;Fa|E9whwR~rwI1%rcF8ARE;0l+bf zbfbuWJrfG}!cVU!r^Sy;3QAvwJ?vKP|JEC@*TE{Y`^4t4GwO4TL!s>>q&j0=lg>X* ztv>?iX*IfAJ_{10HY7q_21SD-u3n(O|4Wp=2X6>clOZ3NCwEKCFi%b7B0$;aM!6vQltcW2^76-=OD{f}IWTv1= zgdxUT1Jw8wKvcyY&dFCaZ3d>ej6m(tw1dwBlY8MWuecFfg4OG#TZf*%k*~1+j4O1_ zo5ZDsst>mMLz}`j`5(%`c~r)Pm%c(f=ogKF?E4+uvenM(^ev;V$Vy=Q56ou`2-Zgg zf-!MhfHW<^t`OnYe=U{f2nq^{y579#8P3=G<~6dz&adOD>gvoitq1n@zD+gkxnV&z zK^$EZ;sQxuu59-C!n=XH0s$8cr)pnEIuDpqIB^g?8`cP|m0~qxW!mXE_r8fxC&jnM znfXLq{_Bs}rsCBa!o{5KB#9kud2+qHP#BKBNHYj7>t^=i2@X`I)r}e& z8j0a6Q=Oh-Kn>misY6~Gd`m9rG|C!dJt3J^ zu4q|H^NTV3`$hgKzi^;1kOSrUCXrvB$@qW;duU=B`ned&M47rtQj?7ACsqvxLR*Kt ziUX|Ia@DobtIj!S=8^z0Vwom#(Q+(sNJQ7!*}2!78hR9%j;+TWGwMd@JhJt4=q&4# zU!62&&7ZgGHjQZs zVocdqw%~0tv(}8Cm)B6O`|BBe&99tUV$nD;Imv^|?BmCe(u`EQ$P;oGib!%9(_iV{ zPg!qAzBibcV4kOEp?8tNHJW z?}31B>oJc+Uq_K!GevpVp=tidPQBWc+3CgjS65dkBhN|PdYL46-|%U!_hAHC4y~u{ zr#CINPQ*v0A+_YgOZZp$Z0aAgq-+wK<#jM5xJw8ZnBdc|7FN5@C)7WzS+dhz*L>;3 zF4D{CJw2|PH2z?gMCD)gO2H;lrILV8J#G&p48mTU7r{g#ap?U7PCL`K_b{gT*awZ(lT4Ue-#2s(YsD8 zALZP2(Gk%-FoI++)89Zy3pJ!~xtaoE0 z$#R}+uL%&TH0_FOH)qa!OIl>2ZHB4b}FRqDryuI;;q2DT}uA_T1Am<2gP2UiGiH`k=|~e--LS zFP*Yw5dxB}mrFW-38Wkrm_Y>Eif07XI`N4htJ(%TalfY*AjEF@xa!6lMR4KLC_zQI$PsJL{|^YpX8QZ zv~sH~H_?A4vtvhCxtU>C$6g>RzOqnW$Ll>+0BQed&J9Tmrky`i&#O-i2<|bSsuy_F zJSy>N4DecG^ZDwIw;6ML8lemz!y#5f$>*dv`t`nk?4(kCxM}0YC!CcJAAyAp3GO^9 z&dktDNUjbpor3E{@y@AlOQShM?Ta@O(w#CcS3SAWV#zh`7ZrhUGe17jyn;ls$7V=~ zi*L)7LSilExz{Gk#^os?VKmbJX^L8q1pmD}}_y=`Yue zO9U)67PF{IVV)Op(;1Ww{F_kgk`FzjCi0CJwxS3&(EiqZ&LL1Pxd3wQq1wHIPIG<0-U9*QR~Ey?vo+8tQnz zYOWwy@`Ao*;B~R{naa-WEuDpc&+B5sYM&6_*J@eP0eccBL5GR}Y7hsAHSzuw>bR%o zHE1^c;IC5|`=RgP)5|}GJC^0RegWQFr}~^7+%ht#j_d00FX}1UhA$YZZAZ|(uyIVS zGPiRR|09|#o`{eL$ER;W8{j7RKXHZWnIvRP1GwiV)RGIXP)PuIVCZ!=#N5E3<>|Lb zRdvQnzc+Pe)f<1EBmX*vDL05`0Krd87>XVLoEgT<6~~@oAlFFAK)DV4#rWePVyG-n zW;QqSn8~E-)L>^3I{eU!Uom!-vj)Zoo#f}ZeeTW%34)3A{cA(cT(2l+Nok=c?XdSf z)Qq9d54}UPq_zqO#8+8R$PKp9p4JLg*WP1Z^&Opgn)U$~(N1-bF%8nELxA$KlR4o> z9xlL276a15pRN^hzd;h`!74#)%|qWeiP3u9rc?HarA$=@Q)ofA7 zpML*|iXczz{HkM*t|y>$AilW2u$w4+SX8xG>WQM^QA~{ON`KzO6T53Q)TCa? z`;HrJ$od(Pm6hf6QD4a*F3sZpJ)p}2UKxiAfuTyoX4FM;|tf(X`ss1?r@|-{Cwh-f+ zw{KZxc=L`TMD;d?I;Wm33PSE!#$J4O9i?~bI*9cfh8S%94}8=8OzUt|y@noomlYh>0m7$pnrOjtxKmVY`L?@_F%$qaAwaP4ba$ z@hHo)G_Ms?m74~DLr(r`&I&R(!6o%S|7oit)zi>-kyF1nO+f=ib++}J>#@_y42u_w zU3a0#MXd;qaq8=BSpeB2w`C~%K~%MF65w3IZZ?)WpK{C1{O9XhELwNdgrGkPq_$ydeY;ewSAstcJD8lMIk%I=vHMZ~)Q?H174lo`6c7wEr|frCAu;_aa&7>k1SbhrJjT4V<0L4&64ZGEMNWqpcO zLy8h%#pqva)^h_r$7iv*d-G7LJtS~22_<1K-MzLeX9&gQxSn~6w#2X2`f%jz4Hp6Y&5_@yI!Yajkt~P#QqXQp&Xl!rF339n9a=0Zlb?kUEMr9pp777 zzR{sd{Vf92+DtKtiFc6a0~)lL9F%4$#4v@ZcR{tYlUyvb$`T-KLeW=uDdTGz5>zLu zovl!E7hdF`w8L}l7%Nh{P9l4CIBJ-5Q-JO6%bowBIhzYH)Nk0A!5^SN@2La#SPqYXi zjYvz=CYt|DJwKU-bcm>Kwb#GyeesnpP*v8Lf9T<*u`yS!6ikl}kePSZ#xlLCha=F? z)hw&3tQ&SpGWpA}F@o3&Z{A!cS#);hod5U1bds!wmgHNdv+S73*D1J1mh74^W?h^a zDq+%kKo18Vajtr;N*&DjsM;M?l93onD6YA? ziE~L7oX+W{8S-hH5|!!}u-keEkA9GmGA#t{v=)F<|LQ%)eGtMFzIvsEVlavMM^nzQ z$R%F6G|e$9s+IrL7G2V%q90(}q6BXzFso7-l-2jrEmC^6>A5OIu%z8O3k}yp5bFn)MOjSUB<7KF zAGs)$FeF2YG{Wu@nWckFw1a9I5^HfatyJo77;?C0Ee%nW=KwwN--cVy3-5d&1K;b8 z-YCK@USsrtEk^8{J5=FO^WUq=K$phoe&cf;jEf*pBf4L=l&PRf4vhoLtkE^@h$m5wWp*F_Qt?H&R)vQEa2;P6=~iY5Iuf>P}ah zQZ6)(W|~`S&pS1Lp;)dHiPXGdn(Gi~?=d1CKwieKJ(0;sn*)nnw45eX9!g*(m^+`Gz~k!}UxBH65RJ*@LStGO6h?59$_D-DY+)uF5@uq9YS{Rb{4Xth8p zvv?jlDz0bluwgUYdu7y6?D%!hOd5njwFBE!Af{L8qLc3XJcKMy5NL;Zyrfyye{`hg z*N(p#Vx3iF;P*vNH2A$ocLis*&gYG+V`KkNZvTD0lanZ30IjXR&W*Z1CDJ;kikGwr zcN?E<3uVu>9(nM|{g`(kFDReD6NZ$J#m-A@=>0#wzB``l_x-*^86TyDmXeAJDKlgw zErk|JMv9W1J+j)`B`GpeLiQdnt0{YB@3ME95q{@Z=>7io{{7SARl;-J_jO;_xz2Tt zhIQ?R(bO{~FSjX}Cdgk^J^DtC_X%R)5A=}k6s$?E<6}vG_x3HX2=m)g;hK0OFTK-- z)h$RiNXG%3BDzJ37GNag;AX$lZ0t-BFh3iAFk_U!kj-}GukcNHAZFgOJw-91RK9m~ zOjl1YX#cqy+v9f?*^2TcFgEts=VWV4EB(LX=I_7uSz&dhI$V7^lUy~>PYJn{u*UgA7Z1%1^VA`vuDh323Z zsC*UYozAAi@Ldy8x>`BX#Px)z_W4T`N8|tOUaFA3$jy*FxzmZE^CBXAdy|W+eeuBP zq90X|gfLkDjPzAp@(Cb$@P=A<&<3n#yyI8YV~rf(By( z;NM(t8|HivyBMZB!5X9XTHroPQlX*V%1`JjLIa z%>OZQd2n`dqlJ;r6wA)V7^g)YBk!7|*y!jZ0LH|G!6fJ;&*~B^+K(i4 z$5$tpCb(}YyE6w7H}Yh&W=JWdFK-%`{r3vNF;^=evO9G4F;9JxB*))gLrq&Zt|C6n z&LC>&U}XGDYvx_C2z5QKtIo`GCEa(rosX-Enn(&!V6GN^;{fnVqiR)2sbkW@xms`l z?-|nxG`&61!RVFkowiGZTTtARhzh1=e=|}@8`;>5zc8;E~l@U0usp{x+m(lucgsBxDmFKCD(wex}_SS0P)*1*~ zzvi^wd)L6>1W9}_C`Rbp)&E0e*&{FpljSWYse_M8#?IwG+XVbgE+I4WJ7cmoH$Q(t z&(dp*E6=8A{%1S#|MsD#F4JW-P`$b{;t`49;vd#@7*s}AL4)%8mFNA}Sv^Ri`)=9_ z&h25csRWC$J$MtlFUoRTxy4j8Pa0t>@MRn{TI=q+J|d++LJx z`Raxx6VI?8iaoH<(lV4VX+T0%)mh!z+WIR1Mv4ta6!+T z8Y%73)7O6pSxQyn#}YXF^9x)0eTWLyKXV&8bc~E=w9Fl^iwX|rO6=_XrIhr4PavkP z6eN&mwbp+5S6keb+V|qtQ*P=&CS$)^-v0 znd^d6p`mk?=V|IR7hpS$bJJOfBiOB12r7+(vD8Db3@Gn1-@iBgemRis+P8yzei3fo zMni>p>i`{z^cQw~8MW3&_7B8P`{z&OBKH@pw#f+k*b^ECS~0N!K3Z+FdAsCQPHyhZ z9@Ae;mfqk)%l?_y|B>Mnu|3IGU-!(09cy|$&Iep9j0kGTs%pfRI$-#D5$$n+m4d$N z!yNj%D=?|8M)byGOG*?a6aW@T;k>l2Z5U{ZqawUoq@$I&{4mfRNs;Z>bio!c)9)Gm z5lc9RWCGV)QC(CP8Q(rkd47AQN5#)L*JKGPaUtq?Mv$;b^{C=vUeWbQPmG-D+@N+? zy|;5@c$boL(R-_ND?eMDsRBGjL@K=Y*-Nt3?(p-Xt%^tfSv1U}dD$-S0HNihd+O-c z`e61}e|^ee$4aE^a+jJ(C#dcCNdE!#zTjw)4o%pXK&|!3!=8^9GWG4B%L9<3>20ER zF~zF;A#kz%pxV8w!&F^UdHO`0x=rI%;~UOfQk7+-J=$8`?kX_P$Njg5m7LWyq85tM zaI+a448XYxK7W010RfIvSDzQSh}QXoTo^KCQ;iySo@d263@agm|L~Jg3{R6{*&SHhp@;h_Y_7ldj;oI*Y7PyH0 zVK+Kk9i7s~4&zI)xiT|+V-w;$vF;-D;qwNBk{sUOSX?J=)B@6pF**6}ByzQ@F(=hI z3~LaG__mw$Dq)4b;+IL#4{(!HT!xN?&d#tewejaKwO}IdLqS1-{L!^#n)GdFuR~N= z(Y}bjR4q8!s3gx*WB={mSo1A1ev4@E%FZ3bge#^!?Jsg>!;s?6a2rI}#l0&rlT_(f zmQ~ehuMCjra9Ao>EiP#%)6XafF{*2mS3uG&5gyZl|VaVA#zwWNA3MsNW7Aln9G$ zq+qFKi76ZOR1Ykz68=_k!V7MRHJAi{Ms+%@Sy(xijOn1n_j(d*Mj;Y|g(@;3YA_cn zpT9dK9yV?+SDgcBNHa~%CH2fojNHJOBevSy9*)Z7%u?)?z{pOsiPPB1tg70w=D%zI zA-z$zLFE=q8xXvJL-$-lzd0G5DUZS+hS-HKR~{6G zr(cgVN?v==SMnSmqG8)Eue607n@%QIa&vO}mwX$%1hwcaAXvA*vB#ku_X+eE(j?R9 zaJ%&f1oF@L5z3EZWU&1H@|nz1bAun94B#0NbKtHIfw)F^^0?t_DaJh>*b*9GcEQ@L2iO3auL zwT+uE_h%-%zCBz*ZR=1*BolRpp&C}Wxb2uopOGKedVpiCra*o7`-TFP<7Ae znSZ%u>tHVuW#ZLAJh7W%C!t$;)CXjH#nz9%^}T0qV*2Hwk4)y>t;4uuW{ziG{=)cC zt?Dc&(fPb*&xzQ=EaTTpGI|Mn)q6kRELijDCJT=oPlAMg@^XE&%`l_1QFW1$6YVnB zX9$|n4+>iqMZXp?wS^JYVb~}}=F~zFa+!Pdx^?UB^n#0|k>VWA1Gq}fFifL}?N}HmgpmkXxS68{`TF-Dk`|Mr( zm1M}+Z(}gQjH#BM}#rWAqI8UrD zefS;>*Sc@QuPHI*!$k=0J#{U8b_$`sFeTtsi~V%o_neRItDj%jOqy0ETIguW__{$Y z*wtt0^T3^LYMuWHYoD5raGn=Q|Nf5%Pk3`HCNt`y$QZ`Oi#rH6LgpUfUu^RZHvX*t zkvJ(Ic8EVyvOb06L;0Wy9{q4|YuzS4<+wrHt_qm8tmoy;mEg_`-NAJqRmu7UgW}*2 z&$K;5PzKv)ckj*}OXY-tl1wT@O%Wd!``%lrbPA%o+WKL?`3d?OcD?u&kQO1VM8&a^ z_rsVME7)+R*wtZft&U%Tg0{9cg(23=USEIn-!+_2?ry@u68#{+gc|Gj;&i5Od(Z}? zHRcV+;oGf1_I`^@cRN9V`Jsi=f;cO zV$@5097oSTg%DoJ_7^W+G-INC$$09$7R|YPS7uutt9w^tpwv5kq5njD3oY@AD8?V$ zXTNN`w2K_?j<;wd%{Ma35CwBHeVZ~FTBs)IXZhDj$^F2iD` zzDLfE#>6bJZ8-i;c7l)E-1=34P@dI@wpUt;cpxWAEoR_(D1t81vmumwahtV*m-k==cigmXWa!$k6L5m6iwJ=J_&_-u&mbDr|K0YBsH`mncNj~+F-&@O|z zLCOiTuhcXYe%h0vo@*>M+GQQ^;TI%Qa-e&|!RuG9?6b2IU+J2Bsphf)QJMz3sk`U1ehVOeiz=@dN7r}N zE?u>XH#uo1bJZZv)~%5X9$0lhhW(7Zipt}znxv9;MqswDqITYCIWbp~h7-mh6$guo zE!=iN&ifhP7kjCC5*=ymz8F><$I>)2|$zuqqXe=QtSpe zJw?j(z9g%h1s`r}+CYI%&~5ZkiTEfPY!tt9vUL#5+U4By3P<<&>6$0`WMiCTyB8hV`R1IxlPoC~GVcIOIt9Yq+E@aYE|}Hn0A3LL)|YD+cBDdxkN)6M()1}j zi9K)6)0Q?i80Q4_!ta={T9$P=IcmRKop^{!XWEUn#>@j4{tq&_L4%(ILbRT}PN38p#TVD5u z8wLS(L7#7%%>d=6SBA)n~arKVl5J&2WB_pUeKNd!{8|*(9McJHRHxPq@n#3|f zr_dH1rPPu^Kt-iFZ3?Su{=+5(O#o6Z*=LFiFw880Vk*yl(dPltLMgf<^3fi;V^$WPZ-3L56npcsvKBiine8nZjs>M-dv{e` z@2=4m{=y8a}h-Iamlh}Z4WQB|7l4ueJ@kB{{Nli zbKXErP#eGzTxGvBE+XHrA|9N%e8`T(%3HC_2`!xn@K|MU3j74aY5n{RS9(Ze{RUtw zZ1k=ggjp!;%6Ls>$LYd#OI1~MrPk;UgJz?13Ox4=Xw0mI!nW5}x~@*$Z(M$}U(L3T zUBSt>sNUe2u)~_qR`my|68aWf0uD^$=0cA1ZWRG}nV(uh<*}cW_!H zeuhhzbS770us|0RA&MrQ3TF1d=I|`VcpaSdgQMYUXZSPetMz#O&!0b&YXVue)IhkA zbUMnyH9CdVCEax!-(J-eb>azqz;otved%ED9&i_RbaeWXa@`XLX5E`+lQ?`*BxH%X zGs!nmV+rdCQeG_)4=rG0NvD=uUJ-Q{`xVwjNlHuCH;U`Ik3!{AT@f5zANyMjZCU!G_Q}S_i$1!p zXVp6NcBV1-=WzmPA7`fF8(OyMB%)7b?vl4DaA#RGZ6jMO^17B{z0&oTCp^e9k(m{D0rF`pLlMitNbQ6zh}q7ljx}}0p>wf=*l%WL z-MJDZY*0p|_nPu0dIv7fxqSmfSGCuQovmyn^fxF_!ENm7gNg|Vk(IQ^60|XCe5gA0 ze20{z2SARSK35QnKVC)O{fyv$E7}BNf%kk4FqytCD0R_bvLOIj-e3qsNrL8kJbYN( zo;oF1ZlR1sBV0bIB^k1KIT&`;!7ko&{hril&@+$-!`q)}{(ch~-BcKwe2ETyZToiO zI1KL4P9g*|WV0;8oLHCmdlg#tt7Nh+Uc45X{XPuW9{l+dXED(XZY|F2Qh>#82rT0Lo#@}q6KHx1*%G77#F=%gs6Q+#`2DUDK`@r_y&G+Za>T&bSanv|; zxgmUHby*Qw?eP6GP`L4j2;84fCqsZN@w36SOQ)CkuZ-A_7|9GD3pW^s=3>szAN}kq zBZlp}BhdBkR0~v}jsU9{2L%T|APwNhd?#BhQoxbiC-t*$*S+`eIY7i-$%bys7Q7;n zHwcvbV7xUlHa6_wC-={XF_X1ua%07o^KD|D6|b7QoHjxc9`kXLFl@>jI(hprGLfNxkf_4K0 z!VJ6VmPk&YHUGSI*Jsn-EUVkG&$PFMlg>T@cj83?KOmU$#*h-AEr9*Wj5|HU;v){30@A} zil+f*f`f79|8rGDufK$kZtkDgg48{cICz!c?15b{k#9niX`#eIh&EIkQxu5ub&{2- z-L4E-D$lJ|&{ly82J21FL+Aii(|}E}ago%BU#MDKcKb2Z7iWp!Hr|xI1YLipoJ>f9 z0n6}RJ`N5UQfF`9zHHab7XRm>$!Sm7j`e+SPj`RiSn6N&bs|{_x1csk5Jbg%b-k9xV zR}{wC2gr+?O~c|rg8A0;E%cvDO9|~WAS$Y;9*~={qDUK)Zx=^`lPb7&Ou9U8AL%?@gbA;r#4=IiXM~6a;+?$+ll9t$4Fs;4 z0=X+;YioA;jz{RW5}6ErD!Yzsq^+AreR_g`ux0_f;YOP;zG~n``8z5*Dl#A(07&j^ zQ$xck&~h6FRxgU6d-tym^DF8!+`)z0e|;^$J$+{xP17m~%mEX-Y!F?uUU2UKiHOK_ z*J{O~PP6^u$}OiA!!8`Q&jG_bpPD_i^0QXfacfHy9QNg$nFSn&l$XIuEwM*L3%?o{VmTIhBWA!!qmOOYZ{b3keB;4ot9cm48f5O0RWae`SS!TPmA|293se7>h-zhDY2NwQ^;dWM>+tovL$LSQz||AKJ-l zu#1{SE_C4Tz``Z+RMfInlapeOf?j6lT3YfC3N%};zPF>WsqU!HaDJ}$(_yjUNWH!T zCg;K@Tbi2od5c@F=i}phcw(6ZEYJ@*o7z`iAeBFOCmZ8mgv-{ZJ2|xjeXr!vndVE; zKFNSw0|#^izO7JmLT*XY|GAwDSoYq{fFOb{^cFF?sj6Ry?Ocrchfi-#y_{Y;2q80v zFfu~bxo^82n_oi5cls@IQ;q7{pq=;r<45sIZwK=45mZ;IQT;Z&E@vLf1*qVH5oxe>L%cJy%wHp$Kc*$@)BtA)W!K^ATuS|--r1=Ky*;_ zo@pNXB*DInOcehkB2N9)k(r~WM^t|EzcK_`6La+s5F19~JM-3fv>xU}7i6=grhk1tRr=5G zx1f%DoRv?lDXJMBgIR=60(Mk$%`VS>u@k139j+(C8gDjj<&ha95vGe&G@P<`*N)s} zkd&R{LeG3-z?5>W5;e?jD63qEI#U>WLXeDDrK$uu%o;2o8al;LHm^_~YIfTp5o_fib`p zTKQP_zY?rDE~i*HYF3Btz2^9@!(l{$qxfAny_o%wq3zc@qViAm3$4&}C2LUBWV0+s zG0lK69RU0-AN;Hj1Zk$)z3kuWh%;?dA2E%Dm=A8{Qye9KwDl3In zxZI=>Xd6GQompo>;y<1Q$4hG3gzKLh{bPPVF=rV)V)T|5dRi^XOgBdVd}BHYM9(F+ z+F{^eC%;Uh#=$3g;9q{AN&vR`fDrlg%R-kAWZqxM$s|u@ml}iBc|@a3Mhh`(*ZGYD zEOV(h?`t5;ML>wQhN*C+j)r9l^izWTG>dtu>S*9u%12D4fX+R+Gnk?Py|A=(|M5~~ z-qSM~->cYFkTHEfF5lUXL)#u)1r~$j^Lh}!cqa1;IjLyn9?fYSs$VobF+LVxQlEzS z$xU=#2YPBxqO9fYP(Kw(`{=r}A{R2|6Tz=6IFW8CWWQjDMPj*jvmf)BJ$F}aBEwLb zi;0HVcPzkf;;a2L#f~I9fInIZ*d=L*mlvf-ahij@_Cx!Z&uDJX4srewa$KSrn2h-; zGf@>wX#3K_`ySU)Z$8#9eZ3!SX7;jA#&`qHlGrel=A#(s0qI;pElyu|(Y-LN#s?XQ zcIzc1C>3eRN5aC7A0SXoC^eMRwvd7Z8B{XOYqhx7u*Ke+FV?z>X)&$-T#YD)!H&|$ z4xjrI(R1Ee>m>eHtE4$pEZj1Qsb9Lz&j@AQ*hn0#FzcclysbR=Xyz5(O}IK44w|=; zHECd^!I9*;x<%1$7oC^J)Jz*MJ42yuMgDLECTjsJ>0OG;{RsYX>zQdrBRE9Yh%%L~1tL-wGB zkS*oXMBaYn+WQc)An_?q7ve}Saej;FpJK-EP@T&-x)A>5sA*d-+(2@(En;{nwX6mQ z81n?^#`1nHwRCjWIPD)PLo){!<*NJVr@9{;52@+p)^C0|Klk|JNWMs;Y7saQn?`lN z@b`adP#*3-dF1!S9!MNVsm_%+fd`YENKZd7x=XzvfN`bBBWTI*Lqm7oe)(FYNxO;2 zbXn+$qxvBLqz-bk1L(aWR8aQ(!*Q_0#*=Sc>Gr+Bs58E2b6W^KLjU-iuqmZhR$(YQ#5%KpH z#bsA_U+zw(fAttlGG9hCl|RrPK2#O6(49mq z+|pe_i=Q4Z6Lh_r5DJN&#CotqEjffgYYGXSL{u;ry^X*{Mz6RJu3+KI#N&xsp+&AXVcQKc0k6`kvhfjvRSty9#TJ!;G4! zx{@*z(YENTpQZ9JNDzW%rhHW_WYWocB?rft|!(`gne| zaDyWGPAWd8n~g)5lgI(*l=yyrI4V%F8oC6k>KCrU9`&=~i#J1WOFs*9h{DZMprofF zYFGY_{)14x5gi+9E80aI=z;sWbyp`4gUtr|>dyWV?=XWu z7wRupk}?P%2}l+hIlH$m72sPF!lR{vB7-^Wwd>9&0R=4l1SBW#{r=Q-i~plV)i z(6riq&lK^G=`gasB`k;6osE36!S8tv;Il^^$8hSA2=Jz~a?aqjz1q&Ff?4N!Q9WO3 zT+YH{Svm+f`IE3XV;tMW(urut@lnF>i4h+|>~F?eYf(a!^nY&62gRZ|b;lpgBJPg$ zU6&ZP+`r1e<~dn*Xbeiv>b$1bqXXxU_5y~@6(NUz3hGc@{mXY2-&i`Au^kU3;CSSy*&|=Qzc+y^d1w z6pFIk%F273g9zYM#$&kqJ1iCC(S`_i5RR-yHVsy~$eR~90_AV9@)^dx*+VP$a89|* z1B=+@JXDz{Ya^o<;T6HDjJoG`R0&J^VX==|xaEPF)`Ocz$#tEOX!z)j$ph`dRBOLY8I4EcF6 zxkwW5qHm9QO9GWVkQ+YLLX^B(5Roi9fV(xgHA3VPuoZ;XD$HaNwnl^+=TOj8Y3r#WNHzuGx+)7_-BMaCu=eS2ifBk*cApTyB=bm+&d6 z)u;2DpTYe!MQ`!&)=ub<*w>sx4rPY*`c!-p-Wb_{2AEE8v%J`yag9X$P_6W|&ySN= zgoVo^4Rq;aDx?Ir$wl}x7t7y0$Q=iU*FGrRvaP;+b}8)$4iCXmaa*V@9Eoe!$;0{X zwcm@JLNjk`_R|es-0lO*l;u;R*ra|vw3aIQba1%3T5KEJXQWQy_a_RWOD^Xl6M3z= z6)YLoE#3rH2ecK6SP` zkxeW_iMnECKwC%mWbfp-bPQDrYd_Go7Ln$Al_AbngYU(yzD`?^qb8L* zRLpVN$J`*kvH0%xuZ-4ny>CGKQ(Ew8?oqL?w*_^OdpG948M$C8nB=cs-#avJ zSH&Cgi0}0Iulrhy`x3Y-_+lETq257DJrQD}!rM$OH^=2BEA3;`u`eHP=^|+|!}?%z zok*CF0`Kal;=8U%6#PvHE*9?}!y~8sS6NVql9gY2q?pXVutCEB7peSa;)G`tUK2-H@|K=v0O_ryp}V z3Frh|$y_W6Hk1Gyf%`{E>1Iy_=FHje=M)tcgV_g0QMV#pk5*lN@?X%v?`lJ4A6Dz4 z_IG<*XI5(i+o!xdcd}AD^iXLBAo9PFo?{0sGwrp9iW;pLJqe8HAM%=wRpWb6`XBEwNUwIMNiut}r~$t$AlftQE3YEsLp$@H4~N8C|)Q~lPZ zG(tF-+Q^X%Im~)<<1gX_jEX$3dN0UlWIzkaDKV3^+3#*P~{|`na$9HHLICGUa?!%DG>SM1s9M4av-M-v!=42 zZ92^3qI`Ue;C|4~CDmg#q#wA+bZKUtCMMklfZCK_iDp{1LPL&YBh7$iKU$lQ9Sn;6 zuO16i6W%zc5cq#0(NyToaKf=Uer~_Q?2cunN?!2|oD%u*-KyL$Ru?~uugN6Q9+OMd zc-Kkd9<&gbGDLOs3fE{JAK1dGs%aZ=BCggK3A*M3EvNC)W6Rg9;ZHsi%gWe>QZW43 z(X?w*)(^>t0c{BGzx^K@u#pEF@Zvqbbu$p)CD{h_+00-S#oUyem9dm{b zsh$io8Uhafd1pE?gFvMtkdEb;0NP7Qr)yE{`JI#W_u- zQzsJCto$>oFq7n!9v^UfDz^taaFPxRPeh;lriLh6S-9`ISOjCIJBOM78bN8Py|EDe zB-UH}OROlPo~oI}xZIt~7sJ{_K#ne&?J=Yoi{_|n7ctdnO^&LzSH*>-U+;LWR9#;B zc@ev~j-$tuCwdd5@p}DQC`V;;Q6lw6#Hh!s?lpQpXl3!Ur{Jr1dT=`Le|RAVn+Ll zR>_5GapU-5o7E@xT$R~BcXjVG=BX#;0t|Y!%^9`XRAA~;&?%SivZGoDB+wDyH%0HBXMMGt964!713sLQDM!jQ?09O#g&;}dmxEZHprGeB1l43W!Tjy( z4%Pa>muN(qs6`&wvuDqyMc&7XUn#6CZ&Jwk`|jdMA-HDwHyxp0KYIqYVWo0em|z0+ zkF$B6#9#Cg;n(;`+8+!eT%%GidH2mvGt?pWm(#th8#Mp874{GVc>m$U)A$03-W>$> zzd8679n2+`#YZsgSeanro9U=u3!u&1CyE_W_(sa!GdYC@#Ik3P!s5mHKI0QWO92Qme!#$bjkOq?6x5W7L zY5yMyI5W8Pv|@=wL+EC_wRbzrnr)G8;mi zuaz$N-!cwBwu8q@;ab!TeS*F?v7xOKZr?=i@S!N*z-PUoWHs`p$uKj>hwduevLitz5_Sk;=~FIdJwzE3~1U zV$t#0Rf6{Fx2SV}6^eQQs7UhrU9okuYH}nja4KeKH4Z`KJqz!ic+zZnhgr55HGAmw zcUohIvKf&c0E=;0h`OSuP}abUBLVVf2d(%BZ%*B5eDK5QFfJ-<&E&}5ehPt+5DE^2 z^@KZ>m`)NY!1$0O0XJbxssY!b!;NPG=Fw7zWMFJz12VUR&PBdJru&bFszzu=T0M1K z%M?#VxDr^)EM9&pW|49Fr4OglWIUd0Ve{tg;`mHGU}=FI$=_OjGwe9G6{9LPmz4jn z9kv)dOe*u?gMYqZ+Qh|udlMb7tB4Ay7&ZzNbaz3i@Su$HRzY3{U6EY;TkDPDJeiOf0 zdmZ&9c|RFB|4Xm;T70B9^EX;)Jk@wtO#~?0oD70b#Js`^%DPg`a4Xybg~_Dk#&@r) zhLL!9hIjNwNUbrj#i=1LxrStpq1oX)X$I|OVO}*5g(sOGpf1tpGPQeh2#ToXFzAl{ zw4F4qp$lrWwlmy3JRwhHP(t8b7QdvtOq{Bjdn>FkBS#L^tPRffJ_qTTe;sF2e~sLL-Y+Zj%GpGFJInF3i?&hK*9;`Fb_96l zlhV=U`x4U?#`TcOCW8I~&wJkb&mD$5C20e~q_*&<+Pnswc$S5VHALd-BCz{c5y@XJ zHp+KlI?xS)$NRAF6z)&@PW}vpsg+YyiBL5MQxO%nl8;cqE|iG^Zo5fM zPlmT~AU~z-Ailyawn5m=i@V=9ET+AZk?qby<|Ds@er^-$h;Alq9p1}WxQI{R?q3ed z3>UQW7wC1(=B=lcWOn%_o7ra_iO`e`27;0*UqQTgO*yurt#8{Em1)=w$w zUq?gp&|WX*$EHsb-TD(iN4N4&CUAzFbuWidWa7lD=T_I(+}|GHB(noEwpunmqEs_^kj+aIlx zd%r{?-FjT3ck|+vD?3M>7~>2QQzJ2;=jDEC@@K2`Sn8xpcpu0{9wcU+6;cm*bCI#S zqoW^)QlGC30;xtwT<4ikWI9KXp_Q{U-;5_b4Wgh=?8+^U_^~o3qywax=wuRJ%e0n? zgfUDZSEBM2D(emoG#m>>==FuUh}3EB3kf zUzayb-4g#=ENN(-*u=YjP8!>@V@S@tWbDxb85~A2`3RP=+dF*2?o!*lfKD;$vI7Ts zpx$sK_{aw642tsXMlj5frjoQ9xDRB~D_bqWm=EPtc-YODm>AtRmuRA`do^RmohJI% zFc*^oQgW_$P(V4ek35joWu)EhHQKmkXc1o+X1|C@)e3X0dU?elu1I|9&oadpj z1#2!gT=+Cvaj`qDJoo(;;1O2>2}lbsF=dOl$BRgr0!0q`f}MhYjE~IR*j(zj$IvQy zvikV7X9*;>U@0 zGrf;-XD3$(>+eHe|2gcW>S~99qDa~&`lp77MeElR2|W;{o=iF-4F=r(A?l=F&nKZ5 zg*%MjRCoGY-%D)szx5Iw^}7-wJc&^4R!Fw)-9lV~zS>nRb}?lu?7TsW2(*4`7AkXx zq+-RBGTpTG)J4(*12sXOrkWwb9<@uRPW}z)U2|ra@a!kr4TxjUEn?ev{!wEy&8H%c zj&!%7Nk({&>!En+0l|rPw?ji4hx~aq1pc&*eJ@JM;C_B|rIb4)gr2x-Kt5~}e@dTh z1+}*0NaKPZFgv)T1XYh8MTAn${Dp)ca~Jrud_K6ks8qWEl!#Uq*H6#@)WO{6tGlS5 zpU`c@J|FSTfad*FftJk^VWX2Y^5vF>TQX?|_pxoqKtHLD%=`e#KEQ2WlcriX12+Dd zUvL~G^=6if&a&wsJ#|{k1kn;!Ec#PyM3Nh|m2w)iY%&|6S)Hyy1an*sOkW-A7JI`_ zz1(-vgA)74Pv%S*CDgWfh+lrbMB{{-YDB4jNPK5Uw;I~WT*$5$UE5N;fLiv*DWGk{ zSk^PMl%Nb)W8ZC85iA{L(*aQOYUdALG`>R5M7z@k`XNtCtFYy|qlO8CjL=!uZkJ7l z5?~rFEESZ7dTKjg%l0lQ1(MS5b9wgE{7265d>xbf)2G41U*a_e;=4v&`~v-Xbf7Q5 zRxOv_5Tc$GojDGmN6tiP&5b22EE~|qS$>=Ofz1hRd-jQRr07dy2Y7QKv#`yZyj?QsAZGrwr=dW z(=+NHa;CYZW%NZzKu6z)aMbFWV@p4o*9Ln_Nu|=PA^LYXf;vZ@8K3G^m*(2w%O&)` zfO{8|Hr#Jb=C>NPdsz_XbJH`#fkWP}z*3`q+o2D^-kK6^!dC+Q3;0G?F$bM)wSAkN zpP%I8?agPGw!nYnbn8HJp4QjC5BcrizN^-ESDcVksz@?sC^N5ZxAaQS-StD=TE8_1 zA8Wdwb-LI%dHDEjK^kescm`wD#R(=_{gYq|-Z>VclJ}MAR@ESi28+pT_6e@6)`5P8 zyl-oK+}#Z7*uqY}>!0AYV?4TSvo&7S<>RU8$70aMvG2N@_SnwONz|xHD8{MCbc_hh zp>H`Xeh{N8D!q3cl8pPSHhHbAptSIf*Hw6Qig;=CCq8ADu=drh5Yv4Ab7IT=@)X@T zd&H-MH&oWVAef=_!c<}ljK1Nij^g`12?eqAD=qC9n{gk~^9@_ot%vI>+U=J*4V>(p zzH{%YA7-^J2kHqSplFR!0FrJ0xg(gidqUxO#GAH?Uu#q|F@oPpF{1isQSTw?a__22 zTPLY(N zp7cvkH`iyQFHcEH?=N3Ik#5)ZtW%}_e1+K5cia5Hdz8GHp8srLO3Pq#a^9LAt8m*m z_K*UBXRGHz}Ydxmj4nLyUce12SVw5c-er06}% z&IPP0Arrp=x*a_fhybCU+$S^Ia|?vV?i9t%5DeALc$;n2HNa2}UIbfA$*mVS*X;*B zi)x{4T67~xrQ>rrdK71cmnk&^a3&oZ=YiV0-j4fX2m!WR)VL<`_@_^=FN2Hm5DF0Z zA{zyYGIoq~fF5{HF^hFo7@-WnRLITB_74^)A9vVw(BvaMn0GqdT|Djp*cT76CEAu;SLcZf2mj1IuGu}zmp+G=Y3 zBQBcK?Qzb`6hMCOzB-NuybhOH74+q^Vtrz~erfiZgn{I}5l&Rf1D>i84z(=f9BL7h z@{fPBcXn7Apuc7YDu%NKZWY868*koM!XQIcKRE=;Sv(taa zZDv>`*WXfC{q=3xoLh!39fnyWi}*)ExgK?RxQS~j^@a^P1bb)Y?A|rB;$x|StVsYN zsv&v2=XD}gwCo$$aams-T^yYP8y!sC?pp?QJ#<@%uHSjt!#>%7YjlA;){U$hCm}Ck zsQzeh+pu*{*TBVZL)(i=i{~k4>jzptA3-NPxBm;|o_jrv+vB3jf}4@F4A}8$R0Mes zTdP=&R+MEX2Ku)qt&Wjd>TuD{OXtO!8~UfBbPijaxcNgt>r|58Rq2nXTT`PXBvKdl z#csSR#ocax)bHj|iE%T9h_yT1F~*$@lH5MeT3}KfD8UDD! zxVWHuhr0~f-GR({gM!jZyQPPV3(~2`DN+zP7*}yLYE->W>uY3xU4^%|BY%U@w`Jqc z5}Hn*p6H;kOE~bAmk;>wuJ^FBpA2F?G%(6@=tKUP1doISC{-!*u1IG#-12tp4XS@` zyV)+RtAJ@|QG8d5sMWdF0o*{PL|jRRtD|aHa9ih{w1|brE{r1Dw0<9zjC0gtCwK1H z(%gNQ$8!*k0wiMaj^ z*3I|Q7Kq2Nej2v6s#{6P8LRxE?vv{|xcn^Mrn|RyK{LdKyvDxQC8h`(T&cdbYS-KD z37e;zHTQDxFQsC4Y><63dNHW2Zyp={gwr$e)K6bz-~5P*G=C0UBq@R->Fs!lh zVi`@NmBH?}-8}_c0@wIg)9EoACs-w%*_&9~FX&%lN=egXRg`({n3uEUXik6A5=uc% zQhR##gGIdpUY+(UOswBUpNueWHAvKurY_$`@!HX}zQz%}_M9~neG4Mqanu+q$R*ZR zeaOGw*0{tt9gVoWCVPifwq7Y+gDxsMmkH&Acl9=KCz4?GZPcybI?mo`b@EZXXmo$w z6H|&&{*jd=ofWYCu5<6!O}$e;K^JjDwp$Y?4Hkb(&(J_~YE*)=NTbzoW{wxWcha}> zN_Ch5UBXEU6K-W~jd8auxq@1M!3n!-+%?90`|;PSrj$4a+&SCZ?y@b|r?}rLZ~WT< zycT?W9$f+@{pN-mW20U8LV!P;j-{yWQ&S0^1P}2u4o`Qs3HfzLEczdnEgom;=`BlX z@!Mj|@FQayLN&-=BFSHV{rsMYGW<(5`IiGh5jANrtw=({HLu}FuX;m7!nRjFmyhyq zo$T;Xt5f;8<-ohNE7g|D>2LiAZJp1nv~*W@Xic~TTU}8TXid!H-&F9^7#8E!Twj`w zJw4}ho=NC6&>@PpqpkcDO>DK#?}b zo2mZwW+o^MJPB-K(#Ml(*LckT&`H~Lm8x;*X3`-nn{LH_zoqA^jmuA#bzHxWo_dQ& z_El*l>x)z4JnD+o(mD7}JPTKBjR;wuI+)_Pyf+xdyyC#+TmAt^9{m$ihK~VK<+Zy- zkzv6Lk0$paD_Il%Txpy`^T43NEBS+Aj~#9GnqQebT(_p~d`GcNf@5D-#Fqn!8YZ3U z%Z#nr_V6D_Of@|SQ}K|TqLS^niB578cn1`zYXg>hcE#5jpVWHX`VcO(Hyl+42~lD< zn}&{oDt_TX@(V8s*QDuWEwSwg4wRG57(PaL=VX|=xl;%$UTL{*)eTdMFx&LA1_1I9 z$JgWbDAmVzycPc!Y2ImxAGP<=pDXuDb**#>c5M9gGXG;;=hxRK#W1weoWQmE^5cJM zRb$os{-5L4Soyp27rpJ){qf{;T|6$(8ysE^J4%AgBN?rYxHl>N+1LGRA1&!Ly3 z?48_(1C8CM=n}>z^__7wn{deFkayKc(yFl`x*~p` z@g({ft1VC7cH4PuO}!IRTgcmJ)md^2-+y5J)oS4@Av-O`IV`FS>;w5nNWi08Y|LMMj@K&QN_<-ej)LdUPE=ziNH2Un(}(=` zCe~I~QXYsU4xh1#0#rl_B%;1Pt6)rx`h%$ZY+b@9|Z+Oe(p$ zE?5I~FCp(xm$vxe zl0WLD4XSU3T4lO+C>^h?6e}MT(iLzgdYa0^aJm$8;?xVDRM{5vbMHTyyuZV zYMhzhVfz-@dZbS$sS|WpXSXIFmCy>W{@HBYs?L9J*!mV5|6`1;cxpTJ=ZX5yovRcO zR7<3b8CZGmXLpA`XzCgMakXXS%ekheLjYmLrS!r?VZ(4MWOFQ6KQ&q$o#|VR*sp~o;|n9D*l39UMI>PZ%5ne zk9WN(1p-~GA`T&^|71`XU6l&90pa1fI$kg>RaUi?2#udeBc5SE-72l%6Rue=%Bs>a zu;R6Uge~g7p1PG14);!X%2ZT*Vv`8W%-NG*X!HfIs#C<8y+mRqTtB8db5Xs3UxnQE zr)co#Z9rmRxuT+O6^>RWt=Qq!C+>VKl)r4{D_$53rR8SJ*(J^Yzf<`kKCqA^7BZ!7*k|a$|jOEEKwBDV5`yvQ| zJU=bPg4VXLqN257DU5hGaQAgGeG+SGd|A1g34@JI*b~M-Ze|b$`P} zOlDNciAKjh4T|fChw_Z5(L@8yTMuECwSo)9(R6lU>Dy2PRMH{|*qg!vo&<{8L&~DQ z;Fzac_uRYqv;hCyOu?m*Q6%4ve#>*1yQ7bmrfOby$cBwhLt)g@ApBeK;ndnDs1TcU zEW_x@j=|4IrAjmN(Oq>8x2Oac&lZMhJFLFt3KlF)&AF8z;Y;1Qy&a@*>g&#RVv5{% z-Bau%!#yj3Xcm<=Z~O<)HPf47T7?_C{B?WbjBpbNFU>&CSI{gTtvHEUr2zDXwZ+cP z2i&R4hMNixJD;ert4B>=eK=fBHTdL^;*C$idHqclqF-~?uGaLJpOt=)aiuAExl)8#&V7JgbO;4IlyKP z3`%203sha^=&$}?(U8!ZtM#tC$_osxZ18M1paT;;k)WDW^X6yQL9v04TDguM8dgtJ zM)fN@H=4f?u|hU8&sBj53Qro^#9QT+C^0~NalZ!2mg+86-WUPZVLdjX zp z%wTVA36BGvNT{E90aAta%eDUJ;$P@LfNB(fOf8f9lGV%MlP;h{OU1n zi4U-Y0%rW`I`88lT15+(j>Ni`k6Bz%d(iMEp8A&G8Blg)=GGGeL-eJ&8H?)%r0CQn zDaV&I0nkMNd|{;ohC%9AliX%(Aq#_K-HEZ3!8eSqWC=84!s_N%Mu3wLME4*F*8`2y zQ{hS0Rv>O2b-j5rrk0~j43qc=Qb3gfE?rZ_6{?S9DB}6Xrei@;@CTcJ-OAnjF^ONx zAu>GUkaE?Yf+vk@y%~h?K#i0;W@*vV zMRGJ$-r4syogk*XVJhUN2QoYZu5JoYqz6uE)NQm&ACz_AtTW@z&~EJUdgDx3lnttb1wa%G!USZScdhjwu>7n~eu1SD+t|7d zfFA}Z`R`23S+u-vfL4;~WZN8TTK+W}6{eG2P@VH~eSFxMO~!g;$^|AYHwIKp8SdBS zwb8!C8fPN_;QFdcPZw0qeU;5GQwup*FQV*tIt}5vp@Vw(S0Gs^Ik6Ti#M?IVMU^I> zI}wRv8ki;pM%90&+Q0v@b{Dx3^Jg{_V7^=MJO^~g`$-nE%UvHI);O!krPx^(d*8CG z{|SrxR2?1(s31Q%7iB;BidVje103&r8IJG_oexAMP zRzfgwg+((XWpJSTKYzm2aD=KZu^11s)}Bl?H0%`gK0X^rvw-EnynU;h!Rxvjn~g0< z2)2E^8c&!_h0|l4me40UK;sri)9|o*4S21)*0P(GOTER0O8`Z5j1VV&iJZzSnqP-% zUoDdK;@Rs{fPdgm1RGvq&_nrB8t$8ffTLr7#{CT=%{+=rW9&#U^*WlgBjMKO_r>jA zSajBiFHKci1){_hxF5KoNkxO7fG}^3{UpnmDYtads~Ld$pZ7CxH#JR?`dY~wGxU=> z!8kaj6&4i7iU)IYV=91OAa*fFwic~y6{x^JiH7IKE>YD;(kj-`+Y_U+~ulwxm ztZ2z|k}M08vM&Vt7UX5*zIwiQR{|HR-Fx9 zl8H3?Y6ooIl^)2xY9F3p&jzyO;kRKmA2*sLUs?Avi)nP7$j8=txs!)SR_n#-W$FH5 zr)a$P*NzQ-^To}4^WscpRYzoOJo`nmwSKE1`hdJsr^OZ6Xs1MNzZx^63*dIhXex`$ z4?AZ3&(AW4V(=RuOH-*OwrI1zky~#`!xP}Qp5v!VZ9D)b36;Ae1}KM)igejmUZdCl znE0MM?0{F%t9WM9a=G!bPKUP`EGyZ`&h1Do9RY;Cz9lMlAVu(GG@`L)ZUqN+znF)I z0`b7wy25kpa<4{7)HAxK{I?*K-T`O(Le zPlWMbs7p`uycMiRw6kolOtU_l()R2vWlpk1bLoNp&rc5RW#4AH;`TrU3!q9G&-7j4 z_c_Tsy0wo14hnFYjO=M)Z709sB-8c_Js}H{k3>@+N;E!Xgwocp<;00UzS`_dVeHz6 z&i$-?+l}cL0IDpp+k!O2{?k!dGooDMFiy~`a_?JGMfrUEv=Nl?^tFw z0;W(sG!?AQQE#q@S)U_tG&B9ZRi zTi)wKg|k|w7UM!s%=R^Jz5u`q=rVRLriK6J;=2LstlORM$T5=!j?MCkH^HrZ540p- z*;XxtF1O4Zc2o6)z7soouHTU?bZrxp{uS$9s(-q(VIse|ts(5>0^G@4Vm&VK>MnY& znQUtZ8b=6#Oq=0iLN>{7+q;-d1-BWq)9$C>s~aGmZKR1PcbU8Fbh%t#3?mR5{5(~G zyXHm$Wa9FstbGsbc3=yebeQ@?-l&n$XFc3DT=e<#fQRAYjRW@{(ux~CnfP}-v3|67 z&mNli#U(ob{FJ-ZaIg$Hw%N{n%BvpJHDc(nUEZ=&SKlpd0-I|)vl)|VxlhcabgfLS z-jR@dh&gYftdqTP?bjG&P6-e65s>4Tkt2&@< z+epK>)?^YPNd##3>~d1}S-ij^PN#CaWs4UKt6zL9(OXhMvwhbqGZ)+I%>GS@2JhK# z1&@H{xCS|pPMX3Q;u>`uhz7WBLjSkBq37%0@Ycq79{oSSZ;Tqi6FBvUT223a&hOO1 zE8ycYet-dIVTsNd;VsmyuNAJcuXJzyS#~l@#cgP0Rck?SQeyXlLWSf@*pr_JU|JDe zWCHQNZC7W07_2OP;PNE;3p+kst!!6}*9oEZ;;AC?L>Kx$slOGeh{>;?mLRwuVN@1& z0QAT`;uapFRMaQ}`G_7{en65*`G=>UYd}P1T*0M7AhfSBu3eve#2fd&cQjAopIdgR z9Y7Kb&ey*`6H!-dN?mDZHxty{2|gudFoG@3QHt=ofdr0UnlDy~8R>CkWrkK+9lP}C z_QR`{iM!}?TKL&$1?AMm7GHn=1xc0rk3ZPM8n@gOtzsv+i1i$& z%TN3e;4TNmITCDK?o|?b9IGkuUbaNVk)nXZ?jj~J4@B2YW~$@sB_gRG%uuOcv>2FX_4IQr8|pB) zav(wR>FD->4UzYk{$Rd~9mCe0=y-<^1^11lo==-sMfaA-&XApB9()c8>#RRCEl-8=4 zM;yV3MYIBQ8?41a_K@1O%L#phu5!TWrJQJ1|DRvU6~(`xxZjuI-=HN^0$OT!*~~Hh zHaH8YXe_9|P&^i;@e0N>+9~Tgtq{MnCdzuHuiv*-w{Q83@={Z;M!xSk{EeYB*iz(? z9WGmj`_*|zP8>h3Bqfd{4&szal&Ma%6#}Qhk!p1`%IsTDuVo*m`zf6h5b4<&;?sDsvFVNY&sXE8xuQ>k;aJd@! z!Y*Xxxx5*bA+LmNK;M)igh8LWsz^8SNzbTc$?dl(M}#4YP|v986q@5rPe2ZrJ2BtqfMLL-je%da^#XgnfLOvXyRyIkmL{I>|Ba z$4#5LeNf24NJ&}o+F!qiA8*{=Ac3X%^T(Y}?RzXTM}5v|9q!yIV0TMDt;^Obny09$ zRO<98v8|cxJNdK}PzK`= z(&GP%X>cUaF!|E2L;LhqWAk)(Wlr=*EOa=PaJs@g=X7QK{%03=K8-qfGwP@1QS0Tu z)>p+uJzoTkDzdFW+YCnISP7AINN|hJ!p6Pt{U9y(( z&bKX35V5;F9X%1v{O@?LXOnm)W3_7h(vrcK8SHPz)J4u!t#`OqnK+lg*^x{9GFj-8 zS|=s|mcGLmV3TuBGTMr}szY6wpHAB8Zrwl*7qMl9j>$>jzhd%Rv&Q=c2~{LV)rpI% zR!NG_7^37yiKXYQC4`|sWU{)uyFaiW7yN%6p1_4TJZ~Ly!~Qxv1Jn;Lt<_)BmYA+)wFRH6WD%42H_eH%CdE2RDa%?}cjv9zNWF`usNVhy{4s zjnL<@-@!+dG;-~ZVva_jelo6W$9ZH%!ZznYq#Xy7qX2i{-9+n&UUGs!Ep(2jm6p!V zAjw1wGs_+{p0@hNMBgPq{79-rGbJCI*5EnYSk}v*mK3&xS|=fTH<_CNFUs6Bs;9W* ze}5g)Qv|T>AAZvTrw^c$Bh4=+(+T7E$5QNjjMcL~?-NruKICfoQN`hUWg;`yCyY9w zI(vakBlxVTU7DVJ1eDe?x{G6N7!u|exKv*VC~gcukJGD`{On@j*HB$5McQIR0u-*|!XiOYVHQ}zaV8)JzvafwvUeE zyY1<@Ce_#&W(Dz&aBg}+W5svB*v-jJF5IG(Z}0TxZ@6>CFZ_M7VEaL}nzqW9@lG*; z$*^jLaI{cVam%fk=MvT(+WD5O9T60RxI}&vpKRe4^WMSawk3Fer4jqrJo*Zz5A!Nf zc}GWdVh5h;W@rUmXjq29$+pd>9-ecq0;en{O@QihD=y-*OCz1kmTo?WqqXACU*yb= zOzM%VKLs4^j=3GffE0d|?AS0KVrn$AfXfuDR z)=2oP)Hkc{hi^Yjt3O2$>~GBZ6ev;^!)3jZ{ozVXLVnn{-o%Oeeu8u&SkUjt93M6z zMsnJl$y{CAy4sS$v(!}tH+SP92MiS7(Lw}=a^0l-7m)hIzJcSxvh8MpO814=-PU;w zaVyAmQT4GCfxVb>&HfMjI#j_!plf=a5_d&k>Yuk$0|k8J^VtkRlkDg$Q4UP@6Mqa6 z6roQyw?={xee9<|%(_Y_SkN=aRX4 z0kCNAbp$PX?9m!s(W)Q}liA-i^Cv~9@iji2`AbHcWHNEb4krDeC`2R|)B8i0i&Ko+ z&AIaJ&Ya;-KTcLjYVCj_+61W_>RV8Wns6bVij2F`#^d*@D}rD2ikRnxTx1{4!ER<(-EN zRe^FYUsE7buDvGVRFPHn87lF~-*Af3_B!j>>ENdRtc3gj7ZrsTBS&*AJ*KB1Uhag4 zgg~F9aRkR?OVk6RTqQ=`=3IFqIGB3}mz;2M4N4O2(nx3gpU>;u(ahnL*if;Y_Eg0V zqS1({LRcERY02#oYz=t$_~Z!z8f;DR2$kgO^5CNJIsx)id2QAGkoMeTlArJh2q<@C zP1qZKeI9wV5JuL=bJ_uMiLv$c^b7?v)c(x%H;k%ID37J)EnKQc+0mg0io*M!H?c8e z7XIh=`uz>WDJI;rQ!6=O* zN({A){`lxn1N*~&Hq6r>h$;%xZ$0tNeKXu5nk|!UjJF32L|&cNUkE9e%R05-TiqeS z(##GHGDAicagWo-hgLpIT4Y#t z0UgaTSH1ut<^#`B%oJU{>UsC>YE@6J>p|II4sRecNia(;w2cFfw!TPwPtn&WV$}?*5 zTnHY}K_nVS;E53Fo6d9ZrZu+~|HzRd52(iifXY^DHw7gnFO*hPC)k?*Ex53YaF3f9 z7OebBWUnh+>H-RyPSUXh<5RLQ*f3dVVglkUw?Sp9U|$Wyl+tM;(kkPT4Ut300ZC71M`nG7eCA zZ`YscfES|q>3+? z^PYSv1KVpj#BB=zyjzWM;!eXhk4&7Yf~7#BCeVC>%eEBUxl;?nB0lJ|ysS7gOn%jD zMEdWL3-*X4hx$o{`*U$=1@OHpbR>L*&Ag=OXs0Z zXrT*xMXc}e*?=^1hfW|l+iDd}Qf1h2BCpGNn#y9c8uo0mSMGKwf|UrdY-w`HfuRwH*8u2V>1Ts=j#ZjwQU|ktHZN%XX?{^ zag#8|moi7wWms{doQsj7u_))ZXW9sT>lM>Dc4`dKZ zzNAi}FJkJ;^?|##(m!9qdg(*Ss!LB>WtPxV22e>rZ=ML0Vg(5g>S0?UAaTLH-hOZL z2=3x1PCu9uCZvzZ!8REz;+usEyKLKCw8s`I#fpvrEDVg?7;D;>}w|$9{sqNE3yiBY(Vo!z?1;&-*7OMY5=u@0;1V zm>VromBBts@iC#{u?ri{AuoiHk%FEA#D~vVF72zGEuA3DQgTl&w=3{V}(bDI?Z9SqNpBF7#Yo%9FMOWQMv*? zx)p_g!Ffo=9v8(zRRIi?H&B$nn&?<_NFQs~o?_`mg=j3QZi)at1F#G)s&fSmJE865 z187rQ^jqoVX6Tm`CZSgLOioTVTejUn_6M#>N7%fDWhtGQwqi{E(pSh`?(cFpN+ao10Ej_H)=hUWG@wTvxF z$h|T8S!>eAj%B^7P!$IY3-_=HAN&xAPx<*oG?rxFkA`!zLtDC|osCU0nYR)=f^T`Q zBc^@ZDRlNE;3Bv)SUR}{WJ*bMst|!=vOyx7>eE43o$Ej{V(wIRKA)~BXq$MU0#>hQ zHaPay&fnWS`|D@_qzn~{4wl0^XFJZd%C(68L|VsPB?)wzihX|0QbyG0WnafW-)8_afWa&5dj=Y{@bpdeY(!dzZQ+Fx?ycolBm(a$bqmJP$cTrPp zajyIXnX8ymYa4rAUip5mSv|Da^pUIu9tgQ0)z6-tx zcA?pOgO7C*ZRggrw$LWf&vjceVEt~&)s~q!}eQ|4{yZ+ZNph@awpDp^#A|1y$2Qg%Swlo1Fp*E%FQofgZG{0^-YQAcp z&%i9&9W|{Bu;Mn#{XzgWJg)CI8?>rU>;?dP34JPFQFa0qcvI`ZM!)9vIZg|y;MBgW z#w+=|Vjafz66=W6;)LX|&g=cD@*EdlKR!{mjN}K$6so>Umj#B4-hX<2u8x(Jl^5`t z2L5}-e?9TkUz)|ECS|*_W%2?{Ml#0&#Pf|->*yF5wpy(XCiA76tU{Q+H>MbttcKa- z;c+jK+L)t@Og=r~f%cgfx>?ctSH|(Yg_NnH)+KRTsJcS2Dpuz3>v+G`Y@kh($W{{g z+19rhhFl@dkOdbN@pG5T9+}+CL!%;oX9;?EHvyYzPqCS}I$0&xMv;kDf8mxHAGPco zl*r6%^usJ?pssi6vA=t@#%gH@NwY1u2er_5gpEtkjLyj&A2qN=yg0VQykQS81{qC8 zLQAO9kJQ3TjMN|Q3ZEm@sjg$Pc-73RXKcP2!htZS1K zZmt6AqTHurV`DdRC*T+*!JA_-o2UMG&%ajTM5i-N{wHFJQj1#qdn4S|!7={nq$wJl zV~x8bi6|Y8;4X4kR`BZ$nAsT^gh2|Sghr<#7z{oIW8J7$H*Au`Yc~45aTJt;K`_ z$SwW-5glJ+(vr$9N=sRHJQ6x~d9g;)C#YK!ea|2Vm6FMS^F+4)F#^E%BNBc9EImTkOIGD)y;o{8iVWxQ~>7WZ1v&nu1C^pizYn;A(U>!uR)1|W8 z>a2Li0VyFy%|l<=P0Memp#)1U#8N1|RzZlGD*fn8V00z3b-29`&J~jW0*AE>X8Ng_&o{1P%2zAR|9*BcK%2EsNm@}F^chNl!zfwk&Cezmv&U2I@ zDB|Y~IcB4DIth8QpHEUUaha|1gG7)Ke%)oyzf)hQc;HB^?SH~i{pKdhy zpV=-gvr$aeX$2+T_atTqc`O!Uq05)aRNo)4cR#i_0(^*Gx?U80fzpr%a<>&5NesQ+?8DY_@M%4caV{}y0|LnLU=YIuwVtU z&8j`=lbpv=E-34tr=_g33Xdx#s_3-`D8z?&cI^0~!5AK%X>-2Jp%wUM6%W}o+w+ey zz(F=BO*o}Ov`RCQ%%Bzj=LMPyp}yotl+J(qd?pqo(82QLO+`wSp-EM8yn36eft5px zbha;*7%GDzBIe-(4%1J`AjBkh_()-5l1GzF6d5!7e%)J7$+5-^;wUB5{IW;DNI5r5 z`F?~-_^AYjLl2nCstqmW2Opfx{9-icYNfy2-u$T>!cy%2m2IOIx9t;!mtmdPpx(9) zi-x;xZKq3QogluQn5>*Ni1&J{`_iJxVEmushuCb58hoT9;Z(!)Pjoy&4TOOHiZq?) zpJH?#=%iK+>%+RVlez0T7+Fq`4TirfO) zHp+qTp&xop2D}LhW(2dW`laMfmJ_Lp}orh+aCO%{lP^-YrW@ zF)8z}3E%g?psi2&k6)5~fihLdbKkm$jeCE4JbLK@FVNhcJPXbW^q_>A#~s{CmKIs- zfl^L>@}bSV9Qm9pEjx(RF!CF(!(!E!{*TV4HuI8U@d{ZPNi-UAP6&N(G2z}|yI|2G zUl$jb%>y6W4HywPH)ryqW2`jTL0oD8s#U@~^ZT=Bpl^EIcbYu%Zi@lAc7{g?`y+Z< z+PhEzaSwQ>e)k2eqJdKO#qL)D@hKEgh=*nu$j@M&3%Hd z{n=C!%zCnQ(I)6|G#QmWhIpk=q+_^qrMEe(=AYpoeeug>ib3!>v_@9(4v9PN5CA9coVJ8!PP+i#DJfE#Y@|#rRsY|5MZSdqwO@+={efiw%P3sFa%Hcj;I@CQ;cOsNZ`FCh=iSV1yKB1> zY`%yzm~1tH+5r@Fq3Yt=rB0;=5jH8HP@P7|b@PXj$+67<&goP`*RG zjmy*6k$ti=DCaNY@IpuFz8Zf&4j=0qdwn+CK|n}RI^jKF zkkcOO{X>HMB6F&~Zz>k2%;}ToQ&H_9CILvTVfV;Tqn?P_7?*hNCBi8+6ZgIss!~l~ zjG0M2XKf0qF!8}J`*%$LceUNbKd}dIQS+Vjt-zaZZau$-HsO#7U3Uz>j&0jcZY)Qb zt8-Oft!6haqI+w6`+QCMg$BnkTB?g0oaj<9`{o-a+U)cTbXf?-gKYB^>csSANdV_g?JtjBT^2p5rKupx~w4G>qS=h}LJC1AH zSDr~CW?H75(b_YnA%8||$3vt(6Pk(AR8{wIL}vW{rc@t|kEQ%o{?y zX`Mat#GYlXfA-m|FY~`RrfaZ`~5C=2TAIYuy2ptgW^rA7MI>QE`VD>t4X< zzgH5=B!xxSOv&k+PutYd1h)bqUb~FN0o(r&sUKT0L{^DY)Ne875LZGrHjmPIVNcQW_q96AC$H|iH~kA7rI1T$VNp~;cllTCZ1oxkM&r-O<+O|)wf+D0L_;OYhRbV-Z_*!EXBFIQct8se+IP>b<3HrR# zRmATfcbMuOyXjzWuP5LSa4d6a>NGbu=b2JxzVVH%yvAYT(giGvdL^UlY%-1>iPg;@ zZZPQ#lh?J4k@(_zu!|_dV#lbr1rtDa(V#|upJVdn0vR%M+qazhAe;xZ)RR#Z1$m~K z)RkDpdaSI*7@QxSP~Nv~U%`y;+rMckLYXSB6NY_m9Tk`{9SpNyaiJGi?M7K>&;5?) zh*stgq_Hyn$sG6(oKLnWswBHc^OJ}F`h64Y_43Tp=5a?;tF_T5XF+|Sr?*IQ`Ie7* zKwB0e=&=dvdJ%PJ=mEa&ogClBamB$MU>R^aE5vN#Dx!qNBKVGbtdgwx=z|#u6C0ba z!>~MzR|)tCm%~HK9%4?!R3Jz+31?m#)R-MRAOp9Fk6saDt+J23!DR3^hoYCZX;6@e zoCA9jOeC4#_*>U#wp{KPjshdN;aky%_Rz4Oa(~ASq>Nzl>-v5K+x+*xbBbDUZ(~(Q zCxVaI!i5W;Yo*SUDJ?Da2(&#Xn#{+?w_KFlI8Z0HWF>RIEwK_4y6lnL?;s*5K@6#E z5{Qc1VvR@8^nPyyIY(W>F(kr~@@7pryy7Xr$ywX_Is=IBL-M&F(275d5OVTeD{c?b zg}!xfjqD^I=AK$Dln;H7D3<2xK>Zejz1jn8ipd!tEvhC3m1pAJWYo98mdPsC_My^W zTc*GW$1hk^P*BJv>sXh48bGoC26Fqdt>}C+yC>ixUk@10P+FIk-IEEBDsGsCb)-g> zw=#5GXh&7*OY{!Ym*Qm=QX&N$<8t-9vGU6pvJsI*?#W-}P|;=uMZF$$$~(^+`u2tL z*<#470v#Qq$F@zmzqmGa+&|DE->_D-^4s{pwjpdfZhS-ZIRX;q_q)SOCo2e?G%`{z zS#)ODx(E++L+y!T8Q3XuH|%CJ*vy|gi6Q8vBClmLrHL+AV4AURvf0aDPKLU3KCb7@ zX4Mv9}0_rOOTg^J=e+9e*6Wrv;|+$3Sxz+7DY?$o<`T+l*(J|rT-&#zbm z96}0unfKck@K43PY-NhEK^A(yv?rkq@VF9t~DFUw{Vd0d~r&v#||0CiYa{VFhF&x-)+ru)$(8%Vg;9&7UB)@J2q zX8;x^OwgfA4b)XALD#|->>BXx-a%TXFpP1@E@1l(HzFfcvVUK?Yc zkkurT;@O))k(2IgbDR#)GzC?Jgm9-^9C{{v=Ig=Hv9Y}+dz($++8KZD{2txqVm4;u zu3S9L`&BsngpTbV-$)>5;zMt=M!NG?5fY2{USENFhx=xB3eQt8U79%qzyBl@i*w&A zv7CRZd&o|wOj-T?R83FByDijx*Y7}+k~Oy+wx3w3)cSb_K|WLHTDE1m4j)NyR;{Su zH|H#7Hx*3&0d0#<*%vTe+DI8ofU{N5pwH|2oCC&`h*zv=aw~(!=lk<2puT@nJ3P9! zqn((|UIeoLLjcFvnp#gvgs~y_?w&b)Mc*Lb+gd8*r}DjWhY@`g7$;hg3(;;{Ic%MS zMJJJJHxo5OuiMQR&O1r*=L2dPpW4`(%=J48gZkY$%WSYlYl{EJkGSZO3gQHh_d zM=|P+vbgd3ClTD>@r&*{O_olvy5Z#}WwO^UEa!&KhWi8ezuywVWEmtvw~ejg*XGpR zy~s|_YZ`aW!&CujUs;UZkFcgoYOD7th!s<;b>g59n+<=-=A0k z-$>9&SegD@v`Q?j-Iah3I;v2pm!;xHQG)cY9*dPrvcIY_x^ox53JPf87 z2G@M~t^vgA<$Q;TB!%2ItV;SrmI2Z7_W?1B!8K|eE`{^-?^h$WfC}BqsTILG&qW|y z{p%$UDT>$La9ozt&R$D{mLxEc^8_vXo^qjlFjVWY>)$dC?aykyHF6#WkB(y)eS=dG ztL~=q{PdNKBH800+ZN!FHf|@YQeVNNA0{S%P{_O4&CczI*}-Do$6St5U#Rd_G1 zkn$OSG7-IRu6}C7)dmhH;$???`4gWpmsK@fc_k{In*<%(vF`5vsoAGloMYxhxuadp z$eqj8X+I7w8_TRmC+v+~g%(^f+5@5kLQ0{e_rU!;;D2f9m=DQYSX-X~S%S zsq7P^x_cKKG&94*M89u-JiHD!S#_5(MvOBamh8(i!W+Xv>>ZZG+RlJT2vDszo79U2D+MFF-$wzz60D)@&Dwb}xWkzJvYv>{8eJJ?P^e}gy& z$=wdZwa!y+U?2VbqfMt;_-c&1RS(_(+)nh;Ix1q0vN1C;5y)f@zRePT&AIKv`-LLD zKwJNZgvps-U3Hj0%vV==&`pkL_=3@qZxdUUGxjJd@>?w&W8Z-W;K!Az`MzTkEf)3V z8cUBnZ~k@#EuwdAtzPWIov4E@K2@4wGvgmK^=&U|qf@+f%fmuWD9*AL=fdfWwg6)UiH6cP^u!upY1Qyi=#E2&GFaAyMHehw=gO~N?;cggY5c{lvo%>p*2o!;@DUFPb zobLszd^v$rbz%UK9c4DiX|ME1ySyE!qcNf-_xNp6vN-|hM0vWn#Bjmt}A z#gIlBH`kq~q^kx+VLeKM>%U**Bj!oI<8gJ9eJXae^z{Aw%sK74{oDN({^#RPKCm9D zsK#r5J$vmZ$^Zy}sixWg8XBsX3`b-ll!Q?5DYrhV1_bOUEJ+h=-(vz(@4Vc!tL0SD zPrO4rD$ICEyAfv_B>Pem#l1h-buXZ$?FlH{0{2>S+!Q%MMqH12;4s_e=Hp+8Plc3} z)B;=K!O*Lf@5e4ifFt^M1YUasFtO5zbBq4_{EqoFHpa;?j(!Z*S;_9lRsH78nD+r@cEI7@P_;w4-+N{ltbw;kMA0>p5V%MIyi&1x+qTuU z>nX{21X^2rQ_k0OZ`kneSFN~fZ@@TuQV&@PGLe423oCOTjQbL{*XLaDF4;2mu>;n` zVS4=I+X1(&l9G}T9PtLh%l3o5Tcnp+TE66N-oMT+`Ad!Qkwd1YrUC+g+{%0VIR%Sj zBwaF4ZSOz+dsS_)!I${bhfsFVCYjtG!_fZrH~W!&r0Z<@7^8Cp`%UvtW_ExvTm)~k zG)70%)!p6Pr45ET`jAFty+k5G-p!Tk%eBpKNasCfrb<7ghwP3$g7@w+IvSeWpdr|{ zdR1=~)bR+WJBzA8{WLxP<(@_iZ>grS0H}$~hObrzFwLDDdD&c+LQZH>PzK|QwSFEo zwQGR=_s-7F1#0VF$YD-2_G>N2|K5=}{_GF`nQ1Dm59E61;o-5nzq#W$$!AvkLP<|J zKtoXba)HuUR}TI|r!& zNG{Pkf~oIDhxjuk>rFmJa6xaU%W(JqWv zyEysmWhlm73~%d53cn5*9Qkgw?DMr9scV9qE05Z>ix7Pp#Z_RZyw1;Gp4ACvCP8Ke ztn(gbuU4?f*UcNl20B~}j<7*>+W1)&ti_T)U=YK~CSqEpVR45hx{Z>Ew!?rx2?^qK zLIO--cfs{kdw`<(x8w6FCK7H}NZMDmc+h1&D(N&Qc*LyH9(UY4!gD)2T-J+?S}~np zr0XctBkd!H!7j>mO97Za?c?^mhXzR%(SKH}^&#pdZDvWeZ zPIZ~_##0Rg!a3~&YtPLZ={QzW5qd$YxkgDCS1~H*q))loXghXL=3c8@W&i6~icNP= z_c?I$MiF4djru|my%2+Zacwgp%nD?+zP zf7AVrolhkLL&)t_XO3evja7Yo8R2QfIEi&+D4o;p;9 zSYk)#2|Sv&DPza)akbNKO5(_hX~hsGUnc=M9NN{5qFe#t;)Z8fU*}Q!WD~H8+M}X$6HNZPCwV$(a*1R4u z1LTM897k>y3shK?ThU*|CX7s5ARZ9Frdz(LZNam~PsCXRawHkukDUm(t=xj52<#9K ze|HfvCg7mRY%5T0Za3;YvquDA46h!)K`w@iRGONagl93-C^=!2picijS|dKF_%i2w zpIz!x5BBS6Hfo>x$JaUDJemOO}S#h?Waa*jHe^8el{R=CF2~^N(^?vltr+?a*_#NFw{M@;7LvfVyuFn(e zD_;&Kl5vvXcrSbEEe{XjOa3e_j$5c96G1eBSf!iF7m3R{AKvVQ+^Il3QL`q-)7~!! zB7i_G^!?4J_uCabs!%9FxsiVE42}V}m{?WJNRPl*z$NV?#)#b;(q6L6p!uemU^{u| zfB!#q%oFWJxF!da{XplyFxgeT+t_u>VN@Cu=ry)XGGsQW z^AWC^7~nIp#SH$WuISBaL)c$?PSPN&E^A^e_9D!GNY|d=t9XfK`yoBVDCmqBZ*mUc z2o5hOZezQLM%K`<`Y;m4o%rAp@xiJS4*A+s4c#0{D>^J@521K7)SmcFr)ST=w0dxf*Zr8UEgp5uzdGaf`(0Z)~HTpcOQBzSE6AE_=$$@QDP9 zqV-tLdja>8`?Xu6 zx<*|NOVp64P($@L`%#+|7}&S9JGU}+K@98UqwVK%j!W1YdjxPur=@1&yPhSu zzZIfZPb=J|rKRh!hw)v!Mov3JI_7saa5?}m+P9;u0@{WbB`rW`@lJh|zP$fx1~KOP zRRpA6AugL*gGBRme>!`E$e+j$Yn}bCP^%tLQ#*;%gCDl|E3mEIE<04Yfmeb)cU8<$ z`My?JjF>R3CH8vNYPT22f6{6H@#9B5foeu5vr%D{_Q5Qe3stJE@jKv{ZdC7~BjqN* z+o4{9M{CsADvA_gheFW%=Zu}B0UYG}!LB1DHI2(?q=l!N7T8sbPSiaKR(`Ar78=|L z3Q-B~=q^mTb*pA3z0XGYN2s|w)NVZ}oT&-|CS`L@`>)RZdhKj@2a#{Ph;EBK8M|TpAe| zu+H(Ov2k(?U=8Mq3u=dg<{i8uyO#@BN>W$1+ru?zGYGE_{0Whr^qJUfox8ZWrshOU zz^mqVPksBz=fX|QJ%tLBQT$q%b!QDJj&C1>36~0SVk2w?Vr;fOL}lk6`VzCp1uT%* zKLWz7#RS@7Me(WY;LF2sts~#OTUranAZEP)))eY8lYB_RETQ3F_<2X38}t+Xm1ZK8 z90H_GtV}wabWc`Q_4aealAKqk8XxvRGhyu{j6q`LUBeurGx<~_K4*t)@idQ@Wqlys zTZzGSS3l+)B zpe4-Qe$qnG0@bc{_wL;d0_A1L`n;BYouDCRygk63y}_ysHhs{MBxuBn-+?Qeijn|- z22XUTs4WVRy(L$jyyf5Y7G2P9E^_Vi}|pz50+K0NnJP&6Km zVT2+&|FNnN8Z!7s`?Eo8v10vg=wV{X{5)A(<$8(Q@rxPF9|jO2h?=A8cxG~#QwlJL zd$4)A=e){=k5I?*!d#*duHIVzzhm+bDttrW zNj9=R=67&#ARn?RmWe_iu*kmbSshwK@Tr~j$Z9AwR z!-YrWpJXY6=3{USd1=dKbAW6b?$7!3`;-5m6wLe;l#V64^KP)uiQ(2srXeg`2`!Il z@nSC65$kj5`3a{i`{T+_fBC>b96a4cvv-YS9pGZz>`ym*B~rn_wDcG3*e?u1DQktRm}>?IpV8pc_}WPea!dTuvk2n*s=qNRv+f}Zd2QnLs9xDLC#~L zb({_`7hy_sj6b%?mmHiPzpzr`tu7Id7%q5GkP3+rB2gjnJ{47Yz;J0ss4zCTYiW zX-fi4bOC$u#qrr;#b_&?{hpFdK>Id;5Q@gePoAItasVN@vB9ls%SD6_()kj_qy$G4 zq`QE46f4{}Jy?U5-5Frls@~uXtGGAYuF)6r9`>*rh?t;+N;^mSeU8ptYD42MdJSJ`ji1rQZlr86fzR==iSf zTu4Xf3E|9Nr+<}iO6@y-*a_62bs)-XzBM=2A@%S=cHyQcPKhX0-vX!YuSMto8&u@@ zgQ_EQ#FXG3Js8%kSrdwyBZx1qq73ssvNL;^Wr4s-)JKb=wWoUE|I}6}&#Li4+rz&9 zy&O?t!E@dV4|_a-OXd>raR2ja%t1+H*lECNi-eR!N2E$%j=YAwLontOC~Xk*;0FsW zxw17e)=^u$Ge2{0%I^_9M&>$|C~QpL9boH8G%Aw=pvm1oQGj^wMqwn`aI}|*>43VE zzgk_;AzEmPk3W6DC&NbeN<3-x;}26b!`Z_wz+6G_`1rn96!N9M>cX1J#A78JTjMkK z^pk-=AHIcn)KleCfVZEA7UhC6DLYVenntdmgJ=-6Ewdv>YjhCeR)iMF z#KQ8Ep8MVJxypZk1UG)fz8=oCv$e<6kGnugP?Lb56@Yy}Fq$8h7tFT}khqjeXqLyr z5HE)O;&Klp)3^(1sc+0g8Z+A+?l_n^%e2bb|7z#3^Up^7Cs z70$a?0fTuSJK(|(9|R6+V-X$-T0_kGdw2eoNYcT7O;eZD<^2m28AzUMWGC6_EIyz3 znIH=>LArHfe#ka-%x+TP;*w1T+V3On@LBhQEr zHfhI;{1$r8RJDJ+n|p`x3`VQyug#!SXuJ+dS+kTibao#79Fq)uzZh9X{a96-exX+% zNWH_Ngk?@*mA$I142J2Lismh#s;jGGVq~n%4iFEHLY67SdV&X%92J*8HGsNy2k0i- zypRaOrzVl*A%Eb+hiB%E$^>hXyM5UH2@uu?(BXxDmTLUt@n$|^jUY;`kw=@h%t)(T zRF-n6cp~a*q=(q56_kI1Ftw6U=8BFFnQ&TRBJvDKboUP!@o!KIQ@VrJK7WzYEt>6n z2yZ&ijvDR60y?@ayE|}xEL1xi+IazjB{T#8UY==&*jIn7{u*^C%AlrDb&}A9GnK4e z3p|oswm7)C$J>gFRZBXl|9$4XWKpSV_9e5;!vD)!|1ujg-Wr|x8(#U8r>@Ih4A#Bmg+E1BZ9jxdedfEFwNKZ&8FXmFie<~zVT#Vo|pO$6ttkC%Qcqu#@BQaB(Dk1Hl+ZQbHayO8v4fH9# zH|BR(>W(w%*-qAC)hU8Ei8cae!N!|h=3N6`NR~j|%;^HHu>=cDOKfcw>GblwoCJcD zYv$RmFdvj{V0`*^W=+&IJfFv~VlDD!>b8CUDZh`UBQtd$_d|p_mvOD<)PQbLSdXvF zb6w;ZGgD&E#!Nw0Jag_M-^iJpmbo_W(uh@IK|$O-Ta4{^z};a}xVME;LQn{DPnsFF zi6J2&dq6Gr$QAgCGttt!^(N&WWo4g|VEMh!nUwW~B5az+(oH%0rAro3o@6aRT}Ucg zzzt~o4^6e6{N@t|Ewu!jL@{^X9xW}c_>-WF93hls%pb4%DTcHDe#W(&x7V*W(2j`> zZ)|4h_^btzC+6i{EB^6YfUN*uae&G5+}xQ!>*z-X&lb z7^ONNEky1xFeaYp7zb>kWK9*_f*vD?$ZrxhNtFKpK{yOvWT!M>D!x4erb0cUYMwwx zY8TJiwFOE%KB+z+LM(SzB;v9UF2R*ufuI#jx|aRkvJ${YHuwM@gKD3(l#~`uaHz2# z?D$8=`Mqg_{U1vSXwDpOK9LRc4N+Ra2torF8k0>ABTuS!v~ zIHyy>%E(B7KWt<6j{oNVWgz~ydw<_Kdv+#U;=2IX*ePYOU|c;}due~WoM942gi!KK zD`X#ZxQSb}X@EDFrtE!(G480;tCr!$cZc1vaoOEY)G)_Zn)6J5Ej{VkK=z$qN2&tD z$I*Y~D8{%Wi2l_Fwf}-~*1F;$bw)lC1p|Plp6!fqHbO^kRL=U^kmi>oAsUk$g@k&_ z`~^|OftR#Lwc4dxk(Vq}2g)qbQNRok?-x5yW8?J^DA`Xun>eN)@Q)1szf`o}0c&6Z z4i#D!^nI(b9a&txOS=+hroGiMN^wIR3Tra-`7|QzSP3u$(_kU6*m^p8bvf5IV`c^p zs#3fRk-tNoqX0qmV>6lMA#WUJ^kn)bJMl*_D$5J|r=D~tp`nWx-SwMER#OR#WleF0 zoi$k<#|PV>J25-&lnu@dq2yhYBiiv$xz42y-aUhEfvc=FJQr{`h`Eu=KF%m0a_O64_)y zzcv`xb~B~VcdP1k6Q~`8J3QRoJ@Yy2-q9o!Ly@74l8l|iM%ogHP<}!J8g^aXi`}`; z7VVko%0Qt=HBalPHH}6Ixwi#q^iwL@|2oP4pbF9B9FHVZmdR&Zqti%h)C6F- zTrRF2Mn+`zlon1S*MGqY1a~mZymwl*?2(dkl(%aV!;)_UxC_tTUue2~7hm)Z%H!6O z-q2}8be9svr3o@giOSuEwuf+`{FsCP=|S#`9iR1rEmvm0*gaW7fdN~E@V^L;%xuLA zO^$_@oVEH`f+)`mv!hbtC$l92#mphhk^>0_`y!$EEbm-3h;kh$3&!fi>ceHs%tRok zln;ETsee3%n3&U?Z!YC=Z*DpM3ghfy+PS?mr|plgw)Psn&Vj&lbThZWv2g*gv-?3% z=C>8I(sg%nx!u)eR`g)uk~NM}u1LSW_dJ#}cF|JMUwtHM{o%L(GW%ULy0-6DkPQ>q z)^{;zU^$Y|;rK)}bs6g*i+-WWy@^z znfa5`W-`Ru!nN{`_of5oW=xJ)Px@dgRFQ#geviQ;%6_ietxlNFUO?cP#I<2jRpNMA zfYzuy#-Et-1i8y7eg(cp;tQ~uht3jL8-QjSpOk+wr>L{C^Gcpa(aBU?rsX!G6`Xd> zIQdQ6Mp4lt@ImDRr7B+27~%RPZZatp5>#A=f4{`+>yx-M3?4QctYBy7#~M6nf>nBY za5nQpNLbGHA+v^6v&E(a7b)l!_U%h#@V_xQjRm-8f)b7RK1dwP=3cxuG8-_tP|P^< zOzl2vfi02VowuAAuX{zbg78?qU7^nShS|uctLcrs_yTuPb$0qOZrOCr(Y{>~yV{6Q z0OJUDUhSh{lnW{gUDRXTWMHY;N)*(vs|kCwh$y9Ov-?xVAwNtd1>KXBRD8*!S9K{}xK+CBzfyBCcEBoo-Yd zo@pJad-)GPHKf{z?JPgAf_I=nQGiP?fFkdCnh!RH%6&4|{y(;^JD|t44UNTFpr!p?59;@GKHp!RFXwpQ_j#WC zx$o<~uIv8gh=26ya7TbRW6A!zA({0P>c{Y__IMO9LpeO zcm4U(RRT<0q5>vXxL{im4d`o!+?Owp%{d1+>&GD?9(|7y9_PpJqB0V%LI3zVI}SI7 zDXk&dD6t$SewrCSkcEc;K6?DA5G>{QfT+(`IclfrVQ=j|U%j(*^&I#b>;Qu)uGDXy zihd7kiS!uG*6sSFL0cG0z0R7uD_x$hy=s~274w#S)>|WJ);!ePbtmdDKnrp&KXaO} z^Eql5NSb;(Esr-=Sl#|lsYi9qkxQ+KAOl&={JUocOU;_SpLX}2J#O*JfPP+Apqk6; zDJQSF)&*0E6y>57&eE1n!IxD*n+$9tZK1qx-;p!^BS`dpIm* zQT3-=iw*mnD7o0Z>(}Wv9*@Z=F00!ZsD91zO$Q7E0#2cmmgx>;YLfOWm{9z|&enq*p-$Zmk0C9jph4(?-K|NgrU)4j4w z3(?)%ym#+VWH?UyeH^M4RgT~|<7m}KHON#lAT*vS`8K>mEwfsoP9p}!Ly|Yy-{(f{HR3JppD`gM!gm2L*TYGdo+dvyC`gpLNKC!|gCm->B#i=2VwzKP79 zOTHlB0e^XDk1ZOh-O)kMbfC}K)X&w&GVEOapz1O|*>LF>)ru3($9mi$TR09^fVi3f z!DZmji@r;$0@<8kEt_`jDm~Zq_U&=tT(=3ddxA4?e{xq*w=nS?P-QSVA)uxhHw7NI zR*v&*;!EYD%7~m5h>vpRCsOJEilRG1h$ZS5@T7^os!XNmslUB;EP?-&j72E1b*GE- zWQnZxUG5rCbbl3KZMv5@VNo&sQ;b0j!h@YrY`>M@tCu~$D?Qf=(9_e5jGpgKNkhO< z@|mR$oK;y0cOf>j{J?aa;Nz0dSqkR+tmTSpHc4dfyB+fu<(N0!wQcKL-EG>wy|7&-Tb_Z5$y#B`g81^xY~JZV?1j@R*q?T4 zy0Z_C=?Yq&fzVHUj4xO(ATqjRlX?bO8wuz1&n1{1p+RqXhLI4OrJ|9~&FZ_CWW22yTCO{y9m+_Tq*e??9>oeGCHTT2xiO4*gBORA!3LX6lc_p_+ zF;sH>M+dIdiofa@xHUL9h>Cn=M&cpRsL0*4&++8EJ~d*P(lS4ILD4gGr3jMheWUBr zx(NZ0n@;%fqF$3|a2!@GRc)Ilh&el_&=VJ7g-6lsUt4(V&kHTvJa7Jd`&tXHzcrXZ z!pEVTbxWL5FlLH20p@*X-K%zsegy4#fW*SqreW)m8K(be1~ZW_G#i9ekq#vDbX(t-5+V#q*#mi`vh$O`EI^mnwQ;HGG47m>a&zC zcc+VQWOVtkfY>!u4<_i9#qrvmJ_;VIeuh=MV}Rq37a1LcZo9(yY`e(U;K_E6dUuw5 zZeKXP>rH~l+z_|2q?^f5U@V_)Ju$q3v>g8vp?}&hsc0RlTBu#cfimsf=M9ug*_egH z=o+NEQ74diWt!#}(9h1G^-VL+5S-h7ZvdB3lxg}Az}VVoK@8RDs03$BYHMq=raKYA zJcd0X_h7X$O7XeRu%vIf3;ZES@c^N-Qh7A{F?g+2v6y>dOnLj~)ygqguif@T=k;ro zW40QE(oH`^jv~$Ig#Ytv36%h*N!(F9TDIeFukjAaqtE#4Qz(Mn(cB|D#zc?VChgG8>fEg+MuZ^aCS`WW3O#1j-XEgfM2R@KpV1MTaP z&3leRoac#K!Xu&)j+JkLnbD_sirw>BvNKKyu8d?;Jr)wYN`ge5*pi;}$bURvT%P|P z;vLJwXNG5G6XtC6%BXEi4BOta)n^i(J=?Yo zE|%L7QTin}>Rin^Lkk9>j_>&rOg>owHf2TB6q@ZLu%|og(1TezJFTkCWiybu5Dtb& zyxN>0ZGE`NJ=XQNAH3oWryf1~xq&ldy43_LBu-J9*+^!7 z+Hs@m0rFN8JL<}`mYcMZ>JZglyH*lqK8$$ytOWcK_r0w5Y^gJ<3f|Q%3|6WKu>x@M zMCw{rDRwq?**>I+@UP(??(IE&(h%L6-JnC4mYuz62)*g<3pG3|_|3GoiZo55VU)z= z&z~~ou~@?gm31f;uQZKIre^%DhR;2I>f$@+atr4K(WD!W5_u8QUNVLO*_L?Fq?G@G ztpvy?K2ENSRvXarckA!S?7I}LlJ-G?heY?N{akmEsGtbYTqPP8WGg5fw9Sp+$aVI; zI2-Kf-nxTE9{g`Zmi>FkmA^DRUS7{alPsx*OYjbf5Zf&c6ea+zCh!lTJ8VE(Yq{jF zo-)6Rhu^_(0ZNEAR?2a4cD{~YyCUq@Zm%;gU5b7Sc0?}y>;UHFNG%|;og!#@X`^9I z){(0VzT?))Cp=YOo4^;y@26Cb967RJJ7@XJL>>)p?>BU|t(Na;+( zt8mnmjFgKp7)Zfb_@CB3UC6k5|5bIPPqA+mAI2MyDd0*hQ<$G5GtjlWFl8?Imz(VJ zkCrZ7zMNybQsQDk$JZX)ckMbw<_aS1ea0WnJ@3QZqolF@$2yi1Jq)+~hOa;;&Fhjn3YlVR{H#c|DE#0E>#qr#Mvj^a1viz)-VGPVmL`(!R`sH&O zA|flJy#e&f4Io7F88O;~hJ`H?kNflkB=X~EW#y0C;8yf1X<3cCNhDM%z-ZgQ95oiA zJ*XoyGPlg*@f1Rnm#Ft(hr59FcS35Z{}c^)59A?i3@tYeN7MZPC=ymQcZ}PMnO8Ah zQsQpE>f1z6ip|cy@F;S8<{sEz*Hb9vnl^(uqlK{!zTD7ybE9uFqA4G(P+GlS!8$5* zebX%(wskgB6T@z+>xO$9jmJmAv8jkkH;?=EYd-@GOdq)eZSbBWy#(%Te|aDIZEzeB zM@}|Qja~cz@y<0#W-LCJL6*#|$pZFz)6_Jv#!`hp8}4$c<5(1IHy?1#GRLnJRu_=b*2986qFQFcTZ1!DQ5_N6evRC;5P~yIk8N~YPv^< zg_iB?sZEh08_OfOasI2kyqnycezKPTo7dQ2uBKJ5Lu|o+lxR&C@j2~>#Mfi+E%q+A z-7}F=I7{s(=CVH@LWHO*2xk|{^vi|b^8scc$?Jb)dkRC>e!Z=Rh)bsXV049ChSi1U zM8Ur%Ro29)tEeqM`aerLNuq6AHVghvE{{^#jr;V=dZsbN zt{ri_10!}L+K!k`zoK&(-EZHrn1?H&$R+sJg9vGiC7~?F@1OpX!Tx-n1B4;dCb-9t zHG8PW@H+-8Dftxut`g4O&O^Iu`@at#ZUNEB119x3I#sw@+_B-rVI37L9(ZVaYv$YBpypYLuJk~S_s%SBbb_*4_-TVRT-ZOb>)`lIXQo80#UIg;oq}VvhU^3 z{|rYEQOn?(7XtHU^XO$+Echdm;iLsfiAC0?ng+wkI=6GXpxwZ~7-5yTsopeZKHW66 ze%!GZ76+xP1^nuH_JuHPB>~esoG@JoDFdUA8~s%OnV9)r2e%VsBI=e3YX~5^yzF9t z*#95)GYMO0_<*?1jD^*@CK}=ZwXxdY%S(TiV?78?NCU;O@2qm z?PDeZ3ZI?-xZ6IXh0@J&*}VX!greLksT!rkVvbl1z`g4IKAM!7_oCXHkI+fZQ1qv@ zq-@tmYUGZ3oN<-)JXV+Z?3PtYy3qYd7eczHjSx*Zn;j6>#F^WSkCOvJ5Ze9{)s+D- zCLyW9o8o))*T3BcI-++t=+h8t;eEcxmq`*E7mM}Erhq&Rc5COe5PEIyn=s->{_Cr{ zeE!vh=s*)926w+mPJLtJ+W%5+e*W^9 z&9_MSV~RxPSQXU?SBlel&7(0Qkb<1kHKtg0Jpv;c#J7+V87(~lhm!&pF*)dawtxsI zH{T7aGss!5v04CkBh;5KkTN{|s0%1a3j=gMz$xaMn*WG$N3>(kP0wgv#w61 zLKUDlF%0W$8Ds$hfA;Lzkgi7=)8Cx>*q&+9YQBrT{ z6>1&U#SLQvH9KycX&(0px~SZnDsFJZ{G=A+wHHqxXTP#|9etKH?TXrVj+>fu=Vox+ zSukg*))S7sR}RnZ*r*^n{}{{bm(Gr|ZU`(T#XaT>AX#=SLfJQuF#L;ou4 z-S)<;rMK=o4o!9!Kfm(tn6IPk)Y0`0#cpWe{5lN#arIfhQ4ONOSIiJ7C~HC|OC-pz{{wt94H9VD z{uY`Vk!TLcDt*!RR1GCzvG{J;%}o2@Ze>+PMK93kg7MWWY+eLR4zO>B+3Cd}xof|! ze56MC3*5G7_`h{W;5DBFn%Tz^CQ`d%%U|R=otTf2<>aI?Gu!powrQG8U^fl-PQ}mY z07ijr_TD!gw}~FW%vAr4W@#yOL`_VF@{!r*Y@TFf({=#6$`1<#X3kCAvYmW8LG%od zkB`q+f+Old0_LFEs>d- znfZ%b^W^)J*39fn%JCsa)Yu1=PNy(&`u7oXo=*=8LXMp~OD=PU%F<@aG(j8n0W`q} z?(V_Jh$0}lLyI;5hq}d&Vd&EtFXok(FJE?4$mxIR@9iD=_%RuPQxx&q#}vAOI6^4N zGnELOP@fw0greS0;Lv4C_R8byJW{g*hODhuFd9xyPfstGHTUH7qfjHHgCM)886TNP z_3(kuoNc!af#Rnn$+XA#@#xstQGlv$99ZKe-@Mpd*l5kn&66(F?(KR|h?YdxD@WZr zmSkY1gsyo)Of166YEL6vGI@~S3{fQA;LpQtG3e{puQxp&`KT3EdD7NqX_zb0%zUEh z=lbD`NElFSwsa;#Ue|PDHnUzMFj~t6G5QB+YCURhyE!{zdv%*XUPi;XRa!+Q`pOkr zuQ1Wt#6>XB0IE!p!>h>n%Au(FrP5wXP2VUiv(*i}bm+t7WE2!iaq4?#S6gTkx*C zRo@ORQU6mr&;0G&SA!{A#6ZpGWT*EXr~Ar$ts8<(vKx4qbAfTIVi#5kzt0$3!*6yB z!8TG-a8TCIap+@1mI9wzJ*a*bKl;x4u!@L^0>_rLj3lN_=_mpXGDCsPc*86oG`mw_ zPdg|p@tPR)4+I9t8MTm(P8woSRuENR)4;f5_~#sT z+}2NktaDY{VdAR7RkZa#2r`6ndj1pz*tK}bYh9`c%>qgNz?t05A9$I(y}TmOO7!uA z=VCeZVIw0WAJ2H%p34W1X8=|(<<(QD0h15TfA#8BH7~c{OcbHShd+J_{Dx1&=P$U2 zlF-=%k*Q(e2SsACA7>N;BjXuxLcT8Qwq4I8ek8Dz_GGvt;2m$MyZ|p$=vnSGZKlga zxq(#dOvt;!cis4u7kn={SX6pXx)G~4BO1dGPj09Rw1yJ@rLDZYNi~z$o~Umh!jxX4 z>XF4Xua1dz=hQ@UZ^J$&)pgpGN1C~X0gx(V(>oewD^enh&>XsQ3(gDh5CI3HeAbzr zaB=pvL+ZPud_`i~%UD_U(EuQQ>ett| zlwh2Z0J=bmawFgXo zncw(6(3dP27#@yWx&!1@h%Kt3;+`vQ>_ZDOmiVfGIjOagvbu}IH);5<(|W!|aAa%` z=DFUyb?fNNq%+Fm2;~%#-0-8TG{qas*_!^5du<_oPqL&pZ_q(z6DB&kzF6S|HrhIA zlus*-PHcRTh`YqAEDI1tIbFh7!vo%lm3lPYt&KU*iyE9Ix|*)Uq0X1zT925!SA#zg zjq0>~*jbSx!*y1r!GP@(5)v^Vstza?J4mpxu^CkDn>lCHF+guQctecM1=}dsHNMi$jG#t|ZNpepg}ytwJsW%jDa)owvK-Lf(w5Br&mki!^dA7WC=*HCw%r^tMC3 z9=Bu|!`+^a`obmQJoOdFyWl*eDwv#iW|Rm<@Rx`(%>;i+MV#YCK3%Df^n#h|(Rui1 zIf{~Y@3Q5qSI3~0Zrl4=aRrSL8R*Hl*X17vk(?`K5;n+`N?N^}KYwOfyVkg0llUpX zt_$lp8X*#g?vMfaI0rTJk5D#IC%eY;y}W$t4?R2-=Xiy+<93$=gJE#xqbSNBqO89! zf#f=#Ec`_^6l$h_ApZGlTVB7e4z0mI96NSY!Egd;jb?(f#Nk6)ON0WQXow3BVS$E( zg>@m;$brWfGh4UN`%Jb=8ry8zNV@W&UR3~66=~+WK4!4%E1AP|AP|H>18oqw^d{=F zK;J194O~PsE)}sz!Qz*ZRF2`?f+>2`(oyK9Teg>A=O0$fkXuT*<)`l_I-6(C#jdrs z;_uznlgpus`L)_Mp+XnfKYHh=fl7YB+*H=hc_qUmlQE*+@DV4i8^59|nB72KpQ-Dn zT7#_1u%7O4RECg*6el?8GH~^7X_FtZDnNJF09HCmn2q4ZtY+VxRM}XIBC;}T=d^T} zEV9sP$d3{CT`9A)rk@1W_DY5y=Tqz5hJQ-+F}hm8*(bQp#+-w3Hq#OgPRoBG=)tEDg=G>&fLlI@v_nGz5gWpT?Y1 z2VsR}`ErGhX2>Qh;KPz=-1yvpeE}U^2~ZA8cy)YKUnuyu<)$n=$XG<5YX2pfXuGB} zTXu#oEiGGtMzyrGKJ>~jr2SD4k&J}LKl7M@Xif~-$Q4$p7j{AKUIm4a%93YmAae#_ z)RR0|DXXBEHX!kNiKCy5Y-8`+4?)3K1*gE#H~bxd+Ckc2#eGHMFLm zl=7`-erlS;_p85nHyr*Jzuz;5Veaq1Xs+G*1)`G-`%jUI|IoOhq|Y*~6V#VuHc-bp zd)&vB6$Q}4?!)PUAtrsLffs7s$KNGH^~}0>h;izuxI}j7t#iSbzNY8Ng<&c=SDhMI z-7UGTjfuhyBZ5+5q25tKF=}G=JpXt3!_EWOLSuUB%g(8_e3*1sSSnPRvM_`0_kQb9cXh`Q}PEtkZeuo~Q#XTbPfld=fNmLIlc zMt@JL=mjz=jix7=rV8#)rH_Sg)diOrL~?L$t-3xpyE9DnBdcJI$o#H`_X2wD5xZ{Q z(L3Fd|J|&^Q;^@TqhBklU(>swSAxOla~!X`RB2$*y+v^;sj1ZhF9Z)AQU`WnP!{UO zD~FkggdmfJ);jMUN7RwZ4RB2~OP$9}$tZ+SDGm%+bT?+JxAwW9cHSqju!>TiQEvb8 zqfnm+_ND&T1O42Bx^%?BMu0IId1TS@JG&MOHEqHbmAUEb5*vug62X`DQH{&!5vWJ? zJhZTk!*NSobu6p;RIk`N`N^OV|K~Abta5QN6O9i~)=xTIGGh>riM^nFr9FF(l+5+j zRdRe*`uY(td}Ud-OxKbq(0D+z_F9Sg&yZ`E0WLS>^14fveKuLl?&m!ZqBv;HoOyfs z47^wFouQu0oFqir|1Sb&xp307GL}0#&(cEd5XMs?lxJu#&G&R45P-qwYH z#k?j>LMh6F#bW&FT0_OGmZ}2lM0PZO6m?>+P?z}>a3R0^?Ped&^nw*1B~lpg#0@LG zfB$|E17`GqBJ$p;KuQKOp%j_jmer;;Yx*eTOx)utI|W$msGi@Pvg#jZheEWuyC4qn%wGO|Ay$P z^9Auvt5=sEYdqwX{`e(LmrC=-C@anlo1{G#=>^FM@Wk{Fva4&nJdFFI60|kdW`&eG zvs;rR#TPmE?MrPi-%b5J@6bIuIv?j%7XNE8>$fyO0oBs0J|=T-m6wkpby)rxB67rO z&#&@t+0145Kzp%~F^kof|JW_+agbDJbNA|gGWJag-e-lcRV+${*}zPw-Nv&&`Z_gh(XSA85RKmHdN!W?{e;Q_=9dMC6E`75T7Ann@4J&osdtMgVHO z!uJB!J<)L2tFk;kN_7fm{^&lEZq4T5ri3P;z@WKERUQB-lQ5KI*c0Yjirsz?AA5+u zH0oInv<^w20da0a$Wn^eZ~;;BL%WuFV}0;QZ*NlPb^V%S^bC{j&%8lL_3-vq+U11N zWtgGGIX>8&^mY0^LN^fW|65~WwHEDgIWZ{?kxaqOhY_e#}p+#BR%9`Nv3 zmoAmt+KTa^p0=u9f%cloW9qd*p4kWVJWLG2jysMw33)!yl#JsEQ}C~Y&3ZY^HVa|c zwk1(b29AQBtOnViZ*r-e-gub`&1hOkQfRL!h6fKH%B|o&a6koz%Oa2G_W$EA@RPWV zXIEQ8wP2}Fo%v_;v9rI?x!PLZ6dumO7wi9Fu?Z7Cde2iPe}&h|##tetmQ-(Z1c@vC zlj}-0OGQoflO^5(ivJ zW(VMQZeHJPJn6yscibwUk$w%5E|l*lD1R$g==y$o`O$FAXx!AvlA6KnYqiB)^(w~o zwT+vTV2q-Vy4oXe5;-&v_$po(!y*k4`Kk!s2CB4Y`RhQczc%&6x~*Hqz#rIqjV~<4 zN2cztVLO)SV%X$GsG>!VK257u9l;K7i^kXMCocT55ijMa1>fEROm^k+^}{yRb_H&! z-&r1kUWUglojBWSvAFY9QH`sf2@D#q4Jux<;>$Au$%U!Kh|E!PF_EURWKbeT>y!r` zj*WV!eM?(|5~u@~ad2^!L32TZ-Rlh;9LLGuE+ph!ynpu0(W9K#RAQ*YCA)$$xd+-c zhE)O<$1&@L<%Jb{?rvWxVi0%Zf>p-`dO+O<7p(Y#`n z*K#k-N$ihEU~TVhd!|In6v6LrH=a0oGTQVG2%F06$&~qvVRR3~&FVe(Np8J&I8$aF zX0X@9ITp&?EMOk|D>(8Sb{3&d4mQ)Y4h*4U@#2%lf@ly4&{#~nVpa|WH`*`jlWP!G zgWhvzM86n0Son?$B zeZzqE>g`|&3>k%6a|7&Uqz_xN8=e1YOF5R54<=m=HC!>BCX zruWHT%8#E<>-<#!3z3Vc~ zL}Jgq!<|dkst%z_Xbfy=ftie37))!s)lc ztz8Ekd5fHa!rS1d^?FhqA*STEi_K0coUD*n*9RQy@etk^hw5>1Zo0W$=xZ^mu|9dx z>D=Y~$%{jEw6%xqGy*pqq4^ry5)~tAkt^dP`+aJ@?bmc}HtVy>U8BTv5mN+N}o1PSczAe3fDnE2#tqZ%E4S}B&nIWkS>k*AKctiGI8Z7oSHailkPr(ci-_tABt@M8 zU5jMPOTsQ(QOgL6`|LBnN~y|z<)W^hkQ0=uS3;=tdU}O>mG4HHRi92(T-_+aHIhck3WcX-;U#r{ur#iNb*Sj^;5ByvJF0TyYiLg#T|w!c%$hB=c;|e23=mY1 zdcQvnlc*!eT~8N3MSsFSUdMncxJ(y|Y^1W#4Btb2U zo|}XzH4u-pkdaZWWxR7t9`gX3#+*kKyS3?8a3C>W>inKtl-KLCB5aV&?CkOx1xV4} z`zDJY&5_5Fj&&A|HKaFAjl}z_WQf)>wR}wau~foGZ(O*Wr>FP=BD=h4AwbPYNH;{$ z+c<+#hZmWRg#Uq$vAa5`R0Ga@3?MxyNbw6a6zF#Y`NVznfNzIS66M)vb`>M(_Phx9 zqF$-01;20U3dwUXZ=lBZz$jfqhO-va2&`QamocKlOR;5q)mY76Vc$PbV8nLVX-fks*DFNhxqGp z?_Ln>KH^k2GEn_)`We{7$p(G5hnn=x{m^%w5s==V~g7ILBQx%hggG z&tR0cT}{0lB#l@w8tXxLG|G}QKUxkO#&BT3vIOZIe89wPLI}zA=|(sI^4C(Gd(<1h zX1>_x-=zA#rLiwbr}D#x(>`olsvBVLf7R9X@m1&Pe8NXK^vRRAyIM|C!$Wa78-MSgk8J zZPtjU&t)1kx@w*~X5eBvAKTE_s1AXO94;gW>1&(Eyzwun*M7@W?!{joqw8-gf~1yJ z_)&3!)WMM_IM8K*S63f&PymH|6!pXaNQ%l~Z+&EH3X9=Oo@8`IpaHa|n6esnN#E)~ z-rdtC8Z+DcR~WTP6H423Xovd7_tT#>j4&cN*{K@O>zdSPP!Ge&$fuyVA_+Daktlq6 z&g`q0*5_*P^C2@$y!TtjvT__so9K|b_yGj$s&!^ta-KuYt*xb{Fqk=5smxnsU!xyJ zu0R2Bu~$AhxP_|VLhV@KG6(IB=g(9sDIaR)OYS3FEScpiW(Emjt%q568b9%7t}7Jl zsYpWOF&y{R_x|Sgg~Rn?oaV9`hzRN6J)>^qCL%QaHp!KAG3xY4U z!VjIDQGo)WQWAvgSV_@xNNOq98WS_};)F|Cn7~ybw`R$bAe;_P3>CbdnIn84CWp2bu=?E9G~7#w2k3LuzBivjwh;%jktmpwb9?pv2*d?a1H}sF ze@9}B;CqLjxLB|3`K`S7 zP9{z&G3+;h3rxp9%1;L1U=(ptZ`HLdaI7dLaS(`ccjwqZM=pKO!5=k!d7GJyhVxXl zCEm;}a65sC5T#)08y;H$MI^4nFib*q{zJIR&4L*~0c1>&wkv96fB!E>tX=<~!Sl-* z!TueU-|pgYccD|K?h*cZ|J$$b%4m64fG{B7CaOzYcLt{`qi3OIOIw>VADfr^YIyJm z5&nftbzz|}>UddrC&cuLqm_I9+=Y+NUN68P(}`i;bKVDGLk2zyNBbXZa?a)1v)x|o z{9p$t?1BC)3fCq{CBGF=SsKqAZW{t*^j3>fGc}x#(zJfDVvgovPg`q@EprAS_?Nb} zwvtCGSDZ8G;bvmH06v=&(;(R6rJBdxaP^00F_-gI@DS_wQewInU0V}8~v$>$YA zj0l*GsXJOmvXQZ`^YTc&Rf6!TR?Ff*jd#)da%dQ7@y;eRwJz5R=q=dq6iHLR-meG8 zfDNR?JrmlNRKF|dlvY!Vg?Eke-GaTw$wOe(LFJO9COV(?fSAUs>q~ZrsYu}fK&JNn z$%lvvhPhDI#3Do~arHASkQX{;I3k+(%xTE*pV$wYTRGp0ozj=Qng4xHj1v-SS!6WmgqL9HlO>>T*)y!rYoza zbbinfSOKu-$gI2rmd$XICz z&1|(_S74J7K0y5i(Qt}#c-CybWgOhxmFNytz|s~0HO)5Z!L^)T{7Ku*JjujBBnj5Q zBiB++-@0ckAY1gb_aVo{{{36l?1;$xu>9i4d-X({Z|8(XL~KCC8zy zV_1`o8d%_g<>!zqpDy+2!2?R`(0v1W0nI#VfO+(%?FNiSCBFf&(T%G&4Z+m4lI!^759&mtIROB%KDmgvzy zuvZSF)Cd0lvGFn@oZ|ye2O~qim^{7{JtFwl2{d5?@a<7@8E55vIY+q*X&39+%r-a4 zA%PLc20TFU>Eb`#(xCnrzvF5SBlb(ir%>sCsNSfD<6jSt5Zu`{+qT0m2qgR-g}uD% zHRw&u_V2io_m2Xc7txH{o}IH;SbaEhJXf<*^+Zqc4ld)|_vt7>lOPkayZh#ku40J^ z&6WcH`}ZFsVNiTwRR;PMtO-+Gxh{E8Lj256e8gNT&*vyL5SQvM1Ow0S{ryo7Se7mg z#r>Kl6H$Iih?U$t9BkqmfY?aBM5AdJK5~7T?`e@wJySA6>Df_8&`GK#1BDIsS2D>W z>xLY5y}7~IyBGvhg3xu{(wK*tO5C%}@7@lu-hSh^6X^6_$G&BxT3BarC|ViGlszxz zy1RTAFJ2t%saJmS;)RvlVRl-!qg3=oO}{HukQBkDRSGGo!ELigWp8K+%Y=*vThL*3 z&wG*6+pSSM3TxsD_(T;oS3`2p+OdKfg;?CTaCX0JCUbU*S*8Irhh2TnFl{SVp!*yD zjhoQFHz>INENtRMotrm(J@uFg%Zzi{TKaLzNqwbXkXN_S=F?0x9*7YAm-J4$fYPWG z7A5Ly>v?2MwJq`V2lW-9-(Ri*H`Sg^z#_aXPkY@TUopm+|9}SWJx*@!*xjcf&1W^? zyGH*v;et9L#7FHfPN#}u;n#!?A9jHuOk{O+wcYKPA#^;q$*P_1 z&-3=Vb+nHSNB$^@^M-Vcbj1@*|0w-wRd$e3_FY>Plw&}XHGpl~uciENoXn9RTfQSt zdMVYGZ`dF$EBl08uVrua=y*_E4CP7d7B$o0(y4;#-vc_m-81S5V!(Ho-z5 zYyp9hewqlSt>xG1QxIu1q^eYY2_-?zLet?%G-i>ipfHfpxD{*QR3R>@X!)tA_`$@* zyIqN8l4bB7ZGW)qKaZvs7#NtdAk~Mx!LM$^h7ILt^||i2xq@nI{9ZU05d?#Vw<~i7 zsGllI2p#5vi0;-+&zOAz0@Pn`?P;yzp;aLk))g;rtGnlr4m&j4imH#f)t_wnHm8g6 zVgE&`aE-Pw0+IQ{YxnKi3R~93QQ6{HPeE>(BpV6VS|VW>7JlE37M)n zzWW}6$O+P=fv16_F<)4!PZ@d%si%<#a#^m(5Fi?OGN;iFE^%DxJo@$Wr{oW)?num3 zSC{FL+M%RLrU0?+);gY**ZgNdcW^;C=H%jvI^CGlRYIsPov=pG$%=tW^F9i>b90V;{x<4e3@x+#XnH> z8lo1iEaQ?iLRu11;#9?dOjgY|ZoqR#61(|Q>B~4@2%}_R~PxO1I|L$U%ckeAW&TpNHyy(bBKb;-gZfG1x0{T!45O8AaDxzy3v1v=&arOYtP{V? z^7S7ql)aq86_@!KOg06+f$B0uZ|U{*+{s~4H<>0PgV##l%Rdo437Gxnojb{0N&?im zi*p+t5tKpiv6rEzCMgQQM=SrWpwrV20IV*5^T-!3kEK&%zXuiXSHsX1l`=U@XPK0a0bY& zntB6u3g1V%e5$<+-~!pNmgI)04i;<8CAjW^!E!;SFR!N%c8gYJiP02jql0L*%12hy z)=K2~weF`u%~T14pqOHP-Xww%!*RUiLQ4G>^Et(2Xhgk5e_?*{`>~1L*|XsA9_ZZa z_hoJ6kpt=1RAWi={ICP*cvhC&e!|8s{Q0R!jPU!Ju}=sUSk;NLI2`SUY=ZM2Jjbj z=o|sz#XY!p?^O3b;45X|tMTX*JW^_Ve0iAOcexQ?fabh~%bWT(hyu3;%p`zALg{_+ z_zD3`D3E!4p0{7{zWdb0QWK9|f64Qk>~KJ0`E-yMQPwD2B!^bO-QE2RCdLHcvmLN< zaL80jKCeIbx;|aGa1O-i%vxk9rS_U-jqnX*#07%x=Cc!|1!sxLy;UIxM(zI1LAN6q zQMv=~5|h*kaG?t>YRQs@OpJ^%Pp4cNS6Ym}0eOsv6liZE!u$;!dxA$|b8dXHLavpC zX^_uvy~v-rG}ba#qeTOL{Aulq*0Bxv=866`qSHVe)#KNR1=bx%tf8N~#K@Xv!_k?w z!m2qp)1Xf!fYEl?f(EP6O*n?w8_Ua~)Foumw{^DewOV!PmL0(jdH4y|KU!Bo)UDg{ zbq%~^%_H|qvGv7zR%5%O^&-{rQ8ysQ@+{F>s4d&0Qy>k|j26v1sBB3p6uyeWcJkk$ z@m&3!|8gCFCu_4?ckaj`H#>0gUiAOtAdBO{zwz_@gBzK8m9X&#-*(s4)fsf{T3-qb zBL9l0KFs=?3QX+Jo(=FOXC%^s(`!$`;Kf#2g9HcAdJ4G4Z^*j$|R_`;I0 zIgtq7VXsYd_5D2?ma=Drau|_iX1v%UP0jVC8<$$QapO^dXPjHNM!ftGDzUOl0>jcQ zmze0JPJjwoj)rec2L=oWg3+RoJ&7GMfDW}%c27fA#u}R@m-Gk6)%jR#up%+iV_?-9 z#Bif-Av2;U0YxfFdD4OJF~}ycPU9|Ojs1i68OL>-6j-~>e{lc)x%zhF$?PRdmVByb z(4od2er=7WesZuUH_w_uA#w71*frKn<;!U3&iP@dg!~T;(txm`ths zTo^F{-`gs{C`R?=IUP5W?w1DL!2@*BiOdX1&Jmw`GN-=o>sq)}hj3|4yE9S+q?{>| z(i>2Hewf3vzAY}U!ZGvk@rnAKpBgE1T}_K~PQax>+Y3dPG6Qei>$wa|-!?X8pZi1v zF$br{&AWz=x-Klme*f~ELsm{$1G;di7{dl|xqJ*U|ETTRQK@Wv28QhW1WUPh3GfpR z{u16;%8k{xYPNZxOF-KLaWcu7`a9CCD_MuPTY1Gxj4Hqg1sbz5tnchzBX_?IbKm5;Nl5-W`TJ`$-66#eT<+*P<0x>7E z$gyMLX#FwD)9p#~bKdi^o5-**Xy-yq41n=;!gPr3hbd19vY&H~(QpbN6p%aT?n<%{3VaS4Rc+UvN}^1_B+znQ zx>!mJu5T8BI=ghp$i)Bdm8N%ienH#e@YPiKKP@NiFKU^h@GIZgdRRI&eC04C@z7k%XnJ!*@oFy3 zmh$J2uMn6YC}(8ZzAbbUNPm>8FonYqN(BQ*Zjv;&siw;|I`q2@e#7h+Wt3F0Weyfr zu{k*KG13_$Pl1Fe&F5o()(EnhFT?%YZ(IYHoG+G!T2zjLgUmbmntKSL zH}8B|0b?adS8qLINi1);@>!pes}Glj?3Ee>A%m(f@~V~| zL_0`u*4>9cyBgfh8oSbfXVic%_O<=VHz_fFl z!w|vQq?anVd9yI|2l4su->=rmnjG!2{Px<{tb3=%>K!U6Mt<-o7DkZB@8LoiaBzdN z9e05-ygI+p#MzAsbf2hgsr)n~mEsV(H7ZmIosN{TkTbn^a63p)i2Tk~gma_Fch0BR z(6daVZayK73lx^ph`Vd(ZYM_-eS{%tE} z;L<)37t8?DgNEhIL!IYuN>Q12=@Wm{KR!GDF{ccxVPA9SRNOWCM`f$&<87)#PjUZ_ zB0v6hrhj2vm-_U>R^3*&M$B1=093U5?)OmJYt9=#4WT`TR80(B<7bEU$M2?hy!x{S>AaRCzCkt0HBf%X6?iOxz&a zw$zQm;&9vxkI@GYJv!aD2Xx+g6_?muvNxpV$=2*tp&*GPEX<{+9cuTyMEl?brrVaToQ|V?!elZ6$HtAp=Q>*L*>Ksk%rjJX*cGqy-|w7x43LKB z`AzSsKfg;l!;{cZPNJv23JNbeQ%@z$nUHynHK}}(qrnaZ^FVw%#)T<~Dkwa{bUp=` zse!UZG*|D^ok{`^6Om-!bg7L@Mql2;Cktt$7X{!zwQhc>oqKR-<)``<02p3LcNO%J`E{(s5S-#<#xA* z`oo#>Xls9fKD3jS=nZ@xy}FxfL_jW0Yu*GJdR?uZC^%~eS@vIJZ~lvWNZ@R2O69k> zm}bTChEjbq$bL>Pukfu=LlI@D3N16(YiDe1Y+@Wcn*7NZ(=B)ui(MeMeCNM%Str1bRMRVZ`1TX)%8LkQ6cudxKnf2IIt zan1d(n*U>oZ@Ljp=bPc-asSJ_@e^AO)-HX>*=8G(?X@L8&PYb+8dKBmkD1LR?L<<^f1UUAnov$M@C8s zCC63kdN)|=e-u9Z;%xr*eW4QbliS@310qust2;GmdZsc5(>Ntt9}FEjXc{}%R{E*b zPOn{7LXo#(G%MoJ0gjX1N{MCtDF=cX?VXaN{cSELTdkFRHhO#Y0TEpbf%;KPJ?Ze# z#7_~lR@uwDs-LdU?FLPY_!M~DzkmAF=1)TcM$7A`>p>The|An4!#(JME!*n9kdXT< z5c~X}UoM|>OBXceN zQLTA50#~x7QanBFApm=%`yZPDXXu!T)WwDjv_37o9J?FvS-9^8SV{ z&Eop+iIdfX(I+Op-}-LZ+T5maap{tOf*QVMB_7hu_D>z%#n@>RSvX=m*`}Vj)iz=9 zDSuVbhs_h*u?#C5SF`9{H^~@L8H6rY4=xvsN*mzl(|&Jp^r^X=Wk6CGTGUj`6pRuj!2G z*fc~~n#8HCA`XbQ-0}K*L%^fDU~`?w%^Q~NQ&yX{>*c|B2+c$UX$M#EK~S!$t?y~o zJD63Rkyi{FDwCR;urO8bhK8ZC@vNxiUY^k~(f}4aOVipwk7l`W(euLwZ#LB#4U3mVtd?4s;*&+jCFC~y`0)2+ z_7`zh`K+`pU=$4Xv#QarbmzR&Sa&qF{;UzTQfemIpac&Sq6EHd^5+UPY$i>RkS9+- zhl!G8XyzFfFy%ebc5RK_aeQ7GuxnUljp4BhbDA);CO$^9!-gK?gib+SJ!r~&f3kV) zRJ(MyP7%5BZu3I%!}~VPjTo+S^k9IocpHFxO0G(R< z!#se2cWRWMSMqRb7We+9%;%&i*dIxsLOj5ucNd@pj>W|8dYfi9QYE3Rn2qyR*eRNt z^}JK%k7G-fNB_#UrR8zDEm?yPQP&VQNkTwFEbrT6$aj8z{#UiGZ)J6w=gy&bYcy7*&F)Xrh&+&MpH$Q~NUSydOtPWC264#P@^c4xudMl5 zJ?UN1E0+TxjP_Zs^3iO88IM+v@b2}dWd$AW?%e6}FC;E?9f$$u7sVG{+E{f^r($<} z?yRf>qv{@=0{nFc&0j54#r1Ox#SA-(RE{l=MMN;ffr_k`IWn742PN? z(zNRIfFYj}?e_TpGND;6&8SRlx36p3NYm14+JEqw+`}0T*uJAVzBP`JZxc$kZ~BGa zw73YfX)Zu28a#5T$sk4!sU11AYypNW_q;s4e3W*!`J8vKfR0%UL8g)4g(A3x5Op0J z93_YB{QT(Y=vyjl2Xz>&TzWNP{pN!C?+ z&p#qqS|^I(l$Z4|CVS>2TXp2fk!a_P?CgtvZBg&%?munaSs2jpA^l3Rhv~Mm))2vS z8C{d&VeL$Q^UjQS!%a{E-kA z(^$)Fq;5UMe)ERjspe<&DOD|JK7DkAgX+-aDZ%NZZ1Ok<5a;;@*;TBpA%G8@|9HJ$ zp&&H`mrqLF(wlz(BGyY08fA2JLI>xWs;Q}YoCZ1<)zs9)=BXj+!WR}&QCaM_`anc7 zCQ9oeWP1NHFliABu|FRJPE3`L@$(2G#T>=KU#;{8SBd3oR{3^9c1+WMl?bsGc--a& z_7cR>x>90GE6bp(9)v8fj@Az3_N*P8h+RAIzCm49;k4|or0jrfojZ?W&(3j`<9y?9 zlCffVv`s`#g>NWxSGxUMzY6XyKgOxbf~333YuW1>7H9OTnlCnrd++2O#=%q2_9$Ie zSbaJ*Z%QS`tLQynxMTr|KYR%^s9R3I@irr3&Cs2E0sth`s#2%N#Ag~rhPjmD-=UlfG0 zTo?lFh}i5&JI3WZ13wI6&S5F|1ku@s6};wU$AM{=gJ&yH++D!%{pR<9i^|z0djbx{ z%@JLsaP-=|tDU(wdN~CSq@Uxof7va5&|YMRV^Vo~=+Rq?l=gq}V>>#w!{OUw|A}$i zs6(HubbBI=Zwsf^^9^}T(;r~KvTABF_Z`<>sWddD`1tC_io{(!C>@Vq7emu7f*|Qc zaZu}tY3mdN;ZlK)v__0=rnN*Ntur5-3`4}BUoD4p+gdI3O(mj^rLyj&crsP!`DiB> zks5+*9NDi$S`CtVhhV#E`EIkPY+A#Wj~Js9cKh~iwl{Zf-%h;L4H~Xx?29wYwAysL zI(1{^m8`sZUpHPm6p1=eahIRqry()px-isj%2jp0@`(uEhxWyW!<|tV)Ri3(u?%#x ztW{8~XQV_=`@B2I1VVdlci(H|`RjMvw{1JwI;F`t_=>BsZnoTie8vzYEzxyQli&3p zz2+cGc+bB!A5;8{zUBbimgfT)EZ)nBQ>TMd_3sw#t=$%`77tK7&bHrA`G(HeFv zq}e_8Xq^al%gTXXs2sdLn186?d^VJwa5sxj+<0o>&Y7wDWpxoxFTatEe(i5ER?oGi z-Dh>9Qq^t#VXJ!cPxTc_s}9&ndrmdy-z@9Kc^~u;y9i3pyqPW9%M5zx2UJ)WxC_P` z3&tWVxq#A=vp}vWXPJxYO<-1;9UgkbV_};AG(%t^R z#C~E^ig9BshWx%1@S6Z==AL#q_nwYg{5$&}1;)^q%ad4F4%ZEE+yzeG zKU#JB;-GO&e48$-=hChT`zp?4#V)otw(Z@b126LKMjvEibQG!zaJnEoHPtgNY5jb6 z!)VruwnOfRqIXv&R+J6)#Pup)bP~(H#oJb+xVLSO%UJevhijGW7s7wo^!`w@o46y- zHMnEj)(;(fiX(p{SPox&{OI~p-q^F{w^9t6CmRFynSSr+U$oxrUM=a8*Tw|RAUlC- zG_Cpy*O=BO^Mj-%2*Tp2xc}94-SJem|39Kg$xJ0e*+t17p`7f!g(zG0s$?rG+1Y!R zEqjDe$jsn0C$nZM87_xpUGo_c=IAJ6M0$2sS|@9X+ppYa~66@OW`{qLs2(SSGx z8B22fEjxqUOFbV%X$MGXWh_GNvCT8>Ux$aG&0{9SCdk2|1j$#4D>k4UT7cG z;K01a2zThGXN&%(x3_oYDQl(W9yx*b6U9LwRCOX{pdVNcB?xHU*mz)&i-Fjh}Y*u$FdJtO^5`@@@k%9ki!qr{5a`DAFGwiOj}c-Z!g?T*y;y+iH#zpGu^ zm34bO=eV$ib%3>F&?>I#IkWt5yUZxh1wBuC;cQypR&{P^`-n=+vPS)Np^XksmkJE) z=t1V)5@@jG2JxISeZziH!#L2TnvcZtV%Z*>OYOpOb6?7ia=FvGH~U^^oSeA{kzv%B zJ?nokW9tkNkO6FK--Q03>T@n0x-F0?!@>f6Xs;XJjIR6@egDqSli1)b7E=BW%s+os zhYv8Z=@&0f8X6h3di%=W2s*+Ogq{C7`W|=Ysr?CqUezWha=bL0 zFWaa5{{5wu!9ho?dpt#$U;?su1H_o_L!EnFwFl{f-cx$4^cbqeNf zgGPmFfza6a=2k7ida%2TzcORw`DyoFhGVxyL})~cGh6kD7Ei7b);f;&DN1f8=#?7B z**yRLxS2{GYN!s@|7pO10|>&gov>V((}2oU8L-qfPOJZmjDIb3k7Fb&C0mm^^-|@d zbF4E}`}1p|w#05st5+uv?kD*3+kAt*B=!)&bj zv0AV_jM&L}h%emBt{|R($xQM4bhq7+@tjzKr@7}+VJT}|blpxyhGjsL9*EV083N9t;2uF90Zul^vb!^O3}!<|{nvq?(ecyTP3Ih(pGuUMxfugAOIir+4cL1%*} zHnUCsu8_|1!H#Q$jSSO%VfKOLegz-bz7;Fu>!k8|=75jv)tklU8(q`NxqKgLcX(WC z_G6_UjM;9s$2?sX^LdYvoO8AxearJ^_ApVzZL;p7>=XG_#nlr2?fX7}hFI?ZM!P-* z$%`r;lEuf{wlY_O|0<_JGf^209eU}^hzRjt1(o|J1dLJacIX;A1;J7mI-mAK=>M50 z{Pi*j9)pOSD>ePje~#IoSvmaAl15KX9fT;dmFZyw26L@2e4N-LH9sl}Z`V6$xgU)e z{_&M`!G1GLzJe#SD;m_5R83Xvu(tur;Q-_T{%f(u+V|x|dAx$ZtO*1#(ZZR zi;Hvp@{B^u!*M+o%&7SyF^L@(f z%=tOOyOZ2pQH*v`owxHr8#XUW6`Pd)_~;1bFbFi{CRLgO5{M(S12o;V!LT5U_grmO zmIUCO`h(zbXxaNVRQzA@Eb2}@OZROArvqk4TC|&xG&M1cZcbf;kzpT zN@6+&1TR;MB z->{5S9ZJ4%)hQf%K6Y-H=KTv#d$H>${C$N?76+Y|=@knb^SZOT&tAXJUPz~wa~4#4 z)1Qr1sbIZ6T(>xse*R^w0)uw!s7f$Sz*^$lUHrb(E>!i@IhXiS%IGVu#C&k#z#qCT ztV=L7oke(S12ZxJjUQvcwDRCPfNt_6^HG!~q!RZBU9Tz@q%44k%utW9Qq&>71o~i> z@zDAu_mzhx>FxYle%?#%(hq}Dh<146&`{^NTjnO3W`hz=C)T1EP!Dt{n;eK>6$%~MKJ>{)5b@GFm6P^ZoYi7877$6XmTH-Io{m#ae**9m zy9MlQ+e2+QctE@1CBYuRix+{ldL3my;8aAHl{t*aK{?eiQuiEwf@+g5;coevzb}tQ z8ov$jNSO^UlivXC=;l&|!>dZklK zpT;GrY4UtzzJef*PFN{>-}7USNT~*y&R2PvpMp4p%qwlVdD}hV9E@`X+ZR&7oJh zdpMFLdQ<=yq@=l}Lg1^iGzMUgVQ9AHd4KYozSD>)RG2*fzYCnWhaKZJU*J^kfMd9* zbcZwlhSQHoh6K@nT>sBoLB#4|g6#x<9{QF4e}Dd;MaOqb4`lXA9Wh!I-9j60p_D&i zUJJgmVxtAG>YhN;6IQiowfAZ?2g+Q%*D+ct1N78rUcY$?1)*GAB}C5(yjBuTXH&D- z;73B}Ww7Uc^rPI@P!)C<6pV36`@y#f3jul*LziwmY_ITOb+U=gjO&<(0e<5pOZLN@ zC%6vrgQF-1tI@tE#Td)JH!1-d=}1-$%qGj7+V4KXd$g~Y38~h$LE{Ad7BN;A05O&@ zRQ>)hkD16#C_{W{sgMfAH(?|Js3d=Gf%;uvVO9W7mFLN(QtZaQPS- zM|R2xS>izfFqP8JrGKf8v%1!wCP~W3lHUx?`mdkk)N{4^P|obTRf~!1YipAXPEZIB zf)deetKe*smv-Yn(m;3dpOKBxyqHsBD~BUMq9|6|(;GE*@9tlkkR;vzGij&RkV0MG(?!a%07o zqr>O9A8I5=k~p&KRC2Q5r}IZ{>(tVFs$E{~lK)Y=F#g@@Bb8Ge!m5zdsO-GCE9P?N z3dIX*p$kYFqID0Xrpu%rjU7vsU&jaT3n1jnpJ4$wR0n)6CSd~1ME z1B2|ZzCC_7SzqnKm_&N@lYRK1#{4I)1G3iP43n_;W~a>FjJ4;90}1yZm7MeJW* z^O}Z8ZsKLR5P2Fi>90YC$lbjY4~(+gj5-r)!qh?2A{&uNnzcwfWy?-P_4sQDTcr(% zb>%|eC4kOiZ+n&7sO>B((;L&Oxc>Su4rUx|q7`O;CAQ7@cuDxW1gQ>>vqGz7$Y{QLa8RKH*SnebSfC z*H@i!0qQixt!Jn!b7U1t#q2E zqaB(x1;|>Q?Z$@3FFq~cGX2~bmO^nwLl1#YO{;dim2+F1myBK|r+e&eKyns`CYS)n z=%#Rczsx-gz|p-G+8k^MW3d{o>`MU8ab=@GuxlG~9I@b$Z%rrqbvdeti42w5mkY78 zcN&fZw}heYx6KMs9*be3EEO{}8jd7F2u3I`R1WSxnh`&h?oze2JC-J}l7%wsd>qocZ05a3%cN0`*>x~R1w1gk~M1o>7MB=x=+8SDR z-KzRZkmg-Sd=^yNn6=Dc2$2Ij!(;uTPtBzj7!nRbxAGwf4VSDG)q z!6JyJnzgR`IcaH)Z*7^G%J5}kI9mXoXbia%V~U$4kKqS1#LT?>1wWKC4nD@$@EUK6 zKy?SnD2wWw@-5P19%A@yiNfOya&aalW_?9K@w=>batk-A4g|gz!M_X+u3=5!?YT=% zJfXuOyYdA(TXtnj5N*^HL=?Qlc#r)^fFx`fj3aa5rTrk*MUz^$bs68J^S1Lv;Pr1_ zq0|dio!q=|DXB&sQ|~z6+Y)X_;Uyx7Q%u2d%J*TNJJu??wS>qT2LZ(ZXx=8e1WtyN z6!%1vE65h?h2N=jQ%Ru&}Uru;`LoDFSJ9iQdkcEShplgRSXbO6I ziPBJG1B2mh)$+TMN~dK@aG$#+SY~VSilpm;r0}r9mEF5;uO_5~Ng5V1=|+qbT^_<= z*bglGPQrWb;M!whtCoAWk6*Xg`4vf;7LmJ1DNz)UZR!5rzAYo?rrD@?ilg6%A;9Rk zT?X{wYl3f2{r5mn5gmbi4WA6JQC4JX4uW&khXI_=zLfVSth$~aytvU}?P=f#3;eQ_ z$TCMw51H5lz#aOXX>h?}NZNl1jhoLHw>VgOSPUKuenegMzCv5*p3yfhgD~W~taNe< zC(51U<`{SaT2f7b@7U>U_}cQX>fl8WpvO@D>DYGjrJ&1qFKitTb|<7-n3%nHutp&O z-qS}Vjzosh0wPv;@cPFKQ~tpc(QUFVT_RPUC1dG~h zr36(vF6Xv5hXmIjox*qZb8o>GHEY{4Tz?jHnsSCv#pG>Lxy8uCJQjx=Z^eawh)ePH z=INSn8)onC&UNZs#z3<4WK9s|q0Ar>&0)jrNpTE|SOhI6Eb;2dip33`{@60Op8qa#N+A?JnEoroF=E@(rT0-7<@w>2vU7$mXFP{8$^PJVy&J z`h4onknf0BcZc62KIoh{c~-&RW_waau?ao83eG25;T4djRx^EeG6Xs6z8?@_>BoPZ zX{SXw_1xJ`4Z3LtOWdva(+@!}oP&dw2MGZq3%ywn=-UN`sjmv$4JsYYHIAibyPu{s zG?1m(0PaD&@`49|dceSne+w#bmCKh-V$)*#j?59XkcglYuGH&|2bBvAVwTgl;JVYI zD~jxAtHD|H+-tZ=FZ8zBZ$rJ5!F*!|4}MJE8udcTC&`{AqRGwTOIv+M;m0?8HzrU1 zeDU<{2KR(IZ6H)7sdO@<5jmJ3b$9$i1ui19F;59jpK zRi?>J5iTd~jxiVuJNC%(R5%w0$3A2+O<(CftGx*iUi>oauGAzxjEFUapx<)Y)}fCUP>%&D`tcrN3mOk?oIU}(H#gS z5O*(M@<|{rV;p!cS_{j$%UNXY;F6_$0xkXCog+2^LbRH2N5kmPF76VS9k1H2S)sP6 zq99|w6k4ETKvb5Q>_%fLf7IZjFt$xq5G9Xn9<8N3>Fg1~V>Zr5&htHEqqCH!MZ1#) zmJ89Gicg9qp#%%r0jRF1kOI>)ea~?O60V1c3J+=9X)1os*F}4e)r=7=U40 z9S}59#z^Np5iA|jX8?7$0uVE~3q>voTL9(0_z|0`!(q-*YWTK1Hf})lig93tUKR&x;TgIEB!NP}CK;J)XN5_kz}JnLC7qiUX0h|) z6sye7aJVheCNVUhKq2%#B<`|bdYFcTZ~#zfV)w111WH#;Aa-BWY0SKgCo#xYUnt|5 z3)3S;m6%5U^8%)5A*chqTUQoj{o8l|h<_K3P(n5q+!{iAV-|83hDX^}567y9E-&V* z=j$@Osk`yuGEo3H_q6Y@u~enJUG7imeNsH9|E$lvY1^BMT>wN7F_2)`uWyCP@iQlL zgrED;L~+l4i{*Y5UD*R7CTWrJCVrD%@PUJx_ZT70B*QgGb94k=-~LMRMeJhRdIL2eOB0`|*f3 z9%St$0xHARkJmXvClp<2lK5OqM#aq~pmN{xy1N~G2jRt)0nigfmc}pw8hxCT zy%9;1Ox`<2Ky;-}(I)si?fy^QtSLDGA{vg}{f4V2&;z-5jggKxk`IoudkBPt9uBmD zMwiX|O$CE@Yg8g3BSTMHS`W{7C}M7+itCq;no6`b#N7BmucBh9unlKzq!70_Bt7(ERT; z3puebYA_Ercu&ypDKz*7zT}<6ql8R$9Tg%$ZyWTg;!a2<5T(jS-SEEx_F{ku>Pta6GzmnMI5fjw`QN1*pK45?>q|IXUA zU-SJ&DLtUEaDyp2)eIWC^kNo4~bk-4cs0C0{tP5qI+siCQ`eFRA|MKV|P4G1jBx?kl z=$NRbaiEDVLObb(-^f485`!BaK<^y{ftXx?e?qq-3`tM^r3R)E$A>uD{XBK}_wT51 z-2;#$gOF%j08@4oU?NB%0?iPpF_0)F9h;ZfKqzoB+(@o1PkGJ%;k^)0O8JO@aZ(ha zRU^`bgLFIJdEFA;kyGl&b2%>Ag`5yuLiTl7$2B0It;hdm6MEz@BK_@MNE?CHLbI?S zh5PH``fo?ISr!gBySJlRT))@BjiM9aSX(0-b* z7MP{yWMwr2hyKDzrboYi_Ag%p3vW?EFE)A_3-{L|`Zc|KxlqYdW~yKR5xHSS?vR}{ z2Nr*PgvlN1$fvC9>?yu|TuX^!cI>fA4jTl!8&As2Zfd>YT zsAcpy$gvG>7*d0L7pM)cefgC@ckc z_TeN^uSEb7Beh-Q^g`m{p0P798B@oQy)@IGA`tZi@W7Z%{YJ#ligUT($*a-^gn;GU6&51bG^G*k8q!;pG4H+U6W8}fQ_y9ny z6S3_8MxWo0-LxxLKZp&DI8|FN_zR-Y?=Ho|*&(1`HIo#Q14=Iaz{ku6#OWX$)K6DL1)vk?iGMV|J$sdXosD1l3J&7rHs%7-WzWD}ud8MuhST&u46up-Ow?3! z+{=)!SYpbiA??0w@Z-pjfnTR4dk;4bdUSn1e2s}^x*a}4UAsHFj7HzvHPBch?GiP^ z*r^&o`}L;-GB&9q`djG{3sY{v1tefU_Fr=M04+gtbAXd z&d6}7#lnXcz~^RBGJbqey)c>FR1$&*!9;KT5nwPdK>2oH_mSX!w4&F8#fFrV20VO3JGM$C2nwP}>@mcYGRC)|~_#E@EL5xmw37IGVTpbV;r2iBoY zx1J0cMP9LX+?&$8thJ#_mYq4iQj6a$``@defHu=O0Bjl4Inp`T=Guer>{T$7k)<5` zBJ&`!b{}J9bG5$)80t#`SI*oE3wo;baxaoTIVwf@v+cjPHuCw=Te1$TMj? zy7AaM`T5ND6M2+Yz^f>Qg)VXG#|G|txIKL;x%eE*CydCVr2H3J zNxGamz;bH(0N=*BVD|%zt}sy#UfLY*HuUoyA+J^tJ(UX8o{9I~KHq-hIEFIF>2-{F zp&FGuE6%!>;ihUqg1qoP=M{Hon)0v*Yz3=dGo5)iKvH}U0HH`X)!X4t{o|$D!-Mk8 zwnqcguC>j_P7{?GXOY7I_aR9htCl)IY;>N?rCTP;#p3a|WGh#KNS#edkED=n%C$oh zUVxEdpp3U?_dq&tumeco-$a$W7bXH*mifSvw zZerq$gG{iVC;CAetSZ^qX~ao}k{}VX1q6#2cPgHod5_@XineEs`6!{2`!W(3N|1&iy;YPMD8EH_aTFI8H9p;G}H3 zoUifXy5g1a@{B83hMMXslHWD)W1xO4b2GUraa@SJLhZP<0W2@Bj#t-Y*4=UiP(_dk zR9^9fFxe&VIkfbpTCPvfzr<_@G%rsatOLQlauz+HZ5K!x26f1&VNnHSS~}LRAP*I2 zj~>&Ea>HlpNu8NFUwZ+%ua3}6s}g#f=yothN%I|X>Fd4D7v_(|o~W+ln<-tqTCt&8VR`pz4+yVpP^EvD^c#goK)2=fBTR&4 z02a}Yx1EpX`hfXk0qxJcX0SpHVrzGK+@l-C-DY?`av5T$u9`=Yl8hecvN7n3J?=rj zDK576xzcw+s{kxe7!w|S4H0*&6rcPIn;TsdyFm>r_|yG2LJv}+uGuJ_!yc|us8w|9 z;f1(lUG))Ov`Co9no>!qJ-5rKYg4t<#83Nq8tv!M zVZ-#oZFEq4=M*NyBtI?3RND=b2?5#E4KtX(u!^|Ih%C6D-(~u|^B_oQW(TF|Je%yZ z2z2fOSk3}7T(`#@ZZ2Ijbv$L`9OL0b&0{~S5DP}h7zk#-PRV?h`;6`kldVUJs@W9P zI-^IIA3WDcqMD~0Cm!d*5G?CbShG++9yvcvvZ!R*v-@r&P1zcFX+`5rYftl9bP+i% zrS&GUM^c!r*Dd9HyquI*|~Em%xV9g0aj~H#`d{J^C}{FH#uZI!DXN z$ZqA|pMk1`geG=oiGPtIU=-S_n=mrHLuTBlbZlTdvJSF(ZH6N#KE+7ur!r)Z0 zsuEwjLOykGMyGy3yzt2t{XjyM*&0VM-z?9*!=H)N=xStcWJ=;$strLQJdlVPVF>wsV;DeD#80y#%e%^KzkpDp8YyeFT=zdT$V zEOdk;v?2(|yXV$lmn(cFNIye}^4VfX2?j)pyxGyI{ywp@NS9P^J~W#K&AZzKjZ)@$ zvzcdcT1g>k^|D^IybJ&&e4=YyR$(C$CO04b{UW^l`KL>`YVJA$szG(i=p?*)DMsPaHE)HSqhD{pe( zr_`7HtxM%oFJ&rQ-o6cXFJdqW(+(MdL*s2h$Y+gol^1T&PU(eMb}Nccw#=0!HMQsr zO%#uuq2f?IZ-z2>zb8$jYVO%qwKrn?c}{ca)Cz)KFnrWt8&KzoOYjibKl-e>GWuUU z&xx&FyS&K{GxqqiH_t$XBB0MB#tLk4$ddQr=(XY$7dY6Sf_Pux%yh(a7&@J`PCit{ zGglO!&`oYarNFCSz1Sl!Tmplhv1J9SU|7tH-3;stsC5DAKC{ z&bB(%@%<)UlF(zrm{AaZ1{|C&eDs(@Lh{L{qHuA=1SYp~d+MdW+aQ6T>6L~xzPFN% z)T34CL`5m_ez@7&bWz_T>WGnGH#WXCI_!Fr_cYsFXUObZIQdLtb)QaEU8?t=9NPF}Fbf z+F6OIsW?Uc#d$84NiQ;;T|{gFWMeArUla}^O$=@}dP0>LxvMzyL>@Q>{DN6{;Ry6I zU^q||y0R`wSFmPuHhg4AgOkMV)2S_8)nq(ZT5EYR)gsy zTWYTBg9>qxbsGHVpJEBmMZS7f*`U_FD17)MC?22(OB{yH{$!&yPx*3C;+H;sqs1O} z9(ZRuyW-tX36Jrun;_h8M7pauVG<8-`l zD4u35*W*_!R#1akuHWru_Pos99LmrVV+NRgT=n1Ls&_* z&9cxn3P?;$N&uU!aEQ!(%Jk=>FiAt7Wr%@9@D9^{V&NS7TJ0|tqp{DDKQzU+D#ds6}rtdOLR>%V%7u&qfT8f#{uV;Xkz#!({m@_+) z-OVbu5Orll&`r+QWXfK_ZL0H>r0M1og*d#(-tr_@=(-;xr;nlnbzqN!hKi^w3^a8q zujz>t1x*~BB<^x*Y4jtFSIDSl_LBIq&qP(ERP01`vfqm8p@N$NABm9;=onphejmkT zq~h^T0h#SV>vx*NNZS4d%!+jGgNV9gGp)}cmJY?ZowT=otTD}QhA{bZ-DxzhN_N_@eJ+A0O7`pL{Lu}ViPnX{3>f7CVck7{8TS+ zBi%nIGE*fSBZR`=I`ixO>sL=?Uu-F6O2zUk!UBhbw)A0VSfq=<&$SQmlJd)-Pyqnq zedZW*Y!TSq6h}Bc?79g;njkDJGTh;~I%wKm4$hXA?>Q~eygkpoy!DC{T0ho#eE33z z_o#bWB*qyBT7OeTXP6tj=qSaDg0HELGx{@~Z9hwjx)grUsodA!Ex1}$?gCf}ZmTgt zC%sBYqkTWq+52{3MFShM(}M0!QE;<-qCB)Y0`H~_!8dydV+Fg&*R{;j^=ws(lQ`!g zO|3w}8kBLUo@7dEk}IT(E&(nU`Hhd=Kuygl}za*k-AV$Ii{fWF0Qh_htq}tD!uax2EXcWHpyYxPKGp$&ioI_^> z=Gz#zfj#Nn44B(*Y`WxWm_j2ULd7~CX`i1u&)JNLU>VdlVJC;_=B_v077!<%WV*BZ z`Hvu;BRm3`vA~TS|A_QUl<;_t0D3x9E;ZNJ(Y>WZ)lauEbu*969x*x?dXiLN)6xvYe8BQvq zT1Z+ojMSMaYD4-nD67akh2yskc}DHSV)H-VuU*X=p=O*DOD-ISE~w5tXEcu3mz|K5d)}W&5jQF;f9{y;=u+$_wRcpPcbX|Zeh4zz*g^CY+=WDfL zj3q~OzJ=4q6;Kn~_m-NUhtEMUjV7XBQCb!%FjH4d1Y5m8u&x`}wW++9`QVAm7_w+%x?LSAOhE;D``C{aswYURu9_{V@@ zvy_m2#0d^s@s)|==m$HJbpj&iwv_pT?&rq1p79eIs=N7Qd`{;*)?+nz}AGpey~(%jvT74i?REV~_!K#Lm#u7hu338zg+ z8YSC{`KMeUX~_I4N*41S=kw5V5%n>0v|JrQ2i*1xDSbs?o$hL1BzDvX?ek<4pADft_eKC6-HNA1C8E`UOGL zUoI;((2g#l@m71{01Y&Dsu<=~E0LH^VnORR#seTc#*6)pVgKbO0y;ChWRy2j*t7ODDj|V?Ml_mc>4gYseyC+$T!u z_XY9Aq-fXh#KUJI)2RZOOhUb$%-3_Rajdg|4Yd{J>dhyURq8Ij4cYCtm>aK8mqP^^dWlnCd5xYK8#C0@~|`#SIHdY%et#@-qZf?Mp0B;gph60!4J0a1#%{CIpyWNi^lUuKVGnVAq#-w zC*S7{0U()UOrsI7dD2jhJng0f6s`QLFF7hqUEbutp#1fWOl47|j$?EUoIq?Wx&8jF zcUhV+Px@gWEO6kmI3opjT(L0Oggo{JsavTzoo>3>p?}G|nAWAOWyJz71Xa$La&qWI zC|O6baEc4b+y#)DXh1t%IQ^a^SWUu?4P_0a-$Uxnn4;*?;)JY|O}gin`ST@q$}Tiw z@JlUHD7!!}r(|o~O*kX7Bl^b2TXeK2CJB{mWIYY#O#0Xemd*uu1o)%*J+l6UL>&0T z@hAmZGLg-2*Z2FbLf2KPwUP7QuK{!K{>S z2Qe2DNPa!`3?yw*jh~(+ef*rmOf=feyw-mN_bK=tFz7330w*9epg4H`hgk2i&LRTN zk4m4kj;$X#a`u^|n5c?a44hlLaEe{(mm{#}H_2J%_Uo$Qu+TOul-q<85z!N`W{I)2 zeF5W~3+4r6>XDDt{jrqy2yt%3hWUqQmmK*n3>|ch079dxZ=M5)LKk8X+z<3xn6`?s zsYLVNp)CN}K8kqZxDwNz59c{eh&FHF`i9P`94{z7op}_kd(OODH>54z7L+sODBR_` zCCSr^s}Zb3sZ41`D_M$&-Ditgm(;pr(^vZ@9dU04XW2uzcUX`=i}Rj1DY1+F7LHPh zTa%W}j2{P0DbRjOL{Wu#f4EaN_GDpGh>hKM zC2!p`rS=oxY&xqvf9MuP<vsG81hKE*eHl&z|81h-B>O6fk`&Et@0J%mK|WGEr4W$O~c{vmqZ! z%O1y#w03-wceo4uKBwb4WXv>i01_DjsM``2Xy%oci532ZERDO#aiU4 zwB2HFt;#%-t(twNMikre8Qlv6Y{sx!%b|{H4L-x~Z39Uz@AYc+O-RkkPm*(_KkCK8 zf#(AKg`ZVR-p>R~XLdymq}hc4SXK(#?+ASo4o3+?b2V!c)zaZ;0-%Dy5TWM{ut-wg zqd5HJfYb8a_r38b>fA?|MN@q11NpMWo%b+29d(WB_k7=euf&+X@R^JqGya#FYahgP z720Yz!f}=Au_g;86lMNu-Y6uz))HMprQj`!ZyaOD%8`U^c_QPG@si3>RbW;SE1L%WJK7 z%K8~Od)V+&vC8~)#Ha;uf>%mTu8`H0+4fc1X zxbUQYl~Xh18TSeMVWrnMOZ3h%)5S4}f$_56(QIECEv80KX__HOu52qXKR{_rr~g=> z2O^|aa9rf}K(n$=58yen%H7Rz7%0W8tB~>_i3#gPVo!^ zRMP;QRk#h0z9>GP!gVW`{7F2D`4zvd>^vS)eYR_sJsi3Z3I31G+l?g3OsNrcSg*=p zT-Cwp6KZ;(0**5$Sev7m95CN}Lh0i)iwq>i)O&eKjA#hHbK%k>4bi=cn>WL0ufc3H zi%y8@T?jLi=a@Rk%~;n@rbO?2Li*1*dS5tjW?fBD_Jg-v@Q<>-G9X;Ls z!byko)>CR^d|Vj1wp|%qa4W?NV&$cWEHyB>9n*FFVaO=ee=A7IMepEpQnL#`Rv+-e z86`S9JLQMF!O`j?;*_HPQtS*ITy1iOEG+X}1KLvuqYFK%k^&-F%#5%yBG;tW-HS;j z)C`hOoQARkj0`LR|G-wF3Qy8$<#whQ7oXBbhK}P<6BvPl>7%LD+~SiYihZ^!!4&R7 zqArF^x-!$SId4+AYbYEhbAOtoQ}pSQfC3Z3Kz8vmT?0B(q#4D!;crS`&UlYEVb<=& z-fy7}4gAo3I`JO3SX+k3`OLvm=c3>%%6UeoD&d}|(gz4A|M}8)RpC-v7SPj>DL!62McHyx3qhGtUdB!F1e*@$AEc3f%HZtdA#xo5K&Blhj|S;CoGd`D3GXy zOlsAwca;Sb-1b&KIzmZYc^CXF`2{e=J&u(+nz-RYk`L0Y&5y1M2EmSZCmaAxtOgJm z#b95Utx0>BFn_w0O`F@-qo45DY3fBf%8#U1L$51tmN@72n!rmfF^UT;V6ojAVW!+k zM%?8=nY(H-t{W}(phO}3u3>7IYZReb1P`w8$z1WdQE;g0(Fpj)pGcIHxSd8TWPM3> zovHtgkjaHaiq(9#{ZCW{pUcIM2dAsDnjao))s`KfuYn;EbaM#T`9dZtGgn{s$X16b@em`RGkRkROihz9oYuEI@S`n zpOo=)FLSb+BR#WS%Wj742zA|x24eu>j~qCmIOo7&dbeuKG&zuEzh<%VDGXrBU{r}l zO}z$1T0}>e0V_HodAS~GfTD8hJa5xPLm-o?U)_K=Dny1I9r}Sm_Da<--?5xphYqI` zopPXgaaYQ6NKwZ1x7-P2}WZuTW zM6qPQweD(ItV+b>mw>PcDZIsrElMnTZNEyCJ%0HkpbpM(G}?T7<%^~6<%RB4AJU=) zq4WuP|CPLVNe!AsFl_lmMfTEA_k&h(?T$2mjVL-nZg}W0$7FI-;sIUm6!VF^&0(@~ zgz|DoNN4IA4 z-7U3lEv{vL`B}%jJ^;%L+^Sa%!?6y>8kqJoT9KAd=FrZ8} zLW?^Fg}xDzsSZkDKhcbH-I+sBTfR-wCObiHdkxT~KWk22-fxa6-Dm|j= zZIswrFM6Uhu&1muuD5_lV^NPdpbo!m+Q|Kw)iKM4+14Qb&?RK-vIwy35>N|zG=-P` z^&}S6c~!M{8ZztlD4T{oNt$RR?Qz@mQ*ll&ETCg=dce;qMfBp4?{r5=3sR}J#+P>V z$FQut+`K{-&KPPcEaPl^^f+Og8c&uw3C`uHkVi-%C0BO<=+8xkm=vl=E~@kIK$qEZ z8|LPQmBA&mm(MfRmC;$Awx05_5sE3VNx9w)z0?^`kvV6!P{|AVLaras^%$p(u!&Na z$DLtAwMZu+{3I4?o|?nJ7x*Ea_uNS_(C|1 zx|=hA zlZJwmjuDKCFT^M=K3(yUjpy$JOvyl=1(3?^89&mmeF@jO@^#-qwrIcO9_I>!7)=Bn zfzSise=fymn%E3Ce@=;~dnM)jq?I{S!^Y-%Ah8H`%SP3a$rCR=kvyN@orIXe8Nbs{ zTMa_QRi~^2_1|lvC{MibD=J&K{JG!nNtpDcV+~_Tl7=I#BKB#EoTktvcEvlQRr2ep zFf@IS@>LOYK()Tg(s=KPV#YV_79%seVW{s6*QH~09>t?LVv41qh({h@1dV^u+kv$( z)QY#Ps}8ss%#6){#i>j5c+>YsjToCRt*-;ZbVv=xB9z`nS`t6b-ap%9xdHVe|%Ks9c+INA?@- z()jM`rNktdJfK7NwRBqUJ+C0A{7GPf>5;{_ z+hNV8yo{P0&~C5ftK<}#z8X^=e_hdfM~+1Zp14$H_^ID` z1^htOGt|l7F?ck=pKyT3Y2bh6T!;N^`BR)N?aheF+yBCv6^0aP^~Mz8?|{7K>)1nV zmg=vtQECx&LZQsr>QE0hSBF1v37Wt4+xygY{3H&+8XG+jg(C`a-^v&VX51f$zW+`L zg0_A`R$`0N+-<^0t(U{XR_?9z&jC9ji#6b&auH#kh5hzonh7gxm=6~L6L9d=)w?p$ ztpJz50xY_5xhblD`OxdYCZHx|VEY3^sLc=@IJpS~sbK^y58ItQ1*!!Ea}+0gpuObY z`vA%1AfBqHg63lb-PQ9%9 z?fZC2&`>sFKtSs4TutI5APWN`7t;^Y1ll% z#hv%tqQztJkntMN=5b`?S3 zLI=FA?DUa8ZzC-P*Ssqxa0`a8q#z}S$BC!#`)9$^*^UE}NFvX*rQa{#U9++Y1Nq!r z;3xQ?@|o=5QtgEQEer^dAU?fUflGbm73hfH1-UZOWB43kN+j}BJHw;1Qaz7j_=*fhcS`lDq>ref0 zE017Z1VYTx)Q2Xne>^_;Hrs(B42>A6#GCr>aYl+w!?JG!(jy1x+rWmSkNF2Q`ad_# z;{;v~jO_8zfK;E!`>el;&^Sd!vCx0sdZHCR*a$bR^w7V<(LLIHN19yV{;+vE!>!E~ z^*Y9h`}^Ghc=L4<4Zxs+-NZn9CV63e!{l|(DURPS!CmAfTwTJ{DT(jDf0UrRwp}wLP)%jn@e(OP-x~_!O!nWuf%`K4Wme1a0(~#p z#G9iVRXK=nFNk1VWedGJV`x-?8HaUD; zrYDQxZ&B7=M2&dm)_=|-Ab#xw)V!k%7>o!DEeF=J<}_=>pDSoPz7Bvj7Bg+pr7$kQ z1Y$r-9Yezh4f`gfpxQm+?m4-=g0UfJ2O+Z2mh9$yQ8#9?-7~3B|{aqOLPe@ZT zMkI((3&8eibIKul%p-aSMY;OFzZtC4uM7|nDuyh3&;NeGlQcxK=y&&kpGf)6 z8)eJ<$0yM!;~<;_kb=hF-G=iSak9Rl%9Zd3!wV=Wq44Aw@qiRInW^ZY*uND4au literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/reeds_shepp_path/LSR.png b/docs/modules/path_planning/reeds_shepp_path/LSR.png new file mode 100644 index 0000000000000000000000000000000000000000..8acc0de69fbc973373de069d337275436c7a30cf GIT binary patch literal 257435 zcmbq*2Rzm7|943xk|dE4MJbAm2;sD-gfu9-kiAzNqtifUQB*P_BQtx`vKnUQF*33b zSqJAhJfClO=XBh^p8t5BUa#)^^mTl%>-y~R{#*|(s46kibI`9@vxf2PnNt_ntYOGs zvu1re-3EBV@?et&{BNzpMWqvK(rdX!;2)c8&s=j@v&P8_`MdUV=d-dkYk1e3J$3x@ zExqxsO}Ckq`+qIRCz&dppm{5|G-(5JpH z*N?^WrhgafmnqmapNV4FFGv?l=XbD6s-y9Ky`)vB1hKF?pI!TT-eQ*L=gHD^9o;gM z!pWW)`$+M*Xo1t*@TYe->h_woG_-VEdH=5;HfO!9jg&QPPQKF6-Cd@?x4F4l)UYz( zczP{<)$i5!(42mcBdJ(={MYY;rDBR{7#SHeZ&di1T3M+iZswFcXl`yETToC?tjw;o zYDdz7yq!^T8xt*mzZ8|e>Da>eyCW*HBIx$d_GylD+y1)sw`&+AjvT3&{_(jnqtX3qE|QQF(5uOiP{Mqw43j8N!(5|aeqN^_}PEQO5_c1->tug zE#;=LjK~#EzQe0Gc6SDm>A99|*w;69ZKo6L_eiS_%gj(+aFeR+p|tO1#0me?{yQq>TJ@us zuf6qH!&Iq3*%I{!b|Xw)Uf$I_%WDWbXGfail9SCJ3T4TyBArp_ZCkWtq_-A%Kd!t# zmkfw|!*#Z)DUfD8d+~Ptl@(Iuiz;j9j~%r+^tZDiQV9gjbYGlqD@D5uJw6+{@AR}y z<*wD@{E&_=AI(Hwhn8?YCdB}qbxX4sKQOtzlNiu_f_nQD*{n9l@VAwjHzy~hq{zn9 zHpD4aJw9+LHp!INYlE4F!-1ebyu<9;BZivCRuO`Hu%f*`LCPvSaxIFvWZf5jCcS<=(jv2gnX(`FfbwLZ%O9Fw z93`)Pn3twi4{f#deWSve`J%z+7JVVg!tFLaC+}lJF~kj>B1OZo3&AT3!E0Y*_x<&h zyoYURYRXw{I&#d)8GW{Jb2tosc@Pp3f)VRvnVOi(x55hGz$znaDf;huLkKsDdsc`CGj8 zlRy)as^z*>YyE3)lm(QPiz2^+>US~kna?cC-CA0hQrFSZIjS=Dc-5B(=TQZvb^8yU zBL9l*;kCWalN-qUTlM8>eFI!a?i3=TZ?1p1G5F<~x|Y`S6_qi{=6}6~a2ejICVfbe z{LcC(w{45(@2q+koa5m$l+vl~#*!7LaFET(Zxd7^_AKUqFP8`Asb9LpQj_s7C9c;6 z22PyYN%1xHhVWol)3Y<=l_*?+513T8wlWWNs$MDKwoGUQHk7k7G@?^(6)90MvOvo& zbun-9=3+GAL1~}(->vdBp*IdgwO0%6jU65N6&!A?Bqk;8zxnk!>jxjEx()&><;cG_ z(!Lj%tvmFRgUl#BdQjaTndW}v)u{H3p4p&5@(c#;g5>))v;}ls7Lh!4M zIxh>H`Fu_QMYo0@ffWsIJHLne@MQj>TIh3faz2LaRo=6hn_|-U@qwu4(n4yQ{`FOK zco+$%Zg&+oy%#7<~-TmWgPfBVENCjb|G8!kWZ%Ap!>*H zx#IRw)}j8eHAOQc2#3vgIUs7;_67{0kA_wX}iGF$2q zi(xIglcF8eB*p}+mtX2-s$!Jtd{~PnVtaP!FHeVy>%|qbNLsdS)y}gVvA=cg+O;pw z#0AbND;F2Pu%lj<7xjG&sG7)n3aiRNjpt=E8L78VUU2^f42C|xwWX!9$Z4$TvMLQO z+oUe&6%!v{4%9D$KaFBRY%d_|Y$UI<`pZfNyzg;NPEMKjKRyX_?iUsg zdj9-5yQJmS6$#TTG}8NjJ_>f{m$dGDs^Pi3I8>FQH@?3v6XS z@7uK-ho3%s_H6zj=O1G6@_-|p>D@j@K1H=X(DR@I?~hd;?e~TrX48s|LNoNH455J{(=8e_N(BqCK zd`pbY%oI)g7KmHtZjeWox2@HJuw1IlmI|`lo<^2asJo)s&R@^We7gPeLrO&RX9F9~ z#FW3sK^$iGrnIoI@Uv=VFb@xlfGSsvu+>T4d|I(h`5C&!lJbi+YV>(SEzBulWJbmC zK!8SMZf&Hz480yg3AU;^Z}JXSiA;#>OVt_;c9llP6DxR|Ik#5d`zvQvCkw zzK2ybU5xn(bKfq(PRh#Un{5rzyUMp~QO-A<2MU${dNYN-!>?~gV9|mmyZ$OdTMoUk zDIi5ox|?*`e?EjnnLR7Z^Zn&3#PX(xgqAezxU4KONEG@?W@`P7I(?b>wiNw*e#GJi zHqT1eGwMsk5sNUx-Kg(dX}UJ$+qAveZCx@|iNtb6AqK^oe@x|DJrH9X8uA`c|BbqM ze85ejdx(9>Dd~O;!Uen&rSsi){rG!l^;Zb3cHh*MoTL+gyI~^wyMQS~4?R7-U5HLW z+(XmcB8i#U#3kHW1_7uzC|c}f`O30H+j1;h>Hb>jp%?73&X#Tr#7LL!o#iB)jqKi9g_Wg+ z8Z}S*3(p1z2PM9DfBW`0Xs4Lb8N`T?nor(-`*QsjR_mS|vrC<}9~d*i896e)bGBh2 zQ)LZ?gd_^g6j31wgAtzmDEYU5BnGt}&zP?kbxb;h^JV!$g-B(5xSreX>Sj%SZl0Be zs-|)gVPVy(ARdL~7<gfvpmteZG;Atq?(pwmA=_YPa|!oJp}A&;PKM zrj9AUd^TPrP|dxMCDRIVEG#{wHM^CK&QXgB@NhZ1N zI2>+7U!doq{Zs|p(0P4&N}$4fcq@=#-AhX*ay*1V0@nqGn7`H@2r6(maI4Gsh3W8e z_v%tGg1G$$&&OQ)zSxWZ^y$;BG3_1>ffu$XmI$roLE1K@xenuFdh{$`wL-LO z)pd#Y5*8Hn^CGo+1%|50OQ)bOa{VDQ2Fd&Pn-R&cq`wO8_%@UN*x#0$O+o43$3{d% zKnj$qZ;^WxbAlNx1;y2pv?hm#f2H`#OG65YUJ6Fl4-2M02|*=i=lv6})X37bmS!WQ zOY`>RMd@aX;T+{GSh6Zov33oHhIKf_7VY8T!SROGR-~ToEY?HNw!jvhb?wrnOFCYp zxlB(I!Ev(pgHIKb|06osq;>F5Z2KRQQ+*sfBG)mAy)1t*GY?s4JXo!5EG+!Nw7wX= z_J}r1H%7J>|H=onr2^4(NUoK&Ilva`pmDio^RtF_56zO zAWl0@lq@{nAWS>&>{R{h5v}QGuN0I(RM>&Wi#PAcPe>oQD$O;q{=7UqNY?@W%4F&SmAx3kdF}!R$ zH+RkH5M~j#2LHaS&%*w(d!)qY2f4mbRH0f02-bN_>I!)sdkEU(5`&a8|0X2^4}qCm zxWg_woa0^Wk=*4v@aWb;uTN9P>r081pY`xrN2flr#3dvQJ}fojuvXhqjLXCJ2`DU{ z9V%kjanQH5e0fgVIN|CaVe!}vPJzv@g>tN;uRulE?vYhw6-h~a@MVQ`jYB#Z5wFG1 zQxzhfqPx)JnRoYaIeZbdnQFBxP*b!UAf@y`6 z7-3y>0GxePx~7f}m!^*0>5}j3VIQt(e=J3tK4kWs$H}MvFEe|3B*{fF=^?5E#k?vg z?6nsTD(g*$JUwc6Ubt&oRjxOdCf{DD#iN1 zhb+CAxHvv@3yXeVz93&vxzr3z4DE(X-!1fsS|vCu8)ap7DQlgQr5_@}%zTPmd9Uzz z{K5|rubrHdmS=37%RzYdY^p$$7X!8oN5Tdsm%dO6G{fHTK3^N1EJW!=eMcWmZ7e}2Aznw_29`Dl5$ zOAq;dTGXF4-IDU#17Dwfu>ejvbNj?r@fJ`L-OC+g8Y2@ z3zYpyA{5UJ=O?;!@$!)ABf|Ku(DdosUfSh}$z|av_vxCWivyvC6P<-VoStoU`Ihb5 zTsrNPWUSk>j72S4Qa{v+QVt9oScim@td!OMn{ZMC@+NG)&14o4N*5J5W=-^$6|uBi zgde(#S3}_6xHiKBXCdp=qn$lai61Dhy3fFtkpGTa)~a>D5ITs9Q^ZdU30t;)`AM@4 zu?94wnkkgcP(FAZcmsiYTZyYfxUzH9YB#5r*RsLHqc#_e1}C z29fdX1W(eKeih^(eF+iPe)HukB#*rG`;;Z=wugXx?~csVBMZV^&^Y-sKl3OCoMJh7 zQM@+mLE8+wikx)uQjWv*PsL4CA3uIPV70=*SI>#zS^nuWRn%H4yiYBPYi984*w>51 zuO8!>Reix;ONKgbBk@zwD~r+pKN}EPKRP;k*&a#MA`yYhx76+PZ%~c&0lt)?dlF^adp` zy|$gWbHAmc+8HUAe8TT(rj+4Oyq{?~I5=*A1VOXO6J=acQGpcjK6o>J&PslAlDC+4 z+0B6nmGi#YCbh}zzFl5RQ@4g+`gC@7o5b!Q*POQQKLu-_IOat0z8fHR^0@uZ>d#7l zL=&Y)FCisW1(mH>C?|hjhAI>@)Qnu)ixcQ(6=RH>5=^zS_dRb(SMegvd|;}QRv?*y zS*}>mrc)mgKOcdHXudM}O3MGQ2-u%_TPIQT^20?z%yH&3G&tpO;lPB11mSr#>zG~Q zH^0PuyLpMGowq*AX{>t<@%fR45>JnuV2pl@7Q*apMif?hQ)1eL*dgRcbvUf~97y$;{$2oH3&Q1%2JC4fVOYI2A;_S*- z-`%|n{E)x5x3@4FiLzla0~owu8@1Dj|1nPsu$`aZS7zs*%Lpo!|zYJybN^ zf_kCHdsAi_SIC2-hBl_k{mo}WssZY&uC0yzK>(rkhZ2~ck3BK%76VK51%tVjO!Rt5n{F;nDeH0j@T{z?Usfe7 z4DY}iR;PoK*yoU4Djr4Zp1;w=C^hToRypITslye%Jfb#I;yN=}F;EjKuE+Q6XP}Kc zU!==eT7G2(n|^295$Y9~ZE2KbdFIXImXd(s4;oFXmyb3KMsqir!`-wWJop&&j z$h7j4X$rEtyq>YVwG_FUu!zUilim|m#-xv8PuD^J0kVX9IqkA2}C9{pSJCP6& zDOim}huUzsLS)9yvhTbv1PSXjy0T5wEW3)1Ac6LovQ2wk5!(XAkLnnjlVpzozUSyu zpkL<3!38oFz~wHP<^N@*Fz^xuMLCYAP)QyKVE7T|NY3|HWF^LcREv?C)J06K$L@n1HzvWeF4=M?EO{2 zbrIbXC%zldaHf|^I(Is2N7DozBaXArPq#5gPxy2@~HmLQ2f3=?+M}CE=^sh zD=$3o?LOQVWO^Ws>Ou-0WltVa){}#+P40eSMtMN}!S{@fbw*kmtL41p_IoH|lw77^ z@B3Q>L!Pm0&tSsajW=c^y1(J(La^9y5&iDPC+>G^)RnkdtGHcszPykYhn~!nad8L9tb5G z$@x?LX8j6iGRekr<8R}FdWRG?mW0;)v3t~%prvy>aKWWj*DS`P)nk6{b$zvFxlEAT z3Nh|gQIT3}E<2fhC~JDig4M0V^lYy%`%s|r5!qV z?wozx)hpYE`7mKB5i&MrHhSe{!5Sp27>oS$qoaLy7zpmV42YXYy`=a3xMQ?tEMg7j z9W#_KxLk_K?w=m%CIkm#%Oht+lYWqW3WbQ!xC{Da8NhyuT6N?kB`0&d*fW04V9k1G zg#`mQWnvK4W-?s&bD~=CgH~NOR)-<{XTlDuI4WiZVN6fkmf!Eh+yOZeS zqTeyZ_BJRLA2Ip1p6%m3Calq}jR<@lPw)rD;eZbf1bJgyt{zJanM>$|>dC-59kbA8PXPb)s|kH@(IRDQAf^ zZ8o7=*~!~`m7q>x_w9*?**-T{+c<14`4wGLlpZ~4V)zTm>FJ#5mlVct#N#Z@ch6d@Vxy_BT z%e&tKbL6nbIp_3ldj5Aab3Dto9c~qNRTZ-~9x0let%{wUx*NL-jLs@r>^+W8Zcz+%`S&p+Q*!^kW`C+`yIx-D_@c%nF!{*y4DEM8zeEF1}-PD@# zoBk)ZBSpae{@}#?oXG-Qo@qwLq@=N(u`$QZj3_A)#TRbo`9pGE-v=Q>n&MeN1rJ3~ zwb?;7Kp-onUxy%S3WtB#1QH_c;qJEzP(=}G4A+ifs{*-A*^^fb4m(4CXy<{)AcNhF zdh&*fiVlo_;x|-`Ef@rb`Ee(5Wse;o3HY^fdCZizt^Uxa79-G$A54tuKr0j9-*3or zbx@4Gk{BJ;{VmEJ^v*=0bydq5kU$$L>>}ubed~E(MODD~eIl@nVVfi*BtF)^JQ?@u z75`_!OR6t78Ev!faq96fiz%H*FBZEY7;!XnCJcXF;KjoRox4=r;eCTdSM&d~=*s93 z3M#J$uVwK=)N-RG^%{b!INf|8zMggqo3#x#GY-~}`y6ia@zUbF7f*9tSEHWH&GW12 zb{mC27rGh9TJc|Y7#{AWIdteyrsGJXskODL5W(WDTwz7mNx;@YXK~WhD$oRi>^4HY z$Z52pVZO4^>tw&=AsQT?s&qVd=1*r3aUL$98pUx&o5@T;WxxY;g~^{P2KgsISm`~G zj6`j~az?XlSGBeV=+I3BN2nxo;DwlMN5>7Kniq%cWSJ~JRg2Zi$w^(t&GB*FQ|355 zVn>q9+&ACY*tVr-b*FG%D=zfn6MjN{)%j&}F=td#G^_BCMJKKF^TZ*kAGT23@AKz4 zqi;z`Pi3VPq1vThYH)n}lgC^;WS$j6DA7hL?!l$m5b?vNW)J#4ePS28e&TYJ?TG-H zm8Ja|uce2zHZtT3NaZQaEzc{FJ}~j*1sS0#GOL`uJA70lJJO_Ap|W@{fry^32%rdm zHDs=GhGHxfIivbeeH_Cor125pnZ>E@1J#d2JqWX0dY31l!N$FRtwTsey;PU&NlW5XFkc6jX_Kb&Y=h|HrD(tD zYuQ_5(m^tB^gFelMthK6GQCXNUs*DuBD(A`seE^#&dZI}T13!qba95y?u@mC2!|NI zmp)x2+36vg%nD+3&2FrP_&3lNZb%^a+jolaqWCuA~5$J-4M{^G?sTnTUpQIin9woTT$TrPyODO8}) z!-D{sO}%j0$o2V2FCGh#;#6^d1;UTuS&V_1s3* zzL(pSAFdMhVnS2SM$Zjf;zQAQ_^=Mj{qh$Y@#M&H`x`j>TAs2NYSsR2E4JVM?dR&# zqjsP4{s?w{&th|^91Yg<=iOTb!dTNCKR^HeVKpzAWK~(KavCfr$BnMy9_~5llEud< zDUCVwlpO8_z@9IINT)JzUJC+ zI@4sNaduJ&x=sn6y$tG?HJslTn3T_#&gLx)91s=>eqKD`7m}Pzsx;na&9j^p4$ehS z#{4p#>*+Zv?(JvCtfk9$;a^EK;JJ&hdhVeU`zN%M0rOkB`EQsJsTzSMLNFxhPXROH*si?IR)2X^Q^~^0YG`QVJuDV$*e*SE z>T`n1$kR+4FLZ#4wXQ;SQ;xG$s{2=q*tk+TZaWA@IG%{OsSgbs)g^Y%mzj2z$uWLV zD_SNb9UFO-t~oaB`(x+@%hx&&hl&9;PqE~|x*nVH-uF1rf2HP~CarY z7+xOmq06mouu(Z~naS%+B7go{0So-B>uBj@U}QPrij2n+2)tqUbQmd2#PEoCH}naF8lW4rOYOp5AuQ^(O3?IqG-kxm*zL(tn+mmFhD%%B1MROd(@KB6b!Yc$DH>*pI5wE(l8h05#x`lLZAr4Rbc zAwgpR8=WjyXepbCM9-^OTYC*Wnr$6$#mn|QP>Eg|=ng)oY&dPAzzJc|kC-FYfXish zG*u@Q+7hn^H~zow8S{Qe+nehrE!(r=mG1$;O}=_ zlXtlJWucdeN&DxtW~t!w)(o{OIfc%$sh;ISc`HjpBPPvIlvDERWAV|ofx5^?@01MH zswbDPRJ=e>;$CDELX?rDxJe<{?W@I&zH$g*1#QF^OFCAPW&%Z!1+_r z^Tkcczx7bTXk!}S!Dj=+WvY%Tbn2nU(lQsDqE!_{qK^pO1X#NdYdZn3Ni8dc49CtH zn_zwW(bo+cn&F<3i=oj0$%`{hJ^8rq$YqcAj}IcpTmbIcxHuDsD~#UH+v$1LZI$x= z8-O@{9E6ESRh^0Iq-4dWzhqDq#GMJ~f8huKLXm-y*ZT%cTWc7{YgER)JZ>(Jn}|A& ze!J_Ojq_0mNL0XQ*49PySlcW>A9F6Er(}L6HukB@x_3K;Ox2VO?EI}AIIfie ze|;_-U?`&#p>ig=v{&S;R}W!48`Olkf>>fBYh8RuQU`4{qyz8@j{{FA1{1tgBBU4L z|FiUB_AZk9A!R+#?k!hK0kfQ-7QG9)C8Rgmdx_cx?d>K?h+~#C1SN0ENRI+!?~MxA zq0`Vch~!aF=!|lIv(%gs1Uc5ZDz3$r{K^8M^rNN>fok$QQ@R%_q2a#t(?=ZyawvK} z&FVcMxR^6Mtimn!UY~!$rpFGko|C8i;8&ZVDZu1;_K)ol2|_Yqf(sPv*qX}c(v}Bv z<*C)z?I3^-3}yawVvC?6(ye=-pDcaU{HorEsjRHLnt9_iV4b-xv;b4o@T0{B4h03M#NY6_8_-B$`cs@~tv z?B(M*s~{qH;6Y6^;c~!HT+TW{b8w0+I&NkrTgygsnr?vB7xxq}YU;Ae?l^RACEdL; z;3*iq(+v-I69dhl@f77&hmMWUlT?gyP_-n!V`{8ZD(Pbt{V@~WW0Pu&-XP-rlIjSX zixBW24~B+(yhUVAV8tZ$B$eT#{7kUEvyVK}GVy=|&f zZSxsxCxyQE3{AH^K8x3#BHd-GtVK^e2+GSlO7P~4P0Epog4*UhUj5=WL+}@+o8&i* zG3}HRhAhADNee%P?U)j%J=R6UeWUyRh!+i^X!gA2<-awO-uAB7($;R`?Bs;bEEDdJZ11V=a1~t|o6wQ|>6OG$~Xp%$F-fxy=_daYAlu6Z{ppYDw&#-?K=1 z8TARUm_f@Q1!5h)JaxP(RtCzkXVK5sq>Rwq1_iQ>y0NCv)3t5BB09>mBH95clSK$) z$MUR*foj&aYS#8_)^!9;bqp0Z#{n@j;Y5ikhg~3I@D!lxa!`&8Q!5ASqiDmWY=Sni z?3s>69OZG_|2*1Lro#p22MO+eZaEp<47Yc8*q8g* zCVOsf^A-{Ao}5H#F_}1GPq25@F6DI#d-)V!0cHX-r#=)Ny}X>EX5X}wz-jGUDG+`B z?(~nQ#HxE<#Qgoyq9+SHc=h+Af9H+Q7+@U2bKi{FO~@b1A%9#%=gE)(#YTbPIa;{x zpCAh`6{*11#%!cX>7GqEW9_CERTI5<{&MN`laWbIz|tob6DQbR+KttZSzcw*ki1Xr zVQBFP;7y)vtL@JtftGN|&-b^MrmB!~4Fp{w>Kh?~v74?DaIvU$g6gx)tq+_dk0J7)f+d1^}w| z`BhZ}ax(I;pQa{$PfdBg8@-Z26)wLDQK!MVu_gn;y_5`j(;2c~Ah?bUH;5A1%6<0> z`hj2{%J1Bk+p~1jF(+TC#+O-iy3?UayGv-W)+rR-TcRpMU3OP%k#X%b(sW4ey( zbdBgzg-B4Ns9|jB%iSCR*=&P;n4*%lwoHP1OX^d6n$77chw%3j^7yOA<}ggB5cg_v zS>)>0D>H-f`lmfPQ2No&=cov{A4Wv*G)IjN{cguB?*93KXZdh?;ox(mA*|yu*K7wc z+xh*SoI#(*e6iEzra6`Zz%Fot&;&IqFa+ zH^2D|)2gAiKMVym72Aq9cgV`KKku}*ty?3;pk}FP)<&nL7iY&rSa}S<#!6}Sji&1 zMaUKq-c`CTU92`}EVl11&ys;#znj_z99fqU2wSC({OrquxfbnyH7~-Y@wQAp=pOei zfSvXtBzpNl+jj1alamV=KbQCbvN0qtfiT%1h8Fs{Jlgrzat6f%iF&orxCBJwhUD$U z&E7B#b&9F3z^XOfwEfNQPeWgJ27JO%*DEk3fDNk~>u>%IK7PnVb2bTTTLMz+yPUCB z>Uw(JDYirt`I%?GAgL#Pwy4Q?OY-CtjHO@H~KnIwKzev?8rG#>MHL#Q9N08 z#xpfzRXvPCrn`rJji$o%Q7qpk8KqND6ZsM)C+p|$zp+??IPU}79f#8X=tP<9Ckyi% zr@YK_X4JSn6BZEj#eS1uh2a>PRJ8NykzBa$N-5UOuH=?x6p4JwLy*{$}n_Op_`Z z3-C*c-`<8U2@_qm3R$J)SPBSG=mgNSy3VcM`%{_09;ptGy6<5DjMRvho9Hb_D~LJu~$sCYtVwgZ4!NJ(Ag>DG!LKSYg|7LdXkyK~)=#e4*sX?i7>7ZlN)mL*&)d5lEq|p%pBHrQg9ka3Tkd3Rd z%^tpz{wft`Y`{FUD+Mua$2#RuW%o zR}&I&Gx*lx=Q#7_rP+P+5W@rva;&z|9tbvBDoEoW3)HpER>VC2>1ID)NCyyzr6Gwh zH+5gcefMBpba}M0mk$E9N1%@*Q9O&)N_~C)A`{Jp{Fr%Uyj}NXL8<2BeSd4{fg50> zVMLT18f9&ELy-+-XqWuJ5Ke3g+dHVw93Lwp+VnvVhNdrI%^v6WQ^5EU|ihr-jU$I}&Cn0v zQFhMghE4|=kiQ+6}Y-$U9{%9`~TP8l-yQw zFJt5jg19l16WZkLt79~BG5`ngu_`l_1a}cDT-wUu$etX?|Aq>p&BUtRpAL05@6H_qVC!n|R zp3NCxKTt_Rch5x4*1_;u;5=ZO?K zzEGh0zXI;lH|uyCFoU34Uw!7gZ7&{~PMQjW z7Le`?3a8%{Fqs;-3*ecv8uLE8-1g^LcX6DJ@qqFDDVQsf5H1`DnXQ_^ zH}iFNYlgI}3cP-6I$*VskQ?dj+Sn)0qB?TB*mmZXiQ{en~KNLtvAW?MeT%8@7Ajjy|flb?9KH-qxzrv%jqy zb+C4KUpFwi>mt91hQ0D%SN5G*@$-_{mS25|%W7*d)V-z12NOJCw$XKoCC zd%g4P5ppQ-51q5Lp*B}sr{wh8(qKxE)XLxR8!fd_qt|)sGW>gpEbA(g1(s%d!03gp zhP2b@H+DHU#~m&guEys=4l*Bxukhz9%#;fi*p#jL4_^cieKks^hMPbF%Llew+Wx{P zvWFVT0-Y9)j_O$D9RJBVj51b@tv^CQgmFPKf@seDF`q^uYiYBq;x38YOze$`PMU2^f~yV#lfvUVmM_vob49^AY2(m#WTNU^@H1V2|wl@x2 zJT6t3CRdo-C4P$r2fT;&c2e<7Z4v~&0ranzh~>e+;l>N-n(9Xgkx^yz?l4yugq|oA zu$pW$3=U*+|GsXqBe{(7_J0qpVg5bUM)@Y}gA2pRDfuz%kam$}L2|Mn0+xj6@cz1x z(~%R`iX@ynJ<%NIHtj{Z*e6dm^F(dvNExgP?iF!8n?JPkOw0w)SB4+2=E$M#eoF|( z-^+V-k#%LmDP;ENsns9+GbP)LF`%VD?`0|D{e5?)s>2jR52L$cPiM}wme(e|@`DmO zAvHVJyt`z7gv0?v6ZiAOIwxeTO3C6*4^602+d91=3hfbRbl9BpFSM^lV~U{C2KPXO zdxSlCQh}7{b8;jmxwGQmg(XIJ0}!RJBGaTfIp9+=q)BJWLN1^Sj1~A~?=t+G!zW-B zksOv*k>7G)uoVchacx)F?`=?v$Mgj%)Y(QyO$rd#C(=Y;x!7yIcs2~r?a!v9`{1bBd6O48<$$ahJL5AF6@ZJif192yOU?vtpTmaq*3K73l8&iq|leA=$fjI%% zEOPHs3m^I551}HladC~M8il`<54=^sihTy?nd8=U(efT{0bJ5zRmESrr#Yi%0BBmkk&PfHq_VG8?#+XIR5}5 zoB>;(c5OnC?1XQT>|_Aa(*SG#C6W_KJDUN2jT9zK(*a1w1>LGHEZG_H{%>ebe-#;4 zwl7+NXjY=LyQRe$#RIdL{&2(54@a+d4fh#u#>{>^w&?=8X|%aZB%|P{qA=7FYFf<_ zoxGv|XzK_Tv=n=J!{B|?#LCL`={|Oee|E9~+8!QT>#ZnCCxIw~tR0E03{?6(tc`(L z^s8m=u5g!=lkhQ!zMcXHGNjx{L%aO->U|@%&jEvkaO3fc??Z+5ZS4(trQ*^$VraQY{A$I%UOK$y#r(3dVmZ=sb{+ zI%WPP5m~Cdg@qn)wOJ+%<|n151^`}vzu+h-ZT3DFprr~OCJ*6296rPa-*g;=-kh;b zk_RY$dQ$Z-mdqk|-k4b5{H52J35JE&%w73nA*hv2P`HRrdqR=^C-|rSzJatPxZ;##P|qWG_C!X$%1jYZd2VhcqRO zsv*aKM2A_#%k>|H`VUfN!IY33y7t6gvhgfIs&Lr2W^xto7vtzv5s9Wxw_pS|8yL`n zDT#gc%E&+xYZC6xm_J!G-~G#RX_p+8>F6lJ$vAf8fJFnalHssul_NR|s_e7nNDjk^ zrL?{bej;{bW%FgSVXH=iER`tSVEmgfKlz1l*DaE$4C3YleEVdx)-%=GL|gP29;Xh$ zEx77l5w9BG8vs$QtOidF*&A}^;vkU`+?(@iCKyuar^j6FgIh*xUb)ldi)a@d?tpG{$F5tvH->7h#UJl- zH44yq!`ij5)$Av@MVmFdtYBf%#FrE}3 z9y{yH_fJlFR{&sAxA4vs*e3f?pgATxkBl;iL8f{c@WV%_a5&^B@%uxXv6eJ{V7_ow z0Jp4UkUU}7lkH2cE%6eQJiCx}=@D=F=`#WD6M4i5UIaG{N@SMgv7oHq5qY2z;xl6) z!8K>zPn7U?mV|CUJ32U^UKcnJw(LFM$VZ=k$s3d8PweSNbj(1##RZ>>H8+tZO1{d4KzEW|XW0_KAh+hT-_ z^fHr?*JMilqcrCXkhx|^eIJ!G zC{=lH6U!D^sZG%W$0t8@h4frO9eXx&hpps0r2V@Wlz2R5-#E=Wz7?(FVo~C<`?xzX zzRz2ezLTj;Uz30GHJFr$XtB}x# zQ*Xef3Om0dcV57qAA)hxRM{H4DI(rG^2t+4F>4U<{#l>9x*YXO<9JVE2m}JaYJ*?~ z*7#_)%ZKc}o!vzyYD>N1(GM#1NrIJDUC-4osWI~Gf?~8`1-OZ-H`hlxTT2FyWE#A? zGdq9w?XgYf0{Um4$`uA4TRgJpFzq;mpFzqSEyANRFiN%Mng!g0vNWRR^(iU({021` zZ&nQAa;-jqK)nV?9rI_)FgNhy?LIH^!9^mzJO2}MjSPpg+MNlw1ad@knm8~iM@u*d zXGg2GKsk!j5THJC&&;<_oB?L-zXITYN63_K!iOwfgEt>=7G6Z`)x|WMiZ@C;fyqPf z2fIWq06C!o_Y^R%jCobG?s7lOm?Cg|n*V%POUn)b=Lh+VlpSS!Bj6?f%>gdu;l_u} ze~pl;stn|0x;hAj1O?06#9p5j1+)vzuG1bXc1scdYosx@J-d6iA4f4?KINy>5S!Dy zWBuud9j8l}5B05&<)Wt%Z1Kz8b0JqykiMGdfkb3H0nH91dEk(AAjUaWP|@E&Lp(<+oXaG++SNXw)2V6}c;j7Em4nwm?I zo~mk)X@#5Ga}9R|*>OF*OIn!P$(SOVd)O4A%4s^@+iPfk{pa0&aE9zAf%1IhC&%}} zlj?l|6MM){{(PH`cdH`JGJSpqdhSXMY4(y?iG^lvPPRpB*d^VfGfh3q8hbb;B~D-` zOJ;&ByGz>Jg1oVx?=eXH>fOVcgkxdqtABQSe zzQDjRe9Ww%`$^<|l}x&S&h&e~TQ98$JE z@N;1mc4=Q5!FJTH@80zUeXTCNa`Tqdk*q$L97FTV%3|}nokki@e|zNpn@7LT^HX8% zdmI=ARz{qu$VH;fOF>srba4@#IFWnbQRxP3XxQuWm2>(VIqR zEbTIl?-(92uWrEO;zuUEL>3Pmh}~_K9TpKGWK%k)v6wGWkd_AVyO?F$;c#NpVRx`l zk-~}Ze!?XQ><;X{GsE@|tqTRn}6;p9fSy?$Z=`bS|C$O}1`B=rz-pv1E&98sbnPTp4 zWct)yiVl=Ff2x^sx2m#o!{ulkeSWmG-HDd3Pj{P?Eu7%EoK2W7lX2pYb+M5i%ER)< zI$M1hdy848n&MlYxR$W8l-Q{yRA2$c2ibVlNEy~Ib7+pIEn7=!eKsV9!o^zVdNhUN zT8pIz$MtsH5+TlyG$kH#l9QIc23L>vJ64#b+)IO zuSfO6-HmWL8DF*Dj+;#3pT?GDDkZ+BUw27cO7|KqpBo$Zo7B2e4n0-X;#>HyyG=x% zhJ{srrCWZkgZHQA(tirtR_h`5RhuVk5pM}CT%f_v$M?apo})k>8XJ2B1qFF8l(1T_ z;D3bwSP0qMXxo}@9%!L&naVX*f4sJMM)iSB!~5Q%`}gl>xz5~dnzXp8D>NXYQ&3Nr zJ67Hgk%95X&Fs9$El#-|{f0p_VA%#}0%aVwYxF$keC1f$-y)t0Oo03H6aM=JclbM-OS|`EGFiswI@B zs+Xa6B;UNJFX|qaX?ZEzGD=)2wk7?EOjWS_t|B^hX=-ZCjHU3l41jK8pM3ITt1 zv^O?hTwEqjo?iKuP<8gkjaYS@-0t1S_w3n2WAkQqwTvxftm$>$vYt%*HEXf!L2*>S zZ27lM`$uu;Fj=F0gv4tWoduZ^W{v#31g(}$F7I&)!dH3Qc|7=?#Kc~C-`!f?&g)=k zxL5Ybl|62AAqCDj!Gj@DQ4?7q`9cNIuQ!`uO1kBB}5dB0|Zdd4f=%js`Uw465 zKtO4FW+u>lk|1#}BxKub{qnLL+l#&WKE0zgn>cJm7>W^9{a!t?joMJ(%U;uqw~g|s z3?j?i!WjSz2FJ8BQh$wN%AZc&dt+y?Oo5Xqna=`7P!(vKiSaGP}vjh zfxq@zJ3n0sd((J@!PLn!vMDQhDah?r>%jbEkIm~3TATE2Zl6(A#V-ufE6W@D zV<9~6uUyYTy-#1zjs1TF>5VR&1^01$wT~hHyqx}VSlA~Ri$3)s|E5aHsl@pBv)}^t zi6gbO`Ox~ViE`BvnHh`8CsyREvq`fzf-X1-aj7h};_ z_^t?vNd_Ymlh4raIi#=Tl%hp5_&W=IQU%n)$Vqv2cx+<@pD|M=pU@o zfVyb3ou4qr5l|=YYtSxRGhqhvLWcb>5pgPCZFJ9Zt;tTRvo|EW64#qCo9d<N^R-lO+>(Yyk(uouky8} zUYY)!Y!eNYZ87_SGv#v+xQTka3JUr`+_E>1sq}*9j#bmN%^wM5H)ieHRHUh|?zKy# zcwDSOK*+SI)n@}E2YUj+h19qxV?W?K^&~WukBG;Khgks@`%AQfK1_68A#rDKpd4on z&2d5C%o%|oYYJ!H@xzm+Z-j5Vld%9d{mUqvq&~NSF6!=6S(gb3-Q9wMpOV`2G~_x7 z8Xo0FEz>_jvdy1-Tb@!n(4MCvF<>3f?f2l(x-@O&@%Zp_I$F<}`)s}?J!00H(?riT zYZ}8YDQf)+4a*w1AIx~H zmlo*i+6y<2S3~0=AZ;{o{i8>Z6btaL6Qic5quO-d(BHb)TndeC#b&$bN7k0UQ_>I3 znHyNK;o+icQ7y^^aCr5L9=e1E&vtnJOqA9L5X{&8Cv16JP7U8&+q;TTSAs=FmHF%+oo=iROY&Tv~`V%y?vJ2hAD79pW*(Y zK;EQl#Y@wle*oS?{QXdeSopz5+%tn`8|xI5Ph5ZbLq5vaFXaC)_TGV5zF+)!L`ezn zmJu0=$Vf@Zh)`r@Z?Zy0GO{UY87*X!Wbf_CXpxbST6iAcAQ0S1^dj$hselJD^2)mS5MJx$&c$@*Nu!MIYuo-S>?hG zUhaLvO~4eR+LIUN3ZaQoZ?Eb^Q~Z-l($W|$znLdrfCp^?JZRs~{``HT*;*Lp+@-mZ z8t}PH2Fks&Z3o3~ZhH(8XV_3i(a-yEEAX=n4B&;pEhD@XQ&`whc;z@he>=%Lb!(T&iDn9&Jm~s%#m(*AuS@rAtsn*tf(~&_RO>KF zfC=b4*2<%9FH7p=LU|?WT}BxT3O+yHCbdNOz*HK%Vp)E;Wh#k^;0i;uSaIOi6`Y-f z&y{-;pIuFUzX0m|RTy}wVqyF?(+4tk)87#TFwJx_MJ?gtKkai|j~*s#NS6E@P_VoH zndqd*EwO)IzaE;nU6<8T@cJQ1XJ3r>C0+Yxxoc}P{!guqjo-vOtd%tEKIX;%w&Gl| z(qZfNGDu@;Gcnys_bD4;)mX?-Fk#zUY$@rq<^)wOZ}duBJej_!~=L?JE zzET$T&Av=vrtj2eX{Q?hlP70yG{4;+@-E9N^r9( z@I2mR{tS`E1mzVLo;M#KV)EunV3i0`uuE>{H>(+^8%?JVjCXG<1xagC0?#Z#x3kQ% zEaLpF58A!+VY(2m_)FIcSVDwxBrVfG`gVKz_?w+x-Wi82W+T4l1|ZYrk`7Z&qankF1c%xk)v<2dw%vXNUTY(aBnIv`Sw zw?Udw(9$A(0h%jJzpnHXa$No*t{!B_d*;j(x+8b@+YW<`wesA-1veT$n3rMmBt7LP zEvCC#)3hO{crC(FR=;^ZuQ%XrS>?Rb^PC@Fe5CsM~;rQBz3sNZgv54;_D#!Rk1C0zJ%8?8~} z?S1NpN{)7pO*}~^a5NopT6S$wHDO2_ ze;FA$m6op75y0xWye`>adERn4EC?$5W&6`Q1O)lp7X6pkVde6z!j&Xz0!%;GP4;N? zCrqq3n8}I0>@IOFpzA%CZ@ziCJ`j7MO0%Y_>a<8=Zk%S;ZF}pR!>jV5H|y%_3*sg! zisCthq(>^$>SiY0>L=18gXVUMlH{i!3bk*Ixv7K5djMXu{P6<1& zqu)LSE2t?@*4!VrywZ~XWAmf#8?R@KCT~P_XbMRGYF&zCrj4$-(DKjUkwFu) z>mp^hjm?IO-<8$R)J|fH-85Oua*Q-Z$=jlh^xfay0%GkKXdTT`Y@K|Z-0cd}^$1U2 z-B%@70=SNv+po<9(8VjoH!SDBIo=r&aY~4m&(3*Ww>R3PBzSOq&U7vEhU1i6220`c zJ9YhL4o{JcnS1l|NuX+*fcI`>jqPu>QWI&mwYN?+G*w^8om;J|Hls0xwM(z*cJ~-b zkEAzS)+^V{nOl{g!saOij#N)UFEc)o7xu;p&i}a6-D;~%uTfuo<(LbVjzRqeV>7GS z^{0U|AzHYaS}{&_m|O3rTPcr43tQ33G^R#9=en7r^<dr{VGWuJOgR2-rX(!tQxK`PhKdSkvb*x3Mc3BC`!hZagmkV7E27Q)-h~ar@yX&t1Gn zjvfgtYk8rUcK13udJ3;~?g!0(E6^p7SC~Beb8ws~JFNSVMRW8Sbwd+rM_uSX;=-uG z{nKq@ZPAgAON!?!ozR+M4seA*TZtZX+{KSwe4G<*fcQWzB|erNZ84y3l(vlAe3{qQA)9X7n_AJhpcj)%qQzAO0$> zob;8k@t5qM6LihZ)H~X|=ou958?MtElW>G+s@S|Lsn=6z;)}d!%1*eYl0648BV0Q*UP z=dpBat*&g7CszF9+5-HJ#tAb!BYNMZ^4pJ36zhHkz1ANOZLav%ge^wCCQe7uPORvv z^N)_L9Kk%kcISG+2z9#kIq2yA!iwMSj-B=7_-b9FgR>1CNb%TGZpvK&7Y}1Ijn1G* z5aE)5!SNGkawcZ`co#p(XB;akR?^Sdt+LmfB$U0Yq0<#E{9@pc@h zeOPzCYJ742jJ7(lF!pGg9ibTkGy0EYb=RDo7y|=&TWYh?ahijTR*!WB6AFF+A z5xKTf@htMkm9w;ispcXefb+rv{ONAGdivp5J{eC(o8qw(Hos7);a9)JT{QGh=s7E` zCCA>p=Jq4*Q;uzCcN_iL3vGe2GZ?O!w5p$<>Uw*E3YM*rk?44VUQVY+vKDdJV0#Y; zaTIX~ow0DsW!5ht}ef4bqdRGkpk98(V;O#%LM zIXQN^QMF-3MM3b1IU%Qv8qCVFc;VV9fe%yD^il!sIdlGZdk1&-vAwEKDf>wNPU+`* zeGP5NQ#$K#9C)*Ca5Bn9F1CkGvGAHjSi z_v!u$GZexx6xRGsj6K%V*N2$|VP?WR?bJdt(08pd~wB9AB#hq?8 zP@RP-IzH%FDNO}mLkr&wm3d!vC-;f^7!~SDgwe1!*FUcF;0^HAz*4o$Oemj#cHZrl z19eL-W(U0>$mtpb1gfC;vx6PDVmt( zr9v1^rE@qf=dM&?ug)V|%=d}V<CsM55HKn7e1_u z-t$lTpkqnwwf=hdMcX zWHnn|-9PyM5XGLX3gQ?P%5K*25up=LsTXp2E}N-h?Fk!T0!?Zv>euqx^(@EctE$D9 z>8+vJtZ(CM$tTt7AZO`lS2mX?lOQbw+#oDcCR_+e!PK)4DwV{S()C))s zR99#hMY|D>Iq+9%|7)=W`uSi(3XnYi*MI&9D*EWwjtO&b{a)0AZrS;`gU$YyH!LB^ z(pQ*jSxg3-+kCAE?saRQ%o|_dA3bm*f)6Z1T5bB^LiXF5QOC1bmA1+K1rrm~KpHmz z>eui}YO7()C;e5g`1bD+PQEg~vV`pbcX`s+VCT3Oo;<+3A?D(tAI5#}oOy5mxXQem z4qddZUtp$-Ye<^h!~A0!<$7QOw$@7Cn!%F2+8fiLoN zG|Pf!||QPdTTgX&1<2wVXEA*M^HmqB#0b!NVGE zNh5w4HrMHwjT`*u96HG)1smV~0dyo*-ISAmjYnJIas*$AcJAa*;Y|T|tjh3SqM(A< z*mGoSU5!|-c`VjGA-qk*vY&&$ge@-ciCtUn!7>jqbLlxSbp`3uL+yJNf{yL|k#?)l zGQr8Xz`VJ_oF98hLqQ5f5Mz(>qxPM*gtl>ZqYaGO#nX=>JBjaBN47|tPu#zP+*){u z;8(Ax5_+2qJj~7W^kz?yH|q*bnbgVu($J8{z@X%WMC(Y*e z!|wiBDPuE--2GG2BX{LseTmHEw#PO?jxH}kzbT^aV!`{uJlj|1^a=-kRAA_Ch zZtwW2uJ5k8eg^jDG8CRki zXd$Pcyx|fMJ3=$v0YOe_9Rw?vrP4f1q;tU73%Hctc5H6H?XK(8h8=0H%k%@cWKL*} zN5(T+&~lj|No_G_Gb-^&n9;|&`{lgN(9}|`Mlnre(Jct+t3?NHxA2o$LyPH-Mu+bu z(Hxs@&8yI`u<=|4Epr?2zw)u#{Nvzx6}DIQ2w4gU2uQK;qP6du$=P|rbgdiXlwqa1 zM>wnbyJY2bYUff^yROh$xmF;bncPR-acl4#!7+}cA8~ot-FP7jg(w-^%YsI*33U*| zltxYbacsb(EW4_BMtA*nFr~8W z^9*;%*AwSGMfEaQECuq1xGTm3g%>n}ZtJ+0S+|=RxL9?y=JA&V8!m`ks?X4I?@O5& zvup%p=-QyxDgeU6FwByhwK;PN(7AZ&Kzb-93;Y5wjDeei&C?>N?(<)(593Q&r5QL= zf5GU~%=j5H2oI^kX`Qxy}|#+I>B7J7H+`{klm#f4L6a?IUmLW z;ZdExFno7jeR}Zi`Kb2BqAdCYCYAT&++XR2IJF*2=`XlGGTPGtj!SE4kyf3qkb<3h z`m!-T05Yp_zCL0-T}`{zW_9Pf+3;#WZP?P)BFjIoilC$ge3~z*p%{$i$Q5{7M&MuP zB_i&r=88!$lgt!=v)|baXz_pXce0QB)aqXbzzL!mBDovnTpVz2jU&bPT!?{F$qSar4o@a~W2cH!5duYRa8<+3> zG*a!fu6&9a7wJou;#0rWm_@sv*tu&TPjIthmPftnjdKkZ@}74U3;=$Sx8Z7}-H$!7 zS6v~J zbQK1%4}#*{Er@TX-PKqis)F+VFCAG%HAgmJi%q~wTB+P4d#rW^lb^G->+oF~I`<_?odd~5c zu38w!w9$#UbMDXm3JB-uo&2^Vdj^1QI?^h39>>9WVv+#!9;MvAVK``y=z*A;S}-MH zhH^rHg3vp=VHq@xX$S^ph1@vbEh7Yp=lC~oE_p1Eu^RmveQEzl#)3=f7g>DnsNc(> zW5IWOQ{r9he88o7$4?3AwQ2zNC&A@XR>&!`r&kE(tb(+yzg8FoS8)0bn&wK0JB?R(%vnsMPQF^y?y7+7XxxZDx z+tpv{6xdo23VM{;Fp8pP*}8&T4nR6>_l`Qe%eLs33qKbGT$E0c7?@a4J&{qybVH#L+oZzBzZ}x(#^5>~s?aX;a7UgJ=PsbzJ%d>qx@xH!hR!QA`&-4(gkWWp z$Zd(8*PiX9SU$_PmjI~773Z9zs|PTiDJv^0c#+y~Z$9LL0EhHXFZ=!Ni5=imDpVB` zD^?9wGg_48DL_YJ1zvWzPIp1SJkMa44` z*?lPiP_;rMcg!-Rbibz6($Z4)onP0L$gO~%83e@`DJeNex9#ag4oJ)0NC*hPC+e8t z%AFsNqy8;9=M!E2=m2Z=$A%#34Apux%#rUUc+*nQzl#Z`xRu6RwI!>{S{DxPTAGXA zI91{@pPd`PbrzgI&0>4=py6X~KQE4T7i0`i5q-bAXV0GDSOW+8vo{p)8x{i9OBbW& zvH)!!>wbN&lq|R+QQl5SW8H3WN3*cIb)9c0oj(U97O*qk4cMyPV`F2(x?_;oiGaK& z)T&M8x>8e9&w||w;XVU;l$y^%g<;<#k!?t~0S3-}_oGe%`~nO*2KStt5>mwbAV=tfVWizv!zc$l837xp)~*w7)Xj= zzaDbeZEFJxj%KC-!J+Oo;YX9la8FjA0LR(A`fJ@5S;PD1LD1<@P!07*r<2GNka=Aq zGHV~>!>QdI|`0XiEDLVgBHC`5P?()MWbq#c|tmv=KD zh}H1;DU-?^l?68aeJ1*M9lSx_tLp3di_0LhMt$Da;C?J@wI{S^IF#Id{9JA9r zjN2>`WzgVZPOZ!E?Y-xk z#ITUMABKSLMQ!cXknXWwOu;^C-b+$`RE(6AeMN)VoO+QLA^ILg)um8W)L#YTesva3 zY8<%%#H`6)O#5i5+T-*KYA`+<`XE$8gIxdlyz7`&hFh5~jWYuW8f2y+BmDwK-v~~* zK`YziEG)z=I|Av1PQbD7c0(#$-$Ws&fz?FE_C0aMiv!CGQyjX*_Inabo2j=wgc}P0 zAL>n$ySMh2#0adH;f1Ar|Hdw2NF+LY)@AkgEfhCsuW_9``E1jsx-Q(*%rW(^v9h0N zlY_nhkgA_bQ*`Z==i_mKX>L{T@9pNm#({yFg?jK^I-{*D!JmoIgqRwb&Et=JLMs(d z5lj(j0W|P?>lV4bwo)?^?P-0h{*$~5Y}Gzoe`X4w8!rP z@*!f+r}*vJ+Lvwexx-tZ2o$^txJkU0ZKpzx)0``Tf@c46dl{L>HN(QXsNaH=$!}P$ z3N(Z?%36e>z5R5;+qaL^8r$=4cJeO42r<<@b+f?*MB@TZhVdy{Iy%ncH1HdUhR%;2 zBn%=(gbo$Ez(w+fI|W*TJ8TPtUNjR+8jFMp^

    WGAsB2xQO6lAfRt+Jb;gA$!wBzr*ze_BYxCY)N8)|ybp+aKLyn3(PePxVpA9)j>pu1 z8#t6!(8oJ{IRU>Izoo#5wTbB5yUl{(zbJ?pI4vwR-%g!8d2%Co*DL5O&LSYt$=fmB znqmTl&LQ}hi;~| zr0c^{5b%+MMW-Okw(QuLe7g%gPaU!O*6F$n*anGN2pwoK&ci|K#-AQiI?g73@e7_r#pRFEdFY1xdIqMsRg~u`I-?-#z3WA@26dE0GtnuWowF z3&H&d9_E7{Vz4B3q!Yid)rynye`DSZbK-KpEy66(lfZ(oA9IEt3skX=WKVWmgbTao zpVG=r6kmjfSZruWa6Al`^X{_BSOoO8{Ys|+99lv9%fR|$UDisHv%xmD@8pcQEU|sn zHb{L`3)etTJ%yRJOX?9NI2YIuRVwUbjby}K+4g|HY6I zXO4+_yc-%B5z@5=8j)0DiGG=f2W>_xT}stGauGHNi9(>JL&IfpniJ-(7ZkgEIVD{v zZ2b1Q_Z_wvg}e@+PXISk7UMXD*p(kSvjw+{@f`_<)DKe-2c-dX=_9T6&7HWli=ly4 zP4WKxdfPqXmDnA&Ory&ERbRjI^*;9HM}BIiV3x<*=XEwvdo-j3JNw?cYm;Mh`%E)E>7b2m=XV|3>0?=4Iu~f$I|fN zo})~0Cwl0a4pi~DvD+?V%{yV<^nG{eRizIPZ~~xYk*U2x+eD0^1w7CP%lpoVY@J_* z9biRwmmhD~#-rZ)-wyAmhr#bauIEWk&NN>6w3a@|s3!q75HuqU-BF}6*MPJj?=BTc z&#BcJd3Y6`>z?O+YVR3hP@hb&cB$Fl!NObyI5hFw^vX%YK)gsWo&u5fVGY3>4{s*8 zqG)>8W7`Vi42uTkd7$}2IiM0RFRwA^+}H1Ktu+l4?xKczg*R|sfThg^dGa7|_q97y zt!i#a8j|T9K5|68QyNIcxmMk3-@bq6aI*o!Bc-_t_kt$W(dUe;NOcqF=Ru?FpQrgjH=878YL9TB=YH_u`tRP*i<8~a_|FfM(vzejlU_XJoU8VQV z-NxXSR48AF$V0?kejxx1c2y3HZbxzmP~lbi37=`)-p3-9chD^8G|rwHo`~tZ|B#3F z%ty&ht;yg=RJyjH9V+bV=xm_0^HGWGVlWIuz5-w)3)Aawv{1=p-Cx>E@(4-|ubnkc zmkXigvv_Gg)z!-Cg0KguDh{9KU}5<@ia9rxp=Rm1zBE#^GM;#EP$LZqcDCD+9STTL z95g$gk|6^_a@=?yOcD_g-IXo3IJDT&p#i(;-;%7#QMl`}%{DNS1Vsr1JbUa3wzMLN z1Mx8-th#ri|m zfAIbP?iR4cp+pb}zWG!ujWQURa_$2qZ;4tfy;(*NE&v>Pt-xA$3_^44Ouv2@r1;aU zRLlm!>w4@v`&DbID=!{S?(5c(Xy+f)%pKFoTi~Gjllwi3flwF(5o++x-TPIjv;n{w z0@CDJYx@`^7y(47YPS@wUVYipqVnkRV?tbg3tHV%Bv2#f^@#~D^HF=iS*Z=o+qPA> zZJ4C&fJ(Ldii;2?55qL*+m>cDcB$ZBYfq?|v5*N~>5$$2R4TRMN$Xg^&Z zB-fY+tQVDq--(Ln<2bFb^fREOSNbA^ad4L*D;$N%w-E%}4*Qm3yvWF7(|18L|7K{T zdRnTG!??<$fPnoSr6Dh0eu1;e1~ucV%ZZ1)`8w983i>zw&{ zz3pxcqQx#h=$yD{iOmmfBuN4gkYrExH z7A(fSuL5%eLD;le+zUzgvo7{<$pIGkRf{a^!5^IsO!i7hqQQVfQr07OXk#vd=@{ zk_Rq)uEwtY)htjf!VITtFFQ4v z!ZaXCLh`L%}qv}bP^_;kT!NE(&zbE;3)acr_qobZNfb zAW_Gm#=|h?J;k;|lNbd*Kkl5ByO$u%lF}Q8Un^dLGLi>Gxb?!BPcN~UJ(Jx93J8nr zO9LLU7I-K>a>K*G!C$cuHd#wn-L+9ZpUk zT{a)lnq>6FMeN)&q!KiRgoSmXz_Pc4Jq2expagUoOrL~j05#**%?vn!0`rI_6x=#G z+ZLEX@k)$c;o7gtVeN}m1{eqs!mqrPkT7`&r#Yd}fC8{hsyQ+4Esqa8E4b3sTr;qB zW!t-B4kGUX%KVGp&1jjIC@09vSN=mXxB!#$pavhy>I|sT(FLdqQbP%v#XeUX#X7P` zDL7%`axsaCmmQ~jPA;1vza8r4T719U+4dVh!@x(#P|9Y+IV%LxuuuZ$w!H_Z5eenQ zQlbN?PQQNld>UMr;n^B)CrmgvDX)W?YQk89y60WOb{&J!r#i8ss0yG5dN*e~PH8<@ zYw=q5qdxNnA`a`o`-e6KXOgnP))jVGnAR+1+sgYqL~(!UWnbI@B+7;>Vo`L<|5XBv zw#_G_{P(Z#EF2s)J4V~m!h4`$zqQdFj-Dte+=a>_o@JEI0W)-VUBqcxr)Xn+Wf&sm z{VTs=fT@~keH14|Jx;DiQ*UtDLYRC-UfvfuOFtipIXdPaKXF3lYZ#w2hTl5k0?hBVo{tPVx)-uRdN9uBBvc3eQ{wD}p1*_B7J$-D zpqfJ`*DK&CQvQdXrjUot`)Hm|&4H70RwU(j%?kea=5`Ru6X%jHGY4K^qPf}*QGzJ6 z8hEH}5#`$rDJxjDo6kT)&aTb$m+3+H0mPx4jYE0Ji=F z%%SHw+(5bvbg;X7VHq=3V`5^&Jiv=0E!&HomyRB~xIOmJL3mxw)id&2qE{XWH^26< zK7E^F!O30(={tZrz%sQUEQ3kyeW{1@? z^fe7Ew6?>002LGI%t_)LJntBkt9aQgmGHlJ?wv`2YTIG@jeNi{ zQENYbc6J$*d4z_5vZwsZAW&~h*X7vwT`4*QK7WNE1Zlhge1p->&-Kr~57oT>JS(ix zZcNCDYIZ>BsZeP8k(Xcpp^XUEfEBtGs|4MLJ-AMN#?&v*Kl31Ly`tQv2MGwdTzgaX zl-B#ru;H&d6gv-o5cva5Q@<^l@QOw*hBIM@@RrzY(}`Zn1Y|E2Ag2KxSCmU5)Fh7a z7U}_d zY`Sehvns3{Ot%R%Fi<_*7Je9fKMO17Q};o#RV0wEg1(7b@pi7_;&iDn_N#MyGHdGtUM2)-J*77qnE-Qj4yrDyJNG;+j2-aEGz3-8me%PhrpyP> z@X6$|7sj1~js!rG4Li=tipe8aOO7gsH1;sUr6(sRNjb*-_X;WiIMUk9AdCF7R*Lhs z174#cBEoN=_N!Ing(O~N2{mI>F5RIIoS4`&mpw%Hp52#1vI~K7+o(TSix8WnXaV7E^gHz9FL%RQXXCIbnMM`Yk?% zY@AE>-Zlq`0UOVia8Q())nUl92cNAlOH%D3EN<#vC~#NK>J>a9i*tWTe4fH`QiNUg z#pz|DWVj+0Nxh6DX`9vGyvqR_?`~_1T;HAVWDk0wb5r(>S7AR~y+Ogf>RKFal!&_X zZBM_`!%hGC1fkD>z$yHbi_1aRs>H8s-_gx%UM5t8D?8*#b^i_E{8=P+@uD}h6qmTB ztStHQVY|L(3BZ6~3`NgkMPR3*7hlk=D-491MLk0lPtqzl^C;F)M6rvU2% z!Ro{VsPYdb(kGFwq1OmLo}@Rs z^W{*+#-8!?X(d4ENeWkPi+Awjme@-jbhzvNXa4vlKMz!#x?ecsjsFJ&MIE6@ki*>E zoXJdIi4@-g>~z@kvo?J?z%BQzS{jKyR%cAWw*UoJRp6m>U;+ER0y4@{RaHgMsxAnQ z?I3eZnZkbh3mS&ykeP3KD@O|<9_cX>Dg4o=umc++VJ$;Vv2~Mxxj`<)Mt+oX>k3YE zQEWw2%|2mjYFZ5_>!@udVt#-FrJx180Zd&MYX~7!yuN_yOLa|{vNH3gxKvgcrK*I8 zHk-D-+}75=ih{Ri<~I*!C;`@2w(8)CtIrS&-aU0_oY+czBaJ2RPdybyB6+_@O=118A5FkyO-T**UgMEw#%--HlNl8hnyaa4Nqh)#d)&T+kSOL!R=+~3X zxU)p|t$>oGU?65e9?thPgZnABv-zB(znm)r4`6jmAjljy zFLE$VeBA@*c+Q|E6-j3yH^O7TJINaw#*RrrB+J6dDfiDm|Mc|lvBWDjh5-ri)O`caQ4JeHC-V;Gy7K}bhbNe{ zG?p7`rD1wzJUiVnLHooW+mB@L`59aQ$7EzyR8%w|>Zy+q_-=cZ##TW_hBWl_8N4R( zZa`(!#kXs|Y%T$zm{&M8p}{|+;$p~scxWDT;D7IC2jRKBH(Glj$@IiGlHa;#)Yb;+ zxgJ0S&n^0Xb=4LdS%l`BPno3yR66X#&siB)zdQ-S+V?5lY+=~&@@z3+4pG{QI*h*@ z6Qrc1M3xT}KyX3T-EF`2TLP@7XiF#S)?uSCg+u=F<_Bs#9E&pq6uyLzW|sQwNS5yj zH17SxK&Lp4G@nFl1Jx|8%{xZm1$hL$M+qgnvG@?*3I=Lo@HEoA*15W%GI3~lI5fa} zw!Ecmiwof8+91zKhZE-yG9WV=a{Tvj$i^x#lzK&{x5s=qaW3a4L{ytRowSNl6dMWY zLTriX6s2PaU9%(&0Lq3Q2w&K{!E-6N0IazD$rt`eL|Q2u`mfN~ih?E|vmok8iL1)S zFUdMYl+)x63pfYEClo9qPq?iwz8L^c@A-t5gI4!@Jf-ismiO_QWkV*|Zo?A?!alk~ z-wC-97ub}hQumdHqi5s9cX-GA)8K_!w-$uTd-JkAg}Ynrn>4o$C&MK2;(K47F@Qs- zi%RK9dIwMQ!XFkO$rpv)?dfq(jz7}nkIGTUB7+s^7e&YA08OEwIl!kz32(8b3P%`5EQ4t0yNr8P^S z5B&3KmdoexP{@D=>SnQfOImOX0Y{5%GYtn!KPD(YcR2qJa{jV_DT?3vZ7BQ}JZdWM z1;A!}@^;>nMhyZO2IxEHBxdkRp%xVDZDYKd>wu0Qy^hx%xBUiA5(kV3(kjy5FDQsC zeHx4c{t;JFQj*9tHRexPG~h`{)FVKH|L(iU`N;fAwT2U{yU6*Vkf+f_(LMf+e_q+L zJ&lg$h8n=2#eUEJL0-W1LZG1&x#XXBu5t~W8lZ>lHflBjjIQO9X#4Hof?%&(_}l*f zgT1`SiO+VRi28x64ytqj%KZc3>qu$Avz|Y~v$xPPQ#YFDc|^p%W7`&;01@{L-rfzs zEmtfe_t}pGKf{6g_-!0K@pCjTup02Z5!(*LKhkmPbr`JpaA(tFy(=~_=_T}jf#DTT zF%B&C0cU7|C-RQ3|JIuSz6P3tJFgR0A&-ARFE3p}7+K`5IUBcae zmK!=lWP7L z=!H9q5F8x`W*`EPz5oYk#+C{Nsm(LHYkrRS;&&oE z7H2Wmk*IS!|7VA)ze}h{=lz$Vo09W5YZCC)A&Aw|7hF;)TnP0&mf}}e`Zt216?sj! zO&RB-M~`CpFH7M7#lKqwh$-}a`DD@z`2nlVP8kbQo%Co=y*; zhEjLvTmFS7pYp%~X6R*qEl!FIvFu8r>Cn}JjRpzwD(Gf;p^KkmcYzo%Lt)C{)nIOY zE=^6%;d?-@bsYk9iG2EfqbukVOM2BcQ|zC$npeq5erKx?W)9sKCbR90zs-f>A`stbwEy`)ZkQh(6G?V`w-c=S$0> zgv3PaSDEYL^ejx&aPfR_lM*Q)Z?RjqvTg$Fq_B~LkFRyNtMQR-555XH%SdKimPhPg z=wf&&;U_k&i#SPht=$paD#6}rIFv(`$2?EzJ3^>!Jss34E(fqJJ&$-yP&W{* zp3|uSy~fC;2#n#-&`|IP&5hom+&x$|pWlhpn|re<{bDi5PQMH#S@C!|UUJwlW5?e^ z5sO;isF(%c`jpumA0kpdyC3|E_QEFw5ea>d&dSa!1r z0jlnRNgbO!Lvg#>eWc)0DU0o#a>Tr@1 zdlIgk9SKtUw>#p>gq&#+u#Q;(;e-J!QnDYHK#+$(YJ;F$?hCNiPo;enkL9)nJ3@W> zx(^s^>U(lBGS6XXn0iy0rzf8P2etmW!S*Ab0F8nwNuWJ@r=PPTolPb zVT)n~Ynf4e^xy(lBy8lV|0Q~$ASFaRQ=pE^La&&8G-tmwJq3t*Q^tav)`ZBsdA-XZ zxOp9`=uRpIxs7-rD-EEBzQ`KGKW1!dDg#YU?w10uPP?hOnFWS?j#ga4RW+cjB4~Tt zuSZJo`XAJptD-#ZCc67y`d?hnV7w)X*9Ch6@hH)VvET}fO}_~6nv)=kr~z6uTBkuq z#J4bSOAUo`4(1EHYS}1JcmNTEq<(X?7W7!lHE%{9s)S?hzHJf2|HKRb8&lw|2}2?= zjBY+d4M-7+HGxrPV1DW^`B@giKNDyI9^7Wg_~$I#l^cK@Tej<>HDt8|asdJYp!%*A z3BFsP7{g_-v%AMWHCk;QABI;bfN8$jsJ?Y&+t0fZ0Rig-sM!iHB&xCy8R+a^ui-9x z3Dg$ZGLN;PjrExg9j^Mn)`=*k95K36@;3wDzhC$>9<;i?MGp7Y4=|Jyp8#^P=f+CE zzg``*EGc%HnGT{qV7*AnOp5~uwrxx1Mbxz=+jGN%xg(vx$;=8UjoH^flNvpPjxRN! zdxra5XYyjzZ{pLcxQ8H700(MNV8)LI3SQU_QPSHTwr@r?FAQIZ&RO@|xZqOs=FO*3 z0qA%WE>`?6ULJ$upCD}~`31#NJ;0|fl>w7X-9#H0;V%(q`S%9YvCX{mQ6T#=uj0v`>ZHw-gK=b{vqUe@c+hr&P(jZ-gnRd!me44 z|B9iZVUTyeMXL<-DLD?2{n?f%NOUdRf5>ioExGs6!{7Rv^l87>p=RCZ997&Ohp2p0 z*834lS${~O4N(UT$1`WZf6hsgMM#C@k;$O22eub9bFHipG-FZjyX@4V?;u$cC%R3pQltW;R zS~*obuwK>}23qm~>jKpX|9?f-lnsC@(F9ltX;4S~v;vT_b8mKDgBVnDrz@Zie5C*g zFaz@b^z)M=A>4Wb1L^Ne5#6i_y777Lf9AgXY5C(r977=bX9MWm@0x~i=^B6V*+bAG zQH=CnA#02RVVmL#%&Ybz1BD;~bhXRGPK)O?5rY56=NUK!l6Z9g*7ifh2{nvg5DL07 zQx<|K^)QQv37i(Nz7>^361cz!e-gws#qQm4S>r&hFgNR;P~&3xJuuCf3jh`l{kL}I zs49fls_Sf{%yjP0Lu_npPf^M*xA5}tIY?s1eK?IEcoH>&5=}FR4D7yrdPFMGkPr?q z@$QMtQ9LFk=7r4O(?>D5(l;+rqCS@iPHLdPDRGWMvNqutmC1*x^;diF;S$aifuFP2 z8-kM>I4g2a4u}E*?E^U-zJKNKe+iXalDT($&XE;{xQ~^6|Nh;7!WtN@*}1}pN#(pz z8$~cmx+b;|T|NbT?abNTUlRd*IYop$$+iJwmabNIfzCCDR%ROKc`k3Q?+yZ2P-WfU ztJSvr7H_X39R)VgNQa}!pkp4t4V_uYfI%YaV2^9_g?C8B%E`RJfvE=H;byTZMAbvk z3NX1%O>}vbIZk|~>IG{}d-FF+V7o&TaTao6ECu5aizMH+4+ykQE*KdZQK!-Xuwod& zu#lp<-{wUP?IwMKyhMmufR1Tj3wG*V#r@XCa)Yf~B$z=w&vaI8TuSGz)WAZwO$c|{ z>NP02GI0yygSm^#-n|gxah$(FoRYmaVwn+$S!DMr9tGe$*e$67StKeer*rBt^m+7E z3n=GGtBibnd0ji#fZ%EZyZt;eQnz%vlfY@MUfZTb6+qiZ7B=CB#3jURyilX;p!cJv zllXNSK$8RSQFL8My`898t50Rs^c_M>1L)tjI* zSfv_Ba1Y1Lp6!8&WtUNT8XY^OHM#fBhugV)TblCX@tF6skihQBt;~bo&z(7DvT$O1 z=^Fuj8b%3Zus9($adzcvFwNAzHbS6z%02V?Pf|pZnyo!kuR`r5!f61f_`ML%W>(|j z7qEhUUaqj_hXR38G}e(7H#&1^J4fMvs1)L2sNZOM@i;pIdQWL&iWLL4V5kDAJbtTX zO#mxZ48x1-As(RG08%H>ekR|o``^9+kG#|@H&9vBvhn+BPC>!0#6%Id-?o9$aqV5$ zN4}tD*!tCmyMrfY{csVibUY0EsWpDI<;j{C&(!& zh_6)g|NE}J%d<^thJgM20x-X@g#}c>52X}$9FEi2LKjr-ngVJ{N<)>@H1&)q7_TJ> z-5^;C`dm_OWJVnpAw-cSBw!P&y->euP_+C10LqLUnc$EJ*e6~ejLUw%<;i9nnHk_$ ztnUbfU+&6ywhmD$(zbpwsu1u6L&+gZAg5r108*4cMu$5o+twnJEz_#|T+!(3C#c!A zy+82P9;rF-V?<1E9oc`x6=pCFBYN?M2XM<#mhxJP8s~Rpx6O!p5G*p5t|5AvDB!37 z6OhuPj|#iw$^@DLXb#DZeb1jY$bo#9>ul12d3lfaDZVXR!7egxOJ)*qfO$$|%YwGx ze^ej^6QLIIWr?X)b0oJw#YhxPQPB*po}&Mi#Y-5=h$=HgAkZSuiJC; zZThXd8o|-6>fcy*0?vPy6$8q$4brl{9)f~n7Kdvc^dpiZoTr7BuG2z`kwg6 z7l_5KwqJ(K6@R~5^PTM2-YK9<1*7sv^#_4Kk_X<`!}TOi$crG66&Q)QJvmLAc9ET zeuO>4Dac?VLHkh#Krned*WJeYN-*&bI-HjZdxI$Y|HaT!{PZn{Y7aC|fUozZnryoP zMsI_C?<-fM=(_wY%XThjkP{XVHH}kDOdk>l^zuE|3U>9l&X1cosdsqnAVG<0$SEqu zvqByu1NeEOJ6tXwK@wX}jCJaR1m9JD)a9=++yye6KQ|_Oci&M}?b=uqiu558AEmJH z@nN_~wCm9O9oL^SG3+Dh*byIikRX&=@?gV7BBFTN9G-_>6k%+MUd(|^q)pmPQ?aZ* zmr0T~oTf&;h8`cebWOg~HF~BvU5Bc^&$4&XjE?a8>Vn|b{**@p5k+1FML6yREZ`7HPoeC13_ThV%S5|7E1_@d=aY1I_ z+q>6xY0$6n1ZoEf9=hgwT1H039aq;H2snpVm*$$%wE3N3{;bZmV^0L78G!W!Q@zo%s;i0+*Fe8%n<)lO9~VZ#m-#jn$?pK&R&YvL}H0((Uek=wIJm{j}_T`rY4YuYn#~Jalb^; zp$YdDc`+2<0H9oJz;k2K6T)RJS3^L{uR+b!t8FS3?-#LUm4n9~4@6D7l?AKt+rm(` z#(SfI0rldxmVej_JB(7bLTPJ|hW$1;_$(nGDs`n1;sFQ!R2KPxQ3WyK2A=DmNK!r! z?%atE^R+w+)wM%%k|2>{r-`|A3K_to&USV}q*b@2+0PN7-S~T{1x|Z!Ek@R6OMboN z!PA>CW@f`zN8m((=NUBQ-~9%%!FFrQ4&k~k$EWb^7ffogb*~@_%D_X{PRA}R99G2$R^{sy z+3^~b@8FE6=LsnXZGx(#vMrLKijx-(!LQj_UiFXm5bjxX+K$xG2>|g8_&b^cD#ewgSo@=0}TiFXjPKrTd&@Pc(~(vA&f?F3p0P5l2h zUs*H#EZ<4qabZa-FN5#{stP9}CcXlqXU~}p*a+tk)HkQLCK0Z%4<*RwsD7-hlx{Ka z15*zCn}h21-l$ms2zHwFQJ`x9Tv0rFzz!uBVvM}u;V+QCNm4kKq*qd`lCGm!sj7_k z+`Lj?r7<#54mdBG9|5>h;d0w4aDRp0>mD(}ih+ieRV0&V(TYmsUdxM-lasf5w66Sy zJR@p>5;8Dgz&V=W8y&45)r>(!REUD!ryX0$M3M^S>VTA5ixwW^X6WI2*x|Wr-OpdYDCdLDXcbs^NxXDx^DlbG2oS{!1X?PcLO6#76|6D!V8+ zIyxHYo?3uGDL>rHh3eajG%vu(OnsFV(fALl|K z_G2{$tJ7r}#IE|BT{Zc9^1+094B%`~KpUT*PMQzN?#oc@k>-AkhK3!gQ=S9Bf&9;A zOQVZ_p8P1w)6me9IDn{snloJgs!;{UaZ@TZqKQMyhM6Hrp#9`$Apouc`~9iCT^;ZPR(g8+w`2PA&^L<>z)#5PQbIJ;BWXf}n!R^NMQ$oNrUU+Jv^-}5vheLMAM}CZbmAK z0>xv>$Mx@uNF7x4tVnv$nXXro9F##naLtn(j>YNgLM`|*C`B~Jg@tIyaZ8+bcw=B6 z%P^Gc|0#EW7I0NP2E3bW^X3!b#|H-oXThfq3$_F>7{au&8*9!kE*7zCz`v{pOZch3 zUte58!fK%pdI0^m>{8K2kPX4$?n~|Wi>QjJ=2O+!`%Ua5IBhi2aY%6 z@8BR9;z%ca0@%x%C|mNA1b-{c_55>Z9Tcz5-+B$L8#>?00UOF>@WcJr^49#{ksAn3 z!pA19q-*iHUKkqo0Vmlfzi;l?!LZ}XrHd*^haOzKD+Qc4Jh)z3bF<#RfJdN2Owaj)J| zXyo2d@*cc-$ofe@Kro1p5-SE}X$}gHoc-0TAX)`Xn^VF`2f9n%y~~{e7Az+!VfXUd z5h`%|E$S6ZypXP==dolW%hsoI*}A26xF%#6GgJBkaLg~j4jYk*Y-R^gFb<*N!@!Kq zv?u|CjjDB=j>np9t#El7SO(1eLi0Ow;`83Me-)aS5?rNq7)hiBy^VLmHecCBZF*vm zOFMT2ySUhXcM5*F;9Yv@4ETX_r1k?cK$?FFZ37yz@BZ;}E&EfV9+1(Vh>eX6Zg0(l zHZ;U)EkGvZ9H2jXbh11-w2N{RfrTiw#&dn{7pNvzq-?6WgDpT#-<8_2<1$ zpFVY5$ZG{}3g{szkv(DHq{HzJ?gKU}JF*rk8B0%8S?!_Gz{lAPcQ?07?n$v8s;v3^ zFd8Yj@-JOl&0q$Vp#vmy84~jQroPL6w&~24{81lm)0*wF0a!{`B-UvU(|}f$ZcBT*a!bE8MX4#^D_}Ptx`s*y&2z9Q^o>Ev?I7pn_VsSiX0h zPf2Tp5(*{Og5A4zStNueBqUhs3ou`}pc4f}S4s(yv{pUE4zh?eDchM`*5eM?`hbGM zfy@N1VU4+iQ8 zvH>>f1dQ~s9XScfQ>YPwQy8I?ro}f^3{Hegtw(xU=`?)p;P2VD5Q` z;`0h(xi5UdPV+tP#W=}==ktFkd+%^A`~Q7BZc1q>+N2?}8)QaFONp#xHY5=;Lqa9p zq=i&w8bnse=GBr&l$}|U6|zP6o=A@u zP^foL;EzTGWx+m`BO@a`>(}q^@2nF+T1v`z$k+kYHSBD`Vwl=oC(57D?i>43$x(xF zQT+Oh#3;jbfCZ<}cAp5hYhtSLO1opF@~jzAXyIv7v}8tDGo~1Hr!9ytRQa=3$l1k< z7B#=r(8gf=_v0{y!5Kq}^4FVHsIi$L;Y&TN)xYz{uS%|r=W0=u#AJR^;B+wY_zK{# zMdvb4M2yAQbbVHA4_UQx<$VB~ALXLH$IeKBKS{y*t5VNoH*6^Gc80M88hWj^hf&O&E z*Z1i3jHV1boLr(>#JE^nSnF=`<;yek2S{;+Sxnnu0YbMG(0m+M^0}=|ptiR5Bl5E0puHcy22RV)$vj8kn|ZZx_j19aG(YSnmIMM{i1Gc4>N z@;I$4N?~?0>sxnSbmE@K-$fouH%)wdf0v;z(bk(!y?q$OOInO(9e-h7k?T}K0Wr;g^7T(wH^?L6{-;#m#4#ngU4MSI-I^%ZFxb` zn)*FraP~V|ISrlZ&q|w9V80&DwQA> zP+iRPM_POPt5*!6{Cq>G;O@;qvWQY^$P!BzhQ~;7s?~G+k9#nxEAO6u4^5Hfo#=H&dF(&1ZbtiX4y=;MG9kg9FLP3&ER&_4 z=`q&?iGhGm^3;u6w<3gE+S`R%OZo%5K;+pC708QxNr&$Hb_bmh@Hw*V@rE$p(gcUuCA$gs{y8REmP^2xrh)1^vqcmCvOE6Yn9osHDz2XE?zza zwb>d_MdEch>(2Cep8?78<`0Z;ljc{KzKNB*=Q1|>A#}?>>Cr!o=NEuh0AqqArHqV> zmxYCeR;f~NvS1ye{OG*mTb}PI@=OlB!`!t_*ZVzL38&&p{O(r6D5kY^1_wW>B`haj zohVqKc0MQh+NtMqgp?!ZwccHV4^aifuRqbc7{PqJ0a;Y_*R7Bh`96kD-n=$rEl|58 zopmVQ{P3rLXFQF%?&tS_xw;gOPS{Z(9)CQ!S7$zc^lsQtENthoO*6x%7W7X7@JBYh z6!m#Y{{XFo^lV|uX~xYv>d`-jan+J3XT-H8B0)opF5Ty*PC!!$m3o{{(k=xEY}>xw z6M)x0TE-_PpV*kx$WJBOsP}FTbAXyzn}Tlsb!Tbq%q5S$ks;4s4{X>{C%h2Uit`pO z_z-!wXOe&mmgWo1L8d<=63Q@D_lMs-do;QhEUI;_$ndC;R7NW8fV!*uqlZBVvtk z0=vKe!S4Qpo(|;o>#+t(T5m5YeECyB_Ob@t8uiMRPfg}vMW7q{8%1L1*ag#EzKa;0 z9S%M99}Yr>hHhv<^Dy~6k#HVD(BljzIPzq%w#F{f@g1K*R)%`4zTTNLXLeVQU@(>F zI!vHh>qkkj&k(G`a77))FM6MotoDU&ZRf8J-ca&yyX3R}q9PU5yJNtZ(ql}nzJUeB zeC3sT zP>vAwz}@B^mNTK%b~x80xhX>J9TKyCdUK@DC#}Z^RzP$1^sT>KJ=$<#MCQbNM?z#P z+&uhty?^Vg{CuV1tUb5aBa0vz+G*zp`1g8jT0LIZoD zKezY(e;BKT&Sm6ZJpwRnCuFCkrTo<+2(kG`uF9?f8`270rA&B4Q*|igcMg7azLzK5 z)3-(Uz2C8%sI3Gy0W$L%%3F*`=7aj1!~8j83~-WLf_iBs-H}u;^}P#rU*8sd6j8nV z!+exXRf`|)6|l_1vEPlQ?(M0otvM77iJcrGjCKvC$fr&4Pp&)mWdW`o?KER+=fWRy zeLUf;eJy-`0$SqwYU-1D-VltwpiNXQ*W(tEpYlK?aT2hK`CCc>0^XIE2Bq|s< zM(cbLW_+-sM*FLl7#ddILdVt%eR#eFX%``^%f+lm(Y?JyB|Irgt;%{kMjj+4xd#_& zEL_9G^9E*zMxYQLoK9TJU?G+oxvZ>!H*~X!ymK0jz|>~P-riaPis);?=CfSN&}XtX z*}UdSE0BZ8u+84?lhZUqGbG=fTDeFHV46t)rnyzyu1{V;`k&16h3)d6#d~BPm?RL#fbdD@i}o8@aO~`0S8LdvAIA zEDi}xx9@@T3riox1C_d2g>TM_B$QUQG0o8#-l_W^?paLCf@5047F`EvO&vwKk>dL# zQ!U~Z#!YbF>h1E(RT?zeF_rMAQF7U(A+IN(B69c|$ONOKR+aJ%He7^X@nR+a42n}Z zc}6`2i!f8Gj5~C`U|4P2`Wl|874jrc6I2S^5i~!l+0l8%%=2lh4ja zj2Awqp8AgoO{l%w3WbZgIEg23R^C;ZM$Djsi`7b}HBQ(>^To#*^ch4+I!q^8I8&@uRtfwt3L_W_MKS>Bhi=Z2u&**NkhJ}(YuO}S>1 zy@45QCAw?u>$KNJ)OlfwVr9=Ygafo`-p*aSu7gl<(DpHxI3#J;F}zH_J~f)UR9`Xt zFpn9zzm%TY<^9Q}N)=-N4;iQLPDAjf)*pJ#6kv@AlKrz=30QD^M(~|GCnOtX#`Z!v z{kgN#Ak5Lzx`$xnuEPMagp$b?Sxi40hk;b6@)k95k;?`K!GTdfR5GGLOGxA-9xVV_ zv;uF;v@Qg3Cu#mLs$_n+Ba82;*)Gxxe$NfisC1Gr@Ld4_Ws{>*2|+H{chzHbNO~CC zeQ5r9Hf~JZX?=>ql3ZQSlH_JA5<#IFqR~hU#pXiZRAQiiUe|ybganUz$uMCULm8po zYFLrV#J+y@ifleEmF1t(nOB?*Vg`TxXiuS>&IzSojRvkU4{*NntPu=#z^o|izJmcm zHnUEUZ;KXi1E6sjI;Brs;a8)5u~of zvu|ZUioeHP1^3B2;RT2+9D`Y+2_6EDYIClh8T{m-sYKS5q91JZym5d?Gc0e@Fm-B# z!-!^^*2MVmN!o#l<^)GBlu$FhEM5oEzrYkmcT~svJNbksE9hUPF~W?EaH#UPE3kG0 zb0BKBhKe5ZOTwDyI|yb@ffK*xV?NA`OZJw7es=@s=3py~YuGv7CX1Dr#HH@LK$KMv zP(G)%ykc{Ym~REAypxiUVi&ZKnOzGUr&rxP_D+`(j?5l2mx{k_^_g4J`3yM4PE3}& ze#JR%F)zInP8=^wk2ISBUw2S8F3ijOz}SH?@=dN1llIgXRv0As zfM{4PRJ#ta_D$R*_6j=kVSeaS-kODi2e@0+*t@TS)$rZbO<>bS*elU^7=hVq&iNU! zm0vxA8{!*_lQo`8S>@~ zw)`h>Q@1f^pPXfTX8@L2W?6R7JEx-TE;R+nT;4vtm{fhhKMs(AP-*lz+@F|p9s2tE zpPQPDTf)Jj{g7^Nk?i>5@qzfQpfBhc76OTmySzlqv)GDrFh&BsBHT-IPPn5QCKGKY zCMF3>+lQnq@8vOU>+MH<{75tU&fxHHThxKbNdzz@3eh=z-l<7DZ+S9Q^;f?({P$O3 zD4$`|S*r&h4vU0KP+R1Km3A`gW^iy!(8u86lAb`;(nsy73ZG-ziyZsr^C}-_7=Y{K z0ey9bfoic$re%Bd&vYqf`gQm^l3lYwWd=o;JUwr~V0bs?8A1E6N(-;Ynse1ThrcW* zMHF#x;M~;=7`gfY_vX#|pqyM#Nne^h{W#sDc@I%BZq(Veihe&_&*I_R>@6ZDWdT$R znGzt6>7Wr>C~*-&TT7a9dP@U}8HeYeB+K0|T-b@k(D5`e-yr*RSJ;`}_dC#m8EYs( z@SIfqrgT?FhZNMgMDc9y)?N;W_6;*wS*^8Jdh`QOHzy7^kIPi%=n)T)*?IwQ$lJ@D z{^iW`8N5ktCymFM3*$GHFAZ-zEa24Ss7IcSz&UJ}^Z(}Jzy&Vkb+ob{VN?VM$d5*Z|pB>Md&Kr0I82NcTXN4 zD)!7+OBn9N-=iQ(f-m2dGpPnh z$wbylc43`DA$nA`J9Yj67$Wz=^z2wEnZ}aw2DbIyWlYa|`?f^+Bm&5jw1K|CTM4`*{VIFz>& z0lW-H9*7Tn$A5nr{RPo~*bIE#%{HtjF{>1>(mgCp#MZ>_U zU5s!hymVESb4O4pkqVOi$60gHhptkeTu=frFNob*5u4HNiDGYQ!j{N!>_XIc{F|fW zgQvxzh_tl}=n&f9pz&Y0GIa}pe#oP7Ig0L3ypvFGGN5jKb<0nuTAP#{Sd9Igar%;t z$GKtT=no})`iA+x9CIaha>Htyz?k4_-GDvfNk8-%Jxy26XWXWqB#sz*I_+8y&$Eeh zBkzXq=U`2pBKm)y!Z@^Gk<95hV(fA3`pEErKSuto=?sy@(KP&!FPQB3V>^7s9QC{L zabil0DdiLWJIfe_<4E=a@v*I;L6ueR;A7As2`L!U3^0IM;kC!-&Ab=;cxKi z)-I|x7aD04ak&mib|-?t+miK}DLYAtOvtMQbJg4e^VL0fHtu3%WYkq>%O9^XZ|M;@ z5Fj^mlz6_M055t03>R(ZTCFSb4-UR?ka-}6o zrzArsb#>oi*P=%+m`mOu^`8Z-NXFq8E?$&6v-g+pJZKl_$$wyE2v61gbM*}ktI!OT zWs$mgVstu0aMMEPyZrPkLQ^Nvf#$r6$P{loOt4g#51O?Nd+QenNd% z`r8FIIwRtmDbcdPuuZ(p31b)Hx}g|JT=U@pb6k?Smf)})8t%t2#`D^^aN(+Jt1Q9u zT#U#7G3L&&urSxP=j6@I9t-McRJ2|Jwf>FTK3RHoA#>jvQ4!g9+9Rg|(FPDHvmfLgcAI9DF z#J-!bqEu9_MGPDR5zlSyeb*s%NR7{G16;q|bOrpST%c7FnJL$<=>B1H2bv`=|0!b) z`ir4OllV|-S4^oVsL$H09*U1d4EF*`F|JbrRKn9*(ie6GvWSE3$4i%i-#l;GGToAv z6fOqhRZ6CRS6>o)Q+&rA;nx_^*(U$s&L<;f3`*St-Ser-Kk@S|vk)bl0urdnQoS9n zL5+F7$z)$ek54vhLeD+p7d0~_X3JSatpZ?o@>`W+!U{}tOVlv>y9aI;=rIYi?*5(vZFp&8Q%Y-YszBp=>(}RjMziu;3ntdZ%DFKx_>Xsd z_wLN68d+yG86Cl)iN^GnQop%BN#(Q zjEr6eH3zT0i?)mH+n*Oh`rIQIXiT zK->WDY&1FS5AV?8q-(?@4gP5CZL3eGvp-*bapA2^7Qts=kmE3nCFxEd+P7iSxf;RxLvakq%nwxj!}YCd_hxBAwM? z2WGjgoI%FTVO%d&=9r8l_4tQ9#!C=jsbP%Zcq8i~`Boj7{@c&yyNljo9;1~sJ@dNK zYS25>)m#$z^BUlRou&s$+beTn6T>*jyOuQc#ECug<`HVc4^5O27}dPx%Pll4e!)W} zqRuLO^nd^FS*H!`1N3;8Zdpt}9~0SUoI`^|?Lge=3WH_Eoj74#{q~Mne(&s!&1V^j zxbQw+K}Wd+=Qv-VeV2St#aVPLQ9e~5jPk&BP)0_^bK~-blXU(H1AO6;y}wBpxI^&v zYl#ga^>csy$+dy`NkRfC)1RDb*dE{oG|Bg6Jy?JGyCDH^ ze6)-u#}D+q>14u%qjF5c4m>@kY15WQbGB0W5Qx!i`}XbY5mVk_F7zG3OJb(hh{53<1sn@S+1zI->8?`kS-9P3 zJuC;jQputRusnZp{6HZXPT%{Tz%4vI-0Q zmk+|M$Bc~LfO5HQq_we;hoB}|5wo0NJTQ(`He}&Jkc@On6NwnJbMy zAniUWq|)LO{{|C<7gj*V>=rKUFQBE2Vg4#$HAy-_{M<_c9*7wr$)O73x6|?XcP`&$ zS4Ybu*onZbzl4h`hPfJNRqs~I9+v{}8wF5~C$^$*sq;mzb}P$e2{CT8V!i+10ofuI zty1!j)2t;Mr%+6Hd73*3)RziBPzN)e1Zw}Fhx_QyO@F&{Eg#Y_GZ%zt^v1PohSrs2 zOo7E%rsX%tLKh61HLbUA+qM(ajP|qzJ}Xofxq&N|4-Zw=j6|!(y!G$}d|tJZOi_q@ z_@ogBiVN`6tPZ85l9{NeAAQ0f8Gdor(%qP>?fT1-+P^FX7bxc!8N5289Km$$02U&gFR1PsC6JG2_iU&9NgR*)PCi zhRp3~dD5+!Zec7DKK6AEO`HL9^dlT#k9xGZ=&s!e`}wdEFb7|IFE#FI%0a%m4>a15 z-|ry#xE`z#)0m)=jxJN3v)!H4+s?o3d5RMvoZR2|760eZkmk(_2bJ+e3)(r z^zsQ-RYhf?7bVuIzAZx!R^W@)7c#-RBXQb5No=ae)vH%wI^ah2AKdjT5g3He8EezO zJuQd?hGO$#%4e5~m=Xs=L2Tbd&;yCqV2Mpb(TWr@mNPu300mN(i>f8Hr>88{OTJE%i5c_8}P7Qr)x@RPnCZT->+ ze&Nf_tc?LYkm?^ZtN;faRv?^D*7&ScS;o+(AB5!!ZXsr&U*Uk0beU87sYG$W=U|Mt z-T(}Ub|kg;u@~fCSMQRS{bmh!ny8xs8j-6J2`qVMI8uS%2H2wBCY>!S=nvxRfK(e` zZ_)BMwiw9!9orW25ZzA-SHM>2UvF>Qis`LDMQ(y2sS{0S7WK?MFde9|p!Sn(M8Q~J z3fDiP=fkF_Ju8ei78ZZWrbAYVy`KLZBl!u z&R*86%-%~-{alPdz97VD&O=Xm6V>yD$p;K1s<=1xg4F#=xrbC{Uv29+4i^1-u!-pE z!~(BNH4qw(_mtRJSXi{b>?gwqE+r0$*T}P9Fx}LQEr)Lfny4>DNw=3VII$2{NHXJ3 z1xklU-M9S`%#>eSUAzS}SK;EE<-)DmHD9^-zY)u?wIIf<7z!m`47BkAmBc^Q?5|v# zH*bc5(&#GBt;r!vC<`u;m+LEvyE29G6`|HcY~f9}?k+Gv+pAaswE8g4fR=<8(aDYIvYi1UX{UR%yFOr-0r+ z!QQs0R20jr!Ap(LU$Tc(!;2KTg@u)2o*13yed*HNJ`=Iu&n&PS`(QBv3ePbo(xa0g zg8tRehTdYt$k`WPI~Rl!vv=RGy8KkYW~+m5D_LCvq-wN-j^1%00y$vyta5BxD?|So zFABi6GKukbTHM9@nwZbNxDA}~iXG}DYx*3eI}ysMU$ zc6KB!Lf&%p?pA&NZ?EKO#~E8?qZvCuP%BV#1m_Q|%j)CpzA3fDxD-&mg&30dk9`gh z$LyAon@=L+cD7thySSRw@cp4t`v9+wdx=}9@u2Hk1pR=+OHHVSVMWO}xXzt(N~zaO ze^#)Xrq1CKM7i`tyM!qCan0F4CJ1N8Z8k|g)o`)&;P|NZ#}CN|Qx|NZ)iRelxUNAnFvS7LozWTyYRmuKWgdVPp6C9;ex7{0ac$jtZuD3YqLf8InAm@`^?MC8y{ zYH~0GWp$>dvhHL>rNW31z(Z@GiiGj|MN4F?T=_ZBGR9=O$y;AWvit{xs8`1(3k=aJuuPzn} zR}Rioy9G@FS`?+$vgoMnbB{>nYI#i_Z7b+GUPFry0N`J%6%*JWH5B|?4K9NReV1^I z+KEa#iNuiJUREqYZ=0x8%f1EF!_C)--HmuBiRxs#Ep&nhFDzEFGr`uJKqfOH)EJZ?7g-7#4%`qQ{XzI!i|$>Yy5kJ61%FQ>V=V1B-}%m zz^Yg6nviRzq>c-VQyJPPS^-yCWX-~Jh z&j?e#Va#2x%t&q%Q?>`ZI&nTX>J3A4bpwM^oxTT*BZS~EQOi+eEhREfewJMA0 z-^!2xY7Z-S|I*vxZ_vXHOr2-wrrGQw3?x`P#Y?t95XB3!OJakkd&usQfk3Z?A_r^c zE?BSz)N}WcO9E`7DYR^CAyqX<-GSNX1B9BXoo~~AZmK=4aCY>EaX#zGkBRR$i;<0V zHkltNPq|;`_wQk z^af@5113VM+3V+8PIDtRJc!W738iEO78>HcuZW+CYIsRh$X*!26HS*|-;Uq3wBw;G zhp-ecJBLxF0?8aZl`9X}EVF3HAw*a0uz)aOHky{b{qZVp9NTowXF|311#m(bm*sD`qXd~n z9C5x)ACd!>-^P;MBmO@p>DQTp(K`Wu3A*^@IHte^oWsnJBL)AP9gNuVQ^vJZHN=p( zMq}MWnX2tCE@3^38aB^40@=k>khIy^2M1^~ei8K6z} z*A@chS}HJbm|gYqN@&f%U_P+6<6`HugY*d0gtu=Wvnh)DOy;OLYlM=69#S8OeyzCu zX=q^xa&#joS~=^jH1Sb@lpb}uguH{n>?CUCHmN{C&M#+%>$+l!E=9b&|7^h2qr8)J}dZtV?BBcC|Q#`WFCZx<-= zz0+k(2X%Erwc@Yc9<&a|*7?%-~^ z+*w^5$cI%@Ye^Rr7fyqWz7dm5hljnry}r4*JBbRcY5&{F*n15Yk$pZxaD&&zTF$# zgK@VvczPT^q|8w}XZrN_iq7mLZ%gdwhMymxjt3*lL@@jC71Gh%?Jq2Z=H!a*%~bk3 zWJo3h`+f_CDO4x$nk1}@bpq69rmCk=CiqwJW11<>I_`mltp#No?}3F~_w{8*yUV_O z`EtF|?dw>Y_3E)>!4F%QbN~_b_)UVLPk^yJZ zZm{C`iqPp3;BY*SoJLfMuy#3VzLWTC>vgDkRG5%&r|b9)ZS?F;lkXg z4!fv0W+SglI}V9_O`FGp0g>VY!2>GwGgquwf#Oue<%iOA%~PY%fQzn^sgjTkAbtW$ z2O7+s9G?C9$+z_JL@mj;rcx)MoP6&QE|p0-6g^Ubkcc4~p)mw_l}77mq0n6oK+aNm zouaN0qQVXI6HPG?Jj1%>ESvFXE2e5S0{(xTP6T`63>lf3M!=(BTJH2>%1JB*#T7f+ zXMGnb>7dAOZPBlL@(svSO>Nj)ssZKxlfX`Yu9WjMEK6JgP~?7r=K1sIjZj08y%T!- z@87?li`palMAX5gNcAYqz5Zfq?2L}=m!RFZuXWe~XBZVj2WSl*gBqh|(74bt*9GgE z791wa387ZnO^{R(IXOA!(tTooeB6iFlxKb?`aT=|TFYnSNcN>~QlISU>7l)!Z7^i) z$8r>9*C9~(7zhQZA2H(@7X0d}O$-V!GETUY3RVlDQcruF>&tRWOP=|eF`S2|&0fYA z_lC4mt_=UobPGLuRu;x6VVj-LP1fTR#mYUT8tH?#eo)_%=>p;o#l4~8peQIZ3C4}_ zuep4{!l*LqAv_;&&|2>h3I=`@4+Fcew1gA8tuG^9J^K{(szYv_;IG*m7&VA25|OqYeWsO2MLRJbad2l?QN;?i{7yk zRuPY6XEsAd2GAkrH<J$Pv-)R|A#XCUmgB7LU7e)CLVNf>q#x> zA40EB+`3HLdJ)#$*$G_$Xk0Qa3VPvK=4w<$y19!}$6+yAB_rW(pGos}Oi}fQ&YAej z1?kP06hb{jkTo9?dbp*W^{Ce+kG6a|KT4MWP zPIyEYyu`psaNKi)Y+%7A7I9XsXLcNxT3dbrwiwf32G57P=P-ly*Bq}o_5eTirDhTr z{Q9Lke^8%@4IR?bL;ewzLWU|^JXeZ3bRWHq`l~>PjMD(`ak#jQh3$Ehgr~4_!#T=_ z+>je5Hoo%F(Cxd79mI+!X&a1T5TIV|KY}A}t0(e`R3rU!FL``44^cJD|3>u;DjX;*aL)vMA(5E z3&17EaVk6X%9pZTUj#dd^iu;@@~DgU0%v>ETTNAJYDmBNEY*tjbz`H+5L}gi)j*^x z-5LU6?Q8Oe`BdtGI)!oFs6<3`D<_h6LUwE2x(*a#vfQ)1Ne5Q457uy$Xc=Ho;zLSh zAPY9CB8ucyT$zgvkT;Px4(!!SIJWl@m}IMN9;L{+fA{3|f41%P8#vc8kOm9ARYXvY z+#RI|5IeEn7_HkfttlH;xw<}L+6r~?AY790)(5P`*2!5G#w)>fHBYNciN1SL8iOlU_X!KDyDz_zkjTLMo0-Gk8dSbSpAH z9--bEcfBP#z}dXV@S3Q<^XpHRapTLg5WI>RgP!KVt7BVGqFLf~P;lMVG$cY072hqK zU@C|fK5sQH05d(%;O$uUXT10%m0^@20<9s|bNV(kfYtc%-}VzQP#SZ7x_j@O@ywA0?f!VBr$#(EY^*_=_+=&rIAZR>U-km_03MP81^(I$RWy zA6tcQeFE(kb0v4aM?a)|70_UP)35Pqu6;6VgsL53)P#)Nz-w zoxdVxYrEtssEr6wX!_}|fweJb?J%*>=tyni3NJ4_hZpX;fvMylx7KI0pTzV6T}hBC z<75~xC%Px0r?=NoPg+iXnP|Dccc964F{_`}V^%)tjr3-6s3=g)%PZTnt>Y&Mc#6y# z)>mCp&lr>P+N%KV6;})CosW7kx#psX?L<+3pG#WAowD=n+S@ZEV6S>ou zr0%o8?!|1-<=(W&#&IKN)z4(;lMi(i6&;IEy>}5({x^$x;;0cC%x1vFIUHa@nfO@} zwMqFSyZJ zA0Z(yXR|8LU%$mqt$Kp1L%#E7%`R{{%xW{VNt8bRWJ1ZUF$WEgA8y0qv`wBnXpb2| z_8s5dO}sgaLbtp!-+&36bhI;y$(xc;IPg~lOE+Un%H5!nTHwD?Nkot1AfJ<;pWi(M z>&Hg8U#N``*e=5Z^G2_s;T4m^0@`L$8Z_hz(l7TEMi;UiB6*UU zPX88*b{S%nO+*L*JmrtI)k@lg4kn83R}wePguYZa#qwFJ7{?tUR4bo`?=djFa8Su6LGzo(EBTU)iovb=v8xF}PMVF0ku9Zw={Y9&> zddFR^?c+o$35gVyc5`&d#Na+v92a=lAslWTa>%NC7sX3`SqXVUz}XbOa~bmP`EC&Eas!^azx3-+k5Sc`Y7JS#0RPmX2c`| zsu)r+PyY_z(4ANmu;;ur7Gl8ute|+Gyu2%1;AtCWKd`{H68QCPYztW^UZuLC7cG9B z*yUik3Wx^|^>JU7nx)T7h&QZ?o1g(8l0v)a8A(ln2dm*Mqk8BJxwD4iZs1Yng7+Q$ z5o!m4-t*g!ZMeIfo|Z5YzyT7bSgdeh|C~K z@toZ8>(`>5$FA2W!QO72P0I>_jU`rxiIaOtEgdvP{Y* zH}WlL0J}i3@6+ErDS^I7z{N`^!zkx-S_OU~?@Sl}s6MkdkP z`WYw}VpNQYmGXE|Lo2`qNUywD{MW9rsq>p5RfX$f*|AchQ761pL(ZDaYE<(1u$eTs zJ%kw=4K?cY9)D(M z+v<4gH3$nvuyy^|j;x>+{svA1Nh!rvWW7?TjvHX=TzJs*lr(jAx|HvGUvyG|o$3{v z_aLCY6Te_ZUDXW)J#C2jFj)pqoT#sJ7h#3@+kj1l$2Jg?A5^{1mU(||`wZS3h~!35 zwG%ztdNKiU)n>v@TVasM+4~INg?Phh30>722tKMw%SAviy#pnM`G7f2ST~L?4m&sa z+x)Uwksf(`?{RgI-OPRaSK3mC`yz4lX>PxFntJbx$YF`!H*Ql&{WWs@)2CxRrj6Ac z#}nG2@~lJ$rT%FDD__CzeIYk-#lEx@V5qNN2OvN+OTNR<2{L<D=7 zP+$EKS4?~0L3dF392nX`L_%-gCQ3+6q0<=pM6V8wWp!W0R6q;#mtK{XV$?(Y_p^>I zcd}<(uHoF_@^e>i7O&Z%Ifv>tG50<7WHd@$z@Mn;$p;~vt}5H9XL9Dc*9$bg$~-S! zim(;%dQ$Qr&({CR1)=Fom3O90Ke}({)@~Qs*8vdebNd*rG5&hyZ0tgjtyb?k2V^=o za2DV0{CUM*mp5_(7p4kZnldBC08jRWY_3Ucgz-flIcolTcDD;}klpK^o}Q7t3(Y#&UoK`Qz8@@1Pumlv}(<-$+8GIW_EFH2BzVq(dyWUGOG$Wwn{ zd(=B?rSm5?0LI<;)b*^qiX7hoXPed%s8tUyNtc=2_n1MDpmKw)OQ^i^mNeJV*QOoOp*U+45iU-j1WbV_gb(FX2@ev0QpSK zJs7GJT$4D_fXlvi`kH;gx@}ddU%!0G1^cAqhF{0S4W~YD^S_c=vgJZm+umHJ|4BV0ZWK*nB#IUg zoBr)EGZPQS*5}*E8UH*!+P=2CyL-`q$Ur zUrTcIVSxD!tcr=%^u#)>@&{sZG4>e}P`7oxHX}PL!wQq6P@+R$T_RyI`tyfXgZHMg z6MD1BK;p5W%8%fnTFzCgSHJ9X;}R&}bCUjuuF0qz2W|=|(r5UF(hSZ%_1GSD6Yoeb zaR6+<+#^?Ik5%t3E4^zWNH)v~b1J9Q@T{3lVHs4^6q#Fet%0gF^F~$p_N^8ad_2l3ijryL9nw&GmwSQf>Aj@a_G>G{0KhQMv$tOR z-F?>E+2n$hM6fSgapw zM|ZN!LNvw3igV7&YW*D&%G8yne`vRWm%pscATd7qV1SM$U;opM1K4{ zFurb8;Cv4%C$a?U$7e5*FW7g)?i@61EH`|cV`s$V-nd_th7u|br#J3ld+5>8Umi=# zWe7;?QimK_U>B>U!dwn!!@En zB?x}C_DY9(OspRneQKUg`{dS%F)iGXrN z#(5eNKSxHq^~(C*1!JG-he!weR9NLr0FV9l9X)b&hENg1^JZx#?ah1(*$vAiJ z9AT*EI4nsl??Myx1~;jlrhJutS0|pWk62vHkx{0Yf=hJjF}d{zcJ#jH^~RZ9b(&AIq9C*y0KX|a|gY*`xDPJm`LA)B!C3GcVYM|PY)+XH0MtD`9UU+y>=@+Z|hNZG# zz_DXcFWbKR%dR8F_MFVj%s2e~d2zVI3S<2k?3}%SfX0Hq|NZCueKOB9{%jaSx8ov< z%{xV%$)Z8VG%sb0=i`UHM@OJY^2*wxvw#0eN1aOIchCZ#*77&tIF2L)Ipba zr)$R!Xc@bzRV0b>5>R-KoE8*UWV1|H(!210@a8VR!d1lA7EO#~$2=03kn_Z^l#8AL z^RH&Mg5Yaw6NZSy(!IxTf=RXnO5d%@@s%(%M=c9is{MowfWPZSUIA z%8F<0_&?sj#~ID$G*H?6U<&)JSKXP@2*i-2pqmY(Mh%%)0f3auV@aBCR_f%6+%k}N zs>Zhb-?NJ__{~XSjktms)lwE6&}D0A7#b*Ln>Uy`TQ++=Q|uTQAWc$n_Qjk!!F;z+^K#{>`q& z2rkRz8;@V>`e=>ONW(3dcUN~YgduvBc1d-+hdNI4#`s}r-3M>AjX$*)A00ykZzN)9 zxFhWz9nK!B>Mv)Qf@P}a%natfQY-O;oaUKMPN3^5+QNuo$As<3x z$|(oo^(GkGxo?g?JIA~pd9-18XbCK9vrnEGfeq4P`$DkP)8kF@G52UF&f17EbCyWx zGrL(STFZyHbQ<+U&KS7OrguJW7csJ{{r>PRWm|B1PkoSmEi#&7oJFY4;*QWBa#f_wm|lo%n9nS!sM-!7cu_#>yx%*;5hz{-V? zgD-bF!$@Hse5;_LijQv?Mjv%NqvNr{`3}d|vk0bDA3ZJ<2F)LIb2S!DiOPmS3`-0gyry3MrQ=?>@bu5F z*Nxym*enO+!#D&q7ag+WOgl0R+}%4CvsRODqxzDlj@wcMj)P|(f3FMUVDFwj z+fG>0zK$=~wf24t3!;2-U`|KNpFNv(%A>LM9x6^anlvRj(r z%v+b3mEUzq#{S5S7tR6>ULu{`R#g4~)X8HFZNLlv%?j3)B$OG}1%jfZlAzEZ$;!x( zA!_-qB~Q=R+}}07p$Q2-r>)L$q3ZbO_GWbC^#uB~X!+=SIR*xXoVqkqr^adLGU7!} zkmhVWlP%GK&+ZWehDk(V4^yxBMaL*DXH_6fhq_S-OL1!K-+ws6Apj5`fa}Qasm~v% z*lGnKAQShi43zQnxVZEizlVjbJQ7ZDrk3i|gi}=qpJX$54NJ99by%dfc@*bO9q!fu}M*zWC%=o1)@6N^@n%sl?cmz2=$Tjzfp;vN@I? z*_h#g5(iUhv9o1xOqYZeTvs0yjrURg=ahp)o&f|xos|C}_XG^AgJH&Smz#Yx~-(hOg@CV^R7StQS}}8ZG_2ZFUzp=GQ@%Au~N- zkOv^7K9Z689mCXo9DY5Eop@Voj{Z&FNRj78p$^ZORj6hj3J={Onwxb|YgBY~1;G`u z{KkJUH9cbL0azD)C++b}HzIW-H8WW{)Rh*WrCFU|ysts*M9oRP*BF)%qF+wAUtwxh zvW0)XaQfRpePR*>_UCL>=e;_c^d(7)f2KG_PkI%19ZdaxxQum?b0x(AGZ?z)Injs(j55 z0}EDI=A21wc^I%{n+FPJ(e*?DMBSnBKV2d&oHIG4N-EeY%$hGUKnedUZyPuEV5YDd z_T9A~jHEP<0P&unvq!#PM>p+%}!@-x|nZPQ%zY;XYVo}&v&<)LyF!NSdJ z&DL>OV1-r||HgCb$3F81WF=l;;4*BcPGz$!FTZPBeRjB=v~%_Jyg*0sM9H{Cp2}c? z!r#$H=L3Z_&Nvis`?kq9!+Rp5ZRXz`1u9yf*`5r4XqnD+ucsxZ1H#QrQiYsewF34| zF&W*v$$opqx)QU9Eh(9ISKlVi(F2S zzL~rab6;nms(PL6gxs0IxC|(Ha|U|*nqgbi&<29Cq`2v)d4GHdc+v;Gp7{JEbyX1^ zK+xZwqH*rD`@4LOf`0KZ6aI51 z^AopDGw9uLKF?cA8m$`)Qj^f91K$K({QpblQosaikXN2AsnZ%6Som9rFeTR<|srD4z6-<<>=DLbv3e*SS`qM`{vD?OI&)}U@X3|WFFc6 zvsv&vrr}EPVI=zn5ve49VBbO`noOUcKhNwahfxQaLAe6;dca3 z-<6q0O zi3=H>g1z5q^@>Al&}?iY8J8T`MHZ3g1g-B?P?Q3nv=Pzu$~??B1P#vqcn~j;KJ}w* zc|QVzhRK$~5oE2)oh|R$9Uor-$NLRJ>&XXpkI2Hk-)>bXAwEHMqC}yw<2$R81(dV@ zI5jLAFVhGFOxEgQ!Lr2O2)A6qYdzZ+WgzzU@Z0eLdHoF{2L9r{Q2!bji2SeZ0k^|# zYX!MrUCz!OWtL8OcYY0|zd#F@GXRhV%P(IJN+AXi%P;>E_1t(s8b8_BiDf`WGUY8H zpw=vP!3K}oQwv$6N_JCn;lJ=xSJ#DjxdWfQcC`HU^fzc^@Q=VpmV6b@AZun)0i!K> zBz2R3Ip2gr54|I>NUy?9DX>LWB6lRh@UCVsd1?i84LrD|8{H3Lf76lI1HdhbTToXM zrm(&N=4o$gQwZQ!wlHEYTXslZ$($}owPO-%1600kX2_L+Nj-_#Fs$!_Dpwg#PC^;YC)jCW-;Lx%#wxTM}AQ zp?=n>GQ6euR^LJ?RN+M9H3p-7BNolNw^92vw5o0)-Ci;?%Ii`9mq7@y@UQ==wUiV zsUDMzn^3^Kuo)x(dx_-aG>8eck zC4w&uCd2Ce$Ur}iIDr|XOSwzQH(SUy4i+y}?7M#L8aISUuO>IxhR#Nj-R7FJmPLY9 z{Zj6}75gMKcK$w$;*K~s{^KXscA^q4a`hQzh@gObQ?@gGpz?T77RXVnxN zLJ5Wfvnj+y7#OFmjpgW1hgJ14(rImw2HueFNKqh(w4rVcK+KnS(w!T#`g?jdFm_1Y zLF-L8{6{v~i>$eeH6(FvuCdC%=qb#%u(#vTKMV({5#18Z#GGCPtY1adAM#>= zJY-h?9z4bi=+HH8#G8;@-r^T%=ngYgO=l^+pIeB-gC3dmni>5cO~VfD<7{kf+)f)A z>}t4yDjJ)UhzfSGwB6$_>&#UG_YB=Ro!yf6`SZjwiV;|XGzKU%iF*2R6vohheNjLDj_*Gd> zxwknObXc2BpA(2>))}CXYP*$`y!EOD_^|rbxPQ#FM zuGP}B^^4{-fx;j|fhJfTW54V}UBaTQmGyg_ zNl@%po$Bg8onT4p9ea-x#69{a<`mb-UCU2W6Y2F&73?o)9g8ka~>&Eqh|5palfqyUH$2IBWabY8DQ~J06 zX5}z`$MF9N@~a#?$WPjPvf||-N3HWfO?SB5$eXZICu8j&KYnaKoj6ofX$B73+%x1)8liq)>rGNIuX2FaV&sFzU^bdQ2W=vUgLR51plX2 zl_eB8;{ef<8HvntpG;T8cGW(HC+N>~RWz3o+EE|qas!mbFq6fg;-rG$i)9O0zBD#M z$l>Yp@5Pu3j@uqH5W}|CKbyAPm#n*vFL7tEA1U&=ScN@7tGT&p@lH+22#oN*Y@4m&A)sU$pdi_;mL~QH~)n5X{=0uD%M~}k7%?F znVC8C9NQ7`p7mqboq5()R$l-{DEFOc-u*(0pz^f&jBrBpX$p3FH~x6e!5?a>(N=!J zh$GC+e&pVv0n8J3BYHMsLgq_O_xuM>#u0}nq|CS<5fPEsg(24mG>!gE_3~7bbQ?pq zdUtPfl16JsET~a_OT}4wt~%{b!zkRM&6RxjBj<> z1|W4sEep>!XzA3R97VW&L_CenTs*$}_*Zf&fmO4U&@+i;|64jvVOY+70Q(W%21*tu zCV*v2Xk-NEoF<*TU5WVd5t!{TOR`SGkP0)S-TXm3TqF7HFf-iImS&xPcJ2-jmz|fH zl9mcG6r}C;i74BD=k`h?-hth3x;i;u8}LuD*tBm*k))CTg<7+SFVjHGT2AUz{#67} zuTg!Rf;oNunp-i8afA>6gNfGuo>=9{crW)V=p2R7U)eQ;8XzgUlAXUtVdayf$78c_ z0Fc_f$fDrv8{hN8|24SQW3ATZHtR<6$w#NEF_vG0x-=OQMZ8eEg%U8!MsQF+R8$w+ zJ0M8T!uS<;m2XF-R9<^|!(`++K`bzC8ZM)d|NOAI*TK&&wsa@YLXbD%I)jsAKIAWM~ z3RtS?QMeM?eF}puP+SCAQ}?B*N$ZiYpx_>m*$=(YI=9yR0|73~M`y;G@ngR-cq`d!N>oPwD%6ExsCsaZ%2`gqD9f9Ns$s-N2C;$lA?vIQYsqS9b~0p zR7T59LsX))G;Wj;N=39os5H=0s^@i`&N+3vf8Xc%KF{N?966usb6xN2JzwwF8-^%0 zKZ70+(f7@qblO)|8jM=3dQK1gq%iWSMWMivJNcqh-VO*@?KoOdEs z$)}j8KtcT-$mlA*Q%Ut-AwJRE=Z7Weh;U!Bb-x5G!a65H^lQ*_?M*uQ8BWSK9M9LV%JBnHSr0>A& zgIU9C|N4tWF~sb*H26VDd%Tg263^G<~%|%uP5j<)a@F z2RtAT!jh*S;mHUcic+E8I=ot1SyMN=<8XjnyYBI_ZV2PRf){sV#ta!Jvgy`b1TF*+ z50Xs59KE3>{^`!%W6+fsexj}@Dg?{MUF*ZjpP@KICO0br#`>M>^!bDf)p=XYnme=N zn`#BLHJA1RJD$rrIWqA94IZ+UCr_Lp+PnV$ZNbbV z@}J+5cwJ9(?1L#A)T_3~DtS4%<$BMbJv#^d(L5U+OP9#weL3kR#)ntDJa_(MV=40J zyAcU13ztnI+o#HY{=$VtNE$z%GuXUln0o?Z`~QvCIGtT%plLE0$!FI>u+5r<0HNgH zS>7o93$*Qr02xl)`!1(mB~`&nv}qFsNpZN}5_PGWnizINnyjt|f36(yeCEzs;Jty< zBVPuYB*H5FdbETP7Sc+1nfgvf4DAURAK7qePx=bxkv3&w8}j=q#)}P2>g1Cz+y6_6 z>&D7~8>nt=v&5Jc;_^KMfa(E{lhxbL^Q+n9`43jJJR2!?GKB<)uC%+Kj!)x3?p&gz z|L+s(lK-4udkdH2)v{-`_qXU(dI&a-BG}uFiH9+ZuVxZ?H=%(iB&Z?$!$UGB1F*ui z<7`gjff`GVWRkX8RfP~%p@4a3t`felJxC>-kBHd2y$_>v#Ix$%(PH!ILMH6T+aAH$ z2m7CuZZhF8w=Qz%cb|FG06AcQQ}$MM3Cv$KveV^*2(Nrg;I@+3Ge6@?%8)mcBsid! zp&RfNKn2NgA@uGsTnO*K%2~|?ewGSP8(DzwWIj@kvQKW)hz*MM5owe9dCK`LbW(KS3TtG!+Vyqp~?zaX6( ziH_gep5LPbp`&5YpQZ5Vw|)Fg*Vae$NS~{*rKRPbRldUCpx+bqb}V47qbL#DV5q8P zd^AVV6|6qR(`xZH)4+qzc0YSA{m1OdxGMou=Hhe}kiuA=nS)&DZdi@%ZR@C-r-%tj zv{!O%(c^d{?ns96nQx(vUUfz$l>ig(-cN|{QySW&1*%P zVfLI3)MT{TrD5~FExrRd<|>a)OTME>cEsHK_B$@lgR$B)NFh= zDQ8d@t-kNxnO|)$M+LCTl#Rog!pRTCSZGR!nh58S5?zhIRm82dc&? zkzJ>q;2i*_1|yhC?eyH8oOJhmMhQo5`nQ@)ebla!FV00zI*_Ls|KEa>cNRN<_E!Wc ziOF%?w&xhNw~&lnQ<+mwYQHOZvfp)fzzwXxt6sG$2Xy}3<{hX58Dk7bd@mvg0_t6` zij1RRygI0r`n-4)Sv8*k>Ly6`fjJ+(FwchRhnU;YsW{KhUuBFqG3w0B88b-WqhAs# z;xxQIiJN?7+&}E{b@}RW%W&zIAbOlxFpGzH7F&5q0>xxoUH-!}W@oN2?st&|?v;0G z_}}9#k3raY@9)L`oiMv@HwN~itcbKrf-pu=$F^|!4@}-lU!{h)(dNx!XkI5{*P#!2 zV0iT16Y|JZqS^NS=h_X0kbudhB3+MzC~Z9s2o@>7xAVA+Q;r5;OsOi@gc0HYV}g4H z8SY#PR+eH19X%@m*F?glVvam?Y+p_vNfhvf+zq5CLsZ?+nPcrbbr)T-0`3JgypfiX zdDc4h|3@N4i$Yidke$1{^+sN1duqp6%+tlcbb6+lJMY}N(kM&bbm@2R;*awpM{tIUC7+rJ;#IpEmkk{=^r)K{u@M@$sp8kpoNTRV_1K-|Hml zTdQ;A=vig*I1?HY&7|sFS+*MO3Xt6-mIKUDh2n?zg7TH)Rfjn6ug=W6pq92^p$@rv z6K_kC7;TY$#8bFL8_k4(Nt*58gu21WGIRjFsW_QB%imsGP<^d3zZ2{g8L6dcG{ z9%zWYHEVESbOr|S8z^*^7sMytxSmaFQ-9$XY`y@v*=s;pE3?r0%boZHrEJNP{0tDxQ#X{*-R|J zEIN0#&B%|)gncJYo)r404}R;LoqG+^j~1Z`d!edoo}LUi9V@b&Y~(KL%!I^FnKTpE z=^;c}{$$NsEiJ;~BK-bl{@s>eUGvWijJni`ar4)$>zw~~y`Q(~gN65<3-TVnezD8* zqklz9yrF?^bI#9@pD_>8FVwAikRr73GHDN8Dp1ZfGa3{%ttbC~Se^ZBG@#|yAY-}+ zG1D8ci-h7<+m=MT+=uDXl$6Zmsjw~loj7Eq=e46XzeIr zuNFBOJ4-vkUEW{RGkM*cCt$C5+}Kzs7O`U%;~w8h3TQa|yzK8xPw#DTi-$RlHJKNo zi5)jQze#*Ei^85EXesRIEtEt8fMAVHPGU&vb6jml$4}E=il7l0PH}4$XS1A5c5Y8V zks+ml*S^}zt-6=SYYCh9jc;rawP>xMY^S zyjL02BcF0QJV^d}(mt{n;rgps}&95m6nlD*bHwI)No%8l>{WIYf zCr^PRqv-n8h%j4iGK|G+hTq>q{co36McFQ+A+thw$xTdA-3kXaUy!LjfSg7aG~`rD zftGE-yU9ljqW?BH-DD`RIDa7YqvB}v+7PFd*h-t!uX8$#hXsUtN=A1-eI?lBhFF<27A~I6QzvsYk+-4wJqrZGy$I_#n*yWB9jyQkTCzJ7s zdcceSu!~o1-hp->;;&TR16r0$DNp(MB5JQPp=HGYw6hquHFsy<^FoYz#W6S9w-`f_ zRIMS?&<-6wtl*izr_~Y89%A0D@ZN1<*}xZ5E89<9{r$JrR!6a#ipSi!CVi~Ix7B`p zgb9!&4?FntmtGvFRHBQ+4sROl@H0?sY+OJnL&3_&r>W^)m^nO|{VxC)1xe@iC`mA)wPQ`V>R@m6Ly_(P7EBdv{>qOTI z7h2|Ka(-<4A-dJd>1E}LcE|H$rgU$t*YeCU$V9JZ;0 zD(hufja3Z0v_p&>Kdvx-MMeh?1~%9^mqL^UuZhaSyqvD z9Pawq`iiRI0uK%HC1^4~VXWfTbR<1XK_?)m`Mdj=-AytV5PpVv{>(Ol)o@ru0!RYI zF)1s!>pj$e@=%Lr?EB`gUDu~heY)rL=KHxNO3;7}OX5VRvZ%R3U12yxcjw+D7Ax1C zFdW2ms|nN5d`xkT(yX@)vfRe8Wp?w^$nZQwew#}3VUAjm3i$5`aee`f#J_Vl7OC}l$>2t%1Q?l zp_(dgO!N5r&ih9+cMLTYiz}@C)l7;5Rd8wk4LL62gJ7phyUh5P5JOHoXJ-S4MH)F0 zE`$my>k)Lp_x^s5vJWrpSJ8mC1n~0q?1+>)$1S6sm5E%cA=^9cH*-_O1v(p2ul11# z0pkV+P>|a3bx>QiCGXg(lK9SYwRHu)_NNA_(=+`S?s*0sxKQm9Rc5pncB72rYrS%h zXYSx!V7B*h?%-pdU(tU+21R-hv=mq6q;ZFme#mGg&lUkig*o-xuB>ouGr89HJi%s2 z-0Jh~4K8yRN7tE3jy^C=QFx?sbCu%3X9lOIO%GE|Js{CPyl<+VarH%?6tgdo!#lUA zKu`ckvDMB-^VAIy!QHG}5=WI4PN2SHB{^q?ylUeFH42uSJ^J5R`E{si)SQzsv94u7a99ty8IG??gY=Wry>=f_u3J0XwO1>X-uT_SGRBmp*%8;JpF zU>b53R7>!ga-CP496tw3bepS&&SW0K|4sD9Jpe@N9^_7p(HWOax=}#_CBAC~KRqJv zM>}978eMD61K-Zxe*``-=!9*0ewmx??(d7O6G$1|9O0n$A)CX`PyC~TlbDBP_4+BU zXXp4ACRa;!Y&l01eoJ`S$dW~SG}-mnQifZCN82PcyM!yd1uo1Z#*2prMMYXr)4lUX zQbfe7xX!nooH7A3;09#AwTJ4fafjY{Gn7t{(R^08=~II7{D`h3}vzmM%M?uj`RI6W`l;=>xP*%NIf)QbR0 zd9RL*V`X_<8o&^bH!LQFkCc&hyAjb3ayc^s|k-@7dy(K<-{(J{E2keKD2Mryn zudB5b+`pV{TRwHl6g?p03DgMavi5>IT+uoGM+(&X4qovo=(??M#m+wP?D4G+EzLr! z^&ms~U!4EszRiRsu^1XOLO(FWGvgti*$2f6Hs&XEn;#HR%ueuc&rn<4c1uKiz8E%r)gd%Fe+QF|eKsP{w1YkK{?XY8YW>d|_iAz@OW zen~>6HSmyR;g&P{rHhoF+H7CPz9IB}^C7o>^Blh&%k6~u*u?&LI2XY=T?^VE$K2xp zQ?l^h=SF|b+YU(MK$pE0!Ms(vqp5fy7*@WAZ*2uz3visl_3^jJG~81s4q`W(u23D< zc6gm+tG}5KA5$x-UfDL}4;a)Jf%2iwn!mEi)d(5B^y^BH%opsaKAz1Ju9Bojff7}(CVU&ir>G`n zuFsD*Gj|^C$J|Ly+4)-Qez&D-B>v&oiZ%sN2qyWaN#d3JZ*$!aNW9b7UoL9n5FOJd zLvS6aLc3ql_J}wL-&B3y7gshP6B0kTK5;iY(OG4XRL>_9@@IrqgqogeDChXQW=*eB z0fi~$zqGFkJnw+VBiL4@8G9w!0w)}udUzmwRjmbGo5>$UAi=v%tw+c-LZu2 z!Fo}3_4;?2!^RSe7r)@hY#)u7FmRCZ;zlYs1-HW=7qgZ@+YZMpjh+AGpL<|*Ea1d> zKq;FqNP=xjI)9gI*)%7&t+2unS4&`DGMy&NOJB9!IDdX=2ZM ze|~geu9sLXh*Q90v2k%4`zc$L1*SYlF!=zez7E{Bl5Ns5_mRS-H!SQbz}GWv`t)NQ zXwV}t8(@48k5;{dzmNxD?K;5are#(q71N80PMq`Aju@dRl&qAfdLLJzQAH?0Zfq5G z;znZPKG_XRGBlRTG`ovrpUPm}HFNkbd2iCVd&d)d^y_`(SP|&wKf$wJzQpa}@o7I$ zAof}-RJDILQOF=Aa!XDaYdqR_PF7~}q<&6}FqtRP1GuDO=L+zk)CvkLmXkXy!)Ehw z9le|+ipn7g2k<9;1UjL$Ci7Nx-@0bzz66A0qbyqOjaWlILE#0>-1D%4{}1K(gzfXI zXgTy_Dq1-K+y$01{@3;5^Ek5UK&sryZoSv?HWNmTH+Cy$O-kck3H0BM#KfSHuBL~t zk=;VIr04nANE2$&atb^O(%76>45XwOw8zhlvu`uQcYeMdDuX9-m!dAGciwYc_sEmB zkg5M6)N&Ir2abu1z)RpE=mL_IwSBU43MG@Td`HBT4Eg!+Tq~d}Y7C0Ma~ugL__R-G zbupli(FSm?$u!@HK3_3lA3JUiDRS9u9_~6h;&FU}l=%}WQ`tS9n5PM1^L}#wsYj6L zhB-KgLi*L1C;(Vdc;l(JyF^2&O6gMkq?GA8&dzs`AkLGobeTo5mWWfmFSTgV2JOJk zfQGnaq}D|rCCI=h450S{;{+b7yx$jIAmlnRAeJ#)fm9>>7lfcKppDC!c1-Dxvt z_O`rjrDJg8gejzC;N81yN6}x1V$zPG1rDHj(x#?rKY%(HHPKz^NBO9oK6vqov&4>uEoJ9J>DP3gtwu_Yk%%*w!tv z9*n`dz!Iz6-}sXLG-2MRS1Q7f>4Q^=Nx4Iq@M^8S1X%zLHG*+E{Py-AX0K_Ol6$oe z#EuJJ{THo|$y2zGvMqYc~YS$#fXptbL_T#C2{}{Ct+gzs6~_9u&Y26iF=36$0Ekoa8SqiJx5#Ib{}(KY zQdsl5oB3GE&Sjt*aIx#}TYn%Rke)|+U_khR={0i?wEF?(>1Cxkp)yN?ebclVZY%|< zLC~=$A~9j+$}3GwR(qf8CYQ&Zw<-2C;&lr)d(KR=zJEG98V+gS zB#~mbFb(Z~y1*Qp{DZhG0u4!BcE|Nt)zu(?^|A)o|5js~k|JVBh8~*Un83MC|2Gd# zH4Gm5fwq>b@~;d1{og7)l!33luo% z!A1A1v0Ps1En^45S?g~z0UoGC=8c@Vw_B3AhQDY*xaME3jq9Q@OHx$KPFia&BNN;@ z33OnQfQss)i~PZ*J8+vGWc%sq5M+t7TVmhz12d430z6ya)z#HD;#CcO_cSE$Kn2TS zDshD=8oM#IxcJHHcoy0q&IR7DO6mj-%=-j@6;!(M!r11s&ccnG&e8#T0wwk3;^JC8 zUqIQG{OAQeA$ue%;6x3<4#4|qiLRNJ>D{lKNGgIw&nZm!@*Imy`#nB!XU1Q#+!=OA z=+*hl6VyN9Q#?6d9A^mOD+=1sE`X%Rn&jp@$rxOegXIWEb3h8CIt2Uo!MID%zS?;w zW&`OzIn20>nS2E2kM8Eztr=)xKb#m=v+Ix=Q-K+g>7>Hq<1c%VaN4`?nlROlu6Vl@ z$q0vE#R`5q1;bu%B}BsL#pu18DlGt+OUnD}T3>FhizNA4#N}l20-)~h+mk?Uj!~6O zBb3{Bv;t2JY`ey7&s5|#y!`?Q>o@?gJa0tUalRTX?-XLNGc(r911;oL4_HX(KC9Dr$rqsv63{5>ZBo;5Vn7`wI%vV18MWun?ksUirY=qQC$h z_UEOg1dPCu(H?vL{2be1I4gSiCH3vogWel9?NV*NvSEKxK5%n$goF-gO4B1DAM2vr z+N14Vdf@bT&ZP`CUIztkY@wnOD=Iod>L-cC+qf9d=e~oXuI@tCuB_P=j1?~ByQJp% zL;F!XqR5Nr=GR3i`+9BBb&9}rhvLVNbwLB5Mqf%?cD6a%!M&fAOv|k8a#{0)99lSA z&m(^%yA2k7Uqh9%T4c{u+%^Ort#5Y0nkA({;M&Xj8hCBofgf91DCdh9bqkn`y}6(F zL|RFbj{0>vI^G$Q{A=Tkcc4$!*xcNl9e`~rXltgH0Nn_r86qDQlDJJ9-w= zFMZR|A~+T;03R6WxYKK`;+Fqv->?UqJb%UZ`K%I?sF4&2DRzBa_{U+1%rVFGF~TmC zuwap-k$Z1;|^P`ROBCV*;Nt2h4 zCAIO3o}r;f+aX|3>fD|^NmK7&=xpjo;+xF(*vg{zaUc_dwnkpv%Tl*vD@vXQXw7;s zkvX&>i7!F2{+8Yynb~6HNfahX_f0v&2v^mZ*LkyJJPt89f0wx_2Llx?BP)BJC^wK7 zY&!Y#@YvU?$&%Jp!czlwlHafWK?pK~wFUpBVGuRi1d-;N#`=}9bIYU87XE>rp$ZO% zE5Vrus-HhT&C~IGZ6p62=_O0Tv19t60K#bIl_SRk15X3(87Ldi>%?7dl-KDD?wVD$ zU;OhYQ#V})&&-kE^tK1)BZ~G?_{1NMc4WNQPPAf^Cj&BdIG`oUsg&O_Z>V7#Nh>88 zwIZb;w~1v6$J9}kXc!1)Ncj@J;T7Q=WH@txd2?A;q)43?urf-c&Y0!wT2tvn7AW=P!AJdN2pe=HGtfuOT$f84E9BC4J2Xwx>_wV2+$%FH8< z7fZj%!~%>dY+4Bq>D(if*BJp|iYf))g!bAPBAP`)?7(J01;mw9$bo9-OCF5b26}nz zBt03+{8pxqiPYam#?R!x{|~JX{M@V_-jo}#IdrU8V?jQEl`s4G*F!JcXB27vNjpm!S*X#d% z{d#cT`ED@2Jg(nH18-i&x)So;LtHe zbKZxV-SYzjwArxh3OPABC9%K&eLN-v0*eaxmLx%<8-B5Q7EM18IsMT3+WKo{QFM{p zI;UJU^6QYr8y$eQgTp2?#TEJDnCkbHz8Jq4qZkSqeR4cLqw9bG1-u?E@4gnAv#rnN7)a-dOE8bkkk#pTS~5>PY>Yx(8cm^;hTNJ#F{`?5f` zoRCrv>VvybZZ-~AV;n@oKsko-6zH+s|5^)l>iZ^78p<%QHSz}L3S$QKLF)0YxKV?P zXEo7W4pMO*>919lOhwRejvT!}t!MdC=EIxp$W`Uvr_PqlvE>v;R@bLBbnmli2>a$c zDp>jN?C=g1n#I8!Z9)uIdEcMpsKKtfLuJlj@3KiVUG455-#>r;V#E}E=>{F|Lr&Cy z12X>3o$^J0X?4gibD{g20ihh=jVncHtF77X(Ok~;tM%mYgdAWea`~OsHhWoq7dQ8^ zgLZ1bd_39(AGhM}9(_xeqrs5y?(H-T5r2+R%p2QB-}-oZR;PuiDqYp$kQ@1T5r1wz|WI52G9S$-B(x#$$qCw%?Iu?9u-T zxCKkG`Q0|waKy3GEt*NeOp|cJ+vfTih;2F^6!-z>N6$B&Mp6al`V(nj*^c>w_Z=*o z-s`^>y=5nAXmkCrTcZ1LfB^|ZLGSe8%M+_pLZ8H!{+FgBn*@OW;^|BZC1vxkE`RVc zqf>w!Qcg>R#l})Q&?XZu8PfG{9&g!3jkBig*|X;^NYfHmVbU>SHUxdt1$8N-NF#4j z<#1|J2>+5@Jiol@P*D#efM_&6~VliiR! zJife3|l+HazqFJ>I} zs#$(4<#<^5w^iZscN6cvRs52_{My?xSHq3 z3oh146gCcSQR>(a7YkA9{?(N}YZ~LDVR^Lgby>vyHSxE&zn&;UV8M^!Rl7e&LxFCp zgX*lm^kxa$k41MdoO(b0nDhV)x(n&sU-k)Slj~ty&>y@I9!T|0v(_GzU$dT|2jqB- zYSp1h|5^jLXn7;$VaIU(Yw%6E-+H!5o@osGTE zsgxcfUl%4vOGrpC&pEUQaPPa_jo_6%WLmh3`NWomsMs3h-4tMK1obp02D5%Gkq-LT z4l1&bd@CDST+o-9w#V-qSlxobx+@0Z+!RVJ=0F>F;pxwxKWFt`rM!_bcjVO}Gh5Oj znk$cVH`Vg@gspM;ouWm~qD2AL`_;qh8XjB3JAq+Ch{IHU!fyX|bJb-Wnsh35#U(#w zJ>&05x|5pw&eXYY;$a>q4pB6c;@@lL&lfxT`^)kJhKXA=F^V=FlLRgM682N-`QBly zosyDLM$YiHdy4pDn zzve)J&&g87bH2_bojy;H-mBTD3_QT46^`4T7Viu(-~c_ahC5h2KI1G5~VOqxh`z0XG;@`Aslhf7o`}bG8TJz?%BD-+Hxfcl>E0f0v7`(OX9n<&077)*fb2Xk8!?snMNvaOb2UbVxm z;BlRY0Illr~1T2B+z%RKJ7%ZHvmS4Yl_M3dTEw{EHCzI-w!%rp;f^YmTXVC77D z$=51Ykej>OoppfP{5U|x>=xz$hD+lBPv@oX`_}=kZ9>W=z6 zv!wjBG6G{8_G;REbuT5D)ZP^WTtX`r!#AwV*9U*hLGhN+gOD9tg95_IFHqRN%)%2{Ys(PH)(3_f+ zoGfdv?rHOFU6Q)GlJl+`C)p|uIdi6? zV3fMIdz9Z`YfJ4B1@{O(d(CCTKp*b{5u`>}&)-=$$HYd5(puH$>NWICLOml=xIv%m z`#jdm7YpF%3Uc_EDvM7FN9SUZx^v?GTzpUjTG}~{gKx7G+kMKs8+ZzTwH7)r znLE&2pAX>bHQaY_baX^8tPK3M>9<3NG8=#(-v#%=<;RAOZ8KNqtDDs(o0IQ-np1?x zl34xymBmnIAHk;a!qek9Q+0nbqh_lYdM6%YEP{HF?Rf3sd#0R=7`mN)8?-s<+^Vfy zFcV;R-)b~{9lD_5^d1Qvi^#pDRb!svtcyQkl{ zP}APtZi{dtT3k@=h%*LEq?uIbo*FxWua~J_-45_)9VNft*;Zy*zlkAAUvENn8nV|L zvPA0|J~+8fo^_Pu2b%aaQU!5o2{+rD8lja761XEiO_N2Wjg=$B!Zc~FKaOzjsDAUN zC2c@_Ym|Y#p(aneLsEW1f+WnG02nVqd%TY^R^m-VqOur~f6d~aPLIOc>W>9qvM5Z& zWCb}^n8iFNng&j?>+r7W^lQQRodBv78&DuE*_aCY5gUEkEU{?_MEVVSXR zb5EN=|B5g!T2D~}QK7t7g^xr-ur#h1En+@vBa~pNt8FIpT1hX0&>Gjw%$)eNI7RlY zx6Nn6cR%0Xb4t^frc6pd|kJ&F;Ca!@f9ZVSs zA@=j~VZYDIV^5Q50%q0A=Mf_vrq$8g+nbKWrGc_sRfCMA0R6>ie{+0$moBlwsiAIf zN>7L^)W3}0Onxya{$h@mn^Sh(-+rCV%LEaQitALJUiI zCjaUy?wza^8774x(LW59-7p%04zoqY|D3@wb6F>Bbd*Oq2*2b|cUvA@WPNdCB`q&7xjcj;#JI<-`BpzXdc5 zcP;%M?BpZy^KIi$eq#`z5X+`;3D-s6tX~^IRV6bXLUVI-@AhxY_i~%R(mAePBe14) zWKrB2a#T-mQoZ`aL8qE=(+}?CGUWcE+~XaXr|1d!iLCZ(JHb%8<=2Xyhs#N@S66Q6 zfCm+fYE6OjcJI}zFgM851;c!v5XOQ_U)pU(y?nmeinKew3Xz9Q>ON(dN9H}rVlU{= z?C%;$n09D~v=p{)(1=@zt2Zc9*RpkMg#<`UzrZarQdHvj8iUApiMXc*z3sa}R&p zab!jgyB`Q6yZM|d>Rb4u7I)9FG3&inbU4ygUMV$2lc24Gn z<~3`Qv-zb*92b{=*aaRJ4w{Y19{!#NwB7gewOqyUkv^ggxz&aCutQx^>EF)3t8o(+ z9ug#C^H@Xlr3SdCyE#y7kn96i=d%RLWbR=8R8rY1Qx)TPBHZAbp)HWKE`zO!9_Icg zCKrsnPwFwOPrTS25Lc4c-K)C*HWxTHl}kQY+;k1oR&hVU(jESF}_0R z=lxdk8}n!#eumOyq(@QSOkY}t=KMJ@qFohH@{$vE-6Tra!t#oWIpCzU{vA5{T~kp( z-(PCDFRO4S-b7>0K!=mRkj%oE65>Chf^hC(M{9q)hH;W3#Kz_K!1opL?tMLd#$B6z z$99owLF>uaUtO&3TSx{)uVd})A`9MuqxLTx8Ew!tSTt3`=#ox${*x%lf4v=TR3U7n z!3!vqeO@=F-Uns+uS=`lWEEh^%;Rp}l(9c>K$Umpubw_$``D#BwPws+8uw_(lC>Dt z59N6zTxhpj!92Zf96qi3HfLf-dJ=KLphnz-Jx(^s)PYiqN^#Ao*+elXe)efqk#t*+9p7>7>u68xNTo$#*Fk}Y9rfXdMHqT$Y(2ZD5l&l|*V+Pm zKHRtvQ8~F5Gbv@%uo*^8>ymtd79>}Yn;B?PlrttqxAd=i8jFXI^ldC=2sZ8D^!XY- zEB(Ny_XJRckNtjK{kw24E+39>M?mDkr-Af^?-C6Flsvp&x?Tr?%Rt?~zg245?~j@z zw&>bei6H%4>klG3BQFbosl4FePFhOiwQq!~fp^Grt&fKdDTH*8vq{}Gdv`!9kG=}V zL9Ss6Fvq8j2o&}SC0H^~%aF}DX*hQDr@!^34-pmzPnY?8UVgbU#VT(_guK=Efp#;yVH~T3zjxAwDs)03zd!4E{0J2-2_hSSU)Y~UTh)^JB5OQT?sl~r-s1K zZmS(YJv|MPxipzozEW9zSS>kg{a}=ljg1JR#ON!E!%^)~hhNRMZ@(A;s1D?dI>HW1 zDU3T>V-b8~#}FV9)4S}W3KW*HOqCvDuzc74^{}7x?WSqWKJu$2veC=C@7}A`a;bTp zxeqnJ%@kH!Suu@Y^LI1XN03j*-5x#{>a(!m*Gs3q>{J=v3FLfhH>v?E zMh4SHb3X+C#Vx&vG@|fpb+l$wDH+E(G(QYfpA{L)k=a#~DYxCiLe(KBIXRho_tljy ze~Vh2+|Dq2EfOf8ea3d_Ts>i&?fd+qOiN{w0rMsHkUYeRtI3O);-N$F|Ec270~SYb zB^8w{?^fhC3kJ%Nj}Xx6QeObyg3ncRqD;tIG+jB6O1yUkp62uV@~5R@eeT|+xf;ej zW~-TgVbc|*o7{?Buf7^2`N9MS_O`XP<=(sD&DgRiP9zTo~lYlv#S+$<>wcl^q49gl1s13(CAzy@<%@4ABD)c{s<2R(o z{bl~LUZ|<8Yds7HAGuZiFN?0tp>LSc78)GT62uoZw^!L$ zC0$x|c<<%|>2sMI^uG*-jJOA|%L0hS9TQ66-EjWX*AsSsO#roZ8irG@KvuUp;SR&2 zT)jA3^;#diHAq5cX6AxdUCbEq0eeNiSnH%5_{~{@Sk}QA^AvA95UOTg;kX&d5tQ!W z$z)zXX*Uw0Hj4GKqDIJZTo0Qc#t4->(dbKm@$kf~1=~69$6|~~yjk`cq=CrP8EM3@ zuh(BsO_c|BU@o-KWn(LJ`&2fWB>6($X?0k8kL^2Eh{hw<-vd*$>M#c$5+}~ST|#`w zX$Rl4Yjza2L!zQ}F~>F;i!-)Ml=!@!jca-*W?JL2DQRGEB@TiMVyG8^qqq>OHHO}o z@n=cjnk`zshlVkb`$ks9X!v@ezfuN-y(^5h;&`Wy9t@MC4Wn7XJP@AU65NX0o%A@_3sju zg4sZ<9eCZA&OM1zF90N#{|(K`#1K%Q@)|gm5vz92F9HLKQ&N^3uc`Fc>ZorN^7xPU zp=Sz>vc+RPCiaeL6h$P$6t2Il;+(jaK_k)VDnF7XM96g|=Q%0WXUt zWQ|TCZJBl1oslY7G3u|cufN#h{^BcFt~B(e^V%CGW+WPUySceJMcQdF?molIz%J0{ z%*J!i1sjocovc=zvUsxW-<2A6b8KSoT*=VIerX@oNIz>hcS07JsPufX@|qe!6cU3$ z`KfU@7lV()L3Vu&IfBUv4c#lI(soS)&!!Y?NcG;Fe~wLk0(VNWl$p=%PDi+^mE;Qr zuGLXoqts5{gnzyIW^9ni_a#h6Ac+?etoPo|cj8vY4N+nTs}eteSn);F4iw@7%kwI) zW=yt6XQ}JeG(s zFN~G+WPAD5%2M7MI31ZxSVkI~$OR4~X#G_oko)>L7770>f_MLXWWF zG7G@I`M3A309=T$G7m9Jy8n!zlQxWKKdR0e8gj`mWW2w>7PZDxgH~xy}_A{AKNF47R}&iQKj>GIj4)`0E3Fm{3^Boh_&@@MwWPC7y_ z9RXhQcW&6a`evP6+;WT@nMeT2e z3RpL9b&HN`+%QAjTA$9V$xN%B12tFn#$6_2;w|!(45LV+TjdOK%nt|OO3jt+EF2xt zuxNbD#?fO*uRVI9_Gk;2Ca}m$=i?{Q-lxPd_4U2F_vDOubCAVKnZahoykF0^K!i4`Y-LoEuqj0M#@8E7|Ca(XY{DFhBWiu` zY%jB8jEoX!=&d(Xm3w(&sY*WTs4jMV|F&YmycjLf8p>ozsuK&F6*GG2{(MSTFgk2vh7;m1&ekA zQD3k;reluA3a$E?rIFJz8A&sm0jER5gH?z+UVm=u=|2q~57$Hdk*q6zF&T1mv-4~& zQw!`NLHzowH~A)757cDx8ix;(+Wln@jKWhzP3FC>)ME76TnwS=AZQ79R|y*d%$%ex zYL(Q`R)7WshgNFRamGu@&~U5x3>?b@NtzL{`o%5zXIK%#*IX>4`ehyKW|wPYljM)) zFwS@^GTgJU`$FvRh4L7q{vrfb;syTw9{vKOKWs)y72C|^*nTVlao#_=nxz|>`(B-e zOEz~u`?a%o1_vsIO}F8<230u#8-k0^?9N#V8x5M@vF#9qFBxOYM-PY{Z7O0_W;JXT5d5j^RP?d5lAyn7sn_&<4gPCgx1F-S_I{t z9{cL2(S(Rd+;=og`EyyU2pDRfTN!e)ay$D`EAAXmbCrLA3G+2@m?+g87o&=h&=tlA znbQDI?0)MGs*V!nYD<$tZgQun@zY$D;YisV?(FHY@mSj-b=HKsB>G*<$a3b}FPMhW zbFvlv@`)js()Ji6Oscu{^u%wR7Tb1-zmv7R-bm68p-7=n9sNdt@$9(ca7a~i=8Z(u zZ;&1rHDD0hC;*I0v(*xA`h5|DFP;3BkMtOhW>nQ0iO}xy?{{!Gi#fO@fb^|?^X0UW z_v)MK!wt-X;x*a9lyUt8kK^0#>{vq-=cN{N7N`LEq2skf+|^aA^BXk;I!TV1eWf2( zxCHTLkX3gfN$Sg+8ZpYr1=e-ztWyTlE?%N?W+ukI0c~`lN%*u(k2BA-$G(gz!g-_6 zmN;7^)w(wvM9YscT4~7H&4lIG@>)RIy!-H0g5gO3bJqX5g6J4lbG2lNey+?cZi`bxZ)ho~A;pH8(#n(LsH&xyrpuwvxxHpQ+jO z@M`%zed`$O`-^s$pb7Gpyn(OEdVe-REIJB@v%X^lujWr%0V~(dYQsI1=P1(f0gDBW zAZ=ueyyOD;sE0d2Y954U)9Gj2l3JL-M;d#DUB_4v^``A$PwTS1FD@0x|MQ#mfd5Se zTy|5F0&>J3NTPdhE%BVxdaF#9*;U-ovwf{VJ3kwMdLyul{ax>+r(ETSJ3JS~$=E3! zCR5Q#A+*aO3yXb8s${ADi>Gg;j@GnuL4siG)W)lX+6(-9z*5xI^)ztD5bz<2)q|K%DdOLw<6rf~%^WV@^czKHgYQc*M4fZgO$lw~B5<%zK~{)h z>O=|*e`I)l_qTa4icWu5+pZaVT~JS9a04HvoIJJkL3SgsYu~t2^@A5OTju+Qk8zN3 zH=sN8?Nxc#PIP3fXTJl)l3-2<+~LKqg26XwC9%WrV|$-(mlT7?j7wXMDh&qnO&38) zjJTSj{acWNmGiN-!x}3~!3M0#*Hor{bjp}=qpd{CCA##Np(nn3MKFP*pmBjjvttjw zn2v3l=al-EsSD%9VF_eaudxcCWW_xpRL)q;xmU7A9Q$J0C`oINeDwbvnt$)oHV*Fn z^d!v-kB!oi-5#7BiLp}AYWDW_yV|O5F2m!~I2b#0l&xY~XRCKCz)nf zvYmNmTZnhp(vcIw)Faviys$clo%wfiLCO;;7?QJx)Zi~4K=yB}^lDhGvWliBpevRJ z%BYN;(vg+5CbmG7x$Zh32#dTVsvJ2ci&l#?fBIUC&QSo}IoGht9??NValE+Aq$>=Q zBfAOuro!E_ka72Ee(+nmrn>4g6%yI0xKOr&?m&gdph1aVHFQ#==h~6Bn~8(__f*ai zb=HbQW`ldgpzCkvHX^2gjw$w=!?il)denP$iZ3pHPM6MPmTqDF5Dm@N6?Nej^DNlB zV3r#ut7ZM`(Z|^i=5^dBq&~~#yt=#_EjaEc@Nt~;^?_o1c&}_ z0A!}jn*VO+BEYPIfNr?fH!J@CkZ%tYfQR$o+r`z)r>z2(sO~} zZHoTK9mTFE?WYm&fVbtLXNyR7X5&c=LA_Dm`E zzYF)W&oUMsW9>v;XbO-U>#F0LB4+dH^oyk^vaE%$bum=F++B@7a0NR^Oe zVT1;N{}3AOY#h$>S&?W@8D3m&oiw~|TeNz9er)a6{+7yPDv8nV+Y76&F;JIr-b94I z%p3Yh=3?TMvAd5j?azDk=S3rm=93lfj&j7}ZF9&F#pM<` zAI`{q0Ok8D@2hQ6NLTWf7-&koN5q|29lgwUJ;`)bR+~K!L>fFDdE)(cb}|`i&P_$= zaItQFY{sxmPeZAL1=8xb-P@7?$?FNTf!guAvRQ_qj031?T-w$HxI5>yek81Yl;gKkh8H@ER~4X%MVBkYRjDF2g?N!jJ+S90 z-g%3g9XIxKoZpbar;NcmYwE6cY|7lf{pOYmoFV<1(of$VD`qnb+V=moEa>6 zIxK3?l7s4uU8J(Z{+l%=9JoAwduVlZbO7<~_P+H8Myf;sB}d(zJje`t@S`G0uxcAR zv^w(p?J?40Etr4h4nIVM^cWF=m(#N43}b+ZwSl$=wLHgy)atiy`4QR`BJyDfZ8)+f z)|ZD;4=`7yoKTE?Z7 zF1v0R-GA)~KYZ5Xwl}wyJCS^=)Tt?1e4}F{e~!e}mjj zfL9s-GtuP|h+2(uDw&3O&W`~HVx9mIyC29-#iR`zFJXKLH1WfZoVpd-tN;Nq&?E{0 z!2ocnNl(fgbOJ&(d$_Mwj;a;JmJ5i~+txCp)pkk;qBt@QFD(@#wq!W4?)~~W=oe)A zF3T(*t4K&HPdM8#X{1Gw9F@bPi_Gfm)9X-d!XBGmvbG2jdmaIHF5aFYO?O(hVm^7> z!0S-IEuAw4CCcR}^rZHP%MV---a9dn?wBm8z*Nm?nK-Gg&1N;ls2pn9Sj;OZ1r3G zO!lt9gO5EHXtQPUj){d)1hGCjDOZ?~w2KiqB)g82_Dq$6eWWyH<_$Hp54nn{y+uHFvs=WbP@`9!d z=}!e(4v8uPJU!JTuOd}~tT0%@=LJsXfPch%E(sN^!K=X7KVQ<#@Z~Z8zqEZKn=l~4 z*=@ZRrxpVK za_gR}4h8llaJY0(EwWEO@awmoI%hP-5~^N0J7AUqJsv(2MCaNW*P|1P2BP|K3fqq| z?aco%wmYIjPXiNsjj`{~9&~y)4q5wvlRgm%`*pW1vgDCnt}G!if@K)!vVM_#`MY;> ziQn_~?b{XM2^VTBr*$%nU3nIA(l>k5P2ZA~8vL0Qr|C;o87d}#nhJAsIN$dS3qrgW znqOq-h8}aj@SD#~c3}Df!IBL0ruj#|Z;C|WeW0egU~A0F_A^u!wz~#ShEhQWSCnLM z1XaQF>Wv*}J)UX#Cp{}BbGEKwXX0{&XvEnOa(Xa($&w|G{JM?$FQZjeD)K(eWl0U& zA1(q5pOd2ULke3tAo(bAHLlyBe4R=&JeZJy^jHN z@K!6Fre{MpA}QNVj~F#SCW(HK<*q{P$rLqjx)ST@RM}?B0Jb$)yx7Qk=$<98uWxH_ ztzyU))s6%9wL~L{bsM1KpJUFAS)ri+$QS>Z_ua@FcOC(5Z+f%AG3qML3;}!1*X@9s zaVBO>SBd=Cnbl#3eIh>U!$)eZkKZAGY_|Sm?pSI=n-_d!xovV8D#&qjPMg~Qjd;h_M@@%!3 z(p0lIlXrhCJh>V3SKi?WH)riaoF&|`(mhhWOe-n9lN@Nn{CHM=0iM8C3LPRp@JQs< zH<`fIv49|h_`zjc@9lY%1<_S8iKm@)iGM^x71I|&k{U6{_ z7rHVfj=kY03b>IZ;em2QjEn?1#FcmEP~|%V>3QSPZ{F-K=0n0J_3gF?a^4jx-)*l! z_43fM%3789uCBMH?i>Wm>oADuYQ*Kz?XNAUHFp|R5&P{2QA#Xx_ z>A=nZ!7mq+Nhgz@vq7;b>3&3zqnOZQ&64D8dWs?3?4Eq3K z-AZZDc=p+2r9nXqzF3lX`c4X0e#C-`f?ZwO#Elnl^)AHR**?ugLq&hSf2w*8s}`C! zAy>@@uf4YHrAb8KZUW0*4JLyCRJ-ki+r2cW0kB)<+V?YW_=c_}+;7Zg8}{YIn~5qT zV=^y0C877@xb-zy>t{$>ft`Cr`pvy@ax*k^4{vT;Y$(Jvf9|2LO(?wQ-xfWnwguHl zXn6%*5TD*TAcBTP0aMXGJ6IaFo3&buHvZ64_el9=6yy+Y|E$Sbe+3)&6Vt}Mcs#>t37gUOImJan!Dq~GncOJjQS)`>0Bpr)oy6%Hpqf^V9zKEZB`SN8V(E&6L z8GrI45#m!Vs)f)a6bksr`?w%ueo1Mm0H&#)#vLuFZ^XVRrI`&4hHXclON(i6Li&;Q zco=@oC2Z7o{0D+DJa&JWD?vCo_VZ|I>m%p9AI`pdMT-JtvVm3mTH z7%aBf$(6N$fD??2kl$OsQss_J-~-F?AFM{c$?U5g+002~*bC4H#%hMfpgiic5?9`N z{V~qyF+k^Z~iXP|2{|UtlO4vqOh;OM)5dw#Ft0= z@$=!%N~6X^QT2a)7}lhunNsqdrW@FskEx0{pS57%aIv<*2OH*cmpwfg)b0*PW8q7m z2}YxK$1YXX7gSS}Oky4}?LkplyC$LcT^gGDle9RkErc-Oi;#siwoT1aGTXxWoShU) zxgO2uEUye9!@j{8!y;FtE)#?c(d^z3L4wp(^@0cHbIAxiT$4q$Cw0PB zgZtvRI-`1Ydlpe^_k*eI7GDQ~-E|ZzZIhF^n9CK8dp0aKdx z#)6c3^K)`BCol*rL+9DKZ<~(D&pmk_0~w_n0i5qYWfcv3PalGE=}-oLzb~@fYUiBS z7;e58yp>m3k7_oDT;WkM?j?FJ^fY6QWDh$6pOQegOjM@C5<=`puVhlN{T=T9~`OHqWVJ(Z=NF6}q&Kos#fVsGHP-NHOBs+!JNq-Qvz z{6dRQBh$~`FQ+#;uTf~rn}hR9UcH(DLX`Nr+`}K`+twXw@HN^3NSKviVF!UYib~-= z0?%@PC4;tg-kQE~{CeyS-;FvdORh9#+u#F6F2!5rt3K4qjy-e`EU3)OIyAQj)VCFl zcUn`biG1DE`P1^RlIdKcE&g1sA{$yo8fFYam{OOQ{(*j{{5VT$tfTLLQA?Gt`zh*s zWHQ^s4c%Br8Yx3)+n3#O`ZWt)2W96d)HM#tR=M5j@?LDhA<>Bu$Z=fCpqX?n-Pj zywk_G_7edYj;Ss&&+1u!JVc87dDl_=<_wyjc}Ivyfi8IagVLc}Nw~xWuW6@h8cPyI z0U?BR1;6q1edeMC4+3fqsJ*`8uJx0GPa{g?KFam^dVFDm?2AV)!SI}wYb;Ufa{V1; zqEn3mcI}(F@D!t%)CAhRcOvA*Y3+wv1%UF|Ac+G5DMd*!7s^t%zk4v^$l0Q~F)Mx@ zYct{@RA{%^Hg>QXh6}IbKukywAD);l;UQ+p_eV-D7qxoo^F7`|Cw>M&0owl$Klwt( zw*eaD11M&VYoh!E2?IeUuyh^*j#GV zU+X-1^5hb?Dv=#m$K#@|(JOQ2ww}X65;Wp0yNVxxpD?diYw57KJQyX?A$G2nk+T2q zy9@8^`cOa3DF~qRx}KIq(i6Hbe`el4I#k&S?1VX`wV;gc#cU4K$-v19c@8ch4h|(6 z86&&eKk+mP*bjgQ-hL1!UH~aaWs$;AF3eqviscgzyG|1RKhapM7k<7syKgCRgAI4f zqQ(6k1bU&_-*f-4uJFD1ZNVWTmPR^5$QC#@*%MS@B!?eDJ2Nd(9Gw*RAVPfs^(Upr z$Pg2v-Q?yCT;U4^ne8%l7+JRu<4rHrn%o~2Kclf@!_rrLeKC!#1=u6Z$hTXlr$OlkM%!&Rm;vh%Z^$$tYh}LzJv&&SFwva&_$APGOl7+Y#)T z&jsbjtqh-3t;Aieq~@2Ms?fG_A3M`PU9bx0TcvtJ2m4or%GkbtN~tRh-@XdJ;7tzw z!F^4^52SK_Jhgn)yvPT1aBC`_XV{d9Q+v8On_k?DVumr`g zX@0jc3qbBxV(D_>!EBe)reF~Kyj+ySulSoGiVXeAbIVBf{h}O>H9VM}P{m$DibM(& z9uA}GDCB(K0m;pTR`Yn}TZYUE9enXt<@_%YQnU{9QG zZ(L+Xc?u{vyGBcJ$5*~TAFm?#Jim?wZf0tSJ>}~IU|?~8|eg|VF6*` zVI~HzOMe0{^obZ!!=FcSOYTFdG{4sE>({wnI~#As#I(l00vAOoV!KknYHBZ+ya6`M z2ytdYxqcsMKvmWr>^qnVul#4=qA2Eug|OP{gsiMRPTfugT1J8I?{~^pkDSDLw07cU zMjZddhAqc`pnbG)?tr<)z}{AVz(q>-x8eSlg)N`;+8i~Ay9B`0d$~}Fb^`Zr!m^0t z9|5+W!K&GQtlHPHcP5v^%uK$b%a^Tk`^pa&|Fkg&fCGIm5sR~)- zFnQ(Ii`MaKT^AP{Vw7#?`dD2w)hS@{lxvn$D5aa-iyUx`a*#&E| z0@x;eQ%;#in^yP~SJRvVg7qEBy(Y!*rZgT>^&kXg=xcJ(F_o*4j%=9iql^8Uh13F->h2$xiIiTvS@ z6p${XWryqUPXUL?O5z|S9NqFEX=#=B7CIj=)24UePZ$BKfdKW8r5Pb*;9)DoXT6d% zkQ)p*&?g(8I~}bblo;`1^sgQRGqGjt<==7PPjLeHrq{S$53TF_{?@nV=iS*q*Z*vf zkQ2YOGkMpabjN`awvQ5>CH7Dh(7l#yPyE0z5keF;$R7p?=0e`-fm_vBNm%C3WW;D< z^kv8+IXeTB^Nm9S0xt#Z6+DeY1KCh;%Q2UbwJ;BLC zUc_`d_nL{TU49-d1=R~mO#Ukv9KDJ>vYuH`1wgVX{YHGX?FzzflQd$q1)BtFV}JTe z#4J%`(aG}1<7SJ6%KZ7-Ey+?O(KuT1j84fwxbf1!vt@n?NM}ErG(FohLs2%Dj?RrF_OrSJx_3(MP4M}q zQewh0I@GHklMMOBMFgzlp0w!0<`8wP!;$rS(C%!TVjc|QMyUPQAtfU3JHY-j#Ti%L zR=x0i7pUa@c8uD*Tw-Y~YNdK`b|1N3!oU_?ay?+bOa@7NPPmNDt%_C8PoR z0dS4otD}0~fw!W51P8u;wA~CsCD24t9IQ34q|8b&s5b}f@?6~nakxaf& zN8uE3_`%d{OYce-vr~hwOgRd>-Y5NAH@gWdKuVs|6_-4nc2jqD~Idn%xNB}bZ#}4)#Y|Y5VHy95ExJC5O4aS+|EWr*Lak*Lc&RLRzfA>6**4F;IVA&lF#SFFle1j=Qlh~;gs z(o`dB6x>EI?RcJ_kbqL-+ftA6U+_S>0-oWI3ug8Dv9ElAt=KE8i*^r3Oxk!rN94cT zNsx_Af>~_Zf={qK$d2>Z2(tV0(qNPV_E4? z$OzHFg4FD@nKTgoaJ)2->||VjPZtgQcG$k__4&1*PE(GUm;{=Z(D7CvEerFXzf?QG zgz5GJppa5445P3wd#GdUd4VqEPUAf&(P_tjs<1q$#s>hpUD^xOqR$b z_uYy)EG0N;SU+`(mdesCirA3z(s(bJIie8zj-M`N`D8KXZ#-JIH}9WglHugDq;`iT zeMdjnmk*qeGpMUI?s#>wuK@1f$$0-_>)}m-G$WDud4sN9d1G!R%xs7n(W zw{+8P9}0wriY{gGmsswFL|kz^b-MEbuoLoHA>4Ck(Z}Vq6&CU^;Ve>sw*Ri9r=wti z2aU{GQZ^jwTHwUepEx3IP)hj zq4=N2t2)Y?0Kxttsv9=6j~%Iler3HP=Kz-MCT=gMWlN`KbW&2%{XgWs-zB~OipPEL zMC7JYVjrZfVkX4{JGDA!L+T3 zU*M0q8MU&$wu;d>ZX%=+CCPs(36@0WcICc|Ve!$izAQ5#P)qDYhzpPO@NtHG``9!P z(uGUJnQ;0Qto}8H$ttOeZTKo`&j!I3$N#dal+46sGNf8vQ(j+WW6n6DI9{dN-;Nfn$03B z$3al^Wp>{^*M}?RBWi(N6t8K%_7SJxrI)W%&zM}P6Cw~6~5z~_d9nX4uVqt-=_ z*8}KKj<~#oX$Gi`gl)t0ST4CiznLg@0U9Wm@x z{9SlXPxu#;nh>&IFL-W3eYN1>4Nuu=v-`gn?DYW^Yo8}uhI0ynqZ!n?VwHD;4;?1B zmz%KneERrG*!3V{#&ZEurjSWg!oGa>CtOyrx2870_Qa#=w%cBpBH5OTxU>R2>WZ)* zx~Q0$>&R*$^3d_mBpemDM`g7PlE8IIH>k_y9m+7OT{bUEfuP&{$l2ysp196A47}cc z$ReUzPdl=I^}EjpmO*;5{NBc{oc`V~a{Z0{Pg>rs2>!9-m3^JFbeqbLHUU$)YcDEa zRGZ-Z2zzoheS3{Q*Ntn}t||U#;(kN^CY}~i#G#%)ha7cD{zQHuI>jODPt;SA(GIyg z{`J6$G8z%d);7Kq8~kUq&WTAdq8Oowy$5;Q&*Z}Ic_t0;TG5zISl1(w;Fe3airO=n zMgLSO#oljf&99t%6MM{+3+~gNI0IX;HLsmUx=Xre&~G{ncI`%q!Pv?3eC@u_;wajK z73(1n%-XmGA#vwgbxHO!jbQe{<)Cf0{mqHOpIs|6CM}e{x!mftl6~hti~l;nvtfg9 zi?HyLkcVSOb6+_47w`QG!tSeIbNxB{togj#r}<8w{`2*z+mDt%9J^u0pQl$$6P`0& z*zDpZnK?Z{#~QQijyzFmiv1M(F*drd#^z&aQ+k`8ORBua#r~cFa;NbwY!UH~cPxg= zS;ixN;u@1%=R4g-BrKK4SG^0}=exS6P1dYacA9qZW=x8EUvJM=U{i%h$}giw!Tias z5-;PnOtr)r;s$rC;P%*WW|eBP_?{+t#L*YNuMxT>I(H{!pcdB}1=#d?Yzj z_deAfSgWt&H78F9Q**mkT6XD=YfA>`9|a~Wh8C$%`*nd_-(lLv(p^gdh0$P&{ikNy zEo_!axt||#=o$PS=DD3Sjh4@oYK!Mcg_kc17cbMwa`9)ixiW)+9|`5;-y$Yx5Fzr)*K9R z{6c@$(7WPYnVJhu&Gd~Y|9q5oR$!9@u-laH$86$ie){vT{HwGUSu#H8%}v3c`|IL% z!D&NDxL0;9@=@{;PDvA}XhC1#y+!GHESRzfBmGe$2v`RFPH!%!+hHut&9YiFq=SZi zpa27R@rctWDa&EK!$>{kE{g`G)vVm7L4YXwrjw z205M9`zOa1B~O+p4Qjk@ixLl_Ng^sgkJx8kvBs|Ds+-hWz&0n>-adfyT&g5o^KJ!% z`R-N=(< zG)vMy%yl^^ycC51SytDgtCqLJrwT+O?NJ$tngZsqOT|^X{LV2N0*Ug=bc}I6F!9BZf#+{!>oghlif1nSR7% zhF!(pFXTxly*|6Yx2<4|)T&p242)Kk|G!W$6IuhX!3;pbT%%E$>g?Hx0-A!5w{`<^=08!@i3dI6*%1NO+dIc~A`4MH z2CI3qmOLqvFBq~Y>S*SHOfgJxpD?r9vXHF0v) zgkbT{Me!G-tgv(}1s4H^u-of8m!4K*bWV3S)wI3fVXQ)e#v@4dpw7{0AjE6SeZoh~ z&`Uoe`eEIuA+U%Ma+u3)Olq75Z*YCpok@q;rTc4F9&$!|0Ltl+O^PB7EwlW7LbH{5Zw8agic|2V6oGaJJ!_|iH0YTS^=xY10_ z2K?I4;%E7)x2Da76=P&KHmM$9QZ>sL6`|Y%bKAtq=$kk9!||=~cr)t?@(yN*MPG=X zQ=X*O>fFWN;Jcb(y_t0S21ljNmd|AbcF6E}xtQfhnSKe&Pt>pRWpY8%{eg<2u; z5Sm<$x5MkAUou9I4t0Ge_xkVu?SsDgFbF;e)T?ch1*)#DG*N+D*I(p9pK0e6of#o~ zth*o#iTyiU#ruF<`1y#^nqJ-()JDPolTNZ{A z@`BY;7E$Rg(Vei!!UsEy25ztd6i`2#XEKiM4_&O3f*DbSAf$1tTnlMGlNROJ6E5C6 z%cu4fnLx9TjQ2_82POe0)Y-q0oFqT8OQ6sgILHwUdW|TN>;EQKK%SyoXFDHxW&K#( zK~xs@Y=@h|t{BelkOd@~8EaxL@~>s7;;zL`CJkgJ9$z}6mj(p5_LjT4X>Q<(x@{Hx zIm1LXE9;-Jk5uqDUJ<#tiErnA2!H7%mAS6BuNG777O(TmCfRk#3@#F1h^mI0OWLA{ z+n-uvXLf$R?=r(~0iabK%+5+H4nN#akq-g#X z-HG6Qj=3{Y;3(WQ_CX8gAG5gTY#^7{z~(x|NZ%{k8`dbGh$)xbAVg@DrLLy0x>b z`{0egl4Q=t<*_weT$ve7TU2s;VLlSq)u&S70td(GdRL;a1)!T)*`@M&ll-;XTZEjj zU)dgh$gGZ8lSo`TScVw8a(!>*Dtsby!(Ue8_V?nM1;?}IiFyeKSsToPtLbDIS=8Ym zHUDFZkkIMm0&ZG!%S}@BeVsr-AqlBfQEXFJ^pTA_fr;KgU#K!C!Fc$7V@aF>PrYRC zx33eA;^dJ9)dewuAZm!kSUE3>YgUOM8Z=?PxB3x-CS&FFThP{chHXOfm(b5W7%y>I z#ufYU0ldAw&RT1`!|VrQcznLuKh@3oQ7eXJnaR8X&|2#J8Hb^cU%vFz^#>WO;3a}~ z&kDm-%bJe?S>eyEFqrk9s^-$?1cJYxv87K_i}NC^*-GLi265eELQovdJ$m{TZxyI27llqLc0Q*w)m-?$!h5GJ#ym-s^{12 zRih2eY7w~neR;5CPFl=Vo6t-0rch5yIrt~NJvrU-Ve@{;=9}$}a{ba|)nIs~2B(kZ zy3sZVcBIpqX2(gIH_g5cf%j!+h4-DAqP84FK$w9&ia``gx8m^^cVt6z0I;=C!~MTXIN`KfYb05XFv7WPXD@}h8}nAPrFTuTvVF< zW=C}D@D|&%E8J` z+FPR2GjI=WMOgB($*2wtkVlCbmhdte~V?R818)N@yRS(Abg z_@O+`fKumAMUF#TMOgVZg7kc+l|taH8QjnWeb&sNN4s-E zu4sEg7~kjOb>DVSFji=B@y}dIXyMx z|D}_unlNJ8LO`$@>>X*yRem#zN?d1Cig#KI&R^+dULHU-;8j%VsRwRalR@C^{#bhMjoM#F;kJ-+KsTP zu3H~YZ2`fBKeX#7`GxteFly+nT@l5btkGw7k27zJTbqLI<8}5KgZ*cC@bj$f>n_iE zaP8DAKXt3Pn_)TkV@yQbY5LB=eh1vxmTF&mn<9eGQ+nXE1om9fhwi|kbu%&_mOPeb z^B_MD=Ba7}Cu%i{zGlDlqDHss=D%21#Nei8it`45<@4qBiE$0bIzQa-Jm3CEHTuNl z&iAT1f;GA;!jzo=SzO1^hobB8TlcO+U`<-h^b20!)F!6-=3KfqU)~Z(uv01x{ZUEW z4BlwVbO=I80#(<7=MgJ04rmc(jQVta{HN+$`13()INH5hL_B|=pv9t>vOq~{TY<@) zsb3v{d^5@PrC3IT+hqOIH29#Wn+9Y6UvRyVUEW3QOnYux=F`_D^<>u20lx+61Y9UzEX(N580gQKs9GMu85y2w5mmL3xb_sVLB zi%C4>ba&yHp~@~KpEpz~J{<+2^(T9{muTg8>e*F>S^(0AnAZ*hKW%rAqiwbd~$WP-4A6&ICV?;l?&PkV?YpykC>a9aeMCY_-5WQPSY zsz<*TS8%rFQxZDyR?JBIW-)xhP)%TT~*|WzZoGdJj7t9 zPA>XbiyHM=CdNFIb(K4N7Uz$77Y$vozPrdlMf#&&+*np2)rg(v+P|6IO92dTD0Sdv znTnSk_+HT&PNEYQ9?wPYJy-pJQgC!U0(Y78#_s;3U@&RrV9||yz{b)WUd|o_VKTMl zTdLFGax*Rg-{Wt2fV3u7TcqmEIVr`03Dn{l-K7@<&ISS; zNqLMMHlirlfdr4^tgipE znm^%W`U6UIh=GNC!0LdWeZ}5WWOelxmz0ic)FCH5cfu)0Fi-M^21}rBE^K}-@I=w) zwQ5IG`_1XCU-!L;a^oX6B+!QwDnFsoQWqM`SGwVc#h~3FT`u_u8XB)IRIx1t;TjGB zZ`+Pr!yaCg_viNlx%2!InM)g0>~OChg;Z=mlDNfgVV9pyqr)${E-3n%Rn_(|#~z2q zz$%XC%{lh#b{88z1^D@&B6xp22%cZZ9+Rkwliacf_{Xhgt8nXIE<_F>5b zk`?G_Li)HwZ~4nM{ncCLMSTbCda-n?qx*Mnd|*8WcC-XWclPIFnABWny%#F-GBroF zHT-dtBNZ@oo{|lIzO7z8)t~GGfI<}CEpPC<;SweH)MsZD*#!+g^A>jyAOM14idIDw zMuNqV+g)O#WpQhhPzI{?t4sIhbr&XK67Xqw<{8b&jE?TE`Ko&MP|wD3GTt?JO5zN1 zI`$#c{aT+unL&~;Qy?!8N_U|n2DcAvJ7E`;m$7Pn7x6ER|C~I*cqg-c)~)ajP8PwY z@x`(|n^0Mr>6v!F6J~ZctW&gM$9I$wGjJFRr4`n)+vnc5@a&IfopT$?35>0oK*;W6 zr0700EuQ7^wG*X>JjH)kx+#Rw5{;pC4le`%WM7-bcmQdzS5>>;PvWQ6ASe{@+$ zzuR~+`4Kvz6zp=5D}4;c4cmIGKQU_6JC*YB#wyJAAZq|OT9M8jA745=#kke}54chX z;9M%NS+AP0A5_BWi#|BAUp;dTe(_5hNGBP&Up>q`&w)AA_^ORu+sRwhBR;Zt0TnS2 z4-`iih8H$t(;3m2W!a4@@5CK)I?<%d;*=j0i^ssqTYgS_ec>NJ{YYs)^A~iVPpN$J z+aX*Nf1y?h^Ddmr8*TLxAAS@0ZBgy|@N6Ct{Qr79!P07?;U(H~7~UEhoWII5o$D@;7$-2V zuayOcCIJ7|Fv^+uKK|D7iSlzg)vn3#RJ{=CUl|^@r>9KED#qGr|9CwGC?)w({6$|h z2;*T@AI!`1kR4eURqbTQ@28Le)ta|2U~@q+m)${tRKDm)# zjX$|uXj9dGPnqj@Q=1K<*_)p^QDA&qq3uG^zXDvgG)8|2lHGL>xNr2g#V9YQ6QNR; ziJs(==GigY$&x0b}SN>5+a?SRU5(li!eB(`G@w(EuHeG%gi^JPTDJI3i}?L$==XB*LUNfWf? zBrTK{-S;7j*V(&0<;4sxkTQ2;xXhjPsu3fc99?~9iB^2dayT(XZzw7Lo54gV=jS$= z!r9H@_zF(8!=5;e3!dC2)H{(L3E%RZ#T7vt^u&|H{?=8DbVhH*VOePIF2H5ikzzS? zSnVM6_d^=1)vbM;!8ZwzT6&R^nlGkhps#4V;v!O7Y5qxO+$n!~MaM^Mjs9++qad{{ zJjbIrHQD5a;SGjUc6rmV&fEy*K672i3pwbCGRHqvBYvM{*;6Fs$|C^+7DB$rgp z5mntocX_1k{i6M4;YE~y@RKy+%+u7X8(0JF;C`}6^kkLU?!~Wa=Nbe_vYMBh#~%f- zNMODHxy-igo-(cZPDpllp_>NEq;5ZU_{IslO&+R@mk;KPM+&T&Vy+eH-cJTSvt%6a z0~0gV(@%dk7ZqlVEqb;YzH?=sH*Xu3Is%fSLajbZlTEJ-$-@FHYGGIm!OM(UT;pWF z@1cxa+9^Ex5)}p1FYvq|c2j{bxtN+W$>fd{_cUz0N_1)V%iTKfU*>oPVkM(Y7Sl=^ zM{zYZ_LIwVQ~4O3?#k@POEO9eZ^Lo5rAkr9*0y8I-Yx+(O8~b*$IA1j92>ZC=T2cm2Z zuE$I;>4_4)+s6r&Z{<@n9PF5m`qKW^)Vf%w#+r!6QYsehUU%Slh>5Cr{ zfDhJ^1mNYGf>X0yuGajSW}*;$v=n+I?Ko#t`nL}`DcW|f3}!<$bYC*9K|GL1os_80 z4)O!W!Pm5i(>t)Yn4|az^uTLUm~#u?Y7NnYN1fMqxe|707ghxwmo|Kv`g9Z+k_us+ zif+x*E&Ex+LNH!O@=0oTM-0{3LFL!PG4V;|YEHPK@ACOLt{IuJF9!^Yy>BqmE5+5d z;uhTsusjR*T`325h)x3;QIA`%4AowxsVp425ImJhzup zKhqc74;r^2-Pa02(PTSCpI#BApiEXsJ0Qgv4yBKeJc4XtyWHL$_RjOB(dMIP9G^e5 z^NhLRlPoJu&M5&a0+An+Ze-` zDA0CyN&w2%weSYW$PWt>-d(jd{m~rsfK;S6HxKLhS~BjJ1^Pb3Yw>0 zspJV5VNKjiHshX^vc0DQ?30Lb?`8oIb<{V{s4HP@#gO-?Hd6x+5KKx?AC@J<(Bb?L)LWF6*bzc;XIDM_9i<8M>(WNsn*upNK z433CK)Y$>!!Gp#8saJk}(H5oyul9E?YF8=#%toDqnYdmOYV4|CMlXexUx!?^RLdR2 z0VALLW@d3YeU3s4CAL%pDc=wAPps_+vcKj#V^#6ICr;o=T+CAhYoY+`TfBC<4R-eY zA7^AXSI0BiXOLD@Sqb0L@pu!5ZlvsrUv&GY4bhMpX}l!AI!DrP=_~#lwkpZ~IM9OF z@&0yTX1VWiZ6H`hi$Y`p29P>-w`h_Z24{o}jqA)|qZ4-?mFJ<}uAKHTiOtxv zQq5g7k*l%G|L?m31H00k`?(?@)u7`wO$l$xr=NU^T5>j&pto!dn%eAC=YLbwk$qWE zfVtBv6VY*i`%U5T{^=?0F6QNW_A$14I?=lg>YgGMmaIy(3YJk3?DR8GKM)re+BX=0 zXi}F$;`Av#(&2Mfl081F)Z>`vHeP2ma)?BycTF~d!cxN zYj4!?Ccyf)Ob{K8yh+!DFHe z%hqve_epV{Hz1y0?0@Iq9sm^P2uhl}|P;XGV0Hi5}9^Q4oAW-?|!5 zt3k7Elk;=P2t6LiK#B9AHmg% zM#6#}BRd3Iwu4l~chjWWJW&xy&e(jvlmibG)jwLHZF96Gq2RWcQ+HcZ7fox5iU=Y% zqK9J9a`5FpjJcBsn`PlgA{qTXC|l%}{_?G+0~Y+?9)WngIX!K0R)17fcTnD|rcpUn z+I%IRv*l#tq^CU>4L;O^8ew`AU(ZSLU{>nllmm3ofAO85=JNKe_JvI;OXfyzcXSi_ zCG88KHvUle;NLW|l~K7A$&r{{$lIA#Me~%YHGC;Hs^U_ZmnxrejLsF64gJOdC}};* zw6d})npemU-svHt+$zR0Zm(2%+N-obc43_gFz>re&NT0fo2HTMn@(h5!u$=XfX)GH zC2r-r*#;vkH_hY2w0KyRkbx0ds}{3Ug<@}-yP;CV|wf;uC z42Ss!vHpK{+AT=)Vb-5ASv2_ZOck2`@$ymv$Db33-K6iB$TS1Zt2S$W@8~o+5H65g ztLLnLe5>mukkI@RSQ&3dPwuh#>&Ve%qf7ng~zgHILM{_=!Wm`6!w<@moI`dl* z%NwlmQx}q>qiBlXKvi`xY6U|0RSe71e_5{D(TSia(cRgqlhPypc;jv3VegLp$MJQH zCtw$f*I%_@OUz0#@r$R;R&1URkb!f8-@9Dc*J|49P7;(Z)9IU-$ zH3IB|A8CF=0Eo?KvUfcU2H69&1#OnR!QFBWO~075%NlVGX8g%ktGzz9cIApa%)dOaM#n5N`>YXK(oP zuTp*9&HI0OXPiw1%>?}8B+l8y^9?=+V>2!{jrK29toiTse=*#6;ngX3nu@PROFK*- zW?{_aN|9KN_lNs9RL+XZqd41St2$XV(_)Y9BLDHVN*2>8&a=cg_kq=W3|Y68R-;8K z=R~|0IfNyDKv=cS8}zC?iJ(X+)WymQTon6Y9OH1Rsyf;1idz->F1waH#Sc@Pa{dhK zhdmhYWf#Z(ZXe&|h}_Nh3~ zME-WE@)%yeayB*n;GKf7ZxZbJk`0}TZNR>md;Zyw5u2FuYY;1Sgv^6woa~BfYQW>u zx%Hv;)eIU5h50v)x+j&LY=Y1K7@nmLJmtWHW=)4muvq$S*cJV0{e5lywVQ65RIK#h4c4#K)f+=p|6iluzfNq(ah$G2-w#=w z8{9L>Z@6+`=C&VlADveRv891P&Ox(e3YyYqVEOd`-O+u(`P@-{_}nTY^#Ph9)%CUH zwD$eIglnaFb3f`Nx)^MW48T4F3i~Y8s;M#I@0u_?+#8p9C{6K zLc$Y$Ty1fZ{X~A)Qeh5Dc602blv5dcZ#u=#dF7SS)N-;-eTHN@UBtA07G`#Ok_lep zEmDEPa3ja0Ua+^niKcor6_3Nz$YRTh4@F*Q0|X&fapJA=&|mk|P{jNH4L$G0;`iQ> z;fb_IJMmn~ZQMuHU!cj;$ijr6^MCc>2M_~dm9sg%RLHr1T@?d71`F)8vT4nZ|J;u&r`+n0jbvqb_9ZAhHni@DKf0ckC6T+@l> zJe7dgLCR4~FFJA}7bfRY8Owyl=hl5}RZQP=iG2=!-C$U=%>?>Piy5lLOz~t{LY)7u zP(1`m;Fzw}C}v5$MSd5}InHHTM)~Xim|1Er5T)%DT@`fG0=Y9_p9t-+6U5nH^D zSD|Lo10^@=(Kb|sb@}An9q(KSiaRB*EoOsw;z})q}6}_ zB0-WJp4|{(G#;+6;_&5p_*P233VQensoqfx(O#Y8Afw`~x@U9<_J9x(mmtR@`9}$=QvysvSBqmK_zmNf|$!D5FEG0hxGlCP;n9c8&T! zXH=BDY{7dlKVL}wS=M{_jcquBd3lNQ=|fJ-f6~ZpvaEjKK%;g+xzbjv5(vq`39>G_ z(BMMJIF^5pS)_QW{)#gnTY26}vOCK|A#EV0MrtDabeGYd&Vl;QW1BVwxcP9>h*G5x zbuIzv;HJokWyX5H{x9&JY@;`gjM@y(N~Ru2FcLU(k{&t^IJ5 znfe$6)d^G}+&wc34eizMy;ZHxSEIgTxj})nYEqgBlLQ=6T0i}_yvdFEq3lk@znd3D$V9Ce0Ftn^4eVcdw8OPvfo_Z3i22XK|IiRYw*V8h(GEd z8}wP9@cB61)CyoDMoMlC>m21V2&{0{n)5>vrag3CcKBq+PIiq|@QVfSB{>x^V{g z?Sqb2x*)UV_T&1GH{)Wvj*S_e3<~{PP|19FzOyTr!PJ8DNyvgXQu1}ZVE|RYzhF9I z8SM*&D<3$UZ%ZXO>f!*6Mqm5J~ufV78 z2wKGR1?S;vxh*bQcdS1aJ}m4%7hd@a4x!!#7PEwPJdBg@iyNcIa2~T{2iLjLsl}kS z$EJUb?pXgtfJ;feR8=^0JOHGf9#AyNH7Zl>MZ-47_$|nCrJN$B9Aiq>sF_-ghgOKQ z*1!J1)TT>%&}AJT{;#rFU|YzwH=V@hBW5EN`zg0^p6*~OH!+h$A8wa`$vnAxS)Wga zqUqqvR~cvtgrq?XJ}IjHCvG*V4E@Ng^`T3K8Y7%9Ht++@CoG<{owRQ(ts?cR z$cJ+lo-R_ZJJf^yMc!RsfK!XA$Y+KJ0u`Y0Pw>DBkV`FSkeYNs)!tJx>rum>L;E3l zmyLyXmJIMfpQ;!0csl+s+h7^qgU2<~9h_%4M=wU0^WF;8_uRwu+*myl$W)szipu+O zalXRbtTwR6`nD9q_eqizRjWVe{*QmdAsD(BlxKG)2kfWD}P?hrs3huZuIEW;lk&Ca|vy?&VZQa&sQnTCig2EB#=Z zQ04C=>FCGAR{?^Hi^FtUdZ-eDotk7cZ_eIE+ATX}I!Xh|%l~Pku+2&$QfpF*R*8cw zi=2O9seXj_SkBA;?FYs+ycz!aCNnsnEsiFv(_zk|d*5Ur(GxhJBv_^TzFlBi9Sl5K z;yClfr;9t$Z$nd+{Qm31)de9Mr6{nwB3CXfEK0B?@bT_KVB&yFj8&RKuHC0@}{ zo?x&$Wx}hul62&!i=98&9L^p2$9)mmFJ~%1@lJG5TGJGIwEfvuo7la0=OkcxnU<~l zvRVfk2GV_i>{9NK^`DD9f*DSQyqL*1_S@Bt$D{Gf9@7~l6Z4MOlmOA`AJ)hzj6RE1 zeNScxLhJgW7xGGMi@@MIf3_@S)|i{rO9I*AI)IW3ED73g(SUsh!UzQ29MNq^yXl&QkV}s^ z{Z6GXYhC+$Nr5NCx*GLrWH`1I|9TE%A>2cTd!^W;`mn5M72f)mqQiNDb38yirvu!2 zm|Y2`iM)C_g$MEFbdoTerB8%aymW^$ej<&YMP%wuUA{YQX^lY-IV;Kj!klv^NHYBi z1;&%u-~2hH@2%ew)^I+zel&@LX-bs&ag6Aqw9v2X0127F>M}2tQ+Jg^KSHuwpD#V4 zB;!BJl<^Dg@fEG*);F_P)0>IqojT*(Dbc%29Pf~jFK!&bbbXu%RW{~>b zt_G!>0Qey<4EICFL99^EQRiCcvY(Ta?XiCt^pG{tk5+X=hWlb(&? zbSwFo_z0;^z@b!KWBkif>N|~6S_?rl)F+c~H(SBnDBxwCx|P+^IR5{7pK#~I+q-rz zUSRO47-5K48Xq53ai&q^UglQG?^H{ZNv1CM8VKeW-lB1o3zULp5M!9s63^h1VxEcU zL=_G)DiOFs)I>^?-3a^3{q}>gCEjg=?8t9yW}Y@R*7;W-(BV`C74jj_@m&y$Z9{PQ zf(c01pRFO(2+V_(AdAmT1=nH5q1=%hTF>oX_1mB4grUJP%yx6j2J=;Tso|6P)~V@m zVrIqlTreH!%vFA)jFpCZ3u{x`ljfcg_u>we3hJg3r=$NnV^^UU8TKNcjcqdA=tX|G zTQxKxdM6V_V8Pu#W(UaF7m7yQ->qYzK0XQ_OVZ%529li>y-S{{FNW+4INP4R+y9?F zhA3Zfahr;$a#q6i$73EE#U0-~9atrV8<8eJ;hb#~Cwt2!#Fo zrivpo%QfUulIuM(0~%Dg{LC~8IJ~9PY)%z=n{PpK^nh>B8lrz}_|s&VcI3CuVQizq zsr0bspMx9mUj+?AIF%)HfTMz0=Yi-~L1K3%U+?|m>3WuWaT6vC>4|m-9T=O{C(T zwsto9-hu~qoM7K6|6Zo;G(OCG=RIxqzY+x9M*rF$W;&cN-^@eyTy(#lMPsx_pD%={ zTo|7|38o(0`xAJ&gZ)rqd3=F6baBAx8MO=7*Zk4N%0q9V*32>X1(u6Mg;Fpq(&nL61BryWBHjI5fJm%a3C-6AZ0T)+s z?typnmSThkz3)tH7SgPAT%kc(H*W=L<9bar5ZM_p1qiWrr!C|cEN~V?>|^0tbt3An zN^e6ii={*qwsLmt33UfXh6aR*J#dn#cEUlLTg*%HwKzfn@}i(S{Y?hsNY}ww6%V7$1 zA+M0t)8-FYf*@tnjv^E`3}7_2Yu1UJyRxAbI_bltjBn0y#Z6jJp3~RizAELHQMT+) zXKg*kIXGLC4^Eyz#rh04rpHe6A>INP{|;D&>%&wv0CWWHxY4l@!j8E3m3z=Lm`SAt zjjjfW_*Hus(jpQ$kpVMq)ut`wB;G#!Qe9&+O2)6#6#lEhgU?Mv@Ve47TAR}V{}YA4 z3#rp#M%^Q z@9VO^oU^)*^D`aj@S|D&Db#YH)R9C<@JGpu`sJ1UvU#+N-RMvHldS9D2vGm`|Hhu4Y5!_j|K{c)Q-NRNB;wP+6qB{e)oikfH#rH52Dz_d zpKTb#A(Q|=tH-d=3f{leO_i>7pfPGb%J%c!KMH8s0AFeK>qaMK?_KJ0&x4r40qRw3 z)c?0*%(sL}4?fxGk)y{i)M6I)1nb|)I$&VVX?Ffg5uoPIh`x$$Wg}m59El<4CBy#8 za86gLY*$+GL7yrl$QcvvQU3x>gMOb&h9vQemr-Z_UrJPN)5*Vh_WesS;T6H)^NZNt z3Z7T@7LCyDt<%974l+mZm;qv;R%8|$ApTFkO7wq~`11MQxW<4i?9?v+SGGjIisihz ze{Y0RnwXe+VaPt}9Ihs-zd|0f&n)*e@y}2XAH3Gt-h9#mluMk{?;s=12AOFeS#dP} zl>7N++*>f}pZ>sV_W{aTgAuB=ACjm4zPLkyyF>;1U#D4=XT`goA()<BA1~O{9I8G+?d)t>OB(ao)tSU~<;Qp)hKw+H^ za+s683&m)tch`ZVa51qT>FEs0QuOx^w<@BTQmB+$v-iEd;cj+TzfcbM;@7n+7O`~` z-hnvEl{0;L*jGm37827w7EAWT2=yDQ%6CWgCIfk=YetZ)|Hr@K+R!LfoEE`YO4;)~y3F_=YDTZ@_@=bw%1#wq}< zyfL%t-2N|bzaONDE>q44|2=?3YBIq`EubmLsI;q%Jy%`pBsOP%ALy<7Ddme&auz#@ zv6*0@Tinnk3z<8pNK#inPy#pYd(r<#+IPoey}$oQl#-A_Drt%+iHPKm5Hc%UQAsEy zQRb~d8D*EuBBQL7tc;dQ%a*O7jEqVY;ro2u#yOvJs`L0ge&>%KlH-1l>vfIi^}L>! zV?o6qD@MNmdidTP7%G#a%@dPGZoMHMG*LOZ@f_qN8*a?_8y#vU ztn$U^Nx&H*@HP_K2*WFD7ZaP7QUI3k7<2a>M z%^@^k!Xbi>+dnBuQk)}Tm5`x3yYmv*ah8p)^h|W+{y#pLoxa`m9f)9@9Q^7=h0z$h zWvr_K(hR@y?0QzsZ8;swwE0H?03E5+Qc^HbO?5!u@-fCJHQAds{7qEze-a1`_t6&a zNV9iNMC_e0IOdGJ*M%p-jyGQ~jDRYT~BY<#RX@9iGIj3-}NP$r6`30L;l1$d0E#lsGnd;|Y_*zEKGDfisP8ZZ5j zelluvy>52}T7EQ4l}xe>4)p8^9wu2-xUB91sL>G$Rvq*WgL7C^ejmT^sp6BLTFQWA zTa9{Xf>T2YV@d`>4Ui-9XePl42uZE>C>DobSfLuabtbL3@)8Qb+vvXT%>&A1-59j-2}GZ zYIMk{8|>)|V8)tN)syDRE)@;B0S_Hn!Yzua|J*83+x;v6mLKl z`cDM>CMhkG&wuiZbVdT~PcAF?m;VjqAZVD5hwB4`m!&(z`_Y|Vf8$BijYa^VWS`Tg zB$8>PEWDM5>b~Wqj;1@9$Zv_-1Q;i+Mvv#|8nF}A>!-B_ldaaj%yA-@p)GU!Q#H0K zgMygDl8~C>G=vAgNTTWZzG@lQ-uHlDtM?3IlwF39$`pIvLOI%sh-KXb_aD;$roYPMxWi2&&hVIPeY!1GPd8nHhA+XVELzZ)v zNZ{6fO|o;o-V#-Zw0SY%ngg3GxR;A5(F=sM2UXLf=ZSLRL$W`6!*Lg`$s%|1yIiEe#B!FzVY>R z`9xu_sYp*co}X&hGiL&rluC;n!SMZA%xp<^qUBVFN!=fVounfn2|CSJ9`gt4q+?7} z^6swL6&Q`MlK;Llw#gw#t-W{AkQK$T)br?eO0`i0*y(5{X1~JpLw8|)( zMAru%Hc;lfBza_Se+r`IV~Cv9$jU%^p47^_JGVs=^{QgBEbNv$c%koJxsMzroZp_$ z_P<9<*jAB|W>XozNod<2t0WtrP0V;`j?fd~|Gt9MB)Kl}y+p2JuI(O7HTS2?wbnqL zgT5peAl_rUv&lFnX=-mAa)2i%UW^ca{#Xh_BNhA^uE$l0lgY#ae8YL;#1kvgjmeSg zTHrlQh;gef;n{z|0_Vfk*FZx(a*vU#a%RN+&xCaJax*a;#7p6qn}WkM)Zf zx$`V;`OLz&!xNvPLge;?H6GVZ{IDVCwk2P%E%Lp>PJoGM|M?PaH4IgJ&5hq2Nv5}m zm+x_R$O=4e5S6YOxJX~kb$)Lr?XeMY+)u!xM%sIHl-&C3I9-U_0 zYVCk6*(Zgy=g;I6TExvD$T^qIdr{DB<%IVKcrPE|9qruc9u&Tk|Ag1wiW9FK)2ikj z?ynuHjds0!w`oXvXkjp9qEroeSh|_*OL+_i?AZLb)ziZ)_p4LkcnwJ9~C^G}OuLU~5k> zu(ZY?OCKVr75i~0s++lWXus%pe=vkidDG8VuNiu3`~#R6uHrkChIy6~mzu|XJ2O-H z@Zl8H6irLcOeBcEVYPeDB`$y(a+&Pu{mHu>nWY$&wiSM)=ren$M{CI0{&}rZG zyLUG!Z{Kb&nG)sC%gfuH9-St&aMN*3w;#{;^lQ{`*%ErHm&{EWX=y{m2={F|I-zML z`+5KH?D0~#7?`s1s0zA&{nP;Y&d1_i8LLcrMC3UZ+Rg_IE6yvM8NGfg~NTf>;FEM1hv zrY_wJ8X{!!8@rz7A2-#~3it^Luh5ex>B-oknz^^HZ!q$Mr)buHc%;J3Gx7ib(lAYK z<3%W~e)4VdAuuwEO|gdpp|XO)qx351%r=J-<}0uMqBjl~L`0b;-k6A`$Mx%i@A~@h zy(me@>NEgUeIy6$k*!mI9yp9_F9X1&*3h~M%NsNK#~06PPH+MKX|+^GMtI(ui)E8f ziOPYcd!a~4HAXr< z-Q>%-Fyjyc(UbPB_V)I`$jGj~g*^TQ_cwzgyB%oJ7KaaqBqs}PL`K|-<=dj0Z3eHq z!nQ@-M_iIpQ#V9@fmCDErXTNv3Ix4QO#a%xOz3Z4DK4R8yUsms**`(wwHj~~x|;5Jpm zrbg3QQPFd&qN3E@)U*evfB1N~Wu5xk(rbut-_>YojyZE6kRaCrxevKYo_zgY7zdvmcQ^vabdcUkMmDSZH*dG!x^LpngU+knfcD<+Q+#dJg zV;e_*e!T`8mXniv4-r<0kvz}W;M=T3GS%DE!Sdn=1%2Z!&u*Knnmr-g)sT;(^n zbVdT;S6bDw!Sp`EIX}Ne0m+$}RhN`BMrScIcaB=_GVf5F_}B*aQcY(Bt0UUZ&E}~E zNBYFRq4k~TvNUh~v7evJWrN58SJY(*O*71T*(W+Ygu;-!xkAJRzU6c6i=Zy_-3m5g z*fCz7(5Szlk*{oI6v3acU+B+wxR?odNGG~u?C|3@J(g?k+O-0EWy@=8Eh3sy_lWO| zx_Hq%_(X5ZmM~fO0(*P=CrB&(Mw8VvoNG)1rBhIbjXr#dQ2+yNZEeq4LDA7YBGjFl zntU%_ym)MMBl8tVNDnh|^YZ+TDJm-RcpT@Ma8M=+bi*z>yLVgjST4@ywTWy>WnI?s z^iv&~peh03)3hWpI{$XswBF2o6dhmuY+N4fdp}ja|I~E+>JaGq-Wa`=@_3~g-=FU> zn%v`z^+A*O*u+sb7v=l%QrVVh2TIa^Z&$Afm$!s^sTgC~0oRPF6=YXyzWU}iqr;Uu+W z;*>?rDb>u2a!b9^-_*3*>p_S7xk1l`!$u$5z4}ozXyrgZ$&W{D6NIitT^~BRftdaT z^6wq??p{6|0boQTAyxJ4f{=tk&iA)Ik@LMbPxz1tH#BJqw11!z#9B&Zyl6-qoQqr=w5SZEqKJJC~9XdKIc_`%-RS9b0D*=rL_VxAc z8$6h8*?aEO0S;H3eC=Jkjy=!ni~EkjTyA#>qik2uG!-wo#PuUdoc-fYby#Gi%-dtF zt*u`QM~4bybCdcW4iv-;6_w^i`KriIc!o^^G10?)Usd@|*9}!4t5B183QGQgpEVdI zt2_SS)wV8h7lM%LE-)4q74`k*8}AAfF2m#=eNtMQ#G(&qou(Z0n>4zK-}=9S(u$eQ zI;(#~OJ>|8^o%I-pQer;jB#yI{*<~#L!|v$)zV+Q{bHxEnWAp)sEJ z1dP5lpFe+=FD~r?{yDl~WcSoYC(*=_vg(28>28a@5Aehn0x|L{z%u5$an~TTAuA!F zD@NIDwBsTYHI^TDJg-5YRQB!V7xcrab+c>sXedN(cFjHQ<>hR-t$54$C5O*s*qfMd zvl{Dt_-zV)#DCrcW*2V`C;&Y&lk|=lL|GC9=-LjxHvcS77{``3`{+NF5mXF zLimqX^eE04?mNmpVfYi~Hf|g(cc}%YUq?qrpIFeo(?n828AHWMC%v7KXf(SE<|Ul# zt8|dbca4irxW0I^%j>o;n81Dp0*NI<$J)G4qB#Ix@6IW&rVwFP>*qgUr^Z<8`mwrv z!GZ^w`pigo^nb1XpJ(Db1^ob4|1kOq|G~WqE0feMY-|Q*dPik%MwgWRadmHS z)cw>YUl*fYtEl%AUAz!P7w&A_mwMEq zX!XjK#gaF77WNO%@A_#pSx(I>ePuRp-n^?eIqh9l9PSIVf`jLlWqsSKq$J(_=^pQo zA3wBr?%eO27`=!~*g))UTW&m(@3=xVU7XL)$dfj#gV3lMz?JyMZ_b@HX^sx71}DA9 zKktu^N)={2-g&a>PNZ#Km4nc#&erKln%1j*NTqdXWz3Rxv|7BQmh!T*uY22pBr2|; zplO-hn>TM1)0Ictk|L!FJyRBCLXT-X_BC2AYaz(%GpISgYYWtJZEk+k|Hiw<-+fPM zevj3jDNVK0+4|-V0wM5i+o7w=Pc$XU`HAJnC{7%1=b1mriQ$#9kN>f{vPrl8;W>_L zw{KU5X{!ynAPK&jP?%Q^nbllV4KrD!xY#f+JZJv=_7eX-gC_F)bbV;}JZL|irlJcj_08EyTB1S3v_c~{Mj1VYLm`4XgMg?E}}#mrb8IdXuHb-yL<)UQ_|XcT9tQCf@3@m@Ug$HnJY# zQHjP5owEuZNzG96Y-7DSaHjT~6>6FquH(Rkl~0_=srZT>g8|8j6NbW%&AMZox0*Y* z8Qg;fcIT#5gMGQ_t>&Udi;DBh5&Tn4omg@&%wMl4CnsklaHe4VD6vuLPife&-qv(p zT#F7fpVMIO9TN8mOXKPXup0J5-*DJfMOD=dJ(<~#E#t8%yuadANm{|+bu7w!@HoZ_;zkPuHh7e$-w!ZWG6~Vs75lLXy9H{rZYG0<}0z7m;@^sUq%j4kzb_ zM}kTcx2IKESz1Q$p0>@a*crb_9HOdwY$6&`-LZGg*9~2)V6uNt@;I;*>=7!ueW7We z>lVl1>-_gB#ve1E2m^j=+|{dc2&M}Q=#+*!9vm9%z3euvYC7-Ko6rtAk#XYdf!NzP ziBHjpR1*4%8aJ3g42p|cu62Iob5$+d)`eYR{y)Bcd{-&{i|MING;}7!tmYB7byN!(x zyQEg8I{}t?pwgGy+iUAJ{Im8A1nUEEQXZ~)Q?9x;gvbg!v_qn&@B=)9#?e{>*&5%< z{_aLAhWc+e^oM#zM{ItSU2uD^LH}VgM*iJiC*CMquLtgIG2eQ|@rz&xrFwdaJx@(Y z?NshMpf>e>5WfcR&EEcghuWN@31v#B9wDJ9R<0WiaY)AhInaH!t3FE=(AG1q&f!bJ z!TT8+7e)Gad}%S72;uSc*REYF=d$eSjIl9*xVk!}u(Qq*jE^)US@Omb8-6cwEs5V5VioSqOxY1B>_?I^`X}m&0K*8^a zE44H6we0iQ%|7Gv=ZNiaxV#((45xkibYXr6-tY&fJeZ zd5U39C3mNlfAh$Fb2;jMfknm2clE1vlKlzW{dEE8%q0B{a~lOz5=b3!R{@JI< z!>7nFJQbNZ;>YQEW>;6#V&AcXd|T=rOxW@8->gtvi+h!MfONdfYn|At1e^H>Ei8`M z#EcqUW8K?k(Jde#5Ye_-PpUcGGDGU2p1{`6)PU&T_u&eNV^tj8ud z9<9F;w8sy)^q|{#9b43^Zb$c*6&&a~&7m%$?zR{+7_E(Ze?0R4LRlFSsZrJ`9(!c2 zV3&1BP+MQ$;wSRn zb-X9-D}gThnK+A_shghqgJcYl{n8z5;yVhaO9?t2DB|UyRVM!fb1;0^mRh{RsbmOV zSn~8CFr(~HBVE?+kdNm%B#Xu33$?yZX4jK0>hIR&!8ez$f%kNHN#K~NrTb8)LD{Rh zyWCE^GMu=d^L-i!uBtT^wK7Pwx^r@zLq_V`m~%U4+&E>3L}b6Yx%9#j2x0(WSURXP zbsX_-*8veUJ7k_m>mSNca>b z3sO>E^wj}ispAg!{G&aYXy9`C8yt1~Xg@|NW%^W~rEz}Y#<#XIJo`1&)Q)xBRznhV z&kR4eCg{Yclc}kxBQef|oq_=03XQEmEH-@xy)6aVqv%cSCbZHgSm3jk42gR+2%;4lh$VYZQ15TIS;q1J zJ9%Yie=zjT{6mJ0%a&y0Yj`Pqa{N9+IkENjVqoB$3UMTJJRS}*C!{uQYAEl#?ezI{ z{nUNa#nTh692=H+lQ@ryYr&Q89>OpMOrWiFvJ++*bEPJ8N}B_mRGiJs%tjGzI^Xp< z3^?ZJ=GHOY0eAax{HX?T+rMC%CP$V|_ZJA}xMw7xhT#mFGcm6fImhr!N-tAie?QNg z`no!UGFztu2R@wjsTjdlDm0@Zo$49aL+n&)Ctm6ePO99-qC6 z6LsOQEtiU#mDko#Zp+w3zt*K_98FG4^gn-o_S7w>I(XuaRf4-B6d4&=EYNlC+`03) zUtMJhJT`T3ReWWT)wkxVmQXa7Abhg;(UWncoMOV1&0$&dDokHrzj*2;u^I-{BvK$5 zm~UTekZpSjUEiVX{0ztVr{61RD7g}Hwbq&0-W$cRaLhDB)eYHwQvE$8Qd_vgbyrJ_F&xnMHE zmy3Z5_V)4ds=Ug-|3hml<5s`9Zwg30()IJ$wP_CZWHi~+G{wbQ?qW6AP5eOhwU zO&xh;Pc}WWpN-``cN<+eGx&T4Jp&kVAHI5zq$`=1}yNp-aGOAiY$k2O>I(iz|j zm+~BX`QpW~f?|xSF zdRIDOO~1a*q9|lvT{%6;<1N56W@IcrQEwZ{%lAGHxqMj=h4$=^RVIhFZaw|L%|1O8 z)@RjqQ5rBR4M&a0-P!ywhCk=RBI)X+5&N;bEZRlKa>uI3H9MX^bKp$f33>k;xeo?p zUB0J7;c6qnwJX#KbEg$Crnlj=@1Ls@HhWy+DQi`Iwy_5=GVkEQgZ^K>d>PSn-XqS# zcUi{y4jb>6o{{fX4)?o80tXuJA`JofX%<-z$Rx@w>c7hXK2RI|hJMCS7xzJ{woCAExnX_iQsU-o2P59HK8 zZ!?qpSSnS-L681|wx*`ZtZP>shGk+|cd=UzobE1Nx8`oI+zIf|)TY-|G&CQ7$I`R? zc_Pw(Y2x|b<@VeSoAH}WDLo0VF5G(4v$0C4Xb1hVW5*N|^AXzL`12S5!bk<+Dg8;+ zt7Q&cxY1Dib4w>@X9f4o2cNjcdF`HdUg1gOeEmW4B>Fkqy1O?t&6&f+W&ZO>rHYD* zuf+6r`JFD)j>WYSP<*)O8F~R`QbnXlH@tJ`h-G0z8g=zV*Y?+!cv1mpCH>R#&M{Y0 z^ceCzEZRCcA9f}ht5#@g9XJpVcV{Ph>%xE_Tl}&HUZ%X3LLPFS0N|BZR=(fKe!3xY z?^O=iiOFg@*9B)ci(IprUY2zlgC~jrMXXn!q8NW7WNLzsZh!V{tcRltTcXc&>6qX< zjC+p193Jf}CJ{Imx;smP$A}V?7-p<-e+Gsb5amZn+Ob!!`UZ*4$drCG?{*}DErQ2w zk>Q*xHcq8p`ywoO>}tIBmY0_wUsXI`g!T-#2*$AP?2y+!RgYCpE0!!-vQ77}pP3BW z%y!tCb(u5#Z#@+rpDQZAzN+zy^q?ZB@v_xZ*vG7rp@3p&7#K#?|X?sOb9kOs= zO=%X~Lc`Rlj0T2=3OzH-<+}%uA}USaO8ed6Gf7hxxsqq{=9McIp$KEKW8Uc6AyBk# z5oh;+6B_8We#Y>gRrCIQAoNslAg9? z(_N}o9zQA5Ut6`SL%G|Fb#Z8Xd_4Qws+OzMxB-HD(4Um}8yBE|-fNWSx3jWX=`L+L zk%4Qk=PK4%J&KOhen`)218p(5huOoWSeJ7v`uaYDKRz_N)uik2rCUpS%(3jA+t$$` zs;-loloUYPKI_>n9k=c8oPE0faQ^UYuIAUT5B|JsVQtM@uDdw+DIB=uv_&+pdeYFO zx4jE>c3@Q08dQ=ffp{BySktQz_B2Sl;L)Q;@gZbm;}=M^h!$OsU-;(>gR+}-R*AaS zIQ3=o+){rF?E5&2 zmV5F^G7h?Z=sXp8{&G}PQ*EtsVk3JnSD`y_nvGah`W_tv(a2Wxq(jI^%B&Ua6opvOJzq(2JoRp4 zu(Y&%k3A&Ao#lLa)9S=ucW-|!)<)4Q1?e#Bg7*aj@^H;3#HU)hbc=!><8s<@iU};^Rw5LbrO)4;2$mjY&?` zc%k*TcuJg0C^4cO;aHQgqoT-P`ug=M1a=g(Z*BQl?sN)t!Bl1smD70y;29ltKQ2${ zxdB(cM85Nt5X&~pCy}&lyJfKlV7+(d_5fWg7~j8tf7bJwg~zgV&}O0Ebb+Wno8H+?iOWw&#zl-f-QJ{zuAA0!a3n9{=pcHk}18G6{JP`4^ zsitq|c9}&%p47E?R6}yLZbuIu)Yf23O-yWK)htG$4Yi$5UiZAo>6c|@vmE$3?fCJ* zt5=um;}Cvo%&W0~k7YYb-G!rWtglLJ|L2kX`}F~1`M756n)seDf`j12a_#-ckE%vS zM*hs{cPS)RG3Bw{6+alG-Lp<+g2u%%RvzbiRr2Rc__+qCWsf0+ZtRI2-xCuXD-VM93S@x8LFmyuh2kRq(m2E@a;gia zRX@VXw2C@)`s{5m*M|=uZnL&d{Two8$PrVnIDCvquImKn!oL|D-uTvNl24-_Fk{Ay zn;l;g|AS&lk9!qPR}MZ)du3F920>c!^PF1{yg3ZJEC-u2iu>|9HrrLW>?Q1rT$bA+ zQV0kNN*%cK{P}kEBLe}l74U}N7^k_#FSHQnp{lE?%^RM-0A=y;nR*jO>=e*w#az&O z<8~-c+A!2V_FG^+bw=peC;r<~#|o_23%422kdH2vT$dq@BS*oN5Soavefv`QIE}514)Xrwb2>c9Z-sx zFpCdsjyNb15qTqxmMOlbg=f`An4LChcb>C8Fx{<7qI{thFW%PI;bnJG8ZZ zqpzHIe$sgVMA}MuQ!Abm9ZT+&8Kz@lh?ickL2?`$a4{DS_2||Nh<< zO_3(1WVkg?CVK}56?6$tdwNQJ3)9xHv9Ypx7w5p-tO`zD7&-fWM=$F;gIdyxmVajN zOo2tet|G<{WRW+FJtf z>3sMk(0%jfO;JEV=X`x{ub$VbIK_jH3vg*oW#u*-o3zgqtf@H)oOkIHUF)9KcKO|q zBM2fyUpb-yfa$mkuNRyfuK<4;J8&W2QR3w7c^x))?AmJ>33gLa_wDraHwHU*1|xN= z|8_5jo^CBN(*aSD2YD-ESZ6KT?4l=Dx=|an>!65;g+Qq6ta#UuYK4AR%$++r;Dm_8 z-9=}y1l{|onTI;QP^nR`3rrtOs|dj29Gj=u7u@Ed&ppxB`<=_Gf&a;~E}l2`*1sFY zpbIIsFgd|uc8%EU%_qL>FWcd1!NhPGkBm~!-Z6g_aSqEGYRk&jE!~b7#@;`Rg@us~ zx5hM+#9Xw}KKf_2wUez;A-%o5F?#$yk~%F|)EtBb6UD);3!1-slD$Cwf5v0^S|s2f z++xjPx5UFQWG1$vtb9&PT-@*VMj07noMuW(`8olapUZJXGf+I}l}Zu%5itLmB>R)GLyO($v^(z*aB24c=He0B`07-UhUud*Kf zucWE>BEpON)Aeh|!pm$Lv_tyB-QC@$&K(w)b8>P5{r#!@^mM{FDKS}IZ>KQlw$Sq^Kb@9D6Pr7!_rU`(qg0X!x{xxt! zqH}(n^SR3JUgOw95)#0Z2&`8uqrJ_0YcxR@LyTRvX2;Yn9=S5AG>ZoXI391C^j6oY zjD0Edd29(~_^b#p+2U7k($htzkZg|1QR-z6$}Zs-&bI25&X3g0lNWsEpm*zlpAj@D z;=gsuWS~v65%UH@d7Eb{{Vo>MLNgODUgW)77n2!?{qr#~h@IYPWF&+^hGnTMrKQ6; zPMtC-?7GcxzssSnt3}@mH4kdo^VuLZ}@&Z;4L=$K~77{)v2qDyDI|!#59zC*itSdqD;=lOge~~8YE=IA^ z)Pw^a=k7hoBt(ByoLdzXPS}U#FP-zYjD7wrk9{~XN0sz;#Q*~MUYmSR;}+-q`2ye` zzVCCmVJ&iO8QWI+sq$SsJA16a6%M?8`!=6}fa(#27SvsVK-ZOb?Fwl(!`iS*qyvyT zOL@=O%lqxCy$haTvQ+uQTV_+Pn|n=?xkwz^9_`MX=HvbQ*-&4ssAP}P+gH-)|;p43y>e9Oqpr#=;-6A z4$_2Y${K*Lc6N5l5wEA{Qk0n_`Ee&3`JEW=P(YymygsjI>-%#Y{N9_7ZzZ+m&m{!2 zrf6%t=RK~Sr!PFHFDfoxwb)EFA)2ACuI@cV4ub)&7u`Nd#+bgm57HP+l8XNoCkc>c z4_#KZo7OmJUk$6b9+uh9NV^Hnd1#e~ynVYDB(ud1jAdnIffq0G13u?8USYPZca*$f zeg+=`Uwpo0s38|6YNnDd4n>k(JhW=DM;eEq-#PR>@?7-o55HHq)RO{P}1z zck;NW|IK?X(k3Zcrtw@Fp@wZcJyJp-Sz@08`|Mw!WQL2dfNMa|sB-iloX*@9E^+_< zeJZIMT~@Y~D0jIktXR2H1uP2mrUsMMSAHohA`LKtz^O6+c*|9|3U4oJ`SRu83pEA* zkskl^uSHv_w$fSS6bZLEZJ#~`W2)?|+oA@N8=|&%yY6ej-g_5b?^U?yRdEI~aRKjp z|G|S4Es0b15=Ixidm+&r{PX8e z6QfO5{{gtofwS0>5g;^`IE$jo^dOD_66HhHR7}5g*|HTVZ};xqo1DXUUD1RaKik0L zFt?Pi1CSh|^!@L(FP}bjxXY}!p1vDwhkPh+ewR;dbXAfz{(%LfCAf}5x$nP!KYjwF z;#MfD-r|^H^(zDV>oKLr;MSR~c~;O$dxnd|a)X0|&qk$(g@>;;H8s7LNzpk)CFReC z^zfn2F*aL+%)a1W70^tC)-Md;{Uxq*1@xY-LP>a8K zPZ#O+>vsS(qLQ=aNt$UIz+|9r@bv&wc(Vpp?G_LfukzAT6TzEyttwD|H9VC1@XMbQ z(&VKrM%j&mH?F8pnzsj)bgupD<+OIsS+!;j?*@}g7cZLMO*%zl+$_#guSGuI-VrC4 zRCdn|5|(P0If?<2b0gjBtk7o;Lj0}2e^TK;Fdi@5V9RSI9a;wzgfQ@K0Jss{jZQDp zYDGSj2nbO55+LlDA`rl|M9^B-c2&Da^K`lS6+BP(UgoOV*;N$|)V{yI`^I4_ zs~}9U&EA+3xud?z%{<)=Nd}zXwxdVCrY{n&Oto?6UVp&%-Mu#UK6*btKRf8yKgC9i zL%G#pK^qY9zP{N)B=h;pSpNAHUpAcM^cuGe9`aKjQ`i8ZhoY@qmVWMzz>fHBu#qV{ zKRC_c*=WojNx^^4bDYCbe&820_Y)|OBy1I%j z@&_~1&Ukv3V7>reW~IOCVr@ed;zvY>Kxy{vu}JK|q62@36mTc7_ta&og1*ELgr<1l z>({TX5LXPq=~7Jz+UvRuzFy+x^ErC-Jew-BjxXG3w-xZRz~B&-n1$pVj5JDLaZobo zA1;V08NrJyo7)1Ul#GWdfH%{{{IKNDmiWJ=k;lr?ii%}49-=dA@>)0prZb(oH*Q;{ z<|sm7Pd~O{t;-u`Qa3++{(Musi*XOMk5+!e-p=M`?DNRL0k|O)AmvJ`V6WHP=h@Ob zc{}Ur=@nHepsn4qfNt1V5ACJ9Pff8!U^ahM*67ZiJIRD0s)~)DG^P*D_=)9!fskH& zV*h3^)E~l*hKPNirazzoEWfvslX58CG!HHFp&1X;TsoE$7lVT@g~o0H1Lq+{;MhYc zbTXGCue@q1#6mjw6_Tz^$xs(INQD;LJ45Jc1%L{0&f7cVp_D+mBi^d3`HSt<^Y|ES z8uMfA7@m`n51fi&R$0qzV~u?YOIlK?o^|34*3~e;{U9=vv7$WbO*Q|OlRJ`}yqSLH z*rjfuld-s!oSf{g54Q5vdk!pahS!Am6c}MDeobrx(Ivt_P`;^Z&5mtpxgCOKB5IbF z*9j~ruYNqMBsZzT8JC)G{_M%UC8bqWE1>he&h31M#S8F1((h1IRek2pn|E&WZPE1h zkN4j2a^LRvPHN(!$E1A#=9cYVClS+w?ho%SfoS)UoQ0rO6mvTjZa{$`8Rgjy35kP! zVd7SypEZTXI2m*dC-=nYZk0Rf9+v#8b6cc=>ltQvb$cv*7RKf|x_1m;(W))ukRpVv z%ogy&_Ee|sv8i;yddw$Sh-i~ED6pZIobsk9O|2HDw)U3@=T}Yj4kLDoLQbzpz#mzA zkr~~vV?KDGBOLY9XBV}1tvPDvarP%96vR(rZ%^xArQSbTJ zwBoO9=K`4#Tg88B?2Yxh)AM|I@#KkrX{qM3n{CQp(R@&Bgm6tL8Q8G1ifJh#{XM;* zE#d&gWNjAk@SGP=Y4!{V4_}~nMw^A6DSNr5zP&j(h&H>ZLx$6LIzp^ceGvOuQbIl{+y#yPmTT+U+Hb zTt;l0eDi=t zfOqYVj-GK+KBk~xH>a?{a%hK%8<&#Q2fG1+A9Jc^H|`6b_2QTE6Gv1D6f#-=Au@EgfifFKoBG0PbFG zy6Gu0pZ<;qz`J@0_0QM521mw`-M5?eQ~eyJl%Q#|#g9v-uUNkPtY?ut=I3U&lGujT zFl&o*iNwnjlx#fqR{OUU%!8pC+8nqQPuZ~}2-vu8U!3`^c>b);Q@hr!TUTwww`-Zn zI$BZntn?N2miem>S2%pSZp`@RE-Ziz0fRDgOoXiB^_wJX({Kxg8A?Qfw zlR9y|)GO2KfqJTOMUPQ5woJdZ_tDH8;1+(zEc`Rl(`{diUoS)4zLuK$vh6EO?kQPG zX}?nFAYoG|eSBQi&kh3ZI{Iz|?06qcUaWUp^SHRUZu*&!rQpygUFr8|jY~*Sb#SF~~@CZ*GQlm6`bGWd^4fzF~`*o~F2LCf! zB_+pZL+WMQJU@x(YqT^PyKb)>X5sEo&OIP}X{sk$z#HU-Tob0J?J3;N3BTRZi{&sS zcTapp!toj@toGZtZ?p5+Bo$GtNHEa9WJWt!6+@^P3w_-^aN(;;-_{~&ddNL$YiTV3 z%}iZQ=%d(PW9XL5M3-ZdM5+OLtz^b{;Ni{(=ePW=t{yk+f4!2H({LF4 z{%y4GqKPaW%Q36;ba1TgKl2=V_3G6{3>?Nh%IUAOG6Uzcco6OWtq(Rpb@1)F&PL31 zko`4cawc`wx$P@|blJEsxV=*7xhu|icm0uTGK^w+H*8*%#^mW&G|NN6WFAX(IUB{q zp595@SxwC^_~J$BMV2+w2k{7&uUmJ-KIo`8{V4nEJBP!C^wKGP>x1-%5JH5ZNFH93 z4_6g=X~rM2Q8=B2u&IxnV+}|Xe~P1H7W*NL9InfR*N`~b1t+-Wa7}3`-=4wpi~BJm zUo3U3(MgU7`|-hMGBB7$&RpWf4KkU11kX5q`gDwg>5*=r4vw$05 z=9w%kA<%MSx6K+je7{3!3F&@$^?5q)xZml`^k@0iLBPc9rwzm8MDH(S&=mSugqO`cGO4rz zk4cJ-#j;a52mG9PE7G|>*@cRKOP0ee#$7r(B??@|B%Ulfk`GQ*O)K^?1^W8VGR#ij zHi?iXQe!2~vDtpyyagO{xvtdkBWDH}`ab@|n4178xZ9W47#;OXHpnb-W}L-y0u6~T zXV$vh`)=r}dUo?cac#q!d(RLpNJTD?)#_KS{6{66evX3H^y~d8LVx2udwAgF<}4n2 zsoyV9V@;g*?~h|YRFmdFmMQ15?;a&356|%)6z&8KR_2dfjs-qvNM(1GPL+rL0bb3= zCQ6YjojH9sOe_Q<2?P9ZR2UBNwWue`fb;?50M zF)#q;x;;$vn)^%WUMZ`q^WO1X|58%E$#uZ^-4HU(++EvgovPow111L2WsYey;H3Rj zi#K&zJ*q*%pXn0?Vd_+ulN~533`Rg`x^w62@`-3tsnP>e$Le@GF*PxRcHYLJbb#iqM|}+qmR|aEa;WExVVg-qq$j7wQKDCS!I7}ViU&B zGWUITz_|~o+59S(`s;f~38FBc<^%3k`bBa7%q z`6)$_d31CGWOj#G?$uGxh2kuk<_8X(Kdzk_yYBmD`jCMD#01`7j_@$Yx>fzC(PNxENq*6|F& z5J4@g_0Fw>4U za!o+xs0tqBvRQr%{d}#6ct-TZ#Uiyw2OcAD6hyD%tC{lS=ii{J`^NqhVf z3`}?OJc?H^WfKfrO>&KV(N>DPdly12==y_&s_Bu2j2;1uo&=4Sc08ZPh}9};%Vss9 z=O^`z$X`I^DJkul)PVxfcw#*>t!ic)Dj}v53C&Qb8Z5ApE{$i^104P%(_!U*z%7Jt z+u5^ZHLcFEl`j(FmbATuNr2^qfN{xjAE+Jc}G@MHQ2 zS|q{{EC~bwdpD+&*Mbl@Y%{COeFs?NbXu|szw644MJ+vDV1~yA&X3j24RdYh9=hP` zD|WIAEne%FMd-7OfC4K$z(60xRoZNh8lm`H4wCDrXev8W52g2?vZOr}7rq#} z0iaPTy1KffhjMYbF1kpJh9P+&q>37apHq0%3bp*ha zeCmfj2Z=2?&u`E-V+z0vW)-|cJpgKb@}TJC8%#a*M^+LZ_6mH0PMxqNEl~DeqBuL} zq4WmT#|!Mx1++)Qy>{vn5rP#XlO7>NNhVz;bWe)Ip27( z_Vee@=jJ~a{yfF&g&Qa1m;CoBb;!?VSMjoZ1SnxDj*I=P*2`oUpZ zn0h@aNf}nRLR7SzDKp{PwT*W@XES|QF@d^i2K4q#6P(esYQ@q!2v?c@hj0~x5KO31 zyI$euMAAwXN4;uzv^lXZmlU=nU26xs(fDDoz>bKSY=*kjl9ZL2d-kjy%)5%lV?@5} z1rTY`{L?WM{5CCz#zDdchq?I)FY0XEzApFyfkE!~Gll*<%r}LOl*xHEk3%M|V+y@G zskP>KTQeQkjLFR0HFM@n)D<5uX+f08x7QXYXuA2nRSXRrrBiIt|8EudmIKnyqbe^VmA7pmpAUPsnYnk zMy+>aFfesqTUS>Ih*lPsmVs!xzT02-{rh)n%EkL^={_*7yia1Cv$hfyt&O11@87@w z2?#?|Z*H~B2q2uOww}`-{F&jxvKuz&9C&`oblLn+%VQp7<_Vy$+QlQ?IUh?fiV(_CtjtDvcVX5X=FAx|S$|+`LwuDJfjda5te9=vrLidWPO}PsKCMdPuR#K6~ z7aL9kvmRyq!z8P=(^OeT0zm2)xa3&O801VMKy06>;eQnilg&vQqNYcQNl({A=Ha=M zhm-R_#LxMl6L{>>TuOfr`H76=K*%oga}Q=@^MKT6fj_dkkVX|`co#vYsP#_0^?G3m zOy|?4?4w;Wc7@7E{>C;Y3Qqb5)ySawzRYb0$10irpIiIJYv5Qg2y-!SH2W1^?<4{Y`f zfP9mlg>vPj64|fPiCOGz^VplRp8LJALR2W=G~Y~nduhyQ%B!F^zfQy2dX1?-n$LPV z`tvyV(i^T$ryt=gbx#2EQ1s}B?WiON95+6|9UcXODPBWC>u_S(xT$u|0uG7tqv=`dPw`>rn!l!siAl7 zYzUJ)a#bS1^blb;!A62K?d9=cz_iP7A9b@hcu?fPVl;6G5pf&StL7n7X(5SgH?H)f zwZE(~3PY7Snc5=sf`s|H5t|iTF+3U1H!-F%h52{M>qJCoK;x@><-&_&C@d*~B+1C~ ziPcU^TU0$TSW=6zozIllMWG;x*Vfh+2%X6h5{%i>TwSf>Rn;la!DFcbjR!(HWVlZ9 zFIr{;sp+uL?~Offx>4AFND+?C9eWT=OmymTv(FxmVfy8PqBlSzfnvk@X!2_A!B%7> z`vZ0{L>JvVH62{sVtdnZQbLQN*y=Bs`)w$I`jhEnUmu_Ka$SH}c_T00W9#)Q0{HSC z?NYHwCy?wj+=iXpgC9lw^`d_H6+;NA_3G3)$HyglXWC|5%p3@{&C49P&~Zu^icd<= zYFPjNy@T(ZrdCX=5S((qDQ}Jm@3@e9@jt&p& zT=mOh%HR+!T4Ut?5+meC$_wQMr1aEUuxTVD+@_%R_9xJ~33wA>U#_fU$oXwD)A{AA zc? z3j+kRxVX6QakE!`zEITNn0GBR^VpO37%O(@=yMp|`68L=xKaydH$xCZFO7tk&X0EP z-k9^&d-dJ*8)N_DF`1Cj!wpR?p@f~Irw{{uDzQUVwY3}L-jm2KR)#2fL&!^tJ^dPP zz|dOS=S~bYsu}_Xyo7zCoxfRg1DHAQmfINE&aAAge1dc8C3L=`{?ySz{ivz4xXrq7*n#PffB;-W5i_1aKDET3_GY8ztr8Rrgvik4*;2aQ2pZkVQ@fK?v66Y z(KFl?(%ij!4HCs*Y&NU3kB1C|yiT&-n^r+?-v98JLjTZ6Kg#Taif`T0dLGO-GV3)W=~e?^|1y_wHS)!pUA*l-hl*J1nZ8ClRz{q#}xmGHcen z)N(AifGK#guJ#MC=J3>yU>64YEs&V@!a)Deoij)w5?MG+M^Bp54=1$85@NGAZdje& z3KZ%&02c63X+(|m^RTJTPxC^SmhzX@*RN(|WJFRV%CJI6==pc!h4bgn(3`>xcFyY6 ztNmW>gjz;mcz9>}-mV+bSqGV3E4NH?%2hWLrBiGw@<*ReIv`!=mjULlGx>8VqTJd~ z+i96Z%QngbdsL?Jjbs8ID8_lu7R=AEQHTRMxPBEQBzD0^@%4IvV%p2-k>O4wYTuEX zd+0V)ptP=+3?XcWQT}wK_&J@adE1pm*ROAdwBDTItnt~%iFo_h6-<8BLp*80y7e@_ zpS_A$CeLYcE1ork&3|NT?lLO1kc0x~>6aFxPysJ3E<5{D^RsS_!A~UtV8JO!Iy>dP z@;4$1oqLrnVdgAfTrJ_*0pu;&`LQ-cj({8_IiwC%hmqyM27l^zz`-eadUSf`i;fUgdpUDe<)FX>CH+t!L&k8d1Tws)t70q8%fby4B=O z=(j6i5Bl!gs<9$a`QI5zshi;d4YQ5mm_8)iCwFn4wVn|ihBPirIMG2+hv)>aGk+No zIh-JIBhI)83<>?4E6*IdD{!U%_KqQpj-9Dv&e8lJXz9@x^OCGXe99mFT>ssFfk1q#RoMTefd&8Txni|n z+pvrtFwaV;Pd;0)#gU=J2!iy_x%8aptq`$kx~q3{uR>pE&04Y%2aMYri6iw_YZqPV zhd5s`x(8nbw@3i0}dJ9HQiU$f~y0nhMV*we^4Tg|`wu>3Fr=3j7<^ z@*p%nghGj3fAq;NjG?9IE%4)5#f7C2cKXV$Y-hJ^>4YqZ(gj`_+uIqG40YByLi!n7 z6Z1n-SoX}P-}C)G*IV>Sj=VfT#PA_i%YU~uM%0?o_)a2qxWh2G!sHiMKznBtAR9Bt zS21dg)v3k{Z1TV9yyTh2%Da&4o2(ezu1=*q!^6w+jn%@1F7zO)ImjZu*_jDmbQQ1E z$%^iU%OmF;JY7U2@V{4Q6@+~C){0ep1PM#tcE{=edKr^%1z#M7y)@k!Ie?{&6b0tE z#%+*G{uXg1Wp1fT-W_SIwZSf@{x5n;#%z3=k{+1nP#UbOEiJ>M;^z;ja$PLSKaQ_p zrY#_YPNe|sI>n=eLoeUy z7~#n4`vIaPJN9BpGs)}fK6*2aFOSD^ zTf;6(_#!9C0l8DUT zwd}OdKBukk`~KO#&d%AMXFY4(>%Oo1y05DS5;3K2aBkzpzYz5tliqYX&mFdfne2>v zLMhB9sc4w;iofyt463-gyxhD%`*&HDHqs0=s&tK`tb03m}57(?4hN6#f(Z znrg&!AZfoDd_X7x%&5gxn61S2JzfsV{JdE_Co}^bV#MffkQ1G59^YHUu{Yh;1btcl ztydOvVp=JF$GMpqr7K6mN(0tf>^B{7xb2WSk6OT#1ubWrdYi)h&UcA+1}7mqRVbEP zUy-&cME&%Ce*6F0l9UH{&D0GE6T6Y$kczg`QJ`ceaFaA`4^}x%xkS$J3nk&}6e$KR zMi*El5s%7}Z4d>%jMm^*%wbEZh=&!!uH>rIy?8)glK4N*U(0^c4Gb zI^8SKBCNba%_sfy=)b{DxylVHKr*bQ+zYz#|w6?M*qp zk6bdV_Mgq1a6|)Y4j z@)*fU|GQPziv!^b%VNGM)Lo)yUWNnBW_q2({KpK~7`$j~mhtzszZM{22d63KI7b6J z;yD~@HMe`;mHp69wik-+5M73+G$%>fOVg&t;`xe=uz66`#$8P69R!js^(2-< z!%8C!o3A5)ZSRIq=g;@s-zBygh<4)5JmtKM+WJlF>BR*p;X({r_gpdRkbp92jh>GF8~e8Ljm;QaZW`pLh3e|V6s_l#m77%Vli(?=u<+!&822FO z+sJ2x?{NO<-pn`!He6Pqv4@syb}aMRUf=D~BJ@gAg0&b@=G=jW1cVnv+z zlty~c&0s2)%IU4a5i9Y27VC;gnewOyUa9B6*LQ7g3q(?)-zN9|^o%=zyF7%R!G~F7 z_MdlFhf#X_drTXYo~u=a-EbDJ2K0oDXCGmEwQaRj@zT&`bg~69Q3&5rgN$h0bDJMxxezeR~WB==V z_~*?rVhE41)Cou7q!_YMjZsP@n6o`3Q6E7?C#3p4eUb7(_;I|>bsrC*C2dI?B`3u^ zK6@=WT%fn=ZMp|PsHey0<6hqsep_=mZa44A_f&GMb?!a&rDyCEv4$E~0Tl0UvA5uS zd!Y}y6q0pwCoQWcgVQg+Me+yge0aA?JW<}g2J5G`>mW*pt50JQ++l6D{?K(Ty)80a z9+d6p>LAzBl?KsuW2m~?z`r=3m~e|Y6bv!LF8Q4LBp~)S5gx(27GI?7 zV~j}6gse$H9(9IiN?5_U+THBO+WL`SJ4va(j=T4?NclZDZC8kw+>wpMsEf?z2F&^~ z=}q_hQ|A|j3+-53Pz>U`<~2Hyg|4UvtyP8(?c(&Dx&rx2oM1(N_1LuHz=8L{H$RzFzr-vh*-*k4SiNo=ob9-bN z*^bIn;VUggJk(o)!(k{zJT?pGsVsTz%&;)vpC9_4w;)vq2EA7HM(mUSdcQ`v;8R-D zkAig{Ar@Z7Ap=Ho8b%G8A3dAn37$qizV`y*kujhYM-<$kSXcmk(l_^Jy8U>@XXHD^&LyF^rWdZKaXiOUCot}PW@tc?QjDBQ-%QYf3ZIwaR`VL2uLlF8-f>@;8bl4-k1%xqv@G0q}(OvUIRG`c8ulHKe3Cr zX}ZW8rpa5Wt(-5!P31Tmw$`H7@<~6>D;{j<0R6JM&)eXuoe_^J=fOEBS-@ejk5*T$ zL36q!dx_G^5DFoL^&if$_YXM@K^$tm0+wW*`!a#aW&Z8sm$xD%vdE!lp4|SQB+BQ1 z=s#sTjB#s@u;Kc)HPK^m+3=hTuIZrOP1&}DLS9d36wn;T;648l2PD?K`-m_Nps#KiLPPC^a}i zNmFM!ac9evOZ*L)OPR_`*`J?*x@?}%o-|j`eLg}gu-?7g_!0&YnMRR`ZSvah$T-XQm{p|dV7sAb)9EfK7G+v z3{S89@@mfgbZo+s88XMX2Hq-w%+^3Q6L)Zd290&TES2(rIbz(E*o&2LAF|~^I;b&H zoIA4p!P|q@Q?4X4oIVXs+DXA~Fnkrm%~kv66E9JNZ0CG*mPo~9@-8}xF)5jH`zcNM z^bpjz*S+Zi?zS*G#9@EpelDzO7}oSg-T|v@PLwjQJ`2;l6yU6Srf&#l&xd)7itQsb zhY{HXs&;FesKlIEby1b^6We-3ux4oVD{BPpbp5I~CQ|zA6gp=IRSuVhk(L@d*Z4lQCxd$H! z_rcN|L8mE=bmU}?zR{Z)u&*F?BiI0^3LfH}e<)d;|_Xep*eagJn}Ml9nU5eq-K$zvWAjg+y0< z=jQ926M)y&IV79y5hmON^WWaOUchV z!2S?mgpZJyvK%>`sh0q0V^U|GHSVkdoOfYPz^reuV{LjbgJLQCJA-A~hx0#B(}vpJ z!8nLwqOprJTfwHuvgmg=AjJs=N&amapD!bnGqBe@HrY;`bQ6$EJ(Qg*`^lF$T0b$9 zoJX}~-!+fLSO{GKr zdbX;q-O$qXi9gjMDv6?MTjqjX(35P6#ZnKqZnHW>X!P@mmqL)bXno^xr5S8OqErsb zPQxP(S>H{nTj624DBJnF*@@haR~#MY>PROe!Zt15Kmd@AFAp_cHft$pgj>^%kCcrs z;nK6-RLb<`08d5P>hWgx5uc}=hgVE}NW}3Kt!>%KA<3eLRu&hz4b9AQNBcd`&e?D; zE3k@{O2;w+r)mfcQ=?sH^V}{$s%~-uEgxC3gS>{ zPaSL@iSJ@CTBlBBx$*2CbqCJ9=BF=GZtUr<_CF_dw`!QqCo>W zQYbriOv3BP?OdAljMAIKWuDRQKZMh*SmJ|WVla*S%9Ggo*9uf`|pAlKJ=jSe`;|sV`Oz_+)-bdB7x$Uj@qSlgAvv zN@BcwtxLU!o-v7-aTYr-zCuZ71jAVb)%^7;joNGyX?LM6FVlfiF)xM>JpnzLhB)Hu z5HPODLyeEVNC!n61Bv;{&NI~Gny+mazXU(b*yF?1d(&AWQkT<)UG}B3wEO&PW>Zew zVGAzHhLN9G_E}(UrNu>PM4KLqV57na;5WvgQtg8r1WdrrA$rLZ=(lqP$O`BADF+Sdh>I)QQC$v2xIU#erb5XxWm8s? z%P=gAjNa!_fgGCQ7PMj1gC|u_cDJj<5lJ$f+I(qc=*3WZmjx;bG5@xySSR4-vqxm9 zp=tj`xiJoj=S;K5>$OhtDU#|A!PO( znqh0^mV}@rz3O1oR84|o$pu5xn2G_Z zY`haZQvhFW5R}&Heh!80nJFwcZj8%^Z>Ccx0M6w=b0G71#5cHLWUyBXb)!#`-7wl8 zA}pIz>5KNhhidpm_`xhcazWm??;`s3&%x+@vSvZ~;wgXmFnLXP@*OF6=`jf#z`0@j zjM+RJq*0}p-%AMIahlQs1W&hg{}(@s@dVi1VgCGMzNaw=82kLAXSKsd!>=6-ZsQ9M z3e)M7S9~SHf~D)5y|Q(_BNQHKeEa_2KFY*q4!4D)u&5)=9_hbH zxYax8=s3ycYO_7=5FINsG_S--nbI-9QwRkdBi!Zts=d(&ApXKL3s0c3%oqKN)T$62 zhb6@Pc;6@3ls)?~3|Fa-78H}IPtO*d9{!RQ*snM}5eHqE)4H9A&-u(bOZM`re?Bvf zszbg7r_R~=LaI~_)18Lwwxc_)Dx@Higt($sR1Q;cH9}n|iTHi3Q};Ehd2$GCpsZa; zU{zZ^Kp{5J47)ugTzL8yyw5K|W#wM`9C}KLr4}$r*b%&55>1cZ#f7Tq)R5B8BrY?K zsZ-=pJPP497^kgEba7!$#>rXBZZ=?d-sKXdgE=Ck7Q!AiKk#9$C0>H{!$voN6aJQG zMgB91{hv4&u8a@!vkM_)NJR;t3{^*+vkn##O)}Mss5enDTdArW&l3`(qRm0vc5S;V zLmylx!M2f63NY@rxv!C43+YpbhK5SKX~fB}bOk{Uy1pAn)+HDH0wu{6_20L_QE$AT zU7y}|>N0pL(msGCB)!{>sMI?cvktl$Tm#y#Ki)F#X`6Bme(O}LBscx{p}fzKY+cGepB6-Nru{oSe)TjA?w zdP~vW?XH8_&dj9fhT1n}oO1yFsJw?P)fL>kaz{3!==7S11qxrO-;V8FIpqOJx`hQN zU2v++a7YO1>3D^MW&1AIX(Gd^f7vhx$ za$ln6Lma~zGr9S=F_Nnf@wxr@upVBF2b}jePmN%$z?+*q_N^tM$ej6jU5Xgk8}mp$ z@+xQ@!49$cUyDD8y<~Zu&IFf+fhkK251k7U=iJoV=Am~%GqdhI0;pVXiIh!|aP)Ij ztF~*0kx(m&XSCn>cA1GC4de(nwL2ox^W4b(6t9nqpn~=t#;{^ zGQFAxKdn&#%_OLWHtloSe!lii&|$5UZfG>xly91KBiQE*lV4&UW+iwb%W#UM??-|R zhij`pg4ZB)gf9CZt3b(Tj2Q0+%G6-y_n!yQ0}msSlr}hdE;xno!c@<=mdEVdo_vQL z%DS3r?}oZJK?dY*2LR%vpBhhnbJkwCGSn?{Lxs(Yr5CnCkO_HG4#m0njbz~x zb^=tDzARN7A0gRx#gNCXiTiN!*ZlYPpk4!VBQYpgIr(hiKM)f<-LLG~cF>9rK8qL8 z+&kj1o!GcXgwzb!6TFvQ$?B4(OW?{^8_^jq2{Lw&$4=tJTy2sy9wmX|y!#m-1#Yl( zPL!&V1{fg~Ru^aohED#L|BeLYd{DIzdnIn%&|3NPJ_|pGN7;U|$Il>v=to~waI6Ld z_vYZ&_fI5`mWQ7SMA#!^(ZZC>wyRJ30o$%RD!)R2a?p`l27In3Z^qnDhhh#437F5Mis;UQ>#N2BsE%C{ICV3*Qea}<8OKZ#)*5mg78b{Td}$KAQ>?P*D^^K{86r*P}I^mihn*%*RH| zsq=%Tc4_CbCKLcOx2wA3=*pbDiS+!aS02ceOAJRp>)IJqAXg?mXhcZwqb0tjlkfTa zr}=e79b896yx&@TqYC9E?u4T!()8yi3l3gU4p*f^gUS;E$WmWwF*^1fRKy@@Q#*0U zq&rNar3+Udq_mQDvxUG{*!0RN45XK}1ZRO1Nf2d%Zq-JuPee`jyFKyOPSC8tml4c9 zb(yrIi&;v@CAi%jN?xQr1CY7;+x3N4r%^Anp%QKl=wnl8f=KH1iuQ5q4A7w1MPzkV+cQbBg|^ zxc*}B<4Vkg80so2F;w`@X+gc5LIHxF5wmvqNg z79gr0(O0yrPa|xO>xK3tI%6DR28y495dR3!bb)h}rE)~-V@#~%(3qt_?MCYj2MmJS zwsQS7#3*RAH;#XAqmdh>2j~V@ckMkdd_M-xy_pUcq~X2Kt{)9Fasto1 zH9|E~v=b@d$lEBHrY(s#H;}76k-oyx3rZN?q^iJ0<=`!Y{zp6d^N9rxl9MaJywaC< z?}4n7HW5wS8#Xv}-g=h}@u-;FyIq5k5^?_cted+S$IGs?Yo&UiA5#hdpj;*Uq^Vn? z+eyPd>0S>$m*z}5Qjeaif1?qP9+mJ}?<73i0rCUinQ!IJr>_{GahNrIUz+Uty#ef* zh0;eg-^o4K(beUGM9pg)Ew#Ot^7B#U6R;2{f<dMgaIx9&WQEj!h&>_k(w%i&jSIckqRsp1N%D zDFOr`>62((Q2E~&@;?G9_#I*nR2VKFQKI2;bGotL@^(Lu`pUC? z$tGpSsO5J-@xlMfb=0W~ehj#e50Epl$}mT6Wf?4?cnOOA`X7nL|Aeh@ZIV8FRE7Uq zp-enUCLg1;At87LgcOO&SLSTCC3rjBPFK|+V=jPCYv5ckNI+f!ZBW=vdbtcVM6TEHGlFm4t%MPQLU9oDEL58Ao&X(E(0^+oI`n&^Esbfs4BGs^sS>6WA#ObIAU)XHght?FV|4IKDe0^ktK7Y_C956F?t}i>>hb9zs*_vm zx7P=C1uENh(_axX*I%393TPQt!TyO%ox)$y%PT}hk-760y0i+eLtCJ;)M=4r+fqcb z;+w^%r_V6Lm2J5kaKch+$Z+Mm%1K_(o#X-xH2C*kh8V#Ha+7TJYTYySR+Lu9VK`

    ?Y208qd2;yLkt-#V{N(=1lQ)DOwRO>MEHP`cAAM6wJ2q=T-UnPVr_=HC z6?gU3AEjDBjNS%bA#GV*NV~k?3A3ueo2RbbM*p`T=4Xb7d?Jc`A>~)_J7p7^LB*ud zmfCdJGUMkL=e^E!>|WEZ$pXmzI&vb(*z@}@tCKcLJX=39T)yL8HO@IOjD{8Imk6rY4okvZ zOE)2ADJA?9$xGdsWXhT8NQ5W!H!wrJmdLJ|pfjx+ocV!!$-NSd7vJsF0UAVvnIlQj zHEl4v0L~tWfC8k$lRc*&644@KtyW`ECM%?ve=W&x|L_f^co}=qF|tf6sT_BLB#pP~ zY$rev+Tdxy`>R-h%n%02a+cd(ci3uVDs%3J!@ax^ytT`Baw!wW*|a4yA%h!XYblBH}a8ku2B5$Se&0pMCR>qn1vtaxOg1JqmR)WNv^x z^hxAo@pQ^bfR)V2H3K@tc4a6hDO89zL;JZ@M7F7+ZhK_4(%S$zxQXACF+nHW2rL(m zRrz}Kmkr*7fPJ~yd!sm17D5u=f|o5Gmpe9er+YIMzwB2e|DQkjMPrXR#XX3_4?WsR z~c_c*#}SST3`81_ z#GPYE?L)l04;pgHwUTd19{rXLfrwSx_~v6u+^knx(>Bu9G=eRsWf}X*%n-~YLg+Ie z19?Chd2UdZi4k4?a%%!JVW!sh<_VCq3eaHE+tCu^@y`#%kxCkvoQ{`b05|^nD~d3= zg+9jICw=@^Y}+>GNAVaB$ZhpnI1l6BmIW_Bw*i2SjorXQ@4!`KKhV!%I?<0tid_-3 zXNmem!)Qmy2AMA(LEJJy2R09;*56*zk+&A979^ z64iF$b8zUYzrso$y+hi$SK3rb&MuUpZN>{zIyY5X$^KOOJ_O^NV7E&SJ zy+T7_@Y9R$(=?RQ5EnjfHyqN+KY8>YV9I|VMQR03m&6r&ErQDjiuo#uk?ZvB`lpVs zqGa$bop9;2Q9t?J;W~+yhd@KI3(MuMcc&Zb>P%Jr|7xBW1)hS+gwNRMaH{$)Q$fvx z)M`U_d2e{@5=5>v0Lp?fKj0Ls|2}4i%HQYg*Ma-{57hJcVBBkMXX06kl=wY*7DyNb zR}}*+ybGqI$?Ll-5Yr8iE`8MJz9F-!yhhWdmgf`@p8$R&hW5|c*WXoUSZmd|1SMke z;zabfY><1Vw(HFl(Da%JWSD7PYXE`l;1<^|yD(3XMxqyP*Ja1=n<8RDZ%rKm0>CSB zzO5L)HnDf9Idp-kQTv5_xH{b=%g-`~V!W9K#)A(44(8-_oLLO?bcBGNv((k04517c=bq!r*K7ZLQ(lgEjUV|reRMy#@@JAWIPfGuh z;9%{OlRX3jb`avl(N+B1XtBugtAKaea4IZ~umdiBbwq;VjzTPE%}A{8jlX z{HINO(r@8~^CbvkeG;NYkC}Pa9NxAfybY^JSxVsf+sD157$aQla5W5PNoTh_*PyAt zwr3@)^R>{;)Jn1!^_oT{jBAPb@2jFM!AV;{Afdjf>+*AN_uKA2mJMWtnhOhJ z8(;`s-=~L6rZnHo^;GZ;gf3E8#<+f*sWb=S@wbbi`JcFg1{JbUg-~2@9Nvp5N#m#I zn4aVRrMVjGbY@r3JtjJruEtO$;(Q#?K=iSLR^Qo97BYhlhS@La>&AN($EDh~5c&jB zjx}po2DPTYqt*Wg4XO@FRT%bcCcKFndhnM%VrcaWl+pL5TI%<8H!0$N(>ZPub72~F z4Y_uj^Tj^CB{dA00N~JRs=n%A1?JoSRzHrTTxJpKEVEbYV1_1^EPB;sG~nfz9H9mcZG%!e$k1D25>HHNLI+S_$Mo~06)rbGD3K@J*E9NE%fkpDXVYM*qwP&OFyJN__-I&1R$kjbi3b0E zhdjd2Lnil`$*&k*g&XHUNDciwNdnNv)w}Qxb~VmPkeg(N6`5I9-rMyWOr>wf_v@Mn zTf@PipvB)XG%>aB{AG|imTBc-9%Ayp_q#t(waBM#soK5q=Z*>Af^)e2@NKoMk|faq z&^Qt^wq@GwL_d=hKOcESa)l@Q34}nQzkl~`c0hpUMZR%MHLa=W+^s7G12nkT0lY#C zU(Dwlt|??T@MoI(y~_zOEGA|qH@R)72p10PlyB49(i%gb($JFd!bCv4rpc}77xV_M z->WbnRA;FT7+4VH>4C#HL@rQL@(9I%z$-L1K%-~@xHHT z&r%YYM+)6XRDuC9CY&1l7A)9ExV*SAILrq>|DlU~mt+>|t#rR$zW@)jPN!rrlQ|-9 z2tE9};9V2q^h_Hv2ZIg?hnbaTjI9QlZGfiMY5|G14b*iJ?{f}Gf@BKmjw&1I`*Ea*hhU65Is1FBG_6$Vx%5MEylwo`!y%l{D+IJTw?S*_F$IhUpkyw4xepI5BuquISBM*2N(RGR zvh21ybCG-=&~g>JiRexGPGQNbwybnHU+Wms3jm|Ue4t;c^4LV}aWhXiI(R;r9kiP> z-s9sgN7OOi2G&Ajo$aXhbQjKKk@zS7vQL5ZpzO+DV@A$qCd&j}6@Yl1VlC~hz7mjF ze6Q3ex{}jOqBe5ZLOj{>iGd-Ev<_?-2CtG2iL5EN_L2RQ zC+vT(NAhnt2v^+tttr9wo=i^P_<+G_;?{&@7VM*_gS|nd>+XUNp1JZGWw#QIz-*wq zzPsNbw&gVC9rFk{EG|SPBLM|nu>2UVpoTYGNmc-P*Ja830=HU%ozjEnMm`n_f-{TbGj|K~ugtztsotCP- zsASNt^{DOrXsg9eUr}d)J21VMwwB;)UTeT4Au*DD>j@@m6br%TSL_U3LN4IaO*vmZ zB%bR#HdOU7>HPuj{m&7PiCtPr?j(!+Ktn6$TfR7Uq4FuK#Fy%#9Ad5fOcs+!C_eqTmV&yY*WukP^A2c{O0 zOR2=ZjB}aBd}#7JDROMD2JY{P=G5UEy`ckHE6F9j$|UBl7lU~2$hS1K&g>jcg6?4A zU^lRWx+Z6O(v)3}JO#XH1OKlDiUrrU@$++K*(afysVvD{Eo-#(b_v&n(sjA;3h&8k zavRnTzHpvJ)EeC2=g^1>u&dyecRqZE#`hy{7V`nWcfS_+w|~&wf;gv~v`~#u56O4& zdw^@lDYg?m1=61Z{ndXacU^)D838Z?VSr$IGvjUOsBbw?xNeRZwk;EA2qUx9ukK&b z|3F7(#6Mz~tMS280(#^}V`@K;bzLhF!9x{FZu-Y&Ii_2 zcW>F7o7eLM{q^QM*4wC*-mH-CM=qC-@i0RTu`mAsu{l>vTw!k$9sZeCQ4Wz(zxntA zJQl_aC!tTf9YCG6roAQ`K85fzzHq*fABPTv5zv5L`uaS_X7!)<2Fn;#vqvrWnQuMU z*kFOS&ImVfW>p~X+l7j5r&KHBUwq^wh#n8NgMBHH#^NDu?mt5%{Jub9y5a~Hv54^# z^AUSwnD|w?GaHUkfy5GgC{DY6p4ra1TdS(8kMN!gM1aSQcRP()o0Y1=LAs3(!LB!- zId@jdGG~U_u9$*+4gx}EwFcU1O$A6tL@7$1zk=&;|8O)A5%5jD9l+In5)#RZBenCnr zxMj@t^nt{?TKN{)jjYJrQ(uWa7O2cYK30?C>T*^YlQ^4}t@OK^2bPX;ZPKxQJgh$t z+}04Y$Yh3!fi$8SAln@+J-~&$B@I~5{><6UQ?|-6v4w42Y_v!QU0^|$h}G(GJj+PV zk8me1(7)DxJR}Dj+_Yx7D{WG9Y9));hQDkLH;F1 z@!{ZEZbB*)Bg`}MT}p<zE8iIq0%AOrc4pybI z3O}CAEr6hYO-wKM9~z7;gaK+P8pDUUr*RO`ZI`ZY>VYN@XnZ!$k&XDcN*XOjLi$PV zs>Ns;nIOPa@xDyWZVS_m$*Em|3$vx^5umw6b>r$|YXCx*Y(4|s6RIndo_&>ePe}Kv zm2JY9;qwOUBR-RLG5uA%(^Ok$F)3RZS4CsXhA(6=*uW_5G06pR8*CwL(byyuF9p+Q zEz$I9iNPd3GZJ&F5DzXhD<0juI^KDZftX;`vl99?fe&TbHdrL(5gKtCrrT@{bb*Ty zW%jH#`R-$VY2v?5(r^DjiNsB&JH!+2j;nnCK`?105#As2;s!YG|Kgg#zI=9IkJ%UM z-aM0aP_gX1yiTyP5gqGoO?>nY+z)6YwhJZ?SMqwWleSr{vu1lCXbm+pGLL(mJsNa_ z9-^QSt?*s=iFP&;CHhtbpYn14al!o}n#?pgGWTQi z&cwgPWze!se(Xnc4*+r6NGdMCA00d0Ya~2x2js@+ZR;CdMe7X9S;^TTNN!qum@vm*kvFuS)QX#eSpDG`> zZWX}n44$QzU#X;4;{D7_);d-lGR-_LX`*4j3qgBRq|`bPlAuk(_CNp zF1^Z2fwPVy=?`CVe*YCa=VeyI9VC4LWi5Snq1G-2+aJ}bW}dIhM7fMIHo%7u8H^2_ zDq3XTH$J7!mHSH3gZ_G^N8NZ=_n0`^9APaoacFw{_Rvng&cP-+6F$qG@pe0xhMj;= z+zCXLdNQE12-LTl*jUVU->QBH(=eqS~IU7^?U~EQoSY+0Rvj5>-_!X&-=cbN>t$4Z5-86c0 zntX21Qvh#%-V@V-pb}58289Xx3gT1OJ$X6wMQiID5oJog)DJi; zac;legJCuza>B3q_!pD=!Ptzsa;u@uviq^CFj%M)%%ki$m*M@PPh$r=8x2Ao;SJ>% zniuz>zuRpf^Qyz4anSqykA1QNm+2#sVmY!Kt)@$GKwM#0N@lFd$TcyBLCAN&6;VG2 zFGbWH3WvcgCK+Mtrn4tb0Qn#5;TxAk_p*P(P|j1@v2{QCzK%dYt!Krawts7mO#&e` z{=k)oNpu!m^$5t@w%iKwt`6NHJ7h#_s63>)ysR3Y@S$I2JVUN@xW~&iMN^yeb^2!e zzV-@*^8;U&G@p0yF<#Ms;1V`65dgRg&J%lh4qC5k##2(8o5pBOXaI)3IQ4@J zqJra4fDAuq(4}^C6sJ)5+g8TT#g>W)V;}F`^)Av2Swb9fOvdCe-A;0Y{tR&!mQ=;B zc{2jc$?V_0PV4=IM$AY$>KmKq^He^4`Sf@9 z#FQ~aKm9fKER>qfy1hxF|?83TCUyf}}?&G6U z%|wa=o!*-Fx5(@X6s%+kowT8p)6&Yfl*xqu5ePjcGkAn=g*GzYEK4|&Chs~HrT_Ge z<%f=KOFyH|__Rc1wEJzbc;+gQdq~G(Vqlz(hKTo~P2q^uhyK14FCq{_Mjz5wyM_$E zP*J#M=bP7!=sU378syYr#3hm)%7cU{R6)^ZM0_b`P(;?C)-HbJeZh(M? z^qYiu>tQlMMdUq*g-L+jo4B5i433nE#o5}J9=UuqdY4endu1sYU6zmY(pt4O&f0~! zD4OTp8}Sc>kwS>Cq=O~Xs5tsY(L|xU;@R?b4JUTDexYnQSJ!)|%&7ulq~i=&R`O9A zA%W=*&?>l^qtWGr575wb;}6mQ@9D(9(j{Miiur{)M~$@xK$Y6PC@Y^Dyep9z-Zv)!xPVQ)DUKlaM>vD`?$>p*K%8x23|SitKs-}!wHQ|FDR8Ac~1Ia z4FwM%Nk#wujb#t1VTdznTOlq$ytLNl5B&h$^OLI$xCy+j=MKZ?0_gZ8)a?bzG~oE} z)5_tG>9c0ufBg19st18B&OOF(=U-V2r#K`|hKudq7Ob>#c8cz2spgq?_rl?Bzxs+| z$k~$4%m_-&lFo{(=53iW(UdQk(5U5&*< zGWQto_WeOgt}Dh}eFk#JM>i^p*EjMH8|*wPR39pS3c@^OdgO%{>2?2TU6-3)S32~E zHJHek1A*N(E|IVP6;?h8lK1EKd|P-Swi-jYxQ+cD#--51eo54$d}->z9##b_ef9?Jy!PvWePvx(F3~qR7t7`;K4U zex0!fAwGJ#RYphDgvO9@boel!GsjXpC`)f)e(Ol9l|k~-O@7@OncnG(x{^DbnOi4&AE9AX{}0`gRzkg2DNFu!44jxaMC!-N!~6@B6X#@3MgmfBb-iQD&X=QyT02?$PGKb9Ha3I$YjB z>Mv|CFvOb-$D+d@G!Z2KzgA*deU9_!%^#KO@y|CFe_kV_Z}*LA^U`LxP1`VMB~f)? zHzVh&f3aDUqz)u&)=VEDeCvtGtle&m*hiWWA#b9-c0o3$R~$*PmB>n+v^)}$mR={- z8IC@wGbWNtxAAvnZVSeT-N(DVNbKi=ollecuC(lqb=o-}`lX+dT&pDh1mW8d?U$13 zE}&hakhPC2$u$J!RuU3hQCy$YCWH5Xlz6{BF#hlYy#ewd1jINw!KQ_ES|&|A&|zWh z{rfM^MG`eKp|#YvjHwVFt+Z%dz@lU6rC7R`$5B3e^_cnhs2yLz>363%H45v!_2AC zp^mHv3}NX;ij*JU{BxId*qs35vaFLgr)_C{V_#FEFlc_9Nf)rN@sEy7Zs zx91+2A?g$_54LtOUUgxhdkL4D(ca+Rt506fPw!89<5YWpG@r|`WMicQAQB>52~Lm+ zuaa7BMGrpNS~6B36BS|__EXa4#rAMKI3ye#XV&;^_uM`1-M^O^iHrLdtCP5$lw<_=^agIdg_VKmRhTXo`n2`lKO6!5Y;^bfW| z)96B>r$4aAiw5CsDjQol=eYq|U7MyVJU$|z&Ae1|sUSa$GMpIb=2=Q`@(F}+>-x@N z72Q@=EOKeAsV?e!trBg~qD4*_HYr*z&_j(t@8BEA$Hiz-SoXg@?Q&_pU`ZQ-j6W%E z>aJzg`dDY`9`8JNx{xmJDXsPcj`wkKja9p&ypoQ-ep=6@B;iIpGW=HUt2ngdDUFwJ z=J1@-r!;hBZV)4O^qPe+dU*rW4o}X#OLhg1{;~B3rCz5ii)A7Zde*p)o$7UeN^9g} z>EH6N8t0RLAxB(!?=P$);_OQ?YSL{Wd-7}eX2HdNj~PxVh3`Uy4#?#^U7lzpyahPOiWFSpqti$ z{G)Xox@9tT#{}xTMiUP1{DTfZB;I#ZFQPOC>G+O&-rIge`^#ed?}a%g7UlNx@CRKYPS`C z_5odo^lp?GEzx0a*C4SKly|JF^?0O%{wPG@bsS5|tK2L^r zB0IR3*QHa^33NKSlB8h^u!e7ORwZX0`V1V-`C9YfD8j#t3fGD7 z=v6hM60SMVMpAcN+Pe><^jhLe-+o&k5fxPg#Q0Sq7@z9zca=S;4fd#oyx?&qT1sAq zcA>N56`&$-#$x9Ss@>u@Iez?M77R|bBGqo3mJ^2>|G9uoY;0JIq6jWMi32Gm7X??W zD8jv4lKv!Sp5?$8wM8RM-(}~vZNB$+M;D=#ImXwCe_n;ww@lf4Sa~Qe=)CkB*MWap z;G7g;>-o@+ZcY)pgI=C-f%n~$;&w-S!}{a}l9xzZlWI{X=gUR?f3GFt!XnGEqSCA9 zXZROidegRJo^f}agrkA$rqDCrF4S5yRZ=qJKE{o=T7f}&4fG7Ig=S^hKIcX4IS*Q7 zWMs~)OKz}!##({I_p}^bye8h%dSgAncZWf+HB6op+haQgYg}S3<9W90>J8%bWcMW< zy((?~wnX8U0c8U;fMo4I`;D6azrAKe#PVZ}S?PyOO*hm)t#&(RRa@>an%MMzz1~S7 zwini!H{ZHec7Ln$z8+OHYoqq{tEq-Y3f1Kqja5gWka+Ft)vHGqq-;FY{+X8kjD{|c z^zHs1KTi6X#y)Xi-D~#7bCrc?_BxB&%KBYGY)Fy#{T2ym(Mwl81O=`v%)hhqcyGL0 zd;V+Z3rqH&WNG)ee)~AebohfklwDa_jfM7yMuTL^;Q_(SI7Rkce6+df#H8y5wVa*tMA~SEZuN^m{bMsfhW2Z> zeBbybung_!ZSM%~6C1kuZFa@Hlk3_2NCQYq)_AhfeRJKA5h;9agxD^KMYBd5

    ZZ}?tZVK^&J|19pEM2#$n5WD~mWLP^HJKZq(T`I9dSMyZX86!SE>C ze9M82k~6mWQq0U^WK}*{;X?WLqm*^t^Z7S-zrOL#;sFg4+lFW_xY-rXsZ-uTZXsMa z9xe4ki~ku%CU2L?wZ`9GJOSH^t8V84_$Ey~+34t~vr}^i8!Q*eY<#Eig<<@-pt^*J z$ymJOH)29lV)i-3_pZe=NUW-&dmD+%Sb_aOn)Pj{lr;5madVq@52H(Z4W!Q6BhBl- z2uVpv?G$nZAx;Ye^QndMI1_&2`n5T(YHDf}r9n%s7v~v&Xc7a$#~}1y;N_M+dN8;5 z%-joiMHQKdAw94Ah>hy@?NSetzDPE}@?$g@iYo5JS$ITxL&G0jj7TKm&_Vb25W~B_ z!)jh6h5sq-!kfp3E9MG+>z^xp?Ru}SYRF=3-+-NKCBw{bjrNu)`dj4;7UbNCcN@j% zX%JKLm!i)(mgsj9i>d%id(ICyQN8JLbKF7Z`r*93cue|X{DVsK;g6mYB-^m`*`C&5 zA+i?aeJB=s8ce&E3miwHOqqAy>Z*$&XF|WAJ+}<>wUl6En8maJtMINFl#=}8#mGM& zMkp#zcO9NHdFUt?SvXeI^KuGSWZIh)FEYC*FE4e#floo;z(Cl|&ff7bGp?)K#kcv6 z%e~nlE;LZB)_MQ_{WV6<851vC0ZviBr@z@ZB`;l(u`FccO6;HH3&q?0gqFhf#}?YS z#ptHC`z+-dI$jlXV_$;70W?8d(8G}2q_3at1|`7OFXU#!@KVDe!`N|XLnXS8Mg>_u z)_dZNS^9^^d3^7_}+2)8XFl7_w2t zLuZM%plzmw5FbBqM1@{y6TiH?KCwMjd+oVPWY0Y|W>D6%>P^ zvz&k=Y=1n36#nNh^11M1I?Tp!q37lyCm|`5X_YFg^5@*4UEr2px^jhq7?v@rPIo_F zw|#-nRa-&h$VLyrmTwzON<_N3bW6GQ(1^JXuyikIUkkr--pU>B+9;Kh0vDd%+cXr_ z{@~`&e>$0sj>Z~DQolpNYkzvX~1|5 zYxJ>-i}r1+53fb(eI0e5kkIBn@deU<+^N&3jqJo zdrwuL!-}x;KJIk%2M5Pt`(%9whZKxWyn9#yAFTIgcDbhv3jqKRs5d$9x^})ex#M#W z$fW(nw@$!~D3qn0;T&3*{s4b38L-`rMbK-#b4x@!=49hi7mocDiFUn2(<^BFl+@eb z#fO|zXoQ}FEtoHRy(8P|vBulMmSfRp;USg8|-ob>w zbfR$;;9XE3se6|Cycon_5hF?)oM)uqHrTh#7>YUA|#hPh2cd&VZY01B3F z9Oc??F|=&XZZ?jbe#us|%6nInj=$4Fy}1(OL)SsByJeTH4R9_{*7X18OMRV(FQrg; zS&bY%0c*5M-lf|`pFKY_R{9ii7Nl3&#n1M^LEnB~nGa^$uBqJ+Av9v8^G0Zx-TeK z0;f}AVxqEQlCp|QF{<}Z5Z|o0qs-D#e)}xBt)6`z$sHsfjR2e0&d4t;49dWKw*;8) zf#b7|(8HsXt=w)0*5xolS*r_}m^X3OZm}i1JufH-jQ^r61(QQbK4*mucCB86LufY& zLf6&(>i4Us<0{>7foy}Ta>p(oW$-g!C6u$U9v2f6Q}0WEG_wH*z%lx6F0^5T4P8$h zZ=d03U5|aY^ih^YA#*9%23$dvA02cqtmwt9KRiNmaIRxHg?zD^FSU7 zt1M47dE|liCIq%a4yNwy-kd3 zrF~c?jB7O*&S6xFM-Lv*K0C!=fX24YB2^WDL1(fvyBX0Ij>I@DLSTD;@Y&=Kcms7IodbG$!Gq=f ztwC05_q8I=XfJ49rn#I!dRuJUN()?r*?aD5UZSgTNUwa^c3dli$44n7I|#5eF%itR8cn*xxP6?^1|>bLfsl6_=9 zP{fREEwq%OharALMBDaA%+iEc$b|XPd|aK}9z#p%{SIz_B#M!xy9AW^H96=pLbZ(C zcL8QdUX*84H722Q0VU9|B+mJR8csoWN7Re%yM;vXSr@E}p8Q*Kr$vtmq|J}j( znrMC8^l<>IN$m=30kU+{Im$V+F{dpeb*HhX6;=ZhmF*A&NnE~iWza!_&@t_Cxfd|3 zbQVYKC7NvS56vB~8^I>}Mx1b)c(BBeAjY)a z)}1X(b{fK+pBoE(`1~D_tZ9h;?(?~D>@Hbznm znT0+|i+@T(LU1$8ZAkTURhm+f!Md2dcZZLU_yq4)cv5e#G@}b!yEHNT=gt<@o#T6X z{QSEViy&~oUd;~YVtn0c%ouDn9R zZ9EB-&Vxt-oBfV=Q+B8ZZRf_RVV-hRB)8`O{9OO=M><)r2%=s&rJfS|rPKUuCd?i7 z96fq8*a|%@e&ToTwPTIUX>G^;#@@XWR@SRnShzDp^yO8w>h*HnvtMjLNpS}$&$6_* z*d=6QLTdL{lNZmcMNd?hMk{Np>0zLp4sRv92f6L&F%gqTi6jk z9M{2GWznv}zpmf-ChTBv-Jty&D`Z8sFvgH_>ng~G`c%+nHPdGjVsowp^NZdL$n6}{ znd=uUX5EXYUQcKnUN4T*8NT>7eXOy%rYnMynQ~LeFefjeLce#aY^Xz-eG9FqnIoQb zTa=8X1-cX4qC&@`oGtEPQYxXw#&4P$D-BudA*#jZ`FTvfWa(HP4jKo!SK^~@-drYO z|M{AslF(%eWGyPE;zPr87Y&U*C#?qnzasn%SJ`D7qtZXyF;Fh*>y6zDS3+#KGqw6& zrD5@!M!sb8$^=P^>Z#|9LiS_YRT_R%m0OR+IV`If+8jmou3p7sQKm>qLBW!#((wD! zSo$&hmE(b0Arspz#yh=AN>Ora*YP-xn&#~#Ylrf#GB?X z`iddB%Z8-n7)wJAcu03thHTM_6Bj(U2Cz^!&gDIE>WRe^IR>#og&XviIVKjaNnhs!%oHT78AJwY++|Q-ut7R5@e% zx#X1F!;TMUbk)^wAR(9tv$uN|5moiNxM#>&PCo9_aNxs^4IZM_y+fm3GUs_BI_(^? z=M)*ftE+lFep)Lelci#4%%^ffFvowNanDe??KI<=!K#NPtA@wIWOa=VR&@`?oe4-B zZF3V{gzu3YloKn6?;+$C)Ed`bplYbsW%qtkrRh!S5lyv37sE!aL7vM&IUW!D&n~O5 zFHWhd%!#b|;4A5<8FyvaIV1QUgZZ?(TSp95u5@&g!F)XDj!f0aZvM+b(+fW|y`mM3 zn*B*m22B!)<++U2eLWq~Yu!S$n)-*y0(#u(@R(7VSr}F#fpyK=7veD%l|DFLTu>Y| z+7=`r*y@wM?6vAl-{-F9Hf}-p~(Qn{jE52r#Ho2$tR6%wQ?dG z^fI5f#-2XlYTQ$wPZ`^i*k0T%Y33|zZKstZTqRTgbWkj@eUnpLRBd)Lzj9vzTk?ct zVtYxIQ(u;t@lGDnqxx#rVXH%&x4THEF zoF71)q*Xi9eIE1KpCHrQaSl;x zV1hd=tynk@_l0i(#IyAI6jGr2+IJe?3DsKRh8YvbEBd*C>FP+*4NkU zX{vwk;{bpYsK{^aXs(N85bDOb+31J z14fhDw^O>lPuUNzV?m3f1)G^q@wcwWxA4dHdtJpS#_C~$gjz8^v-upptx+r?F zRjSyi)6sV!as8MR&3@1C1iau3u-#k}&O*1wj*NL30RA08|z3HuJf=>wB=7h+G z@E|oUUW!3+ANsuX(}Qd#4BvR(s*7RwiLURPbXtP%zsm4jo#>vlQ(q7BmVG|TTRB3X z8mw)yLFl@lY|i>|1+BS{Q`*fR>9|EtbjM2Q{uQgxZ2n4{k}f^dU~SK?#h==(WSKH$ z-^RgYJf47O{9w}NXmRI30@n0!ZJeR(Utd7dXlN@*&6M@a&~1e~jEPv4q)}SNzKd2J ze3Qb*N;%4yAI=*XjLTcQu*ES(awe#Lz%c2d@k4~x0G3!7Quhj`7WUe6@1Se~;W+pT8r%KB9o|@Q@k?N5*`k6*M?==<$)GJAk(mz@h ze6=)QXePec5#Z5e*2{w44`MD_?=(KfbCx zi?yI^<%#w82qO58{pQYp&|x709gIN+hm zU=G@#%TR>gkyDA+=T!`AKBE<7sUx((l|(buwZaxlJ17UT;I7w`HwC0V;&3CQdm z1Az3pEuGhcr?FuytyYke^I5%dSZFxEcx#+qQ(DzvR!rxrUXgcB3)Xt4tyT>1MOBCpxWJp(7jGK_7g^HtLHF_$;DP|>hd zCmS3K=PaIlry+OGCeuz+%hBcOqj}kb+oUyJiWtl_vAC5--UQWsV3)8}9J(qqc8|oF z%D$^Xm6Ufw-!B04IbW^`CvFc)^h^fQ0j;6ebv3yPhYeY zUmSP8+b9qbdOJ8+aPQu|Ij2r(kF+3k;>5OX#4+BBV|*6xkFmwEqXQ$(zOS%$`uD%} zk==Nr#TZL4Lk08%pgC^XC6Hzh6Y9+C{zUJ2IeeC?T+ltaB)?xS*hOgVNrw2;p-_T zNr5#3K^0M2`-jf@#IT&TaYd3v8o?(E^Zl;iyISBlI`Z@fLn#F?>bp^mGi=(c^=Pk(%JA-*@coqD9a@G05uKm7XD-EzpOGGo^wyl{j$~P> zI7AYToW)U`1!n?cZ*<48gfbj??8~MVrQL@DYBKrKqg2P)T}msO{bko&xs>n@?I^oj zIrmqsS=0OVMS-5Av`~g_koI4zQYtS>3l_avh=e?&qG@-m<{FK`$*8O2<_ph0E!RlZ zUt^XXk!Sc$PtvWgnJ+rJgViJUWp4}xtq}crFNal5P@a5XSMgv=*Y#4;qOM{o8Q3-z zwgW{VEeb|*2&Dt=6Mod8_I9^ z1##b@INpW2?9)guMcTTeLvY%qF=FSjFV89m=S)$ol5I1iO1*>i?77pBm!4|tG2h7a zj;*3XmE_*fnB21Pd;O5aiLlNim6efIl-#XAF0ZAbt?Ok5E~rYvDz>Rwb?}j@%vHF_WKJzixH$`=eWXx^j(nhP`#CFV@wI# zumX*AZkkJR6!KBz(jDEg?s14Pl!_?~8rMDpD zy&G(WE3_7o6G~+|Pt!~P_X{VUhXT7S8uwPDz| zuH~mJwER0Pzb9W=yT0!1-8noQ6xCsAUf3x?`$*>#{+eANG}^OcW2wTwqPdM%b2R>Zh1dwsRasga%5x|d-vCu_8F+IqjW zK~v4h$cUTs_kS<0tK#|oQ>Cm2HF_IsS=vP}37HE;#`R~p88))D*X|b2%^Ca<8!@T! zLd*Ah{S-3BN{eM?-&4!!saWBXy3-n&sg8{~yS{2PAm_hre>-#FR%UA46-qXot*+}N z$|#+EIyfSFDQ>Nh$%km}sk=J-Kfb?~@30NYu-AB$f0-^jIQuqE=~*7SnmgUqYq_)M zJn7o2g?gSFikVL9HLn!WCbXe5G>xY|G2O*j+t23x7$*@_rA=_`&fR*C=CiR>mz3R2 z-RD?KwbZaX-yY7{E`<|}OrI>R-tPuF`9-a$sL$B_`6#=DV6$oPJ?orrhm3B&Qqpu z60Less|>E&v8VgHinqp|GX(C7Zq{xL$Kcwlq;!dgU(2pz;J2>o>S! zck5(ln1`G6cHJRIdzbFl_4i)`bGyeqAN%bGokQJ1dec(At2EejId)gw60jGt_mmT+S-4h;2l5Dq zK}!~Ek^$@x zDC^O9dK!xOyNqYJo^%GvOn*DF`hPY>@bt8AFTEQbr{x`0WW_3O>;%eayP;!!@D zuj?_SB1-E>;!+%XBW~f--)vTho$w#KeeTIH*UId_yd{xn9TBl^lv=vID&_DihB60h_d3e$3?(~BtHMPN~2lhVEj0q4r&tPsi9ymgXYf}@Wb=}8+aDQ&NP;UwRU__&D zczGln>8Ag`DAWJb$m7T&=yMJnW-mZHFS$3EkeAma7!5r9oVo0XFB-2|^WGb|{YbGFNzw+5xs}2Zf zFWVe4z>>iD6Q{F`>?5MeFg;=~T${RtCt<_PBcPjf4V^e~0RbS|L#NhrbJwJPeRFo+ zvv_0W-+u7W2u3t&yL{)g`_7>@-e}YMcJW?SRmX_TA84E7;C&;&QCV_4XX_kB0G-_i zIlU0DTkrDpxqaiWaQhW{Hy^K_tiQa9URdFE_^N*Kj?!1XU*Xhq|HrU$QDhlyc zpu6=VMb{N}Hmz`@zJ`|Lc;ro~sbkF(@Q&YVST3n|ERRwLPpS1V;(cWJdV&38Xfc-! z3q{-#GHi6;H1vQ+niW8fDBF%TvhIMSk;*?LgTzY@8WGI>|5?%h^G8_(tkI>L8n~EM zsU^6Uu&B}=p$iGI(`}!A@`qw{PUx%<`dzE_&;Y7}UJO$Of2AfRQ;9Ix2 zOJpXZCjnNBI4kbldGTDmWiLjjUxU7452CMvRqQfv#4Y|WV9FL0+~RKo?759Uy-w4v zO7c^ZRfDd5@(6hPN=W|aisXYu>GR=X)EhGs6aUQ)!vjR=&hcr&f;n4QuB1g%Kt{$O z2MmnP#_UY&t-GJ@vu8ZdoQ`Ulo@Aen^mG3$(}RlU45%K`r$#RSVtOcMc_LR|buKnk z3THf1W!lpffMY9WX#3#=?apFfsz|QS&kUWAx!NpOD-qR*JVdY0$tB`8Zckvg6$gR+ z*;a{}yk+L4WZ27De62JBB6bViamn63!0ESluXTQ@^`dMMS>peG)pGs>j4PkJyXNPY z%8ApRT5470d}YO!UC`Pd4>{a7%Qk+9yF|pMS#Gbg@`CyE%<+uE%;G=~++K~;x4|fK zOLIp6eBKK;hMYcJP+IB+F2vX*s;le7GREs@;}Y44o-KA}3+to?6y)y&{Nw`cZ)TtQ zc7C$kaE2k%`GD~6pV+e>(Q2ac=GwpC{j_0TolR!n^t1WwZ_(fH(wOLvaR_2Vr3<669V1p-(RWprDF#&tG`rYFhO9 z1y}NwGK?oiz5P1;YQ~}3s03k#@ zT6^=wix;2nAO69b+kP`#Re+9z`6x9g1J{9ypN|w(Ge|JW_bfRIOU(qk4%IDvXvM$F zrKhJCF?oAUsw3Bvt-aloP|*QF)O1|)NQKlE7-~yd0V)gO%Uu0Yw z`8>83M*&w9w+V2OsL66pbYop<<9p>w@=Pvv@_V4G97Q)c7t4W;X7BJ7NXz*rTg@x> zeEjrjuFNYqOen%N<-}`gBpy1iD0L9%Yyhij!71tB1^#}1M>J1>*V8266a^kH;34i! z3gf{=_bmTo8~hAp3_^I;FXx8HR-oC*At|XhwBs+;@x^P_thw2&p|+tU6faMVI)@>( zZo?!ZZ6RKC&tM6=P1RR4qAZIq5;jcUQqYMPz6G6kwIiV)ynOY_`TecBI_N+30QqqP zQG8O57w9}vZj?E%KH1dN^zI@{f;B=V`k{C8nWrt_G4m3vx2+U4`VC~v7m9-jwc@uC z!yVgMY6G^pm+&%efOvt@u44P!Q2sBa(E5?@;C;h0?nUqRRPay=U{TdmUQzl);FQa^ zFUA)yT_PFO9t8yjo&#!(_|mjIT&Hbl0WH)>flfh)t%$&-k(x2)uM-(k`;nW&?dy0> z9Ggg2S8uI-2vMt>h$f3=Gv`NkI*)-nyP3+30LZ_Ib91OQ0X{qHldm)8f%)`NAfNWZ z1^aICaYIG1=tYeh(j3JEPub_aUCAc-OU7U*-E05!=~IxAIpGK*7PX4V+(j&Fw?08? zw0=-z8>*4}p6Bup9z3|lg>VZO?H)7KGISq%LZjG8TuQ{xCnZGfJI>yD*ScJ$R^ z*p?7b(Tj#%e9DjGa>gUcK)(dW>@N_0j5c|A7@spT{P+ESDOm361x1$Z<6Dl9FY zl96t+TQ-RTw^&=aM2%~Q+B9^IodQAmhF@5JykrXGYXu4L4yRNJpOA@o*Ue3}Ft>gv*BDeKn7RogVyY^G%qJL5!EtAJN z-}xnUiz!lI4=-ecN~kb(Vh+jzN-xSKchF4!=DFZt^LRmIaS+$3`I!!KrO~GnTuH?E zIZa6MK`niET)R7krk|4S){!3eN+7kKE8~U~DNN|XJ!5TSsfN)_I|Tp!6G|&YOfJ}W zRpg&G0D~~SC!w&1djmIjKI)-&GlblWJ3=%BN388ZN3xNan@nVfz4Uy&WKt&!!vFst9ARoc#m_$mW#E!ovkRCB9SuOw< z^>@$2oP*%`Vzl~z#Lq8f9-w|km{466$^c~qL*$u3YRYF~neT0I%e*JpyEKXYR zUrZQIEwS3ackgvf(_4OlaM-}WE9yYXAYzo~=^0W8V}xUx_fpNVp{^rGF@Ruc)!q45 zbx6VZo9Ftb0X)mlxpVc;HRq|Ne#Vd*l@Ysg5*_@SMRLl@m%*T`pPoUD_!hkZp_Rgq z$T#+4{Q`PXGDskMA<;D}D9UzmMciq_5Gf|@F)$AAI5j%Iv6Yf8!R*%aWGtj-)gop6RvJd{JU^b;_z>AJX;M`)@i8fZrr+Ms!!6qJZV0@0`I2bCIm|*Sa2v5 zTsaK#^Z>0CQz}dkbRdy7GqR0qjO|FmtSDvJ$x-KqsRV7;KtA1W9|)cv1=+PkZq>6n zfAUGvXEV;cSGI3CAr-oo6=orr;P^b zl=?V&Y;7rZR(?=4=#9iRVN6H3;p^~&KjXm9pFR8B|LYg82UytbV{5FB{!)I@9BL-S zb2P^Hq1GWyz{|i8xOJd^mFq5jmXMGz8_$uS*S#rbx5>p6Y*W}@QN>-MLe`l^y>g}O z>2LAbblJ1u!XrRO?)*gn@K^^))`x?oLP^)M&V^vDEoY){&^deK{@|Oi=MTs<(oT+w z%}|<#In4NJ{q4WkV>0su-~juypEUb`AVEc)VcQM{xU%*jTKVmUlxK;^02T{NhLa7< z#jMogc&`(FRh&Sv;+J-Jq1a4K#?4xQN}8Sbyr(nz9jmBubuDE&*4h$bEfdd1KI7auq^dWbb9*eFq%akdBETaUEpok^wTLmlSubWq4N$m$bNf3 z%cjZ^!u0~!{BY=I3h9E@Lr8$PDH<`l8o+WE*=<|+M>%KCk{^;watt=vAOo&}0O&^H zy2^3rNN>TFx!u?o=@?UnMLEkw+>j2PxV9gzS=o*Pc1GwL8aHV5*?lS1D0OhK^$=w` z7pML7x%~`;u?4umI?B{YHBy8Ya8DRiera{OP&YinGOr!J2wYiq0~E{`2IO;MtXE~P_yh9{y{wS?u_O^%D|=4j1dQ!r1lsJOm-PI zPZY5QzYZ{t4(FCi_YPbW4ar_OG8C-dSmFbFNi7k1`i!Q z8a}n-MKA8RoK-xA`_Z4dPRq#ZA14Fzivc*+I!k?k?V|~HuU0@`O^Ap;8q;6dtvJxCd}* zZ{|kkcwpHn2&UgrHf$B2M$ggTW&+`nAMPP^yjKBa&Z?ZTg+?-L=hqMWK>L#OZbgp!D?|eoT4Ken3pbHhr97Hgnzr$)zyn=w}E%!C?V0{2wwUFr=ha&mPw+& zOg}d$+H3&lvO81NVx@ya@F5M}xIVO(5 zZAxW!fdV`s9viclz5)62v!>w*bQynp@p`7>>9cPgktI)0Lt`)6I!W~qQz!Pp{9;Gw z_E{ag;&a~m*f-q>#Uvw=a(aE?(xoL#>9hOa6rA|g2Kb*tOUZDW>u5~hwY%C_!?k(y z0kntA6Cnwq!A;zcPAlpTY`x~MXV{^)j-73$__-DCz7 z8NY2}(@>+$Bh68?;0)gUx7|iF(^CUz@@}_pgm8dYGuq!{-Xkr1pS-zVHcYAA%TR@g zj)ACgB*b#sGc(qEvRJZz&*{@y^SMrtocG&q4)9u$W^IJg!qGXDY|4)Ql=e-{?k||O zy+y4e;1j8n7#?kyYoK&Tus7sEC(F+?^B=4f; z+Fv@J$GGLauT935AZKg7Dkpxv&cPl2Cbx*sk#qRUHERS`+WVsHg-z@MgHtWEPxR9h zBv+pxEx>OY!~%1mY&Uz&8}T1-*!0XK)#%TxUgu!CZCfi|$ZdG}tXuQJfWfwr|i zD)o+lo~B@CkBBow8jtV@*KObW&)&d!XaEygs956L{QT=hMaqSq6VO!hXT)ffOU?nr zcM#I^aN#NpT35B-i!;qAu%g`|>T~$hhc*!?=D-h}w1aFe$u^X`vK{zpG)CI_B zt%fDW!6Z~?`C#hM^Zhu`-xNJvg(keOtN!Z)Ub>7zpUW=dF3=IhNY8UZi3te<%5e}+ zsw2hO6C^UIfcDsuZ^+ODCr1140K^OkeRPf=;`0r-R~R~VS{J5R+{ZgUx)9orB}^Gw zPt-NxL7C84e7{HQzxcuJyA*-MX3J% zA0$s4%nOh`JySCypjh5{YTV_wl9H07q+h>!wHGhRO`L&3zD*;&KAe;i;1ZBuT+GUJ z-8|~hlN)Y3jr(1O`wcX4E$5h%+(HmJoF7VqiBx76?6O?Op8E8I$PjOv1x7^h97o`6 zdb9B5oUyrm(C|E-gj5b)G-HWLOnBqOWqOiB>BxfLuRaycCR7E3dE~e~*XQ8o-U(?` zt1w2A>+Z3)xA!l(I)FsFp7yyweQZ>r$4HHtqa)>M1M7(@p+;hUfIhmEA>-%~#VNXF zrd}ZP2l!~(rh0qR97h@bGQOI+ud}n0T^UgUlWtV3$D2_ylz`N)h#d^WJWwa#6U zrMP-Wj!knLa|v4mXSI=Mc$pWrjG(@{ zYczpK-+Sof$&(M*Q`%MH-9Y^aZ^DhIJ!G{Koo6}$FEpqM5nxE2>R|l)^L@j^Wm>Q9B*I3zfIQSo0$Q~dYPZiN zf}o&wllDw*k8Q;HIuIDlsXqgZADMqC_Cst`N?pLVXCp*9Ln`Hr3%{| zmy6bTU0W({+j;?Yh-8HZ@+$(By{+uFlm}24@wuQ^Q$@&IKkL-ft&p13_0=r;{i4sI z3L&OGyc=iBm1m1F+%3q&)U<6y){k@FyzFHJK4;zxqqlk56eu49zz90h#d)@G*WFqj z3+o3wF*-9Un6srJfsGgZMjn?KQRqpDVIQ$k%cMD)^*3hQerc9JZyvDCS`ZN;Cqm@2 z8-@}qpIgLkrL!A?_nks7amGwbyC2T^?M}tnIYAQOO=OcS=J?el_Cx;&$iZ=%qN}_J z{^E?@htu59G~Q4h91vjsxbjx5XtkBa%5gXtr0So1#j^Hm_t+`mH_qe54f2RUJ7uvt z%%{DeUd{*cXmHtsjx*S+w7KH!heD&0LBG@#;Nw%unHtecpC0da6JA33{Wis=D2X_g zllX8W*{jE>!DFz6lRb8-^v0ndQwH*>3S+ z6LLRaLNT$eAj~#YB{_36U#k84w)OV%T-3LE)x5-qir*JO!2lBLx9nUDq#oC2T>V4# z6mJasokx&V#!4D7;w$s^Q{QK{YRYtqqfd_0P39}v1dfDazbybD%NZBk9t3DT`~L0Q zw}kTlHo>&8XA0J;^1;sScNK;Ui^)6kLWVttjC%EUw80awDleSo(%#=F-82j-*U;E~ zja5JB0d%)Eum4SGnEiyY2xpmMhspDCw9ZBdf&&m70bS-XoULu_1a{)^r+x-%EnnBl zfePQi)s&+xajYyXrV733S{A709_Ykmqp2wKDFAJC3`x@p*m|4`ehe%W&R_sT_c=pL zf=GU$rVOEvV#)lL+8cg;JB8jq&2aTD?nLz6#?}P29=Wdn`xiP5?2`K~CJ{tOIs2s- z=6D%-*X<9MI=(0whG83gA?X&a#yziR0XLfZ(}V9ozF`T0OJ~_`Td;Wdon>G--MDQH zm#60_QJ^l%j@mK(Ayj^@-E|}J6oj~YEOl&fE7F;U2QgoW+lY?1>Xm>$NSrTSBbkAH z{N10)1PAjmVyc3L9N0>E3~Ck-I(cq6H$4u?^wn*-e;+!U9oV13 z6)Tp`zB9NPNN^40YCL=<&vAoha*fq~6_w=qwK1B;DGbRLp2;8-;2?n$d#weo>Q6D7 zPsXI{J~IuMj+~IUgzLzOVBW4vy&1Ny;wix7lwSL?TkE)l?Yd$D(HC)CxOy<`=6Q8Q>p;2Tw5UcW+iet`jAHG&EF@Q?Y~o(NCn=KP-w?B+_Bs3L)kL*Q4Kdbt$rvC zV48PkvO`vY41>rhy0>lr)@IdTjnRMHdvs1ztos*?uG=$(^B0Vqc{H$^;pgU)%VVT6 zguP;U`A#iUn7ibn87POXO*}9bR(`(JlcJXC9-Ik&V1;)rNFASFZJNv^$eRgT=Oglf zbp;S32Kz&YuF5TD6+ijW`$SVtgS?!O%M;`a+W8QBssK5(*0DodRym$h;zkbRZ;#3I zomlX+)x2H58idb@Z-6UW6tJH17tVA)=0Am+pSD;Ess-=b;ikzLY{T~;eiG@G*HFs0TvKve9^Uyrs(~OdHD_dc!bw-Bs>C>mHixf-Nz**L>+{LUo zkeAqaR~MaE_>Th=XN%fSm2D&-IKsnziOH~()iXH#8uq}=V`ioV`@m~|2{JR_B%0z zA1PKWffpTXDa*C}$f$@pT-3^P@^^BK;*6=?1+BqbnSyJnd&ko?EZ#r7NT1Z5i`Lob z!--H!!p$ti^8{Uu<1aybJB(Bfp_RDX6a(^*Aaf$kaSqo&_v8sK18rqdUf#VK(6+R@6I>$t_YOabZk^nHkrYGu^8dFg_h}Q$Fz-T95VcL zsDa<@l*~|Yg~XiFyM(o=2@DYWv~F4@O%<&e4|we=N8G}l)X2D6+T{?sKy9U7jokO) z^MMEvDoyxrXwfCEjzJ0`f*n0a?U9kt3Gx@ zd$7PVwSo0wxtS^*jpDC@ND~$1dNDCE4$)JR#MW>Wn&=UOD5`VvWSW!uRcj@^-WxN|#{s3l-7I7Y7(@tpIdc z$`@e%2iFBNk2hklLi1C?3}ud_CRlrmBf&YC`KVi1twO-MfDgw0p;$KL)bd9HVWgLZ zSs1Eskj6$5PaJi;quD6N(ai3JX*BtuWbi;KeS0oUB6QZee>0w0pc?ll$B1SxuC8m% zD_DPCu{=uT5r|2&3FsK|i&DFfm^?c}OGpNf7u~^$Uur|VSPr=C*{nswrE7$q#)fKA zArv|JDKGr_?f(7p3_XS#PblC`kj}5tm5PNf)y5SaTT}eUx!9^|?l8>G z0z5MlSppsI5w<&-@8`KzYaaGW6C+G1m53o4Ad9Cxljzso0!Mz#-N@zFHT)lofhI8; z3wiRPq*$N5;W^&ZqCt#d*C(IAT&T6R)mu4@!p@#?BXOSYL3Q;&8U4PDZo%}n+j?A6 zEiWgTFKAOq_uCV*P4t5$-hf_Jh$mU`bkOYZpS*cytB%cow-cJ3ylm)Fb4O||27Emx z!{mGb6z)aRG}+g7Vh&SEE~Y;m)fk%;Ks%b8mZfjO^OifsP>%u41K5>%tTUkdtF)Jd z2yrXjq$|lkAo~0Bj35L545zslRsMcY48$+Z#yx%X!>u;aW-@L}Du}GBZpw+yOs~%{ zFr?=D0++NxJ?m^!iKE28Cq7#Z{5F?E-B^W?;U=KufmM{FV}z}M z&pa;C>e>DcHD^3bptdNZS4bG3?Sm+0_o2T&cXO835t83R_i=P22F)pun4K&4b2yG; zywF4NUXd!7$SruYoX-1E9?FfPv-~NVaBC~eOEZW-q+=VBfDI5yKKqldVnmYy9LSaq zZJ+I^{`(pF{%O4Au#AhmMUIdxN`6V{EhUUP=LCqom3@2$-h;&ISmJZ01{1rF zoasiKO5St?awY6SxOSY7QF! zz=YoVVh=D!b)*7w4jD6%h$b%~^cOM_bImcx%GV@~FJJ!q5QtKmh_`M_eIn^4 z6?3VEl0)+Q$(SEqt~rPDn9+l&K+9nM%wkM2+fFFKCLqugf4X(pe@Gxlbye`z zpwU4*u~zhAsLOS9GvJXto}d$!K`d!D zqoTwd(h_*rq?>e%v#hMleQi+RV!2sm$D+P<97voE00T(?3_e$u?+vRpNT)KKXT;to|f?jSlwdZF;q zTbwc&X7ls*__f*o;j}Uk`e^)_9#A5{T$BT?(^MF+&jIrf(JMYy9)$gx;w4XmV@DX( zg(w+^ka#aiIOuZ|oFOprv;f9`G$La-FT}1@*+B#g3s#6I?z+6(Si%Us6~z*1+&a$9 z42ReM$)hN!;W*N*U8Y3d@@av1$6npp{;1Uv^vrSRvpqQO7cGza?Am;3mL9^?^0}d(#FiocivucGK(2TSfil$h*9g;M={mN8@iUK^Fz!%LbhdVMiqaJXtFmh zr2NX?{^NO!&?1o(Vj_#ZkLFN3-EsK!R+IQ?{WST+adY+J=;w2W%Fi2&|*z->B^N;qBlK>M$}7j*l_ z9XOk6{QZm3HY~kkn91zs%cce7^MrQmzJ(5aCt;dgpLr@0`K2%0mxneJkj6bi^ZG_e zNL+f9Q<|Fmq2ZHw#+_)dR-Ej7&%I)sRUmQS-tN@52^GQ?^Qa+HBd_S_O@s-osHnIH zxiYt~aA{`)&d9->vG!FBZq~U|jyixe$}MI~ssD-`vx$_HJeF`{J-0c@YkN4Z-Mhz+ zrAgN2UB6zD(Mp7T&29#~Jcv9vr6B| zm<9y&)gy{_@2Jx`8Er`G;;lDiC!7L1qAcZQTZ|R;}W< z_z+!YZu}?j*3k8OTsnM8OVt1*dJ%E|0ETV|ESHT!~vmZ(v^16@_m9>BOIcI5~cz3xu*PUs_ST#+tC#D4=_G|3X4 zfa{PR6!UqxonY36>N!I8!#ReOD9=oWj4jMIW>mw>Auj%Ltrsp_xQ72>d(sesZaz$3 z?MJ^14*H>QwGZ^zHM(g)AuG902_u@I$6b#=8!^vgr! z$dNW$ibVR0Xu|si)BkAl&G>j>XAFUB1yjo5yzLVzDvB2? z=gNmj`!uVx`t{2I_?_=9dHx@#{MQLvj^mzrpl|)`X%u51Ap@C+z|mAV&r;8wYpH*h z2)jHj@%WZ@ws&-hg-8mm$%d=B1=xC&>sDK38 zY22W6y(AcAd=$2ErtNmqr^FXkvOjAb(2JyuCeru8oK4SzUB*jkPOuR82&S64%D$H` z-$XlJ?+$OdRI(u`b*3m$GODscD@F0_EfSM&^4rJ4lV|DR&24LPBXED*vbXQv-GYEh zcWCYE)ti7tk18zWC2G3&H6`@fK(fCXrO89UrVuD?R+RQ$R^BTJfs^`UFu zmP$%zxQ~Cu9h7=a-;=y*42fG<<_ks8zm_n+gxy=Ih#Fy7f*GjyKXQb9*ChLh0 zvQJ)K{;AFezrCpFSAPBa^=YOdaAy-l%Z%>G^Rl;rL61u7{89Td4BFyt<7>hR^-FGd zGor|ifB@YdegvB(;Lw3J_nH(R@%PAj9>_RxpEOKzr-y~2CWw4u07Cb@$Bso5nwuP< znVz1oCcr_iE%a8xf!zlNs}S(GudYD=R3)UDqZ}x zu+R^C`9fS=9BbAk>=%&bjYt=(nu0}d*h@)hCVscXiLWvn@C6SM;8w&^>bQrW@>0)V zxcV9vP+N}7jCS;}*`KZV3|&8mGN4^TP(QFH3(dukk;@aMKFf7@X0+QzMX2YJ=P1LM zpdNh3;(x1@7GqHvW*3!3ZDU~M!CI9Kes>s3L3a=bkd?XRW>Dgr5RYkIa>USm>$K92 z(G@*#zX{X?$;TXy^35L9V`F2)uA7&Khv(?W{(d2_8XO&5Alx&>C6Zw=kCrxnpsnx` zpf1M-zgPbdX#da2__6_ethGGY@5L1IE% zuN9+fntTS$IfAYG@R{gYFMf+l6pVSjq*dP|M=IlAy1D4FKWI#svzD5f93&js8dD+G zU;2svSeCpxWa6$9{GQXlHqm@^@0>VdSHV>iBzjO2jSuWKF?opju#E39<#$`ejU|_7 ziP#b_ci!oP<3vQ)T4@f+DGVuku8+@xFr~Kn*B) z`GX}Zd?3z(&zz_&4Q*0Fl6hr;rTIhVBMi$}Sqq>*SIqXyYkTqL&29o-d>tN+vH8ST zor8+F!2ziqHz;(mU)FB=xxoLuD`p@n4bqwg&pc!0tgK?cO-zIl*5IK%D6GzYlWPA6 zZ00Q*7Oj{JEn;55LmW5WRH)t$<|mwJG<2UHlgqY)U`F}uDvYqWb{c*1jBe7%1DeZ& zi#zg*%>R#v(cush+RwNl9NnsMCw=|Z+wnQ%&f*PeT__0?Y=nbl1n+P&bJ z@tKT55tNTkdt~M=ZEb(n6S8 z%57Gc$thQ}LM&+u-!cSSX~CP2vy_%fzYjbztMmrolUV%_VC)hW7LC4lX72*HN#oFE zDz(X-AMPkZqvQI2!k(T(t%W05%s)$MlUrI1=V1K|`+S8@P_8VNm6g4T)8%E0+fj(^ z-hCkqX-top^A%N=08&>``?#$g;$8soNdEI`9ww~E_$!CoT1KDghE_E<;$X}0Yot)7 zVAHkf-t+k%2i3;aOJVWXlM{Tr|8iAkk@AnN-b9yNS0@$|$QwAEUDjmZPcA^kVRMiS zxwmhxz0K`UcCt3Qi5)vnrsn~8-UKzGm`4|ebliaH!9F7+4mG-)dqd;n)d;?cg0!~D z{1CJnE4Lm~3wOA*VFrWLuVbXZh4FsQ?9ITVR>-=aPXEx(^?w5VKPBMt#o~YyHKQ1o-`=>oee)G{fZ5_Ic=+;&2A42Y_jk7*zp+}@T|c!LQXWGB z$fWjpeZ0(TgOU-WeEiTI?i5>&8EHs#MUM{J{}Gh6iiF%3_h#+fXHTQ&0UBTr5y`d) zEO^mbBmFQn*-6IWgeC1^7h{OleyTv6B{u5?`M>Lawo5U*h7t;#8y*2m8XWM}j*>DI z5$sR%nK@K{S47`ebhRLv06}70itlz#2`KGaTob$|=n0#fIKQW-r|X`?4Cd>gOE*q2 zJmQLDCa&uysD?ALF*rn<5Za&UrN(M$m;Mofst?rk21*}|!>=oQ9uA&W^F6)SA3%BH z0;A{-3R&mgk@L%9Cqr^-1avfkPKF0HDkE_MI&=g%MFCV6dnqqttv2ticjM740#Fj76`zVwc@ zsWBnX|HqmAr=36hcfusYS=U5yLHFVN+pSl`p1N00w`kKkMEA+bNvU{SB@B?yHkgln zpFGsppvS<-=uk*TZ2>N>4t|u#`s*2gJ^nx3Y&X$Ta9t7a|Fdpx`}gZNZBmZZinID`a2yC?5ANEA>F`~K2d0XhArosw z(g!GDi$HTD?v=1q6_4%IWC|I=^u62%ssmax0uRpgr3827dd#?Y)+R@hva{+GZngm! zmNb*@>#t4oufG!{nbpTtd1OYMrzB&1SA z$nG1ygr}X{OG`^zOJ9qDW$k=nVPVOh6Hp{KzrJ-aU>(gN;VD$zDcTvRCd8y|9zXv| zCdq*$-F3Sv)5)5Qf?KC#rt;eWnOBOmUVUV=L2N7iyBg9GTEnbEjg2B4>6t97^VdA4 zhbUinS>DS*2|$G>TjOco%w0)eON7y%g?V`PFs8xyy)3Vxyta*aZ4vT0<1&ZCnJ(4E zRaL2n;!!>lnrB}Y26a$S>}YkZRQ}h^`oI36gW!l)w`7vnyOuXpb*~21=#6#a;@V)= z_Fb1guodA^%c$k~+1hjHCfxe^>5avVJAqh0MRc;_>}lUj-6ekkSFRqEPSGFgF}AA{ z^AO(*Dc)~mBR#5-g(BR$(JXxgsPU2DB+~8zFqG^&Kv5$@M%MH3MOHZY|HDTAhXpSt zBCgeDjwJDw(v%Cj9jU4!An~K;v9^xwES&xAXh_!^>secJ9r@g`dnw1uccGdLIyfiu z)WbX^5=ovDXrx4cAin7Zz@(%TWG@Nc%R>U*21~B?nYAct%Tz7V-pu`|(A80bzjWvT z5VwO+IxhP7@at_ZLc#poWuHTJo`iiKq1lE|un-~WNZ2%c?p%jdaf!o6UQ+X6@GSBl zc9zBd@GzVNX;JgeF@)sHD@7x@^lW10(?`r~kZ_+&Bkf*go|v0z7Qt9JBBK#6-%^7AK&A#3w|iu-ca z#Ps&COrnQGe6Vzgf+vb5^nJXG7cVa6IWJu=N0L^AwP--0`Af)>SH^jOTm~mH-!%D+ zH~;G?{yxFn_(_8Svm25}<465(zBvvg4lqaj)Z@%hGn|UU8^ThJ^h}~wybgB;ZAt<} zUSzo00go-y{PA$y(MdURmoR_{!iC^H#1H`Rh|GT488i^PZG%d{dSYDhr#DqFsU4U0 zuM{OItm+j)~)FI>5D3y&v}&Xs~#zn^SKUZ;YoZX&uNbHU8-ceN5mULj#C zO}`UQQyAvRL)%#M#2v`Zlt39?ot0>DrwKh6IQ{JatLl;7TSlQQ4w4C3_?S5T!M4J# zc|djz$Lxy~qYo56sQ~$u`Q~j>Qu;UzCgm%Y0ZsI?h&%T9gOzG9caM_N4X94~Uxg0Z zG7`re5$6FD0>AXFgx`m59wkV#FXjknsRVI9)*E%c{N~=WG#GuYmyv0_wiPG8@=R}6 zhfm{jj1wYd&$*tU@c+IgzW=K*+1~3KR9wiBUCnbXBt!^D^TD*B1X(F`k`~qnJz6Z6 zSB{O~I=;p}WW2Jop0q30?Y^ol5J?=V;Od#azf3jK1RHdK$TFP@p}Rqgn4XSK*drF? z`hn6NizJ?Kby${@s0>C|-#NaD+!Hk-9V{@w*>&#wP{5{k#d9iu~R#n$a77 zmDgqWC(FH|y9pBoSDjb>9^77#>dj6Vf{04<@sopDq!kzEb!g*lqOECn2MTE7&hgGf zWUrA?=$HjY#0J6VVb7jD7wX1Z+uAOMgc#oKQeU(MlN1d{1AernB4#xIus=V6hMCih ztKwOF7SB4mh`btni%0SCr4Pc<)7fWZ6JJ-M#EJXOfZT80?#u575Ic#>E4H)}s!gpb z_FwB=v*67NnOZ%@z>)^QvI{^AXuU8V0Zac$@|ESA6<`!9-QbL4R&}Nq1PB3#H5>jRWdEO+-YiJX7c|;5`0@WT5uw99dkLN#E-{jIQ;0*f}2g}O2PJGo6v!+TG1)u%ZE%~qWm^Y1w>$NVp zM3&<|ZN=XBu0t9Q8Rq%-Rd+ElF^SsGY=z5B8w7d=GTUMkRE$8!8i0tpuB#PEXTDvD z^u{jhbxgzYHK;X&P?PEEbvY$%Po^-TU5<*U@_8>&w2~}I4kt!Ku5`aG9T+)i^e_$B~htcy?-g zT-Spx>~nAy)PeoQG3;jC1azC2iTYSpbT)O_TeDmfd;hke;Qg6iwAL$X3rb4vpdPxb z2P8i?-E7#I#fHo&9P36W_hUzg+4MKU$N>2-?eb?Z7~vJV*JoGm_?exG@x)sTYK&FY5s)B?3cd@k$*m%Y*@VU2&sI?L z4N1YvYOu4-yo4wjLAv{Vxi=`|4H*`Oqg)%@HEIio3g;Pk$nGa|e|=oge%gSZPkYJ4 z#DvfI!L5WD0ec`Db9VDB4z*cbSL;6kE`*z|<|3*2(w;ykZM z?oRGwr}~rUTOQ)@Z^Wp;s1J7lSoziXoM|BdYdr?2YPwFtgNJnI+vB3j>neHsc77u6 z9_Tne4tP@D0ak_OQ!_OO!dYV`>ngl$m3yNQOfZLinvm-R|dpzMtFm`u%fX-JG2F@I3q3d+oK>-o;gI z(!0h7v5d@i*AD7dWu(@04La@d9vjU*`iAoO-v=9GU1dS9MCs|L;~+1GTPQ-YND9s2 zy%RXNGNa;b;6;Rl`_VFz`xY6Q2MuAi z%#{RR*5Lr&0%1;RrklG zOV#v!*z`hWkHjieA3NEV=C>%t6l05-={X?^cR)&18CnOiI_;S~$8)0@+$}QL&Qd(Gq(^Rz8P(VuwQXj;s#L@#0A`&!X4K{f7X zY{XL36}^1cZ=Wz`!`wmE`*6*JXXtd?Kmm3DM|r$frlKyaM~=kgOgGVR9%%sx#`&`JM&MhBUa2DEZ=NwC<>Y94~Q%zIV5p>%1w1DCQeni_SA^1JK%6|XjTK6 zstcY`V_l62t-E?SD$to`3fhB!>bToKZANm|5Fm*IPc_%(p z_zDu~^*fU$o!@oGCDjgtlb0b08xXY-;x-cv|7`oXKfGs>X-XFk;V{;5Ul2=5vrlK~ zIMOJRvpPS|djqm8Z-in%n55&Q;nyW#F5bgAQzWP?Qw`#;*>MNEhp7pVt5DXL@?DjT z@_t+MRA4XvR*5K!C$uX{hA(|tVsE@AS%R&8uCbII%NP_(9dHYc`?%OXTUV++%8Lg6 zcB9jpb2Jd={NZ*@>5X1|ggJ+R9-&fm6U7x=p@aQU^>T1<(9ip^>L-XlYQ>U_dY(bW@B(|lAS{tvS2-q&^D@}Q zs<4nU>aocgB(y;^uF}8WZaf&;nCK?*fUTiMGVe1+7hW7|c=9(O;ve&@_kiBFwMa$t z{rJR2k3!g^wS(VKD-QdW!|iy?bu`nyrtAUyojh6)WT>H-T|N|n>z8PPZ+~KyT8N0q z`_(`K8BXRXGgSZakx1J}m%nIOncuUxxL6|kLZ#S|{^t>jx77FKNt_e!$OTe9PNKj~ zq%8p%ve^Y;0Ri_y@91uopWOs-`+?LMwq?sSKS)(~4WgvcJiKNM63yLHxl zx!|<16LDt4V7~UhM{E-2!boktrH@UO)aE3R1u@4)jDfRo&o061KEhNEJvrh>**i#S z3n27h;L+owNR2_zNs)ar(|jmgM3A; zXv2+Xft^$djOPK~d$1`{=G@uo+W78vL0 zH>)w?XZj=W2Gxu(t{efvKC7!!mw0?^B4Ha4rZnX{HD95zA})06Rpl6+c76M_2PB5- z-Kik!WEBjQ3PmTX+jy}&{m|KI7OqxDk~69i!e3*j%JyxWHl>vJ*wE1rFII{7n6;6RDC_2oqq`eR`N102E9*dmuQ zZC8y@lAUxeNiM#OU#Cs<@Pz7x#Nt@O6o}X#*lIhG_Q5FM>_J{WI!ls98-`K6J1;`ytrqjxKRTOPgZ^x@QzELD5ou!E<)Trohm# zrKhVDwgqZZ;h(b_w$LYZ&z{X9abz-4W~CIv&Ats*GwYAHxyqVZ0-CY(}S5?Fv2Yyt?r6d zHB%7rMR6+$EDM@Ltug7s8_2bPk}LEa)(ahe8}j{OJ%1}xT@<+T$6@u^wP>*y4=pan*eO4ni(RJ5%mV>Ag^mx7u<^7 zwf7|0`bSatQ~ET*iqNxK=RPqMG+KF`ZUol;2N554`bDeip@tHwRep2t*)v(%3f}n3 zkZYGf8LJg$ll||*tjRW!1iP6sr)8@=i5HSG(%u?dHg6V|SLII@Gp#OR(~Q{1pe>k; z&OaH?@^x&i6nWWtMfDAWimpjm5(?v=(1CuW^-<0HP0iDFrle~G#%XCsLZ)UK4+*%}DigGkWOrw0cDE%~`16qoKvL zZz$vTBV=mlZ9Y+N!I0@b{6>jCe!-HB5%p@_$1{mdqIm(x*p2{zUM_eXcqc+T3<cVsQ1ewztB5~)XKbt27=2#pAEYgp}~A>K9>PXy){yCy#`usF;y zE8X67kjyDTnb4R^&ax>kkj9Tu-o3UALh+8t)tk4FZ#LcJQ$%0>K zmQo2nNMQin9D?e3lox2rq&tWo;oG%KPXx%7?jTOiAmoXv#tZgq$Gfdffc;!<8kj1v z%1wUzuyzb#V0<*&#*n65ibUm{4HCS;6wEr7!Tb6*ECz%(fFAybxXpK zxokCm+H*8aB*M!aDrS+|ec*K=V8{VRi^<$S!L(h4h=nR~3pCmH_$qlY{LhSx1JUU~ zFFp_il`>=9E56+h-qgGam*HtyNBGrD0I;8~Q#-fong+h8sc) zQSJ2&mv9}4u(5m3WoVX+ca1EW*$a2Y3(xBht0D}IwymDIxsqgDvHhY1@fuaeW?nwN z(2QMNtH2NyR7zCzbA!KfLYRL1lXPSq*9bm=c=z(CmRjV_LUFx6xd3(?+ofQYNd^~1 zCDw5XsV4>ig*MZJd*g$xpa55=53MB>1}@I*YlY7JdHk3KeYeI}W!A)lm@q-xBH)h%!sMsH;J~Xnvx#-7G-Q`TjHb|A9{X3o_L`1 z`A}KC$BKB~#onL}J;%-$0&sQOUg-PSrhiRmk7=UfqoGg_l;=vFJ55liuYLs55u0-ez`{Jq4tTpQ8yxDA@U3{6$c z^a17w2bRQRql8=2?VM~J%SNq{xD(6D%`LJa@5}WNJ6)$8U?nyFCI%Gj!wbPS%gw>% zE92&zs=k9BQkO_Qh-F}ST&_lm^JQM}G~ei7SH%Sm&;#nV4xaq6t@Ih_?4FFFNaICP zUunTFBBD6g@4|%(i^s<>0gHzKraNO4RrB9o;PQ1P1q*2&8}keF%;S)EB|S@w(b(_3 zgc-!DtA5Rgq(d{vjKV5YRUG+s+=AHji!%^!k z^l=@rH#$|%xu=P{HNYsmG})IO`YR4vAT!#Q)=M|MG}uQqe|J zp=h24-JhLA>)1k!14v`LTYx^}4zzAS?>LC&FnTb$+)mJco&7SvD?c|gE?dy}p`sl@ zF*?8^Z4@YjrVDoZnR3YQ?m;BZ(dP$38?#2?ONQ!^muLyE4-O8_34G9hn8Ui@{S^sc zR~>H(l7y3!cbw+T9*QxJbx=}jbr0KF{o)H4soOFmC5h)FsWvRl^7Hc_p_M|K@-dl; zu=e=J*Ve{MXLl#)s^9P_tsjd!xd1@ac*rB(pAV#P3Ki?%(T!2kz=jCqJAdU)^YlEV zEe9c)O-t&pPuW8dmiei1(;T0@Cks937QwNY=^;=iKb8SVTudjHOP*CC2Fr1Iu0YAi z#Faf?6xn`pX@6a_(rMr(9NP>S$t8NSu&}eUmmrN_y>)Avm(Xc=cV`i@u>*y#`s4;r zG@@RBl)Prgj)v~*#2OxKGn2=|(1V%|4h#-h*ELL5X+A8UbN4Ffhm= zuOf*l88snX;_m1P4^e;UB3?v`rv9`C|LdCm$Dgu-a1|ptD^&=s>ujhr{7CE{#)%hY z0OQx>xq|)koOK<`5vT@1DmBvJu;Q|IHyBgK;78bX@N^=bM1hs421CEZRT)gj3Bz&Q$pHEBg(JCVKS#j^tgh)QOGeDSdmo2m zc27bXA$F*LD*<7@ZyL0|x>p@t=^$`H{6DVe??s{@kp4XSv)a@29woP*$_{$$L(Q)n zHf~J*=4ZPG%QO@VB$Kj+y?vHvfBv}QP8fh&bPyt3%j$Mj4u(m0G)YAJ*<_B$k4@&)V)d3az%tk+|=Ua(+65Zn?k78DeK1+F1(-}~_* zP3O^vTboWA08`3wj$`XVBsBZu>Q#pW7Spb%{~QAU+{s~>&DCt%#}P=doD1wfv|3%m zwXoDh5ie%Yy4Bkw6TsF;hJ<1P*EY)la5VkKq+<3#?{N<+e$kR8#?P~dYPCAhW*s^k zk3z&GrbdfvrOPKz_}rDhAHVnKvGMoy^WO{08m2+^#ayY=yyrp=hH8@xV8#BhRq@k6 z7bA+k4+MZE=*;*K4E+CDzEd} zFJ8HF6VocWLOmuIZX}ogwDrWYG+qK|6LKc@{}V|*0>Fnyu|g$+qdyr<>7u*Kw^_9a zyTW4;8ouTnB!L^Cc^HZfTldo;_J)1EYr-Sn=AcHlVHoeL95YN*IeW$w>nS3+?9!G5s7%x0>bv@E$yA1#44qH7fhnP?<*R{(D}M2Vi$fi&$fnOGAU8QG_{b7&@4<>4_0ExHkp5ZOP-Wo=`=Bk6b) zIY&J85lcBNFPlTQf8>B*6mZMuO#j)-c_O&mZ%a5NLaJ{Z7mkw#@lnM*#)sQU4%U)= z9?fN$24H#<6LbQ|5x=EAUc^s8k_E>788d{m8A=f!@+3{Q$?4A1rbL|jUm*88Gos{~ z-PWe>(^v5h`e7p48csD>bCNlBPPR&+6qMGO03!@yZj|Ebf^W?S(UN}X{X$1-U|_%i zjekPw(SV@Ba)+m<=cBWqPY}&-T$$kvX3>(Ci9WuL+huUw3jEK;hth6t`NZC6?pWY* z1PbI}LO6o&uO~zO{dtfniK>KeJqLCzA)y|Y{4AT|Ae=4P zrVEQ9G8u4K>V4_8>(_Znok=FyJ<@zm_#7qvs}hB8@Lr2BWD!v}SF^Xts@j!hPM8J{{I?yR1m8%37 zm1Yb3P)+M5gUvgV7fnQ0RaO$ixdB976aKQE%TSh=0&5M0lJ*BI|MN8epWD^rGtMKf z{;*0`yjcAugf8UA@~rzZ%29bV*^fI#voc&Fit&#Qwg- zWdi%oj8krcXxhmFkj@$&p2CEl7@X%{3DZuOnJGZz6EKt#^a=RUR&Q+o_RS^xOxN|% z-9r*qz<;8+KiPaCf;c2hFW`;0hL3NL0|j-jEl=y4q2%cR@aw09pPu!>clBpgoSCL? z#1lOZ23qY=DM|b@{yUpnv0uTC#rC~VQApxoC4qNW85eQ8DIx;NeUXFo!pU_W+*ev*EpE z8wWultpqm>VDp>2?uT)Si&RhQ>+3I7Gn^4?6TvkH3Y^Nzx2Egnw%KHC;2XuO^O%?x za(pEA(_AWhiQxdzy=q0@@+ov@R7rMe$#pDJR8;5B>g?=1hy>rfF>Tr*51DwnPy=>P zG{_%t8(G|J$H&KKh^7FtftiRZu#5^@Nanx3)M@(B&1X}3d(2Lg^1{HTo?94>16K$y za*4W{XhtFCoV1hS7f>+W=2GoHH9!a~7=oEz(G20#X2Vi;igaw%+wq|uelpym&#C*~ zFgoG;`trvuDZRzKOj!l9tS-?eM=rAbTa@^lGR3$bT2N9B*EMYhwc8lYLjwIT3jz%B9fBW+3_UkN9 zA*|QVp}+8rwvC>c?`UCRM?VB&K)QR}jaX{BS!c48#u7R{7E)Mjw*7Djs>hl}<+t`6 zavPRmSJmXBRXk*qPM}Oe_KDY(fD79Z+nM2u9v*zi(It)srT@I<4V+4z$2hDjpe!Vu z=w(FK0jPdMP^2qEsYpbA_+t3D<|i8zN`XO2*s>rl>I5%V=YLv&DYA%4cb%Kz7b57g z*(I3eKg1Nj+U92yuo{!{hPGbu2x4LPy?8ZfxNnUG4EK(}RY0%rhFRYEKg3wAZ{t%j zM^di^F&)C-CggNSHn(v@HbgouXL@R1uDynKr&<3)|KQ*U5@Zs}O~`^9(-zACF)_7j<_zpaYf|LZHKeAd zFk;5m9NPI|Xk^ST-~2r*u7cPY>$-g2OY0$UCpsEBU}N9InE{8n74X;!B?haU4?&b} z6y3Qqx8rh(-hne@=H9=hO&-oz!VXE}GNRKT?O3Q3lO8VRT>GvR$tFqCT*#GOCRdh~ z8t1?S_wX`oa2?@@#Fji+#%8~La1KQNR090nFEZArfSg&8$c58+a#^yr{Eyf6<0bv= zu^AES{CzR!=_+u$><@1ELrMnA(1R)y=mmcgVES2=3Vs6%QJB=*+Y;#e(6Y7x)&9lH zm!j@Fw{BHAwD!gw35QpL{w#SL^zyYyg(r3K%wPJM|9O!Acu&PI9hvugLaOpo}5p#((RP_DjQ{7lKWewd}0)F(&Aw)&aE z3;hMat`01&wEE*XSO|X2<#1|7qmmHe$vPe$G7z19WSq>g`mJa_rWb}S0|a;!_7*ZOQ*BXsU>TCxHV9DuDyaDmu&rC;tK%PHa~ z{ymD3P4bU_ihu>8z3!sv#c_d^*c@Oh7_Z7l3x@0dhGjB^H%RMtp!u%-VfG~(^*snb zRfr@vHa!WMx+#~TFfBntG<^rmHf#`Q98XZIe-3{B<>H);Q^nGs>j2mEcTaJYR8(-@ zc)@^?8d-nfnzm)L2D}xeCnd7vP_;7ZR9>RNRB%ngSkL*~lI!|&2d@x6gZpN;W-^!t zOJMtMgaba670IU}FMi#wuXFP!rE|Fe7RI%l_{$#Ag{W4@6eMCL|>j#6uzuLZk z-8Iv8dHmkH1{$1XaTn4Ue$-4hKox8);DLG#=YSvRqSTs$GE6_K?X%YliA)vUmc>I7 z6*obk{Y?+}{|)FAMzZMq{+vulCE&jkNI=Ugf!FrN(L9{%cM&b>4W`l z25BP!?q9F+@c0b{gv6}CHLO`)9%Er4+fPS1J|_k|fEp|FPM{7Rz*{iW(}K+5OLtA# zS}Nf)13j|1ZDw&49m#eu`V(I-Bfd}narghUHl7opGuK&u|MX|Y>EYyY9jnQNzoGkb zNeQvbdrahfq(}QILf8iY(pp#&kqq+I5ri8u%L6SPWfEdB7za!#z|I1VO=vKx-xSt3 zk-8pp@*dopS(ReQjt2d{jrXUy>t_=SktCA(ju<#mWuafZhYna6l_!wzPxYSC^;L}b z(JTht#UR+3`1wPD6Md*ohuc!!bCjTeI!SAbF}(#Os8W{|od5I?{`Q>yR6kWt6YY7fB2KQCt9NG+bk`r z0fRtl*=HxR^^yl4SuP~w`ReWo3nINu+LP!>$>X`D&jnxV8I&k++YyqL%gWpBGQB94 zNP}18^84#K@D=;j8p*ngS(9=jJWki1Nh# zZtL+e+h}Q&-Do7%nlckPFZz{@d9p~s`3+@ev`4;%lW_N4+p8-?d>aYJtY-2D7ecpZ z&wHkN;%y?uuJIe)K~EsF2MNR-w{<$WFW+%g;z4uExgR;)Ouo{WJYvo7kJyxSd=7vF zndpf~0Q!No7e&2bw{d^q7J^bj8)+GM3P#AA;h6{-k~P!HxAs2Ck7i_y z&UBFpw>W!x(dllmhG{M7^{LL`u!axO7bpH%3u7;OjB%S0VYcjd5JS~qN8;W>Ge!`v zcu^jtH%=i{>>!vck)oAfw5B{g=@l3MCl|mNwZ;FubxG|ACC1Z|xpPYYWA0U94Q@`y zbx!^C#KXe%41mXkL2yXZJcyMO4X-=PBSL$5+Wx@Dq&_DeNu@9&yORT^SM!LJ3P3ai z;q&ElQ!%SKGFKSz>6JxoQyTUG!ae^2ndlQ(-oC?N)AYq2Uc3(3rDACU%wPC3@3gCNH;g|EvaJ7I;0P>AnB$a6LoC!oI@OxPizjp^UmHeOGoO9 zYM6uAQfT1doKPb$^oV&TF_!7<6)ftCY;~3CoU?5;9mf*_E!Q+NWl41HOTHY5CCJrn zUwMg*5kZp|rQf5Rlf+XARS9gR9ncd36D2lp?c{02w!8BP*&ybDV{_Ns+n!#!C13%~?c zlLFSy4~7cs%9Sf)LJ+%ugh`3K*m!dB+;heLz>A_urHvGJ1qd`MI4+G{SrDsIuQ>2Ed-N|<3w*=b*$ zRbeCc7HkyaZSy3t=+pfpkCYjSn+fRwqtT(!Oq>s|1C9o!yJ+dsuIjNbVth?~16tB_ ze>>y<;n-V3<~bg>T7P+ZcV+G7fyRpPCqv`4Ftk`bpfHRnD-c^bGiL?+`%^@7;SZdK z%v(-S8%76!=#AmVqG?)}NL#!D^{XFMnsr8B44EBem6edfk1v)E&8NUkbg&j#&vm4l z>H$yi)uiOk%;sQ!cZxVH2ZD)Bjw(w-XzYk1)B)s%>8)$J9egQx%zZZeu|!`!eX#xN zKYyp!b24dXS<6T`W=2Fr)c4I>w$&d#5;+mP8M1{^(~cz^|JSi(WSzg@LTk@L6k8k6 z$lw^VTlMs)$Brx{fteiId@etaxP)R&IX7&F2JDR?V zB!a1mX5QX6eT*$%Z{1c%hX{7bG34S!CW0^A%`|jnkR%oB{-(9QXCexTtQ@7)qnxME zJH|3nU0q$%ci~k`3)qu+Z_bRG&(L%jzjC~pO>o-Y`IEjUaaF`TGjQu<6LY!+*GH6K zflYhS<*G{Ok$H0_M1`&D1b0?7(`WGhp&u<(X^DN=tSW(`8nVxWjv@KCmcRwCfF0$jGw*P7``lu7L_}1M@T3RJ) zL`S#DgLM;+?xqt@&a<*bEs;4CTQ^JI|I+ot%dUep^SEk_1EGH^pX-UGp`1%`ZoWERQ$a=Z)E>_ey{|9^AKDpNa&r+q5v5OHb24iN zK_+qx>O&g5Szo?XMvyZDYfip8Tz*Dp{w(@8EDM{s6P6c$Pe+uPJmFghAJr;zw0_kv znuqiCF$foT-?_GjRn8nY&Ne=&lvB?ntnuiXNdDIoAUe5=mC z@_>Pe%`*w+FmKyR&yczQ?(XF`-$FPUn4{WAN9&<} zTdT|ahcy7_xZt@3D8h+He?#skFCE*LqN855a~~0dAcbBfq~d`{8Y-X=(bjjyARMKc znA`ue$%n*#Gw-&xP3eoxOq^G)ned`mk5gO49DUgEUVZP(j3_~@83-(1Ho3Huz1@LT-J|Nf(80GuN z)OOP}i*(|$Z!DA(Bawi1k&KHP_2?vU?qm=$eU+rbyF+v!oOMzaQ)0e-J?; zz*aK83b*O2p^qF4L;*=ER@Ce3uqrKO%rY`G7#foVF8(!cXKWz^LNbAOdbY%pE14b&0QaXugxLnRS+~#3j_y3-*R|H z-;Y}k$95Y(&&x$Gz?V!dzxanjF!jLRqX+e&?-PS4P79B<#8)*|=`oxEPO#iry~_V1 z{ssToiYS-248(|@OZ-f%MQgs4aV>flRJ%GIBZ${3f@1K-ZlWU(i0-Y()1H}a{#o=a zrwIjZx6Xkd|G=Mz9s~C>F;P)(aW|hhAKz2h8=6CUBJY1x`F95TxeJ>V%jDENp~z|> zBkah)c}>QI(w#0}ttC1Fl+6)6=mrH26WlS-(`H824k!aiOuS}e`@Ohk_{MDBl=TKa z0Y)$&pXVrz%rYL)Z&FcSguzz^OaFv)=XLMJujOgPIl!VmdDX{kShO6!Dm8q|j@DR1 z_6-^NfZf|smh=Z;ZEvIx_hyBS1J_$p34Iw4 z#I`{2NYr^ztCl7~mDpKm;Qjo<|N2wW>SQgx+M+WSB0nc5B2b?pfx7egk?$X75B8v6 zlkQ7Vn?3&~nH-N-B=~6a=~WEh$aYrubtziE5vD_2FltWF&faW%1g>2j1KMCB(+$Ec zotmcy4s)Y|_(LeCPpkX&%Lx3-4v}TI>3tr=o=utSaz= z6Mq)=IJ4Wi>krR<*3j7(moU;(R{^Ulwxf6PMu$Q1Bt!k4Jj6b3Arblm-(PbA|5op; zzAf$Yd=*>5%>d${{a1LAGawszv`udh|Pdu;iyNZ|Is`~!4 z7MghiY;T0t#{#8$EffnvdigH#8y=4?ycmopu<35Q>?ZbO5S2F*djgyd{zl|%XhsOD zMVn%YZm9B%z!5wX1~#6o(2VbSsq}Rg7$1@+cRlS3yMzu|gh3Lal0(ZOm}mx34dE=; z-#dS-JB|i~{Z;0c+5MCkw&4N-|Geh@V+pP%>DLR#)^$IIJLNNyA{>z}1@i1;V0ZVw zFS#f!jBmZ_&D(j=yAU$=Fr#F)T#9Vzu&+j8GSTFGjJZe>;-m_f$!1ms*Glfycn>mh-4?9x$d;pgh0lRGs9I3G6DZJ zsvE~6WX|>a3MJO_wc;Q2q8*kDznuQhy0;OzAwxW5&FDLmwl~(p>Z{}>*(R;~@lIKp z<1x4hlet!Yx&_BLO>lF0#a9NiUfhT4Hm=@&Kbao0`I6^wpDmm)?(|i90K0$9r>Oa^6ov4e&0mZnRN(9pheWgc z+|fNVTPP7sc-R|un~Qv}KctVakl+Tz=_zQsQqUdBJ_rV^CZcb1_-Y2<-FO&LN*|U@ zkJQsv8pkz0@mhZ7wTu`T`Vttv^V^3SdD?BBG|-wolAx1$iIu`WEN<}Mk>H=upo@p_ z4JElH-&d7%C9`>RP7NWfK&z4o1o{}_^!3E~?Asj~*_#sY4UYhdp%jduIR?sRSZ-ic zJM)@kOf1B>>hWISe)F^vfq6Bms_Ph%8LY2!Z!fv0+PclWe&NQ$;LVZ|v=~>&I_&iS zb%oCk>t_bD@^kLedu5JCw1v@d>;T#4XnBvnkmqJ_VJ6(7oHJeT1{7~^eL;?pp6#1g zEtHp*p&``UQdG_#Bu14(T~++OzC9#Y1@Co^q|SeoM%F>^?Pm5aXL+t8F@^r}o*&!Z z&=a14S%EEBxW>e4hSB!=!gcXj_ud@sUvue67lnjUF~@=SdapQAj^b5mUA>+FxIIQH^Y}j_o2zg@9IRApT^)!fc0dIUJVWdo^yzYV%5V z4163?&$iAMZREM;8!$vJ$@UuN+|BIV5yu|7Yx{oP_m3Yv`e%_Q)vXpK%N(bXdLR9P zV)pg}yLpb{qkJ5E?z&`@d&6%FB-`9Di)6*3{S?J@u{yh;*v;obKsJLgX#Oqres>gU znPk|cIA`#Tt_3SUic{`In|%heU%rg>w41K<7>jvJZUf@Z;ziP)G#2Y51n05cM+Rfb z3-!HxuDqA%Y-MN=a-KYPRatRI5lExvV0JNw)RiS;s2L*meN+NMZJWS|QG;l=wUdu; zMyD0R&=-1vrA^#YbN2I2$8rCBdbHq@K^ml@JMfe@KtTC9jvpg5&Y44kerJ;NXtQsW zxi`IjNVPN!UgmkJG{AxOPv>o`-_d!84F~A&nyhej?#e*_*rT{6Nw1ZrDKiZ!%^(!4 zTZWh5_dIyoCksXXR(j;<4xS~Cy`%=!$e2Dg66hcVsI0!~wU|WmqW58!)FE|Lr!^Rb zr=v-{+Wd3+jc3t8x~9ZP3Il8|ybRxVuH`*Wl9b}}VW2{4VwiW+_%e!$tgQSDMst&; z7V#RVD(7u~w(mjR--(`_r#N`(@%vmZuB!Wm()CUkaez&-MQ?QQ6j~!eFYoNA0t-E0ya$IgXE~~H3!x)X zvd=o(XU%M-&+>eN5<~awo>$+GWa&~C_#nN6=*0jT{s)XW((-S6Qi zl2bCF` zSP)?H;{@lj zTXCF2<+Ug67EFH8J)}fSNas9O2p`~KX)x1VX&2Ln6I}H1O zdG!z0pWyZ4K=T@KN4 zWVRfsx?M6YnE2Ps@&ze2A2kV-ezzcy_9DZqs6cR*ik0Zl-Gzoe$`4Fb9p3{b&jAMbdI_~E9*D7Pnxf47nKGIn$-x^Cf5#WYL19C_rA_s@Iq%re%s!~ zNgC$OK0{{;ELHL%^PFi*s9AP*r9?lQjGH%hW}JPw$Sk#PXKiOaSA1Q`+}$@n-#Pc{ zkz4cl1-{N1CT~2)N!3%YwdcotUO7e2T$w)5pEF=};ge7T*8>wOf&udBV`^%XZEuq2 z+*l>Rkmlq7@_@Dmzrt+;7=ZSyyC{9 z3cXXiUX5E>w%E^WT-3y^7X16KL)4F-`m>PO^hD?0{O^CUI<^pvU!COBv1u4!O-94p zrV{j_yEefLImv<7nn&V|8Cckw$gmj7=!X!U*EUF8X#kKO*>se42t9|5zzHHa7;lEp zqPdjwWa=U@0XO>F0Rt!>s0TOX89;_l>7VN;LxXg|eq_tyuD6G|Q;hhf`W2&B@a1HD zJTWe6Y^ExxlCqwf+4v~Etaq?WufDgSvt74ua?6FrO$k?RrY27|2y11UgyxODUowtZ z*5}}}ZCCj#iLXsf-^NAFjh3#Na@?hray)vX=gk%c&o24EQbTHr#g&vh%XX;cA9AE- z8J<(n`9g91M&-|N?X(ZtPuF)?=hIj2ni@gcoL1LcL2C;M6j-MuS2 z65P_qhTE2oG<+%A(ljdK{`O(h;O`QHZgDDo;V+hp3e}{|R(*PSov-(f&KV?L%r@54i1;-q1(pUt|&jx^9e)dRgi0Uj<&PSIgPbL1wRQ)BV>x^ z=*stvAbm|ojTlPqjMS|8s@ltu5HvOnVd$IRZ2fee+CvqA0w3>}nTF$w zCBC)rDYy&H+chr3*~Gn0YNTcz*W_pSrh_a%RL2|!49mDyyK5FJ(`v(h`z@@~^Xi2L zzt-Gd-MBE-X5E~2$2jHeSKN;7dS56yU(1U!?25%k8sB$bPCggH9k8MGgGC6fkTU;t zLEN#7sPu=_%1Q0fm}b}R(AxYrlg@XPJH^|sOohHrbz7-5YZuKnd$Sr*eNOe>~&H6BE%`XM-qw)Ii!{#O3@k`|}~?sj-)@ zT)SNy{Vf9vz#bK5Rszw<<@O>Pj&?6{T9 zW9yvTE=9_0kg;}NJ=Q)W0*t2ta6_qvz9k*sKhERL09C3bK%Xr*>N+eo2qf#!^+i^q z%XTQv35}O%f4Oe8HH~eDIU^lx`e4$ac5h%n^Ol6prioe?L7 z$6pqam;cSnsMzn3_ufM?3H*@fi?Jh0HUK!Ds@cIeJ_BJ^NGB(a0D)kPoB}{F&w2S$ z-~Bwd+lFEM(g2RU&0Lq)GIKOw;k`$#4OadsX#C|!;@&geCwlaXl;5t-?IuSW8J$Nw zB8NeA-mh{Fk5LnWrT59)4QY4o+_`w=^4<@u;Zmpg_$N0Q=h}>x)~4^}>}l%d>8Z~; z*VXEF^xk8dZBRw(Y2}@1dQ*2!45|xnWNfr*$=LBRx)Blku85mhYY(1>UUu(ZGo2*W z*S0|SI~A}09S;AeJ$_vkxP(ETZ2;GI41=BHwP_!aK^83v#@OE)_@KZcsABEeH};~u z{CDU1o7qF9w?3v3M?Qrx$sOIh1sA$utVx>pLN8J$LiR%im(v2X05aeycriEq_T*Bd zJI7=0*vQKk7m25;^|-gE?x$rRxNBb5H$|h5>@j|FsOt6(d;M3Q_6B8%mP23kUszd> zztWMQIUS1l=a@)O{;4RhbrFEc)&wB9XHp<*2z~;JcqlP0R#NQO|-g_1s z|ELYB9!`26fbYqJ6_`Eky<>0b3JTD$Q><_`Kb@-rB zc8c1wEBAP~!g!OKfDF(1Jka5 zg@uInO`s%Hu;5%x{GAoX4u3B3$(UKpsrNK@2Q>wtarh_D}l~Ck1kfIKis0;6UOcU>4dNn-M zxhdL5&s=?l{}c=8(8-*XMGXL9OzJ$ zp)g$Zg?ad6=i&OOnkk0iAR(Ps&znDmsU|3iX2!dDQCE(BIpRE4X4JfCUYux}Lz1gd z`!hd&{!3}aJKdjjAjU=BX7rxfQN_THh)!q4viC=kSvOaB6q8FwncoRf5VVD1@*QV8iEcs3At0G0cUS-|JASK#U_K2g=DVNxB||7!ku7U z5gs2L1U&>od>EqMD~KrcHB+Q+r{PIZO=3b%fruGdlc*zcTX}W+rXI1RROOXYPbYOp zGKE@c{LQEMY3?U1H6|D`N8Ew=_U8X)^88tjWV$I}&>C96fp6 zlZC%6fSp%W6SKsbkNQ~DhR<@z(5cH9i@8D_O$Y#mx5l?{RKX;T7V6NFa&_le31b@C zXFDF6ssa8_s7#C)mQyRe+I_-%yBtN#xN=WRn%RhmR*IWTs`k>f~#ncnL~MzkB&jzay!-6W+J+&^;cH9MVairvgk4GxYdHC zGYfMsNthd)Ej{!j%&nQ`rQqn&P9Dek7WGgQT)hMo)kjv8$vCsfE}O0-sy3muWY6D2 z%}hcEOz?!Jg40Kse}cgEW`#4BuLcS)-kpb|xFb}%I9~5``*s!ro)guyJUC7RH{I3) zCxmfjHpxXhEC65uM6g0XJsr9Z_3AjioL7?)Q~cC?Tgv6UNu4;I2WlmPzq<@B9@j7R z5veHT{;l`YZpBbKx+V%E$!A$XJiE(}*Yy_&H2Lnx+?!ru|^kA!!MzL%wO zG{ZhG1E=9L9c{LG!0S$|k(aG2gxA07I0hOwXKy|J7ES-F3emoAg-y$duispQx`$tO zA#PSj$Ldfr<{FH+fwsmzlMt|6nX#!ZH+#SJ=!NxM=51(8KMU4t-0P#OU!myK(orE8V#qefZi+_4qv0dv4>t6@w%d~4%lf}xU*sz8=RvMg0!$#_?9d|+O7fyBm`8??HJ&;;tESEPhq!R3&A zS!-Lv=>aSsmZ`5e?QOTzNu|${ zfj_P1`2Gy>C#LETX{AdPtjB||hM%koDz~nyKqA23S65XUBx1#tX_hlv^p)(IhHWsCi9KQJJq)AOdJIpq zf=T0}5dUlOCU`BDHoif~Do&6RXkynkhf(dG@y1ypgClp6Rja3}Z0Ac-omSd5b59v% z_BUC^T-x5eI8i&R*s%{O{ajx4G0Rs5l)k{048!r85q0D0#Z~5QpC_6{6WzMRL%tNN zj}C;@;aA%B&O5@GSuj30ZcnA28_BW{Ew$^t+j8>hGXI&DwkpVs*oIyyiTqg87vl;+ zf7gkisGX?`XVGlMn6P*-8&)O7eM9H6neQ;DAn^!(r`OwV4!hGf+~xpvnp-M{{Z{6G zeK&U`)uv;Y&{fX0HJJ8%W&1lO&ev|02l%s@m%Ir3GNmxpKd_eZQXLGL(|GfOwrX^w zc7;>VFV$;|&y))j?~igps{X z7raAMR%c4gHfU$PMg^U}Kg@Nwp_l+G?H!6=<}PZQERfg=6A7Xf9Y3;h9JtI0oAK_t zq;Rg+i5!h+Xq>cZk=_1+P;|sq6SW&aqhAzxD`1B2T)NPwFecp1bpHxFl@fvld#paV znQ39;o!=e)*i5>E4|pPKGT?D_J4uk`q7@SP`fi0#@tTBt2|Q!yf*wQps=SkDr_MR5 zDDykAA&5Mr`ji{IFK#iW#zi8pekE?#ZGfU7mF=+P8*oVS1aviDxWR~rZc49fN(ru2 zhlH|jT-R&6GSc^Gae9c>p!iFRaHoW3)A5-ptL4_yF=psFb_80o7Gr!huW<*Sc*3}% z#gEgD=L$XA99tM;IS-+JO~s1!&K*F3f_AEjbNh>u5^I@0M|bvF;es#bTIwM&oB;Y_ zCsU8H4jHK7Vq`hMUp_$`GZlh2uW7y7%~e(nuVT(}w~vuNnj{T`yf;PC^-1VK2>}=% z72EgMGCcoArfCt5Q&srA>V?M6TH{T=TN7%kHLF{wn$@HH^{xf8Y4IwvN5n<@wx<7E z>_Q$VXG9pzR8V4;%f!xd@S?hAEJ|3m14BkK={vD5wDqw$(|bLBo1Y8=l-A)EXRB}{ zUM+E^T#N%1gTDn8{g_bOS39z&mhvS~=qbc3p(hy@qRp?wdxZ5IUj%SZb6!F$b6!Bh z^ifa}o>Ot)yE&m%$tJ_2P2#)l52*(taa$W(W9K?yvr%^Y+^qHjAFJoK{6bHh&26JO&z zOfVP*#MglPZ%UND&EQaf+^2z&Q+r{?)!V1EO|+ViWwN;j<-$eC#j&z(peSH*a2h3W z?Ax*h$Dp~O)u%k&dPJKN0YqiW#?^fh{bytTFX_hWDGOiU+6{eD^RbBMW?$U)?T(0$ zK2BwJ6>d~nO)t6UimZ_9;Pceb*TwR!_8fk<&5qwCvtEdCBdKJln<((hN(_(w9Iv9+ zCb0Oz1D7j=$4#upmnm1;O0BntnVMAHO7%l3D1u~b4hJo{a8apbxterE4Ci`HcCqlF zx6sRHVvtb1gWKk{Ngj>fjr&)dfDIrrxk}sDsC9i)y5D=dU37hjFj-qz%8z=)imP}Y z1vRc2-(rtbVRSo}#!(Gv&nvf8qr~1v18<(fQWJ@Id6+k=`RdWJ_R$}l;tU}CP4a9_ zVLL~5X)B28M^vP5I{BQT{2@;z;rAK_=`8M38P)A45%MBa&~+)iz=`TzN_srnMk=6M z1PGfSExb>&2p2;CO5HF40xOZ?3mUvW3jlHsZ~c=z*R@O zu7gE)wi+tNzSxWjEonq}&e$QqA(o}{*o9?aZV;2@0{#Hqq@FFduvWV-GpK(+=B`s7 z@nH7eV`0nqu14{r*_#qxj@PR<4t1TooYdn2sL7Y>WZik=qfRW(;zD27$yW@s_h_2k zQE6oh1l1(nvinX_GVT0MweB?Us95F-f4|*3Mw3`8?02se8l~<(U84^wzvYu}=b72) z7t2WK>>4cJQky?9W$&^+@sUk)6sOYb*tOdkv^FaGspf(At#)_cyjJgnbxUTqN*nyX zZlQ@aWvz4%g;!vR@f|oP75Q3GEy31gA^2q5YF<_lDqdH=Pw14XVFpG@R7{NHo|8!< zLF#<%p%en3={nN_V=X*wiZrBYZ(*5qh9)EAYwE3;*TudzOGoGll&vok+ldYftsw#9 z_0=!b{rLp)7%_DE1k|7D;1xA6(h159ASODjL!ZfkTB7Cr@{AhKC9nFaiGFt~EOUG8 z`QDTpCEUj~SW$Y(*e9*eZ>(})kEG*V)p-gknseOu=hQ^DRD9Fj&@dn%?F4VN(*hY@ zR6xBef^7HOR+3{o!8Gw+1b9xG8ldLrglJ)EFPHxqI5t=a&=?7|Jlp}Sqb;mk74VF=H7Ue^b)U6t>oT`i4yv?+T&PRR9dBGjTt9NW($m{o8A0N|9H zYbLlK-12MHA0)o^9|1C*J;{em3u5+=iJ7Dt73O&jqsJ;3c0 z+i|w$lDBCWG*%F_Up$f}c9Mq1)ruJX_?c6)-I2YrTdhgX@6E!8;g9p;$ zA8N98CnRw;!^N{={W?iVs))KdU1Y>c>DMZ5R6nEmC|eG7wBHGrh$xRRNazwu5xpbf zVtPLUnP*@h7Sy7CwL(Kn&e=}0>~#vk&K@eL(Nvz@&yJG+ikv*r?WfRk4PtyfSBseo zP=*ZMl;1&BMLIWmg_axk-$t8 zvOL8h<=xI~ApAdUEyHjJqzR$0-+EBMLMgPkw?G zu|R`S;-#eXYC~J!dget(HYACCz@Ndur!Vp+EcoNd(+OlFA^U~MW;BghU^QUnSPb=w zuVV=`FZ`33SzwX$S;leVD1Y_1rBRnPqo#2H}u1LMUJ!Wdea|)lBk}*U{q;q&9yQdtJ8lb!O;w zrkGWja?677;ynRbDThG#(uMdh1lM5Pjma3XA>dVxzIeneaB)@wmtx7)yBOl&GClc{ zndC-PFi3-V&knm5aaF$(;-wwnI6Nx163cIzD9A4qDta3R|gBm5ro%mbF*rQ#tNh zD(6(DgnCHyEA+nY1qeQ@Tl4UQV9)bB}w{#g8<$kOxLC1qb?@so?g14ac zmP7piEO_VHQGKV`iQ6RRX)d7yv;AT*UE<>B=IPzvEH8y_D<%@%_rbG_A1UoREV3W* znF&>UE@JpqOu_iv7~>Q)fIq?BAh1_x>5FXB&dgiCel+6i2Fx;UNqw%S{-wr#6|qucn)&!g8z*1A(AIXyZA zZL30B57&i&3`xjM}#sFbkor_^u4^xE`VTmPn3z$l7o19aaL?^C3X_& zof$+aDcpJbC=*I*0=Wjp8f{}ibNH88_ovLvh0^JpqBh^TeHQQdYz9zn7zQnlSr$*Z z!&^t6=}SXlUVil13X8FMmay0hgNqS|>6O_V-H42AoOW-nRS=qD`!sc`>+Q;)Q)Q9o;%t}qHKkt>5 ze}s#=uw59iKDuSEzHgO_&D+0aA-#YAIhR`Em(C_@vNID+@1ifg&7f*{LztDP2pOn~ z&r&&W6k02-_S7l?`d{#~30={ryM$UjQc$7s>FHIwBAc>!pnJ(*(q=@GIy03Afa=Ka zJ#EWxOLVnpfI7mLbcu{|hssL%sy) zFdQz34m+bCWJJd54sD1oq27l_46ipAcw8rRq>sP&L`~5DfRXgJZuvS^YZvsKj8+VK zKrVL@L8`jVk-(LC1pmGAM!&UFJ^zu9Dr@?r?Nl;2dQFeL>b16P=(#Tv^t_wtSOKgg z>4>Mqj;GCGlFrtQwz@-VhGhg7sd|8#>&7K;Kj~cS1(Wd6d{yLM`M-<8f4$GJ`MtD$ zRo$G7nn8I=q;;gq39c&HjW2C?hxO9cJ1~zcLcZ&`IsxCb8ns&z^YMqf+_yLPz-@M~ zP5Azd_fJVzKRxt#P{nFg*TvggoE^M_W?D@&Y^#}Fvq(ZHe5!*p64($rGdRZVVR zq0S^#TWDXphM%vrdxlyZtO3&3fG0J~*b%8qsd3xKEJBp>;_@f*#VZ$&8|oT_2N05g z7z`ciS3W#`byTw6XyhT8?>RCr-`qRsIOJ-vWTfEQTLl#Ou3u0XH*6l0+Xmd;GdD^U z_0aT^2D^u$`t}XdaLlP|d&~P>IffqDb6_i)HZY{&CyBpCfiJpgt@GzLP~DY$LdWK! z)Bh?}OC%*Fa%Xp0(Pd<#k~f2x^G0=1un!&5U$PiF9+gZ(RC|h1t4*JOXnlGIPOAmi zC|OdlAH$iX_HjVJ{&ol+UFP&EsG@u+bZFaJXUZz*T1fyBc>;K)9WoQRYMJ;~L7inO zoAiDZn0ddI*>hf(pKk5d08-m|=-pvcOv9?MSJ20buds10<@1lx*>Y{i6$FN$ZKDiu zx=(hD+kg{scf4NU)R)#{`G$Nt$?47}&-G;MTV?Ae5S#Xe`M0D(%^mZC1oHEdjDn%x zFPnM$;L`4Cm9S6W#fPa?avDuHrMeu~GwAJh8Uv*3@`Xd!BO4}Q#kO6c{ea$<=mU$sw0)A=sBX~UX@B|@*F*5Hc_1zu_lQw|AzP; zS&+Xoil$-iB)N3^pkF>AD(nn(h*zT}ST{%XSp$lkz#;5dZU)=^|c>26AhVGC=zabEOWUR#S` z4yJHUH6Kh*No3%fV&0q?2lgwO-8MiA zq_-qUb2m$Pdd4cqt4E7ZM76y8wu`~j?%+biMBk2{iO8Xp&1JFP;717l8)~~pq-H~O zvq`RHs0q;@JPE0rc|SjgJVs%eLt5mV%N<`LdA}XtpA&O=nypqTUvf4)EHp7=R+_pPbGKzAp#AvhE%xIcfmd;LJ ze7{MT-=`RZA=Bj)Q``hrwW>eYGSpx7 zo|CGQ|4k%<$l-N?#o%Ipgd9BAkT<=)yfmwoCjSy2Y?g3QN9H{*RRABT+lEVl_ncmD z{wf&y#I=dLzSHX=dweBbto7QMF=Qzs~MHWp)WM#t^T1*T?sCr_exF-TMcQzx=h9 z{o4u*EJm65Q#0fP za18#V{`l4=NW~?c$WHuNfGy+{ud};EOSa6EYi6Kv$^E+7O-Rxx=;t}>$3WnVJTtBv z#BP?+B@~X}=3LJGw9-+unFY$UzUiJlqL`?Q4Hv%oRzri_bN}OC6`OpjchO{rCT|O*=6|O>%lP)A4Yt-lo)wr~yRd1ZPWxTi$v^rA019E} zzEJh{j6*rTrAL;;O3X?RmRcJ;#jl+H;jg*ks}cw(efUe1xvbfzbc^=t!W7@~!1bmD zTnM|*?Kyg)0PB^0Nnu@kZ{?7Zm$70?E2wK-n+m%XC1CGl->}nf=yS%IF=9}QRN61v zytz<(BF$iEpW$%6tAjb?YEZ%&*eBHwtbZyE;}sdYyjq+0@{w(b*LvQ1UiFT6gObs2 zn-nvtK-S~m)`9ykOUkZjuA{9{ekYmQ;2e~@tx}q!r}=-c_81ay(apbSTkbWh2iX+6 zirB=5NJ==24R;$){RL>TPeZiJ{<2kQ63o@#Uc=O%-@e7osI#zPS%pOn_AvR!y9G=Y z1g<$tf6h-b^idz1JVJY7#@7?TBcaN)TFcRAH5}}AB0KdZkt6=Oo1eS^g&fI3!_0Pj zUa`<4s;e4N)x_4{Yj^&l+UG|-q<;GIc!A7c>#{?})RmRVRcy$>vPGI#eOYub%|#3& zuBYS3PTR_RkTT>Uh9;w=El5Wjl?gwEJgSz2S9!-3?$@FMyU4=)8gl zDK|ZGmGsK5OT3;eRxikZeU`YK-puEE)1oscg>wy8R}PijNQk2Ah;G>pw`yjhi-=4` z!SQ3>I;QxfqAP0_51Uh&Rr)3l|x>;?< zG~Kkb)eL7ieWt%c(`Ih4xXI6XWQ-T>R`+IFUWiM&PBrW5)JVI?Uhz6rtK9_hJ*e`P zmn#}+%|&Vr%sO1X6ZpZ@O_iYHJPZD0`MXQ_Ye}}4WJP-fs+o+kviEL4#1LyTXzrLD z?}iTw*$>P#wo6QqGM&Zbc8l^H>Ljo5mJgu2hYWBIrW#Mt?gJXlqVx1@#da3$5=U9M ztKC#q<{3X9b|%Jnk=Dk&PmW12LB$vCCYHXpIMaY|?A|Fg?MqS;o_;U6OsB45s?O~= zp_?97YH>CNfs_%mMT#3g-1WsnjAma9y#Vh8tq0RhDb9UG9SuK4Ldp-9*&AvSZ>Sb9LFt1*W zs%GaMCsW?$Q}@=*7H0VH1a@ng$uMD#N#I6pwzQK33E%QkIhjgQLQ{HgS*qK|9JoVu zR$r+om=u7XrW06^h#EOx$(dY3sCLHqTPxj~L^+#IKt(!Y@}|@D8>*e1gfkUiE-})dW^Ofj4ZxskBW4a*lCV3d!-f$^(od5nor+#{;URq*SAaQb~bjuG_;V8hRCSv&L&+bBTHU1XU`+L$+axZ z`Ys(QDH$+C7)(m(dpBgC=z6o7mmC@xu|6Dl=SirCa5`_at5{3K@V0HV+9SaNYDdzk zx^0N~@ClIx{`>-sv?=|#eRZ}^jdKM0onFs$>9m^#4Xb0*A(!d_2U$qelWqS%zklW7 z<7}Y?F19t+I@0j!V@gw_FwNFx$j*T?? zkrYeM0oVReL7Hm@-v?(jxmFa?so#(Cs(8IJ>B@%swW?Icn1GKt71w3Nc*JOu#aU|C zwpJ2h^*Yei5CRzUmW81W)8TdTQNSlW3lB(~M&3U|5g$idP82UT)jsR(7zzsG5U=)W z@FM58AJ9>5w~+{`Ey+9t=%eQ&n=y|>ROm;SX)F;BO7%B4Q<`=P-s~d0zK_l5k{r+P z<>=C<0rR~fmOpsDddE&dYC3{?{(->4svRJpg=*XqO-!6Oin!JZGShH8a{*|Z07s&w z@MXG=pNp69F08hQnn;_H!4SNE-@7I<1@(3ZQMCY!%b)oq#9qKHcq}*ueP-^X*t|O< z;{lxa5z4%Qn?n5eEr7=LA3fUHdSx2>+51$3A`W6j7j`Pj@}E2fqOLVN@wa5x6dCUYQwYY8r8MQGPRw9pn* z&J{L&-?yvJ5Clqwg6|%L22FP#K96#>BvFxfMlArbnu;>=$?U4yMzBu8wl|7mld`qWqP} zs%{bvW=F1UI@nLSY@P#u9YP)l6<3p3B7{^nL(X5r@=MlH^}b5-j2rYbcAOQ;4x>#3 z2|^U~rNgdbQ7oQCmD)$xj_#HI0||#D{cl#yOjnQAyny)8(KQzlqKrWhTJpfiV#uTZVv|?$i`u&E;lRonk{R45duIZ4 zoc^6@!PIZSGTHs^wS>F3@^QA=?vJ_n0$5C@YHDf>R*GZ!MgFWMX3ELV;a`ffP|qC$ zF9V6`gE?g?8a#*W%+A!QCjLG)QK`ldEFCbewE|J@-5xX5*OEEc=Ggmg1Af%6so z07!;*WiC?Rt!}S}*1nI)kHBR90FBuDO$YJBsrC#N1nOxJaDseUZL6WN+jBsdK)JnJP)%hLnPJvT&A~tRmCQq?NYDP3Cb)UrCnb* zjFr0=lPF#;K8?+5KRm>Se&|W0uSnA{@>(o({|3UVNKtt=Z7FDlw{CW$Q>Nb|I$3>TIRpqJ)95EoZ)ba$QD!~H z3twWyvb&orss}=X0?2h`=d~e2HcfA3|gSecI{cA!P^{_x0azsTQyN&0p75z2!dpc|$hF_~Xeh z=)P%mj{`a}3bY@AyrOl1<2(x6ab(pz)r3x%i~>iKZnF1ZAu2 zWP$PF%s*Btm@Zt%P)_f+y)pSq$Dh8-1A8zw?VQ*7^bcF06&M0t+<_ZK41V9%HA|@= zma_(8*x_dGo%t2u8&DGLm4|;kAS$0^z5^XDaNw)QsSY!5w?2)5ey4(n$rMiWJcm9F zoy=`;^KY;iq%KD%4b_>NJ+?CNS`4GKULccrncu^jU{$u673wF zHbmF);|FmIEw4m8)(aL`6?A5xEk^`AoLQxHI0cL&bT{C;&+w`2_TO#)0Ivb~z%^p} zGX^Y@uw?T*e!;BL&z*Jeq&u}B_TCu@IZhq#;40J@C>}QeTzeMw+(C1WH*MgYmWO{J zG^3-RjHD+gaGsIefqd^S|}74CR+QQy(0=NABRLfOc;0gApwH9smRyNjD)dG~Zhdq~K+4HZl^%mI**Xe#?3wFB z^@YN73@(zjVH19)T~%2JOFQ}9$qi!z@@-Wf!-_nEi^!Vj#KU)ln}$ppUCWN6iJg$x zF-Qjt0VA_-lzknTWUQf_K%M{8ld=WF=FeKBP4Aq?6{@VLwHY}ybb#PAO?d?*U=6q{ z$k8gqxyB3+*Uaazz>=4*@hiHJTR+5BfEq*X=0q4RJx@ei{S^@f`5DgmsABJ$)T9+@2=2JWc{#+CZXRuSywAtnlGf$`3;vKj-ld`$1u#j^%jz zlT+Xyuo!m+_QZSfMb_!Zs##VVdZvovz@Eo4|UBZ0KIwjCW1jEHoN~XEh(F9qH@bXxQ&>%lf*V!%#?o-miW+`ZZE6fi}wPSZS%z zd_J9lf%UzPmZo`S)^L{Pk_|FRfDLxNInUfJux>bPe_7`9K5++NUl0MGzdYN%H#{tB zpR2wZhuMXAUapphe;J5{JJTn{4Ofxs5~(yDkM=OW~(S4+?o*aLW$as0O;24G7fA!8LsY7Vk7f^Nrme zJ@Qa?pm*uC_j6en$eS70FgH=*jPsTGkegm*<0S@8hf;nC=mO$A#sJs-CRt%!z+>wj z-dAqj^Yvq<8@nnsfmO&Ntc011nw50Q1$hMj5+ALUK07ahe3%t58M6V=L3NHqzx!yb z3h**v%^zT#-v@^(2eYQm*=-IS@r(n#h=1xjHzaKJNkg8wyd(PKj$vUXABZF?0(!BhwNozZ&v7OI$VCla4 zuYiUxiFzZYwU`x6WmD(es9Flx96sd}KVnP>7@o2=dNPN;YN^qHc9!c%`NZ1)q}hC> zHcG4c8SNP8K;K!mg6BtX6T8car=;8QslrlHQvNURV@sEruM+0aV=~M{vsAPsc~i$D zrF7{gG+~N^Z;?xpyyb$**mC6sVC8+Sofi?t!P)e(g@>NU;jUJ4qb?=8%pj4hhpSpR z+8e+Xf~UIbMd9&n2dD=N^P8L1Sh-%{mUhv~dj=y&eT{90w(hm?)aoC~4nRb?z|yyW zDYVcvCU-Z+(1M-9WhG>*d|4r@={Ea5l0Cy1S9X>@)Darpf8KG~(UFTlAR0`BaH z=Q!r3!PH*B$qzI&D^ouCv>+eGmW|kwoSCTlCY@Ay^cawPd-lAKO(Gu{fKX&t=-zlQ zo(&0-@j~^#IeaI_dC{))lE_k8l;~&i+B=b9Vz_GkcrUu~4`(WmY!tR1WpJBetEcW)CRe=ubgL}weDZ&7va}fXa*?#f%hB*bS%z8 zq#{4;E*RL%D96`MT4*?rg-tge>>cZ!9pE-R%G6tL8HUTw$K!~oqY|n}5J(FILtVv) zwr4~J+3hF--i2n?amVv7xMHdGC0L?EO9ZaiH80)I66|oPkw#O1KxEmUx^$_7P;-wa zM=68&XQthyJ*fmhdy(5)rh+rTR2gJk22U=mRKe^P<@St0dO*Meap0N8hC>OIGaJwo zv;pNHdG4$6Z~}r_;4IX_MCF&YWw<`(xXy2q^d*Ipb3EtV&Q1S?8&e^_*H(?5D0L%g zE^~bjIxV3=E_y@^z3k(oGC{4r3~roo`QmxzYUd*PMU{tXR|IX-^)q z(4Eb|A$pqof+_jz{Xoadgt^paKJkkQ$)N~9OdHgKs@xuqqQXJvnZilDt<5L9vJmGgJ;q#=Qr|}|BuSpl@|3+%2=uB;Zav7uUxwdcQAqFA zvnUUZYO!PKMzNTti<<32yXOSmrvy~&glC1kypy{ruiR{;XFp6%{prL`0ELiZ(0b~sah;aum9td^S8qC zx^xG;t9A~-Rd!mObuV@AU2oj+1R|vV6QSM3|AzKVZ~pz~LI>&Aq<0$3zn^ej*Y+B? z6X67=0e8SL2e-`g`9E`00nvtp6ckt;V;IRhf16kxy$?lnjIZ3}p9HW^Pfq*l+qeeO z>)L)$dj?!eU;A%i+TS1e|5{5Ot%ob=gfdF}69t^WMmG_7WfyCA5Mod~U}GnN9f)X z`^O#+`7hkKG|sZlE7t61u{(?U7bd0oQSgIYu4nwufEYKzK=M@HDz9wzoiTj(_U+wu zm(zm(;==!G^fc1J2QKUD?l8(fPg0w1>|!F$^Fe|B-a=#-35E>=`#|j1T-(2u!T)aD zgk>@rrAz!*Up)K@ b&v*5+srlt;ef}W~@J~nEP^;psL&SdpSa?j) literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/reeds_shepp_path/LSR90_L.png b/docs/modules/path_planning/reeds_shepp_path/LSR90_L.png new file mode 100644 index 0000000000000000000000000000000000000000..58d381010d6c238c888955358135091b854a1b7d GIT binary patch literal 339492 zcmb4s2Rzp8+jm46Dai$=~-3z#qshWi)LzZF+tR{g3Ei*e|Y4o7gtVo;`K( zj_z>V*5_(7z_nXPOqB!=0o1$3|5zXlZFN@ez}d zQM2LhZX)`ZAEda(ryKN2d&>O`e|&t{v8%r&)8hU0s@F1V?-l?1HzHO@y;cMVgPOVIHmVC$A@A>=H&i>06-X(p|LV3r=CM~^3l<0t{X5j0M zwf008iF7#aQjJk~nrc{D66QD>_(ELhYSoHcwa-HR!9Q>0lS}N*!0&afBA}QnA<;Ki zD&FJ2-xWthL6*tT8Dsi%obsy!+%G%MiPE`{JrRKJx$T zrmej^{@yNXbN(#eI%*=~RnE>mN@H7o?{I`AX#rJ6;jix}I?OH<i||(w z|DcU@)VmMt1 zvo~cnc-Ac~kExjHb#iZee%gM5hbq%`{KHnO={gO{tiE{(?(qNhYZKsWQ%Ca(uwToK zpS(A6e+!kH>++CZ2W2LwB6(I{T|HO8#<$_OP+xj~{e0r3)csoNrgfVVw0$@J^3NOK z-AEp^D!V}@$ugd79OzUuLs1EdP%O#-TCp5p_&P8J?zthZodD+7C(Fk zRaW?&uBTR$<(z%D3fX@jgt3N9bbja(nh~2tmZ;@%<_WGRn-l~k7EkOa@ z64(uc*L_a>aYQP6Bxoa8;UZMP94W7HPM^Yfx-&V)tERxC#xW@t%9eV@p|;g3@$Q@O zLFCA`sb2Ey8^<3t!F{vw`9y)6DRYsC$vQ9%UI)$TiG(HSB zIrXF`Y8E~acTP$zVKQNpm`{IWTp9Lb^YOZ0LO~nP06(47#$|~Y&MHr1R!N%;G2vMu z(R<~)xOTGV(r0DcFD9t0Z!g|}Rz^uT{HU>#)7+28CQqDOv#cftV#7=N!d>_3IZa4? z4HM7Zt!W+8$FZq!Fg_tB77oybRX`ti<9(HMRf=BWp~Dj*ULj3953zoA7ncNwV^-W} zwEiFzMT8PzDW4X!L;qSdSx+#|#KgpDX`*zZ-EpkA>=}EvpR&Z$iSE)^qM06!+Zrq6 zLN}X*>h)Zg`#TC*xsPfCx{2 z>`@&abAykIiv%x`mZ1qqo<<{yz<>SO)> z%t_MzKx{4lrMGO(yqB{qe>U`#LcUySpDmp44Zf6f%Y@HQ?UHui_fU;3ZGLYZX&lDD zbKaXZ@G*&)hrAF!9E4LMyK_=o>Bjy2e}X851}+N{n>seJ(c)pBcHT&%$AockPuv0G ziWmIeJK3c_52Y0DU0v#vH2nJV$dM}_9|%Q-%4;+v>loIlX)L#!`KzhRuG&N1P}Va` zOqE7~_r(__Gue+LvSrIHIH$>O`(M4$k|M4vOa6L(`7$o%;J8PweR=-!q`mcmu>Ci{ z8^#NAiH_5Qbj;>iSD5Z}-0Ai-48ECB9=Jezdc)sfD~oyAT6J3&QyeiTJ$V`Iuu?>2 z9%F}K9uYyrdd|~odDHdU+CcoWbD4H|TZmeCrIo(XdBAvG4G+2(Ctlz=t*fGvib3LUU zk2?J}Exk9XF(~n1oGz(~RSs`-SsXDOO3GAHzB2~s5N!H=dwu5L5QH`yj(%b!+Y7VY zLu{~G;%0@U4G$~BMF{Pe6WncF=1S_TKmM52W%o!+rn2%2^ZGk;x7C{ zN(Sl4*#(jIJM8VSYeI2LO~&DMSK~cKW!o3a%ZFs|h|e#yv7UH(g8gF%s}R6sq2aJR z-yPCUi`_j!b2&N9?@e|E-$;{1!6LOzUAs7=#hh7oQ^EO2Y1{ND`@h#*gdn5S{d8>R zy+R3Vo>>|6!mPQOoFkTzU+aC`SB~X{Y4_f5!42ltcDv$YaFe=D1JN(K0*%9D&y292 z^YQ@ejtP2qQQYa9aDxYxNUMPFto`cBvc{IC6SjjFr@u+lM&TyU-sR|Dfshx?S%84v zk=w(Kmojc>)-Nia9$~h~v$|0*-)qw8oI8>sFRAhan`2;6fskd4xvuTOhB|8%@Vl)d zQnDDo>v>SLH2nk%qFAYMgU*cJB+jb zL}9`YMVSCH+9@%6M_pzJu6MHiWHctG0Q9N|;B|k-eoorN#M-=WRYx)Sm?zQZEwxQK z2lj?ZvM=+&1dE?04sD^E>+w_WDrV60 z(9pF%01+igM&ji2Z)Ol7yiVQUQp}e->|0Q&gIx}rN-Hd}IDa(<1LD{!!F+!?ZT45j zxLhb1N9;D`K*8v*tqCaw4hR?9rp3s*pVOb{DxLrYS0c}!Ps?ApWSuwL?wD>~U^`Sl zAX{JlbhyPl_vVel<(aBz`4?K1X2is{`vk1IK2MdC$U@Q$3YiK^;+~&nBhPkS{8FFS zyAPXK@k=`)0f*;bIE+2jFA#wpRX2hcM2SS4wdrDYw0z;Lr?0Q?RP79aAU1ZDn|O|* zFp?%e0gFl7?;)afVcoeRQ-gKf;;+Q)N8WzgURCJ2s`U*(1=V2z=Y^@Mv$GuiVROy9-wF1tM6xa)5(7UQ5>>=5j|dPf7~P^{)M-qzBD;790Kzv6irj=B zqvUwitt`3xew%!$7mMLYdP9j68#}(oc?!;~#GSujH;Sl9%ElH=Y1bT>7R_@<=og3I zDI>JVSa*dQ??n6Zgq=B)r7I+1!_QB4PJknwo3u&K7Q59?y?N_)kMN})&eXmz#}YVq zjo^V+`HjN^=N9FGb-D+uGVMH&ed%Qo#!kzG!6GlW?3~8z=Rf}tcb9m&Lr(WU90^IO z3PAfKzRCqrp0@zTvmlgrv#!pa+r}z!vS4LlNJ}j^W-1&7kOk@e$|a9D-sUxw-92!@%R z$;pL{Qn(WMkWrOUX5-y(JIOeRzEnk?dol1{%ALLn%EA5A{}?EeggMVN3H`G&*X>>U z`ROh*K`962;A1zd{i5xfuDzJLb(>SZ;bpa_6x(>KO=WS7vSjF%c7RwnlUZ&z?pvPa zv%i^Mr=A}8CI9bLZH5Jiz9pB#6gPKqir_D1Tz%LQgW`NA9O@Isqejn7k{}hL8uIiF zO=V$PLi~8j878A=SmN>K2hYx6^Bj}mtZuIfzwjjvaj9mhySQo6m0#hjpDFqCd?b$S zv**<-$XoDR8e@SNKJg{Ok>>W_I2E@7`LM4e?9I!K+(Jam4Xes$#GEwSxE`L4TmAFm zSYf!!@@QR_Rd?g{NYB?%Q6y?RDLJk*K_E%m_I?!}o%l=|5LC6mVkUlu>R4lh^slU^ zoA8sQzB>*dAey!KG+Gm@oN`1hT*A3JVsYQ&JzZyKnYeSFVIMyYo}s(itImOO7+gIh z^LNrF`!U`!c^PVMadN4Z@xl5e?OT9=Dsxp`6iM5iXWQ=dJUiC~iQ2Pg>>uImh1oII z6JvQcOumXr*DatpSB$aRK}1|fiz*=|YuCXyv4rTSEHNJybabg>JoI++VQ`Z|#2vi{ zP*CzK>#rq}4C+RVejJJ3`D2quPRA*3j0dRHBJ;~$UXcq4UVP29zFz!C`rYCVx4^Qq z6#UjwHpA^-Ig4RM#^KKNJ5G+{PA*T?ObjNZ1c-i<+?C9m*($h&iiwtB=Xnz)fvpDH zh=^@@#+%JjilHb8+|u4*-xtc16yVfolG%3Kee;f!0=`9#lecy-U_%~RPXMm%VT(+*OTLO*n=j&&Y^m33!Rb0HmD1h$q`^RDRZ71|1n_p;T~z7u2aj+OvTku z$sV6GsH(0j=%D(`GgL%i!)&`v)z`NQt-jVBz-PXI_Ja+>!0%z$E$QNfsz3#Q$V|GZ zoGDGv&{ZUrlb5f-EdmS(dvw|O>&x>aZyaWZ10QM6f`>LIll@is@0}~{_y4>Nqx@$yvw5X4 zd$*ke;TUPJJ(@9T93hR69`+<&l1-|Lt;0p>ylM^ti00H>al;qoNiXV zmP+rl+zh$ku+LK1_|mV+Qh>t#F5}TT%2tgA?z{%x;xkXq><}07-64~W^+z1Awm{l; zwEjifmIcA4)gMyCkg~Wi3WY$y0|jtqf_11!@U6L{^KhR}NOc&AI*P2Z_&NwM>ba?* zcI~1wZFU`v7KO_O5Wx~=md)94Y=tDgyILW`jNa*g^|%ZEqc`dkz>>%)+emia-E0u< zJo7Y0F<70jZF62Yle5pMH}bF#D)@WVr7?^pj;#+o*~VO+7Q0Gu3J!cCDX9Do2Je*jELoS{Ln&p~bxzjg0!NWX6gi;WN<(FOi2 z3vyZYj#2>i@3a(eg6nWA+jLldqDrt$`S7>pIYR;)49@0TqA#^x%S;$274S8nh%?;D_fa#e^HkMb=lvb=!Xr6D$;?3A$!#71yVpq{ z6@Ix1e18u7x(o2NqNKnt_)$Hf2|`xN$#2X5oY|37pT7kI>cES7!R7+B8D%%jYZE>M z5enJ7=dnfF^dW>jP^AoJ3mag>n-g^b!Czx z6^8G+y9xgV<%ly_oAfD#Romy;%V7Z_H?izn=b7Oq6KaQ*rTNq^TnV4IFyHX;&sMzP zO1wH(D%l0O+-q?(H$}_c97;K>#w(Ab`H5;ws~8pT7Ohh7T+R{@|0ZrP4z65hJ<#;d zn8{LE7kNKnXR%KCg@M|9_WNJybuUy-eG|QhF)R;0k&;L2{hyHZFFwT2SDIwsP-7n?Xfz$G;AzcF(mlapoa zh@MgxcKSK%*I@^|sddm|5q|U0f=V35cF3p?0oysM^B1T)Ne_qF{Y_O2`vPtk!Ga_% zF`9-8Tsd7r0fdb={Q3B!ZHzRC`6!u1=mj4{20=}HpoSyNVek#A(MnYJSQZf-x&BYY zR6_ziuhvzkaQt6pKCVafcPUR}`4v9H^hy9bglutejdmBCg zVL&@NcHipci$V{uS7V1@EBNLzx1z>W!y3KZycnp?A?FOC1~Q@i z_jdhB;3~sl8^tTz|B+mOVcass)rHHW3rSy0?GeH(4UWBqT_G*L2tavv3A2TQvLu{D zWVEay!%hAOfuw$P@10J(M};O3toud3Irsnb3Lu@g$JkMyjno0u z5Eo#I#1knNm}gL&hA7UKky;cqemIP{MP+0oKgK=7Sqm;g3Z@ZhwLHTSyVuy^z=ui{ ziMO8^ev7ETm`p~f(eVy+cfc6CEL<10nQrN2SzeJgvm0p^b^*tU;x8P!OsA}|LV-+wU?thJYIE< z74jKJzl8l{kB6K|ZQS{7druyx${u@Pqr})|hG=!Ezdi0W(&Bu3vu0=KmK z?U>=f&nl!qwHUo`wx{7V7K2Q4c52p68|(P_1KNGvyBG8JWIaz{1ztBE2x3>jfIqAn z^BJh|NW)Su1c0yC#jE8fnmuzPrRTZy7M5f5^`%FgZ~h|GTYJwu+V&LUoKU1ABENAG zWQbsgGALtiNN<&iUD~58s|TT}W!s4|c5jc{BhA2Mt2k>f31I<|zk(=N`TCgyf0JR8n7v!TSJ0zC`B8wNNhZyc} z-QmUVb$ox$tpVRE@h$M}YeCN}I#){F>PVIgCTJWw1Uq-HS?Sw`@35&n#aWBZ-6N&^;(_`#@6FqSbXX{X z9%fI@9nF~oDq=6dudmnBIcitCHpZgebRVT$@L$&gfXnrF5O3NrZd%VG-vjdd$+aqhb3|EaCcihx z4Ao3-B@q(Lp<=eCmtB{qP38n^c0GF7JY@4Y5z4v(N*?VDo@L>gO4k(|j#W>7KeN^4 zS#MQkap8=%+bs%@n9uy#7>G)Fw2)pZZmJ6Xu@CrR1*M_T4P(BGOa0x7%Hm9cN{x+4 z*!1EJ65D1A8dGH@Q)S{8eX=+aql?)mGN*I6thN^XpOZpAr0pAr%HlIXygiv6 zE{+bTT@Gp#x-54=E$+Qb>G(dsA0^1paCF43^A&nskR3dr^i(rRZ#GRR_Stu)E5zpe zQ#fUH(e_Q)XZ4_RqG0&B7{+wjRJ`t5=4O&&_lT@ky)(si+3d1yof_gmJ!0fekCd|5 zU3SpQbtf#4TLt778keo4TAhAs(;R zK7|WDoUO+q6-et8dBBHQ0d-q)wDP216|M8)jN+LQ*}K(*0?n3t95v$h%}TD$R~`Yh z!o|>XyX9tgl%JB@{q16LUsAVVJP^nB0-VFf-mW&_3~}_%^S)=M4{gMcB3Fdnc5T=s z{ANTBF>0Z@^W_{8r#mjXFDss#Je@O^cy&;tFy1t74B=B;0I9@6f8^8v6O^0U(nrUD zpP7IVE0)pWvglF5i~;nU@Rt!>O=md|W%fqCiQfnLkBa9E_7rezC@M?|LwMp6_ElMg zl*R&}+S=cc3hfX+hi>-~gR__IfBK{7eKA`F%G2)gPdmJUo;^_yX`ic<8DrG&WEyyK zbejt0Ur#;^PgWH8gnhC~6fu9noPmSZB6mvOg=iejgFRxmu7?1uQu7if9O9rx=R_&1 zH#A=l>N-!?aWUwEU7$UelZ>j3S4;S>N2AkzsG|ZU-Ns9s0;i{Y=6EJ1xA@ecmifew z$E?z^N};c9`o2F4!41U+7BT2K?Sw{&Z7T$1HKl(NHQyZv9;!R<*LV350{sfQ7_|8) zM4+Asm-{eakp+A-WSQ6hVFMAb;Fy^mwkBc%@l}Q`xBkM^lf@jj9*`npIM=L#`QtdT56OSPVBjR9_+#ME$F`ER@7RrXj?eQ3q3!aq% z{9Oda1VMrFHzUB{Y*v4Y>k0^|b%8ohZJ-u9e#hr~{JH_1D=L=)%?6kkT<^j#nSICV zR#qqKPmieFwJq|~zvyN_Z9i9+;z9@bAlW*R2y+(HamtWT7iu%;u_ly;^2{}r8jK13 z(@6}qw*OB0vs1EPp#d(v+WRLkYI05a*mN6GhOB%>v{i1s}uJm^iZA#ITo$Os{6@2cctgd--4|+&uAx9i-&bX;fIH*Hc@jWJTVZAD4 zClW;nN92x-a02FWyG&ptIA1YWX=#b1$|?qFW#owEx_jMvj{l$^2y_3Sj5bU z*d7CB+P})*AlR;kuivl@rJk@Nc)2}rKD?@pKyk9LoVfip|K3pc>%x`k6nOe%Pq}|` zE5w51-5y7~AOWQGQScJlr1Sd)T$bjJkLCU90zKiIw4M+5x5mb1aTXT-)m8g{Hev_5 zOL=#!phunaH3;?7R+bmf$;!&+*Zax4D+UQ2rb>r=H{u^q2jS%S#OGZEqX6Qx?*gSM z;=b^E=(3=b)m<&m&pSKYITq0RMl}`?<;k6&F=Q)bHXs2~%&z>xaz7EzSOfIkEx)lC7gXti~ES2l9?o&4KzcqH87ba?qtxtb7c<{JH^sbddMov(uyD^ zL9rMPVVuhtVTtZ8cYZJPww(2-wEl>TNQ#nUP=ehWw#Uent{;7lwO>yXs04Q+bx@$= z3Fv1*(@n{<_iIBiP{L5+jLInglQj5#2Jt9V8MDy8(`!)^L7}xLq6lin=Z{)r6#_4q z*h0nQ@vBl&637I~M)%3NgVmroCs6{blL9}V(m?m}gp~OiAovolV$E%TJ zH=BE$T?3B^fCBY6xK}r{6H=xEK+hHXY6d~snm1-AlR-IQ>XgZhPzh{2a>J?n>L|hc z^X{?vdc+Dk#^*p*7r&O?)}xvr>TRAa-%arKHSp6DhYD$Pk2Fl+E|bv*)@=eHl|N%J zNzcN}NO0AjhXVa8i(}sMeAyh*o=j>cCm;-3Fx?mfAhGX#(pJJrS>YjL2`oDsPxV*% ztLH$Ux>&g3@~#u3S%zMAQCMB&}p;hrt^oYCX;0#zD*RuI0 z94Y^TZ@yJaI-MVwU8u0$XAQ&zbFp*)rV?6mfp(0MP|7L7-m+;ELrn05qJnz`=t6a| zYrlHG5j+lsKyCS8jBp0OpAPEcYR`sanB@5oVb0x)aTv%^eCRDi^r@)H>gwvT^p3dm zk*J%se_pGs0X0^_9tAJuC#MaalUz7|*{YZ>^=E)Kz2M_^w6ScZq+#~Gfmu`4^4%b^ zPI+J5bC?}*M5z5#dg8)f%#*W$?Fmab5&2gUeU%M9B=X(2VK`(xQAGqXQH;W2Rc(a4 zpi3gEX>-g?E7d^CA%5iTl}`rH+oe-#0uXi_db>57@(9HUfdpHuhrGl9efw)1h2d(q zk}}&Jte{U>Otf{659PH4Onrqvi7@#)DpfwrB1sBRS-8ArM99E!5)>S4IB z2OCoKK-6-QwIx2S7rvVtM9@HX_&alVP?=ttt|JsI&Q2gbKX_frd87M^#e&ft@Y-W`vhIH)(0=yTDEf8<} z>k>4iZF*WF5|VSc_;UJRqYhqlG$nCw%lG&fkbR2}3qW_2fUZ#Tir$3!ewTr;edcuM z+h5^V0iJgByx=2j$`(aO7RemRgYhgbx|hdpYAFN>z4`hQcoY%P4eO~mP%`j&7Yys^@|EX%8tEk#|Mti& ztinefmh$f7bsEf5$%H(>pFd@3V;}{-nLq>hs_OYQ067{7-K-<}MR%K(L(Uup9LH=0 zjw3y3m-!{Rr>BKuPa~8Md*XEu|MsJ!_@3F^8l@AwNW~;)AtNzt3(A#+Wxk{8ksBd{ zHVK|uWu9MxDU=S8Aa<-#N*r0o+HMi5Q8HjFxORJRZC8hHJQZ=@E}TOk<()UO&LDmlSFGG;}vQ5o}wI5uyT3Ge)RuC)Hru+R_W9-x!;6779? z2VQ||I0*m(!QG%Qf5~#$>^D8cK@2|Z1+hd_*J+|y?v&T@t|wX0f{Qe3NbcO&Y-+Z* z7a&juV|(<0^cz_t$}Tlj~*B z0Hgv-*lU~O_Pe>(M7vwU>CS>=y5>A5J#T`ruV^4q_6f%lgnlNCjp6doO6h_CuTJ7IZVvAVz1pTI^lGu_ege zyd@T{M`wltg0un(OvBjJkPt3_YbD6avpPUY1)$W~6y5wu=^r3!e2PMt#M1aD3Nu8;)YLTZ5bg2F8<2lRcu2%65(E=s z3N!gYY4MR}JJ=@zoUQmMt*V!~RSF@!aTEt!AG7Sn(y3R6_H!BpBR4A8?AC(i=p z0%;@?0-SB?)%rfDV!7ExJ)H-tqv^iq!>Xb`%y=GaJ~T8Gj7rpE-cHSv5A#+(J>KDs zxORl?C|dSF(&S(jG;7JYxlgs&Wvw(7L%znP${^0MUP6s+Gg)Tf8 zyK+NRnSKV`@+Gkvf;{R+v83oO4)_Ty0;Fd~)M>O|C`^o)ycHj)Sj&1BmGy@kQ>{Ml zJO?5$cCI`WgT26hPWVRr<~Dx^CTLazh#Fq5W5Ku$DIb8SPUb}MjSOYa2TW*CShEC- z)F6Qw$7;xBr0`D68H^WgYpZ>u+Ksv`v0)DJAH`r{2tS^Ay#3pNF75BsH+f1QTKeuF zP>ia+U;*OTpha7IiYvoSjbY6%3PD03s$CbJ09S#YO}(kbQBqe%Kp zAhSW{UVf8G&y5R-Gp!L)aSNKkJ{nxPNOchtS^n>92t%u#P}MN--p_6tE21w%s5zsVLt|`}-Uw zHT4_cUa@L6iB)SpJ?S_BO~vPxH{-D_Y6^e@`NG&d@vpu0J`&WhZ-kB%chV40gar1s z&s5`g*Y6Mq9$HEVo!!1XKdj1i!^}_d*i*X>=S-jG`ZZ=$1xFlRK2Sqi>#a^!8w+{g z*;J%a%O&uJfCJ@5;T4B;r(#=P3}{u>$1O$J67E_c}}qD z+SDT86%7B0IEB=P8d(=0BX>dCb>rwC#ZVF;*nkvZ$ZCsW2XN0I6Eh5ym<40JBazUl zfV>id(kOR`4L}z!$>jlMB&fc2Q)kzjzXp<{UibuvD%8a0zMmNL04l)v*sJrH0Mzpy z-c-rLy9>L&Dj-zJwIjp4B8e&A+Z#=3$R<%88E5I+^SKe)uQ2x*#NVUz+YchtH*Dwo z1T@exs&^#R#c#rnFsWD|?o9gTz75wQA-k#vQF$@O2%8R%lhE^B-i_p5ppMM@_y}Yh zjae|w5g8Q~bzJ4vZ!w59OzVU$zbIU~7EK2LJ8S|vBYl<(a+vfU!375v|G){$Uf!dX z*?S^KxrTqbi&GlT^)+N4%`j2N8t0YyzKNRf6(I@WtSLD2`(L|vfmv3x zzcyMsb5mXcDAyZN;{wJ;k}Z>=gpvg5x5iMq0tSxYKA}Mgk6blO%)5@m10h|EvJVK9 zZa-9eZ_y!vn!G6ZmH0~l32X)3fNMg!S>o&m?_&dmDj&e}=50*R*nMaumj?#XttD(HJ^lMs$DTm0i@Oj&N=YBJH3-WmmGQ$i zFE#VmVZxOUDIS5oFqega>oC2v$F}x-Dv+xsfESoxoazan;$!9@QJ2}PTv)46tbb=EDe)( zY1tP&dmZ4+3@XKE6Q|l;m%3RIvr~KBMP$t{ra9k25{y;uOB@b@Vg{0W`iff`4aVNn z5g8@?iX6LfoOtqG2R|e6cYqVXuu|w(=*BELj^&FWwsNX(478_>0DA;YCqOEwe18JM zfW1FVp&k6H?_=q>MdlI4U{v^tq3HJnt$KiF0tk8Q9JthV=oVuomk&F;X-H|HxtsaE zaBs+=amjK5YjaazW{8t^feJ%SYzQ%gNc$6@aSWTCY!5(o(n#z5i+3b#hq@T~k0A`r zJPUbW0NSJHZ)`xvg(SqWlCG%L2JQNn=lRQ5WwM8obGtYt=Vg~Byj{Qchc$1fF;7W~ zSj1RhSwImQsRl2(7Bd8K0F5$fS6p-q0~TR!I>nU*n(j9r&LSzyfM2fI?cqx!^B{>N zL@}YnBIwo9fi5im{S%17BFCDp`aR;U9mE8ts~nKlcKZFMJ%0ZhtzQwGv;o9g1?`mz zy%icnz(|jT1Hhkv!GU7naadpI+}4zyt-TE!ev`Bf+r~IX;=9Qn#O-J%QbY$BOa~eV zpmpD+Dx~+x49cx|&7g+b9VG5!-XT7v!jTT+fCw4mmuR7ImqtqcRA}u`FyBGaanRsY zR&G(-;06D6z{ZHULB~$VVbTF2g8>qOHYg;cI$76c{wGvH?5{OabSHqlEd^|82m;7w zC)*`Nsa6nFK*7LoK#+<3KewSa6*ozeSShiX_?0X4gq>HIxMTgq;7{d3gJL%srK_%E z`LkS?S3&aP4j?$@)Zn{AzYW_*hrr+~yUT9pf736gWZwbhQd;iYCajUiLpo3wRm2t{ z1>{I}=1X0YXa5Tb%7Q0|45Nz6gm{SxdZZ{7G#>!5mRHY2#s^NDv4k`1joiqT)x#2P4Ee- zPLH&RXuZGw%=19J@HuN!Gn&K{p4QtniXz1zu~JF0Uzg)qYqQNCEkcAjlC-}4XY1ZO zY}=1_-fcBMYrA1wZcshvKM~Oz+W3g$vtw-=<+pxH3NvKWnFTCivACpeGA#uZXa-EK;o36!T%ik{ab7) zBtYFpx~{JLT$%4_kw&u5;{f-6#q$?$MA}325PS`qOq@49VpB;j+VN?mJc7eV0<>_) zXBrI?ww-mdtLAtc7P2Y)K^I&B&?h*g76|0YrXZH#5 zU4a;J&ieGAT}sc`$<14~J%PGzP(dRh6$N7?cs_m(BCo;H+yolc&`RoF8uW}6Sn zh9g(Yd~W4%hTYlkFg>W2@aExvj^vsiM#38;KMmAWhX%zZXtmbtHeX8~!wO;`krv)MESc znhbZUo3^AMx9eee7uNyRe8cfZ9%xFzy2V%ge7KI0sFqg0X z{EifmECVT7Z$0zXTn}z7h*mCc2IXuQ2qS>U4r`K=UdzApT$Z)x&lN-XQNJ?Z7iy<_ z`Bs(Gd~;aNhLzDihd^}dW-Ng^Tw|Q#T*l`1w|?GDTOOy$gKsBBK(8^ht}82 z`P%Ywa$I@)$TK*V|3P;bOdk|po8~@r9FJJ1WEeW7Sd=S3GeiuRJD4^wybpr6^BIPN znB)tvxSaeXqF;fTIEH4Tq#^HAgpR?)k{6nr0~4S_qXhnDUZ6eZ%kJ?-=kCzuSQ#c> zk>B@`lHUUrrXW0KKw$48{l_@#DyYH!qvtVrnhlmrG|Q@6-Vq5CLaGe%0fF!0^%qf_ z$tA04o$i%^wri6sf)G!vfUrhxwGHctTR<*lfpe1ID0oO2my_dj%sc-Yj;lM-Y#M@Ow7r61seZ0R3J|xeJD6#y@=6l0Y*_ z=qs;9h{4nP<-P}yh(l0S1PFE%Mc3C4G6A(8TZ4w8aqesRLG&;P*hS7-XUR%6bbh$s z4YkeJ@@BgAHw3bIHY<6}_Ek85&&Zrym6Y^5fZEn@;V1vlfn>*$oImDZep9R-1cpK! zt3X_p`fKPi9yR{%0RxhyV6A(BnKwh-J%|>!~hbg)&eM(5PbQC;BZqH#O z0h;t94paRv;SvRoQ}aDjvoLH|Iv_g%c)ubj`@e=m9ubD%ouF>JCT%xReW3ob&9`mF zZ<^l5-y7l2pStkv;O#XXFWh=j?y9F4ws4^;9qzz6H`(z3+r6(vv*OE|+8EA+h*%Q@ z`ITaC$Twmfb=>LBPdg+%pqhHlSO)`l&@Gh;ojWj;l=g*-?t5rRBVVH~=hVU9v4oW0 z=j4xfFtkE9lMUFq7$#-a$G0@JQ99Kq~vFFgi@nDQW5VU%*= z!VlE6M@=NpzNF!jtKUG?u5tYA+kB-)#ouG%ZgTn%Nm4=0q~7?8A5?}=T^xv8SAFS_am z2}%+{3=K6O6XgCfu}Auj^|Fd!gbmAYMq$yr@)bKfjnK4Avj@L~`VQ_fsg{p(4| z@T4KFM(o`(7depj>!q-n`t#?{&%$*R@3#AY)vgi->~ja?Qtt|4{+vE!0C%XGG{~$V zF_c1jrNCZFB8FH__DeMwJco;rfRh|L)5Ns#YGk#UxN9F~keVA!DPITQbAEAcjg^dm zIKMg?v=kWmdI(zHo*>xGl@WTsF+~&Mg5IE^#T4^})Mfut0Bk1%g5V%hkC`912UDA; z)}}UrmPQfJ8!BvyTxSUJ-NurOn$NCZ_xl46U;+-bE#c|@m>Pr4#}?pfqF>O4c4-rS z3oSB3bk)dD^|!_J+Mgk5F@n6rq=h+~#k^(h(;^_TcBd39m}c9I!T9nKr@8U#VCbQVH!rL?3Qmd` zlZ9JR2rd~o>r4gh*PLj zmX;qizrG`kluJ-9d$N0GHML-=+EJJnngwc955_qB)+J8ZP$9ks^Tw8Ux5yg&ZwHm>U8O#=Gn& z%uFGzKSc2JH#3be(fW`OY|ZJG^UIjsV!_Y<>MMo&)h@_)}C*s)(@-~BS`1Y zJ+whLsvv@;!IbI`^c(s45Lo)6hQ|SHs<4_%)l);(o{ zX6RC>Eg*3`aNvM&JfVpP7ZD-$BzqPFwewccL9M@TzRtsu465qG9NsgMRzJ?~&+V3b zI3;CaApp6Z1FrFIJoVphq;S)Og}k)W8^bI_DdPQmA@Ov$zR4BBEjPp3AauSoWeS9S zXesW3$;9*7vpZlaXcV|urf(w$*X`mAnZiqfeQ3lO1QUnt=7DZzUjg<@=&VUSCdZDK=aIdQ=a9EhkzxVX$ReUIDnkN2o`__L=LDVOCY3anr8!)cXUX5 zvyQl-VgSNM7x4|xNZKlLA8lu00x7CtL3%W1K7a~F2HN$f=&@6WxDkloW)|1~YW(a% zGjK2}%JJ@lEYg?#lWXajx*rDOo z>kuRma9$JSOHhS*0hCE@EdfOuBQV96;W~?iIsIFg$BE?+Dtp=U7w!q&ej>5cv5xKc z165|>=xr@-kZ#x|3}y#HoCvK7!dw`D*P=jrbwnlkpOA;E5(u;O0J!o360+9&T0Yvu zXu=8UseaO@BkBciLK%J|oSl9xzWiQMtyzjEJ@XCf5ulwY-vzD#`9rr6&EvYYf4!IC za{yocWPH;E&y}D@IAO>=3HWPkWFH}OOdkX}!j8{S@m&1jFx%nkx(9{>r`5e5!u0oU zqSbG2ue2t~-Nk*P+yi6kRvpf>{@P{hAdjg)hK{<-w`fVE{Rw$&7?Zd~);=wZeA@sc zVXCza`3f6SoVVzJ@ddUqu*qL8l)~$o3o4yX5;QH)XqJ-S1#J$#%uMhDQOLhp_lC63 ztl1OZf)wu3+an1c*9{~T7sJoj?tE?lt#|Ck-=lsxo}gEp*P!b@J(|m}H8rY3EpD>5 zC)Y2*o;;e)6vMaDSUO3Yk32U0lUNaOKxul0135BZ?IlM397a(9!M)JX z@pnm?RaKU%sng(GFGS_VCs8*C?vbbtK(~paYbGH# zA(?G@v%lzj#lgy}o$)oU8wHDx;|r^cuB-egs+vCjc~q;BZ9TAVr`*PTj0YuMYi=|p z)D7WAPV#d9eu#Xkpt>{?pX>aRwzx8+cfR_)NkRInwXnyw6->#-QuX;?gER{8;Zc7< zjK&=o$hWS49y_ z(DWW7Rv5)d7}*3Jqh@a(Q2$IYk`Q-c7%bZjG0A8S!D#qk@C_QIhwx%Kp)Tr8wC)L~ z>18CwXMr0EXhD%<4|KrH_hqJJo~D5uCUK(o#5T|tAtrQ^PvX}W}k;66c47!UL%>&@^`{ zh&br-j}pcsprRynuz{;vSsiX8&uTDSkQ~oVquS4I;KOr1D%E)SY6rVKqo?KWG%2@J z9FDI)L<}D^yUNSK732FTXZfA z8=KDk{&LYt>6z;h&gfsjTf!YQytth*j`%>x3^nd^@+6O1YE}kGew!pCyMC6qVY1wx z>k?5&;vn6Yxp)!KS!W^f{Lb@KTi4>$X~Kma;JdqWFWeuP9%|6*HbGaeMmo-pN+k~g zZbNa{?Bu6EATgN?RU*$E?k^5Ez1zhbyHc$PJ%LELMK1f}tIBP(mlmcQj=WI}z9ed< z{%T6twBF+ptMhX_%TtBlP&O*^?vI&Ud31q)*@*(tr;*|ZX&yLoQV-b|)L*TCy9k>h zDZ2az3Dftl!ay}O=!+J<6^ugVp~s?ISyAB*1ku$*_s(?-aifvRf3*yVfp2mS1n!&& z*q}SUr2Osp@Pgz^aE?b(l*2zW4%H?xpU9t(4*Z^h7+VwGPS@jdLqj|H7D={c8h3>L zb?@6A8iCfZGcS_V)*Kgp;U^DL21BLAPZOIAn&VW6fy+keKm?Z_Dc!RRnyqq)C%~&H z+r_l<9j2|7hL5j%{cSQNl|pwVTs?|19lFV^sVa^yO^!{tHjK%fe^AqPw#{%6hJNE+ zgx4gl7eis&;@@dt=w%|}YxDxGx<;qBVoAFCp z1Q0%-gMd;k2C3^VBzOIuW4eB;t;!xe>MZYtbhrP7F3?|A(8gov+iga6(G9nfc5PzB zzOUGKzl-QGI{nB`+ud_!+cXYq(yjrQG`%8A$C-}Q?HD&JGk`k`Cx zUOj_ustAGaX{t$764cU%L9)`XoMCfydyk1u*EYr*mU@hyzq4jT&Tyi!l{zwi$?Iq+ zcboGc3B+D7bM~_b65My<4Y+hv!_yq}Mo4q+w&Vh=MfW3S^UgnXj*0@l zR4};R18St{j`8t=sNYA zQ}M6EpjFbP(XqD~YRWs1pRK>2U#~#$X%ySwt}Oi`XCRE8Mj}QO-BWZCG;)d8hB;MC z@nb1DT=a0{7NZ?qg9(u{qJ7VE9<3|%L24$@I{Iq^uK-!P4NNZV!wb%h`zY{SG?(7$ zp91of@4PdFN$*E+C2^oBNXM*(Q%lk1)w?<@K;r=E?*tOatDisjWgR~VYImZH4BSO# z*};{ChQbmc{X&|kvh8ID_$UB$SjL^Qy5VLJ+CQ?(;pLQF6CQZQMg{m72v!$!nD}j`~8Gr zx1pD2w;1L6ITh~&x7>5UZ2iw@jXp8N5TvIJKCkCk!bj+8RJeqKv$`(sJUfyjN<)C7 z={Nz>8g^k7wOZJi*|Vn96@PT@D#!4^1(kvhho04C?n+k#@@D8WyoS-3YupARcp5T= zk?I3Rl8ZM|Z{KiST|WP-^S*m}{d%{rCm`d?j#TKHKgn&XBMs%)X*3!nxiyeQ6y0;Y91t>EI#QfPJ1ZVX=MlDPMHF|WnCjXUgsQgg`ByrOUG|rPc4h~u>iWD{$N!4$Y)OD5FE8Sai2uas1B5IJQO7m8CvzCS3Qr7C@3=K41oD z5`J_w+15RlxEc2Tw_iwlrv~X%&2y8^PTM(jdtQn)Z=)GWT`#r9&EP|W3pWBh=nT^Cx9oT3miwIKadd;eQUVaS*S7=Jm_(X zcb?m`6Q+OVghCfcKh@q{E{vpI0Wd;m67pT6;5_wb$!9L#KY!5yW1G(S*N2aP6W;&16C6T7c0kG*{PLL>et zv*#Yoc;{p5VaE-8VAKX9a{SkbD@QLwl~@VaWB|>lqLK}&>xojy71SY|u<=E@GIUMH z*)(jXKM*MFV&dn%x;V|F zOfFOBpUyU|XMj0j2(S{&zx^FR5d2W44<9i)*}vW>+2Z!2ZWIdql#f~fLN404L8RbJ z&h8D`uR1;2b|MJ608&r=*ZaUd$weSghPJ8K6R@rW)JU6tuQ2f)1m>T7KHn>(^k?Au z#M<03zB)|;Y@?f?Op6x#`iGwyjNUU3|Hpx~cO2VMfV{@N`LY`_B(^pZbVU;Ah_531 z+Bt&MDZoDSx9$HEVapitKv@d$0VvzQcoUE<5}k+|zN(sJxOBwE$OD>c>fgfk;y*P2 zC(yX^CRQ%J;m<yVfaJ-ZGa4sW=H^(@rf)rXP}t?ewn zbypc+TO`4(x&vpke_G?VlGs30>zOL6Y%+z>+QYrT&%dc`wp?9~Y(KNZ-=XkN&eo#< z4-5R?JPhuJLPQKm{K_klqs0!4b6El@u1?)f9LqH*I7L0FoK`)($rWXy^z@!0= zU4;j)sVvD-1O1CjX0B#cF)%R{Fw*j3e$O97zQV1a)n>dNZ3uqE$OHA+eST%kC01%Y zwK!b=}|s8+A^u=6ILeqv2O z2gC~chiXV;lVObOJOtN9kQ`7x3Q`iE;gGLkIwCA&|xT){Poo!C3C$A_x2!| zvf1CF46>+HNE1Q@d#X0v{o*r%CJSaKo(`frrlTG;z?JE&AbUS7r~{ZAQ3`6$FKhle zTwgK*MuIx#b3m=$7$cnWFbwY>5dE%2oC%!5qan$Ag=KyV3F3uLO5)SCcVGi4SFF7sMRzY9xv5nP9hb)b@lWpBAH~*T029RK zlxJn@qyiz8M5VxnPUSO~ufG)u*~N!Nz&ulKX;fWZ>WGDORs}1*_aoL@a^?8Wq${5u zA*~oXXSL7je;TV1&xt_>bpz4ZeAaewfA)TU{*>pOEdlPts$)6aMhp`Tn{G26HqxVe*}rq zAfqK}r4ROXBC>&CW`Nvjn-m6jYxN3o{kdJbsFE0Npi|ES?tuImXn9IOrNch` zF5)p@bM@sZRfVq=?$LVAYS#yvwapn%fT}SlV^LxaA4asInvgjfD_dt%nJ2!+VqWP@ z=K4Hia!gTb-M)y3>3Ds@!&zYtntQjk9u#TlAAmuLAEaZn8*LdpK~Z!t8Q&d z#HSaP5li%RRTzY--bWrR{9Wn@NE5|xpyGP27^ z*_qkSHZseKP)6Aydsa4)k-d_Uy+`Kvc%3=VQ}=y8e!tH@_v5;{yLi9fuj6%$=kYwA zM;jla0-S}}0zH^-ald`ww8=iC%m!(Ufyg5~f}qCz4bliiIQ3&(_>(mRmUbB@ohOdn zSexXZtz@T>9PdogNi6t1IB@mzewSH1>en(`i!h~_QAb@OvCgST> zTX?SyUq*Q}Web8~O^Y-K5T5~YVZ=)E^YfuMCz&e|glk2LMm{G(tp@PdX%*MeG!>Ez zR4*gTG<;F)50H$mwsxX+TC}1@1}HXU7S1=D7%B7p`L&`?0IR6;^`yqTC`e zOP+QUsH><}1s7LVw=Ztn0!sfdjZob0gNbMmks>FAGCFcpfFlW8v8VGR-#sDZi9>yq zp6!?vAa=7^WMhA0uC1I&+eB))?!$sb-pZ@ZIA2yJ4px|R{M;73nWh&qg$OkQ1;tx{Ew-_2VWb6KQFl$In zi>B_8yf)|iG`$mYy(@sHkbo}uv#vY+6|%Fr3iEWMhJ* zZqP14d50S3k3|u={z2Bg^%=p5?4NHHA}&nft<_R2QX|U@ZDeA}8wXLrlg7>5M~==M zd8;mQ^lQFvHJj`+cYFI(%i6F@Ka3AqE1IknZx3nlE!jLP6?9e}#!UoHFpLp$!nIK~ z*X|*<)GFSH4jGO3XAR{*#T)b$b#*?_P$>l<(}m3*^3*6$5Zd(?6!J=-jM(eC+!!&1 z_c{H(q9gPNktB>*Ibwf);uACb@M(u&^qcQGWHt7`2ZAj}lXeB?YUPzl$b}N&+^CW} z1V+wVs(%LNHb3?NIx(k%ukj8`l$nMEU|(7&OS3P)mBK9z9+}Fzk3kBt_H6^DF z@E`@pL-a5p*A`p{b4>62C9kw|QBPx%ugW=JZ z^P8RmJxB;IoK~Z`;+A2k7#h?;a01^YVtxn)D?Vv-1c7|z*$<$f;TII7ntRC>e@OcI zq9caoO&uMQ&-eNL8bAt|Xbk74W0Pnl$>97jjfl3Zv+hq7Mxipccj4+Y+sAQt_~i>Y zC(8%c*b#f&oru2#*G>6-!WM4X2np<9+Xs&3w_pV*%j^YVW+`H5Ug`Cr;nU?}YTSQI zsuU**X=5L#VsHpt-bA0@H#m8y78bwMF!vJVD+=StAD#Mf)if!CQ^Xf1@r~I4BVN3U zdoJ|j{ujz}j6@|_b3YPu13ZmB%$GsC2&5rA&nLl11S~_NsP%Jhnm<w#vep5ErJO6!G?-1m3KDd4C%maCl>vJ*$(Ru)N{zAtp4~lW*+c; z?@CXR{#67ups4jabPH`(Kp8~`B+U9?3Ch9Cniii((8fwJA-m3dl4$Bbq&>D1|9xpW z&=6la5a?gMw%FeNerIk{4@_}g>HJ1B@u|x7q&KM z{uj{1@dioQ>B7tqNgk5ZpK4xs8;;eyo;Km8AiHq*manuXWe@ppv^485+C4__Zs^ZBBQ}rWH@gNW32a1UDiL> z?IFAQbuiKh=08^Bf%|-rQf{UObBGNR@RmE`7nwK*6l7?O(gubi>9xQChg{DMZ#= zc7-WnP}!shl%aOQLWvUIvsC|;^xUj=v2M0AEKeCnnNvaeMCR3HJ zf@4>L`%xx~?rsftutFn-ZxO}}q@SaGNap1p%q*!G$Y$W67Gi-bH~TC6QXx#zu0H== z&3Dr70mMU<+YqhsX_E=u&g`S`n z=w_Ee>^TG@>+;s%Xl4=Nc(?la!Cx%8jHPV2Dvo8lk$@f=T<^4U7p&u)VV4*|$7} zr3A7M%?t_rU9`M`B~7D^e20A5BMJYOxC zKurRzTdNx9@eHw2Es?d8@zCIOmwJh7jU=iSTdchDO8hHDX@@JU(2+nz*xxLgLyDv~ z?}7IB(OO8cRnTyGDztGyY4Yh7x4R3?=%8(d#1bQ;u*Hro8h9vzR=3dwF?hj7D_sO- zX)2Vb`&<1gHXTMLN*xytG&A9E8_c2bKwtX+J%e%MexC$S}DlWt798rR> zw`dOPuXCWF#!@#1cLpu>(;O8{>?0Xm9HkfeXdc1wao|)-2^8pB)7zAAulrIFKJ>0n z+~_-EX7*P2JTn@wk4*pL&udX8lEX!iY!}_VYYy1hXy>n3IpT#w`a0T@5^ zK#A*s^}a2if|yeko^ik-fiUhInMOP_JBt;PM)Gb~XMn2V4Xup#X>Z@-8`QpfSVb$O zwgjxjuwVIqQtTi-mXMB#kr)|0-O=XM{%St*Q>hDsq2;w}%LZn8{+o#M|M>o-`g!nh zCPlY!&~mH0lyLFV>|X~-eMZK6GP+-9T+E`Na@_-=OrL|lY{w|JInp}a8S zSYVviIQ6-g+y#KoHnCtJa6qY)ALk!t05;Js4421Mfau{wW8iwED4CTK;+ax*@#n|n zh&1SdBKTDp$!qq21#l-}b*ttN!M!+hqh$UD9v)2s5TQLm97{P+-ZXBUm@$R3xL@+@ z(!~V8LdOJ5ZY)0y+628T)WBm3I?glT?>a~t9zd1)7oHJ9KcjeK7b-CUiJ=7uPwE4T zXGm$}=ax@(4C~qvxv$KdG4y@Va?Z*5**JD*5;_W|Lo~B9EHks@k2~jTPUuySCd>5n z`ft`^f_!irheWn&;!{@W!()XwIi}%Hnv#PX!HL*q0kBS#&wmi;;+{ z67h$vF7Z>|0U?CAt@%vz8GNsUX~fD zLLnKxL0q^sNr@&$NIM-!;U;_--K3fr1=bP4|%r&c7yxO;$Bu#bd;=R~8@Dh`K8 zTDU*-d-DB(vhuUP^?CUSpU%wr>3xdnCQkc4k_^>yhYK4BKMhI*;#?^r2^C=X#)HJnK$ukSne%yub-@mG z!tTNIxpqDjp(mvlmu7H=fhzoRk$>8^+GaY+DHhhG2oC{NM@VQ8vYT|p7m*s#KBM9- zhG{?q(~h2C6>K9wac)C$&z#jU7WG6uAgs;}bDJe+pgr%7i$}f-2;W}!i08fOBBqp( zJHtsZLT1H(!7xij(+IGd=nhgO>w?xpv-+QgzA@Ca0oxd#;m2-$zY>8ZJV(UtX|NVr zBP*mL)5NDY0XiFPoh}mdnI@kf1w-YKYPm3WDd!9fx4vKec6tAI&kuh-zo;3?dcQih z;E+<3VyUsf*OB49MrhLu@}O04;z;r8B`IJE9HhMS`6rs`ZtBe= z$gql@BSjOX*o~49-N{PZ&`3O*V+TslX-3^arzcE6tsg9ySNZ&=-Y`O3DJ6XN!sdz$ z%pCN$!q@GN{>zu7GXKT}d&@UdMIAORtv}ifPox}n|8vp5W1S#8GV6Z<;uN?*#IL3BK7N_fl3c>Po**)Ayh@j6{9(A$lzq7je#eJ zmTbj4p12>--I-tL{Ik4hjmPiDo)#UZBFM5hzs8=$Mrn>rQ7}TT1taowluXcR#|Pqn zC9pCW!5VX{S_lH$6&En5_ybapj=o;pr-dfBtp}023&Es-TV#kOBIN~O+P^ltXT@3f zvct?%u)u-U!EC8s@@mxWuVHE5xc{UHzBzCmPApCw-Es@vL;-j@Oo%)1cK`>xhd9&j zJFu1jBC&&~*$9=n3OTBSuZg4smWw(7AzgM*1=gT#$bCF&kme1;&~VO+0!W)K#D;cvmXH3unBOEH zAQ&Kbrtr35R0tmHJrM@YDxf0geb{n4FbY*j+%5C^vxdTGJSBa2A1T6V-+@!lp@`aC zlg|7T#sAKLT{w;hHXLryK-JqwsCt=aiNVv+8iw7IV7U(t7Oi_nz4{tsX`q2svH3Dl zeXp{8)P?;@k!d8bfN?)!cDxL?_GvQDS*KL(P8NFx*$ zlZv*eG)Z&%I-FR6D@6+=PX!Y>3X*Y1Ojv~*90=}0nQaQ>j7mzy^ZE0kx|s%CKvgYS zlk5ESXL7x(R7LvVpi`n5^$jO+MFLir-bES>Q__tV527 z3cCdRZ_uGMcz(zCJw= zGN5y~!MxDj9jN08ble+9i9gZWFk zvXBvq9k9u>@$}j)e6q3Q#b(R7;wm^~L5JyfJo*b2gAno<<-#L)@)07q!jixe07YNi znL|r55Z!KNn>EhKG5gLFpGtyiI&fBrmg1`H%pK;*)f20x$ zO{KRtn;m~#MZ;zI{SKWEaY!XRn~Tg%NP3T11`nb75%Nz)f+9U8kt!RANPWO`lbxFd zbRVfHMx1hvy?o?_kc~%9O5v+#4O5^d#c;qZcsG>+F5thEhF=rcYVwy~Z~(Wg;N$3v zHvu=u9nm(hdT0`tWP#AxK_FHT;Y=BfCV?2uNy8w<{kQLc#C--W^GO`Z;0#sEfG*z3 zkVtu&)C;oG8+I$>Q7)6+%KPPTYZ666zz+w7e8WwQVb9?GIWSCR!xRDhiD3Fjqq}R? zL7{;?5Q+aG2hn%%*5>dgN*kY3gEHE7B+&X;pe0f51QOH63K+%*SyKoV=@c!!ab6M2 z=K*bbqb#F<&;BjLxaAHg;Ji(N=yV1axrExRsfb^`4x&f5MHV&R&ecv99xz^+ z+^>9()o2r+9N>Tmb&#JCM~=pZ=_)iU)YgX&V^Fpg76Z4HKJLuNjhWxTW?(>~4%2(m z2+G)^J9at26i_PAz)K)vki~#UDA0orZYn4p=_{TY-fwfslMV~#Jk~I7l#BYbGWpK% zW*jaPWd#qUO~frj2noP>F$4Q-9GB=PK(SLBBr1tFt{(q(0>p5ME0K01$Xi_8e0-&7 zFvO5eAO@)X+b6<-i0ayl3I4tG(|!90WRIg}Mb5)}GI3lFUpDl*{VXN8JA$=` zyWkdsB))Eii}-vQbX}okPyHCpRUo;W(w&L~phc9HEK$4QoGqwQ1w-H9&0ZK3@c>>D zH;j|#amog@#juClX>%`+rC*X$(g3Meo2985Gg(}+0fiV00CEss7OvTUq42&LM6lu7 z8Bq|?c9KiN%_%w}sMVJ^uAztbT*T|Dks#!X#3P8II>e4dxha!j#J@Z(2j{aB5g{Y-_NsW-tMpBdH!bm7&jWSBI&Pl)@2nZHC zMsTFc>{HN!7K5yfdK*B&5la9yMM1WyOwW6ntIlaGHF&-Eq5E71?3YhnH_J1)qpFL` zddMI&EV}=73jZ~Ez-&x{1aO#uvHG^C=^urwUxd}j-|*vpKPHU+EbJ!lgO-f!S%56q z(WG|R;<01J(WgyyfAoHGH}#V6<{rMSE?RAsz^++jiq{C~UI-o}A`9=zm zls(^1gC=nkHFMGw+aNLEda{Q}JLGB;!H*~o5TQYJG?3|j5WCe76zJn;oI>{A99GpS zMa=yKdOqI0jz2*n({%Omd)ZuRwavhIid6r*g(KV}tAVYLQh|ynLF+aGkX%8ELHp29 z6)e^aFf0GHo-LX&6|5Lg04o75$w5RaYyt?^{19{(y@1DXGU#ko)96^Zu-=I9;?Y`! zRHXh`UkMsE!7GvvAN5rR9v(5*UmN#0QE)QgNZ9f{?qktaSXan_*6g$%*DZP03W=Pj zov$+C@zbvKq9u-?@yT{B7mBMWBrn`_w={FcInOpV(se`3PvVHAipi~axZ~i2wu2+< zL;O4o)-ldN8Lu7ws&>nVKK-XwhO~Sdt*-RjK539}8@mh$dx0=Dl)pg94K*FyKY)zp zO($?aA@yRk?=%4`aO#LxP7D*yQ}hSa%H5$WPxan8Jdu0=_}~Rj!mkM?55Yzn!M$;v z9=HmFlyXTK1BjV8;_X0ZOH%hM03viCtJw34@OLWIFu+HIF=!{hUmIYO+)Ja9;XTmx zsp8@XxVPl3DWsUEFD%?}+WcggL}(v}E4Re$#~C!-LQ6ULB*|S{R<$-L--L7+<%p%w z_X&7*76~y!plCdmt4a9yoSMBb3JGYHGj!l!;{e*uojkQ1qTO2#t2XUHR_~5p(5Ht{ z%R3I}J2=kZPJj$j^hM17-z~&~hiFwD(Cm*ooWtP)jR_LC$U+QjK$z#77XZk1{XK@{ zt$~dYI9L(ZmX1jA7O>lDwVa83K41Icj?|yzeErWKZg#aWodDm43)v-I-|`jG{tH79 zkiQ8`Gej0I2hiYUg$wX`OJGpq^*!M&TDbFms-YubF0!Mu;hBEmzH2~lSUZLR-#(U zKrUr-rv^F=MRg1W03I{gDO|DutL~4Pfx~V%6gs~W+v(z1bF7d4uH8fnUvsz9Y~rNO z!#@Z3-<1-=4WX_T_T;_Jg+Ju|$36i2MbRDk#5pH zi;aOsh&d3Qxh%^rMiCyM`RE5A3zWk0BQl-@=ov@v=z-bT53%Edi)$p?ca$uecCamX zul9NB&3f`y3GSiTG{&66@WN*%)Pe{+agnAHwagKJnSm|2{R&Kp@ZA<(vt|)n zgK-<1td3-(FLAgA_wJMt1ptgCVztQodLLFixXraQ5z7o# z941M&KYql=*LFm~Rvjh>ARixz`Kz&WKY9x1#1Mttrm6qQs&YwU;0s z^L#|OBU*+fIl^~%U^!iXtaWLj)9MI}zz&Vbo6LruJegPOrnd6yx8n#j)KX|1 z5$!*0WWM!XB6z;(IzL=wv1bq)%b&=-QZhY@SLdLG;i!TK7)C-D2hQIEoxfi$KrW>NI7nY{%iMF}#(t_MTwGK_UWju* z^)E7$0Rr7li{#;|8VG?(SkHTZy6^0dM_ASA$C>5`)d6yq7|Nj?66f)Ef!ItzM3zB4Q%=gara{7ph=WBbYz!SYRcv^>@Q3X*^C1Vn6jZ^pIs zRf{eg{*Cc0np1W##1)@X_F0vmL zaGm*!VZY7+XL3O7-77qNR$&0&B*$rs0v1qIR##UaWM#hF(T+&!*&ysf6O#h*{1W!)BKMBG|j+2SQR&ri7u9F2zKVBJASC7D=ca!Ga z`7N_r%*F`({Hkn3=n2Elanv;Q%t|)I{d7zf-4ZlsbfMr!qB?Ma4ncX#x%Ul}wfxX4 zM2Zy#lGm{y1l7TuQ5+WlYY3ucza;H`tJYm z5Q2o_zZf)?kG2?I;yMFF_ByLsVg~8MVZ?MXQ%&H@Jbrh zE7OpYtgj})?LG}to@#f7ApxU9=fDgdjRQb$6HM#mB znAJi_WBob+HH@$}w}zFj0QciSA(0Z3l-bUSl!<NwW7R7wdDP_Ea-$$u zFY~R!^#-=}29Jsm2zL!Yz0-#Ebvc^Wc z6+6@R5`~95*@;dw2nsk~mceE8??q8@@oejnYeOVOVlt)tmQ0NnWP|`siv0t-oEwDmab8hNi3~SRy}+^DXFW?j}OR^kgm* z>jPF$wU(pZ8M|p4CZ8GfIMdUpXFmV#Nk>bTRsZ9uWEac2rP8tuGj8r8aup%?MR7DZ z`$w+nDhBOCI%hMY^lc4lZAOTzE+#M-n+mDV5;RSJ0%YnAaZb{xcnx0SIShBF)?5oX z*BOp_%?I1Iv;!IdpkQ)+KHT_jBg_hD-KdZen?O5a0eF11utrL_Da_Z2Gl8LwcDlaF z#!5E80K;{4j;pn8br%j?&$E^qi*xL8POZQ7G~icam1e$WbK=s-vm-9NIinwLT{Z2p z;X3g^{f~``(xGI!ulhR!&Ygf03E;ATF%|k%nZ+aCXITybD@SY^ikMO<_SbunL=nWB zvw-+(47$OqXb*neO>lv}>qK!y6(>RQ<3U8n#tK&UzUD;T(a(#BDGFVMIdf^8at-{Z z{Vd<0*@DOhWHDOMQqx052}Aw{SLjQ9es98MB~P@T?DiTdTG5)`6W<>IR=rV(p0>~jWgJ_8;^w3HNGFK~HGajvo5-Pxc!MyK`*EXotg4*Gv{-gWnDHR|CpScCi1XQNF^keJDZEdX_> z3_u zTa!L1BK9zgOP>^L&^m_W|LXjY=j#Q2hzH7;dC z^uDaLu=MjbL_E%$RJGgU(W3o|!2`Isq|3st3)lJa308NL?1H1}_(@J|2dA&p6RRZ* zOt&iq!ZSg2h{umI>*+lo35}e8FuJ=;0MbP)m`lb7P8scmwX?j<>#~|3jk@!fQuWH0 zhNFDmesY{FRnIVfXLA607RwHg{`mF%h==(zMREJqhl|2a=66qJLzei!bpbd$NHqIK zp_9EP6ugLPNnI|#R=o<+0(;xffSsa6*m{Vd3coCHN%p{&&$wiYU519L#FDp==9L3$ z;xVD?0=7VhRn7$=0hut6dh01a-C=UQ_ItxnHfqJf@Ucgdkez&lVv&Cd!0kGIZrCSf zjzTPvx%pjNib>I2vYOXIXJDjY#ws8AJZNk(p~XxYOzQ@zXMf~2vE+u_gR17-v)MvV^ulMz$b~bNz?}Hh>UO4fTpn#@(42pa$~&yk8+eGB{6xy515sp=mKO10p?&Z7y)Y*?O+-4yK}b>Kgw z>Z*=TfrzgV&^mic_OrjXzLpQUw86QK+gm)m2OVmT{6zS5Unsaw+qto}6XR_&s!6DS z%Rt`k$QLLdObIopPsZu4lg%CX%3GuDXIp>yUS^3`_Po2;MV}t-k{cOuE=Y?m^tJ1H z%0eK6L&WSzLh7%dK6-5>?x~jRtM4HJ`o!!s(n;~^q`Mqw$QU&x=14>+6_UV=_ygE~ zGTfq5?y>&_i)*F-`-QxoQZz(7Y1_sMz;x?-`)?OX1U(&)7DU^o7DVK~;A*Pf47s-W zNn$|w;Ilu-Iv@K)7rDuOz;8yoIHtknl>lV}u)fEIA}~>T1NNZ5Ndd(iPSnMl8eE{h zs!o7&B5x2O7B(CuYcmeS(tUjk7kW^1Wu-?7H@Ywb^Y}E1jwBo2!mlHmzAZ+>KJFOE zArtt|oLil0UC!*#9qF>8|M%0oaGs7VA32RoZp*r`ARXR)k8}#|)SG8&>wTfns|NC( z5k#YuWQ}uXnoh73Cv|mYvZW&X)(f^&xgg%FdQo1~#uV`Wb^l-QFU|4+Htk}!5Fwf1 z`zw0(`M20kos4kM@cOaf-}xwma5X*Hzab$&0G+5ki$FmO!~-r)?@ry4w_&KsVNByB z`T`||?y#B>^eLsCv<*zI6i_)sKX>Cyt9FvQiBkzx>W_$Zr74v;16c0Y*T|_6J4I?M-z^CFZ~|P+kJrUd$U%SK=Aj?P-qEU3&-7>X>?oCg)2-L?E;5VSQ4i* zHFQY?RE%4}vsCY`wQvksGTE#T)|ng^w=o)otUIqtUpcbv(j;Z>919Db(o1CzB2Kc; zoC&;~q$;A~uSo7bNOrq%gOb>QWE=Sdjt9@A?bQP44qFpFq9fhq8=gOu+Y;i+_QLnH zbK#<(Rj~fV5N`y#p~QTlCeGGA(!dvs&u*iJcG?y&2hLKgx5gB`5u>n_3WGwVz?QpUlSO zhLmEAv_BP-xps=6!$+n34VTbD^|dv?yZm4K-73@>sF#ds|8R>1gE_r+Qpr{KGqEx4 zQt>m=yECQq)JicPaz!s1V=LRlJ!=*paHc5M9)iUxm zoX5Z{`%^4aK!@js)n`9=segz_nH4|$^JC$G*DnnE7wn&)|Jlo7u{?Lz-P=15sMOLC z7o2793#Vk>`m)0wlpt$lAp6yF=c)m%@~Nh8+X$Zl!$lSy6C-706o2QAu%V2UlppM@ z?_hKUN<<~#N{=|V{*JR(Z$j(Q64J_!uYj@cselOh`mELT(`IG|OY4vOBXuJ#T(cT$ zJ-@Tj%~3W*`|Y-SGSyt2E@J~hthc^%HnP5Tc8n9TGb{9L{AabWyMT3k>0aZzk={>( ze(86ov|EDg*YlOKhYrOF+)*t2$#_6Wg&Hi=)p58*!N{AzpfSk8aoSb>EcNE&lhJ|9 z`Ufgu!jZy1VTjOZ^)a9+#{kFUdnND~)Qb(MDQvX%UM@z@wGXvxYSELz9vx1)a zJfy-K1f?&)x0OHxIePM>5~pf1cL1lde{b(iwLIG-1eV!eTJBkc=A-1_X2cz7cj2pZ zOEl!j6;Oe_K5te3wC=2({6eQ~=)7o>hjy-Vg40fqjk)XYq36CYJ4{$O+N!@2>#=^3 z;o#6U+!&)7#H*^=I=n~ZWn;Qw=!G})qcT5fxjYK}ioBm~^wYRI&dSXyx5>XgYShdf znhJY&Lj$*OK6NA|5$xv0h|zDcYf8~bX3XqRoeU5^j|vNe1kx}IX!(bC9ag8B0rVsw zIC$UP)(>xh(~ui^i`?n8g(F7Hn(!4wnRPIUiQH|edQbIl-)^6)_f*Va=x;sG$-}Fa zs{~z*3rbtQnP_n(kwa>nw)Lw##`E_TM_N)Q``bKEua@#?^iR=_sDNP~G%-ecz<@Dm?%B5nyRsE(o#Kn$hv_p141Clf6#+?sF!EL^+vTZkF`-koK*K zV*4+po-x+xw`~td30q&GF8nRQJK1{p?$bRox3Br@v$7B6{g}!$jrp|t`*aG88DD$d z&H|i4+yR5|927VI%OK!HpFjT>R1+T|r6dn&fM|oC9~5jj?Ek2P@pA<;!H>9bM$$*b zMn|`f7lHt3L#*5ZL5p6uuf`w<@B&mxm*eO~EIzWWthTg*?jb8y@z zX&EtDgq0C#po7|0=$scO?5IMteS3^_0H-DB8pv#{uf@QQ z_}yPvIwy`x@7OdX@GDa%wiSH2CM)|~D_i*d`OekFybG3D08P-}=TC^>Pt)4+S;IIZ zH=M)665_Mhy@9N5D*rm`{lkd$smp@Gj+uh8+Xoo9>$<2_l3xli3Q2#{*+{u}zk)I+ z`|gY3K%q{T+qDM;VQ;`-Mgx!fl`jexjy3t)W*8e%Bujn`J7!>>Tj|g_-J<; z3g`44K9LqrtrOuB6|(sT2XnyOW*{iG1}BM&i&sK99t|{MTMb4LmwYrMRVY#Hg1b|g z&*XPfhul8fy<;b0rTzAn9~67?z8>pdMF@~s+=i%ZMXlN`;TAF2&_R^%}rJ=S()h3S6rvU))I zp%+G%pAH&F9==cUC3NkhDHp|HUDj~uy@kZF-yJ=PJ;td9p2UxyoNIddY4g#FT}eo@ zRwi={hX`*+%G|phUfH?#Xc`IOOZZS;fdB_<@UDR7qpTamF`X=pmaHBZF33&ipUtO{ z68cyL&V4G&~<5FJIh*mJn^^Nfp4+V1j(a^BJntyc4jN2=aH$zRMEaZfx(Sk`F z^ctv_R7uar8Y)P6dYxLceA+=%xUTN)#b~Te9JJwYW*F2_@p$FL#XrZm<2{MyH( zYjZD#FK2h@xzyYs{qrU+M_`qdx%{aE;so#V&o-UC%$*aSh5^Ed@p(@6b!H(U4bWI% zhw0V~wI?o<&}W{|WUxAd|0~SBc0?d-<_o%39pfvH>9u{2U5~y0{He;#7U{9T*ns-W zqumq zXw`1yPfpAZh8)}eJF zinOg!{P1;bK7L)notU`QJLDB-xrCR0iOp!uqD^O6b)eKuZ%?9=M^kRun{IpaW^mrO zJ;SuDGXMTnZ?8iS16ylR2NR&o&4H9++iv*Y-QEz`h0$s$i}f_ z{QUkO??nxVs%C2yxtdi{3-aH4YvU6Wdg??#%VneQ{)uzeQe8zlD4}Rj2w&|9d-LX+ z`GSf2ou2M8*3kymHpijY%^3llI@+8fbH0yGnQ(+iN%?y`*%oc;0gy?ao?+rmnhZy{Hb;#`q zf}i%Ltf;8)jf{-s+WkFA;|ypJduc_$wya&dciWZ-?AyN8COnwYUcYLP%p3E*0Yh?~ z@!L%H7**!kR{ps4CGqe~exSaTZhYE7%Uf-jy#xVTz;@7V`XOhF?wm9Y~9Skh3u7p0V;m+eQyb8)nlIM3z zaAiekeZ1oDvMkl$%|u`CX_BCP;?1mw^K!8CMEmYNjGXkYze~@j%#S2odt*20wD?vp zTqE@o@A`5=^r3S{)mbkvpS|&*Dkumg9H2ZMSTWJX8tLX~k8VmjIb8*KZ`QS%{f#2o zM#}ElpmA(bCwwi}KxULdfQDwE|KnZ%xzUu^+`K142^XdxiP?@zXLtQ{8M#6E=iLig z!GmYjvghF(0`^0RpnGA+9yZQ`ch7q@dTStN&i%SNI(_TbEw+B`xNEGt{{8o4kBH64 zOIVQ5W#$c|af+Zjcw;O_kP_KIaSoA#p?6c0(kw*q)C+Z^qaL(e(zTKo?dB{ds`fLY zzY}?!=;EteCK;%5N60oTPiaSv|WP zhR5cUKM^YSSKy(A$4)Q|bS4Czv+AN;DeUa*9Tbi*C=_Be(O$T=pfTKCkf#*^V^gXy zDIq1v=RS=!d5^=s;o-c%Ax*PCdi3aCz32_bw{|lXjQ3l}BS0%zuTbGK`gK$PZgVb@ zmzDjfCJSme`oJ3rPc3FiW)V7ac|Cuat#WyE<0?bSjl*y3iI+Uja(Cg4B!Uv2kLI19 z9034;l(z_7yOtAmh4{Zm?7?C&-6!6bXO{xyUqJydTbm~pf{$MWIRN99N#HaGAzgO^ z>1FKsoW0V!H2o7+=23-8s;C4$lqi}xjxv9UMMOZ&ypkVO#*Y80em>K4r7zdUpY8zH57Q3muR%JscBZ?yRI5_?^=d{h25?GUrx@Nz ze7{B;7y2Q8k%wzE(PU`0^=^qqK7uPJLt62J;4WMaN7A~~y%sXeYJr^)9y@fo$Dtk# z1nN;ktd51n2Y@nuKc>MR<$3X&plLY+5<39=JTECPr#DiAyXU{+*Mr%%ZJVzBortiy zl#?MlIzvz1)qOCrOuA(ydBy-#eoA{S`ClOP~18FXG+d}yLKkJ9madY z9&~gEhWxbtI=TpSbd5B1nS`Sw#H55vq($Tct}XdppHyr!Tt31LopG% z7_3`ddG@TGONpfyIc3(_`lwULcI=K->dPa|pZ8(EbS4p?xqi^8>-07N2W45#Xm@{y zs!HHNhLcx#*A_x;gsB+MT?z4KWPNXGP?_tb#=9~7^yvE3Lw&>BuP)q@dv)dEV{+Ex zC!0~+9K!72J}6f%Rm6GywD561~Tpj3f7 zrR4zSwWlJXrWxQitdP^MpzEs18TrFnCQ@tTtMg%hUN%GDF6!HM11vnZ>Ow!D9iv3MhdaHc40AYNAtuV7C|Sq}w)KAbdWzha|QWoyYFpy=xnlY0`G> zl9iIAW`RQn(2u?(_keB+3#|CHn2O(rFr+DS4D^E3FOLIKllJMGTV4!j-g>BNukg?| z7%}k&p{Fa5|FLp&*W_o79vQN#ZefrWv6~394-;|iUhbTkAE*u@KhGcNn-`PjII(>$ znVF$59|+-O2R(OVkMc1+DtNGn-f<|v)If&#$4<+ub)FiT6_1q@`e$li`@76U>%WV> za`S#Rv2q;Ck0f;|{VcOd*?%Y!aK!Yslg`(JP zi;y^+=gO577gtNj34$a)TIT0{?4wZKZT}cI2BW!UZ(%ZF1{fhfAL1Xp_cDs*zx2~+ z@sEuTLj(?U-LAHc9~aBrM1PQg7!|v_ySweqlP0Z-RY82_v(6Nm#>K*RGSbr2m)swp zfpVCX**B;ddS`O)odIn+&1Yy}ptgN{`Mh1@$S7=B%G}X@swO$0QL7C&Pe*dsLDg#D zfNhJ%R4y+?u5quhq384GAD?uddif_Nz-Sn>+4w*kGUw|*%Y~t@UKw>iy!+>Kqq|dx z0@j(@BY9hL#(%bnpn&y`J=~O#f9~b*4Gd%xvYYrgN>5GA0wpi3vx8xV+Yf>SHNdM6 z0B4D$RvcSeV)9Amgq3e)Ra7rFNkObGrd+aLbeq+((+PuEX6nyCE9N|m~~;BG|$;J@7;#G9X?Cwu9pV%jn?p3?!j z2s2Q7vda@s+4f(_f!S_qr8xgbO^L@aw{G1wwTYE`am}FGq2`?0W-SW=EekzNaQqnwY{pM z4@Vh{HlS~6`nj9IsD*4OCn3yO*;eMUZBp|@lH8){t{kSb7R9#@{C?b-k~7FaW0`XO zop+X5s0}g;Ui!0^{m+^bRO`&TVeGaNvM{Z}@O-u!@Zq`+^Zw7%4NbLon|G)%)I>~D z8S7KwjLz*HIYg(q6D7-APQ)TpH1iqpSx4$JyFfTC!%6{O{KauQLw;wz6SfF;n7)BA zhHFJG&Uur@l!b5?ZF|rPG6Nt?b<2KgN6{{5mq}NyGO!|!I1K$O)9C4S@>}wc$*`nr zG18VmQIG+}+M{DBMwz@C?_aRDLnd?TSMo~M$NWnZZ{ECVfK_fZmVCaX$p#Lpf|y+eoZpxh5eW+-%+ zd*@$f$l(EG6LGH4JbljzF@O)?o(Qm{?g@K2NO304f9|yEbQ6_&){oD=1xW z>7gP=G?fIZb5Mx@3;Qm=CW0V-k=ECb)^SX=hu_L9f`K_LWo`Qb z+Pt87t2p3|nmv|j|8UX!{Ot2ChIm-!qXetMvXZ?j@n>L84W3%g&@+Qj5uq0XLS5GE zku9eJ@?Ow>se*%M6%y)rBL3wegiflYm!Ybo^-)iudDA`^lUL4U?))IW50nQ zF)X(~3WaEzAGk@V(G$5!FWyy1b@6x z65&>?Lj;&+!29_RplKT4nvUVwIRJP9 zg$uud{lRoka#jb3O5MbErGpT!L%1e6SDcB3COEcXyQ!CF#M^&Z;0 zSAQ*6r^v+;IF+={7T)NrofIP>Oj=I$UJQK=aanGzXuRwD?)9Hcmi8;Qp~KrBJcusM zG@VeVp2c5fZ7z5ZV+BTX{3XFgOfk6I*YOtwP8#mEpB_{5S9)dH26D3a8-70>U6c!siCD-5ehBvc zR<*$s^lXs+LwHADA5kC`AZ`JaFe!JUKiN`b51BzW`VwZC`misSfdrz&6FfB3CvL95 z2w^lVQe+h%qo4=?5_71pL#;hE4bAvO*)4mmFJsVXx)v+DpT;EXWWfhmcO|2Jz@o(& z2xY1u;cVP>{f{$f%8w+^lD58db{{<16cGj{e?k_k!{kI1=B${99AgtQEtene>7R3) zY?GrurT64z!SCCuJP+;hc})Zrc;^%E{Jpl^9XB@-RGpWn*M{T0IPt+_-!=iuE?)-k zfA{RM>sNY?K&ATu#jwj%9~@QlsiEDO3ZQLMvQlp}&S26)Hjtxn`*!S|Vy&UCZE(T# z_4UKc?|ff;^oY2gJS;y4asXK<8g;uaO}MRq9d18X}0i{BgKf2U=S<{uQYqU zwz4P#aE#1J+k3k&oWK7;vopVK;u{_0+oFde?v;i-)Wg4!D+)IXhM@&`8wF3}R)>J; zoa+0w|{+s(ZfrR&n98!o2beUCvqh1GyhKq2`aN z4K=5;IlGMa7^Kfgp+xwX@cihX_<#{IQOfQUL-=d=AGtl@vdV%mS`A3od0l62RIOTM z6a#l<0Me9?@(Ie{tag+_p~C5KOHoP#Y)ej2tLG`SMtP4&JU@Q<^qp^_yAPhd$*7%> zHQIIZZwTm1(CY6?+E|V*pb*RX^=R(K{LvI@j zNK%^%5*ksLqj{cR5FC9kF9zI+6eLw+v7q<;hj=uc)(2x;eKXmiQm>_698Ghy3rc=m ziGMvEWS3lq{?32dr4F*o>c-kwPtHiS9V<2JS0&$wpiqMRMx-bJUz#@Gm2HLcHd{#- zvh^|%z@@3yi(CxEFg2mOv~$1>7;SOgSm}v@S!34QO`>@_I!^T_^YHS@8?_|!sHv$9 z8m~E*pK8(63pf70gc`;z5O($A3yd36=JyG!bikxEfYgWh>ukQNPYVyV%jDlVL*bkE zAWtQ!g>0ey4GM-vv4x?u zYRD14&eCh&zX&4|y70>PDdIMvEsAw;4=cyv&=(t-dw%7=w<|oa$SieShIIDZVA3#wloKKCbbk$M)b( z{6EgVJDltHeLJF(QjwGf3N52D8Y&t>5|NSFG%_=@X=@;b>=Mcz*}I8svS&p$mA#+y zR_OD4e$PM8_c*>C9ev*F{d(Q^eO=dmUgvpUY;QG-U~}X?#$wkVXSQqA+ym(nu%hQ- z9Lv8M{^w34cssMy8m`&TIf&3vELRN)3Gv>M`B5K6%po)~KMa_AH(>DQwY#nR@YC5{ zR0ES|c{}%G>ifC0JJbnR(}Ejd!4q;ad5emSjO*FgGDik9^kIJF3dVKyL0I-@Za8?o z--)JUXq&yme$VCBLFjExgyTDaf34NXSwoKMaPJ|RDz?UwzOIqrMt z(D%86dzfTWEotuc^T;4xpglnmS7>=1nvZ5J97ZVLogO^ktFQ`}57(r0@z{}gn=yag z!vf0!0P|WqmXwosZ@)?@QO~R0IzTYeHR^(eWLIrMI0)1qzpfthk94mav{kM9_<*T! zJVimRD$%SfV8@d){|rKNqGwUgyd_tPm!IOtRT|IiPlwC^(pW1Z`-t@+pF_=CEta~ zo0s#SOOZW#waR>G;GxUx9v+FnUJp2wpttOAcAW_V6XXUY?0aQsrpBGgvp}5?)}%^G z%WmAf8H|`M3pVM|n>tD+I9ukED>kC*L*quy(8$efu);6H^0hMZ>c@VtyZRFpvU_UY zyeeNCKXx62xJV|5>zXvC`U9q)jbfm~cASfZqDaOXZl>Kpj!wpVrzgT`*z113$NgSr zx2n5C!wDfwW;)po#&$=K9*uDCL&sga;J(!h&**ir*sDKT0KOxtwEVJgr9_4c0P!OdGTs<%ZCl^k1<2PSU;>?a1?NXk7} zRgz?PqW!QM&UBrSy{t`!+3tnOiVjy8RvIWPcPz& z`H_l&4})E;?Iy)Fg&LD7Z9%_SykSSOyCN+y+rtdnt8W%BPiR|q z8=gGVPa(AV96DZZWKJ+;;1;QO0IGjRk}9ZzuIMr9jY`es%IDPkzFZjHa1TUM()Bs4 z9J!Z`?X7Z6edq&=@69;>FSQ4)^sO8n7S$)*zI)fFv*)TfIifad%`igYXS&d80E2W- za4&>x$8$97)rxpkH21p9U}^kwAFOjrADKz{j+)vt}XgqLCrlB`#sS$oNmM1zK_wug4_ zJ_E*MiS zge;=S+`iKR_DvbXC$C1ONl+_B^C;SmN0zriC-C>-va1MhX>6UQ{oma6XW`39ydN8g z+dum`AT~2MM|llf?P@g@FzoN24OMU{7qRKB%(S(xNz`9IM81MFt@b_qU`M4<{GvKO zKE6W#L7ugi^6$*n+`Ch|^X%*Ml(n_-%4v(@6A0N0c(r~=<@q!$qs|h$_L3JrQlh3Y zt35Da)l><8brgk#zA}XdFMW(E>+`lgP-ll0FCwwWj?1XMgsqfT&Ljy2ez~Cj^`7;T ztV_&$apY$AkJn=(-(?5$w)!2|dvh+7Pq8ADvlQ*I{!fcFfFRayUU@v4Z?UdED)Qdz z*RNm3U^45#2*>}z;KZHMOAz;K4*zbN8roaB! z|4dcaRT17+)`M2Si2(yKUWr3o!X_j!d-w7)buktpimGPg{D4AE4nRCc&z0g3~2FZ!7o+FPXj(ey{27Uz$D-9rKuY8an3tJo)` zzU!6dW@9^|S?td}7A+Xr7{#jVhqvmhM6y>A^U^9#LCk&rVj7wv;w zmy2+dO}1*8lE-{Ri8JWOrIJ_>!Kzg;1UrFzM3rt2cb(T6V6bueM)m+XEQ3R6|G^zQ zJ~OK#>b=sgu+&#hNCz3J(pFnZn2)cVyUU_2NI6A~J3jQ1lF~EFC=c|$fnfBiZkpkV zon|Z%vIgp0q3Mh~or^X68gEHDx05Rlp5JR1OtCNs1`7N1)fdg-5fcRL686&{n!5^< zfOU8)p1AGw_Vx4e+~{#OG?F}Mt!Fjpp}pq;@0w(7##5yKl&rvtYf^fS-$Bc=vqDv2 zJ!8>{z^ar{W%txlw?5qwO45HP#Zc_UCx&uBOH+~Ifh2A-mmxkeP-ZMA5w?h_y)5`agi2D8W*~em zKTl1L`w5PMUihS(#Rd=jrNB#eD8$ECkaywysb$Bb1r!Nd|A&zmK=>RcubwWSU(96j zW=y?U8Cm9^CKYg4%^yR}m?CfJ9F!M%nMvWFy07xK2o06p#4oXP>DOb|v2k-3qRg(0 zQWF9qY)^B7XY>VgZj{W68&7e9mkr?(_!(G0LB9mZI;dwNbic4p!Sdvidj99nZn!Bk zSPfT&5HvxTcFB@m@^uOK(-INPB!O5@xZkne;^5#y+rIH2rWEekYhSwD)vRB4JnA`9w|WyDW()eENi`mg6d#PW=*9Ymy8}gyjcfVSE_9vp z=X%_by5H)+r@33ggaU!0{H+A%uw8OaGf8A(D%xy~wfXy4+r*n865)T5zC%7tTw7cF zNCWNQ7)J7LhIAsSD}4HqZJ|Kb>Z{8Rke%Mh{u5;aIX8uF%24zo-2zma?pIJXjR z-3Oh^46~nGK&iMg+34#Hfrp_D@y3Q2mMk^0d)Ka*YIDd{J)$$mKKG8G6HSiT{X;y9 zNtE#47NcJ$NKlJ&-izMJ$;lP=1B+gF!1Q$v*SVdKJa;Ode)s-;p*R06jYwqy&}#TK zy2kBDksEQYd@NOg3kBEEvqQ-yY-8()f$_P>ckkX6^aBsS*BE>2?|R;%VSpi0ta)8o z@qJvgg-p}DoSf*(U*5g^BUMHGugc|a(Z}<%58{wT+E~K@3x?)PVSHJ2ZmejyG|Pi| zq;=b^Y?NpbFFyG;2)uq(QU9QBhM@FJtU`2oxo*s#n~>WqI;SZKM9v{C@v!ZfIG93* zu7)$`0@qI0E}1+jh4#I_pRaHCnJ$ari-$4wuS@g-4qoMs5oUv`;?tyI(kw|i%WN=^ z{EKTIFb!|Z8ae8m_4|IqGl3jucd+yJner@}-<@jMomtaVG4}I^3-^?(s1Vd`$CM7v zRR|&!l+4-n3A&zY(Iq7%^mpaaCE#YZ%B#6?;|4@Me*J`LIr7xuPOU(F6!*@Z`Dc$+ zDI{E#w}drkXo>aJ!h^-)9^SG?!Oft^F z(;_#EnkE@PmD675V){k+GgSVE5_BrAWjr|nu(yz&Z_l2BjfVy(w|QqcD8$*rbnBG7 zwZ1Zq@UC4Ys=Ic<&z8PnkctRlvdgJRdznn>RjC9z!%jM|-#vWXIjmF7-5>I4>3v#e zSaFh>OSL`OaxKklgb>M|VYmFFmcxJfd6BG@&2Oaxb87{qAz;5NAbPradFhl(FSJrN zQwuNk2$Bb&LQhYxcSpM{$O&weB=+~l1h8qoM#;c=Dn`BFCDIo{i73lqo8+9uehJ2D zjq=Bu#uGZUZrmT z{0++w4ya~MGT4tCai(K27`7U03-J8BaPa}XP5($-MgmZI+R@KnvB>ZK7vxm+jL6Q{ zEZ|^ANh5l2?AQ@@+=}^rJQartUC`TSgr9Q!lF2UeI1-d&hYwu)cKi){hElFE)e0wF8@ZGG05*M1%X;xF#0fj!vnANSYIR9J6Xc z7nk*0+p@+!8>F9*^bl8i!b#_IcLqEAb6}=WaQOvL{d;;uvL7IiS^vtr)G-?~up;rB z^&K?U_drk?|IVnlGTqVyDc96V@7wq9qQ`!xs6g1?8h-HTP7d#fGZMhPOX1RR!h=`C zK!MO^z()FEnPoQ_gl}b_x=v0=g-ijB(<FtG2%VsEsIBiQ>K$$Npo+Fu&KVohE zNIH5WEwQ8?{*$cGvFA}w--h`Z3D$>DA;KqD`C0{Y z>&~6po?#Twp17dy`@m)Z4Tna0wL!!p7F+hOJ+=EU(=D3gwXKZ7?W9Qh-){B)z6J-W z_w3no8Hu8@^PR`(BS(&urJCu|ELpNGwjSNbVDwGQzhfNN5sXk&`}S)cS-GE7jyNUf zz+=|-2>dE+YhO|MN}8pkI`-vOuEzrV&JjBfvU9Nlw{(=j!+Bdk-Ew!CS1(P=J$PsC>A`u`igy!eEIavgcFT%4XDDv+LYT z?D{>r>r=|Pws3HW#>K@Im_+_ihu4G!ugjO@kCKop_8*l0 z{|>qPPP3{UKdD|&cdhF}5Iv1{#n8ZjY1(e!lUHt7I&06R<=4{_ZNg7vwAaf|K4LiWyAMkQ5|={%i($x7t^lF zLNnS6oMcIyD3>$yyJE}L6qIDy+mC`*B6+YY)S}6q&*Vq-BL=*wr#)XnKYZt#dHFNH zh&19nkLJxMLGrtFk};VA4tmUI%=24aU0qoh(`|?uw*$ch_Ags84y5=J7F|2QB!IuwUXu9HU>k zk`-4)!JXPQalwP%7BlfW&2;td5-WnUq{AKUalpvvu=J_W#&s-BcGZUL^O^-tn12>t$_w>B}qMJ~)}bM|;M?7=0F@ ztIVIsNv!9D#{&H*#v>L?FzZ!9&Oi`oaLTXMr9P`3q=aRnfBbY3<}K!zX7uC&b~a9*ew?3=s5@~i z+P2Q0otfkMe`j`wM-B>%ji|!>PKt})gQM2x7s@k`u-BfC2B&r;2|e|K3K6J9U)FTy z1W1LN)HBbj&{HX-STZ3gvXiOnqe|@npTM?l=#|iJ++eA=dRq2M(oE7MZ9_7TR#38R z+8%|Gn3IR)(07;C78S#qM`wuith+YhZ;nM^oZ9Zny_sSv#mrpoGHMV}&hI4NlW+d# zmu!sAOtLOYInOb_HXIE5(CmST`ICVwj)%lxXN9ET^{AH`Horu@a7$@;HVfANty1gR zo?E;kG(oQee~$a{Cg}jnAL}f*a#~F~8(+SBS@<0-+h|LOn2yD#8lt-k=aL^kR)GWh zJ0ZpDXu@?YZejeN+L~PbFt@a|vvn5>*|bKExXH^Aeh;6)%|**2EF!n{-nx5t+2aS6 zXYCD#%B5w)R8zjuzcz|qF6;9Zx-6HT+N^< zv*8x6NuqYS2_#E-lE($ZCsUhmy+jFN5dIi(YFL`ImchQlrBR_wnL>T3DNuS0@tnH{visn*F{c_?cuk)h^4|XP=);xNnyQfkrPF7a$(>6@J zmfh=ewfCd{y;&_kR`U1iB>>)wqLdTDNHY$K zyG66ddPr}lS&DJ%abYnomzI{x`@u3Fd~v!K7FavU-u@D)Qsw?CFW98;FUs_L0i-*c z29Yho2KDQ)^b5Y63hAcO^Xx{U|+*&JRpBNo_h^t(l39k2zjJzB|=L^pzgu5aBX zuhpm$W?hENNuQ~PahP5)PAoG0K2hJ7znTgS{x_P&4uk6 znKu3bw|RtgPLXnMpSVch=@(4=MlA;y?#9eWqR>J-iW1hC;a(OO6FY;ot$EYMBZD# zIf-{dM6`Vr*gOE=^otfB02>8^Ss=RBDT+kKHk#u|wgfv{6Y@3_s=EFO^ynX>tz+4E zLozuKg?T_M?tEXKc&nQYSivht*Vhc zzHiXM@X9)~?`12KL6yv-VK|JxvkJ z)>g!%>kZLhjL5#xl%k=f-T8@s!ylRCT#?Yc42QZ%=E|wrP`-ddkycy&Bd)`r;g%=0 zB=~HoY{-pN1y$1%`MmW}70$M?VX=J6)-m9otk?|xyBiw*pSWb2m0$c2@@LKFR%aS>Mn)g_<~Bj_L1Za z?acqNvc4p8ho&!^uY8&p5w{Yb9q)06HLL9&yeJ8Bt=Obzp<40wrYOsNOO~Q)2^C0*T3u(yBp-q2U{Y5MVoO~iM$;`c z5!yS$5uV$z2rekphkZ@no}7=<>0;yo-`-qIuEC9ORw)paqJ_;>F*yVDkKZ7?j6Lc8;-yP0O`(mlm!&s@`K z%FGapcq~eS!AHjHkPt-nUGvzzdCL|KHntbJ$NZn|J5$7c?xKb2O=?q1b6!mq;x1#bv8(-$E{t&xx>ze=wk2KlXBY0Q$R}rqx zjF!2!fGRs37YgQ3D~4`Xw4JtnobzqI21HN2Wt~CNGOf@bo7S$~20U$tk%ym<#Ytsl z?+&I_t1cYvJ!{SD`sj}|Z1&wiqd**mod3y96G~V|Yk+bz4u8){?#_DkmnW86Vtb`q zstD?8#9q9;4Af=7!NDNS($!U=(z}c-Tn73)QG~w#WHu~TzY^N2q|2s5 z^%)0$5Ww~%`!3wtNu#`Qt+#wxpg&3c1Jy*#?YNjFzDr~D#oeH>pI>ipy6ZgqO&7o+ zF8N||#Fbol$By_Im6j_D&CCoF?VfHGzeZg zixFF(2&n}bjfZ;iwVsM{O{Y_a@P50=`{f+UTNckX-IlDD%D(W`{Ex&e9Q>_M(ZONEMx5-rCFBNCJ#WlhPv(< zcgwOQ;fbH`i36B*f2EQT{@(M47q8(~zP#lHlQ3L%!^8ttES{ROkZ8=P)AV(4U8xgm z`DUt^wrqY8c~%>VCm-VGmV!=FC#n1SbJiJQD-~6;k>sgaRra5ckGS9fPVcYkUOig^ z{bY0`NfADlrxF^#3n16B{3H*JWVMC6QaNW}`9ey#Kjgdb+=_Jl>xX_#gxbzBm|*7G zNbgMQ(z?H;78PGfD;EbNic$9amwCjs7T{{}hXByyWZUF{C*n3R&Y z5_h>`p4~*3T@1Z=E$5J#{1j~1yt<0yFc9dbIw*@^wnxB z_9T4&2KCNUemfpp!072v++3i_Zlc;iZ;zkvFr$lK!@ zi9()Bh$ZlEl%aJ6@~HXt+f7`5(I(8V?W$UvSQush=F$4#vo&%54QjY$hCSK|J+-Sv1%o&^=12^ad89o z7*fWcOnElS9jnEpRHyBUApu**5(JlfG{MC2qxu7dWQ|nQ(Acsa!zq2=F3==*HN7?2 zyIiJof|!rFM9Eff?{X^aC-P~V2x}gLBCtJBb7(lyHuQPtBp5KTNINKtMkkjv{rL_738lZ-+kBK>4gI6 zl?5a6qJAIh?l^TDGvFQhM3THa>9NV?*jX+>x;IC=L1S97J&I07S4iclMbf(F3Z5|t%m-pZRqtGagM z{3prp_5%O1=%+bvHTRkvH`8d#$Sl0iygBLCLV4Ag!-Cwt|cNZBQFuOaIOF|5bUpr*3iIlQF<+~;cx3as!txS zUT-VHnf^BL|Ll-`3fYlg%_D2^UbgF%pQN->k>EO$;a{*8n&Edh2$jQ<k){MBYMCHdk5iJW-3Aq^=1b-!Nw?nh z!7(ufQ%*7#iA;N>qrVC+VF6=RL;yz?EYuQQdSel^sC(sH#t|}FLBR_#1Wd=l!^2bj zoqz2Vrp)C+`LQ`RHn#Gxm7@aqA(0xoxedQ#R6n@8yK`WOD?f<1Y5w|s2C_&TO+;JL511k3V(iuq;#h|?d`~?nC=y4Co{{m&q)(i}jw*BboOEqG zZoKFlk#Yc`*s=Q27*fMoLA~nphxz!M{T0izZii3LaQ1)uPV%?dp~`v2nt9lix9BQ? zm^VN=eX9$%K>d)?Q5^H0i0$kCZZ#;~FGD~s*xx}NKW3*UlNO`-=tJg6pjr|$(8J)x zEL`nI>hnwlBR2r=AT{@ec2 zeVwt!ttb0q&iWMhH6!*)00)pdud%SMHvYgE%#&K6Wsli^N~0=^LpN5yHUR2e7?)TQ zZXsr-?Ho8@V*bUf(?Jfu2 zX0D66#U3$VQ7_ASb@%pduQugtc9`Bf+qku$A=px!d5^MB2LOj1(0^+=O5V5a;7Iw| zlVm>0%&Wrrf+scYgyVytxn5}VUCK=i21(UjyxjaPQ7$*^bRPHH;7aqk{y-$!uJp{z zop)ckaa+4Vgg((%rTy>w^d-`Pl+1_oiL%*;lKJumKFx;>Klp8waFc1O=T8H&nne#g zYhT|3W}mxj=-Zv|-E)P1zID*eJMWpel+I6`un7+Ns<%9-2{Hn6rY(iO`{gcPx+KMD zF{zkSw&Q1t3eIUT+CgQY;oh}wKg{KV3ePK4z$lc$M6&#-;n;9Dff#>`@2?6S{{ku$ z>=Psru^!kq5*0ZR4ZfVk)YK9vVlAVX7DJ5?T>agcm6UwjDaX{oLO$Tr+AexD&7zOT z$jQ1d`B<5BKw^hts-=m}NXIMcO_KjeQ`=~+t0o_6Q(&N{FW_b2N^;rBbyNLoRFZeO zMoGzkqrV1`N#$#KX8dz7CC{Tr|ND!abj|W;inU@2`DT@4GrNDA`1#)YlsG6N%B6ND z=~7$hTeU6aUi(8rA73{_+4@K%K%(DpMUX`O-<=wTE;<4DkAC03u%7v1)pvp=dS|id zKFYzuMLVrm7-4b^FPlZ_!zw zzithP?~*mkT^ZW>*5be~DwE2&@V-wa`{nx{kHRiqRqQUsq_*_1$&>r6R5H*45UO+e zHGi3$5++{N@)d_{uFD<0E5cf)(q3l0O6JI_BijST8IIq-ckjm8Rk03ABB7g?-n++d zNg=8((`~vYW4%>h1}D`><>6_IA3k}v3QoC6^cGAEDWCh)0=rquURSRajPk*07rDRG zwcbB)!gm8gAu=G8P`DAH^0r z4CvQghVv^+NYUEackAfD`13)Fxld-M*9_0`XfJLU!x`IBzomoeOJQC5Z0&zC@_7c< z6u+E*wZM(E+PBX~+N~FgPwhcdx7GIU1_F91oe~MJ=;UE!PBLr~)L=%k_CWGb(u>~= zl7Xl2^hCLiYN*^R4?y2%{cVTN}a>T zjct*J9|ZCyA#>$1YzI2ZYYC|8C}-+_yFn4#MU2w~qG?~w|M7^hBhZRxAJX9DAmJkz zc|{2n*o|7Zhsf;UbEOS?7HScX&!h=a?o$`x!3 z2zD>s39qQb1;}E&ty#IEL7`^KjL420;7OtSJpF(ae|Tx(+vv zHG`uXhfU9SPD*eYEiK=0i@uZD_RtvJDxU2si4plL$=>%~CP9isN7h}Y?J}t29(vvH zy&ox2ir?}}v?Nj)?JSgI_<~cTOCL?N2&HQU)@35@kuoJDP`*x}3_KUSXujz|&yuc} zdF^9^=&t0}Cg^_Okb22&e3HJw?8rIXNrR3%(GwX24SFQ@I(XrHn=t;HfnD*&1~@b6M;0S#0`c$cYfSA`<@+}8LDv%YHS6} zwFA{oGWqR?S6@q^Pt_GY!rzBsrO;c8*k>>%pbE;y1-jc^Z;5OJSbtR$kZUpf!>?ua6cvWQX=q=5WMnq{)-%W)R>J) z#kQapB~49MbqwpoU4FbLl|el0EX^j`8M^DAQj7hOhzLiL^~u1xUefOhwuI!=XE zt4qNf{}X>!1}w76u4s8A|sa z>4OwQKwd9eE$zpbv0zViH-uZOl7&*_5O&dOC-lL4!8@$Udjw4#DZX}my?h6Xg~ypT zaG14QPECy)V%F`{7G%Cyi|Doqj8YM`_;NaIpJ}@*(Y1vLseBs(PFwITcqD9)vtm>( zEMTy!Dj)78ml2%;i<7R2b|1IM2^$(aI05RobR-C2|73;f& zlyD?p7$8r^fVopeI8+#{niRY2d9#|tlhB~=Qk9qDfsREK9_(g)mYoz>hzh;hA;9x zWLpTSpz*{3WP9~hTR=tS_NDNLPp*-aS_p{?U z02;2`uX-j-{bDC$EHZQ>!=h;KDJSabNFSFjuvCmtVtc^EE2!39RG-+8;)8)HumF%c zRYh?vLZM?CjI7JpvvB}K--M_1`pU*@pCMBO(9hW2XvuRf?l?v)=+$aJPDTdHM<3yG z*ks*~?8Q{8pJ2JOn3Uk>i$%)0vMDtt9Csrg;jCST{=OqWk9h{P+4mjFD@{*nvfed& zTtrx9sBQ?RH2k8(-q>BFfB&M!<;aoVWYN&Z1u)85d|WYEuJDk|l*FzT|D>x4NgTWB zRP~2zX8)cgrW8`%ggl?mFJLLl@GWAs3x=vpfD(H87}Oq55pZ%&zQ4>xHd-Jx|J&k3 zBe4gT9j7ap(F3vYY4I(2f)sNO^NqFLI)K^j#LdPHE#Iy2LY_E+e@bBC;-}l6Ob#oD zR;e9%!@m9&i&;EDwANN9>idu|Wgr$syBSxw&N2gZm_wHQsZB*m^-fx$smt1MLY+-w z%U>v}Ki1W)OpfP8EkN&ft5{Cq*M$wUffsrY*ZSVC?&T*JjV)4FOvs^YI4Z3ep&OX? zy^vu=TF88$A}7xEJcU~w!>Js{*&hd|eFZ&^XeH8^H zm{=8^zTewHD3>u09XJJaZ=~I^t6YbIB{Nz!_&##^r><*_$=BY$EIzIXH#4-qJrHax zZJkHxN<`11rrs+Rzrbq^d--e7mQ4E^4@nd=KJ@Dt)JI39KEt|7XAGVAJ(>m2&a+=A zLc{2SBNL+abtq#x!zrm81PvZxU{N_vW(p>;s7Wq#@5QKzuL7 z_Qnq`dK9GqhmlK?ATR6u2l}O9Vof>p)qDeia{nNCuJM%KRIfxYUflW~{l(Ah9)LeM zb)=u=Hd+n$a(}R#PK%C!HxV30lVfJ3C+o*F9)UgNl~th}9}WSY8@Gy} z%OacRY>FrB0b8XvbwDO5mNOFgnCDbkkmw_jp6;#LT;2|&r>8t>wM?&;g&igZ@H*Te z@_o(DRDA=zAQ+h430dWavgzn$Xy2}Cw`X&8=L+-@0n=1 zc$up&MrGv~?I*A~jyHZm&CZ@=y(9rOYP5m2uDb(heco4l6R%Qi^1rV+`>8)4%^@E> zC39ic?6i?&71SK#Bi)S_(?vpkx$rk^Ha-ssu9f~*2JE58KUYNQ{WOYk zHvDcv1HPY8Lp9A@Dt=Ed7$V0l(kj=Yp@B+`v&PG8l{;rFjE1UguH?CWe0ap7aV<A?ARTA&6$5_Gga3;-yu1der6IJ^%;H`{kh}db7llyc8R@T^Bzr zu>>HLS~0wd{H&?YvcwNJsND{4e#i9wrS#lWIZ~0s!RFiex^(YPD-(4M zDr*M#t%P`|P5qDD>?Z5bG8FVBh^LB+8^w%5}wPnO-6(yndPwADtbXRkwSo9AGdm9n$iYRd`_|?g?GMg3obJIY^VEfZs`ATpsARW@l)aSDqsWk*&GzqBIZuIr z!ELl^?fk{s0e-deAXccc#|IjO$_8_7=g0KVQug%fSeV*uSBQAVkyG%T)GQyCkhx04 z$F2N!T4xW)%e(S^0yxd++Ya^*8?iGga7{m;5TFam!c}Rdc-zJ>`L}!ZYcGf0X2@Js za$93;orTSdw4{N~iu|4h@!#x8Z48~RCX*?7_u>y{pdG7-7So2B@34}uEB~G`oF1hkB2QS&hRdtZAlaD+*WZ8Peh<>VbDl5st7DFYDZoI3jgQd5 zS<+q0A|6x}bLqPUrVd|4-IJY}Bj0GPDPJnkR~4%YVCo^e zhV7ud@$#Gf^G^U3O9tbyK0IT|h~$w?H^3)$h-mMysa81)&M?LhTxyP^gl# zajV+~q|V&?3IO9Pm{mR$&`=#GN|!zo_~3XHW_(Ep9H!v;FfjKR(*)fRtC9*|+`cBl zyM2>}*}}*j&vzD=2T6Q?`M6}B&V*M?6^B>gXk+HJem2iEvrsB0sL^J9pvxHENKb#U zMxwhZOXEHhZ||N=^iCwPL%4+u7LnA;u5cbyJk729ChIZ)lc3R^+_C52K~-E;8MTI$ z<H;`F8w*M z&;m|f#?%Kekuz@+AuxpU#-(=J9&Bfh_uKYS&pswO3siyR;jhbk%?)5_7N&$0f?kT= z1;a;LTrp%tQo03nNjGGDPq2OjPZ9Q(q>JBMas_r;RSiQ$Os-ZL>TTEwj>b?iZ^Bh; zERkPW5*k(NP;_&WW}!;Oq1~76_f-Ri6^8?P&-Zx7<+Sj*LxjZehFb~LrWOvk!us6r zwJIFA)+Y6oTSWm9h>k+Gc+mxptgA{s#)EWp`b|$|q>l|?f}wyO{fd);7c;aZ*013V zo*vmE{`48=?4vc?lPvIE0I%Qq-0raOFE0ZF3%mv&UB9zz-M5Xm73_qe31}(utJC|H zv)ub~y0-5;#drb51H3?kU$h^7&h9721xzI$#HExTY~+yicnX!Avel4stWx;fPtL^r zl=IZH^Bu8##9)f`1!XF$#Pp|06g(JEYFYlMS6qK*Nvl#u22K#^k{}36ws*L-B!hIH zi$;|8SXr?IWRIT!hVR5M_mgfWB@(}B>Ql`m0bE>$fHPCUChd9MiQtM+v&YmVDC}FR zityG_^1&HR_s@jCY!@NX<6XZ==$*fe%JDpMhhrU`_FQNriGX6Kh_Q9Hx-#cneW|1_@*o-I!uu<}%B@MN zDaIZwS#-NF(O0udK1UmFv4mjC`>B|f;APU(XmH=?h^Lw50_-3)5R{x1>~C~$#3~pi zaU^uv54JG_rgX&>a|XB389uE0s^WUW)pUI}_n!VUQpUJ~q^#yuuh(h|`QEasI@K&3 z@BWjG8o3%hIqf4@XmfazM*F341Sl9RPp;N*eSFZ^7j|37-GngAvyzZF2Kt(sCMLR{ zZZ|&Qd^`O12^SB&ZWGF*RV+s>6dQ2)Dwj!+jm<3L#6EHqSyd8r zA+j=xrq}rzv4RD1I{G-$iX0VUTvY}u#XLYd_ZbSj1tdXwy!7d-Qi9sFLNUf%f6U2Q z;HDsAajW!x?^v*qkM8Q73a1WFPnaZawZc^G;}1S{d?&YbS>%fTR-WyR`Z=T_k-s!T zHANQjxNT1+@Tbr4a=L7nnRRS&$~xU624Vayb_k|slv~6Wv8?5r11KiMarJ(n!PQVE zpJe`Mqp}nyoOsu;9D4r`?GjVG5K(${FO1Fi$A2Dg#@E2$IMFA~Q8aE-^r(OtBfHzz zdhZMEXPenD^lQO0lUVJ%kqv$qVu_uVV<|yX+*R83$+2}o7d4n6*^oeCeL?s(_piei zz4d4rq+XYnGEU=-emFQ*d3y;irWWg}(XZYi{o!%-)r@t!Hlw1vmyLV8DASRTbQxMv zLN>kud}62V1|H}4^`p9KxwmEeVYW-nYq8f!Wr$yzmf*XuuVU|#R}2ck)P=LBVnos0 zIvB>a65=3Gt)=2(OXke_NEA_$#yja!V>mG<^JPU=L2PpaGMBb&B=_-_kdwS*M^W8( z;1TIWNT1}(LGM=rnW5DSbJr^Jkb|y>TDC~`6P?=neVLeP`D^_4KHp!0cV zBBY?-2U8ayKKzZlAJ_YD_T>6_x)x$bFq%yFPorhM6<48O&XRqR9VT}E2Q6jwCVWv@ z(sS+t7}NpZocy=2-+8)O^nUIOPYn;y*5_1u6_Lc+AK+e+qHdLhGmEggshG}k?&nu_rU%nxrRLvW z({!>Z*=95js>Lsd=~STq<pzW?%~Nq1=? z=<@@=0%>}|-St2|wmPfL)2datWTgn9#*=9xX(H_=;vVrjS1cySjCnafbqt^Ds`7mI z{gdO}xnqC+8i|s2ju%%HmtXDnUSbc~?)X>0wMh(Ldd}%8SvT*0kDvR%CSokK zg7%-srss)45xeh6wN{}w2T)w8>p3%61^dfvc=7}xLvHfB2DC{QuHBxAIW852nu8@bz2HZ@B1t$N{TB4^3<4aJmuABoEo9s$Ip4oA%M2snVo2iy>G8^ zNWb>|j;eCpap&dhzU_IRzHsr$)9P*GqwZQGf49WSWmwe3?edK&Ca>Dpk5s?dYj4^m zAZ1*P_v=vPuQT5sU|o5Te6%=0Gh}u z6di>}=y84dE0_5aKD{9&7X>h*$YbKuDg_Z0>V>jxzhu0^V^{ z{A9FOPXYRwtY5!=b>q`I9jo8kHpI$2moxD24#8-iBznN^c2M-A6^=#TrZTk|J>O9z69x@mA zGdhdK#NjW|u*tw17c6_AH?0X(>LwP+qlac5-RvdC)_Uj2nVOp3*!US(F5-Y-UhmjB zA%x((tpxDHrg)G~gON47$9x3c-^0=FcUnDIbl0n*^7e`s&ByV-=&DxFLS7i4)7KAX zHQve`soL9E^F}Mlu&=G~7s~ZNd4rsL#}-n3T4wB@yIZX+ptQ<5$M6;xq$^89wBKD| zJ&x|f71%tVmLn`tkTyA1hU9EOL|i}(mMj~Q9p)DtJ$m%=@0PqDeWn+`LGQ!)w!z~| z6iuHqO*ULq9)o_*{$us zV#x9Ab@eYP@uS8qIqUxF?QSIo`!JE{;A&E4)=03KxA&hfXV}{EEl`vvYp0+|$Yn0Y zqW63y^OmHn9MtFqN=#nfmz2p?^?5m{%1jx*T6EeAc{6@7Zra2%cIZ#l1pl7)AKyYJ zZ0R2oUEIB6NROM=%twPfj_2|=xb$8;{VMMcE?v8Z9}9df33!PJNt|Y1ZEvr~M4{&5 z@{8T*C^b_eoH0sun>++jQj!>SD8*iM@}EQz+)DVk!wf=iGk~0wK^$;AV5|9J(w*iy z7x!VJI`*nHSb>+}E4V4ZrN!JORJ)y(7#^L&?URgCu*t+5xoEucfT^q4CQJ4gYDTz! zC$A#@2l0kYjlmTV!t#s?kBJ-P)P7|@7Ah-i)2pgFzpE#X|mWSlnsz+NqQbY03c z3z0OZfnd*PuT`-Rqkgxt+3*i{0qbl@TB@70ismGNRA~+heGSm8(H=uk5B3dE6z+zW zm=H>NOv;bj^*&fUz9nFE%Xu|N&?NJq{M?N4XH|pOIi^meMt%v4ihF*|cH=|(rMxO< z!xg099OM@y4rJ{Ku?#t^FJCt}PC8v6q8&P{*o`-_B3=4D4*h-3MuxXrVo;09m8xao zn$$h`0hC@T;s=y**m)riGoK^du{*gyc-qVM{eBg|ezjc&ot)14bHCH4Qnmcb=P#11 zAIbjsCFwe`kTj-9km#!Tv2M?0*MpY7#esZ1u`lsmHGfzrsJA|Y2iN!Nhs28loE2dMLU)UTCRKXTyVEM*_Y zY>Zq;nvT=ve`HGSa+n$~c)Fb-5xl%Dj_BH`16*kPVh!4!-o{-by%Q5}^3P%JA_rq# zk|(O6G411~^N^(LQ)Ixc!65;I!F7xMg)EBLQ^mx@tof}Xo7G>-u({Nh5y{4Ey-8)m z3rM~nY{AF=hB<+3a z38O`ru_UbB`}HfQ8iKoA(Of0;RxMx!>ftf{Kd^4}Y8Yv@xAj(=FYKjgh@8HGqXw)}Q)sPGQC?Rr!8k*Br~A zwS@GuFYjo-8uy&r)Uy~x?a1U8!kzPOp%)^TChYye@zLFQ)$rp~JI)W;dcUO~&!)1h zBgl(M1%HrlYl)=`v%u#KVGlx3Bp7DeqXkK%mOoST@s5Dr zt&w^+%xU_#ym&f%3Nd!C@!N6*Cd>A$<&o`C!|kS36psiQ8>RoZ+a*hXV(?o`k`p+l zXhG&ONFV$ASl$*4*A_1F=hYXM;BJ;~6 zO>L+hCqPRDru>G!4?f z_rry5BIf~L5*9E~TGgHGCSn1?Pj8I?Dz=(?ANo$&lhpCrmsHa>K8#XPWd0ad8=sS40ASQvZjotB$KO>(+V%1uO&!F#stg z6+z-iNJxXUvGlgoI^8_YN}HQ zK&sipSmI{84=PJlTZnYqmu$Ts)goj)`^LnB`-{dK|1(SaKO8V9+}N+fP(%QTIIW~G z#Nq^)zi{sL38-&YGQ26D(7-t0l(0L0?}^cA>Znok{EoNA0U7++@drD_a9z-J;Cgs@ zt^%zCK>jhu6<6y4xJfQdEnJf98hNtjbc5WRoD9xNi6FyJIp_-Z&3!&;T@*9jEJYgz zE`6V{hdAU5fr`*9+gk9Du8!BL>Atr*K^o*Vz|rMMqu6UdHrUS3nj3#kTdkrYwAy&I z#Jm2*;B=9kEZjE=zU!drvXt2j+K}arZQd@%F7`b z0xYMmsL9sqm)O@a7TsOc)iLFDRk#O%&7q_mJclz zru~nDWF6c^ZgbHGCQm@U%MN#iU1WU4Gfw3siT6#>{{QLn{vYZJ(ed4zk|&nOtVJ5g z+@oHIW=Qu2gM=@psal&?I4aQK1LBdCVKio>G^aRO?BTKjP^ocfH}I{DMS_@%Cc-)1 z8r7Wz`+d^vPdOAer^RvZmFv^kd4}wSXih!Bc@J=Vki=1u)4<+Q3mynn?T7n4scsw) z1|I)um_dZ0uyO1Iz?*LXxpe5;wJb%@vwmhQZU=74ZPlHb{ljCDq=95dVYN*=I;^Y!;A;a=7f-IUPInOg%cnv7|W7I zkbs3MBW4}9|h6#P%R?;RYntE->p!sfIBOr#I_kv4ykv)$zVg zH0uJw+a&g?2m~P|5kDk83~xVcjm>$cdp|!A0swF4wgzlnEC;jy#2&pt}2YI){vlj!tuiyZQ9ywb> zm{W37g1j4$tBDZZz@1!A)BydKgCl2i?yZ&`e(l#bRBnpaX%5E4R_%kF3txOIt|G?U zZqf4|3xBzMK8g3w5ez504RIge7u@OrgFFCg$V%1r}P(pY$+$y{PaH>8QB$^OTac zf=_WLU8fH>i?#SBUB5U+K4b52tP`fBFwC*AF@H(Xy|^mNR??LO2Wt!XHax+ut?zq0 z`>({?+W-NIRN-}%`!o0g;6m$@M^g!X7y1e<7=g8xod+ihzOG|)X`Pih0?B{dNofIC zCDo?5OS@WeA9fUcp(=2r(w80qzb?a?tMzc*iwzg^ZX*q0W5~k0t2&sU;3#|^M4__Z zzQOr(oc4f@8d8ZsTNXnQ!U?s;om(<6T9?4tw*uX^zk;9C=Q$a8WP~>SdU;XuiS$SO z^>BL05NdjtEVWtF^tFvtndzv>Y3j8Z3GyCGWvG7VyT42;o_X`P1eSgc7cz0$fT$D3 zHM!pL5^F_)X0Co1I3~N1m%D%w6KAvfpsQ-gfA-HFpLGBzo09*U#?fUELbc1J{ZxVh zFs)(zYz-;nu*Gftk z$oh!nvntPy7b8FF(2R#hBPK14VscRqmZ=hwiOIS~{K50-O<^pMIHAqrP-ce{;7Q1R z4)%nAJFrTI6(F~^+~ymcdb()myopUw?*Xe6`luB}y8fe>wQgk?SG-Kj;WE(Y{@fYX zZ;_*`vQ|1%78N?pGY7s+kzAX-lu_N&Mbr{~3}%E*n}yiN91V`574{AXg6~I4k2s zQ4VIon=18{OUW-O6oSbz10^wzx-W?m?lJ6%8bG(d)VrrM_dbm zQ`dYL`0LLP19b{V5PSdr-(%z#kiTN3q@R$0_-`zzRX;JbcypdfRGVPan6|Q`fu+G+|PDe0PIP1r#Z@K=NKDznB z*K=9s#pnbGJ=exqnvJkdvmoWEgL-#HZL_WCqR(%)o~l(a6LOLz`{sg#tSB{#QVmw@ ztGvU?@1HF|dlrqjY$r;mMQA^Ax`+2RH05t^ecaznc&7J(Mp7Ig4XVF#_-a}yeFn)! zAulr!+7Hi?pM(cN&vzlbwU3%dnnZZxUXovG-IUkH>?5RH>kS#s;jdtE9R@G|fh zJo+Cyi6X%1nv%~-5+a9ylAbKS#H{N4OhTPxm*i_YyDQ=&ih!!?x$N`1JXV!!{g9Yx z3pi~!4m5o-FsM_#bG^>~d%M1y0*rk7Z7(a3W&vi+9pu{z;HC&kcZG)za_t1`Fx{As zi0M$awKfqd;^pZTqaPZih3kfZsqK20`^2t&lawgA`T-=oeBhZ#YYlD!cmoxbbLN&;N1$wpuuF(?Pp(n_f0}cWV zs%1xgaWLADo9Qh_O0+YJ3JiZ%hVChJ7e`aF#$MVrs}E>D`w4uUrOZQd@=Sn8GS}&e zsM&O{)!_`ykO1M|*HbhBPWUtDG(%l>-`DS?c!_fg+<~W~ULPAJlmgZ8Nf)rm)EyQ^ zlNdX>TT&5avyKX4hY3Xvth=Pn*7JgEZZ>Dkb{_zUk-TI?`!Hvc$9q9M^u&w*^mIq z=Z>PDkQ`+s5V;yIC~9Oe4+*c($vj#{N(@kIOnIcq;I5&DcY7NK-E|SV z=ME_5fvM$fNA_mIbD)02L6`N(rHr`=yj=ukM#N42tb%tNl-7l76eLNr)t^2^K;iV$ z%I)Gz-NK@RI4Z`0z8ZZ%DLD1;?z(}&At$_+l?GQo?+#XPNcF=2SJB_E;F%d=57-`Q znlS0w$pvj^$ zO3foB`PDjLz1$kT#!`E3U;V=cK(BPKV%D4GiT1CI`4eLN3UTe};J=oE$)y;8D#AmR zQN<7)iEyJb#*?4k9j0l(JKB?}$^5v+0XVkvcO(ic+m5Q15oeE+BDB@dZ}%{R5}O+B zTfeNvQ-9z|A7BuGen%JDk0GNdi}Wy}`}Ew#^^APhz4lS&AZ<2=v#9EV$1pGhmXG1} z9t-^_7dy!BvCu4q4(I06TnK)6Uyq66$vSAeaA|cU&aG+cI!sB}+H(z@%r!wFhJxI> z49&bnRfs@JEecmAv-X}hfDX(}g&W997g%h!FP6L6f{UK;l*TO)rY z(^$$eWGSLzRjXAqategnP8P80#t<B|E`!f1=@kX)Njc<`XDkdqmy136qI@)#`X@y75!hM`EqM& z@T9x9A|!^$phV27W$Y!T5w4W}j(lufeDZ*1oJ zff#YmqYN;4MP|haIxS28sUrj|FdF^FBfa+>ZK z3{t`@3^X8NXt*&9b{|f%o(6fQ&(I0Ep-A2j0mxH4r#!gsK-`((=R+<(A5xW_=A8Po z8}?SBUzLkX=l5Z4@-E&g6obmCZa4ihQN3I4`MG26HyRNK@!xVG9c`w}hA&3DUmj14 z9F$OA{P<0R(*IGxdw0EVrENE;}8 zP9R|GFrHxfrq<+uxONFbERRD50+$g`<2f0&fgGO#{p^1Xi1W-k+(k_aPk_~<(p~*8Gf7PYJ7AcOw_A_swa0Bf&ilr9i4aOC;8ot^t;%**QCwd8wgvRBj6qt zgJ`=WhOg_1d6ci=?%b|{do>l%NR1PBLPNx7@?Of$>5q}_-KL0u!wgL-j4{ae_sZ-i z@-6JeYY1~-ynYi#0dE0adnsnGZJ}tuP#gdbY7nm1af{3i)FB*zSMy-^9V2pP!-LZ~ zirPkwou>q?ejGbd(VwtdA?tx%r;^@bKAzT_Mjnf{;kMOel7kkA1>xd}7S2@5AX5uC-y_!AUx7jNH(-2d zu@>tEaC^c~Wa%OdklWO(3OPtQK~@5}^HF^vr?DESZ{>m6)LLZhEgrB88Vr37*NT@c z?7qesUKjm&qYgqg!0$PbnHgoc4EIgoB2u%054m?axixe{yfRk}J$L!<+8gI5m!rj`HKO zXn=*A8Ab*lc?tt(K2M#o_993*t8XYYF_)3wd*zoK|Ap7AMIz39PNohZ8K=|DG*Bor zB*ZtvSt8Us3*szYFqEEgY}7VWC-2G6#ClP6+Y%bzM|0VcJ{T0}z`AgKhW=Th%|Su1 zy@wcL*I4O+y(2g_unPF)@H%4s0>L3RC%$xW3Gp4hs0xZ~he)=s`OX>a!NEa5u>$q; z5VSuIACTN{)8k}VmrD#C=?%mp_`Y~(?FXU;LIJ@5ALtbQDu<8pC=}U^_7AhH?xzvY zR^?S&LDuM=-MbJY3R`PW(PQ~tYd`6$d&^&z0Co_5j9`8`LR&~JD^$?07b^@TcM|>c zif~xhar}mAu{K>fdGaNPZqe(E>#q)a5zP=FHzk<4*$#X@{BqyorD7Ne>Msa9f=TcD zGy-wZ86`!LLZk+V5{H@i(W6Ih?(B#6>7c$DRikpug;^T_zev`s)G~yi;1MQZ zG7bBV8g>@gRl&UGEEI0GCD*4zyZFGj#8KdNHT!$3ZAEhze7(h|6v%9k>OR17(j!=8`0}HyPrK^-y%Qv+VO4;Q6(72O z@G;!0H6{C&f7SxPbQU^bJAsdY0?6N@fKT<6x(R*(X@WOlfQIa~n6C!?))#fEh~O~` zZSaAoNTo0i@@l$!FiX~CD`Vk-j#9qOe6wZ7zn=nWVjAOwbSSq*L{!!jA07HsWGrR0 z;(LF1{p`;Z#+#36hM}Ekzx}ABh*e+!*7Nd+!>jI`VwQqxJ(M-bbN73rnKUd$zLG*j zp(Kb@y2L{21WcM9!mB^+FU@-Q=(A=fZFt5KQ*;S@{AR17;h1Zb5UtWdYK?Yjk$+rFXNhBqZkveR1 z$H*n9|A#VO#*th;G8`cKp4jy58j=XYpOoRNATxET_8 zqsIX$^kKUP)yF%zry6Q)xnN?)?EH4E@J3cKD7iG8+S^}A{3g1xfEPzpz*W2Ev*%T_ zUPKnPg?2f}LjiKBZZyg*Ng0Z)X34iSXmo;7gA}R0=-IBreKPcrO8-I)2z;`;6?bm2 z4KF~8TzKe6i_nWRoo{?+77bI?;LRCm5$n5wa*8_s1K`5c1DKs(Qg82aXT66Apl7sH z%DZ<;7rrVLK*bj)t!)pR!q`|PS6?W+wS0SPo!fpCKS;BG>ItE)~O7!aQ=F9~ksEL`A8nvLTX;v1HePq{2Iy{=>UyFfKw(ZJ>&`Xn>cJ%#%G80f6MoMimUwp+;HuoIn1Q=)^aE$j zz3^^fxYE}zA|3_hI|8E&|i|$o17ET1o>x>39!mU!$qoPvi0@Wr*#h(fQw#f}Z zY8~Zt_wV1ucvn(U+A0$mSs71iOSZoV{25LzH<++kVFLogUGrNQAET8dNpHUo1MQHlOQ+($I2k&LfAyU)3CD!9@2HK3tHfUM9B|8oQ$mj z(4CMz(U_0kNgoAF%TZW3)%18URJl}ig~&@{u163O=%c;-6&XPt!} zxSjoQL`VN!wZnUOAdTNmq9)@Qq>dnlR+py(FQOeW{X^@QOe)p6_#ax+3dpJ)4aQse z{#-t=;iCF8mIV!^fOM4tqbwh+%~2B#a7jnBL~}iuXQGz-kr1MiyrR1YLntJZlZgss z<4Jr4SEdHFxoGfDxO`D$BeVg*ts4u)!!YV5&$g07dz&>OSHY5^2OODLVNmCIa2^4k z6?Ygg2K`_W^8)aN20JF%+J#~}Cfq|@mujl4F&rPRrGC@bNsk?)N7D4|ZKzR^N!An< zN5$Y09BRm!O+km_eYyu^C2{@c;=hFGXl0~uoE&72I@@o8UXLGyhD8`R7$q9*+ury%~a- zy#S5tQA5-HNa?i*e?+AL(P++bI2$MxNCIMSO!4pKa9!vgT+02S>RX-4GCB8>ju66 zGHj?kw4bkYyqWKt`F`9K{`w~93bX@B2eq_8XNF+d=?5G3Mj%bW!C@11`uS;b5%FlK zr_sfxWb*m-F;Ti=!pqjZ>`<#-4C}Gs>_ga|TI`|ne z6ril^E=axlfx!M*6$qL1j%c`T>d2z!LwxLUVBmAuKG70Cq1UeIs)pGd6H2<1JDH8y z0=p=t!G%*e44Ro=cA?^ZXY_20*IYVLIhj4aJ4YT&XHZJ#}LXLpX*ekgviAtVGCO}NP4mlrg$`|sEj0JgoHsp;{K?93Uf-n@S{-9Kma z3Ob$*(py+|&z%(v%n5kagBB}Za)3puQdRKwtr#FZgQL^PoT%ydSCPm_!e@KWEkB}_ zXYXNREbq_?TNUP#YGn-VUoG-ltfBPUF!kFKP*b=WayPLGpD3OR&BKrl)WYE@3ozsCD!ZcvPRR&r zDx+=fQRK0p=!10ib4ZOYwF*~{tJ(FuPzkmHD}|DiqxRo4}+Je6Srvb^4r(C zG{so++}qKI#D5-#<{<^MMx#l7A7Vga2|%>SK2Q_ll$E63$D45jhx30$FjM!);3 z-fmPKNEMB{;)(0dF^}p8WLpE6{(UtRn`?_W@J5L?P>A9|{QYNd`(sW6)bRTfoC%wg zz87`>p1L>5@vL-F{W*LiJU@F{rDFy2L1Qa^#<_oQLD1asAjiMg^(=z9_x(4{rH=>_ zbfm#Pa=K*| zwwZKgzVTAsB_c%1yUKwCF1QP?0uoLo1D1tAd}m90dPC@n6ruq_L(Dp)SslLQd3Kd> z!DXP&xWUM(E;RJAiDIR!l_rOR`Bzl5T>S((@uEGU-EkWs=bHd#t7A-vR{2z(!y`8$)nNb}^yc8!Ma+f)p-mXb zpk#SY%e-+!KahV5DpmSm@aeftM&6d=_A!5`1 z5&PfX<|OQ#^5&%f${OPi0`=@Fa=*5Hk90q**MQXkO9k5GFlcOKjf{-SSibv;0VANu ze!5#L4^R5645O{!)fjP+lf@FB;8QmH`D7iIx(O-3_=!->cs$OI3SgTs_+NFGd_ad; zs2iXQsQ_k7mkcfwA4hXfv_C1IvobMp8~vUbbYwzyMBtZwba?eT@DX8#+JFE4M}XCQ zwu$+f3n%91!2Br?AaH`mh=ycKAL-{nkZ1llXHUDtGOV%-&xIb}Ot@ywzNP1GyiO4Ox+(bPTg-AxZSI+&U-xj9r)H$;_!SqhY17ZG`}2>lO6#R zfEO%r&c1_75BhC@Z$%LF9!|L-(8Jh5>y!a(!qpOkQH-f&?kt=lQFkHH(7*7Vo{#Nxt!WNrg0VtA@L=lbAe=zY8=8l72Cl$1{oDAo*-lhO< z&q^ruIRll@UkLy+VuAwyjY-geX{!Gek}?ZAj7L0J1^|z-i0jDlRe0)5wvE(d;au@Q zi5?6(>M`oTyc_BsZ`6j)5{=r;!VPg(8#+x%xMUpqzJm>GI2`!VeTcXL6Hamqs9Ho3 z_WJZ-9nUKc)Su2vWVRt<%n(lpJZ(8>Q5oSN{T@e<{P+ETodTQbMH%~{|B!J-33i80 zcOa`w9w!a8wCEf$inIZ14(f1nVdy)ku02E22Ueonl1|F6)fLGVi zhir(UnGDFS1Q84YtR+d{WRUY%ZEjS;AJURaJ)uKnyShm*e-#)J&tG62rNbH{4~x@5 z(=~7wWae|5T(=CIt{}=wWFHK2Q{b(va<7X-q`sR3o~uJtk>E1Csy{yt1=Cq5&K;VO zYmPgp0hZ#Ag50Ue@%346Z!b78rsLa#l-J)tNEdK+;k1mNdW{ll>vf$Hb@<2Ytt@HD z$bRJrzyRhCnoUFo`{Vwg*d>Ksc>5T}RcQ`Z^Ug9d%3?`+*^gDrA_cNXxA8Av=i>m4 zWnB>kYqRt07jC}agV;DH9&Ra2^pqB!r;|u2dk+fVL1@6ALIsOG%nTJKx5t{jaF^_= z+$WG3(e1@3D=Q<*9^7b!=ca3Or2}ygn85BZw@ac4e@4EC$cp;17=fvvee}gb;NxyP z*>Q1xO_FW%A1+o7ro^rt=x|eCOQB$S4inff=PMOw+97VRYOv1?PTN}OXAVOxMDP@y zBlZ^~pLh|El2|L)wzJ&q;k;CV=c|JvwSW)UKRD==&4&z{D*!!WXv|eYEdwl;h465Cgvuha5`s~o zUV&g_UgB06!f1j`RC93yuofQoXXxR336C_`Pv2rnbV@ZIx52D;5@a0$xd(WR>yOWC z$K2ye$gMok_Uil$CA+EhDWbY5!AN*58ldMH0u+^{s%KN&2lN9_ivR_Y(xW%;A?FcR zK;^Ntb8qhn;ggga{wIX@WZ##jeCw4La(*xylo zNAOP>;T;agsvGe&yWO2pOOWR~4Fgl%JK3}wVO$2nwLD~(d(H^C)J zaGHN2M%KX_Cno^yLLG;t3EYsEusvko$*8Y5zec79)&FN}5&-=ayp%%;VUNoJqW?i_Luj>e5nGlMS?-@&K6per_?6I*yA zw$nR3Mvg`(x+}aV@suS@N14&!!1NXd9tZ|Zk(S<<#5FSSA+#r4frEA`>x+fzw@g`J z3#OE)?9sPN+ogy)Ge8;1r~OyF;;Xddg8=lRaR0j)GZ>KEKgziGQXE7>=UH}rAF73d zB+BSGd=43N0=9d+G8u#_KmjhlOW7SreevwASR1t`2S-OhNS7N99d!ff&>DHcDAq3{ zK^pz+KAZ`;#rYpzF_%D!M?B=FfLEpEuT%tqpz#?B-GDRIwsfC6UFqe!ood%kiEw6| zV$P_Wa)DH3yzNk_@6oJbhHeU(ZcQeY? zekCh6*h;9*t4IJOZT`dN(goB-6%*PwhcFjU^nC#qWOU^exGsjmZ5}yNkK`Ze@m#od z*L%XyUBgNaejC;$ViZN32%DUR?^E?8f)-U_-Z=t)Yfid7=&1G%s6D>RN}(m$Nhv*p zEmd~atShRsUp@4|d+z_AJ{8jXnApm6{AU>V2p(~1; zM}+6QAX=Ijd3Otm@4THbQEJ%%9*ABn;{v+GX=x+Q=S=i5xCJ?Rs4l*VMOH**c2vuQR}2(@i8gXt$y!Y&55 za7*vLJ4^(5p-q74H9k57H1i9&xjbel7HAIUe6qmB*8JFV)XHH3t8^PWLh!@?DbwoQ z1tp-VnBZ<*gV7Mh2`uy`X%x4(JuJXW_@_8?(7e89BQNjN{OutoSQ*O8AAqS}xOhR6 zAXNS)OrGXod{DaZ(ks3Kq8%vv7$bRLN(3cbN(wrqjR5j_3&_9AP?%=-5lJc+Gvm&V zi`Knm37N9%P>R(8dX#E*inupJD)_m3{#`kUg^wYg-U{u=X}`gCYQTG$oR?K ztZZYh0jTp7g&|ab;V>UW6s9xK8>YODDG_?nr>rn{RXlhN@5dFgi zh!K!vD_8Ze<2Z5n&#YCNz+R^XmG3}VoxvJ<98Rs|g3(e9>o#~IqR#3}K1*>A12fIv zCXms`yJ8E8Gl~n-DGn|6-iFnkBK8jBmhP$ zGmQ4+C}h!IfodbpL4xg{Cx?*`4d`)za%myI)X+3^9)P!#bng}{Xi!jEFtodoDlZ)c z`|V$_&-EV_iHJ9Ak^njMWLwjsNlAq0>1_QsJ(odkuUH3(&Ud!>K%cfmcnJFHP^g$( z{3QSV6nOhY5om-z*pP?O5iLAcklk6{C% zH;>~}7NOt9%WtAE4rpVaXy|?8FwAFdL^(0HPrgsNlizB5#^={JVxq4&}lMnhlC4KobP9|ETo?Uo7M za~Y)FQ~9m$d1qP)vn;_FCUQ99jUY)3DC68cX$=rhWNm3`f>LqD>28u6@MPp?v00zx zz#-7XP(8Q(%^5Bo4c0&!3Dq#p5IBgdFGnz8h#*yIm2W*=1XuAvtx$`Ffo5FXC2L z7``vDPEQ{Jf?z2sxmt?tOwL0~2#y=?)jB~{|H8#1mG%s9RwVOE3{^l$D8nQp@^|A9 zed4+R9l^Y|h@*TAzcPG3Vp_nJ65=IIx!1w>YU&8QwP6ryL69#;r{oEPBE-8yedw1X zjv!e)IylCSToT^D#h{V~=D}{f6`=4|{ZbBPj!KI3vE1NAhXKBWl+T+4>`G#oOEkIa zy7Dq|mEzBCf>NS1iSQ6FPqCieW&2r+cwr9}qbo7HiCV9Hp=Ho0A_?3JB%RUk#^|#4 zpVmHK9gRQvEb2jOR@IDV^S9_N(_Ka5O2B)-mW+i-&jEuF`dtaASEicrT@b9JovLUc z1=*a{E`e4Ynd&GYVp=(Vn&w&ewBqBw|IS}|FyK2$sX$NyqDIw60HNVv_$zFtD8@y! z66rl1SOBbJC^8jeX72OuErGJk^D>*?gknDoU{MM2#B+b@GXc9hX5Z4E$=Ew--s;fn z+t~5D1~oyCi#?2UdQT7Hfd$yT1Rch7Tqp=DNQ&{<(Z?H}R+&*#Nv3p!h{$FFrN-7- z7+W}fgaQn)*V?~Q^6-goW1;hnkHrP=GE}mVC(}*YtXbYN{KD z(DsdyVi@7!)AO7lv^bP}R)e*hXY>OIqwKy4jo2B4>MZq0EuPkz%7x2s81OboQs62UHGubdYtk`rKYO{ojsv_>f6fg%^6$p%71j<0v-wSj6aSi z?)f;{R@(~-;(>>L^){^ve04DUEE~rK?HoX5R2>kiguJnLE)6Q~@*n`A8ziapjMTtJ zw7m3Fb+t=Zm{iv$G?7VO8fCM7-La8ovQ~Y~uM>64?j=fjXlKmA+dc^9QJ4H)4G&Gj z?Ds~k`uD<6Hbd~u!js|G)wSv5y?Q6!X>JN7bKN)w3+Igv$W;qEQXfoeYHDa~tR-Vf z`19w^jMu@4viTA3?5#D8JSl3PfA3YF*W~yI^Ki-gYs9sJ)!V~H9DYhEhW}Rgy$Z-x zQ-~hl=at>z33E(%Q$tK8DV4-%$*{6Fp-Ll{>D)a}ex6UrI*|JEE{YAGvh5+W~Pg0srev+-n{M*yuw#>SsYe9_51zjm$9v|B}bFFsaB^L{- zaz8uQXBA9TqEHf5^0E&Bb@8>K6= z50o8*NE6qaGaaG=bNK8Kl)GewCV?@fKm0TV@#gc4g{5DlcMVSIEC>^z3 zsG62=Wi#V`c$Cp4`1$}aTF>Lsd$$8Ed&d*<91z8I=O-b@ts$t-&rH#iigYdNihYfS z@t6KB_KW$^{t}XPk!4TV!qXt!^IdK^b0tX6lHcfL+pNkFthpy`MEWqh_1ZRYXhf3? zAa&0nACb*5r8%fGHSyBY(odg1KVDZ?cag%dZ9+;bM?XG$Q9Kdr4Twh1!PAz3lsc%KLf|#v%BBwM3%FVr}j_DncOL+Yn?_76v z#;l{_dMaE0;&c!8#>d;0J0HnO0D}|b<2udZ&mpCWZf(9>J@6!7Q|@y8qHtNSSNmh@ zxs(3ZF2$eH@}76NPBF4_Hm_`(1SrXxEgd=krSts5lYOCYRb4)BZx7IJn{E)dM*s?2 z9Dcxog7a{8j0kuR-;3o2QG?F~3Vhhq!qBNNBCSRJz6Vp_-uzteyXNFFI5c!ZW*Ye* z!MdE-*3tY7qJ`X4I5ux(e$0bAmmE$DAv9e$Mt5C9;|@Dh1|Q>;9^M@6hkF0v+Mu`L zCmqU?WoX`jk@7Qub5BsTl{!pN;xjhk!H#5RmjPGiTGBJFtKd)NYO#BjJ_r$oP(mnq zzVgs#KZeFV>vyCnQRCp-22LD`eE1;!%>_=vq_#|Af)6sH8EAXFppqffRq5%to?poWLA#BoF)QY2F~V~J%>`cDTeo!DmI2-* z)k{@R1{9C%^l8f&)rWRsl?_MtK;Qb_76Uc&uVVG71!4bQk>-)y95M1=i-fP{@Dl-G zY*f-2n9JZT8Ua`6nc)KwWAyz2-Ws%ma2Cv_#q_4g!h(3tOBR-{A?enmh8P4N@AVAnQ+ zSAeDJSrz@MAFWmO<&^2~@s(KZXy}ssQn+77#5?3EJ0EI|GGpsCXpK zPQV|+eQTWSWW?F#%tPIv&I-&N7@7smi~i0jX%ZXV_cWq2PJNK0vrJdfldqv;3xZlh z`?i(}Ictpb_piC%h9CFyYu*}!k|V2F5U;)IRHKIYR*CfYz_4Wnb`(JpkiYQ&v(G+!(W zdze8Nedlpt=qk`&T;JB04vqO^LQ6H%>Y}l zL1@SYKPp;UE=bM`jfgnswch15ERWvSL{2;;zBa30wU;af#gLm&H%u8$Wci_huQRTr z^ttP|;9_}Q0SozE#IJFW&r>pd;oFA3;eyjQfKd_17x3o?6{R~)U@y=HhzAYvFv^fK zU@e&V=#@|6^?hXV~+vK-y`Ahp!?!=3%^7ss7 zvB=EEaTx=}^K*dn&*R8&2)WmPeqN93TI>UYC~syF8bgSlJ2?7v6E4P+;%JcQQGc|x z@5E4+2O7)Rf+gvrxo^k^fZ#fyrF(w0@M4~wd-~$Vo#iwqNLFx3C-P~3KS&r=%X?A56CC#d=RC(CXJAWiDx~XU{wjZGWXa<=}OMkOvXO`8k4|FF6)fT z$^NzlD-RmMtt+Q=S}=b7P}mWBhjZmG@Q(umE^V12$SpK9l#KPG5%T%>mJto$c%B>F z^Y4rORd#Lil8}%dXT{3x)#=h1_vsMuYJMMu2IKQZ7tIO8R7Ax~iAwW(RK9|c-h*aXkB9%ax7XzII; zF^xg7T`GRBGkDOk@fsGh7--L|hYRQ3WSN*pKd4`kmtnM@0Hk}P zGdcZe{4D)Vvf3|Sc=hp)8gGPndDVIRgVeQG_xyV_c$1)$7qpIkB-E%Ly|VaC_49UX zxUj>}x0HZwrA((YlT>*F+pgE1cx`qUNg)x)TI$#9qegHfj^r@p^#^NMx8qGtKq3&) zLwfH0=ppC42i(S*G4XD zv!wL~;aT@Lt$azS5VgMnp4P{+r^z4Rt5NJ5Y%`E8NMxCSQK6k+%7+hPKS~_#()n2~ zjAiSg8h<>d=|l5A7BBhFr%RKP&H~&WVCLkithRMIHu(+0roigZYPlh*G1YodeXE4i zOBY=6U$$a_(AAs<0HgkoF~=b)=U_od{EL^Tc(rjW$D_#brT_LC#@lj~tXjLRR|^rH z7H(g@{xe$-Du2n4?00xp5x_=>Yw;d$z*aG=0cXIgxi0#^GrqWl_-CymIejdLkS5eK z+GJhvcE7)KUc9IbSMsR+xnTXLv+XO3%TKlf?T>5!RP<6*JK}Mp9mdfwKl0z}_cpq7 zXYFn}#oBCj4%|j6Abfr~(9(Bc&5fQkaYV_Lv!DIcj~~njySntftWAwSh(0WI)b1&T z;!5#R>WI)1YvjsZ&Zx)PBNf47U)L8la&5th=LWfVN_mT= zttanFI+drjkVH}G-t%d-8C`9I@u8k4?Sz7R&m+#$GcwNRn!SY@aVUMPRd4J|8Vujv zxK9;!l^DKkPZ>85;Hi=edHAjaY;0}1F~=%8%+C62T(PCB+?Wf1*ac=%alX(2-5)KO$~5QMkh#5Tg_z0dU}nUe9;=sq=%$UqK=N9;)-`BBZ`<;o=uApJNvFrYVBQ{ zmIZL5Nk~XA7wv6!zEj)*{;c$Dk*|v*t_dG>u;pIKBcx4YULoT%t+4FvpIs}mM#`JS zz8WlCVTMJG)i>$LVK%~6%-QMj7AnZL8BUISMwZSm40U$2EygCV&rJt^QOBA%4t0$S z6vnxA`ROZ7QMXOuVf({(4sMNHTd%-v$9qD<$$ZSpfV z?37q8$07{`!fi5?Q~hFJ@bqpHBK;X0TYlHD{EXcq<{h@(siLt?2b)chxxB%%H5=kp zi_~m1ep@-y?YZ#{BNn}ZeN@)zTjN zryu{WRt!irvwH9jzp=WOqIM97wseAj%G%6kEa=RdO2kA_E-@MwZ*#{qC?6SzeEfCq7(F+KP`>9f7wpR1k{zG_>1__H%6XC^W6`0k9VEpC+c8 z@-Nm+ZSl7EmcjR*g75!@jC+DVTm6=~w8UES1FNZSm9oJ` zow`M@bj}er0j_&GV_~~<{q~4rF9m$lkRYsMFQpMv@ut@>(8XVXogWP$lWw{FV4c%5 zO0rfHA{fC56{;M7ze|{{`!oy|yoRTPQ0sJg8G6J@70Z@gu$sxxkN$bcKJa&@6XD5Y zxwDT`CKe~d!dYOtGNun5hdg2A`(Cx~^+_l=@} zzPLx2KCEl1bS2rgbm!wocx(V0YOwZN*LlPyrCQvx<+L9@2A-JH2JSihpqA$Cb)EKjl7B9s z;!vit^*2`kC;rPd8TVs^^v-D=^s-(^_3vxa;QZDn6Q*f8*Fd+WQ{2-gyD#d#k+u5a zo+hm$51GX#Iu@%x0%>M#s9LMb#m&ufQqH%avKyApAQUZ~PoowCdX`=*A87}ptt*Zx zs8oz51#B!%ah8M@<^o;?h1hE8E*9yLeey%N5#Rq zso=_wun(=_Rr3hHE^pO7@`Z+j1xVY^4~cD%lIZLg42 zBC(4P{7t*PCW(YMPC*o&L-e~^0PC9ep#*y~sIv?v>#=A{zRXcedH4hhhcfE^e_z=s ztfQLM@+P?m(3}t}+=gr1;*jvEKU@Hyf-aYT++O+(dXFcb1vAAXXAn&xa2t#TJ@nZ| zUKQI}%3sx}^w2qRx)}HF+K?l5IObf(Hl4Xx?iS`AW$+|GUxTl0#az60s?(g)kBJ8T zG4LEhA}GLoZA`}6QBc;3D?X!lr8QdDb#G>yuEobL0!uHC>1_9;{_N9rQ@viU-2%$@ z7H)eN9{pWTYgx^)IP5R{+m>>vmu`XSYL|gwJJWiM`qg{(G?y*Tp&}50v1LVS0%acFGr2C#cVBWDLEF|ec45IUrS}}M8k{o*Fa9|- zx}45?dDA|gQFRKXJylNqG%CtmRwCodHQ0N!yw+2Bb2#Qb0teww6YxcUj+!nfSms$J z1MA$Na`X{)7%xq$_S?tS+|sYWM$eai@NWEJZ(~jPT|>=wr{E_|&X*M3x<+}UvRIe2 ziC@{a1nd+y?`oTxF0)bt7+n7i0!mzx+D$4RuwkXRJn!y3CUmFiL+?I!gU{xr*``!9=L*C{aj4eo`5q@GcSzy9!3r^}9zve9R?-wy@~%tB0yXOXrRWOnl_a zs90D7vPw@8mHL(n?r2YJ*8=VK%A>*IVH*D_VAR90@1X^I>KVL!5h}%-BAm)lanFs8 z;Ft%;ste!YPx6N0QWxpNggfjhqh9H54OfbI*8W&ZWYKc<9cEwfQ63^;>(s|J=&4`& zMw{j%duYB|k=BS`Zm@NAY~NE+bx)|PAgzGDNozF7O<|2l&Gc7JR-y6Yyh<_aZSW1z zWA+>m63V`Q3YA#ap9J0BY1L#AyKK3aYHjkoQ4wczFLK4F^qGvmjOW;NQ4`kREK^f- z&YjG%rWjLrEBc_&acwiB?`4x1?eDRJ>^>ycQwt+WS*hQ7Y(DmOjc!E*a5=86r`tYE zsy9@z%Refya{J{`=6r4Fiw>yo{O#_ml_s$dw=A0DFQPv~H?GV4c!K1(>wR|8#L9pL zr_gu!`lD;2<+h`QDdpob1yc)78C!~n;XAb#*%-bQZ?U85Vm#s%(x-!6bPSV7s%%*3 zz6cFiEHmxsMLSB@oSczKA0mUvG9l~v_A6!it??r{WQq$V^}Pq_3JlxB)mb1nC1x2i zQokpgX)UfbQDLofm9O|Zv_wo`*ZF-aD(06uZ{+gns^4s}+ap9pB(Y-a@lrFijp_H$d*ZYlbG#e&wVIyp0wULWA2*A;W7g~o)i z<;y!IY|)%cbnie5fkD^$Z>WfuJM;Sev(}B`n!f5_4W=911g}X=?ep+h1|a<8$UxY@ z_SVeyAeb;Ny3+jfk&8FkENd5IJ!G76X50n#hvfz>UU2{q+P8oz+VzYV_kp{qa$v%Kxp+}(LFo>}%T&!;Dx_jI!s7J39@UkZrbjoMe-pN$f!~-{@`GdgHS^QU?vi$iW znrhnVXRbS6<`r?5Rs&Yzds8@6-S?JJ`8|KxD^O?scXd-6uWUlRne+NaQ~3O4r|ts~ zS*;zI{GCEcMr?wu`^P8aXkV{N)`yksVW4rU11qz!ymI|6!tvhl-iCYXH)Xw8I^8_e zyNc@vnm3p=1r#~ooZ@*sw-~Fw^HZA)nb1^udXB)Fj#&138ff%Fe`k=RTy}aL84Ca~ za#_Qrh00cU)7{QQWUWzJleTr;05Hd=bK%>YvG0a+C$QEt4W))Z6;C?l&ai@kzO6xT ztW9z2XB}*uSyA%c${;SN?UJ3bo$2p<>K7IqB`kpWbBrZ{Z;`jSCEDn=(8bo1k*-zK ztUvjF-Hg2OFDxVR;5`gmt&_!qdcDtinO!)`+{E~2Q0+rRc`xtmb1a*Q#04GEv>dKI zcT?p#Ufnvm)~`F#01#=s%W zy)8USmtw`~2iXT9C2 z@aheVp5FiplQc-H7|+adpH|b%>;-=Kp;P?Vk@m>W%N`94kl9L9O^`AJ=@O>oN<@W! zI82?{Urx%5a_g5!gm7L=Y3SWmw~6wjNlBAbcrm^A`)z`zCq(T|?mPC!6!=GeOB$0h zFhB;|XW!!ld$X@)sGnzh#5|Aiw5!y|N+lp_1VHw*GRSJ9;I~ipfeDcTXe9TNV~!9m zoCvBQNX%00@S~(^iFY}E;@8I=->Uu`?~2J{pr-p{b4wWwmVHa3e^`cZ4*w5X-yKhN z`~RO4b>yy&q-fYHB+-)SR3f2im(dVP5>i%<(jXB+_Nc6^ima5D(6ACRQdte7QYz8! zd7Ys?zwiBrM|a`8$927~*LaRC3lvuDlX|*2dP!yKohBy2sLY2_e4`%bG6!7KRu6j@ zt%hO9-8t7T80A=6)Ya8p0gz>EuAByxIaqE7Z+7QWwc_b!W>Fy>+5Y{ho8rDu#gO@} zs7wbKSf}ML)F3yM;80eY2ZGSb!Y2({SfexN7P6Au{+UQ>!gQuzr9#v+4uJ0tM|_Pdu*NW@yxEk{I}Cc)PV_< zrmgUeaV*v)4aRpKE@1jt_HD4b(GZ!pG;eo_u_FW*#hfvy4Q}02{ggj9whV~EF5uEa zV`3C+tM@l(_9V&bqYW0`)MRR6@N?zgCMyPv3q5;rPr`tl&lUL>9JYuiJN zQ1t5);Cc*x->Pk9kYpjv=159$a)|Mc#J_Anmo zr2Dn%S62Zuwp(htNf2fbBmzF`WI zH#6c=Sl_hLwO0%0OyV}bkcTcZ21mVH@UkV#1Lk>D!)D}de(wSTwgBPK z7PEOpg~a8bzkc}=C^cNAH}>JmtAay|FqMgj6P-9tI%(y{{+}=XYCMR&5l>t%>g?<+ zrJ$e}5D@U(AOn5g8KR=1B4K&Gija+52u+a1Su2Q0T-EZ|UVCcI7Ju3zK>DM0U7zNw zk8Lk<1yhYwg=bzV3kN^q+4nql0hqb@_OqsI{zx3^YiWFYa}Ud|<=#wF7%0L9>`yCg zcj%mr`WyNDbsZNR{?>AC!^MmH{&@6nHrpChYiu&r9SDi5VA0;2r#Zqzzc_7YVyXcl z5YF1OXU}=RZvg0=o3$XzBq#pxAq92ymLEI*TzqV>yiJPCzG6I+Ag$&{9JJmX_lpvx z@Jl$s>`SuJV)JoV_inI;^bi1cJ|6?ec-zjMiso%q%`qpG)RV_u!)a333@5p(9mfwe zF}|5IXA0@|do0QX3~`Of)DjaegBP`aaaBor2U1f~PWUkzDW^`Ix&duGGsvW$nk_e^ z`2&kb5o2G=;b*6*O;hYnJ%rP&@ZB8_myw{9+bYY*Od<>bygsiPO?mcV*Vk4+PvWid zYP|5J&yTXl=DY;pGQ?w6dbCS^$xjQDZWQNZ9T^L(bSC&xLDbYZF>TrQ^m>q?FWTNz8We#PRA>;Q+gIXL?mY)pvLONu|S zblcD&P8&3&n*emO?>s!^HhlT|wa*cpsK_S?V?(l=OHwo_ZanSBM-IBf>BPWluFBrC zAY4$EvTtWr&Ft0rKU#r8Sb$lFfJKz{A5Cx&KL=WwT>a2mbQA0iW4uFIAbG;8N3Kj{ zZjcUYFP{O)T);AU0=i4!-EYCOCe)m`N~|!z9MJZRd35yfBG$vsB2a1H3D+mdK390vx;ZD$4PP( zR)RRgI^%GC z&IFF8h`6IQWu~BDB}7g1T{dsnpd6tFRUIr*^5q)BjbpgvqkpUtB-V5!oe>GWJN7Ln zCH=#n1b`u>Xv#XG+yoT?w*AH5zr9jRA3lEk1hz0_ygOs|?4AcA%`<^{Up4mQU1)r~ zqXdCO{Kk;kmrWH+VCsZ6H#didhf6iK`)qF*rC;x39&7!@89 zOPu|Lz;GiP^RkZDLw&3u;^osPPr^Do_fG%5VLRtW#gqw!q&(b`y|w8)&jU8h1gE^i zmtlOc@k3wuWsKZzKqRmB%3g|Z6$J~99NJZcfA!Wb+zsx5MlHPDzonfz%DAGGcb!Nt z0e1EY#Mh3EKX0ca!%^_KCxAtN?E9y2iEF$SPcVi@ zFo|F8Z4aP2!I_;rU8d%X5up3K^UE>8)J)&v_ef+b#*a1#*Tn3bn}4u`Fp{N+Hu*Po zpsIyoqy2hV=gdFX$-ZI+p~V06BLDYCu*RmQ)$G2}wH|~+L#Jyy3bI3bEiouuH6AJD zu`NqC7B!C>!f&}sLAX`P5Z-_Il%JoUeA{yMua?Aq-Wj1IW~I;yr$mT)wT=Wet7LKm z!NX@(=#7o#Nz}(9pLxD7PnHu88O_L14nJ}?2{0w~qF9qMX=R}yP;QV;sVXSss-tYv0q-lu=F+zw%u zwVs24n?SOZfIQkpu z_||3MfY`SegxAq8SIfbK&>$s(N7aR(kmCE%I|T=#*`c-k%XVkIa?DxlxqpAgmDE(7 zOOxu2d{JaoLP&qT)y~5+4G`kSM9a6o%>`>0@RC7E?ke!EK&B;UJoYdUqsy)(cTda z7-9lj$?EWnr<oi@s=y!I|10eB7l zXgNoynh4V8*Dm0u+?!EDSuN^46hi!Z5jkdO?#i{|M5pl=eAWq@PV)D}vLT3qd-?)r zwqf7Cl+K=>C#YH5`sHACy=~jJz%w)b{rw#e>5St~%i_thSK>r$-$4O61qIcNRR=o5B4uOhW^vZ6GKh*jC&$C0Uk(E-NDbMAxm%EwLBT;KK!ygO+r|;V_p_C) zEgFa`A(68GsP7l@%fK2CgD+22t2gZ28H+-<<`|cRre^!0(fVR6!B^KYxpj^7RnuPE}oG|BT?J*Bg=Q^>y`XY^27BZN!rn{Ql2aQ4ib&nmRZ zHz5-KH@=+usl6GVFO?J%{l#0=oqJ5r7{@?ZU@bP`zBw;|ud)GqK540`_Pa1fyMSAP z#CsrLr0LkKNL zx&Gk%?HASYAlxH)Dpa>O28n3MM}Nu|yw%F9^tNqlGFltV%QKvXGp3rEh|nvj7Yt{r zoH+r!G`*MVh3wiH34QdWD}rtHb#-fP69XR}@WuG9iZql6l?+g$b!6n2GqQVpVTtYJ z-nen&r}%*n0ZT24U3nwzRi=+$nC}D<3&bGig$pwz>{NnhH*{(AJF0_Qo%+5eX`&q` zoozcSXcDs^xO;w#ZMJ~C{PXw2jjc~9gg$Q zziAE-ud)374PX8|?;UsUf~p7GBu#9k_&KD~%j;N1yL;4pE0G9HTu6!W|-E#p7S z5X}$CkRUZSmxVE(tW4AKm5EP%h5C9A;wX4mCHLuYFI=zS1I5i%d9r1_pO`YZfOKhY z7Z*6V3fxTN51lRoHz+x!-=hhL$MN=OZIVV;1cmuBp;M+NVn8(^u9*yEQz9F5og3|CX62t_rh)P?)Dye17-%yfEQ}q1ksJ^M$S$ zEr3EKPugZ5%)UG3@$M!Q4vHM~8vXF$>p1yhigkg(halU?D~%TRJI3{C5q%bZ=fo&@ zteftz1|*y8vuHmhvrn5EjvlCvujQWsB4*a^>hjmq-f$N%MC7HP(*R9Vy3Vi=oU^i5(%O<=VxkMK;v< z0!ieDw#;Alj`@7B_t4{!QdO;A@)ifVaHHD46;MA3T0t`o;&u3nO}V(b^~GfCTS-Q@ zT`RYUL~wuZ$UVT?18a#yDs2U%RyYU5;MNYz*`2{Qo>GcHtcR^fgs?QfKkrVG7_3sr zsURJ|InPnY+dzCbNkzY0T*A!EEP2sgZ zQXo>)CzdLHXJX)K+LT|bc38b?=xMpdFDPh}>F_|_XqRhl)D+J8rdeZyP5e)P7>|>Y zLpn>u8WywuzVi&g^X5EhEe>dH-HDdV;Rb>;XNDcddNkq+dVTjaan>8-JSTb32h2?l zhqvh|e}>2&jTGo&WGhR0hwOs(TJrG7*^Vi(n%?GU-YVhHQ@ta*l)n((Q1|A~^wcTa zOflCT#;u3>jDEBd^yqZym$fct@==v7X{`l^5_FR>YJk};pC5A%u)a9$K+af@&g`gh zo6ujoHfkLyT|m5BP&J%Gg{D6L;;j}iSV_{^z9h}+?wuzGPpIpC=h#ifBS7`13-xhg zB8W}c1GBSIb^w5xCXOndnsrZQP67`JEbe3rk3tQZiDXU~Nu4;r^s6A6D!}f=f7H5m z{Vtk$nTZ`53Oi0G(h(v;I_|(o`CZflG;=pex6xK@V!~*1lgo(c2Bc9^l8}!I2Fnn4 zLDr%l$!fiCd-mOaaW{t-k|%9UfXmZn^Oq=hSy^>Fy~ zh`}|HXqUab^xtJIh~`-=z6Gln5y$mx)sCkWVw{XpA^J|D!d81{;_^Da2xQ3tn7p1C zUzDvSYl*1f)dmcFPX@069n1E@AbZP5OP z3lgg%vX3j~PeFU_b=sw!YTeZdi!d6}&JN%n8helC`y#9&fl*7>nZLYO0Pap=yWsi2 zw($ewr9j73i;weFwH;5|Q8-wDad|Jl8;CneUam|vqmGkwZSB*9bYL?b;Y3?77c{cm z+u3>x+2CZ*0i_Dgv@hPJHGan>6hdvm6-7rchaMVau-`f^&%1f442IBq(bi1adSLx9 zlFjG4Z(i?q@`103J31fh2a;Cu88|dX^7r5Vx`}k^m&!h2iieVy?>m8S=Iq&e9v;Q^ zi;8Esque=Wzr1YBl~XEH{VwCG-yAcH62M~=lfcFbJ8^;%tcW2i+N3xM{wYxYnFq15 z!?M|276%U@;y}7xc>D6`3FwOs=nXr}y-)FYx-`V1x=Z1VF~6wF-VM~?_E+nkR8@tV zSa}=aAn0+HfO=^JW&;6Z2ICKyx?&a^wi-RBm#^g4Tcv+jL@HSk^4gwcMMzM7F_z%4 zMfKTzIJD%>dMn7>qT6(*_bvzSPqjcaS~uLJtisv_B#&jtH1~tR^Fm5ZEo$#8>W|*r zgZKHqluev|X&-T8H_P8|#7#Bqo2jR#*9FM=1sJoN`^J&j>W` z+qL@;`?W!&(fhCqNnDJLjdu+dQ#L_PMta$@mnUxSuHd}d36y)}Xl&A9jFPBlB(}xW z)b94egqWBE#n(F=hCS+&P;qE4J?fptF%F{ll5ElAu^<09VWXc)8s~(BwI33gI|u>7km4MTpp6m75zc&RGi#Rj;LQ4$*txIV0b(%^ZhnMFy|ZRXb~GQsfZ zxxBUPG;1A-(J1!z_NeuCe^?1P`_NC7f7cC>OZL26z6{qw7ows(oa^6@l1Jp33<|{P zWe4|56|=OPkPv#2{MY9{q46$vM|v46PCm}VFyq+<`q0e!`+fOUHr4SOHYoE_%$T(T z0{M<(ZujPT*xRT72EXmX(RTO8Hons>vYbH?*Jg=5(>75^>z!Ebl-uGgYj=Jyb@^GD zIcx!hAA0lz)qz*}PhP}jYh6{?MhLK+fOrfcyrjUH44tWd{){`i2~klC(ECfCe!P`8 zYwyL_*iW0bbA}dl2GQ$KR&Ea?R29XpEzvzPDn2jLgXQkBysOmZw_NpcD#4s@HY410uS`;KkLMQ!^D4SFe`Y9Pbdl77&`fNYRYr z=j>r-t5k6=?>m{5eI6plV_s_F;=V3Tw3XWb@o=_6ZU*9{v4(TtT>K3+k-lb)FOhI9 z6y8eq{bmT(M4-M|#PCdIXKJ)TVlllr&+dQ~{aU%UFLQcJHosJ2I8mxQ_-e=g{qo_i z*LsEg>KvDd_aY&PAaY?#GC|keGWM(S?&&(Gb;lLW^SwbfbbFjG`0C8mxiXDAUC!He zxlw$bX8m|#H6}qY_H79Y$lIs(q^lC?feF51yhO%SE;&W8<=Z1T;&B4t1TJQme|_*l zvY(Y_*Vx>+dE-W))-d=jdv2NMTPWzL@s+wK304qj7^tngvL6mH0|kwmjr+g%&31sZ zC>gSxzCpbVGCHEhx4Ag^pb)R!sjeqVCHk0^$v=g<;-j?ocF0{RM<29KOv{yF{O!RgyUpDmhF2+Mh`go60y2r&;#&^OjR6}iVCtrBO z45ZQ*5)uw6%Jyt(_}*4>bS|__-@bbXW;8;FbN%g%X|qO{8Q)prsw(-xNfp}NtmL4u z3@3-yIf`Krv~K)mR0Kj4l#l;DMuvF$6ERf!IK@s?xUIx&Yk$&m7O|5K>}TU()yosH~T{Buzp_g68<8JhvjSZrUmFYa=MU= zMIhH-uM{*}75PAF7a3*%rT_9=Rx>wT1HgXJ)(#ZfYv{7~!fpnxXteta*zI39cMpsc)HE8=N?~Xk% z?S(0e$f?{sUn8GFs8AwiR&Sb2X7 zCtcK(X435wfmfPxlyv>y2gv@DuM;VRTZ5IqlG${Iso27W2I#ivdp1njYhF68GWv%k z;8vSG#s}CGad3fU$gFR)Wm#TmcDrirhdyqiM;Ad{Kg2MDwl+MJgLUvw998>9GO+sz zQOhfNc`wpdj^ZS8PFVa_lUKjV!WXb!Lr5s?-meLry!S7&VoKU-#@ow(ub4`L#hNbL z9ugCe@%BzM&q}_CDGfNFn#+qYY_SKGVuDJH{&eaVntg{Ou!&B^2!w{zNZXv} zQQf5BDG5Z`C&E z9uIpEeHEi`+7yKPEFhZ^2>@)|J=HpSfnKa?FXZDXqotr+@|#@u;-I$_AtJK?EdRaX z^99`e=xHP)f0DcFf!3c}=l%S+$^1#{57ROg9ryJe==MWWrq;#6FvqfOgL7lD&DO1% z-0#jUY#A4*pk5*>1KXKN4$YOzJGX??M$5+MB9yBd!~tN z*NX95h@te);&!^J9(^jL3<{GrkQh%92G@TFGRWE5sz)@!QKc6lvRzF}tFX(wrfKQf zm#;nJ(C*#IABl#NAC)-rf$5cVY2UTii;(}Hqw%CLYekwISE*aAZPE8+HcBGRqWcmMJ%Sfe=*?C0g zcPZC&b*Ob-?T41CM)Sp6te@};$DZGHWW`^1a@^wSGScA&T21CWT65csb1di2+DNAN ze2Z?^WEK4$s^46PSs1hVvO!?O=FO2{1+^~eLl*NS&%R#b{K=opm(EQmH2EImy6b)M z8GT%3DSCg886-Kr{jFbh*Jq+w{&m|%j0fi{IwUa&9u05gCQpeJr@^!+r zMq^%(gv&p>A~Bin=5`B8E*8^7R@o(+!Ic*Z*bi^)#c3CcY09~=QA`oe%B)9H+EH3Y z#47OI7atjfF-`?A(;vJaJFuDsjPnf5CmLQq28*PIaW?6~!d7|QsS>y=F;Y?Zg>Pb> za<>KLz!84>RKIreF&Nc;PK!Y>nWNhe_<2NHnq2U$tL)(z%TP}z=*@&C`+J3cOFOIio|F%d`4~_`1Q~Acf{f~dkHa*z_r^FGc)yp4MGM5wrFs9 z+VX9A=5&l)NC9~HpgpTMz-YiiE_lVi=k`Bqt57!4s3rfy7qsgQ=EBR`N;_Dj&r)ZN z<5mApr0a>PSW|z-`GPjLm|jt2aI0n?L$iPxiUBAYBItQobe+}hREZ

    @Q6f3gUaYZcM}|DLu7UKk3YXV9yJohIcF?>9 z=A~`R^2|$^D1m<)oa|e-UXM&H>(~n+RqQER5(|Ci30)1$3Jb5+Zg2o{DAbso4!7jBOE$wQ|P_yVu4M`Ve&5BwSUGrHOx zqSKUIlh-ARa&pS@`OwI&v$6d(`Wcc4dRW>!Z(T*D_j|K7V0%OeSfJ7-(qf<2=6_2s zcIwG6B7MpaA$wYJDRgc=yYFMdF`mw0DIQo=B-x@2-y@s7W* zb*C{6-WeVo{#Q|iig2{(T1GEkQNPkEgSBKBU^0GrUgNGaa=JO3*uHkB>12s2n^lGQHa8vG3 ziFAcChJn$=H4;-HKAcmxzn1`saNImW*xI=%9gE2sC@rD&(kz%CS&_aqf+TvQ+)J37 zn0+j(aWU$SZk|Uq8V-T5DPk{T;%WcjORfs$!ci>BrBv9hM8T%J@`hQI~)()UZT zv5F|@vhRoF;=PiC@HQzdJ=JfGPuVio(gn28Q_9$F@=21y?Fcy(axB`XkeGZM-a1^f zYvki$tR4cT$bf9a4#g!=-VpgUigp!sn&8GvzQ`B9>vXhVd(RbzUq;`eysGivuxLao zFC*QXOo)K*1%W1*bK6Hb%_rwB(R~qLZaIk^3N>&`KX;B7!U&&g6!hK0QN%P`_&Xu5 zaegFd!u_A*>eW^-eHJ4jqbPWXW6}El!gtdm`|N1f1*2xW7DWG7lt>rnvfrkbeiN2MVkqJ;5VGrkMM7;ZC zdi5Q45sL>)OY>lQTwodMtB;Ki_$`)q-pFbQi8+wtE@oY&7VG^9t~mVG4`B@%5S|5bl2q&afYBXM zbKmpc#=>}~=*xz*tq)q-Zq8>e)C#KUO^11ved1rac8jqC1$kkH{^W&0GfcI* zXq90i=F2trO#8YLk`-UMa^=1z>5#x!nh4uYa(L}JJ_Zn@31QARjUZ9dT`b<4o7`rn z_RMT6Z9ksRHS^d}=GOAdWEe}zNFS8T?Oc=U);IE_<9t%0bN>lbQW3carne6U!(b8`i9SKh#-rtzr zXY9#VW$rkSgswg9ItLUY*0I_b8spoqzw(J4>hvwcYalLyDhF#Jol20Vt9swBHURSa zpj773_jQlDZb5Zwtf=QI&)Um7`-3J?wQiT8{Y2bYWX?b*v;sj|vVHOd=9Ld{&(j!w zVU+zXRvGcWB&hkX?E}o-kYEh+UwFpcIud#vcxj;_A#ZB05F7Fy5(}s-bDC=8i+IZO-ZT zj~HAPJrRKcX!E<oM9Q_U}_42OCGAho}PPDv=3!j<+%z7Z53 z8UYv-85|Ht|P+OMdT?9I$kC#?z0Qx`lI$jI)FR>dN@?Ab%bXCY@ zCU}KTJWPJFqaUKjJ!S|;=3Tdh0cGC7-JXNf^tAfS_!f~q^%rP7MR$*qq6s>fA8Xzv z{P~><>7nYOBNnFyQAepvSpsqq#t;UMKIjYVMP4d6NfpvPMekE$POPSDGmjN(H7@VU zttQ;H;S6~l6o%&o)Bhfjc%Ebcqx`Lz$swVeQhV2FWxb7$in1T}y>(M}|F?;yYlvT2 z#|74FEZdG-&=9<=L82nbz&b>Ii7GgzxCU|W`TFLoyA4%u>gC~D&Ykz=7ic8=_oolX z5Ycw~#_YH@%RJMQ#@^Kx70TYFIIzC}OIv*XXf&R+5pVDC2e>xwMN+P<@-|djPs^u= z&7C?Xp9}NM%M6pQG|SRr*AFi$>-+7-r;^D3UX$IRzJQgZXx(6FHocTOYEhMwnfX+5 z3d-;ORQ5RpEYi|uEy_Qeo%Gj_}3Wu7Fl&>1xOY3Ws3r} z@m{AG{g`LFZ`|6~l=KR&iLNPU-UBU^QXHEgQ+S|ZqQSAFvaabpc$g*i7s(6?PdHZK zY+mPgs9rt#JWf10p_te>iV=-UX;ZdB9=cyf$;m7B@O}{wC~W)l(dtjALU!T({@alJ zmBVZ)bzK-t-8bDC{l4R!i#qTp!myLHYuLozvDl1IgB{{o;Jr1&d5fRI@1Uis<3(&H zlyH?7pI>1{^ZX1c8d=uz#Z!zgLgJdJ%$znX5*9X$C=#Hxq?!CII`&7fbA zE|@GB6E|Le1LpkkHx9Z>t4JFW#y0nOeG{p0-q}cOy6W$c4E?pwAA(6~nQwxI89ciT z2#*gf!>LtG&Ev3Q2EBtPPp**^!s-G3{vqgnoV%0Bw2x%3N7@w9!n(iJ`akAh@QV}R z*X7U>C9`a_(D3nRmA>h)mu@=tZ+t*4Q(l;?hd~Q5sB<9!HJE<{n$H*yc%$ts)^Vx~ zfT%8r*@a+o5_L-ie5|K&>W$|t(KsiejC>KB$GuTcZ+*@lSHX;`T2L_UVfe5@KTPd! z66WW>C?Ud>g9X56?{XH4nnX4d1C2rtPe(^!zmG$1a!&`&shJl2)n;e}R{|%01yx>o z0>JDa^`k>rO&)!Wy%@E1?3M=%c1(y-3o${cZ^W5Jh(>Fs`X){xcH`QDZl2ejyEYbe zM;|z`Qj-AUI8SRHu`Jn$c8+}y21f!G7ApaieK#*5;N@w-DJ9_6B{b4eJZVL{__zL9QRso=$R_DKwG&L0X|@fIUksT2#HH z3-_}T@ma$EMA7LB^yA0xKyI7F?t+JjIyR@(MX` zn?*iUSrN-Kb_;!)IQ|AEa1|g79E}M$&AN7Old{^-9#px>MzB*RCr$>NnYG zk#7eTt%MCgAKUjJBZ2&PPse`&rP_InY+9ONbEKk~1P>3-=~H*SuEP~+!NP@0n^C>$ zVkkJTcAvfomjbnSc<|9|D~D4_D%#A2z(*zO;=qvZpJTsqV*sX}RTNe0vwt6Ehz!E* zmHCIenJ_79T`nEH_ygNYWC~a<6gE%W7s&#XwOo7x%>2DP?~X!Dk{JLfw~M_c`}wg&@-m1{5g5 zZLF=nT3Ykx4|D>Bj9L{Q!xyv@aL?eK^nF3}vwQ@s25Xd-&^fi3b?sYp6VahIRZ>=0A89q&4c6P4 zp6s`1xdMlB=(jj?8{a1+=0Ww8r%c{6_VwEB^qk84ZEjsPk**X*#N<0w0Q4#T!#qNZhaf3$xWjcH?8kcYG-G#FWZY*e7wjs zt8a8{8jn3#o(%G^mCaYOR%h8Cl8}XBbdUa-s{E}3Mm#1V@$pJz&WC~&^81m

    Wvq zv4$Ceg!`$zRdizz$OZ2V-cW|RT3Q5uS2%AXxbJ* zh3f$^JKLD zSu*T}ZzP6IC@6N5j}_ZbNauPEJDz!BsH3B!hoRq{pdI;^8K%i6+45$MV1xg$?X_!TI|fa z;@BzZwghN$Yj_&Zp5h{6ZolbT(MRWoty>l4yQ|JI*Gm#AG*7wtQ_DF?$s4&ug;e4- z?CPDR`w;EPu9Yk2P4~Faa}nt_27g4h_+{6IA=P7$nHPS<7yAex3mc%`Qe=Q$4}n3| z#?Y`Zi~e(%;?Y)cl|uCElPNQ9b^h#0h(r;_~Laaqd-9GenryB8r$6)mE zHBl6Lba>T`{j?<%y7aG@ay=nJzGa^-vIuVXH<3O*blDb6ox7~F>rt+Hu|6kS(9S9% zJC^)-OqC!JK_+FUhTxt;-#w^z>cXSzt`z|B)q>s~@K~G@M~sU5namYu!CXv8g|&FG zc+s%*w|{QFSY1g;DOvH7gEe9B9W-=&URC8>cp0gHu(CDdKT*w{(3bA5WuW~d4gTfb zwu4L3$1uhHnznilXheUw$G$|~tpJzD`ok8JeTC36_+23B!OBn%_(B|UZZ*$R*Zgjz zoabiUVyY3ao{Tc}S2nKCBVF2r*=o9BAp3bH*36 zW4Ql`hn|WsqbZUiXCCleyWnB4l*=x81Ln~Zvrk7&*6%>=coAT(rami$6$hL>P?nUo z-<2u%`BEvH(zodL;9AM+#(W}3|F`5*JYKt@>63hId6PDZDsXrGW~XO-cgkfuXUJ}f zrCDS>UIte}Yp+-Sf3; zt*My#5DDmj2^VS<-uXlwu+-DcNO+=b+UA-g56p1L*(+AzOX2LF??pq)=G*zw+Bu`%nyPKYInR?SAU zT6`F6y1PL%=te`O@AI`qam)+F3=84ucswsWlM;jZP(CFw7E-erzgTK~$ z36wEI&C6@1d5rcv6xh5Z!*iJf?))MkER%}$enAjjl4t02D9|?THbf-FQUt>S?f&p* z%ukDzBP7@6;v?4%?{Pecwpfhor>0u}c~Ae+Ps`p?{8|5}#!C0EqY` z%f!UQv-Jr2jd|$hs!e}(hxt3_ET9*bhB!I=^APBKymq^M$q7jaQgf6&aBlDDt%#rg zHQ49(Ix;=H^?>MqlZn?_P3=hxh5&azgvpxGsDEN8>fXsuMn?kFOOoUo=&DofaxEtI z&v7NHsz@KsW=~o>4w=F6vmaNSW*zW~>i<$jlc4J73h zbfclUn;nf|)st(*wV`FF0UpS}kJL$4z} zBg`K?KU1u=eZz`n|J=M-1qEi|H|+$6P8(daL(+7O=sk4uAA4OoX#hwO%SFemN*=+0 zN`XvjQQ)3&4V*WROPvqI;dOU@f6Hp zeQ(@QA?=|~5KNTLh~N+<5@ZWCq$1xf1h+E#_Lq$X?}Sj`5-o6XQOSw)vLGhZoVY7v zFOuaYSJ^kY09%gN-ROqc zrWgy-6%fZ75SigN?Jt`Qq5_oH$49b=L${K5wOY@-s1=8ktwyMBsgU2-!4Z77NaHD5 z^fnlq+!LXU=#(9%z*^`I=Hahx+V>TGesoyYk26PNXL5LHjC90U~}2@)+D6}FT&LI17+#brOxQk zZ3GbXiJ_&}=k>Y<2Km2c3a=(Fl}_Wy$jFeAkdQd5W8KJEq9p2DGMqentGOhZ?~Yz( zOv<&;goFW=R20)2!2x$zY9d3hqL_OQNl0#^wYPfCYmDIO=?fR@1&Lg-J5 zc+E^-)Gbk%!tV5Ve^mvoLjS-(hpPS)H~OGAut>7wIEu~4(dl!SJv}(6AvbYXDs=^& z{`xWTD0GXm$Lvu*L9>mEqR(UrCSIp_NcN)}wtltCM>L@K9DU&S&*fjj<(ItQ%s-Je zB`Y(hm={?*=reauD=z-k+i~VU;kREO>=>P}bk(Yz*kqYY?X^i!?6(DXP5rF4guURK zHd!P8+lDIgkR?dlb*Y<0Tb_mUE;X>ml=chCmnS$-cKMz2$_FsjzU5X{j-&YK7y+GN zIO(c>8c2ppsP&81eLn2O{YgR@Zkj()#9E}d;0&%5wvFAzVP5*~n^hCghoG$f>-hTD zsbFtE>9IZZY}J2m|3FLW=cqKtL;U-uu@Yy-SMDK+m`Sa}{cQ?F+eIn&=YFtjBam6? zfkq1#I!lr@?Ao>K&a!tTh%hcA^r-(DQgvsoN1C0s@7uS#Q7pJMU%s>4VDsif<&xJG z6!_+8dYQH#dpGqbOp>mqq-al?E}}?m&BId-4}BuQUgA;)LOyzYMD*ieca;{68eaCj zuZ77*K)P-$ub^;#SMRqiqirzaf3cqj8S!}xkV1-+}c6}%6i0}5aMn*ZOO>^4KJ z)iL#E#`T2GD&2{V`lqPIh`>p^c8aVmRdkMDs#g9^j9wZ$0wY@ z*ntqVYB4+NmCd98VSWPz-0&jP`}YIo`@yPG9-YyiQnnZAWrrNTIcQ~@K8HhnLTZbJ z#X^F*0!zL@eJxTHf}q%-V^d(vU-MCr__P7aP(0rmxhR27qLGlLBAxTj3)%}^5Y#!+ zVhj4s4G5d=cp9cFW-a53v}4aVJ@zA>$^%guA`djAq4yxgM;&8Q`ah>hnH!GMgGV<; z(O9ehr9h3%Z4-Eso4;u@sh=K@AMJ_V?04qO$cN{{$Z37M1=9FKa=TkBT>AW-JY95e zjPu9o*z;P*zONP*nhuqsC1|l;LA)+jA=l~6TC+U6kj;#1Id{ynA)=5lnpw9CxV|rS zdW(wY_j3}1OclZMaZZ=1F?}N08ew0)I7g}xXKL`Zu0V9_!&Xt zp7AR-5vD4PjXK=gAz)XY@puXQvq+fyBu6i73$hJYW4E@}aAmDb5)~SNO(DWDC3+3E zFTXPcTQ1}(3q%-Avs>m$8Z#7}sv?(WmyS;ma6rp!F*KAS7R|qjdrA^8&Rs$3{mR+8 zP1n8uj1Ci-thowvmN>wOo`3W>!dBmkBi-X-3Vu83CSg_B|LW5$-V_4Vz&v*U<^W=* zSQ96upAcRRIaL$4Qp|-jb91*~0IUFN!W27E^MwnM{0t?>$7NjQ@uNe7&nXt~;c=X^ z%-@Qe#_by&J%_*&NW&G&@V1Eff(5!{nvojsv7e^BJKF*^rp4G$>guBTFAyUa`TQAq z{cNeVHiwTuZKBgnLd`LVZ`r+txUYnSh!@{q{BP1yGKJ8uh8 zLbyN%f;x1`=EoY*$C#`t5jTvMcVr8qdKVp9?8KUy;sKQ{p!{-g0ywIz-6=gshv-Lw zR=4Smbv%1n;UEJ4>MU$fX+7s)t?2-09r+^qmx@crTl-^tP<92 zzwM=;>@_RNm1TS#qcO?O<0vcc?t2Lyt}u+rt-Rlp1RC$M1koWJZ&MAkB}>ZDO@ zs%EPmJ5Vgqn%@W!;&{*O-i?Ph9Ypse=r`p1q5VGf&b8Dq@7Q0rt=q?Vdp}G93n~y$LQt7-6*@ zdv~6QAKlCmSlNoH-IrFE>Y}(0Xz6w}+a?^LOmxu_6Z1ukssuf+_r^1He7a!3#b;;5 z+{v`u0-|4-X?3@~FJLWJ2%%>4PM=<|oWe0CCflvU2M6|7Lr!L;$7g6_GMDRUR(JO7 zu@B3#gd(D%bWQKo*JusE4*@zog1qPrCE52oCSqtt|7Xg1ba?wKwDI)!Y+5S7LT#3fQKY4%QRA$>lAWF& z0u(**nyU7Kd){rYO|=1nNNJsuDqiF4jZmhKXBYfKL?o8T&FA;N@Xee4@2 znYvhq6e%-SwmfC`pU+SYjg3imO)$9sT@yv>gn^Q$p$vc%R8|m_TaX9pBjJWu-=ZfxV+lN= zD0OPly%sG8FRi;#=x+tq zW7164$ z=j{2Gpech|5bconpR5qcbF^2K6c@ibHsFI~~LeTo)s(y621|!_L-Vnt`@`VNIBv=UItF0es`oYfZ^s5fKq3P`fmDzWUP^g; z0~}yYa6?N+XNSw~S#!U^Lb$6+A;(pH|7f#0iU)Mj%^ZyXWB0GQX?DU~3-4SJYz1MP zm}P=3*RC>o*|)872OK}tKVYewkgJ%51<+2Zn8#@(XG$hEEY7=eDF^lb-T7J6RBuTM z39!PO(^Br8>A5pR!u^ue32(l4zu0TVzGZ7$U(`TVNUkhWgdp{bu3_HS7YEe~Fo-DX zirAs0&>4EUn1cndT;@O!d0?WvyyddIfy zjG>Y*%-B5RpRK6n=cK-QoQow!_XRb-8PoE|S%l_z0kn>_49^rI>p&~SwU#|=;@n^C zf(w9mW3H$aHh>Du?&_iFr97IydL`Y_oVA$r8m%VxzWl~awFT#begUN&j`dyM*Neux z9QwF-*14iKfoS+ly8`A75%ii^!<45D3!WLz~;iQ;6S zh=%!)w_27B&x=u_hu?A%qRuy=`rH{YpQf`e@f45idVge(voz(;{8MeQmn-)td~lm( zPgpbixT9a-0Sba3k+?+RGFh3{-3|pLMu81^yk#*YM;S*uG7kA-E$ITHt*4XK--bc= zYxTr4={(C0wJRQNI}%BBtEt5YmL50n<=&*;x8x^;FxsYBgPQ^C^@^IQL6VX*Ev|)U z7sEY54N;^k*5&!)JEzZ_nf&=Ivx~_|JlL-~7YohJGu~t$r_5P1vnId?Q6U`fyVhrN z9kTO-ey#Z@1VkNqBy=EzHi*MKu7`;;VV<29i76@NX|D)vB{B$>k)aqSQ4QpCF{Cbn zh3fB&6SsjCxjbd{!Xa{|knTJaVm&DgTb)3d0gF0)JTY(r>6bL{-T}J#vS-6bA2{np z0(Z0)y`1QucAuE=y)t>E;@eR15R!}hx_z<#tPa1OX!KNU=9!h zUMvzCD9E4kgXr1Z->M>Yh(frIhx>g@_KX=X}$WNJ2#P^tA&Z#Ao5)4DEyYo zPA#kk#peF~`wprmGR!Vd$6fl?tsxH0Hy+8kVX`U%tjO3QeT-6(#>?ajSV1Eey7M5A=cTtlJ5E?9AReeqKgl#bWxotsBDU#-d%a|S z{X;fU&_C_r+XTTSU|YhL^CM=YyW)w$-mXvZ!6S#Y|>S)nwsenJhA`a&0~TX>1&XT6R^K0nW`8md|6 zIMR+(i>S{1$QNBHZoQ9dbpA3-j%(+-epogd_pN;Hq1=tWQJY2fkbQeXilAX?V;tH9 z*KO3*4S@_G_xp-ZoaPOAAD+la3Ld-foy7^nYq_$jk{Vi}g*MWA ztV@35Z&C;5%tR^5yqhwA<_H2?DKdTg;@VZ!r$2pih+4eoG%VVleN0R{?hx-Xt9L`* z#t}dd2Hb9%Sh}wV*uR^8RM&@FUwUxB=g$rjydxK5I;>AdD%;P8-(!ZAyg&{Fs_z~F zIAL_SP?Z+MnZM(5p>BlH)zHJm4xGInM7OcIy0y|`qTsJXo3oG(5^?a4`hmcJF&2=% z_S+@OY*YzNIf;>-nU9?t8FT)@{reD)+Abj}X|Q5{&wuH8d4>dN_Y)LC?{-=|P$V!D z3k4c|<>U%&)rE@|&7S&m3_WY5n;SQ6iXeD!UfEdd%fhOHsk{Vsa04nrk@g@YTcBSR zTYk@rnHr6mSR+e?4*HJj%b2kPK4lyDcS|5ro*|J^g83qz$!?L9*!8SH{ktEdjoa0K zw?(|^$$k_hO7-ki=GDPhPeC3yft{pLQTB-gj8Rm`wXGIuE^EEuy$g@k38}D8$h@;*z=Alh`m%Hpl*gTYsT7TNf z@R;cFA4xmG=5ai8{64R21uCekzz-Y8&e`Jz?il?Dg!~IzH(d2O(C+osAiGg*Q0?AD zb|O9=Z|I5cSp3U_B|SN#8txNHiQyWUcf5CwMFq7H!qz8_driY-b|dF^eE#)*8v7}T zHb+wA2|R`6*e!j2oYwEP}ij9uDB zBom>D-sx7C8tWY3g|^;|xpO}%&fIrE*Vkw4YXX@@lmuEF>L9xG3)N&NjpGQ|i3J|r z{~6VA|E8IidgR;Xmz+Kb$f$PLQIsqz$a_+)W+N4IGwA2f`k5UWjF>kJBITS%4Y2x!1pP3e3mHYRfWSAmRS-uOYSD3UR@5D8k7Uz+WeuM3bBs!E^o`J> zG%kDc^y$z~@tp4s(xI0xUnXsWa+Lv`tuir!7+(68qXl~?bKYO~ZYuXW>&j4R6^K;^ zmpreixImoHw{72k^6;_m_83Vny1Nr;y+(ngDCWTgCNem`-JG3Joq4C;_g`MaM1cq0va`e^&imMFN3&SP zsz~g~nv`k~cFD%RXXC~gH@N|uc>85nj5=4ATyjGzz!aN}_-!@TU&*G}S{^;y&FObIuP|bQSs%-mv$zkXVEdR;7 z``Gwu*u&$x;0J0!f8&c&u1HHs2{p8S+pUPT@N^Mw?sw1G|HsyM$5Y+EaYtmONGgg* zl#Gz*`thOR`!mPJrc(r*_&`=KiB6-^?RP@AFq2f&iQ^n zw4pW`EgSS>4-7=7ql4-+ey@~LS7OFlBohPXyj#l29~Te&s0l z$giG*<6B;JfB6>hy#sjoU?rvmEI`0)7=X(9M^vL+OMPmL_O58w#&5(c&NpF9$9um8Gr-><(fqBv-{lp3A}y^!+*Ldb zK)zC#Wq5$0HxYblYb!Xfv{*)HkB~=(YV)qTi4*uFidhg5liG zqhLn5*X*2*)p6)~$sdgR>A+1Cq6A+hubwRK_f_lDNN#p0+nW6gAZ%=Rx&gUu++E3` z2qq30DAod{=!imN+jNZ@e2yUBg*L4Ag?Y%OKHwM!K}xvmk&g1c(%ca4p2%>&KI9hn zEaI_)8Q1vPa`BnME65pX;0-^Dy(oP{fQ=AUBnEyR0kZH=cgWQcsG&#KPZnf zkNV}y$6)en%U}Y7&Uap$8}ZBq?PLk`oi-2x*`)c2F&haeRVC)meN^+AyLJ_wsdnu* zUb}{W0*a_`9zgrt5_105f%ssIzUroiEeu zS-}A&CM%6wC)(<-{8ome7X!Kk8tc7*ToB5!b%~O2vt|(BvuX1SDr!NERN25kegO)9 zrP?5wV@9TM$T~?C{2>pm(YC=|1+8(u!xRjo;F@3kNVVcZ+t@e^7@5AC*^M>OO)J5X zJuAmzMhpmSFi>V)yEf5EgpO->#~cWKrb)7GdU>Pn{CtRJ+ja;#h9L_X0l)SRAh|=@ z85bM-#7I2-u9d^Lzs9cK-eYjsgiXKXWBIelhDcEX0NTgPFertB*^}A`M6!B?i%O4F z$w{;U2e9=ZIF6z{7ov;lElGjk#&;ibd!C5{glxaJ=U7~FO3F(R*dI>zY7t7+kZ@Zt zLnlAGghbade&Y}=`Vc4>*2dJleu}Jt`?{_|0OO68u`||>sYb_H^S`kYW|XDO#Kpc- zD^hZIr*!fn{^z=d9EdJv30?f3dFfSE%C>l|L_Aa5dVqRTQ}>jJ%}5bF zaEavF?RQ2@+vp8ZQMjeES;?0jr@O8JQE*?S_2`6rA0)OsM@~>c?|Fh*6~yVWfmEzw zx6c7O#3dSpp#k2d5SY7$yhRJ&4jkS~wk^F{MY|b@v1okaWVfP|3%4tjo0cV2{A}9~ z7M6!Hx&^MExYz&Zyt+w?AZA)STspPx7FV#ITkggYauFTa$#H7ZLBC~WKD!W(t58`4 z^*1 zA*|3+BJ^B!-WP$RE=ecTte(-Mzvt&L!qWriOHcm(#XE?aDPeD(2jvfF@6-a1i2g@% z4rb;afyf2|%!y^7HGU3eM-)_4^Lf-vKqIz==j{{r{twH<+q)7t#XN|XE)8kpc1`jJ zWqiHaNq9@v>|9|mED`7kHf(2&%Se=J{baW9M^O@iwqj5daGpA4C(c5hZTSTc9#rxNYxg_34J>=ULxw;2|okslvN8b0y{umVcGn+1Pt#gob-0!*}pE) zk^^(h-N<0!&p8{;`z$Dk4Zu-kH-7h+kdPL*A_+cx`qWvBdOqht=>uA}L8!VGL^=re z_NoyU&)fNwf4@~2(Zbmwv8ywy?WxwS5&Ho3DE7d=YR5hS_<*Y71GRr~ZK7=kk?3Wx z0yr)ySwyN(%1UD!2u1ryxaG}1EIR@DKH%a01h4ffU|@4=YHBVzIYQl9)9u{b{j&Qb z4>8ZF=!SMg^&dDR*p2|6`~d{h@7oAIH)Jrblc3lmEyTi^b*|IF>h>@jOA#{DrPd&k> zvl5)L*v6r?UawB^cFVvDIAa(C^>q%Drv(?ZOG7hu-X@s00Moz3Ca`PrX)W{0+1rkn4n*Fdb!1M>kf@8S!qo456CqHfp%eGeX z8jLNcOXwy4t`p+@NNo+J&|}X!XkDR%NO%7|54)Cm77Y3xnN`Yes=y0tfcxCl>G!_$ zZYEGdfN)abzH9wr^63l+dR$)Z-Q;x}$jFJGY2eKp+?NL)V-z#9$3GO7vOSeJh5{_V zx`un;+kXNX;F@Qoa`X_%g8xIXG$K#?4qo(UU}EBd;^fu;jybo#0cI9H4_U)2 z$>049>^Kq@b--uf6vOBGXN7AP>^d2cg}!u1;$wz_u(T#4C*LW5Q+r-Vt(t);SOf(THE= zhl$DWQxS39_Wd?zMEhA_peW+Z={cb;SoEG z9v9VNl8J0N&;Us!1yLh`D9#1uKn5es3=EtoXh84w7kZ5&PF){AyV4oJ@K6tSIP-}# z932erb8q*!ss(u8Op&RCmb3EyQO}dGG0tRrfFaFWsGf+X?$;9@dJO$ZPR=u0Po{v@ z^8N=MVV7^0a4D>CqA-p;y!7WwW*@u?VQ?>Bza|rC$judD8|(pEuXlDFKk@&?!GxKU zchBx*;V(kB7zHN5TRv{~yD?mFA0SsCYQ7$J5?C}MJ}^LrJBgiWe*q441DF@g3318g zQ;@r~FbrhvVv+^tsq~VKQ{Y50*AhHKSQR1Xqk%~VR_ksK=b)xMOF7c`=bDBmS-OVC z_FjR92*)cdAeKIIpYd^vrpI+?R>NC&j`v4W z@Ui0o6mgM;;PmBu8M6pt&zI0TejN#76&1Zk;GY4U)=&%!Kad#7z{8z7%ncIalbLPH z3z-_E>9N-W*Y+jBpbLsZkK^1 zw^(gqQpX9FWY|36l*Um@-~7+HVDVw$2Ly}a{CN+Es)UvGA>p@U7ho(qh>?9WbdR~W znxJKx?`dO%7deKV39!x^IxtXlxg1DKoRGGX4A#zq&-A|?B+{i?L%soUZ9dYnUHsmf zZg?8@aJG}tZ;wNf3r0|!A$j?0PRrXzQhQYY-l}kY+oR5YY1!D}?^oI6iq`BBEbQlP z{6T%;?i6@13Cm7H>-N92OK*%mky`LU;DufXSybTXmAS7+hk&^vB8L3rQDn^^5TG32 zk_9Q0zVQK#FYsmUd8w^?b%A3yNk*u8hY01k9}p z2!Py(9)y-ku&*my-|JFj8CeH80Dva1tBsMCmi5h>H?drT z?MY+qVPH}4OY^xwFO??L@_@Hbo-5S@?+0&agTiDyA#mX7S63KV3__S8<+w;&-ZFCb zLcELN!-v=itJ~~DDe$h?d3n>SR*lL2t{m9Ec4+_BhqC?Mza$rcAM`n~7$bSn3_P4EDi@t_b&ixjDr$?8cOpH0fq zfS)j#%|a?9<_jCYzDid^Q_X7spcGCrWZ#L{?F`ArfJKX59|p?Vp9^gJpZL%S-#&6H zA!n<^fuL<_AG1pRoqRf<__(>1!Jp=sPD_(+^SB;Dv|uYhICQ4|;#URr4;R=-tpSi& zhC^PyTno)pj(0tYBwIoywrr~I(((-Lyc2n;WgDf(;H@p0w+ zi$P2sFcw3}Zn5<5EIY56MzF(}=0o{H$WG$;{U^cefOr~E`bCjqsKb{*!ke^UQO)00 zc-IYJH#A0&%5MhLs2VEmp{0_|qT5yv3H`K@6j9MNmEOJJNLq2{uF0Ro3Ru1@jn~ng z&T;*pcYSkzW2qaU$cA8WDf^mN18FdUx%f&;% zauE(4IV6=se~r2!i?FaZvabi8I*R)N4jBFad{rZU_^LwUG0Fr#G(ru)!bg-!oYcZ{ zI2(MELA{GH5|7InAcfjrSZkE*RHSuaE|~ofL3M#dZ`zRjJJzJkMKOMVB45qsDH={$ z7fcBal!rqNa!7M%frEOzWA@VO=AxXNN8n$A5I>a}yM1b9TgJPD1Y}!TE3x2R5wF?# z8e+>os6fjw1gFsT8%f>*V^1)B#3)u6vDXZQ^*|JWsvw`4a31B;vtTh_4GHo6XY1|j zMHOMfXtpxPk3luT1!913z^45`I}H7r%)fsAd`S4-icV3>1=VdrCSlEsqfvbMwd;HS zZtZ{r$g~bj336}s!YJDu=0Kr79xYXllxQb^=WgNF z?ALRrKN)ZnRe>ilNBa=vp*a6=FXHBdIg|U8E}RJ~^D#0m9%e2EB~FuV&n?b-ayD3k*k-xHdVHCpq%cADPUzL2KzRuBlp$o|KsJeB)! zSMoy4(dh5%IlGbpO#0zi%}9f@kjGsd>ao_q0=lei?hQ<21E^a0 z&Mm1Yd=4x$$o5;Sfjb2l7p0rv)-7_2jGO7H?`V1eo9q6Zz2@O3+Fa{7o-NNL{uHUR z?8p!pR*cH2le%Hsb?-} z_6K1=JF86&l|S`tAJKij^_0xsdiy_}Cs2Y0N0|wc>`N_hm9R@mMefb=ka@GV3aoMk zN2zt}(|j2x>P&YFMs*y!O;HvUKq$ZS2`}TXVj$B6l&%2Rm3OJj{wdB1q72SS=O%Sd zLmnd<>~&5NCv`=>e0dy-;Gb@5P^~C|9gk8J2*fV{4HahvBAgo{ZWj3-R&7N>ztT3< zHd753chPNsdJ)~y?g@(2&mrKP)fqOl0V$=2h1&t!`qq9Ts-2BSmWa9@h{meG`R~8I ze=HwlpFQ_-Bob1mZ1ytPd zXxxp?FDJeede97m*NA~3Z1UYIUoG_~^Z8tG#`^NB@vCmLQNgaR!$Q=0%h=)#0J#MG z7e4-9MvI4myn9zb=+uhRCr&I0MSR#S*W0I)faP7e@lk$%e0+XAwT*ph<(8A}==o<3eIs&<E4Y76B*Ob@mh4PRg8#_b^B;n(pkj*AqSj3Txcdf~nb1b+FXe?zTP1Mgt6e zgq`fOw`*%E^4x+dwfm{b!=vM(H*HoruE?c>bBT~O_WKeAqur9@&eZmiFTZGPLrbBU zI|W1Wd9f*QaH$4^t_TH_$IIh0L!biBs~vj8mG%s1GaU!)ukS;@%(F;@0xKS!kkUFMTr^+~c`Tmq)PUCS- z$FH#7*ZPHTg?9Pe&goAUjMlhk1qty-UrEE|qQIVuVm?p^BHO*Remg^@A<$Pp-1WsH z3+}a+wsa}nM(^gT7dq8(BZ;0n22;)H#ZyDE^;ta~n;|BFbNLa0x;vLXS%6+q%7&%M z0&l@gM>k*}`HAtw>hCFuPX&e9p*v9J@E(S8wBxFA)ua`;-XK!O<22tZIr1}{Y$n4B&oC&UXs9T$|+0?Ry-A5K z$X!bPktTDKOCw}KG=|3MBscedYLyAHhLx-jAHLZxYI^9Ex9bcg;Y3^!W3%K7jKK2E8p5@4d|U%k#$7#RmwB;&}*L-g~YdFuN(p5(bB zp2*p1JYDnhqTK0I#jEZI#rDt^v(nDCTw+$ zPwa24Oh<`G@)Iu-r~OlcITp(b{JV=ZSA_Z-(o z`d;dE_m%O9BU0-N%?h~}8VY!?ctIsjTGw=|AD>UxvNskuy-)5(N;?~_C#f1bMow!bYi@HgM)>z8xd28ShF z__TnBE$hQbOF`8?C+c8Evaq-bo1Y!Lmj`w%+`LqD>3gkkp})e@zt}Gn8EWX*l1Q)p z>jcX3fY|MQ5s+q)7!V@ic8{Ldkrx9oU((MhWW95WbY>}=|~sYxwd zYtMXj=~gXoLAq|emC@`oXU%ErjFfDy&-{e0n_)E^LMzPmT;Uz4Kp;iOJ~jn!x1;hb|m}+{?-d>qXah!g2z)!29tfLG^xX|_vkVFTtSi%L1i!rAeN%>fR*7v>JT@ENkQaGb=!~jQM?<$>4 zLb9NEwJ2WUZigVj6Jy?&CT6UiTiV4T$``3Ecanr0L!}olkw;M!FxY|D#Y`5@r4^r$ za2PjX_Rnr)=|i1yy+}jtKbFAfiNT&h=u|bDlWIJ|JD#T=H4|Kdxs##3)tm=4d+^Jb zM?Ai3WrHL&q2ZA@6h<$=Tk0TLYT_{0p>(Boi}Tm+Hf0&(jr?9M%Ke0dfQMRaUdZnr zkT)4=XRW`#Cso(}HmD6I>G2LD8)Ee86N+6a9tj{Xj zT>T6FuXK0;)#fLRWtKlT;_?BmUda3LtbqyP`^s#H-du^8CWUHq-=~X~3|yfXmA6TW zf1`xa*0En&b%#sQ4ki?#mKjgb6_=6ceLxBV;ve7UX}QuId4PE6TTK(; zSy96-oDct7d10a%NDxWIyI@zh;4Jg`=Ef`(ovs!0Uat9(6ZFg2gEyBJSpDjCU%y;z zMdYNtVvItmZE?YKwciLXycx?N_cGV8S!&rwN9W-kz zC&S>*b;fi24%Of<{;^(+D_SxY9Gt6y*T{1UUQF0u(xz-woGKyMBXmI-xjDD$s$0NM zoj-AE_e$dk+9ZV1aFR1RUEZ`VbO_IppU>aQvWh}mfvXjGEv72cH2fNCpDsrG2_rPU zDOcZ@nV5P!m4+TB?kKSO;m*xM#yh+_MZp~s1wm1+?_hv%1C~A-qV>brlLp0j*kG$bGUU9%fY9nm0FA+BK;zJTJq zQ5(Q_-@7M6%(VWM zQ`Z%$y?YO)@}?TrwV{oHoy; z$kgH zLK9dX^gXgmVT8yAYO^TBqG!9O71!du3OP&zx45@}*ghAcqT%@DldWmHI)Fru(sKv& zcl`O#@CpHT1EJv?0{F7^14B-dx$iB(c*8w&-ypaV+~Li^_PeC=M!a}&45ss7dC_z% z4p%)7B%A;#EoEipB0hHq2Zy+&FaC@0WXP5nz*FS5z-XHB5^%2-m~4T4TQ*;O$ze-? zWMoe;@P*zG+?MKH0+P8R@8#D){4UCKNG~6STLI-cg9M&-yx;B)EYs&myg3LU(laoF za$^Gj__!y}+`+3;MZnE{_l@?`?n4#Yt%5bzdm_R)%U4ba)fBf;p!3%|**k3?78mZm zIR2$BRzilbW`F;Pj)Ywo`P&GYP&D1U3P}0R*n>aeMjE$2jx3XWeSPEB!6@qq%`@Ki zj<)#zZkT+zb{B$93TVljzdXoOKO5wnEqHV4_KGCMV~68iJs(b7v{7z~(uQ-TAx+xY zxhT&B{#Yq89q?&i>-x3gx{${vwpFAVu_BEuqnEB_*ap*gT#ioO84VTf+Xzp4AF5Q| zn(t_doMi{$R@$H1MHmcpQAjKg1|iU-X{j?(2fEfL-YAJh=9U6n#B~p<($GsiK+|Yx z#iLpJjx@e}%NuI@OTR%|k?wfG_9PY78cQ2-{<#ToyL%fSAKw$R@M9CC^u&}nGZyXS z>*I3Lx1@(dOzv3s^0{a@(=f_jJb#|=l+`$!goH%fk;zRY;=Yehik5!OSefiGI!;Ng zy9M~ROkfsAY?0~oQR?!EhUXi~V*y+wBeL#+qGIUXzz}s|W*7<<{XH~?4|C;XFP-c} zX+hvmASOn#?tW+ZjcGM_C8%jusYf0P4Dj|NK}O4O&fa*m23<2=%%bScFd#Jti!Ow> zI{4)GI~9?Qb+K{=^o+fHE_nkZT(1;I)D9^A5l%p<%u{N=gM_T4|E-Z{2s)W)@K#F@d0S)`m$f>Zf&|nGLhC{|WHmUt{mUkx^OI!GOc?19^kQ9Wl%RJB8#@`$ zTZfP`a5WIJzFYucGdmkw+?=?H5^VLi-f26|K-}FMQTuq@@&q-aq-TQRdf9W;I?=KG ze*A-3zN#?E6jA2}f_d2$DzghO)zf%1^z^u4vPYL%!3>1Bu8fPc`>#mfICSKn>Lea+ zVe5`7TdmacDB*Z9y5s{A**fy# z?^Y{}SG3tFhb>j~Z_67ttXQDQ@2Q&2{=HtazlW#>q)1%DhSDTP-bZcpxDP&8L|&>2 zA1UB*hk1XEN9%}<&~d~3286K1Ztmx|HiwH?I2bK3G6fovb+8s+T85XEzy90 z$tS1dgs6v*!{CU7Ll~;)S=&*bh}P@0PJugNZ{CdAOFQsI!GSR!5rk2EON6MkdAH() zUzoLQGkF5&8-r!g7!biIPxRkHtsGog_YIg)U|BjKXg#G8{%LpV=xsD0ce~P#;;z7~ z`79Ob0G!8U-`0ogw&$JG@NOAH{$@+ ztM~WwW9Y?AW$D}~Z$*H6cYf9vfkV9gP7~5(4pqZQiSTgLf-)cLo8tsi4wFtuP8{f0 z3wD`!d}b%%s`4T^aN2+y*yM@YlBg%_a2-7b6aaZ}GvE@hsHj-smoHfz?X5xVL71+& z37qo+Q?^P}IW9?!qAw-z`VY*KUjUs>6`h&{D@@bP)5^teO5f{bvd6wT31d2CBT&oR zAuFv*W0tFs>ktA8{l9|%cmTD?$YavkO3K1Us;OoF9lsXmsSb8< z>riw~lHPOf_s7iVF83%><9Y<2oO;b0fi>RumV&%ANkG;97(Es*zXjv1QxJE zpyhKmt^tqjVnu|!$+BjceBF}=QwDi2XLrjJ;kLfCw$c+RA7#%d*DwXy77VE}>;$gg zVG0;zRD$6a`>|uPAnCiYUnAz<0t`4~;2P6&NHF`KYYd2TnLh%w99l8%R+^^Ha*db? zxW@vu%A2eZdmm>eIGV<~0ZUHwyZPtk38x#^V$fr0q; zsI9q5EBzq>vu7##1+BT}b12>mTu>xG+*!6;E45JGx- ziSx^%wQenCF~-bDHf>K)3Hv%6DPSQ-FYhneD8v8*_l_CvnOirzei5}^@(&nPGU&s| zkxkrrdbe35Bg`KPJjr7;oy>;e*t4FVr>kuO6&+ARJu&wiS)Od%vD5^5S%!D^JA%jn zGY`{OKcJ}#J7K*VfE4BOlnfX*NjdxOYu&`*EU3f$I~SK$eMzZ6{@DBr55(KSU$zBe z-1_+%aG+U+j8ey-xgqGqL+MpRm(1&W0Qr4R4AP?#G`dBR8*bg@XTBaGl&gA2~|{SPN_RrOpp%c^L^46;-5=Ui!~uxyUTXzGj<|jw)`x zWH^dHMlw`vYqeoDUPV5s4|w~rG4G&b_GS_o{SNUpah<@ZV(K=8NhrOa$ow`Jpm(*o z@u~lyxWi~E*+I|btUHQjQ#>}-uh^g^Io$7LlPv1OXnFnmTabv}oz}1yu3-S4FH4_* zkI}tOI7WGZBjdeoJ`;285cm3C4>s3_!|1V07B&?%^&_USL4WMjMgAH^%_ zWM%Y?w`+DwH2SM>{qH55?SzdFG74}`4~NxoY6_<8M0HoWQY_hTQYX9V#;!p*t8geg z`(k1VSxm>rlFK~3Pi@_6!osE=KzCU|xp$>;FVjvd9akke6dZI1!*G&$9j-?o4ssH< zu4!u#r@c8|Fb(?#Q-ZkQ@uG-*9y}>tO9%k+enX1zx_e!Y?>KB!49nGEU879z;jzqL zZ9vu&5hVkO#$n3QtTDiL+F>MFH1XZ-ZelS${(pD!Cs?1%w~X5HCQQJNYjIT96GCkd9u>5{w({NVL7jC~&_>G9G z$Lh1IM$lUaN!rOl>HlO0*1tpWR?l~>!)drPq~8Q~bOH$jBNSsp1HYS$sD-0|o0nI} z^XsSujgQbeQ!^}fjBwnR@g-C{R5?e*9L}Q&Ci$4koBZ)-S{~ms+*wp?zM*k6?XT~L zj(JT`nlO4k4h%ftaWwg9 zhZk<$E33DezT82Ob=_cU$?>SFHJUE1Ev9<~L$#2;n^CB6b-DnYF+hSBRCRBg8xN~$ z)Y7uZM}sQX#d2jSA8H#Fk$qwR0Qs<@i=mxZ6^bSMr#`I%jDce(MUdqKNhF`iBxBt1 z(|MLrq`IL&*f(Q?WI9XsCQRSgyCv6s!I44oe1=d*DroA%t}gg9dTBrC8|hR~+Yt|X z@OXM#om`m6OjY#867a%`2|ce4#N30X!>-_{z9Wj#?BxS!6_m?1PF*mas$n~ELJ?*! zfxEs7eoos2|o2KizHm8`rzA%FW)WkX~fp|ck#fYfr%(b0nU`787C{v7k zsoz_Y=i`gQH*)ZC4-qOOg8(Ga%yXLgf(AJq4r=CJrYQGe@a_y)wZx`4Q;lB@0f+`(L1v~AjYa38E4B+ z53|m{peiL!rp;!-7`Upw{y=I*WLTKHKyI3}QhrA(ym%Ecw~4)6kT6bO zIx(}Kx)i77H3Lx!V1QYf%X)&9mGwGZ3vLcEtKVPtORI+=or~A__ar-*q};nz7$d^h zk5^B$2OUF3thd2@3yxtW=ZkLhMDt3h{^N}Q;gy2b52)&TE`K}nw=6C_L##7b5k)Bk z;a);gm_#c^+i!at<(6gg5`r`?T{6CRa-rNl0=DD&TNqp!G$i3W0sf->jw93TxjWAW zTS_ENwIdlSfSoEZ^M2466=k#Dcg3q%a5hdFValqg zVrH3MxQK!WbvQUGFuFjj)iV_0hRO%%sBfJKg!YRexE(019#LN(%gN2WRQQ(2v~ zyuasO=alV%H;|A+as^}awwc}tEE(@GD{KyfPBCCYO6uKKE4qDu*1<%vC{Mn9+dvC0 zAQMuc%%9^LGe2((4CPiCeHTr24OfR(H%}mC zfSf&rS>;7-^Vt#8%;|<4f6B#*BdHeV!M!GRH!3{QCXOc;Ved-w(ghEjN!b=KH(=Y} zkzp=B4io<>&@*x7cRbH&1%E^okpO6n(2zz353vk=`R{=_B&aX*av0ggt12@LdSOvsA zm+m5VA@s`KWfxxB;Y;9>#Op$DEViV*lQ*BGWIP&+)G?Ef|^-Ls)vPWu;j zeRIWL-@t$u4Wh8+tx^jm6H*JC6J8S&O8TtlH}wnjr*Ivc&V8jsO^0_`s7uQPT#*JU#=bg6{>q{npbfZtI`Oj=n_s z)jk|2P2hyxujK^X>;nfI=|!PYys;Ls*t(GA2;_0ZWCvTqU!tbJ{yDxNtIW2brGaHY zv2XLE^HC!$&842Nn|yo=3`V1JGfekf=mZWaaX)N3)6_;Dn;3nPk*?QllH--737^7o zJIz}c3in$s?BhN+koC>j-{58<|873H5f9G^kA~|ZSMYD%G&eX)Hn{S=@xU8Qd{pZ# zS==_z^2X?qI>=yHtu-amx*S+B2Ll}YrJ2I81&|8aVKYj3+kDwcXAo)(#rhYLekYJz zLAS)SsJDVr7Qj5N!iWrdbU9%7Dc($=@)JB zSAwke3s7sQT#b6Zc&+`Qaxa`JlF$%k+YMDeyWfPT%;aiI^A@M}aiKsOrT8jO@zv;=m{6Cr9Z?&pcbb>mGtGm> z7VY6$=aq;ePX%t}^rAX_j~Z}^SDT)C?r*(#(Pu>pB>D(Gngj;d(vc2uP_#zv7*$t- zPVy0J+*$(v{d-HE43(_>aew2Gt4A3=h=u6sR(jbA2*MeVMuhoh8c{N1B#(LZLY_F4Br ziU8GXEh|dg@bGZH?HG7JBjbQb&Eqh+y^dI>z}lNC51#9I##~9xHH!goK47P4-H`ZRS11*k5V56Gf_=zYMNk9knhtDm+b+ zj-Bl%Auf7)XyX870oPz!C*pnSe zJvlfhNZ3N-6Oq#rC{ytG7A79{`Vsb{wOB zOFzsvN|NOBN$jsaLrQwmvxAEB2-vgweBe2K8`Nu5 zJH}k6E#2z(9O7g7K=z*vTB?tz9H9Krc&|4F3W-dZZ?cR&(9~ao@KyaUy+N#9X_$;t zx|Z+au*fF_-=b{@OR8CqbVyxg<_yZTf%qU-Eug;a_tM}iJV(=L@)M-i0-C0qFhn#D z)r&2)%?u;H5z3uNaRltiorOv37Ib20&hkhR>%3E;@6GzJ6I@%sKv;5hlYo_;v*_#!e)T z&yjtgeI?k%uM647xLbwtdEwj#0bRdQ^6Sg#aEkugd!m945Hh&$9EL9Ql-JW)N2REA z!H0oAj#1dfj{fmgQ;R@i2VFBNnC+rD;bcfyo_cT-eI!=(yy`IoVnBV zc$^#4qRkEXGQQYc4t`W1K>%BCpE!BM+m zWb*o22Tl;BGS0%ElJ{s5TOSz}bu>8g`i&cTH0~{E zKoe^x;S?%DtkZv<)w%nQkF#H&Ag2_g3Y`k#s1%G(Qx;5=a0wTAjjrDW_-1+$mkbe) z)kV9a0G2igt5}~w29ZUe%jErzvg5*FI4lT5sp<9DooL6!l8*|vLoknaifl7vh~=Ex zogVzq&i|jy4G)$CK)8C7f50xEQ^b^+5GfP-%38B|?*^rIbL{EpzGUJIpHSa9%FozS zQkqelJm+#HSDq>b(l8J~@S5M*EJafFg>bD>E`EOgvt-7n(Olg(41bTk3?AC5HV6eV1)$-gyZeqn`o`*;Zo4hYUikX2Y$TtW zaVvUy{R+DQX_1GqGieWOo(YZ@y#PAm!9U*5F&8+WU4C83{zK*Y_Pd2Hn{7htp7JX& zX67KMYqKGa!7mG|u{*yKP5gWkDM#J!NlCj4s)TgIy}P>Z*PC0E`RiZ*4f5k)K7>Cf zO1JR$9k5IjQ|?K6bghLlNGDR0^@#rNczHEU%ale7Z#W3!_?^!vXsR}QwBLpUM&iFV zjvnGqvVr5TBg?Uk$rq=&?=#Ktf0?7ju(T3mW0PqjwQ?!GFDze)neSa27Pb~-?WH_K znWCM#kz$3?dl;!@jP*!)*;+IruCj(=Rg4W)G&Hz)c(TBbAgqV&`+iET2WN$ag)es- zNt>UFuAW5JJ zOhY>i)deM;8bk(m=gffDc`k)UeD%z#Tvtnv(NJ{ z8lngIfYR*4%i_JGi+VvfinOY~e=4UgQ_PH;{1b0az;6=$;1TNd-Tvzzexk0Dn_$k4v8xgVdzj{YvgrA0FQ0yf*i>6Z(d+ z4c+u)?0)?`_KUgtpBOaR(-_-u6NRV7wf6KD0zn%OOwCTX)}|_y8lG0r`lZ*I{9FPxmSo>4RyB#adyAt@Y#bhaDAgUq zO$wClAH}DU*W*I3#Y$0VRm^({sw4lp+mieTcA=75|F*6y{Um^Dn}AbLO5y|IK} zlTYLxr+M?%CRUHYoK99%D6xY|(^G5qTrdW-d5qnv9Bn-mIVajEV#J9^0sfka#PtjK z9ThZ}KWIjgcb~072z{LYD8S#o(;L*lewpWe{Z%`>LQv31 zU6?7-0DHhwrcJI-vkgfvTjWd#{|~6!|Je~YO}wN7vl`nVVTb0oiMHC3^S+HH2FZIz zb7)nBmMma!?7$V+<T_Niy#f!B~v zIjI?@^`d_%$R&aykdR`!-Jv!?OV7-64gdE)KFdG~_vtdQ*Ge)yN*{{X+!rq!bwc}` za2uRdR^9n68cjtOLk;R=7LZU%RWUp`7$W;2sRwSL6$aIaxiQ&W#>O#LaOtFsWS&|* z)t7dGYiw3eHG;qHJk$^Rqzfw>;Fy4)ZP2d`va|ei;D_!l^#cVpW4UC{SMn8 zcE4YU)WmTQy@T2i3w=M{_9*SG*C&bHn7N+B;eOb1q$M7^4wqxs{2PMg>X{2P%TW-| z3G9?+5GCoqUkT*!?|~!S+L1}~rnaCyBXJ9Dg&bW_Pca&;MmwZ6STm&1qysllnT zNvw{F91A^(0H+?Sv!>G~s5Ne&Bs*YIbB)W11CL`0JYh1aP8afxfBne>@rSj@=Dm5a zy*d@lxba}l5b8-q;4UVejK-B?EOqNJbWqrwkgh zewYElp0j=*j=${F-*G;CYaMtFaeos%wpIjtUJeWZtpN+bPpUy8bCO*Y@ypE52O9lW zfY;pt+@dnEoczXS_?OSj8r1HJxkdiAT|CAlFo7J=YJoWzMY0;UGVz%^ctDkRL5zvb)6m}5m+9DAomYIL@Ooj0j&~4@R>jc{))7MX|WtJS%FZ>19~2dE!N-M zhvJt)AbS;g!NuObibr07=kzfp56!-?rN_6-9^lc@ptVR4dHnj&|F)*r0r`zgF%9(m zJ3AzyZ~UUFKdO<1$JS_&=}u7I?{ zr_-O>-M>-Ph6y)-zm3U?Hc@IvCJgqQ6atT!n?^XkS|3%E#@40fo+dVDLu2q&u-xpn zSI_BCK1FfQ32c$t!PUnEI6+PUDvRBipahhh>pby2DG2z>^&4QJ_SNRcqq2pP^(h<6 zJKWQVN$^<-<0qa;{DNa6neV>m#H@u5XAOi5__2rW0tpxUxQqY|Mzs@TDt2c+puTZS`(gg1GGTEW)B=+Q0sP?_;2!gkE+N7xbR7h+PMh&RP1hOOZYz>tSu+42J$Pt| zv|IBe%ViZhRSolX5TB5{qm+~sNQUEQJyC4tn@k)XTA3CcFx$$yedMX7jcKU?3if_G z(mkp9F*rK{UmdeRvhe0&R62~QCtYd$*cL_IOTCG#+4rQT#BHi584{_8MFKlweSOBu zIR?d8wpQ6f}a4m3|`|;q26+pB?H){_;kq}N5 zM`jUvWHH%ry?Vd(QdWL|u8zVyuh!{=*GxR8v*pAoC)MXdAC*}C{0>e*lOXMRbY8k0 zQ3YvKh*Dp~^m4;Vv2TI@l1Pb(!pEnRTVZ?K@m4UMFt5U2m;2fU*qlQ)_4*lA}weVw8KQBoq z?o{ZR3rRv{UC4fjoHrWR4R-*d2@P}XlLYBS;qXsy3SA5x6Ur`ghxX(aoJPjI=|BD5 zqO_msC+|qSh*D!MGmlO~&WGT^UvRok0?*yiXNi>RKpWVbS{C#33tt*XPX4UUDmrsn z=-{ar8F=F5bwawIqh`{j@WyrLpW;2wJqjj`nq)gymo>x-3o6(3Tl!&XF6%4?h@*p~ zXmU@)#MvvdxKH+0LBjXCEj604K3xyhjg>F9#d$uy%)lFK0Q zdwnhvhjNR7?<&kF(g8+b)6AAY z(MX@>MXBJiC!?20Zaa{-Z*u`O?X`m){JIyH3*%FviK1s+vMFA!@at|F&pCXnPPMrF zY-rX}*J2YJS?a=!bGr|9RDl%?Jatx^qc#RzrJ-Xdg32|TrGR6C>$`ztnP-NS*)cB| z^#@sKR$XQY&RX+R0uvMd9^m)QE(1;f`jaLi!Ax)&YHy?F3-fn*=Hq zD`Yy9G@fl>$tCO|6e?sD3XWtxei%P*UmeQK5^$F1UBCusVw>SYy$KUZJNgdIh$1`o zk@3mqb9+2hMqES0uLNaT>j30`%m9@L0YlEBQZn;Lw56yYtorzgz)IYH5-iuy={xZz?vK_I6G~~u zfCEK*Lz4}tUiHb%pf;_+xm&zj+66{FlJSh0YH~I20E83kzYV{4jWhP{B^vd`kI;R) zPG4(j+W%n!XiQ;~=Lix%a_(rBRSxg+H7J!1aVL z<~N^hUp<(gRA5#UCR+&xTVP$1&%Wt>NT!TD@mmS61R`g}hQ8oX-_0!1X8+$k*^iWM z*!;_djQx0*D*LW;2St#F;}^N0*l~mxh-X=KzM?dH==oz5=2@ThFkJr)4h@m&RmEGF z)=SJQL&qaqyIM&^Cx;2DFz{Ty5eC$9515>_Ouxi_fH`M}Uk6}x_bhs&#Gz06K{YD= zL2JjQMvslPWn<^u_DbDU<6ir+9;rrub{nWdM}HDH7zZ)*g-Koe9~=^~H7di01+tf5L}Yj*r9k1}RBJ>Z4pPiu zs{G_wcWzh`S5MkMxlY$sq5x(Ef|%sGAy{cf~Kki zG(96Zv2}n_beS%~4QAOKPo191iTA!t`b~O$Obri_2OZ$Ukt~@HE~9y;rt;10&H{A* zO}7sM&g|1qU=s}lNkSc~BU+Zw7P$)G4jtB`XEF$`+C(2@8IK_{qX?g+#YARFJF2K z8Ymeq?bf6#U*Trx_cdrLHj~edP-G+CAcpBr79=T_NRP_eSzGg7hb@NbpgdU%6k=1P z&Pn(L7ym6#akYZaf_LYE{rf|Rr;Fo*ZviQKOE>a8@(sxR_ClxT@n+50Q0Ir|N0dgoO;@$+ z>_0h?b|J<&CX+;<>LZv@4Ne2DS97k>EMmt${XDD!PB7+`98x>;JJl7Q%nMx%Q8>)3 zm#Jknk866o_Qyz&Xqc;hiUO*S8*?$-qiHV+e2w!H>BkguCBMZ^o`zmi)B?(aY?wGc z>NmSVT4Zx>z%_*O<`a;&UDm}!=_B)ZcSy{ggd&iYELqbG`A=XAnNrM;0uuCd)gF*a zGzE!&=$SdVPhD^m<{wozYeQ&leXk}qg#-GF{}{Dii-H5MXkJD&T_5}G>youEMb_V| zZds(Jxz$+CXKWhayOXn*9!s}_c4`VX!|qkjTc|wO&^CgLG5gN)PjBaDY}^WudQ>w1 z*|XRJ%j|z=YOpH!_`z{!_upei<`!E#zj?>kMn&RCJA*@afl1o?D@p7rli6_`N>@sF`xm+i1=9JiS#3@de zPLji$P{0JqF6zocFFFzes#a*kZ_sy|v$L(^6Izb^uRvi3aTdVj2IA7w+s;97QtTws z^w&74cyO1Uy}b%Ot2y~+UChC1rHdC)pOOtCL<>j7g9QRIY~fTl48%FQrrAID((-je zxKmq$uzsahX%ISlju&_vtbz>G8lo1Ljy%%JR?l+sXvJHs?0!psYr*YWp81a?Z1()M zZY91AFI?W0X#E`Eznz@i14nIbz2uUfFwqYP)uGsaxAe1`*6E!rHFjy?bZ4S}%G zHblkPxqm*_PD?z-7Tr(}d?DMC#WDLS*w~WE|A(#Xj;FeR-#Jl6$xJG%WJW4vcThqd z6bD%mg=1zG8Ak~%N=1YtvtyUNm5P*oA|ooYR~cpGcfUo?)ARlP)2p6(>YUH#{l3R_ zU-xxo+U3dMQei%l1C51RZsgJVnuGrmwT8&Rn+-fqZqBtlxejxIRfqi%ENP#HN>_0K z+uj%+y!o>blJM<>eWIbq?;+^E7!M&oo_`>mX&d>#*}J{VKG;76d*MP3ECYT72h_5z;;4~}0*qo~9QnjnA%94Q@J zcD&X%2UP)SyZ3uJ2yK0zoIBC^hAu4o#=i1)y_h)kSX=dxCi628KKWHK7aCV_mh<$T zOAa3tm-#v)mOV>g$J7Bz)b{`pb$Hxg0AKs-z^rJ5mUcd)KDCEtIy%OnWy0SmBS2#so50;XMR;5C2&hZA$k*Y=JHga;$-D|<&w+> zZq%Zi0#WyU;e{{Tx16-##*OPXmZ1RKVQ@>nic4{&M)HPjSbNavAHN*fIlZk2Y}y?F zwpmU2#OxLL)@ZYe*vRxkhH~2-i|z)ygwM;|PC@xu*+45Tt~D-q7D>B)u@)NiW&>9 zxdnas#vM&sIR~j9^Y*6M7{#o+Qyfp(1nY^c9wayuY+BqUCyo-$BxFA$ zeSLkSC5qN>b}b1eN6v=sLb^1-xp|rOyy093b=GeFQTpWL!~9^r%gA(Xh%oCf@*%Pv5P!`4OUzsEueAkQyf>QAoWpu}8e zo&IRpD~u938%QWNZv^}#_ksm!NDPHZ4j0fVdc9wivo+12K`g>72EPfKkvYqdrej(t zH9PKl4`fu;@myd6zK1_q!xgEBz9xkY4Yl6E(1hmh3tQN%b&K0)^F)}$9uRx!D<=ox zOqrK^`xOPiDY`8OVcfK3L1`u7A2Gs;o>&CqWA_q=)%(y9)L!98y#H&dVBFWU>q5{i z7~spf4fg&jz@UlvrosmJ#737c{oD^;HKj$-w8?%?2F=EFtGJkgqy0s4MH@4XDLo{q zlRi+V#QL;cPXIVAOTUV)A?7Jswf-Fxejl1!&}X(q-j@HmZaH@+E^gw1-uuKb)S83(>Ul5mq0dOwi6BlA zae!fyOSra59weipIq{|AsOEdfCAK zP;Ob9B)^I}M*AOK4&DgZK-&J85%QaI(2g7dUFXXC5xKbjiH7;bENqENHi14L)D%ea z?A?mmG&^{iIH=A9deC&t$h)O(9nIqv=NcgW^{gP90MTK~jga5)_R1|I?v5aG97CL0bM0fARJ-OiY$=qb~q>#paj$D~<1N3Ub^9^E~qB%&G9Owu-yR1w-3-)W|+=j^gFJKD5 z_8^>m&kUsI(AcDS;tY}*;Jrih3)DzDKuz@&v!ub95ot$T&UYn-Wsl4}a!cD8$Aq#~ zU%tN9{`w}TC7?zsdDoKLPWBwp_j&zZlTfaoqQ%8w)uw4nRQh6f>S6i%K~xS9xFSG8 zfaHalH#0LbB9QAdDav`6v$!aw*B~dDE#TR&^q;eJ0gW&PFEaiaVJ1fTi=2HDFb#|~ zRYn{o6QsP=lG60N*Ga@i(hgoqzA+i4{@JeFxkNl$w@6VSg?J_Lp}%;d=p+k4iUse~ z>K*;@3tB|MN>an*!3nJ_Rho`0Pk{e|B;&~JlLj6Xq?R+n;sjDfCR0M(a|an}&cwfi zF-j*?@yze3{C>RP(ZAXut8H;72NsU_gZ;^=%fkj0PhsNl{@Jl8b1&GekA6NzaWJA$ zwfF!*W}_*MDto67pC`L5Z7T@t!^Em{sKh^D3Z8Rnj6Y_K{5CThGdABNWjo(R9!M6j z1_1otfHjV(Xv<%Li3#}}T&NysTzg7bGOf^$0>HAuD6VcNC1CX!SbE_iFV62=!Ekn` zx)A!4u_fYzqJ=TdeR7C@z!E0I4hE?12!>7*a+s-pr?0Xj+$^*1=wv+}0K6y$kIi8g%d1>zARiXUqMh82Xw4 z#%V^_xDqg49aLIx^L!Ao84JJMzA&yfHe8=`m3qKrqk<)iOf1L z4FfNfc0e;fD$s5MW?jE|4H?U3;G>~$L++TCeGFYv-p9l8KMMQ>Sl$BXFBuFN`~XFL z{*x3JbP*54b{}6^+ z{PGrVXr}UeG(k(WZL{Aw` z#3^+nqU52QP`E>aXMw8!zp>`}TSIy`Qu3iK~C}M(+G~M1{@# zoETy`uXP7Vh2srm?fvrab_%Isj6&2JIJ#jxHRAiMd7?Vrh}4rQ;*^DNz6=Lz&&{Tg zK8dyP^SfBu3B}TD<~Y?q=dD(Vbb}ROA$m@GgBdc?MJAtaf{0LzSzf4EwgYG7(=`yF z8-cR7VJuiYwE(1PCmvsRgG<4z?n{ODG%0Y5VMx|<0JmGm85V>VF{xwuidLsIx>H5- z1{L%7Z|#&lU{RT?@)B6Gi}MNQCxJ}DnjBZ##atGo01~0nuss6UMZ|y(cpegvO+2OJ z;iJLYmmA=zQ)9dimkyKD7WHZLs;(lm>NB%BWuXU7#EC#IOdgB z^-b}e?o=Pseu}52J(dsGEk#_sWo<0+5$v*Xxl)zGwC_E5dj-QkLG;JO`OH29$C!8f zrW1PW!6w{}K2%Tz@$ezIy~`4fswOwk=SDFIN&K9Av85ASW746oa6J~a*Buy+B|0U~ zO;>V1o*HeVFMQ!y9z66&S4;LK2oyXhWPApNTOhLQzA~#CZsMan2bg%I{(IUsZ$F4g3NX*G{Xm7GuuReyqz#*ZcmzYQeu{8zGGRP~B|A;4=fhT_ zA%hJ|E%Zqyw0d{}d{g9&$s8qyom+_296B_0ut>T9gPSWJv#?T|2k_@h9| zf0X~3q@d_U)PqJ9j&Z1In7pa7oJ+Ef6&I%VW{6)C4c_6{Qq3ONg_k^m-W0 zXoz0abDYmqbQ{!ZsI>$fC_|?F`f;JY%!$!*zthBb-&?bZLD1`OGzm5hm%B`yeIrVB z&C7nlBct{*aA7lgoV24#Kjl585(EhJUl$4DGE&yyX80!>No{R>NpCu614YoSxhgIw zH9at&u66nxYYNna=b)JXjYc!eOei~zFb@6w`M?eP_Wrt!-G(6#tN-BNBqXiOTTAm` z@9EDNuloiH^pgB#4Y4r4_5jrh{_2HMm}accoPSJ;Rl(&>(!h(gMy22=Oh-14XjLrs z??Y@JWz{ixMC9Mvc=aSMQ>ztVb*;|QORhDPCOBy4L8yI`47HDdPN8X9`p+m| z1Js4p@Qo~7!MupyPMka9)5?Fo;b3v>J_;G$<)Z=C7u1Tek}$NF0Gp@JU6?5|OG5{RK2!-Tmj z1I9<}%ccd6rdcK5=Gd4U=d^LjjpX(7ZF4JkjEqYHio zzIlasR!%~CwWj_G%^BI*je$eJckVB988n@kqW-u$X-Cfzg6cB1_c1(eldR^pX9Mn3 z0fe1u&#;|bf8P||es~Bei^Avq*X|1T2c}p(`NlZ{m`Y?e-y_SR{Ct6C7l3`Yv^W&- zK3d9iKpXI8G-B@s=Ft(MHr?x+nSK;h!U693p6;TXnh1IZ$^K{?=dJ;gvY!Qk%7@QC z0V4kFk^B489u&O6X&5Q75-Q1~MSzJ_C{4xke6(#&To>2@8u=Ct@#|A+d-&XcyW7b9%$LZJYeU? z+wCCx$)btH??2-;w8tAN16+K9P6i+c;*II}yDT|R-dF?g@l0E4Bj>!mu+7Ry)G}1@ z{P72S>547@C&46X7DSZyGxK1kSG3W2H(=(qNTiFftwL68a)3LPOlfm#@mtWpO2!qi z>mMF3{Gu|h66bk&;sSjYY*s~=zm|kYDjhUXu1xLb>+^Es^l4T050niszde1k4?w_! zxZ+d?-7vEO1J(oXUrgHc@4@I`rEXjM;VQV5D4GcW(Kx0)Wr$_B!fQzD)V+E06oy+# zlY^YwF|}e$8O|lzN7+r-T?~W@h69^mEdh*@XH+o5N@kt>bDS{dzPb;2jCF#rWe*n{ z%V0~&7Ivl=DOSg+S=4%gfSvrURn}IX9shZZ zM+_nMURC~p;JB3s9F~qLHe?aHm(Y9E(b4fK;|<^4Vc#%Kj0Fqp-1)o!7|J9>ia&yz z-mG`26=qOn;va_t%EY_ge+?*W%YiDdmX|bVgeOenJ@vB_U@iIqWBhF^nZwh}L}wbk zZiRjO8Um}zI>7J20j$GftM+9r9a)&D(vPtDSbFKXepG0_M(UENga;r-kPll-X1a97 zfJqAcxE3vWu~^fu?eIadT{My(z5}7{DL{-Vbj#)2#L{8^CYtPQ;0TJj<7N6)pVg(# zxC0M)Zpky7{rt44Xnv9+)*`5JtL73Sfx2m-8CaGbI@Gq|F8$UaWF; zxgs(p(wh02Y6WAj90f<)XQ0DhhaXo$^xXgkaS0mtmL&GATRY%TuV?f`gYqzM$>{PR zz0GB!!5MRD(9#AeuzbODaiHdhGikNnc?{8-$T5Z*#px#K}JJX;% z##T(?(l;wnkm)|yNSz7vvl8Q{C%)3_b4orUKOUOq)v3hAdjuXV>j0{UUB%CLPS1^o zUfG>lL}^K#hKeRFt9V$Xf+Ef~>Vx)#B)mWEHQLZW+(@@!uo$#}FaG$#`Q zW+r;+KVKZ}6FeWw(fPXVPyS<}6Ka2~d6NA2sOmas6VzLwA-$dU9Pu5OnDABaN1k8$ zT-TzyQZcx37(zpei;^6Q)J*gW)xGbCchFAWDwLi4%X7F@c<2?2*c?(Kw(rTc)vZyz zJmKB*3_@=wL^t+~%oUC!uQ1J@j;d`Av6(Ym?ucg)XxuV_rD5`Sl?VJfqaLL_-$q|O zat6;c(Np19Q*L0|B-XqhMII>Bg1Q`VFUCMq`2j5D4T&3!?t4U75>a{FV=!%;!7Vy( zfFC%$BuYpLTv-oU`=SWV2!?w@Ez9io&$6K`CUWel0zHZwc&nkD+y0IoJIj@F;mxk?OWRAo9L`euMErXeZ8gPs;Gv z{LL&3E8>n1k)C3vMD^2yJAQ&g)yie-`^C-_;ocAUu_erF&eSZ7!2+*7u-@~^Q|608 zx9^nym$u1Dr-WX%?S&{#{?&7ySmH0(b#ZfpygUNs4VZ-7y{UR#Jr18S^J`(E0A%9dy83aLy4^u! z4~>(T+FT{t5o^NPvKrZdaO=jg6dWE<@N z;O472$rqJD6ORs_T`hyu4^o*58Rrr1bAgYdsf2F!JvanUc88^Y@`%eOSAwjS!PTz3 z(R_pNftT|7JODTr6BHC2OMB(@aB8lVjh0P@;`$gM%_p+vYJpe`EgL&K8tB?LJwECI zDkSZ|nqnatG))8uyl{jSt}^Qdk-|BUfd*PC+tL-mUS=S*okNPcK0o^-_`Fl-m@4Ke zS)+H4i)&P#Y}|v+%mr%L`Li$v&c&Ia%!*%L3$@z5cV)P6jj=YLF9L}n+U-G1Obn^) zrb)r{j%3W#e8F(W@N!lU1Kaj36bSB)KuMK39}fJ!mLuglxYr{4_8rPN&pHa5*`{+a zJNko%uJxA08W?DWKHB5`r@3O$!p0Xu;h|5h*Q%^?fzC5(kO`B=qCO2>L)8>b7})UUQ3qza5! zp;ZC$BKlmLUO^EANs=dZizUkp>?rIsMP9R`55-?(Zc7PRD(LozRs`P$zSkc~%Ig`kWq~sgs^dZQX=_k!y;V$mm9wbeW*G%bu zH8W3vUeVg&nCol;!vat<$Zh4&IcgC| zS&!eEsW5*-ytu~qdvs6xT=`sC>oJR~s0yK`HoMf%j?m4;SvOeJ>;&9pxAWE3kAVWE z;~$<4L@Ed&wuXvY8Y*_+7KSI9d?qnF_W(w@p(h^Pz#SX$nK z>mc=jh*ZHoa*aZOZo20mcvOh}3L4Gkw6Nr5<}oHklo!+#p2I zT^t`g^^NW=a6lpZeQlcps&QRi-LtN)uD%^?ij2m+pyrVaD?4+^_=5p?zDx5(lM8qQ zQ}$V3q#=9Pq&M~9{y?!eVC!W7XOZf@M?q_~;B6nr_qxB?R zhryd0iIEIlpr|qaQ@?2F*)z;LXaGYm`N^11(@YnA$?tSTMU7}*6{7wj(;gsY9I4RV z2^2vlbv~lD($8vcpXrko%$qq6RKps{FShNrZr7fIUA(A>2z`+&?jmL4veAd%u4I3| z!bG%CtS1|Ob1g$PoAoxvtD;2r^mC5L*^}-E#&|^5B}QUJ0y}+D)bP4U(gkT2ZXew2 zwta^bp--ep^rBjSF`G9j<)`!XBbbIrl(lUnc$IoW2p!`S!oR=AhiWCiA3< z-hb35)wdJjA)^LH)ogIMtLPbn54v)B)Tj1$jmxXje}h%TZkldY)0!+VH6T2mpmgOO z@rKl+J9714R4zO1Kv_8;YL4vd0VHoV;f08_JpcR;c8kE z4azqftdGF0aYf+&`W-@e`2biD?6Zy6UAvV4EC4l5ydC<$|z#sizelqUs7pUeihvAk*CPeRp>>W)aP2 z;}2!HJ!aQFRW_9O9TZaXKpfyepAIY|I)cebFxr-VqV@a-0<>Udzw9eHE%ShnUs~66 z?02;PDZtl45FkxdLB&)60tMH)hyoWuT}VpoIKdv6M7H>VjP^Xi4vG6aH?qC-hT=c1tU|Bkib(l*d(Ml^ z$0?@lzAbiY zxV>uJKqJDb(e)$f>=(QPy3m9CP=*bNzj(x`7ntyQu)kl?O>n;n^hC9JXWNp)WmzM0 zRXS;MbSY3Uk3S$xe7E)f%qg>$zhnI0Jep!~>WJ~!fH1JcG6=1?ezfb>LQ$;%NhE{( zmM#6s=d(bzF=bbS(2-aUf66b;(zM;6#xyG&RZL&|U|+F8a!OFIW$7W?z4?ZRdOP^y z7*37dJP;d2FVs2%n=kF9m%alY6|SVGp@08GOOCC|O@UW>4p39)!3-#QlLnx}X`2?| z_y+E5fnvZ0=oT`fripJKTEljK7%c|j`%B}V72ijYTe3YIqL9Xy_eQRiZ?rpmCVSVm z?atu>xOAwYY!^6%`nBZN|0&7V0?lDeSY31vk`H&AXaPV8!8h@_6ytOY`10f1+yd7E##H73aA`-B_FO{kRMM0`e&F&3E zNu+E#pNQmM7{ksSum1ae7Ws^Qz9c;yOUKDL)h%`= zl9mGHuN9O(R;NPm*CSLgWbY)z;EprPFs2qq6C`P{z&tYUr8$EO-=xRCyRo_rcHK(u zzk#9Mf8MM=b{9A|Yxg}0c^DCc0C_caHc=GvK%H4ncvdLZb1ad z`nh0u--;;tAhsRs`1f-frbG2l)58Q+ejW{D`&v(;X0n zQY$Q*-GVWlME0LZcZ2QKWS(<`9i*7AGlk$Ir+CB=tuc*X=!OSDJMplakI9$_O~VJ6 z*@F?=C0J>TkJ6VsMKb{km(}^N}sBFuw5_X+7PG7vW}Q(wo6?NQX@%Sa>U=ox9$R7{Nn=B%Ll8o?9X% zD8P6Q@nfN$9fOWP2aaYaA<=eH2TAiqS4$wfwgg24q24*hoipLLykN`wd^KYSKdJ<% z?xzB~tkx{-Ew4T5)t^a0=rdE58HZ}}U%$g2u?2pZ+v z52=g;ZQ_>JK)WdXA7L9XNU|08@W4ygL_oZd@J~*_wG=&q{Ul&Hop3cAA(d~EBki|* zWoTv=3xp_ssSWRhem}h6J6O;SM}mZ)g)vy(0ww)_9_%{ME`$dcq40XuD{=L?@8X3v z4-+ia6(~YC^4u>wc~1{JtxkJ)8s_rmlFDwT;NVI?kTc*MC}{0|T&uNf5Avdi<;;L5 znw}(xXd`6LEudg`D#+?E-CmOBFQ`4P!m6{WZ}=M#&xP`Zao5f@-B+MtM)j7#!ht+& zf|ginY29`oYJLeRShtKTN9y0t?RSu3qJp@}jJ4ued!kr=YNU`aqILfKd9|~iqtLuH z9|44UQEM8yZhOGOV!3K+YMiV5fzD_MrK3WD^?F2ho}2{OKOHt+Gb9_+4EABhbDj^# zSkT#E?vULK99P1Ucu_SRV1{s2VjV8ciRN@mnWrT zU&-jxL@q(D-emIzpfA^W<`L{UE%C~qT49{DtK{R2t zt|0QW>bz`y{#+#u9KdFVT7o7m@5UT1zJXPM`14x(Fc35X1JYU`-=zcn#_<3vh)~iC zwU>i3r6p#s*X7y4rYrv53fh}q&$3>G?N|r6spHFsp>`bui?j=(XB$gt*yztd5*E%* z)}V^AN~+bb&5a6v{ zd|mecyQ~jTG=1_eXYI5>ltIKgc%FKTNzg4Jnvj9T%6bqweRC|=$9v|+I<0};(|sXQDtg-qEOAqvGVZZr%g+qyJk0JO^z-?s9hHKTR7m2Y?$lU;x(S zR6!pzJxr;~UEGJpFtkV$YCks*IUvKoM1=}^QVUN_J}UeLP~S28{^Gpl3nTi}sAphz z#+^nUOvhV63^b`raQ37QVAyL`+K%?ykU&T`KaY_cH5=n$xFkLGXfIZzNYDjsKO@z= zeUHu*HGq~?_;<<5H7>vv(72Sk6Qqn1IPo3_nCA+1%|(J7TSSPOhHw5HR3H!*5BM19 zv|Js9`e#3nvH!E{4vcQViWm%~@K0pm1PAFO-YyCs0-S(n7LG>pmx4{xMypvbhZQ8*GF*{AX^Z z%Z1%QM;*GwlGHS!s7{qfMnXd4mtt#h%C)uOf*Z#ko279By}krmaMnxPrqL5tzeN1} z`RtB^=Wj05Cuo!)BWfgg3AR6^dpzD`#!2Ax=!?QD<0P&@riAgY4O572^sBJZpQ;hY&caO{5*JfTi;0pito zz&KH4V1qnK#T)E;FR*vp(jL*ph90NsVn6%DAS*W7Fk+DMC}F6oJVA64mL{Sc@tyD~ zZI`EbmYKV+qV6*?*oII}d$H#G>+ca26;0?>Yd^cPzVdfj*91zh+?(+$`a3JXqo)e; zxqA4MpIB)+y@3r4E9#W?_0b?)C5NiN#b;TX*T|%_uo7}{P)qKjJmuMoJ7=Ri=u<_$ zKx92ZYSU+GzCN9)#{TE3=RKhW|D7sseiDbdrZoyeAZr#WaEOKgN!Fb` zcZIboLT3}`kD^0{&B?r5fQ{B4US8DO?r8G*=_-fd45*3@nj=XdyB-YJWmNTC9|O2+ zb4S4r$HFSqV?%L)EBw{M2j_~Hi>Ca?X9n+H;>N{mpgsS(6LdT8-{!ZK{TdK}v4h^| zs9f{6(Sxw6_jfvej0h0L<)eR-W`fDk5~qGsa~J^31&KTslS(iX_oGE@3V_Yhm*eh- zKg!?7k*8aI8|qVf3{vPqlO1;N_g1khWwp|Ry;;Mqz6{Oc9-q0GA)m)CE#9w4%2!TM zI$58T!9J%4Apg!=x8$?pL#;BZ+n16s?+t2gKlTA2{mnEe~`s8)uHwzF~fH_#(b-mGpt>>Kzw!9>b4!}!f&L_e-Md-TZHbvEc78X}u7|{@wn}G*j zul+iAD=+PX_bG8zyP4b}5}p*i{ecQ~Fo*$Gi*8(2fQ;Eu(Aj8fo+chj}gFD3I*q`3^O1w=cm2{2!Za$ zztO&zO#cg@Z|%nM#mS(s8)q=0wUnD=x#XCEB zA_*4ktX`%}YJB*|uXnAaMJ>R9#UGv9BO2Jc{aN5}O5@WC&UYq(nq-cnbdS1sg(YK{ zHy7|oJ(IJge|Y4D{)~O#t+agTh;)Vbhtyj>b;INHp}q1v;W{brOTt zY}8OdT7iQW5_Py<1{Atl=}X`Ggm&ICy|z0WP>D`xqI#0&8JnT5boOATI7lj=2dxH2 zmLu88y$ir@*-r7zc3r*qsWDijVfe9Bc2G+)Clk6|*hn~Cvi^e8e**)Px-lFoTkqjN z=-Lru5{Xm^7HaNqEs&h$Csn*+5(@|n%O?(_DD= zuG3Rb)JnTnsAX$!3;oGlsG?$Lw@|HHJ&(NG5s(5Sm3*2m2&fquFwkw1*}DKpFT#*w zeFeeLx*h*DLxCvrdlWtp62E}d0bS*#v6X@(@)-FecdBq|bBcCcVbFP5;~dr>kYOBP ze}O9P%7RyX+itv@L2A@ic_M^~cG${WVr&N+1K8it9hGD0RR_RvWfdM4+*xyZAS66O zTlE*l1UIghMZ{q`FkR~aQr3E{i>bR=2V}Eg(OOz98QYlyzM)%c-_n`>ZvyQNjw!+NYLtWcY{HE6oNnap6>uByBx$ShQe$>NP5O&Bo zlWda$FG`hZ$GFzZ&ca^C#?b%)` zclb1O8BS<>#gV(%l<+k%OoZl``bdu-KpR6%5>zb=7rQ{eWdsNgCl;!!&h92 zO6dR*3OoArRjz#UPjpCd-G_Ve<6Jq%N3M2}4C-9X8v@lp#Y(qjKkhS^_@|Kg=bL_l zn6k2Wy%y*tsP&jVK|;Y}dhldLM&2eT;6@_VEsN0*96HjIP?Q8Y-LE$$U;hX?ELT`; zKHm@6KpxDjHI$?#)9(a%@(26QaAzOL%^z!wzmn(F!(GV6f`l9pV4K0jOdgW@g4P32 z=H4!CAE|<=J;)aL8dflP#K~BxREg239~;3U_)OR;@P;;!lTWi z-S1$X(&voKSZ>QGsGzzn<5VjJQ8{}k9>>ZTkk{2^0_0Gx{|EK+PXQ*o_O9QoM)aLa zY4jedv!}c93F_#+Jc8F+c}RDV=ap?!YgZ2f0e}Kt`5X}FHQ_>f~)yQ{af`aUYW zl?ia`ga^4(pLms!3tR3QlVHOGDq0n-;Hg_WReb7WeLcvDW$LC9eLANfxfyoo80stG|XkKz~nYFv)Ly9zdu%??iAsJ2vfD zP3w~52v;79BV zHWaoKbH?{)5(4RcW4QL8z1j`mvUWeM7pE?oivGY|OYNfac`yo30Nsw&fcZ}_hl&z?J;WWwU zT2TVmFrqJJRl7MZtNEZT;=uzWSaW%Dz>@Od&K(Ps3SqZJpw4+P91`NcsE! zr2JMDbKp_xpE||jyanbV&K$NYy{RPJ$z!^Qq~njKFk+As`6?I_Ov!_qV z?uVtd6p7Fov_tG!&zP=!Wdqu4(`AZ!(2fCQ`2pCsVw%m+HS>6}`H&$@h)SjVC-$?n z7rCZnoc`|jp@j7ZnQS-pMU<6}kB{yuKhtx243YZ2QJ$7e=PA+08NcdC{{9DoGgL=t zwYKoMt6;0>F}G(Zm$v4}FQh1t~0@EL<>FGJeDf7{A4U7&IM z(g{+;T+&j>iHS9^8QAlSYOtyqGe7?U6qf5`heNdC#@%gf)HyCMA^SfS$E2BmpU1?z z!ZjiUlLWO<8kUWfb@$NFkRH$HJZKMmIe3e@C#oNClb$|pPW_rmch_rsND3}ILaNqO zv^czS^hwlAW{c*{d4<08sl8UeW`2Q+#yQYhaa>QqiGfwKqBbLDp6Xw)4CX8vTeTxC*X;t?2)e45rG-_NJI zXAD+&?=buY1rKlUh^Dm(NEA3mkeVAFCWJcVJ~tx}$Y57_>GBp1qvNDJU3=I>5P(rb z!TYOXlF?C7+l!#(xYgiejXRXN_${L19)ti*J-vH@=N;cY89cwo^!SqTp${9#w|EYl zApyIH7mA?Y_pPL7NnGcX1S5KT{#$4Wc6LWA>JN2ele$M5%BJlqenAXprCO3DmpeJ< z#}{kIDZP4S`}at$_Y6^unQm%=X&T11O6>4*QXaXjAClr*J!g>&~ zA^8Objh#Mkeb@vl?4lsv;u?8Nzu^%;QHe=Or>&Atyx_rr$Xs3vpVuHO z&m`-B)rj`b`_l05o0ZPFz>1y~lqBtVtRGcE$XF)1Bi7}Oa5FF@OTI}!6+O6)>Taj} zx^4kg0^SB4ehv@P6V>@ZK z@7QsRUKK{eTJjn=-2Hp^?&WW(j6uJ*gIe9uY5n$si%0}U2>Ou6l-Ve0?TWdfui%9$ zk@dR&S}!vQ5K4#?+U=Qpa4X#5ZQ1Q&;yEaPT|S(Ps0HN%8DdRW-MQ<7nLvEL1pHW& zSKmVY7F7Wmwb!lIWcvMeSlja*qPqaCXFOzm?p!VOEgktT~dK_)ow$nTy$@ zSj5pteSXQzP*0D)c<6Xqeo#L?@D=3n>W7@bt9gTfj2az**z;?);2W?OiXL5YbkWe(-ZCu9 zvLd+TUjsA^VW@uGNw72bi+A9WDblKqG{6A2JZ$fvy?d$Chj?pZ2z$mZr^OBmE4ugsiq80b2zJ}S zc;)o@*b|9GSVzZ9wyj&YFSkFl)&`Rpjw4h|HMO;O;MCukKjZ*HY!T3BZsf&W%YIr3 zrD;E?3to_Y2~qJQ>*=2~mGBWO^)XJRQ`brtztu6izHgC7R9fTH5+81}Hd-_IWKwWX z=YRcIIt*UVEDHoFvypf9s|W=t1_KvBP3jcRqfHZUl!Ju5#zyaV!fzAv8N#|gddQDY zSFAWwR(R&ygXc6@hJRjOw=G_kdRo>NPLf)nuQqwXQ$1|!&S}_`2nS9``_MqNK$+_s zoymP(=guYNe9}K$kn82hD>5K0DOm%K(C5JUQJm_=_3QjfN=iS74_EYh{HMNW0$h7? z+RnQrS#S~|H9vl-s#f-3qS}EiDRoa-3mj{P@%M>{|d-lgi7>Kk!R(9+a0io}OlfOz=aC zR9b3+b|d!e*~1v46(y;m7Ro(VQZ@KQ6-mJh0s-&ftM}CVa4r)~2|+f`;}1s(+0&++5tb{IBZ;D#vlpw_!O9mYLAzG*W$T}<)Fb|K1_Lr8s0;{| zIy5<;qu|t@U1jkiOuz3iG(3w3o*^}N+kh`2RRH_+fpG3rUAr4N+tKni?#Ce0v>fHU zbKYQ!2UgI}ECbH!b<*0LEz!5n%FOhLd?rx1gSU_T{V)N4G8bERtmk}` z#JN^xPHvAX!HLoerlgEikacTeCswnDGsf09o!Zagi_Yg*X?gJe2tYCD3y)%0FdbFd+E=LYoG-rgAHK z1^+rECPTA*`*tg!o1KD;gX-VH!ouE1>gyisCxG0{jyMijiM#`xn2qLo*Ce9-9p{^d z$8Z(WgvV__1NPZI3`B-KZ6>a_>XZOVH~mS;^6hWgKeS@0L;6BPPD?unD{znf4mmV6 zH9d9d*9^INbMyyqNToDpUapneGow%IY>C5zn2AC>EUe zi5nPq3c(KQ^9?A;maVHDOFpv;Gkpphekku-Zb>qwGw*tdK#}gx&X@;9N}07HKnb}= zCX4Kr=r&BHE4J6SDc35d>IKih2q?&AtX__TJjf|DugIj?6Xj1g_%#j=tSlh6Q$NEW zJUIWz=2O}%+_5+81}2}LmcT3+hr;uj&BqR}d{6%+6)gNbw$WI$OhB2gXgfX2}p(>)vmMcfW4Mour&NQdaKPY zh(qCl3>>kSr4=n$wr>|<*t$0iBJXo6SHu!&YS?imMs5al!0Q0{nm9EBKU!M`zB}W3 z0&F?b#Uw0WZ3-G-^bt2Mc6*YTm}uzz?d_l4zCVc+j;|Y>!DvSf+O_?EITh%9P9e*4 zqs=+CV9qNkvWu{b84V>R65wT>H(@_Z$ikYM#@Nuz!74VVAo*ek$mqf#N^OrN?qbSA zZR{cO!3`U%#bjkqd(DkIl#|wP1OK@@r4a3&0-zj`zzDQBP+X~9r}k1ue`Ws*8OHTX zO66RD%dc;3?h9|mKZ6F^7e1iVKL8k4Q$$2$(+yaz#BpDqR5mV=xb&YmhJH!B4OM@c zWfv#=YIr`uPr9#)_Pr%9iSOE_0@iiI&#ngxL`lcP-+vTxR6&i(fz1&ZqakB$gC>!e zA9LH=4HKeDVxOx>IXm?&`i()3Ndj?+57^>6*--1{D@hHM&3z1qOMaS6CL5VjcNYQy zL3`T{30vA+1FSaPHc%9(bBu*CP0?6>XNUZzxs_{A9fEat&w~YkL*GEtpccxzK0vWH z-L0W(smIJeGd&Y?-qQNm*T1zj;X^(|iL`~l1ae3#AK}Os@QnPopRD%*Hia(`-w&_gpBO7RG zAN2M0dCa~YLoeJ9!uVX)zOra-QhdBJvWq8-7c0MuPVQ-&S&+~8LZf+nQMiR|jSFym z54eDT{`~o7pOL)2QR_fGRF<`Xc65uYpE`B73r2o-L40TBTd)#A0tyP)>vhLrnbYxS z=<<&(+Qpy$tn83fsp;wItpN9IZg00KjceSs$D>=KlaHYi(YsKr{`13+lW?aGL&3ZH zAF1Q~1>V?FPT+Ez=^rEJNaZNHQ9gme4RMIAuXfiP&iyg zf1Gb*BXHx-J-FpT*Gi!vTJcVKj}rs};n6HR3(Hx(GR7@ioZ1Y#ZeqQu0Xq}`a+ajD zZn53GSB$Kyz>Wi5%BQElKzY^-Q_~85>!CJPgE3U-A71|1uoZvKX!YTl(@-f=p&C^y z<#B^HM7c$iHhPA4JOA^6?V5U8)c#x)obEwH zEauW;?bq=4tgEImqqo7-Lv|KIqPd;&tSl@?SZ_7}*Qub*g(yWc&3_$mM|B^cGPkh~ z{Pajf>|Tn|sp1qCTU%R3yq0zs%=>IE!KguT?E1*s=OQw$Xt!SohwQJYj?DL&scnEB?&NlLg0o>&= z*2XMj#NT)y;#l0YSq`cihw(+A`rU#4OQviYCd2n&3a#6p`>wcajR8VrYaAGbiG(nS z*vq9W9o!5$GGToCS1`-JkGT#U8=kYx?EgOdyi7Jw|E?FSzgQ*E*w|>UcVUj7&kZQB zYLq!vF#!QJXh&{Zc^bW@wRx(E!`*_CFT)aJ^E!3o7Vdknqj>@eU*$&t7Fi2Y{pX;f zbj<3+q$A^~+lj_yNc)*yF$d4^)Z!pz*1Twe5B$KeMx7y|fw z@qPm-ZyyvA^#8}!b;o19zTv!4=u{#^!=^H`BT-SAl~s{ZAtHpx$Y?902-%WQR*H-i z?ToTQW-5t_%81P0^}Me-opXNw^l{?keZJr4xu5&K?(4el`%ElrDEv=_y8&!#8W}|x zENs8o20m8iuU9y;^??#IBE&3ws3BlAb9>m{CC%iX+C1vXT}=u_YoX{ZTVQ!Kfr3P1 z+OcKh#*KogNAeCzi{GT+y@i3yb>3LEsbc&=z0ngmE1UGSgS7f~?m2v_ z$3FNpp($QWX}HyE6B`s1G(Guo^P=w)!?&!;Sz-5N8utzwIBj=~!0k@)G^Qq7yrc9( zC$FL<5IB`3!ftnb9D)Vm;^vUkYB!l)H8ygmIRVl!F)@kB-TQw6?E@i{?ao=8wKHj$ znle2a6IL)e3A=oG<=FZ8x|gWlxDO=ob2oE%zsG8*iQcjQ@FP+;ap~BPKKn?iLyOKB zAAAG0lWo}7z{YjC3P+a^C=wdYrPfKN~Yz44!C7F&^blifBFJnq=(a z(TK~Vr&iNEA?S(RAAyz@a#@y;9rwO!<;-_#9#F=#L%>Z;4C0rT)`u5|rC~a4VMvy} zrE*r}#%fxE%cUpkVE^P>diqM4QwMu@efspt3QD{M>_bQDW^SFNm{Q@_#M>=h%`X|T zxdK}<_~4K%eGGHYXFufHb+6MSnx}Jm%NKbaKUvT)i3&NWnrml-4o0;sT?>$97d>?s zErrw6Wk`j~QM@d($zuA7etzD?IR^P*q~^u_rnqiP@3LVot!-ts2I2p0P_Zl{Wxz9~ zMM5)YEzdwLV?;J<$}?Fx>+uct-Bd=;O=d*EOwlcEHf%K?>9Zm;{gCwseankE?B!M5 zx;=j&*YR>ay`jlC!ycpT#smyrC5NexN6=qo0&0jb$YHjkjU)(-S3GFWn;$-WNLfO+ ziQ&AzF!u_0-SD+ty0o}fcTtCI`!1p%s;w3|(1$B05@I*+dZ8xjw%Vm;3EhvhNB^EP z(LJem!Ash0d0OYeOUjccPj1;aNu<$_nI8gA`KioWs$IkH6q(#SRg#G8Kby`1k|BTp zO-)U7{M1qBcooT7t!QGetn?GMJ{rVNZrc(YIO|7}+<~?7xggTGz&?{cMO9S`L>NH0 zR~mZq#;zHgG^*?0yMtymD;wMXWG)7amBn+s-svIoZ2A`SI$Lv9hw;rHXC9)z6ddk9 zq|WOB4Xk-Mv4uaXTg&1sl$6Gy=-m!D&@4qkK9gaw&&7bG)ARwywGn)+<-87{|&F{w+eJrP^gK zB(gYaMzhSkVp;a|%*@5Q>+0x3BXz^80gB8fJr0&vWGf60EGl83mu2!rKJvmQndx=R zw{Kizx})$ZY2 zK~90aS+g02hO;#LU&e5(t=%W`Ut+9O0q(bMbDrdxMpl43qwU6VbhT4%+^D$1sdC&n zbWf`OHf8@Jq~tn$*Z`{{19%<8lGvZdtJts9+_md6agW*RHj+|Y5X=>?Hwie=1%2o= zp89j=QE<|U)N8#agqz?`Q!PWgU7+R<1M>E5*OD3&3UnzKPz#;WwA*)AxX`-=3nYxy&u=obb89?{(kgjpD6R^&wpx{kS)&-g7Hpl{j8T| z6aT*I7)=m2Pq_CoE}OahOxQ5ECLDY}<$LOEO6l3$*8LzuGRkWA2TfHz8g%BO|B#DVv7ZRGG6w&P8=R=Hd zyMe*}lBo2I4A;xs0Qsh*r5Q{-W)*!Q_^%aZuEa-W-x;x%#%Qo~rPGyy@7wJjNhy;% z2=iAf(xxax;mWvc15y{!Onz5J8@gltHG-r{4HVwzjqQWbu>lbz1-L2}R{0scATes> z8Bt4oItac=1^8WcVjS%^r7+E`2ypJ9qV+n($0%cRRs?;quy~UxFv(3!J!^%R=)P70 zd=)&R_Ob;%US2pYSdLRZIL>Srl5A8|Rt8g6zLY1RPC0x$)VH0Y-c|p&=KTK+mX0Da zrXM`MyE2uDe{9})KsV!-i;Jltl$@ZojR7lJw$rJs-JBt5|H0}&Ia~H6WRAgF{fN!s zXnsn?Gul3Ra_$`SnNZt(KLPU0?oKUV1K>LxheaTg6w#28?RC&k;;Z2x6BkJL^idYL zi&1F8dcOJqq=YZgckFt-Jx+}z2z>+TJQBavftf2wrv^e>y|mP?4*=;oJ+YG!`L*g_ zA^*4u8d^!_>yQ5;8AVcJoZ(@&FxE|=MuuPjS>%xt4zL<$ux9l`98Cs8={!C%~RDCYW|V!{s8U{Wuw*N*?D=v4w_tRL$U@B~u3Zr`iblWW$jSz%VG!C1&z(^Lzr zVfp$@5nXE=o8nW%$iNEsf`qDw+orP#=CIPiNxqrm@0-(%7JVEv%0DzLyBQ~P%0Tne zc#~*H43yAZ+7E8(dUo5zi#q&9FI{^1$1%E@i(oBp?vqMG8T=clxF{04!RX0?|+rI&FbtZaIz?9YVM<`T-mbilU;LO z-M#f+J!79|*be~Ecn&T_kOV+^QIco0?}~Ps%hc7~&27PEB0t&IltY)5kCwzPnD+=3 zKPa$19~v4(gaCrl?lr~IVq`-I2Y~0k1$-jMbvviv{2hj@N=se+Wb{Ts4tk1kQkq(? z%|eyt+h}*uEsYBJV|g=Itv7bmJ%#tb`gKxQ{Dp(;tT!GgUk*RDFrXPRQU^DZ&D?@~ z#Cv>xFI|8dGr)4;+XwaY*OwL^j7eXPV*Gi{@qJ>{H6H#^l~(ON*7i{|BO@bxdMsx; ztQ6vDeN$8K0S?_CCIHx4AMe}tw3D0OgsrBj9pLzK^GZmUf$4uURyauNJ74gP&l&R^ zX(U!0Kl_~gDk-%5mX{n$R1}GqYEE{DW*2V6|9ytqF#kt6Mt(SzbieboH(Aa^kIw7< z!U}fm)#RX?%B~WVk*WW@Iw2wC#S#2~+7?vI9krrmql|fG7=UL8&9E>^$rnn2!NCzj zLv97j?T@=3JzCiMInzBr*mgNcTzgGS@`=g}h5Se3v`nKGPH~g2p~pP;4nID-NczCb zWf{3^c*2T^Qn~fRQyI&zDlnf^4N73k3XwDWlXWb>8Nhzw$LZ7^ zmdaM68$PCT^~3Ej-<;iW=~Gu%zbs)x*;uAS@v4Z7muHDBPxy~Sb34}RxtzAS{n3MQ zcyr$jjxfu*lNuJFC=rsCl}-P+pzyl?TTsP!YH&4%8xV5Bdw0C7~5+j7~5QqRNdkIf%BY!nj*U`ES%zA zU5JWm`Z8FUZ?F_;zX&PD4_9oebbq<_<8w%=B#YNla|HZ$Kt z&n*zuxz_s}<=u2ZjCzl;%_DFD(-#xZV!QemJ}8E7ztB__Hs{|cb6pKBU{IL{yT<3K zyj44&)|0yXpM)E-W9f}?cb9p|{QA!5_M{s(w9urumYkftI|uo19c}@h5cQqpHF^S5 zQTW=z!bO>4tvT2g!_s;y-*~v$BG=8W)a!U?Lf6%D6Ocygpho-&+mPVLS?`~P7I2#b zF0lfUd|)tfx~(wLW_G}4m1lKvgPBMLqZNr0;O;!zi}hv0`NYZ8RqtFnHCiaCTf*Yx zX}O$uE7yTIKJ-5Q&OCmc#CX|^T)~QcnhG`YhumA$9DW?(U;nRbeH?uo$HaV_RNA}S zWvnJz$g}R~_Mz9iveISXq0BUI-t8|w(WDfsF+>(=zL4=XdUESN4{k$xY`Zb@4u&&n z8XHHN{-ryo$$mK0s09>=Yq*Q_ckQwjoMkWP;c=+z`9*0s_ywLn@9MFNXG_v126I@L z66CIa3D|`a=Q$<&Yett)6Z0}33K>_fuCVEj1IqP?dbkz%(6KF|2(yqmNW=_@bo57NY1eV*4Rn$)8EIRFZJr^rs=n#R<;Dr>c-Uu5P#!+)MwoORp z>^wn=4q`T|UN;!D2hKc)xNX5#l17^-w12WIe47=}xD{rtEgGPR#a>vz!g!D_OX_lB zqSLx*P(F&{v5QPo&>703Tv@LmBq&&T@7Wj5SFc_@x0o8>B$(+o;qklYc8BZ3D*uqf z=@dRocRH1b&Rdld;ow-VJsA@pFHVL%=2C5F@B+%10sur3Hrz6`Aud~x5aNsE z(+@RkE6i3nWU}=da;K-`BEPob-^-`hBO7$L3@e_K)c2pQ!Zmy}ECxX}k>o=kFl@ug z_(Oq8c^~ZkQ`^9_Td^Umt$z_4Cm*4rVP>HQTLOl_H*Q6Ti?w~Y^h6eTWG~Yjvzex{ zW8X|{#$*Hm)Ibm9b>HP*F9UZ-gs?mweHoUUzz~UYu%`|haHUdb0CsArDLDFl zf5N$dCqdROENF!aH?;Y-8fxcxdTcDklaqDXTJl%YedRgY{P!|wU$Gp;Tb%9m@+@sv z(*Dwt5GAVc&@R=B#M)u^p^0pDO|P{ut~6jz25+tRHUSxmB-D&(dfvun)c>y z2A4rz2lmbD4?g*0-cs?$UB7j1AfRJg_8WM{1$|z3-QnvU83{FBHHshbfG!NTcTsBD zv`|Hm94CMNy-Uc!39!UX5rhG(@5>*zu^s+A=P8{0HBo7tuwMN*Q0)wpp`qbfW9P3J zwS~0PW7o3(pyL0xF>kqvZc+oIaLiW$0Cz#lxg3^WLeSBiR`(8Tg*6Q?4oGAorWiYh zw;p?<=W;hkuy-z<{XDYSkR7SSq!_PN-SMLRixKni=YDAR;$CWhB=y=_C28RavvE37mjQ6T*kD(eaml$P<=eO(1AzVwcilgIsw7(RXe zd`v&6tnIcS!3_S9qg0WuL{Zb3oAKMo44l4dVrOfc&Xu-7hl8`G`Y!YWOVZ}{bYE<2`TqV{@MHJMsg7Id zO;kd}aSc354$l2v)a}&4EGsWx0n)4x#TkSFz zJ)JhAZJhzyUT7p$ZT;~h)h_HP{9=O6^~bDpO#M+Vk{H*vJ*B)91Af;>mtAB3Ozb79 zl!b&e^bHJNELO^Wt**w_itgr0K0ZEH9v&ybqGyjEE5=WX7qsz%&2V^ZP1ft|h}Idq zy1d1s5b=G0kHKMou60LmV#*1R)W6>#^~D|6B1Nf*#BmzfQ+A(XV!d1R(7}j@D6(5Q zk4Fpm`&-caM6|7k4rMn~;Xu=N$UYdzD(DECX)at`?A5sY09V6Mo=Hg#cX{9auoNEp zFGAaQ?_LG&7OsJnfM-^0GY@w~_bDjHE<4OsrN8RMsj>XQ$HIah$MB1G`eI&dIhkIz z=Z342&*)89G#koZw}^eZ9+tD=4Q=hi<TO1T~BX*^escQ zwDr0Ay_jg`Tg$d@22ECEyDW1cWCHo=0-oZ@AFUr?i#zMT2rN0&NuVgHq(`2&q@l1k z)BKHF+5mwet$eaQt5{RW!~6b<%W{+{mTyKb<47_j(ZrEq70KUrK)2N0&S>P0q4^|c za0>&}c~Si0#S6LBB?n94IsAR@!ejjY{-?+>x&|Q^$kXLrK$D%*tE~YojCjh8_`#QF zv)m8lZCq)4kG2lkUlr~za6no&+&f3W>HRyeai(QpL!c|tEA<_n`27NHfvMFC5q7TE zH}#SJ7cmg&JM%1v`r+5H*062FnQ?d7^d>NN$omD(w9iyr_m1s*PWnF~2Q6rRzSru7 z|9ucX1d9Hu+q-B69P<(D%&fa&e7H&LjLG*41VqZ)S+=vhFUH56KY+}Gi)3OGehztQ z(8*fJlv@-Rn6oXET{Ic2&~X99f+zbJoV?70Z-%$^vkP%z6S2|h)&O~mjJ0js+v`du z?#3D=fhm;{YR`Yu@ii$u9QP1cw)fL=fgQ1_79I*t9bbkbVc{Hh^4)ylraRh}P1$C8 zs%a+o7f52DZLO|@xG5UgndbLeJ|8&k&hX*|^?Yv-N)quaL0^8snrUd(E~0(J(6EP* zBfyfHKpfs^2#EEtv>|eLsgt@ve_k=vOfLf2?1ub3^t8Igf0BNPlVNP$iAdcHe(%`D z2US&U(CSQJ9$j5z#@2}8B-fCvy5O2q{>u-S%2kxj7l;W@vL<6k9>#bn8~QcSzhq+? zG;|!<91e83EJ6)%{Kc+>#6(FDl^w5uc|}qU#~fFW07nWYp622jk-a;F`z@0A`nLBi z;CX{|dQB*%QEf+KN|ak>et;U|7kHSB-hY$Vn;Hy0M)eb4gyXMb@4W|Bo`%&y~u zWxyuhjn-65CxCZx&B(2>W62)|4S+88jIbnl9(Ufs)SO2d`Pc@UE z%s|*PTY`m=1}|2|JCBWL~KCSGUCeJ#fk!FQNftd-#1 zzxJxvIQaa$5H$bjl8rH#wT^5;@6+2tJ;xT@I zf&Wz7);Fe#_Qjr!t>LLH%UOPvYkwz}hp~3?`(-){scR3g*cRaifgvH0 z5KPmLzdDOYqa(=jyz2*&tj)x!scH(fCyOrgp=|<1_f)*vu&ol9ZRNJ>x=4bW>#hyW z0C1*PhZJILvtymx^3g#m2jTv+bF&7gnIMtO-USAhEn;dr?5?uo5hv5A`P{PkcxsBi z6NO;9JQ?+Q{^CW%Jc&XzGGwpQ4J5+9i{&EAMzTqK zgvgS4{3doFaZ(Z(Qh4KI0N0Whx%pwOtxuleV0K>fH{Q_nsXj(3+d?^?)eHH1#ywkx zqgfT%L^!lsic#wt<+TGNf2Od*a|@c z2o81>H-$n+UGzJEkva!HHtOg)|8goH1B{mJ+_m2xyM`t#7{Gj;STX&F8+b<UqI*ARx%)2|IiFzIMh=$wei!g$L<=b}N3*~)e z^idVO8O}PO_}aYB)*ClpU+sHyq`0B}>!W&4KLT0b_-^gVVTAg`lFe)$a(wI8tf}q2 z=X7s4lJuuYb1how$m(j}zTJZTa#>|)3yUpW_sze4lsKD$e&?;TR5^f(?q3FljORW^ z6C{6CfG@TPWH8be7t~MsGtdvI)Bwqfdnt&j$jy~Z$oMlO!^`=N>izkh<9o_D%ln8^ zKu_&g=wYQ+e;fuO_j(0(>&l#xfpZ|amm~L;M845ihplVo(}uW5LxUeCve44iv9-8xYUR$^Ah^3kLv)QhEzl`__0yzNCG z0FB2!m+2`si(dn2KOAFJnX3AR3q&zYb88OT%l1q3@w+nEK$`j6#W^4R$*J^LrT4km zmJk(nK=4NIng-(K+(kzCG9JNA;R2R~Hno*F7|TM4KfEUTdRM6VnF-MEcmeSqM|)Ca$TZ3e(lBI z3epFX;C%4LDmX==0e7an=V=(6GTb?(8GVIp$X)XL)8i|(aWv1I5_vrS!Qx?Iz7!Fm zdFW7I`SW4UF!+lme4mEYCLFfKJzdWpK6(Ul^pCD-hz~d0yo|G(C^fcJg?4hAuTFRa zsGdger-zq}t};m73P?Tpq@J#Etg7Gr9qpp)*PA19sw6Jksq5m+a(@;R7hNo4&*=m> zrW+1@Wz)@A(gBN@u!|S@aQ5UcTE;L=B>JzPH}Q6%pR*QKZh_ivF6Zwh_?I&bebj>Sbk5XAWva*gC)q%1fB7IH3&0+F653%o_*j5 zOJLNG!qhZrK`#>695->5vjWuS z;d*=y58DsWc&yR8T{B;OEG;*;mhl5-*j|{PsGhz=PTnSE#K+vVTT2~_@7_^yeWkm_ zWbYbaQ7Y}ul9ba_j*IYu_GL}CV25TzJn2A8cN={TxK?NJRILtK`G!hsEorkISLi0xR+Jxtm90136*5`OS`5MI2&WOk_jMlPwD^|Pqa9s5Bh ztbF%PwysZ{-8(+-*jJi=9WsEwL(NyhRO|>+o{2pu1Wg(Y*f!*?PFvA>gGq2W<*YV7Q*XTlfz9rN>BTRsABet&EYL+D*ufTH;nFmy4KK z=UP*yfSC)eU*B=wCSfFw5I z2DsCj4!I?;r5Vc2FNHAlsVnb)BV`GZI(p0W|5}+UioI9pw&?xHY#{Ce0x@Ok)SSo} z#jkP>8Y(?o>9QVAMU_rGQOw#Xdb^+z_nH-ON@+l61$^+r+=kfPJy1;Jr&D2-dv+D*lQKQ8RzlZI<1vHc0nhJYPsL9anOq<{H zc^b8U1m;vLo`vqMTy^UE!d^J?#n84|A$v_?B9Tji*Bo>p5g=NW3&CDt3osvS_DV~7d`L@r_#yBLkbxBTnr+V89L)_=HBlpx0m5WI%Em1x->js(#-7Y#!;ic zdm*)l`T{NY2Vg?`Ml$lnhEg2(sXNvwQXBSjPo;I12ZV6ej7Y_F_Gk8PehQXU$ilGy zc(^d~lN{VOmvM&BEy`?L7e@Hc3gSzRTC)n@Re=)dL$H|~jb7xcdzfsW3=&Af+`CWi z`i&b0*;lVwvjf@yei)Lw$8HGaQ6{>gTwHpLFaW{ir(KThoxf<7yX@g>P<*RNe=Rni`P}HQzsW_rznujE44- z5eEHp=k;{&ZdY%;)hqKB!CzhB>VI2aWinWlitD@8Gx6kGco`Z$1fRJ=j5#s1Htt>8 zj$RJLo0}mh&l-1Y+Z^|gW`Od?>cMe_WRd>7#=L!F1VIC{fj#SZ|9N9GvqOSKoQoH4 zMa0}`2F)OML)-iJ@0Z`mwNErTbl18*g-v(;6|cKHU){OCYugoH_4k*Ne5Zn=c6wstsVaNczcO#u268QdPdhdV-ig4z?NYrap@ zy#J1f)UPT5A2}8YS#PB6ar#hy;nlqhC*q9`RYQO9+OZa?9I4P0G>(+)!GVOy@Im@Re(PO_v<`LOw z=}_HG$~Y;-wcEnmRL8%_?8YD+bq$SjWDCdKO+qC1rJx98IebL_dV)(teEbXVzsv<^ zE;^E_Q1i8;L`pe#>mK5aMgHPGCnVLqJz#O+SsiM;nOi;I=Y(T`JcO`kCIwtk~}-e5qUA{{Y^V zclTo>w0q#tyev`vkjd@GfAy^r7uUt?6d`!7JDNW8EzAIx4syq;Rfn6s5g~-utjTSD zCbwpHqOPfYR%Uub>#!3yE%sG^3T@X{f4yD%c)OXIIMGwf;9YfQc-8WpX!n6u#adY~1mXvA@1?*nDtr(pZbDmQcjR|i(+3NSO!rv$S*U84l<1HlQzwBXt6Y4IcKW?6snz~uuv8_jHVOGm}448(5*r2BR zA`^K40gHjDUT6tA<$r`8z3wj1jV{2%xaiBR$~HZnoY26)!`|_`C2K|n`1wt;VhS<; zP=L!^VPAr+$pf?Cq3Xbc{WkFehZ&5MAen{%R)a&$b%V4DBoxaiMQ=|pwSq5m!2Ams zBl-V6EA8(BctH71PUwoHs&9pFKTS~1zqbI9tZh^+^ ziHr9gNxcXm`ZF3z^hbV7duaH$2p2?o+v@aDkN!BZIIuJk-$w)Ad7l$Qh~OK2!NFsX z+e<)f-I1^IyeaA%UjBYO{jWx+U4>q3{Vvy=1U#rtW*s= zIvxnlS`H2lXM(HC{v8~to7?RYY4{6O7t+4_db=eeP8jS{qy`<^i#72dhgLqkgohsR zgHUdKH+iX*Nl;KgM-VPyuiNmOx%0WLIGNK1*THj+WTH@`zW(x_iHQl8UOcrgF3W;9 zM7q5@u1ykkDGr;up6a9sPhDFHow9h*8Wb=aH?DlqEhnfzhz2T5 z>G*}hp<&Z!RR?bNZ(dvD(5EaOgzl`Ajc^3jtm?@}lJTZbQBaD4hoH~OUs z?(oCg(BctXx2~-*L}%&^1r(}ec8}|$)uPk@oFq;eY4=F{?wZFYzG{`G#JwT?BIt!% z>XwfnAePgkbEYxx0YU%K0)m+6iPa(+i|E%yMc&17u=2d0jmap{Lg}4FHO!Z(^fjkF zd*b>sPPTMwl&J%AmPA+|KNX?3=w_z>`fzxP8pvK8S64=R@B=bXj;!r^Y^Z-Pfm65@ z-Z^hyK`U}XX!U9>H#Yy<#JRpLjoqkWM|j)*efv6p7rrH!INXGkL9q=MLc-`#{wP*; z#DN@S>={3g%Q7&5y8+@cdL)*sQF?|G{{ecf|6I6kH_3J?ne`W~1Lwb-e(1~(6Aae8 z@?dZArqh32gd2mh6!rG|V;y;A1Oh0m{X=H)QTms$221XZ?Evx$tmr5clD7_zG+I(k{Tml zB`H0L=Qi1f2B z6LPaIU?x%U^=|^>U3Lpy*2Celc)GIv;$6w;QnYI0$e^a-iza4|@nyqX|I&~eKqL*2>9c{0U{VTb<3y*oL zmxq;aLO*pTOk&>PLvTzq$Zj{*WjT-JeB}a#T8ingXang0G0F+*Y=8Hhlb2h*7Md>_!^2{0U zBa)nR^^)vd#(8o+iInm*G=1n~Zx|jJiQDJ-_WY)Sf)~>TxeEMZ>gLfALIN^u6i!6} zDi%qfRffA)LqS6RP%$3{-&sT8v?Onk-Z0MZ1jCyb7c`iHzAEK7fOl2yICAuU4RHji)_ImAr_VI#PJ z)8a^j5h3}E#5Qsy=|=Bt){=r#UeG zXPN!Bd71vkdta%uPhK@@zh?)W@9CTx+-N)UYnLjjnzuG~xzD$&3~=EZPE^(M94-}g znG#bm?_v@UAYaUc7$-@m|0`TD*H!&gA6TD)XYr zuF}b-L(MK5Y>qpfNTJPm(Pr%Fl?2h{>LVtpF`b*3NM2iS{$HUMIUcVykjLK5lpXwi zFObD*6A-4{+FGAcmJQZ1YgXrCenzPgm+rayXx~_)cPXe5+aqUaWMnN^1c*s{)20(U zFIrn!fqfLTbHq9KEBzj!g3skl`=15@feTr3!meQwE&h(Zn>3GYx;pVCU^=p`MC*O= zw1?g~u|mE_9&~lorh&gTb+{kc#Z&L3cyy08ef@v#^~eyv2%^r5H;yg(M@QiU@~nck zFljz|J?2YMQI$}qd_W4~k^ZhZY?X?N8Ms{H(8e;x7=n+1F(-R+e`vzUkroR8< zJCg3-Hy75q-09q+jiSC}s80K-@aq5ayhyxpC!Q*L887zyxpn>!RGs!0&VwcHMzs4) z*a^9rpok>D2uqqh(E?KGMT8%c-!=*0;^x-u2XR3{K?0)-47`RveK_)_ty7t9TUaa7 z;I72!iL@b1X6h}omuIh-_O^Ln9(u@o;6R= z{~1Doy?-+nSG~LG;cgnhtTu}tq#t!rUD{7i5IkWzn2XTQVY6j{8Qm*^quC#Mec=L2 z?a4Gab)6F~tfz=XQLf6e*BB&1M4E!!GOnXc`?qf%Ex?pTB80ZOG)K$Q(y=M_ zT^J}207BEn<<{e8&&EBZyvTj(04np{7Z$U0-bhm#8XAa&RXHj$(c$6Yte2vHm)du# zCQj_-H_@2JWuw1iN3B>JO>1S>w3yh3S$XQZHQnf+5myu(>+bH>LfUCN{0)4+JqnzS zzqkO}$PZe*3(H*TJR(|AWQ!5V2gKasFGE`o2V1=v?kf*1_4s(*rE%5agt-qQsCPpo zM@?|Bj7^pE<^9l8uERLc$OPqZWZxetF|T}KGg=#*8Pnzqa8B*ipD8K1CHlxIY7djy zOACAxq6A)zv2sn;*u0s$Tt4R8B5v+aZyr#w+nZOgC*=3Ir8=w)AgMIS6P{ObW#}p_ zH20evmWBX5Aw#LtC@JtG8qcmvb}P7!-MVoQoju!IcZKx|8fBX`6e1FA$1=03+ln8& zGJ7(zpmSaYU%L?mSs?y|DEHeQah%JX@nJ~S*JB_ibn0l#gq2!T(hx7roBho^NUOJE zXoSp}5WkVTZ^}`u_KedJDvXY3lIl)X6e5oT_3ppcv2W32Bk2tZd%ypXz*;|E`{ho# zo*iaTchS^aJ9M4hCa>-AC&}D1)8HPDEyY0VjJd&1gk(6K2M{Fm2hHAGsD)42# zFdm^Nr&C6P9Q~YWntPTZiWhekW}7Z&-MxSRervd9#yw{p60Ji2MGsQv z&vpyMP0^uJ%&%0|$|m+Ye_T^H{qb5jcB!Y*7VE#8UUq{$YU2fOZHIq=;S(*S^N#F# zF*IiHUW*Jbf4#kv_(X$BUH_pfpLGOh>;pQL1y@3Tre;PgMk&-HM*Qozq%76S6kHtJ z3U?sIU3Oup$TYFku8-3;%Vit{b?dqmO~<*O?^~}*4?a2c^vK>Te78Jmi|SUzv1PSA zJWQ;(ENA~x#Pmzm!#vm+ano`(T`DB~x(q`@;6KT)J@%AG*7gEAX>^3U^!sIz&3TAy z&KLSJGrms~k~cAueJv`{M{4k0zX+!AsOqfEWNi*aVK<*MewC?~C6uSqP&L%v=maHE z2ffz@7a&Pe#|< z?=NzWXuIz_=>mt)TfRD9pY=m9@u{?4kZ^n(>DkewmasYpwro?=? zs_GBEiQ?|Po7rxIGe0}w+xzKeX$pCo3y`b7$X%cwfF>cK(-Ff!J@++Gj0wC|k(0|; zX?Mvm|IKBN5U^PG48tX9sA?n_E~rCG^Vf53H%B3fr0Qax#A-c z)VBO+k-bpFk+5S;9{M}Xoc4^3?>P1$bmy?E$5M21$$bz|21v&WCcq11$U*pkrgeV6 zECZwxJ4t?1T-@^Zk(Y_##*Gx`|EzK&R%t3G6Hd!Jc)w9hboJTVVZx?a#k@{c0L;5! z@}_I|$rx2qaY7V}4u(#NiieZ;V3bB=yeQk?JvGFUi(LdhL&f7bSCMcJA^a)SV;dSi zc`ZcemB&)&x#pO{(q4a|d#Xvo(|wrk{lLu{mY*L5R3p|0?nvl(Nz_HNC>$I|N8g^& zcvG40Koqw`j>eI&)&K$11C5>|BmM0QqI%1Bpe{b*p-fvo?be{4J1`>vlJDb+rYfv| zZQ0kvo$zkAH6-2+~iwH~#FCS$gft_cwymU*i_l0TO7vA(hE zheBy}c&o8v)Tfp?`>Rq4^#&T^61NsyX3W{&Ifojk?B`+9f-Z^Muwr#0!U-3Us7<^d z5?iNrtb`v$g3;R+C=|-kdJ+^Ae05a@^pbLOcff>N0P;^(UHJ>5~D#hvl{TAvpBJx-5?fBn6HvI??uJdZ^GnyF2F5xa=9Z>8iKw!ioT zFiN}vT!~(m!vKZEcHdH$-F^AA+7{*+AyNtR2DW>0o|~s_uWijJz;KRmqtCIz1q=I@ z3vAL~p3%IsNvkM75OotpXi z`2|HqD~*?KKc=JY@#oIK9@&8YiZ_cGE8m}a_bf^_xkmE?{5|Q3cN@B0w}?kxk^}|` zN5gj2^SBTz7!}s9iER-ED)iVl#-=WnLxYy&VjXQ9vQ7Okeor^#0Xh0{n`}{gtfp=L zkEIelLLL*havrNs-eq3*=k9f4*b`s!3dKKs#vKqb4^H$MuA?`$G;ur*J%=ZH@=}*mZF}JXAdh7*P?%I?UZ#i_C>{;R4BU)!KU9nr^^56pf&nI?)tendo z892KCK3O#Zlw7RaxS7q-_44u84j{46V&(BTaVXrEM00ZSR^7SNE}cTH>Z%M;;aCY zYY)Z{+D*(+DM&Gk;K}|WO?C46Pl_OaA`@OddL4>_C+)2Vk*@r7h*LXa2xa}cH}<#g zzkCtPQB^KyvS<)<#>3%~#bwl*c=R1pwBlj@ul6OLbk5?xlLpY=-2^^?#<6THZ4x@@$dXgkyY+2=Othfyesij3oEPz zdceXx=t&3%#5@C}k>k#DPJWRjet>crEx!BW0KDM4W)pIm7UK<{`hcWtPQEMbd)L0W zNDfdpip_SjgB77ph=AmX)V{de0xBx$8A^je$=aq{w2z*o<@AYV$cKWGS=Mct^QL9d z8j20e>*6CBJ*#erx5E56XrIh~`ntb0+_Z?!!b_*?-V6_%N48_M!6lBx6R;)AX0|5fMV6>&Mdl=3W~~V!b)$dKmdGJV7*ZXrXjeG+U~h zUi&!4(gA*LE&#xnHnhZ&Or{cfYOt>O%%^D)NUFX-gupoN+#+}PxHnr5+)kX-L1byE z7ayVC?XV8jP-wX0Fjf_V!2$wIsZ{sRzt4&#C)rQ8>Z;gii7n5(!W-M8L3xA3eEo{x zermG22YAa%``L8UjJB+GXixA14h`G%;Sn1wX58F);(1*u`0L4L~6F<>XfSY2%VWxgo>|^NXmr^6uwg( z-b_#CeDdc{TFlPEzI^*)c7|m~HXpvSk~ew(qs_Tj&ML_-He}gApUXFue$jkW_$^d+Q83f( zrnSKRW9enrSYuF9WbN@2Cv+KTsDwY^GkPS-3H%HxBWXM6QKyWb8Zcz(qv&$d-oE|9 z*CeU>L1ti%TL|jCHWjB3cBvnZcmY2VE}w*!N53tR4yRUfKXIJT&CO+HVd*@~X?FP= z(aq!g;<=ddWCEA|uiuw2QO{c0PYRkrR#!^5)IXC1UGC$y3tUL)(E%5^hO@K#Y26cP zG%?(?|N84!|Nd8u^uJ3!aFpzO+P3c0pu{{UcT8o_!G;?`P*)BmM@zHg^p;H_vb0Wf zFS_DNPrA}1b%E=C;q#>Ym_abm&aVrZ?X!s&V3531heNaj;2POOEwAhsf$^-adhWKX z!N!fpH zD_3VTr}sU$@V)~oww%qH0}L;Y0M+S<`ZmA2chG~^ghbtRpC!xR!Ikz^8=-C~U*ej< zBqZ5hW2`Ai&bw^bd3YoP0s_qCO;dq?Grl&(73OWhlk9rh-`HsibAP(PJYKBptZI?5 zr|4E2EE((I*m>RXdYFvx)=Q3yUf**KToLET|=KdAuUV)9H5W=89Ng^qoT?Xxvk*em^{tVfYB7vMVPOP&eo0e zO+SklBB5x6slTaBcAzk3etz3;_F-x(Dtcs%=LQz$;H4s zLiYZ8H-Epn0`ftP9p}t6HGfhFw;m)56Jh;Q-(%1fxKGhjDe9e42xiOOA22q_Q%tT* z60cXFq2_rm<3D4Bg+saJDhxYQ`J5#JzI<`egt7Cw#Jm*+Q0phg4fi^Nx_#($t;l>*A9(wnG7fvGx=D9QA<}swsv*%}qFm+#Gbb^sCqoCG z+BM(0wr!`O4h-|bkE6&#uN!{(@@4*GRIlT5-_%-EQqqT8N1 zhy!dMz5bY2Zpa5(fc*RU|MRPW0b*G=@mmFz!(PLjX7arzzn3E&$;42Lr_37sA7w8| zfcW`|CAOWO7_u6q>MWWpNO#AC@e0r~1-ueBZAvPntXj1yl{>?}{?jxPa0y2RbMHOS zNo%?^S$XJ=N*+A?1-P~#6ahz1o;nq6HHs({n3(v+GZ;}tjNG6;z!w-o1{Y>YOd0JH z6tPZ=dr`hRZ{aZuGR*JZ4{j;)S^myI{`FN^KlzZ8%!_zvnT$Lu%-lnlt@nA&x&s%h z5I_IJ%@IWb!OF+JIdcgZ9ejTK%!S4z%ol3cQy zu7O)i&CT`tVsnA7-@ja19(K&?OkBr^pUc7Vk?!x~aEXdg()ocr z=5csRRWIEL-_Q?;-SQ1dc8r&dIzef=g^BUn3Na_mprO6x{#E89Fe}rr@bL3;Z_q2R zMC200oL{MDXYz_RJXCsPk?HEXP|15NW!Ypm58g0`^@GSdRYW{apMg3~K zJ05POn7r~n#dc%&*?Ft{L zqmKkj(VcHyWwq~cp@099n~v>Dl_6VjNv&(raz2EqP^-|Uc%t+kNkE-n*(^=iuTqj@ zweqK?Gai~}E*MzuHrgjzHQhgRvNgATJW6}KU7+5HU3lk--@SrO5ksQLjs<&Ag=6;Y ze-W^Fw;PjXtbYD;W*KM8aBGP(DMhR{3Paq(X-o`VDWywJye~OSUt?Gih)~J zz4i;+wsm|kuVyLL3SgD%G5EePc=eI9(aOFT@`Tu4{ETVK*8J7RJ|}t;vvf&uNi~Zf z{wzXlAo{N_BhrgYCTii$C?2X_Zh>U3`@n+9<{2xG-$;zVzX2)^k53T-GbUVZE1l88 zZbk`U{TRH8>)2;Y1@^9_KD?cH9G-f-+w;`mWJ3%BTn4%{$zTZRFjSI9*2vPY)>0D< z#H^|K@sBQ)Myusn@3I5?0h}>-wWFu5x#AUvd-Dm_x=*EvQP-A__wOigxw{cVRe51q zEuphYuX86hoReHjMt(WQK==ZgaKQF#-(h0>VpF~nghQ2 zi+L>|S;3yx{cRK?hXgfFE0|l(3SHIhe3r`i7`5tbO^qp4Yp8=i)JeuuKh@EK zGFZU~L5p--#|21+3kVHfBVEx@_8iqww5eUdZEu#uP3lm}KbO-fi@g-@ z{^ab;z(Iw1wsNmvCtmG$;}?cgdCWZ9xDrOhgeV9)9IripL%c8}xl%64l7hrVCt)Ejp`Jr!QeN zb(_mZw6Uu$uemz9{IDR!k)?+D9N2Bi>`(LU^aF+O^lq`VOj^qSEtoHl`M!kU*^;r{ zOgEZ}+JxhkKCUR&>sU=@Qo=E#xNYp30QGEsT}-A2Hfui4HzT!h&(%<`k15gcB7VJD zjkA&Ha34cm&yQYU@)PPjw7)|DzEUJOa+>+tcQa|TF2!V6XzkjfvOB3H*uiG)?kWnc zs8>wHX<4W0quGf;C}akQtJAv{$CB@x!CH>HAwSN#+BIuCUAvvyQl>ukXKfg(*^Khw zqzBH3!dC;w*~@?S%vl?LSe-!1T=EXPiiWkfPgCbA= zBDbw1xhv;M@EfeWSO)F86%xTn*H4XEq6TSt;yWzJz4nr`5M!XLUe4#s8rOb(ZQ-TL zlP)15niV1^bSzxEt1iOuFG9Q2jaoi-##2nhf95`0@qX%+vZUngU%X>{?3Dqx`QPo_ z5nnGkbB-0w$TPOs@Q#Kgmd&O>0YP%ufQwwzF}7voB_y!jUnvFhB`E`=yS+16oqj>h$7z!0Z@yyXYBA-D@Ua+ z8O^!npL^jBp*zc(fnE7HHu2Rsz}&3Kgg4vbm`LJm!%y1>>m1 zVF!LOX)H?9s#?=J##yh$B5a^HD>W2XpB+Z7{#++0sDAwT@v4t8>FMX~i5D|&MBnJA z?`d|}2j=-;vUf61b`~5&$YD6JEu`n)L4p<lp0tjvWTD2`x4bgK zB*75Bi?Ftj%={%qe-qA zDJSyn>Nn$JTz}m-D+X0h#6cfD>XCAeEJNfJ!#a-(^&s^sM-~?^$CZpkKZjHC*jOI@ zoH<^T>!Nx8`QiON$ZlTV1i2bX31MId#)lJ0fmBgL3>TGYpiA@2}qmi)l%dE951ZymFrx4l_O2%F9>Yf23 zakzVw3Edr^ZJnrdh?%dZo?c{Lo@^~cv{$vxe>yt7S7xXAX~HoDi1G9nkkFZv(HWfol;;Mo2=Vr58unS~p8Q6L-cXt0U}d6*o5 zrJJo8$^R2jhgWaTE%);KNwPJ`jAOXIed0gkgrm{sH$AD3B8Wfq!z}tZ{+qCe4u73c zYB%5tcqLw%;o0NsOv*(}pM2>euIU?YVoGn^PT3cueQovOu=raBw+uYALZ)JG$vBw< zeU1cOwLfl92Zb?a&s0qO9MqK?X>)Hs(xeI9oQCNBgp5;X&YTx6CzJrebxPgQ>Ph(U zWkn3cyNC$vKlmflsMJ+xrzf)L&K-2RwieJOeVCG6xpHgEokO2%U(>A5{;1#s-jU@k z6AGdE0+&6bZ_G9`O-j~A-f&$$-RLhGj`D+qMDwN-wwV;zMGe6JwGwk!>^Q39bBwY~ zj7WQ`2z0wE>Sdp)v%z2>nOBtoiwRZ^j_xCa!>>;IPW?OpDwuZQX&$hgf*`*{)HKT+ zlnpfF{A3$84l}7POn18o!~Vg9jKDsEbsUTT+**)Blv~}dG}X``{g9l62Up$l-2)0{ zd6Ow2*1tC*i#qUSmGP6~drg%)Z}$+vSu#@o4OnmzO^D^DPT zT9>^yq-}|k9cmei96L&yrSl656_MeFDCkB1kFYlZ%W-YH$Mq;mHqA1nQb{FB5+!Ls zbCEPsNwZ4Ppg|EDh(^tl%$n>5O-f2Bnv_x+&`1M~D(SbbCwuSL-rw>6e~05cc-cJ9 zeP7o(taGh(Qmu}INu6AGz2?jLqe!9!fSa*K=;mm3V@JnPBGNrOH`77XJztEY5*?_c zENWL>Aj+L$oS*HGq*MIJA%9SEs`LDEkzL!Z>lMec_PU1jVfo&a|JAG8*P$L1Jvw;x;@v3O9v?BWQ^97umOD z-iNyH$!_kwRDOe08Y#>63*P*x4$C=MSS z-Co#Xhjr7F@h(sHm;O&UCV|;egM==pUjbTqKcL?Se-kK9j(fIbr)_;-|S#S zGcKE~b@HGWP_yoJbKfr=_aQXx$H%LL>^nVo*|LP_zHCsEHAp$y8p^L~j^GygZ8O1x zp(YyPN(0z!#s3;H4Y|NYwP1dFpe0UYd~X6)fCd^540BR3-pn$OKS|&vt!IBDwR`I- z2hVgU|0js263Ae@lIfR;0v8LItr9Oer-bvY>aXb9-=)?*&6=nQXN*~oUg?7i@HH5} z)l?L+zv#u3Q!X{$%k{Ja<0PK)gk3Q7Z=yiEegBzAR#pbvI~ox$JVF~PLR|c z9_YL zCglV}_eh8JTFfg} z^nUQ?zx7qN) zIF3CfaOnOW##K(PS^HH~#7(V?rqAfwT9n*S2vJ-)hwkSa)8B$JC*U zsN4Nxc!6Q4WQ<7ZiR3Khu)@H46c^??Cg>_CRFh#nKx{u@fFks|Hja#AxV1DWP-G>g z^&*2r=*y99X}Kuks_whyk?3D}SZ+n~a9e&;y)}S^>f9i$sl9RzzkLz>E#XF};6r0i zF8b{&nykiqIN`j}Q}P-X-&OrtBWu|AV|I2{owojA#c_m7ULa+0vn5^{zaSm2M z)+_q}<*}??Yn(w7o-_%M4iY4+Jg41F2a#PuNbO#HJ(J=Ej%_m5GbS}k&S#?p_S(RT zX<68me|jg!Np$&AmwZGkhzM7IOLP(4;>EEZR{xnc{tXe512`Z1$?-5F??z2<*+VT~ zG}J~vQF2m_5loFZWh0v2tIg;qhM`fQbID+}GKYVx!&7}(7;AhR9sP6L0TLUWc68PCA1>+#9hExdm{cP$k>a#eu#ZI;o*Fsu1hpt0x6C7 zZ(e_xnpZi&aJxHD4zN|Hm@ky8l{nj*K5afy&|JW=<2LwnDyZtfh1zKGtQIx|LU{{c zOc}ViWcTfZr_FI7G4)SQ9=oe{UFx4U07yn$un#cxa4rP&89MC${kI40 zJ4(*Rn_C5R61grAjftZYQdU>r)~1;tqmL2kfp&$ubrji6*GQO-aNd1tk22=!w{fIp z2M>h4v^_q7#b@?Pqt5BOlM z7AfmBy&uEA!VBl!{|Rv6TAhH;$!?S?eGJ!0LCiAo;={kb2<|>k2KyJ);rZW?l9xN1 zk-|QQ)6WY?MknZ0>7n)H)O1qyL281U1h1*UPIr^3^RA#Bb~heAx~b-7A0y3;6?%VK zT(RmN{IN+~JoEw|znjI<)skvh>TX=MlB71ZSV?tY@v614&db`csp5W5>bkp{H?nC{ zcfXmMnK9&QvKc}fA<0N_3hRj9YRgLoJu>Ult=|a1JDAm2ii)(xi6k<C(Hnm!;-^HNG3&c|LCXZGC)=CK zt?P(gC_*1U_9?LB34{>(xkfC@H(nD%UtpIpba$p=b>G={JS{wNEc>7d;0*DIiqW|> zVXJTGN|BHfUy^c7@09BmuwhDcoHdn|#g1Xb6m_G!x(Uoi!fZyZ#EYsd?PMHw>F8i>L=CTmLvH%3g*5BfQ7nWbcIa7jV62Uy%&0c|yshp(`O9PR8A;~0vj&@*e|L6@>*xg&81Bj?vf++jr(8K$Eu4;3TkhaUij-T?b)gPQ1s_hJKgz}17xo~!#A~-|PfWv4m};pa`FLK`dg%BQx;kQg z{|?1)i1bNgkHM_^jAQ#g-C~U0_Re^>gjfQVas72S&8*iuY;|06jYRE>FiyfzKTieZ z<9voX^KdRz-_M^*NJfOyH9(;;mLTyW#@w~-%JVFctfLM4{0TCniHDN4zR_PaWe~TQoDCW6T2Dg6SL~qUC~<|yIu3tp5U|` z_{WEJVs-Ci#BB{Jnk*2L5%MZ#}&R|x+4-!WAakJ3D`PiSx_jmEEQRm0h zmNb82OdQC0_VOCwh}S*V)Kx=<`3i4r?D3U^N2HdKo}ZD3#bGMHnq4G{-1$`$EzRWJ#;dImS!k=V6Dq(97?@l1QInOQRp3u9&XSN*n zw%3k3!ALhEF_C*X?$k=lEReIT5n^tSxZPHX=mONUBI{U){f7z+M6tbdQ(o~Dloh=N zECgDBaOGZc6Lwef0SLVg7EfjMON6EFbuqqB&an!Sp#TY{zb41Ge2Zw}X_uAh`mk8+xaO4ER5tYisl25jIH71aO{Ud`;Ts9+*#OP=z6t=e1^RkkNDmX1sq9PM6A$NHjRKj9P zQ}Z*QWJ6V40VnBQ?5jTU`V`Nts1<54*jATiJ>rPXDvnOfwWYRRvqE-zieXRQ1qb45 z0OLA!DKzS4O>GN7OtRqE1zKwqopx#p!j=>K|9W;kV!WN1XK82m$nWCCNE5|n|7M#0 z@5Q36#)p!w`NakE)RPm=wE7rJg@<+SA1J$YJZdL7i)(NeGJ26-CZbpCn>_K81JY}{5&43@2wmO6sQhz(pa_>KujF=|9@E9e`xBzee6nNy`?`U^=mqKiR{E^)9I_~ z$fO)aT3sW%wS-JjJoh07bmYD*i|&WVun@#(*FgK>U0wv8STcCYN?heMNM9Kg>|byK z#!T#3j+(Mlw+Kn8 z;xk(srv(P;hP}HBpDoh+I{6ciFCE$7;9$`aJrc?SSJV!7kdg4BdJm_^0<*G4Dt&iHJw$fN$6$Qx&W=3&GZr6Q=@<0H1M+tj?iG&2`Z}|cSmG7*~P9vGApUbj+ z<7exVB*<^KQ3FoTVbJbGFBzO_#S>y|^W~ld^^CJ0X8%Sgst(}BAGrK#nmDa=Ms z%H`Hcb00+4ka8#dwQd@6D;{D$+zNVbu$mwu{FIw$CozIHU-;^-i70+v<0qrIqHgWT4UN)|TCQ{i+F zirj&x-3DqwOuAqkaBtXbi!%yWYns_yMc2*`r_rP?Qlo-Cf8X%0Pw=w1z^?lBvMgz{ z?cVW{(ZLos;MX|J9s=C+BrZYXwtd^oxl7rg(H$}{afJATV%rhY0aGx>2Mv`t!Rc#1 zT9-9D4xigw+(e7Fb&TbLu_2IrCD)^0$KRs%MAE-o{&x1sNc(s$iGyXfP=XF_~-~5S1SZFWUnVOj;$^7{G{4xCIc7S9Spv`(@^>%v^l-{p{^dCO7 zW~s)8IwXIg>^R0fSk7^X*hnRH^rog@rz#fzet2VU5Iu{TPdaC&O`{4Ci@uR`i7gON z+yrt23=^bb1+|e0W19N-ePc(PbRX(&>aV+XN%>To_N|L;ca%`Sb}ppkJuC$X)P*rW zoyBSdF)-xJZbmPcSscYnc`BmSEP7yiW|6U#>VFD?gE+<>DhVg&EB3F6KDw`jMVJZD zm=r)aUzqoz4<3rMJ=C&)gL(|#IIpHy5mNC$}4Kw`gxktW{cQUBg@L^Ixy!*+P&q zKro1<1l~IS15Os{R_(_QU+|s(UVm4x&?W8ob&^3CW-lZ>bBiH^*~Z1zQR3t;kwSW1 z>-sWqZMp!(8}@G_WFZMidavCLzDeeMPC@cC&O3w&0p?U9L9fhjQd&|}y7H0b25?f~& z2}xbYE$gWV`l%>Y3+whZ@d6JlgeA27sJ+}@1%wI>d>u zTJ7cnJsfrcR_c7v1oFG*@BWWecMV-+jrcT?SIEk+s-Q{uuKHQ;5F)i(3 z>#-q4DvkJ7cH{O&9vkB_9&Yr?=&xo2L+i1cv1`^naP5?X-&PJuK%k+QQBu%kecZe7 zVz2FWBc}k|!hK_fT1CrI%D!40^f>i`ZKX-2iEEqioR430CLguapV+0vIZ?8rOM zWgzOu`uh4;h0#MX#D7%wNw3g$vz`CK*8~X+!cY4NUNGcD7i`*E74jDsU=LXwb!Um) z&pSnr?CX;QwyRy;L8=~EqUoMA8X_i`5~c^|5+A8|JOp)d^ub;0a~`02+;6~ok)qhj z!I-|gXFcsP2vUPxM<+iOqId5*)$^ReRx`MMfLTQYL%o=O`&J3abPAa|dlqT7|l ztN_C&8T)3b2fZgGBfr)GTY8$%hv2fh{6EgNXu>!xur^@6(6II=O+M(8rgj>oC;fTEw%s`6Nw4z%6# zyG@zP?E=^?lj%A~BZe0$!1dI{Glz~a190E#u90)T7(`ujmbTHkM`RRBMl`UBnvLW6 z?9qim@@tP|fdVp;^9`jZ^;XibaOxmD4z3~KTu&Ab{=eG=UnjKSg=@t63I2k|umSt% z-=hTXM)v|2a8ub#aXUCd-9|sB5k(QBN;A8N*_rInC5oG9SUn((b*!IiRNQHVkz%a8PcJpxQ0|3Ae3G0slo&mYZq&6+eQiB zwk%9Hj)EeaF=9pt12IZ}K;^bAVg_s@ul9GJJ$gWmHGLrJ3J)lvu6;1&@on_{eIBg@ z3ZMzHV9v2{4#XFxfuy#Ua(eov@v31-1 z;YdUKlUz%v#$Z#lT%KR|xWi_ClfW;&-YVgBOtodr*b%!ue`VK@`GMxlaoIj18~J)0 zWcipjHLzhj7amZ<)LTXPD^wh@ZP$!2`D#<_xb%P9>u`7OAV`8`O~r4=S}q#A-pyNY z8cNrikAaXFYpmlGs~g+6JY~O8;hED!%BgJEJU7FW7rvSHi|5@guj?hUj!eff7SFVnEQGtm%VrWfjMC}_QhX=pDMqDmU=}M%$=0oV+K+i zTZpp^Fl)9H3B#BPPt(VWt_m}38IBbT zTMwIHzx)W86cw=Q5y04kK;@XNZVxJ~ZW`NVa5WbY5-Ex&;<-cME1k>O7py{LkGUIa zIxtk|CW|XZ#&5k}n52MPU))2P_E_4+aOr}tWRaHNKT|&P(%hmE9*(%|iT-V^?Dt6g zuM>Igzi3y;@H()0+_c~ zJ#0^9@Bm7Y*8o!kH7{psWvJmxvv5%b22UaiPr>dZuJEoGOZ1kp?ngHX8V*ikpuU8z zPV5fnI|Gofueoz5W_q`y`s;WdUur1SV$FOcoDYw3i4>s8X$u+-xZFQXKo)D3_bR2Gn9o*Vd4oa1^IEVPp6JUxth6vU zkMd)2&=hzFwW0p^TWQf#hIo<3(VC-E;W0RL{bKPH?bxg&wv!MA#8cNLwqPNJBLy2g zxJsBp4t4t45goZpa5U5~4QVPnFun6b3n4@T%)PU9!`=oQRJk1teKqTlC9=ji*xC8P ztP{Db-S=;bt8WqsiY@-@e|^ngr?-^=d{e5o*qd*-_pBs4H1EGi#l$r6zM)I6W_^R- zgl%f>9eEZVI8U3ue{zyAaH3Bxq)^nHs?i~c)XsY#nuJduM zU+Cql@72T7R>HmD%NtRYFRr4+f@e{(S@*auiqSBftuycJs0UPQCynu`&w2Z`&ZgBO ziPWF2(Es<<4Tl%X#DT<ged$z7G`ddp>;)j4JQ(yFUJS7`bljdBu;Kkm@(#K);cO09Kh^+Jc>bsIR=gbVEj04LU zk`%fDb-NCT$@n|bGx@jYd)U5dQcI~FYI*woBO~F@wm-K?jhDJ(h-myFz>?FpTUt$jH8_x zYP02_&yy_NY~~v4B!6f1Zzp+yFE4rLq5i+bR-ouRpV$a@EMZ6w$Agu{8A&jpW}H__ zn5F%R-t=^dR)TG~g4p!D<96^6Tmk6V8ZWL>am+?XFBz@;IRo7} zKDHcI`eYSTej2g1?FyLTPT=|1Yab$IjB!0dZpn+iM0ZNnMZMJd1VRDptimqp-%%Wm ziZ*{TZ!H`hi0eOLO|Ox0+v4!`hw|XG3I6D9P&h`=G{7oltxZE261e9B`@h! z)Vo8U>+pG5rh9t6D4$;rv~;!rRVholA9(w&D>~oAVptLIZ{7N*To(@y4;hgxuD*Ef zUwB0vajjxaTO~GMUui9&N!jb#Sxi$EjX^mJC#PN@*AD7JuVOOUIsD@gnKgqf93)@@ z?<)z1;vWHn(CZ$!wf7I=d`AQdEUQ)-eDjSz<_7?Zu+B?J&`?8yl{C1Ji08RBZoZ2pnRfS{SwTELDe@&O3yJ? zU${~peCY*oPEycw<5=(I920;3DJnyZDv7~SCN=a92$KySQ_wdY2d6^7`rwMY(8jbp zrC}w6E=<~HcL5;VCvqzXGBS~*d1f7ngTL;JRvr1CnOlBoOH5dO8ya-#md}2Q_qI|x ztRCE7d-J?HFW>xnym?-6*2j3~&kY;N%xtPw$t?GEmVpOI8CLus&i?qct{ybDkEf6L z?(26pgS6a&R=woSH%~p&1KTs?xkikHGFUunq50cI_ikkISqSx7F>=AHR5b%%Jy%oe zfQz1utybwQMz`7NeHsVy(yvlMnt#4803po9kJOcn{c==R2OVV>40&{Xljjj;Vr(6l z>w?bop&Isio)R7!7#JwngVzu?nfvq-{2UI$idytw#v#^@fm(?vZ%COe$~n{@y`l2H z!@gF}JYAd0B!-)n>Z5DdR5_S>;%n!#5m0IkxUdXNHX_4)`pF>^1cedod?EW6g4A@I zJkH@YRl@r~UFo3lWoDQ@piXtMeYN!OFA#o6F6dL=u!2$Sklta8Lms=-{8DHB^FG-& zq81HNT=PF)7_YjSe5a8@NrPQ(5d9>vpNBAVWT$J&+tjnQgXo6HlD)`7Rm8uu!*ldX zz-~do3cmKMoMQ60$%merjFHa}zNfQZb#nx`a)xJ!k!#^&icDGdX>d*&cSDt!er^fFkX_75j%Dh7S1xSJjRwC- zFmYOSimE%tP6I4+;a}&!l}XUj7wGd#%%(SBK34HXpS2J%O~=GE?n`=Jvj}Q8gG?*a z(0{mHKJj$eNoqZ048Hfhrke_jIR@TMl`#KiK^3k62Z!ckVMFz0!xt<=-Va?^5wY=q zTS8b2;FwO>7Mea^D;_sgAde?q9sllN$`SjONTsw>G=-N4Bw+==qw~3vZ4m^dj4aPOH$&QBP-3$^z{gg z#47H`&d5$%%5+TYJ?-^i8fB^(!)4Rf5nW!lE$G0BkF(Nt>93LLfHF0#%NrBxKNa@C zT=nwm?HUrwB4-)lFoZ-LOJ|k43H}T^3XMuG-rnBJbh%G~H}Mtzy8c7;4QSsO8`rAJhZyYgWy?9^#T|1aWdu`;rtbiWO=@LzdxKK77N{I?q{F(#6* zwmbk~jvy_fai)g;U@bT43jaRa`no?q3rB1FR zfeD>)jZ*~~!s8roWP?v-1z)bMy#3EE*JP}|u%cv&i@T-aWxBcnqABylXbV z$RpPiKNA3au3~38=b0buQkdBEo#SbOJKH zZ*|W9%S11qe{=6N69cJMIFN#BQYL|mRUXvb#SgWzz{UeBT&%_Ob!}>pMI&0WLfsL9 zs+?BZc@33ZVC>#KH+3~YOiHTx#|-?M*bK6$OTmFf_P*{dVcg8-6^yY=@hskRo^!88 zRWTSY5m0eWF4kGL9u$GARJX=6^-WeOOYTQ}J}nk(`zBrjixH}LD0yYU>G`~w=Av*I|QW*j$KYe zt)$rqi*5Qcpqs6STJUBM*4f-`fyh_@XoN&#i*u|%INB*<%2_aNeHxdW^s>rd>)H&3 zK-0zKQ9^llY6{@k$eBf6!PcP!Rd_FaEg?Y^cPe|S!7sxfhb`R_Eo)uh^B@amj!l3_ zQ3U|mySnn)CWFjt_^ZMXvYk5bvy1lBvo;|3O0EWPF08$*1&v}wwHhxx(6EgueVF##Af!F3 zpEnMd<>39N>1nP5&2^#gzhq9aZl?57p)z7JFy_HCmuj2W`V6w5YIhp|Rj=*ovB`ED zgM~~PQ^f|N6pWU3P3@aKF%+y$_4P64oKG+2l<67v!ox2+PFWTpwnaW#AN;RsKrWG% z9Hj+83crq0l8O-&8$0I>`@Ez%LNjJJ zokN>FwAyn>|GD2FcRH8_s+;%ex$&eJU2g~UFS+G)imqO1=&O99Jl+Aej4nF} zWcCs*0VzN)CR5R$rCHX`7PPGm{=1a_Rj|t`ks^=z!Pu|5>I(L$*Gw~7HQiy?S5Qzm z!M5=x^-qQq)8Y_d~oO!LTzJc_8uNp)T#yzNDZoi10^W@|{rcBO6lP1FgF! z;3e&jBR|Swo@HQ%qE2ZL!9!hq1`O^|p=>g)7(w$H-m|fC2Tsi*8m~>#m}B{J@vdM0 zdKsIBEgG-u0EzTVjy(0uJ@vWaWr0N+F8;{ry8@%qgVRiDSp9A}MP{Jh-#;u4>+?>% zGr0#wEAB_%8r#6OSOBy6Kl?P6|2>0B6u}uehp|@A>6;9L)6#UtA~omo9#=TQ*W{n} z1=`Rl)Ka}u^OoU0*BQwU7ruMB+26mrg}vWPrCT^=`=o8iu|3d*`P^uB#aorZn68NM zaP#)L%#RLW8WE?s5TYj05t(e9z)Ou)NheMY&^$#6O@N|%@fbLi;w}SvqqzbZw&F85 z@LhqzsavjYb7(h$!_>gTQ?FLjTxIB+H2#@<=#SEXh*u<}t(363R`!h=z1O|D6LA-l zDVrU8k3NSOP{!pCc-3h#_LcmJW<>ev?1Uj1lJc+dx>D=0uIbM3H$oXs#zdpX>&D-w zARP7-?_gr0icj}yA1<8gn?HL0_hFDuNQ*4BR4pxgHvgEUG)+)>350Aq`=<0MSdu#( z#1*NAL?+B%8@nc8*hY3ScB2ui*;-dBn)2hJdf5A{mJ9)nWveA$ZFrcKFRM@R<0-JY zUwzC5ySoyVoBHFTm~B{7md4VGpgl6g8Y6ik=KB5|aN>zZc1jeO)Al8>P*EWJVoVf` z6O#_r#y1e$oj?zpc#0s(>e;q4hhTgFfvq3td?}i)L!}p{NEYIXG0MT*7{_HKD7OY~ zB$xF$Kemj`8Vf(^l{Dr{QXZO?)sSCR!}qW7`p+-(37LITSkZI-DTHgw3FkwQ^hjcKNqB((;jP1Qp+`%AXn z{hSgzsD5!k7hn1@uqIz+JsgPi zt2b}pYU)X~K!?(nrz%bwmOcpE!RgI#hbH$UD5nW2Pq;u&&&2PsO9Z0H<(IT(|^4W2o~hXqWxN~7IvzJ!b=(7!Xs7{U$#YeV7C z`sz)@c7$w?F>?EGp(l|lXmQB%ksFktkrfwzEVmdmhcH6Hk&%R4YNfP`NGZA*0h$!M z)Sxp)u>#39BM;hQMP=)6NV^QTpI|r*StVi&YrdxMcP7WnKB96n#6cVdq^P)s*Q^^V z*={JPEhhbtlaV5rjp;S1vF)$I;-8a`pFt=NQrYwpq7ElVfL$;#zy{RW?8{86R~vHk zq*D|U=U413;rI%7aNvgSAb+dz*JoyCQUa%ca;#Y+Vvzg&ag`{mx}9a6?zaRhVy_FU z7mbpVl2;7NWxpp97JAPpSOgVtX%t!e8vG926$T>0N)GMH_-@LtXR`TcAZVn zP>h*|@qZOlteL|M18580*L>cU`qQr1>%s7@#Zmv42ZzrjQ5ASKg|9@K^+yx4n-3F! zv8ycvbXQ73cMT`eOY_!@E9l*hIn4mF*obiRn5;^{Cft$KP=T!8?BZg%eo$`;ut)uN zULYoB5yWWZFRb?o$dxh1$+#cD{zt2o`&YzRQE)b%-eJ>Kn#RX^ zX((}QatG5oiUtQUAtmOSeEGc&#PtXE6ba5Y;JWrC>>0jtO6-r<(sWQjS_XZEJn%vmM)n?AH@u0+?f_a2MApj3eq1&cJ0$=0<%Szl7F@Ky(Gvc7fONoldRP9cLRK*L ztxM0rlq=d4mAabKYHHOByWRF{@4bP9uY@@OG3f*owvMub|12d>psjD_x_~}mt?EQ$ z^*k01m>sPERvlC7asp5e8FuG_+^wE8gHy_jiA?1~^J!d}DuDGtZ8>er8>V`4J_CEV zqVqTb(R6{#NX7czIC;=x?|)C#FrYcYdT@LW)fF1|A1^QE-YP3C-H+Nw$os4K<;1i! zC~BVGzC_#}h#gksO-l`>1-_5ziGdM#QcA-`)s17`1E2{CeLZfhb1T2q%B-M0tS(OY zD`2*l7|K`g@Fge(-z2K0X75m#D@6bSZDP4A@Ok%GtwQ$I8w*G!zk#@3zWC9uxcgK_ z+)q2gr}!;&B^D68&p~^7{x^#EQotB~jFwkb@mI&zEO=m^Pa&A%^CqknZ0b!hj!$6< z3KNFvV~!~gQily=)Qkb^F)Ue9`A`-lLIUwvW_ zyp!?U`c8TpW51+)jV_10;__-nH3>1@Pj7DQGm7=Tav?j|?K5*SN>bp2M28G!!=D2d zx7gc@=6-qv`Lw%^54JXmh+n>Pg*_!$-8sPr3>%oV)20TkIh7%A%E%$1uN_u8oX=66Z)BStHQd(B;ymPpt1oK%m(VJTf8A_CWsA zqezK*Lr-Vy^$Xliwx1+~81~X__f;O|KsZuZA?*76kL?xkWO{uvreQ0DlkzonPn?A1 zY{Y+HC}UvW;j&wv_RPJ8=a&L`nPZ7lsJHv8kW3#>=>FdD{tIte|MSxs{6|yCIRmW;%ai z3d~Z!6gGqBuN2k+3yn*)<)g!tTS3dW(d-lw5*p@u-n(F}vXkaTbUXw-E z=a`LONWI((eCNvB-F;NmPdJ>tzkj%J#RY}o!u99;_pe~z!=_EkM#IScbK|)KY>Y}G z6^EFkD;k z*AJgCT0wi)P=PPJG%Vcs;Y+{X5p?<;PF?<*X)4!6UrT&sc1dksOMWw5mAj>MkV)+i zE*U+t*aN`!sRC0E##Ww3d(4m0*P`CLS;R|24#g zi?@sH{Al;fh2LBIj^nGVO?dom*kskitx-Wo@A|WEf5^LTQe7IoSHKquLgyMY?Ztb8 z7*kI43%>mjQ)@iOFTSer{=t2`JSv;x4rQ#UCtScTa2qebVl6%rf`=%_#wwS69fO*w z%L`VMb~L-8*R)}^dXQdhhPZz@X}?H#-qJof!)Ov+L4Jl{9S zBtQKp=t#-{BpRFiWu_21>11f&6nUsW+Z0qnUETz%ZBjJcNe?(KjN&&BX^)!HEn&L` zc+xO9dr3wuf_-C#BZnRwQ!~v>ikja)e$qgs;N1$Zy z>(~vzg0(l)NS~2b3`6V~_c#Ehio0(o%Ugtg{4nB0bO$o=%trzVtw5 z>6Z%tRP}a<)bpM%1|>Uj4TniZ%*oLn_3^FZ-0Y%8ddKUE%LNy5zis<&RUO*CUViVg zM`hako-CzIU~n}hvA8@CqXJ2zHWO)b_OA8O6FNtE2EB%c#WKf$Wo(Pp{^ummpK2y? zJYt2t6-$0SdTu8MZVE3i&ly9UmSn{MmXKEKiObX%!!1Y&5w$;xGL;B;g$(j@+!i$A zSThPyIfz@lib@Q&G(~*tr02H15UE@;v){kpVwTn^$ui9)vEp%_e3%l!TY04T(E$n0>EFgfgxCszOd7r9id=u-#*SXB;GI?_$Hm&bE$|wk76C4{FqKr|!zBHNlcR*?!zy z6L?IjFtepdE)<)=AWvr{y-4q?=wokF{C{w1U*!=x-@I5CP`PGlbvc)Z8q+h@i+%A- zQRl*<)xl&)0GIKQh1n#saY7wG^goh0fF*6iU;l`%d27(32%EwZpMf?#8+A z#t3VF2+Qf5@jnje?~W|f3kAOO-$>x$y}ID-Ql?xW0hO#%s|yt+uVawq@pjF0!m&-~ z>^AEKnXKK*Y~)rm2&Z(iUf_YY|MPETh^`JW#-e%Uqh21zOU<(gsoyF)JS~cLCJCMBPW)jD(X%3f#mJp0g|V`*+QJ zewe0$&hPw38nJPJ-?xK(qxJ?ZW#CB`$eT!I(q4<*@&i-sn35ghjs@6Ch&b#oW4EVa zAAtBh*}d|n>B=``3oq56OAJ3B+haoH)}%1kISk%D|C30_7EZLBmSX4v+P6cbxRbv2 z{=p4zKItK37IV?i7k%JMW}yF;bLEEErBzDRSxtdk_nD@a8Qt2hc&gmUri^JD=ekW> zFGU>FyGXmA`v+}$f=}nl(KokMuj`cBt>3rCt451s*%hYT=XIiR_xv#I$!m8KMhJwP zzRl@TH~cwLyob;N13KNn&HU)ohXNltA9srCE{hE6UXUFY??N0 zz6zEu=gz#HjiO(8{yOo0AN{|7Lcb1g;CXq>ruoBuO|F>%`^63xX8P4?{fVTnjO9De z+gC`=zeFs5*w2!KQ>7cw!hC3Li6W<;CR0u4LSKQU`ig)aAJEn@J#Q96nsB;gy)m8V zJF)xchnvB-2Z{~H9QORdyGuT9ZN-+0pv*krg#uLjT!PhBMcL|WJm)vWSfEMVr7g;Q zbL|&e#kSHN@_d@~320l7Sw}gld`CN^qc62Yas4{gg~xetDynE-TwS-B^xvB9=8bY3 z%U9v%53tC+c!DX+k~KguqiGKZD-)FrWE!(8DObgStKbresa?_#7 zURov??{S3wJ#)y}(GYUE{`-SvAxW&y^?Nvf9q-Pf&09iTR&Acnq|c#Mpk526Sz6vb z?}O=s$;=q^Q3GzirllWOZW7}2zAkobFTX{9Q`!xd%a_cUZhTsJ-hWX@rzzq{D3U<= z!!x+(2Ov0Vea(}1Pn*xImHlGB+;GJpQ+)TU=r^BCwxC(nG@ph6Mip3{;alSb`nG@h zh%z(TsxB$P3`o);Ece1g`^f(lX!}DC-*y6RE|>W#_mS>-NSGWiuTNG7a`;BPLG6#0 zg~ljA5=ILrc8PE6s*X3rDg>TqM&~X&OZ3vqjTK@(bBKqwUrKX}`9Q{M?O7bv%3S8& zDO^|C__FCW>mKbJC#p?;r%O*{^=8mC(@nA$f+Xr(seJBV1>oNi0zY9|javKamC*|A zf9h{)Wac|SVc2MY$pn_X?IRc`3VjRY*vK4G%oFphXbXLdYPcYef4gC#9L>IJwxsO! zXQY=7%CpfaxP-z(uhe$E&Pflr7nviH1dmC-kKjJzfwQ)7Zv}9Zjzbcfj*7IdcsL6f zXjM(X(4%A|wMV_<(F+yPq+}>8u+2hUDa<3TIH@sT$o%950kIj%wg%=}IrfSNVE3?y6!*vE8}_cIe& zJWJlO*ESaZ({lrV)-0iHcUv82v;iii8xP)*czCWOjQY+0^&sYdsmOricB@Mi-(-8*9NcOUEzEzYm@;tx!o)x`+ti zEW*WIxWGWxpb3D||N9YEm!TdePb84hA zAoBm~%t@0o7w`Nsu`~GS9v&9!(c%+#GJQ)nB)$WBG{ndVrrA*A1(zEtr6#!D=PY*3K+dWKLe6t7)pGtZCCCAd_$CgpTX&z{O8k% z$7cQu9=nYJ__0)^>fGRudU0>%O}uU?rA~ydb0RxXGK?v*Odj4Iw<1G8`s~jFA<7;} z#UcL|bw)K4(EQKYscuoU+t=m7$s4~LOn=j7IRMDAdfo#bzU!4@dcrGkm!Ir&t*4$- z$p{KUNz%6_E_LfT55Pk)vBRg(Ulm+_NY*2E|AO|*YO4u4&I zMKNDT|JKQYck78x7l(hNuasXM4xcu!wZr+ZU2qo-2gBpS6+vA2+~=ViG*kV=z5{Em zUGGxv3Nl9+8mtFSOnn%QzM+|EhH>LnPWq4Q6eX^1lRh(ckLAzj+-uGk)0;H_!Y*&o z+QEg-wt^vC=#WYP$9OiPeD@l~^`xRWOPhWNJ?U-kht>F_e*_U3B*drp-`;4yczT`U zP_+1QGd73aJ{jJGFfh%Lq_D}r8{pgXg!{dSFbP&e_{C_ySlpIx&(5$x2)U?R#4y!p z$4{F1VnmVC7juGryIAG#Ec5J?qdPy!MvW-HWm;}Firb|3VL|rNh745m4gFmvzx}=s zEz4?}?PY^Z&xlbQu>e7t?6Y{2pV*4cM|5~sawd7N*myvZ;Wi_iAk*7}UtxVEd~@ki z$_aln695zuGVUX8)AgwJqPN*bPVc7OwQ$i=`esdkYoQ`TEX7xy2>}KNqgGJ`}w1#qT*Ss zW?~6vU6YjV-LyutQ2PA1;N#uIoSYPmX*c}ai{QFMrr9mACcDoqPhI|gAL!Z}pxp?Q zzpz9ZZ-@3>oYj1;sAlyE3*|5`&YwU>@n9n07y=)i|M$&j@%J(O=+Xe) z?l9RZxNH4+M_TQz-!{woe@u`(VPK8WqIWCH5Ejjg_-(ZnMA|ubaH7d-l_MBMcESaDJb^eua~Gmd4maUNUxCt}D010aQf7-Ytc*m|s$bhRhgUC&v( zWL6>QL2Hr{BkF7wMI(Bqeezww<1&60*`jBwem2UA?KEE&ME*V&eww>wgM`9JM5Gw|xblnFsj(h}*6+sdB5rI>72kLu zdH43!MLSj#A4lepk{EgS2yC(5PGL#m4%mu)J=S}8*)#`Xp=ti~PC#3&)xARvFezJGLW*;7@I>T=t%lO?#x>B>M z0_XpDiE8o2lhR2$o?@&aj*&F~vU7s;ca#|3?xkZ^CKkD<4nyHd^>x`>O_XmVzO!g_6FLDX2sKM+lDWNZE^Aw-$U z>TA=|Qp6_}Oz4emA{q(QgYO-?Kye*Xnl3XV&qtry^?Eblryn|1jxy7I*@bjkGfQ=~ zbA1CBmavB+Eh+;IJb$93aRf5gvEEm)Kx)8p6mI$OC|)EC9EA@`7?;wke+ zpM}f))}xBaHauQYzDKVJRl$ujohCsdOcpMPQe<6>rdUI4l;S;$xbM60F6QV>3O!K6 zvA;I1viJrW-YVG{pQx40=G)FMYcE2-vrXYyBQ*Gi@D`o8d;sY34+p+LJdr2W#;l`NVv>jKs^Zy-qtrCof{85PDWj?s3ZwPw8D-f^5M;J zG}6zqiP(^|e#s{#{?clu5G(Cko+S>=={Gg~N@?Yp(%zB11Q2C440B&r4&@7&o`S$G z41?)1Ve)>f_O0_u_Ff#qnv|>1x$OT@_8;I_zx^LDULqrOS!M4PGE?^6mB`*BG{~$A zNk+ycTL~p1WrXYzvPWi0B9}dqEvwA``-ATL_x=8U&;NLy+_PxV`PJWH@7RGVxjE ztCDH}h0ko?vhRVL44;97dZPniTpG|#e+>os)pzF7cNfzRQl9|L5oiWnl|NNUqWKFj zVLsEbh5!4Q93@AQJsR+&Ieg3H!pP;GL6$`#MBz%X6;Jssn=#(c;=U6U|jvV=%x-8huBq;x;VhHYTrFshbF*U zU6J{d_5`jm^HQ>Ma_a;bZg{4Co^1}qKxzevyx7&?Im7B2Qf)pfXw+#7v&6rKM`5Q& zw1`fy&S@sg47ze12W?B#USR#mT$=bX&(aMT{~4X?X97-&W}?{W7qj*O=j>Eu1$?P+ zFcUH`gP2Uquw_xuXY)ogdYfSgc0uFsBaB4()@Hv&CWMh8%uiR0zkFXV;mOe@B0qO_ zT6$7cu~{2y5lo^Hx=8w41jK-p3rTwx<*v$6daaM}bb2+s`3@Q|O9F@tF42^slj2ii zT;rDq>;FFwL6k2AGVJqbojuIX{Rr57Gv>dCnk_D9^O5^;g_^+>5MzXcxG`c#K=nF< zH6WN(LWu#Hlmk#qd08VyTry-Iy+uFpKj@$(ndjR zmD&Y>`Wk|n?!LcHl_*-qKyARWD)cCb<|Y?0&JG!yN`_;~;xjcm?QeAFZdmpW0!EwL zMV2*g{6WYy*B_lZxSC=H(3XfSvU>lSNog@Sp5cv)V%m)=9bew?{Zp!lg9vQO#b?qa zhK@Mkjxwc^Tzde^90tz5#@=91$BepJhpJ-0al3FEcuQAP6!4Nc1)WAD-yT1@2PN7V zl`7>VM0ArJ|H=LP6dEB$*|P{lutm(q&e*6U;rMJ5=r3kEP zX1^nlWb0tOW?dzNW(mggfGYa~dJ12=oF$a?SdxYzOcV`; zfe6x7qd->)g$PH11y0i3Kkl|BA|G$?{6OL~Qw8#aLcwOiGclKS+=4 zCADHnmG}VCHrlb8_rQ?DAG3<$wj$00#5#BIk!L&cg{c}-FTzM#_`v9=C_Z4LM|--W<- zGH^)$_2kN9&TvX@t(wQ)^{&c%``uRwoOlz2rw>RADoka#!$eE;j8_%l|1#T^!9X$W z{U3r(?Pm`u5|i@I2T6kh2m;W-RB56DrC|V^l+9om%4&Hm8?frXfZC9e?D7GTu>$B6 zrY}G58at{ScY!&<TiP?KjXTep_&& z=A4UHvW#~cFiWC`J=ddft;1@7!#WXbV6Oej-??ib^JA;lNk*yZkUOE-bO3xSbT!nn z<+u32=lt}m>dl5Kys@VsC~B1J1h^&F@uuod160Y6u4Ic2#dFBUaej29VKDwV^PO+P zrY{#Dc|-h=&u(DHhqWom>WgnI*lDV0u3hN4H-fSYO7W)41Mtxd#UZJ>Wk#_y3>gpJ}qh=j>k@Cv2)}O~ZkKy6tuAWStuPI2=8jzwbnxYRP5tKE!W_A78 zLX7W0BisL$J%Cy@9EjxE8XgU8ym`rEZH26Bp4^ey6-d9hueU%`lb}E~o(6XeWx^J! z0(GCBK68h9&s?7~K%f?@+n^DnS2$hBITaanNyXXuGwv+3^&dkd`TFqW>}LR%z1?#f ze6I&9amumCA@ZQS@;#E+jH)toBKU<0tLGj4_sSvHi!4n3R=yv`^Z!mq@ClI|Hsm{S z3Ethh4Vn?RUACZs#Ef8Nvbby$&c|epohb3T_hXYoTsreLw%k(>^_n5s=3~s6d^PaL z)qV2kMhWE9tw2ldK?&x9$(9L#)HyMh>MK`{7~vtxvwBDBt~w(W^Ve_^8=%leso+FP z{lXy8qP2fIge!?4a}qF7Edc25*(S|rn^H*6hJA{o{eB2(?KLFd+nRk>od&tk%r{i| z4YI&xADal@zH=}Gk2#~msb>djl8Aosnj4fUdQZ&vo7iIN2o&Jfhemwu>pL{5N%ls5 zMZ$1b7`Rau&?`T4c4~=YNh)3fCgLQ}L$e0p);6HI!1{HB?}$r9(+bcJ7@IGydV-fv z49xky?tpZR2Jph~2O-%>8-hF~A@e#m_wcZvkU~}?!ASc4-osap@9)&w(h=uyNj>{_ z-$0F7ABiGwuRk3>gwgzcC)7|lTvw8w@EH|&d?!`LngeU!2qxm#=dX&=eC{ZqBwTrChDBf0QeyI+^ZgZ|LzgSqX?9-Nuu`peugr4!x>{z zZ|JBRCjVI{EWf*4hS(P%qZ`$kumBC_i2y-DIO#0Ts+1SuJ_DR^9HhlrIM2$e0B0+7 z_x95EW4Sa6Wc)S($(LTV{iyRqKyCkZpgkb%ZiJ7Jm~k~kjHTflo$z%)C^Y4fJQ`q- z@6v#K(3H~|DQiA@Lm|ua3YS=WfD8_1{M+cCDk3%?Z-7#stENT^?Xzo4JllfH|g$8wI&++gJQn7XFClaJ^Xd35Jl8^Q7&xvZueJSF# zpK{<{bryEh&D*i|{8yp?_=P?e=WnpFy^}v3r)Ii}m#!Ag%6v49>I1aMDupqX(Ex|? zZ62)^GS9BCQgga_>JO2(%J5oHMySe9{;D>X?}Jc}V5i?dGPaImU~NWP4wlt`7(WZh zCfC=C=zjSCSC|{&&rvWY0(5ye_Q9*G6?03>GBC9tubOer}?P1C|Gg(S^il_o)k$uhTzT??bm$nm0W-I0~E}viOz4~TrmaaF|0pZkSQJ|wM9Pr$NHHpKb`$`$F+e5xqw80kOy<7mui|yBC)ECI)Tl(g z=;BkWj@#%C+WByoocI^-00K#!B*4{V9r&WUDnE8-5NfyyXnSbh`I=73JGVU_o-?9O@~VIpy4L(ei(-p$XN89iZMP*UB~b51yR&m- zr4G6qQr=D5VV?S45mQ&N5uQXFDoSwzI&Z?RzY~NE_9nJ0KkKBmic@V^wf$i0F6m0B zHm)6)<@0<+y7(_b2Gbo5kvN*5G2xo}Jm_v8@)Cl*1UuiE*u}kwm2QQrX#yH@xp$-~ z(faG$gjLlm&7BUB{&(4WXB`vt(DAQ?F6;m=2=1&?v4kyK{Spgp#sMxl@1`ZExY|qM zb}%3t>=@#}710zy_a#>W5;{wxz5Baquvb5jP;kx%t^`)=T_E0)EWAE(gU(yd!ey~p z8u!{X_-$Wj>IPLJP*VDE<+Mw3eFc8vE4d)gRTxukP`wEMT+xdlCrZVyNtXf9Wl2XqbjfV%Euhgxj_-y!j z2lU^cpW5vtl6(d4=Z{}1TaxMVuNW)l@=h&x^4#p<^6{eN+GHY#rWC0-_eT|G=oU(=r)ODHhHw5Jpd0vVCfC+A;Im?%cWV`p3{X5NV~AF3$My4APCLCh;!nhmmAjr7;(9SV zEKs4`brNT2Z^_vKvM?FjY>$NT(F&8)60JTeUj6nS8lbY0u#U?Z?b85LB@z2aC|PFZRD3E`19!0S=u~{-&@W)Wqw;4FS&2U zGYMXqCJ`{|NNmr`yEBVt!96$9cb#*jVW;M-Dyc(id%)0cU#x(I%*Yx}?Hq7Zf%Q0F zP=CUz5I^5=gIZiyLXE0Gy zAI1QE?lcVdPvEJozHC0R4X0sK+5l4oFjliQ@2TrPPb(Hk=4>3+Xy2E)hMD%SR=E*)Pw39>E~X!^|{;j&Vxm3EQkM3hka^QzUF z4?Xb8+uQ6q!+%SPxc;ttfNl4rQOLGTjLR?C1JxNyiObj_WZVF7;I5lBp~pmisJyBY z>Qsf+8%~mb>4rP%<1_Kvk;cj-28jDBfx+vJ;?se3of;Cq1BQnGTnnCUbcisjK^e zIz;Uj(0xKC`xuUR0!>Izw)rvrR%AZ`y2qa25B82qam9tEd*3bv5Yz^n$e&TL3ib|4 zC=~BK>L~6SP;lY=!0;b0ey2%^lB-RmlBW2frv>!8w2HlP*MDqoQG8e#(z!;W2a}6Q zF^4I`>#rB>=3pMd0+SvsJ*)YgoN6Y|39{N}{83i23%!ygm5Rb{j!Fa5$ELKgTgBJU z1Hs_eT!M?mDjL<>^zg?~F(!`>r*3qh)UXj=QQd{~*yi>`y72WT5A)#iGf|_96h7&W zG)Ywn;wK)y7$T(UQt#+IZCFm_%R!0ukh#q{a_%1gVvl$YZ3CayV_CF^fMrQ_y_4bIj1E+!ju@%3QWoT=N!jDg7!u_(p`C{F%HiXI|9v?jghK zcQsxQ+66X$grbw%B=7F@+2Yp<3{l|=OX<{p_>_g;@eQ>Y%{-P_P|oRP?Xi+)EkkkLF9&FNLr!ABXjZh;+{jI%=Cqs zyt>XCPV|o!S~EWk*q(-eL*O`f!oQb0Xoqgb<2_zW-za=r;p#7rd~2><$8e!W`le%? z*?#<5D6#A4*m)6Kl`mVBjD)dvZB?*C%AN}kUwr_9TBp$Neqdn1g%Ws03&ol)6{p1? z4a}RX>_)n|rHqvP_B(+$zVhtT7(PE`;+|x2Ma!5%?QVHqffmdcWh{JDzk6dCTTk5Q zQjvG55K?|Luw!9{W=efdSk%qhINyZr=q7C0oBp!IRu08TkjGcaDSvJl) zJJ;2_u*uUkOb_A6JsJq_LN(6UnwIyr!fSWj!23{ao)DK>HW;tX{%D|Er?Mtk%mKhf z!tM*Eip|bdWel_Kmx&`+NJe=R$=iFeySa=aE?zL=k@CZ-WS~Rnd$fiuS7CmSC;ure zqyUEdXMWe@<$?q7hPRUAGdUAC`ZX@+^s>Q?R`@OVb4lOe!panJJ6@O~w;x0A+{e+T zTTtG#IlMXF zANRMIU?ZkGpd*lXrHMP+jcn&cvRwb~uue^8w8xo8(#IB947YA|mqi;L?GJ5FHBx<4 z#&EyJs0~Hvf?#T-yR)J@vcMN6T1Kn=q%|LP7JvfC_&75BXPY z@T#WN;d$Z=DN1KW{H-0E%D-LDd0jTRTUiflI)|+32{u@Js|nb#kRGKdF_p^FHOa=n z`o!I6Ylx_(Wj}?8Xy~^LwuF!R#iSw9Ltgy%`s`6euC<_$ZOR0Vh@H z^cxSMDe~Nw`H_>_$)%$lJfB?#L}8bF)P`LWh@1};BXi>m6Xb{Y-=Hkrg8^jHbbrD? z$J2_K*XW6Y^0NDBrv1W~m#$K2|L90nvrfhpiY%=)YPGndltYhu9%_#w?DY$lqndc;Jo)}@=(5&yKH15~lbk#&%Aa6toWMvUHQyK=r&kE&WkQv)utef>g{zu*8gKHCa!-dS|IGvwXtuh0XK%(ZXIVN zIxbAGBuH3hWypO)TYvj&qzoNl_!5em!jM^!`@tef<>PAvfef4imz4Y*pqa~45K3nk z$H0io_W3e%eW-Eisi!x-@k^#9G}-|?;O=SGwlXN59});bANy!U;OPPn!JqJoNxP*x zaP?7Bvw=pM;r0BItNnb!XUrF#d?nitw*6O!cDuVuy_`IzxP{ciZ7ALOy zno#M>E=QULUOTeS=g>pmHOEn;gnqJ=! z)Lb)qi$BX%8259xFG1YOa^7Dw%mm(-UKYbh4?2%ooyD0gj3`@ggkypkx~#K<)k=}t zH%`})dY!t@9#`0BPO#cCiO|L)?{wHFiFl!B`G}Tn4IPs;2}bx_ePWpBVDhL$t@Mef zAG(8GojOMv=~eC~KmVfWNN@B`X}&C3q0G;-X?O<@hj@pUXyuG~>v7?w-o+DZlT|PB z&as^6rM62&t%BB2pd960z+s*@FBG%b9R9f#=$&a|Z{AK}XHB#HVpRV9(9#9#lBveZ zT*Bwsrp@uq0KQ3obZcxKCb7Cp-E_SV#AN;2Z#aeB>tG}plaK_ERV@Di&tqAi2Vd;b z00EMjbB6L+KF&1 z+pl!Du@(%YCxL*i-PM6=93)hvL)0jYn`e?`sqwEfR_b1UeN`p=Q&A#g*$tx4bh?L}$>b@CtO zkk zqRghtH+OHFD-anNw#qr-2gu4VUro1Q8Xvz9hjebIu4C;-E@3hz{CdCc_E~j^g3h~W zvi0Sh`OC}h;oLvOEbL~_o6df(oIB?=x7eN(ea#2o(a@cZ^#Qb&rMhI75N3z8RQ}!# zFqx_uZGB|5htr%7Kq#-IMXTx+(4@>1J^n#;K*eVknhHfuMMyS1DkkMqJDh1^=kDY% zSuSNrBYsRw=qXf}e=F!DA^R<~4<8iBzf6a2M2_LQ^;p^ZTyN-Xb^D_>I1Jy%l({8Y z(KY$vy?I#QPvtvhOruUDG)k2n3vQl}6b8QN9_nj#^L(}QLT5)s8r>fVKPO~2xQ=wo zdXC{(LbsbI*Jijxb{@P}A|@;EcQoq{N@4hkV~$Oo!$Z^wSsev>~v) zv%QB#Cc|avRfeApKD?mts016E0 zFHaz208Si)$PW^^>UfV4p$UeYRH;Zq{_Q1V48OxSX7)tDqjZgeQGph#rpOAHWAnHg zW^2ixMu4L@uG_C+-tP9Y7t;AuQ^P^MQ<%2lO!Nd*wI_ncA{bn7-hA0xZ6|-LvUvkK zwg@ce>$|+9FZ7;d(nFbi%%fxFpvz>GXX)4T*5C?|UFKb!fe^9u3(XVkMzwGorAaI9 zJw`vm_#0*qO>TKduL}l^AHp$fXmC^(nY7$qX0vq`wHqUY;eY=5HxU95Yp;Ua^sgpy zXc*F;Lz>rRYRr@_UNAtnf!o;CeI`3*Ise^cu9r?w&zClz%TF)9t=6)3edTcKH$&>S zoGGB|E`D)fVYxfCr%D7_p{{=l(@7Rx$P#sx0e!$a02Dv5)mEcpFzVsJL5;B76UYXN z+|^vu8wnCoenkFgr7C6JVM~U$MVhY|l~CO$M9Dr4$@~mz=)%>N%R5QZK-*r z+eQ|Y{PmV#Xr<+rX9j@D1Vn2HLD4|dsn8^xnD(67=GsctqMXMK_Re#+T9V5c&NN1A zFxGjdF$6|YtOL6?GouQyI?AhN`-3Wg7H31I5!AxasUm1ohj=%3IVatl$@J*%1?(RW zI2W8syK;dXe-~gt!T=)BJBho{$6J$!2K11X?x;f0TlL4BnKIWR{k?Dsh~$^vfzW&X z%@brpqAb<1@~mvS@XB68QltNn^WHT}LV0v-;uwRmY2g9Begsm zx;!ouBjbH9)+G(5$}>X`lW+cGb02K+zkheD`;M(oOF7Mn9?rVr$!kKtK(zhy1PW71 zh7-uh-1jyP=KU5B%?)K3$!_N;{Xj?{%#S4byuS#!I`vvV9VqieCvS^vh?aZ*DI&)p z5~a%bOu>jyN+_(Fh$YL6xS#$&M#u*6!?!)yA`I5aAAPMN&N zQnGQX4^-nhUoQQE*Qp!rX+>FT($ww`kFKq7L}3+1vTe|zw}q@Y>l=WaE`*nm1~X@m z+V^Cn^o}E{Qxd0A9eW5LDt?9%nt_9TcYX@yTCs{0sYQyFkvqqUwPyk2GnhepLh|Av zF6RGO))77c_Pv<=`28?aGg}kLWe45B+ygOQzAyeN?MBwB@FnYT1ljGZU}K`h9q^iO zt0;}{i^_rqx$Lu)q#v(E$0vSm5++$F&KUxCY0XDTCQ-~Kwf&jsMcYkZu_o?klAkr$ zzUSKgmSt4{O&vp2H$yc0JoFjRAI072SuGIvkSvAESQ%h(G{0Jv{C2HZ2`B$@jid>F z>K{<9H3QNFmGh_gdXR>G&DvLoxJLum=L8|;lm~&}+VLM5py_RrOPAVq?&fC?))K`} zpcbWAKOQGwksI**dlhC3-4<^IgHvWALL@A`(R`6L<=MXBN6hNnUJZzcQbc7)Jlopo zhovhl#v=20*PR;CJp@qH^miS&}m?lN3cD7tG?SyvVIe_`Semo~}+K?-|xNvi@g z2evF~9CtfppzX;SiYsZ<$KHCLylMrG>_=O_hKmpb8oU<7T@U_0H5b6} zP-U|u0@5tBhiq*nuA@pN-Y_V}-FrrZ8--AN?o5BG&Cb}|1-DmWt2$h$&MhY3&7E<_ z^yJduatT)T?Z7_bab;)S0pzOrjzc52W2wT&L17@sJVxZOvdCbM0;pU4`T3j*l0r26 zb{(7{ZEOcoz29932N6o|=X-OWGe3MdG)MFUs*{WIN>&|2r}(%L!%~DPX-j4VRm!Dg z8MBacV4s^>;9mo!IA;sLJOZEcYk-r#2(Wmb{0h6%{H9R=sjvw75S@99Dc-%8OS@TRrw2{VD_VCb;f`Gn40!v z@ZZcqNDdZ|S}cSf=P-y;lY!(gU^`?ipjX0^q!qn-5D!u#YZ^mO$1>AslaNIZnmCZU zs6hb}o54VO8G$v6$`OztbAW(A3~R{rqoFs1gDeh!(tp26RQ>Rn9)PD`14Q~ND1G|g zhThz4kJ!CW&}Y!2w2g;uYA0detPN$lT9=>oJYX_sW5h@|~AmpO19d>cl|6J0lO|LL2Bv zx;|3KLPTv5l=fu2@7htQjy}VSU=6Jq_Sws!4+qx$YZR?=YFc5&z+M?;Y0&PVtYX|O;u4}vlpjn^Y#S!g9@zc1jPWJh)) zH~SH*eZ&(?fWo1|&=M@Y#gzTAioskbO^pT0>nBKkB7Rmm=B!bHlDXHs=#{v0WDg+J z=$%LS*Ki5{Km5_ccG~}~3ap+br|a4{Xv^|K`mduM2p}y1$a#MGLIE)Pt`_L--1(HOc4MZH zY-@6ACdMx@TssLrcZ^K#6iJmES?UY6_vMd!L8e;1$fIiKSDOF=x#oIqZMGk>U*M8+ z>q!e6wZD)w5GSmaZyCtr1m%^zd(TTg@S0ba?K?mNO0E)`H%i&n9;vZek!T!A?XF}LL)O3%CHH}TXT zW6x&B46>CAb3SGj*U@-kO*0u?kic>Gm)E7p;;YPwW9Y?Qhwnw|%y$r~r`|dDMeb{Lx?h0Z}nub00bE&W&$n4Nxlk`DFhn%LyJOovL#v(@ilU%vz>>Bm#651 zypWv#9*AntOn}$!iTC_I_}ft4TrF`hN`A+yo52jIPINW{lJ~>?W|>?Aali%=Zegb( zso0OlrWlF`C7($aNLYoZ8$k*88m7yi!9k&z{|bR5V#R0Q+s@YTEw$v;JIwb8nZNIN za1Hcn_0G$S8M3@(+EotX#1;R)0N8Te2naHeF_PmTy6qQaw5+o;XTeih+Vago_0z{? zsfTs!Q3%rAX!UJgc-;H7aA2{Mk0}qSQAaEnCZ6M0CW9z_}$K9mZ34KW$LN^fo4Tza9%i)l`OX zFCaS1Shg@?d&wOMQ2duXFcA$wKaxD34#ktpS3RzhFNeL8oSce{6P=X~Hq z!gq1S88wB_fhtK^aPdY$FG&5$h3KvdTv$_ZSBh`Iw`KXH#O_WobjI=I&lrLkOB+wb zs9ECp7#9H+fKz9{2%a>H@f4@u4NgH&q1f;H??_>^!3OsHGeuccLvxx?**% z|4Z@Rbyyeg%~+0$rx3l4*SpWC>h6b4KY}VJ+<{Zd4D+o6T{Vs0-^m0gNj(y(S&92l&a(cTA+cWqypRT<-CqN% z&q^MbYzric^i2BjZ+HcO*v1Lmjf0%TZ<^Kei4~C-LFL2$mwVLt=Vy+7V7^{CNhXTd zt#b&CTqm4voR?kWV~aiUX2oQ*W59hPy_oCu#)O&c`ezb7e%k^so3^E_7@mIV5=nCP zG4yQ|s#K9%0?TG zVwC}57t5b4OtUDl`6f-G`9-@i^LKvaYVQscfP$N&c@&_mtX^EIs8X*8j%iKr-_6lQq zDl}NsL0%qjYz45v1GByh++rf5yMc%vU0fUjp9a~aHyWO*w*?IIUbf;YA8clf3=TqF z1gv4>tk}Yt_<{ec3Pce>xuTfTeC@C#XZ9zQJ68s^WHKY`d$v@m|HMxMeJr@?&At)& z)st~KDX7`~4FAcvj}8@V(cF&Tjz7dy0;gMd>=~G&fP0UDlr>uEXJa$BKYIW_=k!@rYc=H=S~2{oUuwIV-8QS$k9IcnI3gQ>`nG4Ljqi0$7+w|RPqwULX^eTq%Y#U zpoL>!UhR)36YU8)t`jYzEt!Z!5kO*_(sQAJR}UfQpueg3cH(cNKmut?Cp!E^%2LFG zPa-qzCQP@ax(AAlS)8vt(Axrv6wr2PIYu zrpbK3V!Ttvp|6S)eUX{kMN*gzu68fir4f12m(BzO-K4B6tgNXfv-gzRpm6zcWe2n$ z;^18pfAFhj5j1#Z))X$OAM7FLr!`PjO#pTKboN%1p1O!qkFt%Km{#o>Dtou8$&Zg! z#kKE(cK+3LL@@@m%p(j=kv?f*#AN*1Z28dg{R!lklcs@x8xXLJ3D?MM@Vi`=YTXhc zln~;~9WodHakm5YoU$}nA+i}kn9KQ-*IZ1mATPpqkSZVyV5_@kLt(jye1DBJ4!UuE zT6>hSZF26l4;%Y~?MqgkS@+Nb4B@9-D$dsc^&3&{oIs4TV1IH8g-8En+Zda?0k?4) zsM37~H$#r7lt9fR+M)n|f6Mb3rl*?<(@JbmIn-p8G1RRi6$21aUVaL=*cVZPBJAeg zJd5j>ATrRkoAP2Dye_XQ_kSG#q$ff|jj$jBdPf|j=#6hrlU@cOuUqBWLz$)}fuopj z(8K0MG&2AIMIelpgEA>mbJ=HcSe`hN_!27V8)*9>%mxmXZ*++U$xx8}0ojHg1E5%5 z-S`NKA(^6;c7}V<=1?IVB01up(WaQp=?}GYE_sM;wuK^hh3Kq14?3_6Iu&Qyu zZ8Tj6dda5%oxX^5=4`O(uA<`BVz#-?M9=|K;zb?z(YipAfjeX0RK-5nico77C~3_u=F;P`Ki$SGdq;rkYVa!~Y=j@8{jMQ+Y_uKls8Z2b z0Hjx0u{@JxRb?G>Mq24Ts>aT^um@8c-dZNGtCMr+BLb|>v3chRmBf#VxJWAb0HDtPT?SZ zM-Ek;Wo0VR2cwWd$90XNuGqXOey{@>>A#9tm4NWRzck@)TK%^47ME{TFLr~W2Dm(_U+=uh}Dk@(~Z@^FdOZqSQZ3!D0B|u`(Pdv zHH)sm!3ZVEKn zlgZxeMgtGcp$Um(Yj8iXB2unqC-=*~f1bntbYCzGh(2Ct`GnekR`%e7IweRIOTRm8 zK2e{@oavt|Zu-M<`PWD)?WR2&XjZz8*5R#*1}x+uBJx1HxLs^QsNZRVO@adMYb3}- zTp^<3VTU3#779x4qg(;!?2c=bD1C=F=_$ysX@F)zJE?llu%cW~sgp(HkxnOPa^E}# z9FSvzW4hZg|LvWHLESn;CvJMeGY;;v_wR%0GGYa@sXGkn4@XZQ938o_eNk4J7(@V{ z!_=0v+XO1d*!Z0m*NmLnzgU21HVuN4z?6GN$#2?so)7DWG-!Hv5Fuv7c&uc0%nvDf z{vZD2%R@`0Pb`ui@1GZ~95rDdS?REMoLWvQO`1yd>gUv}=Rdyaeo$n#n9`J5W){l$ z0N@}rqPLzP4bu>NREKnw{Ef$~%0zxzA3#;*SC7sWb;wF%J)WORt^q;531kFbjih?y zXAnIGji-F-y6jOI1k}LZC_v=25Y@*=%6vovLb)(`XoI}VyK@84L)%Y*Yb zM&bMEJ~S4D0UU*N{x-p$wY`;)s>Ea28nJjFFIL1dX3h5(sv=qvdL57i>zVw2=*#_g zH$BH)9b4y|EL2-xRrkJC;jKFHx!A;YdR4DKZ!a~m+Epi3{n-S+XSuxj&wlo5xmCtT zjRj?c&k@#FEVUPmFL<)XAyvDdC*QDe)~5PLk{3HPGCo&&x>0pYLu)eSWklvRG8!My z;<{@9+GyzLiK%Oc+o0DRiI$EKT4>cmfC1gH#!}->~g?K5#zH0N?v$ z5^Td3SgDS@gSjcQpOVs%2rXp1mniA3DIPsk=AsDRiaEXG5Q`}0R1@>SOHDJ^w44>n zm}p3@#k4v8l7j#H)c?KXFjwIKss0SPR{F0|5_yELId)g4OZaNJrKR@L+H-fC%^8Z% z?ydad?td(zw?v9vTefbGE6}Q0la<;>L2HZ;X2WDkjG!N%h5g_?P=6AbG=A8Yt8Xry z0lhX~@^ZM8x!9-jot=RaIRPy_SMbr{4L*YT&hqPZw462D2z0*A8DrK#7M$|rvDD_> z;k}(?WWZ#%1c|#cB8-!~%xuzxs8NWFPskmd^h7r2vd z_vVf)*%g>e-o-^dd@)1o81m<3X2;+co~4n#SHxU54p;}h3AM90p3L!L{Lm`Ym>_kz z4lGuO!pPoZ0>JEq-J(CJdS?sz(rO?xWefhD-4g8U&v6|nmQIy=89+}`TO9fkiPB#B zI}$#-+n+1koz$Q8T(}rK-$XGjXHyN0owwH=j4v>c$pVC>MjHsN2WNkm00|;P9^)jj zESaFG5#i^*G6O{ZNnl0Af)PW_f0n@43m0|g2#s_li99|~q~^_EWheZvyNX#G(j95- zL_5-$e|`-t?NTrU-I3>Coo^F(uKAWm*RP-#a+`7(rCJ2#%>VjYB0DOp%zG)U>en*%Sk}cx*Yudi9iF}gMu0Rb zx&91H+|oB`Pti9cXlrHdx$1GFeN*!zaudWK?Ekjp5A zQsg3F1I?HQK*D_zMjFfC{a#)6!@)CkdQNh%=L0lH5NA)JYfWmveR~Zs;}nD6!?cJY z`ar2u9Ox3Yf^W_LT%j7Mor=Ao4UDyaB6`>+{2zyiod|*n*P}1(^8X^Vim5Z}x@^^C zdfBXQKg_!5B7U{?bLqUQR2o2<+xbmOE+H1#;DD;d+6up!H@|{YYfXk|3{6l;X2$0< zROx@?3C1P~8em)k&oP;^kjg)W!Q)Zq^o_vwj>P>#pq1xt9d@tGA#(JKXk6cP89ee2UMI+1Xd&6qyah-?5I2AJRd9#(8;3 zt|TX7JRsN%q5Ri z>89#;XQd2PB~i?8SrCH9H?h=XM@i#mV+Mq1#e9M7+8}cME(GJ&I02@oe!I|r^)Dy# zdH1`9j0?&J7?y9o9Pj~TQ0#c*5Ns$8NSH|9%Shr=6IxOac9W_z?n_z_?rWT01^#4l zkm{4W*tkSNo74U)6bm{CxRpZhph{sr8b|oa<*RK?_Q4$EZ*LwsghI$6T>kju)4?IM zPOgE>b`mn8b($L>W=H)(bp48~Du@z{u=)YHpBKH$))BPF;l8jvP+Mv;DDYzTN6FU# zWT0gwoET^MEH4dOYr+71F}WMG@)FeRikD4+=?OX!9J1R>50UvvJu&G~RQRTd5(P+2 zM#-VV&`VxpD|4s0+t7@Y7 zodJ!4%=~&mMkVar*SB#X(!}QH)ikBfY(-#5Rr<;uR3*s8CJ_sayXWEN{MBpXB+fY_ z!s-l0(U28~b{POOl<@uFH*>GcGTTdv$?s)0r`bU5)2mMt9>+?tBM1rmHKI6>3q6LM zS_6!rUc-@RDSdd|!0>tfO=4NNJ3gm(Lb^pzz{^6%awu~kOaOYKI-SX~Oz%Wm+VSy? z|F6O}Kmqb-t?6aM!|VxzgX1BdaY5;;Kl9;8%`y^lCi8T|;~x{J%TGoM!0qwJ&`?3HA{*d&BfTX*Oiv4vz_}M` zZL#uvmP~8_6X+Dyq;!qg)(2d5_YrS8TM*C8(o@oTIO>jq(G0T?Ie`k6R0dJpCQXs# z1C*1-2x_NQ;_Y=DygFkh8O&pyeobDY* zI)2$!%ci_AG&m|E*uQ`}EZg!f9r2=?GpalbW5Agqxr43spZX2?z)uTAQW%M(8UKPo zwB;<}2+5G$WC`&5$I>!7oSj^}$jej|{@A))kwRGq%gE=sHwklI7DP0L&*FnA=$B5D z6%N0@dlA}gb{@=1DWIYD1k!R%W!GTmbDwX6h(N*Zf%D~1YTWTI?U19MD- zWh%@-zmV{+PC?GApll6N13FbM2eGSL3!G4WS^EOoMW~;qPQM38RJ3G4o8o6*{;Mm} zAkJJlQsMj^$+V!ay!@;oQ5P~kXY|9{2dPDX+6Vv|pThVr!x%1msvhr;6+aOfD)EHW zT==i()?0_Gj@i2q46>yCRaZ*(jV@#8zkrYocRTZx|C_NNuAN^zE6@@yz0f2*Q0()? zy-&zoK*eh6NtasK)YwRNdOz3oy^K?f8F)PCRho7=T8YT!GK=l6*H4jx=e7S&hZ6d| zJVd`zdEjfqH)Hk%xDr(ZEor(VtxzFsw?&CN4SSmS=8N1#_cnTg;Be6dBY3wIS`ORh2B_s6T1#AXHMs_?t#M^ zQ9sK$yWQ^?zU~y6)3H*RMT_?y=RHtnAUNp3p2 z@jZd`rH}HwMF!Ex&Q$}{N+dj+ezy^eO?@?L^iXBn`r#2=dSjw#7?5SjOM|Bo|Lx++OMZP;3WR@cvaGIf~O_9#GDJ2EG1Bj6=2c z=gAG>7MX;6grHB>=BsFYE15Ijo!FO5*Uw>m+Df!VtP8 z3ibY0o%>?a=vG;o7*z*@wY!r06#_5tctA{l%iv7eW0nwz~Yk zA3G!(uH}&BY`6A*eN9LadF*6*g??eBh z4S@0^J4ZuWkSYt{TW>x9r{bE_1+sm=w_T2xA>r^{$|xcjn%`vsEB>*){Rw2Iv?nypNOl-r5iWomCP_hA+gBG?dT`zw zxw1cwtgBO~V401efquez`b|Ooe|V!EIm(2%X5$MGDJuNKHqDd@J`LuB3>(3++ww4v zu{@Vb#l%Z4h|Ea(LG`f`R<^)r?}1KZ!Aw>;7dtyL5JMcK-wxN9N_jz3T-ay#{`mCL zlJj^W=d67U8CYHQQhxfubXmBkL7^EzL#L&uUubCnMhFjRiwLddjCY%H5bVFcJ#r5) z&O=% z0${{*QAt9u%)_h=k!!2PoD?sR95 zujKMifz7lZ@js34j`-aJ&q{Lv8O?oD>%%8Kic72iGHYTTI;n^hD=pfRfAs@gyW`xK zS0gYO!4C^y`KR5Djk5;fdjz(0O)d6qN%fzp=bxd4{Y6Xk;}1|Rd;)Xxo(#=7!^TS# z*zvKkG_wkHiQB8x)QOmj{6ge|k7Hu659B_LlC8YOso&cxvM4VlR6x z=m^dS4#8VJ+zWR z!I&KXAX{&MOEYo$u2@x9XKSl)RymC4nr`mhlTC_`pI#Ls-G9&w;}KYU(H*&D1Kz!= zW0L>c_P8^wa;{!xJ!1HN_fGUYu&=)7u6}I)EbjmHlrn>-+>F=ek4`L~g{C9Sgv$}V zgQjcgu3yoY6?`^-rrY1Y^a5IMA9gqGyV-vOE>y$ZJZb(n0ID#YMfQOr%^GnKBZXqH zAXdo-nNIG;IQsBZyn2D0iWQ10QdYVVT;R9&4Ck4Yxt@ahty@`$u&6v&j(RYF7(~NU z#ys=o@l}89zbO6_U>~c2wC#+*NA71Lf?tDC+oG#Ul9<-x0nv|U?z-TB*1LPB`xY35 zx

    tH{g8%Y>u#vZzRR^H9ubRUo;0h#5VGm^P*!2t1bku>nhRbPlO@w9iXWQl$Dj6f_F!ahT~_UeD%5HtIdl1hq`B864DxzT%_PX z$3xCod}|A^Zi@!DsHiAZA@6`;({f0@05ndX(i@lG+Omx^Lxj6DMHy&nT4!E zvNC_q*Ex0HclYP}c>KP9+~517?mF-De!ZUKdS2J{H0o7!8xP0JGHOgG%qB-foE1{- zw1cKOVrau+bHSoC*FS4VX2P4?w3=1P=j&MyoFk$9>9Su-ytxH4z;FyIyz$Got?W8d zH!KQ7=Dn5k5cT8zH0?TjF$91(`k!*rTK%uiK_{3c0(JpB#l^+RUlT~*qa1%~@RMrT znqid|IelUzIPKcr&K_OHU|ijc7Y_Su&z?=YFi>gicKi~o2YvbK)v1YoW>F!l6I%kd z(X~-1JvizlwvbO1=thRpz`wskf2=QTTQ9t~e~kDgaSk2CK+rurPJm5)6uDTSqv(Of&sE)Fy=NCX}?POgBL^i%dD0yL^A zgY@+DY*(-DBIc6X6%4_@D<(;I-)3^w*m(Mxe9gxdGAPkwIjQu7wzx{z0RtLnghJu= z_htY5GW_?#m*KgU3rAX`J2ZtcIq~UB*)Bp+**zqa95E?k0v-)H>=NSmp2>mbV zC{sLGwgd|xvS;7JL@8zH9r-Ls@mQ_ecQ!IM3dWha2Fa~{{mYrd3brD*4?-;wsu^jr z{`g$`b#v48wzjGK;4K0I=W>m4jj1TisxWA{udOWWjsZ48@LiL*vjsEF+}6L>t>;42pgPaY{7;a?UG%hDTx(k+Oy|%tgxx}`H6GF`FFK`Jp~npz<{=K zTv+0?>^5y%jfxX^@^qDoWcA#_64Uv=56J=@XL*%^Pa<*E zw!eQ0C9-%$JFeNB;HZWQ$Lt_Rt<62ziG2m)ZJBDJzyfH3==v!oYA)bZp;`H9w43*X zYP!ZJ_&QJF>Q038R(y01=43Y ztTKDEY;I(9|45+h^fM)B6h_;>cS2T&X#h+%vu?`Z=yUAHZow4zHE1vF*!-s#Q(K*? zX(7DSWA-=L^%F{4g)Yuf9IPkCkhUUBH{)G(P0dIcVo7`*8fQl@l`NpLQm(y5_Sm)= z>E+s2XDR=xyy7i@z{Zx${%5CQx=<%0B*6U+38#1vf2fvO*Bp`3aCL04B_#V zH_sCn1+d-VvC&zcQb*SczJ?kYAM2?uHZf*0kWU^=W$Z0=t*|P&@ZmH-PN$rPr3Sn* zDgms_N~wVr-s!T^%O|2^W7%RZI?75}u*g~wGcx5qvV7IY`a$eU%+adK%H+Gr#ZhgR zOZU35v3UJk=G*}&QIC2ga{o_iy0@kA+d})W87VofDPsjI3t&;9#797mHDFS_Zq2ld zxMRNdl>dmwk|Lh~eN(9oZf8&KH@1Xh8-Ne8HjWPL!e#%2tPxTznWitOZV+~t#}nt( z^SY@ia_jcpEIYp5x^=7GU}&YZ#R^7ks-G1gP*sbDKX@Pr30#6&f|pkXZh3B^Ki|u# zP0t2A2S8fRa-!p0%ocYh%^$#8eq_U3H`qy|y0% z;WYB|=W`XdrPuEooIXJOooi?O)rX(k|KQ07s^L)0Z0Qfqt%i)&aOLi4Q_sui{Fn2GV@J`;A}aO`TF(T zbZZ!gWwy#HD*Doi4IJ0Zz^~}+%7>KAwe#N7|hvA#7-g*nOo1wmwAzH@{z#od9ZsolJUWj%(z(xRIp3Y~@MHrF~} zR?6<&tx?mvnqOf$zApd&%NlAJbWP#)GnIqWt{fAtAfCBeK#Xue>socrGt5j~5|~ zb0K=ecS&?61TT)a9q81dmN8kcF)hwe9&Ml6{0X}bnn8Mli|QCF1#`faX=_$i6x#g< zDaY5J3>=)29|h869{%E}6vJFC_8z+|ANck>bu{+8c{ey%oGDRNP3=mmVS@61x)oAJ zF@dWM^g*$`q?3`$2%Mc7Sk<23HvlzxyVM6tnjO)>l$HBmJTxY!h124DF957vbYbG} zEu2@V>THBiaGs|e_JinwPx;vgN-EbYHj;ak6F_;_>-P?9?YJB9QIW7n zy??ug7QA^TA`ussD}MXfK_LaBi-ITXAgDoh{5Zvm$=p0^fS8?G8A6G%p8To5NGbuy zk4}^(&)1+8h=3uy8RT1r_s3#vExKERVlK@OnC6u`GA`f6r`P^>SNE@{zXElYw=yYv z&~jq*^}{-H97jF!hjfTPTTVf5wA_|Z(Fi!|!|d$WcDfAeg7mm)!jwokbSnLw5rL-O zuns+x$H3R@m@3rOr-VC>%i~Y$=lL%%btLJ8`IXa z4^}=0P1DiQ6(qhm@<-(Uoy^EX;B%8*&WYzoM+2KmWqtlUki)NN?}Eq|3xZd28JZtx z)%MzH6vxb-qFV^aW=Oq64xRxgA@Xbp)6TR1+RpsGYLFWtE(45%Ua}AjoO+rPTGF9q zP?cN?79qU09s0V@FKi1Yna&6_NqS$ab=#G$Uads>v97cYk+#jTu(Zub;$mWQ;#d=6 zhfK*I(AQ^H{_Sb+h2Z0Ye1%JIkxTyg3C$Bcii#F!Y&EI>;7(8wG&BpI|8pIGJs}rQ z*$;kFpUH_OM*{%DtrDy8ckTMTb>x&(o#=G0nfQ+^u2@tPr!z1*%t%X3<=nAjN3rAz zOk%Y_do?+zv9(0^^l3Ed4Tn0W5ptP>BnFp@wsD$Wdd0}|zDqOg2HnMb*h`m+K{(Rb zW%R2=&zhOSBmvg>etwq`@W;wixVpOLnng!OMxGuO z*|o9`d(b{Cu(7h*U%jXDc%hOd5neYXrzIs|qAK&r9Y;VSDgY*NCvw;Vo;(q2ghrXZ zpK9k$GmnlQ9>S1bR9{9$243Ob)<0kn6fe;oEV>IP)u24`%~sM+n90S&#I#M-)l^h8 zVEkrw?12*TH(tfT;}I+(3aeK%(Qa4MtqHIDVO}>p2sI)a%xM4tbZQ`gCOJMX4tWYi z0af~rf`y=uF(0o@q^*ZDk`A7q#P{QRmf(Ih7&37h!8=x(EMBp3-FIPiSY=T-M* z>D|8{i}Z*53NqJFTD2(LH%vlDQg@@OpFW@5SXv^Y5ZIdTcA;m856Om3ECC+?1=DMG z&%U#!vkz;iB+K#K5)yjmem`vhbhqedTe|U=MEn<^E=Hgu3shJ$%>r)#u`%VYSG^uaTZ~tIpP@#xgNA15Q-rt#diw#ns2}Sc{tR!A5l$-Q z&Yh9r;jniA;gca8iq+24tDlU0EQ)|*XAHQAon&L~_1r{1ud}RAEU1uR9`3!PRN$RE zlrVCw=wE^n*SVGC{Rr!^`hHh5kZ*CqnSRBXVO2n(%&z@~YlZFdoV(=(lq|)`e5;Ot zJoOB{hqiVI>RBQa6Td#*;b$J|FLJCKvj=dW!+r;4s7jr|Iq0uCQsK)OfN1An;^X9N z|9lJ14TvD+JbZjUHoM%e{|>#RTw>`2i6!6HH=dnzX+1E;#>P)PXUwDS^5p|yn0^cW z{-N^-A>6o*OOnxt^4wbX6hp7%bNn!bCs2@Nbyc6DN<3v|CWOKh+U)|D^sB8K9Oxi} zz=A{bS8+N{;B8AGaUX-B7A%5ccW2m6pv`s^Td7q9;J`iC+;>60(-Qdaf>1bH)#<#@ zm?7M^h3RTm#_7|idEneWYG@fk?*dD|46Vp0Oa+hPyq9M`rPl;fE>Z4bWMtKtCR`5Y z3o&2>GD)V)lPk~cDagqCICYJT_(6nnw6qJ@qZ*o;u1Yi#|2Yh_H6Q*f%3OAJoXFr86l4(AP79i*prCjf|Ei%u3s~QY zEqXIFiT!1=PB*ur>%>fM^mr0OA4ob2#6ArDqYH&-pYN9d=0d*$SiD96{H5Z&+a1n@ z7-;aI|CD@9tG21}TSP*t?&P&7psWL7B+2vRg80ZWf0?!sAud5IXv z?m8Pys(e9`?d}-;7cHf300gB*7?R|zZSJ9?JG<%!H5p<9XARGr4_Zu5!T)qLaq9)X zU-G@J^Tn+tblBP@a^#$vI;($|})wz`N8T z@CNa_U^B0EX#95k_;J-+g}L;-f+da*hNkboFVNVZ&}U9(vTh_8!r;!_M!pE}Q#{*! zF`K))_RBq+roPOFA>%KCr~^qk_q(|-*yVxxk)`tp;*rA^%%7nqa5>N=AMPIe($=OM z6dW7{U-jzSeJrSQv;^?SsB)^HLfP|U_C6RB$H5kf7;Afu%2~ot$+KtgC7wV?a;>^L z>vM#Md<~CHae>Z`o3KSq(QS!x{c%N|!N!B&n%1cA!~pQmb&yDetWSOZWGnF^P)gjX zh2_>GQ0Zq?ml7OC9m1)_j>!c^D9Qufrw+zNeeho;6VbB6l|>-uOm=YD2*1tAZZFkLCuh%shwCTe=4g z3&%IX>Fil^2mHM@z)Z}FRRs19YFMbqnI7~X_fDI%iKB$LI{-@XCLmDp^7E@hs0if)x{K;?UCIeT z2FK60S~9o*-#>uz4sY31E9A;3?7~ul72*=k0q^u<^|$-)6+j<@V1l)v2GRQ5-tcQM zoqhsc40378)vnE#qs!Oz1(Pqf!4957`Kt23;+@8=eRdF6ciAz1Imz$lty`@4$@C-? z61&zRjEDf@zx1wXd^~^Nk6{x*zANalE?p;=GMbBap0}WNXK(Zix6@W`c5& zzMox-xpQI)E+FY(Fc#7fq|{w#lpm)g6=vC5R>&5hXs9uD_Q#H{*jEZkBMJ&$nch_jk7UI98^%@ zO49cO?`ooD+K!4$ixQO8=8H3fE>dy#@3WxPC*d;CM}OIxp7_$J1!qA#(Fnb~CELvb zCGd=>IlEnLMu);}I}6UWXLWL9#QIUgREwxdzJ+J2rna^OQ}*q^Kw0^F#Ekbp4>_9& zH$1uPq0=9~Qd@`FNbW0W9Q*$L`_tT)C*{81?7SNe!=fkvQrVtBPF1Dw#9i;1sezr4 zM=v$JTx%#JV2A8{gL~^nS_&te5W@mFv+!bgr!Vg8A zREU5#@gU3l*C5<-VM1Jy_z6TQ$Isgwq~!hUq!01IrQS^H+W=#t*RaFXDHq-dk^w@{Y{5-R zoUtIo- zpPAwd6m1;7^AR~}cpjf_eM9d{JZ_`Z0pEJdw4enk#RG`Q8q>GnCkJz?y-Mjce|*os z8V~Ya@aeoc|GtmJ5A7#3G($`#kfXUzojO&oe+)?br{rfLf<%G@x@XxOP(N!3wq4apZ(Hdy_Klnl7fjYyDRmwS$!@_2Y8eceuAiAj_YF07jf@hz1wl~NJ zU^#cdiOp|nScj!X)k;GT-wAIYGDuVYUzaFAW+%*?)sE@>3GG}xUOO1o+ue5LIliV0%ze0n zjJbt{aT3LUx!Rpuh3Eo%h4)9mnDnFHo_+g-Pyz*V9j88@@23EhS1cu;tIfxts?@Nx zwar)k0Co(+-!H+^;JXIVJhVlGT2x#WR?gkEPk;!LjQUE06ontek1%`PU*zyQ==MVH z!KR;&KKlU30|iJU6?ZC?%T7DjRmgE6uU?b}!3Ez7gSD^bKiv(TJ`NfEpRXyvPL{`7c5{%d+Gz8Aye=LBm=1CnDQO8m!D#djpGrE zfJxZIx=i^=p>x-tSo5n~ z-<^u-WYfgvsfhrm9!ic~+SeU%c?xGOl-01@jqjB=yYZRv1&2;LA###stLn6=)m< zZfgXG-|};8r^t@t@x5l)8C=P^Y(9eHtG16XL9!CsKpEh# zxC1SwFlswhd_(2cd0)TIG4K4gX%-MVEUju1pmmTEcqO9>zNyBUpHI?Q*55_tjO8J+ zDrUg0apv9lSTkyTYL>>dNjpAI8s?amI5J=M&(A1TsTh&$C4s@#;8%S7{bC=&R-KHc?z!C*UvV0xN zRZ03J$ph6~C3LIBd92hcnR4M*17b zcTEO{rBS*2EmaJ%2FvanM(NS9puAp-d)`cHWzz>ugLcFC-CD?t>(_;=l_H;;n+xGt zN=)2$NK~}&k}gmAO1-4j9!jqh*v-vCAa``Rxw?wo+9pS)^Wcw{jNL*N-nYM&IVFb_ zvWkGwaE78QJDVRqB-JtE@Ac!P&2Ib#=_BFP{<|Di*4zU&F{@rPF2^&?_qZF}|Kl&QAb!Ck7xbobYk zIriv4KAh^68~Zch!r^8B@OArE(!nJYDuTttP+6BUv{4*QO3i@#bG99K3VoFl8Dziv)}?SwLOpUk!j4dc&qVx+lr zFx9xT=1PK|XIjpk*RRzlKug{kKQ+i*S_^9ci#n~O;bvV`OC==5L1nGtdHR3mpBLkx zXq%4AWG5Z;HQga-jliCRt|DUUfhNAfBL?V1iivbe2*|`}p{5k35TN`zZ}t*Qc$ydu z&CXuUkJ$ueiS1Qi*xKCQ^erJ=?$YO%wS=KJPfY@@U&pj(E&#z?R=?xr5F$&2LGKZc zMmGgjizd_85+^VDA0(G37X%iLmtQ9hwXecHU}KK2`;4~Ti~yFGEdJ%Epi4fvZ^4aS z-QGS2|HGuT8gf_iWTXeNzSyw9dcG*1@6b|Vh}=OwDUiDK8L&KBoJUW;VWPf^2;evC z>xJ#m)>{>eT?>4ir!aP42#>&kAQ3Uo5a?$$p?mk-uH^E^>E42g1rWZ!BQCCygly{m z<k%Yu=7GMxoETVu|P@c^XPRtZEo)D=>Rj7H_7r3k{lhVn!YjNIev`vWL907IfF z_4tht6@9|xZ2?$3g_{~vKV8R%0(GC0)xfE&aCSRu3bS}4yHkc&Ta@5(tz0wQq%qvR zer*ttW6@B5=RYzrymb}8u(0JFZ-`^?-$`2NP^!iN;*mvCO0?sL>-V}yD6AbQxxNTB zr2tH|qhT+lMFC+_!0LTBZ`o>HB1^{1PDJcPR#=@|T%LW}Rt_VztDZw4LPO+e<1tug z9esNRT=7&f=`km+1=>ICX*zyAB&Oi-<>On(EEv6}^2<=eC@2Ho8pr^6ChW8}s ziBx=W4pFQD_&!LRqKLUtK&SR^;9E_@JUg@XQjsk75H81?wqyxY=c zF$7??q<(y-0Rml3gd?#~)4VIR5Je0m{HPhiW$0XQnz! zPA2E+_m=upSm{=E9~5Q20qlcd%JCKr{q+LS%7h>~RMBgp_}ij8K_z4aZU?q(2_kkn znwoR34v6ysuz4+DZq5~XA~q^*&P;Be{hy}W6Iz979o)x1smGN; zC5|0?pWTudBw=D~$}KBv3TAbD@Djy0`hgK$4usN>YbZ;gL@cV+nG{1lkNXJ*9Lj?!9?fQquKa1qg<{_GEtJfmgMwk-p)Y4$>L!QKR+90{ z9GlC56P2(R&%oHeBcn}Xe;WpQnvAQBwo$MWDu^lufP~4u)s6HYoCQz9W{{m|Q%^1> zU!BufavxC=j){pugDY+Bj+Y*|XcDbNj=RYAEgM>Ke-+{!j3>CNd=?^MQ$m+`Qo8^~ zpVBUU1)6&m3o62#>@}ESATm|uZEb{IRjH|}o&%7{oIcyR0lsF5ps=vT4*qc>rT3r5 z$XqDFGa7G~*4>*&g>&xVSptpU2d490Ru|^a z%9G{C<^`FCr7_Yk{2a(dP72(`Ph7_@SMxQ|5-(yhW7`!^oZCGBUr{9cE2&)uzO`@%@||(1shi1|DkF==e2J_?@x*1)+_o zNPqb!Il%wk&Sg#4D*(Nn@?L^ddo=Rn!eC4WA=4w@Pad>mh|hp7xLORW0VkE6N+*b2 z%9UvWB>*LlIFr3yBy|85hgp$h-M`;i7L}g$yP3j{z#99XV5A`&3MC1#GJ0U8u6_q@ zgQ?Ge_V0nH8N+*U%>Y($?#CMo)d!9oIpsFS>>H{9P{%4HrD`ZQD{i}w$@l-f@$b%$ z*k<*khcS&_B%RgS%V;jy*xVciW-Kg>uBEQbq`X^!p^ooMj*qw3^X`KR{QIY6zDK$G zdiI`=(|ceS*Hg`I$ir)ex2g>njVFJ@^%Auw+$Z z@5XRAXBTLXzhCOaNi_nA9>)eil{gcbu{7Ap@SrLbcZ$JA;_U5TpE#hFv2B&Fe^dp? z(M&4@@uNrIsRME*2+^qTV3B<%-yso^r;fVJUXQY}2!#wLe+DC3?9e7;p|Lb*nYhxg z?Xhjv*}s#LoKTCvP({VTX__wJF2GQpeq7=W2YfNJ#sDp4x^RI*Ob3e<&=NvgQMrty z)ZD}G2ANG7eSjVi84+>HhND~GzUM}(?2KH7STSEI_%nG~he+IoS?$i9JBb!rK(q6>V5Mlm*DcUs&k-OwPnwDOaA= z_{=ffebODK#d2PxfO#>DMYz+0^Bfsge9q*RPpMtJc+p8`6o8J4v@k#u_n5l8tG`$~ zn3;6`e;-?DGoP6PAH_4cV?QZR`3V%cPZ>yGS$y0-z7U!MU&ZP~2+L9UMN3~YoCC`E z-+r2U_O-R`tU+L+=@tpHAJFEio~SUe@5#KLdxGJkVB|+wS>U+ffwS$&Tm;GEGaECB z>sX~7cBM{$Y;Mx5Y^%wmV`Ab1i^W)A?67RQ1l2Mj-V^@%J1x;F9&ma&k|qbX20-SJ zXttU-mk)#X_%As@VhM+p{_gHjs+dlhcfSbttC@4fM~}*DTwcZ6IhiAMcq9?MW*_~?cYHbg0P$rOalS~?Dvz> z&NaF=saw!{+p{^t5cDDB%MCH=dLjoq8jEZEhW2}-3P?dh1HYMH;Wi$qFk{G5?0C8& zFHL_&Ao63L=C-!UuJzTWI8g7rSAQ3B_pWQHeV9_M3k48L4}ggI@sl|>Aj2cFLfvSKvAMYrE%C6*AWei#C+ zsE9~`U+Bf77zKV^GqVeNu01b%Ap*szWm9Rp()d1BL3$6a`sZg!0v3uGyJ*b$3!ogyvB|6iz`zAniwlKk}m@52@X52|^~A|^@#MjTluf_i0$hm8hptm$Zo9&qGix$0fj?u1I0@@pCr8FM8L7`f zHXs^@_b^^(8@@n(RS)a=ynXd?f(J*Q!#H$ealpIafDe2EFatNW9K?uxKK>%yyvpZi z{T5b=KMGBM|4~FK?&GyNLAvZ+_|#m*(~e>pe9=YvF8z3E)K1Js`^!f4;&Il6_qE`B zhA1zh+Ef1{WIdQ&Plpv<{ppHCJWvHb(@Yo|vIG`N*vpqMvCNj3D~n$vzJ9$B6cPf& zCHmnhxaaC#US9qh?@tgUm3pS5QWXMY_;8*mMMH=j9?4n zCkTvAgKZ<%*6q4;85_U7^IjHbAg8t4f~c^st?tR&PI`k}O$-|GZ7g(nt|4}mLvymf znCt23**pRiM#|$YMDSEwvh~eODmBOoA+3m|yh;IR%I)7t{O@A%9wk(ebOvmsX?Cq5 z#XL#*0;^ViYVe(WjsSmc7HmeyaZZMhzB*1B+< z;^JqRKzECFG(cc^jfQQ|*kl(Ukso{7>nt9&7hZL-)(LfW_5N+O#tH{gV?HjhMRqw? z?*qPjWL(^No{}G{^#}JC?1Bp`#B~_74yc0czu>k#9yvJ9C#PUJY02H5XAhW8`Fg30 z%Nv7WsdHj%Y;3RW*PFL*%gD$6p98EuZU|Oa_93nddhBLOJNI^|X+OLT6!sCm>>W=D zj5}?3z|xf;(2#`0ck`CZb8)?hep#ULjmO;N>+=_GS2YosrJ7Fo>prqO0VUVdy7}a< zXjlvTfXrcDoRrkkx{e*vZkIN$KBQ&ftSIcb^hMLwJji-9PTja%-A%cuM29j?BtP9+ zy^NeSVnFX4*Y$NvgIy&2*^nGz(;&<|O0DK;h0xH#T~U`fha}1H+K+`BM|_zbu+)#3+Kff;o) zAU&N6&FzavuZ*_cjeswbH>bXpLy+Q?&D_Vh?W3WifxN5QL0W&=)3b8bR6LGZ^VT!n zLE|*iA-xYIMKBhBkAXBCfo!C2f}NlqE4V6I4j*3iXKL$d9UUFj*?gB%(WEEDSGXlO zEbOTH6++@gdeg5@q z&rYVADPQmF*(XelJ>>oX<&j;Ci02|bW+`2plZO;=%w$v$$Be{soMi_n+IP(4Fg=FK z_WL={VX2Va2Dm*QM6%d@G9F*~kpSmR6hwFp;0ZZNZGUv|B53?dFsqDzy=(lU^i%a( z0?k6(a@btM+5Du%LTP^sV?6RCuLVUVCAQ@B#QAf^A5Jj96UAPBP$r&q^Fbx*(++GC)t122O_V+B=mL=aRQ_Ywq{^!J256l<^b`Hq7r$Ag~sHRl_xJRZ#ttfAohZwm8<^_ATfRa ztw1}YfVjB*(KWt=hNE|CaO3=C7SnRYRddUM?M~QN^Eu5g@|{@j*@LPx z!~>&nFjaQW9&|OxoDKB&UoQ{aU@4b#u|RDFXND6%)pAk-htdjVW#z78)>X`kzAGgl zBhv-|z}MX;go+ds{{sV#ndbq@S|spiw=*kZ0MjBrWJi-XV!TAtIBes2a}Z zyPEnpv;iM?BI-ugU9OQ&RcigkFy4kzt_Q+lcqZAI#U{SzN0-WD&=E}t7dRQ^3?mnqecjYwynY{&7-P=8$$DeLzz zmG>zc$RSV#7|09r^B-0ybLurXapJ^dsZ+KnI6gBT0-e7rG_!0P&tfvberpcoW`uI7 z1QI{V~%4q1H<;r=|7fk{nW5j2tQC!@o#B7IF3>XH!efD=bLpriTFrutb5#i}1 zy>Spf5t&V4Y26A@QBnQqx4;%HK#(6x z$o2Nd0tPSj?{ZPh_t8qvZ&odaf4NMOpY?$%4~T1MaJ^w{iR)(vKII+XNy_ z;$K~&!uR`02n*+Lu(uJ*0BjY25`|I+s5vdA$#9v-xy}Y?gij!ao4iE@1vtGq^AH>* zHD35)wsNc(d+d{Ul<*pReROU}l0Bpl{A13WJ%Sm?vqEvIk`go%9QD9$XyS0CwO@g^ z4E3-yS=DwgsE%;#X1{oKUIkVr&<81DH_quANm>7DU#fFOZ> z?>|M40aIIUK6F!uBm0AcgYn4@Ff=0~LlBhUAiDjOgLP%8tI_(dVoQTPLxsaKuSe*d zLJF__9AyS(K8M?GOu}r+g9naF{eT#Pe~WJs5#q@{K7gFsKvOaE_+XZCN%8-mCgi_{Tt0~{smK=AY$EqBPfd~8_}v(B-s zv6#$%xcX8<(L1ppAH(WJaN#C9`0}`8pfg@{onxLAd z=3P{UIZp-NCf1h#3LV|3A-Hmwmp6dDWUz<~??0dK?|;jKuW5L6+Lv8@;))R3qiX29~qC_8n_eszT+pkp^~V0YNcH84uln zzHF(Xxwi_Me?H8);w~bt_<_4nMAmMem2tmNZ%U2Pixbx?Wwyx>*;GXZwSc*fzLgr3 zz|BH07?oE*Xd*D2x20Sz_n-cpp)n0K%SZ@A-Nzn)YGeWo5XdPm(M*iRC4Ktu2;bkI z3hqmV|H}h^94`ODoogU^aIK@3x>MZ_{XdfhJKr$eSw&ii6cu)^NX~p->LXNX-msM+ zu>~ur3r1$r@*=b}M#Yk*^@=s^M;GG!9`N;8M4KJFd*jj0QETU*d0bFV=TBsX05GL| z02+O|ja4<#{i3?Pd^x-N!pAU?)fk6Dz1#L}I5!Z3X1n?bo0NpZ#MZ=V@(qz{`p@73 z{aZGY>g{Lw^9lY*&O;d(7~VXAp`BYE3^I{MSlebkY*#ut0vf{5n-75P-pm_k z#+9I_wq}}I^4M$zXTh!ZBsk=nr~2J!myM4nx$4-u?`Bt;S-%M0J6a+9K`dJnitg6}GQoqqvh35)@-H+7VR|6kc^nK0fcNA&H=@D)p~}^+d$Fyp zjg1U3u%ADF4j0VXm){m7{(n5e{|wei0o=bE@=n3UWTJ)J~v& zRULhUDk;^2CROWqji;>ZHsnkn4X++-{2}#7!^`e1V_$1bOfy5uwGkU(S@{1QSH3SV zdl~&7y-W=~JVBud^Nl}s3}4aU0{LxF3nLYh_wuJeT-`V{5MXeWmloJ#xlRK+Z9jkh zYz>T^`tzZ6#wucyLGG^eZV^sq`SdSFTQfd3jw=LpNbq$zSH5~^^W;L^A#cC$WR1t} zyR3dFO2*l=T=R^x6dokWa!DOoWi7B7M_;J>*ZW$t=`~ZE+Gd~RJmHsQ6 z43VJ>;jbC>#{u*&Lp^4!#5xFN-7%uo%js7ax(%~9PJ$>);<+sCFkIj`n0;#jS!Xo< zd~yV+hwADt^5>~L`|v6q?6M}3D7Usv{spFoW=C=mn`hRmf4YWR(l zs}AX(xUp5RxGFPK8R%88^hTV1?_NQ$6y5PMkm)k<-Jt4E8$*cd0CuQ~V5MOgh*c-R zs_EwKkD{qJX#*z7LB4GR#e2OD8L)PNtYmdHEG%prHN4k9dXz#m-qm*|MNw=m8^*@Q z#uYYJw&xct(DcJd=&$;h_Ypih6bM0a^^=O#Yf2;CA>i;vw<@e^qnYCy9fo^@S7ziN ziQ{1f<0T7eaNTIu+urqa4QAVtauU$USn0XcfCJNo{k&sMqcax!qI;_4c#PMW_PhP& z0{rCFNt*XBi9O}I`F_z=WkxwJtn9_{6@nEM_%ON^O|Uydhip-SEM#)_?i;e-&yih* zg)0p9r=49oKmyLp%MKLX%mWJhd2!OT&=-zEm5a_j@YboS1qKEZmq$iN^B{wXGr7>b zGz0b=vU3diZNUl{RdC51otLvvu!MH8e*F>*d7SQ}wIs-RXl3!6qtyJ1NU@);!-szQ zT#mKgC&#^AjEc9Ws4M&P0FRjR=}4}JCs$dx)7I0wjt#E{Fqud{0g+ORqMV!=P)h0S z_Pk;K`}qy9GjS3}j1}D)_EJ}E@6PR&ytV%d7$pyH;Ae{O)B@sl*`%%h2rP*ZhOinC zTKDxo-$SJU)EI{46Te)#HkppWHsbHLfmXWZuWAYfGhpz)$+SFlg9dTQ#63FNZk`SW zlCb)@b3=NI3p0YR$LT1|0>J&BrPU&=9VB1KNggWU!5Jo9hlk&RMgJNspIs7qKshS_ z#;cTlROSuwj-%?h4%c4| z%Y^qnOI!e$NHoI``77Test8cXI=tN>F8H6ror0va=S8Wv5^Dq`$O5cdIVyag(%|ek zxYo^3-={;-l?hyABnryEuo=TP9C8YZ#_$75A*_QwQ~9oNxlOMwYJ<7W8h!|YIWRma z_-H@Ql|;v_`Wgn8yfC;G&C1hw&un%v;A?+Hk8`C7#bvntz;~Wx{xSRTxWlM=KIa4r z+$F06aiVzsdg!jq8QW^!BKB*ZZwE9SMkiA%E6v>E67OoxFp76k+)Nk&UoJv;GUYBr zooOOkIN)@27FYXAF~d8>wElR|+W+`4$cd!7q&h@aSQSa;G)zpOSbiAz;Vm}+^^fGBmxjS|ET~ma~@s1BL|9xYOFkCZ5U0z*&j89qjj5f~Fz< zlsY93uWMsHFLWoFg3ro${mYljA1<(n{F&VSYY=!aV;KHR05)Vp)}ZJ*wKqG#2=OBY zetP{hX+siOumrmY4>fBT0L)u7vEVa_sUWo{zyR9CE~8hHo>}+`aE?*H#l)$#YCJ&| zy7KYjx~-ha@za7D2D|a|sZkP57Y zn1h0_NNL-%OIFB-qJOWX0|J{zEHH?!2D8qJ<5QSG80E24P>>Wd|4JHOXP^{wap)v! zHQ=z(@{5Qt;Z!@MPA(`7z9$K%*i<1H-M;k55IV4Xe^c?HblH3KLbiT}4^8flX_L2T z=u|4xb7p%AIHDTOPOw0)6$AUgyU+A*Q?7s~WBwqc3KKeSd3xG=Tlio)%82gL+#|(x z4X}N&2?W`)5V&_m19TODG{w(^Qe}@LA(w_mQ1jS0rjF<`kc8(pv;FaNYjbn6O+Uds zJw;FrUUnu_&kBlu+x}CMS<0in*%KE}?0$ZiYvgwjpzN9!50WO%)F4S997KW`zez8x zB5T5t;yKLy06T*#bNq%uL?zs*5omfPs12j2p-yMpV%UE9%$w$Bai;e&sz5kYW{@Gi zDqV87gW;P$Q#Oy_JYl`c94y!v40urs{G8fQOv0P1C~wt>j>{W5agpd0tv9cMxZNYa zZ<+;yNr5X_;kDM-_Wu<8%QxV&Zd{CE`4h|14Xp(l6K8@hD<~9TFO^i7LwowIQyQVz zS{*D^QE}8Unw=cXZTRa*G{D{N3yG?fEni^<4^9y2JN!(}wmmpyVj=*R4oCEvdtOd~ zAW{o5lvJQqd3A0c4=XTba&mHFABZxbzCV{92`P|C0&jo7=MNPueO^hs_JDKkq<>Q6+DyWcbAJYeNyycv>pOp`nST9RQAsU8+(J@) z7jJyuHV3VPkh~#Z;1)~(D2qSA;wNHgd&huyqbdw3RgCbyV~`rKs~>dUBB+KgyM1=T zuOu?lAo?+w!C6E}FNmKNt@YvCPe*BVCN(=-9T~9!FUZ9jRUSMb5fBxvnvaw`_~!8> zZ|%%=pYIg&jfDHE;Hi^P!B<(q1~_gc6ptARSD=Z`dvqz0h7ySlN^Te+G-bNKce`o> z?Vkk;IR?y>7O|C+Z-_EW6x>ijBZN9-8xdZH<68n8$ib5W45QZDc=n!ehdHkI*W!jm zc7vG|L%o)75ck1mOC6b7oOu9;D-tYFiw1n#{a*uL47uU(-G#fNap8gxl2u@9cdUWJ z{K>gjJGsk|Txa*QpW6lSI>D+!30-_P{7Ksf zQ?_vb$2zA7N!?;AACm?+zd!!JiLxcvM}SRe4Y=7;hf@6<g`>KAipB9#p=N=hlMknpZ?b zME6lEu={|w3-bYpaX=v+?~%MUotr_Wqokx%B_Tt|0Sov}AW1w(XnS=ArWE-nJAe6` z{l3}ol_VjMPn`WAY0N@uOrV+X8)tV&R zGvP16ijV5R2f=wVv297T*K5efRYD#?3fZnNd&1ngQW<$mpIDE!W#&MXI12~#S1cW( zK;XI6*++Z?7|0raup-raUS}oTKJ6y!kI-b+lvag#?aiAvpJh;e{G-f;Lz4OqE=5m5 z2*a=Ql*)(Zj2S*B-P|N}iGPJTnyFB|c7rcXK`=Gw8yM$w_tC)66lMeYePDGV8D_}f z>Rhw#v19k{SlGXdI%c#aCuc4Z_>E0qf*+DXK@q6o6?lL?vF+4}`3!rth&i!C@}*}q z#XZ?lf)_Uql5HU25inJkA15j9)&{YhjYh*bc#B9l_r2$M^z#1S^b4MnYAFl7)y&`KY-c~ki%b5BOW0aZ3SjM^pl}81Ze`~EGF15cxebm1(Lh{? z^VD~JC!$!Ggdil?4H3LL^|APp#P35vI(_~`DHui!PwL++ZOHOlE-%lXt(cUPu`m>v zH~Mg^97WOr)RCHY%!B0GfX)lFeIsCuas)R9nu%yAQU{ke(DG}PA-}sD^#=2JyaYGj zjR}<{^~Q+OdTC@71E@&P%1YeuPNnTY`UoB>(e3Qfx(NhHU#4 z0!RV;~5t2LZ}k_wDu%U@R@iKEf6Jmcy{QUaKkm=GCV+^Qjmw=uVS z-+Z|%-uzL(7hhSeot`4%E!}>lxpJqjk>v~JF!HgZA&?G3&g7u1F#7%m7~9wdq5ZDx zJyeChwEawN{fd$~ACG{~91n#91h+K}O`bxlkh0@H&T<_Abaw0~W=)B_MAT-1G6 zNX=?320<07583WMF? z2#@$(gs(OVvGBn+JR~0gV|^pomt!?Ki>yQ)3#$ymI21*Yn*fc6Y+y8y@k1hK9c)W4^GWggQwno+d&|9!nxk1%a{eAh5_R;u#Q8?b=UjRHoQEY zC~q(}^4|fZXcg!ewEudSVv7sFA*?iG#-|aCi{0j3?BSP`ESJfD%8bbFP7A_t$hK5%exyPm72@Q>bymcG_ ziAI{10Q)|rkcZh@ERxH>GS~|_(qgRSw3I?9>NNt4jFS-%(1cZP^hPYya=pkz2z*L$ z8Esb_s>=BOCyc10FmgJj`d1ja^BY)~c<{?mN5!^L0{vHmAb{#$D%imdXBb*)sWiSucyki`IefuXW9+Yh=D{HEn(>IuuYXZtzUYw|9K`< zKlM6%XwGj*@i#Lmp$QoBBVbrn@?uXssI17df8**L3115$A|ttg_Nt?@d%qk%WUq%W zD$X1l+iutGkw0KA{p^v)bUpGr{X3(e!wx2%{jx3dq=}dRC&U?9Qzk~hLm z+kCjY_2a)nwQ(vS1znBDoWJ=-_5#Qm;-N*2pTT{u%jnmTm)VmiPmm{*j^z9^cx`MA z_79i92aq*rTKOBrd+MA;+r;08>UTaw6RWBz+%M^ok-=~FZGy!wPqimMY|o)HrUW3* zK==xp3mGs#_Yn)iEGrY-ZF#Ow-?ndZTv;O9?;a!Rw{~;OAzJzqJ80F%<&U4LrJ&-Z zBo`VYyesv;OGrH@O8MG^c3xjk*`S}IhtWM>Q2#Dv@J@d98DUyYZOnn_n>@4ET6{Mf zAG~pijMv~hQ#0o6r8~Ca{By0|x~Y7OU=!rM8rvMCGOYbM)Zh`1fapc=H-qKfra55_ z?;allaEH6RYOZn~UWx)|ctU~z}y+`nI!}t`?DwiS8NtPtZSHP-FQ`wsx8H)sf$+g$?93K+Su_ zag$kC>z)|&)=cZ^0mR>bu@Lg$^g^Z-+!p5m(0(WM#e1PV90P zO3~gH_kWFU{0@bK%R9K#7r&8*=_>3?9Eo#0*8%^9zbJa-X3s##d;T>$kO?xZNxhJT zpLr*mX<{v3CiJOqLc4LTXCVt@njRWZ2={fk6nUn{EatSZer?6PyN9*hIr8O86HIN+ z3rxg@fKhG}>`#U@mI2=#&P5J+AHE`PU`HWrhfHX`1<#kPrjxL z(N3|_Ui(+YZo$|_&XDhAzc;}xUF|$5g5i}e zFY`~7pZ&{P)T@c7$J*NZ*~61E#8D-nPDs}c!WUtxN}vnbKuZ`3XDu)w(wX)csm=%gT7|#iZf<@*-P&dz_%uV?W8P7_c z>p;halM8tejiPmuMNDy8Nq!9d=UmTyKi1e=VFp7sLHKLMePLkL2ok`|YnvPNjEtkP zm&VD_-(9;&F)ty9b1n-7y2|_YnT?ur2I$Y%)5e~}ceE;w(h9z{uq zu8S)&Y=1Tg=v1DEx?t(CR0i?WankO=n0ynHlInS4fcw%eAWdQnUV#kid5^ma9Sao< zD#j}3ngqXCWE6O5zUbZkc#qC>7)9idI-bskSIid3!(OD@0xdg1TuD$YtC~E$V4PF@ z4BavG$+JL%2mO1QkoEr~>$>ByZrgXn6ZJHO(jYstK^kVLY_esQl&$QN)uy4yx|LOu zJtC{nP)V{!Au3yFkTQSAb)#QB??1hLJiT?_-|scf^Ei(I4ngubTZE1w z){s~b`jhdXQ-OQx`}I&~2DS9pC4L%q6{EIp46=UTIiJL?r}3~bTrs;De->gNPI)hg zkeT^`G=B`UGqFpFFvOLSZBzeh!O_<@$UB=RFG^-;&3#ltZOly&N|EWg6I8N{jF*DO za(xaYmK{0ek#n=M{5p16fL^PxC;)RV$P2c8(pJpc|Jj%v0YBq?rv?eI3j2i+iVtdY zGV2^J7vF46zGN^h#0Ok z3k?)opxlCp*>Xx^m+I{y%pBOx?y8U4^Mii)5kn-Mha29!4CAR^onZ*VRV}|kc<0qJ zGjH3OFc{-X^@q1IH7}O`aS}AAGiXe9Hs-VE?hk{~rI^A9UJ5k#39+n#2?Y2#g%ryZg3<+C%v(t z#Xm|a&&VlM<2tS}i2*3-4+p)wbO_iL@dNmUcgKzG=wLQx^b1U-FH+0cqpC4oB(o5V zMhqoYyxOWEa14G(m9i9xWB?Z-d~-_*B&*jqTNpQ+clO&_dXuLjL7Y}?O-1|m>`OH_ zU0JX?%b~TPQ(Z}>8$f9`j_ns~wB4J-34)6A??zu>Wnb%amA(J}mZ`sUAVTVj7?(L5 zV44rLfsMeYradTf#BAyq1jys^Q$~qnsw68yWQuDUs8jVswOA*{zXinwyXB zubkBA$mcY5vtznQci|Q{0e%d6M1{*Abt56T&qXXZ)9Ls3VUQBS@< z9)pK6PH_#TtxINhfE+&|<`79v%0p0x)V+=`J9}7&+^xry@CU>4tjLLxCv*&K2^Cw6z{>rl~NZi#tl3^#!voFw=a;M#0O4&(`r^8OAlneDm#~)? zTyIOef)v_6lS*W!zAmk9xn_F+J-(E312> zzN`O&B+0VeLb}1kxx!snKr<^KPA{g;<_3&6yH@GX=!Tr|#r59=CX?O!jcyMJWW?ks zzKl#^h^j{2$r|oRdpGE(8u5^cv!$xq$0_1CQ=R{_#vG2eN1T1n7Yz|=-pg=|W5Mm?vgUJh5)94k*A;vFij%(3?s8YmE=3kTUH{3K?d0U``S$N4&q>6ZqiW z_9{hjy60{cEQ72O4{%g&_5Tcw`EZN7uLw9YyGAvS`@twWKrhd(DPx1#YrUJ-1av74y^2pFi)P|Lnz!$UAOc_Wh~hn+~2vfLgJ6!8sDIOTICm8??Gqy< zrU1t##A*dsxyGn{x9y6{Q(JU7YlGIo8A4}oAS7u`q5u4` z^M5A!daqdbF*(@66!hRKtdj-91D41C_!At2PYG$}!$vuy)n359?@ptkbdF1m5?RT{)>jiQ z_M4+X{ni+=8DPaMZP-;=FjIES6tg8mq#7JQ@RIh`imP?>3Uge5n3W8bi$xa_R2bnq z6Qx_ufTQ~g&M*C?5h3e$5*3iJ5jQ16+Va&(NVtUD9f$@BA(?M<0zbDE7XuTysCNnh zMtFq}1v6~w1qczf6Ni=<)9PJrDI`CmF!+$m%*DY-hPFDVL|0P@yp*0a#-aaND-1V; zF>|b3^4HB=qCua%q6y+05xnZH^~K=E+v$;DZ=$(~P7AOm#rb zU@vARVpdhMkQZ=sbKlwj>G!@YmXwqiW{!;kaLMy$SoBk>Yw^ z6JIGtfKD2Y=lO8a6E<0j{DC460FzeLaCsd$eE8+X<_3P|lqeA{?W>nV4BzrXTW<^Mj%3DR3j&Oz`cd}JW6dWe^LK(=8y7H`4ibLL+xssbUZ`#?UKx_OjEi-qd-{E3d5|to^yAi9Q2eow=8d{E z_H0%~G&S6kl9J(u1|-j?odiyZ1Rtlt@6GjNpq|J&Ibu_8Q7JWgQxYy`fOkJOI;~#4 zdW-v@v0=8=b&|W;n*+(@O9I=iXq^<^EXl{W*QJ%D!=XS@Les^As-`!m_K%j@@72N{ z|M)S=Fvu=pATR7}HNoYmbgWUqU0-Ia4BP{iQW~p9H;++FnOdoh*3X$nYvxd(uBeho z9BQ80(U~*H1;c)t)H-kQmCO6Y4bS%t$c^1Ge+w?oLG&_$sxQvrb;@Rzz&7GALYY~v zV_yI2W9cP=wbR@V0eOfxVw2$+Zta__kY@Q1ik{<_4m0B33WAN1x?arFUbU^txa4jZmYn_5CQ(OY;+voJG#vBx}nM5<{ z{W0?k5|U8NjIBFFDq&nLbTPiXb#^Uz)q}@VNT@lv4&#;~* zwdWRQ^w2Fm5CX|PIutX>1)uwC!6>I@EQ8rAqI(_L0*Oja#psGrMn2(-7NTs=hCxVq z3l_Q{m^i~_JGO4bUw4XX010votxs$U^%cb!lPsTLBHAC|i4Akj)H8QP+G@U+Z8R}~ z&V~gODxwwu#ecjFypoCCSYpL_YN|6f%zhu=yyss|t+n1+H53FxEJL)q%-WC^9G+zo3H4g#1!Q6T0b;Yz{%vHP3#Jv@(%WLyC zyC#l;%!X~l?;CK2uqM2|iJQZh9=oFxo|vIuLSs`22GF8{#KW~$<^DP#$k#gsafX{&-lADHnIFf>jMVpO z{+r2E8nyin*KC_*L79i~EK0~|OmZ_>5&^_bjRd(U2==~v4yLRn=#g>t%g^v2e_IrR zM9JtID<@K?2l=00T_*_XvwPiZ!9aG{*Aa`j)rCa84IWAQYk#@rvK$`t($f>pzwn$c z(F}JKcq9D~R(fYx&xKH-ot2A-#fY6495=#S8$T4_y>3iwsYJ)%jcbBMSIRySI()1D zFd8`8CCKutNIeucyZoYj^&A_|a;gbcTWAp~#XOouy6l?4*~=>!?PG-GiLBljh*IL1 z^JhfQ-{^^b^$Ao0!dFiI_`DHxeb&@3>r!ItxpIQWvB3~e_d?`M(fMhR!%n$5Cpp}! z@54UwmwSB5@yy7Mih|`|?v_A!Q?YRaM0P^rSK#h;0w4enoa7^GE$pbDgM9@*R7&WM z6FN33ys@ilft3PoWc}e$m9l-RsvY0m*$ZB%{%6cml8N_m^@`Qpd9KS1gL$i<&D5{v z7r@xVdJEugFfs)ro;`uwIr1umCnA8wQVkM}3Gs!_UlumGiQCiaAK8C`OXqcnF|YQ$ zpJqP-qY}~zzr{ViQDD;Rw))kN!@adDRouV3u#K)rN&SUXLO~)_>W z5aly+pL`{av2$hY} zSa!W5ZzXW@%WDzZj$*sE0 z&Q4B3w{4&Nhz~Qh36f_cWSs*4$cdbu}jqLq@L8EzG#7C!;PwAL(=B22{dtX{3QYcO~bAM*O| zJeF>PG}Jx?2VPSXo2XY4`Gp@n!Y&OGN*QyA77hJ_NKFsO0$##0aU*3OfK%PfH~C2h z9OB}-#0_Y9qFHg#Df9^BhFzYDQQJN&KFgF@>t@L<3;rS9h7J)y!hn*8xS2)X0~+`b zfroK@gs@cE3>5eYY~6Za#|)*(Hxhn3>?%69{HcG4EH)Wp1FPYFDgSTem4|epz2qLs z6Ct)qz%wq~giTppDdp#8AacFH+*}4*-i}<&f5Hi6@4pd<@aZfLT(x;OG1?3CXGVS= zK9A7oL!65w`y!LuGf+4jO-+d?9httuP||y|J}>d(Ac=1$cV8^3EUT;(71wHgNw)l@ zqQU=>jeOz5^*!0^uo*WWSyZPr$p9F-~n2!Dj>)#bU@f?(7g&U=V^VxW#1j0=H<ykoIM2vc*5R|1K?7s&mfU3P#;?&7OODF<@ZiG~6Dmw!+QX>Yg+ zr7zqfQGiYac<}JZd-~vwSk)*&YjVZvr--GSDr+`%L_*!G#Nv+(M2TEhTvW{?UF-Jw z9U-r(@74sBeLblLec(*)K$GAUR42nORTmth8eXPh#zYGRRV? zpS;|CuqA?KY10lS3P({rN4)rlF4$RDd?=jw`RK@MRO}MPSyXdA6p<50#N~k_HV5~to6aB99M!!KaN`htM zyTsn>ErTnWu8>`v%SfWYy(hlzRq;{OZALvIj2pzc*~3L=GbuguKV9ARS|cCd-CLoz&7i&843(JZOOer33nLENxdKGmQ(c17 z`QFm$k-NpqZfOVJ%(S`LD_l+LJcA0{$67yLlO=tex?S59l8)- z?_cf^&QPBH04V(u9)v=m+7NG;U*F0_J7HZVp_@GTXw;NSA$;)bh0N3jl53DSHTLxd zdzhyQ@G@iNo1)2E1#)+Jd0JsR%L$PaG#|@bh}Nh=)5p|Se7D!F#B>S9p@pxbWy~;+ z8a%clHa4~f%tY-9Vx_&LnN@r{+#L~AVfaqMu1OQyvCBn<+7`WHGJrx08!o^h#ir&C zqruF1lV=i>!nv8^k(RJxClffnPGCD#7n?A)t~AoAFfj|8nX3N(+4R>mhn!kEM(wC; zvS651IEnls7u#Z5(rKC$+2|4+DJ`nJ2PM#JXWx#s`W@Er=(A+Jylz*+L`rqE z603>J^`1mcl>hT*_dqVOjaNfUVcDCGT2CbU*bU@j!V-YE9CtBZ_`#bt6iu3cX^Gn4 zjQ_daTX=9_6>|5^$>&-GNcze5g9Y|I7dptQ?Kf~C^Jt!!kkqL!7i32+J;1y!ua_#=V&W`3bAa!W)sU)hlXwstnPj}9{^gI8 zQXe#Bg3*DidAOrx>j+~hNL>I6uEuUYM}%b6#?RhYJbJDdfpys#DZ;{KiB4qqqMHBhj32B=nc z+GZCFXlqDWCM`k4c4OBV%AZKlm84|nXrhN}92c708>ps?_<^JeQLOGUu0_Pcew@1I z-QV&@Y+Xl)fhJ&HwN9^QoBmFC4I{Kw$s?m^94$Bo57nUMsIgj zjLdB!S>J^{v6QuOY%vmHmK)load)&HRnnOK&+SM2;3P>rTI2QAcJ{(+x+gP%0ATG& zC9p~rCZ~H3t2c=70^h$uH}q7;%n^L@#P$8EgziP8n8Xo=P=LOHRvNILDOJg3EdD)F zV1mYX4ang3+FMVzjq!W}1&UDQx{eaPcZK-V3roYGZQJ=Uia^JRZ*1`%ANYoh$l9#e zg#1OA&dvcBc=r7mX@3gur^RYnhY z+z$G*gKh66C6~`l)mmHsd+GksOj8f{qx9JUU67#PiHRxM@&dn62Bc8==9WK*D?l>febZWm_CEZQ!-1_w5K&vlM)mxzq#KPaHBO` zAa|6dC+&VwD=-kQPZR8A=yx1-gC4o7-MJ9LBy1B@XwJML58#qjz29L}lnU@XnHA-RYthV~fE} zVoM$w&Z4c~aecRsn-@X!yTb*)qBnhssZW4tHQgA|j_72-9$zphTXCMB`7#1lrN{***m=Emw zeE;zLRM`|6rc1ju@~Re^ut5Z_pk#rg`xy1;MzLyZ7_ZmWP_YL!0^>2ib|X`8goF$- zWPt(mqk?r~O;1RIid6-d>6t|r>N&|L#$V4$+^j4my(VQ);{F~65eGYOk$A>IN{{I` zI{8*fxL2$@r+513_b@J=|LmI6&=CD-e>jvvbxWE@Q@o<;a7di;%Lh!3jcK>)(oCAu z8=f8px4)29*D${|BIFU0u?eeETTLZ7&DK)*s65jk(tY(>jDtJcPJLI~ajczyb(}S@ zYoj$aM_@TAM}iL@TtjS-E`w9kzWDSBKbgtlU`SE+f?{eAa1hd{ElwT#E{JhAZRd_d z|8rwQO#Rz1Q8R}VIvS2PZADTJGp~*=+n2?&3JMINVt_77WQKM+cU|7t9upmCz2#w) z%g4l5-)X$K4A%bHZWz$Lv5nnsJfTjI#zIRfMGkmd`^u^gw@LGsZ7}kQ2iC=#7);Ke zo69}0pgY^9r*a{qQ=1|o(kJ|-?=Z(vNP9(7z*n&}4tzPgDC{F!#u0Pl& z@v66Ae5h?0^=g3mNXKrx-%Wl89P$-ODzTw1IcJEv74+?S2R4^y@*M;2{N2+HxDWvp ze>JyF@sgH>m9SpEfjAslt2;YLZYNi%IwM9Qia5qym$;GN|B_^M^Qke&LZVGOG zyUXkY9~~>!C?Vz$U3_y0AwqX*_>3_r%kh$kaRQI1ZE{_S8Z`u5yOk2a>w}5!N*6bx zWyzRERzmk}vw=8r;-E2E>M^@>HFuM7Y?pY!l*yLtWAccAU~W0_V7AeiYnd4UsWMVK zf0X!+bU;UijQpy%k--?n1J}Mne77M+5<8(6RVKruzy4-PgxQ5k;_X zgZc8RzCoX<@6n2aYN3}iGB!ns+lGRD6i2|jCg$x}wUUs&IsxL{A1HyN1IkIYy1CE1 zhl7htez=aQx$4!x*f@1r&i*HA+k$l*HGlSj0FX7x@d9m&xDZA-&yvI(8=e5uEAb>E zy}KuE;coH}GdPqqhayyQvKXK2jqmEN=qL;BEa*>j-u{6^D`EysPa<`Q6IM`oxYZ~H z?j@#V{VTb+WaI2M$`;U7Jk#+b;MH+xCF$aPr%v6%oV~Tt|Ky6jC_i3XQ0}xKQ2T1Z z(r0{fJPmh>3uS(`&sSMGw(|oNzR3!e#_&e+6N!mDI>3{Ov!Wu-XSQ?}5JV;l4aljB z!as_TRNBeU729B)_VP%_D`~^LS*z9=G-nyZG89PjJN9J#JM)9nin77`-Qn@&o{t(w z_&%+3#?K6OkXF>q@p!Y2eb`OrrerOKe!7~V8o^0nNM!6mdfFp$yd8v)wU_uM?So?9 z*ttUd8?;zPX>T8S<`TW9le2SY=mCe!$g{o2Vpc2$Jwfr(1B}dH(gHKOj_dB7+O<3+ z2&nMz^;^qe5BR-){0`%NoMzR*aRDDOU^@~VIVIi5M1$`N*XZw@`@c%XcZ!%w=)H|% zgByhi-26h76u4*JFsg6wAHg6Z1#s1+o0+jmID8&m<9}UnM zT+p$J9T?FOQP+2RsrdIEhxIIg-R1)?p3UG745of$&I7)c(7b~O4?<&;psXvm#8g-B zs_ZdFt8@IR&(r*EDgXXzvIz8dxCX8twcQ}{)$fXLw^mAWAqMj3#+!r{3!{zKKD7%! zgWD_YZOn8)dg`ae_aS0hOe~*u7B+O`K};GU@MWy@R@Any(bE%q!5-Gx=z)n^>5Ec4 zI$2txZYM;5P-g4SVz4rl(V7LYUkVINAFgbh7iY0?+KdR?TR8*PzRx&_ z3W-?WIWb)%p*iZ;le80-MBy(yObapVHGDfGy;iU=A%Rl8W}PvU(wVfZs!bejAn^qa z&j$71o7c^80Z=+7@}jwV3Wu5p8RTj3Z=GxK@=Qv8 zoUu!-AyTjE+r^|CD={Q=o>xTtO0NIJd+V8*dGHe!U{;Ok(X9@zkg2sO`{OuLcRRrd z-?HX7fq=*2Z%saB#!%*?N!M+GjebXf zU>ZmM`2;pv8lhuAJxIcAC(g)ty~MKfpqedg54k@x8`NOvv8@3;*eK~ie-pgLHR%6+ zfK^kFpZ!piRn5s=hhDnrvw`TJMF>Z`Bbl5vud|qYXy$aoPbZ1!C!icY5?%9c$-T$0 z4QJb#fvfjTVQ|9?RuC&m{Jvk(vvD;M(gN!EZU6}GD=%;BN+k}>P+z^%byu<ch&E0+`| zDaz0c6LiC-$2|32RB$lYF1OFe#^M)1+W(i~4$oyAG*`w;gl6|b3@z=^ zH#e6{Ic4KtWzM6hke`#xkJjm-4d6y&$_XylV;%cO?gh;xAy)E7lLhn8O~EsIvKsTN z0eq6%2l|1IB%plYKzty!uWF&S6pWmD%49rg_b>>{Lzez^!7EuhgoL+9l8u6 zeCY(+E(m#;g!674f0E6PXlcaV)z7*5Uw!_^SwU^Muy9t1qrsZ{sO0nhA=a4Ma19tW z@gX31AFm`DoD&d`Pg-nvy``NFZ392qzCg{DaBtW4lg5-xC`Dj^8)SP^@Ad}T_e@O> z>?0+=K4S`H9RB=Po9Nz#)GlA2y%YEQ;k1pk85}eHijq=YkemxBbP~Hv6V%rwq~kC6 z>l4e?gVAF;@_dG^_WM)o_@mp=eWHw6ZTlzMrIKHKRimX_x2U8(%ysHiPBI_=Il1V3 zuQh!c9#1(*ZxB~H$_0Jg*yxaBQob#-5_bJ5ec9=@hF1fGO#+fdxIf@>JupuP3xki$ zQX%Q`d>uAbKwRfP2o0Hfx}IP@A0OW(-opRFu|&WmK%yzL4 zqkxn`8ArgheeX4DvIDsci5@2Drc#MeOF63EH00no6ouPjJQa#LRa9{6C}e5uxw^JD zW8LE4TOFG|#*W4-@LqJZwc;pbCWVWMg)X#loBjh`{=9~lEbX#2eBtbx&@q)w&SnR< z@|3yB7ScbGK8D?QJ^8!Yi4^#P!#~wzAv$^eUw4=-elrK@|8%gI~CSBplx!qvs0|)&pWNZm05hjR=EOvY=1MpPW1T z*jIpN9fpI)pEtjG4~%9=RJF9&0jh>u2i^0JSHF&n;~)v7;*MlIz3apAPtVH`E5?Nx zVCP8mbj$wYTfL~nI>X4k+dx4A9lCFXZQwMZiK>owe1;Ka0v_Kdj9mL?>k1> z7ljZ%2p!_EYPwwRz0zxV4b=}wC&mo{UkVO>`gloHBy2y^abi#U&IH{>+>rAhDCJ$r1LwZp_V0LM2Ser7=GgSmG_-v1=NWMSKl z^|KqVWC0!cX?lGgT56KeAg`15Ahgd zS)3aF2w8{LP`3bLX#3^?WGfy;JU?eU3(e%Z16wj5-P2aHA~8`1o>!@p862?$dpbn| z8h$kvPwBR(GewhuelP6TpW0ggJ{^e-Y(f5UKp&xu=WxCvokUTlk@uls%$l_C-@XY2 zS6xX%Ej{{v)6PFnTROsu^7C{woV84q6OLgAzV^_NFrgN+iCsgntyd6tNb^jV2MU21 z)8~dw$Spf|rUV!*Z=lqV@Ybl|%)RSRD8NZf;AF}}`)oWM1bw$`T2vq_%gx8Pm)Jtb zRwWG>iMK`s1P(gYA#(Qpi3F>WA3?EuuD~j;b)<*_w!{eEL}t8=2O%) zCe0g@-aow6&eOjZQ&F)sCoqG%F(NJ7X4~hf{+|~WLzLU;Z2BkX-0Iku5x30{ZJWll zf%*3jF2vu6K_WJzc-k;J+j!Pzfv@jIpo1NWdo@01F7{e{Pj{Gsu4Q8k zvv^L{UHhIR@4!59U!v<^Mk?xu6W_{1w~=wyWpLDr16aC5^zx5|5qHbZ@sXt;JaJ03bWJ_T+kJX42spM z2PE$QN`k^fuCwG2^^>&-lG+s_ig6;i!qs7?!8``C7t-o&nbIEaN8WC9KZx#2f>9j;3(WgYvQtpg{9MSAGL42QO zCVMq_84u$e3RU=IQ=g<1CSsy6jW3rgYZ$WT_U+s87#t3+f8*e@^8&!+hzfQ-jVLjD zm|azf8185jdvb7u zJr3&q+pA6-Bg?zC512_DY)sa#)>-wyHxb&kvNY=gYc9#T0j4Tq=N6AB#X;S zKsFxkW?v}2>)(2lL_AE}4@Jo1ra4>|#8X=Klqb18#4bg5$X#F*mNE{y!OR zV6)viIyc*)%OOVTzpfbyek42CSB8j{0^P6dz}hsVMY|CV73$N$r=-Tf*e(18$$y3h zE<3xnV_s^M8i!^GtPIZ%Iff||(So!pAv)Qw@nDf_p@7&LujrV_ z%v(USZNj0h2w@^Iq2Er( z-oz1yE*S;^| z$6^T$OP2<=WoKI9;OSYaXc)aq@EwPnuMoa#yax7}sBw^9F$ZC(vCiQBT*7FxNkRa4lQRG{}PW^YknbvkvjD@w3}@>_?1 zZnf`|E&hpGyIe82!CpStE=>4<-b8eH(&+@|LHNF`TU`2yAx}+K(4o(BQFGPd8@La0 zuY9_C6?lj+sY)Sq4J)V}-G?n$x~9jtApAL%GtRYshm!(QSl0U{TPRWArLHhF3ls>j zV(X1aVj){>S?l72~c=J9{qf?C!%y8~}Y(gS2?SkFT?_rB(4sEw0 z_Z^!HG44Pz<`I;(oi~eawrV-1Mk0$spScal39iH!Ez+~B&Z#G&jME@P{xC0SPGR;d zVae;g8`*&aHb-a+Tqy~`6jj(pZy{mf3T~Endw|2-LCxv6xU}z-@^7Mvb00WQR=Wd4 z&+#@|)%Su<@d`bZF~tZC-M_0gmB1NZSL^?;`DX8rm5X{7yd)b9E2BZXaX0K5=_S;d$H7V z<>aVwn;s=S5;@aZ9#*KMxIcLhR<;RTSA^jD`L(`tv*=t+2rl06NF#xGzb6^qzYEr- z;jq-=2T-AnAME6b^#t+14UHwyx`uhj4kk`V&GO5# z>y>M;LGJbS*2vJZ(5USrY`WHGWR(V=`dEG(P8~!LvSY*J_x=o>74VvPuQQ`R*s_I$ z9Jl=bbm1+91cUBXmS6+BS_hLAWvRRAZG;GBO-z6i0gqcI zJR4!q*(b}iA52Z*#`EXTQv_~KImMO04c-zO@hs@a!q$pqPJ-QgyqAsbH`o3#XH2v_ zDR;9E<=R`(4}!W&zlgqHNM5$>Q=jL;)X(XaVc$*%A3eeLCwd~AK{%B{?iAPA?$uYZ z9n%M>$yo|@SN7EP}mAtno$5k3`W3#4xG=TMMnnlGVT&GN_-duAw0j(vlNbsJGg6CH|cdT=7ja z6pdn}Mi(wCHltreR*$4`Ov0z0jd2fRqj&X>hl7uH@}%Bn44@-ltEW;-Rp6 ze~aVxc#5yLW9*QRio>?WixzF=li#uM(Vk1AKg${SUu}5$>CaWV>?V%;1>Igp>t}ze zxjQCBVWWKwSW(rtrK!-lKEZ41cRhUw&_c)$V%^c$93=C0I0Nu*5ZL{Ntw^=@kq#)C&Xo>TN)RpUDVvat~Y2xSc za!D~I!{i6wrJwibzC6mS+3<@Whfo}!pyiPxltykSl$Ug;q+4b$JOy~(I^BP8uEd$y zx&MQdx4Y4(1p$eS1nc>EP44=o&2T`hKD&|}=wB3Z&3JuH+r&qe2H|kv)!Kx+qUH`n zg5Z?7j1}HGXVrgbZlql;o0W& zlts|%C!%!2QqS@4D@u5Tu@*$^Zrc_1uUDG5bxqx*Tb1UHd{RI018ut1P0dIl ztpW!p0lmxgeyq^S4!WvmRHrZ_xezB$Y2fN6b~0LT$Dm_V$lHNZu%$&o0pn-YWU_^p zU3Em>t2Ok-jgCg<(+i$ageeP-5~#16lc{TjDZME{}|U7Fo!tO(er=( z2Gd&ZMq}qIN~?}AWlqZol4O~;&}FxtBZej1`RUrtfed+-&KBo#=JCJ!y1 z5q-fu+2wY$!{8*yi4`5$6gNEoQ;u=3`8nv2%efH}jf@mUv#`=<&*+}98UD3a=q`}E z_;|D-&+J{ieM5}@ej}w9rdY%(SPZv%&hg@D|6va!TS`x8x7w|Zrjo-|^4|~=zr8h| z_o7wYE;9`N_sB10v=T3c5ag2d-Vq%?uo+KS9d29KMQmi(_}g1NIm<|-xNWz#Z*}JX zf+nX7Y*#d0$L{!K*W}yRCFzz!r1}q^m*c>t*bvtt@YL^reRQ~|>jn&~GnPMPb!2lU z^sWh2QoX>-S%7lb`1YQ~GLcfXBMYde%wQA>Yp3E8f4l1cjppU}j+rX#KJ8F1w93zy zIB}Re@GP2ZbKDtbclc*FW_ET_Bg<>#tUX0UCT0a|UZZk-wIUp;$5x#OJU7EZNPD9M z_gRgI6aUbk_vIC_ruBcs-Bw}{`#rgeE)D0Gp-9!JE&!1BY0vJBURm)`d9mq=;$jg= zVA4(8mmVDnd{kRW64rxz-s7Z>Hmb!*V(UJ?K~18Sn^;0JSFA zD3!he!xfmEwQZTN=3tCU!pf2~)U+D1OicirYz>>>&tM69kzZ~*hY@UZDXKTOSEm@X z?QQm4x{i&_Ca7h^vAK#{P|b<>$e)TkIWR{wyNi5j5#p$X8gxPREz88&Pu*TgJ4X48 zwnT#d)UepbRt2K>EKGl)oTlA;6pqJd{#pE5X_uY!X!lVX=Rb4-9Gl3Mbb0)xz-&ze zYhk0~4(PGEo|-jRiFRS&*2830RCv711#Q2#0I@MU0rm_bopq@Qs1;QcH&3crqkd^N z?zn4oV!yt=5=_4V!d$bL$q3k;uh77(+oy5_2%qL|!XhCe;%%8LZ(UU-A35IM^n+Ca($topJLt+sLd?P8mx%z6)tL|teh2^cjHHgac1lH z_{*`)vQi6L*r|e-L6%hzb+jf`?0kdKAb+Lg_sfMB?#SR~kfTZcoSLpra0zR022Z4Z z>acF2H41E>)Pm+%ETMnNM4=!8rLrzpd8d)MZJd2A@FwxDKjW z8JeBXdd{NCPU#pjSl-3hI#e(%Z#P;nsf>W>H6QWdLr|n2cwX10Wn@Ukd^5*1tszlg zfnA zWfAupYx}ew>hG9GBMydncVo`w#q;fyD=8|$KvIOV$x76ra9|s;9A_kU=H~jc5^OSK zJ-0(&ph6`Uo7`*r6UEQE(-91p;EJn_H6&}#@>2zrkkkb5jeu%E;T}Z^XULmWHlXM~ z_+Y6`h-Pc{TVQX9vrns0L`o%3kLh03=@)XQ?W^g5)0mDRD z?EUgvS6L>i8?E39bI36`E}rS{#?r##QabVMW|&P zF*RQ!u^eOgcm^neG31MPcyX%TK?GAq;svx$#PETO6iL8Xio z1J3Bx3*HMaX=3i}-37jzsJB$NRcygygpZB!R!a#9z1DL64;fQ{pabW6^X5eFr{!de z?=*@Ij5LkJRf)bIx#W8F4>$JL}L@)qMi2Ho>s!zy1G?5$~deaH}~Z zipN4RW*&~M1-jV*{=89eL*Yf~kAH>wpnj|~KSc-?Rd-y}?98AlHMvO=GmvTdVVQcc zPtMput)9$oirqaW&Ov1xm+g#f9PN8(TE#rSw9A#>U7G5K!S>$j?(JWTY2knp3c6$U z;6D-HE~9DsR><(HE0t_jpm7E;G-l+Zb*7jb){GN?8&{yzaTxpnClutFA14onS7*6)x zu%hOB>Kc^XKtgC+2Ku0@; z=}g)1*1cW>M~5a=4Ew9q{0kE0+uDxxr53lkc0v7v|0DGm-yu?bc#fW3{db$GPJT>P zo|VYcQu3xg->-bPZUD974NS+MB}S|TdR9|YBV-TJ-5o%d>LYSobf>gpQo0{FwCqFL z<78yU!h6kVSO~i8gqu9N8h1i~Ebdn&uY zjLN9t>e+K1jdioyin@*;aSHCuelE^0A=WswqV<*RZm%?r(}*`03U<9RAesqR!}XE5y!%BlnkVQUWP!)6 zThOb?60=Yr<(por}fmcpCFZfbj>@F8TW(55LzlJWosk1PUN4 z*KwgJ@7qT-sgXA4&-T;W-19G!nfP+1oVAi7UaoVE+nA{;sSiXI307-YBQ=LchNVlx zz^^E1hzL#LS6JBzF z3sz;Y2>mGzrAs0uNYY3=U|#CuVc6ma0)0f%B_qG<XUf6Q${%8D+1c;@7dHCjrJiwzOm82cl~!D^+#WWhF{_{$ZQEz2?wb0J^Fa zu`)nOxm;gB0FAKeV;j4le=n{;Z-<7GQlis+RALl`QF1msujv?xvl&$M{|tzM(DSV! z(28(w29?)}eiQ)4Mc#*Phy!q{Rg=*DWweS~qH!FfA0E9urOru&bddXgH#KQ%UTJ?a z+r$|$0I);isM=`oR~)3ybsUwtbSk;Chsd&1v=^4F3qoBQnRJ{Y7P~i&kaA>oiE&^^ z0r5t@N+(vG0bXVnA=#3b`G=Ta0N@xuPAR`!GuVw z_v`7@`Kc6Bom(dMDh^gB;oKr+bn6Ge*3$YGSLb|ttKG4@`>hWZ>b-GYDX5=z1A4)7 z?$5SyyAn2TU-9Yq-13ddCMNevPNKiwsTOl7!PgNJ%aC$coJ-n57l-zH=>2*8`KFTV zV#ekQFBlexR-C1nyeJkQ7G0S7gv6H?zPPRLw4G{-7=TKoy9~$a`xR9-W%?$rAxgYC ztf0;3T7{TVA)0Jo-b2%0B+r>tBMwmS&@eY#c(yzsdT9AQ-Fv4kQkju-N)HhSuCP$IzAjZ39}nkVish3;>Q z#~1VOZDNf5@OB6y(=7CHYtx9(HVjNnmfYGa1B4auwBKsx;_9L?Ir- z?)x9Av>@hfeP~+y?oI@c^+@PVdE{Z_jT`Svh+uB*{XHK5}U|D5O8&ynjGI z5TRc@zUM+1c)#taN)FHxCn->RUJQPj|IfeI=ohhg*xFnsC+{lsHjgl0)2{GBFBZpG z@rL_QAe*>y_SmR+qp?NOL)-c?^ChlzeV-{VcVdUUE(v_<-@|L>QJI`@&pK$FT(Ms6 zH(K7u$jy%cHxC51@Eqc4g~5$*uU!8d}QF9ro|U3gyjQsuk}Rr1LI;%uI6!&CwOR1tfNVF@AL7`w?x%EL6aq zB4p|xpL7h#yp7z-wjqwK57%DK1ZR#|)>PDh%rnx6ydatvxYv-vL62&9r$X?*79b~~CoQ8zhMNxE*@J^SMXsh_(N zixaM{m$DH^M*$&^($IRUFs)4MoVQn7I`d~7*=jNuma=ba3~Ct+)}Y~~8d;cd2n(xS zUAu#m%20{(@al3qwDaFBG+t5<@B;SpedPCZP*+t~cl-HH=w+V4pP5;58_|epzIUVA z^^#I)kfloWDFVNF0WWr)X+;03RraFwRwS1yVLb-Wya+a`|eg z`)4j=*iNJNto8oUKvIh2^loGTK1!3TZf0BsX-_BGIOj~S>b3AdwQNW+M7U^K&dI%J=RGsD>+m*>rD0`r1$o+a(lJ3YIJi5^j@30)M zpu)}{Cj&KFd3pbs#QRdQcLA9*Gu!9ObWFK2wtDdZ+-LQdXMb}%KTNi3r zLRc1bEM&>lU7qv4fl+gKzvH?XhC^SCh69*$jJlUENZOyA?JAr4N;2@E>iiAM&M!MZ zJzY4#!y0sR;|{*J<2Nh6pX}su`hifGQR$AGk4EoDos*Shyq6UxAk^oVzut+={bf^d z-UjAu8o<~;k&vB^pgy;jy+*2Zu*^((HVG@H`JYB9sJbL2h+|jjC0T35s&AjFpS?u| z_Pl(P)UK;#lztK^2MM?K2U>&zdtJsUSp2&A@a9ViNpBBa$AAT%iGV{>NpaXOm=vdOfa-QCTAieB-C+wkORR_bB;Z;Q3%z?m_%I4fwk zeYDcm8RtB54*AO3q4*5EBAEI&F>^EF9d$ihi+^rvdSMRn0vlK$^HWat5+*+Hc^LF~ z;8z#_5}sOpZu*vodGf*bc*iDYr5VEeb^(pq!g~TgFdlm)V8OnNLAOkg)*b_DuN~Wp zT?#TXspENnIsjjly{1m8qWPc+Dz| zNaEw;Pq$f!yS@4@lC+=ca2W0ScDAAg7gY zI=v2g;N=&BtUZT&4jO$phs(Eb(Y>I;poWo2AsuoP@;npFW(yqLz+ZiBXB%FTn#Bn18sSjXf8BM|46=OpZc<39NI3EP6u-70iV)2 z=)=Qt{<~)3s|82)(n<2i&>2leYR7s0(#%R*aql8!x#l@AkGcy4Qk6TFFcYTpBvS8> zMJ8_f+5Y%UDsYcjx9`LKP_y`1*DpD@_C`}`PeW=XjNRYWdM&-tl6EHn2zV3hnOlp+ zOW^>en#@Ia37IQRI;Ez^ac~#bzk@#i^Hel+B*n}<3BLI*AVhP0zP%-6|zj zooqD!=utXJAx-bo6PYIV5V}X+c!xH2X`pY~pEZnZ9=e$ef~9VFu+*nB^N3!MN7Td^ zyNlsjL9O>zfNgFK6f$j^${5EY9$Iy>`+4n5v2_{4huZGi$?W+75+&9y6Z z6F9;PWh&P^nsfbPU&OzeFfh_~-dulmrb5L@lAg4793toKw1$R;A$q!vMI>qT5m3Dk zVob*(Q4b$@bkg-)BgAg2vjQA)mb`w$;9+bI$)ld8rlz&1?qW%};eO)UmooSW9F-ra z@^-YxxE3K-%!)ANTF-8fc?SFgQHnpp`;+umREeiRQC=#RS=PV7nP;T+@|C z&7f95Bt-3reN~KKWYaUL)}-+)KHB=_1`jx|cU++aN8FH;u} zlyz=HHy53p32K=~%g7OvB!konC*4UGd0ky^k5xhQ_@Xv&F5|*QXF;cOAGj)n6j^wA z`XS0BkF*GK2phqTnI?>bowre?2yvO(o3MSkKaWv&YKJF5$1q8ZEDAms0AR3bv}jZ+ ztRt;0bId3GIglbdl~AGMt=fm$s7G%7D7af5In9=n3qxAc7K?BA;OH|R*}S*DNB3ZH z77+y50o@yn2L~qq>>lI@PqW0FAtz)G9WGA`6cb6=i+S1fE`{D&e(!-V@A|Ip?l3Qz z#kq2+pKsd?QaS=F{Asq zTQ>NReu}|C%Nj|6UcNXd~Pa2x}bp;SP{BJvB6)wn>O*B>72UQgQ!HwTLaH zYRaIn^bgG&Bc|>;CbFZ3!>hFnXZG!$`ZY&2=$2g!@GZJ+6Q2yrpjuaL?%3V(W2OmU zYWd9MWzKFO4D|^wxut5hQC@bDi-zYx@*z*l*abt%>eX8!$Q*K6VhMl zsW6ChxF|}ds-vil4Rov@qnGPjAjwoMCG_Oc}Qf zXnzX${IfTg$C5M&nM{+4=ZJ4V*8MLY)JH;g;T3ZJ)#B>DIC}i*L&@O^ ztTDoChWlH>1T5&Q56t{77S5R(B&mN`a&a!o@9&$AwD|575F;z0hac|R&zmbu^&8#V z`9Rx@CU*V$bp}Q?t5jznOx5iE%CfoH=FS;bzh%pt+J{JvAx49nqn3?z?Y9H@Q)u%O zl%9FCeS^O@*?y%G@sJ~e%C0BeU1V1$&wW>k$Fav;b?!+m(>tFAzH!FTZ=rgnx+QK! z{N)A56X;RZ3kO5w{7gWJSGB6Om)EJgspwNVqA3-XJU)>O68L4-xob+v8d9$(q*kKw&X^wCYmD z;q%$rpmsiWSLX1Ek+Z+c>8n-J5B@y+T%T1X@i#EaUZ@moJJh6o@*iG38h6(Z>0#o>`EW++I^wB zvae&aNbL2^z;_j~L)tOwggI)#4tD=b7hz1t=1%NvdVvMqT+)Q{4dsiIKtm7wMP$)> znifZh;u#$)3zg5b>L^w5eCU2;tWk@1?I$%BwJ%!Y!v#>Z&)2>EK+Ym4R>4KhL+4vv zs?qiB4|tyjv?eZEf5P3V-?1ew){;89Wkg2H$`QHaibPfqg{Y#&2ExW|in0C2rk+cj zSn20ORo~YiQ0MZaWaZtT*V~6o!4xW``^s?R z_4M{c&Y=Lc1v@hZ)P(wKla|%eK2@X&;M`4BDzeM*sc){c=9zk4t>bLerRoArGn+L# zA~^dOAdD#jjZjLj!%(D@8%=-X)!B=AdA<;-I!^ZfIhH6pEF+Kp*1T+qNAb{3Xo-Tz zM!#d^7+qXB= zW|{miUrf3fo<~4k9p_Ym6BFvnE9k#NQ;#$0l3CM%gwVB)D{d(vWUs8OKON7ZsM`vu zt4;NVnJ-=bcDgjI@ZG^%eI-#p>%Ba6%`zm94GG79V^fZ?h<{qJV1Z8VZqS~hqoN8s z`P@9X7Y6CPL#w%#)sT-^xD2I*jm5v(w+VKZqgeaU{GHm7YO`SovRt!~@7j{*W3f-} zII6oNDj#dx=Zml1306ra=BKId_BZqY7>k!MoEvW0cC>_`?ZIsUwzfra*djvxX*Cg zLI4XNjWv6w0O_;b`~m_wr4+ii?qtThnl)>8Kj4ZQQs@2Drp)5`7F~$G&m6W0EThhh zjM@f_jfJaIR%spN3~^X=$@~MT_0Vr<>@A8htva-Wt1EXm=b@J`UkY4(9CakYnI}Z? z`h^bzU+(!+2XO!DNq>ZjV_V`KvVbZB0}Yd6*?Q3ra-VJ-x#QCZpZ!#|fI;mgDt~l- z+U@e#Y3A>5hyi$&?J$TU?YT+HRDu?GL=X$pN1R8!v192KI+6DGUTv7#Thm&7=fKEw z&@w#9Yc-|q*om<5)`zvSCAjnl*p*5>pX$b*$dk%KEz1+eDz(i&EUcfNBORNM5=?X! z9FHCD@+bAbl2Yft+5bs&UMcCZrdk29WCS11OFtGfbw}%-+rOLQ0^m=4coq`is@&&4KS}~MS^xuCd$nU*#s;f=RpsVw3L*qUKl3$D zz9|SIeZtBmMrCH0ykjO7rx!Egyp-st;(mP`e!9@c!&hpl%&YC)EuQrAU=H)E~#b5T+&xtF)_(`UcxX>b!;fvb^FoWfV%cM?D_)=k?C?`KZ ze;u%vnL}GQZmgoQ67K-FQa0itLi*vRgZ0FgtWj~E4j?xcazv##;A3A6PrGHBU%)?0 zHV(Zg@zsm5traz6DX)YtgR{+aV-p_7O&YuU1 zrP5RjYQ{JYm$g^lZHe|~Ao@lDX0mRPHb06mB5LJ*GRB|u6T z_lRpcoV)GvC6{kkmQfe&B)4)u^HzpOx=P8C2Jc`H01`d0hK`e;*N2Zt^Yoh^UxNMn zt8F%2uKzW3nA_lg1b zdv4}3NDU0&!0F{yCv~E80$-WaEV^#E|=zce8ojVmM;-^5~hfym1}sQMmHoDY9E?4a3t+KnGl&x->=F zelgsx4Q^1DHh2q2ncyN1%zxE}g0YFj>kdDRqH?7f5xEj@8>kTiHs>GZxK`O->*z@&q zfej%Q#84?=7vYV(Mn6Z9lY!x>mGp(lj}7no&1&v4%MR3ZI!!f*_?Q%P0>UM%O_)T~ zXRyxa1h}c+y)|%@qzgbN)uTDG5q)*%W@t8Hz2Il9~q(o&YIq<5(6bx;4nOil>xbuXll6irmE??OZ2! z;VoN$g?Ky|c+k`MrQ-I|=l4gHX26!|Y#rmm@jYYP$x3B&!0R+rc8fk@;^zn&S@Svn zu8(Bi=(*1-Z{hnbPULpe*MmiSXCyDQCv z-h}Kt+A3DDm(BDrg=UP}zr-~^8+n$2Kzi-)iM+WFf`iS#6BZb`1s*s|c`{^*KF$A@ zMbXl_t!jy70s#fH6#7^2ZaLTLibk?*C%lF3%4jcvIp*xGXH4K1GemL{YF>j4S-c$r z4$HdtuRm5eW3*etWr;Ng;PYjvNrwW{84+iEb3rsf}k^#U2 zS7&1rc5$c9*#hX&((upay-Qbc=WS|CKXVe}q`4W=Nz<>ML*&*sQhNN+pD|B}N9d2Lc)b z%pXPx(fp_|x(HFAy$KNOdt81h5yHb9dS1|$pYYjjAp+g1jE(>4;wTmzUCv6~Y?UW{ z!yY^^M{dX<7;$vsa3X9|pLp^w0Iw&F@58 z_q$=gYy()WjNAK#&%bGae`@ud&qaJ1HU%q@aFmX?;p*R~*Zt!SMs+>75hwog&`SL1 zQb+zCPxO;WOH1P$W?N52O5qDIG3{Dd@XI4kE>=Jm;Gt&6YZQlf`9Bu8xKy=E?s|#& z`jO?1XSy6yoC(;3zIm`pv+Lho*^~zy{0kQ3a>hK1#J^@48B5RU`QLkE{)CZ)E;yCt zSmts2Yn;ZqgskEBlVae1#QLCp)hmw>FR< zGC(ET^~H-3U92nKiaT2m0)g5cEB=w44^@nqbY;prPO`f}7)C$#g=7e-wxd!?aKyj> z#n9cR#Qwm}2iEHEY~zFWkMxiKJ*%5<7_r{OmWR06979>1bh@XPiSxGVvZ#HnJhhUE zGt2=XA^lALK{=4E^SXYHh=tGVJuId_4(_ER-rDEC{2M7#$1=}V>g$=<-^9&aaoyNm z5&={Y$vX29$cwrDz=}2<&GHtJQeWr66$ETBo1<33z_2jz{{6#dPOXI;Vv)qR6=d|H zF&;1JbHz*T{nf6LLwiN@V4feaYkKz4bI;flEAu1{JIYc${-Ti1#A4{$mz83#FgLvC z_d7sLk(nsOLMi9Zrv$&I|i^x7{3E;FdjK^QWDGFXLnW_Q>^TDo?AZc!M`nReJSMmyfGP z#ysRdZHC%Le-1r8H)DL?Uf(!rxV--32tR;c^hoIlZOdwpB#YUL`(UyNcv$d@RIa1= zn!Mf(ut*Q-@!@S${a^3l6(`{AheM<#L=0+*&1@-PHzmXvt z&bb-wEiJ<)VSzGP4@R@DJ+;)S<-ZpFN^Cfle4k`C?wdT7N|G$ii^LC$N2qVTqIQn_ z=ASu*-{!ANd+^{vYSGhDijsM!#brtxr_eT=*MVz~8tSAB9&*EoKby@yFk9ov@XM4H zI+ZPOYGSN)`F$Nt)I-*N$%^*0TSA*mZjH4qEI3y!W+sg}@(Mw0T-*L9h1Q6?eirr* zi3yhHCw#*6_{+uCi2LX)z}7o**ste*E+=oX9-47;)P!p)$c%peZIjDBpp0un%zSOg z=)ZWz9|_>?E$TDLPb^v9mh@z3g;5NkJ~hF z2yLzW`=@i)XCRiGlHq1oE?>T^vOlqXhzzc&$6t4_Z<^mmET8~1)?*9QK^DnFet8nK zFuR5`kII6u>tj^bhrG=OVA5?q`g$1#E;`Rg5jiwJk9~4wo}P@g;bsq;nwq$lYE_?X zUdwzLYdKAx$2y=WDC|)N1IdQLk836q+2-`g}J#4&J4^|p7p+)iGu1`;So0N}y zT78*viPUl}op&olHSd$QY4p-swXQgGK~ikz%PEXi9jr%;LgVPHLAJDuD}l3KZmuTrXF1N>I`}=VMA?0KE7obzH`sh0YT2LD`rCr$unPmxCxt@2L%`u0fPLykh!MRev0U+HrSg*8FV*gA)%t3} zjLSk9ev9z^Ngku-7}T!h|JzDZnKOTR|5|*f-x}R2{7XC~WHy`C$aLMJ+E7N}nlyU8 zYjEqmLaldw9vsa67GIQRlSlG-$3~Tj?^eorZg@rLN8VhmSQW*NyEk>0ABGHk&&RGC zE4g1?rbKdfu@q1Bb|nu zJnZGz`t?nrZuHq+FeIjXKi66|a^DNa$NFd5sRmRMh+aFOsewy;)0!jM$qGhC6J#n- zxn(_PW0s$-XIW@wx_+ZTPfRhBwpV7L6h2)a?tkuKkM@|5po)*~!9Tt(e@+UnKcQHN zu~qs-vO^a)v$+pqmn?sO{>@q{yHJVSmBuGM1t$x9&BA~&Wj~+!-=e}9imK+d#@^1;MXxBEzhbf-Lr)sAX)jil85j@! zC)7y_ECNvDgq12RyD`)|MN+T~w&>_oQ1>1nBYfd-D2pR>MqfQ+4h16DeycYQ%Q;-7S!<92enzZ(wU=Ds;FSu25hIbfH`FBf?5qIyYhWyuF z65}4M8kx3+b6-U~Dd2c}_?~_mJa&E^#-G>~CO_gsF<}w6fLU5q!h2rH_uG18Mq&7t zV3_X^A$a5a0vMDf!$OB^e>av*#igqvKW4F~bNNfe5Vk2_f%cPxz5PA{bs#;dT8(4R z#T%)_Wuqf->oEs2>Jh!ac%P{$ea_+yMI%Fu9=}Q=G|0XC^Zt61^6+aq%d1irt~Kl( zD)>r|>qS6m6Jw5+iXvPk4s_>!hJdVZJNGc<^Ea`LVu&e$g}?!Q^gm^#uOE9)zJEr; zY2&F(g@9ms5ZzYLhcAPENZt5u*7uL@dM+Qw2CtBJEylC{mb_YJNp>K zvHZNhTwNPab(97e@tG2m6S~LwYFB@JdEG_k13XJv1eD9!!Yds&L?=j~ z`9g|}wC2&9k^$m7gkQx(H%ZiF?lghvf*Pg7SVc(l2N$m1U!w63>%3{Wf=A^Ti8Ky_ zUE#q7;7`Jb(bvP2USrq-x~!@d>9;c=a;+J8<_4rH-PO-0fd7&?jRETa-BzHu&E<2F z*;xZPx;9e0zL2F8m_9lRWST%J7GhPp>Jb}pi><@x|8u66xV@7dRdy#%``ur4;K$uP z6&4z5SpBFD8+}k`>|q@VO~v*oT($V}IIx0(bij@xLH#LTd3y&g{N1tl@YPBM!un4~ zMSndpL*U#4hqDymCNCzAHKmEuMD5wO^P8pqai{zN_g1)|Gw}8_C4`0D#+ralkGS?b zbR7+8XSp|@5=)Qb0g-u20xn#+NOWBMe58UKpsWw+iKKS`0-0}Rv}Vkwy1$`P zNm=>4a$nG||C*?13Zgixy}GR!Ldc0jZ>j}N)67IxPpS5RtMvNre~4`AFEOJ#+Ijus zavqh|U4K9C>cwz+UhaL~7MT0I(p39S@Nb?#Qqt&W8Y<5V@Q`@+rM=y~dV!!Q{s!W6 zDp|=*qrzUQ%7C{G{Xs9ti}rEeHy5p6PUSnE{}kDN6j$A%(3NEfvu2Nsd4kNRenFQK zCIBgYfSqQ52jMfp9QotY8SL0R7D8qURu^^a1NNi3xNC^V$Zx5@72?D;uh{M(Q&{9GkqRn%u0-%s;r(OFI_lF zNGV|}9IjC$iP--+n0Ee?Y*-TR_>Pt5cP9AE%jB*WSDnv29)cVckWT)fgZamBIIF6f$jF;v?u{)ye2 z^fGdovTesJTTf2O2`P}~o$t0fqw-bpy>t8aC%PHmd6Cu#LGz%(4ES1*eA%SfWAc*F zAi-O)3yUC%y!4>xrR1TzEg_DE^R}=Y@?xNGx0SXbsO}8b>V zEhe7x_|c=FQ0f1=e<_m12qvbL)2M$dpBsh{*|QW??2=^Quy~S?P*8}3-MD7C{MJ2O z$CY0$8h`jMy6#M+*yy{n&U`lOfHY>{*_Tr1Ungh4R3SVj<~7K(M*Dq)Vh7KuC|aVb zRI~9oDR#|Ohpn9JB)v5>BxGrZRsjafB#Ah}-?lf%EYV9ZZxd7L#^dOA%!`q092+Tg zWW~$BJI=vgM`;I(!Mrbo4p!k7x|H1^6e4u#D(|EGYAR2L=d746{7*ov;uwGG%)-ft z!SgMftZ6rgKOl?rM*67A5iM431dWd*Nd$L#7?KchRnRiISlCgf>okdD#Jbx5$*1aa z({(DYYO1PfP}E+`2p;5SVO!3xnb8BBe%680BG2R%H09<=t%C-`5gfR9XdkrnquX(T zhrm+E{k-N-GJ(8{4>NDZH!oNEtR(%cHOJ0olDv?(o*ZCeiS0!MHD zoJd@e#GpK`m1m;o{Pz^niO_rsjXk#s4)?o-ida>>0JT;zbLBf9qd?D{k zm`$9!zdRfPb%`_y-~kNZXXS7sqlnC9qvjjXnr!Fkz4Tk|g}Ztf6_TnA)=zq$(#@R4 z5|AZv*WL@VOuag#b1dSISDhEH+cQqK|B1WMY_H&9_5)$)3$fm0Z>brmce#XaL+a~Ts%1O_JqXj#U?TPdl5A3y}Ag^n5qQ)#WKuk=ss4PUL1ls#{OuvCCu{US^_1;%N8s`%MGiUHNNI{ zR`OcmHcwe$DhX<_u!S$I_jC-~=DuvTDck5zFa=RREMX3mq zP)Hn%&pw#t;6{;Tp_z_%taUj93d7v&ZrGLe!d^WYuhG-=JzvsV!zbC50Y_2M94GF{ zip#q3*QrM-EwXS6UX(1#+Z1>9LDy!mY>^Mrb(AezTps!1kO+^I$Xhu<=n*Vy!h$ zbmhxK^6>PxdG)~$=a*I(=LnP}w6CG`!ZI=o9}RB#^9uC9r&1X&)R{ks?27PHN(TCD^t$(4 z>t(Hlw~&fK(||?5rrgPN43J?={8j;F6*aXv^-ucN!+}q#-OhZvHxjvZhy?DM->1_j zK9ab9K_u7KA)wAULrpPtS?q2r%vN8&C_f z3a8`5)_?#S#Ngk5U64iXAHkiMvIR9TTnB8*BpnffO zh8JUfM>LrZh3l|wI;>pK0$Wwms@D{_jNgjm4^)q;aS~UvskRm08(`WocwTejWFnqe zg{uByB zS_A|mcz6~y(UVTk!&HN7OdSc~?b`z_H$CS<^1 zvZx7iP_e3eNGd#qn{_=euHjPqrsDvoEX!9Mv8|@b0XAyc8LnMzN5f)0aC$OO|GrYX zdm13SDy!ZG!`fN&QhW25Qo|Ug8`9%`u|aX zA^ls78BHx)O6}@aJWd8m@y+5dCUV2a1?9M_+5OFV!`VLQb84_o_DSiP9JSW9|l z%~F`*_L)q3mb$raW+N=ayLG~*8F$EaMEH49(JeKoz?p#bmXK@=51x3aH)tle4RBVH zSUWHTxD-!ku(4L~97;QVvl;1b2zqGu<|abKZ2OiDEZlPGSF);U6HI`5 zW_vL*T-3YBQd`YCtRo+jIO96@+<7E>F^HM`nO~I53H&ztXCw9*PW-BfISY+?(BoBQ z@J;jxnJ82AP;WiAyfO#fXzmm?*$9ea2c2>h=w#oFDReS-)j|b|Q)Ed&ilHE(X6fPpn6B&vUu%=jj*Si{?Tcf!AQMOg5Ak>`eslkn&}86orOe@skz&AB&ftV2#?*6` z2E4$x5t*7mp2_`Q0I^^=v&SdHjJtI^UH<+F-@k*AUS$sI9!A9lOTHd9pZl;{AB%mD zM103-)k7>eX|1V;N}`Nga{lfT6E;>^(eP3qpk~RqH-}MfnYG;#V(vHz|A&qGEFW1! z_MF&UW)g3eWl8uLVXUsVv={EPfiSy9xgeSsTl5Q{PA+Yi&Dn|8hxyX3?ZR99-2Y(1 z^69tug>{FG_ty2Zz;(gzy?AtD4_lB8rmk1R48yjoVEr^2c| zso8tx3H@xn{qN!U_rC!4Yi%6(vE&Kr!M>;3rlzK^BULc3wUyo;a8-v-+i!aum%~8* z{-nu6G{f!x)P_79tHS9Hgy-^x3(~{Q?L#CP+$QjT&SFOqO`02GYy-5T<}h5?9sIha zB!%3MYx7so9V9gv_E@cSFPJ)>5uwl*32_zyJthB61?ce1pFNi@q=Z~hiwttBwzew9R9=2!Sbbh*UFdQrq z67L-DMH`6*bUij&4#4{wG03j?870fc%J~Ew3OmpTf~D@wx{mTBw`d3hgO_toV@_)U z-<#(b29uLfyPw~v{tx=Sl=hOFl%c>L40PJ)1X%Q@!42CjOpYltWk^% z^VC1n0zyHLM0|iRl2s3Crly;BSs=NwVNd^hMaN}}9CfdTKvOWtC(TzXmQ4PmALy>U z4Ma9UZ!+8o@>#1N_vCw^uYlooSEziqGfhmZz}cya%Y8(qQsu?J#TtxNz`OmsHPUnH zy|^Z^Q9s#zZ+l5FX|6FH+Z%9GK6=yh{qj~@eA;~Ht6gD7*@Z8*&%ayu6j?WXk0x!H zw0cP|X4m&){|1rjNtr(`vvx{kDu+bejtTsv=H!C`+&T%dQG__j?hv&b)%nj#BjK2D zDX?&&OLP0mW#aJ+dW$TTI-Jktri7MKlWC#vy>4&Rt5;J$BqUAf;|9J6VPZIWgB(F| zNIIPM3L>G>S9H@wD#v2+FE;sxu`EX_0sa*wSFFOuB7XAY`QoKRD3oR`wFD$;-d5yg zhnauz>gzkp7Qz4v5*&HU8+5zqBK|;YpGNJnLLvj9XVM+w=-I-8DyBX4X)8-Cw6q@0 zpZKSrh=)76q4wUaS$hyD=<7}zhjV;zcMUv>m8rS0 z&(kdnHNcu#Iz(7A<6p={InYXAL@$P(o7kZvsG)~;jSuX4q@wX%2&j#9*yoNF^773a zHf(6S*mYwL3tOaEIGeqAcC24qB*J^&c5fy@mU*->)1yb`;a5}3oW(PXM>Di9g(~kO z1=lZC;@vm|1g4RTn_HUSltYf!;IXN#0?oQpuli``gO8JQk^c-rr(#sbnq>I9YqKUw z9V2r?1D59aWvIHHFgi@U`~#*QO)LNjjP4$>Qns15&y1re#no>O*07y`Akw~E3;PdW zIu8W5+(Q8%3WCTfkU!$rQE3*s9Y*B*aO|f9465kbR`yq5{NtG>*f@#gyZW+k($b;X zfastS8SY!Q!hkfAebcE^xlw z))=NAhlh#m77>2lRw40XGujI@S67vTeD+xtmrlN;p{K{tTOhjFzsF}@UH4Emb~eaBnKO&vmwJw_bleYpd@g`9DIeXLed6YKk9s9 zO|R08aR<*mDdb-JaMejNmrs-|IEtxqf6B?D8E zsz%mMKsMH_Xsfa?URh>uP$)}z_uCqiHgYUjInB|H1AVt@dJ}Z52EI&wBNrxa;xEH+ zoG_@Wd8~w(y#rU2j!>0*lBU;pQ9yKeFE;?0s&0ekv!>bv{-ZQ8A{984!gP5V%^>fKkJB8vrBt9dT;rWE(u7mS8< zeEIT^#a>k|!hpvT=0sDWn+D91oWA@V3Y@!jiBXq-Q~(Wq1HIEW+qPeqW28(bF$~HL zcA{&+y-d3GTG!!Fvu78w0H@RXo%1#^*&v#uthuKR(oM8Hd?Z&rMMleL+3heD^*D+m z$b{m;!Nt5&Q3U))Fqea*c7r|gZm^RQ5fz9=P7gp~tO~yyC6YvxuKpRXmMOK8VWDGx ze(gtW7QUrK%$(wS-@k~tMP(urMT$(P^sumH$qZ6vn_f_fTrqjoM23jjOe*$X!F7L> zRage{TUh?Q?X>RIn6;nzZ~-kPaK#$ycI=Uk`Fi+2r45f0lKsQ8D%Yn{E}(E8LZ^*u z6Yl+VKd5$tFYvoZDtT4xnROlcKpzi71`cdo z`=dG8{@`xsjlW+k?-No81tcaj*dQ$YLxdQxjP=-)!daNTyrek&sybtU9>U*N~YiejN>m-Kp9ZZo6G;pmBiP*PmU7CM$Ca8?(d4 zU>-`|GG&9irtEh#Bg$w7Z%p^LA=`O0Jg8-!L*`ri%Osi#Ouj+frXAAcbYe@#l~}H` z$(jL@;w!)I-^|I$#!H;=6}L6skiAuiYs~rp zO^YAHuknw1QVHLS6z216J4jJ>2s*SNKHI%7$Cl9$;GK5<_uONe%#WMGTbFAaXHlOT ztuTPKLCIM5aJMUQ*93in`6mPj9%AsH>YtlM-bA~tnJ`&yjnUX+=PuoL2+jCwi+b$F z#trTp-l#MlC$-LT$UGRkw}}W`G?;Kfh=MMIkfYi&y|SM{@NFOvTPkrIOUi2fUo#({ z?CS6qWsoj7w_Q|j8P2omR){oE3ls7o(3S|#X4W9hOyoA^$l?*k207l01H3-LRqrXx z4{EAJ8E&NJ%WKAjyGvL~ml%X){d-di$H{acZ+bdFDb!^}Uz`E7wGIr#Jwy5e(TAkA zit!2lI)b((ER2%7EQL&=dja8RVZytk{V5pta(2CkhWD^7Amg!;j7#Z6_<$p#N1tKkvlv1cWu67y33RhHtu zn(MJO5Mc4>5s%%=vkTD^T7a7vapjWj9C#*+?D>3)*z1 zP3J**|GKG3nG{!y3bBm3EYT2q%w2*LM7TXuok=yn&D<$3>z^DgApn;*$N1HpE6%%}!S?U}``6NBMc=I{C z!X!LM)pQ*D%@@=uSZh6fQ=AD&R6XjB_MNk?y~fU=0|mN+55H>S1m52KT$r4<+3bUk zDsOVl4yuQ1Dj1?ZmIW8^s(i$miSzMiW%%gn5g~cdMhoBf=&5)y4)71O{EjYWUTR>e zY#RkkE1j~A)uspBR0w;cVx^&`*0Hgn@$vnSQ~l~R5s0MpUymzScXHt*YE#~5qYdE5ci)rQfK1nB22VDLlYw%e`>TCa1D_{3A^tI+-@N zB+jNxGN^P@9lNExKMAD}0;qQ$Z!@hrWV(F%zjsE7;&zU&h8ArK$H~M>52-3L3u4Jw zl-fdm`q9Nv;~ngT9oI+{8mJ0qb9Z7&k$!Z1q}C21A&(6C3F1bPudCmTbO-HlMOQQo z-;;Mat8ZR0G2^>Tfl3ucmySs+eyavl9y4%i_c(ILEJRYCiIF z2&`L=e0jm?9PUh}%f7}pcTV374yyj7qeyFmR>t*8G5bJ+M7h;-K7>=^{TksqbsCvZ zQguNU*DMm3S8v^#^Uwa`2wr6-KZR_Xz@@2AzUuUTYiD-U5K_>;pXG5O;-3Xv>jnH~ zK(9!81K+aU8>J@B5nVJHyd(4sx`(+zPpQFwRJlwwI$*6j?d)+LNBy(MZuyE8F9a;W z+h!hmNFs^+HneQb$tlzch%@yVz*f}Asa#2zgO{mq`NZ~t=i5#4A&x>A8H^n<=jY;d zWZ~BSes$GnWDlj_I>C&FtudCk6{52@lE}pN`3f(!(wAfYOG>lJaSE1543wB*vcVAH zhVSIJ8@$Xg>Bhls)0~0b4^?a_M7fAt5^J@6DwloaA$OXopXh1+5phB-cR&5|rssSn2SOA9G% zSE%gBwB!)W99f##j^x^$@ff3ZL_!!rjiaZ^Y_GXWk@0IJ&Ig2O(sYgpY~NsS6Quh! zW8?7jO@Nv*V?EVp@k&AKG*e$TJ8vKyKvLM zzKQojW!X84@8{c%mgFG0LF{{;N1j_!QZgBUWNy^YW9L!efth>T@ndv=9<@l~!_M!P zuYXM*A1E}ytnYtN@vnfu&6Eq)q-8igC&0TlT8&mXr}P6Gt26Jly;h?@fGnT{x0y}W ze2oqe2GH<0!58BmsKJHA)wy3P)?gRraolFZ=$M);b2=7m|J{D)MMLP#=L_*cJ!40- zRaCf?!#|~^U{^xXZC8myOHo(>8@=DOWPfKs1PMG|GU1~$3EznT1t9P9-M^eNaZ7o! zSWyxlPoQSP!4J4oFi?M)3x8|!LZXx$xdvxL{Jc2W`H zNi2j(POnr((vh4E@dj&hyO!sH9Ag2p+i{DseYd$~j%1e)t~)UP=x6`o>R_sP71RDAjDkoC+!R1{H&O1g=ytvSy=uR<1NeZrs@tJ$)ncJ_qJ zfZI7Xn}ob$&seik>r=F_61b;L=bgSJNfuD{>s4I7IK zBbP+UdA>_=S|08_jwG{A{GcZvTyP`w7q>$1%x!F)85>!M6GkXI0z(+LS_|AD;YuWw zeejk`cV)DtmD!mt78lGM)Cy)z2C_e5npA50)5e~sH7OCC@jx@3mvA{vQcK(A~{XPqdcIvwv+Si@YS+wXk%nRh0QA`nP+bq3QxX zTecK9FICudr;*lSfk)jJkuBl4<5%kyqd5Mq9bRIK^eDHDAS8i(d zXz9#=6wEbql%qc-d`|#-*$R7t;*m9yzAkfJK*Gd4ZWGop=UIVAgA5ET;i-=Gde2_u zKQ^2AIjL*NYUV~bEP5==kn-xIO%bZJ!&%@!g=4Ja;E)zqTt84EQ|2@S2%D`Du}ZUxzy z_+oC0hJ6SzH}mB~VoS{b_ME$~-=8f`s-KNX`2f(EGyKX=T=hBYV$|pm^OZUSKJ`SE zu~*|5X%|}rJNCeK!UT3^AhWLtpY;duQ3j|MsS)rbeC;sQTQWR+Vb|{)ge81Uo25Ce zGUHIU$`#Vdfn>p3**17-qs+u*Tt2^icxLlJtx5te{p_3`q7L2gM1k`=@|CUhvt(~G zrEL=#714ST;7j3|)SzkVEYG#Iu*;cS2e2hRIeA^YTlc;QOL*;~_&&~fv5$kgR|KE^ zsLNQ!JFHl=-7U=nFN2KdQfzcKdq}TxgB$fCj$sx?b&D%izJA9E3MFetSi&%{6e0tH zuH=2THHVGs;pqEGDq|pTy-aG1Wt8V(2MR4{@L)r>u=-DU9(hu=svp4<=v%I9;F(%q z1uuq!2^JBO=CDzY5IKZYX52(+A{OK-(RYS7PPlTiWCYTC=M9Y_`k)THb5i9$P^NDGj0oJL zy+7-0jk}@LB5Si&i|;FSh9@%$kuN8RO{t9Sng4*fYw#@6U_+ku;4^yg7fVh8?`~4t zwR-HeT0!#bI?35?Ca7xicVNNnuwjj(wpSmfob2Hv{w zob`RjFBe?Wp~t(%N{HW>wm{)Ig?Vz+F&9*Ia_F|IxE3e^)}8>W4@ayhDJcOMJlxPP zB2Qk(4w>-kU{D16p7xt@k}>psXO~GSN|6Gk#E7iHhdijUS^0L)^s6LEI5N&$QF?BF-i+M<(gVBzicI0;;#Ls^m^f0Fte|dED z&=GTfN_cJwBlnCvwy`!AxD;$xzywf6T3R|L%P)^wqJKLi!~zTN7j~}nVH@1uJ9&m5 znOE-F@}kNw9kVJg;#>J16puKtHMitlvH{lu%)B`(ILU$^jyHaG>fkCy0T6ga+%U|wAWUrkDDt5yI`Ja?t zy`5U~z@v{ecCtsc=ifBODR%DHx8u4Mdb@Ht7pcdTo=0=?qTb&EmrAp_eTc|UN}H;^ z$i&FXC*;u>lkx>zr` zYYGVe|F|6#2$C%SKmh!L*0c?$RdXfn64go)97#5MaFa8N=SH;ZaaLWaq*WBkgV2ax z{m=H=&_Y09y}S(pb)=QC+rKH|Q|g;FX)s6=?UUk|8?wHsraj@ijn!zAxJ$Qiu*ZTccJbNeu*@A?qA9t59RIGGUCmSA06e}pJsG2i9n$&2T z84gRPo0$($uA%2+!>foFDSPO0PPMmYaOfdcN`B46+-ss^I7db&6P?FI@DsVpO1F#< z8!q+RM_a8M;6p39ObM4_tyZ=?iaDHG=#Jlc+%LA-5_r$Pn)=*}D4k$G@=31x>r8AD z$iidrOp|WBz+_4r(HeH4P`l>v0R@#Hin_6p+5(?9DjAM*dsEU@j+bvzj-5R8^M8N% z@M_+lj@_dJ#$|ag*i|iSw@@?kQ>zuJ86k>qgSMR{W^jL`!ntg5*Ec)a{lo1PRvSg5 zJ)V4T80QXq4KCKk8n7Q5AAwSL{AiM=wRz@r8M0hpi>I>90}7yw7xkSGBAud$v5_ zwBzK1kOXHqWO#br9b&4iNVsPpdDf0+(k+{}#d{aSt{^d$fRtw8kAA20F{^gNcd<0!G21a@!S-C|-^FJ4qV_V~IsWf6WhV zXALS}2QHu^&|boLop0MlvLH4DHzLC`x?A>M%p2%UINOp^R{J)~_IHm(+23ZnuGhy^ z)lE$q`Wab&myR@gjJcTRHxBQ#{G;*r^O@1G92XAL4NgT@h8~8_^lAL^?e>eIXMQ!dBUEgIHu1}VnqaEe?5^zMHDYL%XJS^x?Zb z;4tCbFP_s0%Nzi*378D*-v5Ye5oV;eB~gTSR4sDn&YjPSSB@+0AtOMWfOH(E{*Th1 zih#x#SUH@L?L0d6RoAXkd8J31S-l)tRh|zU*1mCgp~X&vB|As+RlmveEpr&rMNBC)4+<0Qpx z)xl%$8s!E)?-I_kp!qchYRvBZ5SN? zeMfHUtKRyExt>wLVVHECMeC(8+s4=TpfVp3Ypb4iL7{8jQ`0YX*;A0f??BmdmL+hs zdj2|9{dg#>?Bk)D>c5A_dgBv~_3{E4O^%yfG@iaYI_lw+(m%Q(_Fj2uozVWxex99w>)&6ras5@DM&ph-t6OrP z=gSS0?q}4xJgsNcMjhuf3wdzDW7NK}`181Fi{+8lR~x%SN{mXr)y`RD@%VID+mJ<5 za>`H3mN#RE1Fp(`iq8J^>y(SrRY0Z1^BxE6B-I;88~w-BmK;10>0I^?x46XV)2H>o z9_xIy+mjikO?4=7zrnbBM*Sv2jmeGWZ5*>&y})$Gv`4oWD0FB1yAu25qa%zD zDz_3xVO5jbGN`(jn`WTCG2&!^pXzIJbglWNcXw**b$iA;a(@hL+}Du3`=k^jkhkgV zMdx_N_Uy8;xgpkX^aDR`$Tx31d8d7Qv|W1rW~a@ZQI`%l_74yBJ}%2CP`3y)b$L3} z{kdUPvvbK8al4=K6*`x?!bjuA$6n6f{_st=KttZ8FJ%@bU;1?ne`%F1YuKghbYk50 z*@e6=ckTqkW^caPi5LE;=%=4aX>=}4ZmAD{+No=z?R7Um&0I6m2$jh~bwOt71ebZQ zJ@hu`-aVs~D;0EAv`Oihzy7v+Vk1P7XSgY=lzB3i^H#Ng(_|VGe~7&!i%|aI(e!KK zxS&J1^Lx{(BP}kQj%&otpT#YoRKD?_Fukt)iXdH-x7WGo|na zt6r&AKz^yGW#6jZS1Af(9 zpw)I}5DZhn8@wx?-g8ND30Cx^sG2SV=|4&O^8>l>GL0_h3IzW;o@~h&T)<#Gxa044 zzM+z@8mk`~<&OQiAsw%~uPoK#g_`Af^Y-CJztyS<$NJX@I#luqI=zo^Ezaxt+0vlj z^7OOeczx^(#`|ZVrOh49Q*-_5&yJUD$+8IN2xx+;?znz(Yo1hp@zuZY%zm)aL{^O5 zeLh5@eFv+P1}vX`h>f zm z$b=pmY2=Ra9Yqq`p+_iOQJU6J%YaXq9?I@9EaS4uJOSevo=`d5}87IE8YJ@YoWc91PiLT5y0uy9;h!Q-oIXi@&g+5l|cthdVSEF2V2s#YWehV6`@^lV6pN8_)aO+)>B zNcrM2RvyS5Djfv)B~Us};d2T>c}y{qr_7fV~t zJ1rgi^U1{l^SAfb6DX_^V@fGDMFqQyro`qDCYF*974m!>+7AS$n$SO2X3>`A^%QN7 z*Rp(=y;Xcq)6UbCadrb{E;hE^RrD7zG%sBH+k31X-9 zru|dLIcigR_QVGeVtH3Be)>lGs%1Vg$VG~I$D8m}cwTF=ZaYPP@u=d!ZGW4tL!KIA zn=&u`iBdM4dMIMSg#bDUv)jnK!cYer82k)&{N6M1O+{{fVdKeqd~ueRJbA`bf5)9e zNpeNmtrW$tyhR$JJ92Im52LeNX?3{SQ~)9Y}Tmz8{@J!#FBM zWD}vxlAUAk7UHOol|2txA=xvVP>QUq?2!?&cXru(k1~JvyPlr!^ZEVPQ$0H8^?tqY zaoyK_UH4aeZGNpyGCki~9j`AnJhiF`-P9tGIP;Mr5s%>FL%{Ze1pLI_9zJWO;NQ6v z*}o)w=wlOdTezNh=4$(K+w*!y2bN4YPQ*AFOP7sp;nJrD2XB8Fn84hA`gzXlljWe) zV9A?jBmw0QwsPOMI+rPE%lY+W3oV?usoS2Kx*5Q17U|ufV)LRix`AB}<|x9Jv}C_; z!X1BP$y1>t5@tmAo^aB9RV9nE`9|o0+!Oa^#zb2xYJQI8U+~@m=|F!WPvglJTjujW zw@8fk0&1dLmf&d38;U}Z!34v`P*p~p#6QPFN(*29Xt&0lv;Q6!oE(<0LAO+>P&zNT zUHh>;5lzl_wAc{MP=()}bqEXtP|hs~JtM5Hk-+!51uIMc{N8B2iXO zQq(;q?-Pp8Cf%9;asKb$izjoJURcFC!~O0wWGJL<0p^FJ;SC z(V+9w4-sKt^K%zMTo$Jaw#Edw2ESci{3hFX~*cPL5K|}Bh^tcd(MOImUwTC=uVY>MLFR}mhAhT?bNbFd5S*y@L8ef3JAC zDb`2G+7&7!rF_SBaf0IC;`w$!6})FQ$tuj|4v2I=IH&#I@&_gKA)I|c-^Q=lxQ=6M7kMK0 zAF>GB7&qEZlicW&Ivh*3(x?!cJzF|i@L+g1?OdUO4MEp+N)`71#;rS1ZbF`o@^8zuSg*Vh+P>EfrjPSw zCG&NUA7U;uFALT#HtNpXx1#yW4i9#>5T#VaCQ#5*O*JfWzx@_T0bpvH(44J)S;Twm z>4h#5U0c=VxBUDzl%3}KK9*`|wNjP1?B(F{rNczwoyKv_pnInu^qWMMUo0S@IhY~a zohNX$o+T@Enz<4Rr+@@!?6LVIMMqpbI~$t>X>`)K`x8h=pXn2AUm*)tk;D;*0v%4T z9?4(G|ML5E9)5m)j8jdYw`(LKA^qfu6Y8SM&J?Quyq8rJ5P+ON%P{}vijd0a;IEyT z@@^LfHZHCV1W9Cf`1zZRUla*D-_&|Mr!2bPT`qF)Qo=6cV zFXy!yROE3>rz6J+?|MSqRB1#3)ba?FmMjZ``--cpC0MNL!8T5N}k#i+`eRVknWJ5;9&73uEDWXJ90JUw$S_nDf*>(G^TSA&|yZB)|Kg zulv&N63sAE#$`@UrBoWNg-dv~iw8Ly48PrW5b6*h+7^%PsISP@GCoF_`Q-WXL!2b; z>c3F;Otth+&-3Mfxcfn>Zlkr^eldn3+tz5yv@}TAYRa|jLlZn;>BDjEU7Ib}+SO?q zhfmsqHa5kR9NLB5fqP9dVXRUwisH#m{eE5@gfn7uP!N1&>^NRlhSL50A%ivXp}{CX zH0iJ80}^u&@c8a~FFXHz#$plV2;B^s)#A)ZGK(EC$%J+2;(3;T1I7-ND+veAlBbc1 z=%0H*8+-;ItPw269+U%tYbnhi@Uz(J8&W)zb;q+=;)qxzh7zt;dvdFTG9{wYq|}i0 z8hln{Sw*#nV916R--VnUY~j)${JG|m@Z&bu&F7iJWxY#+tHd`mc0Z=J(D2OOE&Wv> zTEbgXa=PH~#%yco#_P6U)trty=xzJ1GUlzNyXKLN^E=lB2Ifc0XAfK*f@&68bw+4% z%7&fn264(*L-J{5He98NCB^QvS6jHO>&|G~$27n9#fR*olT zEkso?h!);~Ha}U1fKP;2JEUckGX2fQ za5_b-Y3L%8AU&wqEy+3#UP&&k&0qmfDavBH_9v<$nar(7*f!%b(SLKck-V6nD_s&& z_0hku>896#!Jh6X@#KrRwqU{vn1d~)jA}6Y`(#NFRs5Qwx(O?X3P1Ro)>-c-`4^|2 z!Xu(YI8X>u;0)X~GU429rs`=+kW8*iWXpCOQ=(A_qUnZ#u0+Z~gRS8Qv`} zuv#1+Eni;aG+p%_&)fB&{%Rkm%QMOP97wMg~97xxH?Ez<4c4cQ5JL#Z!r8$-}!%C z_?z&232Dug$qaqn|9Q)i$R?&j*f5SU%3ea&PVV;6>j3K_ng3Su76|)>%f6}m48_{< zW8#T(K1IT~;gp=c$w-}&J|Hqr4*qb5^x7}7yPyjjT8Y$-Gf6PFpP%5PKWWwb!b|9_ zE01fkiD?hp-Av{5kx$C82lrG8tBj|+Kb?Lc@GWC9@9EwK$2ffAfl-))TD=8gH z3QUH2`OO9mN4er3nLpcpC;L5X;|)o1196G9VdIyt9p%zRLa|eP1+AEPEgCrY!@XAF zt)RBUaXf77Rp~9EYRxmeg_HAI`}sE)vt)UL&pbOQHq<-W_-dvY`D>J5uhm*#-2 z9eeYLUzL)xu0l&swq0?Gm3zhPrh~0(w?+=EUXw2jFl1YftwWX?f-Gf|E#%5KV^cc! zQK$5$9l!=Wc9$704(O&tV~E{9TZ`Z!jjN%EinZ=~h5kzQ$f` zJAY3=r_Wt2nW?T8gO7yQrK|Hm6OCJu^$y}Q2znyeAZov)1+?X8;QdLE{$J3b4IpZ` z;G6t0ORKn(-~1rx4S6=Q7eai^(F^mZ+;$TSg%VDg`(f_ihxGgE^OLbIwq)3p!V<0# zpYdMbO)Exb#PfK!uv+x1{0o;}*w=_%!5OC$Q)vOe8gVA!c(McH?t`$O<^;kB4$b-f z5n}XPNG7lNId(E^+li=QFaH+tjar=k{Y%LHWm`rg`w91Dm$;|PN=|L>I1`@u^>W%_ z2PSRH&00!&g({KS?kwwe?M3k)cXG3NJWx<~>|GoJ%NR=ops&ew*911^A5A_EoFv`uBO{8fW ze=B6P2WCH51-pp`dRX8SlRm{4yqM%chJ1K; z8|K8~!l~~miuBu1EFl{R%}3wO4)M=T@!%=CrvHp%=@+M^MY$aOGPs@3Nff)`WYk4R zj}h~mEElF#Oo{nVHAF^eNSvA~42@bYFg>O9xokTw{x%3MT4XTeZ!~=OK@C5VjIAVK^T{J<=Y`q zh|EvHmSJ>tcAy{~dfm3XU`_gEh?$?YZ^Fv?E-dSkkHryF$bZbPA%$AUT9j!Z@}mi8 zCo*}n?PVDN+;#f=)hZwxiPo!D+Yt?2BYaDRuwc|-+oj|#d+=sRk@MJdSteU^)%LMN zuci3mwhE42^%lyPn4|s0cPQ~MNYIA%ZOJHxHE3H$g95qz^)tT@XcooGf~|N~JbT22 zSJmm|(UCzOXUTSvf8Pp~2)8MJbaB&-z~t8mQq0V}DBG~^WM-CCD%CdNIQ8Xk1+b#@ zeZVBU05M+Gwg8FZNOlWpz|}5a{%>wM;?77GC18&A@wTk=3nmEQ)Gk5w`mF*1WD$Wq z)F+tAVC;WZVgsl2g}zPnf|_Uf7$>>{DEip z2xW+3${p_dy{FXFT7U^txBQt8T9fjGmmKSEOL2F>cKTl*mIjf`AIV7GMRaca z0C(#LI+(_fvb{2uYFpgR5JPP)qWlff9)Y{ebQVbZ19drx5T){&5~pz(&)XZNul&*3e0Njffp zs9U`C_2+;8i1d=XI=+4F;_50R-~S$p9zMFLX)p$ho?~Ql00FctTaec^&Sbz1A-WT= za2Lg2#@>Wzv6n)VuDvQvgL}K48~qXyv`3WkkXN)E)>3`+?k*LqSF$+xd2p2r#i+mNr6L{1McP8kC&Dlaj?x%zI2zdbjFplM(HvhRC z8cGl0b|N~}+-Eiv;yD97bIbe;|3EsZa4}x@n`2vUc5FR=Ti$;vf?ySCiS5p0`|L$? zkgOo*lIHQraNS$2=ayykjl3=rV{md63R@Z6%PQxS6h;V>t2EJT|_B(WXQIG{CAkiLY=`Wwk0|S_Wdxh1m(r-=DpjhkNE0q{|1-T>+WmFo5bE4&i=pgM2_(z@Y_z7GrExM zb0*=8kkV}Z>$w)jfry7Uhk(XB={eW&6i^Q$RYIb%8q6x1$xEp9l2rp86jte;Ux~E$ zU`leG%(2bAJVVt_ius4*Pm}4u_$62L>4k5_H9kMO`X{JUWXGAaUKd0SfwwNOcDz8a zplhzz&*eH@{2*o+UWcztEA0d%gSE$ehR5F&&{mpNtS@i|Ev+q#q+{B?nqEzTbG#re zwtl0D7hLtmA?n$Kf^+k+-kUA`6V4;~fxPV__Dnh8r}-Z@vDnM|!>(cp+Rt87wC-ZN`{BsHY3(Y02y#>x{s#qe6O$qfW-ZH~ z(M}lD^`d$$>gp1G+6tE)UcYR}+_4RA0b$j!S)gGzm-fD-3|T~vGF{R1K}6H0TH{TQ zIiJk@6~a-DmHG!d=5{X|!1cbt*|XS08f-7Mlrj}dB6V%9m)leZx@exsGL<6CU>xGR zgRC4S@|sob;jf)%8&e*e8FjiRbypF#7|MSiH+sonlw5u|5DN;oDw+#n&v4uJ0b zHE*K%`}#68!p=NFHj9Wl5RGSgtL-<5$RGvr;Vtl+Q}?#Mxf{ZSgO3RJ7)^L*^!D(Y zy}-xk!>6yf+E?_9#>aZ9HJ|~q0Z{fbqbsfWjw1nm(NteokLG4ZI` zG8y;%h=W%k*5$vT9niZ`6N}|#hQpK+{lk!r35{(wV6JWl>?5+ogeVl{kX7*Mm8SSBNenVtPvkTL}SQja7)7;0h4ck>Dc#IW?hh|kBJtQUtFkUNmuW%5P%@|A7yhXV$P*kR;m=eKsAPYDFNH?VRB&tuXnfpwnc zi)KagTYS3wFzxq~?yxW2l9??V#Gp-l++BfX1vH8KJ5%K2m(+ITMHitaErg}x(kt;r z!)?ut?B`MEK+^~`8m(XTc)YFE`Tg8dRo@I1Re}ZUA~0v0Bc61%USYNXJ(EF%4J>`h zIe-6Gn``T1G_UXjLLpFcv+Gh6xX}?w!w5xcsN1XLeiVHbtwJIYEo&AZyRjD|-`1h|~e z?}o~AUh{eQo3J<)WAdHI-Jiu`xqKU8DjOmY5TX`&VRYo{(?nupIUBkTL%27(W^bXM zX!Qxxvx-wwS2qMUKQEDDjxV_b%tsc%f6szIkk`DPHnRZp21h8o9L-4;^b?lF452$)F3SK_R_K zp&hORL(!k@x^FVd#>6oV`=qmLT{P#%>_*#XU3gug^?iApXarYTS6-HLz+q0BzZJ8{7yB)aBAiw4&mO@svGnYPm z-2I#?2m( z9m#@G`gCSNJ}*%hq+lkvW0&f=h%WMe09|$b`x_ZxcT{-apX&axAh)TNwUxUAXL1z0 z>t2HsKDkCwL-lTn*MVn6%^cY- z%R?SeGZGnT)fUg+vLnLt z5&S;C_dwf()=!OXc@l+*gUpE;i3FFbv?xGK+hNSOV?Ia5wrDr+t<9GJC;UONRf-?> zOpw4fR0>5i73g9pRhcW3iNfK#;yGwhsw0!@LEAfJ&ry5l3Z>DX(v6|m`X(-3dCJnM z-6?p7MFKt@{YDZ0OE@oroW4|RP_-*$kq9#B3UI4-*asb2%O1+>77wd`P$4S*)02)M zQ_V!bZDYc-=`JRO%Eb(EW-kiHq0Nxe5BRPm+?`*UEv;xpjB!(os-qv&)y0V8*;xWxsRXb?EmF6{*Yg@V4gZ}NF(IRIrr zbOB*+w_Gc8;bzJpEVpVF_vpY*28-X$H|+L$9T4%37a zyWJGq$@Uul>euC?#xUCX^E;u+iBN=Z0SKf4|I7jylc!m@1MevZc%8-bh)YY^XI)Z4 zLHDPmg(h!q#XbxX`qg0Kq*C2++%f|oOY@k%?vgY1pZ;mgl-jWczLiu8z^k|(`uEtm zaD8(h-=da4<$ENZ6ej%JTZZpioG^@+Sy^93^W!*VM&rl|-aVp5@j7z=YT zQOwb%*wTc^@ztp;;e@iXGR8j6g9Uia+Wgs{E5ox|*$qBdD_zB9>BRe})Y!8~xWc6| zsvAhPyf~Mzf~WnRP;N(DGkrrx`Vu2XW#K3WV&wKou~!N81o6E15cLmaOE`Y)3vDo9 z5+i&|OdkxPTze-FxuuWy8!YX?%U_2s6lmi5#EH?4ODunom(|MS1Ta9TrmLw< zV@(==7UQWphC)&f1fMs{T3lc&7c-S{>CP>(43{anQzke8bW&F*G?p!n3}cW|V` zWTP~4_9jOJtH_ft7ed9Z*k%J0q6DF<-_peJaL0?uv}ZXzpPJ&%tgkIGpLg@G#g^1J z&A(j>nHAh8@eq4Qt`5DJDUiOLDc-%g%F*?!tD>8{y$p1o0wQ3q4|ZSEvX3xHB!&{s zV6&YnGC&vi)t!^RAo$%9RB$e1SAV9sxXcks+&sNe*5LtW1CFH4r@|B~Wv|VIC7naX z5f&H-r)T+(q{|%_SUbguhl%aAe`OP?Ihgsf4*iK;xpwg^T@&B`S8}S!h$YOo!k*9l zWTEd6`@Wf?>bN;x016`b?ZfSE645=2j3x)5SIICSFQWhXm`|X9k+5{ss5`vsE|b>K zNOGbVd9MBCxdoRk)Bbwn-qZ_4cB+q%KEQ<>Q6Vu}*L=Kb$ZS9^SahKgnZ@%56??mOmN)+c(iws4yF)TH0uDD$5GPq)DRs;bCx9MlLNF|`0m zZa+>y2-kQ@fXLhCG4Qu4IagimXHy~vpz?}Lb1lnz(#uO<>L7Ek<2xw@p85k4*C zb6NtdRGnB5ilxIb`AKd2x6s+e%g<)UAk~j#Tu|^=8BlNiZSYXYLE0#%?RX04qjlOOJ>EkW)z^uIs~|YE)=o691_B|^}sDh3ZL7gm)Mm@{+W&Z#E6ZmYOV)7c{#YBtSIvD5Bc-+ z)Fj2mwkpBmkJ()Xhd42SF%oKI;C465nWK1>L=Eh1(9oK;(Rj`7WH<6C!%G?GP4f?L zfbTwKn;ldKE>Iy*QB#)Z*%_PkaZ*TdB>@6!ao4=-}?&O4B+z@AhsxG z(7H|^ThGXA&4oQnO^|5J02!Z(aB=9^;hw0Z_QP7^tIJw6gOkP7zketmAu8neqBAlC z5n@kr`bo!`ZTdki#TTYff;pvFz~@&SFC)0zRb;ou?zKFwS&jFjZwzX2M`&t#y7VaP zPTb@FIYqHKB13JB`KBMe2&Mr5$sD^RAUS{T4lpaQc!pZ||N9+iwF#d=-49-S?~7H! z;Z;zMG}dn5 zw8qA6AY+e9c$lMI;n1)qI*nHW>^ zXF7VsofhGLcw&3m4=-L&> zcUAu!_bUu!aQzVFbt^>ER#|v69O-Xi1Cjf-1ErT8GSFJ|=V`6FtrfF&VE3O%eG`}qQw_SQP3eo4o=8>b6CDU-XA1m*>%CD38A37XD+tz$ z+}vBK=}K|zK8inyJ}+Pvhb&BQftAk9j$1J6KxCreBkBW7S$SyUx1c}lAM0XSg51E_ z8`o^Z*nq`HjDNw3qZtu@Mj*`xN5J;Vi`wqnBRlx)4`6QX?BP)~ED)}D#|H(T-%APN zl{<6nUDML^7jdkj;P5mo-}ZJjs^Stzj4aNEf;x6RR15Q$P1(?mZvv~oym$a>+8I!= zrKRHQzrEp(fJTVvDblUN65=;d+kQ30_s)^@Cl{V*J(me@|FztFsic?81L1w_LK!8j zGB$%?E*B*Rj^;PJj=RD{Ye;_m^uEITmL0@L7yQj{>~2>cnnHrMef$iUBDzv_bPh)Uo(n%YH~LA@VqhxgUGpQM z=kywyXqn#qZ_91R#5tkMLATR0I}ys>M(R)5C~bD0|d8lfSX zj)YynY%mj>S>N;IbCkLl#Zb_ zvcF~Pk$uNxb;V7=iQrocfal}`EQZUPLI}GREM@8?K7*TONw=ncKr@3tJ=hq@m{Ux& z?$ZoGLXW}xE1SHs0cvMM1A~Woq1RkA-ZWOZqu`tE`RIcwB33C3iY1f1m}KelOW6-II;o_OsY!^g)l5vF)$I(LS|nzYK@;pMNx-gi9!gScKuLA5-6)#7TZMIxa?ahu7a z6mh+h;4EXCDbmD0*j;@LBPtbo#S-%NiXPApn)v`Un_(yR(z*8qv49TUly>;>&Li7# zs{#NQG-YM;VxEbDzN1NWjh-Wkf!%JXt?1USwR@3pUj3t?%rH`E8oY^~H?Yj8wD9e{ z@}=!UNgmiPjwIhQ4q1mtvT2jcwIpYOhuB`NI>HWN>FS3Sxq+XZr+HN^OGQWo`*)Cq zYhrLTw=(%~wIN5MVy9gp*G;S%bpSw9$!dn;2n67MP>h^jlLTU$CbtZ?JIKFOo9@Zi zx&Sit4H&gcp4DrtE5O|BXU{GhGfp%_tyxU>Ad)wTiObNl8G*`Qip7yey0TOi=TX%} zpi@*gtUTGD45f=5EUY|$t&8Eu-(k-GxNykIZ(R-sbmqI@ym_`zU{0o%tdNJ;LqUw@ zYr&5+1ErSi?4q#~EWJIAF4PZ8zof&2lLq5{iUn`6Z zuqHqq)#&lWsB1gE?9=?m8xirSji>3i91u~3_395f!j@x_wTt~XF5>si=>_QY8sZC_ zd6xaLcZSiXFE3i?qcl%T+h*B$vlx3rPL+P{E)k#VADG=Ewl_-;)5LVn9}uk;Xrv!y@iqyRh~x^|hdW z%*!I}@d}8!oX=JvnwbIws3XW9FDPEcgE!oD_KWtT+N{zgK?K-+AQMSvw(TF{`ASTT zYUkFAQT;@TWb>5k(MCzB!u;*8aqI3 zZ@M=_cdsHeUk$jxAMC5qI$wORs*DJ!h18sJ z=IoDXw!GL~?3^1N=6aQ=A^OFZ&SrFPjQ&qNcIN|_SN|Z^Ly~v`xEDX<57#tc#Jdrq z0V9eBZQUhLidqtc2LnZR4Bs=f@9ZJ4rSip!y*2sWo@|#%&rsj|8aff>Z!%}Z@CUjC z;TVTUdclNhIO%TfBHlv7sjS?sY@oT)uV5acoH>u`3~{UO zlkIi^|Dck&#-rxRV|K!ZFZcuVXIMWo9(SiDZ!g#Kn_WB3pseqxjv1nvplL}cX>w{} ziqsktqC|?ORwtvP*@SGTN(Fq~Z0zHF9H<9gDFri4B(pcuq~>=E;3r+P0R@!eVj0Gp zfS1Qp*jG+<0dsp^gj?IvOX1O4_%XYN7iAc)e10P|MrWqXX>GL~B*y&( z%9Ddl2kou{8~Yw)*+F+dX-NFfj1OBZ8|(D5YX7xtrVpI z*wRPQIiiZjn7YkeJ#8U5*7P9A?G?dQ4 zkV6mHOpU36I0;&P)P@_Is&xpc5XaC6+B zN9Yyhnuv9uwtcZ7-+9y+9XRL?gf?(a`lyBLur^0ZEXYMAq{2fAr|r9c&K(qlN?0$T zz4w7~_6d3==?pnmN@*d9&Gsi9tM!-6p(v2n=ew3=#YYilA7{~}1;wSA*n`edl`EgK+=VCQ3!-ps0y_U__fL`KKJU)+FipA?R})IzyTQF>MC-2#T&asnNlh zE>G;h#P*o;9r_)pJfb`sCR6&JiH+o#7yUTS^78X@3^H_UWpJ8}{GwlE$f%Y+(Rfew z_y$i*<6!1gIHf(*k?c6!1rL{Y1t>tqhDJydCPK?Z@EVm~3=fXPq0fSVJ4^gPK^7dhG{fr0HPUku0)8gU8ASQn83#x8xF3_x!^3 zhKmQi56o@7xf!ioq4V5E7kX=EP7@1vu_asLI$EO!4ZfUDI(tZ0b@4?AsUCh~$)(-> zV(1DdRPPbl_9Y*}K;tRUPwnc?-v0)BLs~=yi86$>%2gzmrJl@d$&6iT#_>`;;v`<* zyS}^<(z#^Yt%@ws-}rp>xO*aCpfve3O(Q#Ol4;c!W=CAW((cvCF#vQe6R=7mzx2A^ z1yg{>U*w=6@)nuGY6dgcD!R4d45vEwRV#3kUyh8GPbkMUGn1mD(_gJ+Fy$yPBHqPv z#9D@&sykv>3?ZFaHX&b@ECD`=(25( zi6Za6I1S#cs=aexFEY@pu}#v11m6u{PlQU!tw~S6k?}?wAe^=K`zx4)(s3=VPKXb5 z18Vgk;oB{GyB5*S!mWG2qr1S`MyJZElezecg&ZlzGm4Qhtlos$ zp=2SqNozyy6uvm!3dqSsO5VE5TfPQ#xI$?qiKVi2C2;;I)wXWoLu@Kylb0IkbRf`V zLa)Uc`kMCy4A^AEti>^W?Rj-jPLF-b?G+@0v4cQfdaGu3@A^tkJx zDDPwzB#GHJ&#Y-`ax&62d#$a@+V!C6B6FA1^}NBzjNP2k*C%TiqlJl`&4&RLn^V$g z$}5#ThQ>W2CB(-QtzAr^&<%8Cy;#Rtro#R-#kMttlanWgv!>f+5?UCv-+L&ov63&k zWF1Xgn-j5`X!u%7n)4J_8`7Xn_YfHJlwI-$1AJ~LnBv_ojeUQ6KNO!~E&%1sx8%i}W=4y?9a7{iBE(DthY8)d7Yb7>O|B>A z&bP+z6Yyr0%(2-YS%%9IblHrAtShEs>+WP3W_}gA3;QejkDH*oc%1!2IriV~!s&}% zHAg(3Nkrq(IiToi&-?^QE0#Ex3u3f)QG29?LBM_paE_LEAZViSk}hqvr8v647=`l2j;huEoKAZ2a(ihCUSv-=%ej3Q&b*eFA+s`0|WqBKe&!to3Q$9Si>@5G}FlPIv+4S zW)zvFlf=)WA~caFF&)AxSh6t0ofEvCybaaYqZ8(oP5IwMz}7xeAwmDlCekaJb=?g) z3!?p;)231<=LGfWmmk7gAPJGmB6vVvo5#=X(s(3aOfx0<><}gHet6_IOuu%qil%F@ zCdOb~p_$&Xo`E_RQ)t-A3*-M}shtrjCj(Y@#~E;N;_Q0#6Ja%S+#S0^ZMD_KD+RWD z0$4=f*Bs6}I zX8#08)q8kHkB9ThZQBP-lPg`P%W^8?E&@@JMHqzJ;*2OAGuvl>KGBV zPp2om7Iqw0T|jcK)g<}cIarhXn!g0xSplDJy%Y7_kXm@@#Q11QV_|gn&0i*j29;mM z5oCD6l_lpfjyWW!_6w9WdH1n6rYDoHrYphzI8q7U5%=}904}i@>9Hy&ou#mbSE0%` z^uS^h3sg8h<8be4E>P;`R_-sF+cnU6GydNdKs*}}bI?I}HH=9_em*SbQ$0gW^h5uI zyf!$8M-@ao)F#M-TyE<7lgteEvMgx^neKJD_dwaf`y_$U4LB+*w=TvhEhcgHW2%CX z{B9QzZDW{Oog-gX1}uVd?2ao&k(dXpkw`bKZgl;GUceAd8V5Ri%;rJ4u;r_1W@d)* zBObA>)?(u8!9w4ksh*Rp@CeCQ|s!KuxqhrGVF7Ip>VaOWzy)rH)`VL zcPLx^(>0nG$Ez`8Ze)ZMh4brNpI7uFwa;0aazAW&Q*uFpR%LUH0(sdSe{+0-vo6olIb?BK*z;>m z{5g$-Y1ac5-E()xUwl61&h*{8Xjp!n$v=Git~1t#R`NA9l8j*7%_@u$4x20^Xdg$YZS;TAZ5LnvqU?qBe)lsH4>vc4}9@p?z`}N)=vj7ZkFktE}?YTn3WuC&{356ez`eEmf1w`Zk zUarf#D>WpF+eC}?Ut?*GBO3)C@>Uac(^Tkrxwj*!stiuhErBtDUB%sfAc1k+xR_Go z3N#ltb6gl1Dire_*h#kQzhnaWU>NTw_-hA4o3NU0@DV0ArL5m}gol!accngXSvyra zhCJ(ZKVltaGjnWCMHMN)>erzF!*-0w*UZ~!7AH$+;+_>lSKO382T9x7k400x1AhlJ zR~{4+`iRqNphB+&-tD{NGkCWb%;G16?F#jvTr(t{#`0QIH&7# zVur9}FDWnLuZ5~pYFnvK5O@N(=|`e%UtCfp_>c+JV|!r#lm#Yw6uIsjAk8Wdf@4M znMjm6P4I+b=2bg1xneYTT_L3_oEm~Hm+p-`TUVUMJL>_9Yj5Q)UOYq7&7+P|y8$R4 zQSY~g@PV(hUS(zT1~c~i)Mk!fUj1Yr$`^rZr!OkGZ>In8#!N?Rw3HEOIO*KcLdVDs zCA`Ft*9ri`nuzO7KLD@86%s~aiKU=jsG1#CWeug#l4f~#MEmlO!!D=QsM^Jxsb_3X zt#LQ>b6-U|;|7DCIQHJwOYD4iG~6+5G3j+Qt6mU)AYh3`2=I3Ll88{kk}o@l^=^?x z$n_Q?&xBXDZ9tO>%4JuRj@drlql&dyv^C z!Q17GZL5wsyjr-O&eF(2O?cH?)*G8he3mIVW7kp$smjhSmh+Y^K~?r)#UoBAc*LrS z!>K@S49|x!|7GSjBQY=np5nU%jjK4{zHAmLCMDqDHR3c8A{`pwzn2$Y1z?{U;AXa7 znum~oUX|k5+H`UecOqg~qdGC!h5^C>ZLgFSuCJ+d0JhHNh4N>3r~fuo#dYx()kI3D zw6>wX(lZq^KHKk_>&DKmGM-D3vtl14gK{HvT>2%} zX)D)QE)g<@iLupvZhT6BGhlJQ69@=juC;%PNqT{*j^pLic8q2OE{c^ix@BTho608T*rKeFOpF1gNFd+xGQ8DlCM`oEX%3A-btsp; zRq2yA2tt15BnL{UX_@+ZxG~VO92ZQaGr(zXH#aq{2l!XiOp>X${**9Duh3VLB3%J$ zn%-QZ_ttx8M(nz z&2L@n2%$ZKimE{+hNV81#BbCxS>1sE()!(BhL(}0eQXDYLgoNQyf}lxSEPM4wgqmo z>NC9QLY?5Rb^=eRkRauK>ics?VINDjkZ%7gd$uGhxekrX?Ru9_JnMz3cWK{6vf<&+ zdeOM5?*JHV0iCUZ6n|}nC0p`DdDh2y?~7J4wGm#Z^0m&?qtZT%@IFzc9S)Cu}-45Y8T@+zNm=x zlF3XW8Djp${Y0va7FUdNPnnE&>Djw?+s^N}8i9u9pVfv3llxlpVU66vLGr9LE%ZKv zP^oAQCP#aoLYA}TdL|p*1HVUgJtFE>to@H(aFaj?%xZJ5WTT}h>jj%*o?obS^h6%^&Gfs#G>GntCmJ#wKA~hdp zAA-R1uoFi0y;sGSaL*emv@OJGfgf=0!Ws1hLv6oMguEH+(8TlkfH|kf9P!5!RJnPt>M-HzjtsH!V6`IYEc@V-EQ(nnL$=l26tz0BL&( zF{iFihTm2Q38vRD#G=`E-0tVXkRy~{yM!!w#<LlgZ(#yql*2|{dBNZau=sCT;DZ~9c8RlSR?E@nSK~$eQ@kkEGIcWB}6WGd)qjrSZ;VB?kd5?tw{ESma*2@_rzOMP=l=lIMfq zsV$%UFq1qFx2+)Xxu2liEgju&#mv3b)3iS&e5nbqA2#PAsND?pHOW;N%VF}-*<%T8 zB}A0=yH=xwAXbTIJEwD;aobPxqqVL-V}*`YF?MIAX)$xHb>F;+g z(IeTsd^5t!DV5!MMPl6-JTX|B@hzRI2^$m9L|TrsDNAA@WkD~dI#SZfec71tcA$k< z&+RAA{JP_Eo?GwbO$$dDWtRpdSs+9bYNv%9r7P!VOBv6~$oaKy_|xIVVjUx@Xi1@I z8~d)V4;n6^|J3cdj^5AM{oIm08gFJ#2{|q)ba!n+%0Of^&Ej>kK}kGfZ%LX8mVswI zM>`bSCLBe$OtFA9GAw`t)_&>~c5EY9rW`0KLp2K(XJYE2VFK*M&1$`SWyvmvh6PX9 z+nDQK2rU*AzwAdz3g@#*Te0A_VV@lX7Q>gc*w^xG{>#pI(=_^^1&# zvCpxXAR`!4$p$ag!AgOd=6fR$ULAD38y?fijQ8=PZ!ZKPv|loRY0m zo4y#@XcG<>SBMn#b1he#4ncX+`jIly8%>uBM>N)4grb#!*4_7)Q9P4=@hmSX}3A!FULrOozgp+y{S{Clw z;9NfY;>C{GLoUS7-RfirUDvJTFZl~F8nqbv5o~nys(=8+b5a>9e54vg^nJ5LDtCIa z7m!Ijbj>&0Y!J71axvqfgL$1pZd^FKspiAi*K}Vz;0-U_3YJCPu$qu5{F!C4Nli=g z8AicoJa?&-5Im1uo-H?^ti8cW=(u|)%7zOu-;O_j>v=fLmOr;}*i_z~;q+>G)n2RI zb_g$shd48BkWES7Tpka|^$OhYqf_(Au~DA@&ORT`ty@@Ud#97R?H!`Wyc@aHnDQpj zOESn&`L(Q9Z3M*~j!^bw@3JcS>nX)$LN0f|B;9cyo%w}W0L(uDn#c*OLN)u>M21T_ zFgz`{a)v$IVLTDj18@2^Pqg7kD;?46o9+v23Q)p9f9aKD{iuqtAw8t`A@5W{!ui=m z+gWC&5~wFekUX~ zZ$rLq6l&H{$a-A!NuxNd@*)9Uhh;{AOp9r^xn@0=sd&`j`w0G&W6^HCR|;GiyYjNP zl58HzD53M)-WGffrd2nI!fqLRG<%c~__=-2H5As?e2%Et`F!Jh9R((_lLizJH zD^OuSn7JwtlI0B9t#vvt@qj5NrPl;rwPE(!r|?4v8@hstwONO37`xu3d@*AkGE6>0 z_M1S>9_w~a&}DaURM6dt5ph4!mh`ls5_Ngj_)L3j1k`0Yi||i9hV|t8!4Jdo=0)Ji(Rp_V9pQW*W+|oA1|c0-tF|xWO~}S{X98Oibwm+ zK0xdY^u|+xg*N6FpiNz-o4ZfrF4?P@yx8_ZNEDd|U8rF~P0VgU#~kEGIJSkfNElS; zWwZO_fQ?U`8(=zdPo0rt%CI^kfC=~FzPbni3A6wt5SB|)>yiZI=bLzT0R!GD|6u|_;jmJPUDc}~wKx$wRkCj9Wh2>%Gpa=^K(EvjXuwWu8 z5`(1V@LX`Dl(u*nGq8ZA@~Rvr)B2se3&Y*g_OG2gd(S!F_nkfWp7Z^Fzwe4DTQJC# zceUV%sv~(`*0t7X8PQ44Y<0^tv*)BZ9RHOoAGC_at7&|m&lbZ1yWG!QEoI!A7)p9( zL_}Gtq8wV1>_?oa6VD1ny4}uk1CYq&Z_zl;vu_$>x(E{7%>TxabS#?tC#p zlvY${@sHfthC>6Fy7wHY;)?y@B(*N)Jcd}?5b&1w22XdM=Z8h-h*8z!;dlxin2HmE zaYbL2%8ln6lzuGvVGu{9DJ~hf|D*=A*2|m6Pa4kS(Q&5URk z0PtEy_9|CVNw531YKGYQFbXQM0WGgPp z=mB4X(?PtX0V1BjywhLLd_A}e)Ul;%0ZAXc(wF9HiV^OBc| zjt|%-`tnJIMuM@Q9R6)?u4G5j({|hli$+v(b z#emiKHK`niniZ3FK%?K44)cVKfG(HSTW?@m4qORNhPJ~Qz%tdgOAFuDnJdNs$jF2AYtoBpv z7A2JkP}#Pthcqf+OGBq)6_-na9g)aSx=u2l%_?len;`fhNbFN8X9;hNu_qb!2+ld~ z)R_i8Zt$nCx4-@iI?$M|zk!~9MCc#p&2a#09<4)iF@|hfOUg2tn{#)8xRT#hSfUde zn^L@YS6Wx=8QS=V1M(LPt;St9Z2V=Wy0Kxo@MngkM2<57v1tTq%KQ2yjnY}bba6g- zv~YurkbCZYCtFnE(pVu;6YO+KX8{D*jc$?rW;}F7CE%^JgDP1RRT!#O<(OS3})94V^~!n&L*nCeEX5CgE>&4f|;LtV%nq+yj|Pa2J*~;%P>tdHA7MPN%Kn zkg8)SH}%u23OvO{poJc}yj}~#X8)}go1j1Dp!Qoh(OJPEjC{=?iaS6O;8ee#58awD z_U2^wat%0K4I)xm=neHs_98^rk|^_>ioNIv3RLB*mZi0xhiygEI8eW3-2LE5g)sX9;Ik;B?G@c$lQ*tbw|@f^E-{$vfq66QJZ7x32p;i5 zL4Cq1>*RP zNINVqe;l})jPep8s0F9K9ir3kCuBKGBWPt2aLT0elfQw9iAfz+wO>LKKKvisjU>=g z83Js(hpU8e2h?S}jG4fuAk6n7%MUH6j%n8uT2596+4jSG=-m`B_byp3E0BS?Mu=LY zy=VFt1In7w3s(b;B?AqSq&Qelfn!7qXNoA#U|>2H(juwxJ- z^<`M8lt*{lXffZKx96zK~46|meiUlh!`w+^xrR?~us_GIKtAXHu5ce=GRAn8K)-e@MP_qeOPZSA#}5 z?6_aib@uAGaiL+yUd8YP|A_e1@sC*}k9j*XG|DygJK8C3?mcgZ-(t6Q=d)JKdL+B| zyW^)(3?;Y{18MVtn)o*}k%N)7u3Pk<;Rok6loS;e?_IdPWh;t|f|?oq-yiCmn&><| zJ%f(7cXYgtkN2VeDNP`$Cb{(n7(O#XuLty^Ler%tg~=VWJ#5XL(gG&MC@ zGwEqqe}DD!SGVolIVZx!X^>T6Oz1Aw-kq{NRhEBh;5@QQ*5h`=4e_}*`!0A)y5s#~ z7Q_7O} z(>voaOJA|Qr9M>k9UY7@3m@5gV^)H^)x@`G$#42y4EetOOiTf*%k$-}t*r)v7n|DW zC%PD&oSdkH1hIeYP2&mdt$!>lc;9A;qXVfrDYIRiox6n_<#*+}b0`KHr6YDTt4SMtSw!4qP_7@7jUU9nwMOnBsl6+D~NXTOQDVK@ItO_r9da5GBNgf4nQ56S~ z1!uO9h+!-0JeQqq`f6j$n&ZkR+m#DEdf7bP>udAn<}%A|)&r=C^ZA$r;_+>08@ht3 zGxz4P-AvMw7Kb^%MwgBs{CzjKOI9c-a%uxIGfCAGvrO5^XuV!#E=>bso~lss5}?Xi z@7W>q&}gmSh~Ca+b@T7XmY@c2yo;A7M z5Y+qTc6!BsCA=ZX%N$$35qzGx7?POFo9mbze}OV2WHk^I7MOCqCq zjss0!I<>kFIPL=6X zv)SnW>uu!J)HZxul8)}&eE7FZ98sJ-hI)GLc$>U?9au*EI?0>iL0od^uu}Q<8&;cb z6)jFhkrOgAp-Z~4=W!r&IhzPMqG$TARcy$x7m^DpDvoCrxNDZFEk{FQ&#MP~l^+ja$1_cpJGjDj`{b{Tl%;qWF&syd_63a8~C zKY7xfl{zvqa_f7bEDO$xRArFIQypXOEaIQ|{kV>BfL--&UOf66*$KnK{p>2yk&br; z1_oNeEWasRo05tQ2>=!#Oe|{yhIExxX}9f`SKLl*KA~V%yPguv{zHc%-w$;axX7M8 zd-mFu%e=oIRP1LmaFf<&6(5j35=6P3M3iEfnZa7wq;6?RNsr~@N=i!g_4Su>gARs~ z{vF7PnH|n2GSu<6lbc~@?v(a!t~vLw4N>P^#3kO z49i|n=x6@?yGSKsr-07w%G#_Tm_-`IeA?UF7f-zu+`C!G#C1xl!e5k~{&xw;Pkj~9 zxwy|FA00Puc=J=?cPf>MW^1EKe=c?w4ne_tPYUT%Dv_sDiF~#HKc0eo_5UxPKO~F1 zund&SP}2Ph8>x_(X{c>nj&9P@-_}oD6q*%GM7uXtPmn|nXtO|lJZx&uoztiu+!^Kf z>%HjnRFPsgS+cF$>^qE2O^;hzS#h_2>?L(8$ZxO3fbAszrj`F?J5NP1J`_1Ir(90F zIAIWu6CyoNM8kXO;ixB8Po5(A>J1unin7yDf$i76RF9&-V89BWbR^>-0s8v&E3Nh1 z-Me>hg5F!N+`oVSa;BLQL^oN@V0JOOzq(3DB?j*jM`G&M+LxqX#8N|0_fZvQ+a#o5 z4!e=Bi9_S#IIH2TtgMV19og3{EtAgev-)>IKUaoG)BTcdKn02R{io;`>Gv}-`XTw! z!oq^VS!~kyGGW}0*1qLW74ijD$K?_}Sd)H*20NvopboXg&@RZQJ$m$L%&FK2FOCfl z55I109XV+s!Sr(%#urdsU0pW^s>0;T-@ku<&fR_a@u!AAt=HHK9Kv9Eo6c`9ssW*h zs}Em{?IpW#;ev^yqY${hgcPChJNhkYM&8EPr8EViZs@%;l^g5KbEy1a+nKxf!5*gQ zujU=uH!@7hd^rOSA39XE=B;Z^+3=6E#I#X3Iy-;*@#9C_S(owl{tLLa+YEF)} z{CnWtGq=ZRNzcic4Spgwvv@1FzZ2JuCn?vRXGSGwZXmPT)mw`X;D+W0I^dZwkMRHJ?jXI-ynIlXXaEc-N3 z#nE2m%8_Dw;Schpt}jIfc_j=M%+1Z6*Vb-{yAlx|{_6GXV|c9KkxhECu|jk-$Z&?t zVn2xvGe6}+VxHW=2PLIcaU(TeBk zZk1Qn?Zz77706G2X6;;yMe9%o#jCbyjMu$9dvj)>`arFermM=)`K6_$f^OSYLxG=q zgYlsYO|x6ZiGJzQb)sw*6&2;W1O&(7k8Qiq?d-C`yB>nt8M6dO)Unhit>D?(F92X zq~`UFjq21@`drZoNmGe#D>z>AB}PU@Y^1iixw-RMbdg>XWk*B9K1NZSs`*CRs;Q`%;;s=9>?|q(G z;&HD-B}#%0hrcsUmLkKGgKzW$HxPc5|o=J7=~&?Jo7o3$vd%@<~5OzCMG62 z3|{c)JR4V+5DB}!p|d4p7pT?5hN7Q!d6iOZ-8X{cUETak z$=LW(%9=)~{^P}fZDr0%dgHR@S^ z|NXa^T@TuDP}|6e$&a4bcQ%^qVTi*;sWiL!znslmr8JwEjvT2;8pSWo-9`OyCyZ6B zU@fDfqS|h`WG5sf3=Iv165L!@=UR?wg0?v-y0w_G@bBHLDJYIMLRKsLSD>XB@|%*pQ3UT$+3Au@5>YTLNIdMVKAH85PRwaUW0pYZ7G6iP&e?id ztU)6cUm^dEm{X_XDo1ikM_r1rMk)+R(e;lUqt(D{SDfosYkn+e-{?q?JkdoqHT{K8 zWhB$GDXF#4b>?}wVUdUU6DAqy#M-DU^NxadM@!0xRa`KS>SsH5BO@b6Cnu%e>VCE? z`EDAk->U@*+8~hi$?^Mnzg!9N1Lh&5A_u5H7nihUn)d-{5VXA;=k5Z_LP7sKf%Dmz@TeTU1kLX`btsZp7TXDq z?aK|>6s#(W^PUHs$XiNh1%)rqv979gwFCmeB0y>DTUr~V!dp`YrwQO)&+t~~Qt|MM ziR~YD0>3*JOpr0)RtPx}WpBnw8cXwlAWGt9WOiE7ftCwYpaz6M^bu`h^+Pc5Gx;n$GI@}_l2?GV_@RH)o zd~o|8>+0$pyUb_T8`V)-DY~qoqQ``zkoUx1Ca2tMqayQQ9&tl#nHnjc;D#>g>FK>a zv;lc-xT~MWV;2C4r@|dlQ~H&7Rz;wbAPT(0wlpPcAJf#U%^L5_69msEaBbdUu;x6a z7--=&PjwE%W2zJw+H?gKhKr}?^(J$oh4?#WvY-gn)9bL_<8lb30aknvbLL)0K|w(u zz-d9vtq{P##h%Y}ra7u=fuh-aNz=kFn-t0j&4kbzxpUXAq;=!NG&gf+w2{hdx*T*; zP4t~H&bsKNOclkrg%4F7_jfUxfJzF=)a@l3kTW(mW~M5@yTz|Z%RwHc_x5sz3EP9A z4XnjiEtdKlp{Ay0xqE+}RZHqcmC^ctRfyK-_NiiD6Gla%bbO8AFc;=O|3!M3rEr+s z)*ra-@;Elprg&)uR(O=uzO{*(E3CXv^k;W}#^lHqW2A!1o z*m;d_t6F;bjuvCB8CTnfaVyhb0?*9k=mJs;DO9`qu7u!5Vqr3%&W!&?=qnE>hZxGv zdj+7-4Ez4dMg4GxKP-~s`)PEp)Sid;e=8stX{l{$u?ZQza>naxt0x5n1d=)9f4EU* zV4vE$sk}7s2e2eA-92e2`p!fm${lekUzAp#91<5utcB#rWOZq-U-8-vM1@sNP>Z{B zR1_6WRmevsCW<^AE*lsajCB==CM6}wE0#MV2W7lQ#>P@w`)F~-nT;r6qWk{fcW8h#rYXI^~KW(;GOy%2cQh#`Rv7A6}qC zQ?3ixk^7Gx=*CdFFg2|(x73h=>aTR|-YT<~Z5ChfqyUJAcoAGx-ymUGF z{0^G(J-nFJ-T%px3szQE@3XR$#OJ1_rfv<#hfItFof-QQ!dH7HtI?-V;qS6TJ9(a? zliIz&@Gcrf3|sMLfx{?IP>M*1Y-nx0TnI{~6GLmQV&n(ztgR*ff42%k5nOAL-bMP~ z<3diG-yiW)ajoRL4~bDjjq0K#*g{!f{^YP9)NDNH2t#m0Wkvck$5ic6oZq7j^CZc? zL7ErHHPqb!Rd*&kXIyLnJLmIGR^w9SdA~UnmOMyCXy~5SPX5zkiOKNzu*X60z-;w4JeIfsCDvUqpl+2@V7yAN`JJtO_ii zDcE#(0IpLX4F8Mplfo(#)SuxRhrx00#=t*fUMsia=EJh#7`M*TI;vn?{`VfA?twjea2&i#B1($y zmtZ9Uq4&eJn90AoySw*6y>L=OB3#qN3oyWhl+PYeUJp%7JOTU(9QAp6`x};)zF^N5 zwTasRx?x39h>#NozMy+5`4+4pVIo38rbp*rym;{@F|neb+LO4)lDFgygLSic!d*|p zytZ5XdEWg<-C($EAx!d>>UJnHuBAU>O}|HLqJ$wJ=~3nlTie<*N$OcIU%tGUcJ0fH z;1Wxvz%3Yk@>HYZX!5ScphKTNeX^Gtb1v3v>V&09^j$r?anuPk7iA)#7+~t_>(gnO zoniCo4B<19?s~Z)8c}K>)vHuA4Qd^MML|laEK?W~{Toh3_}4g{U0+KsjDlzkL%Q=lxn6 zo%$-f)8yauN8=e(FRbH)&K5V&4W8DZZu5p0yn6J>+G$VdxV5Uj^LxTC|3G8FFdCHv z^EB!_`-8O+;EORWF_DuhZ#nuq3V|*#VH9zITjag|GmUr->8bnTSbQ*v$3}-C)>3hy z=7YfQBa-{KZQCXulL(Dqs`tqa(Sl*1nzR>tz(3#Y{rE`kHFok+gvbr9I-OmcI&7qV ziM9Ypkz@tXg@dBE^F^)O-?9Nm{9#|p?jBdKUe($wuBn!qG|lne;%`TY8$Bo} zQXWDPEH^kjH1s(s_aAibPcy%Ul+go4dcq`M(PqHw_u484DvdAAjZU>&rAgUoacjN( zd}jR4tMl166VApmBl+<`(X`q5`SQSHvTU4jj5nRf+cl{V--W8}V@g`wKU{!6OpAEl z@khas4lbL%Aklo)(_nRU@7r82k9_;^pzo7EV~%W6YU&fsWUXs2k-|+f@^5PRi_d8# z)e)k7V{MrT=2x)Y#@03feC|qg)lcw)RGi3Rq2)k$Azz)tcu2OYaR*VFvFWc?hd`VC z82CQHOR;4`qoaP1?(lr>Zf_4K@36A8OpsFE0T#mZ9*SKwq+F)>NhsP)kYq=hle|y8 ze;zUn+59lspWqj1a6{Hpi6Fj(ghoq}uVViKYx-hLW1e@9)>6iM%|jn*c*cK{SqoW( zt@EI~iXAG*+i72y3=Lh6i(Lj~!bWuis?s;ol&rH~TIwas2KLUOf|+d-^E{y}Y6pne zi$RtY(snuWZeuW%0>9tVte-X3XGukN@>41?(w?WjdW}BcwQE;~`}~A!C`KL0NEXP| znh0kf?Cuh-r?odKaK1tB@fCSuY$2KQ24r?gQ8=N6HP)VG6>auS2=t9Z8MA>YmAns9I64nb^SpwB-_zyyx=3Cddy72(XA#L3T2!2q zlfy9ivHI~JI%teQ?hb51zkTr;0pGl&6fE9rL``>(j3fTapHcJzq*0u_W%}T=o@!$v zL~YGPw{!uk0DIF`(_RICmWWGmNMU9*UIS_%N24O@nGhkffmRSr?5Aa6rooHz;c;04 zpn{j7=_P4g@L069VM7Zsz6{hhX`KqOSS-78jC7PHqag&6w+00wYG`$$Gc2agbspD^ zgbvT()8$v^{oXO&(|UUuLxgGN&mkcnICQVA!v8zFC`l01d|EnXo92#~n@OCNs~(xsV!-btTLXBn5~ z=ch(66eMN~>O))Ey8V6PMRO}%6*t_e~fH>nbkL7C51wOAT$MKrheYZ0PZ{0z_eP zqV6rc1K32`srnT*{09#n40q0kx?M+AKuYHd|ACdUs+h`jQPo6m4*)%XfGrBuFwr@{}QU*T&mF9VM^~U#}PQ;`rk17reF4)v9 z>C@flH<#4aX~04H&!!@wx}=oypZ1p=xDW0IbBjM~l2`$FKljy`lxHMMlShnULDcH{ zbq?id$pg^iYE;fHDv}nlZlwl~+DK?3q8`(HPm^+DWW1%-gy$bUnmyFE-XdbtxgXN0 zigh`E;?WB3`x(CE%HtT%o|2F-6M9ke(;IA(bv$%d4BMB@2_#>s-Ul(16(lB3+frUk zkT03veta^@DG5~w(f#_38~zaVdJUc4N>1c1i*J&O#9ETfvLko2f zp`i`Q)O_Y=9hkFbg`PNWQwQxg{3Jqwob|al?A0-Ru}p*clKzKv+v{RVjszNH|`v z^d0By3`L11S{4u;T0i?!uic%6t_}^Q;D$_~t=6Ao%nihp64bB8v*09H-a$r22IC9L ze}GXo%fL0WhqEI|L1F3F_rckyn8m!^{J6CA23@qCYR)-8-A zr+tDLAo3ER1;ogpnI#J=xT)B{LrkxXQNzpY6+!GswwF_z;WjtY3LWLYYb=amT^i3y zAOn9@T`QOO;l=bHn%V&vh-v_EAkREB7ptvBCAVCp& zQHBah>}Y6cGR$kE0n-QznUUBD8>!TR^L_8Vz9y%js3O;%V{0VN*VRtyQIQoSfLL7~ zky!Q?3=42u_*U-6Q3e94Sv`C%(PVPE|BJ&&GOAm#K*_?{>2jt8xf?t7*o$@kpJBC0zTua?APYz z8b^v%l7|z0S0&=bAB!}qkt``z5}X-TW`L+|_v5SOPs-}*RGsf2JwND5zb+~&;%65k zGJG{6OY$5BdjUJmX^Dzn$#9)9)9mD)kWWX>nN)~GWeQCJW3lc(M4C;LQ67hOgm-In zbTr_@vvHUZsDe9kY-`tdZUhKA_NO+lxq-~agvh?fbVr-F2i z8z9cFRnUTjrPfQJ+6NxB6CTq+BvG@jvkS8zYtwjK0#MB%$y@x}ckE!w9e^SRfHA<) zd~ar`{`YQ}`PISOg!vBtW}1{d;2!t)(6B3i1bl^USNG3D6HmNEJTwzBBx?cvjIzgZ zwnn2SIENq_KLw=y6(!Mff35kS4>pjK73?RKC^``Q5rf%TNMd?RFx#LP@GL4eBjaSY zP1iv{v$(2uZUhZFcEstG2QUT9N^2s0e5DAH^FW^~JD|f)Je18*Y{Ljcp&!^a_g^G6 zJH`e)o(ZYucQJ~*X*LuyI|e07>??9MHa0{J0=e?AMlx@jnwqYO>cC-Xz7Hw;v!)?# z3v&wKVuL-The%`tnim~SVrYb=uEB&0I=1MWZ87(UoQ4q z{p&(A;ymKnpGv18UEB<4FOO-0hja7ezxv0?{ohDcup6*mgsJw}w7p|}0bpb1-MNi! zI63Xb;Evj8DMm;()uXRfJY&_NLwGN!noo7Gh09`?SDmqc151cKR)xTjSg_Q)IpznZrzmSIBx>=>kX z3CsqQTelW4=8Bq+L5;71JZIGR1h}qv-3!aVjD#-m@al%t;A|nT zYUwceHzD19KxH7OKn`Gnkx=Mx)TWgy@rJMtitGrp9W>^Vqz6LqNAM)g$&d>ZCc3`- zSy$gKIllFqGsADD&LIGcs$diVV@2!>YUCXgT5$MK7bLG;Hf_lqM$D#U6(Y(EV3Ie# zmHO=12PSr2R(8i3Q1jVaN{T-MNrRN9U7S3f0`M@x;t9Xe zra!!~1c$vpySeuwiUwW{UH-$>Zir9>)Y_zDFX`k1z&LN-+btvB+;|z-m)qvO5SN;c z0}!(}ZO;~>a{dEBcTfYC`w(iSb52gehu}3lx#;{UHcuPqulC=mEhE)rqIBd{z{$=M zsvaW&_m{k4tH`-HJG~aC`*|WoPoA7AF)#q=1gV#y(g>R@>?a;AW|+J|=?X#}oy~NB z^b#?GG60ein9l8im(yNkmI|~$y6@7`(VjAvkp2R;m$#UJ?!LcyY=Nj5&k+4vh3BX6-J7<#v0se@c=ff30!@+#gx-t1TI$A!jTC%6^>8Az zqmpW&4@f(u9JW#RgnA>694Vl*=oV|Tp=)>D#wL1wr}!~A(g|u{{5(b=JhlSoaoVuA@r`gU;?6jL zFQu-)yNHmzf!&CT@tjX>cAs({y9@((AECu1@37ZQ={8ztXXoT2MGMSNa@UI{UEV)f z!RS~!Fdd&vVSx=x`bW>8v}V2EL8C!AoY*X#tnleHA_CRFQC?nJKL+$9Ff99!M%1<) zyA{JPffIlVH|?RBB^Ozx9<$WxZ%B^-nWzJ1h(X%y_YjzJ7_03TbcJy#S-1GBKyo_f zX@Dp8Q3$li(VSm$f}EBxs#hG+-B>+_v^~6JaKJHA>yEhML@ItOkdIEI_-~X|+6%Fr zrQ>H@eDahZZ{Q4OEIor$itlGxk!1QGuGWJTqvGzMFf-po?=mXDFwKorIODv)Kyp16 z?di2tCKC-{mSTAh_ib+0efZId_y!;j*zV}ECGS?}koM`eCGXSI)qRD-Ndce#nH0GR z1kCt%k~5@1_6KUd-xCnc`sPsO~5I{ZuXvwlytRkfCgGhml3n3 zzlvyeoc5AFlv>WGR*HaV&qEf2nocY&B!wvBfkS1O?`}RoB4X79R6n&10>88vc}q38 zTjnIC1P{N^q2F+Zx)?Z5F~=cQm@_hW(9f|kpr>dA^?1sM0a7f_TX)+T^V=Rf8L`jF z8fv?c(hDphbDq{vC2dyNp8IR`(siG`P}WvRk6O2;AEhd`ZGX?1Oo&b@nuH)&Fl9)J z2K53|#kVFUaF)aj-|%D9_T*sE?n%4dCuLf(-ui~n8u1xV=-&uNJ~W{~l=Wi614lDe z4h9&^HI=0_uYDtY3fuWS2yJdYIL>%|LLZWWf>#+C8Idn6dC3GYP`%v(YV$kx;P{cz zVW*|pVKH}twN~J2H+H`<_Yr9Gu={j14#qxU@)9GAwK*&!Wn7uyC1UCRj|HK9AUn}s zAU9qlm8u6S{)mnDT$8q~wso=g{L2SNe1Sy8z?6Sr!(|K5UZlGUz?(fjnAad*2qG1I zVre2A7^aPKc5d$4R=m5Ox_S_0Mdo=Y{dx+7t^b9uI1<;ObO_*}Dw~4}D%^FID$G)C zY^zaa(1m5`ip;dd7v1{6*iDTzIG_-m)=Q_`?8ajsLdx!U%R!Me+2K-;{rX`Xp+X;% zeWIA86|#0xZ1wCEU;|tZS5r17IIA*|y7?XDyFHeWWwq4~KqcWC9oD!P3CF_@5V63Yn5&YDXzE2p4MCS1h{WX(n-g-P!T64FEy!l1}_3v@X%jotE3dNd_z>h%B6J5894E*FvPi-RQMC&>`5GWjIk=66Vk7bQN!RYHkPVwsaTgqk7Jw)#cN7=>>>=FC2jh9G7Pa{^vJZ%;?)XeSE17&Cgu3?SuoO@$L zH?6Jbs9vAJq?@+n)JK~7*4A9=Mmy!r_Wm5{CCS;wRFEbD;*`%7a;3(VyuFKK^~DY2 znu&99tn5e~!&4_JATV8$hrMk8*la~g^}U_ckQ8WKSq#=TgpBx6fpRpLJoGvM*PfB# zG=F;wLu=+WkvGV)8YY3mqL)41gGOI$YHqZGr|B3=k+(GZUmYIiC>@>2pbDxDlwOYe zu?z|EJ8c)2`Em3LxNfY+J0)rJ$fUgDeqP&0h@hsjb8x%`^`}XFS|S1)93^oNXn+kW zIiVx^K4F6y!=;N1xFfVO2(=!uXOp-9#_A)=-{+yn#?Ry*Py9J|0gJfckAF6P? zJ|ZyQqHsfeK#v6lB&jFn(XMRKo`klA?)jn+DXCc1al~ahN=*X2Q>}lTY3&=6bKixR z>3-Io;I}X0`wZQN<6Dcpy$N}oKHcj3i>P@GtZdyHBi?CK78FnU+wy$0c)S^$#ymr~ zEs5g-Q2TCj6K}{cCc7cD=qD|NmyQFte1|*O?zAqFH&Q&0A|h-uUXm~vHC>YRlbomT zY?T9@hk+AMldicyes>VU8|Sj%oeRuHsNun{qD52w7d6|8m%Ap-uJk!(I!Wv0A2_CI z>y(yKx~S;4ngTY%}_Zd51*&W!`L1woS*vA&fEkD<=Su3#&97 zJsYg~z?lhd4J zO=TiLCt3)zfakNTEzFF4Niwn`Gvj)iip9owNkqF2gf0BN$BPab z6~8D&5$CRmJz5A>@!UwyW`nHjxMTTyb6wrjuBriZui=S|Fq+RHC0SN2uL=rILAnWr ztWJ|No@ts@Kf2GOj}iYc&1)`M=lm!P$+7bJ0a49Xa&4h+Dtf+kRD0WlO z8TUGDy9*Db6|cD=0Zzw+{~V?J&io^>PVrK`@tG{2r760I+y~ z#THZwQ%Xk3JZf4$B{ zlGC^i)kGN}fiTibZ%rI6u?~S*H6p8O>?h}4^#W>mAR9^Wmi|(O1}AvB!0rv0%uWX5 z=U$;C{ zD-+`>5^)0=C6Ju^s;=`{3RiIHX7;luo7|JJG_qp#jy%#8qj#gI4%@_}T3RhVsGkjZ z3HZDC+Y1aEJ^%)0)Px6UUmZMfpdta9$|2+(47|D;mI@~~X2a6a`J5wKpfE1ziZTU@Rj64HU77^waveGkDo@#wd3K{>FRA2KX=!OMyyn{t&U+-5 z?jR{-A%D83N!!Su&vRIz4H+s8Z+hOSq&Dd>cq$XU9I)CN07!EA+fO&)TA@Akh$(XA zuUEvZ$gQ-+tm+&RvoqGxPfY)tMn!V3%$&MRu%;snE&smC5`BaP@oEqO13QsPU#>&{ zE_eDEKMcSi4GaLEj_kKK+Tbm5%J>OVZYYlG3ltDofTN=R!YY#ko}m$50(NV=qdmrJ zX;_E1I4esy+HEAUBMmyvwU&o=z?q-I490j%Qx&Wa$E;a+EO+3eo0vhTzSzhw!cT_Z zz5{;$+{U*4U5XhOG#k`U{?-shW5@>tJG~%fy)~ZIqG8SVBl_UREk!V9i_|gz&gigq z!>5oLwG@Bgw*s;99Hj)7T|5OmX;PAgE9amevyZW@riF~lMCap>@H^=)+uMn>_LGOe z#jTOUB|DKmo#1704UNlY?MK|lG8U$o)~6Qg9!S$7jN{>NOC&z(0+^Cu@9%^1w1&n- zrQ^^&+|<+)$-Qeu^Ef`~>A--G&^~p@2`dD^<0ocp4IP{5ud|rHq~-VC%1C!UxxV9FCA_ zbf}jR0K{3Y5!1Y?c!m6*;{OLTW`~cV`a0A-tq`W*GKek5(Xsc))rO{klN_X#4w>C$ zm|5GI_SPP|RwY>baZqM`abZNe_~2k|Ow8VMOWkXYGOLX_Mn&bd4^_-j=lOngI@Dgn zGZjq-r+pl5#F|UuXJ?~hRw`m1t9VTZK@aN50j9|8Ju0*KaktEyq0skPk|z=aijuO>sTygQr)}X%RnhD zD4}Hzyb;-+uZikYK71ZW*A@cS#iG5}77y@^txkG-(>tn=CU<5m;8bXM5!U`D%_)(j z00o!gJx1Q3Rst{@fK=DCGH^*rmPfRP;6{n(ktOHOEf7@gJIqSS2F@}|?PMeGY~1CL zsOz584na-T5NW%8IWqybTm*m;A-#K7-t;Q1pwh9J)iLuv@71(*;l5xTR7g+ucn+PN z!tC*2UKV_XpkI0@{BrkvuS3kTJ^|N1RR3D=jvQU5`sdZxOsm(Sr%*j~Icn2#|K|ue zT<74<0(XUcxx>ZvmVS!-isgopekO0AxdJM$;c#NwQ$Pyk04RMqNVvvne>nr1dA!FQb zLIV2k>9WzXl{YVv&fD-bZyI_*AAvMz=Ai`=BK{Tj<;zHK`qt7gw(pD4nmxkhQ1kg4 z?qRtO{S_orZF`4YfiR;D5=C5aZ6Kd^8_&TF$f|NIlfSG>>W_GZ9eaUFuik?GBrMEH*2i5!I z`Qr7}sTTNgtqlsfqyz9~TATG%{QBy`U73Zu`wt$hbZvEkBD*cSD&cYF$B^8 z9`e*&nzs}%i0tpkVK7FE!A6f}hrZ7~oKI|r%NgFy)MoW3+b=^p zugQ5YJ_JLYN%UHH;4LP-HWg4VE3r^EW7O9F(^Hsx4^L8Yh+ryT2Q=PFtyMZF!+6jY3+me=Q~qKV)!1etJ+@m zQe7G%`kPzOo_u@I2ynOE=1o4x8L;hCJaW_~B5jY_7Xs7wFS%y^Av{A~yiQZ6lL zeBhQryn?G1=RH@rWajO&L2!Qv0U*BckOQ<6OA0CDD91TD!n+-ABx|MkA}*qB@UCd# zw_SNh5|G<@rdgo8bUF21x=EdWQc8#G#8gIrCl3`cc{UH?X#7_{5h_dHeb_7{eG-A2FSP8v}zHPdbbXwb(5~ zaC?o#4ibdavfSv@2J^X}z`D^lcXsl17D1F-z^>26)LehXX}1!vRxeW-ZDVgvV-vIY zbxk8h-00|Bi%~#eU|@$-*X_Y~NQ3k%3ZQMBSgEdiFSxP?+d(6Pea@)A!9nua@?jP^ z@4v~4e)#a2dgl;k8&w89p3ELEoyCo*$1G_`0&FDCge3x2KM%Vf8T~o3e4Xy!|T#rqNQokuRV3;+HAy^${a~MAIvVL-U-&0c-VXSI=GT zesN~kjT<){qQd(S#~XVQ(wrP@L}(3wy47Pw>!aRMuNlLUFtbp*z9?f}o*>^22|}$G zZ>QmLMuY8*z?XMBB;_Uq$oGV<66mtzY~5MlEW8uA9M4M4;fa|Q4)=NiqvsO9IFU{t8i#X}jM6 zmp27gk9(!$=Sw(Gb{_^lTcyQr2_k-QldAK8&3Zl4YW=N&F!Ogii|28Z{(C?R#Z}g{ zz2~$ud-RhYhk7X^_mO^iLT6JOrdn=62GKp-r-NyB(G(z`JMU9jQ0JNJy1EVnQMCfAL?Mh!ob9TvBbknRCTB?1 zNgEjvMmnj8>rYh2_WBvEn9!@L&{3>+6)(F?eN|WK_wd~VdF>RShh{H-0B>dah&D`@ zXgYaAkPn&3Rd%hG?KT<&*xe`D}Ey4JI2 zjTzcPFFe!M=hxTpgR~bEW%$${dYYK9bT2jMn2Flpew0$R_1^1X@Cx{1u^ky22I5tx ziyTmr0#Ori4ORbpQ>&wpNC*e-Mmcqte?-J#0+*&Bv`2_^_tqp{{NPzKJl9$}GEiHZ}MgSSz`ljB6UOO>|{7g)L~o6CzDgNtJFg>91BqRM8uN>-O3K4u0SZ3Q@%=z5>a{ie`f|=;nD`-9sdP+>pJk!t?0G?2X01=g ztDt>o84n%dy_0*SW>x98C z>{_>1V6lN7{oFhZ zZCJ`wWH)`B+5*zjM~Y_^ifM_{I|=el-HoF?f8TAp33mhAAAQ~`q<+5Fk*0gK9XhIT z0ovKQ>U|yRjl6p>j(0VdW4k@)%iQr@oy4kF1T2uCU-K#PGyI6p5*AGS8sI`CdJSq$}^H)UU7kFc^l`w{l9xaAo1!fMP=LJuB-i zG+H^H^9fl0>RW|v3#^%ubSI=F>Kh?uIWNYqoXJ~~DsCR8Hox`Eng%9v%7q5*L zNAr##aF*5_zfYf$`*_yaJhY&#ioaNhK>Ianwr#L^sUgU$fyNvP+5u>12aZ4=AxIf+ zLk^X?boxtLNu!EPluvsMK=qN^*A~iUqBSkN2T$R{)V+x+a{>j{G2fTtHJU@rIPG;C z!iBBYWC#=6BrCbxR~F=U?9;t2H-uw2uODp4bGtP?*5rJ~ZCXxxV+%?y1Feq}Ctgu; zyggCMb>^}vntJa=j)pT2sF~s7*Y&}|Vi}#!RiWlQ}j3D|LqdQ3K4s3spJ;Y2Ak>%G2g{rGZ@7N zqXox+8vb6n)b!5n3UVNLa&vNW?!Giqt(kY@nSiTq0@WlmLj-)=8F()DT(X|;bO@LV z%K{Mi$Q+gic4e%IG4fv3?Dm{DScKcKq~tGo2Y7%(?C%dT5|Qq!+q6A2Ge0?p&7LZ! zW0sqDjYb-Ve;p7wSF}pdOVmz_9(v^3ZOJHN&9D5RA>q6a%wnFXtE0_fco^_tF9=JI zLX6v{B?7&D*TLhul5g3KRYLhs-?@ADuw+f7_*Gi>p)4j>lsv?HswOzFBZsJ1P=c|G#_p+X;8WeRe{0b9(^aaSs!;G{46c9qW;99N|b*&S=2yvVH(xpq};dhA=Aw%hv=-ezY z69TGry^?nO_P_QU)3Og(%dGr3>wM{9w`4<-CiiQqvT@96IK}&+#)gK+C>P#Tr{xytZT&aHi3O05^{f zx{dnEZmZu3J4w$)8+sQtztvHXzSX<4ejA@JEvL!N!wn#>f3{g7fuhaPGv}=!`}HH_ z%k-3zhkK7bX2I=am49fceQ4jl-mhm=O7seEWdJ}SOMgOts2OQ@On+ju-A~Ts)>{z0 z^!=^>5vg{uM`@-N&)z{AjEb=f)w{V26_Wp%bOa8B7VP6YUU0a~w{NeK>C@#v-gOCX zoiV$u554oYh_qDthWTo^GVNg5Vf6&Xz=sbh`Z{QHIwqYoS`WmWa#3DenNfM5{#rOS zJ)Pg8E_Q42C@q2IWN|z>+`2MmclS%sGkL2OC_B1Q%l0O*Q{*jQLKCio*At2X@W z+%C7YAoOPrn2ng7=QQUP5KtR|;n*JkyObU> z9XVnX*=`6LGqz=xsdR}jZnc7ULlw{;)VI(jTLlul`qkc@Sxj>j9z#Fxw$oXtkY+ zp64leZu|v-dAv80!?K>r00?99)udoMTu{aaH|smyWvkRR z0~K5&%P#E{xJ&B7$))ieyq8i4G%qSRPSho|l*2%k ztl#$i+)+l!E)|iiWQ0f&WkiG|Wvh%dZZkX4r%jn5grYPgmF#i1q*6jf8L0?K$*hFm zaoy(A>-T;B=<&HJ@Aq|`*Ex>!IFIYRe9y?x5Bj(%%`OGyM=&~qSsEs$#E;^Y*z;CO?~*7w`( zC!wPk?zWmWWFES=+W5)qC|7PSu4QD5$k@in0DQb+H;d9N%VSQObK2$0{7m2Z`T5z++dIt;|EM|> zf(~*@C`r3ZM3ME0Rn_nzYWnGi}@eg1x znU~hvOTx%fkENb7DC@WoV>V{Z37P&Oz71jKOrG2m$BsQ!ANe`&#LhlNZM9+9<;$0s zZtY%7{=P;KTON|GzP{)OO9Fr0FYn7N{4UShn>}~&YU72<)Neu>ZvH`~5-WHDUw*Pw z+fo35%D>-tUtA@2?g4jQk?&or0?&^48GXISN@UyH=Doj1(bLnDcdS_O``g{hhU#{` zQZ(?c|4h=S=M8enG`Q^6Gs;cf?M{9mNL~inv#j!9(~=jtFbGWer3&Bq*M`?qZ_f* z{pTlbN$Y}agT&Qavcp$8A+jY%J=(#<`|49F34*2b@FXGids$hZ^)jE-g;+Th2A<#F z;G*>^fpgC&_p7-xNJ?>D!Ra(#UfWxQ2YXr&L(em*TN?D|X_Ib`bIU8JitFDbm~3F3y1BDUn-Mb60a}f=kG9X$kgt#XfUL&S5|J2 z_~WkSia?QZ+BPbgA^UG>^8a!0^hUSBV%x2b&(|p^Y(gMJK)mI-5<{iPvaknC0 z{>*W>*snjdQc#g|_+9GbvlewF7#GT2W~A019lBV>r0=LLJ)P39V?onYTqj}(ZmwZg z;9#ToqD3blaQ87sR$%(!fcgnrfgWVrus zEZ@D#3u|i+*chn~XA^6=ZhGz0ggsEUHbag)k$DwxVn zH0XuW*MDRFWhDetN4Bvuu_^PgQ?~O;NJJ!7wkdTorfv*VVy*9Q)1}@-$tJ(QPA>oR z*|in%tZsC_?XyM0#cZ)MHPPV0nr$Xqw|WTVV{}$0cxdK4)#k^{3s|Se010Z_s{c8( z#6=3TfnsQZ=3a!r<2R4H08&RUT(y_S{iwmD4~{cx27Np-I(nJkOhdFZMCIkH1J-kK zQp9-je12Y93=LxVjb$rVR2=2}qm+iiy!`5x)MX&T)Sk-zb-26veh+HwAtfQ5jbwY| zF4J%t?NLPbAYUywa|^>EIuZV-xI`NUF4Hr>3CEZ>A5Nv1Q;lv06++>nOV>LxA6+nM z6+c+vq4mJ}T#6|BZlS^2&LR^N6EA4{_~a?> zd8M&o!v@M~g$;NpTh?}`OiX%h6EjL$;TL&`dJ|cWJO)IrL4QP6bJu?QL7%~~19cwp zv^YXB`?68u$B-mY@K9gXjPlbQ(^3q%T#|g*EV(rOT;koc@@ObCS}~(tYwvqGuNaBv zrO^a>2|?ePZuMYDr9X#awty~9wkR^}qht?VIbJ<@1h(FDaQfnJyu6v)v|RJ}9M0jW zvA;@tL)n^ccn-R27Ma%TmN&}ge6W`0~1$W zu1hjDvSQ~P={<)#Z|0^U+wZA&DdpY6E~qncs4~Qwzj{l&xC_`Ae<68xQIT|5Y1o zm?<{>Ia)OFZ~-YlnWuk9a)2fd-OZcNrKK%{lgx9>BRL>=h?liaaq;B(&x~I=ZVogP zin+P@rF3$w$oKf7XR)%fB-u_$5z=qfmq&@F9*jb25mP6@Nit`u4%F=?vHTizr$@v- zNz#vYJxlvV9*d&PgsWDohA(7;(AD#D?GIhpOIN5a9kd!-ir^#gur?fON!k-jGyV`M zK@`+ck&T7kPV=33!S9QViqgI%cO|blC{Ok5xLwEazT%F9IL4W%IAo2X-1WFt%=uk_ z-W)8ZSc>+ERGl-C+1ZM*^S&OBQ*QFnB>c3ZxrQ!d-bbqiZa;!kL`N5jBAJ4@4elX7 zlRU9ypQg+Rt0u^5-0)qPr*ZPIjQg(c%e0G{Cqgd`pg;K>sA4FE?R5Pi$(MEGcEZt4 z0l9>CSYQ)d{lfdsM<25N6Dr9))GPO*!&!K89U{>+0=y4>`tU4rFYF@rceo*c*$!42VKv>D0d+q#=X2)7vvW zX(s-YW{-~(_OEA#wNET(@C+_pJ-rA(_>LPFqjo|`6^kDFCRbP284jP!ua*uEBy4#- zGCcU9?T-d(pU|j-E_okkRnEFHf9!pIIdt{)qlo(e(i79U6=WuP+&+-Hz-C^4%DXK> z`dUZ6#jRGEe04!K?B_~efoV==tYjf&-iVtcA090wi_zNbeuo$@!4@GVSl zVds~BwCP$D8+qm+Jtl&6@+<9+TP7yAaAO?0JG`vvUb9p#B%bKm>-m42(ir?J2Mn$ezi(ceE< zQqJk+V*Ygjd2ai*Q*T09QQqMh4+|R`TZPuCh0|76mY9Wu@$rA+j7Ia`V7L%y8iv?A zI&MOWmWE%dvt>6GMVyT$+0A>5d%l53)i{W!AfgG%k0iM!a_>OMABj@Qx{7sSs^x7*)iHR!^%p!2L-je+I z_Mx|FdQmNZI&bBs3z$!uKeLeQIT(7;;)w$|u?F1{8fIoO`|EQy1FlR~`!9)R3MoQK z^E+wJ%_XUWRY&Ajz<7`u{vpP+WJ1q5NSeUY5;@g3NdY9)&N7Vvj z&NA1TYaE`v*0nikk8stSn`r2l{n)9<_)RE0B0?D4e}xgjXc_DGb@q$O4*;F(0ptBC zUe|r|XAmHiS?e1QNU+fAbYK_8kKxYfcglWWV= z>&0mYee$}S!RR(w^^To`9fr*lxSH=OYD3-X^{>rQr4OdKo5&C$ zynyg=dI-ZddsGX-98~3f(zb7d;079nV)3fb<-@x4^X;2iMK?ufX~d)j1+`K9{MYZ< zbG2<=Tt*uT{8pgC#f~+uFF6*i+Pe&iXUx#|!bg*y&!WAW>N> zQ9n}F*>X+u^+LDc=G(S~j*PAR)JFJ7072blwJM-r-4uY3)I2AIaR>NuM*`q3`Lu02nJ3E)@XgV=z z!snZSeZ5vLT!g|Pm6Cf7yRb3vckBFE6^NIV6L17IiYM)hUNilf26$gphRBxwy#xPS zpmi0w>CfLk0FU00r1SSpI!;BS+!bk^SYwG~poRCCAwXz78CZ6i*H?!Ce<3BO~!n?@rSDKuGTZs>EQZ z+`2D(&i0#_IV8rkp!8w&%Y0J^H!dl@n7 zeoxuAkn0)ZT7{;)0{vLXoyW&wmK+ZVj?g2K^4J$B+Qlu3^|-@AbzN7%5R7vfJXRC1&9zFCq zMt3TkoIx?;L9KZD#wHT1>Bcqw2ZJ;~J`LF=_sMCfE;;0HUJ{URg&L$f!(8FkDS**S z?(BRx%Neoo(UT|s2drjoz!9}j^#A%=@`UNV1$juHxcK-SXU}raPN6~Tt`#cEI&PLw zhq#RBz{ShUD|fzxv@{U1^vzrb@Dz@sIMAI4Iy<1x zDj)F6l^<8#h2RyDS0eX-^ih?%hmtgNCNd{Mom45x7kU+id|iccD~7#DVXJb)lk+i3 z%~qWBSp0w6!ZxW}MN2Ja7>yY&jY@$)=t|ZGa6mfb4>rDrWaw(r#qTQ9ESXwnK2oKB zVl(iY`iTBj$$VWyLnXtFE6g(Dwu>QXNrlooDCF$Q++gzed$1oYuwuR^5IE2ZVG!RO zzl`{{+A;?r#&1iTuXF6^y#-T`USVD>!_(r-Nh;$-KiE_(;kuUrg2*-pb;`^p;HS1Z z5b@^=q)e|0fgBZ$OeV%_Igqe0E&>``GC>(#KT|H9`@H}IGNHd z3Y=qcZsI#Zyi8Dt6GFgPWl}>4&C6TO!pgeb`1)i|KX?P0`(d%{0&5m5N*45KX1Mhz zwYCZ^+uE`n&{7WvVc3uEX{Z#WPBHKtYtjS+1!WMuqMMuT3M0Z@f>_b+SvTZS{zkI> zcs)w81f?65>Z1*HDXrgrd_0%plHbbb`=fX;4c_$1i~ne2N3=VghKzX`Nt#gh=O+%3 zej#bhjm!y|j+u3n1H3NP!R{Y}TFbm=XCYsVl`|(Nr^!u=RjDZ}OV0oqc=nUjOU;LZ zS8zV}glm|Ljg5vYDk?mE)+i~NefspNXXV#XwGD3mB^^E-2qSW5 zXc*v6!-iZs{8h35N2JnwKW1r_Gm~qNJO)DbWzE?notuw;0Q6NX=~Fv}^5iUq#6gHv ztqIU%tM7bs!|B;4ySJRdQWVH7#egK^JM3{%_Gmx&f=24nz;iuRiugWm2EzC~?=!pY zQCi&C+V3#5D+}c>Ybyb0xcbFrm+04&LD=PM_xvc1$)gmchF8mdvL;G&@+10N2E{Vr zp+&Dq3u=}J3r(j%shAl*Q==denxLtpI3ru#*USh5pdQ?H5&ah zW(dvD(^_vzcif-zQG)|2+vYB?8$C&RkV#UFfF<4uX}Bksgtr~#&hzYuM8>qH@#>Ci zCZgAjFH)?S<4iP+_CZ?ZZo6as4NGI=a7857rpn&!LuR;&&>r4hMtX@~yD&_bHQ~0w z@4X@t^zDKnIH@;k;Brca*qtbc>j_GzkiLHZG;>_do04~7{;dCfUwCF7$QocCt)ov; ztwRAIN0^9B{e@2hXt2oPXYH0V0C!*Nec;T(RgsIRdG}N28l$?50Da~ekiRodq!;Y@)UTtzq)U_j`2T@oviI2WSt&sU@W}M5jv#Z59WmBbGj~f#TnGw zw8{OK4LWtEw`>{}_kt92dg3t4Lkqp;k-_+RVvMH&R;TjhwRt^^r78}A zB|lSo)u$<(D=Qy9Md>g@_&R|4#ssF=AEzuinSI)Dl~+_m!&RJ!;yU5oo&c|KLY0<#DnXVa>g}c|Dxn=7GV$zdtwTBd|7p zNlP~-jOqM=ng<)D-AMzQKnUhhu-=Q`s3zR>h9Rx1YYX zT>RnC;Dv@mgN^y@gSeLNDJFtH-<0GZM{?>}+mFA%K&lpE@|S827cQ)7#L=Ti>)xK4 zR>V;BflSgYWG_vv0zE&Hun&g6(RX*hqsarrpzKsp)31$7LGbX6I4_8^*?lJ{Y0fZK za8Y{41ze!)-v?bq{c9$dLpKb9Q2!Jh)>c$B?>>NL-sbS&C<~H_)-77ehX&5C*pWp` zEm<>oZs{O`f`8wf3mjROXyDUng&ezkr%#J{CDlyAwxkGs3BT6CHB#{rTR*Zu48aUz z-rqTbs4?=-D|_at|20nX|E?0N%e&l^<51~W{IZYh^wEu%^~eTN%sa^zH-Iy?;bdqGf@ro z+0LJTDtKzqHc|X6AAr1@2D+39rnF9-Jeg(U*Ro4E7^v!^MHk(biXAju7D-fGS)|qE z^Lg&?PTSG1@}UXT0=;#=nrBvhS~HOr`q(yu^%;)dX2Iee%I7GsJ$*|Z7ZTpEJ5PK4}ShP5oD z_tNK$CwAl|UTS|+(K}();`N(C9{0Zuez0FeCsgiqz4g7q?*;nnhWlzZ$UcxY5cx6& z$kUck;54I9=;tSHI_&hTBRx3{k2J!3LSc#@uY3k&uYU!_}f&Ml0SeH_MP% zxpJkAHmdO(iF3%m&U2kc+6`D8_LY5K-{^lY8KRax&cPsi)!=+-&)Th@)eiVY;#CNJ zB5Bz`C$@oqBwMd>}5?sc(NCn3%sY%(k?2bfob4Yy>?Kzw2u! z`i+03vV4B->VTeI&1jOZXe8+)m4z+&@qrdM@grox=OGRb&NwAA_6Czh$^hR)>xDsh z>Cz1gmG(aglaIVqUR{11t=2Ru15oP(Y$o&(qF*_1b%y{cilnj z8`*okofnIbi+XB2<(x%8qP^ULT>Ty?+N)>q%xk4K1p3taj4<)tR)<#s>iYw_e z_C*XKPqxQ^GgXrx2(;qf*X0M)*U*2LkFC(km0M(NirVE|$CLgc?gIXm!ov4guUwaV zCE+S0#D5Id#gR;ixa7r5eWg3U*WG?7`a(LlVOPL9=z$-fH~vlX6I;=@p`LaSVxBay zv2WgGg)UZOhx1XtuT-EIhq#oGIPY{YCX0BBPW#yNN+>_z_nn7DV6|kL-Y|P{>t~D7 zJJf?`HXH}|zg9Zw^@iESnMuckE-+PBR};Dv=}tJ!a+hTc2E}Eqv<^f8<6hsg{qTcR zdPkPV_rf3RVtZpGwrmI-9rjK>WY**Vz+j9M5~R)8=h28gvvy2fR15toAz@)*zNc}D z^p~XnK`}>6(y&n*LmJ7ukA1KE8Vy=m+9BK?Ip}nU;2_;oM2Byv#Go6xq_>_y%(JV5Kr`B57G}u9Rg87~uCSF&;lOwQEoSNsSyC;L1 z7NjKWxhqMpCQ-Bfisj*Z;Kn`!LDSmMyHaiNWYX6$f(tgqgRSUi*`iCy`qua2;uhc{ z^IMhd{c^eNRZ{`={{nuY{%v$i4b)~$13wFYY>OyJXih&(8on!7%pw8c@6s&XQ-5B? zVrzqOHl5Qv2B)}U+Rc_dBzwH(f)zO5rD=pAEr${|Eu z!-oh+^!j?gFn1UeQ{N-6M!SoPTy9ZIn)W9|-9e(&142$d&)Wxs$W<&|nRE$z8t=7_ zwIV^;NHCy#eeBbY<1brU?5VqNf9Z+hop2Hy9Kcd%Ka%JCr_~&!&eRwE9<_)rK>LT; zerhhrv=1$0$7ySIa3!ZrmI7l;Z?EhH3$Lms`JUS7-(J8R^Ghp!RO+F3E{@FUVB8(l zVgx%oeEfkGv(GjSqYMK*J+}o4#DlKd+wvxV!5oI|l=J7$lNvOYW}u$l?%YNC^BlH`DpvT-*AjjRRbk#5fkRZlx@QERnrOqqHe- z=zzWre9QwzkwSGE!_fF!G$XS+P?+WPJtxY{rn*EyWU8WHf4yX{18R18>7D; zbAs~rISg1jiw;@;lYc%c85mqB95=@!zPT5=EKxX&IGVx9Vk{#6t! zaM5zo(f%}mD)6`HrqlJq4=R??-^YgQ)u#`Hj)FQw%c#G`Yjk+)S^l$oe)6(Bx7Uje7XBe&z99yY6 z9gTUvkbwte{-&b$L<;*w++0%yf`k>;m#sGW-9Nn$FgZwZ$V3i`h7g^V~yA^<3pOu9vuT`-wH zE@40RbNm<4DoKBVsvd&c)TJ7Co~Umu^Bmt@#Az>Lxo2+}zMT4q{?!#eeE#~mrYrrw zY`7Mz^~yj+@IAh2`S#32>z41g7HutxW`9TwhCw<-JO?*dS%YqJIKM)()Em6I*`7&^ z6O5ruroOkAQ0qL$Mq7DV0C3HQ6sXR$tqWL=R*{h}|KjnGFmAUqf{TE4CV49)kyFOO zyn>;)I+llWU4x64Xy{iKh6-e^5VgMvWT;o7r^75JD;wS^%k5AriL) zQvfSfV_u@8?sh6_#5{onc7SCL0LxfNMcUu$f+<8)HMZ@#np3483%0I(#gQ#a15d89uL%X&+=t`?noO8@K+AIzqa5~9lr zpg@XYc=jknIyX=YI>b_EtW{NQF#FxM>Rog+&u`Fd9gx8I`eoxDu6Nqs{UU`(5}Fks zG!meSt|p<2gBtUrcaU3p|Br_JyMIxi%1AI*8Uy*psZ?Pt^Pe$RQ=Ti~GPg^DvgBOP8jB@OIn{WEgsN@oSR?Tci9Fho^RoZPo^T6xYT?L`BsKg-t z3Wb{a?On&7=Y4?t<;P7yv{r4})JlILhoGTTbJ}^Ke{&rlVf1Zj5L~=?KhN2Ay{u!_ zErxD|Ve>D1B&SZ6m6UOq#gL+-S%w(wf$?-pj8!g9<$e!S}KZ>@NjE?xns)QojL2<(UN`*^xA`%A$<-^dGYyCLpPJTpB z+=G@d^}QYdSuTXn+sb+S=?0{y?N4+wFP#1~up!lH7xq@Dk}~?c@~}PrP4-G$^kH#) z4u53Z&u=3%)WoR%utBY-mZHv+c>P-TbV#q(#{P7e`^6+!V$!!x&DKIwt_AK5B;BdQSLenXW(M;2NIsOH9yr3?A*B%{7I;gws(m1X<`X17AGRz1aa2O=WYG5 za$okdvneJTw)zDfN>Wmt@xS_YB#SRDm5?Zx^6mIV=vYX3%UXS~OUL5rkO+=n8trc7 zI;kax|K5JyfSN&^%+rW^h>x+(=%;9u@U?7R9RKMV%AE?jLE)NfWYq9FN}27(mIj+0 zJr#rqk9(zRu57-8{Pa{1d9a?aHOo340ML#F%I&iZTt}hLrn?qW zN_bw)jV#zA@5DB5o^oJppV`VgvL1H(dztrC_N zkh=9faMqsT1tnJu$f%{}bG(Ymf!JhAcOwB;z%g*sgkos{%l424;w+#;#H&`^xacN0 zZSqiji`Cpx_kFHI8U5^N&;%(nXUz$RU(Yx2g1pZ$KdCEfW^m|Z-$tHGI&WS5qHF(g zbjpMycMfg+(<9f!_kYz(_~#9du(UhBL{%tTC!~7e2A%GTLcMJJ-o0N}9rEx0DvIGS zS_?}oT$)g~lWf4Bb9}vQ`951gZz2d91K4X=vXL3WYN;;Rf)*xG-ffV7^8u zd~5TspPxZlZkdsqp4)kb;NmI5#(O9QAKTFF^i~;F{tzI7w8i$~<0r&B5SPgDi}I)N z(Ge!LL^1czXOy3TYrF85UL?ch5(j<25)ZCb;r?fdg~AIF5Q{d9x#aFM=*rJd19>zu zDJk#;BRIU#V1MX>YU3j2XsXYax2Cw*E=SL$ ztLFpowBh0m9~zD(rgOBT@MRDsjc)1r_y2jg zy7d5Y*JjA8&_CxnPJ?^02kOhd6>~sQi8fXX*mgyzki!B-hg-Rhvc95owHBi4ibzRk z#?wK8Nqf*6fA0DLSSz@HJ5tg#6DJmI2Bp^8`vU2q8;S_X*#&{lEIQ+kkk-_3xl8i) zm~%qxQy-0eHBw5JjAwkwN(i=X4;m@>yS9yhx9q{cCj-SljGmp$;nX!Shz4J9O^fB_ zO}sXiIljDcB2`#dUFd}@0}|-0fnm%DXiK?#VUCd)`!_Xc@)W!6?fmP0~(AOKf@2huItIAJL^6h(*^l!0uD+ ztx#~sKkzff$;ov@R#c31eDLxZpcS&!fb)H*PBXPzf`_y`vguVnxp;yG)L`x8H)M5 z5dtGI5rV05uKDxDkq;^#XaZN)%b6Kq(|(zh^u`g0#Fgr-XXCm@8%D{WlW*93`IdIM zMROA_xX-wSrVFA0)V{Au5;+_((46uj)r>Z9}jNEGQ2%>o`nz~fIn z@4(F40q*>{Tep2D!YB|AK|m$-yDvQDnr52Vrh9~^tz~3YT;Lpm%Zj#Xg`BB)i%hQm zG{-y`X7^zVZ2svw=fTr@w|6~m0U38?)7Cw2ffD>dX)d+#>|!_FEF4HA#we*h)GoY= zm$z>7qP+i7pCVp zfyM;+gFPlF^S08e^W_FdOrd}<-3SSN-9wL-a%+SxxbqL(wFIdxArNu^u`7Q6lUJRWJCiEJAnl_@uHxK6*u~>xG*~2j1X+QT58*lH%Yt5 zv`EpP1?>j@MN&02H3D3>ARwWoqw}8a=>A)D#sE5~v(JsshcYrTwd(CB+!aiKrB|Z& zX^2a(q%0K2c{+GpR((61RD#E(*KEITsz)kwJ?u1_l|ET1EIvL_-wUK z9guJtvc*_C*n*Mm{O0<(EiE>wI&=4lL^Q6VWGZcsS-x%4-nSX2V$Lw(qIFqRI!gh39TO1i zolF$YR`cggZ~>U(bm6qQrDt6nbAOZG&}aKZCLjlnqc$0LYr0SolDehgySBk`vJgc= zavom{%+dLMsEbPMTs^h$1)GALmJl<;jfFI%QnLNFyT zY}EwA#(HN6LqWHgCNjJlXF|64tl(|qa{K4OiqHvc1zctyIE?v8Y6_DJF&4mn?a(l? zC`d`l12eulFm*A`lNY+uc9HL_gzc!?+miX=>QIy~^x8FN9N+AK@l| zYLp6#cB>vh2QwOg3%~aFf-OfJaqE4b=jXnG8%7;(qw;s}+LeZDuiom%g*LEG`1Mk_ zXFYrSwEDJt50Uz&f#6993F*WAimxH2SeANwO8(-PrN&|9w_D#smi&|FSF~ZDLe~Gw zkF2<6aKe@?`Y>-hV6@7`tNPQy^LX3UL`9CtnuV1R(W7vQ?K=B@W+p; z9iEeJ0qz7jllxFtZpa8!P!6Dddnq|;oXbcK*Z@IFnmUaJ{%6;MM47U?ccUH7o_`FK zS_J3K$qGP#Y?o319w#uP%HAMmnAjeEGbv{?!^O=ujK6hz5ftTE8&O`%fT-uGa->Nt zHDTH6e6=Oz3_ayYL(W7Mq+Ys2S+?sz-#Hrk%|xw${oy!Rq84xFGKX$hC8Pi;8u`;H zcxGJ628*4N#Y7Zn!1jy<&#p;08YI5oXuJ{b<^Q-6W}ZuMjmJ(_zW$#Vnn5YygpP17 z96@!5`dL)Pe;iF@&u+r($Vz@PmnRWKLptVw#D!fXlwUyy#i?0Pgzsy13TA$YMgz#) z?;vNQ`3y5F5r{-h>^vZRv@!knyd~?bvV$7UJ8==2LGrrB zw`I#Fj(o5YZes-^`PI#Wft=rm*WOxB&|kRs*}a z#SFrc;(l3EfvFFz!zWmdCOE0~r!1j(apS6zQpmTgO}m*u?YB4aK7f{95AejbU2lQ3 zRYe)i{HSoYQ1v&cLUgZOXJm&IU*5OJKK;}Oz}7vW11?BDG2O1n7z# z?1HKiB&8|8jWY{cNNZ3zs8c~Z#E!tSLfG0R-64wMUVaDZOEp9pLY$2JO1Q{;lUw8v zg0cf{mY}AiJ$V`=Uws6|%RmOIQCQ_xzJhW@g-H1M^O6{V;u-G!%E!aAY^+t3W%b`M z@*N^sV;J%o4#OVTeU??uo*$S#r3o8zkSrZV#Qsc8(x1XnZ3Wu?Zn!VnsnMzmvu#iW@La#4*&N>Yzo4YLO!3^d z{bR!h{Z=ASzR$RQk=U%^(D3Iaqv4RotC(jlNAF3HI=Fc)p>QvP=!Ry>-7AX%XU|#C zTsUI^=|7Amd9-Na*4)jR|7W}yc%eGwPna-pB=#_J^Bt0}bIHPNt^7zOj$P0rUTuFc z>HVMs{ZXg~(J&;i3h{x446FtCm`B_uHg)2P!Z_k)BBzlE2kwSu27Bu38{3UQIPnk| zCY}z5SEZ{Lx1T>ljnB3~AZ#)ae&P6qF`UcjZoBui=$!~6EvP^I!=UIZZp_k}svw$4 z_iM6EG-Yce9K>WEN*1nh0U?2mn2s>tm+}BI$E!1o&Vm@ty|p+-Z3ejl7Qa< zXP#>^w`{X}bduB1NERKw48;TQ6>mMP`f!xuSN{rctfjoGIz!wQZSr>j8#Up@d83df zVqAsq7A6Jj4Tl=QN|ir663`hOG0~8yv(QkED=av71u07p1_||%-|j!4)id$9K^Kr} z=hp0vlA1_s=}C{>P6p{Y@5$iYaqZJQ5jeE7OuwKR``VoolTbSh?0}8RsyyefHMS{7YziHFyJwNX%HD+)?C?HRdGkLZ!ay*;(1o8oLP7rr zLDbGSm^1~zaar60;j-&!TqvdVr01!n#Dv&!YS4C3{>d}=Jc zU$2PUeeF07z^deY-NsZj{6%&gCk~{68J7*N2Zr78>IN8+Wc2YbhlFAyC_u=IYo(3D&YU@i zu$X=-NyS5Fjn_8`QZ4?0y&blN{;hAPP{c%IT&P*A852X7(z81cFFE+O$+t~_U*4YC zYr-IBQ2zg;0GJShVD}0{M0ed)=nR3ewZN4TCfN|l3Fhk#^qdQA?%1EwR3g)508uQK z=~rW95;wPO|BZHSrruo)FOp`~rqwsQ8KG4m?03Zfr5RYFlHjO(WGbt$;jKfIg)>|e zdJRcVpO+IoCnBC=7tJl}qKc|mHPYIl(NLvfjj ztwLJ|&igx)*732eBdIL?D+#M$OjqP1&(`Gdqg+Wk%D)HPc@4{zgd{7)0$bgLoFo2_ zdnPrqy2jm^nehmr)XJcd<<5USsVT5^nYY@T3ttX1Nc+5f(3ZGaStwf8wrP}MWojj3 zU++^yt5yutL?R%K&xfV=&P8&7GI(?PheCLZR$N&SR{6<(lGaZPrN9Vol1{LpCMJFo z1JLNMzNF2jaNH1e>4bsWkRBr2$vIPgkp3OxJTf?6_Vgqq6yJ&O#KT+c1ur-+xYfh! zbbT+&lim0yg61<}`a=ScwlZ}_KG4eI)$*Fch!kk%U=Y1%BR71WDW*K7;TodD!#To| zE=GAX;v&6eNbQsiyWbueAZ%cOpx(2bcxrIfLHctP^K_Oc$lWJ?5qdsOyyrr1QiaUj zj-6d;ZNoT8M*U@B2YsbW%GXr(;RocYHZ^mLrd1K0WO$}{m8i(n2I4E)TQZN2MC_gq zMn>d?qybKpJBaK7zH*fYPK&m(K^1suK_zCf(w2@q4+Nnj_}TT~%qJk;B764vyI7!C zHl_3iZe&;_?pyOsIwe=y^Lv9iCf)>uJZqjpA*J=~+V5G)T<^w%5OO=rxrrcFyY78; zW4r8c(aN)oYH&sk( zTuNW^Rqs2pg`Qt3YnI{`6GlwD%7XD9ixO^)0097GjFv-?R&|oB$CyN>BO&FW9SE_o z^!tZ_>sMnIg{B{RaMzkf_6gCq;|sCv%ns6nZB7fygcmH zGthbRCkOBXO!#XO&V)#4dAY6%dOexK(pGuKNL?NKoKc=5@8$7gtq2QpU^Fo?A;ift z=kLHZdRO0q`}@4idl*E?fw86iPEl}r89m>|=e~0~qR8n$L1q?~;K`C!qj{8#wC|x| z7`D3q)#m&^=HjbYFOX&YD?>Z{W?-U0P^X2$HerRL^FN3@nmX~ zv9i^^*(g1`rwC;&9PJPoA|=GN=NP$hfX+(X)OUA~X9`)d%z4r)jIHR7jrhDXL-f3m zol~%e1XUgAH5qh%`CRL}5+Cq)Mbv20mSXc|tX!p5V&;LMJ@tWL;GZR$LVS&kpY%GL ziVG{C8R@)TEg~C&l1XzkmrR^Snil~}NE^w#*zaCVL%&WQyzl#$$Bs_gp%e}P_3<`Q z2$7Zx)3l9?mQ6*;=@k4nO0aRm2y&I@_!rWUt&luEhKs?Hm1yorxZ9$`zf4qAWz|*N z(vl+h%bY%8XGT@dS1*<#sG4B-4flG+fE}40*6|?~Y~42oIhP@t*@(oI~uI^8Aki}XSh)k`SPDUe*Dh;h3@;Nai7)S3CX0w zS*e)*C#85B>!Z!gOoxZt^`dc&UO1Vugb_oG=T7r~@<%F}43pPMle;mKHX6CgA_)BC zUAQoQcr*+{?yR@v6%+(^?Zrg(?fY76Ez?G9^Vtj%lr}?qwK=;6w@L})jH?`-IA!Q6 z$qWQH4IDcIyOS46@p+YHWKl_3a`#~evt&pjtW^T$>-=9{MxLLjOFFelQ;+3N&+`{7t zS)6Y3we%!+^GBJ<{Rb5$3EL=CT;YW0HQW<%pRiAQc&Ehx+w#Y(t>*V};=kpCqo2I= zSBU5d+4(cvou4~zk&*#KRRdnE={S{-Og9p4>wVzx3=IvY>>bu24H%I9Xtf?N>I%Pt zArN6g1ECfc0SHGQ_}gXZwb^}Hnv(9*>3AeD-M9192k7@kz!Lu&tZ4pvSMOziCnjNw z016r^kXrS5)W*$;YbIzpGbqQFyMn*HyVnlTf#zbrnUT~zPBjNE%5X+a?hX_9L&X{a zs{fF)n_U>B?`$$O^oq*?!d2GMWwwVW*K#NCQ&Rj|HI(@E@8wqyEPA*UR~DPt__p%$ z0mSN&AjEcGtyH~FU5*dasP&68)@dd0}&B==M; zO4#PZPA{gVF?0iD;z4yHZIp?B@f9bHr#VrlgW80QNs7ubnZHSO>fKd0K zrTP?;4tMA8gWMWv?cVVrojry|o;#48JdutiAsu;d!Hsuq2T}1n2h6mXtM*JnL2#5K zmBCtFO~rKdHAJmDuMPS6A!gLK=G0T802Zq(yST3q9E`Vh4bSx_XhU}H^gh7V(I-uZ zXb#&(Mwg5VX>Q@z;`&K2&!eSD#L_H2#vyJjju?8@W(MB9xGD2a&RqwH2yKe8 zv9Te3F~K?BweW@2riJTinM|RJsilW^zTUhQRS&Pax_Z9&J)su)AQUYYw<(XudDA&TdU+6s&;vgO}!^#@+FOj1%WDe#XoqVn4mNmmY|HAi=)rwaV@e@^_tS%)Zr-?TTI>X9A&8=e7 zx19KdUUvmavt5xR=Jc`@ zA@4=$obAcB1VebZ!fgJReWy=Pdj6TL=+x-ppw|qmT0=gj%Tcr6USMht5Yht7xe09+ zTO=p9iT(;2YbbkXdpkKfCEO8ipl*$ga^%Re49>tM5uoK0@tQAqDd{bvt6!i1@gU?F z%fG|J_i8aWEkEbx4eJk};7ft@S3@K{<+eZM%TPj<1#R(z3Yc)+Q5X@mQ-(f6g6nIA zz}+Z#@W%fTz*&!m1^fTmVH>9?bJ&_ z^y09!{V-?fFCZW?zb^R%%3MZl`JixGAnT6)_&djohB^r1?@HS&+1c6O%S0I(8s@ys zd@;Z+ARvwWpX*@M_V*F8w(EXF(CIQBS*c$A%w(G5D=KG4n{i(KaA3jnFoCsZuPX(n zzX=E47$yO-irb^F1&`++@(VoTnp!x zuG}*h)Unlv{$zvnqG}xm#p1of-n<-{CYMh)##xsHm}7Q4rL*?QlZ~6AC3Y&aJGyuR zg9HcZn`gbTvZq0u-2HFTCX*dWJKbP(1okOEyW$;nak&q6laSsu-x_Y2ddO=`%(=a1 z|0zc`Xm&X1bG_C}Aa%YYn&P#@%iG)N-R(m_c6tyI)7RD_eIdvPpo zfAtrJ6By6Uga#QA4_BZS8wtIm#--TESU7xL0Hq$cW;jl9Mzc=N_~;cPCqD@$Oq3b# zc#YQ^o-h^XrdDQ(wn2cSiV@nZE8t~oo|!Og>kq5Q%*?#@49+Es&(GW4Jrd}iv#m%2 zHCswgjd_Qekc^BWnr-4=S>~M=Ac}9W;gf#PG|}u+@Q?2}%f`aOdGE9Rdoq)RxU|w* zeZVx!Pu&~WnZ4f1QhgR!PDpa{5@pG{nng!!#t*YlCF43=(0gK?G`SzJQZxBZloQik zGNwEB*g=Ltu4`SUk#8H%HrTzi**4^i`x^_kAt;I<$-7%uL=@KF%{MNL zc6oP4+g||pch_(OvC<_>UDSZJ)T6iWxefn0h{`7;^Cn3El1g{;E)pxo2;{t_gQ{j0m- z$n*%Z3c~JtH{z=A`QN@=hAnWwTSnr%644(r%wQ3e1el_XgPEE6RnoUCat|_ZnwP?M zVefvEtb8lVGe6AAqd}18{R{KGSNC1=vfpmR^$YBG0{VBDtp@v% zbch(Pr!!7iEiI4{Z9!20crl~B!M5H&3z`)=OewO+>C z*It{uKu+WJ*+-z8=)GggMOpqnc{pal@}pPZ=K1zIUhjxUsffW+9$8sg{S^-vgHgZ` zjL~M8XL3%$5PA~wYN@%ox!L<_4cB@o9|%lRn8aYo1`@_e-SHgPGx11x&Z6 z;8~3;@H$TMr)N%vxv{_8vq7V)!5^p8RR2bhKX$M8(&8H#dU=h@D^@@!-D_z#=nu|o zzg`g_oiDKMY7BYya3g#*6#H){;VXOy@XsC7qW2fJbhR|4tp9Jt1*f$Cwq=ci`dbi* zv?LAiyUy}AnR~a~_u_RmT1x;TGOqAAfuK&%O-~v!|xCns-7m1r~ zk9@DIt)})B3^iqw{MU2=clrqieFpiF)MT+Yw!;g|Flo1*fR%e|Kg>RXD>{Gu`Li(R zdm^7so?7~mMADJ_D<$XkZHEeEiA=RpinGwM z*@US@dH=kRXZ1l~L!Q>LZsvTP+3VYHQSL@~^#cIGQZHY=babio?1#9b4Y|GR`ggebE*7DVV@(N)&X*daKf>Y)Y$PZ9kXftf z%1;o0tv=9+a~}i!oOc$_`~IV!9sChzgJnN9`^EF^@lduzlUOe_9sjhAeJTn}zW|k&HHzvRsvG!2$`eT&`JJSzBMm zb1EG`+H*x#_66SJ93uj;IIQ5!%_}7*0x*ATcKwJ0k@O)-7?+PVY+KMe@(Y?_QcX=w zVOCzSrT0!1Xq>b<`l`gQ9W%^~p%vf0d=V=tDN%_}h`KA5;Km?Oh%m%3!;!ZIr=2so5wtN?m4)vM$}|) zd65n8i`|{u3GRZPm6g?|(XVAEA!YOw-2qRcDaCoPhH35L_g(eJ%ElcNjYc8k0swW> zEk8m-X9b2QJaH4C<#atA3)#YOfZX=;Xzl9yJ*K$PDU^BRtD2( z8hQo>25+{3o^u%%ru6n&iNFJBcbsy@ytKQy9p38_<+$@kq}^%2nDUF()QAKHMKHZi zp8K`(WOgdr-ej6w^IQ`8u;|`wx~9i;Kvh*Wd&WBDjvZ|#mmAe=8&&&p)lE4nZBHh` zDeb|fSv%6@%%;XQ%43M+F-g%olGZ|N1QV-{IbT|*jZ;1+geM0dyiBkBgqU|ZKV=f$*5$n+a4)xG?cwZk<~>KLiio$#dYcazJAXi z&;9gmUf1Vyp6_wIkN0t;)4%rAq1BP)5fW0=@ZCUBk?I}&{aeSF`GhiFO-=RHZXC(q zj6lGGT3T8(E=x*CnCE8&K@;Tn0u_KiZP%%E;$NMgZ96`$Y5W6Q4?k?bww2^bglJTL z|NcGka$V)k@cBKguU@}CsG_10&kVwU<*HQX`w(=p`X ze*o%BEeAfl6uzTGt`&BAN6UkEo_z?`UgsS#q9{a)J|yn_ms<@D4Jig?S@p__ic1Ea zmJBAW>UP@-O>u*ULTLqth}K4%q^RILxYp|_RsP%U?&VSvZUuXSI|p zr6$?Y`q^$mPCV*1sF`ONZ(M;PoY@J+40^t+dFsiQT8ee)>R3Rrj$5q&nVw$jwUGYc zFXH%%cU~^G(k)*9#kcmN1daMXb*{E}6=ImZVb?ALZF6)Gub|Vxw5ILJ{udMpag#YX zD#~7Dep0V1K{*GM_%W!gL*9F<0dSpQ7_8M8m+%`Z-fJ;DG`4OSJ~3_Q*6?q+B@4kL z9DQ?U)Mf|gEacjVz*NBrI*-Q)1QTzn?+lnp&L(;-xW8r5hgYjAn=48IW)XldP|+^~ zE;@ai$5B9Qz*i*6j?Yc5f+^j-9ChVTHw@3p#2S3IuUQL*61F0=3Z^x)!735n+?k9(0B z4{9aFxj^kXGo@VX9)t^JLf}KS+3fF5f2oRi5jIt&8^2UGGjI=Ww{ujgq@SDrKOAE` zz=#aKgq@wIyLzrX`dA`DwxfA+d=6`N{fEcVs(9p)g%~T9HA)XdGBp4OGdebW(YOe% zORjl)f407Vu&;P;mqcvjz__m~b!nfM02mOR(RFRiwG${$g2nA_zBVHe{trb2 z1%Bp)xJed0nc^ba4-hQST2fIR#x#wl_!pB z@)U*7X?1kXtNV3*7Gog$Z!`-g=$Z23PQDLbhaxUe=K>My@mlHy6*G%;9lFAv8=qv(#7!mIO0KS)?Ru$iG^s}~Pj zWDnsRd0)IZ8?l&H3hm%;>F5wZy;$xL0GvSes3pWjZaN&2qWu=nvuIRT57()zq`yY; zRgAS6F+nG4cik>pQmXN51S#eyH)0YFr{EV^y}-ID!6_zXzQ%9$ny z-(H&I&=WZH>l!30PPKL>&d;3JhIMHFICWysgq)IhLR0oB_Uc0JUA)LGO5hHU$?@!6 z5Ul{oJx1yrJ}}Y1F8nK2KBDf*5$rRsw<5V0e2t9H$>#JGiY?(NQ@w=gGE9x@Fz0pbxDes6@liuugF&8O0l4d&k#g+UOJ4Qgm?+`3C^ z4LeM1py7~rg3!7#ym?>2#dY`JLZ!_Gcdc#W5H8aoz2zg&@|Q?XIUCcQITlhGF;0)Z zV$rhg_41?JPM=vyb2MNHK8U6+BzajTtskFy2RlTF^0R8b5p1%f?c*FHHKbJQ>T%%C zXy13I)$LV8a{U42TQA-(>f)}f>U1+@=k@??u|^jVw3wKfqPWn0y7&M1;fua4&CWHN zbFEv;nP=ntNME1Vv~_n20n@qzHiFJ6zUZ0Cb4$Euo~}FSSb0CehZDveW4lFd1tCYY zdCR6<+u2rJB7$p~wFyOARmzs}nOcv$dVUVFb%tdi%40?;6!`o-JRR*ztV?s(ZKWT| z1ME4DlzZrIQZn+BJ&=9XfDp?E#)VtA0px=hW!>5CD=O$^L@SbIgk#qHd1U)BIj_#! z4jn??L5;#LRFNNR+wM=vAybbln-|6or23?uE*I(u0Q=B_qwpxF9t4!W?@8=AKN$Nz z4qt`*xB>NTrjKcB#i=J4GJEpaa>mBSETud#B0GSq8t|Y9B(8RF`-#6M5i@|3g2+p| zojk6LLKVp`DCY7+I2k*Pbr=iN{>@noW9-3_4)KTXZ97G0`9Q|E8gq&@W?o_xH^bm6zo2u7QyCnHB)&4Xk>aXdm@SO>aS;jkM7a8<8W2R<@a zEF8t~wJgJ2opt{Fio@6gFj%?ml*-5D$59K?{$h2uSOI~Nk&!No2!Khk0)Mv9e~HOf z9xZ-vj@W-$qd4%j$OPf1C6Ay*kYdkq8H|4d@kMe*2xc%8Y(pRrV@t+~i3#FZWvCD7 z05aLB*UNVH+Sh3F-%OVfM@85Mi=i*|KpRElI ztreHm=#yUK6L=D*zh5YumYb))l@Xlk(8*P0*u!lLFGS2G!Wx3}Dv}NL30;v$o)*Z3 z5O#8E8j;wC!I_dqksFySC6M8dUY6BJkp+|$sAnFmIAQJ6$?Y1cj}s1b@d4%!#rKOEXK*6NB>{bKffgy0sNvNdkG@Z zOKKWD;Im>~Yinzqg{_^PKL*tYFSBvZR~Noa;z-~UmU;91F)}%of+qUI`8I|>6!0RCI=)zMDy0+_m8Z($>o_wuTlZe#R6RL z;ZFrfJp$Uby=mN!Z#ieb`e zP&uNwVlGg+OAls##r}JxsGh&B0DOAx{{hjI+*t3MH!CwAT%ZWGe55^GJWiNy^fez{ zCZZGh@*I5Jh@v0QOqABqLDIRrC*;5Vk}S^v)q@AXezfEs%Ko^$;zL}v0uA9K!|d`X zB;8mKh40eEK0&PID3&IjJ2zPj@$Jv1-aoMHY)5~Y8|I5!H+*vB^{6?8YP`g{cj$P4 zQ3U1<1m3AdW!w7>XpA2*6b*OooQc9bHw&?#ORUCF=R8U$Y@uJhjjOlL9GH0|7V+?_ z&wL4LE-^XGvu&FOC^2ebZ7nT401B25CKN1uK^bys?^?~kB({VFI`^nSitsY|WMqt_ z8c>vBxEuUA?mYSTQw13YnW8|uG*re0Y9Jq z27LmDdRW^OE~y(@^yU_SgY}8!cO8+dzA$zduSLwLO8||Xz)3e!o)dl%a3=H-8+dql zG`)$;Em-o3*y-A8m=_acrdU(}#&3vB>HE1t`7rX<18*qS62y%rUt;9=o}w!CcW5=p zvDrh=L~K!gPKw;y$9ur1=y5;@%G9Y#k-8h7eaPuU7agUhp0O>LJY6m&)Om?hHo`6h z>s4>qw|~=Ie5rmwG28+1*NW^a+QQrl!U-2@6=R5P4$oWaCLK7G(f8!XpN-n7O1JO5 zd?rl{P;Wfu81ODhyniz91o{P`l!Bpq$<_|)#4hhKGD~!i_XT>_&y>i!#i3h+fc@70 zBI}uTvnp1_`DxOx@c@R1;*;B>X8-4bWA#F)A(>Ge)ZjSBGbxxhW3@FnO+bnBa89F| z-}@QZA-NEbv<-iA-kfP5KMnn{Xj?L4z3$5Hfpcg>G9&X75-hcjY=8YP$+?j0JE+}5 zWV#{zxJ_=+QmTChE;z6RamH@5I$T_Ta>f|22zhh<8p&;E*iLBDK3?G)z%cbS%#YX5 zeuf$(!Ab`I<86?`1@d$2>89qt7&$`MtAaJ}T~|Mlz8 z$T;w3)rifSpQJ(EE$1fN41h7s*A3%rn2zq^U7G^|ye{lZCBMQ1@g1rN$^@(0fv1iY zbj){!9I^BB!)&Fq1kTuA1f2pB;iD$xKriB=NgYt9B;QKQIOGfCTW1NOF4Rg9aif38 zK#prSZunzj(|8H|uus-24og*hhyv%19sC#xm|O+2kueSGL9aDiZ=)(P_j;6Z0tzQT zv9=PNyWL`DJd^4t3!WLtVK4|u*6*JN1a#t-1kwvwD{aI#ijltL|8&Y*;*encjdqsM zLwcf!4Y*ea;i!;l0c<)7gr?hxxLdOG@)8;w%EKp9Iq+yV5m#p0tAYB~AVq-&e5Uad zLIg1@yMakp`?3@KGjA?*Sum6ZeYmCds!xC_l37}dSx9= zi-{@&Zh0%2$r| z5JJJT$q9Y!uTa!8#X#dqa@ZI8-C*+JV_&^mm~iW$s^85vhRyyqM29U}&o$^bAovg- zU-70D?K4FP^_|x|#pA1g_QoDPSqMk)Rn;9~m@N6?L<;C3(7}ea7aJgIosqF2F5HdMVDX&N{R_a)|UJZOeUs&cq7p z7q?O-$H7otaxbFpy#3Hj$ApL^gLzpAhS#ulnJ`{LjcdQ<2_Qn6s;?UXd%)Rgm;ND4 z$PTmSCG5UI7<&=te;&MI7iajHEWx7J{_^cxU~7MsBoBPhjoe2}iNBh4F@`7xIK-w& zYC3N}F<#oaz|DE%^y{C^*6`F#A1YVEh~1wxv(Jy%cGafGFeF6NasB@TApv2S#EH+Z zqY*jI#gdW{-6mgN%5F^kiN9qV^~>%je6f1xU6hRwO$7sMo%{g^^prc=g4;zL7fg0m zqXKEe@}*v^5k)I*;>ji~3|#4GA7UW>DS6Ky0!$>jfctf627x3T72PVtfI^JT zWQY$3(%l9|pd59#x)v?e*4B>GO^>dWBnzbA*os!VAoi7EI}b}U*DAXe@>M|mC6XFx z=H>i`3xqEH!YTfyds>7}$KWw`XBdonLl%BU=Uj7|Q^v3`v@Ot^tj1IlOW8H_Tw-T~%!MxuiBgOa&?dPM~2*MUejntxX zLL-f1!nQ9jDS+a(S=D^9P!p<2X6!Y8i$_gZL|O^Fl)czl)6er-KRE1*Arq`bY{M(x zyqNg_S?jhysUQUHVsgkdLTJ7EaM?_$Z;H>XHOEY1Cf?vjg-y(aI17fk!Z901$Ev-( zXn{F0^Lh7OvXSb8)?BKS7uLZ_@KWvP104$hg`<}Kp)p7k0(@B=R}ss&#=eKf1yJ1w zhDdOa9*%zi5nXB=L?8_B>Dg^Xws@RJ+Jj7y)$;a%0L=rbc*FnsBD^;3C7h>+9S1Gz z`Z3(>x0_#|TVYRwY_*mmbI4f*{uilXXNON)xudnR6fueddySp7)v<{Q1!glNSSmzP zwTm6gX~Ja30FZ2rIC~>`@a9a`%}+(wty?D<1l^PyK|$Kdu4{JM$P#`P2m;EPRUQ)q zYn@RC+qsR8&5M0zMg~VvN8U(S#3VTFd5E^!a6$aZ!Qn+S18V|2t^m0=%ISm|Mtx-S zVH$Rvs*m!Q;9F=1g`WIRyzzRnTt!NX;5I`0nK=e##C2FtL_incY1 zD_Po-3-Me;39m%7Y#O(*bvk>JWV%Beec>4k%0XU9K|w)g46m*wQB)vEZ9&DYe$r00 zl}1e7c{g{?oDxu|fcME#f1}G3n97$>c_-|0#U|g~ z{W(zt}rYx_51?b!0bCn=6^7L!SNb_L;U; z-B=`TAbmeRHNpSfQu`&FotDQPeQwB|VxUu3EhH3v`My~G{I~Stg=K|-F$jHirJKqY z4(95N8-&bsfWFSSkRjP$=n&J?L&N+A*;k%aD4~xbC8Gvlkn3Z(R7`?rJEYmx1LJV% zWW06j7Fp@;0!k%!9Y<;L0e+M)9BdHhGN=%ysH}U1rYJO(SCNz}crw_6%?0f`{xwdy z0G@XC5r$eFIm#~?bRUf&^hs6cQ{tZa4mgy$`!nO0;;)L+AMSJ>x&CPEnMaJmwViyd z;ztgi|1IM!J(BJCL`*l+A^?mkzSW#D9*PHAhpvih6iP%qsmQoA-!(o_G3(CwxIT1_6x1^s6)eqE*g47G|_ zp&&~+2XIl>P!5S_F=Dd4fr8-{PD9g;^l#br|x|Y1u?oXi>bo83nVqCMZ^s$ zHs#Z0#+5CQm&HU*{!Q)xDn~_9bV6R$lAGk+9F@DY%Jo7}w1Z8ui{Z+W=<@Z#L z?Q2Jd)-kK~64hgF#jdgP*-7>U$!Q1Az63IW_Iz+)E5T@eGrZ7$w)z^F-tHaLr;q5;LnfRPwVD8tcn%p^i`lgcSsNNyD&2bkGm;|cu|%2F z@8>qI3Ekmo7AB2XKZf|;6}eh^;N6nR8)>$sn%*}i#XDv4?3`DQoxjXg{Sr|fpMv@y zX8|%1p?v!j92~467kkr?Kn$nvy_gC+eTmqM3CLe_GGxpb;;7D zQNo54mnujfY|YyL0UyY-k_kYi05lUmCuzeqPW8DB??N)8hv&_*pT(zQClH5)y0ryT z;=j}mHXGJ#l@zB`r+he*FkXc@k=l!&x?x|Re@$Nk>iiS`pgzUPzT3s0e|Su~{~BEV zv@BghDyO5(#by)jX!uq$66)gM-G>;dHGIX|?#G^=Iyl=?$79Q7+#+=Y{_8XX!qm@O z?c>?9MWw#=&-2#a-c690+3Ii+8iax9GM!;*oU!Hnk-4oy_t|VAArXAo7?@sH@5f}u z5WrN+9C(*fIWH}rNlP4lMFVtpq>f4>plf2gLPxoh_Vz*};Z9CYj(v|N!*93~T)X%v zeJN$+Mw@W(cw^_+Bc}snMJIPH-cMml+1o3zvUWjs!uB(7`AgEvXSe;nETzZF%^YUZ zoWZXa6{&ti@rwbyUh&$6$#So_RgFsiKLgKILG}mv%=6e8nGgHKW)N_Dl#R~n^bFRDMBcCP;mMh3d&KcT;+PTWkACIHXK*gFj;Zd1sS7S`heSt*NW zi)EEa|G+?bCN0HUJ&<#u9;_l+p7rbZju}Pn?Zp;=lEf(Lt-8Lr)~e%|a;m=jop@KY z;A>mch_o6)(IE=gWGu7Y5^L>&D~31k1g`z=e`&+ua>F}|OYiy*=V`n@dwXV?oyXT{ zO8gboU>>6k=rI`f9ctoyQ$joPo(Bod>U&kvy_g;JO7xZ?!%!PW#7;_hb3=8uXb$~Yw)T{AD}&O_-yU8eQ?=aTmK z{Z^}Qmk|;Yl2>LaHqSBK{%hzV$IpR}@AS^JKVd7HFh49(Cg4BwhT3k*%F248q^OG+ zBLwh=;YM#~F7UYw9O9;Rv%#)!CH$4XoZPKyL~BNL%68g5tK9jtYjFN29HL=N{I6Kl60B4np#M(r$))bXxC@8 z_z@I00wcm%cV4WC(J>kQEiB(wHF?F{E^d28^T9MJk;T@{w%hi)xI1ike5qiqcpzI- za;>QMz)WzS&l4FwMAqrMg+`huCj?+saGyaaYK9Y?gVTD`^>i%FreW%j0$Jp2d3yHi zmE;)EN3J1~3c4I#ZLKW_%7_7>rxUkwjO9+|E_y-H<^PJmFBJjJZIATe`hvbizz+O@ zLDj2dXHctV-!)!jdJmnR&4Rzq?H1IT%=~`n!EOOT)nw7{8~pCaHX2vr23VC^dfSXO z=IoFAHRO13^x0g=aVO)$&dCp)vMj&spSgxlmSeqocNA6v^7aztEFvs8#uztMz99B& zNyQtReUwY_zYvPm!4{D9h{9<+-}2?l!PLFgRR^wI#f9MR#c70z2kEu`p`k!13X&zu z^a^EI!9Y4DM$!yTHz8Ub>lhMIwZ%q2u!=E;yo63**be4mz-^h)qDyO3#mJ=q!3BJ| z4WO~@3jed;pk#Y`%`frl`M#HW))AvJcs5#Pb!6_(F%<0``*GVnV-PjExJ-%w|IMycK0S>l1KQhrgIp$FY{tsA1fhOp+wxr48$`VPV z{5=~fDMk-8A^GvT^*kw?g1v87x{e13(%6|9i>tcV*2PUNj>tpZJ$NDwbJY6izu$Z)A z$52G6^YGQWA99U_UEjZ3@rISrd$IqECuPqBS_bdi+iR=ch^eUBlXGWZ-ZLz4(FCox z9gM58BzsK_;?6JDuz_IEh&rai$K5npZ;d ztv|)%>cgqw>AqYX}UhF(Y(tr8z+JN+hE+Y_J z=cp$Y>UXCZMQ;SR%?lv8miTln{FwY@iO?RLCfS-y4rf0!|&}E{LOzeU>LMB%{;4EN6P*ZXzuvv z?+l=~Ud}kl(u?|a|I4aQUG9Y$RS6l#P*AwZgXTQ{oz1|v!(<1B$W&o+v!5b%-!XR9 zXULInT(@o=@k1Lyoov^zh+Z2X;*pTh1uZ&S+RqgXaQ=jFTXMs`vcwwa=jm>w#A?L( zopZUjRRlyXQG)j(Sb8gsEc^1g>noR+zyZU%*Nz%}{su3LCuG-s_!2+XPY8XAC_FSY zG;rsJ^Sz+#rsRn5y6<|B^fkD2&jqs`%S-njk?8jK|LZdIf^Hfwa0vlQeJ{EZQFPBc zjy%wyfh8;}_TxP4*~DZzlWxh6vP9USel4^yeCX;h*i0Pt+&w4UzHzIa#9D+s5@4YY08srz$aIo^Y-EAP|$nVlC<32P;UBCKACd(*m?CVVaVfadhi4yI_5sS2j(bc_!{iVs13vqOH*P;^y zojcEP0KxUZ<3g)0IC(s?%Czlk*yR1E$B@#1^#gP9 zB$=HWIpgl149B0kj8>qs$lM2Umj{7%+tz0uE4jFD{QRzs8x@8(tUKYjN0S~122l*^m);BbZ?Mki zB+d!Yh>PiNE-zOH3EN~92j|YCXx0hQ7~J_}N_QuPB5E-_0?(I&81RZ#&BLOgsu)cM z3$m(=LOx+TwmotbNYP5V*CnbEYe0!gzVg;T;<{39bV#qD#ej+TyfJ~LDHncr$0>E& z4U;VayPZ3Co?15yfD#UZ3WI|LMI|-~f~sF4X1N@BL0P{3OH_HrMO)GCh;X4Gn}E~) ztG&}7?Ta2Osq^aYGs)fVR3+33rI@LNRM^Bs_Tq_qbTS1Z3A!%7I**;<`bA$R*ri5R z0@-Q5f9m0R8E~rP%U`*ARSCDdL`hU9UPF+Gvn3~=t}15D4jn8}6{iJL-(kZ4@CD=O zwA0zaj3^LFu466}>zQBs788dk^Ky^bl;rJ4eJ|WDSU=Lh{j_|f;D_6if-(JrPn-`} z9&L<_x7Km9p{@u2`J={Ms~Kz9xH0lV@9@#?`$&|<7*f2huGS7+pWiyf+wt&mX~Ux> z?z~!|Z~uw7n24};Ph0r-(7XNPw0Am-v5SQ)QRO*O;>Su5f?`j{|JBa^#&}Aq?=RK~ z^{Xe$i;c{$8)>Mmt?jl9J+|is^Q9tFJx|5UOvw3Xwi`6 zx}mjHp!E8eHj41A%Zdtn_XlrinD4)T&~m>H+e`S!o4_A)ktx|}bF^E;%6bRHwqo$2 z)ovB6wb=|Go?9;{Z#OsGx$M5&w01~oNyP8I@}%fzYMP^2?ca{-yOoyF^>!kez%h-< z|Ez{9aopEsFZ;~qM9W%S*C)X7=|`XXqrVv)H&}?-hhm^e9A*9csow_<4~qH#7;u?( z{UUfb?(t(Vg+e4ZgR)0#Ohr50(Ew<4#D>)a-VW~lI0e8sjDPH5Jy>kpbL7JPoO9Zn z8m}vDk4R9G8F}Kg-8ru7rBg(y#%C^iLgg_&=Y{H00TP7KTb(I&AteLlfHLmuH6 zTlzi~iWBCFjv71;^9cR5T-XH&zyOsj;+mV?rSsl&w2&K2r9X zr5?KoRamt#qb%sg+B;c$1czR{crD?^qjR}ZN`qyWqnx)d>S`#|FL7RMA>QqJGmmxx zKxpm60{$P6nDe?I^tv82-H%D8Au|#d0R-1D+;n{gbf$iEM0kvnYy!F#GmI@EJxUuU zyye>)BlpY>fpLM`u}`AprO9S76D$l(Z{9%V2Q}0KABUdkO7vscf{mngKn%|(U+GF$ z<9ItW#0-`<22er-cMYGDa*crG-^?#5(o(UP0mc&HH*yZqpYC+Rm32gnHj}?;hgnO} z^!ALgp*JDuphsAdYi~jAlD1s)tP3f?q}>)Zl%X8_%!5#5y|oCCL_k$uM!~kTlg0 z-v_RLJLdHz&)?q%F%y-ZG9w;%AjVEzdP6vm7$JXSmBWPl6{vz5HPXVom=f;YyO&gf zAWQ#aj)qk0NQcf$5cZ!(7>m(I!s2_5w-kDbooU+T?<7A$3vsd^@d-N`d{@$5I4$L+ z#^Sx+uoVNDxb0sWs|;(aRJnr6CnMiN36Ex1@~w92S9`x+1sG5+NOQ@=ma_yz{(-~= znRfY)9zDvMz|ZV=3)Fr-SW{D@v7Jvq;09Y}LRg2}`SWTN*-6N@9RzkWkT~}*UVmz` zr%PU#i_o1>pWiKHii@Zt**@^tA>sIT+P5p*Nji2r(O4$hr=B``5?&YsA?dM$cuIME zVePO-X6{MR8unJldB??IYOq3)P>C^ee^daBD2pvjt*GvJ? zuH)nJ++95c>4yb=i4U%~*%M;iqu)Ajh$lDeju!aB_eTVUGHundKQy++WFde+mxDb5bz6Z9p`uVDUbX2z{9Y@FY>F6&yJDPg`+R_R! z>}ZFvWS%BUuyxGymc4JU{2(RW>NsE|B}Au&`0$XKBkQ6?)d6ad{SZ`%^jxfnc0;JG zG1F4JvA^3}#iDwMATBP+Pj=a0?w zepmm7&6{~F=`umfmZ>Q3N!HO6t#Tjn4Ftg+Qy`vml`-^DS z<%D%9ue#dWqQ-}z|IH7QUd6;1(1;*_L0xrNx~HzLowNwjoB14K>^hK}CkkLr8bmS_ zoyc!`x9BL0;Ap*B`X>EtQKMDvX8Pppa>Xr*MTg^?mk3@1z0;`@F`&p>7L)=mX%`J~ zIZ%8a16`H~sf+J;3L@`MV1C-!C&?BmS`4kE*Gq0-Y<%$e@#C+aKi`9O-3aY$adBDazw3K|w)xls*pBArg=9MG}*EYWY=I z!H97XHmYNL9uP0^=tC>Ze?@m|di7xTgCL9j&B z^)x(|*TDKPzNh-^{QeRe7XTXc&QR^!`otPYOAv}cvvXW?>0gIsg?!87AS0q2+s&qz zV{Ocz;V!!96WY9kZH*>`^0Q-3Fr z8W@b-ykHllXlrX5f4OpD3zR!j-T$f8ISYh?3{NrlT>cL86O$8fo=6jqpFnH@B(Y># z=GPS%-Xvy~ch<|d_QvM5+@o2mwUVFQ?~;xDf)<~70IvP5w0 zXv~$%m(3X*w%@;hU(NcD1*90~uh`OZhxziQOV`qhPEBLq_wK$VbZ6iEQRtwb`s{P0 zqi5y`J8vNDK)jhiEO9)JkHj7}Hrn2s8oF$$>&Gt5Vy3fAf;095#khqjo~m2hlDjR0soo*HX;iF00gQlhP05S*cUqCD33&xtn**v_^a?Nt~y5g@~;A1=H^z#kP33nYAzQ7%(laeh}|dh!gWV_yT`<6HyIV`(nWZev$V8yW@xEK5%CKPk-7bs2#d((A3%7E5vmwQY+*Vt^ee$Rk3w+ zTsEloHN-6Z4wO^ZX^%p?#}|XJcR*v(wt1l41REV^HQk-%nUo_wcJn zcwsH@bckFqGp(ZC;*B@rZ?KVyW7BR3eleAF>O*!(T}v7C7w@$D=0k)&^Bgr~&tkR) zcXCyI^8gw0`^#A{Ki^joQED!a;an8@zboHQKzf19a12j(j}bG4C`z3XD2Ds0!i`id zoQ6<5o;s>VQAoT{E)r9+nLjCuAq@r%L?}5B?grlI8HN&E z&?z4t3+T7O_k1FS`)9>y;q)&F8YNKU>S#~OZW7a%svyCy=8`Ad>-&-piq$tpclGx6 zS{HFc0$qqK4pk172&Y_gS)zc2vjw_NE^_eYC;<+XxmiL&!u!UJ8$->&5OT0((QM&H zSLVrQlQVS$uUrB56cPFMZRL~7Uy%}~Ke87W%adPaN`lH0&NlZTv0V&~j@_26G4vMo z8)1|s_sl5EO`SY*Cfd@Z3k*Hv2Mo?I0hJF07G!0Ibaa=Ozb$a9} zp6-)#nz0#ngRQ^gHF2x3f>(3>XX*5>Bm(26nGM<8ni&lic@?6peGDy(yp=}hTA6j> zySDJ;H@cNop#j3&2Zw@K`ep(3iEO!9h>aXFr-?&#atr@IG#a+pcWqpaiqk=mFp(z) znt{-0Jm6%3YtRM}n-3rF-lsB^A@Kxjc-Dmrt3GHzg0cVS&$L3ez_5pS{b|slXpHKH zMCPO$SwTRitx3D_t<0*MzZtti7U>DkX2&6dmrMW)diPj!>+aK-Ql13u!F=-LP>Tq9 zq9E7=zt9lpG%@nxrI(*ysZsE;VgQlE);tRqoGq9u7*gJ@#4FiFPA41kUG(OxG`Uc?RE}DIds~~S& z^Y`~3Y9>3*5K37Uy@>Ok8dSg}U4F$TC&QEH0LIcL!7hUICOCDj7nm>au!d)!HH#(qfH629X~$m9F)YBDCGz2~r=+5Ij1w3^Wc!q< zg#o1?K#2!>T2krq`}cQR+ymKnn{|T@7R5IM*1Zxxa_luhqG3#s^s6ustC2vf@wdUNW9iZRV{cl(f;x-<^+czpAgVUn(8DJ_Q;<-K%z4 zfGI5pt+hl-!$ixes>Bc!!m<^vH|g~UkFSH*Rq5JJT={D2dnWXn@&8y+cHTg$@LY_% z<12406Bz+ty*h-wJsnFL#3fZ`}#-`aE$5wj}U{# zKQ5q@h3R6?H42IMp|$UJwH1@9%e5O@^08V&VaFN+klN1^`V^Vwl%u;}KG`gySp?dq zTtV3_bkK_EzeF?V570lSqX393yRW$j8P)v*0vnNtZFK%blTECNKrSE4|7Jf!a3^J= zj$GmV{QY{&>sQ|Z);nia3_hPGGhk`C@r&K0n(c{SV+n%}lS&tz`3yZQ8*UWsmfEtF zeaj8v2DkyL6!n7!1zc;^U@P}9c-5BImcfUJ7m@E_@-j}gNi@DO<4>WzvQ$*Bf_?C$ z#w)Z%`x{jv4|p*$t2u^xfNV%MW>$t-=cNE8(%ZXtuf0R*z3ocK^T+etH`2Gpwp{ld zbyjkTh^gSP#pa6nU9mWNfn2m5CouQGyI23YY@TlOxIp2at3oFFOy)l49Z-~wbgO_x zv5{f0qXJrY4lBCX>JsX?@6@#|x+{xbi|7$JS)ugW&m5z<;u+R3zI^|FKW^mb&qyF$ z@1UpmC?L{$1GZDQ!%kx(q>xJAmD!q7P%IZAlG?WpA%+zP|8qjjK)rFJ*_EDq$9TEO z)26Se2#$w~o0YYtA^BT{5(7Ybf? zh}b3SPf_gF>mDsEF(Wpzbsvse#D;Z*-M^nP=?3P48-Fc~vk@Mih*B-ip_ooSej(tINg*PQFe3WuZLRm_Mg@USLk< zF=k-u&5UFby1=Hu!Py$G!@juvy5hJhQ`df%KIsQnxPPaZjqSD*uv6nNes5CZnzCJZ zorGy$HS1P0zf$+Crp*OV=iU*B+;z|O5WTc!CmZ<}N4mxSD}cij#Nr^NXGWv;I10Z{ zPPu`A`0VIlUd0wRs2E(lVl#J?AGzG0Fa|l9G}}yEEWx z$(^djrdWN%b_U#2!n-P9dUx#a^UWj6+^fnM4 z43?7xiroXSmwKsT(9Em&v%3>(7yI-T{;d)TA_rvt4C+@74!@NYoDsTXO28X4E=cpC zYl?vD#LmIv-+OfVAHZIuuGEh~^Ck-Q*&it%M~|Ih$sTK!d!WQ}DcDm>z49#%+VuVj!e6UTC6Zf&CA|0M#s2BuLzV@*?Ta4V z_@MIl+nvR5loj56MCavnOgYpu5PxsdHTK7V!f;M<{3HuLpgC+nzvg(Kp}S z{xp*C4vv3;`}U3R*%@{W?dUC3qRbp&v!W@0u*LmfoPuyPR^K7O{OZsxDctevr?5$9 zDU_@JV4Iwk6)ih5Y)Zuiw!7U^_sdY1I~aRX>%6J|c-b!{Jk+?M zo;tEz1V~xwZ8-CrIM(dBZyX*5u`q=e!gp;QR1vR!M{yqWQhcc$L9ac5I5C6R@ zq*-z(-m*OUW*f2L8B3#!x3OPi1dt{s+%1t!ZVgHCAhCPx+%QUeFf1Dg(xp3fyn4EF!?RUqTv-p*v2fVGM~$c~LN57G}JDqr35+iG@%!}d&LUM7)2De(W7 zIFVD6H@hce>8=4EszKxcjxn*7m~FG)p1!cC0CiQ@p9idFN=oXV^W973n&Hw~xte!+ zcDodxSYoZ*bWIe%f*m8!XkW}(@6EoF{X5$v#pbsD+-Gi-hX#6Ld#$j?K}V;iIpuL{ zs~8p_QnYUlSM2=Lz7u8=0f-i3+BwcB6SU;Oi8DQDrg*MxW+qrFVed@2L zqu2*#$!ZnjrnN(bz+O7$!tmnnYg71@kyzR=@r5l)e&F{jeo0sV9+!SkWQc3;;KRxj zUP#tb2--KIx4+Lct}OSgNs_^DhikP?0NlA3ER2rd_nn$6TZo*X#)UmU5Me_Vzdp4l za5Z|l+9UZ;=!nzLP9DiSa<{UjfODC0>}`~ITh|Rk?zBF8JC{dKmFR%YX|lJ_0rH>e zy{pOVzGFS^1DE`m<>6(gK*rnk>(f4S8TVLj*@S*#p8_D1-z7}FtT(rVyQ}$`hoa*# zecBf*>|+Mc{)0tq@^CirH}T;^bi*2+6+i{&e$_Pnub+mjaB}k5fnV%i#_T#E_F|&(d_JGqc$42FtznHt!b7ETwtU^INwLQo^_luy|Lh}j zsgxS1hi*P&fi1kl=_ z&jnfFy~AUAMf03LGNGbV`i|YZ;C~)ltfq7f=(=uJyh;IRzlSJY+a?bjJce0S#TU<4!mO+Z^OxesfurRN276HegxU z$d;EM9*gesq2^|X070kF@D2`tQG~g z7-4aBE62QT^aq| zSjuY02Qy#wsOKZbF*_<7vaM>5OC@XBRQu-380ce}lQ2(vpN{pKj16?fM3ex{`QWH0 zsGe}r0#kwrOzC-R$7^{U7_rs1Wu22-;?ZX^O?!xprKnzp!q39IJRNL;9e(Ua`)WMw z3XIUlBTS*Xygv{)DY?4VeTBll2atf9di|aRDrr1^eA+#3*XF{dvr0p4r+xM?bN#J1CAl@BwlYJ}CMCgpY_FOImMuP}R$#KpTwnUxwgkV@ z^VIZvDbKSh=qR)l0acqY){K5CwQDbFXE7Oj(TQO>XVRzMIy6IklM}F8REjQ?$K!Ql`e4q^a?A^L!a<^3VEJ#JU(CxfZvSf|S)s2C zcWojvy~rLeZ8`EMlHbi8SXAs}d8Fi~e*f%i-eHj@&%cZPnkf6J@aP41*X+5}v8+M? zpy#kCSg>E9&?VjcoZ-G+JtR}1A;1^>oyawzS~=Ceu9!5eX&xok0I2W2 zHIuA;sLAd7zi;1XZEI#D_F%Sa6Qb>Z@0JQ#+kK zcmk+8;qUKDlxJlh=@u~vZuW@s3uv7F`GmG&7sa@<-qNpOAYM!T0-64CVKHX5BEZ^n) zvk0m%9Erce^TN}DVwh3W`WvrE#Qr_e&pJ11&qcR9|B+J&Y{I|g(o?t&DB{9>>mN8P zOUq0=(s(K{F)|%=j?3O6;|D(A8jF*h1_?n|}`UWdEw zi|`rUmGjJ6Mp*esEx(qL^u9TFu68f?^T^t?DO2&P(t)5Sqa(uECQYMT#oV7ClUU{U z;cTy~CFk9cQq9BaHY|enG%mo=8d5T`Xn0`}tq6tG=|<9Aqa^=rqJw`W5L>RbA0Jm{ zA#8m2m&pl-#l@Q^N6fc7CHQ4$-qdobR_w)v3=6$yo@yBCZoLvSE-f&z{WhIwjp}8c z&$UwpQ$ox7-j#R|9Q_A2CSB!IAqs8BrTAlke@AH z(r$V7+bd^VlfW*wc*XJ(XMc*q_raZA;%+g2(z+5))PHUiDpD6+@81}-0I$Kzn1eV& z^Xgb@t}4AN=#L6r5i#Q1U@MH}48xtjt*m#>&>PAyFW&&QML%KfP3rvyyStycHKL(2 zf6bO6S5NGvb2qyPfbf5oadWv?t#9{CnCEXxK_|>-#1j z?p1!^{g*D->HCxs8vwol0bciD#Lu_nNzmcua9c>kris4!eveOm z&WN+Z={R-%2Fkw1JU4mn73sQFl>Adeg7?Hj6Fp)cNGu~ICJUbzmWYBQl`xwkNDi4X z%JbAOUkE>_J6IE|KQf4}m1u{aKAHl&rpwZ0TT*w@I;ZMX-=TI~w_6syqkX{pq!>T1 zs_+=9H7kGg?tb}UFF;v#rwO$bPxb8gO325W2=^Y%cRWlQCF_LwITHJKOvh6%_QfmU ziq%<=VF@MmYn`v8XEK}!9?iveMKQYR@^n`i3EQULw?RK|UGu#;_;ud?>ITl4jP>MN zo5%OnPEJa;`8hYhvaQs?=$fo{4`}PR@}E)fNdh*oUq!6+F(Z_4w@3ou^_AUs93} z?-K`jDSqs12NcQ{f-`h|b6#MZ1j4KcM$eoD0?%Nj_T+S5L+**uq{_Y|c6Z>D`}d7x z6tWX5##4MwZp1c0Emq~h2C1ijtcXdTM!ZHbQv>3&5YP-3pXX&t)5nEH(o4eb+lHMI zeV~+zU7j;jD5atkSQIE+ymLDG(7Nag2hcoyGEkgz!Lym|ltUfXSA!?obDexlM0?$T z@A`L-VdKz6gNYLt;!f&=ZTj})s)_PX%|N`rSFP1+4lYpU-@MCWs5C&@-^#hqnzb~% z_>5>55rJ$eWz@@+-n8kX#_3_xRKvr>C^h7t6IX6_pm+#$?ah5Vl4DLXT- z=g(;zrql-+KO+#$Z@magO=~2hekI!SdzO2!{HI=Ppe-NbPsb$Hv|9J?ExJ#~{M`iPF z%X+e8zz&eK8X-Re0{<9(Z+&@pK5uUstM^EBLMZ-Y2G4lu;t>S67=`)I}j0w?}0#VBQW^l zD+@eQqW{5FU`p7}Z|@0ia_B(~)Oo3H5IAYH?f)WIUrl6d34|jcBY)I>*XX@mi%Oxl z)%F2P+@#BIXS6J>fx!ft$PJ&L6MK6b4ZB507!J^s>?SrwKGXkP8FD}L$W#4X+sC^d zgJkG^LmXjp3GHyChw7^OZG!}N>aPm;MLCaLJM-^N?L}g zaQ$A}Yq;m}Noq=!;Z%zg&7khRS@f@sL@Ry$Fn=13oK`4NSt0%3MgX+x0S>n3X{G zixWvn!gF(XtWO(ftXPBZE`ieU;Ys- z3!!flxI^?GdBC9uDX8}rE`N23$Tf3cYMRXdPq6ijU_GT{it;VXs4J~+72^XwGEa-Z z+RKlCLR8fo(LimBc~?FmU99(T&voTB`Dd>f)c$a4A4W6eJx9<`|MWSg{JA@gCF)}6n;=;Ojiw`GJNL9ip{z3SJ0 zifbdY6|NjAc5MCDwZ_)Gwtk6I>$O?{8X;xyNF}Bc?RYSR2_taMhv29dy>;8>H$w`M zuyaR-!~M0R`g?k~#>PieB-LW(r>rhEnoq^HmQa~30Lb3P1k^(h=LCp=x0B=vBN-XT zE{UCG1w&HBGn3*a132?$*GC)C8mSi-fYvHlcl##oD|)pt!4u8Ieez2kF-qI~6&ITPR8k{|;e0=hL_wOd~LLURF?$2t(u;V<2IuA?D^#ZCh zyA-*>O7XwS?V?bZedf&5g0WYe=3;+5T8AbVCW#KdYai;=ks#5NU6B!@O@W9OquUyi zj~OMc>Z+q!w#)oB-q^pjif2g;G&w`={|oZW(wmCf|9tXZv&w$aym?BWpVHA(mJJ&s zpPeYa!+VvYPdLLUPuXS;`$qBzUYnY*|K|~Sda#lu7bx+c?zy|^LvrgXy)vZP5mr2a zqw_kWqJXEBpr@D9Zcf#UZn)zoc*Y#SqUx82!zD?b1xuW|qP~t1aVBj3^Nlnlza9G) zdghSaFm{(Dh5&gaLUZx}_qi4Z4#x_MUV)ECgYNCC+L<--@aT4P?Q-ta;mk$UW67vl zSlv2A;67YfD+9nD#7v4=hy|XH` z_YUn;sI=?3?#Mak_q?9h>-ooVj&Z)<&*#41<9c7$^=4|wb#u{L`7w9lt9rH}9gaOz zl9KyRCh%&X_cefqS zB|DdyOTAls_j9;SjwsxTxx(5FvMNy~qgQ>fEShTstGC24&UH~r8jpOEu!wcb_ z-*a&H+xyhN4?-p!s?umbPqQk@#TmA*C|MIp*Dv#{V02_F`jXYi2cC zclR?J!y-!9uC9rbjZu*qVCJYZ9VEN`KoD1eH?p8{dA@fd8Kz)gwMx~q5hv#K>h7$p z!AvF4g?R83_ZFIu{W{cO_uYRY`|29`( zyM#tpr9hXW&D3P?(+@h%`~Hx&SLb}e`!Dh4PsthnN-^>M{+q7hn;T?jSsIQg9-Q9f zTBj}rP1#xLF|COl09*k6N@SihdoI`)$yMl{yFFO#W7jn-$9jRYK;o`*umCC<|Gnq+jCwED2Ye>}`$%#vl-yu&WGsrmSKbJQ1s6j3^Ex|oDx1;D+-uJAgrG_%NS!|w5$nrhN{eL*8 z&tM+zhw(r|6!w9dQ|303EfMg&^+)djhrK=YGyB0vrr54rw@O}%n2UGK5jRPejqYf! zy7c&-r-H+RVfb~7>l8;0`22OHN?(R}A}4IoxMt|1^NLHn_W<>%+o?{v(cB5Dxw`UV_QuGDmDn)(f=%4BzABnsoZ19oCsgEn_q9z{p zcUGqC8y>>ZZ=KBhS(&AtWRzvM^VhwR8M~|78`c`8miS3^+;Fey2xVU4|4$bV#Wa!S zh&IQ^o+jZpk?@iTxWIN4m%1c|IevhU${=X|gWv{+kB#W=Hvtjpl&uRf(y)3H;o_g%NC+sbA=Pq~*d10VtqLr)hR(ig>+6 zEH04$Q$Vn7B}0SGGiQ$cISmW(z-v3OEWZR+H#s&ds$|8iE3ts@&Wgs()%FcQWJP@a zm2k@3MArksS4w+V^p!E~L&-kf#_=JIG;_-fKU)1Or{i7y#g*PW&D_XvJ(fE+oP1N? z>O`qd_UG|dT!NzE0i{X1?T?5j&G&U)C<7IM3$T3t1uT=)wkl&Ni`ikctQDzy3*Nkd zs^n1>H*hCeO`-MKPIvF!Fc*i#+TN z#3Yy(9+9K~jd3fFjKB)-UGskh(G$9_L~L0{2@C6p>7O6@)o`JU@9lWloc_a+ZF=+E z_|^U6?U!|0|CA8?fJ+#C6sczscJycMw zEridTbG8J_{LX}YH;Rz`T5(!JO)Cim3Vmdz2V3f29pLm4z&V@s)@1%Aq5R2Njfg@r zQkY;MH3UzxI?~ovBI0-c1tH32>X${6HIT9$$iQ9wn4jH2@U2g+ zi1~@y`KQqGZkhb^^Hx02C%?1^yabrVcJmuf@w^;6_qHU+T8d%L(24C(U5`iQl?oY` zWt)u?*&Ft`wNN zm}}{tkl9sA;W$wC;KtsL`y~}GPZx?b*zeak{3wq-sqQPMQuGRc3C*?7j|g5B+#V(; zT64=!@u2P7jTdJl93g9hDv=iw6*VgYP@whXu2v;2*2SZQYH|Ef9dA~n-MiZ$$%|f@ zB&0zNJx5Ds&uXgyjN4`3bTfNb-#e178=L1bQXwatNh)phPAvMqw{HtG#^{jQ@xjF+ zsNl!7+Yt@d>I!{^?EZ&5%nEoX!`a(!dukZebz9Deygbm?JvluX8(rW?mjMdtJLN|z z3B|8+nfbes^7k$|ak*Y)>)76^;wcQM<+3+n2i?w0n@xY)WEvwt(_XHlJ^xtFlZen> zNU8PUD4(Ec8c3ZFKHUEINXQ8j1s3&e!TNX#M+>-w5*s0>sgYt<2_!7;YtI9ls~VFj z`!FXxgBswrb!M(`@8(NF9q|+_q-{J0=I6;#Qm&qSG|x za;%FEh|%HMvm`*mP>L;u(zz{i&KF#S9axmN8>GEGN4cIyPr)g%?!}QRY#8Cb_jIj< z=U5f3%A{@LnU8C=ncBRsbWR`0cb4$0mut~qzLxWs{OyuSH$Nsjo^PR#*0+%wqM30$ zY~7R}?W;)rfif=&V}ij=-f@4Aqy*&YgICvG-ubr%n?Jt=Y>8Njok0-52;-U{(6_1I ze9so8em$Vq+1XC;5PgpsF8G4)URkQ%BsBfZYb)K0ahWRjp8hM;rvzOeR62kS$M_cN zu{%vnABi_L8s*(y0`rfwhmu*V8C~M@oAK<@{Tavk#2lc`8@aGMDcZ|1jx8?M)fEB# z?5l;TMSUl@J@=8onpQ@XMc~Hyj*WV^ZtRhb1_6&sbkB@jek>&^>jx*E_=0NY{F0A_khW;Hc_B=wg*ttqZ3@C$?mUobcL>eXZ;4r$|(US44m ztZuJ@ceX6w)=Aqc$(y!Z@^ObV4GUK?Hj8-7W&<{jwm@TVD*~H@K2YxSqhsX;b=bW6i2uT-=&7 z?fDvZf!b5Fe`&uQT~NOakH1z})~t4$Tu)AFzl zi{$oDNo1W*L$Z$+8im14p8p>g*y>yTE^K9tve>Fcr#2U^p!63c-9enYMR~uQ(&)&1 zZWPQ13(fd^NG)GsjUSX>d4u~>H5}@qDaOfcSlSEh+R}Y78Ch5O1Nx27-w;KPTDYWF zhj8Z)qD+~OOv z`nFF^!W))ltOE%=M7N$hWJxk_!r^KitlEj=ah5oLxiJpw0dLu@HUp!pq>p9t8c2*0 z4!S4HHmXcHx93wN9pGM@T<78tViYmw@coJBtk(<@SL!juVO=EjzK`)#%^9e- zo4Fppp`p6zd8J;+JhCLFF+R)#J65~ApdxqosH+wQR{fM~A>JPs~-te0}#F3?)j)E>m6H>PVnSM?VIxf+@A>U&d^>wwu z%~lCCK%|V)mDGH7GTSK$3$QB&E}5J$2UTmR%4C)&ye!PQEOzWgsS3|?Ev81sWy$>= z>~6Oq-2rKfn$G{JT-5>A{Z2>h&PdEW8#^fz zsGm8xnkl4`&uT+oo!^h83HhL=s1)fguAseqjd9}zA~1w*t4m7BgCeJ}MsZ-Wyyp6g zXekFeUhd;`x;$%5!gV)ex_o#}inDz2%!BIdgJ8hiLy%}lEuXr;*E2Xh89w$4OpL(0 zzo%6WUYh!D>LZSv@fKkE5&O5Ig*@uzi9E{ccmLMmzjNdHCpXJ)1xTOj{(-m?Ns-=H zuTIS^s!Y0yx#_B~V_O*B&Ko8GOMY|n$faG(R&~FiBK6UjSQZuS6@&otV5b?=?zsIi zDs#rMUlmlutiO00*BqnEG&`fvU5k={IOZR-J@Jd6B^MPX^(D}8b8D&8r^LZ13Z&Qb zQ^bLmOITRAwa#A6pIQLa-S$lsAx9z^#{@gv$G@LSQ;lRlO_vTQdaY$^wzmIrH}Ba% zblIZP1Em2MM{;%Zx|vPuTnzZi<2T1)-(~MDN8iYVE%>NcXJ?BtFmE6F0ovi}^Q(_T zxujf_gGq7g0E-+cJt&piQKH|+#-PU9egp^w>;zn6@HirC;Y{VXku#+rxhSqeb;kl1 zVBs>(pER5=ydl}x_Zg|Ez7;@($gwFk5ZQ|EKg0j#Vv4y{;|N$CnDy@Ua_Ej3K)Fw> z73w@h`_8IztA>7~2{(IIsC70A`!9)q$6jCm?`O4+sx2OzB!&?UJt=j1N&<4-Z~I@olbOcccq*OLKjG_z05) zC`YcSNUWk+M&agx+RV6Iw=E&7$?j)6gp>V)UFP?ty+B+*+PMuq-M-e)$?4}cjUh4v zm>=KeRtdfq&%5R(<2J`{_3W9_0j-zB_Qqb%vOO~i@H5EI1>QHuww89`)nTRzyt4U4 zd`BYz3Lc2sn|`MYTJ@*Sm6RuAXP=Ls*#6)u|_- z#@iRax}@Qrd~vsyn6HZ#X+aN-~5dYIBuZZyI{>NTx>Jht&E@>6q`bCH-QLXm|NTij8nO zxqc6&`<8I^0<>$sXluFZ6L>c6AbIf}R!{n_5Bzl1zyrz1bgRjme)S*p4e?_4b$AM@q; zwga~Ev8Gw>@m`K}AE?x((BB;7TWVGn9?eu)ef<_HGWoO!vJL$uWYtX*Z7?GTpYCwx z=ncj#o|4APA)PK+6`afoir}%7U~dh_!&^^0V3(oB9Z`-9^cGUKg_f}Ca(QC3*=S37 zuGURfuMwte*RStpAHxI}g}A2jIlI-LF%9I(P+tqGF@L7Cwib6;)KHI`i^FKmktqV+ z^3)bT&72IeO>vmXQGj_g@zKj22oDPxz?_Y{eehf7q@Ls)EDJ0dtrEbg4!h+!NRCVH zsvgLfdfvL!MVCER<{d2&YTy3nT(y(s*(Q=)5 zJrH4+vVo7Xm1!KT(+;B5;IWQx)WhhADt5>@ZLf($=9PDG`Rc$65Ay9bb%9^Q6C@uK z2`S#&$hj9Px-IA~4K%zewD!iQeiyqttUdw-4j(v8^6wrr5KjXD)d=Z7xP^LapNANW zVtjf5)>`H~uAeWj`}ARhj}To>sF>r<*0j+Ka7P<;4j>N8kd@M+F&T*L$KY`tV$M%S z!4t?r$_!bk9efTuDEyLSPb|PKHiFPDlJUxm=)gvydP|`Y!6=G%aErO>d2LFjx;T^B zMpGuXx8LV*OkyizPaPEZ+Y!BN=km=-bfEH)1mD;Q<_M`3J+jjn*exmEx?#cO!`mMx z??`6j&Ht%jlRRfDejro)D2+Mw7G3*fI**sVC^}U8oSq$&v)jwzS|xYTI*!UDE_#CFvQOT!nRBZkrbWXlI0d(Fddv5$IJtMU(4;i1a zRn#4di%f_R;EkDh_ausuhAP|hKwCerVtgE6?dQQOq8P6Uj`TH-uqZ64!6wU{Xfki5 zJ=C}q4|Fbn0$W$Fmk}q~Grr&QsDG1bKxTAOr)?3{m8?z=ZjaRJ2Jj{xU53hR32|-!C z1U+$yzUM_)%E|?0f5QRbABu;3SqJJ5k0nVDQoZ)?G+c}`C@r}-U{bWbQE(p^pLfo^lrotPTwb=9nDS$rkpa3EqwZ{iVV>YtQrRx+|hJCFD0ZO{9`Vi zZ&8tBtvJoLt_O$8&bMZ7IB$Q8cpn(J;1Igm3{XyR0wCGN^xfW`A-30LWB1rzQJ+45 z#Va~aRXUPs&q2ybt;b{C@r2Rzvs7#-s^`Q%^ZM~iDC<4amyP^au|cCo5jW_B9WqTl zXo8s%Vl@0#O4PjJXbv?MbpV3Q1KnhN4SR}+rbS);6kkI2>LVJ=Iu%w=ghM!=1eQXy z^d+s;nJ@hPm*xhn1-zyaX{+2 zGv-rEPX&drLOD|L1=rfdI-mVyoO^V0JznRus$^_R9(*y*s)gBBO|6e()dtORuHQ~{ zgy^~VN}0#Ld-u-gfP@yK$L@2b=C7|!>L@8a@H`w}|MJWYL!Ojs-a!pMG?h1*g?P^_ zJ!3|mkmM3FS4aFz8_fmSz8l1-MVpvf{?KQ=j=(91^@C)m2YI}OEE_MiAyk*cP};j8DYCFWzq>` zzv<+<+<{u?@;f1zvVC+sY~83xg((ORf@3ey+5fO8yx3z-n!Fb$l3wrP==MphU59A+ zm5q6q3~5PLuaoa_q@K)T@9tKZ{@W=@f&t$*R+___|nW`K^+3QbX)ipcleJvDH(Sc-FY*j zzjzRX-&Or>6hd29O+fT-1OUO(QTvVRq?`#R6HJOEt%D|pqKa7XT09Mg#Evwn>vY>; zrv@My+r91+EelFoma&J<9?^^j{-&Z7!&rK=tk1M_GS?k~_LbCi1}<2(pq!}7*HTr< zorpC3K+G{7-+ge!^5wSEV&$4HiVs)1AX{&xHSTnXYaeW0wr=NksI^vbQNLfHLrKA8 zQCxl}=bOK!{QPs8KH829`w|eWc3m>>NwknNNgv%ScwP^I>*urUKFgxXo}Ap+xPud(14;rU{qW z{{`6-M7nuys53I^bU{$-6p8qb!W-y@4Y)-wxM}}nY z5H2|=gqhpy?^|UJy%1rfEZ7>(ch)!^@&fZbV0(|mT{M96aUe!m=hICPvq>QNLGDnl z=|Uf5d|OflII0%0_w68t`b1-u2u;tf zN!xDXAG3!->7m(@F=7fZH`6vZVLR4KHaYlldx3ya42qdW;R$&9_6*VgEt4eK2tzaq zGqnHoD_)Bj(=qrb_)x8x?&?fbK>zbdhy=RgI`YdJOLhJiu;ZeYBAAoG74+-#N47UX zV_7MZ@I*GyWkNxr{^%ZiR=A02R3JYzju z3;T_Z>r%W;=`~Zv>P1O1Qc~jzXF3Dx?4X`p=R8w&Th$ucN^2fEdUtSzZ?mRTHwk4U zij6%rq?h?xO){o(Xt__4s8p>fwylLXgSi?(QLq(azYZ$WO<+5`5{~K-H`N?AJ3W**>i>^<^w)f7RJML{`BYkY2e~tKeXVXw!_0-^lyHc95 zzz+~VQl)x_6RupLWDk1g5hM=0bi*Zl#`gFDl%4m`?@<>nQ8HS?%t{h|HtlemCn1SlD^#7;f**|TRxV+nwMzyKS*-THOh zrK%=iB;%N-N@W+bc^=#gIspp)96Lp&GH1sX3-6<TW=r5nwhMR`m^Ny_?q_K`abt zUzX=b`d=cI!N#3mNr*+X@M0q@iH>zapZ`0;>D_@@`pLr0t5dY@X_Q3%rH0Di@MN;A zGX$@z>9}QDOq$r{z1z2cLKn1(l{NI4g^gSrWFGJfCvKd-4yt?A>bVtRp+w=?Kl zKeN>kNNN)qk>u+Ya1t5zbG@8Q3wc7_b^Y;fU4h{7_Y0o<>}-gqR6BRe{2gEa&O0>Q zNj&*o1al{%{UW)+T)ipIFN?ZWR~v&YU{@&Q-1j^JSE2}cUd1E1GLl*?8I_0v(aPoZ zK1~pf4CEoILv-ou=(2fg>@Lb+p6ps9R0{VfDemyV1{lDaZ45k+aH61uZR74Yctx9+ z<8mH_^6T`VnOY_0RYtrSQ%%bbAP(eUuR{3>D1YEcW2tepGJ34RSNzur#Vf_BtgElx zzI_j7Sz@=l@BrXpRE@ACbMC7EIa`yD zJa}WOk^7k&E}j)!@z;*&J6W2fdc$Tvm9(k>I=aZuZ=p4Aq)rIr6e7wjZIJl!B)|pk zy*{r3-gEZmWBS_7=K%6?3}p}B*4GFg;|iKRs)eZfA?2pGPY7s#emeuG%O>U&`rY1f`j@L#L+i54FsKtpY>7GgVTBa3Rs`r5HU>nyiwTQjrt^GVxnc@)S5QVeuuPjepv{XLQr98}Vn)`yT92ZJ94QZMT;!$NSMn={yG=L_OW)nr6 zU@Tv?agiHfXiIvXp_8C=nn(}!CQ()ZB`^ZQa@$}QCGw}4lvJ2lT+^V2U#z3ce)FD9 zUQjttU;w#ksiPi~q9%nC!g7x7>3JPO)Fnv_@-1R>di$T4wTo}ce7|iW*?6r%`cYlA zZsUKWEea+#T&&i;T`OQ|;7MKZRQUl1HoK+?n$;@DXeO|pzs4+39pgVK-$Ng)0c?IK zUd8u0`xw~VQ{F0ky1CHDo*q5OM}O{9P{pGu_`t1=t5&$dA6~%A*Kq)nJEKdF$pR>V zfy_#}q1kA#BfXB{xFd)kcBo{_G^?t+(!sr*j&=VDxL3I~bUkatR0mfI6Lq3=?+>7+;i4v#FsKbuFgHun=80O3YTz)0u-KuJq-eSre z1f0P}Yh_t3>zeX0B~dR8Z9u@EI{5m<-@`t>G)k3T%XTY5p1v1h(sC?~SMex}Ec5t> z!+eBrm_GzYhW*cpV+X@g+-RrJ;)D5ygrX`~U>}Ql&qr?;m}jyMu>hh70Ff|A!fvoF zug$@o?w*-|oJ6KDUAJ*jOB4I1xJJTzd01s;uTK|hoYfzn)d5x8_n?yktUbUMB5MKz zOee8=eP*g~c}UlXz>h~qG2MJwApa(a46@PK?u(((UR=j^L(EH6mx43GU>Y>^CxACB z#aKmbWI>v-XwuUUd)7QCyk#Q?LnURVzxUx*ZMd1Co~qq(12IVn$Ut+WaNNcj9HiTc z$*uaju)M+LGhEpeuPbKDe|VVRi%bNkl}&8*HYxI4Scwtx@usIFf_v?>Li!hTfBI$r zJ**3#d|@mVzOiy)68xPW$7$AjQ_tV^#0yt-C4OOA0Krd@itH%|kt1oqAIKAdY-BH8 zr%eHD5F|N`p4XzS*7LS{Nz3R%tpXxFt!Tl}(0oY{V#;MUvTQpcq-x{W?{$W=s62OD zf05N5gSN*aW;c&!O@n^n!8``Zb`Q$QOe{6u=qsyPP#)8(AQUG#4Qu!Y;S23vOFLki zuDmMgaJY@`Hd(%oXim1UNJiqBK^2#evPp&QB#)$JQ|gWiYtv2#-Oj>wDpR{a=qP-S zPoT0g4r^0jkNRd^OFPT9HRW~hab>T^?~GI#asi4Nhs7&Iy0eD$P6@eubBtu=fh$Oq zskeKFJb_<+_Sh6Hhlm$MDf%?v9UJ9v<7L-`iO+OV#Dw$zE}1?5g>-)p%7|mQDrwJ;qk%}z9F@;crlQ`_Yj|6lq9L;%jBcDvMSiSD%sfm5fV0} zR*+WsSS5}d7YsIUr`-^vn1c7B1?s2~D!Wnkc}0D*@HkoYOI%y**SNX6!4j+kY``uZ zA~6q;PC?2jql$u0U(cw!)x~OB^FQ7-4z=nkBPj|Jru~g6v9K-XuwQzXABiwum1;zM z?%C1D<~bEUgK#St4bZEkBefGLpxDT|-QtZ&|8wFzmo7;TZa^vjX|v~YjK&JKEG>(` zoi0l;;-qoXmb@QWyDX6Qa^+luz(%a_Ht2679yg>+Yy0)^_TTC>o=p87kcUsH=-GLcvd^aC z$ip14YVl6tP)m|9s7Na*-v1%}dp`$-gqo@vn zAE`B+F)6#dP>YxsCQ5VCE>VEe6)BNaZ$C18k=ZesvHf-*Y~|q#KsP(!?<5!~U=q5j zJf>7@)D93H_nIiCrW6|&n*j)lcArYD)@kdwU4n0vzlV}}t7Axhq+D%x_qA)+WL0et zbAl7Y%&O+bFq>Aj?H&;a{MlnGI^Qzh^_-2D8Zr^Q3(`lw5xp32TJ{r%E@xOk`TbOk|y?45gZ zu5RDLz=F+>1BZRvm(zv|r~gk6QB6Z6qRGyW&8n`y*0}tlnq}{aG4^KG7n=91+1qs~ z==PX)+S8d}U$zo4dG2EDvrS`Fy)=xylgXP@F;2Cj3o!PSmBCL|`g7JqU=9%^nIqi2 z>^f5Rlgtyr2}ZA%lI>F&xyiJ%`%)|Rnr*O?>T~Z^&Mw(HOlJ7cuU`{8JQA|;04nuk^+Pq zKK)xPBA`Dj`aW;cikM&(cMfvVou2?*qr?nVIPZqF1rdL)cHOk%?XJoNr*;}TJkAK~ zkPQGceplf0>B=vjQY%Gwv0eO*=YA@g4*Nn>52uTV@Gp8Q$CeL8{ZTLpeQ!(iF`L>u z(Jes?C~`25bALv$d8VfkTj~vF6PY(`cwiis+(*pk2gh@%qvP5?U=MHv|r!_3xq?9O6> zy7jV$7dYhHx3>_zkU*rx4!uB;exl0>=Kb7=Cnqu4^H?oGFUQEYfciOOxs@|&qk!$V z!zso_olz_tro;IJ381#otGE6pxJE`SS+h|2(pGB?{e47gRs-w7xkDT!7SLrd#7NP{{qJDEa7ym5Zbf zx2TU~(K0gqIzH7324RULU%ED_&Yv>|3wG$Gn5s9qGe6SDYt3=^(K@Dn)ex4E^}PFaWC>;oZ| z`gL%x;|>vAEvLhhL;5MF#7dxBDi@N+9A7<%;Pd$5H89{m8ud7 z=EYuHo=w4wzlBA3C!eb5 zZ-jN>m!AAwx2Y(UyAX{vNWcs+B^ulB<(;_Da@rmdb#>FUHfaNx6puZ@iWo`M&l zXs8H{K_=Z)x)u_!80|i}?r13{y7c?oPpaik_VEqxpv%%`zYDtgG4(t5W+|Des|o?) zwhSr*&t#eJi?VVyZv z{V~xGcTh`v*{$6N1{JaY2QNL?Toq$BK2(ub=1*&0+jDWyWsZGo*i#X>%U@hzWBQJ8 zFWb1cmX}Mz{@4RF%)x`_E_5u-uJJ>AVa9*HRn?fS)s&1$LHB#;;SQ@#Vh=T(aX9yu zkIyRIC&okvWmY;Qm;50~Ok#^Ay*B_uKti+_p-K{V;*fc!v#InFTGwi>!}A8@Bz;7Y z&Ggrc>la3C7u6&+@0Kv!-D3D#@@*2UdvbX?c z%Z-_uz$LC<37u^(RhVj1iWyJd+-#P`6k2*sT<5-tmGdr4Z244nOEQs{#bUhM;BJ&8 zdL{lqb&{c6FO~|?W>sbL7^t64YhBzc{;c(wX;t|YS{&uAx=n<3(CH9j@Z18`m|B{p z?r=stn-iD{a^H2+YU)Y}+ZU9C65&!lglw~s z+TFoH60jGifJr4M**$0YGP?Curf|;v3UyOfw~?b2f&9jy>&mYW5aU>S3sETzo^?Im zN)}+%dOX4N>9P&+G*EY{^XPYZ3f*nckO|W-lujb4Res$Fpr7*c5N3cX-I!?3aLzic zmkuTAeu=H~?ln$F^DkUp-d)w>;*`@i-;B>kI4^>kGQ_WT`(Mm-8_Cr685_1!Zd*ML z<-AJ%p@-B=XbjC`)|y&Xv^7EQs!{}ZxY5*jEvDwUWv7XphPWiQU6q}CL}gbzOqR2N zNz&|4Q65X(90nOz+Sn->04F-_Pz=+?M;`$v*hxx4{I$f~geq9-s^&}ko6-`#+H-vn^GeYJ>-M=%r_&xf-sF2l1jH~=v9F<8Q#5{uB|)6JRhCS4}=6g78LM8}@$H9c1AeR%=( z&h6Hj5a-}{ef<16|9j^Wc;s+3hL-j4Dx>HR9pIdFk2wBZ4gUG_9LM>bu^%X6i;N!& z0l|Owlz*~`DnPTbyPSnmY~xgd1_4Jde*+b4Ukuaa)H8nUvX&m4Bwl85S!m>hB9ycY z;3-E7AfLfU(1G~yBE~2k zJ2!G6e{?SI3S}&m#nE5qy8-xY<~*Ii$U^0eRqX4unx%AywduRvO=`ZwNhp|MREA!h z6Y1rLecGj;uA;QUU=7^%yMU6;u=1|Et|otyhS$qQc1yPPA9!V45qXwt8(q9v7EDbq z^av$4g4M~J`O-(&Z6=w!wePxG=F2st`Jq|kg)xpKwg7Yly39!K3SYp#{y#L^?d%kB z%p$JiR!tS~s^P#Km$s<=6L47caax_48w(uhXA;K?PDMU`j8li%RHRg$cX0eZ0npba zdUohavhAZ1wrpO{ANBNcWxhTx&=gv#`nEXDPKL_cJK{H*Jo$lBM|N1Lw1?ai_QK3l5g^y5rO%H( zzA}yb(A9=M{XRrf@5KrLag#M^U1nOnEitEG1Z3M?tOEl3#Uf!SEq8X(Y*5J&4uHp z{gP#!SN_`d@SCQsPEUoVNghflVn=MUt~{|5 zNylPorD6)fxpU(Ko59VoY=Q;b{J2K2B&5PnKgU_9)f#MDE+jU^;Up1K2cfaV0N9_5 zMo9aQ@m`|+!ApbALth&OIdz{N-qeeA0t9gpzsgYFU5bqKK)^s_#X$}t&H ziUL#EzmdI=$0~Fm<{r}Gd(dOn1ses%Yz>S7{Xna_uF(#kh&@w%eOt(=!8kpX2q35~ z&hG(1ADJ58XLbUr^2MiUMpiA{H3q$h7%ftg@!HPqUIEU-J|WL&ElLky8I;Wnf^ z1z=H7{TZm!2J6cGT2Wb=x0NdvFjFNr0@~P0G@2G!5b1oxLD(-HJ6ES0`?;$)Kn}|n zhVFc|B|C`oH&aEchV7hu#0)M+|KZcHq7{fM`>1tF=h9$i%#so}iqR^U0!V@$h6sA= zVRZ$gT3y|Ps;8=AF>(BGQEbFiDYdF50xxrDUj=G5Lg_AG>|e&6`SPxCj%v!q5lnOa zfqiDRot#&0Rvwk)d8ozc{3t8pAR}($-P__{s~757&nX}9k|zlph9qO}Cq{*lkvz*V`8W_`t>iah6gQX5fWKY=8q5FwN`&u3_-2=H`ZGxH4 z*?olH+?&4N!(JEGw5z7tdR-3h7m$ek`dl;#+3?*sc(CRC$L(q zlTZr7%nmxv7ans{ZQS3KWMBr1I-ayc$#j5-wJ>zOX27!BP@1iVNXhoHukDU5kkB2?H)XCz zkK;eU!n|g`>v-attw-2ux*c1sann-2l8suxvczp%SCWzF_+!rl^u(s<4#th*1;vL@ zJ3R;POMk5SlH1b+K(s$uJk_h7|$w14w#-Tz&xv#Q0IghZ^0}uvFDM{}Lo=@?W z$Qq~T>F>%E1(p--H!-B&_~nnS!iuhlJ;GFK+x?(XmFZWHId07oi>3FsO_NJ`dQeS} zweat{m5rCum76yv7ysH3QWV3eMSRR96PFt&I>SY-i}jG^ODhZJn0QR=a%j{Ky^`0GAs{59Myd?7)w?8-s^3r7~Cf9g?P?kZQbfZJ8P``zfz? zOtiF@m1r*RU=QK2mXglQ61&Q3@NCXwU@Bzzp~$)RM-PsL*_OIUl!W^#qC z=|IZNnpMRE?ibH#QElffN3*wHHOC2FzEKc2ue}wV$Y7-^$ru3AtHo-+NZ}bzy}d57 z8f|vx*Tx@0eKV3wuhLk>A7{Gpf~Y@th}oH6z|BOrJEPL)j;LfL6RBO?wl-=3Ja!uZ zR8gu(?tNYwv`Ypz@2u(Af)QxP=JO+ zZ7q}?dL9>M26s~c%~50nFl>X5X8b0Hxb(vK&DnI>`#+2d3aV^gNt-Oq3maG#vdr%g znXfm$ln|K1(jZ{aH#B%3AI%5}!*3e*pbS3ogYbR)!1`@q;fhngU_wI`n-3|85r(Q{ zflt$F%#-;@W~<_Y65ODj!`^|`VLW8V4Aw?5JBhJ5Z?TeVw8X%lRdbp9d6D+fW9}^nxZZ;+`mD9p;qSRpNq`kOv#ycwN?Dw zyZ_v5PyHn$Dx;Wc?|T~_SezWW;#P-)J2i%EbF?ri*8vRFEBOO*J$YPH!m#^>TlbT~ zc0u+db99YFo)h%p$2`_^cge`{TNoNWeA|!HBzDC3p!JL>JpbPuVxJM81*+vd;^+|G zx;(BvlvkZs;SR^;ldr*w-~^Y&X5uGow01p?3zvpQ$_R72XkYGR)RqVB81L~}KuT*f z(sQ&*J)lXb7*)-I8;|M&t$Ro-KdvOHdRP=SWpXbj0BqPP6Ot!=`k!@B8hBQP*KZJ! z(R}>-^TXgW<0mhIR-28`IjTrMzSCSOR2OIX{5V5_-X}s@x zayw`I)RFQ%sSkQm3HPbj-rNPcdC?fDKtVv=46;{0+v)a3;Tld)k&(0hf zY-y@F)pJ!+o)!+$dc^NlOI$P>UZ}eQI`kkAQwZIELB1iezMRRa_sM-D6cQ^JVY5Y` zNN0Y)0O~87@9k1o*+rfd2Yk2*6GLQjg*wpL(iCj!6hBY0oJIE#&72|ZMt_j;rO<;c zkO(4uY8yucSIl^**wDWV*p=*`nd`fzHworzYgFLCV3VQ6v(vQd*izKl zrkVXZ(4%NW4e&g4h?ipq6=VV>m`47n4rFgcpk4fll6^vGC->h4vpP&{87=DDCjU;^ zexEBRWdjtIi5Zadx*k0x@dBDP7|xEQxOYLI=h|J<^1brQsPahqS6OlrKd_i~3r z-mKGZ5z2e>ruquzN$25sbO$nJZH_}1CG$-wgA=Qts%{2uk0k_L@_zZ8MEnt;vSnv% z#V$W8yT{eIo13I-J@^1G{TNq^*URC(O264*y(XWW>1vMoCy}3#kIXHrYF#Oj@-izG z-NHjz%eXJ`#f`z(sM7K{6|&$D(+S-C?>mk5yYZg}NSB%bc0}-xWYJ9S^84t-Mn>hq zQsacdZRxr%ovf4l536S1coD-|WoH_t-ju?Tn{)rw_uPrDjUx7acYD`f_@atIVkgKd z4i4Mqogk)nhCg+w4-0L?Abh>5-A|W9s=txvEt@1v_%UGp`(Mb<4y-Hx8lw7W-)8}S zrcHBl@F^_w;C#S9@sXCy7707~YC3WF00Qw!C!5OKQ=LkX!W@lxml<}EB`s45NJ;i5 ziaah1{E{;7mC~G0m*jh8mZCL96!OR1YO7SbubW&_z*L$G4?Q&W_75^52wz)XwU=8t zh;33#EIQz2oxJMe#$30o-uS>K`<*H_o3SP%R;HZTWq*Gt z33@zP#$D0n0r`&+u8R8&fVd02Q9X@cGwa43lm8{H(>TczuKh0VM`u7P#@YOGM}+bM zgMZWFiNRH3l!MD(Xr~<}V2FU9#%Y$lmMjWsgN%EmuhAHDKxgn#xu&XKa3(F<#~`>P z6m4d`j-o!5EAc=&x#ubOZL>2YIH^si$ICosw_px#dkwyE8b7g-z=f-pC z*>Xqye9rD&m&j+6+73rmq(^=vuRAD+L|z={%P`{@13G3A*t$iGX@}Nv;>H03Zvm$I zfrp_l>VVr4lzigefiVTF4(RE6MoQPh`>5(G)^m6inn~vft5{-HNHSN)=nsC9V<>bV za!(f?Z#f`buoL|$;^(QI6;zW&g(p-jyLasn_8)<9j|UBw1HAd1l4#jgd#nB5^}jse z+AP_Hvf=lclk}tQxq36$>TDZS^;?L0@XMO_?jlH%tvC4?Xt=$wdF?CeD>scIf#x6_$*TiIN z{_rJ6E-D_-$mV?UCzSUJDK~lxAT?^@oEps6CPXVMWLwE2PDH4 zQjuJrT({dgXO-xXMrK|ryMwqh%zkQ`YvG8ia5>IIvKugYUAsm@BsMbpoF_dG)VbpZ zu;h+?+EZ2pa#&6(l}hG*Oitd6qmtdDex8J02#6WWyM?skW)S_jKTjj1r4|Sk=q_Jg zzqiHsIEv5VRwZaiKBc9UO9GrYt$s^qvl2&a4)#l^9lFiZn{oN1Q4~gHA92K01mPq0 zG9cge(>D zOf9+=1cTFpM9wgLGv(1Gf<8wXnFq8{5=4PC^wR0a>8nGxu#%7r2ZV~y244%kXV9j2 zck8K`*2>>VFh8N&lU*qd^+s(Rd>Kuewi2i`oAW%{IL-SF59tISpgyRvWESM|i&7cF92q#!GG{4iU^ zTL%@Z`LTt@T4U@c-+m&IP3s!c&5a*3PJ9WM>i>Z6Y<5c!U|L+tJ}gA<-&ZMbnepXB ztXB|w8}2g@+|K&pR>!X+xl=DTQQQIe*vPA>pX+)O3&zL_04_n`vj-_uepY%5%rrtQ z@J5-~<6i-{(99lH~27T=R;3w zogRs4L3H1a-(|oQC3+{phiALX!uTg$L`+@2w|n&{I5&=TWCLkSXDY|XQ~4Ri{Sm6I zlW5Y~Yn?Q*oFJx+48?5?073o1cj7}1F+!5ov$v$rkY#j&NbC$G0~ND}_i}84}IJJnta2-kDcFAg=Lbxqi`XZtk&#W`6tZ@}uSz?$5QkxQB z__-I|DAJD?+eZkD47^#dnn1*$itV~x$0jDylH4;Gl~`d!B^zx3qZ2Cm34 z%a+VDv(+Dv;_juWcib|4W&QOK*~6Fp;fc?{FQ2=j5!{sAD5YX;_v|CJndjqtRFR!f z=G{k!_V9e4ivS+cUY|zL41Uoxpu&^gY{;t_za36Z-;07YHV}?;S2d#r_I2#_Si4i_ z1oTZNfeb!C78tG_4M&OcIE)5BQ;Gx{48FiU(;14uE9QfY^A{Zz_#vh_5 zw-g=$0vLl|zyaQL1wObDpC0Zl3pgh3@B;PVb?%n_usd@hyU!?weJbIc|DW$#Zr+lq z?hdE3fS&j=3u1PL`Es^gdh+UN+`E$KX4JsWM#`}(BA-S)+GqXRoAE(&Jdarpgy9;r zcZg%Y*ZL(Rg11m&%T4Lw3>fY|L;E)<cJoGSYpR`+p^rJam4<4Ztg#uq%f&O=hDn| z`oELPi^nB>-yk)oz3Cgdc07(_Z49~DIm0hD&VQ66ONc);@CQ2@ea0eULoBJg)_Q4B zK5&w4@ZY{DQyrY2jy$`edi>@hPxXXSc@WR8)DOF{TiZnAd5Xg1Lq(N()#pS z)*i64?qLL^l~a*Ej|1cq z(oj*LO#Hla73}5z{c_&U3lM?$%4weh_Dw1Zsq8);etadroYC#`h!m8lgzb)}>nk%7 ztc)dHUW;^@PAv_V1PDy5WLKV|-z0h*CBP=*kL`sayBT)!<8&IV|N7v zZz5VYS)reX$>x~Pg94oREbSs*LA+@g@tm-1%iV#KHP$S9^Kb3pq~O`%z+bSN7#RI7 z+~%7rPcurK@q2*$8bx_jf{&{`J-lPm%j}u3f0N8;=_^Z;r@SQBkYdURfRhbUkMU>C zSPd2Y%U3%x0}Ft3O=JLSDW8*Q;*sGi96kGodGY^tyo|YE7J$-8 zEhB$$-=hGAvnTVj#Q|cqT`-bX+Y zcsael`rC$IJ&n3i?kl&kzZESamN14N9|?4zi8rNqhBzHy zt1Jxbjw-Mk>kpI8+VC9TqXhhdWCN2-gSVSO>ZmVrpJlGr#VRPf&{qjD>wh@WW#BV8 zY;k}81!^24@5>H%!^~cv@E?(sl@0EA7h zyL5!E4QrmO(An(xtb&4s3wEjUvtxa6&-o^;@0=W1;lGq)xkiM*W#Y`ZKa&{34Lp$L zWK>{T{{5Uc{VM|;t2>pTfAm3I@+$V_Gyxr?;AUl8PFI}XFBk%9-@cm_u+Uc?XeVHm3L^Ba~psB_uS;>L(0+`Aa(7F-`Tr#rmi%uQH3XxHAQ8RU#)_=#I579z>Eb(Bpyx z&MwlQ!PZ$HB2`0p2ZGNjxbT@siAUs<=?7yTOp8t{f#(U)T!FE6c}7;LG#md6H0H8!>S zQll;J9VnvqFs-y>Zdb4;&KsvenAms`LVwE@8g4{*do z0-@&?iJEOEuSPguAaOAW$MM{qy1$D)AlPrttmT>aK2w}9N6lft3dcUMOw*?O3EYIM z;;VuZBGZj{v)*Xt%l*1b&PiY0oBFB|#a|*!*R~+x*6hOsjX)OVOD_=DQUB1DtwqOf zl2yZ{OOd1^Q8!&Q`sRcZc zmPzYd`GNw<+*KHss50%5*BksO@c)5ylHbe1RjioeEFZLF50&h!s1o z1|H&N&ZESM$1MSZ&w4l_ zn8?y~36%kAWRBiH_4|4<3!y$)^df<07fBB!SO2a~Lzm;hZJgzpmhAV(I)0E*N3-t; z{!*yv4Vf31JvA^#?f*<4kXQ-zfrH_l2h9%Qopch<%7&D4nBWI+nA2w)izXcfQMlkc zf>r!L?u0lPCCLn@p#C^o+<1;@r79~28h)CcMi0hM?bg9veklG`L$#M~lBLU{3;MsQ z__Ph@g)t@tlT?jh9CJzlKlVZ?8D(c3>n%ctDV7-6nTG$aiH4=tHT=2Or{SlL=LUaa zsuc@800uRA+w`yk%yl%8>9Ux4sQS|(Y_~D&I@K*~FKSVehZ>NLEXqVH=iZ}8z}2z5EVx#ag87f=^+W~H+TCtTZMC(TyRIE))08#s*NmxL%%#UsAr!Rlpz zQCz0BY+0D-H)p;MUa#yw$VLWcK*x+VFu$2KQk;amgLLA~-9W%K<7Dl6Zm?pHiHn(! zf{U)u7F@A_f=Ucfb-u?66vN3%#%L8ZI8n`m+j6Pd-EHY&f7E@kRVq#}^|=a^ zCur_LYat#|6YQa%_k=F%z0aeg>_o^rAC+$&?9G=_P{jA|x>hlTISQ_}hEjV7@Sx;nS?Qe>Imlgw+ zun`w7yO=4Gk*m_NfVipM!-h4xm#7T&Yi|sY?MSdQ0R2;o}SAH zw%hWYyV{3hes1Z_^- z42_I}pv}88I26{Lrwp_sc;vz?SwA(UXug-4I9f3)Kn#ns>`RS~w(w0pPpkfpT4&N$ zr+kf0*0!lWRv8PFl>CUnA1loA?fJ3P^xbe(4XH`1Ot_$SejI_rwq@{R3V@QTQ#ulV zGov@=8>N!@v42sa`3TYzNQq0j8ObqZ_8V5`#(nX6-f7SN+iNV7R@TlDWvD=d#joIW z!)$XCG!wJNm$i=!GWEOmJ-3-a4XXj{ZrvFPO#2Yro=gXEQ@cukV}}0ECs1I7gHK{H z77!fM4nD0Ys;I!`qQriM6JLy1qpxtfeVbv}G?OX??&Hj2I|MKXiW{p~3#bG90_cZd zDpyw{#YLt>sPw^|#mHfKQn*mUVD;yF_WzyXz*8x_V`}^VW(VYnyTN{^HGrLLzi<*F ztsCpT?{+T!eavnn6e1l3*E; ziUjv1k8^z{cT!y#FYB7ESpL9T_X&EP2qp}o9WMI?QbjSru?)jca)RfQ^*;rZG|x=0GwHw( zfmGs4AKE~D2#dPbiSlIBkJ8er2a=Ei!sfn(TOHyYyV7*m62Gph5YBEBj~s6+y~_G-w1~hn$Zt-hv27*1J}3L08NI!N<|^t47K5>%Uw{BN?#B-e!8c zMAL}V?0;F@|4$K)#><~eVuLpfjP;jmZ@bpKjCn^cF7hRh1i3|}mAJq*Anyo-<)KA+ zSZ@9XCC6zNvS5Pkv4@|(ELgZW6wOH6^yiT@0@NV)Cs=AP>SiMQg^-?g6d>b&qSLl? zyW3E^A%52TnVuLbxv=skgf`gE3@-I;Vxh8jds+9PA16G9`#Qn2gp;MPOF5!luDGjwyuV=w z3^Qof{b^U2nMplV<;23!`yle4;spW!-a+}X3+-FCi3}^HoMn}q{Z%Y7)aXP*mEaV7 z$8~t@fYy1lQASDYv(p+M{X2xgHrrkm-M32#VdkosP*QU{{Hh&y$v0l6CwbuFaiRb* z89EPi#ZcljvLfr`Hk(I0O2`MEPxu%ZqlmpKnI4-VYrdJ5W$iWTw=UVL6bZa@XyWs@ z+%_nt15blp*i$ z#U9=*pV@}(8Fc8S&BqMNS@^YLUVJJM9&F$h{~+)k4Z;gl^It;h%@bYGtK9<#+GGVz z%$htq6z?pZeW(fRv`*O5yKc_VYT-`X`KtdJO> zTseam4vo##%#fZovL>A3^=XcPD>Q#5k&j-^Qm=X+Q=S*d7&mp(1COIcnM876Wg;5A zFF>iPWg|*x)n_IU59}JT&1)R2MYKOKePgn{H;K3S0Z>5{z>zIW1WEmC*g!BXfXS}y z-PhNToq7suE?$UI$?os3=0y#idoD%L_;a*j2k7~=fx>aGv#W>N$Hv67PU?_wP1)Xq zHZWY$O6kIGFcm~FS6dpu&-@p|QvN`t_E4Yh?;m&L$ONmDx9Y5NCtY5nGtTA*Add|T z8{Xd--|+;K`=>rG*(9&^a^1CS5@`6eW}2;yY~x9m|443X0KO{(^eha8{iY%9MRoMV zPgCJMR*qE&d?aOyAZP>hF)_Ag$4%S4H;s7S43we8lktTFu)@=UFpjwJ{rFD&{a9Kt z=!65OCA2<zPTPH6eff7ScBZe0C zXTT1qxbrXYm2G8wK@dqnVILI~?MHri4DHyloqBb5k9sm1fGb25L!!QCii+QhA(~_H z^ncxH=HEWoRZ{Awme!h{wNQ>&t{%MV-Q60Ds!_XIobj2;#9UfTEUDR`CCf~ZDCl6h zqLGhtTlx^Z0hFfudC{c?8DyC@^A!Ut?|vk@_)7h23)Uy@3m&0wThA_sc)lv)?QHQh zh6?ck6Su{2Mt(l{F`6cYbztM2)`)1(7xa$q1$cWU{Y@gwWTL0dvYOEPsIdw^#;DMC zx-}`pE-VWLadLcK=4&87)*b)E@M*GWhI08cjDRhB=-|Cb=M}kJewD0r@W|yt>EPBs zidNwzz|kulfA0LB(8ir&k86fN zOd*O)I)dbJhW6gIepp$`pb8B|`jf`W@{vAhDD~FmqjGD+9K1SSKIg)b$yt|aQw>a3 z3sAL2P(nQxnY9ZL3;V5Z9&m8i0~aV<0&s6Sy4QdL+IUrC5o2S zM3OidLWc!B$BoO{3Q_KB0&4YMx1{MWxO0pZ@7mef{Ez$VZy2D5mqs_4Y~%sGc=B`V zwZ5JvtT4P~OMTP0i@UZB*Ie?uMOQvMVP*o3+vB^?#=V$(ChFFwBMKyh>Qg+uXHj@0 zEREjmdN`tQ4l*5@KwJ|hZat2mlhq{hCVR0L+`u?9;RFDTkl0>Ib71LO;b=&^?Do6B zouh&x$rT1;p?_o&@wPqfO_O+DxHF17zU^md=jf{kT_vzKn5G*q5Z7An)UgrHDB%j8 zW6w8^gmUjl!J3F=$a_uJeuu*6Eo4NR+r^aC&av2VZ1&R2K472vL=Ht0u<$3TPw0p? ztJUA~I8*)m6jZK9joa1m-t^yBgC>X3HnJXw`pyiNHH?AM$Q0wxE+@W$&b>bxBcE0z`&}SkzLX*E3FsNDW^FUdnEA~co1sKFJ{_f1^nu& zjQb9381;WLZPdB`_`5nwqTba=8|)ooCBt zArHO*4c`4@+VSN^mvmh8qQqiPB^ZFeRUy^yrPu8}dbty0zcFc1AhQBXeP+|Dsi+rM zC@t0o*Eq2n+I;ccaMf8Ojl0Lrf06uAtut4J6&1zaQ_n^~5%L4~+=9yQ|7vb&M48rY zK3-+uSa=k*dlZIE#+%&=5AYUui7QF$tYo2}SBS){_6c_sk&8tF5MR!_os>Vh%j*L^ z0DBKIvTUxB+-FACVEG9JMjNHGd6`(>Ocz`&K^8pRN%o<8ZZsb?%d_3Dd5a)i_+9G` z08F{Y|DGQbKgyM?6i8*tM^+;uegMnJeM`!mb4%4Q?#{B^VB0+ltO@~x#edq|?ly;)68Gy(tql;sG51Y1grHW${}nFH)sQv0d3iZ1JX@7TzK5zLkEVzcCZ4Aa!sYheLyJH?Kk~DU5Y=gUn}r#5c22gktLC4xC?r<_kWB z#D&y~nY{2)0f!5wJl9`poLCRsS{PlTYmqr{w6=Tv*^fPEOVBh`#f0W)28C6hv0QeB zft))|2CR)}L-%u8>^9%>{=t8oOcNehKRm+`g!oz;%eJO>`CtTQ~_nmATWt{tp*` z@|OKaOT`?21s1FF?8ZDCb>a_~t!H|_D5o-?U)wQo=ySaMvbX2%ZJ>U66(}r+>eMLZQW6b5U+{Zy!cvqe{xH5*;+B~ zBSJs|!dvV`LCM|mq_g$P`h4HJ{Dlr1yb!lPzG#q>de7vVBFvaJHs5@($+cCkWmikHbP1IL$3be z=b;b1D=@~y5o2p5nvT)a5uL*z?jq$K0=glBWR`B#WWp=F^@p)R7iy)4fes zTLi6zFyy|mvh_}6s~h3oQ*PmUb9tN3Py5hA*cx^qKsetiAZlfU(o)zY;OeoX@kz+X z1k3huIegoaM=Y9{FJ@F`)yC`YooPNb>bPSCK&D;@xV3N>&x4!(f{dY^ua?pOsg3Y* zN!U%LlO@r1$PAEa?S-T;-H10(m)0Jwn5MaBr2b}^)3|5W$<1hR^mTPbGqAm*%)+P9 z(^!Jy-7);5yV%To^PxrcS_iYQ%%oJOcMdmZ-C(6et*F=MRhk{sztD6P_^QWefS<2D^jR`0!s?|I1&y=}93>Q5&=ae40T zMq~5=p-5nHRzG4@7};)0z7=!wer>FbI^is&T{O)ngR^Ml(NnJWPpPntK+;-Qx5sv` zp>dp}m@5?Aa%O*z-^!vgj~w#^8TChpUtLvSzPw=E=GU0M<}(IC8ed-%@;zD~LNd+r z_PF?W(EdA88jLh9Qy8zit-H-lY)^8)R0iIeCe(Ozc}nNfIk^DHZZq}O)d|trL_SI? zgT*TMN?I#x% z+uN$rx^5vltAgy#i<#VuQ5}M_w5O8aKb+FYjtwk7d7^LD1);IF``nB`^3ou>@F@0h zmn&*gT~TQx{L1$=U`n&uXFAWs2;71c4CA1tyEVjccIlhG6XRR3{w%zc`PBCypEIRK z@skF0-ZR&?W^w#N6|g%)0EvKPKY`8Q=(T%WuKF{kU3R2Oe9S4Yq*gQo%9cxE?}7 z&bk$8JGG8~toba}j6hrabp0C2E81bJ625(h>!L(uj%ZcI%1ED(EZBdxO8Z)C+ivgQ zt`LQ2^E`q=g8maVy}7A0H0N&F%{wD(^6XN@6`c(;wqvZy^-=bgpd#T%3XL2 zd*c^5^s}Dr8NAS3Zp&9VqY}HB`Rjv9^n^SpgWOjchn)VX;Z^4)!-I|4s7e$uI^cG~ z(;!rntLgIDSK$d*laRp7N5;?vd_7L%peqOSey2Oi**f*{u0zugydh(% z=RG`JY8yk?JQw5r5)}xP*|1~;z2b>2&k-4G0*}76eVEvpeRu$NFWqfF#>&>tGBPnm zU~qKF`QjjyAfBBZ=UahVP@LrRZJH6=fS?ZN7Ox`5>1%2w3iE>sxdwV`uu706dGMfw z1CzqyWrh6t-J9L|b02>EF?-jpYTGU0dmWcOz5k-$A&jc&6?>Ui>Hu2*l3*rvv>SR)(ydV0?tk?4| z%>d6%L5IF;#}v$34}rWNzR}4v-Msjot(>8r(#Y{Oej!^4?TIMbNjV_3)I9Z5wgcQP zeM>~msbn)ZiVpvKw7sg-QQi{c>7R4+)oFx9t?~3m$9clSAOdYykqIf=f zj@g}>Xo0$uX|oshx58zP?5a4oUZi@6F*7GaR$695u0_x~)h@AdkcP}ajURkdM#L_h z1cUo$Hpg{xwB^}*f#2A<<~sET`!e=>=}SBDyqQeOFv=RJtB>h8LurYUh!pkx$t@3F zt#C=NS>ZsKpu~9UZ{FQ7^8Ii&SIb{8VE+96Q0>9Q@i<(#E)?f^mfT;)F@AQBZgAuK z)bYpmSp~!P4)sa?wjXem#?!DI1nPB_^^3b&(4Wl~nW6dKwW^2gJMSOSi%xzYRbgm%ji-C`&ZmM_-aS% zN;|I;yp{A%qG*Up&zOf$i>JSTU>{&s$`!zMvhPkOQ~xsf9ThC&9Xi_(Fbe6#s&xmm znma%w;LJEVJ`Eug4Z`il=wN9}qLNR$_dlNSOD5vd@Jp38dhc-P2V$#QsQ?d;ifrul zz6s+!jjK`fkc!^Xd9zE8a^5NtgWFt?LeA~(J#YYrl`E8PY-%597i6V!Y27R`H$R%~ zrF|bZS7omi96$ArfHURjGqz2^!GmI71~O74x{V87`%uvOnJ#*W;@5@AmXfa&QsF)r z)pQP=FJnOay?NK=w*-K#x27CBboUgr9wn6DVr^@@r6=i`9GF&C|oD-m(;rYNIzsR>Nl6VLA5FqutC+3FaE7ao*%W`$aR=cg=DDhIaku!a85PFXG|>rjtB&vbO9Jdu#g=ArtSimvNp_F zS`FLFN&3iGWw_WG9?B{izMMANAC@zHgUHkJV;0Z-frk zESx6rz0O3Jq%#M}Ck<@lcyrRr5D0xcmkS)Lz#)m9VqCVYFiS(P>=^%)4r`07o%rrJ zfzHpa?YFDF!g2=}LLy9i;fuXG*Gf)};)pMm9!xXP&AvgNVvePLl5tFK68u^*?6145 zIiHw#Bk&FSU)S~)v-MvhI^0Kn99dWBr)Y4;eO;xI1pwsd=PtL%Ys!qSLT z&4`__=(C=gLFBw-RAdfUoc^$8B58!0#YKsjRQ})XUjaHzNG)~0R&$3f=xxg4pgr$d3YOucQS*E(NSmz zWqU(kap`{Os%&~{KWtrM(m^B zD)Ddid~!6HxNRMp(k>JI)T4toJnpHlL#J4TOX)>lH;lGXPTaoL1YpNJf!R+R&e)P%7}jf1y`-l5T}rndzOGr9?`jZao^>G1>*>AUG8GYZr( z08AAG%~t952F*((?})v5ynEm9uxHijyPT zZ|O#Ot(1IvYC;wRhgaLr_IfL>{5?Ou0yJ*8|Cso{P9j!y>Hh3A#Owb+Q!iDt(Zu$7MJya^5g$7h8spF!#f4EEdgxo?12YdZ+?_E8Y zmOF!<2ds2-GsZ9%YBS>7E-%?1O?EG}(B@XZ54ReTh~V`D+B`P<4cS3;tr2GjkNhuB zPo<~#qbeV7^>EZ2@(AJd5G^_x$f}*YWNqh~v%kxF7j+D0J;sXI|8>fgD?bq>(2T+k z`K;R$XwNPQL^~XqLDhahq_DIJdM=V!>6K-Bgr1)ldE&~kqB^CSnwn?<-8F5PVh`C4 z7QNCv?q&X==npYU#X|Wy6B^Tjz{TJ_$Y>77ExyIpG}~qA{Y}jTF=59l5M(3K;>>J) zu&I_41{kKoE#<%06IpIa7nADS#SjvmpVRG$uLfo#o60hk{V8Ms0tDt_Q~6v!^8nI$ zc1Q$}tb1L0GqfIEd~Ygzf7up(B8`0PC~o1$k$h9H*R^D4DijKZGw-7|2;#`}u=zuw zjV#eWZY>cejp5jfYm4pI`-{TQRBNbka(G;0cX7q6(O$!hk72nFWauL`AH08Y8)47S z9i39)t1_iuBf3-6RO8UB>!=R9>|PaLes}wWwu4MMEk(IDzka%gTz;lJ zpD3!-5Z{V!A6xRD>uN;@O(?!+H`isPbB>`5Y+EPOg{lJ@2_IPBH&w-9EvaqV_FNsI zf&Hv7vX(R}$Q<&D<4WZWc4)d2XIiT(`gqWskP6kU92DYC%6bf&hZrRD6?f%qv(&lr zJ5SMwB?&D1s zX>zA5x?hJlVuvIee39m#BZS|D*MHwfPxKz~a}fxeJtmH%ya7}w(9ZJI%|S|}=RM2S zV@RX8JsB{lWy0Bc0JT>lN${(fRe7g^o&t=@UoNma^bLG^M7<(!3-hf5Y1%%{4&6Yg zCBVW69=vN#y5N8mWvG0&g=QO;9<-lM^mjhc*!Ky8aoS*Lw=^7WhHr}iD!YQ&RG%|5 zFs0!mEq^z_t@8fE=byj$Io*0EaA^96HW}uh(e1(2*dQ3*T1XgQ0Q=866=$le4ksvz z&VZwKTP-p7ApfCMEspgO59hz3i$O>Z$M(Em^S`+i-&h3`=%oga9zD`ohpuQt_0aT< zR8jGb)k9knIo!*T*GXGoD@VpzahDR~zNV;~3|?56_|y7Y--&(0JU+}{uU8^X>Zny> zgc`eS5k>(c71lAUNi-#dwoTb}Y*5&cSAUv@ys1feO!&ybwTD86yigprfuG&~{^FJN zNVXX;0_uMOE|R{*K>7Y^h*@IuA=-#pJa%%wS_^y(hKRtjrd#-B?320!SbnyC~Kw zhs5{LI*)V;U$F9N<`wuHFBjoBJL6>|ws2lerqY5;_t^S8|ND*6_g^SAy-Xz~bDA&I z$M$Z_uz&-@P8!`!0GjSN*~M+z1Gp^WpZTTAyV*o!x7JP}uAk!+B~-NGBUJEzUTLwf zK+Jaez+!ft^Yo90j^Uk18~q=3_O+t`{(xz)TdJrJ^=tS->!z;{&PE@C^~bF!PNQ3_ zd@azwFyA#w#38k?PaTONMx(A;+BQL8vxT&nwsPUy{@CF;5M|^TGW5P^#OSdOiG4E^ z@NQUq#Fyvu>m_zRxG-$LXVv6QYg%7=bF1RLyThlp66!)Tl^q;mY~Ow?`A- zgkpNN@qFO=zcTlvGIHlKt_`#lOP2cgL+H}?YexlM+o^Z7e!v)~VxqBTaS#bOJ;F3u z=0C6{7#~oCAX1{>h)ydN0KddI*|LR=n=(8sOKoT6id8Gnv-8CH*>&GB$`Zk`J7KqU z3uy#y2qaaX3afshXIkoP)7V{s4MTR_F{ZJPfqfIo@+ZxIfL;yl0- z{8l4#tUQrv9{Gd!PW4bC`yn#6{*#2Lf9qU<;$K%;LcKDG0`_#6W`w}zntD)hPeFa@ z!6um<)bH=4X%7y7K(!A*>w72$1(#k2_iHu406svycB?>2k!s%0OB{R%JMd%G4OG?b zb4pm*;45~xHw#)vZTDcHDk@P7f#NnLTv&=1p?sSjt0rXmmIrHok<>*(i|I`Z_OZTO z@G!J*;#oJpt}V2n%Ee>#e_6pq@mtMxFbG4*JR980HS~pXR7!FoZMcB02v}v8H=a+V zKV((gm8DtK+DKXX^fK%0C8wA5X_sw=S|kgi8-AmrIRq3jv|RXC!Q}Us!ZkrcGTHh6 zdd|^@M|s0tU=8{2*bkGq=_xB_>k5F0#Hdiwl7|4yJth}yUo2N`yHV9S=7 zgF`~pC^HnWb2awfYHIMVBY^$>kYY@u@}0j%RpJ$4MfETgXA8k#HFwFl-1=P<;2O{POy(Mp!%L z=n>`f)?Qe(o zBn3g20c!WImYpA_$ z&mIyKUQ}DtpVU?Um1TdfJKEAy6FbgB`KMM9;2DM@!piUv!it{CEp)D9!0br@uRnfMC+8=LNc7z#bxWXq%iR5Mgg z#v@XpR)NX5JK8j4&5J)=0JTo!g&qF56)(^H(tglbD~;gI*0uX8@Mq4Q4-NeJl17+5 zAC@8LC$km>+h2K3p_k1I6NOUio{abLnYs{c#%kBtXWr$4yQ+%rs>aG_7tk!=gZts} zAIL`Hw(TG4nphmT=&Upfl)&}#^io%YDO1#+5t z5q7eeszb8nb=JTH$M(a}68)M{iP;(-(({A^rb($8&l;t+@vUa=Xeu)Wqs#Lg9q35PRLdV!9nrm!J9XHi4dPh7$+I`JTu5)GQ1 z$NOQnefMG|&{9?Tg;18-PN;RVB1lUKOH~)qCeu^hJrCDjA_9ucUn!XSb-aB0PH`iGw=1=oiq%f+sH?DltTO_gp4I5Z8)a;({Qu0O}X zPv0Na2yUykj^R6Ofo>ie(ORS!*iS^r0Q6Ra>I&3MAlv+KvC{J8%kN>+()Ji|T8+GW zWGz~Jr6divpPvUc5|Aq1FbcW)GSKKfWA0m*&{#2oQlUmV0xR!t=TdZH8>97QNGZ~D zjK-%t>sEAoAyHp02W=pv?wQ}*a{8I~%QlZbSs9X`V0d{=c$u%S=8qVC=j@t9@mt$w z4H$Kh19JW3)Y__i*&e#s%wbS7QhbVeBbgSvesKUGY9%-xad)LPG1@XYnz{;!XU zj)kYY9?=V^S~dS%C&@x|4yz0ya{NzL_RFD_Wf;fKO2KDYe*r8-2}sLtjEY_$DidA2@Rnf>s}S8s^Bp;jc+xG}p|@pbSU}||NpIA5LJe{FeVUQn zX|%(Na$@hv?^0qV(%(Pfv2o9_ZG$U|nvSlXYkif+F4wPZP7I#|A(11DCMe`ENF|aQ zIC(1V=bpe!*qUkV*RKrsWn^5k95OD^$o2~-dM{eOy1a@z`t*-?xh$*O^TIM`r@7~8 zmdf>H``NAVD&2fS{_~tSM3Xq926Gz`ZK6TYh!=_TZv`E>s&r=!e013afHFHrrLDCg z^d}Tdk)X!YzCUh49cd}Aqr+sGsvrq_!RJt6UHfcLvegOLg~clQluW%u3$BSpCWQ?W zXUW5sGZO|r#I9qz4^DT#GR1H<1tgGHCEt8#J6Y-@c7p}N`hFD}P^!X8*0*Ak`M*Xh zgVX1fvp)H$3-$s5ue6}cz2^jJZo3A9nFlT}X{q)-U-q?Ky#Ky+YBX)WT6C3Rv=8&(M#B!(*@;UK)70)?HV66c&<5&BS572!)Q(yjgn z@r0M$_ZL`b5k$v$e9KLN`-84S)PSZ^^%9iqx-`CRlLa;D+x|b+$!^_!`{@@zMv+uf7SjA|mfz`1Cz>kP!c8v*)7o*s(XVQ^SN^veNS8 z_TFb9Bbi&f)hk6Qo_8wAuI#&a?;63yAyCe~kNbC%7r2sw0g{xUMq43V@OF%;s+d|c zbYi)dub}%>&Ebc%c1>Cncs}Oy6v$X$dZvJkN2B+IQ{F+-p=yH64EiHB?USf}TTy|+kmEN~ zNJRxlFtn&v?7uq>p=8G)rBp5Rp%9?ig{}r=J{geDe*p5r!y=nER9%rC8hPh63aU=9XLmkc7`CCLW6NH1Og@DQSDU zCwTCZbt4GmeW<6>e1Qjl04nSCC7)E0I0P>tB7DtA=gJlh;8J7-J6zH0MD+XbZtA+h z&GyBn<5TIk62Fgq4F*7HxuO-eSP;B6apS#mKaDMSTr~(@5nD)Hnh%UzS1910hQpV4 zlX=#y<$#eSuiQKyD@m9ADqir`^rY{XtHRfPjP8w(NCwXSSo12Hqvm%eNx@P5DMkYN z|2#7eCg9gTpiOB9%&~+dUg``2vX=wB7%lD6^;`HbK{#$~2gz5P`lRjLT$L=;kI}iD zNWmmK1&9DOz6y6FFh9Sw?#K4DxTpPds3_=O2X*c_P%6$2E75#kR0i1j&a(A!TdK>h z7rP-<;pA6kV(9{@s$>1pQu|f(P0A6UhQ;KJTI}Uc`EX=240+r%;1$C_gAdalqk|1? zrWC}B#C#Q=HIfV%*QpZ?om)4LfS>yF3Yq#hmAffd4p2apmJZRMZlx|fWeV*s_deB7 zdjuQV67`?DWe1ter>Bl=hQQy!1-kl$**0sXlvz@=4$VGc=AQpvIM@-UA15uQl9vAO z%d!@y$y%HqDGuppF4Ac}{Jbb4PUB$n&f}$qBa4rnJ5vc@OA@fw3F8512=Rj~zL<{k zhN>~rlU9iwor(-vutzpl0h6=Cu7}8&GPzVBL4Eep7Z^EMVe|IuL0%$NLDo@fq$z-|=5wf)2WV zi$jgQ3WmFt%=Hn$;7G6?yo=H`5>tF_;73F>!atWQS+$3Og4+{`-Zbvn5OGIxJx%;*hQGrZKnsb*B5n|yZ5zO^ zjWEd3jTj#@V6oyG?5gm!A{=q%TSjqpNGsakn!t$rDd~c-In{Y^t)nbYmzX|8?M`8n zsCI;Z4do%%U2KS~24FR05Q#HM^-|v$Nd==buwilstb4Ok8@7qiLxBvL}tb}bHBEGBfZGmqDp$Y#7 zUCZ|ZW&?V9sE+BC2i-W(2nJtlg7q|4nnO#AqEQ)|kk>D_U9&dFP%*{t(P*-T2k^(NTQXwv^rrGnH50vXcGW#aM?P zep|NIDID4&8qkV(ATP~J%DCJWgv&-oJnuw&e1n=69Sr>Zcv!I8*D71w@@MO6nTpXX z3gaK+m4Yv(&nMHnB!#|tAgTJ_y`t^@F)Vg&Cv}}C)ly%yN}TJPXuSmZv5uZ(A1FCL zv^`7oeAlU6$JMCQc_c&)Yum-^!L^-&LgU=FiQxqbcapt+{?L>RU3i0EmU~Q~QI%Pk zhf(Ar5041Da>@fY746*ySFdQWeZJ&JueCfS$oj_56pdy4eE$E?u&8LNy!f?kGV%eR z$BvCY9wQ!!7u0P&y}CA9EN>HiEwx~_YaH(|*T$eF0gh3Z6)iURVhBLx^!P8Q& z$?T%y;zNV&*Ua58AAY^wWhCV03GdVJzdOD`tOYzF35GA-6;@ysUjJ+>EiK)?^i59L zL>$C%rJCjt%Hn9l!^3UB%KMI38@IR=nFDkoP6w?(W7G)e>4^L_gl}37-QH#YePW{E zT}_rueoCt`1H9dwXTPbRXZUe>ov@mvPxBU5KKuCw@wka!?}YinL!0LR@ozcvlC{Wl z{0>Md+gHZix^>IojzM)VC9SBd*O`H4wK5T*HeJ4B8g;%5L9A(LHK;q*T(>B9r1G#t zS+alK`t=`>{9o)@J_*@C8wC6I)&a#YXqQzlJLnFfAaBne|7-@LHB(CK+qf?m+58`@ z*d26)OwIwyH@=;`Gg%=^8!X1We!ciW-c{eZsb_qT$rS*{T4uxYVhr}r(cflGdYvY* zY@_>@CU7dm_*5PhNro~n=iU!-*{;RIm&@Yge=J%Q)Z$v_PvtA%K>lLf-TCU~|HX0Y z->gR|!otGs+s3*}J@le8rWg5ocz6VDNGj?|c3$*wm8vpZK?Y@VOnlR(*39){OCG7l zQP0-0<;0Ex#v1x9??IYvW>inOcJ1EK$`vd400*>>6T3)5_U81iM8oAy(`mcZzm1RA z7AyfXLwSNWIXRhxvt%XTJ9RZ+uI^PuERMcek#le5l6~CPCKS}F?Y*Ds>vu=^r}v&P z?1R504K1UVa>7%af$qF+1bO0twEf(Z2LiMP+e<|p_t6cf#pwsK^sZdN$DteF`zK>9 zqsJq^|L-Hy`=e9{nto?9op!}G3pN>Qt9N%g?T{QQR(rA=~(HH#9F@mRlX_pp5Clu;r~QhiG+H%-1u< zq5nJ?Vt13F|2I`gnQMeLJR&0hKwL@+Ul$*Wla=!Fg%9Etf_U{i6V;?jctdy4i$-xsr~JWt7L-m>7RR08rm;sLAjg>SW!dY&Lso0CxBOfSL6_Q%~a*s&bR;Zg(Dj8Eeo^B>3+!@ zQu*gq3(yKVf6Dz&%PbY_*B&YHsOsDGf&OuIv3|}lVQ2XoUd?27E*JO$?V)41h4NznuqPea4D@u+L$YCZhYr zzM&r&Yvu+{Gp6b37m>%0brvmd`fmG1N7T_{Y&<{zb@d{WXaDgxXH6S z*uX%umU$D}Ad)CwRy}*B?)9q!Z0|imyTCqyEesjJ5fhy76o@5|vSm;AOTtT0KFvTR zA7DEedU(sYqBri|6jUK>xLn-dDikZY9zL)1wr-o`-1hAUKJ}jYU9!?EsQUGu;8^yb zpuU6Q_JK8q1`*}yoPGNssKFy9CJkO85-9J3;G?dEbXcxF}QaI}7!~KI!>k@Iy1{ic}x%=lvH8A57 zoFvATiclA)w|x5aYA7%;@Hk?k#TN|jQn{o$Jgzb=|8ZT}(J>Rm5cAV>Q%BPGPq|)A!bm<>@UQR)xLbG{dyTM zQ^}rA%X$yLsmnZ4kacM*a5A&c?U{YhEU^!L-$up-r>Om~jXoDQ_jXbeLOHblvJ_Z> zvUGiI*LcS7k+ptIu5Zo$IvAoT0O`KkiBLL|&g?UDC`=>G0P12&IP>YjWdc6@)UR3JnG7ax(>eDdy(@~Oj0>QCK%$NWOX{5L+o zE^^EthWQ(C+=5F@^~-S|gN1owG~;J~5!1NoqtgUL5Qegh|3aN(UjE-@iXYNSSe1)y zJ@F+Jb+$v0rNRC#Od}VkDVI=xdfRg1&j&UAogQ}JC-tGeVaa#dP}q*`IKF{s`zu$j zY(O977-CibWC$V-(HN4*bNWA5!cUIjHjh#M zS+D7j@7{5vag?Yx5OS8>eOf^NwqN@@$c-oTe*7qaoU`FJ#f}Qc#)u}dt2gIZSwT6~ zJ^FUSie_Q1ViRK)Ha32o-Iazh*`|PZKU|i7D<$74JIh#7WbuJz&6+zwWncvNzJDK) zbq$MWyo|S-*1Z;9J|G)#As@P}7exwEA++{8Q*c{jQxtjl~)yhBSFY~9~m%hebJ}MIk18& z|FNf~SQPAK$`KU><%mlE3mp8zmX*uK_68{+mBda90>@($6uc!C64Axf+uPfR*0ba# z@G1#l!_~u}dim|AI@Tg9L?VC1MY;lq?L)~Zmm!$|4APq@+}Q~h-5$wEixZI@f?eCx zf<}^gq;~Y+1|%!FrW_qGNKZ=QlGzEhU;0iZ7v)Fimqe(t3hqt+mhkdw17io1oNegZ zCTU_aj%PT(0$DAzFd^kX5#cJ)ZRLXk?u9+KcXLN<<9jYCcd27kJMPq<;@>}$Y2DTn zIvl<~k99c*+NXplO>4}JUjKEmu+ZbpqE~&4`CD&_7(?p{vI-9$ZYK-#rx2QJ<3#!S z)rjdGb|J$sZ?JD^?dW(3G^`5d#F^5^Gn&AGa0}Au>gr0xM5tJf?md^aE9Kj_Z-jYb zQs$X|TMfiA_cf1DO4hX)9^U=nitPRfkoMbPSo<4r)1xI@&skgwKE$_- zxYvOrnIJfNXM0`3RzV~TX2U+u3d8ihYA|}t5Pv0`zrYJNtP_d*hQ514s^|6K>oc!F z@6bg3@m=g~@IocmkHIJ;2Q5#JHK^w&`(U;W_}j<13lATq#d;3L{7_2!`#9`e`U^r$U=(z z>7RRelzvJ*)@0l^SM-C9F7SSZ@7sls`sc67DrM9S3p#D~67`-x=K+6vZmi69{dS@%(KyOqZUjE#W ztzc$mMjNx@e9AXuf@>k^qL)M4;yG`)~?+B>xvA< z)UU+|`vPf-?Z}ZMYwNC!p_r?n!`gmI!qYKpecw+QM)FqdknZ%}14;!10#|<=YA(q~ zGg0|z^<%}gd_-G@3+>5@!cUh)Z~kYXVH{Qog+*PCLCfOfhrWIN`g~GH$hpqrxWL~p zu!iL%kfaYd(k;sYAdpdu`nAPdz8Y_U$3BR@th;cY!;TTaKAP*E`Mv_{qZ z9b&=NOp*_{psXSk!xaN!hofcX>vS=~Dgq|a<~>Xo+w%eX{NVVkKHt-ndlOy6N}G#R zX+|)cYDq2OT6i_!e+~dS`u9YVPTW`Uns6LAWdE#`jMR+xBiovkogGuJRG=Amw}gZf z#U$^5WxyCU3g5M%$(Qj$q;uoGbD$C0uJ@I9&F)bf29tt4-&h7QsH1ik)l~SkYhn@- z61_u1;&-eSxVV&2cifzP%VLUx>nF5_lILcu^_jGrDf(+DJK1&z5eILHI~p5-k?1dU zH?8`uQCpWMxgIZfgbt*^txh)>2oU+4$sdv;YH(09>8c-ay|ktHT$DUzB}$m=Utf2e zKRa_`P=J5Y(wg|{)l>q^KQs%N@bo?LdISGS9KTqJMFb+6!&Ws<_OA^$Ruqof@ZelP zZ6E?O8EwFmDM;23r)ho=dvOmn>^klx-UaQuK7Z~2-G|tb=2u@E-H=X5FvtT4jC;&Z ze*Ewub$0JBy&aXd6#MNja3|E*o&v&@X&U?gG4>|VT&{2Tcs@~vCJ9NQOc|0SLlhNd zE+S-1%8(&5i8xK7G8LJJ$P_68>9>$lebyVg1De9t+Z zJkN9A*RZd>_tmn2@W5=C^sVQA8uKOo0CO8iA6cI{xs1+fD*ahjT8auVxRrUw)GuU2 zd~VkdbQ^XUUByQQ3H=mzq5C&oG4S+%yU+2MJ5g-)<<*5!l7Q-PEvMY0p(zNrN0?O} zyx>*Yl4D|YxX>;G>tv{%;5Tu9V1w#t%H2%3yn31KTix9?pHGdlaB^mC64Of)c(p>j z#BclgB$UD{Sy)C7Fcz#Piw3~vI(joaRDt9qMSq6$aF4HycJ93Uje(L4R^M7|geyRB zA_)og_}=(cEWGR&mR)c6o;)s7(Onm+1LNyaOW#FvL$?Jq%z^D*jQ=^6D{{qY0^2uz zy|Ch{COug;a?iD2$3zSwsq3gx+m)^Yx|_SenV%6}xv!IJC2#|jT<}YI90iW+BFSE> z0#oN0C>sJUhtk#%6(uo?3p{)FY?84G8;#MbHweX8B;UbykXI0=ikFBYpbfh0;Hnk+ z#OK>NCU(@fMd5;)%N&LWgnu7>901Iz?|1LzxsR{_;0Df%_O2 zv)Iu^>X*CnJI7% zJ6lC)EEv_49Jp`a{`k_lV$X%cYh^cJO=x|&dZfnH0o^iWip4?unr;=#i0qj=5Pp6_ zc<%I)ss3YSO7=LexUC6*|o<$*kr9f@cZcP#{1;__>+e}7wqvZ#F z*op5Ld0eT0ehAm7XJ{xsXe)!?O33;a)` zSlYpTH;VCpWjzEv7nG6G`!4OIx6~wDyyS{PIGU{of1^?CklfMCe)?g9!214gU+ z!8}d!F2=SLvVoL1p4HUWE>^@Nze}QkM-NJEv`U6fs>Jof5JyVdHU~7Fm$;t1kn);8 zk*$VoNoF6LM>z9xECZlD8Zk*UxNCtL`}%Ryao_i7yZN>aGwsLLSe9LZ%8o>Ec@lxW6gI-4m`IbF?3P|t3HK@W|r1`0e|#>Kk{}^TgFca zW)3@fo0})@;#c9MIm!g(wmKg6+WOtls4C3`kz2IBvojupK1u*Wy`#jBP^@KF6-{6e zX!GmGl6~KS;ru##w&qo<^u?`CvU4>oy`?hX>D$&+!R!A3wW>lWpeA33Wv6xN4qOt` zK((kDWPj5>ratx-mCF#U{d7yVOj_T@z=77)J zrs-QcIy;Y5`O%C(eZ|Rg_BI9xb~FViO54h39+35!3`>`?N=r-U)g~Q1OjBS~ip>=_ z4~-SHrZj(hpF1A`6lqW>m@0mo#~}V5HS?bojE7hXPIylpN>*YZZq4!hica3~uO!6h zzblVnip}L?VT9Z|J&IFwg6>UzEK>*UyhN<^E1QQ8>gbI0Rj0)6drnV( zgDv3d)dZs6j_MAMK+kD52dpp8+I$6hP373n;QV&OM!78#H$p0d;jgrsl)A=m) z+;(8lll6K2k(&PBui@E8-G5>S*UO+)poK!bYDEk|(rGyd# zPiQ6V%x-uFK$8g6#JpVB3e^ls{geq^HUEnZE|JaleYi`nm9qlX5V`n%|Nh-GFpyc! zoziEl$U4g<>#QVw04&Mg(0yF>KWQ)f;T_I{UxAW&S(W>s{oUu}P1DJ8OSwvi7746& zQbxU)quSr^JQIPCK<7>l8X?Q(P<9%5jzzGWj>O5W1XN!=)D?H+B>&>&Y~9k``DO1e z%_E;@Ni~W7EzH_FL<=ia*aG@PS)>RjjN$o^$35UV%qa!_&Ef7_I*BNnbWsYSe3C%bTa44^rS+8d->*dd ztJh+QjO?hYfXQw)^R-rVDlJghQf>B{&QUyj%{`JZpbetS{pfCC|q*L7WI^rvcsBZ*#MxXxbLkcej z%e_gyUFp~%9u?%$-+1_lchZHW**o=D&IR$R2!hU}ma2;V=SkT_Lz16MZ4=oU*#68S znT5i^NY->f9wRmArndrnTDNA`nZ%XNo3Zln`spYeYFT$A(&kQg=ZWbJ$lqpj-$P%U zNlP?N$f(jBqhO4s2rJyampQGPi(i2k{WL*gHmO^I6y@hhr$o4McXF3(dx1W>rnA$e zojK-$Un(Y|{>{q<2}U0h8yjnhHUd-}W_5;0Y!|CqMB7}+@C@ThU{pGJ+G({!^tk9A zFC9wSz$zjygfRYSw0iTy{cb(FAm`qbxVC=UboTw?;ve5@IX;>eY4c|1cE0WI4%x{! zw}#g*mGn#f|J_K3d6^*2>3auRhEK^=kfzM$+b?(@^o}r&MRkO$_OAHxfL1 z7_wFPe7y0Y`DJ8e#)H9v6XoLKD!jI{7~Lp?KkPIHt1p1$A>W*a1TNsAOGkROx~tTv zk19)GGij{larfVHL_qslrAF7xa4s}7)F$~3;C3=y`}*~%-1=sfI3PKFTJiEisJ7S(zCG9F#B5y>D1F`$PYgHg6cx+a$=W^FsIkFzeL@T8 ztP>yB35eaUm&~^L`AJH`)pa!r8&%HHQM^1@R#VlMD2qwFWM9ESwZBKav@-)3{$}BW ziQ%mrBp}MN9ynisszY|&UOf1g^$S<)nj?QpU<13!1lXjZmskYX=$_A~HndyJ2S%=gtW;9Y&WvHcd*OoPaBVfg_Vlkd_)*@_R1h;r^6txa=!=vsNt1FflGN{^uIO8s4YxXPf^ z-TvH#zqMv_*>`n3qGaIeJT@KXawR8|-f9T^xH+=}w@_Etxh=z|?Cvz**>kEg3HLwy)>)E~j90WtZQb1Y#>K~`3c zoK-t2ju&DOUqyT`V4+h|)jS;*|tV)nVVb^NkJ2L%_2lC0ilTQ;&^{dxf)w zd9C-vZDc@wlF4nP2ELeaDj;?up0vS3;BKgP&x^Pwce`LYpEk?A6FE6O(#J1*Don;+vDBFF zS61&s^Y)?Rgv5U$P@S?r4op38G+xv+W6xS!^-(cL4!*^;m0HKXMwj%|z%Y)Ee8Cjz zQnK&o{c~sJ-7cDfFG(57+6YrE?k;CeS{*Mq>H^Of8c`maao=h1PEg`Jr<|pfEH0F= z2UbnYyPA6M$}^&*R|X##bS@2_f$1%XU}YioV~H7=T*K? zFz5V-HAupTKIGX%KNq9-#1DPt>ecDqhJ&ZK1GI#Hn{#w)^Q^b0=Yr^9YX68{I6Hj? zh{56Y&S=ZYQRTjAE^M^&2LxEh2%{l2WoN_q*S813?65p^hAKGr+LXxFHTdT4qh3kW zhGAq<9@YUM&-w&hw`@8!aa{fNJddiEo#+S$lMd$v~EiSVx5bs{zc<% z0WQ4e3w~3FxnZX;^aMsH8W)yx$6sN#9}fHM_JvP=TZIb`tlZtzIvM2*yr+^wN`}nGNqbcr#c7S<&(l0#x;Gv7R2yPj&nKHn~qBnL5 zoT%_oH&B1>t86x-9EGb%ogPg=odcZJZ63RxJo)nXjA5ME(J{91XVNQWZFDXy;d&N* z>CAx;88(sQuEHa84NTPl9ctexBbEP#GrCPD=Y}299D5Ol$fi(3#!x)8)2p}dC>V}{ z;9Nsv*K3tKmZfa`E72`uH zd(FFogF}dHJt8~7mXu(R+6c^njP~zVg09Slwpr+4@Q#TaS|nTE!v>s3CrsjH4}yLk znRM2p)SZ-A6QUQk{mP?IAp$>p^4&QnLq-2{;290xf!~bT^E#7N7zZS~-^kC~I$NX` z*v|ChxI}pi{jcuXnS|3n-d`;7L|;!vTgic}^Emvyz(dIVMCa^(;wb*O8@-xkE=g;kVeFi*oUFdqME(-O86HM z{o^tguUbvRbsk-e*>UvgEzOk^j%V&4E=cKVOg(O<bqQ@es`a0M9~#Rt**r4Om+UnSNeg_b zx8>B{Y=dAforl#7Cd<8Ff`ituVlI9+pg8Ls8D?hw+k4O5c7scPZ46_;O9XCaBXzD4 zGk$X$qciECOInNA>6b3OPIg9ESR`v%K!gBrlkO~2=uUEFs(k#30T%`pZag4dKy#^u zX(NLH+r~uql%)&|uaqG@7Q*??s|sKcQlM)d`aR&%1nE;+T-^bbJJ^H9mA0w(lcu>C zh=m8JZfanqYCKN-t+fOsJ}~xJtuG&v^9l^Oac05ImRqXtBKUK$_ncIPV(BOy$ zio7`;C?F(thz#M4`Wb(7$5!;dd(boeF~;y}05ww4%w6!GVt~FX!ngjRX8i#_vN3HA zLZRP)hR;oCyPTXlp`&$m?Q9xDa=R9=jJ^&TR|NI}FICB!HLMo$UorQejP^UcWV|)|5NTYv&D7MC z8n*FC@S|uyxMBNhV;(7~L(}Vhuz5|(0**@9Ke6Y3d~0HA(*9P~=U`CM#MigH?(TLC zHud`({+#X=umT~cJ7VqjyM0N1hY#F#=hNzLes~cxrNd=qWg{ouFA!y^sJh~&sY5}P z+;*79T?em71%voaA_mD=x449EjifaXM1}iDOHNgK;{_4%L{je%mz=;6H1#14{`cbY z@>XS4RmwSu8%SOpZ2;s zm2es&iI?B8gL{p9&0vJLfbeCQ+!E;U}~j5+9?Ms<}r9DOsHmiJ+ZwYotB) zhYL_5ssPf(PptP+8rPPK#(ineJvW}_j-05frluAi(3WIWo_32vUvbk$K*aX}0;X(8 zKYtZN@DN;S4)zOA@k(+jh>lIa*Qv1*2e>b4yj2(T!D$c=|SRxv{2`caFBi{AKhK_z$#A;wW&7P&$At zN~}eKf`VUGHxC&Sye8ygk2|k|Y;Sy26&&4QB&QWC6M8EvGBT2I8Nkxm%J~mqCY;wL zJTHMN!o=Z{SQC(gI^uHz4wUov9%W3$n%t!}!StL6MHWcBj_mn!8>+IPQHED^Va2%s znO0ie^<+CqDm3&XP{pZXZkB(?hScxox-WwJz&mccPQE(3Q`XB^EsakDi$+z6JtPFBxV8n1AMIS0@IlLn2J0UZy~9r^|)L{xu8&e z{jZ7NXio^O&W29Ymif~5OhZ4H@jrU!(9qD=A9nu1 zFTfM+LozO@JMH6>ioSy6);=XgA77khVkEY$=}2?(Mf_Xp08*3(KhF1I_>pgGn&UDy zV(XmA8>p+wu*_MkyQ$dcouBb)c>_Qq^~bFQ`KQK0EjmjZGT2Q+&YhVZlr!&BbILY0 z^iTyhV7x}b6x@Zg0hct*xyq`FH8_Oiyqu$*dbHxyMrXI+_pHXE4P4*l_wVMhbW3-I zgblbPU8)HN1U`MUX1?jLB)Sij)ALE{-wOOAQ~K_;dLiHl$K{jC;ra9DC9QaQ-I4M1 z>7B-Up`~pZd6)qDQS;bpV?_x3;OmKr+W?>LgK11|38}|<;;Uijmw{CwetrwiG95OZ zBI*i@b7PauU0tSxRXR{9`GuW~bC8qv>iS0>E?T{Ittilg`@gH}@Sf(rg=c^w_EuUV zeU)(8J{a<&Svb-nwqD+N_jV7hO>6Iac(5l-3>L(-9SjTa8w%xhK00_1`@m_?S;?7S47av%zodG(%NA4u?tHx zYQ}6Q#{<)^& zv^x+>#zDw!meuKqzZ1+BJ~tf;*@W1bSMzw@L*_4NL4QLq(VZ4iDLwsWQj@e>ncelp zS9Qy0x7Q4QeB1bU_owH9cfid?uu-=Tg^;T_z`|?z!}|P7+|aN$ZwyQla6E%9UR<2c zMztBj6!f+7L>+H1G2svux7aPAPYOxAx|=gPm6hEPh4CZP9RL1LaR@cmK3!#i=#oz7 zgN{yml(7UXOjE}6ngS@uRJWd=lKz0&xpgIAc?RnD|>hfkk39uv@9`QqafV(0qLs2s7fN}KUZ#_q3@FQ`C|%rQZ!apGmU zw+Go~GqjtVn>#zV9DIbft1kyE;|L|W|I^2hx8gGQWA*s~6pB zoqQ@CJ+7`dJ>vFHJF@I20+w+*7KJ?2bbFSu82>2ymJ^HM_$Y zpv9yO3N%AdHry{fo!F*|RezTvHu3j$v*bQGJrU)(V=}h>J1I7-O59mhRaJdV^gH5X zMFran!o9%?^$Dz;tyraBnq&2{2b|&%?1)*{qlbM5cT!(2O#6{;F~x*+)IC=?+r)-b z(SqzAABf`G#ILMXa6*uQeY5SI$T%5od87MUO_4nlb_&AA^Sq!63DDK?YX2y zGMBlfKPtjYZJN5<^zkhYB>j`VLHOVmlDLF=39w0y@>^z9hZl&Nyf+m+7mMDH-{wKV z!I7xOo?wW^w`Gg=lgQ1R!GeGGyxBN>KgD+PiJa}lI#;qRq{q&p_VH=PAe(#Z$u3ty zNjZ1^{Eji(f)o8j7lSbS_QrX2Y6#$3bps9*FnQXx^a+->ZbYNG8nc4~iWE?;*vAW^ zDp2RD@AOnz?`e82%iT_2?ta#Bv-A+%>2ZDg`{S2ErmZaY@g8V^Qp1s3hUXLHNtJin z+tpj_+pAyIeyW^J2-`53W7^_=P+u;q+ws$>iEE%A+0GiJ92ES{xlOn|!*sRG0f(VC zNhW5_RSUlROb<#P)$WM5KRmy=m#3S|3#4rY{vNlv*df=$46!y}G8RUu+On3#4SDNqaI)Zng{!Nj9(%Pmy{HYs?XZ&TkPQf)VHc=qz;OUbPmbvD2+L^FOODssK)T+g1Ssf{6zkb=k1p0ps-O4En? zg0%+2D~e_Y9-epp8MHaS6>iMe{rVaTy3;yJ1(}c529|X7h3-q~U^feJiIQkLp*?n-Geb_W5DkNvr5_ru20aEk0VfMB$gWvt|Hmew~oG)M^Dt>L4XE zkIM?q%%~?6PL++3U7(Qch+)tqb$hoh-kaiY2G}a8Hfz1Sbr{%oL5&ic{W>!mx9ytX z7`cXL-l<2j5;${~IW(7|@qgP4!HCOXRs^dSA=C^Gork zl&4k+HkFm^970JmQ>q>PO+DXc_xB6U^r!WFZ$8*|VmVuER_BMT;kQQ{-%nKdfW8;h zvBTGR==??X#yGjKmD~wQhJgN4mAWfzOw)>XbaQVJm>YTUG>}PD)Mci*llCucSZ72E z^4F2CviF;VST}+mF%as_ak~B0)PvzAoXBVnTT{8twVCe>p=liEmTYIHhgKC(sL5{h z0jvd0($DVELde8R%qW29)WbPMVrdRw-Vxj#G#qC0SOHJSHh{-MGu{Gv23cBl@bXjq z&4k_Ghk?&!#{2-`HB#Tyi@$pz+E$djCzmsLD~S%Ppr+K<0EC zxJKA^a#sxptH}6V$gDzMY3^UH!}OK!Tla=bV{1XwjKHHOSstZYu^@vE+yh_v29ojX z$M*`lT$?ZH0g%rl+zgAON4IJ!b;{|P8zM<-Og9n>U`3v33K=HfHmfw{Omyt7AUWOg zj5zkA`r9$3pP9DrDk~nE0?QyuK2*4!<=Fd&E<3!RV1iyC5_smD|0?YA*0{5?Ezv*a zSE=6?AE)V`liiUBrxdzhTv`+^V0*u|mFbJLy6Vo~M%k%rM)*j4LoQKLM zbv|YPuH`;VQ)Vl~z~KCGyp>;!ua|_tAdeWS9uU}NBE>dM3=LU)dKYrazIS$3-gC6O z=Tu<(*7EDr83zFh2xM8;zMD*K|K}Us%LZ_#&Lg3tiHS5Y?SrEaUgz5!%&sE|){j~U z%?%R?UKrHIvEAnjhHbyFe$ZmJO6<&{WB2Ow;q<&Q({sxAAf}1RCqeVOTYoxxQwHqB z>VOXMOGrpGy#(4v>;B7E5GXkoltV7UKz*o!fcwb!90ytPzNi zUrNw3*Af|>%Z0k}ok^IYeI4p-E2=>^xYB1z-gTK?b50;;mtVhj4E-Ey()rl5zvg+3 zGUvzF@jIM<|1PurG%-7^V87U-CC6tv+Zf)h)8%nDZ(fU&(v**udM5t(8$!UT507U* zHkFrN``j+A*?mJZhR^QD$-x&Lwk=_S>X9Eygci<&UW(62j)>ycrw)k!$2$zkqCgu# z788&ygPx~O5#@`E+v!Dnp!Uu&Ef+?Xi$smm|L~B)x1%2WPn5(|6ECmcc)zKNZ&nAeI*zs_kfojf&RC^Y)>Q`_(`7(LdN zzCDMF?-9Ad%);S5{09vm?z`GNCF^-gt-z#Ir&a++xkJ`fW%>+tge~(UN$V3nRr~aW zjSqB5A^QSVscrF!y1SSW$qHB!>!rVK0`)NLti_M9?Y${NBB)s^%iB{U|Yc-85k$n50lB&W;v)sRdHqR)2UDsKe)U)b8}6 zy;bQHXQoOQ_e`C6f0KR$3QV=ebB zKNrjuH-$#)=lH5E#Je1^tXKpP!q6#+c^dD(@y(EpSlFR3OEvYVEGma6m*4=|tAj51 zG1EcLMl5~8*U7nCpTCs(^XJcc$eb?M?Rrk$)qA?;Nm{*cPOwjlt8sa;Ll71$t%J|G zAjBk`l&P#Hr(ZKOHTWOgqIg1#D6o8by|XmM(RNooAPKVE=~;HhYO0W#CzuWx(R$(! zm~Ydxmn;CQ&D$bRdCUwtLUz7mw`t@_+|y$~2k96?;e3z==IxdDp+84c50sx0I2tJD zrncMETa!;#c6=OfZs7bujKUc}ob?F=)OGE1>*hymhe_{YdS=J?xZiLkJG|F*W@md{ zUJ&+o{_G^@j>CZ|a@k*eYpYS&qbyb}^W8CixEt%Y!us7C&Yb+@MaCNzG(*v5iPG`) za~Cz&9Hq#nA0Joz=gszcv=$&fM9Tzq}!P#Vk> z#p}{qW`NuTKgiFz>Un+L!}G z*p)I+{tA>*S23*aXw>>H`g!8r^ZpzfnvuGH=z8AuM+w|M_wA%?YkBE}Ri>Xj|N33i zkG z-m(8308weYpo4aREGcP|pA2d*FE8(VnY71ir^hXpl=K8e%eJ6p^u0mEZ&YcpNS%te zieL2;);aSj&chOLxInlmHZqrC9Z^XuCWlI_9k(0@b{s;`yRuN_7JYAcRrMtnY@XQB zrd0`f1?vmfngc&qEoz$kp$;kzuH9kN$fq5|$ZZFK?KQaR$;aGu2DNshKguXIG-_^4 zjx8Srz{|Vl=jTVcSmN`p>I_rs!DfX;K{8WQf%`8mYg;yu88Gu4Sk8yE1U~+qrcYi( z^Rq8n9?^SdwnAL5Bj+(a(~@g9%zRa!0dXKO&Q;|=6)-TJCtt45w%+mc`MT`jgBdzH zPH!cgG$tL-cr05NmgiU*wccPk(&3`1Cow zCM{a{_GWA=I?R=$mlX&fjonZMD>%^3l{|{KNYSkZv(o=$o)J?;R{M1dzQ)ru$y5H1 ziDQ4}H(Qt-c`3+lrM?^TCpJ-W45T?^PA1mVW7M#D!0q7R9BnquTXpc;(EImC9&oTk zYx&hg(2X46&8=Gw`Qw!=;paNG0%dSQ)+J{`?~0Eea}R1 z`~8}V1M3GzuJu}8ij_CaIWrkIF@3RMH+IQHf#)7LpjnWG#yryMY28VB)|l=9=EJ)x zgi91!a^eb0f1TAFe3#?yj22}%7uSXP79|oT-XbRL}!`^qQB$@WQ5fV3Hc3W7bDOh|2SEFqxpg$%nD+@D( zM{L%0>lgYXqk;R%#?H=u*_kI7hNFY|=Kw_5-b}X;Eok3J6f%lc?sOmo@WB>bA}SGh zJDDQK`W`L4pYU|#03mY`chB|f*OwSJ?|z6GU+?>`hTPl5_>^)s8428<91O3{(l0Q1 z*>ZK@e1hlhz_O7*nc32i@91IL#D+5Ux^j2L&de0VwH$>dl!#H}VvlT)Z8UHjI9uBk7Ziz`kS7Y3cyam|dzAJ1VG2{b#ITeOH4$W4aiTot@xqbDLQ({HX7{|C#p zq4k{^*9R{Rz=J&dd~P$hCgq(PUMYzV+b_Z>it6Y~)c-cFz->XAxG+?Jit>`WuIYK{)lJ~lY6$iqa3kFVnBKnmZi9~dW)7VX0 zG5g!w5K*Q6CsH2hod&=muRDGhXQmYLe8Y;yI@Dho>V0=>xxz7^GB_4k4}Jeve~U5O z%9&fN(ODau^{R*7-b?}qnIv(tm2^SGN3%~8^ zbUFN*wmD-l4rCUq++ey6VeL-#YaiGqB zWJsUfZ+paHY67-XPoVsJ###OFR3{4D=k8x_Dfbzq1n72Fm`wYq>4c^5@dd!9=)AIq z%%3l0k4R(GzK+*){xSYMWDJ?5e{|f!aGdJfB4k=7vvcm()RDRYpH)ie6&#_WwjAAi zK@AQ>D>*nayvwnIN(Z}{T7$1ER1LZ3{{hxi*bnQ3D zq>-@G1dY6{gmyvu7_8W;>+9<$*4M4@U&~1NwBQew@6De`Z3Z_KkJk*^ z3O4=t;pybzaX+_?VX=QK12MppmzPiRotYx`@UcrDx6HkNkrl97A~x{#Ka2`&uOCUe zUcy6o9&jOt6-UXJ6Id*QHs{cn-S2MENwj5{b)Im0VPnXCAVIoWY!KQcweljk6}8zg zh$=lT5!5G<`n7Q4&YQEalNWg82thMIg6hKuc^zm+G)enTd`CM^qxL*>A;@cVQ;{o+ z^5u0R(ueN6{@tA6=_EAUqTi!aQ6?5kEe2!^e10^VdRtlO(!QNB4D7gMy1gp1FI1aJ9L#r z3D_WFX6R;wrO!6r6C(@<`%qOyMZbw{hL|JYUjC33Kdaw)hI9!HIi{fcut&x4f0-y( z92B$9EU<4sM0hXtLMu2abiylGSa<;*ZS%@(2A7cVfaunkP1O&Z6mPIX@d<`!tLZ%# zceWRYva6w-aQZe9hFY?h^xD%^{>|z>+uc{4(fdp_xSDJ2{~xwww9djI+D@fY{&gU= zDGjEiM+-M=D+>_za$MLK=8Y%)L0xOWBGbg64}{275W_kb{wL_*TrNPiSl275V-o@? z$+adu4Gz}m+io$RIt2ChpzDfgdn&Yu9y!0a+2>GcP!`?N{Co;2SilZ_f_#l5FL;nk z?_C$%Pc^2YGbeA~oo)j!RouI+*z>@#XIAd*<&%~XF8=80i4~sf!i*+Hz&Mk!`$HD< zR>$q!L<$;6M!9yD#Ko=h8QdlWACot-+duB&Tk=PxyO-Sc&-)kr{10Sc5bFmsu<=LL zMAvaU({taTij7rm*HJbPUWPh5!d|xD_Y!>5l;X$r^{N6IH>$KskE=HlZgj3GO~I%; z^k2$@D{M2f4f9Al@$Dt8V`m9Jcy!IE&2yeu?^KT*pcZe>&v*c4~RK`@j> z4RRH+xa&@8C-wzP3VvK&|Bo@X*uN*1*p-$+nfx+4^fA_#wt&ZkwHU-fp6n{3A0&$p zt{%hCPXbM4P@kHr#<~nq4_kzB`?b3C4qmqUW-d}~0k{olhLIj=Sji~9xEF}JD$^JfF@p|*jq8*57 z(+_Ha^=oKpBa{niCo4HxL{VA6IfrEZ^mmM4)MRY6gxTgSv&l^-ZtCj5D-d5 zM`=D&)!XJRWZom~b?Ty;ZIvGl(I(`L1i^$H#2OQ`f*<=gQBu~MukxQq4K;mtq)6Y8 zI2M@xVg*?oj33}BE3v60<_ne{1?dMi#oE5fO)7r$YB^2JDo{->V$Wxzr2|<6R^xlc z*sT1pgTvbm${4OZyuuk27Zjw~#U1u%!t(`+iq7prEZYC!w5?X*x!L2cyn>xQZI1V$ z^mTBMSe-xvXv?!nr@-AGCZ+YM`1wztqR^^T17XC%Fq z-5!YksRx?x^zKryHYy;#US?_a(||Qv=0_9WD>(Ur2YtLmaW3*LchTu_X*lc zH|7egBH$3C7pimJ0D~Wg+lJvs=#{s7uvIeiGD;|YB&<2|eb17Q{gQKk+gzOe8<-+Q z%(a|K1Aosms>3g(@6JJSf2l1l6go7*s%u|Y3L!;TDx0X^q{XjG9lxdZ$hKj?28726drKAcs$@Cs$ZIy zMYn;-r;y_;PklgFQJ{Pl%*iKn(jxrKb(vMT&;=|WL(=0rhZJUi1{2#=w~bT0=Ho<| z91ebTw6SLq?8|N13$tr_Z-m|02%ev_OMBsxqr$ImUcC0Xsn)_m;E&^vcm!(I$0gmC zb6#sGQ|DfSIUVIA+x@JEY;sWzzOw4efV+l%{%qa3ZH}$pEqX=Ss(qzrZu*SxaV;$^ z9Vi>KOcqQbf|Gmi8njTeQ?@{ThRiS_Zho&M*nTR%ei8W%Hqy9-)uC4D0~zP=`<(6k z=PvkZ(=|W5N_-X~eZfCE2JDROQJCjU$)PvC-rW^=Y+37&9~I*fHPsqCe;!XBedQI8 z7xi-P27D`Zno3xg>&59ZAkObk9;%yL4OQid;#57?B6G#Yy`xF*1fN zTDr#Ia8WgNjR-N-+&B!~Gf`xP^J-!xw^2}x?t@=_4Uv7AG{6Mr_LXcc8e&%8!Y2MH zB)Vaim0+;xpLl)p9-m*%zS;B|mX*{Y!EP6@gd$|LFS7hcEMYnrdnne%+y|HMz?)0z>@(y zGEqZ_<78ytgblB_`?kU_`wS~=0;gYyQbgPVt=i{3&i% zNNWf6LERzl3bJd0gR;%uflTK7`}+bTw0{VD&A|ai0IhFgjAM7 z+`m!Sd7n8fDhV9aX%3Eh3TzleJOt|BZ={NE-aqOywM?lGUCYSMHoIJ5)r+)QZtqDN zF1@H7zQ6cZ=%`Tq4}>j9@;FDQ#N03HZq9t$kFimSnU3LzP}0VK0#|8oSG&7_B9gOo zg}%~?U8$`H_AK9aZcW{+$I$O^O^K~hs`z7M$BS^ms*dT17v<}v!$;%qYjSz_xc&*2 zJi}O<@ToI|?cX1H?yqvQ6t%+J3r10Za2P3`;P-IRhTl_|@z+z=twlFeg;Ye$C7}6v zqOatN?A)p`L(0_bG~D=}YN@eH!MVl+Y`j4!8y~L5fk9fzDaZcZFK;K6(tqAS?-78A zQ4bNAwNsiv+#UetsgRfGppWvnvGV8~Vuf%gucqj+8Ajarr~;$-PNBry;pfiol-XbV zuGTz$5|^d_>}t(siAEK>dHx#Kqv?Uxt}j?SD=qxx_+<>DyXjx?Km$ ziKkk1FJA12bFH!h3%$&4#RO^6dpEkGWoypVYhX6no}y{8Dm`dn-d#I-b*!cMQYf_jz+TN;o@V?}mK-s-|lpcl|*oCWt`=-o(cjeqqQgpV8P>1j@Tq`P) zIoirhq1nHJSXetLe7PEJ_=q*LP*BWxV_KI_>jt;?rNa^Fp}eUFq9o!^%HCK=p2jbY z(OPqJ*Y9u5Stp!K`R;pn@>@Op&r{}zg+$^hV^SHfPemWvn{8UYz2&aSjKH^d-{J26 zR7Ij;b@a7Vz4n{Q$?~2bHAv_AO^n(Fg2gDRHAS!%^vB-pjCs%4iME6oS*UjJ+O}eNB>xS4NS&p^WDmGq9^ZE1WV@~u**+%Nk0n9pyDxtsD3i$l( zDUZXB{?lXXLHi$ns;Z$KiSEd0l7-0{lJXPF<4}^q*GiAKK2EXfEd})*v7d->&8olh zR&T;>LZ%(EEAB$I?4Jf+;CF<-$XQD#txlY+wK&?R6G6w%@nY%lYfZJv-zC}4oMO`$QUU{l(=-ErQtzi{GOYCD zJ@ulfYo7jnYCj{UHzLJ5wr$fxKff7lslDfGN$s||#j|6o>*S{g+%PJ^uvZiF~>xc>@Dv91v0{N8#Ikp51CsDU}Km+i&ya&^V5!V}}} z**)>wT=j24v5@BX+2tikdT$t!4*Hh?)tE{>D&ZSp%SUkz{2#jQ}u9M8>HCKLz#aArl_wx>E4t7^o;`doJ zw+%;{oz(9H)nc}j`9aBIc;fUuWF08)=pfT@5Zs) zTs>}Lue#jQ-Rz#fu)tJc2AVSsltjJxPA{3~BIxs#FO!*$)?U31h?&!5z@>wfbBNJS zuUC9tOjF84>|#sY2W=Z2Q0`x;SqncI_u;LjiyXNW#89I4wq0GvwmfLHgi@fw__c$z z%2t0OmZAf0_KWPbpZ+2Y^Z(=>4~@6LeL3p@$solXstTHLS3yJ9!t78f>zXZ{DV0uN z{iVE)}GORzO$U5x!jF00xCu{|M61FA3q$Ul!$A0w?A1! zN*i}E*Wb-w9T$!4A1dYC0iq_k zkPZh&?KT%>fA|P+styszPh?r}T<`j3V=m-kM50@Bvmp9CS{Hk}P1BF^?*I;rS*x3> z#tPq~0(EZ5p0|{U%=?RJX;sj5$4dPqbtf`&_1@CPZc3CZ zHYq=)C#;|I^=l4dVJV}iX_-O%=@Hd%DR}kqf;#Z#`Z3l2I-66~_fU<@-%{q}I)4!Q8}Ntbq7>Hl0_W1ao<@)E`nySc zl(F`vJ@w4bk-Zk)U>iJNvvTHdS>VoswJr|VB>%%M_Ve?hjg9MwkB$~5s47MlYxMRP z{1bta$VXt0$e%+RN&$SY1FxDOmlNpG$RfGK%?huBh4*b^Y__{~p<_bT3=0Gg+C*kSvm-&+i!r zPSS^S_}F2qN2gn4=gQCPB+S>i$x>5hOFQhZG#*F9)T{&t47{M@^+>x{Cg64^45Tvx z#>&MV9USvQq#>R}xg@*xLQRnVOg&aZh`fPjMpk85y<8#h!q%+9gt%?$TKi*;Ywv_S z|I%7nonLAZW64>Mbms^gid9Y6?KPP%^5pd2vp9FYJ4~w#>jybR3aylzQeuH6go%Ef z@L*w?s~D;($RbVRbM%V#h|4RGalv#if0VFZa*JU&3Y^_v<#rt&W%NgBRtIXm#>Y&C ze#qnR))RyAeCJOPq-tC}Gx64{4~(SzjCITAQ8xcshR+)w6TrxQs6&XvNDRaup7m>> zFPoWYhpW^HiFgRR>TxiyC_@N(5ZuyBOl$^UZ`JKt&cWL5vyifO$Ets?(OO|e=h8i1 zHgk@Df3MX7|5zp&kzx~(1gx)Vw{wm@v>SC@39O+$o~C&1;MG$)J<>-1X})6eE2opZ zy93@(D8rvgnSjzyd=9Pz4$x9^L=%JLJzx$f?bs#BaU2mc)ly1NY%>hSF~SZTuAJ@a z*|6MXLGqaHS_<3 zXEWuwnnUXrIMpg6?I#Fr*~ijI#@>*Ydqpk!bgJ0T;nnR+N0H~oof&QswzcO4KY_x1 zd-oC{?pp@p2?{7(&7#!G*x}BN^IZ*Ok3v*dLPEml89Rs2$2c0q7mug_4sSaJqnchU zGP`$b?c(|S;YXFR5eG5U^~ZWP0-(RlwWCdl^=|PplxO1T0muU5`t`(z9}5xclRPt| z9qR6`-_twNR=_qb^t~rYXP_@~-S%Z`{)Wd`A$-@Z1^s_g!{7J7NgEs0k@M)4*;-q- z+oS?jmFFvLKN%`homoYSh`?J**GPr{El`8k)$RC4G}LRFBb0b)5We7HIB`+y%pt_T z(rKRlW+=KfSlf_|*noa^*vr8yDXA+NsukYRWPxUK1m!^kE^@Xrn~+YmitU+i4;H5? z`cn=Cf0_?BWxIGvHK!c9D>jjR0%#U)q!xY2DYXQ0A5|gkeU`(;b)7%-J*)MoSAJ0e zK--_S3cugyKIq!+eQ2eH1>etL1j{F8VD0}-&)jvl5jx5j@`oHgTAq^pw-l+$#9Du0$kNJ)tMc8 zUxUdm@vpsZ?;8tP~eBgW8{r3?`M?)Sv zif%-tIPQy|UpZ~p=}}GM2g!x_bKMJYrj?*HcH~ZgsqHXm~y3p%-&Hnds`U}D5)sqR<2uTKX~BpapI(vylcYJ zF)rI=EI;0Sknq{xyj*#a$DG?AlI7J*TzMD7@`+XL*Cy47Lt?W(Zt^WzC+v}9Cf#0P zrgToJrbhMKj!Bu6Gi(0(+ZgY{jz#?<#>>=s>fh1>Zfr{^Iq?uf#fkz+==t)c!EH~K zk~s`F;D&c}WEh?m;rLd(RQ&JVB1-f-PK*q&c|lsP4JczVyvO$>(80dPfo~f&OBf){ z3qci{%zBT3cJ2DambY+};{`25e8~QUHueH~fjDfKZ?!aVPK3Ln?tB$Mh|9E-aM#SU zn#9P4?6NV=e=0=Zt6>f}E_u@E^+v2DBu=+bOUCCdvX_~{stRX$vFAOZe<74NFV|fB zdq#&u5U{3A<@Wv&Q~fD=k|;T`9XXcw%^IMPs@cvO|!Ku%wN%fa0YvNV#$q-I0)}@sA~=@YK<}vXTMl5CI7BY*#YiX%$l|(AXsj{i5MN) z3woc8N9wT-G2z^!wacQmoq%fIwQhhORhSs2ZMSj%qifg>70efZ{vAwqZ*q5Gh8)uG zC4Th8LeLYzuQyNgl(iULhyEWQois>i*hRA z?a1Yx;o;5u<-eaJTv=iQrghNr_S|n@lFr4 z@Pv3pJBgy{loTb;rKAcGw-3Xg2yii@$94d%_)w8&73(>wDO+iIsYc*Y+kNSk?NAHE zcQ&&9{bG&ei;eXiIr*P2*0u3nVErJ>>%supMwPEcgGAO}sT?>EB5f-6aSn9xYiA;> z`N-zvpwV=UMqsM;QfO2|O)U(5{83}6a*qjeDReZEWq2iVBL!&LZpoZBWbqAp5zZGy zY5NnT*jxvO=;k*j)63|SCcTzs-|!zU0LzRxJ6d?ugCbB;JYTn}+$;b8~`*x90l>dI&W{$01s+m$4<^^DaEZ{tp&2_a;e?_nn zX`%o%cjkx9Ml%gB(HW{c+-A9*T1n7oKaE(=sfjlHJBqhJsF3`ZL`Jwy{}F3J*6y^$ z*AY8%d$`%ih!FNqj4Vlk5AY5Y81E)lv+X?+kTXWZR(R#AWD=n6-+aa`f=x;DMgc?` z|8#UXp@g(me_YBjDs!>^bmK@oLU+WOGGxgwcM%r?9eDO75AL<5YfUxEwx&SLzeUzBy9@q)M&!QlC?SD;7TUt z`NlzCS16wy^ZjvCP&a7H;NKU%4&J_f^T}*_|MQLC5LvX1*h!Sbd=U}PL4NbWJn1`D z?MNfF3$D-Ed3XN$%~OrkTC#1dwr+4}1Atr9n4|~;lO1Fs?e|MSjht&T?u9y*G(<=MUXphB5U$&m_z0q2Q5Jju;4Z* zuQ#Zk!r9uKdsG7mp^;txdQJ?TEr}PxaikhVM-jKS|6L|CEV*)OtcV}Hkd<9k| z4(?x0cYXvO)ZclN^%vpY{Ue8XcSgE`_a0SMRW-nnVqOOXT^%^y0t@R`=oOJUxC{t< zMDG?02R)$Md`Y{dDudTd4;v8GKre~l3u|pv>MFKP$$HCT3^Iq;Q7mnpZwzt915sjR zUB(J!KT+v>PNcaD5s0V{tD?OS7^BnKx1<%L903b8HGMU_cjPL3u-8*RG$a8Hm7`}8 zN+L@54EYb=aQ>9T2FQi|ZbT_aFJyy3qJSdx=7JY0AqrTvxqDPTKKSbWWd-W?#a`m$ ze{bt73xr;b_O;6WCDHxsYl%Jkwl{qoPF^689@Lgtp_T*7r)w}P5}YMvi`hn|*^*k| zo@&^gn>0>T2jKbD-TVY;5{f@V5YGZ7?W!L~^3*XZruKFqb?_Z5%5D_5jlBfWl-HRD zG6Xhk554Nz_y7WZFqV8yRwpxey_B`(6S$~#UPBu0yhhKT>^ItF*u|LdFwqgmXASnE zi*yhLRp$o-@`iQ8xR7iqz}A9xu~i};K&c=Q7agr0{Bd>Q+{>B3Pr`iNFnUV9!+LYm z0+jN1zx^OR1TN?A0Xi4ZMu`KX+%%mPGHX#^6C00$?9U;R#^#Tf1ND9=Ew((|?9IV2Ab9y`o8xyL|Z4nC22 z*6V0KTWSUt`9Er{VRZWP`%Hxf0)S<5(&=(`j`6?H_Uizay^Pr%fRuLzE)tGu7V+g8 z$BrEN<(~5SEIXb-c97X>+Nww;s^kp5ra-o@*g2*eBKJUDwmC=tW)X}kx|+tfdtfP+ zlYno5DtCPp<{LMP+x4FVI{vfj?Rd*;TrKAruABgk;U7N`QQ&>eGuO2JK(>D+!!BvelbwUb={#}Jme@UC@Xht7QoR>D;F=X zs8Reiyl`oV5eue)p}{s#qWEvc#l;~Ic%V|EYL-4a;A-9jWA$F(IaYRvNE1BkU3|>G zXGf5I8gX2_0dfM`@MS0??_DFcm-WH5v5&eS=oBnC2N=rL*_7VOYWsd)YcC=-fzoeJ zPLjTyDf93snt8nVH%+~PDQn+DR^~JN%)q^PZgB_8{)X9|DbNe#1xKW>BfP-HfMv*I zFC}K39)^;v0$Wr3k#9H`YLO7Z;Bei$By@Xb>3@MGNHq*4bS!_ZKgwfK`rd%EfcQ($ zy2@3mMvGv@ttSczpE?qMbbK+9S-BN5wJB3D;`afemt17;1N^$@0Zsk6>KT{@To8~= z96f^YE-6so{|Vzz+Bz`SPys6ZhK7CE6_-K{jiTlszrVu8r+j{*&UPdGuT6tPF&fyo zd4^ovzumhfvU|_bLSrk8sPW@&phh9O1W_NNu>x1b8Z-6DodX|ARq5@t>Vfy0oe(9GPZyfXf3-v&|oywAQ&{9&-=Ge{lyKXMd{2d zj=jzEzh5ti*kW~Lg>w-045R=(Q!`Kdl1!*}boDGU0Y&o7uww6Th)u|#bV`nAaem&i z;UycoE){jSs7Y7KgAMAuuOTJtlPQ(kZRw}h!=oGU)#5X*sNRl=~SxY{eUgbaWy_F)~0`ZGuu15H@U zK+LB}^9a*dz)%xF8od5|a7d(CZ{a26Fh!mNy7tgtc!80Jlf?KQ?puS6kaN(qld-Xn zhBTfn_BLpM2~sZm{ZBYKcrr#3H>6-%GLTpfQr=E-!fqbYUsR0?_Fr=ZNsE{I{ExCCQ zFy>hNaqz>_vt2+%lO6rHjK;BOFgVhg6ap<^V5Kh_OD%c1Kf$pX!?Dw~I>k~4;?w>( zNW>mMPno$iP-v-)z4eJ7*G8X0lRCuqs%YDIe<`LmgoEz-6>xmI~ zBKi0rM<_`P%B@zPo}3iAj57SpaZ73x@G3$8I>+|l z=^se(u)j(f#6g!D19{qOiU(tpJ%5iHVt^m}}Gm*J4H%WM{;*W}hAc@3YV!|3bV({ZD+zl|}?RxMWAao9b9>C$o!>|2}CYC!< z2Eg6zqz!0zC-eis#sgYp|0jVwt>g&HV*&D_KkP`Wk(aSJIDnn|K~WcC4#8Kpq~ z4kq{M|LnwiX7A0s-Nr6%X#zf|98t^ic#{|y>_u%K)WMNI(@XxJ)% z+&odi&(|#p4eiE%&>k7QAqwyX%;#%&o-4gmY(K|>4yTie8yOVh_j)mEV&#Wy3vh^x zMyr%#5JLsZz#F)*%t#Fa_!H7~=$;9z4L-T$7~(#Qz4Vn>JGhn)L=$#wi9udkj^Ds%A%kKr`viyAY=3(?772tylHZqh$N~J{f$OIB*WM!~X zP(M?+wBg055@OFUMNGCso!R5DqXopa)5s_hM7Ru@>@0pZN`ydzaW+D`y%9GQhBekd zhd8)*zj}$xJ?JhG>wVbuHPjJ~ZM`9>-=NzYfp5+!8zU?{;d-B0K~Z4@>K7}=Wh1ZW zM03p&l!uOIx1Zg+HRxM*Qb22YT#D@f(vso8CG+i#WS|tP4;N=y=i7q>MrwgY1U}cw z@h|}@G6+zdril(v0gV`I|50d@XaSMRzH>EqhZB2Gau8Vie#pcGR@O|K-ovqGcU`x6 zICcgb>&_`DIXNz(hlm4GA0=#VD+L51e~9*^NA-n-(ziy|2PVer4?@Su#a{r-;U<~r zeVDB9Sp}4c2~gRmvz?P1;`D%F776CK5$<;CJdDG?L656%%S1ocaQ@{?HQXeD{1I7J z>1wUg)cmjeAPju<{G&jo2s?BAFTlBXsRlW*u2UEAoBk@A9tU1GG6u@gCuUZECtj*i z+&#r9*XsndAaP;}onx8~zo4@~LbavEvE=B*cranZ_FUi}FqExrPk@cO%Izwco>E5> z*4Y*y=`me?CRnYR0K=g9m`8R6$g==i?$BdB9UUDXgyzP^#>^BS?C;UJyH_0oDbm2k~nyH=Vsn&iw5R|9=yQ{@~v90Kq)J zW`tZ>p3!o^4Ji(}P(cD)7Me)@@&{PGXegB5IIA{1y6&$!os|68dAfKv*-vetZ zgM|%PXZR6vr1tv^E)sAJ;WYH?ax}1Afr0mTP=y$4$Nz~2f^dA_0p1c)%fZRn+UfCP zKe()(M&xJkey?{uR4c{2V}!E+iZ3Cqt|01;1U>aq?3XjjN0438)R&`+4LP`YQmx}n z3QNA%3-R_|6}&||#8#+}=KR0d3R<`&Y(;`~HyE8S2)Xb?WP(~2!P&F#?kLnZ#8p7Y zgx0QU(-4A7ZSu1zum!;v*4X9STNn_2ySbE;(D1tt84W!_!(^&jN{Z@ZnavLKCiF;H9}0g3r>`NvN; z@W$);)B{}KguI%9g7j2ccVwTlk2KKueLLOgc)OTHKW1Ke2__bzpX^g_+Ph zvA9^C`(MQgdprnF7%j^*rSs5dz$%Cz%od%-PJoyZ zF^k3(-Uc|VoiD!)32xLE1V%e8PxI-K{_D%uqTnm{9{=~QcYi7jb}yhS znEELtEj>j1g2hT36`9#~GwS|LNb(B4s}L~>&1ZDd1jOzQR(R~VmeVa(o;OF*SG{JR zP|cKl2RgmNzD^R@SV%KT?%-r%s%2;bFGgKz2mA5HkCR!mPVPeGvmiJER4!e1PZalH zBG+eYtL`3DXl`^b}*i$4#jys9^xI?mLC z+%esNV-=CW8M`7YEtVETT5y-u{BZ-xT!c4wRrhb5G$aeFNZ_ z21?&t2HN}DSZPAVd(P6~JeHKD^AN1g_t@;#1}mpkfv0jiZ4-FId7aU-dhBk09MAx8 zrX}gjU6B5H2d&#V!Dr8&krIwAa|}gdJ24CY9y!xh;+TWbGH}qGi#%gl@qra&w+^2m zyV7F?W|s4{GJBY$yYbO+jzX3TZL7iAl?P7>P(YPqorc8`YJwU(dcdzwZIVzM!(NLd zK*e`fh?Ts09!U!&y}U{grjgv|onA_Yg#R4D4;4j9RVk5;Qe zNS_Lro;ePUf~&n$FgWoCmSQ1If=W(3pK#is7Ic-Mr*2)t>o^>px4s4M8TktOg@ziP zT3cItF}o1kaR19A+~&xeb&f#RdoreMc6RrAYupe?fh~p&7>CR(1z^^y@rMoeF`?~VN)zA17p@Qhf9K%GeFg)ROOMgaLL?D?_y7B^B(b7| z>};xzmP6pPEIr{Wl1aI*aJq%Ny!S#LK9Tx*+0!K@KGUd)#r08ec;g1i^KX=oh%xtwo-MZDH3#FC-#2qI%9fgC zD<9vt_Pt{BLF3Qpc`tva_M#kdb%PE;opUt%u+N|yI_v{n4|j$8_TTgY>FerdKwnF5&g9CN^k7Rv;!&lsQqkDIoJVW zIdF6WvCr{NEZ(eT7}p^FL%5J@_gX*s zuJ)8X8J1?3tcZObT1Nf}A}p0Gyl5VWW)Q&QnQrsEo|gm4@Hq`Bp`GbRXaCldk?tx7 zI>s!mV;TgIv=2buMg0|}4&s2LBm?#5Ybx@lKwOa!Eewp|(6r|2iHrFkh`1g+eQG;B z{x$i=U#c!hYWnpoc0~2>jYIaq>R$0dxR$UF5cLg;*VlO7LPA1_ARedQf<&|cf6nW< z0dX#Z9rG&KFb%}drGWKH0qnK>tF^wnuc=cSv|PG?fd$+4Ii^{lB!zs09oHw`&$Q+k zbH^zYZf7S9o|25p&a}?n_B6Fy&zdX7y4v1`?f3mB4ivL8j;6B7RhU^m)MbR z(s>Wqpc;kuR>%fG9TW-|@HC&(qOG?1`~5r6;36;maNOVWboW#Z=QmKa$Z+J)PDpTJsry$13?x4=Sx9v)M)}4W_cHX z8lZp)Ob!3Y_M#RCbSOoh4aei7D-|GOygF@^DWA$$DYZuhRh0I`-*3fU=xIJe-OBtI&8gr zwIp_2*1=caKkXJ^P_N_d`f#72)fYs-L1b`9E6o_U>8vVoMh$`$!p10Ko0tUJ!hP6b zPzW2yX1<`_5k{U_Cd{Mr?G(|W(czyaAohza#PqI5&$R%xh4wc` z?^m#KWjs3UJx;n;AVZ9hgX#t-5PQdO|GH$K9`7m003@waO0r2i5U8U}ElsEyWXLzR zT1KnXE+bs915i2$!2av+!A^qNUIa8U=c;>f@y>p8)xY47I4j?np)D*eFORw=(zXmx zJR9}k(3OF^RWiLw ztWIM9?68GKv6I!X{kkY14xvWU0g@%J!>?%H=m<@NyiKSAWep4r`uUckbMlhgpqOK? z8!y|K^#|I96rfas28lONGPm%q01;bO_&5HD(K-#wQUZ zqFSg+{&xA;n{#ZR6iI^j-CQZ&Qh5M522IbAXqsL_%j&^Ao++MVeyk!wv}k>%CRc@QdN}KACnuM>^!V(-vx% zINU~R(17-H%gzG=ibCj5kHZ(5|Fe3L!=HqU7Ti_&&9W>j19OznZQUb zZv;_WEAHZQHtDYY8Vd2dT&p&oelGODK=ieP<_Qn_e^Veu2}FGc)#S>=e%sr3K@-iC zFYww4+|iWOaVIZq<=VO%1 zyh4)(G(iR0!8*T^GKxffG3_#fBMHB+y) z0?=mxOj=&4kmV7rr*?t7({RWOaF5cYo=U@4T)ZBxwRr6tUHsXsuBvGA@eU+cWF z?)!=gkvoyEK3A>)c=R1=O7E{^Bo6`hh~2A6MD#oWQEO2>y97E-`m%}{T7o2C>4|Xs z3pYPt+Q)NVxUnFaW&n?&un}`go*-4o|t3bHSG02 zZeS)eZ2TUM_X#MB_u>sj2DUo03#?TWg-vv1L}ler4V}YsEz487r0w6$RkYdOmE(8n zJY#j()w^Wk)n%>;I&=L#B-CktyS5{p5)i;KSDKIP7x%mUn|sO;1JM^MnxMBiDs(4F z;p+$5P|ayrLZFt`O!)vQTCl}XJ!=Ax-$0^!jB2IWT|_q`1f(pmb~9o6E;?GaeJ=9B#6*7I=V3O zSIk}q7MxG`%xc?HASqGbQ}0*BK}W%x;qy)k1dQM2QV(RnhfrYNZEY_w*B(~gjGR3V zQsD+J8FlA?sTf<`(jHk}^0A7$xSs; zds3OZ_f&y^I&A!G@3LZboK=M(C#oNR48kTdc<|7s^EzC;5J2?P05spaevrWjBIxt| zwc<HKhEy#WWHteK-C0NZv!sn_Z64T z$XG&heh4EeZoSL#P=As(h^fWFo=fb@)~CZbHn%@Q#*rZAQ^$9mb%fc+PuQ?{(B#3z zbhs?t%W65KwU>iOo8!dO_lCPMahf6%trDyazv0L`d*K2La(K1FrJiPtZjb|1i^HzC zmUMk<0>o??m!CWaV%6REH^b(7!CBP%0<*+L*VeKpaa@1HE7o(gTXIU}A9H&*@Mb=D zr@fv)lcE2|gxNz7Q&t0jm3p-Rrcp*D6qMmOCyHR2T`3G*q6{LrdC!0h1RF!Pk>A@b zP56P_=r`#zqqcS_AXi3JKGCbszp%!`>ba#-<#1+xv592 zPVWMfnUE7rxVW&B9R&W6-QCJQZ(5RnhkDP$%@bes@twGrPX8f(?8od zXN%0{fl^Svc)zx`u{lQ^)Cdd+Wj}3U0}52+0xc3ZS84;_x{EZ;?XbddySH1las1bG zdT&edcZ>}}=bbg|(UOiszFYac<;RjMY+wBW_009Ar@g1u1&zTFu<{d@_57DJH@_|E zNBRy^T~{}Gf2+s}p@v7-dj?Wh{&R|vP6f@xlm@=!{|s<`ZQ}ytfR&2A=X6Y4QJ##w zUChgN^=r2oX^ry4HyeeGxt0OVC#j}YFUp8DmRX4M}7Ve9YWEMi#PIu0*37`43ql zW+S_xWo(kDQj3EGw_scDX5|WG_K3sn$uwxLFY@!d4++J8q%EEs5LBNxHSf>M_i;_U zan_5Rmq1FnYb~|hA#(-)V%lI@RW~Cio94#S>grX3N^3buPDCr(1v1x_f{lpAdF7)Y*hFJa*H;x0i*C4MfAW%BLSdHB(sw z-Myrz(`F{q*qRUH?P0DtDJ*_#>@{-_ds!$DxV5W5CURi zI)GR+ol@y8-ZShtf7h;dUWfR4gPeU-Q^ZqPbTMlV5L&gH?rd6X6h4#AjC9AEJm0Nz zogpEq7RBi()9~KsDTY%-OI(43z-TzPp*zif<;tzm0%N+i)#)rAKPW3-f3Yj~qlvhp zUc8^yK!T?L(5w}r1i^oibLS^9k%Eynyr-eZ!r5~1?t_zdzKmftdA@?tV@ve~r*3_@ zAJQ8+D#z<&k?V9n$R0Flha+Q!NhmymMpGlFPE^md)B3VaX!_T+v0xgtl?)%NR5s$+ z%9#}q-OV>);}y?%q#op=_`w(nh@*aum<`l9@{M6oB$ze@_n532eHwb|Hsf_cGqg%E<+!-7N_1vxVI)J{4jvC&7Ccu!vwSwzx(_9Z=SD z%H2`Uv%Dz{y^hnNEij-PifADiibx3~&+p5?cE)5HC_a@79^#oM*IWU?6esVrWU~(H2AL zX`fHcyZ{1pedygpBSye*$l8>hFp+P2BNeHwt7k448a-8P+HgT#xxe5&+@%2f?+E?*F$~91Sy-VI}>Epd4)1)lo|HSrESdo5Eswr5y zwS8z$$6q<(`{j#xQ}V07M64HNOws(~2Foh|t4c$)5`QyF2)UIWUX@w=_my~0uffno z2iluTY_(6tBCyBlP0pF~?9B_8-VeU5<(8ixP|??gN|(|rrrLixjnY@p(eXK6m@z~N zO@Y2KxKqChqQ9aEO(`9e<$V)IY%2eCwkV=-Iqz$x7#r)hz$iE+?l%Yt+(>rl_RCD2 z0r3$&MM`J5jBQ(FmKCr-!H9-< z@X}M}dLT4Pw%N)#bu<(ke9|y@fGL{~cH7X)Fb zj~xLEL#P4kng1u5zGbn1;*9F0AahKg24Q{f6Gnh$)r%vh-?R-I~BU zYwSV}mL8R}jLC;;1=^5pmtsAQ-oT7zm=A_Z%5)x)ZFmK85ixSItK7TG2c+dl%nB^N{PXb6&_pY`Dyu;D>&l+|aowD7xToS6afKC=E zAUC=zFXn#z2%3dg&U%l=0)MZP#p%m74j|0BB_~t9O0r8vY(LYP(H4*Rk)7Z*E{ z0f0T_S;McYXyDpE{NoTBK(V8zHv^w@7L=4Q7)`dyzcY}XH`fURyQ{|R7}{AVYV#BD zm7IY04kz!9~`=2+EsEA{1VBeEdrbNfx|d zp_T3-tO@k2>`(a$hO4Lxvp9~mS@aOqhlk_%CCY%%n$C8M_?#z^Un4ngM}~HkA?NDz zr{8*-niRf#VhJg5as8=;v0E^7aangVWLe70z@ZAet80$_uW~A^17F}L9fbnDzY2sF_J40eoY>pE_^^D3(6F!l-8Sm=Z z&|m29kWxw6=fR%Rn{zu!czabH&`iK#a7!rO3(j%t#6LrcH`vt6G_bHf< z(3ZlyCN#OZsDucW$S~s%4tE7y=vA4d!+Rus1I{G}{cP`~!JCl=3Wh|5X*V`x8{M%8`eQwT6nz5> zh7FFX5O+;B*cy770zAwN$d!G)`1lUMc^`6#=Gu=doS=mZTdDk45B(QJF^G$;E-0AB zhbi+2=xD_00}UUv=&Tj?!-WHNE3^4hDYKEV-9%kB_28uJeOZZGAY#_Q{tGqi$HOMM z_enXM4m&Ph=HVZw)0VVgm^1uYgS})}FQP~{4KJnbehyF$N0BN!pcHHvGX4|U9Kc%C>WK$>^6FELhCti>1L(Wf&)Kar7SeQX% zjSdnrs6zib=|kG+1C?U2Cg`BbWU=rhgQ_FUnIfPpquVjQD!YlUu>SI`x3C65?4 zA-%v;zx3c4mj0gPu*d0Dgdn+EV&?r1yGQ3gQ+g1fXyl06baic!AoN{Ixx4fRpnTtD zt;3BGHZ;~pS^P`vOkW)h#+V=^Pi6{9qd;`hAlWGH%c?2m?KLNv_pg28H@i zOIYMDS?M;W?Nd(IPy-IhYMDRKQMqeEB3c%tiyyS_hIHg#Vy9-}LT#Vb+oRYvGdzJaWIj8x3vOmzT3>Xz=tu z5zH>Pi)am6Vk0-2tb=-xf&|RW977rrV+BBw@2%o<3JD`Wn-iG1omm7l7+zmw#m%Np znc5f(9Zbgr7>z%^yZHfdT(D27b10)lEs8lJCxvAQSzoUZ1a75$!&K#m{|5TQaA5E> z0@sI|JZw2SSKLmnm06?EBE5Ssz87Z0k^EPk!vg}R-G(cVH_0Tm{{Vr^vuPhf*qRC2 zIaD;cI(%rU4BI}y{7P-A(k!C^3Trg=ZPtQfECJd&yQ$~TP(A$T)D8;Pn*Ne1{~5~~ ziI7WS*5aZ2mLD8(;N>pcG<(gM)MHCA-%vme7`s1t>xTfe%ZvyIuX_?okhoqiE4` z>353;tg&iqldds8_`$6u+JZNP;K02m0|;P$D{Z#@I=eKOW9d{1rRE$v$F`Jq=?OL?9qIefoZz zKCt2{vqnW3vr(4LJB;L$ybgvVkij~9vAYI#3c&ufDLy1OIWP1};?dbryPF_f6bMxY z$x*Z)BzYd1+RBbxH$gs1&MY$!A)=K-`$1Z6zjd$MNQa^NRM>Frpi`OcZ@`njLGVCa z74A2HNNK%=t+Vfa_5-Giykx;@6d(m`^HHfCjFh?kM2@f#6+oo4UjWEhPhBa|t4rw5 zFEQz!pSX-TR+P~g+!rE_7@O<#K$(}(irT7039qbjMV2;uB@6J=#GcroP ztyT(@G8M*D{Tmf+GF+iNDM$0xKL)0zJI+g++1E|^*(!yWq-*=H$Cw|R>PT>VJ<*|C z8J~ytwqBm0L+&yYa$unoPluWKM6g-hdQwo^znAN`obVVYXP0!!1h7d4q};m8Trq6v z0EUp1ceZQ`+uW8_7cI>f2GhVKNUQRg9}ei;58&h$4**LGIV5qviGe?fy{KeV5K=qs zu`VcAUZ8W_HL>;8Gip;Wll~I5(fSC+_0oQgaUZNuaWRUw=dm<%OQ1*a@(KcP_8*y^ zenlj#WBX9b4EDN^4@I7c_M~v z(%Gn3EI`F21NJ=Y9uA72^G}F^?bnn~!SD_FA%hhO?*c}<0SmTsxuF{jk&EnUccJ$}8tz0K}0o6;lxt2M#ezNsVdr%Mr*TZ%b5?DDl z>#Z_$;EGS$=K?5Gmv(ssbl$5^C)T=Re?cu#;rH#xKZ9=2$XUA#C7rdF?4 zy*UMJuYnp5)oV(8(l+daKWD6d##@QFORRcOMPx++%2Tvhls&Ug|{k1-whGyNI62AY%By zFQM@Z^`=C)+w1o<$Mk|m(g{nqmNOoa)WO;*sh8H0*qL$8W`^4LGh5NyiKbJm@}Rdp z>m=n3UEHZ}6w%5HoFopQpUI7R+iJ$4>~o^^`wWtyMi@tgXLBrc+gf3%X~V9ZO=Ufa~`$4_2=Ss`$9(|glFz*h~xM3ZLmh{4vnTd0u!duHl3 z&-aKu;*B>=s$ROewJ~?o+`7UYOES;pxSTt2~Pl>by$Eah$@HqGA(WzwIVb(^tYnj zgQgtXm!!>BQ>Q{~xe>L~POjSgMYPOem*da{^^1FSP4a;G4yM2fnpFTme zHCPHTv%UjZB2k}N8Nd(RQJ+0lPQy@Tz8I$)CK75wKl~wuL+B2;|7$&C^4Snm88<4BK^KIxdQ!&KQr>UY| zt)vVIRDzB~qMI{N=#i4kRvK`yCLYzd4f0eE<6O3yv&^!+uR$kZ77UIccru z!V7ARg8Evs4!J6F@Yt8c29!Xw#D4S95R^Sc@8h@cKwWoE`YAO0{-Bun>BD3{tmJ91 zA$_1+KMZYumtS;HiaZah6-kJU1|5{og#6vS;A{ORYCn2Hj+I(2^|SWb#^Z(8EdA?Z>x~2=8;`KoY$Pc zfOF#M(?e?>okfS46QkQ2mj!mhs;o^p`$UD06{>@ojk}T=bJg4#l;Q0M%ZT@ zQ3B8~{FSA^f3?MLWwFxUrB=tO)2p2+WPesRq1E>6>MYlUG9%}iNM;B%`q~4jIW3-y zhWJ`&85J!A`1R%ym{m4vHwJ8Ox25GKXKg)D90sZ*CsFALcP?M{3KzhYj$p)S)pKkN zy~!ei#t1{GtR4=F5%+YG!fpvW!x-42d}~+aIpLv!53|3@53Oc3pS(b*7`EkwE;k4) z-f(&#m(D*bjssIev^%5`&m3Iq^oqqhT{SEAIJ4zG17YNS1tM`nMWgpT8k2Pl#H%k` z46?-V*Y*M*0%dMTE=o}?n3n!%YzSnaQ66x;K{?OO?Zo{?iP}qZglNqwCMayqd*xne2^Wm@`5G>A-31hUYW$=Fy)x z#R*Mqf=T>(Ral&?Szx%CWVApNq(M+K>A;NoZCR0=rVs2f*klqRyrMC7n`HLAmSy>$ zMUQ-;jQ*H}cdis7=xKeGqo#4tVB3L&{at93A9OKgNJM|bF4k&25Ce!sVOc)li0wcF zqRa>)-YX789^i7yHbR)wxSDLS4C^?}vA>YGO!%uAhzj}6=Q%UC+ESi-_BO`9%yXQi zXH-eNaibHj;0~ZH83&$5W+ZnzeMpKH|EPAW^wSJNN&76T$mzFK`#j+~i}8reXeCl5tE;$fSjFDWzKS`u2(;q0l4Zfh~%G*y{i_yf-wNXNt3 z@+t^AESZ6LOFZyNH%L?RLqvg+C@$LTJ`a2z5cTh~#*i8$hTy=^ zcescNpW@UzcfH>V6`DENMO<|Ulo&<7wnndibvi9V(Sma#OfBn15B_4io`KaxgQu>IdDr2*!nmOB87stv{e2} z%dLwx`U*xAsbeuLq^Ep(2%8^XfB3ZCI$}TV;g}1q%)U-a5oaxHaOj9@7B}dRLG+1; zu=sQ|E0u394+-VhflX0TG9U}uUv(o=k&e+f)}8+)vbr-51}+>sFw?7Zhn}Bji zF7OO_QXofX-7P~6rs3)4Gnrukd{;R*6O3}0;!gQ zi?*$|+kxmxml^Zx3bP|N-!s6&>bi~F_-6}0FOjHa(sNpW#3c@XEI}jlPO2a4LCulE zBbPIOLG#@?^f@{G&zuU-AdTTc#uz0W*yDAH7~y@ec!fO+d}+&>!HZkJ4r5@kLot1k zH2lx??g1VD^LQ%r^uBp5lIkWyDl5k_!ZF5;O&_E9d@Ts zQ-VhH$uS!N5c~{jy^DC*MDXR2NsY*h-LVuQggyH z?+bK;y!;Gc3brbFPzVFnRZBpnh7TU4EbiGuZh$&WgIs0~h?lRaG!pB850^bd9^*R^ z*)sP}oW-NZHOq}|C4QppY7S&ldr;78CEGtcIx?aPQ%4i1)l07D{FHl}xRK;RpRAIc zh;X$o(p}^+4&JjKuVS@`gP_&)J+{pICrVEraE}yRm#f16PtcL#E-vWY zPAVCmRCb-8x&@@Q_c9o_56!c8nE8XKdLtvM`Wm!A(|fEv?)pjnCO9X(4YDq*i!k-> zQ?mo7yLL!50~rsmq4P)`y;y~uN6bs+pDE7t+*G6yRBphG$9kp0x`YY@Yhl)hAvi}2 zL;{k9iA|uI%>gntZS>)!tfRR1mimQ$zEcdJ3@#3Qf9dTB?9kWOpAZ2H&@`0Idv_{z z0DFQi`W^;*)`@7QowG;zqtVFAe%U%AYuLc;o}M3`@dYV_2f-n)Pn=~nb3S}LTk_x` zoOX%hlP#Mv<6Rpt2$E|XX;U)M147DmjfU%Z1;%fuI2r_oOY#BFzYwWFuL^)B)7B;Lnc38j~fx=NXbR;Govd{>07 zUcH*3U~(&#RANf6IvPQnxnu-mig561-7t&|GS7(KvH_zoO zb;5O`;2eIZ7m8Ph1HVm(e|ORAAJ`z*2fgw;#x}-D-D$f-(JyF+CGxf9^sN_#@j5<|36C z-nWvEN0{2(XMeYC*hf}s+seu+6^2%h2R{Il?>gO|jInhiC%s3I@A+d^4_|Po0P@K6 zpKVZ^>V++pk>26SvP-RI;Gyaa>po|i?YaL=lYePreVQpb|DR~o0S`*N59+Xt;;f;a zFwqa$a^`8C68*DhBAk#G;%?VOc8tsB!R_xxv`xI1m2vb;7n2_ZJaUDl<6L}}!ist@ z@^LVEW()cvq4)@~mygyIHXHM{z`W1=N}?Y=6n?W_Xu|~JtV^h@j@v4snKlqpP5X+M zUqrM;zlYu2MDhyAx-&27A~RvP?n0Bj^1}{&h8;a3bh_a9D-j3t*(M8uB5ryg(6qAq zpqj5wRefm$S|r(OAkx^;k#xq+KMXE-uQ50jl6*_*^+a=2{z)RMLF&cnL4z#JMXKP+^^ES#e;4%M(-q z6v9R98K_0%eEGD&B~pKK1w^u1Ij5eA&gL!=bb^eAV#p&{6_qCxQ#QR>rS|e{dxr@Y z2)?n}95BPoaKHDXI__aY_^qxk4~hm=*p_NpnB%|u=KKbfnnx(!MxX_mtnJn9t*EJb z<5S7lv+Flb7MFs74fjSmX8H#y*C#V0aB6BFt)@#;C5Q}~>dygqB#~h@#tvxOVL+<4 zezXBui+7c`9LmN1xx7@oc7wn#z%=E}Ax#{v=#PFQIQ5qzOh5yL+U;f&G-TYZfZ)9; zsEgbuSGG}74g%!Jab+3aKt8ge1|m-?C`Kg8uyEr1K>wkZUr5mf&qj>xlwPQWD53sM z-k%5>O-Psf~L*ls5R#YpIXMT`t z!*1Z86TratOoNRW30K~l_tEa@0ie}un0zE8eFl6GbGLs-ZPT~9;;O=8?&m=-8^O#a zep(NJak`)@k-N{@*8=G&wA?dT+!5Xus@Ff_{~5lxoe2`J#NBU2XYdLRlYfI<-&|92 zwomISX{2`g9eD=#XSl=^2oCcw4yJDeNl9Gt5#Dmx0B|yVvvFGItj&?F&6xd#k%`R=b2fZ@VfY?ZIG zvAG}ypb9hY@LL$Yph424%T7#TN06CE4>-*jfc{=>j|LRfGqB{63&C7H>j7!2gcyZ0 zj?GOB6r}np&u+B{rY8qjooI+$#c~Fg0Gzf+Yy`lfSXn<+a_F3~B<1nmW7&dMbEPVV ze;lTWVn{cN<9xDL-UtxrTy@ESUAP}Az~Xuz{JLjZXvl8h9n)WlHfjxMd_GloQT*qV ziGStJke2~{&e6Ova~Ms<5jZE4#WT$u9$H}%{3X$A>e)kRbq8gAN|ji=0wZNTm1t$< z)DW1s~c|w zHNqCIv&TJ@h=K*3^ZTIKuCJBF%QF^vhRw=}lPxFmaRoHIzuFd9Lr?~lV4U8Z8M%*J zJ7sHpL#K!dys>ar3NJx*>25xK0io#Wm7LT6ah*;{NqE3KnU}B!KOc6<)N}Oe6tZfT z=w)$^6zErb_R`m-Boq z@RLsBVL&3cN}hj)^YLvq!-WSpk55CGHPZT^sqF04?IXCNs(+%IZk)rd0(VlTa|!!ACgROkw$U(a(!?Wu-v&%f(kSlL}o z^~gPq)Py4LVMKeb<=<`Kt#Yc3GOv>fI)Mq1gTR?~_~eP~^K2P+<(*b8k`Brg3hF7S zz}?%$IdNzqOk7b{`NwU9KT2YWhHhQ2j_(2K%B?5}j^@AvmR{EUR=-8go%0~1bPC#< zjkQYWIVDFs=!ENyfWV^Cu)T6l|=Usa=Z~NEhlM-6efZ9PYPi~eMqv*mW z{g7~L1Ln99>1Yi9>==pPv{{xbPP3#4)+%bIX8SOU>!2cdyybV~eu){v8Xb$|UAd2I z`Lvo%_xG)vck8st2HI%ecwN4_Gw&B{=CRH4iPn8h3Z5o z2rG!fwUHq^#P?sVUp0X$xH6h{W)8im3u4voPf~iHBx87lS`7X&duxkx7=r)9Wi(;k z(ArM?;|dTOcrLBNFrT-r4`!x%8>@2-Jxwrjl{|(eAI4pW9Ce)`zso)Gcwh?TPb<;? z!`FAmQ{BJ+M-)e*tRm93RY=Gz(Xis!BxKL5kQsN~4K$?4mT~Moj@?kQ*TFF>S?8dv z?BDg$xcfXF-^cHd&wYPxk@J4PuGcl6&*wD-y0Y%;X&cE0{N-JZ$ohp^o`&acy1WqtDc-rIIpFl}ZlI@(cC*OX%quZd z%lL!cF}ZhMaQ=+W)w_`5y&ZH`7GORuwe=i!RW1|61-f2cV$)=qg-J@!3(FX5q)_DR z(eCJLrbFtteRZ!?hrM;*@wZtOUF-{!5v=t=#P(0eTQ9&da>u!p-qQ~9h3oRwQ)oNd z;is$vF@4-d>TV;ed#z4%{9|c%mTfSFgmj%|cu`+U9a!bKmEmXPCoHDQ z=3ga2j19a2F*{2N*YX%w2qXRq)#^UAC=tt$hp>mk*mHzMQ}+~?3QJ$157rNf5If># zU@3b*H#PKgr>T08{zVjIIWR~*h70HGj;m^g?p+Prv2l2?l2b0Wn!EEG-Ov6Z`bpl{JclziE;o! zumiYQrMrswOZT%Q?lg_?Y0IONX~Tjgm2pWdZ)P38Z|gN`t$1Bc9L_YicEVWY>X!&!&41MK zY|K?^&yiQtuq6HCx>M^tRu)KXMUV(c$mRyUFI2_e-7o7~o~fIA(7_#dGP}M7a?Uc? z;8RE2)&?`xs%pp|rl@+cr59L!B-q2qp$G&tK6=fKU0e3>8CUzrML~a0A8I5Qm5di+ zuAF2sWzk2H$T?L&>!3-jQU?#0n+$fep#Na-ud+Vu+vfU2msqyQQqdH7OMbnISK%40 zZA+HlZgi5XzXrRTvgEHlExvO#PB1R^xJnG%D8c7r}gzz z?|m$WcSX(8V-l@d&mp0lFg{8?n|2WHSs_%dkGNhK^oHl{d~yBkTRW|iOM~}e`+3ij zhS*}uQm56Zty^mSAAr=to*Zn~QE@(iu~r-vrCfcb@>>C>()4 zXI92!254%4$9)&VX$$$_N1~tfZ)rWlK zd!d_}G?kM@zIt<*`s!Bk4omu{We|T~R%8Co+U;0*bcc)kPDJP~ea?QMoafgsu;TV^ zqdVZ?Z1f0U1kbgrEHpX7LYnVFxWwuKS$W}-F*QNVCEcLf2ktV;5z;{cTz`rq`uvuF z1}2`HLbBsYPtL@?fQi)r;@Fm3{^RA4-2!W%;k}8Y_vZd)?0=v;%)7hs9@*nHv%m+( ztYtwb_yWU-(|bl99N1#Qz1&+Tsa&UgehlA3Crcgt;4hXO#nO~0q&pOXF4JFR&$6h)G^4`64mYahboYUu3X}Esd7eG*;?p&Ph zA^L+Fackh*ir^vM7RVUCT&H9&n1cYq+`9|wOc3q*U9d#mH?|20;*oq$@o z=}(d=II`D1FVZ9h`e!u)z~+kB~c~C4)wylAQdL>)_%)xBmit^Mowg)%fX3TZkjhwH1-7r=N9!zT--xqwnXS-e!r>mj``zv3_*-wD+R1^0F*knP8qGHk$;dVMhib16cy}#$U)@&{7$hjOY2rE z8goEGEbm8PG@;Lh0#!=Tlcp(7snv*M__kX; z_yv?eJ)nLU&gP^Ow+6qV>Gl$60` zD=Vz^a()vTDQayB_7Lh!F8{qm?33Ven73QHpDDzRR+t}2SCpk2XcAWHjai!3TVWR? zeSRVGxxX_hOYJRtjOW+ADGY!~Zl)`}3N4y0=p!U8JbZ}!Jlan(d&V#mTCXP>)id?D z#dMcEs#c6Vrlp` z!BnMG9SYrE*^50D4{#TbltpGm{D6*<4J;sX888K~Q6Xd&k{i-6FvXLLh#2fJ89a6c zEUHvhbT35ZSejO5SI)JwV7)6Z{RTn#e|~y!aCR798-l^}zfZrjj#+GjjGsby1bpmaMdEA>A!D1@MtXu9tS%Qw|5B*OodbO>*!$=cFWo8T3hk-g2jhfw zVX{pQvaHYtk~&4J`YMF?bL6ledVlNc-{O1#o%rA z9+mIvIej!Pb4oqMcNVFX4eXpUv@P!U#nYFrEj;gvxG3B;-w05(FRr|PC2Oc&gxoge ziVoaw8uJ(aG5NOdu1M!wgCvIthnaw&xHtiNYSNbO_o`M$gcpG8C-JQFn?BSx+}EHO zW;)-9fTF+aA31JTir^l|S*On2`euX4gH1y1v|kv#zO{W?OyhymVhO!yGd~XH^(pF7 zZ%6@f#xWSdNGEUT#gI@PN*7~7V2yN`Ql6u4f?Usox z4f`T{UZYkPIhxfI{y@;y7|Mcb#KMw_3HboaJD-}i}u zoSQv-+CD>4&bo;`Q!kk82;zyE0I*RF2)t|^xl22EZ-*;G(%zO1(21Sw^KOBk4KSx2 z+nW$$Ia%%sBa}C2}^WWkMcj$DEe->1FJ=TVhYK zE@_Uj3?kev@$~W1PxI7vHS}*y;lM=NT|YcRlU@~u&$q4Mm$+BTg>>|hwB%LVi_hDz zE2d2p$cs^5E3eFO&DT_Zlg`%+zE(w6UUa^P{|!@N$9-J#?Pb=*~6D=*p<5${C75$FM7g~{#(25=lcGNYRc-v}uAHnj9 zs5|Dqr_Xq{Fpn6$52GL}96S9&I`S+kTdx0?Fl?_IWs#HjP#$a}Qzcd2&z zxiuUVGfKac-o-k(KE`!+k==m|E!&VDn3@@8$GbYzUk%qHOiAus+K4sw2AMxy{P^;+ z71>pWP|ACS&LebpHfL+8-sqTeBY9mlHqkiz463Ox0@SUhx$X1!v&;?_!qn%vLYcg% ztoyQ56wsOJ_sjH^T4;3Zs1P0+v)sgf)AAERf9kOKu1u9M@0C-0&z_3v@crj2=UrKh-N@}Liw^%f;4W6s33-jTBKoto|=!S4VE z`x@XhY;TBf^-|zBO*y+}YvwF@3T6AIZ^#$ul2*?|s4c8TM@7eue)n2WSk#Bd`}LnF zxdk1cJLEE%*z(G)I~Gmh1q}cC38NBkGuh^mCq90o7Neu3w^|lGT6^K|jeW3!U-jb{ zCMEa??a!W75pXYi_Kok%Bhs`eh_|nuiC|b>7t)uCe&Qy`m`3gC$96wj=F-!LcRTuG zKGscEaNUn4xEYjqKfO6GZ7y#5h6WGluMDjUvyA!|YHzR4uW0+45jQ*|!g&q4vdX^K zmt=@+Tm&R1mveO4RVQz*cw5zM(&I|+2Xkk*H)h|rl(}YS&ZOwvpNl>}RyaKMFtO3d zbN<8h^!2HcsRbW(fl~e|pIQB;&}ibC5&TEC%+gZDe!T9~^y6qfIuA$E=z2(l{;)^b zw%yX8V%#L%Wt|fJbyV4Pi}gp?U|yt)*t)sO+!bSVF;Z)#%Utcza+?uD4_B2QYR z-laP$c&!f^EGuwK_n*#nu)Q)4kbAhmyJxPIqn^JcK8mOR0adGOyc48w=M4+FLO>KM zz2&6W4>F5F$JUxS1^e7?@DWY3fySMlftckVx$P0(sU6SHQTtk5{O+_}g<%JHht1Qq zEO1{=sN;7^=Lm?aY*;W$Vc?Q}Ak^)8ZCos~Lg+@|a@!$RDWBX)mN^Z#g1B0;FKLdu z%!FH=;ijbP7~?mejHm&qho}~eL%UQN-j&zZd;Q?l@)u#1qLwM&Civk@s(RFV6MT7? z6avCacNqfbok+m7)G?Wkup-a-U(mEvv{_!6Sqb(Ll}c?6SH5lH>f7R(U^1)eb1`5& zj`C%0x3x(uA?}C|7nNApS%R9e{IruhX7Zd3W)+%eB9X;`*@SbpDZ)V&T&9y{b@pmV+ zgKDyRbsV!Tqecj2lnbvdZbfQ^7d(@GUogx(Ew=$#$4S~+QU2ZMQjh2;awnx zesb-q4E`E#9zGt3D2r(;>w}=m(mto+m-g`efBpP0I z@V7wr)cqK4-WD0NcRSi;Kli)tPqy3+GqG|eE5f=Lz1Kqf9XP$7B-^{nDzS<3JI_B{ z7|=k$6P zp-+*vc(N>)XRE|qsnLu?<$`?kDLP}9H#Zzf?tUrF>*-l#^-H9%P$KE_L|y4<42PS^ zDc3WupY5MbtQVe&3r1o=v!R8g{DXQhAm$}9MvOXh|g|Ck$8Ss29tt7N37&dv+#%TXb>U*CfM z$3>Pi^4BY>9z|yPd}oVvGSFUg=Xk(wKUJTu=IghgT;cr7tqJMlb#Lex`+T2W0Z0EO zD{#|K(M2rYKjkq}*U@~^mz2<$5&Y3;X*_~((rf2BEWl_lo$8vcz9||_chzSeYl)2< zc|AFMs@HxS_`~n(P0ba~CFQXYE6lt42C=?V5Bo{)GZa^JY*bHm@aMBmt#7`Zg=bFQ zG7`1q*2;&qRYLFSg5zE@v>Kbg-Q5yWw~J<3;Xv2S*(9F_Z$s#U#|EWad!6GMD@tSO zsNpA8{_(zEz|d;8L@CSVEnm`a^vKEkhldV)X^pCYX|ID0k5a(Q>eh#~!NmFFnhev2 z=nW6{O|8cq=$o2SDCzGHcEaN?CA=nM_zk_ug`T5z>Lo_kwqjiv=w~iyl^9)(oD_M( z-^bO~etQ;H8NPcFE!XHcvd}U)|0<4)#NU@KTrhuJ>aK7hi&k63l`*Aw$~AAEeHTik zxpc}ljFcpUi1WoM!WcKwyhMCXm4bo1R=y6S4&hW;mgdam#goRJLWvRwgNXf|eYIo^ z%ec$&jrrutHy!i2L)@rU=EoL5d~Pt35De#?$})4)`=iG{tzlxk8Civz}{}es0}y{`Q23!Alm+BSq!D zxtx8uy`HB&iJcyBxlYZhTn`p&s#^%3zkpY)3k>JQ;4>}s6wP15Y{}!tH z9*Nu;HvvEyPk1W(1s#t2t!_B7f z$M(n+e!nDiVU94>lD&LWJ{zQs#%8+aa~Vg}SNc_5|HLg-VqYr4ltvJ^Q>n8YOO4H` zNxy+7KFDL&8WsB-x^3@DbU$Cm_WlUaJ|wz`!(Yp^3*LSF4euYayp5+a^-^wI$y;;< z?kJA+{Q9D42miO7#gjewZ32^}w?etTtvq<|M+$7ppk7*yttU_U1uqL=TO?D@!;OFD zv{Gf1+7~muCO@+9Ble%ba&<67-}1mp^zW&dro^Gup#9H39jP2u;w#2`Pn^Ffen?&n zo<9#gKYBnaP6r*9j}k6lgM99W%l2ha#4YE^6J%Pq!2wo&)0{WPo?vO#9(XnX+mX<501@3;WQw<=15 zwT1G0OfJQY_F*(Ry= z;k03iQOzen;rGIN*>SBLcRDNEey^g$Dj>Q;vozWN4v{VH+Zplkmr33V(m^oSwKXpE zC}p<8+)h)IhqTfoh`5oNUE^A|(K7giGN!Dlb<}M=>;_}qg{zOpUZ$=vVUuCalS{X? zKW*_HS;|&bKmCq00t{wf`dcKWMY=V{FNO_Bv42UJbp!<|pDG{Msh0VeqIuZS06Qtp zzH~_(*l!~rL=-c5PhK}5bVZ6)3+i6!aKg(F&&oe>3MUr&Ew5I<&>%X1lRfpwotxtD z;uC(q_%95_wzO*xvq2}}g=bA>utm9gOMm(<2L|DDU~BJwmlnggcF&5?wN>L-=Q88a z4p-^;o&Zdd)z)6$xb!-tG>_v?NZ&k8+%UZN_+lAA4hhrcAvBB@&gV; zXM9z=!0Dw}hLVa9C;W=W#~`N_So`sE^w>y9>6`lfe%B2LV(u)C_9o|6d31FGe);aA zQmfr@Y%Mvyl40NJmQsc}8~E74KQ9Es2Ag6@MNT8)IU>aC?5etm)VsuSy%vD0MPq$n zN(<$2;mwSq7D+H$Fm+kG@t1mse)^paVz85UZt}V6ZgB zb&J`Z&1YTtit7l5w)YnfcxhBshk7)#Y*Tk@Q5Nj0_Ja#eO&7_N5ItyFVBsrkDa#mkDaRO0BKZwx!y5XwM4#mWrKv-mKF(( z#qIIQ0e;IqHOazG1?3h6H1yk|PF}wl2XT{NKcohwlhI15%u0oLR|SNxCAD_TF3^_$ zOm($X5{mHBnK?ufFT0@Pbn(X{A$Q94wMxtv?7*L?p7>BTKt3W+61o@xuBf{Mbv|jl6nYg?=N>VprzEXIedNQ zj_jM@i@~yJ^A&W8ilO`e?iVeT7l45B7g%5g_nk03x5YqUnGYqj)687j)kasd-t~&+-^1b4+24V{ z^2`17MQs@eJ~%83bPNe$!{~yCu=CPdyNp?6m`kv)M5xoSoY;*Ar{W?T);h)f4Rnn} z@K##_eX}PBm|~zHmz~3Qi`lC3G;ra{qDhsxYeQ6lVEyx_-aFwf6xw!d1DB!q_235^ z^%$aDJoH$aJVss*h3vD1ks>#>RvlFTX9HBp&TISrKo@J#hA)ZlJQ78Sm%cw8y&wVH<`6fJ7MGYo4KU`-#@uW$-rQ zjo*Kc$mQYfN$xwc{0HI$Z~Yl9NRSa|^KI)Z09a_zGmwv`dA`eG)JR=@=v9O<8Zf3X zHi!`n&7jGAfi@>_ctKa{6>bFR=dt;bfa%f)c}+pBQt6E{>;dBgi`+Of{w?g7vdLJ) z-%qPok-Qwl!w}qeHo#-8n6H1bYQBdZOtpo5c`{*ZM0LSWntimhg7wulmsTA0k?8t)WfLi>CC5XT%3qF1HzP zC7aT&ZX=j=z1$Jt%1{hVk9LqOj!SyTY3NV>??Ba<;19Q*o%WbgYzKG43XI1eF^fzo_ zeymqd@~v_57R`6G>n->I%eF}*&GmXRTq`7OOQ;4kN1N1O{vUmjWSDq(Ic;hWzd*JUcOw;ZQv1AGN%HK&CaK@}bQ)C?km5UK zQoY4;>vgG@mMmp`T1gK%`zq^;R?XsO+52Vj^p6GGFnW8ClLPYDQuBzHuV*doF=lJd zNWoc0{A8pM-P)6 z?sCKp;asA2s9JM3C~+Fz#e*5Qxi=1|=ae1VHBKuqS%?;vyWck8H7N+8{@(24)nWIw zMYJsukuR*@+YY zh)HnDwWFZG-o{cdw1irSr)p&;{LY&97(nMR1xQ0WO|_TqhCx)~K^@R@`Ujq{|CEja!;|++dl0 ztJ?{`u>dfV(x6LKmK)o9>4S|*rfD%g!@TiS%;d*tu~y&cZ?c{rk**lKsMXMtBjh7LzU!ipf** z$JoiWv5nw$=?z&R9NW%M5@ZuTl?6`3PfTL++ZmNv0$k~#NxO;w=Wu(tnJ z#a7;KwDJ?}RY8!SCW-TY_klogV?6}L6#uIf(hTZ33IvYG@H@?JRW}5FE_L%S_TTnc z(73$2w29E*JIuFa^8#_(KtYszXnK1+w)oQsPAcAA>eiQvz^t`w{FLOhYR;z2x10i1 zZS+UbYqnh0$dTTtHg&rwQi}v#Xvg<+pr90p7<)l{ljq?7|B8cKD3s)`NnjnDWm!rU z95ETZCC@I%pWP`z`3=aVTxyMTMiEW1kRVvbb6OFLGHt~c&8Mvof@SOY6zzcd;rR!9 zoZpN-hY{LVje$(SVD5~I4a zw+%$!D~g;8%4%deiR~8kYac9E5Qg0X$s&wL{Sf(%%;5LqY%-Ve0v!bvD%n8X{tNtCI~X86Kv`jp=~<;TYU=*92b=sEO>r|d6Js=r!9 z{6ZPd>w=q>?#y!fyP?d+T}m_dv80P+lxA!~`xZ!h3HJFXQJ`vtK*c23wD9L80crCj zg|s>0wYymGClHCS00+=~lG>duAOV8DaHLMM5CSE1L*`6J9)RTC5oQ`*^<;PGm>$@& zR)JXAg|$AuNg%5OJO0k93|~foJ;sM}l6Qz_0r$kke6mvwfONCll6Yp;;r4c;je}Y% zH*DF<(R!D3*xDp|t9;vE2S;Vftd50DFhcUSHr=Vl_ep^?zT2bIF*#FofGxUSMu>BB=RmG4xH3a)zm_jWrFhEyB1m~Ftf6@b(I(fbkhx$8n&7=4{Z4z?^k$|fk{TTt{t z$bNeOImD!&1{p|l-bbNX!w_mXh5#$H;AxoZJ4k16Hh%P^|LL6f3g&oB8*AP@0gN<~ zFR0Y^1F+|D>rT>tTn9OK;JP)3d~Pt_gw6j1Rx#d1&|ejnYvqxHBjsJMr*}aLUQ6z| zk@R|c6s^SrKPp%t2YD~~@g<=P7vjwC5QEX`9wJn}W}um-crGz9R0e^YtYK%b%|-n- zUcdyZ1R!P(%!Q+y#?L?iC**Lh!E#3ujHnw{eE9w$0!+dIM9s=Y7(3Hpw?h+%fer;t zX*&Cd>ufAZ!(mnW^VJC%6g7;eZrh50bMsOv3_sH)<*;gCjN5&9d?b04G|V0wODnm@ z?mv6rK7eetw&DEWHY*SSygvzsc0?Zl9f}u)E+l$NUT*NW)H@Y+|6 zhea5O+XRb-kK}p`i$`OI7u2Vxsy2L)&e=h25ky->c!8<1Nuei#=pN4OZV@;aKk=14 z$hApgG|1-z?8P$yOsC_(v?jDE#&L+O1j-O%jd{#z)?KgA?rRv}*+HfJ{otoXxQcRG zlt4+$MI0<=)wZ}uKpq~CJIbeFyt%j{>;fgQ!w_g8sQ-v`yH$5iymgW6-}@k69E1na z3^}~=7YrSkp~&X~wxBV6ccQhbSU(EtpN_$I`aT;kNrso-2kUP>C>TL0g70@H+VkQs zr7=6OwSkNgC}3QJ;yYGR6tO!6|w>B$eCPir(BhE?Zzyhl3(S^-mNU%{f7*v6chJx+{S) zsxaB&zYM2(zQV!yXT>HbNtgN~Am;U?=dBWLSS1cjLPos=FI^yclmji+o8$WT-57m80HGB@Bm9v2EcB-e zAWXd?Wu@qsNK?%Ny?}Uk*P+X6bc7J8sneD(fPD2TLl`je0bl5NT4Zi~QBFC8#cAd4 z_gig+`poNGofeA`OFxJVjqljjU+R)FyJG$iu`?7>o$8~PpPNXzlV*anp0D-VW)~)g zNY=aPZRTL6Ebx}k4rJ`1CcJv_2?vCx$)h*H^wGt%K8DgP%dZ{Ex37pDiVh@0@V$s% zOMJcgr$7I36CCd1?o9&%@AmULn?xQoWN62dTQjZ8X28WhPnLTH903ws2{ZA_i((l7 z;02kR2`x^YkwJi=KUe5Y>$@V>CzKC8n*oQ?5!RLE$?Vs=fx`P?s&tf#K;F4v0?brZ>S3Uhot9P~`i{_TaLJ`c>9JhCpvkKePDI8IyryE{$DRJjR}Po0 z@sL;6br9S#v~oo1*^zJ0s<7+xV**=sQn8npu~;!>5X29DQ6-&cd$k_ zCV*WeQ)Hl8f?I=9QVB%O>P1s!I)I972Dyit7F+i(Q4HQgLkp$4IWCbGu!~e@Le*Zp zKCkrO?f(Q$Ub-nRxWe!t!f+7 zba;(g6gev zTSPWaVuJZyeZlypZp*R>=nk#w2h4*@;mnm3oCPTS`QQxP1oR9vy9uDTbLW(G+u;=U zJe?uMa4sMkOj6Cyd!9u=|HlX7CN~2ci;dV=4&X&UjBO+SOj@|DDI=Y&p~2o{(xaRS zTKB=*nvQ0+Tez=_tp6LuBd}^j_Pj=k}R`Ye~kD8bwSsvI3Yl5fyQ;QhT4fFkr|> zwf@y$QHFQ_<|=&us*2trN@{B6f6B&_qwHW`=`Lpg74HP`jJhqzVA>Sq!nvS4B{!&k zgFRv+M(t1vG{94vLtH69ELg-?S@zq!ZAR3tF#vZ97PD>(l3yJ6VjM?g>aY>Y$lP=B z3(6uN|4oI?bJJywv|gB|PCSag`pfAzYVccc7kNl-D&-g=&Ou?Vj2 zu^mj}p4vfj*Wgu`^D`>HtOi~6%M=R$FAwe?LwsJO>{19kb!SeqOUMeCDKTC)Ik;XB z*1ZN?AD8tCfQz1jy?DS4-@jEW(P;!~X{&qi-5lEJ6wJ>BiaQ)>R7&tDBhb$h57i@@4)CI$5J zlEeVXIK-f8Wjtg%r+x2)McF3Y37YSN$4EPQ9?pOXR)NF=f;pa)B5IIAt zVYg{?PMHA_ybm;7x|mn{3T-2#XR5clLxtE4O#Ja6*-cVF8J!h!wzG87RXj#z1x#By zF8_HF`60C47r;~{?uDSu-PDkV!o!l$f!|cMU-7`27d)RJ1EO*Ku_bO_N|3ZJ0LXhc zc(B^60?2b!bEG-BlIzs|5jzle2A<_ZzS_HIu-|&3;qD{oHa=*~Z``1`p{ zdMFasvUGEKlTL)NP49zbuf#u#h)C6_fg@7@>282CQ z5zrdb?phdzB+OMI5gHZrwodiDDczcC(j!`Dfm64IQl8Gr{T1Syz=t=7T&C$O}+OwK2eYq%Diu?9VITtp-XXn6Le=;4sf>p2tKhJ*{XGg@bwF ze(v>jGvrAmh|=O~nkw=yfe@_=n-?-*KWxv|N2cD(h&_(&tNQWjevWkeP&SCjwg9>1 z9`mGhzdQg8loaRD(vxWtP5qyF-TUBJ@UTI>4E7 z@ex3^6I{WQ)IjXDg=_2*NFG0(zJGYZywbb-)bGp#<|0}S&3$GcV>XMepXtaDU)-G$ z;Kb&E9#jwuAIR7OsJRc2&JPblHi267yIYV?V6I4A#C1IVp#T#RHTVrmEx{qjz_m+BLJt{KM{) zHv6Pxy+;tr#w6Mm>!)~ravGHl0)WCMskq~0#V&{DxkC->e?IPqU7+Z*&!cFQT>a~z z+cvfEL2`}(?}HVy1!5|!sX1fqWB!`P91ry%$#Z)j^af7>(_KO844_GEp_p5cOPYzP zoT;UA2i1wF%BMRCO~8&v(odaGPzEmsWkE_NNr#ksp=n#LfIkj8l9R9vKysSh2hmCs zSWkm$Ei!6^taavu+kGR(MGItAChWicx(%xsD~m^vwe&zQ6Orywe5w*w`8Wa|ZRA>F z`yY>1k390y*>l_fvp2@ORn^e-wF6mGrHm2~KW}=y0G0AvzuOrg7Wa!*WR0JJ!5s;f zTJd&lptP0i=1@REfA(e44 zc)@HoMAb6#90}J3&5y&24;oPv{J_@2eNOr_Y@qOa(`3b+fGZJsF1u9sfD2j83%;qsi&_ zP~MpVZMX}Q3>+|V+5orS9O7}iatu}nmmxOI0^E}k@|=ozzd1OB`kg_dy&qvIXlGW{ zx|cWnIlPhEZ?tOG8bq2eCrT%#LwK>H2tEmY-?5&Dkk2%vZ9&`XkZP%PgyrV7jiTDg zb;b&ANIrN1#Xj=Om-}F?6K}I@-gx7qniVhInw}j4vhMT&u1qi!eIf{zqGrAzVa&!?*_IDz1nMt?ADc(9#i<-#d1Y86;8zf-!@N?LE z5Vp&EQ@Qk&V{{Y=dH{9i@Qqo!bQ(%E>G`LqVs)P$ATRS_uWMGXMcQWZ*6QoQU!12Q zw>1h($Pzw8A@I!Vo>U7`We13tg*1P;7#4GU^Y(w)%$9*7TI<=h3rg5Bc*&Y?qdkx~ zyT4o?71DI|8kp)5bx}@kdJY_N2gd{2|1Dh%Q$sb{_CF5+zg1T*ypcxT;v0v*k(wSj zHePQl%IW90QYQ5sFD1UxUk28*L;1J!h`!0htZ=n?7hWi{g3Sv7Z! zLSeF;1tcHfA;x`H$9&vr#^@&bvr1}Z*5=xCq|Sf>B63l{8a*kc-hByrPCSsvvmz5i z9JPF?mGQBpipu9SaObP7yJhQ%K*DVaX2a)&KQo{uey7nr+^0Tl3;(D6Wv;Y5)o+ZJoHR)(at;nz72n=* zpbDnl^N=Ba_#X}=0afX71EovQbW!+NY}eCVjCD#u~MBCtA8e4$fxpP4%8v4_Hf}fFZ$lO$K}@YIlBka!hJ# zGn(of0c|@LEyN)9^*}S1DUFz;H&<&&$Ob-x+>E%q}PFCcD@-E0VU)0Vr z9M^vvEid0Qr)qK)+-txXwW!PELHQ(**L@#3`W@xPK~+!E)DdO%RO2TrBrk8Tfqk@j31&mmoxHO@ zDy_FZz)k~hZc+JKmPX<~sKb`NuUl{PIwa6qEgWg2OmLDS5QE7y#cbrYH*LSK!4}GO z_*5${ro4Y13rWtHK>zvLZ4t23LQt!E<+?ErjmLeEe@1&yQI7M@K;sYP#RoyPASEWx zz@hYrv`3inA;>!Xx4jGjo<0nO*qX14F}hXzQ=suBKWsu9{T@$^T&jp=Qvn3Ewvh$kCift(@mJylj(Rez!c$sjd zFJ@fn`Pxry131LTh<_+CW%pNU2>B;+qjS{uHQJz?j4oPVaUG;;+^4~aYI=^kG$Nf! z@qwGKVOO0Eq&1f+y0zMKrJ#goxe@(040tq-=v0; zSm9lquY_q7weRhi%ZUbd^EgristAb~9FT$0`vMeTlJ_T9`#=Y7vNJs*92jlWe7Zs^ zR7g~Kae~I{2!aMF}m_(QaTRIbtq)6@CtpYRW4Ae$f_o zh!PU6`DNE!f%-{s&Knyh0Bqil$&ujAXP%-2=0q+G2&G1+petVev+G$yDLDv&c=bhg zJ-eNSforw5Q?B!J5_q+LmBJy(_!Sf%3&Uq$s`KB>9ex=pqc{b%4bWCbFF(O;C;9S) zy|w?G0sX&ENY2FJDR2HkY>!*|*M1<&p#oU|<}%lpFDiXHgj9Jgx4ec_>~)s<0Rm{3 zsZ)!}e952=2*Qk&Az`LM1gr#wo-@V$kjtR~I5{;j33`ZZ4!#=lk*@Xg|-IPRFJ{ zyGGec-Z{K5)_0TTcZTgRXAU-4e)e}Rfa2P53YBnp#K@CT=onGCCmm{#WSowhhR%w< z)g#oT0?gt`$2&cVXDFz!Nqhljo1wZdJ4c`%SR>^fc>>Cz}$ly!>%B zIQI8XqoO8zl&E_-PT9TZ1{iY?QF`#yuR;P<6O6%-JM*;M+yq1YXVa7Fyv zr1slv#0>|9OTRboK1K*nYuOVb5(*kvPa`Z9z~pw~pJ0lbVc{qc)1!MBNt~2>x#QwK zqy8M++K>|QWxNcMf~2?%ZL^0TV{92GL0uS=nU3^JV3|*e-Rt_C&?dU*_YnjPK}UJJW5a(6QxM

    Yl3EeZ$)B2qFWI*-()M2 z)<7GVgmTVy=_DeJd1y6=+Sr3W^fiwX7y_JvYyzx9+fYMG1!}^JRYb zZ!CbJR8u{Cz5r2{=TaV7wk(72@eN?s(B_&wwpp$DZ_BWmc^p%`Vjbz635{=G*6Vx! z_zgJOyHDV7PRr-9|MkVd-KZi#!&n$9Ox^Ot32T7A3hMzUBQp5|ET|6_wdq-<0NhAc z4}6q}tz}QtT}sKX&;vJlbA5f8P}K{mcFMSo{0ZK2h$0HZZ!0Vi5=tNIcik@h+ zy9o>nVy?E;9YAPUfq1<7R}zo+Cj%2$VW6rws%#I?fdy#xtQa4IgkA0vHN0d?kAAm^ z{9$NdOZpKY9MWYR!U>c@*H>Xu=dC-|VUsybLxqGb1H)je2a-qDgAz^pO_1;tYE z@*eSAU@+A%D2z^!PBDOMmkuYZORYIN5AF91AMgdil1cR-nm>0TI;8DM5C-Mls^I1C z5bEY^A+A`M9=r<2Q?gkY!AIu;*zhR*`Zv)Z+#gc9lr$-&v zHq}J_JlkW`!0}wL`)`@>mVg|}|p}Y@PPBWaKdhwv)tCS_k_~?+Ev*x9D^`;{=YLGPwR}hv04@bhKXYox;=*n!R z)_SO?8J&L5uw)@ccI^WUE!TJSdArjFbTGCQE+SdY{jjZam&nmHK5qbgX(l|ut*7%< zQyW0Znh8vD-d3fbLRK@50TAMQz!B0p^9bm{(ss?8SDM|>oMQ{+zq{0j1HfMf_dmC= zZ}ahl5d>5FfujG!F5!DBQHp44df+cxg^MbO=PSCC{t3r-6?D;#y?Olnb&WQoGQzhd zwbt3cj$H7X8LC0ILSgb2*k&d;I%gs)|3$w5fGvE0?Ic|8N^>zFgFtNeQ|j4Dbw%9- z4sW5$z>#I*1z!T_I6b*A{S9UgXciE>tN|m1Nq`u%ttkDR8H6xDhXQfjnA;En@B_`g z&jYE;U68AMLxXM&2(H*i@{0Mj#~q3e6&t$?5%pI-0Z){M%yB-1R{Brk!TA0P1vL>H zo;!4Vf$>gqp0?Y0+pj^V#{nlZqGg@AuN#sQdpM}z z<+zE*(6hg6GuV9^eZcBRl*70pyu^49%&)=bgOJ|89JfgTMEU(E%=Ez%Aupe-aPn6p z{HM+Rwx_Yb@{4D*sW?I)HQm8&M6iB)2%L>4_X4zo#0-dV@4zP&d)-rEwV&|{WQZ7Y zC*<>&4_L5MI#6O-;Wvm0G{N{rd<8TcX}Dl4p*IBFGf>QV$C=v&iUQpTR|^>D(Alol zYzF`ofM$t+)GgiE4;%LEbG>Pr$7)Zn^Xj2x_sY-xx2ZsA;4__HSdC88N_z|nCBj=V zd!06(=ZNp+fO~reDM!Ar5aokjd`dkCd#VtA(6fu?K+mOlMDKTUxcR96N2`cpl&)F1 z#$EcQPL7eL4nSeKrKqkzX35zlPa1*QgO%UX$E%pkGWhTdASARc_d?eTc}fsnD+-la z<{@!OZ>-L$4m|@4`NpJv*Kn&6?2R!CDwR_%bd&sN|;#|AvOPN#q*H!^|I&~J_@VM*+tc+Cr9Xo9$XR3E4-)PftgyP z6wwGGi)zVnEDD=8FnR%Hg`yF+G^ow`_9xX-BB@N2!!W=dxM417X^WDH<5;3qbpPmY}y z?OaOh&bs)>K_$Q)YbOjNcy=<2ks>HJLk}$Uj_HlAT*%+?z?7m3))8HKhpaIjCZjhb z-)Xn24k0N#kbvR0t3u@%D3-uLJ>fOYVFkHs3iK!0K?H3)as{@L<-j7~qo(Zv_GiQW zSZ)w1&O$4ZlDLz9bBJ=c${$BPxi2dgo_VQP4#8!^r1F0(eL~Le{cZ|+!$#RLkpdzZ zY%!W0{7Z@d?|}UOF9=T3^DQ+C%u?L0+XI-HAX7Bmo!Cqd!P{93+I17 z=P0XUH3?1J{XiD=8ZT-iVDcJFaL@EY0$S@Sk=bRDR#9u3y`ETPv zvnCiknzP>>N!fK{G4ahw_$fik$QRbYjL*WS_eAbtd@49iwea82k(&dYxaDgNi~avK zj;~yl!?KMw$Ev+ucq+-~x-Fms@Y^x^b*~*AK?%Y+~_XWzbIkc)4l#cL+139&cQLBGb{!IRMxigg(Wdt~ikXaR&i!i&wj( zekuY-QhJ?As?menzCbd8Vm%YErZFFLH_MAGN=Tb-SQNHYcPJyF9$2$BDUe_}29Dd3 z(YB1s^>2MYxK>d7N&l5FD2MsSnxH_gLa|t28>xcV?VXR@c_=Ioo?LUGO)qWU9k{J z9;hHP8Fo5|wNv~$5G|&b*#wCEXyjmoM}p2!k{IFKqSnzRb>4+GN`vZU4Kg%4pSGS1+2k(7ST`t@b*osU= zrg*M*NIhKoHuUhyyN~>af5(jxH`!$<#(;*%{%@ZU;tZrN$Mifi#tgo&^zb-!Vs#{@ zQ=C*f(_wPAYL|2^Hvck$DKwdc!sqjv@`S<4%c}b#O{Z_Wq=}OH$<=@y30Px*Oy4$JxTRnp2?Fj)&hJZWU$?*F4e&8RF)flbt_@NzRwxdbq3Xd}m)dV6u6 z_qs1P1c$rz*v?y9BM$;^V{mQCLmT8{s*CHkGU|AaG&*VNVBYj?X-UZZ8C37e1J@Dbkeft)0D!DHEdvAF32 zZDbjCV_9pf%6Gh*Ff3I+^XlBzscYA+-OB!u#m)&7hSSvGP|bpR=g+@fjT}e<`SJEo z0uM|7y0&uFf$&}gOL(9DHz677r|daa;$jN)1(Ec#aXj!1_Y>+0X@2~JkeAn?+3P9f z4vE~mMix=3GkRzfVV+&j$t7el;#7%~9Z&36<|mIqJ~8+Hy5)AJ!XMB!WIwP7k?aO# zw$jv5MKmXPd(3I1o}~wL8Lbu8ybqr|nfC*8?I=n|BK!y95@FHL`}gmix>Eq})<+u8 zVdebK@iWe-g8LaL&CbA}{ADx0s{Tajby3C2D)rk<>&;Px0gQRFX<^;*xgpSb$iD^1 zCQtOK(?wzE`zU_ww*M=tIoJP3*_X$2*>&AVbQ@BU2o1F<0u|2azuD+8#M1s(9~v3XxUUzGTX z1IgP!rtYZNzq+}Q#)Zj$k z&M;|!q0QDzCri;Su_xPv&4E^T@5Z(=$x4%$O%u+Tjm)hF8om#UO!YfzQY@Lf^o`lWngnuY2G@+3%853aFIXFv`w_zDAwve2j zP1P%U8~2$Hb6>qlSYAH;%+B!1CcT*I$@Ck}xZ1R2im1A%`&V5gli45HwS~)<&!%Ny z-;B(h=5ftyPcUmMz(G)WQRXXoe!ST5{@iPW4}HDPDg`;XF)J{&$Od+b zR?@dAZ|?Zy%y(f{6sY|bYclv^^jXTyZrAO!yaR)|^@N~yvbL{Sbexx#PQ~ODf8q7b zRlOs3*Kn!ZUvA8iOhV#4^;txSgZpvoa?Z&xHG_tS_I-fk%aNIn$w|C$fn&snmt-`* z|7d1H7fN0-2vazBZF}#Y2&}!`{Qs(#?uIPU9#JqK0am4;y1 z12|?PM%qg4NQ`2&p3B1W>GOfB?%R`hPJ5XsU=FozVgA$ZiR-i=69>M2y)E)il|z=- z{Hr80Vb{QhTbp_|uM23JC4>pF`W;2J5Tx*t>0jSC3;Y>s1Y!bws|J?tNHn_NnsTId zYwO#4Jo_2gBdL%tSR&C%IrL$rDEK+w2oHtx!%y9be^iOSXV}Eh#E^`4*6tkIf>5G` z`O?hvTeof{ozcR9M}5Q9{TMquOg3aoyuNJdnm82^k)pb|KlT+a>m9ftq~}e0!?PkW z_3Z)Y&aI%YA-DQZYQXsWY$NYea5jAm_m>4Kn|N&=`2zw3dHBYWe~_V>&jG{y&YV5_ zywVCzfNJ9HAR0b@q!Ws65dL@0c21FgNc{XIr|ub}z;P2O>oMe_FTHy+9O z(Ph0Mr&mZ`rQA5LOY`)bE%HNrW}AF^dwY4jml%N%vOb8gLWhS}i;8NK8$GHb(OZak zLr&XQR=7@F!UURdbNs_>apv^Zf2#Cx>TsVJ&MR9=+g_h%+IxiO5NgDb)2A84L)Wt) z+w(!-zL#a=&fgDR3qMp+atoB8k931N|K1+ui$9_W3#%D~q14Py^y73UdqK00zs86vEe9#5Y>Jw2;oox1vR4XPzAnIwWK)9>ZHP%>JU#jKTz4EOo{ zFUOeC4s}JfSJw22o;qcN8KZ@aFNY$qNuv2;^6DStr8^!j7&XG=+=RLCvhExwwZI zD760o#$SS5Nz^|=>)Uxl`tS)d3CTf zO3WlrLXD)8GJa$c^*K5;bX$YvuM5?}C#eZ|u0t+mR#jh4dJYFCr!d$kE02O*#@Mx^ zqw(9(X(wc!!x_9uc(Sa>^t6ENu~VREn7FQXF}`&z0PtFdt@~$9Y9bX-0f>pBD~Cb8 z-UG~3iiU>9`PsFZw5M3fXbs4UpD?^V0?+S9E?rW<^u=FnHgP;3eb!^Jd#}0V*BCxE z)Bf(Wn=DzektyL!78VvoWKcYqsIfjS8+PNoxyc4D+uXaBs!1yKFhU5blDm) zP^|zG+ZcI=OJ?6me;x(BpFe+QTckT1;Mn+LKO78soF@QT=A_PO9 z@C2@z6kjX(n8dvUm>^TL^WHMP-8s%E01M^a4~MVG(NKLJCaH7jVN6n_1Z!j6>*KfG zG`(4_w-vW@TURBBS?u5cIa6vwz17#QO?IihXT$$FhqVe=&>-y`P`iq0yu|zW?xQF$ zwkY(2;v+eT>j{Ncupzfx1 zf3U~7%y?`~<^1>GZHLzM!UrN=3e`?1_U|5B$89Glnsjp6(NR&ynwAY1P}(oPN0(g` z43ZqXzwV%9e;lWhgY>7y7jXRl?A)TZP8r06i;>=DG1umg>>ZCK4j1tUcNEJ?(K6he z49RD%CG5x4+2bJ@Znv7}y?b~l@Ny|Pyz7vnBH{gU8o~g`?95pVwRlepMn_18thL&MX&yV`fF~(N|1BX>^ z%*?N8*^24RXHK6MDH80R+FfKb*I+tl?Y*D6Q`0%kj{0Ql8A^aph={x4=TF!Eq&EYB zL-V=`G5u||yvnY?`E>Wvgtr+S@d0d61WSdzhhtDgmY`D7P^~<+rvcp|S&#mMV5OP% zoDxAI!0IIp+PVFS_o(fKkX^f$x|U+E_O(6=FR9r7dT zyP%}G0j+TVqn@L5%6e)u+qw7W9cc}2Njf~XMzrO4@2rhEZc1`;+j>3TE8E;k zBjC+k$QDXib9g*||Mh8hHz4mPqkALezs@a3oAznz*|55`XV*~=h1tR2DQ z(^Fm%vNGMiUaGaVHQoeyHrt{_?Sb-FenpOM3mQ+^k3fEOb#7uj<2E$I>f>zQ?YNqF z^B%_8#41$Tlo_kqDn|QKgqfTBJg&#sGBGhdV%`6x-iiLrb+mpm^F8CODQzj&>Fh5v;M{ccNV{Mx1))avbxG8`Tcmd(H2cjSQQzChpC zIC{PFJ(gwutbk&*V`K&TSQ!kBcL>Tz| zz)9oS^^+Hy&%Om2&K;K>*+NH?C0)LM|GvVjAzoGDI;r*(fhl*2y+0nX8XFSu+Nstj zU=*2}xVOd~pIfwmVdrMzBos(jKL8X*g_dS=5-+Aqg7GA|+(^yL)yCxH{b7DGz- zhODmT<>lpc9y5Nb7-y*8{Gt}u$FuotuD>F{AY6Ms$Tyn+H_w{o&TwkU`bMqF0by>3 zs*T|t1SD{%hClI_J}$stps3)m_MbfarHwnP z1rraAa*w^2YrMJT`VGx<90djp4|p5)`5^OeIzu{%$x4;jy`tcK$9U%BCr$_o2^D_xY5CQVpad{kGnnY7No}m8 z4wvqA8A%&8)?G)9pyl3Q4LH4}k`vF?{h@!Ya?9)J3XZHT##c+;6L7k$e5J zwf$v{OyN{J6bJYY4siO{mzy~!H$7z!UC(Ozjove^sh*A*|F|H-bRO9Itk5*=z(oYl z%Ga4tNXVjf@od&LPTD2>^Oi1^o~ztVVSQRu3&RRtbirA3iUU5Y&}wUI%X*I<`vIq8 zL2+^M`cpOw@1hISg9hD3z#cjOT)Si#o0s=`waa0F=54xyvcJ*SFpjd2q`vhsESakx z&|~0x!lSlq8tPiHZ6~Vaa;DsbrjhiT#2Y>v?Jm@ux^ovqRlxj-rMlyMB z4TrJ|52hF&X@6JFt+|z+R*!uUGLBDh)93IE-qeX0rmzb+@_Z|E5f{dm`DXz%??2Yu zml_*sYx_PWuJ`L3o!Hpen(ZkYUfoG>#w?orBQt$`TlblpGm5$Oc5YQB%dY0g3}~ak zH6_feCFJ439D7M!;NLsK5$QQTZ%zERm4@Y3n`rxxBQ$k9d2e~VJFX1ofp2?#thBUT zxIb#O%S**8WKfrhSV_uMoFYFx0|bIO?9x*!BF&lM`Ym>mq677_*oouEZ=l)sbMxa8 z)0q-;X~ao&G-ij)epj8_m&FEr+?}L2h{OHRDILr-&%uX^`KXqI-Hj_Zc%f%vfs0@2 z(nY>=I%;DFNwHmO@bqxiW{hbhj7g9cQ!}1_f9|Fitt`sO$QYl7`^Yh$vZGV+-1r_8 z(W7CRXZ25Q--EhshL<2TRcQ)s|9N>$qgH;ed+bB6mNQ*LyX<#fcY8=JZR~4T^Dt5H z!HQRPhWKAtq{I(tocuL8+qeE*(jNUfr@l^AJ}4I!;wy44TWK(LzIPhnAftyM6`7#Y zy3ADmo!;s4%N`rHGq{3c<2=yS4ixPZd@xon=)rJf?SLgJHKx1^cpKDxzy^`Po{kKmc5>Dq zk@(na^y~JgykfN0`tdp0ttDFv+&>h>2%Szu~_1x4QT}CYi zJ4H}Xut3OnS;Ds%qSRId>YMdIlX+$InqqUXqTu1~=I%cU9^&(}~&3&bG^!&22q zhkW;bFqtgST_C8Ky-@epwAR*PFb(AIZP8y!W+Opjzobz^TR4Xn3@BlMP%F=KaC3{5 zmzV2ZKDGDvZse7wVOdU&@W?%{mZZMkzR1Wm_si=-4#+LK*VtdP$)4%;z_TCno~jOD z^OU>M&YZdF>U)(h%us$*XB6|Trbc_bIwxz6kfE7p8f97;DZw^>zMz1>)4_(a(Ad+5 zB`2d7UT+ZdikwYr-QG?%LwL;?7OA*zBcOmmeo%<38Ie~S@gdePxP2i&2~IO4gKs^K z&UpzgiN#A#M>Du4QwfEVt_G7e?RRTJ3S)r+d`b4IdMOn?zO^tv;00zeOG8bK(h^OC z1BGXT<-RZiUU~L;Q!4&w2nYg7_WbK7!Y#4{*Qmv=Rj;@elVB~7TV=a>m6X)W*TQ0A z8=pLR(vxFof25M)VIt|$V%%0dS~fqgZ{6_VzRJyy);Jp2OO?GEx|Z-MTx`3T=>;So z+D=X>Iz@{zxt<8lU-4(5*xkNZ}!hlv%lCSg_Drqk5C;5hS~IboMBEi{cayZ7r~cFm?ji2aG={zqRYnbtGx`BD|N zAoVQ|n|w>+)SA$Wpr&tA5yJjJ|8BOMr8})YI;Q6hB)}D< zP*x)#X000;`)u_4GTWvGu7JghOER6}{t>JWAylw%#k?`?@8HW(Tw5im>1wxeRet6u zOCG{%Xxcx$U)4KniOS;~D7cU{_o*{IefEq;LHCoL{DIejKtI`?wnuI))ssnzRNZbxSl$aA!P2Z6Qg+Bo8G1R%UF$`$9MJne-`NscZr~ze*pmnFs z^sO=2x^i&ch7Qy~}F64p$Bca7(>PY8~n|o3|qknA_PLYKHHJ z!+uSur4J4?_h#!==ebF)O806pING~x^@~Iw=jjYm^8JSiOy)iJCP5fTWrnNb5`E7q z%`GK20VD%7xOGW<-zxmiyb0vJv-!P-T7}(!W9o+3nl->S<>Q$po$opJr%}{U-XCcx zTYF)ts@?5)5U+Yb4%R}5lH7dD{$fnRaeZI~kZXjQH*z~%mNECW-@Ef*n%fl)ZVnEi zEnBv5+zE5~{Rq_UwC?$lb;|dI(``lS-j@amKY2H_=4SNDB!!w!RYr^L?4e?Gly&zy z1fFhuzP9?hb%Lu_t*US9y)lAxs+J+q%I}^1oCm8tq!-See6jJjqY`%PmA2xEWk$No z!C5vhaCGxC!^6$ZOV3FM^q_VjlTov*mdU?Mq#3B`fZih*BGrrpk^P!fep*5!QU+6R zPs+!A^^I<3|I$EmwRXNc=0(9D!TMO%5GxxlkT^o8mwY^H;H1=bYX`wRhxwjV$ z83fXci#$=P+<++N0$cgtuec81)T5)`;UgOUQ{4-HeVLTfIwb2cRdg( zCWYlYNJ^lGu1Keb?mvDNOE2d^5fEQDw9Z>4O+{I`=5bJqFJ*uUqnEscaG_UyrcKxs zDFk%tdtJevBbM$5MxkD_zOAQUQC0b&*{7ZR^MEf;P3wP z$*zfvlYN)k%ua5vydQ^6@)8XaE`*Bjkg8Y0fmbR1`59zWQ5$fSbE`5})tDd&%1UeF z6LkORd4^3;LqD==u8JoSd`v&a4I}udIo<)gFrD{zgr~6hv_Gr-I@hoFAAzBni$`e2 zV|+3(K>ApJDq@Azb7Ygc^HDRK!0^K8C%w!vT8;%R6>;Z4cdOWTCHm1|m-pD7&fH+o2+1lQQ(~AG^A`t}qY8Y&S-gnQ{LiGH~aaMoUs9Hcp@& zb6LxHIulKD#N5AM@v`1&H1i{3Vv!3y(7q7dEF7*EhelWM@={%wULLMe7)y_)Cf0}i zCOu3QVrDv|E6qG{KxfcgT~KBaNHh;og|=Ox%dTqfYec{xrbh)OiNbBUpjyPzJgqqd zYN_+mDwFItvOKh%3$(Pf0&)H};+)Y7&ocyNQH0R>^XKJhuLBV%5>1B7 zVAD1SPg=dsw^=Us5%RVi7Mko@+S)+`(m^o!T2@L+X2p>>0yml6Pa`saPjstiEn;I; zt=}ajKC!k_%R#5S9tqsDg9}bgb!x}A!Qff)xj)!=3JiBQ=6?cjFkTx35-}v=qT?-x zxonpp_$OWf`wNyH>-L$=CHwS*q4|}qeXnl7>TM&3w21^v1cD(~e-8S_T?5`8PteIe!l4wHb>P4En&ce_|*4062&`X8CMFc{5i`5=UA))m^vf6HyT(_I{ zX{PSgiR(p;EX7kztEoSv&svuJ2BM@J;7zkFT-YLNX+U1ij3hF3oKNunpD-~&?sx`i zHI3F?QaT)uxytulnfI=wQ{LPF5J3hLbcaP;+A0$QSgYgTbC4zxK~Z|2I(v}u5rNoC z@7oHirgEZxJr`hObR#;y?J1(2`aLIR(mVipM^IjVJ1s4(KV@}-Z_g@#y7~m+iLQPA z{CV(Fufer=azVt0Bl@f_&QktivR2Ci(y~(AG{xe~k*>PhnL9o`3Wf~@v1}yHW9M@1 zOOt;5_@NDnC+P!(lkP{N$a<+@A}ozVcxL0^C_JC08Qi>YYMuW6NdxVCv0oc({N%0j z!Q~gBHy0i&DH@uZX8;;i-3zBjGi(5b>_D!Hr6z-G)6y8B zx;K3yVCu{ilCA_)hxy@$4O^ulyMjrgk4Y znZ^FNG=p|><58aw@PlpXQu_x_0J$%-RwpUpU68SAzpmEs1lw^BuZ+wV5^o8?fpNpt zlgp2O-F8*8GC>`rvtMi*kN&&HerWk|2{(dI_uS5ORfehBSjV-oS;e)z@h8!0eUzs* zZAGTm=GRZud|c}u?|ipRRRU_Gv|ucS0Z_fXs5C8y@owP~1BydF+u+HQ!R0*L2!-sH*jo9geI``wyX ztLk}xX1HZkB^FJyzn^J5D?wuuy`xSykM#sb`+d3nU_g80Ia+c~QDkuUd0VjQDoHQ#2@olXe zEW_f+{LSIY$E#?c1uP9m%!y=TVrC9OP-$b|2r}QqKmYenu7L>nbE~H=Hcvnq2b zxKGF+<6uLR7?wcF7Ls!1*I{B)Uy0}) zIf=(=XVUeqpEcs*H>(!xK|#{!rrZ`CS1?Tc+kbv^TLLkD&fPqvS{VP}l(}%ZaH;)F zY~4t(wSjhq_-j;TyB)6DR9FPYj2aASEkH&U@KoXZ3pIQFBsu>s)on>p$C-;eF z=By%QPIkJRA;h+UgXp)%Hl2x%R@>^?PoFy%0x0Us;7FLH%)xidBNQEDcRV=;cL`az z3{_SiKYqNqe8bX<2&Fotz3kK>F~!3BAIs$6i%(-EB0KBvJMCAZ`XbVIYZal9$_>K0 zM40;_awf`Q`gq+4el!|ZvT!e2B!LMucu5JIQZ}yB4vG+gfH&TXk=bF!^A@7!;sd469pVgqvVYLex5PB(>^Z5F+)T zdF>y+{MA#~Ram-*a{aRFukI<1*?hW}S5>7srHlg6TGB#}9JQQ(9XSbaNniJ84w+${ zO)`2Pq#n}1d5?^q^atwYOGPfIaiSgcL!lt>G1k?24j2anR`8f(lCv26;euhNR(2d{%dCnC^b@?~UXWh5h5EIdukIqtw=~_r>UOor;PIe=`s8@JJ83>FwIb*kWoX z_~XXks}HF3*608uwUGd7eAfAsH%n!JAg*X>?EUlGAOO2uR4vnTS45EdjEnV5Q1<{4rb zwF%)ZrR{MCHDFhsSI##X(0N6n)3Ft{I6^lskN{(-g{*?h#_}KmK=(H}ssh9@0Z@SC z-^7iXUR|Q`U4_QeDYVY)j>6la;o;#WGk&QrCIiy+r;S;Ni-~iltijasDe5<%Gn@iP z)X15bsJsDQYYo}O3kglefv8(Q`cw(~?3CHONBNEw2i@5nW&m}ZVDioNxS^&4iy4+T z+Lu(YCvfJ2^IR*|6FH^9EAZkMDioF-(>H@bcW`ji>2y!N%8Jh-_rP{#8qE_>b_rUB(h9u+~k9<9xDH|4au|D5w zh$U@dYX|P6BdtH_7ym@Fw<6u%G%|eCrR8g3bhNXKueIwjEyyHc85xR|Oo-M5>|K&A zyYcUwdMaw5yAFOr+R|;~X4T_|CNMxvUHy2JvRlRLd?eKS_U%)Y5845<7gx~Qos-^g z!tv~%de7-!6i*igHVXd7vsS;nE@Z~!D3ySbqlRzn5?e-inyQ3*lu*?(j^h7LqY%we&I^Z zb2|-(2Q2{QB%77Gckb~$WRU?C30j}*KsJv}_%SiPVd^_h{X`|);44qTphy_0)%_3Bl*gYN=kg3i@&anR^FC=!NJDKIjk26Kp?ViYI=*5-e8P>ktF?*N z?o7j+rpNejkFcwpSuH2``jR*(R0}F);=>tQLaswaE;Urg?{el&h9~B2 z$s&jn9W|@}izH&0EGm5Ju#-o*X`uV{$0+a)&fa!SogOvu`5IWGv2k(j>V3>bWBe+! zdx8sqGsV9g{s9qat=UL;RutlL>IhZpJu(RI)e`)hhb~~u2aFhfp@}LG{VsEQfHWXB zfaj^pj1)h*rGA)D6Q(xWpFcSy;$6SE%TAzl1O3(7*ao4S2k z5P@mZEiB8cl1yDTW{i-Vgm6+pCw6EOaM-bo4G!tazPsu%ZK9GFhED<3Ed-8x%Q^^g zrbPqQC;oWv=NqV1HUe+*IhzCSjKt1lHG(w(6Z~OvM`4``#wJu?B1U<#EQ?PK?YD2= z2u1w(tu5DQC5(J``bC-g^UM7DWZ>%|X`m}fo(c<^^ULO)@zr)xK&rd!F89KPJ5w1m za7Sh9soDDylD?x;)=H~WAJB-C0=Ya8isj-A$ELFdPy?4=0wOA+`m_6lO<!oq|g_Ya0ejyg6|PmV^t{#RrU{p>k5!M+qp8qZA_ zBE2ppCB^BO5-+bB`q>5b^-C51Yp?lGs{B6mZJ6sNMKRZ!`h!)B))WiW8^M<^AGmx2 zL5Yo(wee9g7fb}Q*Hd>j_Jg_k963@P0EVr3UY@%i9*n@&+JSAlKdQPKWFb-tIPT7V zz}?vYL}$rrXI&FmoL9~uxh8QT>z;X7kd`4sw*dt3P+~kL=Y_lOeC3C}S9L$D^;Jg% zNEAn1_~D)mFdYbYmJub~hwwSMk`6u1+S*!L%lS@@GpR!Do09(^7yNm$j6@px8l5?- zW#Ak7JF%ghqeB!H#JVp(pO}zl%X`Lv&6w_0GJ|Ub<-wB<;`4T}_R)3_J_{S9?Z2%y4Cv&xp=xz~NL(dr|dsT|^|7)-+pheHLHA8_w2uE{*C zsbBK47DFL;;ky)y@AOVm)BeKi$WUS^o8{R`q0}ABLf1uGUteKwOWuZFmEQuv$>ipb z?Po;dw|pYWM}NP_W-Xu8RJo?t{V!hVRx-FhiH~m3CV<8wRtLk39JDiIX*M20l6IOk6B_Vi+p!&;S?%@U`c zp1%vXQR$2;bJR0()Iw8mJ(2L;8VdtL-QI21h_yTSG~lKVg_Q2n+1ILj`UcV;ViLl0 zkih`E$=4UOXm`0E4xaS^A=S3yl);rxbiFn+-1E0}5{iUfXiAOUmU$B&=8uvIuSiKJ z(AUGomMRnP3!=Lj0By6jD^opz2$#{e!~r*JZ^7 zz$~X>ztNOoN&~+SMExigcIaM*jHy^rhH%RvsEAR_?*Pkc`SH-|+@C!~x}y?ZJoOE*Qf|ics`7Ic)fVQM^n@ctDJK zk2GR3l_*LHi9rfk5WD%-$Q@d)p2+-Qo0PL(`O4aQg}NHlO}vDR0;t*q0D6s~!hDZh zH6+Xj>vL;U=Xo+|0mf;`+cd2qIPr*+C!>K#yvDjB1^Iurl%z?oTt8WhEMhGS`G9O( z43O#i0esV2aBN%_UhxkCNfF=XsK$Q8PSQH?|3RvMv^h1a;d4gcRB7PsH=AqUBQ1Mb zS9q*5uUwb|NlFJT{5#VeH+pn(ELkEYozolq^NZ@3OfEapED}v{duancsWnlccg>|D z2fm3MHfok)awV*ZR1}=ac`*LDYULTjsIZB;!Dh7y=$R+%h5aep@VT`08_w59|3q0e@0IvU$;6?a9)_Jfv+iI=tJs6 z0^MBxj=?;kWW4#{n0sY#blte9Ty^BZZu@=L_!^iXq&iZbkZ$zoh&Hagmb0P@r+g*; zNDjt7au4wMmpbE$nW^8Tiqjb_u-manC8rOM6h@54Q=pj3gt`fW#EocV2*P}1JVk&6 zxpEO>`s($WKoOg^jn;I4YZFdI?||M~rff5#n%U)r0Y~5TH0eth7eU%PBL5Qg_RGmM?eE(nHUy&94aFXpc6wetbRZ$bDfIPy>~b7fk>QzTSmPQg!mwTE zJ3DjB1{6s*aI>LWjJW;~*gNU(>h}5i`JIcNf&bkzJ?Yf6e%}8&kpG5hHqY=04P^&W zE5Py8tQx$Z6w(nXh&jl9%_d~QkrCq43$;Sc>u+!cxky}xM`!dRK!q~_h1UT_-|^eV+24)4AC{MYU_P9bE?XmI2hAcjN*d!=fDL|iv<%0iL!z5X+c3T zT2O~ygIVnc^x+wIZQ1q z{>X^s?97fdi!u#GC+kMYI&UCc=^Dppi%Avsb(mn v%F0)rnf1ZCopAT8nh~L_9?Wytsb;Fb;liSz?rw+j1TD07m5xa+o=Tzr zwehG&NhxbpQZ(^(XV9*sBY7hT#ZDmC@R&-H;`MeyUY_dy@jt__o^d4{GSHpIyui3f zJ&n#8yQi$aNe8B+2cex%Wm6IX|6l)wGEd~{$N*Ioa)+yxXE%=!mzH1@NIc9eOiaPx zfqgl;!lD5wDEsT@iNQn5Ad!1g2~@p1Yx z6N;pq))|VlM;6W8tdT_>G5Ryko;eeQ%=mK#6z@+JbBwPx zsI8+$tAYMYFwEDR>>nLM>no?^$ErWC_CI!D#=qcbUT+ezmC*Uu(9m!=uv(e}@vT7! zu`YWNZnm@I?M{Ldq3_WimZ0BEP%>qhAV7qFAl-ZIDh!8NUxyhGm4a{+3_=T#-9lt& z=q6>2_QtWr!C4?{pQ#J{!#nfu?1Z%0U9PIE_&Wxg84%U*Y+U=nRD==>%(f$SQ1Ocw zsc5XA-3i!SHu`1L*|5-10jPQwu!z*xJP(()kE*M?p*??xZpkGR{+OgjNN0HT1E1IS z-kO1n%_L=O*i;?xcciCSAwe2=;d%YQUtwOFa8wE+ODg7d^O7PKPG4~_4Auay(Qar$ zxav@D$bqJ0S0C%V5aVL}7q5OR_X6Y@OZbXwE{<-?`PKFv>b23<)62cTHAg8HiK$7h zQ`lb?57VBB(ua2N9`AsgWQNAHM2<=r`H>38K#Xw0h4ZLgzgpg}Ywve)_5)3?7)}6xJQYmtRY$xy%RF`?!$_@FF=FHB{1AyHs;2zvm7#_I? z^lVFbvEmkOO{}=|Uj-=mq5p0a_tTReB;j|kvhtx|PVuHu8DH$#IDJZ{43OD9{E1RC ze#bL_v;Jn{;9H-SDofB`ssv3=txs<&BQVBnfJ*N>_AFXFYtAB(tH*lI*xW{OT?84z zx$AVF|IcqX{u>U2jV8QLmVGj0sOb@twi4(@&X0l3?xx2G%inV)m+qK~3()@qBYBUDxAl(ub1R4v?HCk|d37{?My(N> z$=|R93paLj40EATc0IIXn&4gk@8?^N&d!(ZQ!%80ZK4TebCBhsE%g`AGBBO&w3V=* zdT@77x*lmIHZh|qM|!X(>bTr3e9)`oT5~Kz<^b|oWpMvV6}T3BsVL=;!+vB?5J@lM z*Y>6Ufae*2;nRnOE&gNAlf?`tv6M@4=H!~?iU$S<^JB=M42|`2F`WFLBO{)ieiz9f zn1fs?{d_8<&ZJx0qFsSc@1horTry_d;iS$R)bKY_MNk^Xp##}7*c6}xcb)eB^o@SP z(XQ%Y61(<^S>gI2{gyp(x?jP2M>`=7X4f?>4MN_eiTS^mP%Va+BoVQirc=M~M>;uz zqN2sG)3HkmZL-E+)#oR6-j}ZH-p{PHf&kI{U~VxuLbTsSm_%+Ubk)7=V@NVYp_GM4YwiCXaY1Y*Rws`)T@#pi zG-?R_Rs#b|A|?=QvAO1cAS=2~Z+wdsAunH@1YZl0v!rX!YE342S|=-Hp}C_Sd;R)3 z+0?isGWhlrP-D3_gTIvklE$kGGWDo$&!>aeP}p?}FhG{wzV&}mLjO1m>iDkG>^z)P zT!&^shvp(yC6K#XOHiq?Em%NLO!6p{nIvgci)Dssi)b=R@Lll6YHfoFWhnfOT<=9e z_1F-dg>gJa=#-6}o^{zKR}ds0AxMoBBzN0qyy3C$n`JbaW;Y!4frgw*=B1&f^2Cb# z{;Z~?SFMv(x_dHX<7B>(kigRzbXQ`8Rqy57R2u`31DqV`X9pk+arHyA>3X-p(1(&m zM@&Q@oHn>%@Zo_i7w${4*E_{ZKYhn==C$b6SzWe5aoz*cN7gYfq2w?sYU^e+zT;z` zONOmP!$QnwZ``#69CdXauU`*y-g0>$2UcPq}fNRDrvG}8Ylsbny3UyyuGBSA->K>VI zxbz=o?!VP@t7(Z16U;KoUuEtAP7#O3+rsgiN>QYt1g^L@1a57XtZXxk zZ+s_gLjG60l_09}Se|veCRUJ=z$hRjL@0E+mf_+%^sp{pY)YB;p&cPtHiEu_HZJ}4qXUzI*~#!^7$|hEU{uRl#F~7B|tieO+tY+l8TBuL5+x#W6uBc z5&w90ia6;As9%(sJRD2sYw78Q0Ro6HG=`au4b&I`HpxbKpO_ZfTyDFnqj_Va!$MTT z_5$*EZcYgUgX>L7w3^D{&$^&@QqM1df^-W+4b9iYojl(Ynj&ZxkwO(b)|hc^Ud2hB zZMWcbKtMS5j{(bX9Z^QwN});M_21urJidNsn(7{kq^OxR2K{Cwo>N{kle}ZDP{WCh^UNB@n@=ytXl-_)xA`e*T*R(^h8tubK5Y`md@l> zJ->r_@*C@1n^?lDnr_YaU!t-bvS&*%Z`i01DVy8Zl$#$eOa>m4#>PhEdT0LdY5Qvj z>;#23t3cuORMvcl83kJr@Uu;pY)kGBz1)JozH=9qGrt22=xfKmmny^`nuvdfby5e` zQE$-#JPCvM%0}=?Y90F+m54(*8D?u|YT6#7Pzo9ha9^b`?+=I4ixH?K1UH6uYjPx+ zJm^e|u8xk5w%cumyi^cYOn0hYeY{~#vtoh^Fnx8YzLe3Bz!k2pHq&0BVGH7>%7HAA zN%ng(>=QN|ydtvE^{KmurY15MCE8pLyDFZz-|9uBmABAnBQ%9q?-j)~V;E>Lvm;39 z@aH0gkoF6xIQYp_M`Dpdm)c>i()Ze+P;?MB7^gUC_ryW}cM@?7K2cc#cFHA_S7sDnAc{aF=keDV0u%7R!H84N#a(FpX=H!acAn(Ouwwjex>RlZSiO=Op%y)ix@>Zlt98D z4#wYN2w?YHa~OBE0`uV33?$5LvfyVRt3Pr!(XWtz&k4xu4K^WV$$KKBUFcrvV9CBFtrGerSq9k6OfyLGv4)8jm z9}c@45j*|+|Fy1EG7^0U{lxL2s9mFz^UnbCTA6lo15-gUzC1;34vi^Ox;J!#aHwLh z6mP(E=M~4Z<><0E@k&Z=!hG_*QQXm>$ho-TS_%g%Uk7d6+T0__lFNUCQmyCgv%mRf zqtB4+c80QM%f_n`7bm-6f_E&q{)nP~TnMgtB!Q?mH=Jz8WN1uytyR7QToNVnmCbP$ zvQAUB?l^}mUp<%hcR}VJGa*4R_y8;JPdXo7?)Fq`0Bt6e=tK7Hi>-ZwcBrv?f4eC0 zFvgP>fr0+r4zU?br{iChf3c-r`2PL-M8-sa$Aa0k4vwp{CD+zWUuLRqr|mW*cjb{AJwyzlPMan^1Q==^!Tu9izyYPI#UX zFKDK@MHd-%>YAZUmNhS&UH+nnIhI*(o=XOUwUt&m;TL)Umxc2xgk>4yi*8P~) zUt@L530$<7ST&JMypZ&pVfZK5|n#2*9XM*Hcv_B<>b9 z$&jxBP%@Xz?keam$IyX`?-+&8y;yp!b7WH9?45a>jHI(b#2R0+Vga)fs1i~RV}$-s zns?F*w-TBxi3YbWahkZUh4HcNdH!3mo2NCh+Caq@8}c~!U&%l;p%xtOKf952Iq_dx zx_tUqXgEZh3tMp9gM90JFFj0zmpgF^vH!63ZBx@YNm6yBRX?Z-6gqN03r~k{-kel(P z`oCKS4a|-G*nuUgV?Xpmwm=aZ2lm6MhfV5qcg4soA`r&)F7zPFATa$_;L&%&I<_A@ zzj(Fb`U{I}c2^P_G@(cBxc4TUS0)%kHpS%7q0KbJMsNFn*IsC_AT|}OOkwzI zC)l%f_d9rO-5NZ5;c_)1b3eETMdvpq2?<@2Ul5*ee20Z3!$Ok2t`8*Y0)__z1gB56 z_R*7ptH^G95v@&|N@ai!!0T#s$X3Si$+nl{2q?i(^U_nUUfBFQ_gRs!cQQEswH3)P zMF<92KvydF_W~=5HFPxg15qd@RtxaXQqY3vO$>NaDALJQ&oxx(B>2cI1%i?gPMmYw zdsxx3KItgCb^-_7;XIWP{fQkoOD?=P-O%eaS|NI!BT^0bEvu6>nkvZ0$Ng9+CQw?2W7wdV;L9pwZf7i?D>tp-FXGJTD7={kmMv>q?}lw3 zh7l&a?iqc(&*y;8c{V!M`!F+La13EJ250`{WF9uL>EE)I*yE(fY1bn4BGL)t zTP5!%o{PfC2#+*ln5K)senoZ-CjK;P-Z2-&?^Dv~vXyEQuN`FxJW%rDMK-I0JHihC@v+*dgip>~?Rc-3o*21tC+jtxg~f3^SH$%25TswO7hBS#Hx z!4)b5HKY3zwwqIZv;VQtra966{=N>0zexg(g)!(Gg@Y!dgP?m@c;7Gd<=b0_VeGp& z`}*9%Ic>K(kh;fvhZC=3#m6czpF1-1qHi7SI<<-kkA$_lJDNGJBojZ14m_vLXKu0-ScT?@Zp{H@}%|ONq@rhfy!I3yava95be2(XP z`tIFMJ;#BJ+8btcqv1KLX&z*Dj;W3o&fZ`6V);UU$<^;aCWcDdifR-G^Jj(}spP+A znz`rTf@;oK5y34Yv22e*wff}??b`Dt9&*hZYa977lKaJb|D2axFTJ9>+AiC^d~xiR zmD@4>FExq7eV*Q|8J8)lHJ=oA=68@Q{YA9O9;j=h?%8@Et-gUH^sv$?F3Xwj#C(xdtQcS-#*8-3QMAMEQ6_qxzvUxhv@<0@01W#DFNrgiEZfbv}UbD49(N#W(&W?hA^!H zKlZrmmxIJrqx-zta^DZ*-UrB0X-d&SLX)o;UCKCk{E%S^k@fa98C!_bwtB&bT)E~Y zV7|aLprqe}B@=VybV>I;a(=!Wec-+%Ue-PhDd&WB#@!s)(96wQd@DI?md z9=%FRsvg7%il7`Ake4x_v3$1{BaV_b;b)j65T=g~%|IY6)05IUJS%l!eA}4(0O@cs z@bcph&wTO(a}*CC4mbfdeh`61=teY5HkBE7^{)M|_h|sYJNM_|qB)cAlf-DfaLeip zLSkd$l#-~H2_N@kamZ6kKJ}prx?}bH-9$_TUgP%+aIq@@dW+K@C>lYk69~5P!DrT# zEqU$hI+2D8H6&iC5v6llmW*rr2k$`I$48eN!!7lqf0*0-nwjbl2rM@PE6b_cX(ijbH#ij&k&)8e$x9l+FI zK2726zfKS3DkGgih9`g$qApx^_p!#Ebv+O*i=Zp`{Nm4x>YdyU>2u{_I9Wzl1C{1qFfi*=vvf~)_MDizCJ>AR#da?^z4a9G z*q^+4*4u9Q-F@>E$hQ3o@E`3{ObdPjW2w|Gup>&cB)5O0+qpICtaRYd;@V( zrjj9+^``pB9rV0l+wucF+7y=Si)-YYqlNXCeD`3oE}qjVX>-P z?7a5rMQ3Q7rBN9XzT&LU`*$5pq{n#2Lv{L2Z{chp3jU`@;4l+WeJ-cMF+J znbJw-4S+!}Z~h8A?!n?Ks@`7ZF0^$j)PvmWmyrBPNvuNzV5*Ma9k~e_&gS8eM~4+KDWaGL8QVLEYH%bE6Lz>;3iI z$2E9&KIuSvAqbt-$OrK2rx)Fs9D~`B>q+>S@9JV@gEc0sS)P?voGv5zgp{J*NzcUY z@TJ%PlNA}95N`lm#WA~14u`Y~W+`NZf-3I4fk+-yKQNYj8<#lV08L?zK`kg^vBqPf z|MxB-kJp7DGY~DmV)A`x1l2g7QdSvD07E*i%e(MN2XUv!23zp+3+s$`OjjU-xJTqr zuFd`((09<)$lpA$JzCjKm$MTf?0YX*hbhf>$ipS2oHA!t-xVs#AqznBJsAIacGRBB zYCEO^fs_!?VtbtFkPoKPl%VQaG!Irw_Lf{l{f|unp&~JE(L5MG;i^SPtH~=a zu0!rW6v|s~Xt5ID*3@K?~ulnqP>zKmO;}ic7HwB`){cx;0$5{Gpgg42;7d|opTr@eUKq+1ZK5(r6+Kp5`0>&-3!|%;lk;m zdm^56Uqh|5^y3P7a#5+>WHMq48e4jkX*+#?NBy|3JqQ(knn1WB=X8#Ge%%Sp9NihU z7{3o`9{rG3SUf32+Bh%AdgC3!X21Y~r06)@O_!uPk<~qPV`dlO6@T6J=yAiURLkV1-!{s`wE63CC-7M{WKY2*H43Vf_B#cQ;1$>V-xAdyBt9 zMlg^qvtly$p%HX|$aVhLa=onnxWylAU*BZi?6LPgdA%4WI`kgaHDkVe`l(_P8*xuM zfmDIxA4c9&eKL)G%tU1wxO zNWlAwZM%kC3K{Cy7b?3ZgL6~3_c_Ejo4}>|TpG7L{50{nI~E3Zxm6Y~B-eZw}y-uL*IB_q{Ha!13z*>^IXD$g49{wz{R#&Zzb+)gP>NIRUWrSLWBgcSo!A@EaxGN__yNi7&a6@go zl2gLL(ZuYEj%lJZ$^xfni(M2Yt^qub^}e1h9y2CX?j6}&8oA>vhvWgoEM|`0PX0@O z`n&(Ry|RfDMq9J)Bp^7LPFcWTocWx`K6?v4KmSjUZ+GWl7c#K{LBxv)~paEUs6i}AuYotoEjFcC=Rei;E2lEdb*co0s z45RH~@#G}q=Nquay@_mlLEC&~dR$JF0d z+Qu3CWds@po=4Wuy=d#)Z3iB~JT^|qAD!cWMSC)DcG zZngTWbC<4Z@6N^zPYku3RF>%f`62$erhKS)oh6E2&Q7s!mT+q6=!C%VP4NYpNh1n} z>1SW8#*ICE#ukt_0+?foBf5X?uOt*~*-Z+Eyvh77Bk<-A?lE+A&1ebVPQ1Udp`O== zEoN&|f()Jv=OOND-&eWAHz5w_Jl}nnm92Yx2*8V4a4`qs9rG?U=IuE-`5&~=r&p(` zh>Mr(edhl7o{9f|-@@oQ&8<6J@^a$!e2kchYAm(Q<|X<7k6;(`$z3^m{CheaqV-v5 zR}cEDwUxPK&P*-b2yRB#*R!}`RzMQV6XsV#SZhmgTpvcHdSrPzY?bb=Fq6k#VM%#) zW%Z8SAD?*$Vs)qjiC%C!p1R_@Lp;f0`D zXsQ}G8KO-dhrbhTI%6t6O>M1-pD6msgoZ<}7Eksg$Jlm)_OZ@SgJsahPvh5B=RsbA z;QOBt*JZSzsC(cU-HU+&z5Jryi2y@NpbR~v^Lj?wtX(+0+ z+kp-};fb8{dbJCk&YXiA{vT)G9gp??{vRRbkWwi{+C%6h$qY?OITgy5vPs5muZD*9 zpfVdMs=QSEDNsy7AV7Rnu!y zV@{kF?AvC}l_E;HRPPlI*S#3khQ$;>Q4EH;v(WX|dQ;!~FC!WGPtF{GVl#(2UQnj$ zbmleU^J4`<$HjS2Oe%(|i%EzOR#w9m*`NzFa1eG60h`M!-&)EyZ=RlfXLVyDP(!L& z)#>X+9KD#iUPkUsiN6Rcm}_~OH?#z&%a>kdBlCN2dxbE~;SyNSL}s8K=U0j5 z{a^Mn;`VHo_x|$bi&=Ov8!Bl`&a#UW0Dlko`+(jKyN5==Rh@D!{%D*v2mgATSw zYlkH9(MY1l(^6-(ggl59=>g1WzEsdK(*-`?hg0p(h<$vw*@x>G>^4)8m%cWqE<|Z5 zOmro=Y2OZi3(F*wdaOLH?_2-GkL+y)A8n~Z4LF7QpMzG$b`^|?tPBPDrVE)e)33nP z_dhki$!lZi$;n`vF@3~#Q5UR6FGz~G>|`=d!zuC!4&mVJxxr_CKGrnFvo?-onUNmX zr>RD)7I0w`gdcJ2i-E}upMuis$=8*B`#S*+z`M;m)}mG&o=eTWRgPlrI4lad3H|wU z8CVlFWOsHTX7*WDwBsxfs4=Q*Oa2VF1e0Z1;A$PZf5GApB;w59$a|RNNg~iCKco2R zos*^#zqt7E{?6KV%S(j%b8xcHv{&Q5`I=6I$X{!B#BPOQqg^B(i2}yBRJNApDhg5z z2$|5l)Q@2RdU35Q3pRXeK7Q`>b{8c=dnIZgVuS>5j2uuUmOC#!wO4M9Wp{(zbJ%EQ z`CseJ7y<=V$l^>-Rr$bddUe3Pd-u#wrm^iqjgQgN{L=h<3Avc3zvo|mG z_p~|1puFx6eQ(=lTi_yVHf_q|-hbjC{s{i3%#3Sl#zC>l!F*tmf6t|&e{j&A>m-L~ z!vJW@lU9>yeDs-}!}iE92mHOXII1Gt+?BM4z&@%Fm>!>niF_3Td$QOWG8VzD;oK;i zUJg?~sN!upYpS9u_>82Pa|^_?F%%$vTuooTm@a#D2d1eDO?%8?#9OA8C^>euKQ# zSUbZ)wH|CjEHt-I1QsbzaRIJ|P4E@D`6&OcQc2)*>}=7DIWqOA8eTGjzB8Y$=o_Qx zy=eo6pFNWeTIMW94^9h!J}KZ6s)E>h`n-^4qHa1eW9yk-K}FRuQ@lWl=yXc1)omPc zcfy8+*edwIL90NJUv`g-b@SB&fihY|oP$17O{I9N>{y6!9BX3yG{65br~ z^YTf3$+C8Gb&(^)$=cWt8Ib~!fW~yA8LaA@Q4BWQ5=n}ga=>Bs7!ykx`4C|3o&+-s z1m1afafmjgCFd` zXsDc%VuKzyfnNYE!>8!wX<0jOt=xUqAkb_wG9tpFQN-J3Tnc2@nB6 zkx+R5J+af;1moRxPI8jl>ps9dDqR!s;DPb$_hc)zUA2NTR%4HQJ{TvPRs$qTalti+{HGxk=D z%*3cQyrB&F&0a-SJhPj?Nj;av)A#8SoDv56s*g`H6Mwl0Wi6P6F0)QdSX-2Bhuaw^ z>uwAtkL=5I0bWQ0qpWft-pT6wpRm4HBey$~a zC5V%CwFf-Glwl>=6@4;opFY}ZkJyD7n(g;GSE?YtmKYf6P#^pb0e3efC{wvl(e%ZV zv1mI~pv1;o?;6m!JDA2tetr*}d5q(H7N=nZMzXK`&VrBh5U49oV=!L*SI#D8P9r!# z$YXJRF{T+L%kbVuIB@8Am+NB&yEHDv&8kr09`Kh?L86I~U4~Q{Q=pTrq!2Kc6L@L`A@<@-Tv-7F48c#3gXFZ+upB5 zOR;HP2^Qmb-iJ2~%A*Hx(Hk37SY!cD?NUcg+M<;^Gp%=}CpmY-`UXT{>tugW;}ipB zTn6j84hC;WG!2O)AsN3}R(%<6X#xzk=8TTBZsuyOKZ0V`qpdjo7XPDa{d^{}Mr028 z*ppA4K3@ZDmT!|rCKZA5s+l@jlf)6&pIp)A47QzYsk-`!#_obyXe~53Ign#ry+GNN zF!z+n`gjl`7)I1((EmcDqKd1&(Pl2X$$PNkI%<(VWB?p_2BXL7&A1zhswL|-G}kN9 zk2vz1zdc{K8eabmyU`vL1}hXK>63?d9-`6K~yn37#ee zLli5V9s#OO)-zE4d_eZQZ@J@wZ1n7}7o@9|qzr4pDgKUDjG0DBiw}&5*aYRxHXRtM z7}SxSE+p&~<(a$w`-M;c`y1SF|BZF|MgPJC@ZjX`&IZBA4}6^s5U~AenB7)Qy+KS6 z$f|AUa0D+_MQDyz4{Hg)4cgflNsusawwe3pA@p4b0;H<+T2W<-F|s3&Q6sZckh5Tx zY5z5nE58OyBH9L+T=>;P~hs*WQ~;vm2{>D#%xOISfN!E}~g_}0NN2FpkgAQgaFrDd!a%X`MXrI$`q zBPmx)BXLg@hpP#bYPi%umz8N09-<>@HBPm}`^2u+)@R~0pqGEWd%t|K3|QDo%N|^i zONg5PxXW018QlIzsJAYV28g@JdOiWK89UVpZjQPpZgcSZ9e?x^%DuT^WQB*-$j2LP zr8v>M}xKWL|iOA1DOknyVb8IVP#m4E=TQYgbK$~%h%=-Q-h5euZ4x|7q z!{c^P`1L$D7&4A8vH&-?s|obhZHoB*ycP-&r=j`mmPaOZWK$AMx$OkmlUyc! zSJ$@Zp-<7 zJ9aP6Fy;ZLtEM{2F_SK&ajOz#H0G#JR&a)PLSQ%~Jl9bg!V!T83rq_OVGP{r9WV$+@ zIJRi2OgAVn(AS1*QP>u4JeiJo8#B0#hzsja;`WJa8xA%0W5to{&M@;N3aV9G=?0&owJt#pOW&ZHh<&hkycfpOIfYd5l|t2b5<1v$Ya zMoxw=cN={HU!_dF&V)M0{aX|FuW--2$IRzCs7J=@WgH|Z5ghAz#Jd0AhxA|nDTbTT zZsrfe$jL+QvDy+RwJPzek1154K?HFR6YQOzt)GQGfxdf zBSg*|AiBxW7TJ`zy?ge+@1|Ep_~{2&!a|U#VPDsp$zYj@wg>QVaVNd{tyVaiMJ$#j zqqygcDX)S*rbqFNWQzJB;Ce7u zA{zmJMw5#JD|cVnhgZ~}FWkSePvE{pqUivI{)rkaH-YV#@3~2gxNcM0X1S~+#}^v; zJP<&YB8|s4S5JtEQIWVAW24y?-AuDcQSuhn;Zt_{)_&W1USpa(rw{8Zs_eO#>Ri#~_& z6$QX16#=6AsVDci6EY@&^=LOSC)_5t>((H0;>ws2&nN)Er;4N4OSLzj%Vtf+ORapj zb6;EJfn&{1`LV~DdLYxc(a*jtjXbWoQ@@JGWt9CU#<0MEW($ZE_}jWSt1F3Bb3+E> z_^RaCE8~C)RFxemo{*cA`^Euck?h%NU`Y8rP?%eN6(VI5SBWz`;q}#T>Ip zrN&CJ$=RJ#N`8kVmPxvuqk1}y40p$up7&yu@812&``2dR@0Tm_N@i0Q-KST(D)H}z zi0KItiV*Qnd}m7XUUoi{by`2*${kFjD{82L+(-r3#?P}a50dm7H+V76?b8F_F}ZD}_eKvI4{ZSJ-Gn0sd)t0+U-*H92OIcTom-g2J; zWcBD>W3ek7ZXVLF^OoNs`wXWpJ7a#1>4oDj^~HI;Y()9R!2`Tjj5Zc?laAzjPJKs! z$Dvi(vchhR*lObKlAUbX8`d$7b6Nxfp4g-wn{$bzcR5=aq2u3gk@{^<=wTjpVa>$o z1?!bFml4Y@NHLOI^NB2aQojx0r};GT=EmjuL8_cTjU~=DUsr%$N7br{i#?Kj>c}(Y z6-%&by1V|bl@%K0o$a{nw&)BW%W5NrSqnBD+gzdl4OV=XLea2ed=5vEEDz8Wh|Spc z<@`)H3J0WJ+&&zK28A*A~4j}wAZi6> zudq9fkya31ROYp3!(Ikk;$cotJ9I-?IIZFGZ$F_G+V>XG|3P3Gl&Bg1y!AMY^`TpydE^+o1x7BB4lv1^5t&~`{@1Q!If)9_6v}#Jc z8+h8ypBV8T)d&|N`J0F#vNDMwCMxg8F)o((mxhl&USXG37z*q2!?8w1{8dY6zdoja zUXnjjJlE>~{o?*8!VN48I-WEU5fLIySgWZGOKmQh(wng?(K=3a(W2`e`HC|;kW_eE zSVzYC8A~L-0aHFxSrU-4`9=m17>$JQ7zM6$(l)Zc*5Li@|B>6sP3;DjN%v2M-#VoZ zFJAci6fR7#hJs|Wb%Dz7U;?41?}r_^A73^DjPjj4u=qMg?B*}7OYg~-B+9}T*Gx{Q zcTn1x1Zk0CP@gN61IptF>hTx z-h*lI3#NWdu>wS;`e^6H_50}ZqUqwe%n_N*;ZAcH^m}Bh}8(LE?BJZUVA8D6UYpf$pZ9< zsC-8~`N>|X04Eff@o;)@mrj51gkYN+ZPd5=BY=>)0Va=ke2*~AdXgB=K^gx zc5KHHq|u6{WSrKyk^-rot49RcV@(rF+T>lKej<8Fa&4Ti<>KNZ3q+33BpB=^4pz^| zA(^3FAl&HlwM)c0Ipufe9ORzQKWh|)g{b^!CVj7Gu=j$V{Z^Bolb6?}%pW(6tOTWF zy}yL*d>0|?dg{1fIDXL?xxyS=ZT`ZfsY|=C88*%T)>f@jePmzBxae>kD#ZH@gwvE$sc@QT(XwU|-~ia8zcr*TD_USZGEi z7P-sBt=@D5D?gGam_u&oe&Gd1B#pD9s^okFI8oi{neaq4vrCQ+)ap7~gjbqdY=->l);n#GCD8gsIFa>}A zL3A8TWbQoyL-{Tg%nF{Ia$!MwvNp_rt6+#QG=#*t`SclXNfKC!!zk;+q7yopj!_sh zmxZ+#VuDbRS!{|O**i7iwaOx6&Z_$(!5O?*&`RQb0JX?LXK<5*WQJ6 zFUztsBr6P6VOusCb%_YAXArH}<3Ro75M6=VJ1lx|pFGiTbWh#n0#fl%hjvMRYTwO5 zzyTm~EK6sO$noWR*I18RxqTH>C-^D*&A6oK@ zHQ7IJJ0?bm|D75FcT%R`(d`QhJ1-+`$7VYf^_xk_uk8%!-5XpOPG2M};Z=~#ZeCi} z*$4!x`3&}w!GL3g76lf`vy z!|-u9uCRZ;D5b2gznV)S_#DS0SB z3J!>4?ld+wBEpoH%cT8)%sS;R}uB4w?R3`U7Uo}9|l9W zea@2`OT`Ytv&86KN#EC&N^ENVscQ;3h(sE)tsIEpNZ@09Q}`*cZFgnS+mx|1lcn*r z@8UwL4#bE=w5JOudwVn_rf6GZv!#sAzBa0^9r^( zHWStCI^pOBzQ5r*#Pqqmii?p!aI?)hseJ+eH+~NYS13rVCI3!}5~oFhKlk40N6oMJHIM&u2?LxQ&L7JOY<9du( zwR6s4tecZSloc`~9U>?`SM}o3xdqjadj7HG(|lXNXfQZX03@CFjcmt(j#fyONB3hg z(3)efamTi`cz5ibq;d#Gg%K*@@8Ar|3D;L|_Dltajdi-Sa_m3XR)M%v87p3dI zVk8FONevr-TkFC-=itL_=56y296frswZ=jP@9s&g-Hre+nTyQsLP}Lf?Rnl0b`)7$?^*C9yRdnr(ELTyU@rnVt-!`(ADj*Mp zA6_=?^1}3t1cWuAA>jxotYR}Q%1j&6O>kS~WL0N4eV!(|UKR4l9E+Ls$3tK7cSMK4Wa7y?~QgEb` z4#`JB*>-AvHlCIxospeq>rId*4VKE*@12WWBKkR&N=#8A#B+)xyu82@rFK@O#j(F* zxqd;4$U8u?oTCb6^i03}e2XeUn3~O1&E3cOvVDpRAjdWLiHH>5084+yI@SdIbw`Qh zlWTEBv2v1US$pa8Rj@R*G@iwySYhb|s&?KtvT-3K6{-BHr0vquS_iT1syY*=?+h5( zj9ZK3r{JwNyIw}6gJ`_7PJQ?RCHQ9Qey{!pIg;lG1U6TXB~6*2=NApt6jL$|J=pS= z@~kXPD8~+5gYelO zml~%#BT7mfGk0W@Dd!9Hy9|j-y-CqO@98e~nhv;|I8XB^k65%h8s5O}W*@HOVC+NG zm?~tQuq%qpN~v4(6vJ>lwT-yKfFhYCwF6W_8_kL?pKw2YOr&`>w-O{`3m%H@2P`4e zbCft+UaW{aA{BE2#)qrp6M28}(J&`#y|W|rUz)91h##1d9Z6V;{qzr}jXm~B94qV1E3nVA}l0UQZpu<^60E-TJVS|||(SvYo0 z`;o2v(p*I{v7SOR=U8Dkxp%m%|pdMy*0&5_vR?O`*8Id=|C3 zY~0ZlzS}QxrHEV&;4(ch>5c}dY=ZL{48OCOgNa@psz|Of2X=nV5zbe~a6= zbIh3$DxD~LK@b0P=_OZHqwH=!y&e(^hi73dsk*ZjV*we&XkD>)PCGg#!>B<EQ*a>(T}=x5KN zEg%y}>We>`arD+PY9-s;f|A8RQc;-W1ARm%NUojtac`QqAsYTF=e55hV!3C=0e{L^ zB>H#5$8;$Z3x8s=N;46CdJL?r8C49q1iFzwl6eGo`FiT3o$N}c#{p@4L%fO(S>0~Z zN-k}T*_lNj9@2BuyUWrDhm*BnTo-5H_U9EtF$=b!t4U<>{1GSL*ST0&ENV4-^8}V> zA*PN71_tq=VMW+vb;fzUK`&;Qf7yFjz0R)Y%ta7^q{V2Tj-hnj%)B&jm5`I#MT{Ym znp?j-T4V2037u!rSW^V(%lptsrl#|){S{-Hd^dmmk4FO;lcid2`%jlM4o0{_Sg|%4 zi`8K9`}hZ!G@CJCPQqMb4hiW~j5VGuPvto3uGvc5FBxVz*mv_tB!um|wGv%dXwZ=6 zUw245aqQ{Sr<&gu7Q;!m$TCT+4gNqOPAMu-ao{nB=~~PY1Mjxn$Mi>Cxfyr| zNoC-@KKMOXxarYFzB!61XyA!CPgWgSGEINou(USz;Pq7-qpu`HISmu?#AG6Y`0ar+H zcwtT-*5pJCXeOgZ^J4jc!rC53cZI9a373%ex6Bx;#H>kNGkS%VINQzh7+E#7iJ6Gc zSbYUC=R{i8j<1!y`O6S`V3{a+QQQ8B-KCeE$@6TM8t$BG8vol@@HZ^Pbf~RoFn_A7 zW{ymnn!(lJ;$a2rxwIQDU>sz_zn{o$y*GPlKDKGK_5KL5sDt){V_PASv6!bT)fpM4VJ1E-~C%F zrnW5qV?N}+3nb%Wag{;TR0DCCC|-#d`9*1x84>Q0dQ;vo2EXd=%Oo`q$A<*L=FOp} z#1jQJ7zeF3O^&Zh5s68GD?4 zv1~75io40;=qbjie2%`H`o2%+v2}d#qVF|hTt!=5S_(1B<9l#N4#5Yu9+;x;OKMfB zfn&B?_~7i2;({AQ&4S0y8y{>ptMP=dt^}=PS~T|W$(K~ldP4HLCK)qbYWcVe55@v9 z;OHrZ_YJ@NMZQ@lh)yH(26GLsMMZu);d%&OHL^9wkIB9SXidt~TgWVc!-o$6eXm#i zxfL4cH<4{14;_7`{3`g*G?zl4>?eVBe#f-qtDG{HES%sCx`!h6EW394rbobN={=5d z-u&2eskRIrRMSj%hICCH>s9XVm#~p9N{y;igO$)uu>sj^3Anm-)TPn%mO7p}f~$hj z#VKO>|9FB^C1q3=m*H|hChzI{!(Lt&6V>AtZ~Roy_lL^K9E!O3!>CP@+tMy^3~xCJ zD1Nmm6Z$zEy_107slpu-*GnxEJtHHF-4iKX6@_ssXc)cWjM?O9c1T7Ki}*=7G@y%* zTfy>$U*FBhkyKGPG{jHwO%*4e(a#vFafY_ejGKy;>UTaYzcGC}-M;<;PxG=Yd|;Zg z=I*fBzH!Z(HP1R9+61#1#qD=7Gusr!HT9lNeW;(;-sFEaBop9XY{jHk+vI5--w^bw zA9EtilJAn*E0hKWXtzVl@rlwCD&)kv%}xZIQTtv%C2V!IxmqrvFOhYOan;KvQFB*< zqGYCuy0g^8-APd)n?j>~H5GAWxdeCB)o^~%+W=f9{L2srLX5a zHO+R2L`dTU(QSCCJ2NI+i!xJGl9$uFseysz-}=w_gAPElVJPt(1lQ zcH5#TXDX6xEDm{VKZD8I$&f;e_o|_zSj+AQSz%qM0TwS<+oKl`hJt`&uQOKQL?t(w zxIFb}{(EXQi3E4$f{Xvz778-hU7(2`1*q-DWm1t03Cj>wt_Re~w~;im(AcCApSLZ< zB~u#fvH<%}v!iOHzhDj}NWsqQ%fwe!|7DLpG(Js(qkN^lzJ4$sLWrpou*#=s_L~nS z_v28~7>B9yt%K;9ZUf1p0S~ znmVWqi!5FfPM!v0sH@@Py{cv9mfyuk4JXd@i|y0SCC3G--(#t53em+WaU zLPwE)-=9J#alir(K;h&{wZ+Ac%UA1wuI4%D{S!=3QMMpZf!JA-)*opt$BQ!4W%f!o z5WZc!e%W!!#P&Y}2z@dav~IJd5^z?PqN;>@!viXl>&TY1m`BzJ*`3RAn0HNEw-*bb zl+aSS<^N}*J|)Tt+G zf#f}7DJmvqpshn0_+_Dw6R@>hC^eO4*$et>%l?2I(DV(GBw^_|GkuL z(bnigKpIXn^*&ybw)kB-S!1Cu>Hm24{{QVtL7*d9v_K5@#mBZxK@2}Ww5%l?KI(X$ zNI?#Sx?iwaT5D!*%S8o$hM1%AF_&_*pxcW6_=v%bZWN)CLNSNfy$&6k&nOfTFO5sq zYFO%ImvUx!R@)Y+w!R<}3v$2m&JUCD8Dd=JR&Lum4A^xQ8MJY2zLP3{C}~Fp1L9R> zYZss6*A+c6o|U2pCeRIk!0I{g1;(`-3H=Vuc}tMqX7}}zbJ|FGOMA5sESx=y5B8{v zjiT;dp)`^HNsN)?Z6U&FCG87wL!)!>q#s}ScZ=}jKu`DPlmF>KQ1s}0?(km<87l*W z-FccXTsn#FU_}>{-r_L8o9#k2bG@en@U0lU#~LGVE6*PZj9-RhD2FnzosTk}&BL=? z%))OJFD3Cu$9OFA*=UBAWH9Ywb>9GP{rT*Eb(UG|@k3i@>^Spj7h!k}`Fm!GMpJpK zBfrJ=ID!R$B($<+J@`_Ip=wOz5NaTF%R8$QP6rN+L2>$Vv3fv99aYc8Kli1|EKDXQ z??E`EzQ4B)G_5{1LaRq;8O>}a2$Gl5)tF3LTRgRQ?fkW7{p+yT5m#hErEo%KB9Lh7;44m{lY{;i5;y&lh{()@2cZ^~avJk@w&!rg~% zGFj>}bppVzsJ^;~wTl(Ds|Pk~4H)T=tBmk8n9_yS2!KM$<0#y%otqP3>0f;{xQ`eV zU?ph6R}XI2W4*E5d*kV7LYfcpcoLP)l0)ryF$k^FXW+i?OcG2f4r3XIE85$2KjKH0 zm*JHDQF$3C5f<|cB@Mpv@>+RoE9=+Jd#!ZD!TdfZpob~S1hsWO-X*H7F@x(jUy5uF z@uB$#s|kySt>;f%U={5S(E)h+$A!q4y(p&OHdDoFsCw=2JLmC&NYVUv^hyw(k!^vBQSUKVO8FHqAcC1fs04{qU`IVpKyW><9_0-uuO>$x`` z&9N~#T^RIAW#GA6STJjCszIc5fK1B#)kka*E0YB$K&IIy=6^&w(mhmLDkxiB zt_Op|eynRg*1+yA#5BFB>);>=q<{6=o=7qoaEQbUqlkc|8u5joytsQYo=zVM`D4kJ zH;qOvJ76@M?Db@@KyP?F9{LsQGk3kmN92WXZv?bHG{F43S&`LV9_{M7qf4eOrMq8b zVt08URC{FO;is2c*MmbypxunjzVkG=4jD<@G&O#vo<&#Z*;l$bAz}Z{deWCeZYUDx zSta^~S_b73*T#&)$kaOu|6aQxjPQ9a)o9#zOTIQOEFLayQAP5r&4O~}6xZE*_9VwD z@t%fi`thr7>v)}CDCa87McAhUKX!&MccgYalKalYjoJoWdH>AE_%8G$Q55GC= z(VC3XcZ_1?hdiAx(KpdmE5OgnB|}#AUvJkhwMT9P%Fg;j0=_>9SRTrY3Zv^WG%jO} z&3a7n{vl2o)oE}q3rU^3?Au`j+l7a5iq-j zNfhUjaL~#Oc-0+W$fChKbIr>u#@62rS597!u$?o6wRFaFnu7Tk&S6*=aAa`z_M{1x zpq*-|etn^JI}~4jtR%rJUQ(=bd03ao4e9=4nM33oqUhZo`_w1xnHh216d4U^>c~YYcY;D2kyq8na``;@>`y8<`DqH(ra=Pr%sgnjmeNzFhi~Hr=e90 z$=&n=W}0BE;IVLnxd7pv|GBi(;tLN;g-K=fBf=O8UAhBSgaoCH_k{h6#^Mn?ISd^us#q;Wtc9t4L0S!zfIrFH__* zh^k1@BB^N+ZH0sZQ1KygnCoK3u&!-St(gI%e!|{=u*0~pE?GAS=%v99JW+eK2Dm84 zPjJu;J7JAOT8%obJlp&byRhvTn7=wv(?gF36N>Ne>BXVwTb&fW&rCxj%Vz^HyF|H` zcO3oJJ?OcXM{e96lD2xK!&!ZS4n_v1QOySR*YxVYG!EVKUb||+G>`%hV^g0%c~l`8V027o+qUvNEllOa zlFUJh(s9h8GpU8D7|MN51v*bk9!e51!Gl22)ol46wgck!XnK_fw}O#?MnTWBqM;S` zZ#B{jKcgzMF*@G5>iL=;j^XpMojPl2amt~uwOf1B^2XDIln1hY6X7kJnL!53fgwHH zsUwmpI{TQGMPwJx;!-MIRk!;gOOwLnuW557dc$ioI!?qAbPXj|&H5f(90Jv+2H;56 zU0v<3^t6^1*ON>UsmT9K^g=6~wM;P{9$?kkkq`@Muc%R>Y;2YjDCd4kx7ss8L72&J zhof}k3v5P^cf?oI;#2#}wayfj z8F!xe-K;=oZjivUsN!H94+RJAP<%sNlz43T5K@J8%fo7`Z2eV@*V(a0w^1_owmn_uDy|3nYo$@*m#&JV2+LfG( z78&rtVKz7MFYsuzJP1;cSLUTsSl0$HNqRcve`^oJ$*N3RbjMG}w*AtgchC8m*S_@(@d2=d7R{naQr%EjvnAoXzZ8lOx(FuIWl;~nehGgIBkS> zE>m9%+31FP=bmfOaC{0gEwXgLkp9QA?aCyqAu3XG?b>%XrU_VghO7AyTybazuyd&V z>QyQp*M21wBHEwB1Y>^~C|VfiPm@+b^Yb0znCj$)y}NeZe{M4uO5ljlkW&aQNIdIa z_uvyIIJ?1i=vr2p%A2r)(V&XI%c}WAZ~_l{7nn1aG1g>dTj^L!M0Ml!71n z29>b81(bx7@8>_*e&(^!AnkY){DDvq_z0T(W{#1h)Af{bDsQK#pM|Z;II@XOr5tO( zOLr5?7aiL$;J+kg*({qd5IB0(dCU^>ucegxTKfU`*1^K)v}+`#diD+gBQ_t%?32Ri zD3|9p-n0Cof{(CHXPFlzHO186x2~);>tI6U;(c|}9^xO(in|7r6_-T?wYGZU7%KDH zU6DG~Nog2miRnN>#JYrYBxVDQh?4}b5c;mRbmzGy;5YZcK5C|HOjs7>(G6jLwM2qx zjw^_$1|1+qX~wg~jJ+XyClWR`suQ7p#RJlt?NC;00VX~IXoOr{!1Uwn>W`ve);ZWx}dq_dy%!aRS(j)s76-h*W z!5gN@U6@%BBOKr*%Rh%`xq4sw`}L8Gceq&ACI{nz9ERG#>|N@&cS}zd z2FVFsi&{Y$yGooz#nVxzx7c^n*a#MHV|JVt+yDvrW zkiu|l#q>+>Hm{J=pVA)JRoy0Rs?R(5o2hJxJd<{M}`s*3w& zM}6K$H=+9H-nnzf|N7%s?eNk10K$x0Rd;9!gOrUdmI%SPLa??sG#G>`=P4)}%`aH$ zMGL8q4hgb%nRds(&M`j!9m?B1EJA!UOm&a$e5?*riN|tkY2BG6!Htgeny6ZD!aKKd zymc;IPwi0Djc@Z<*D#FLe;TgOaA{>0A>?h1CDb)F*dtlgg+df|vit-ytxsBM|I99s zJhyW9d>zpN6{+@CTBWZ1$*Ja(-L+7kO_Hda5{ zjzsH4#|T-0EJh-9v5P1Mzo_Tf%s}{MwBNwn<tD1vm#Wt zf_p#7h&BHoU&D6zUA1oWjX~PDZu_34vNXNtI3cn*a}wuUxIxEw5{T=&eUg_oYF~AM zPSXlPd3MLvWe|TKeE_)YX>hQ(|6bwfHnh8N)v0cMkuJr*Wy|5-p2Lztrp7Y>hdpXO z14+4Axp>7O`f}gGbXBlOzd#8R&HGqJ^=oa3(+HqZGi##UjoqJKE)bPUvg^P1_FhF~ z6@?MIT`L5fnXPs7xT?MWbN&aY0Ve#rn|)7z0Hf^Vd?9YL3Q^PU+F_~Zz)Zi6%>Hfd zw1=l^idftOB)9%}L%O47K{CKKAdz?Y`QbGZ2~L#(jpUrz&DqYD0H|Z%$cu;2GJDq8IuC7|TGLU0(aSfCETMHuP$hSdBCMcRgRB12i2;Exq1R zohB_VUbV@Ms75(c;sVjeD*(7SFhCKED+-JQri$C~t@FU1NUaprbh!4@+GV?H9+zQ3 zZd@4TA?BUAjFlf|9M$xiIkz;{llKblWJzT?W$1Zn@RwhOUQDDXWxm-Bgp_Vn8DH*X z$H=E*JK;9!>%uUfpR7~hTCDrKGGrs+M>`AhDeUy0|z)@mT>itu%iKe_0SNvtJPE71i8 zLBzgg>3a4OB)RJoGz`$_Jo68~Y+v-kZO&pb5u*h*CAqXbEsSP$_fw zp{F>8N7E=rYEOE{%iIo?s}O*ikjU}porD$qfNeG;e0dAvK8yf*qnD^~M_TEqDG6^c zH0i0{T4@o}g?*{fTO&lTmHNwKH*pex|GjPY@7MU`;2&bq$}crLq5V%27+KxEb4Nd( zt`M!|lbe&nnYQop@4_-zOXC0sBrh^_nyTII%bB-U#$%BkDrnPM{Pwhp^VoLYWWwWK zsfsT_E1c0(_b-81)0JczIyuDPiSEP!%iaThj*)lk$(~0sj|8O<0ZDoUOEnPim3Ycw)^j3P zXOJ|AvAbBW#Yf$^HZhVh5#IA6T8?SuaoMiNe~IRx?%Tn)IWBmU=mi=~C7TEYMf!L1 z%}ylb}(YWKktwnVhWWaTa8s#VAenZ<&V}9UL5P`}($*rg$31z7(GP z?fhGrOy(rmwU;YdSy|=n+FD}~UQJjfxyvU8_Xe(gCP#@JPeWIJ#3dDW=WEw%X_bUE zRA^dX^Rq2KE@LiMsapP_g{RZ3^x0pLo*^TjK)nqKbLFoFIK6Q=SSfs%R*n6W;oOv2 zCp68tJoa&Y#o2f6uQI$BQVWK(^|#CSB9kpsv^Af+>IWG7@M97_<~MCDGq~HgZ<8Kx zZNI9$efMv#UB(rF207cz{)SQSxT|{C0{TDFrT$lZh~?uz&z%XAM@4(iQEm%2=mneL z_Z>T65*~&Oqm`rs@X;7KB^r5vI!3^*x*IG{mu@v`D2-CxhKn$WtjI#mS$aMYF7qGD zWi*NIxoC6Wi5Zb+Bg$^iEW@dnjF}r}{FcK0+{6ihVlZ$U51vJ|-Ta@JK;2jkmVCt4 zE_jrEKrQMh*e{^0iQQ)cbY%ldJJ=t8^u+aKqn3AxGNlD1Hg;`JLPCd8(wRp@F zAf%iZFQzj|IQCk0lH%WD}%TY34+TfDJ{`*)=U+FF|BC+rlH;3>73a0rU zF0&lL;UK|_FZHrmM&j|pXutpPA#Cd+X;tGgO4|BRlid7#Z!lFa(F_m#SI8m7{fzTg zTh~CV!;VeUrguj%lKE#(ivu|KFp7(d-wq7aG2R1eP%)Mln;)(@LN+w7buv{FwS;xs z&|64fH43k$uIRz#c9~_JX$eNPQ)dfzjCP+pP6v1B@j|!oZS3MOS2`w?^kqKj#$gm5 zz0G%a)hTX>hjHJEd{)!9MFP$}4Ch&kpJli*OB8mpra}ec0GRUQ4cLIuS5yNYJp#LB zo|hwMJyvm=Om5p!2S0h;^Yr)jHW0f1;w8R25WPR{7UWU4GjsGPhAI7e$BT0{O4zJo zUpke2_7QqA_M>b~ciR6x7w{;=#^tFDjTH6C|IemHg8;M%2mYR8+2#OM-KUe-!};s( z;g%z))|<%s;=y_SvVM{L?K`1VY5n#k_HY+zi1vGL`m^kvd1P$tQMAEdN=bm@$!@27$hZU@7rfKKlEEJE0ryklU?MM)5Dwzaec9 z7UopEb=d^5z^!e{il?S~R=)NL^`|^UI=sA4O2?K%$s8%CIF@baC)pDZ2qWov4V4bq zA&$`W*0+RnCrTs7+Q3ZRTstF{9W;8OwBF*NWg_R~`Ik)^jgYt@zmSmZ&S&e}EvmId z(e8%0Rkm?zXW$JblxG(bAZsj*lT6rckMAR$`8o0h4m zG;VktymsApix4gpRXj?oA6G?zTX0w3K$-RY6L-F-xWkTRAzdY~-8QVc%L@W(z=W{d zkQd>0)lCq~%nRJw(Q1YjUYZ#A3?|a*(pIfow|CB*IZv_e2bs^Js`BgaoG&@MRnh4s zSVc@To|zsI9aqOfJM%1447tHK_j7Xiu9$rIN9R4m2nsSC&SBQ3ro|Q+aE)(5RG@yG zE0z{XOWkbV!K_NDLC6+x}5f~E^?I~i-$aZ+oL#zK%?c@Y1TIJ{$4S4Bh}dm9B*lnZ*x0B@g$5>q zQJh`c*Z1+MR2n=ZxC$v|!*1+5U;?d4f@N+zzhD*!bSe3(YmqlnX-8pC@CBD0TeY}S zfYfn#Q<}XqNxA>XuB&d#i8q&mctvLJab>Bg=eM+dk&xuztTKLad+ot(d>}^eA1ZPqJ=F-d(7C0^Y!H-n~-MKdf;;asOqd+-SFZ+)eviA1$ZrEL@XO;}0e{X>*>xp(=&PU(@V{g!5dlu#7Ql80X1a3KX<@r^cVoFQx@zsyfeWY4_5Z4PZiKjcaihyLCyrtMF{I=em1$>} zKl^KyIP%nIZe6);($YcMKa*XoMmMUQZz0#ZzWg+;+b^jRiy}HI3#?95d0ClMBp57V z*O)+jjSq2^a09y1ut+28Dp-(rAQdR0zud%+LK&C?(D?K~x!0UnrTd#79cCWYefbcZ ziU`f5;y>Oa5_N!)CnpqJr#{B(*;Z*OS=cX_cX}&pNy2$VoH`1bfWf>pfj8Kre(|%; zf8N(%0t6)={T_oIZMQPHXJ#i#))hS|Kc~z5zdrNS&t;xKpSS2-@wA0M=ROb2OZ(tr z6THHxEC(vlSyso)CiQIs9;h&f)*kd*zwV&lX1Q;0)krMwL5OI}7huHO+TU(_f48(= zYD3ZcYtn6@mVKHVj*Y)`Ij-TJ6mm~g3QQTDBtWqTZr*Nwkoj}B@KJbV!?tow1 zQ|CPP3oQC2*`eln@!6i&H3UXVfTF82Wa~Qsk?rlO*Ma&?syYYkrc)r~^q=bESQcj< z2O`Xbuh?mC3=ay&k3Xo=G%yH(8DaUd&zJzG-|PSUNOm)x`drVn%*E4}o);7BU(M%+ zRVJGuv=crw7jo;0adWU$nnJRz7Oep+5+t^sy&;fJ$~=_ zp_!M zrT&@N*E~&4O)X|2+f`5no~Ot~6DxH7KbVQh#ztCmbF(5=QA%a~&}iDLB)K5m=y6$` z{?Y`WJr$$#O?pH8hm9XB)3V7pE($2|d=xJY@@k8)EYn2)W`B28m2uF1^FH9tBD_xu zCEm_|*ddZgh9FTkkN>oIG7EmhL^^72krtaNv0W{lS# z0tT@GP)&DI_Sv(H*4Y<|iw_UM&gg9a;HRElt^aLLr{7tqgkKG)RY1sGSs z+1dG8ct?GP&W8^lHVQr|`&d&uo*W%rc=UCTnkf+fYg+C1Z97ynz@90EZO1!Xv?7~; z2leI_y1X#OfyXUgzMYCoM8Ux!N#|YXaD1=0idsr&Ogs*d#2YXvrptyPd8@sie#3Spirym(FUh}Z+gPq$i`!BQsps%h=v7^G)Xv)=94!%~9pm z$;dzt-jt9r7CDr3ou<>}V4LTtt#hQrT0eV0nNVP0=T_@Xc@p(D-T}&}F<7aNC~7ee zj~=WoO*84~ckxx3>na^uF>pv!RE;ux%q}5gbS$8P)+2eSE@ARBrL^T=lNR4wRB)p= z>4Zv&a!NXP+Lzn=pMomlZ8L&xi*JER$U%SgR@>k<@hf~@y?%#pgb%xvg=DW*%NC)X zIWQ2HqW@AqklGbC#oECwpnk~8qQk;XWgz|I zM!VB=sUgjP9?1%)_uP_)^8Xqg5@SD<-=*ol)XD1l{6AXk$RC)|(^9_`zrEkuA^f^< zdZoknbaM(;Uq-3P*7|lg`gFHvtco#sE9o=Q*Z6)&%hqk~_b)EKI|{mTB9dG; z4fc!*-4!tibf0xyMltL zeu0KJ=*za=mtabUc8AMc-m+zj$+FP&2QV4*Nw9u?MtaOL0=KiM(33-Z(p>DyLhc=` zWsZ#7@-Smu_p_H4Zd%%o9FsUXw+q!$FLK|%KQl+9P2n`|9n%_};btSO*IgY_jY8|H zTNUieGG)u;+I(Yh4-TH{2&imbu7#oLYwQ?MxMcP~3*^C{e&wvwk-z=(9|_!bMxvj? z^cIFw&aR`V_q}LimU3Kq)8Aj~^XA@}ui)!-O!R1|Yie8x*DaV2mu{#2KfB8)z3e{4R8S8?crSI6=FSXS^x2PyMrZCuPqsH4uoGt() zWShFOn6`H19R!%iaH*$+WS7n72>%FyjdUHsA-3Vq3jv8P*&K@Ec5({ko%6Gw#{!BE zS6|HO?)Gikt*3llZQ%RUV`nX`kkbo3#oB+_2W*8S<71ILm&|yl>FSfTksm6By(!`6 zH{fkVZ3QpsQ|l+|7zHArkiGPfhAKs>5Ya&6NygW{4TOQQr97Q@YD z)w@?AnfkEN?h8~RuFR+wH|XD-`1PJq?&BK~5Bb*3F-%K*?k-{J^<|&WEq65uk%lJQ z;l_yGl>V(vZRZrkUvJiI3Fn;A6!oh5;?g9SbfJHgx$VVIZ?dXxP-^WG4``*)eq%Op z_=NZI;9jFb$vgUHnVfPv-P&q)erryYSZpjO`LMt(v~^x|yp1FPs`A$63|)QRNrc}a ze;O5A3%jU304oN!oAeh&Mkik@Rxkhdg>Zy7y6lr=szS5qTAZssZvnA6D&KxY`TGxK zYq?r#wRCmA)woFoq(seX+Kn$!>aNqeyiM$p|*M{_a_tF}Q^UVfvJr(8$RBNa=Ho>-h{gn0Wl%-X_H3&J(T^5>-%mE!Q z-xWWLn$g!KenL*}#rl4ZOf9)ui(~=KFWK+h^Xt1)Z##&#yMDdqJzV`>WBwNLd^5`* zk<1qFJGre{ER|0*v^I2%?%fjk=|lYqpYPpsaQSpb!ld}F@z5DNla{Q8j(%%HM`qU_ zujD&<+GZIUNcbAgpC8g!`uN3XJ)f?6 zCwRp*nXBM3R1?#}*Xz}_UK?SxZOl#7HEQzlWLYq97x1zr+a>p2Z@#M5yBn!P>NS<` z7noSPaaXmqz6k8^9_-sgHA^^PT?AZZyIS?V z8iy-wIh^0a?$Uj-Ds{e48RB@_W?*>|-!$XQ*6?caDDEngSMz^3+FvkCv)ZhzhUsA2n!eRKyYDl}!|Gvrkfwg6st?c?g zLE834V-aAi3oi~(CDQR{%a3N%+~jKjA;aDxVOdVMeLp1q8q`kAH8T3=Bx>!v7mSiK zQj;Vnw(_$-W1(06<3im(ZlUXVO9l_6f%mM&K5M7_uARIhpM3SuYa`yx8}dHf+0eHPvoTOq zOLv$7Z_hiuy`)Jb_r|i)dkM&!=Y8-4aIHz3C)~M>PjZ1KPvBqxuPPM z1Lk<1>v_SdaO>lTQ_e&kN*qFR)GT-pM`Nd0W^0_y4BPn7(dibC2{l<=8Ks`z48^O) z(FxzEZr^6OaZRO0EedVPm674iZHW!W#dcaW6>YCuzqO|hF;!PKo%V6bsW!*;uV!CW zeRtbXsxXT~GNb-NlL!al#F!`M$pNm~`JVV{BtRZ>ay`Z-U1fxQcfD1qsG^B=>kfP) zM85gl`YcMg_>H)ulxF8GG-n?GI;Hhgs!WDDi`>6Y|72xUjYaF>nb-~3ADo`Q?++B4GV25r zs#Y9a_v1s|o&9U<&L2$duT_XVd#BO(VfP((G?h(IT3Eur$M$4!5S>w?#*3L-hl7oQ zS$M3pEtXC#QNz`msID+1YywvHmSr~P4pNELo2)U>=f9x+ zVsF@n%W-j9)tgA}Hn*B3)@F%GX?Is&*qdqg8fGcdZ%$?4`P(H_5;PMGr52i43(6#> z_Diwi(f^&Y;m{WR(YP&R^P!QBjeqE;ho#gz0H#_iYzgs^*)I1FdFGA6RsC z+_YG4y8}hcvI}p*^ojUWBj*aFo>q~(>bDP-X34|rdJre~9Q`)4b*sGi;wH{R#y8B8 zo5jgAGkRcB5lcy<>S6HeXvT3)jJj~*Ij%{*n1|Q*u~d`KRl5hzWV~}?4e<8lqFh@n z3;uKHkCcS1Vy4q8l)ZHaHpJ|~4BKUm+4uP-)~Wl6xgqDqFC|4C@$~WHqw0_O2fI~F zb1q3sO-)9j$2_tX0tE4kI)C}jD?Zo1!>#ay+Uwr)TH;(+z0!MhnGv%~#XOa;NC8Q8w7m-tS4RHFD`gLY#t07qQI z6uB%%IH_@k#r2rSsbH&^L*CW~?6LabknoPAeM5mNJ0IFgT@Ma}=Yozxjh3~clYKCM z&z#*9IPl2hHn(+uE>v!sRFN!Sc0OjyL^g3OP^T8Kd>0+nb|*@}JbGQ8Gd!>NvVAV{ zsW66OC81b%1b6%4xERUFboTJb|TfA@rqT|QaaS8Y)~Id@Q+Z5quZ0d286Mx@n6 zT09=*utZ<>QKw{>306ur{lQ{16Uuqzi=*#G_n^t*050rN~G zd`THjN2xt@{;evVyZcT0Olx?KU$!PG{5lM&CrDU8nHPWIv8la&u~k@2xSZ)VR#atz z6VktDGNxJPRv<&gVz%uLVCDNjtNQ9r=qlVqZ-VF!B1dK4WCR=!U|;J3B)WRuvzsBM z` z-bfA~6@6dl@5;k3lvVvzeR#O+#6rI_Z#=(RlWOdK4~JBCr)wTKUMs)ZOCtZ`a~7_q z|9Ny)L&@e2WRM6qBBlNIM#u-qWc*NdAdMnX(@@!KyDl62le{FNv<1kLZLzDdA7m1< z@<%lqWDXv@*%zhRc+1#y-z~4!Z%h0J-n0se)pGLTcVc>MbV@Z`=2^= znXSVI!ZaR2`YE1Jx9^bB=UJ zIC}6sJR4nNUlf~3MEJpTzIE>&KiX|Y#hPxNT!~*YPLsQA5KPr-t>~^vv1eL}HlV`( z$C7pSp_c)Q{&d2AIWlp8+hmj_6wN zGkDblj@A2*t$>0}m)yL^iE@`gQTz^WxL4*d_{rXWm)@y_sxHUvfu3CG5~!)^Q`xQh z*QDANT9gHDMtXX2k0nW!Xk){z7x5om9SOGhYC*v;kxg@Ac>|ByMhqS8iUYn)Q7I@5 zeL#r#p3%E&?q1-=_K*yjIa&r1CG}9m#6p$?AOdnC2i08muN5#eLEt;2e#Ljd26~{< zuy?};?Hhc|JTI#4I(R`xa!vFiPhA^)~5tPxHuvvXSa547vfLTOr-FW$@!P>pX=G&NhyMP-K~l^6Cd9!ssk=9EdVaGcS3s3NIB8ri+{}O$uUx%V z7*miIngEd<4Kz3Xlf&zo$>|!T6{(UiDp`YS+qFagd=RZ9`vS=iQfGYZK|LQe-(=pP zrWdqiY?d0tT&#o@6PUN{JLTidH}p*O7SrGt39luclXA)pm3oN-3-XH~lm+Q6=KD{U z&HvK|kiM9$d8+@Thnr4++rxu23w?GV%Zkqhg2D?gke-QJ@dn2OE>wmUb%jR|bqzE~ zHW4x_eB%-iH4=-<{}7DhjSOH5G$b1C2x;&GLTOSx`&`(6{qxD6E$4@&-DSP>#U!X@ z?0nPjCptJ+E>!^-mq!aVYdKbP?CI^2M>AWgwYx!}yt@?IsmFA5R!T_J%x(lT|F-1N zxBXPkrQ8&*9kfJ6f(>GPg(p$4UKVRzbHz>Lg~(s3k6g4!%U{lrKXzrxstzwyP5kUs z)&Jo&`z9vlmA6<~1n1m3=4b4_>sv)|+F+8}y{+I-X9h)+LpH_clH7T9dTKd4dP2^zSoW&lubMpIMMW4!NSiO2+ zrF5X2K$7E`5wBa-Nogx77b*phUVkeOr)?zxBY2Tc_b*?*yxYD}|NhOJ^KbIXvQsJa zL@%iWKAK8Jtfm>c)jO+VgX`<-WlT)M4_V`UxdDo=7RS~4`T^^j1?spu5vTcQ^}qH6P4dM2`uMm z#}S8tWz1)ndCsV}FgJgYgx?^r6RqSE_Po#t5VyV5Zcgr8$?W5)~IFrSHw4MD$SJyoP7}1P0i*bb>_stAajuo?@hp% zsFwr0bE4b~jl(+{VHGex|jYa5E<|LR7KcfiU>pE}$A%{~^szOw*iw)7&=qwU>iRSdQuYA12 z9jYYfP+y{EdP8*~uM35168sr!kXoRNBcEX%E92LCLQgLn z6;MI8L-O)2bqx(--Nm@jAt;idyX5cNk#;YRk8fT1q*m?6nN%qEKMSQV2Tdgij3>@` zX-`-KN+aW$g(i~f2Ud8>X|5FOVPSKc8GcgOTBGLmg4v@-NSzNW?+z$Jd9IkKs4^gx zdA&#CG(r*pJn(I!b?6S!%2Ls?S28$n8}$ti{#lL-HQw6?V4?zxJZqvJ0kih?^Wy)m zt&f`{rfh7_oi^?3tR{Agud|b~aWxQB?$?x^fvtKzO5w=32y<$c$F$g+-@W>>e75J3 zc{#Nb)!ff6Uz0PPo)nN(D`n|Xrq7rie@z-S=%)ZsqA$eJ{?bT0tkQ9EN2QOD{+Fc5 z!53LTAxDs0-wx$Cwl1A{-P1tKQzT{R4ReTcrbZ>Wf}}e2NJ9LzD@B??{q+0Ygsh;# z-ic)RN>ss8^E=<>5#TW9o2y#f^vFN|bo#`D{ASd~&2h#|_>B@Dqb7TNGo7Si zzfc7)qcE}}!BiMN_}utU>p94-Uq!q0MQa?}flB|Y9Sy@__48N~n68<(>U9Fqub`^B zie0;?1W@;Hwdv{TEfg&Jg7IxMj(VnvXg}zNS>PY*r0tiLT@>~?v=!j~7%hFK#P?Ch zQNE@K1geC6aCpV6@)kTg`*Q_`trZc(Amy>>rAmqO>HpnIkJ&(LaX9P$3K@f^m^AQO!SQdZIFRdX3v5`7SZySxFIAdsRe-igZ_es zq?(|=voJ24M;v8Vb}e_>#DV=eLUZKRDO~IF9OKu}m$4S(J2KW)aWJo3|JZb&r@UW1 zvw3Ksta%ShR)xkJzo(&@Ydmp?efsVFXSW>B+r0~n+Pk*gYtakg{l}2_x;ouXQ=qa5 zn&y6+>P!e~FWO9ezFAFZKi~!cx=nera0tlwhv5p7k=w#D?zjJcW_Jyl-Q)Y$PLh!` zXs8_>=7-Uc{m_2Ix5Tq&jHj@WBm9$L^QB6i$4_`nzwS2Svw0e+INXzE(wFY)aI0h1 z{5h}E&ls^h``U6kp*cwnm`$9S>l;DdY}U=&KE07^WU6|Ul= z48*Wx>&vSVd9mZ56==G`*B-T)u?}Mv)2>=rfZ!xtXl%dfE#jHtT1>p8IKjrxJTo)W zW^$hxPD6_8ZFLmP{Il8Rs;S2P#QyI%m;um`vCjsU_L~f*CpV4A$vAs(@;>CAch+TD!titlKpS6FIjEQe(usJnIMy2@w%m@!^6DH`6LA!N}M&csIoM5h`eSO2^)a z%O0Tbq>G)`;j^6$x8`!w0#MkECHysac%B3_&IK2u@C-4mCsZymM2*C(^pU~X2U8hTxNA@2=}FRjQ+2S72!j5T+*1F`L*^5R2p4~R(a&a-Za3`KnNW`|AX zMRcOsowIjhQhz^+V*w3iErFoFPR+bK>Gg4v&ctK*)IhEDw9`#RS(h~r6Ok=?t!Y}B zt-&3Yd@5NTt#4)*TuBqG|IuupeD{i(-A{>!e7>F1(X>( zO7*@a%%u%{r#kcPV$;t65xb=i)(gw0w!vG5f&EfkVs2rvQdl_OKqIUy+@sRquVda! zgo*-Ev(zWYJfB2c1VDZ3;*4sb_MPXE;M$3C8k+7-=Z(1SvE_|i{w9s89X{-LzPWGs zWcBdp4#VSNk>T6Ba6VQG4*B(`Z)$xn#p&_ojib$MUOvA2jzGQ%LA?&oxt=`N_C(G(e&yBro3@ z@!69^r@+(<00BuC4G-m_@9Lx+Udv`gK0Kf6Bk)LxPt~{9423Q7=HH|+PrY2TEvYIw zJ4Lh!{`A#LT*hzA!&2;Dvz;L7vQ1{DXHerTmX96@z{t zP;Tet)tbv=0vHP3k1i=cq4||>q*_c0;gX3F_Gll?n^MGR2-8n`|`l-HhmC%jO(om~vpL>Ur zVNQkrMOr`~4AM${djhcDo`w^~qDc^Rv-q^H_zqfzxU3v=$|h{jlB@TW3vB2h&dv(WWzT{WR`pKrHuh*M)u}O3; zFzNMLt1ouN#bt5WORehWs2NrJ(Txg@Fo%knV{2TgE^w`S?`)S}FxgoNg}O7<^D3lh zrZb+P!pLUB2n)#l06g_3ELZVh^^;o@SOD7!+cgCT&K3jl%~f7r9@pl|Jb6m~<9VnD zkjdqkWp{PmBzP^3WV?@~rW!T_9Zhgti^Zc>;W#m|(IAhU`ux?#69LH&5-*i8I_Kz? zK6j7a7;zvwTc9Q9xX8Xc32#n&>dmoFzcOkO+Q3MX1yeD>C>iZ^>(J`j1As4*%*o4- zHFR`vNV|RKjx8+-uFFFP`Ecqi!E@DxW zdjL*K>Jf{^C`xUqr>CdN5rQtf<d!P#mwb1>*t-N}9R{5PRuI7A0r6mgpUS~2 z(i1e$%+~%+sCs4LA!Q3v{qMNDb2|=H*5&{EFZ-S6K({CDxCJ*SkwuI!r z3T{Qf0c9kcS0O=04{d)m5yo=V_V#xLP*oV%ybue%oJtdAJ%RgEcTjipIT%Z_WM7KIFPf?)%P~qbDbqg@uOw zoEk`Kh4)CyN+4})-*bnI8kHhH%H_Gs>WDJl$Bbz)&4CIH4}dNiz5E| ziqjJ8H7-T|AfakM0#(6-o~W2%s{Q)BLQvsS-x+%3d1{i=0AQ4B5U#}7HOGTEu?lU~ zbf21UFhzRjJ5+dbz=`@Ia*0sl%wY;=oIZJSv<<-&t1$VJo``NgiVk3%ME)OOq%sRA zZx#e`Y!7qk5!UF@GS+m4(j2CqX2~0rP$GbQh%}MO z5+-RUu)%}hD~4<^lGdn1PV}j-Z-#-5{dFi4%JB2^^K9LE1h;P9dP0XD{4~$;`E7DvISk%rKGfvfj4Vm5A);z|m~v|)7R0VY=y3dQIBDhq^-p;_-F1}0dOrZyHv zNO)HTu4#~oqS|J@T>O{R-9J<&2+wky6T7i|GBw*qi$p<-V*SR|t7Syi%8Z&=dJ|0b z^HfJev8`ccK1jr(la-!Q>OX?;_>p!UO*r+HqmFqz_wKr$@PV#x+&GCS_z00o(&x{| z0`k(3d5#80w$mc4BD}aVP8>ZLL1fabJQ|HoE2>=IzrUE5!|l55bCG)u^%3r$#V4sk zf7!|ZP`?BE%`rT1mu=jlQfOzLtWB%F@M-D&OLa-s?HpA0(Y!gmAlWBz>D$&0c zedV;_S64~~Efk|xLb@|Fb_j}D2fE4{WpZ+IHn0SW8hqIGp|H?qUONMO&VRW&<3FR6 z5nnY~Bm2UXJ+tF5D6Od=u|C#%R79VkQlsW`sS>5FmDswm=PWFZA*&aSicn`Wi4_rI zKip;$T@;}ud7FdxIx{tL0fc!j>Qkzt2z`;LZzg)5*uDEAxMRv)tiE#KrqQh|nm?RKRzBr+^_1(*0vjNoijziSoF>_7a{xHxf zuWxua>coG#`X-bK0f|wY9xq3z0@^ zFB(-56P{)MiTe0*qF8rm6R8rbTNW#sBugTf(NdYPp9u1_)jX1GuXqo6(}d>eKaFv8 z>oLibff|^uXPGikH0OH43|1e}qP*7Z;pwrW!9Y&vEByELA zQ133R5PJF=rKQ8V`+;vTyi@{B6rGk(Ni7itE$=%ODK;@AwAGQE1I+@h^wX)(Omr^**dRK94%W+0er3J7@W;j~O;uI>b1_GX zwbW2??@K@pl=Lg#vtqTy9HKWLTvJ zI>Mb=VPz(Eg6R;K@%Q5Wa~vs$40G0VeHt@N5VK8Mln?Z3>%*w3!4 zfpxwam+mDvZk>0zIVoSQiqg5v5GNK7e_Dfmqv4|M3uH$V2oqP{GGizT5K%Sgmgrf| z2^@g|3oTOGzMUHM0fHqa4iZT4k(jh}ggW`Aklc=|t)P5yzG}3R*en0>Y2P@GTtA`?W@rqe-!S z!l{av<}PFZnYE6Fc7?h&j?-5g^|)#fAl5_joWAsE|CIgn+e=C-c3J7WYkm`tM0H!B z3Oq?Dcl&ErR((zxCV3wx|{h( zOI3jEa&Sf0-`Xd%E?o?bXH&qVj@Ey_qSJBCn=$*?Uz)xbK6U28>xY*!?Vy3Ev&RyX z#ODStZKYEx?tO=nE&ph@=4WXxP&|Cnf$ifpLc&5vkOEhrr-{m$ zW9tNHcgSi3aY*{g1{{ol2rC4F=O2qXIw=zSUq*(aO(KkvhhdWrr2{h|TcdsO(+{Gt z6-LOs3?*r79fdu8MX`K?d`8WmURg+!lh%j zuTe2ZT=X^b4h)6?h_{X2%l^tS`-dhSZdk+3$t(Io6x`aGvM?7L*&~s9TB|hyfuapS zj_G5Su=4f2(?fBO3B3pp?-v#n^uR)7LkBD`0+*8PT8Wh_cY|=MA3oyw_!qlG`5&2;iK!bVZJszwwVO8b z^6r5~Q=X@?MMMQ6C?e9;LC``#*BCm4Ss#rOM4q8{FCv|_a#y3cn4)OV5x@e4Lj$!V zLgW@M%->{O!E^EAMS02mw{P8wiWK*YX00DzDea4ti&u6Xem{RIaBtMlQUzY8+VJ3L zUj0{tKVEsd_&yl2k8Y$3VD8%}!vW}bu7Y`Cc;W@%%MP{4BPp{+D@`38pf$cVAe$8p z&7^?i3l}UCrPpq!Z+bah>qV`O6T7V=$D-uHfBP9`i=gxO8tDa@&ue zs~8_Cw?R0$d?U+@Ym`JrXgy0W7E)I=xQ8&$eDLQfi=)mupc>sA96ZZ+3q{d=wzjs3 zht^3>o&Vn+m+VxIbx}+c=4@i)SaMSmQ%xS6w-GQ+`Eh9wfuY_N7o|$6>#Uy?8MfYS zcwWYIg_a79plq;|_~n!whj_PpesPx0lY!ny`%A>6O;z-^`2 zZvzMgatvDpLzpY$%t<)@>(fp;7Gvl2BMTmW+hp%>D*d8W0s;$%oLyaAGs-s{$FFiF z5<}WM{G+#V7#a}S07K>JL7QZ>OacFco`a}5B%alDL2pq=d+2cnDjSuKWfTh=EO+eK z@m<#W=3hdle`ux=&5V!BGQLh6Bw*k+1Aew>(IRQMF^d*2zNak*;(9E6DIw8((b4BI zgpyS1V%4MZftMhhG3o}m{8{EGoHlG z@f%BNH11sc_bTiT%+KOuADAaL2U94`5hW;KxO-gkL`o0^*5_MwUlW1BU7=X6E7jfW z0R|&3)f^|t_Q3z#yJydyy3Dl}wC5B*g1_hqu*nC5(At=%`NJ2ER@nMVq8EUwem5+GI<9Uyl`W$8?LWQ1IG&`t)gUmy0(>p|M44V42r* zE|-K<644aZ>%bvdz{zQv)(&aLDxe;3Ud;@hPj61eJ$wXimG|B!MZG1q2|Se+s_j0p zur?bfz`sBlB6Tb0yd}Fb z_^7kyU+oB*sSJ0R4njN%1Zk-6S9|v^E76iX(B+uY`qt zl+?hwX>!Dj)Gu#bb6_>ROSlvdG45JS+^r^QZNS2b>u ziQ3^vZK~G;EH#ipgfzdz$6ZgE{sNVvc)PRM3Nm!wx%W5a=Y~Ihx{L7CZKqw+DQtqw zmUYA2y+^;ZYR~%1dTXbG)6gvUZT`d=rr$bI-z`l1@Zkd~zHZ;7IfE3acSU3Sy{#C4 z(2Tz!iQe;G;@;miJq98qo0KYXqc1qjmAjbAG{3;P^~keSL;U2{ko*!D{b`X5!Z>gwvGQEMnP$L>Nxo4-w^<#i} zkVCo!uCa|^$+dT}260xS*+6^};%rAA*?)d{RsMXTbDQmtz_j*~-r7-)JNhHdXn4vx zX$mIpiC-6xi5554d2PP6v=dg>SBMq`KR))yAr)J#+tvWo9CB@WqI)3y{7>&b6 zUL1u<=|DS%a=v@$Gzqlw*AWswJU|iulWWH8`SeGr5EjvVx20ie02^ZR?PwUyGe-4k z?;05Q2k7%3Jemv&eqFnX^&BQz9*#Qk6R+uMZx9HuUt(h7hcn1N@CXP9=)ZnT!N{r7 zB>7w8>I9VquZ>1`TB@EE%8DRKb=Dvm#D@AyOHAlZ|IxclVWr>p(&1EHag} zkB55g1HHqDd9t#yzBa(IByhq*&mokNsd%z9yY=rTf_e|$LMQzsMs9^PPW*Hd*lo$% z%+0+MxCn0Pb3w#NJQpYcSkS`r2F||>nvXKZ5GgF_5= z1xQ}iETim169g9hqQIM@aU6v-*Aq|r5@dIY{Dx1c0i%c^Lv=U zl}Yq-1VL8u(9?kO#5bg{F37CaAP00aamN}Qepo7wc0_=J{KjhiQTx>jDI?EyIE*`FA1>z!ze}v#YICbK!&`Y^TgS3dXfPLw+=Gp z@~c2?rx{gc=c32QWy$NVJfC?)zw+J}`O- z1`VX7YKy&pv43YU}z%(*n;fW`sC|0kZZ#uKMn z=!~9UvcI^V(pk0F2oChNTi@FWat5TeFLqV2qT6L zjXC5T_8}_VVR!2~2O_sJRKO4-y)*clP-7bcpl9~C25&LzJE&>x_FZ&n3P0obrTpJB zx0+zAp{c`*q8o17>AOe;bp5WLO)PzK&bU2e%0kS)^v_S4?UC55MxkP~Wk@)sK zu9OS2NXTJcZCSb{Z#XEx=N3RX%KbLTh(p_YH`o{dnHR}wIiQeV*KEjn)vVkg8WA+J=z6wY!|yfdQnZ-L5z_Wd%fpltyK7) zpG5c{nsF`ZAGGacWv}-+BEYGG4i97A)pdrnOlxVNXL|=Q0L2fRn?qyjNEbX5CbFP- zmD>)|iyuKe)3E$~A5&WKyrnhQH%=Ym_xn!Dy%NwwVmN5HxgUh#+nw*k_M3pdm~QOu zV!!YwwD9Xvduw8>Nx(-FUO^DUs0zf*thTRQ0Lu!rJ1#N-Orv#0*En)^^0t59;0Wvi z%{tlmN$uWA-|?5pxPS&6J&|QMWYKNv*8!qXRsoU|>Nn<%1`a#IqPfwrpUdT_L9pU9$DS{{$Ei{X=tDE-Chz zog^Up^*{agau7tM>WGxnV~PHMH`I7~UBGQ0>RxYA+F!xU%&f=i^4w}@1j4&3;mx`2 z)U5;omFgtniJstXMTNj|)}!DVsm*wL(&L((f)UqLJ8DdHc<0PvZ#LFT15QsgqImtMJ$SBdTFI5|6mJL%$tU5nTdPYuyRHKxv$FfboSDD;ldx58XCGEQtPZ0;ssHc4rlr?? zh|FbA*j49=(Xwl(~+khd(0O!nXPOyHsVqm zd#yqTl*m$I3ySZ4MaN})Q$s^fT1O70w%ePY zZ94SOu*vNmABAfl(f|Fl8Jnyycwo3Uom1;)CQEdz;qm!nll>n9F;_t(X*+758(GNke@^Z3^VQQLp=_S;3@F zXQWTyEPKl~K3rh&y+SWiQHZ>3r8x;MKP=+<_!t_SQyGv!S0!X@`MMqZm(_y3p} zcC5U$&iF2+ou#e~M&>%xniP?XJWoAo*DNEyQV@?7G;XdgD{q5+x+`Yg)>a6&$f~`} zXWO?rv;#41Iq(hyKq*?XZkr+7To}Ae(&6lAzG^V_LCW5J`z)SvA7Ajt<%!n9@(h$p zU!0f=WtKBY+B}JmkFVJ#BOMSN99-NWI*sh0A{K1bG_lVx+t-l0Z52A1uWi?n<2Y36 zc%!4EqeVb{H!Xdv^hdBvZ;(2L@paR)UzYrMKF?uox1AQf@%*T33=@z0Kl5UM2Q`^B zv1U}&q|*lI(jc_*pt|}}q<>IIwA}@Md?Wb-lqFcdgmph1{OwRH{tSp<^-%lUx}wzc zty;q!o;qcbN6Qbz?xkmXdpARd&wCO2ryooGfs38lRia;?T&djya4Z8PSP&`yaYSD8 z@wnHY9Gv*X7Qsl+#fYuoFYuwQ99tg;47>G2dP8n;adD9L0FI_Yx)49VGs<6nX|(ap ziJvYlc??m*@`I857*AjZdR-rb?`@#tvSgDG62N!*?K`Y35WDPY*vR_Flk8hShqh8f za|ZoG9{)fN-@6VeV_@gMh7c`_V;=l9#_IoO6` zob*r{7$w;`Ih_kBDt~->s?`D}6H~r3g}-kc>Lu9C%HFiQ;&xV5@OYE2Nn07BcvhXN zGvK@Z{O5Z{;WDjtZCn&CN8@XiqqonPH6qS_fg`M6_OzZ!S zp_PZLsz(01|H@JOJ^B6|1}u85{SVyVFL5tLCp+mwQ7DMg4r+8IYRpcellwP+;O(U z{h_S=r~1GrF3xopncIK=v%k)P+u>=SdU9>qZ%kP4v5&?|BUQZnY+lk&mGpikBI=zS z(F*4u(BQV=d~AQs2lhSXdF+)qdv!h;sIqpuD6`RB|tlB zEw|a29}&!Ic-|n<`>YXwDBK%*yThFSI0X8-Cs=%m@L->bbrD>I+vx^Eme+8)6eQi3 z@uO2vVdg;%d9pY+U?5DdD|F_|3@`J%Pyw-!zUuQlBRS3Id5KH>uJVAZL)Q~&D^nm)uE2UeXpwtAxz(qBLse&jExM?rz&(Ea zedo{xhlJ=rjo4s=3+uWS;Ioum^0@1aQC(b(t!mqx1~YdCm<;Z|XU(es3cXnF?qp{U zwRFBXqfT^!P>W#VUdZL`T+(YnDqcNQKU*)yK=v-?Ng!74olxVVKhR_}b@vTKx)5F^?Qah7VVt|2(lU|2w2- zLR?io%>scAGbOU&sH>?}ba=zDp-gQ&yL7o7eceW)l)%0m%mb5r1x6*d*; z&;Mz9xG28eu$5~0C4khAP7(D1vufH|8)%Pj4I7@%y=NElnC9`q7jY!GSn$ye345W+ zE7Mw%25fHi`Nh~kG%Z>Ab#S_+WFKr^C%^UE(_FceJT$cC^4bW2*FoTy+>)skuA4t! zNra{cw~h0`j=q*Z?{6l34YCs58@G-xDi`0VLx{q)bci@ZHwwh7`0Nx!@UHppk54#< z^!cw3A<5upMb9B-b&|Nj>yBsNRySBK&~z4T+t1*|1gY$cK4iB5rVy$qTjSIQkid+2 zthXD!ivvv-%TZ{dKUAi4l-ofid3T4+L1pC<2fBM+f1I}iT)0u`q6;b}ERl$kHtLZF zA!gei4ZHIiq0haow>ya^;mbhdsctR<-3@-!{pZWDiZQ79z#s>Ce#xK#E>*U*WEgEf z+a#W$=*w)lKW$B9^UsenC0W6ZX`{|OJ!2XT-SY3anbx6E@ts&r$M5GkUjlda7{wW` zr6Mx_W30ccP?N5#IyY{`W3RznBuC!AJ^nCmLo}#Ux}q&<0P|M#3}{3Oy=Rl}4s5x) zKzy{5rH!;_;4e#q_XJC!#U!2fz=O8Ro!e$s7VukN%5+?fhj)eZP`KJ@fwX0Y9Stch zMaM3VdE#9M6crVBA;VD99lHF#k0cg;!e0%%`VX~-7nf^@m4(sT zrm#y!eY+E-X4W=j3WBQ3dnJTYzGo)(H-$V24(2ztEB&+g!c|GaE#uuqJI81A?FuRn zk1Ccl;xW&v%~-oN!3wL%XoN8u@sbVYC&l|df0J-Qsr+TTLvONTqr zF`*NPM633|@NoHNM-;^0qu0tg%lDh{t4ClcQcoqx_=+>c^G)m3klL9X$G3lpjFl1R zMnlCfGprV42l1J;M7?>9lxkDAH*E!{T}za-&rhU-6wG+pd4Io7e;HJ)Cw7Eg)_u>3 z%`^SqCHf#?-~aOHp z4?VZidYhd(!V!3vqQ)?Yu*?+(&tGm6&~%B2D<4C5)>z5eX5x8&8O4P0UI76(RLw#nPQMRN-l2&6uLDKd*}#3Nu8VTj>-1hKrdhMR-Qs~F1}Qp4tW2LS@3{7-BZ(!6RrEZh{&AjQCFj2dm+rqT(VbHec6$(!Q1$QuRNkW!!S_K@hlULAJs8 zC#XA^rLBzjTbb69wog*%nw4_kaF-n7O67%{TOwa5?9W9T2MwNSZ76cTA|9EM*1(aF zJg>0neAFJEG9TKi-fg!I*mYENZU&C;&?Bo6lkAdWMHXty!bF&+V}N}cTwEy@&nK23 z_LoJgfX|lNnwKX%ajLdZbsMsgqzWk3P*P$B6?jXj>p2)ow>;R?`2bnVw-%)VIBL7k zqvZoR;sqn&+&}j2XytogwnJ1nqyi^!2NhaWZ*bfT`R$Mg{IZj?|G;A9P+U8|jwCXG zqOohRc0~U5rSWxw?Mb7jPiV;5+ca@07C6&DWbP_Ruj0m+cFq$QnK7HSzPm1%kYt|!a*s(ze2EbeAKvLkM^^?ZC|4hcpOagje|!Dftns5bU1B5C&7bj<#@ z!pS7DQFkyVL?F><9Vp(nzSu`K1jlSpCpEp@VLpw|UBl_rE zi*OujHn4Z>ykC1A)r_Q%+eBo4voycX+1tgiZ6^;iSWcX|Xm#zZTPvfmM`HOwxM4$C zA+Mv!1E&mO#H!n713)8MU#>uTqDinIZAWXCOSViP3X3bO7c2U~WB1FrDaFACut=DS z8nUU!z-&GBcKK!9<9W_2CXe#eZx)?{*;yVM%`p*)voRrB-nr&T>?-4@Fgv>zygW?? zNYSH}N87bCNG0k(yZ+{d6ok%=(mU>I4OEn_->_ZGML|U+L98H6`}w)pz3BMDlx5WJ zU2%Cf+pSq~U<>|eRZR_IV0z0!Ma#rB5@1{f#C85~b=(F7VcJ=PL!7@(&2JtH^#RF< zWgS06+z_(od|T;mQ9h$i1OcR$z)dy_DBIwDeK>c;SnClRSvbyLy?~puY+X4eCEg)v zR3xC{T9?I%od4cbc+1UkFb=nyHrT8jNoly*^7sJ`K*mT-dwuZ5BnBpZM=HsvDD3h`n^X`nsWR`Y7PR4^OX-v0!&oa;jQ&C9!+(9mh%0zS>QP&NMK z;iacu&i{caD_LRzjuvS>vwQo zn8;YN^9zQqKZmM5FM&_%!jY6Sr<&rhpdyboV5h3mdQU-k=#^bfr_biEcXf`OFS(14 zUui$vAoinP*l~;8m~$@vYa(=fDkiR7$^cAfLPUD`#CF@l7l{quSRQjiWYON-XL^fp zV5n;ry^S*)fOGd5RL}Bd`VqK_4^_wQv+Jl21TEXP9W>Sen$|3#RunJaWilUxDevPk zLpz%{gm)C-2a%DNfSh{vuQA6%YirS1&ObO3!KyrEG~=eKfF0&A?2)1D?>4PKma0yV zc{sh7rWFbOy%#Isq2DVpUZB4}vn4C!k?<~%iA0$7_iOsle8|23>Nv?geuOZq9BCM7 zQ2GE3X?|SO8e9P~PubHS5B_WlxZG@D3v%zXlgs^=F^Z^hsl8}L8t@vJPvl}cR-f%L zr^nitVrPCZdV_ffGMi8C8P^eyQbbA{*TgAwFnFrbuQk%Gwa#Ji=hxZa*nj^I)6`J{WjSxD^WMUGv#m} z<}pLc>J1q3-WBV_%jXQCWsD1wP3zNo;vzOCXCoCL%BsEp>z0C>7s{uPY(?fQHPO%+S2xsJUK>CF#ofmTEh<*asgJCT*SK4)wAj`q}TG%N~a712MS6L5+H6H_6} z#SjN!wNzJ&cU$-zhMKh!4lm>V^F_k6Inv2&fO_M>WJ;@mo~qkhi|FSK=*XXu@TzEk zmv)2o9dYbesZuXx5{CEH7xN^yec??$*J3xkt$;_SOrqSwo-CybLfUz!ulB-F6oii& z^eT+nVB;WW%mobv6O4>`F{6LlOo75!O_#~l)Q``Abf^x{ao8i#`@VP$RJ)ngKjJcH?Zu<;cn76R0*LElKWYj$Pg6(ycRDP_6s=D*@*m5@Fm)_2xqVv=% zXm@%jXQT7td|DCHqp>Thd3J*!y8Ke2?S|sD!gRA}P}3;dM5i)LpCx^J)j> z;yoiI{x|^2bEI%ts%{zG9iI`m!&EeVc#Yum!whjaR|;ZtMjc*X0~$W>(+X=2M?Wq9 z)Pr35ZZIXS(~-eH&e!8FNR5GKv59Ce^sd^_@pPZ@F9v4HcInuM zv`>1;p-tlxKow;P3<R`QR$0LkfeF1om)J z{jE&)`&?KD1HT!~*`9=khH9GG=Q9n2_ueuZttBw6BS9CEF@>v4QoBnM(L|f+&$Tgn z-A8c877IDwnpl!&yx-BkmxNvDp_uRD#JqFr`RBAn~T65Rg4^Zd`-w1 zKFe_>Z|CJC^k+oNKM@zSZ9M~9-sG_bQNDCd=WgGVn&NSP9K*#mTveKHLn5qyTeY`a zaY2QuEufpv<#wJ1>X!yYg3!Q2%RFo4kMo>^Trh3R)9xG^rg3y~hfe*5x&t*R;Vv=C$Zzks zDd8qL9Jdtnz%`RDJgF)8uBh>mBlYO?{N@XMxt!-NxBq+{uUd+S%{*-6{o8FpnM=Z% zj1{YI{zDCACUzBp-Zte>)q@eQu_IrR-k7A|787rE@sG1hOTP;m@{AL!J2q&_VjP1L z?~kpz_z(5L!o=bJ<}WCj$%PDn7<@x(s7Yl!Y@4!uC;rGqUaXkDK)BZUic!QE(3xo$ z>}REc6)D(oS!4PwPJ}7$b)r}?6crcySs81=w@b}LaHWG(&Z&~aCyuK;55}&UFilgx zkzR=6SQub2%E zAvr*_jm7t_=lkO>aiT0l{C=PQ>*^tqcQ>yJ~@WC#NZ3*MtKTJ_1H6Kr%w*|f4_-^CAMo`a-TZ>zz57GW7Dv9 zWG@=TKIk;vdQA@f84%o1`JrY0%R~LUZN@(2W<&$; zO;u9UF+x@>&H~Ev6oq&vl{d?c@)1bb#4xmz4(S1usu5i0B ztv6)0Jima;Z5|m|q_Zuq5myLK|O>U}^{lLL^HMsgf{r%n50l|YAiWEcJpu*yqhQ457O*WW($S#qRPlDjXt zaB{f+yVu>si2oU*%s)|Rtb0I#+lhs8G%)M!L25?|gq3&QPqnfAV&k!aj2M?Z{D*pW z!Dgt6eFkY|ztJ~z%rQ9&w?8*PxqHVSA88dmp6Hyap4^0qso1X#0&f)j=2#lA!Ir@_ zGDy$N9gT*V5&wR;co4b8!+dMOA!9{B|AJl#U!J2#ud*(6`T^b8Tq7Vj{gvt3%m$9m2MGEieHGUtqCdS4RZFVW5^rN8~Tzh{H zf|Ys`AkiHJ=nuT7puc%fyd(`cKlj_@^XDy8g;^yg%YX&gM**;!D^j*=U}saekwq-L zSd2wvn|}t{v&X>6HPBgRS#)q6l47eM%=mWOjK3IQeLL)!_)VK8D}G#bJqdOLuzQb@ z@}c|o*Z@;3g0gg58YUXIP!!KfTx^L$Zit-}w#NwPz+C-f`p7`~m)nQrWt#twvg?k=^8Nnx zM3JB#KH#gOW%_NJbN>NJ>U1B$-i0*6)2OJU)%@ z>-YKV`8@8P`@XO1TxYz``<(NUz!uV&b$mvGHSb>sErT4i440K74t(7u!jUG374ut3 zq#QpZ`8aaUj*@eBgChv%Z032Sa4S(|Y8f{ye3)aqhEu0x(uhF+CW4WX*kva7UJ=z_ zQfc8qnioF7&%fqrMLGsE(66*G36VujRD(Cj#J*)4&UQwQhN>hh{7Dy`g&2bEaQ|De z;+g(oAndn$kYCnbqQ*XJi}rS3Atwd=%JpEyJHLd2TFHJRCgucuO3`=nuqmi#lI zA^aH~uJ(}Z{$-%S&O@D(-j@?>Wa%`nB0HR7xFduZ?(Sh<6D)L9>$;PC@yA2$?ycya zKm4yptpBL+{rn&U_kwZsZ{@m%NC~U!>4mMcpZyV}f0NKsV-oL}1QBL{5eA3F2vYWe zXZX~A;e2+zz3L=|ANp(u6P~YpM-9?qCst@gUwfggu0Bife*30x;G8Kpt-)A~|J-+U zS!9~vCZ+nvs*lJKUDr~z-Mi=KzkCd~lF|lih|#MgbJYX*f#ti17SwY;#ln>^gNmww z$A}`{)x7r3`tj!WQ$#YXc);4>G{c{77cd2av_Ikas7|Q6k^`Zb1s=Bo-vDYh{5MY* z<7VHzeJvhXh`5`xwjKgPC`YO8|0G&#Fj#L;EG`Z#>tlRI>q&UgTLGMQ+%S$CwQ;|F zm=czy8HtFRb3oa{Sjp5qIp2ey|VaNBPR&eMu@|Ft&PlBa^D;jhd^Va zFne9xH4>{~mhwXEcG>oLFmwK@)^wIbEpCzt83nb44I=N|6AvuCd~6ZNl!bfMI;RjW z0bSQjHy|A!(e3S&G#HC9t4)CET?IuPb?fKdVIoEHn+Q6k>r!TV>fR?TwR{U#W#Hzt z%w_KJNVQkf1r}BV>5zMUB{*x)Ykgl_G+<4BFcYq-+llfoP>gN_Uu{Vd)0)b^|f%Qzwnf} zG|Pvsx)`>#<}dx4;xhzTpOeYy;TJ1jK0c*G;f1dvM_Ft3{P=5?4g7Ie>+ExfdQJ}= zN7cqPedS)I!ljG;v2z{Uu@{0Nni{mSv|NIUvzePK)pZ9+Md)OL8RdcxVT=&>EA&|| zoTmlwYrbA6^yERS(`Q>J4G;)|=pIzTf4q*a`v-0}!8zEvDR^6?Gw|Irej#-438b@J zb~JgSGxU)?dv2+&v+|eDEQ9O=N93=X|NRVA!Ll^86kGX?9xHq}vdjT}VskqSr8#pK zI4i9@oYk$8h1{#EXVdO#LNI%RneHrLliJQH0tqLx#I6l9ANnUgYB|M`FpC#MrYQNq zUg}bEFk6A$yW7<}F>LI1lC#q2H$Oa+Q+UN9`8_#@(Vw3 z<)5PC&MdS8aMy7~`I#?B+hS;rI+xJOJyEYMl5ojJGVb$}dv9Fmr)UYh)k`$Jdo z)O+C*sJd+OE+*2gX|*5gLkv``YxxX%6~0(<3?m|30b#_AIU5!g^9Kfsj6Vs@@;0pq zqFpb#E`H)I_2hc@=a$&DkdAa$VJex!`_l`(1i}yeXyl=PL)`FO4E5kZAGiad^ec~4 zyhlHgIf*%#(%RC~;62zNe30OMDb{^iQngHFN^P{#Gw#e%JqbZD`OI|2AH4 zewg^alZYr9ERU5hk>O&YpuE7^69?e*qv;z~9YC(A**R~wUHY<=z8~lU_7OALZAwZa zdY_wrL^Ek$s9#yw4G9#`uOUb*;?8d^6{3Tm><4)SvU)zwmGX4E`qcV4X40KfcbX0$ ze0lqirrWuUyq9KzgJ{{ZEaH2Jo{P5B-8f#_og1%js6zxV(;9uBJOwfnQf{`LJE|l! zJ`DT5>SyFU%AXAn}AId1o8C*~;#rFfG7&fxe;GsQ5FMSTpUi7U!U(PJm zy9#vn-G@r|!pfw?_JKD2Ve6^%hHZ%RElc}bU9)|`+1m=R$p~CBB3x2O!cJqSwCRumpP zC-QD#;VSw;0V2I$0^z!2x#jgI=y;l5$jG_B?o8U3o3Y#53PVM2t1r$cnNOm#O9|g* zaIkGi3PEphdHMihMtJw7dix^6T^s1rCwSni@A{6srJ*J5=vvOI7$RWX&hep(M_v5F z1nL5IH=NtrYe6bj3BDxz#iMjSpmyQP;T+JPU#Uh0c5TY+4yh44D-${uy~@@h3=Upr z4!sJ_WYoi}9Bu>VnWH5 z{&Rdgqg`yO(L?JJ9BoHzBB#T1NmWF;vqOS_rWsS~l7t!Ww0U_p8*}>B<mpTH*Bu-zbM zKL+*?C-zkOs(mVnhddLR`r~WKV1X}RzR0_*7U1VUMVt_qLlIyLT+Q9P1gqktJZw_X z?29X|xsH*IM3VO#B-^%0KDmzNPk(!nII8~*5JtYa$OV&1x9a*x^u>^TN+xl02dU(@ zPvow-Kvw|(s%qVq^8}HZO~$+~Vcg2|A-AtB+dCqKw@nYX19OQDDfE}SPG=7dwAE@v z{Mcc2pLp5o+S+B!cX*Y~&qRx9#Wx{`>jA|O=jx1uN75EOc^?@82JVPzm^dZA?<^5L zk6U@|xV@*`t?LwFUr;iVy#M{#m+ytQv?+Viw-IMHZ#xxL#!n!VSHNdVQEXUzY(d}; zbE1AYfaEHxx~OulcQ7P$`94|nHPx}2Qp3IA!r`K|`<`DE;e*LL9d)!1(d|4qAukr` zq-B=v6#&^tjy|h1tnD$J)B5BuGmu&!_~lh3!ehE&@dz9$m$75rh-i*exx?ZtV+_1$ z{?)n#Bf`_y$&9(AlB9$eX^`fd)%9)a?{j_|;S!|g-)uensj>d(q&Np#u| zb=f;2gj+NdeM5UTS2{dmz5~LL8|V>B%eJIlt|e3eh>Em(SMxk#Ty?%(WBkxHNx+u{ zs%629}0Ot}N> zJq^0!BXZsT_wL;zv@&D#4f+1X8~M1UWs>W~0vEo+6r^|W+j#eUk3b#-K7S==nsw)v_N7oZljo=1SmQjw+ME=BCcJ{L(PyPnd@ypUbrZI3R9=a%-%K0HI0 zGvV)j5d+QUB#GW4#anh}fOGHz=k|?VUJHqSB!IdjL@0HxLR#jN!;>M4Q|N}BaFJ5o zAT3MaaoY{HDr8+sZkj9Uz8BU0^)fpZMp%*K9^~hdw1|PYDAMbVs0)%ugCqM2VUA1O zgE~YcAvu^zQ7b3?L!I!*V-~(4u)Ex%{U+QGy4Jp2fAxV;H@lsxfV_(*2;=VkUv_4n zBs?&9ZVTb<`IFQg!ScL^y1hA37W|yyu!G0exy+kyTbalUXsuU zZ<9nu^BABEb7$~oqy1Y)b>!e^@L`eeopN(!Cby~gM?@R8(^nky! z0OiT=2K3>QAl>$~+NJgHPNoc%Wc%J7v>v%HP~pDv%uMuCJahOe$(H4r;%2(YPT^*P zR1%6}FlOT9>MR(JrM=A+ou7eMPFo}~clkfw?hkkQ#dXbopoQ9Oef!cv&(Ay2JY-HV z4#=LkR6E8w2XpT4?<9~M!AjoRC5HBqJZe{8-3bXe-$!z;%8l&J?{}vDCyOe!V%Pz{ zC}Le~)rPYF1#l}-wR9=SYXxDtJ#1;kZ*(Zvpl-#FRM^GEA&*SJ46i z9>fLvX+QoYtB3LEO9L*ABFq6^6u>KfIG(bAtaThQmcSRL($wJ9O62TimJ*9htpiid zX=@E!@I9VgNfEXQRm1{2f)jZyGvsg;di6R-%N-eYihkEACMu9Y=isfQGyn@@DyfEm z8kv7-AIg|sA$_|pK5s8J(;^*@SipP=cXwe}wJU*(sET1=#-jMzHe`i%UK_{)1p?ok=7M~S0t<5|abqByk#7L{?GAfK zhl6q^hs=6I*IL7Jn_~-{#Rn&03!+m zX_AL6Wp|f+8Qm9)z#Nd22yCgodv~ad9*CucSD?&Mm`@hK9@5;UKd}>K6^vA*VV9y^ zQ}N_u_psH&5i{(XdmFET!U6!?IB+Ic4zry)vqP)o$}HW#CnvdzNOtnmjr38XC08sR zLL5%T;8m6h(WtAL>`MRQ=Hxket5M0UyGO96j{s>;z^6{uBI99u0IVz`q6?tjC$I$Zt2$ogF&IV$FS^ApesIt+^(FtQ$vFVLCUtw!0YYY-bt|hrq0$@ zBk8MA2^jleK~#j+nN7KFxvaw2mJo=5lv)Oir%jT`2ElH97gjt+-Lw9*LzBA@|7iF*(S$#u+| zxhv6R8?h31JbOEmUy&jbx53_qtMKF}t(`YY5g8G_F|##X_td%1^!rG{Y`Gd0fj2*D zeBzQ@6%`bWK%XIcoO13Job+_=)y7Z#&WrD}!q-ayHeXPTiaj@hN@44%9 z-L>N z(-5W2U-cbnGZo1rOL~ny5WmouUC#{zuY}Nv=&)ei#P^ z?3US=IePM)!Nep6P0(a(CT&1FB5=R%CX97#z55^arp>*2&%?u{MuC*b5%M-r`cu9F z_vF(gec#Hjpqr{)L!yM?RDD3rd1L<*glmQHHob3vu-C9%JKFl|V#J|pkP;5u6kW36 zuWR5VGl?t$)A%*QB7m}!JXc|{Ok{XY1Ue!SIBS083CaD%k0DC6h{z2tmIDDZLZg6~ zCfKnnz|q&B|JJ>~EcWoL7sK;;KWFp`dO?yACUtVtK;A_)JX6&qY*!0X7*$z=X1p?y zd#KQ3I~)d{up8L49}cz85);Vo?-=MSXhDe0p9n1gA5P0bM0k|X(Pe|ocFx6_ksH;O0!HMmF}pMI~ODgPn+6LqR7+xO6aM&?DCWr zjCar>d0ghZ9fYtZkX{$4Yp*ddDj6j0iz1deDITm-$DI#qGx;I^eQJbP@>5A|U;xAF zF=oo*oGi>RS9P)BM4Jb=psAa;L?a~6A+^cx84+S1%Hf5H?a5a?P;9s&qOY>yBbqc6 z9u;~+^HQi2VxO69zt4z;)&VgD+LJNLPm)0@o8(fM*aei1lucpgn1j^D3X2&p;9M@m zhLqizev?Zrk3vYFx)`?0Je%OUU%?>TqOShq<;h=x|EB2I|2mjVSl!(|4ckXow|^$e z;QYfSJ+^}RazOYR4y_ZZ3~vZgn?&cNQ-dstE#_*8-2s4;EQNZWnW~cCcL1Fhc~{$9 zmUI<6{|dq{!crZpCK*X6GVgZILUqUAIjOuM{9uJ`jJ zBV1Y#D>m+qd0TKpU0o3omb@9Gj%(rrGm`uRjj&v5zFvaiMw_bpVl4xZ_7Z{C|LF7a zuQmk^g>*mwAu`ka;aAIwv_^)R@{FEfSD!|@Gk)W#8J;zh)?jPB6l}{9m!UCMNY{Zx z4;U8KJ>wpd_P6jRr-;`wCn)HrcZ!9Zs%Ho@Li(w!|5mh_DQpu6lF3v!N%Ofvv6Ai- zX|zW$LLkO`bJ{#1?reo^ zBLnEspJ)-p)DLuFQk=4s(M^n8sY5{rBYApR(9lS^_i=crPto!{xv^!f8#sc3`t1Z7mi$9A`}i#_LRLz%49cxeO(q%JJ1Mp-dZh91k#4n~&>0j!y) z5(w|>o7)HWWs4(eVRlP5U8v;}8ge~FqMvDpR>eOA>^IPJ>L#u-vHgw3QOsRBpj4oz zJN*aJ;ig;*cel-av6ZZ!Z3P>~75QT5-kps{Nml?;Me@-{Hb1^aL`1~00lJj*PnhnO z2|W1^oAOJ{njsUef@2rFJ0>%`N5N(7d*{+Fz3Zqa&qd2Wk`e94uLP)LBmJB>{3cKb zkev_(0(^VE1W8(*B+eE33EVY!gkHF$wMg+xGEN5F6FNrtJ7YH)dz>O}{34H|*l1~Y zWYI9RPDBHdZ}MBPAm_?0aFpeiCh35@vk=Z`?o*q6at7&mVEvGDus?L2TlEH+<7@=h z$P`)Kk#i@Znl8o__OG|+fX;T^J@#DdeRA*)Mr7r~&ox(uH`jzW4>$gxu_#@lwI=nxJC!$KBw(62sqM5)zZ1)eHN%pQ=nk#*--kpTG` zHqfX+Vb)*c)?Py}yrpu^Xr(~MK^zft=mri7X61Pji`BQ_N36ks6*+UK!rj3yMjt%; zYhe-n{Ac@>>&6yz{9BVd{)UT08V;)>6wUjZq!u3~wHokD1b1Yc(0i`Cw{i51hd+#( z|B-dLxI6*0vy$np`}XAz)$bSr-R~rRk~9Qhk=sYQFARcR(W(M*cumPy`GV>Kdxv** zYa1Yd*2QN@qpxL(!PoR&1G*}y-Z;+QBxn2FW=bC7xG~OCdjY<-eRyc>=!2o3l)>fr z!%^r{gW4XFwK%veB+wM(G4%z`7M?!N8XiK5OjvaKNsCtXi3+jKNp{e=i+MRzD(8(AA zY;)9}8^e7N>F=O-#$-7(5_ji#S`^Hd}+I~1we0mgkJtgiF zF?cCI4c=UX&(?`I{!=+H&fs;C)1*4KI~JE^X1BXz?lI}V!|cD~Cr_IH(vx~X-zTvM zmv1FYF(&)x)Si}J1atRNYDzYokdLn;2KOfM7^GNfk|vavrRcvcicY4Lx7O&%j+3#m zb511SwK@v+vQqze zY`i(;!mM3s4tro%TAdRJF#T0^=$q<`@KyV_E6=v82Jt0x4R|680m#2tRC;9m-N!$e z3!?T6_Avo9ktg{hRtEsI9+|T+H_jM+9exrzX{Z)`vzM#EEFWtHm9@4Tu`J0 z7GjdgaT39R7`9d@exs98PItSL&4aUwn8W_m`v%eYZTGDw>Q7% z-Q<5{`<5%g+&ldt5EXc_1C72welm1sD`aqB}bBdH^bYdv?X51;`Im0LF} zJ6nVl(7S<$p_9sRb@Ug;WNB3K<^@1-j&d=NVdjRaR5TFhWwpa}xyb}{=E35No+!wt zo2qZh@Tt(mGA#!2hwQVoCj9flcR*r_sDmkDgzzH~xdYN#)-7JRkra<|D& z*Aa@dp4?;9DJOYgi?CXELLSEO{ zcR0(kxU!XJbQ!pc{3&2}_#!PRhs138ov9iK#FQ!Cy#)q@$K;6CtwfL2Hb@Wczj+@y z4x5!4{4n!Za|RE#5JnhUnaFnhs~Q27W{Ad|ZJ(5k3R!^YXpxEna9-qFKtc%?&9poW zlg@~O@TDjb;Xp=Co_?5r_-#iVhk{Mm|nD6pt+$Gd4{T2DuD@nTNTU&MYl7EoiXIil0 zBxvms8A~Wqy_i<*zPk#E(z%bkj-@f_hv|sI2GhL)hyHcvcck1{e{2tmrc*qoRMJ;e?3tysjmsDJ zN^)~NyEXC@Jy}@zOr)6a-rmN*S2wM!t&K?wq@6o=+E=1W{bRI1GV&HNO`iF$JI=WT z`G3HlesnYtP26Hw>VIRKj1Bk_1TnT*p$r3=oP_H(2>LWKnownCufnOWGG9hxn%C;L z0B1HrtBNy+N#7DN^dc(qD>RoGGyP**I3i{LZMs^n&Q)ehux%n4F1H?*04fQ^eecE{ zcV|eBBgML?t1^iQ;+fdl+u0z8%6px-1a94IWRHkI43{+T$FaJSoSgjTlknI(6eC7C(E6daF?Mhg6?6BoIH=NPmEXF~z~&h9UN5cAi@ zyu*JusE);1-70SVpElG9aWd%W4cd+-?5zDt?$aD13W#%f;BO?fT)Hrq!jL8xi79Ij zA3a(){VfK8YG=BqfFhGC$!jv_@6CXR?`gw>@-DOa5BJhM+6@IRLBYZuO3Dff6pW#z z=o)@5x*T}!+_J{TMxHvfNj8`#<+&cy0jgbtkI7*AkgTli`ok90S(&|AGg(+Bv5kz2 z8J!NnHSW_yKG;pe)ZinFN57^!DT8SwWKyf}x3{;n*JA#gW8|t+`?!2$SkZfY|1PeX zo|O25Ex-dhkb%G~gdOc468<(SV8U<$})#qpwojMK77~_ zBZ^VdI>{Cv>=pN9p|>%XKV!@Cdy8jsQ7{k#(|9D0#UhsU1;6y5p@&biXo1YnU;ayn zWe3cB4wGY`dHZ#&%a<=-{lLY`+sGQj{gNTzn>KB-5%-A3G$avLaIH1O{5R(e(H$5X zaBX}W7y9S~D2aOT6xmN4Ki;1GWR3Cv*gq>S7|+QT3l5^0vzv0{4%xg_?x#Xo$jZ8~ z2TU$rol&7)rKtVPNQ8yZ0+Q8wx}6^5o}Mc4I_`gc$iy&-pJS+g zidMoM85ftkjA7a32S-WVOqEhVK-+B6-SwVrMw zUGu8ds7y1g?=D_9ItmFCO!5)!)b2)OorDft@2x<;99rUN%bJ$EvN%3Fl_ z%h(_L1p>|0LxZW6E)}-=25x3%(I%#*n&S3|N|e95{JVww1WFZVk+v$^zQm~*c~TjE zdNM8t@!6HOSgXsIFBgMc8nY84KMEgzVBo4z#42Q!G*mLA?Ia**F|<+{W|KUkq8Ylg z7|1}C9!5-88|j^)v@k45=W?o4guJryxrBt(OjnEO|8j&!4mf~ZJJ*P1OUE=6R}Je# z<|~%;u5op(H&SfMwsWkr`FyU|VKx?nOn2xG67+A^inkdV!wEJ0$+s~- zUN1xTQ8({8uj!Wym;H|+HVkgNp@&kRh;fdt#RQ7oO!Q(4hC2x~Pi}#K@TE(uNMHI# zWpmM3{yq`VijS9OOzdXDAT3o?Bz|$I0S3_9l3Gn_kXohFkIYKZ$(Y>4#Kgq+y|p|g zR#r}K_uL}_Bda~O?&ChC?Zl&aNY0}jkawFAqL>Htv>wpt^g?ZndcYi_xYAFLPhd!k zB((MW+PviqJqm_U(JqL;29Kc_VISj+88dv|B+}7Q3}pCL2x92sqWyKV zUfr%n@RGYq=TQRAPeOLi*%cafm`&iiUOn#9AWEsWnV4KtWlzG7tZbX`I$m!BhKIH{ zR<0ML*@53zN~V1(=9pJyn%9s0Z6bGqYny)AUE9z{tT;N`(7;8u`Zd<2io)Uf0_qsE zO`X*h5Tcs)w0{sXdd%RVdZ}!&j}OQ)WHR6-n|JP0 zB-KOU+SkUn4o?5lb6lUv6LA1)0xw-!P?Pbb zV@!$u=~FYN>b-xN@u-sKk2j)yw2UyPCllkuHN~MX@9|VFnmv2_3-v|}BN#pZnC5`A zfZ;*Xi^*yIJJh9`hGqzUcBac*D~q8NM|!P9dNIF~k%=i*a_Um98uf`@%^jX^uRfmk z-;oAma_ln$i_$kULW5QhGg2}ClEtC4+mv5OXgirYrjr?laW`GC6LxI_dt4Y62(}|T zoQM4EjQqSj2ZpuYgPvmOfp0qr^Qr~P(w)ttdWCJ?sp;Icu?*cWG;4Ile-mD!;eXAa zetC0D&MCSwv58hWdVJ~D%e0v9VpRN;o}1c>C{!|qZFScfO}eZc^bO-7vw|?LZAUuj z^%c(mTP{WF=nnHyEo;Cx=P>zE>!Jpt(Eag-pXhJcVOssahYHE=>+pkWPZY1kgmP+nnz(hQ4-I);x|bWPxok zj7=As_y1mkVF9rrLn)%?KT4iC^9-1U&(L169*y7jes+Adh5dxqK2>@7gfL8EYa-K& z&V7nn?787(sf&*iTvHkW8`0b&-{sUo6G^H(XQa6%AzKEKF)%kd6iQePMHW(FN6^_rIGye0=Tnyw8 zeuz#o8F?0XjVg1H+&HuV9gr~#SvEHH=#e8-j3ktTi`u%>O~u!Tg$nRo6`}o?lFvj1 zpe5wXyZ#q0T!7=PX?XzJKBTVBq~c}h2^yP3W3xx(oi2ooUn#fO@*VjGKJ>DQaqkXz zvg*XultW8mAooTl%&CX#_mPcI@E( zWkL7&!wLspy!dR3?cMicJV#|N_#9|Cn)Cbcj}gI>QNw)Z87FPc&WwD6N7}(pRE;*0 zk5Q^t@09t{a&vPxADckY$H8kgbx=9xGl}#e&6Dh|TuMe@Ta=)V_`*8dizLi{>rdv2 zgO;v!k(6#m0dKz>z9DGyKizT$0k{eeQmSvUjcps%iHfEMBu*mdXFKc$0G@mDva)nW z@GVU75A-KD>}A-oI3PHf2ZM!Ntk!z=IFK49ZcMIwdsHXR3uz0@!TW7LZE1!3pwjfQ zpZ~)rE?^$1Q%Vmc>Ci~UN(LekNH=qH>=m?Lym&EaHA_HU*+RQL)FBokJESv~5OmNn z9(8qfp*;`j(uW571|G(xrM=r>3qH8_k%(@0*I+;eJx@5!j}9LHgNQ&N+R4s@XPQOP z?#v2@=67qzl+e!}wm^~2lA0rUWFs;<{~O_CodGvW4vOeg(G?U6k$KPage?N9_gm)a zO=<$6kuw+$#r=&DT*PG7?;3=4X|<;#o8V@`s07PAxyCg z6oYN*vj6H2uJh#BcD5$D*fV_&Qv?XjkNC*d?aT4w4D&?oE=eH8j=^~!TUIzp(QM(L zZgNloZ>44{>Ps_>2c8jpoFv;rFs>u@#VDr19 zq#CBPQPK234Q$oAz3HTGZFm$g{+Eu4sY&+F_ZoTaoCZ9&R~Eez?PWu=@(K!q{QRb^ z;OFO$*eff0m@&RQ|Q75iWHet*~xE6 znYc2N>O#h-y;n!C{vcAsb49b_=ipPCQ}ExIw#Ey}ph~pCkLH@5C=$wo98%U;X>4S4 z4TOU$ZTKa%wG+Lkr8Z?QNV^qf*7rg^oP9moA;vrep=|GU-r;GNsP+v4q1f%f_C->U zaE!RutWifbdF_X_YsjRvKc3cKio6wgL94#%RvMAuili6jI)CB93iz7SOXqQLtR!{< z=XP>3z3=864a(qLyY92}wM*1?Q<3481#Y=VJKZVj(dBRcOVJL<2Q{zi22rge90KKFs9yKVTqO8msw_TNHQ~tD4Ib^V1g^?!wSJz7ww_5)%YXr%6dAbdfim1#ht3mbKo zELoz&+Ku*my#p7uCs4wPfwtW9bcQgsP^$0w4(lP*`G*PE!Zz`|t3r{i%+l3OXm8}( zT%Da=Tz=2BO#quWG2M)fCaNFvNk%`-+=Zo?WG$`DO!FjCEac>1ny>=k#n)ooJUj}B z2yT3AO$z(?c#t?QoGvHC$~VfiEg+`wf{^LS*Nt>eDP1h=WPCa7kjP@!%n8b+Rfy&` z*sweQCM@GkbWRjP_z>B><1UM(aM+aIyfbCSqP_0NwH)o=-%EL%o4b4A#RCj<=OD+C z<#uelH&f9e@Z!p5GD7_IEM$=dF}>E|y~DHtgkt<#5WZ|mMAz>b96zge*Ooc8nk)^cs!UjI?o?1DRLcjAN!?H|?js4(gI z&!3+~LTH1eu$Y+kMNxbG_a7Qh%gDg^%=p}5>XGoQmPm4lexgdAA>XE``))~wzxSsItx!|rP&`Ze9A zxbp@;f#jK{bR9lSw@pzoD5LeB;y3eYw1;e*#>lCrSJ=Y+xSIVzKbDqylHzIY{Np%R zA=TRDU+YQADtW;Bq*a1F#W8_!Ns@zg`9`4x^Fzuo)q!e>6NIqsC~F(uICWJEJj|Z!c0PdYfBx z;z%${`{Tb`mO%m=Wp|%0qm7GQDWGu#!TUR|WlN+cqj&8dItg;+>xX`AGborHokhkp z@33~gqYYV`J!{s78M~h?_#ZEv0KD-1Y?d$@#VnJXUb(ynSHRA#aH#IcXS&qToi70?9 zX_N)?l?%+Fb0CYAxw71SaKYKxdD+sXS05^2A~!Ely*T6Zp9ie?rx}NvKwOG9qO}a; zA4x_<#s8K;c2@C)z@Q-Iys)D(kp!P92{YC6r$b4C*aa!Cd!Ol*UtX+wU<{|1Ov=Wo zU~(@4LX-dO+08mKEII~!`J%oFzi&6KFw{gq{05w>&x_E=$V7fM9i5fgLxUN_lhQ$3 zV4o^?Hr^$u{JKjrGbk%sv1ZMh4%BqbBcfMxNJfUy6C|PzOzwOJl%l~&4-6B3beGzu z0)lXe*P+Xsp}wzOzwSGDUm|OZtgJk8@vCPhkSXe8XW_q}s1xAmEQ*|8kVtbC+&r+4 z^O1Yz}BctbW)x-%_f+iGc{U9_IlZ!$A;Jxd>M!n`tjg;HtTCF>VpZ?Ac2=uGo|( zuh69O?<#)MjVJcXp7K2M2kE}G`f?Z24QUcRH)G=iiFH9CP-CLt!ofMk`Llyj>YCaYV7MkhQS5L6Fpo!j?-A5k@XH+&$6t zXoZ1$VRBj5Q>{rt}vz3@X$L2fGCoX?NTQ|%g#-q3|$Gd4qa(X|II%xTs| zVGdD>0^)AkHNeZ*GItq+2Q(W4ywRoN{DlXY5`0rK2q3w}!rgpQAt|s2`_alG-FIV( zh**s*;ZVt;L)B0oGODe!<@l1ToeKDgCTM@>9HW_jXbjTrxmI;SHumnZW5-GjcTC^- z@Ab_&fURpu<$XR5617?!5Ef>;sg<6dUO*1%DJo{dYdUIRQfv%F?s9%duu2+s^{CtG{M;DrtW$5YviBpQ| zLbJkcBz{elUU-wOD8d#%a{RY^WM(bVWyI#UWAPt->IZ%5Q>MT+&V-v%bYO$Cym<0F zJfB#}ZQ|e(U`n^v1d@<7$6;q$=Cy0GXk^I8aq<)pS#XvKRI(>Hnpz9~bFb5dOBIE5 z$wobx5y3?UaK~`9-n0xDK#vq5d-srOIxTeH?4~2wj1!he+A!TB(j|ET8QSfpNxbj- z?psy<<~a34z&9AGSZn4tru`>S*yvF&Y6`#Ylk%ag_={Thr8CVi!rNl_d1vBzz0jPo z19Q_um!Y$Sq8-Yp32 zgXkTak4hc>7yY1ehLYT`5K8qF2O3S3xz?`LfZ1EQ&ko5!D6i^ru5bTCP2{LTP4wk& zB?;y+V|OEyP(#QuMBdPF|7zy+REt-e09vf#+$=|DwY0|Hp%1vcDHtQ4jHbu6_9F={ z@8*`qn1>|(TTclXAWsP%p6GS2>)%Zvm9I&R$xWg9b4;S3-uDZcJ)gU&MJwTEnVjHD z1y$ACd-nwI>QI|E!Ud?(JN&HY&EsqTRQ5hT1|*R2wKWQ)mG~MJDr!(J6h)s4$e7Fk z4wS&+#fw`nQH&SYsO2pD&_(hM@Co+3Bz=aSfpuC?c%9mXSqh;;rx%EAN8Ox_%cO}K z_1UXR?CL$P1~LN?!5Ll#qeZ6?V}d=W0bfnVd$z7-2o{$IeAY( zc}IPLDcbIT%KqUvAi?iOj~08poo+=;OOUQ#wUP9fb^;+G)M3MA7ey11FW00)P{F$l zp#rOasc&4e)rKw+qk1md9Uj~3kx!w-Z1qlF1H@?LD-a*<`y8c$1j66f-FDkSh~wvxR7hUWWp8~GqZG@cFs2)~tX|EaU1l07|0(Y|oaA+C zNB~4shkFl!I%%VQ#{LMLgx!D>?KD`U z>lMfdi4L5GXXw2qh$G|tCbPd2M37(*V=k(B!1UJFHotT1xUNwb##t?*kz}1VVA#5` zvHP)@nZHO(rJbDXCnR2JA8Wi*0(Wo&7C%EH=nn0+aNVF2TDuk?Ola-TNOI+#^xvi=o6McdtJuI3W@1=MEzW+eJ)2{;j#SGx+t|7< z7fQwSo@!p75psvUa(7H&$8&?a&Nob^Z|=THtgTTIyXd{+;iHF92g2wY11dNEaQ(u& z*?n5@=i?T~YEMV>C3yBXNp$wE2$2+MaOLEdw$~RB6mZvm+ommeti!1;%Gx~dR$JBC zHqlki;)V9F*%Wp68tPgYhUBt#j;ohQstqRr8g8-&?$1eS}Ah#^gKjUts1$=v1FwEb49%I%#>VE^zE1Be z%*eAzEjpL8#p6&T>;#5K{=QN@UI31_US8I3${1=tFt4jJ%Bknw9%mKipc&2X{>ch9 z%g%h573fvxW77OA;PzTJUoF?tw`}H&Kvo7C}Cr3KEMePJ5y4UWM zTK3)O%Y`A)o2BwP>n!#R#u@O6W*zXgc;jNL6Eo2KauRpSe$kknyc?&UoN7{AbxO$l zO+&Q%{kxCfO&03*7YkJ5y&PCjLSL8{TAghw6~3M;hXS#@=v@;nL}p7m=oDGeQ1VV*DIJx^Qe)3!MGiz2W7C~jlI$Y2J+dvL$+ z)}H81;dg?C zSIhb%#sm{@Hove?H1|FF1QlObjj%ek(R`Q`Sa`VnyK;A))$0v%7W=x;%cPjDqUFGu z=S;r(f$Z#=Ho>JyrZe{Uma}uOTynG6$#r3+>B=kiRS}j_-91sK^9?ivm$!u&?BKet zB$3%a^vlSdd#ZikuMXd> z>-ZCCtuktp&Uh1}A@`;9wjdy7_%iBo#*NM1lsAm2)?9jr8cjbmz^pt&3wOPiE!ikF zOx)YJ-B}mSK}-;kyjgT;l9eFw4nWOtH34TDIS_9xw$yUqZe|ag(FpuhvVC>cmpxK# zuDRZAXQRA5%|Cs8_vCb5QTXNsFB|)q3+fCEBm|Y4M9)$6UY>an(-6{~!eLkXtTCcr zTow9sd0e2*Gv}Sku5MYUwGJ$q;kEjKXO`Yo7YL~<-*-u=Tk)EuA~jOqPp+7ryO+(5 zBqjj{i+T1GuIwuRM&ZrSdf(l9=osU_&pq8W5{Fl6jnCA%u#%7y#<~D>Yb)U=AZu#8 z(tFejh(?6t(4l62wJ?W1Ag?Cid75oRu20CeTo}t3(?t=ruUduCp%%T4z*Pf5D%jz% zVET=$oRh44b?Cz_^ro8(G>)5?e6t&^+qib>Iv$BBX+7O?S5&URwJBRvqjcpbofr3c zURb4NiW}dq7&xXYWt=7^8=F5QJXpAYQMLb!*rr^O3AZ=8$-Pid%LFYQeKU3~eiv^n zjHW`jpM0_5@S*`l$$9Hn@eyBhAk|cfR>hx2pwYd44e!{2B%f9?Sp=-vuwi#sTeTpE z+wE<@4#OGm@p5y^TUb~qAFY`?f9ek2N+~2BK}(C(-a_CLbc_BUMI#?Zgz??xWvZK#!!$JqocNS@Zt#ePb zO{-;v`;y8m5s%PmVN$m|1^9UTbsIfezININ7Rj>tU1-?b>i@8XBxwN89j`id`PPxc zhk>i#Jbdif&Wb~mz>?^u(CzgEkT+`G#=jk|kS5+`L)IE=TJMs9i;AwlEKa2f9&m0_ zc1E*Siqyn!?C$C5vEnS8*fl$W!w$)XOr>y%bk7cgNhYJ%@u{!&eYZQLi1d?N++e(B zO$vuZTo(lhMYNEIcBB_f#hXRKOO`yOD@P{9DINW!V!iI`&3NbP7J*GYY{L0sokod_ z>uI)_V!`@VVsY_Hm|Dy0*VDao@ zJNS6|x%XUVZ9DJixhvB?cWr&|nL_a>mpOLGJswczB?ac z0hAEFaiedH$lG~BCdYNrGaJ+5LQ34Gd5b4R-jMk;&~?GHqe-H7Uz5G2mfGoQr_b`K zq$}A;_i3Ft;TMx25&NM_^>u?{xyOuP&I;knG4qlXU%w2TTOqUL;n2|gsV?n=a}LRK_%8kCzW}W6|BCoH**}P+tw%!3`lfN)o6SOs zb2hqqk(QY2hu|D5B6@iJ9YZv>0g>K+wT!Uey}Ca=zF-SJ3jWTEczou2QFDWD;B;(L zQhG8qZz5xZx$hDXo|!QbsTyfKsWV_RJVRl;wS@M7c**KM48t@*SBi}bEnJWGO1CIcZij98z_2>?k)3n7M$PcdXCdMDugz~LKx35MlCPQChZ<}DAuGaL}MAhxv0~wP;GRX|or^fUZ z)S=!k<_mY*wUe5keh;kg^pN7?O_*(0>eJ5>A!+JwS$ZSvd1kHN^~3g_-3I%AbXwMX zA&XJ5)c^axvxGgHAU1*}V!S_hZ;(6k$(qgmmJgq^!WCgqp+0=LDMYh^3B@g-ke>4) z&Ij};v&#C=_=}+Ah;D5QAk6dgtNV}@Gkn+#o>a`&Yv?qqwa82wg)Q8R7hlHnf27L! zFFX?vpcXSk25DMTsqlKY!JcJ}MQtPlg>J@m4{4o70g;vWX z+Adp8sZYR8WVE2G0nhXJH)XK)Jcu%HXr9+IzfJ7|z;#ir&oo4j2gI1~tylVMY!ruj zw8DG7Z7Vxqcue0AHOab8ftvcso44B z#Y(^KSI<=IF3;dOe|p&yo@YCa*~KNQ{cana4Ph(1)!u75L*ShF8P-WXg$KS~x_|eZ zbaZu;m%y2?n_pjw|IjnI*}Y$rM^EV0440ED{=KhUHInevtCBt`jXRY-7yxqHKoBB# z?o-iKxf$RRyNaiR5||IS332w_etrP~6;jP{FIq-Y?1M{T+bxceBW2m3LFybU+xOJ{ zvOK`}dZY+Kdtn}hNyjqo^vJ$m z)*olj2Iu+u>Ia8}++VU(HCw@Ks7IyueA3XML1S^U^O3ogzSK@2JRxWmk`HyHyszt~z_%Ou z+Q5&NqdMj;8bt3pim3X>zKux&ksCYM*)n$=kO{r^w)pmI?c(L}XC6O!yiI>&xW#fW z^{2DT_B&i}+$nm~zrXEmS@D&Pol|-5bsUN1HZIlaywh{uExrBP<>=xcullb#RnvE$ zKRq;Xs=~DFDChHR5jF28D?;+~<5U8Ri?^5Em)1zW*XKWJ!!_q16``i5rFAz$ZlC$? zvF`j}4FA1?6mwnveOHa@zqwq$cv@4mGRx$>s8hpk*O0=#WS8sDw()x?yu7nuUQtZ; zH_O)*;)^8zr9jJ2PYi8O1cSuZAsr1L+IH*dvEdeZdG%zpCpTe}uket-Vi5di!%^HuKZ`U9W#tq_QD zo2ab0ou6g*v!D>wbssueLMOlG{9(8$>a^%KizQ4?pReVt4oZ@X_x{d9PW7WxpUV=D zNo@EyZ`+L^uB0pvjqqMi_aj+4nR>Bl*0FYJda)%2{r&ZcBG%SXovQaO4l>rEa_VQ-{ym7qbnOWa$9TQl8oKMV3#x)` zr`%OE*>z3W&wBawlnq;ok5(ESP*TzNZ%lG)nO$}<6D8M**VJ`41N_oI+O=TifX2&} z*~xaWDlgQYAiNsgl=PVkV1U;skua=)GL9WoXrH5J)i5FeV?>-btVaOZj6 zudluqi^rUsr*Y`}#8;lX@|SY;@1pycH!<@uZ08}jPHpjVR~c@p0a_IRvf1uNt8`Uu zO;_fOjGGJW_p3=a-}p(V*4qvAN*H5@`}t8d?it@42k!5;VX`yuuWyf7OYNS4o}7p< znZ-oV(5&X-Qeq3$OQu_|m0I>(S`)4Cz*M`>pN1L=JreFs4bKd^KsbX$st0 zYes6NAo7ZHqj7X{Kf(#$!bfBkh1~8EC5qyrEvxh{x&*#d{^n)gSbocQi2v|B8j{`b z;m5?~kq^4Glgv)AJ@UY4vW1f?8B?d!d`jXTr*?CKC@`q?8(o=o|F5vG42Wu7+lFya z5QPy0L`g{j0g-MjLQ=Y0O1eQ}Ktv=(LL^nXLAn(YMH&I6Ln%q={_eHU+2@?S-|v0T z{-H1%oHc7baX;66#q7+?z>bSfb-lC2th$@)0a!-K$;*dX`uX&6S4jvQ-ad@ewYzp# zMqWO~xl3#?ze}#KcpJ`N_r}W0%D%Q4S1i48KiQ4h2X5E>8;j5`*m+i_5nBm}@8^o1g((@3otiKCMdSK zy)}Jv5inbtWN&CqWkB16zfjl=l|6se~6~ac~-H00^saB^b0n@qGw#z|7wbkG<-9 zKwyQie;2JFO&dslAW96(s=cG0^@D%aOqHt0~ho24|wyhshyfv{7`yo`+m)xT| z6@>2&-cQbO|25WIs4`4PVw&@pn&)r*6aQ^IJvb9gq$!+BS5T1HDWp10PYb0-3gXjAFb%UD=dku>UCl>eY z3&vKKGGmLN?{07eQ(Itt1+*ddNM=v~c`3uW zue0~kR5E%Gn^w`CQxiuz-apYYw+ zru)lH0TZo)8Hh9f>Er~CJGp9`x+m5yhPe;$N`mu=aQw8$f-<=a7hx?e?ZZJoK%LaQ z7Xh%nceLGj{25unc#`bR9qP3Z@*F~j1!(C_l2hB2Sfaizc>L{ZU0mL94>wIODsvI$ zLZ!KR3@waGp0knLJ*SVsm6Mz7J7VD4L+1^LLNQ+hMd)~;H*6MR>nq}o@wM*}QSKgL zL3kA*Z>`3&lL>0K?MCnJmCZACEC@J{Kcf6U^^f=_xYD@p@0X+w(v0T+GHU!K@beAo zhtO{$?cuD@3tnGYeO;ZM{A8_S{k&;37cVY2c$|&>wObz9U{$`0kO5)H-)AeRec9OW zi4c>(q>LrpoA+5&+}b@oHICaYw=;Pf8e-!tDeoOy0yVXlt^}K7Ii79IAZwSzp>R>) zTtP1l`OLQ=35`~cK=p}*6Lqb2*Bl*5E?v5m&q1TT4G8$wr>a)sp$cQ&`JUIc z@YILVW0wY}?at9iLjdUi*nR#r_%X#Ob-WP;C|qijFPz8M!Xy6+b;y@1O=T3*XoyFc z9RZ3qE6@HlXleFfTp%W-j~=)&qB@?UOiV5FyFlW-?RSpLMh8#qDsXAGOTTbB>t=6) z(Mc>aQx3nL?47zXi#=X=(f3E6uc=(pY1C|9xiPt{Xnd?LGBV8F2P5_$b6rm1KA^L*SMLJfvGidjXrC)&w|;%;mAAH$>RI*KV+F5S%j zS9e*28wBj@ciT~D~#{xTK*wiQn3NWNW!IYCl?6RwaLYJ6B5r}sY5t-Pv?=>mCK zR1~IC{Trdvy*PVS+_Sha+~wh9)uGPKi$*C(Hpc(j-T*@rM>09Wvhuen6BvXGVVQO> z?;;TCPPM+)Hdj7P1!RzX-N5&7){wGldaX}5x7}PSaJGi___)-smL|iA*r$++ntEwN zSu9n&h|^~8?hYVrOjoYRg0F(k^F9sF_J6L#F~!;3^THLu!ynE6;Im*~5iV(5DXl)*=Sspy+@nH@dWG ztGUrDH$sg@uOpO9`2J@X2+W zNw7Fse+mbCC5`L1%fi>s9Ez#68*@@=0^IIHB6+=`B9VT5p%WVl5^k^n9h)m~p{{zL z5q_ERxE_HNkLH0lS`BTKjus>(HGG&nYx)R!CM1KL218+%D;18Ee=r!EY9xmr+h!;w z8uZq>a?Ous#`9(mH&GpQ`5mbu!og~YU^1Wj5HfHoodxB48A(`f8A-SgtRx4;T+JY^o6tO zZ@7{#LbFK>kbxY~-#i!WKaP*knWCRPqeqB(KzZNks7qi)^^+l)<%p#0H`GeCL&QTk%ofejib>g^ambJ6vE1({GoGm1Q{LP)b9Dhli9;9XCr3RwQh^eIk>$1!74r;G2wA5_=IDnS&xeRw*Zx?`$k9Xm z4;Wa=7k2%Ox5nV8Y#b|n&aTp5mZA|+cnuD>{?G?D+blf^2XZ7Z&kA%;hQHlc0?mK^ z@x3<7q#Ml%ES&hoqTJ)lsksmlRDuqYz(Qq5bg8-@%`l)q zSq1)C8x-bOAc*A|0IwhWvex%@U<1o5UC7XAmRC^N+B`#UrdOqE}?T^o~~)`GO(;jP*^pvHT zx8f$${2fGyqa+bepE;5CJ>=WS6Mke!`qNJU_IME@@nFRgFdE4@^(-HM2MNqDYP~#} zqLpDnj;_0T2`t2(LA|DFf-w7d?MA+l5vLZt@)v1dTDnyJoKr#Mi!9&~;)dED&rn83k<6T6+QjHeqQ@;Jy2_D|$35c>ziYmn4L4GiDLa1O6IGWz!FG+X* zd_fcbDeu_C=hZ5benoW?0fg;Opy14P#hZl|ktC=%SrL);+`7j_)X`wbr9N!8<8Ac3R$ZeGGoIug~Y&&*#N%K2{Pb};p6zru@tXtF;UO#1^qQ5^W-%78E!SZ}hhiOK)` z3<6C>L^}3){u)23pBzl>%E7E(>~$js=y_5n&t6m$zoQ=MXu)y;!W{E;D?5Ku0Rw~s zvf$mnM-t(C+?YUw8kAdr%*R1J^tMekX~%U95;DC^*kEbVMe{0i+YE3ZEO`a85k&0) z6M~7KUjs2TLEJjP&Qwc$5V+pyV9*%1Cjs%bJYZyS*Ju8bzd9E9d!HdOnYPadtTmwf zZM@li`Vi^ofXZOTbk9fMPcwsl!WQ?i;Q(;-Hh@ITfultNGUKZ{W!zoWMc_V#G<==p z%)2xoUH$hvm3vY0Xeb1(EmKRE%?N7TG&SQu0!7L_WkjKFDCz*2=qt8K#-_fpO zFvq^{SjJrnN=QBR9Or7-xq)!1@AmbC9uHO6+Ca++vzqCDgjMjP=pSrbUtjm69!cCu z%DaP#IBLi#dNp@@0Q$|hV<~hNsNaqG9s3|=G8^@YjrIeU?1G=}p!VF4AW~Z|j#Hm) z@1>Ek@hcF0CJvHsdUk>Y!C-pO{6U#~CJ7x1F`C*PpV-_auNM>tRU{;bp09=oOK5#& zw8eI&i0LBrDsb7NfSw$`J?XlN<7reJ=7j5`AjZPdTDP2SNW6Dgzv$|ADBNwr!;4;I zO)DZ?(Dx~~8e4^g-#p$9aOeL7Yo3+3FPxh1y12M_(xyBgcGOHzb;a|b($wTw-KV8} zumXbHx`W?eV#yV%4$;v7)_eggF83ZoDk{E$(hQ|2UU}2dFaJmNaZfj-H~h&As+Z>(89r8hYfhc`Em@ zn;zf$rNT!$bwy~=HP^|!a)+@AOn2xqjn^D~4_lQwU%}Tk*xH5oe9%uzgN~v-=#`FsP7O3XY=6V;eA&FQ-2u73YVP=Z49YgR_1QO0EP8GG=e{&R zAHs(iJfN=-?if#Xw)y!iARs{Q?f{{3#POS3uJUs>3Qf=jRDFJ))J&lNyRJ(-99p$6 zmBrO>+(-whGzj9@XhR&luc`=*Fd)_oJVChNvbX(vt>DoxwZfg7(TM&%qngC7^203_ zuG6c+RTL#cvBT({{mfxjN>+a~7z7YkLton*dYwd?85DE#<9wtfBq+t65E>)`wz3l3umq48w_ z*tfIaSaL0mW?zSL^3WPoIlStd9lt0!Q2VtT<51~uaG)m{r&ALlNkq?RM#vrz2W}hxzKps^?RU-F(Ii5`aDG2<9fv zlRb!~lmTte%KF|=8b55DVt1kmJ?JWWS>l##|<=Z-2Gh! z%DmW$7`!ZWB;&_=$d(;P{Pitetf58iw-x;?*1J?#$iq^^SL1CDI{Gi}^z# z*06rs>-+fO=CUzVon=b{O^*VkCH?HbUS=OEyS#Z;V8qCPX;|p zc!H1Kj<8FN8QtttY1t}mcr+ZTstbU>Co0_*1f!V&`ymQ`pB{pVKxS{8 zhI{2j7s_iUj|kKk3bZ!kEnt6UPOF?3fkY;SDE;wYOCg(|2iFvil`}NMZ2A@+dWG_W z1c#)1rE;%XnKpRub^6$QS$pGqiET?43%|0_?Avy>pP?+ zeNuZb<2Un@lkd}JHq@!TB)w*nvzPeGejs$o7lhh;mN|_l zFzF>9?ywN!&pDHwjfyQtdh?+FZx8a^^WgMuD2Nr~Wz6p{(Ja){9y@MhFXH7I>cgxC zH9_*9S&D@Xor)og6%cZQtSr^H;kB=IMiQnU&%ln6mSJ_W*LfN7{&E_8ItsjDe#2qj zuG8`d9?>pVL*LcRR{*cIP?|AuIZRfuFCPM|+7k{vw;JPZ`ekfEAXmeebb!V}-!kN6 z&Bo?3c&K!bsAPiJGE>v`{gM}jSbcM}!Ojo1keHk&9G!*F>R91X& zapG`z{OJDErV-%vy^hpp4 zeI<{Xl!nI67u(Mk&ca`?P}omgHcx9`U_d5f_6gIYn>ug%qzGj8{vQ4%PbNsZ*=u13 zHX&W`0gns?*Fe%ljjUh&dGWie@Gv(A1_sh9k`i$Pfxw?1td4p#!NK0$<(6l6Xp$=$TFT!rw$ zC}84Pi*0vPh=7XgDp06rf*28LSaSYWasmlI?)*FtgjA}=?YTDe@`nu4EZf2eF^ z(ZTW;K8NLr^Q_*y-qmoV>fXVLmx~ zv!2|@MNL%kW*r#ObJM#^N6wS7H2<0?AEP;0{Hh7scpZb-nHt`=8I8_+%p-O;sWQ#j zaeaJlhZ2C4w+-q_3(f<>iU-=^@0ZMoY|G2#GasWwBW&;~egvPhlbFO!t2{H{&>lk8 z+E!DbRdSk>*KXvxn7nk;XG1zuW zXLROOFikX+$wQV~@=V{*P~2#~3MdkJzl1dZiv+8IaG{EgeC#iQO#Jt$16_KDcheRl z@9rhtObrytO-hfohRDo3>!AB>YywuX4+?e^Z#EI3fbK}RR_3)3V!TzlYo+d9;JXKk zU|EnCE^^z>VA4_FzkmPfe$B~c?QL&N&;#CYdGvZLvaX}Y(Mjq(bh>yt_H6SnoPtGQRLdOsJUKtdS@oZp0b&*KUuH+5qJ zw{s5CRS1!8hUnzb265S*;4uUewilo_Bb#(4<%=5Xr=GI6(>}Js|EAwWZAjr}$gsX{ zh%FtKvuyGqE}raknP&Q(Eh-o2-) z+CgmzT`miA!9BVO4O}03gOxo#_hmg*sdD%YM0oL1q*t&8f4G3uh#Sp;Z>e0rsHhJ? zy|G|X$QHThx0Fm!rfzzvHB}>;H9TGBO7s+ua% zwq~}Qa-lcw^N^ccO5Wr78P`^m(Xi>)=(@M;&?(j@KD+4CxuTu7xw|~NKiakLy*;)K zfBB_Kzw^RdGJh$+Zfd}5+DRRbX(VRD{jelOT|Kfs%@Njps|hj~-o0cC?J ziQ&SE6r9NN{f>_~;{v4UEYVK_PuYH0)kJHJ{}A_=bVSl1U2N77>>)9pRs4xmQxO_D z8-O2Ds zLuka9CJVbdEs1WAIKww@v(*xurEh=0#bxrZ5=%P~A86;zWT$zcNA{xaX)5bA|I!-v znFuL58RTADm947(<6iq~10@7{I4x=+^6Kk|Wl1z4D?xH@1fOL$jyz@+57#_%3_(QB z=N{{qSw7SC8?4p4Bx7GS`S`^lBN5GYHli~)*i^rx@4#O$0XhhG3-irO8Rsfb8Lc|C z-?lk(~!K zP~L*#>R>^817bXo45SB*EJbS7kSX}~J3NLT;xY>Z1vX%1{I)HYz4a^qDXAtd^o^;< zAcd@@iz=lu!mN_wa^0#MQWpXF>)_S;X5frIU`uA`Nyv3VjK=suXSltu?0H4vS`!6+ z4C6$LGp;&*`cwb05=5h%3>r$iW@Sdg4ylcOI8+buQiR+G+xUuv>lQW5W%TneZ3;_B z6$RfV*8=}swcGFpm3DTSc^Ut%7`l$xziQOxb=fQv7Cy*#&zzN-vv=Up9Pa|jnJ@g6Lnp{E&8wo<_Z;HXI1T+1cKNBFj5vd zSZz+0kye)g41`mYKndk;>wiz3=?qGWPLfI#|IMRFCW7LI&tj98P?QJCtQU#TM}p^A zjgVZCLA{LHkHkx8>03q+sxkn`o*4J}w{dBeP#`%LHIkm1O=)9B?e6YoenXrMejNp! zarEX7ckG+FwQZ_P)yp{-=B8^?j zy?;QEm8*zJxdZ!T;VtfxApmrjSko3Hk}f%_<UEm}!Xs5eW(?W+ikJ9nK zr=cpw-ljv!7D|5pck2Jhzv3&!f7SO7)PF2-Heg@1<#fp zmn(&^aqDbjfYJmMn`N+JjCP8y%X@vjqB9`3jX3%RS^qQWSno(!K5b`YAY(42B> zA&jL~*H#_|F67hn(&a0r`%pFOPx-^)VusGPhKd*U;awoV$jd^x%@14vSqWS_bCu%Qr%_rpBuq zL1GG*?Udp;XT4=53C_Vzy|BS3=b{VL7_kl(HaltOxu5tw8kzVGv=&bvt`>z>iM3r= zn7jz(cRi5aG&1DK`iS!2>axs!+|1C4<>O&|tn@j^@;uP6ztwwJetE$5EP&af?dTO9 z2G%qZnfND~egZMi?j?Lu%ejeVK7;aQiYlCaUv${YCaK1l1kD<~EW7BS|L&$!p% zeDM~L!6DFHSR+Y%ZFl6%Wf@Z<<90dBiMky$NV|gzkC;qO&n3Ys)S}pbV=!D`%(5*` z2Xap|<#qs=mrM8T#7bU6c}23Y;SX|tgW@EJ>80Yil^_a(xzbaRvGWePMYwk^pi(f9 z0^xIGiOOs46|=FO;N4m0XHn}(=Pgm6JH-I(o?|mgf*pn*d_1c}+`GRCybjNg z`LG>AI+503O0M7)x}cw&SU`xX8-KwuJdfJ#oAGi=cjhb@dsOFgLi+GEb5~6x{Y$Yo z&6%ImKdus^^h!#!M!`A4Ree^i-Uw27GuVtC6&3|)#&*W#Tr_~CNX)r|%h}H7lFfRk zeE+4gcelw>>O6=&PKG{yD23x#%k>zS#e^ zYX*>f3I6*Y<{#eGUzQcgx$FR;LEjH{*A?CyG3jzx!Gpe?;x^5c)9d6-5BeQbHJ z&Xk#*p)(RO!##Fx+Cze5LVRmF+iV~!pQO^zrRTQYDYeU6U|U|DTuA>stsXQPifL)l zW^Ht;P~+Ts8L>-6FuWOMeT`S;nQuGAbW;+80{~x%@Q~YHpC@6QduV>p{k{)&_sJAO zFPk|=U{}GSB4(1dcJI<4M zCx-CJv1YS0z#DQUGa(ZCf$@ea^0J%n`$q)J`gs<&0xobV;ATU27W!|^9N+`=CDV%C z2z_JR8dkr?;gOtsO}7=^4*)JIQc}xvg{g)<$1)MtGPmbHUerP}GQn#3sxHV%?&4!Q zpFZ^@E6UL*cxjP-z%y$A#2#SdmuNM{V70Wr#&l2zN4)H!Y0Dzp zEx1=qPc@Ydx3{%8iU!}H^M&Pa+TtT+0!!20{h3xA;(*%|Wqpco4Sjc+UR&~L)xR5l zz?^oAn`F!Sdc6sU+>5!`bEmeSGA?;2Oh6IoLLgf{kn{ACoReBFtkDX|TO{;pJH^ph zYlXGl*;L|0L4p1$H{RfoFsj*|aF~?icNo`?%wnrX*^@|m!TIBh@BWeii(D1>I=@$p zuB$P~PDY%l^d})y;Ti!YlyuLU0I@TLzK=Uo_r|$3u-Ovop*)G(ND80paPe)Io4N$d z9}mA(E?>Lo%RkE2BQIX8Ym!g)w$^R#pe? zY4hpUNcZ>V9PR{@Pc~vvQw_RQVn*R|m1P-KODZ0yVa}Y^zt=+6zoht#p{n{#D7|^sMOK zD|UWM<%5e*t~gp6_#OVS3@LL@S`cCAh*C}jCI#u6`CKPF70byaKLKI`$4k%DznA5o zbwOyTK0tiSw3oL+apR{a`m^0G)GB$;r2qBsLJo-@s|M>aZ=@YWsIU~0oZ3b+gr`42 zJn@pV#UMH{JtSwrOfF1p;L5v~XTu-!)3pp!bZEw?eI~r=JcoCC=o2sQ^0a)U|8Zet zRsDw-;CS@ehnIC-0}j4RFpa{s3`7Pd5hJrD=&ZN}vpeUag(ve7SOP?tEZLeB60qYi zqy>40w3mHjG~S1VYgL1uCi^q1ELG?_%v$bZf;czgl%-Nu7_QQ`L5~gPVYNKP3D1rM zsmE=`SJ`*apkkbo!(ADv?(6u>r^#t`x-Jz+JIuHd{G?W@D!hF{ZCm?5zD+>A0U@Wc zl6J8X79fmIhl*HbyjvwBjH@8g)`1DGH(Oq^4kzTZgj0ak76VCS)LfzWahTazNAFU! zkVHSaY~BJmQk+6fz&UF+P+ZXpX(Y4gSw9zwXVqB{Gz;e5C2Ez{1NrmcFFSLz3o>7T zJ@1rh(rWL>h%h5gBCl06jL9o@9LQ-1TQs;@^Y#8JY8-P_`tA$vN#Ba~`|E_x`-Nl((>Sg^s5f=WGekP|1^qGRkP{le zUrxdp%Vjtg0eQjkYUcwbg$Y=<9Kpyr)>BsfWZz4R47u2Rla{B;TIz)n8i%AE#=_Fk zHW^QGwjFan-S?|~GJH3zgr~(aE05=aY?J{MG3hI)*aBK`d9aa|I)p}9jP*KfXvLT8 z>v|4Fqdi!xq%Cpa^L0!6yUAL;lilW^9Da^&o3~<`2zufU_z^#J-nL6#IemwF#MvJV zPDr2eQe!eyXci3rb&({UGcXa<@np{G6hg6&{) zlea_0LhmLZO~tUSk^w_sns%wm2*WCe<0!Hn*hp|7ahOCgUMYFCT42vEY=_wCaLBHlNrw!g?sNQ=S=FD#h6bq0lNTdZ*zRnTwQaSUEvT>VSP zNebxtQ@)*h4>?E3juzkWvs}S`fw~vyLvERD9!v;pxD)bWHTi0wEveGd@M=9IaNoIo ztxXptP3;=9zxB2D2$G6_S2*ef`Uj(9&a3>A=_O{%vCMxw!>w_TYSsb{2);Dbe*2HB z>ObwUzLAGgB-!D1XcAEme>}Gnm_V@6Sv7@pJdJ(N>!5vm^TmD<5wo`6dA%_tVsgcq z@~7LzbP9C%_Wx)p6Ps&AA*oN^0k0E`n)v9Iqa}H|@ObH?uAp+Q(>>n?Y`4930Z)Od z@Y`*f>AQQ-OjDqYLtp`D^0LolvUOM*Yi912&wQt6-@`4C7xYSH7x@Wmo2}u)wIEsE zqTRX%LdF!$+eEMhfV(?v%Y~?TIka@{hjK8?5lc`=1%F8}cG14qjj3b_ihSNDDY-HO zKIB#HKS?Uso0DgHbi&ko{eiMF3{0M8jjS)3LY0q}a#zz%D?%^NdHmfZ|GP|MnW{%! z_^i$^X0Ff^UNx9M{zcg{Qx_E*c5N@8z3TZ-bc~Sv%5v2FAx*B@8;{BZrl=g0hR@vv*d-#^ihj@nds+; zhfkhXZkQLnsn7F7j!$SHz*@rYU8oAtaTF|SVM;b4u%W({{Z_cI@0<$F_7_t@uUuc# zZC@G>l%0T#g>UOe>g8ByueFDK<5SWUy_d)Z(NoL9?m(5QQFu+yKt$7it<`1)pU!SO zg6V2ToFp%TCVc&!wb@QGG0gM!An>8( z)So<#S84Eus^Bl^j(wrh>xDjk8Oyp6uPU$htY-Xr`=`x$F|D(}KdG)mo(U|=FX9do7 zwgLU)u>iCS=-+H|eJC&K*dVhWA8p5eKby_y0-8rE4KTJsVFixNeI2sc8yW*ix|H8f z5mC)OT6~rdLyhygd1)fbbS?QW=O`IBA60e!hTWMhE`l5=a(TXFp09H6(mL(z@EO$q%b5$ zfi)Wx_(D>dN1Sh;X~S5p$cE2q@a6;FkVDq#x|-B-TwU!Fz#A-p@55G3FGA+q&5Smo zPxF{a5^~lX(Q$N8k5VhgEs$6+5SvebF2{G1N|d~m>Ujs$8y4$x_ch0(&sAP$=_>T5 zkN0k_H0O-;HSv)iNx2}<8GwVP!@KEo9?Qg#y0%8iFr!BjC zV`eLT)sg3~m-4^8DLMvcYRjL9%I@Z$7yZwllw2S{TCM|N4ed@JTU-e3l5e36hg-vO zsi`Zzl@NRfRh`bgPMCJ5X<7dM+kd+efBu`21a#oM-89Mn_lrwUK{R*emObx*?`!){ z#OQJT9N-wX0R6fF0Pzi=;P^7rC&SP0$ej4s{rTHf|Mh(_k_gl!XjygU?;n4jp&Oj% zfw7hVK-L!|x_Rq86tEQlRMr9+Y!NJXm4<{qEXgvYf>mS+FbIqVSs=P@gl>V&;F)aQ$J6oFy zu0>zKt2~8Q>0j?Zfxsc)HlqdF+X5gQB4AWkkyPM+zYU*U;WC^LiPDb${$rSDwo6V;ORzv@$cjR-*@BBSs_^n^P1)-(YJz)t!m%+Zohv|mOp-2NYMx$ z2!iG!((d=smP2JZK&a?o(=1#hxbk5s#VGw8WU3%`TE?lz5M=m`NO+E}tMKN{zkj?x z-|^og;(xyt7*fP6K2g{;_o`l1H|S#R$=KA2n~6l)YuuKsk=!bv5wmBynF!%KdUM1G zoa)c28`EA?<=<4NBCXE^-ra+(@pHQ9H6uzKd7OU1u# zl@l@{si-|_mhK|4BV}-VV}BRGRMTkm^)cKFQ~mEB6#pNMC82}I|Nij*Sda3NriV>% zTm)WJ6BM^rATr7jm6&;9`T*by0;5O=%D-RE{~W(Z@NbMZng&|@{X(MNz-OABYwEKd zKL;KK#eg2i{?2py+2;1+ne<+#A*6kxOCL4aU1yJH@_BXX@4x<^cL*y83q>U9h2a0W zuG~|=arDk5=o3eqFcbq_e7MfjIVTWK1eS0Ni7Yr5@!tm_4%&oy)zI%FcC}mu<%k3S O$=+7HRd~ZF;Qs+KXZODV literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/reeds_shepp_path/L_R90SL90_R.png b/docs/modules/path_planning/reeds_shepp_path/L_R90SL90_R.png new file mode 100644 index 0000000000000000000000000000000000000000..f2b38329da384dc354626ca26d0359b9bc64357f GIT binary patch literal 335979 zcmbrmcRba98$TW&N_>>E3ZWFqN-Ei>r6D7-XDMWF8HY|KMMfoL7iI6gHBf}?aqPVg zS;yvgy~&~O`~H5vkH_ziPxras&UwFI<9c1!^Lk#->-}6#<_aY_1Nn{}J1DPRy(GV5 z2SwJ79i%N}JK+lT^W94DKSWmYS1#;GtYR95|Fhfts;bqF9ryW>|A=zWin{IC!Mfwx zrSrEQXpOb+@@-RWmsqVfb>NG>4MU1vAvGESemb~o+2-qMe;(aFcMuVikWsOs{!br@*-1ajgfOTZr(CukZ+lC#?I)D1a!1=bcEo-> z`X6^N5XD&AT)f%KqkruG_y`6`RCd8_jmqnrLy#*b-Ycu(8ndPI{6CBm zrAgA(DMv4+yL){Wm<#)1guV=EB6XJtAYQUE{ki z{Eu5sspxcncICfU?mJZbLF!*-(R1$Z?o$s0uX7Nd?bAv88MlCTjwM_&IEt}(jLVxS zbex&!lwfwA?>4p}nv)bJsrY-#Tsh^K_nms;YM*I)`QZ+XD3waO!Oa_?qC({rb!$FH z@(R%3d=B5#&IWLfkbZ(H|m?kP%)BA(G$V)83>ueZyxZlt!Y%cy#% zyY|Y6a*HAH`0NX4=6ub69)N*@nBT)A6VQ7JRNhSxzI22qT3#R>!F_pHSbBc z8v%nVEaJ;gJXbc?%14{{&0`$Bwv&a^VqI9(XB=#hy04#K=|TPAmnPSX#fqwwGXA@r z{&XTOFE8)OXws^1uGUs$6n$WBJ=&PCK-?mM_WjNI=6Oa`K|>F?r8Xb>)0bG0 z6ssUM`V>3YZrAx>BqoZaEodq{UV8Hzgq_*=V0c(gUVi^X{&dw&qPf+Tr7KBV1%~_) zhqn!^UQuWIGtNe{amfZC^dqrFfN;BkVT< zsEiupzl&zJ8paK^=Ls@y-HRmfDlFaeE*`=xeDa8c$TOp2CGjYE5NsMIZp?5_VtO=g5eRCeDee9Fj?RDgc`;9CgwnY z)cyPS)4>?*OG98KitKSxhlA#@x|Cl(cOkXD~Dy zmx+C^7^fticQB6nkCj^``^GU)ts3L|pF`Mz*}0F()Qn2$_5RJD(4?Yly7B3A4ROj8 znep42Jf1Anjc1UF5!syc-$RhACa&=3 z^L|dvQTmYRpZDrnrn91X!`mKYKt|M!e=2u|WAhHE^AvC{XC_;jHn047Pnw6t+g!%&gVSk^_U;pv`33?U+RRYjgL0ffh+1d!cf-(?a+xalkhYnzsfpWczb4&df6 zW{)N7RR%s-!ez0ww`nOFH6?2P%OWnS1};xqD$tE^>m3*eIx5p7eYv`Qgq<&h;dY0m z93t2PVdlsOl=JRL9mm`hbcs8yB3(zO36{ILBlTXza%+I$mc^bHfc?_5?aCyaLODCQ zlFJx~*?RULJ6G?IQdL#8)m@tEuZRnlPcA5oth~6nC8+Rj*b~N%W^%#`kg~%H=0aJk3VsLe?R~I+DIfkyqS&CS^Cxeg>5Bm1AC_~-T_r}& z!d1r9b!c#01#bRGOpTFk^KpMH3Pe!2IVlC*E!F!KemrS9jzMQlrgS*2Z!`1o)Q9GI zgCvBF#xRhRWi?UVu-kGLf2@L>EOFgOX%GA90YxEo^31(pvaOjW>auZfpKh5ArW8!p z%-CX-urz%IV6q)7?2;gTM`0-ZZUO$go`nN|oTx&+fmk`dk+wPiycrA*p z;TVFq*SdJJeaoo-xI5|)DV#9cH2vyCOTV6;9ykR6#e@^@oFmMZh*+8jB1S!j4tjIG zn0#s~)9O4ng_GO9we?K0zLer!EKXDc`c?6kyTE{ro0ErrzPrdgAve73Tk*71rgIuw zyCHWGc8cNAungh6{Q1F<^Q6n_a)7Xn;hPABWHj8dCPlYQt;+Pkwo&B3feJO^c+X52 zYcM^Gb%9Nub=$YLje_PG60L3opX2xAQP1q~0<@N@;}|6qLVh%Foggi*sL(C<k$4F4D1X^UC7p$*4Nd*mRQjhi%q{zE!bv$F&$jBBy*Fdo#qP`3FiWS_{oua z#7s$#`IwqbG^gmE$9>n^bo21I`8Dv2VvJi?>gB+LJ=MwmBl^P)DrI!q&6oVtO%F~K z%xUSFf8NdU6%vTN7G@Ub`P;#;f-g-+ao8-gAE9C*j9hJnEl-5^H$OqyU!vLfSC|nx z2BxA=_U-_2!|r)f1)B@Z8&KEtFqr#+^2V*b-tZh#s_^0cB~pD9ud8)BOQFZH@f zEO+afnT$23yeyPo`b=L)B`dLFjkoK@SF+b{0r20e<)e&vDH{#^vu?l zZag=KJJ~cFU9^JtaHXIxrm*OEgw*y238~XIM8cz7sG$S`ctgE z!1-)m`EB{pL8$&9EWmVZ_QF6=+O;~$F}5pS@wOPjPA7rHqSeLtPRuUm17N9MZp;qH zm$V>j5=XKoA3GX?Y$Par%>^h#OrlwNTQJI?^uu3CD zaH?;+U^q_aj-4S~>hpz7lR4yeXX})#j~>HB6Mdph+CPbn)_dD}XiLM3dkKSWJaUtM!~u(mR%`>X2{WbbXuJI1z<^9~F-QMaw^&dr@5 zB0fU{BRCu|{`UydsF4wzZv)T7Z`zjqqffnaQE4o9G?7+3PC2RS^Te@Z$7=HICbCCj z<4!PBo0{3mvN3KZf}2Mn5D6&)qSoq!KST$?mGf{AczZ?y(Fx%f{vi^CV)_Zpr{pxh-o@vc+(If6tXzGzaI0Xzlvcf(8 zB#RREdKKu3!OpkavWJcRFwj7ZwxXh<_cI0G3n8lkBqh?YsyvfYLZ^P0^y5!Q@*;YA z`Z8qMHFK?Fj%#EWSXBQsgmsGEi-8pCYpi12d-M{1mOn&jn;{wO1ixI_G+CpuYh9bO6*}O$xnJg!N*;7$CP#Hu&80O*}`D>|4WP(XQ)PBI> zv^imz-Ru!?eta(wNA-KIGRT;Q z({XPIwz%;j+7n4?FMH6H2n_~P-@A7&r9nx(q~Bk=P^)VtuXDxJY3g;DhS~jYd~5I% zei*+217>D1^brp5Z3X$&uy6c#zxfQ+$0*d%+*RDNDUvB5=)}ytuD>HpIS0lR%Ej?+ z&$e$NtH!EK8cUHCm1~we{BeH5Wi800JJ2ZcIYJ&yj^|BC4pxQqK4moh_Q+@SEJQak z6B_`zI%o`yao9PFJHEcY@pC97mj!Yx*B0mg2amyspu#>@pVtVA_kI0_(|u#s&)_om z-yxaISWU<3GcKuc(Xj17uV>38Hzv!gwpNbz_V!K-71~}AUc!ct5o9q6!}eK1k|`uN zNxggRO-ZI%r+6mBwYJV@Q2j*I+d6|RX$V~RlV~Ad6r<~uqu+NW>8->lXHMrahAbYHfi>Y+g@(~ zoQyM4%zdb0Fzgn&k7eu>`hmp8d!5#!Aw4_{Ood`jQe%$k}nP%Zq_=!%amp7h71VSBC?Ps zBvWz$Fbr4wM1*48W}+ly^kq*wtBi2SEzWV+qPO5p4j&h$P7M}c7j_G5k4+07ZDw2+PMPvP8#uQ&gOjABGpXQV!cA99Wp`qH29*1C=k)33HO>6l8e z)lLo0m93{Z0fZTk**wC3nQNt{PHXyoezT7J69?TrJkl7k*bJklwzp$pTa*4Txg{iY z+Y$Mun}&z}3?}_38^&xkSe5V!Nf{^^>Amu7pE%)u_~O$`;3a|tUKVUa_;OcZi-d_82&4bG3>Yz}^DUNt z`^FFk8<>a6O%Q8u)l!uDg#Yw-*A*a$f<#`g{QtRSS}~viT__$f9s^>)v_1EX{t?IR zGY^F!jqa{J{d@5+i*(1mpS@oUt#|ql7yifo1Je*7Xr^@o_=Si!dzj9hbeI`>xl82c z5ttgo#p0r=vrkjcAX5uZh7F@wa>8w)b0P#P?`ZJ-uN#K=O0$AlC2sZ1`101pxe1m6 zhuQM)x!ZYKlrv)MgE?EdWcY4)N)T0N?SH@L&uC)crk^8RCQw;T>RH-F&NW$PostP9 zch-LqZb91iwKKaz33!#_D_{+wySMK2KUfD$KCMc&`E5D_umgQ0H8GoeXO7qll4U$} zoaiXfjZ4Uk#YReQ+d)+LI{Km5vaA1vemclrFbeXHgF6m5dHX{C3LeX^Tl&Ji6|zAV ztXUBn;SQfdTJ5jpaKB?rYCX=$*=Jp&C{#uOrXH@*%L4t9?2RT;z!an@vzX=ZSe`QDNHPhjKsOl8E)&#gCQ;WIuzj9z??djprIov+Id-I5)tbpn; zlZi4(0>}Ck$(;KoIb*kMS?(e6uq{3VClI!9!x$3OhH=Zuo|4Js>FTnjiK4Jsv6-J2 zbs-^c@Tyyg|{Lmg%PVk)ltN2V^2FC?-kFk znw1VZ%M8@b*LC);tqlB zM_7jqaS#mucLxzn4P?eYJ+{`Dordbl=waU`x6s&aAuLelHy zS4xhP5KOO{$;7thS`Y8X8mCFq(9)i1>(SeusT51X{)(-;*7aaCaud=J@-_c!_Mb1NIV;zfk&-)E=hGvE zko5JB>YTU&MROtWFGrd?ipM{03mH1S$m|dOJ$rkBFA|$tfd3$9F~R#E;4+%-M1|Ov z8w$gAN8GFMo0adB;wzvr%b%1)FxO<8Rdqu}@OsLCc}l-o2^O{$hqR z@ciayh(p^+nDPH~Xi+4!2_q4bp6-d7d8OTMELvt6(r-^4gRJH)Qd9g9B9hfHaAv)l zd^#TmYzHuYGRXzqF$vqS59$mu?<0TD`@hXKd%8-bw_ZWklUFnM>%J>YH_b9WsJn!r z@hyl``|(yFYV&d1jxrqfX~boU>zhOo9x{tmC}e#;67s0ujw|p|SEXR*3t31~TUyHw z*=YbNk*hUwK+seJI7)GRi+4yE`4#38gRKMc#CtwcH?6ZTv|?(CB|MH zp%0D}&X@2t-WPw2#IbPvwwhMJrQ!m7s3gH30;bJ|NqUZ&oZ0l77-A|=dOW{cB1Ey{hJxC<0xG2=W9~C+Yqa00VI@OuY%5MtrTCvtj12{-l%pG`Q#OZYx^MO zZ+i0OL&tVw&uu>9|GCf=evl&AqV%9e1y9ypVkEE|12vja`(SZ6N*Ay_LPf5-iGd)q z#0JrwNNoq64K#b2&JqYsVuPczv(G)<%fbv4brSZ%pE!pI42_Yhsh(g~uAE@Y0fUCh zge&VG!i9Eg0Q)#up}l&Fj#uLVK#B6q!ZK#Zug~_e8GijW-|Jll2rG?W-8AQ3q&j8} zzz-0oB8I2EtJZBm5Xr<(-MIrc_Gzm z@Ia1V!U5!)Xj?-k{BF|U-hzJDG&)>~SV+N9-?=*F~PUDM*S=OF)vks^af zB|@craB+8x_oe}}4uVNrjbEj?wDqm^zZrilPRQzDP}a0jygUJiS8gD|8pXBF^eV{&`H{9LgrkSoR^XTljBFBVd;w#QbYWfcV`wp?PbUl z-Ku3$8Jq@SBN>rNwdv7N?+`|}{95a-%_|!lVIWRCymJ=nWZC69j`E1B((U{9vV{`o zEwTCl5jHIaf~Dg1b3Y+gs(RHDEU2mwao7L;0wChfXqtVyAbdGjFdGrdY!Qja`;6}#vt20sOmd4U_D+AB8kb@eFBh1MX@oBTE4!M&n?p%q_KrN&EBg?c{ ztbH-m)O?~bLA@Yee?OSmX=Tho0llxmLRM#US7?mq)PfkRy=b(wg-tcM(W?t8%RdBC z9Pndmw2gziB%U#|U1>CoKfmR>ra-44)+uwNfN)8g7fNk?SHgGvX}>5P0g_ON{Rhq% z-ilwGS86W*gimr=8CCsNAdY=4D}E5tx)>FK$^z5kmFNgBcR(ap{CPD;tW>SQXsw8?KJp1dxj2`Y}Cq zj;zlEJX~S0uP`C$vP6hceXk3L3FF@Q0Kk%6Hk2u=%~C2KYJ!s;juR&4x{l;;!yLzR zD0}9rT~-Bn3+H=OQtn(XS%xyevk==>P6Q(iOLo`Eh)B<;o}ZBh`u{LR-(qNa>g%snK zRO1jxE_rwUd%&l?Csd7G=c9VRG#k!_Q`>n5`3>eggUDQ>v{s61{}s`oRB@Y z`&N>;VY5f>fZ{7N)BxJ7y5aRrdcs0iA*9M!&2a(?wlTreMi_u! z5)_$`35i&#FdA!noB~5U*ZV?%q2YM@fwgaJ-j`x|GRldNoKl}?&bl{weIXdhfiXP^ zHkE%faAxPbnVm-xx=FA5^Ll>2!g451uhKBNL=Ezse-iU}g+V|`nfdfN!AQyaa=~sB z!+aJArfew#c01^GY1 z%!hwk7T^3cj_85u%vnGm@VZ|ACbER7D2IsJug|G1tM{ktfHmZuDHq zm{H<=A5!(%aUgv=oZSvF+;!d(w5v?u3~b%Kp6MN2h1~-WSxyt zmd!~04>nS)a-zmTkQcSg<&7^6BPG7T`V$QS#N%~QvPsbhFO2A3(P0;Y016o+l_zPn zsFI*}sKx5Y=!4@}zv=7Yu@4<#Q_v%qsY81DbiFVg*)=pwh8fVC|zWQ=193eeq*LpunrNF_a#1j`b|CQqogkRdMh(Y4p zx$jnxs^zuU?DzU3#UPPjq&))+1JwHH-45BR@cPCfCCNTt6nS>_TLF$mJT6GV=1ke0 z4zZOP6^IETSsl)0hk)i*pB+&g%(=0Z8ivau=|ulg93h{go@x5C^sn?K>@6HBreG-35_!nQqFs{ZfL0eD!;z5O?LGAH|>u2qA&g$ z%oa!{;Y!^tE(&u2O1^yQ)EO)=;q@R3YI8^e&F@fbhTM(IM8rW<8#+kPy*M>;f$kV3 znjsS+Tmnfnb5yY9^>ipZ=^tu}SEcS;sIu$nTwArf>v77=!rl*Yj`<^v#TTGig)up zf6Y{Eo2>XkUo(2H-3rY$g231il3ETmL{I?{Up319U(<7#ey9X5?_zmDs$14*|B_dG zQGTXqAW*nkmw0p8AatC7oFtOyMMY$(4qsr9*pGhjMb@mUBfqd2n&`9d$Ux$#;B!nt-6%ter( z>IRu)eitdDF_(Z)aA&ITdkUZcDCF{_nmdARa^WqW9V*rQ9iTzxwW1e}#V;_1Pd1B9{mqoM z)uq8%W?EUGp)=NN1X-QVjs-ePt!1F9$J?jQf9C)d<##DQMfIz0nzqk*cd;;~C1&4w zjdlz+zc3@TG-f!sK@9&sNn}vO+h!pDi`@?)VRjgLhp6{Y3|tjl_Ve@8>$DqfX%{8Kt?T7 zaRyM17+=1RcmwG&B+ z!6MxDicbUqsv@g&2+s2qduF` z7C|P57&NJ+&z9Wr=L5Lnsc*8qnFGcE^+xB_>98_Jv;3RqlTDKgH1lj#*Oi#0*Jhe^ zy-UF0=iCcGOrHB`9_Fdct(tmN2K+{L-z%y2(b3VYb7liA&+f5wM1cuBE!l{mF8 z6uwCs2U*1DbwE8%G&iD_1%e7wBeS&GMnzln+)SPBaJB`l_pI1lTXRo#Z){LwFTr<^ zkljLbnZ8?D+y7FL)?W?J&lly*9eNM;ybIw~-2r@+fga>YyBZ)|iH|xa=T zX=+)~ecoIoZ5xVGqd1cbi^<;=3!@ylwKU* zzmQz;60`toQ~uobg1nkl`^j&}t!?AlDSr18>33(t441kVoJeLq&SVx%2sYr3t$ zh^iUt@a<_^6>tZU(Zg=Huy!VHEdT;=neAtDotZ2< z$1uVKI0u#r`pNO{+k*Z7kc>7PV}i^Ig_s@3QXt6fO--t=l^!4V!-tAF>UFvxS|Z|c zIH5seX5uy)NZHUB0+oZ3ZEnH})MaEZLr&1Dkc~FMLVUUd<*kME%NfWpP;3BrtP?Fy;YfrM&$es9A^%19%s}$q#cR!J5!ZtZAKo;d-`U=74X?wP_&%0t4Z^FAS`TKbmF3U8j%!W4J& zD(IQ+QYTSnCKbFBM@v8<#Ir+10{l;Qk2}{{vce{_H+o17cz^;*+dNA%&u12WJAxz5 zU{LnIWvQNl&m>q%f1GG^bV*|eDY;y-x zNzbj!)TOO>Gm8m>{zj?a84+4bEY^4<2f`lr4jQ_qv{?&;?vIxVx<<*iA2@5Qg1<(i z_GLG>!}4T+#V67hVw`RB;mie`nZ%;YAoTjJ1Y5oDd!u|-CBHorD~Y&W-d#*T&0XKF z3r8()g^Lz^ID5rNfeyAKFblGsX>pf40;v=YMP^5ypZ{+8!y97tPn{_B8OS$HqQ(Z5ma=@@kXS>g2KZf!0h>X zac?EF3v~3PJzN6mXWB$Xd3h>hTSY~k$>V+MCK-x!<{$%bT%l_rOM_-T^dy9otUDj9 z(<~5}Gy(Es&~V-P`fT>ZwNEt^yxFXN+^X{TTvwLnyu+6JI9@)QM2wz6K?gt9!Ve0D z6aK~k2FAe1Jym7W)QqgY;KU@oemuhQWHrB6U1;8tykeZ7mQ?NkT7IiLs|qN~!5=q| zZ>d4o4^m%3F+xHCT(6THl^DlN(v>#zA zL6@BKz61I^hbK6j3qhTroD)XFEVi~h%_VxmZUiU_4fJe-Jvsv2!4!F6H`Od=RZ_o~rbKTldmGQp5kdn%Eip9iK8a11w;x%77LQ5YrOs>OlNN zR|jZ&cg7VJvOD*^ywX!buN@y?+OC5DSipTYf=n*IKJ8L1Mz1a}DEc)ZVpE_#r%(LS z)-DthkzGv2ybn&0xlLlo^P56)c+cAH3LG|q)@P4A_jvgaKAY+X#ANbvFYW7=FKmzP4L2?1ZB@>xlAj-d4 zyRB_(-F&03cL8(jZIqa!7x4*yaj)2ENl%81Yxy*xHw3ez7#}IbF`0MX@!&bqzFgQ) zCfG92bL|D_pJPrzVmv zT_pPvB*+JmK&ihTO!&71^CEXU_aL`s`ffocj)Bj{fQjS5T0W{TF9iY7tyaEm*~G+AurS9+a{ zho)V7hU78GwU6h0LhBZBjKJB2lL|KLInaQ(xrW`5vR>=GIqkJUHnpC(N4N&g#^uS> zSFawd4N7=>g{@j!cbF9!Kk|fDzUdavEyRWj=LB~WB;VOea30W~CiviuukTl+R5TA_ z{-T}PxA3L!ND=XCR+ia56Zm9Sfs&+k( zD0rU%@qJ53+&;4N@a#lqk|K$R&iESf`$8lbF5w!pC6YvkN>i%1;~q7@e(mj zU;VH)=aMpH=HhV=&`$hY2?_bG{A}GagN8Ky^tC>Yhzg=zm)vC0hG}^1+y@ri%hO?O zl{s)ij%y~fmMbTD_3SzHUJ+DVw+BNau-$G~u-#v{2BZYDlK>pG0xyLZfb;OakxYtnuT+Mgx@|2M5Dg z?str+m5I&0SXI`f<;k^fF=)CBuzy0+R+Y}H^Dfs3cPL;;hNV?|&CjpBHG+NiYtOy+ z1&*5tB3Cn-y((AXYy)0|b z5I%u+RC!OPHa2MsxNVOpedJi>NW#50^Tg+oa$o>ShP z^$mJKCU=4yCp>#HO$1q0ffdYmEIqjI-n|xGlbw5BR4w7?6EfRQxvOQk*Dg$_VcQgn zG7_4y3TX=p7b?9ArF-2y(u&Bl20shPP!ik&$q3YqwCpYl5R&fGFN=Y-U_;-vGaP2Q zx->i5bo>o4wd84+H+i{@AEP=bkXFC-s!WdMy*G~6%vy_v-g~^C@0HWiJev>ND(3o&p{e^^7dzk zx{u*&-p(@-2gIEopn3Iq0rb5@-ZGKe)EaAQEc@@{os{n5?RkSQzP*^P@~{?wDxu@d zvrk0}(&^)!E(MEF52jOqf+Vyf9{~wws`pxvqGC3>eL-z@{E&L5tvcP+q&B~zS*84? zN;ApfSI1f|ig`(hF9usx?Ob6;uZ*Vj0K5vbo1cl&9R-PiyINL9c&FQ3CresVq41JD z`S-mpJ%gT5b;sk<>m~J|{a3>bwVpit9g&t~cjgHjPsUnpns*kKJQE?(_b%Qx-*-YhJyy+wH6i>_SgiBJ-1Ln_+= z4~E{+qIa$=HmS0rbxl42b>rx-9V!-V`hsP$?{!NU^tphj2Wj=uId9v$q@=8M@R0ay zOl%YvyaQkti-v{n@XOxs(Vc?|N#Ql;8#u_iS+wLH8T37XjjnUd8%d~rWcZSd2(CVS^evpBO+ z5)jU2LV@yfP&OGmX(c`MK9(?_aKjElO*As8z7=E|7nz+Oyk6qb&N=ZWPBH`e)Jn@ea2aRdcnFI`BWk@WqLm?~5>mt(3vN8KJ z`yK#Q+T+-{q;)pZtg~=(1%8c)0=U1fLXEQ&q&}(^0?lBqEW?@Uf$2!{zEsv#Zi47E zu2g+2c0#+{wUr*J^WR#^b>I9Aje!7#1ZWENDD|(5u^$*K>LyNu{4xVU25sKLBhgpQ zy3C^SP)H~RFs06q?$=pD^jGs!lBRo2p9R*M;6b=(@GPeC+C!88l}e_u>J8uv09^il zmx!fI&to{31J27L<6e0zh<5(< z*lo ztLd47{+7)NL6RMsb|vEE<|WJsNo`pXw5z4vymgCanB@|{^}xA!hxS)#!S?i;Q%C?jye$B3Y{)eolVWsZyy_&xrgKXqxlc_$eE6VRyw22= z$U{JYPDu9&?{huR5C}0^;A<_l2>D%z<{lq4$Q+s|rdce%9iDuXad0;^F(jV~3U(5Y6^bK+&!T>QV zJzrjRy5WI2&y3Ir$;%THPWlCIuGl!SJ=@5ZJ|tP!VtRdqkbxL-B}4T9Y5PPJ-xeSQ zD}%PIv=#+vV1H_r`)$E0ujIyD$wsGf+H8BN!1@_JlG@1u1);*5Jo3dWaP$&Y(kzQt zprOnI-nSChVR)VBCylW-)aK6W_rvQd62vs+ec}>0tBx!4)L%wq_lOiUQnn~Mb`~fQ z#YKsJXL-mahfjq)|4TMYe z7rGz?{%*>-1WIh0;j{SM%$b+%kg@MKP2!4N7aneNTBr!JHv7R4M8EBx0cWa?X9O%z zHpJ+ysJ$g{z*$UDN5cLjT z;;{sEXtn~|L@fBFga7RO_uDW|W@SJyqECCR+;GgM^kB{COkG^UT&1jwaJhu@WBGpb zrJ%gA{UE7mVfx2q(qm|*rCLd(6EpzNXWpoRrq9C!`eg6iScp~RUtsKfM*Er_J(Jec zGvrWAR5Lss=G~}nLR*5vUb*Q(N4wGqZAmK2-Y$1LDYBHMlD6ss(CYwn0yaW{keU?_ zkOy0qb0YPjl0osgoUz{Q(N++>pD-Xu(KnpYaV88+pDAQzRc6OstHMB$;V#St%j7wN zD2a>;yzke2EP;%Sc35FXK90$_)2wKv2l^2cXO}6(%t1HK53MC*wkvczYF|O_b-b(N z=gme*;)r3x~T_Lp;pqjX}!TV8{C(K+NU!RFW1V%|FvzAs% zo`R)qoy+V&sb3QFO2e^cNdaqL0L`^DX$7IR>r?OjJKs`$_FzDmJsiqkDP`iV)zLR= zmP9&L%_KaST}1UX%+KS~Y@tqzUB+h#xk!?4I|4fJ!Ux-Ga)L8@M1M8Q`vYW;SG2UD z@L|&d-O3@mH+1F%&rd>rfz_2sfi)LiF#u#7{oQv%8m5R|K@@C=_L$P1?5LmyB=uu3 z>qc_jM>q<4-XEn(dom}046}f!(fFXFlmSt~lmd6bB<05)qXJ1o%1pvVRu>X*VXs$0 zg$mx?{~3PX{^tA(t7=cgM<|UVi5t3F!sWG1(rVY^0P|v^4R6D2Ef)`RBgg#TYNEJc zzV>fg^|?0qX21)~6wLNVmmCK{ss(5DOJ}Kj=|s9}RM7y?=A6 zR!Wtn8=wDx{KQsM2r2=};zlKUTQWLcvPkb|&I|qiy569WH!wg$YSmI^=nv(vwX61^ zoNvsrh9)ZNz-=G_iEMoZDDtP;4#OWNL7S@Q*m6HAr010s@AF0$w*^a^$9qM8p_Um}P2Q@oRBy9ESQ zi-EWLrBD@#)mQ`x*|#dBEeN&$YLR}`tl+5xNBIeD7xa&%dHj^j(m3NkF8DNQ=Du9P zuqZDGc6C*v0)9@*>@hrrlb%D49rmM@Sq@df+)kkv#!6URV!zib$UJ}LvL-UBynvt2 zf}?YMWq#JKIHO5&kk8p7V)g?+qQn)AlRTEZ)x3Bb%b}3B4TAo zEw%A`KO(XrU62(rjtR8~;-NZsSMVu_7wVAqb>Ted^?Cb~WXtjp@WGlyT8k?{&}RPP zq)D2Qpa3x8V}l^)tsY)M8WjK<$|}{X2z9OI0NcGse7?(Y4ta0MeAwDT7}DaMRtUNf z5Qym)Xq=WaIczg#j!Gvv zg>M&>KPi@hfp1#3I!?Ir_u653%9Rp-6m~B9slSJI5;GdZZs=uD?fv_-7s{3IEKK#+0HuWJ3fbCs`iYY}fj$d)-AE}^H3JjS zzoVi8pAD=jMZ~pD7`L&us1EXVJu~R#(#jVVPUaUn@2c@Z4WD{glt`@;57>1~UxE={ zFEJ!3g}he?Y*ENcuQAFp84c=d4+R;a4~MhllB|^XWJ4cZ})?@ zkWS$w@s(n+2oXcwWS>?G;qBR;u*F+%z9`=aKJdD5b@o|ms(Tri8&TI` z^-d=%>o!R3`~)V(^LkgHnVDI(d$AkD{Fk9>FcbExpRa5LG}aSKp3H~Zy+u>Ya~hrI zZ{GlTs3PFvT+%BhbMEkBFdFZ$(o|qy2$}WQvn-uzMLAlF+W@=|Bh*=QEcR@5S4Dp) z763erh=}eW>Z*|LXKY^2Sk~stX7Ls&&~quu{pGLK!;k^IJd8;AD4khqlC+DEKA8y6 zL)fR(A?-Tat5g2&YIUA7AT^4ecLuld3{aiZ;{wo{K>P%+7$l~op^@K#8vwe%DA>03 zzWwcF)0am7j03G+{Rk2Mmgk8b57>bTq=;-Pn91z`m^cL4LM6wy$$bhiQNIGbn$kV& z;fr^EhS*7ZRE0FfIW+uu%WqR3J*Llz(psHdqX1-9*E^xm^)` zL-9jOn(H9e`G}s&yP0|CGG3(LMi3!FZW+Wj>wuWSNGAztjx*^z;BFxjjXKIkC_YAMuPM>w34hioP9f@&-h6AaP$fo~@-7isNq& z@4&@rduCpA(>sj6msAw$+EAgK_#(k&HZH)qO6X>$lYL`WthwWG?FasQecx1a@RTwp zSiN`Ccz7`Z0$g(MtxL_hSIZ<$G>)aub+C}uNUXY)wDxL4R>R*P`TE4-hd=~fr;pTe zC{>3r9)nf@4|sV+xs+7IT7$BFR$A+%3`>9Gf2IlBP#&PqUi=N{r9-Dqr&ZXM>gfoIAp@hI&J4% z515Co<#m>f#U++s=uymg56Zg=DL&7{U599T=bCk2cjHeNT6cdAKs>5-Teh^seRq$D zrI%MEJEyBE9t|sIyja9ULVuq`Jv1so{&pJ($5z^oxc4|k8qmdT`cgjuzO)gnjr4v z-l*%-4TCo@Ud{4LGJ!fDq9M$z7VLPyHYzW)UO3WU7rO~AXfZ@Qga(95K*TWWavFg^ z14V3BxS$ug<`-v(ln1eb+$JxKN+PdKf->_mXmUydbF9*m?c)m35xt>~dPFmgD@*zp zJ3*Z=MmJagbY)^qa+D|Q$7-QvYr27ed6z>SA9}JxW#%h&%9zC3_W^G8lp|`^BQyz% zvmSd8N?&9w*+9TRE`uZB!qha&1J=CD;-rIVLW?usiAUS_NQf>iwPsqD`vyQ|E5&Jf z{x~0(M<&*odc}GEi-E}9XXcI>wZa4zkLo|k)IJ{wJ9`d2mH*S}!5jam5h+j)6xLz` zlAwJ7_YZ_s$h$XQix!uqW@(SSL9*n7zgD0t7J4Fa9~U*mxij{`%b*;rYC%JMcIahC zBoe;$ru9N>h#(Zcn9Rc|O-7i&Ip#J9z0hZ6mUB!EKeVsiOZ1exyN6iT_CfsAfnBDQ zG`d5;uNMIE^VPr3;M=_No9*oa_k9I1$FxIVi$`f`Gd@RBJF$R~DQVp<2H z?}@MGCa6vK{_sxNhuT3zLWTTuM-I02Um4+xlABl7FH=1e!oWL$<)DR;6{3!NP6{MH zgQuX$GuA?RXPeP3tcdNH!6V$kg9rI9=ma!jo$tOQjiGN0l+1|eGw!ySnDw6D zGonJVGLe#Hx%I~Xs9`1p9TgEza{odD4Ht;}_18An6DbINAq)-`EqN~bI7u*9>x;Y4<5 z;>)KyBBy%mW8{A=j+UN|Q5Cqq_Cw%RZ6W$l?_-yxpt0a{HzP0jtI`brTAr?rmSvfq zqgKx<2mPl%H8%6Di=g;~=yzrzd3nd#*twiLZdi=eBU%0&9hYc#58}}jFr4)*vY>yy zku1i+Q8p|7q;5~9Y5NJN^k*>%S$<7b2PEweg}Up|eEK;CJ3|V#q7i;~LaW6Zmm%-a z_3-60DH*>~dJR@eS#j0IA3en}Up;?Q06BnTm|6n63@iUrW96 z;$&Q|!k>f9A|cDlJ0_L4HPxG3Krk9c`C$%kn(oHmzGgq%i9Hh>ALpygw|n<)OL%?D z^&;n$J2D1<&8Aw7lD=cso*c2EU5ZO8RD;)&?z5s3?t;FwZ}1|r$mr;AmdiOgIj4*o zxv$B}dS7GN>A8cro73Fs%gz=MM$6};^XB%HmRzedN_szrrxu!{QWsVH1p>3=L=HqN(pM;p@Hxi z8yj0=%mE4F!}QGsj#+p0^`&}T9p~uc?UWM00${VWsZq>5(~BCvN!wI5B>(6J@o=0!oAvg9#_2 zGTlqg=DFcSsE%UDJ%dPNcmjXV7o$R}l4JP+8pBktOG)wUHqFDG%>m+E_l=u{IvETa zRH$6a=}DR&AfmE&g}!;?%0f)`hq>C01Rt6W=S<39>k`jkEB-4U?TeH_In2KEWwvp(?KJT9C_c3yFS&2{VpO3ZI1 z8}$13Kn-;m$0oAZj7T#_Q`x-fOW{&soBQN#5dNrc|zL|pH3J@pXb^f8b2p{FPkvq|V zkc;g=!(S^!MRpMb{W#x&^W`b?X2}|B2Mtm`yftd~m(aQo=G4czxla?>#hpyRpJ8MB zLei$5VMuGL86`n>Ddb^?L8{fDjCb$I&v%c9q&aG|u1`%JU3;T^)MeEv<~UCRgQ>=y z_eV2~Ij>a)K3~<8(y&ZDExzXTJ-cuJb6IImTZU4%?NJHxuWT`5_UF9FGH$Hy6aO9E z_+Np09UgC9`5nU^CJ_U;61d$5I(RkH*tm?*SR4&WFgf7(?{LQNmU$iW3yO@2s)$!j zJ1QvHbpLhz#T`T}q)_4JfY*-9Wh=tZkAbHvQ(}wDP0SB1GI-g?r^0$H&$h+3@O#&% zR|1xik=A1d>i*=L8=ZXON#~{(V0}0!^lqpX@!iL7jgIOJ;+geM93=Z=J07C`B_DDx zWH4?znW}j3q|U=Or|C-m<6nIKp*?5W_spK57@8z_g5W)cFMk9JDYQb(cPO!$nTW)2 z_gH6<_Dtz9*~@0!_kjevl}B4R7rHxxMKh z=kxpHx^Ab#Ii9cQcsw8De!o9FPDCn@LYd^DSx-SzR$*(aN{~3V2$57cf{TU?M&k<( z?I(cjf&8;sr;-Njk6bmGH(dT}kM|5U$}n}lJRhsfR#Up}SOaoc<`YUg{xq936alcp ziZ$6fTU*uL3pv!8$}-je+N!#@?*IhN8u+lXmoB--J|yo()ODUdd-m)u>*_m{7schi zu$N2{+>mrkPXXoREM2JR>O+v%T;gQ!WN88x1hqpf4xE-wz2oRqG|JrPqqXjYn($05 z=jjd%>Hxjao5_JHR;R&hPvx#>CD$+gV*u{2D8T}6em=44_j|dxgFZpc#}^D@gIfK$rh&0YLxK~aY7+SK=Yt#?ODRdxscgeKKTr=)%S}(uxBC9E zM!|JO8MP=IO>q?mVs^eDx>=!@A;!rmhv;vp?tN0WrZh{({W_{aBL6t5N?G1_aw0wO zxg1aKe~j@z{YLkU!!XA7mMbIwzSGZ<(7PNHwM&`oDQr<11Zb8&KzdO&JIyIcFqA4P zDu|Og2yE(e3KWQ@My%_`I%di*Z@-s@J4nuj+yQC4!l5I4e0;HR+u!0_|IQ%zR?(?q zBE9=1`*}8*tS3}_$+`dZm)x%*gQ>}u>EE8P%O}Bxo|>FI^v`wvYexjx%VWa2l@q`v zP08*}j1TAVXH$6d{{7X6t{7etcM3$vr#V`NS{PuDq{g1+`@Ph6h^0Z&s!uPY1ej*0 zJJN)FuR5}Goq0w2>~PKc@?7lN%-!w*{^KGl*3vHzQ5F1qaC9)ZF}`aX+k+cN!^SM} z&%Uy?=6{cJ?Z5?>wSpT#yi(xdsOA#c<3mpZRyJU8P`|88p9T4K_Z7Mej`In~xrPD3 zIyVFBB7q{0>A`|(O@xGwyjiF2o-k;RU>LjT*^BFLk0tqs1*Ty~OrJsADBITCk{yUk z6OtIo^4r4yHj5pUfXhWzOdovX=3G-$(0M)2n3$LjjLhaXcAufSU^n@8cV1vXfV$lo zF);x9jve?>u^6Qw?n~Tr_>*sXS>9s>La%1l6Y9W^7k5{-dv9GM$RD9`Kt^LxKYD(9 zG+s!Q@_?j6Z0oJRhvPy4no*Kz1>Y!*J2KueX=d*xSzyc1tKJ97Z7;My%VQy5dGV3t zTguUc7x+80H8e~*t3cKApqY=44|U7_4*Q9YB-PDh={$10yS64(Q?6y8Dt0Uv-}N7} zl!%PWc6d~1YY>v3kdyj6{5Z?jt-KXS-r{<-?Vc6_nAo7)ZO1J!ZSp5>VQ%@BP7o`6 zIVgNmphG+Bp3fkU#;N7GVOc5Jrzr1&LH!y=!5djJFJC|U_=3>!Q+(?WZq82=NfQ$$ zoyNDoE1X5d=l8lW(-^||s?08r?)%5DZ;p&+CkbQ^eF5io?b4-7ZAKIYG8ON6AGz&J zA(=`{Ol*d9px53!D6!VKqqNVzTl`jhQ8NMwBM}?r!HqWi_toS@?mkMLFH?2)Jo(m! zbuy$N6EtR;jcTb z_eY39hlCiFU*!Ka8k!jnMJ=tf{-LZd-Mx8oD7bC4mK3XnR)UsW@?_8edl z5<-PL&&o#9cscB#Du9YNTEuSh%+se&_YYakW|fY`LcIfzC{$=aTZ0F$+yRD=UiKCh~SA`UFxPZKs&_h`y4q@W8VFrr-*>e2-fo` zL^yw+70E^v-n}Q9OQX~zm*~#$@C1TSaUD=ujotgCJa+ZFXwHr_1nQZ#cT9;BC$m|d zep(vO>uebOhgX;aM$ac8$T0Nx(EcL1bP)D5|8@Gy|DGZqcPJ)&j*<08A{W(e(+n&u z9pX)GTIEVvNsm%ESp%)CD-YdL%V+DJ=$EHVCyiqzR^yvF_&!Y7(bCdpfw-x#&FCwe z$&Oo~7@~`duuQdlFs5|SglA=vubW%&;@Bx;5$6K_qZb|)N ziKjtqNh@bxfYo*a;O7}wP?>W{zgAw+f`sXe6cJ=8=fXed(E=p%_KD`}Dsb{x9N2$Y{q40y5JE|?9()lVSw?e}Xf zE;L7TFw^XTA?n?IbCl)R5ci)dKN)jZKpkwTiOA^Q-{W?ZJcVqEN9s{N+nZwZRpv>{ z`O#aD+IkT%z$;Jo+>P7=Xs0`tK~pdm^!|9UD>g3s9+*GUf=qX+owYx2sidS-sgyH1*T4#)s_8*ht#6+p`f4m*8C2 zwnHshE(3!Ue|YQoAA{UnV+pd`zP;4^f=_q5gTmHj1du7BS65dT0JpWQqod=E3+Fz~ z9Gns8Nn_~%k9KfqD5&Dp>C?bw4LkIvVi8X8we^QPt!FG;vmYy%v|R_!&p!^2zK0y- z_gS#PZiiz(zWlwxAApxt&q?;jAedmstx`z;Gid>H<$UPpw`V;1fJ)%i`?%K_pBCn$ zseIghlokm%dZ1{dq^NjD_!GpT(3wqIT6+HExvUJ@8MdA@kEXV6fv;(tc|t~w%qbsH zMHUf*JX&W~N9z2&zv-r9pUGYK+ce6s@!kdV?(}N>|31gKHQneOJBkH z3zE!GHSQ}eTrPyYW|c|D|3VVI!?lXgrKGMNbn4WpN3_YFT>#S#gygdMYMcI7No30z zH>QRl$HJ|=3?^yr`u1|pKn5oaPyWX+#39&Q+W&lfdkg$}b>UFsomJpv-Tai9MPq62 zC6oL1zy-^%Za_Uz18S3=@D$h&pDmd81r~tu|eVNbcChT*#>dFt#K7Y)?tM9;npI%x%t29Ck1-6 z*S`Dsm07+UYzVn$dZ<6aS3Ob8={*Hxm2y*=k|?3uS9bye-+_+xw?VT3Tj>)qJqNAAOh<5>ms5J$kQ(mjfba5Hj#@zz5Z^ z(?(qn2NQ(|PRx?a_^@0r*DOF+)ean%Pdmf?W_sj{Z^2TZ|NE*Z=Ba#8=|EBvu~&9= z7rCn_auT5h-210V63H7SP&)H_`*zfp4lq?EuLA` zf{lOi74{}|DLdEJV>cn;vWB6b)mBJD(Ha7F$}!py+=+h#Jh#qffG2ZM3$GZVDon^} z83bwvYX{?p^c|juwRRBIna)W>w{cE2F+Es|Z#xZAAX$lP7j#{rpwxBa&C`sr)nhu;nhXbYRV zYN6B=S(Kk;N6=`B7g6B>=6jyR#;$$GUUBU+3th~$D*;}n6S|@-Cg!SInwEO}G9=@! z1E!>S$_|)rvjFRFPdrFR$HvaiETi)})S(u2>drwNY{j5i^ zFcBG{heaN5pJn6~SZ&Ci`U8R`_*H~zQvjL`w6+8}*Q9B<&@ZgqzkSmU;y3n7(a5b; zIw>ry9(NMkb{ml`8tDu$*Gli@qx=e zzOPrn`PFu9pWOZX4)x*(+v_W+H&6Hb9ZBXvFa@Mx4=MLQ-IKFFZ_C#Gvd>$f0=fH2K}Jyg#)?*V4Y{b(i(c$DObhdl~TNjhbyP zz>b;=tn|{+_;@v=3lguQv~x+PfBg92&R>(KjW{>6|9@`7HJLjAhvkJRN+h{Pjl`DF zrD|wIah`Q29~ljWq$J8a9CF1VFxit8@aPd)5M+@%QlpMZ(sl5Y?<{`YeWl_D;Rn=yW=EmH0Olvx{7P@9=Xn5w@ z1U7=+4*#mO{weu<32n){ct>XO+hJ|Ay>Lawzy(=h;%B$c0(WuXcJ}Che-}$$h0BK1 zzSlPJ(4j-O9c{*2Wew{?*{SIH%lAOBnK|-O7dU}6z^viYY;jvfYLO6eU+Q4E`98@l zEdza2WM81=YS)Kn2K^E1r-DT7yW~Gl&D*F42eF&-@g}KVz|Rzj-#x|2nQXF3E&j9o zQJbxl4Hu+s{ax3-Ga1q@0#{ZVKxJjOr;;JRI13i)DS1q;(QT)>;W}%$H|Q5^Z7r$N z*x1-mk2{h#!rH3LpQbYO)vMyD?UW(t_9&ap1+U&RevxBM!`2f zZeQ$*Ja8x`9tVZ}(@s)c^(}`JTjxz!iC0D3OlbIp<5;7Ux^nLf#Urh+01WX136J-B z650<2cGlF_?{knC18e|NWqy=<-`e`d$d%)mjUN#kuj>@V*@Gn3?mTli!!EmTp1?_! zUT|3(pt4CTMVEgUO81n0A~9QF`{rV zoICX)r}|LgER!~lxee&@uF(!^)4rh8?s?Ck`pI zv~i3K4_}8Ab1^0@`QyY*iXN}8T0xe$`vgxP>>@d`>El2NveRRCk-66-Ht&2-jGF8>cGc#7pZ~N;AU<`U_--_C&fm}_D2^;YG z{nf*QA42U9cB@c@9o5bWs_Oxq8c$C4tk-=BQd(T>_Ol!GBAm<1H)a__>2MJmL>2Zi ziJ!e0%zwVy8L-7!mIIfwl~#d|#0A~bUPJnOP7Iw1v4)P2D?&FM1k9gPoA=Z%YR1=J zzTB7-BVykK2BM;=LG1yDq{xRiT!<4opXVAREV^YlTFc6z5yKbC=>Ub3jg7dpN^SK6 z2M%0CP2_U|BVUl9!c%mztnb*ROi0w%bCPb|C*^RO?6evF@G$eG}N3ub|=^Jd^HO zafKGMF%TO#__gwJvwj1kW;+^8;WBIBwa@OPb=Sw~b=#wot=L#ugUU=P&|qG5-%}j4 z#3Me#b?6C}q_&t=vQo6Z8ZSXiOmrG}Ojis2BNd~09QkSh(PX&J1D+N_8tz7MJbEH& zWtFL(S~i;-#ku0d2_3DnK#)a5b$<8>sHu8ZM^|N$*dH~6 zC8@^C7{+VRXyom^n%lk3?D@`(4#GrepOnXH%gGt%hv(goqYJjjS zRaKq)jC?LTE9;Bv#$3b(e_8hW%oB-g&{P?Wx#!C` z@i9o{=%hEb1Mij#GE}@9_H_dIPe3m)aV|?q`I53%=hm&e>l>iL;d{Scn2q;zsP@XK z3`noBpE;9|eG|Gbn0ZXld*jU)r1uaZ6+CC$?+fPC=~M$FcFU{kf%@-M8c*t$b4qdb z9o#-=LRCDsvI)PY<*TT`ey{FKJ(+{w?4ng(zo~6bRAyZ#F0n5BwCYBunD=RcM#MGV;}^r2A^Zid z&aJj#V65;UHn8n_H@z1AFC1b@Z!%&l`z!f=V*%!y=vVXi*fz;H8CjeFvB_uf7APq1Vv+8&0qNzIS5Md`joT6e7%;^pPvp#ec$(|U6 zs(yUr#z0aO>DJ3jftd^x{FOVVxB~v^-3#nCTORALTZY+eCkN@2)6!G`DD%s~?NXVS zZnJj>**aHbGKJ4kK55W_pY~_>0%QI(s5}2ibX9qIV@KHB?5uS+!y|r*vb$B}J|3+Irf!Pf z5paROT?}R#PT2N(260FKDA6^7Yr5-&pXVQ$5aelfuS#CgUR|0Fv?FwV_~do;G>I=~ zBqudA5mcL`7yKVtB*VOcjTFeIJgeRjJ`M!aLFEvzV*lGy$oUX znl9p=Q*GY{wD4A1M)R4i)4nw&ZjxR*LB&KLn#68e7O^JUo`sFwDxMD>Ue0hT>AVX! zyy^}@E%&I&2*?WTG0DI-)COd&H_5QxU$*Y{Wqj%rSck@4ALnspr)q8~X;-*$BZV@@ zG^4l0pCU&aj&PD%H>0?70cfB!GAJK*lAt%MesKnzQdIbZ6c= zAxJhKw+nj{`sA$e-@y{Wr$&6Es}|?p{ke|+hk_8yj62P41WW$<1%r^r6cLa|zTkU! zCfu78d`(hhy$aQ`7>NFCq5+`^7>bmTzrycqonzTHegwV#&sM;ftlfL5t7w}*Ng=~$QOe=L+>5ySoHo^j>#xgRe5W{2UNTwgHgw zEy!0HsO84Jk3(`OH_Opgo%CkZYS)~A>-+g>*}5t{-QliEOzoG~dH}2dZAfEvRMjHA zp+$4d)8*bl(+O5 zCsG~URpOBYjUi0@qb@UFFR^oS&KVD`%q67XMAxA$CL{k`(=m877A*Og#P3ZCrxgk> zbc`OXJ&cTVl01LxapZ(v<^*z;GcejwH`vIj8P5VtUe8GMecygb<})O@q*EYS^9p>4 z3=@Hg$jL|2CzZbb{PF#CE93J!tHCI3Uo23L^a(x2rkSDws*7PRMfz07ZpWvQH`~T8 zAdXplS}EhTrhtsx^L@r222Rps^TQ&Pkg*?3Kh0NDHO3F*nn6O;sc6Kd&>(kv_Vf(GeSKyp5W zDXwoO(#!gsHJ74=?9c$%AMOvYBotMy0x_8zQk_BzAR)AO8JY^zjZYsUbKc)b+p~v~ z@l9F!a>+N5zB5vP!8ZQ3xRsDfce+qdiQV=z{|D6gW_hXHU=#Mv=(=W=n9%rhU;}}q z1o0Yp8@=`Z?O{2d?Jsu7Ru3zKxB#XRPl*ksT!-T!ZlzAeOv(U7W znDHcn9XpOR@6;ppxV0T*UPTgg388A_+X=d_aS&Jt*&6>@I)i*R^8qrDyWisgw9%MJ ziR9^Vj(h|fpk3l9b$MwFii2e8UqAV>G()(|oPYg3W{(PaH#Or$qskt7&(ysI)1BEe z06k=33$yV<@%vHsV9rjUT=6$5scc zEh*p*3c8=MMf4U9g+TNcvxfNiJGk8E&&+^U@n^W(+2DdWjOKcKK$xUR*9j1YV>8hH zWC*y*{*b@?3|@L&L;$NOw9U4e#*idKC)v2?^a8aL%=ymqzGkk&M~#axVO-KKN`8|7 z{BaR9@HX#V0gPWKZ~QfxW>&p)KD4D9po7c&+;{fUlMyj{8(flK^Iz3W{u( z?78H_qoRd!jfhZ*lQS_%Y6y0`|AcV~(rl)e2`j24Moja=M@o!`KQdV8vpPgP?%dp{ z$p5^|!H>uk+jtJR(Z46D9D$&_L}u>(*KDXzLVor-<(@rt9Jv5D_7dBH{;&caN6wMr zX_Ey;-v$KGI??RE@C|YY!RJ!mfI{g_$YhN@I0VgC0+8-B@GFOI|kMB6a8UR?<(A3APZ*(+fw1o+(Dm>7_ zDA|9!bsGgEDcQhoUe9sqGO&*hH|`O$S}0bq`@JVhp|rgu^{nWRt9#4hHJ!P#+o7aCRF@~$=)xK38Xqy7ioAs+e!{@Az* z5;pHnbm9OPEeKLT@0~SKdebfOKK!QbUnaO0cJBwSVJZMFvy&K2Ek%M@$F~+XlM61l zypf2e?HKYW)b5bF{2$w9^U$1e2XW^c09$5-B>u|;mlpL+_&ubfjslz$%Jb?|=U7;- z7&e5PzhrqmbEq+d+HSg!>#1<>sqf9g2l|<-;$JeZJO~c$nD^}*_MhsF9dlLV%QqR6 zG)a1`ZQ~odhU;I>@ljOc=Hdzf;!Oy*(O(b)d7egU?)h@@@?l>#fQ2=*H`Bs(=SxO0 z4iLvo%yzK0&YB->s`^gF2K{yl5HPkOE`m6DPXP1Ms+kU5K?JHWziRdKqk1kfihr8K z|7|6EKkG~zN~Z?!@n1M{fv}Z8`9rFedGss^MFDptr=|~skUW2ekt!UCG7OP72raiYAAY`8@f{TG}{eW#yX%#5bB4UrcXNkjs7y_1JvIeTkhQ{$~K#?yP$aj7=dIIOHJr zbV^jTJF9J6!LjkLVi)Oe3c^riF9wLAp)!`_6R@@>75M&4nUErO|Bm0$lUqAn(h`bX zyYT+)f6NZznO4f&fr2Qn!>m3yynJEJ=a_aZ%>*$yJ_M{4B%!ZPm9Ansi)@n(@bpk7 zf&l9~JI!5wD_7`SJqX%Df@0TKJDFk!YCMQjXsI9jYa(1@RbDd&ifZKg`3eiGniCK} z(`rcnwPE)7pS>;#LZMI&18DFUn=2>`KBN>Bg!+TqQgb1nv#>XFLz0Yt5UJR9=37LJ z_Cxx0EVJ-4H|_@Lr|MQtLxe`DpFa!f?N4y4-oYGLhT96E(Co;q{d+e7WC?!X4mb!Ftt@Wj?!_?0$!; z0F`EUe7}eHH~B^Iy-L?+<%}(7nPoRRkMHoAfB%tssBuGHh~V5;f;;x9#utHqRJ)Us zVnkc15CQ`wxSvAvwxIwU2ld_nNKZa4GM!{{k3@jA*8qfL5CRH0(36q(>Vbm?>#k3@ zdp1!siJM{eHZjN`E)m?t`^Ik@LHgqF)ngVx>hskXc`1Lt1I8XGE!sXElm8%M0eDB7 ztUXrg(B(voLYU1VUcexLeK<6;M2aO*CfZL-grrjFoBAhsp9;SVy z(VxXail@k|JFiYwXf5e`I@-~(2#6ca6XFZ|T(QN046HOb5U9EK{o{)gy9uaB9Kybj zLEZ%KEExBpBmm6wHL1r6PcBwhwTiYv;mkR&Lw((|z7-I6!;16}&ZV^9)9boA7oJ@p$jvB=Yb{ zXjOO?YLnWy7^bU5s`EeNB$E5Q1H#gbn)A#x)4RtqrF_m~Xk7`=1n$cR7Yiw$F$k2% za2qR5TCQvkoZ*uoXsO3|d@6PH`$N<8kB3vvlj-6iOi1r-l!=~jI+E`l7UtQ#U=;=+ za{&{m)iHe0!WY%c@uz7hP#r;BNwn$kEwba5=V!kzm)15ebi;NZ-(~ZS;lAIU7vMG{XWhIv>GF%pJKa*xUP5k|(fRelhcOXFxk9-6_l-u96Q5%KV zX9Q@VPxWWOZmNQ#a=Lp$sY{#LPCo7Pla;l!ys(#@HMR~V>roQ%7+M&l+TTBc@AsdW zeJ5Tvr#~`SB`-2|s?7BeGHA4T>xex( zHnD^|eY$2oTSbg};)iN_JW}O>I0S!P%bKNz@yE;lIYpN0p34F; z&_#YawO~QmZ%R46sspQ*Rz_`lk72$*+ku!cD`I0%fbPaZb)ha-TBu=qKHHk`BwyDS zlTt{I<@uUg;NUVc$Va6x@-djL$?Q>nRJw7=;cwEr-`7uJL%K)o)GNi;Q923hi)unExEkvMxnfxQr#+km&dW zUq7`bzjQb)NC19$AXt5FX^s0xnNQ9ONn}P%S1Z=mxG}(x6=xM&u(E2Kp31wt3jJ@! zLlw_>qb;u}MDi3mi>U>3|()>tU~6;AZGL@jVQ` zP(V9xr5k@YsEg_4_=i-8B^|-R?&%qqeXU6+8rm_&6AoZv z{L$=E;jBHDCZ7sdo-kH~x=BugKA17XeA7Yw{7QoS?ves25wr6GX=V$<>Lf;^xqla?_tU%S zh{=b2;gbk>WMLtSNiapLusJobsF1xmBux8#TL?W8e6+15(e0h&)}2^oOlIKl5IBNu zm>`g{VEf~zH%#cLggSd8I$j+U1@>e6(y1 zTbkhlLE~=q*A!;5iDH?)!k;a9r|h$70_L%SXy%))K1B|ENo6A+S6uK@*|krY(_$yQP!9t99QA@`;6S@9W2VZdW~VG@DiH z0ds+uPxtTYeV&9b>Ctdwr4cO=H>dlWQ^d`bf`8_}`SgWu=&x$&a}YjdZJO5-_FMh; z9XVHyHiJqV>k8wSq|wy~D8W@MI%dXWF9?@qXMttWmS~_Drg9Wfqk1_WA^(u2$V=8- zs8_8&zY{&uHurpdPv)3IUTJ#bn%0fgcXR6q+Z-WfCrT+8^N#+wL%eWpV0G!*k360m zIsyuc>hmM-F%^vYn5Z`K(N!K?gaEd#eLY3X=VmTlZZqC>=-ys1SrI|XV(E6tKb zgGI$I@`Uy%j}?uUhEBrEgKBocY?+!jZp`h#^d>NUD$Fdy4|y!C{J_g+OSHKfrmjSn znJ#oKvIc7DI*AY2TwE#rh6D#~3w#_F_={qjcSUv)_jHbr-9l)GvF9g_;%SSi+B60E zvT0;WFTCmrXesS%o5OR%D|AGtvjmMOTOp?qpQ(KP^u;0KS{+*Wysc98)3CB20fjX^ zna5TV+VlaSyvjRU92R16sAr$VjC6&g_LbuVc1zoSYLJQ z^0UO{?j5i*rK=>gb3f`%MN{N!;%G4Wc2);mX5h*ob%q~It#|FmENzGd`9B*4lK9d> zPAqJJN5#*rP zs;~FeETbRu>FtUiQeIG5y;X$P3jOZ3r*}2ORQH5dRMAzTcY?XR!-P(_M{1ksB-H<+nB~>D(R;0t$>Bm4Q~GMpqT6V zr2?@d-vqj6mSCaX>@uV;74&K#bNVbKNC0MT7<#ZX5nxWckvZMH@GvDDv$nWYR9rSq zN|BH9XX%-m{`_gq4pVvySR%nfl&}Q7>V>^sk8xj9HrFD<8kf6=6BY$tj4bJ_r_p>r z6?wCux2yN*anAf*OIjWQ-C|BKjd`$Q8Cmd!8x7pBprUH<2k#ES%Bo?OocGQyoh&M2 z`nu}MpHj#QKbD0av6ZK1mT=f*n#s3rJ0(AXo-*n;#HckE6{pef|yfy{<)=7Z|BJ#43QGVs#+dfItksM zdyyZdz}gn?UvvvV1gBvJ%*b>{PT5Np^g3cfJ2I_t8|kLWT)Xp~7EkqH%&)-YJ+@pe zgXu*%VIfeQ;yG(xSGPI$BcBPs)?oMF$KXT{hH!cF1F#IB+c@2gEauvT&c*?3*|aqL zIQ8#|!VtbKE{FNgkPa+nW= z>`%DG^#NAz*E)H~cy=y+GT3&FSXt)d|BayYG%X?dzKVL(`5tlLB@{vrADF%ewy=vm zpSD`!UP?zuz7u+fNLLO2Jp4SWItdaf9sIFEL!-7k6dnh3dz{eDrh;u0w<3ba$1yy% z#NAWHI(jg&^q#>Ow%;!7b^O>i1M{F|K*eKRiDq`x;Mxw!+q*6!iMNY-;^Mfx3- zr?f-b#ZCK7>9E-tdsH#^hjb>zB5=K1_AuGmM^8k@%s(oB@eLfQFO#i_{&?;&bP}c{ zv-S9@X*}m&qcv{%2xo))Tp@hK6sjSF$Gq6rdD>d{qsesRnes+Ih+9Z`EIXcPL%w5C zeHG%N5M82WV=DZUJR6z;4CiXDoRQ6EWIO5==1D`C@Sbcu6d+ z%pc;VgLYKaPMk#t@-^Lcup9bI9cTqRq(;GU*kK$S1wD6Cq5)mu+$JG)|@9SF%t>BQGS4lbEZD@JY;lA$^;)7>uf62iyCtPAetJnXU zIsPvrsYc9SQdNf$XUlX0kfapJLWhx{sRjS+Wv`~yoLG999sPO>J~%(BPmQk3Ltxi> z7r5yy_`>+V^dpJX@9S%p!x(jXDA&j#8gq&NFVUF&%KC>Ej&}E#Y&4>{`-cc2aM8MV zbcRKbuG(PBrqsaWhwn-2NE(qvVzbHmTk}2R&@FB5=enG0#0y5TuEmo0c&lByzauLo zPK<7ayR7$U7UJt{Mp2V+Yf~>Qhp{2S+!ZW1gvhTG=0u5FhR~>c7ObM?4JM8)}q8JVWoDsZ5P@&ULw#@J1WA$v`Noy$krRE zP?fX6=`Q4XjteF}5z8hW+Ue7#GaKMM1r$8eHx~J3K6mfj^$OFnH_fCWLs_4>4^l0u z9PUl;y+@D18YW>I?sjG3mS+oxWxBDGVSxO@3~)* z&^ARWhegyVZ$#+e1w`zUSXgcbDj{*_h*1c_{jk+ ze6-ZF^q*GOVL)~c5gbXc^TZOn2JEQnpd(wA-Hz~a(rn;jfbzrQTu#Q7h4`9rDmr?< zmZF>F5}??xP4{8a-EIL_?wJUS#U#X^t8@@+(Q32RU2wrwQ8# zpv_mn@h++zd$jxDjlY_cjP4kN`Oi~u-;;e8nE@|mcc?7NL!F)LGouf^z;&R-dsEQA z$WCkDmp`FKzrGHwNx!G;2npz30G&aChEIhZ`f1Uuu?Z5(8bB2@%Vta|dwQ@Pd+K}E zuH#Ep${(Wpd0w&fU(_p2P1fj6jX5^6&lu9g70Z$Gj_{ z3@2HB6R7D9Qo{`qI(l?SeQ@t_k=D9i&lEzfr4y7(fG6n9=#vYb$Tc8p9!t;(SHmDW z9S~Tfa@BE}fOCI)XLYzP0z-rdw|u4KlrvAp?M~bBib_k$>jSPpg% zjwr|~Wh)DV$DQed^BgDLB(G9zYDZJ%LRWb8m8I!v<+8Hn zVTNT$`g{>YWK@vt&42~Hp=o7NmF-f27Zp-UKHugXHS(N`x4oR{B ze4{Q9eU#tm6+-w#%0J2ixl5L^#2Uq?a%Nv`TUb7a2S)c33zO=hi%AS%)$MTKS0RbN zlLYei=c~_gy`UHHa{&|$^m;6LdBf+tV@hY4YgwXwyZXJSjMTu5i3PxWN*CkK^gW(i zhqVBy1yZSYUEO>#VCmtXJdB>${MeqW^a+8HuL)y_W4FH zuu2b_g@Fvo{A4GeR=k_b2{(}Z1HPBBnkAx)V_XPT;o*+BQ8 zF$sU&HWWcD9Crt#^;59KL@=Vd(t(Tcj%603R=5Sl{zP zLwo<=<}1Qm?vz>o(pv$}?x=SVy=BAa&;IlCHVBn>_hAIV>267fsMG*SRoX^s7Frxi zA~H^(J~+@vpeH6nxWn))D?7Vx37@KY55u37kZ|sV0u>J6zFpR4eU${HSbcGM&>v}f z=49J65pFQP17CuvU=&&eZo zBo-44QlTZ|j#P-c4Q*uFP(ZpjRzX=xKtDAppX2f2j!8(PH37Rg&O#?AT`2>Dl8VGj z9^?m@n3x{iGv3zTVva)UX{|O*Q0_){^5z2~0!;g|C7FJ|^S2fJC94LN;z3Ua%quWl zBE8QYVf%nIjC|;YyK1I7nYxdGfg0puGu?;gzm|BZ`Wibx)Vel6LQ`FwIIqn28eIG! z2485HIKH<|xqt`+gEt6i0lw^_H85~%kAu!4+!u?&$CBPDQ58mj(3BrY=P&-q2fAc9 z7z&ZqmVh26fZkpUI*ed0xp$|4I8o1|nCcwKXN;@RG0)&7+VT0*7(LfWy?ahuPqkw| zFsUj3c%uKtq~4r_@^=V}VK0+-PfCY24uB3)+5or{;d~-$R@9g5uqU5M)b0kbE*L>C zB62Lya~WwWD1yzQ%r_lXM&-IfBc$ZYja(s6Z7aJ7OrB;C4vu`Gxr7J~W%-G1n9sEiIhWeY#2CnqcG z3o2i7Q06v$b^CF*9LTeP-Yp~KM_!Qk_nrZsUC_mua#Gvic9#ip5RaPth%r70Bfl1z zk)bFEgn@hSR}KLk0*!j|2bTM4K8$=cTu1sh3J2Vbhu}KUDH?CzD8DA0$31`(RSWdp zaeST`g71G6QjWmIp3(6LCI|6=6s8UBlD9V{=)8gcYAJU0I+Tx*ejV1|UkGigk(yHo ztmx5U@U;kDgFE1gwTl$K@peXpq&`BB>K$3ZUkV&?zv<3LfgiEHI4{i&;pBkS>y zzu^HAnLZ@Y^`sEM;^`(nMb_!$3<84%;ACejIbFZ*{l2<7M8cNUo(mL${rcC2h5Uko z)O|{9OF7vF?92(-4dVWR+Kx5+DLdAoY2({~@!Si$^Gy@5u;1!M4?hY9L6HDfxi_uG zW6)_2QAFK!mzp0grA!V*ZEbFe^`Fs5>BL(SWkx*`5~ORJc4SMX>gyZWT>1LOe^7Q! z5WkJk%6sn5C6Z)5N!I5uavX6EC*}j(oUYzr3cLE3y9SAl%W^Ez2U>MQ^Qc++nh)X_ z(e~t9^kdeO?aE64#bB5_7aAIxk!?$l!M|(>;;SZG&YdT8qmWYP+!FK)p|&1vJTbR~ zsD3CZD@(oL|FRCy*jnJG3`ITTPFl*e=+3)|)R3S`Z@VZ4r*yeS!9{5ri-`Nuph+MT z0hejsHIPvUdap0A^5L1tO@)x?_WW5zH8teMJb$*l@wX6?dk3I67(?dj6Mnz5gNy{Zi2h;>*~YqV z`YL2+Gazlg9I>&?ln71ho7%ypVFPTUc{!m40pTk$krdId!amc?P422#l;bH;sh8MT zqenNztC@A>)U4?c+;C~kX_sce+sDf+9Vb-D7NC8G08bHD0)7VyY`yB-65z`by*KEZ zeG}*<2J7j(Js`x2`N%Y`bo;iEngyOA9cqLuMYS$KGP}~twFn0LJV#`8Ed*XqKKwW@ z9q)E`3wQRP+Dcvs-6NB?T(&KUWkQ-LO9lZVeo)~3y zlU?1mQnPa0h3}guK~mBmS}BH18<&d$#olhJhaFI3zM#g4FcWzkiQLD$(FIsQ7Wx6m z97MU}aP%4xBDP6p04rG2tRfa^5Mi)&Wx#A1IG0x|Zp17hAfO7YnI6mW!&rc?A36Bx z^JhLG5&@$|Nzk^_brJdlWOfo@w@!og$HlfNTQn5DVDM=wvb(+ZH|DZzl=LCw&F!b_ zIRt2U9lK5g>z12Bg@v45NT~7fbcXfN^@C;*!Sb1pN3h9%G458Lm#GRz*v;P0#gdHL#Uh`&FJy1Kfd(28r329CVf zR%!`6H$-%5S^I)#H!=4vXn097-zIT<-r7$Z05RSr5!-S7mk~(J{mX{Ce?oR)(42Jo z_Aa~(2r98hKPTz`d=h{cc_Ij^7$90DAiHw^iOA}+RN*MkPEbJyn%s>hwp$n2dCJzZ z5Q3uW346F3tG;U3u>Jt&jAJnQDYS56l5o*dOV{Q?Y}yUb0Y|#HeFBqyl{84>Fpu_G zXyT)NoE*yG+D8HA>VEqGbo$#*>{W88QW@%4Sh@t_V1*7|+s5GkBqxY$tM|K8(71N8 zZs@jdvZ5{80p3>pXMh6|S_+U>kTu}hCgmkET3UcU3gX6C11o5y)$klA3?5idpNbvk z5Ka;zP7Q<$UpVfnse(G7eR6pk<|Vc1I5;Vx$GZTKYeaLq%%ucmc^!^%6ab0PNIK{`;vKEmxxn536-8xD>uz2SSr8&$J|L##LE}lVmX6p4%pvqp1Q*sOz2N2qeh<>DVD_2LTIDpB z?EV$>3nE-Be&9c~8>yj!q4`c60u((x$#_%B!o;XC(tT75IkxV1_5fom*lpF9Wy7aL z)cs{r?Yda$74k|N=DX4~6gv()B=ePc=+!J}?y>jeg*93;vP@cB<~#Qz!zXCYaYS>O zKRfu)>m((~{tt&~X=oH*JM5b~c8&SbtASK(KZ{Qc$E$Z7w$rK8>dy@1Fk#tCBPytK zYg2`Rb73OP%#xLrl~*N9k8V%TFi2Km*2SVOZymlJ{;&&#Iz1JCt2%Z_GixfO=G+wG zNA~!kn~1dHf#b)y=yoKIHa=m3xm^E-fqwJcIyb{ee{=NBacy={*S^OReh2i-Up| zeOk}~UbDNWBWAT&_X8zxhcYkDH(mh(T!ZfN4_(BLNbDdMBgQ3E!c|=76tR?so}L5J zTx8pxZ8@SBauvYWsuf?8jJOQ7Poi0iuTV!C+bF_pwhaO)i#TY*ya#UV_E2F9pc!q1gR;i_RByL| z>0!etP%ys^QKvpo2IO_xL5{`&>h40}Oz`fgV+ zJ3uW{cq04n&#yKtgd~L8s^nwPiAu5F3n8(jzgMdKBa*Q#F5K3IVE)Po&oyObu&or2 zSj+N|o%P{joafJ<7e3L*z*QT_!vlwhm1eZgg2qv%T$cniV_rjho&G3==*IuY*n7ug z-M`_(xkARRn}{Msh3tkc<4(#7MN(M}QG`_XxU{6wloVNsCW>si+Cm|UtdxXgWRKEw zyf5R@@ArLP&-4AG*LC|EpU-=o<2aA=IPq>a1p)p9r7q5WM;-k%HlPfWlHuDrW!5@> zKfm2Ttlwq2+FnVy{^?lFC}AICf?<*B6V0wiMBD)JbOU267HkAP>GtNk;p)Y9E|YIHBWNdXtUT*Nd4@)0w=rI;A-n4k zCIc{zE?btNw#mLK-rAHHmnctRE{%QN)-$jDLtgj?#o=w#iX$C9?#Z(?GzK9DwT@=} z3c?C<X~PHz-9KclXiP4cFD%?KaQ@K=>He2DNmD&A<`~xkbedctK-&I= z(GgytDZlikeJrb}h2X!&Mt-NoRH^`b>)>@nqxz73d~Ds`*5PwXeVVXu= zg@mIbuBpFKQ(CpAd2DRVMeN<-{=~RN0Yjn=*YlV>xoGY3o@WqN&Uey+KElOo*RFNV zkMHotX&QXucfI$)qpyULW-xOv52Z%eB}-(rzgagNYH(Rf z-_h|_>m`kOjK%)O13M9&A3JAipO{XQeYzc5#Lp8DYqhE7-n5Fz42qci`HL49!|}Sm z#XCutUD^+o2ze$ZCNbLu(j<~R4(|S8h3e%0)(Cqa?NHoT$<1}}3Igu)s|0?#`+t8y zHY$p}hqX@8F-3V^w!345KXSHr&_Iqf76LjAl*Y69UE(z-q;9BwCq!K%T?3H*y?|IM z@{aK-V4kC#tz271mWKXXXKH%>*zw~(!jUB^X+*oUscf#1%qXWzgJ2Y%?bAnZTJzpV`pl9;p=jTN!%w+G~Ny zkx4enGJWz_I&<2S*JK}pj1&01{>4?Ty8=@FG*`;XKYqb-toF2YVLKx{CZTf|Um15R z23wywpOCf@Vq4x|-kw>$j2NWlxm4C_3{aL`!W`gVH_sVJP9DRCgMJF|NL+CG04=5YA!q`RkJ4~rx((baL%|_W9q4+`L!es_oB$IdlHS}}4 z+8mbxF&+WN+R#5`ZPb3Y3K1mlZ`U0TH(-|loXU@w&`%Ky6IX`o$A@A`l{lUdF}|Sb zKcWY-)wZoX=MzG@sGQ_kb(jVui}tZgP{(iflU=%WZQqp>!u>I55O|qFOzNLQ{AWsP zQ(2q)Uy9T9CaK=&sWxp!vj+uNxN~O+_+>#t+n5UXuFLuU=ktvW>@`CAg zSs)}7Db4J&tJh~!ZZu+x%vIzMO0y9qjR4GcirS>O)JvoFzE-d=a)X=j4vG8ey^s)> zXsO%+H`>JP)1kBe(Z2Ty2>;^?Vm@UZYPW&QIkF z0BwF(oW|%a*VcrC_I6@Caaa~LdQav3?aHvLmk>qjAvHP0=ThMI`A9nINVfuCUlg0e z!?SU5K3pHq9{#Cftjv+9~ZJEwUe=J2?X)J(*%8RZZ7@rs4!$7 zxHW4@Ad~+hS)06SuZIrkcG-=&tZq~0f5MU3!85mn((fSsAJcfsh`?$B$O2Q7U+Ml; z4=D3F9s~KJ*B!vQl#cvVBMC50kJJSlw*Rq<;r!59#W1)te{2pbDXdmSyB0eqXWF3{ zKAVvUqnRrM5JA&B1jEJszW|LG zKyIWm#r6|hwty#K?UyPcc_{AmK#nIwGw$ex?RMqyy74A63e}0yc3od{)3a3n)aQkEX0{aBmCD> z^ada0jB4L=b&VabKRN;K_>yDS{N9{LTt?^@{ZZV!>W(;7+j;$;%PW0-c&t)ZyZ z)e2cz6s782WGnuKmb{g=7O_J_3iBnGN?cqVbDiwtq_D|~%m0;{(v&C=6Hs2LtnSvR z-Bi`T5yZmiI|+e2@i(B>v6Ao(fzO@c9z|^N6(f}1sEVb)@{ilw^2ci zo&55ZB##qkj2wb?W`vskZT3i#-sK#2N=b{|fp9C41~n;q;P#@0E5nI<7zNG;yAS$2 z^nq6ijopc~_xYz!1=aqyN`DRaLfoU)Yv0Xi$5J=GA=DL{Abm8+xCbHzu<2&tf>Y=W)HTv)&k<9QvusERo~j$_7%p!A2a6=tcE8 zUaJgr)~CvXVt?BUao((jZYIXY;aE1JGiGEV+DuI1Tb4ctFSN-N4)1KR^F{tD`}=C5 z)?h`<7S>s_a{JQVeyiS!W?dvCBn<`PFCCZ9(Eyt5M(t|0?faPC@9drQRO}y$x@Tt? z#F&z9wpN62jy|_r)wh;wGUCPo13z}hm0LU$F*$c?7Hzn7RM$E=$zeI2(vh+fnRo-WsB#5U=d0g_@a7 zx%>uXZ2c@s&ee9S=l&ci6mkwktet=mB;3XPXosNNzg%3G!4COkpWk}>tB=Y$1cJ>l zH-|pvc|wr_mkvh zQ!(B00{GM3E}pql@OikvywzT*(BZTqz%@AQhgx4<|LkG?12w?&sC?)yL^rxO>S?Ds z^t1A-j~OuxIpdSv&LEN@y)3Obgy{@=kTN%Z6gbu!(|j)Q*Nu?7@|Jt?UYB8G46q@( zfekHpeqz~*fzT!(`hJK+W6K7oVsA83%c2A@JHO4$7!;g6#nF4wzj;r>ZKQ8+dF1Al ze{F4T%gt(wFH1Y*@3}Qqu1`IQmpbjtXFv5)7ITNdqdCJ{0X1Uzk!4LVzQGoC!Y);> zs*{On3~D3Ux02ZBft|c7nWks)6W*5^!UCO0S;23`Z{LQa0BC^1%f|h1NoROpI{_5= z@}1M-8tdI%yLR0~qhfrJ{}wK;5x@t)Z!Dk{2;mXE4NIO`~&hy;hy=ylpZA?J8#t30XOU~J4)1Xrsu zYF#d}Dw!85J%y=7#G5Pz-{yf+Z68Dh_%XY{_ol&R5-jlFi@rFO5;!66%lr_qQFd~% z?Noyx6O8iskI+!7EVm~^Rk5)m<*!t~-xdIX@LAUPy_vt#{+gx0kY6jO2Yf4;Ps}Oc zSTjSGcn>YGm^)<5e7jwCk_ z3$x1idEZ+4>eYJI*$bAT=Q7p4Kmp6&AWi3w;qLrH&0`t_;YE;XFg0~~F$H+w8@BHD z9YUxen>-jby-QNa-Y5-U3n@6{AFBB~j$nC>0q%b*+lNK5$1wPpam%LV8ua(<0`StQ z;kzMe%4F_kap89{0aXC^VE&^&aIWW3L=;Ur2UDVVMb7#wgih zY-nX=wK1uusA>b|ueazkDO1pZsT1w}ZGMVE++N~jwIQs+%*tv2fb-tR8Jnk4D{%s5 z9N7@dJh|btTJq{uuV$hl`<)1ea-Ppa_fB@!<3D4*OZt+vWJ+9HZK+1r6!iW4{jJxa z>*fDSw=6d`UiWOcfXcSY{omj@T>SI<)1ODXZTSeaSZ8EM7}h|ezgfBOqFD!iON3@! zp`PJl&5_m{>%44Zo^Fidex$i|Q(*Y~1q)=rz)0^48HlbfBv=7D<(pE|3knMIAb-3m z#YV#jJlv!kGiJ%( zoEc=c3}h9L9XqB6sP!vhjDq1^b#pGSi>IW-rN6y-IB&!%hqE%)ISO0qi7+S0^4;@I zmt${DO@ml4LIr5(LAe5gdVWN;27$Cx>!HLfIdCn#YMKyJpYiEyI}Z$As!w#jkdpIx za&8Y2+R3JDcl(ggP}vXq-H9`#J})MX^TVJ*EU?J`Gd5~HVE%TFOGq<R}!Q3 zDeD%zRu7b?b%+RZwM`?Yv|NS&Z*$*O<;Jn+ye5U{A+%?o)v*K|3ux7Mnx?Q;g3aSw ztVy76)MI(L6uvv6Doz6Sp-%uJR|4cHj&=+z{#Nhy-_D)!gl}LR^A4Jkmc@CQb=uFu z5UjZet#Wuy6FL=nm_g$zf)e>_w1 zR#s6_X~_X2rwD`465$Idh&-Bl(u z3)oVLxzr(LVL-0Tja)Tpo=}RC$Zcxs+>VDZceiexA0;Ov!;Dv z%H%fCsQ~3de#z%x12Gi9vIf%d28+2wNHGN%+V}Lw2nZm#SKP12bvyXjv3U~d?R)!` z&w|*Y2W-|EQy|;?9zTA(?tFukM2)Xc1;jW*g(!XB9^^Ga1vnRz~vHo-s%t1!(uXI-Rw|-XO|6816+Hw0;PImrxEa)n;}sCrvDLm z$V8d?Ol&S|&GvLhQAA+wUir}bVU!u6%>Vj*am_wWuHf(NujonRKFZarS06f6$-!hC+~xyOeKF*> z`}S{?pA2SAcVgWQ&s;msxCcL=p;#}cuD|F5e`5x#Q`e&RQ<22CIeG>LE01&t9yz20 zHIgML9w~1rHzyUV2-8N$s)Rwrr`bFl&yD224Q#g%^W>!T_K*&wGs=_`Z%?pxDh_of zufQO>tvQGGKCU1|9LV#0OK!eOr@7INQeeW#1m@R;g>JXj#C!qTFA7}xr`>Uxsj_7R zk;wBNJW<4WY9lE;b%K!2R)#ggCv6^PIh(v?<>lqWthIMH-xWvy!X4&Wvjlc{*pRF3 z6+^>c|B865aIck)zhHN+CKQ(?i8|Hx9VE{odOIL76k*!@_e1y5U04LVyRJ#;;g$)P zs`W{%G9I3#Qzj^zo-?dodj8rqDYTk|gWVp?VQ@umKXaYGzrTjLaPgE|{suK@mxlbf zY5fcJe<=boUkv?Gd!pElaV|Tr`X_eKhL&QE z__7g79=+O6OQ#6PSuKAop(=z_<2+*WYZ)FKQyyS7nLTLMbB{D-jo(*0QlJR0SL0w* znn+~k&fLeR%atJ^F0Qt@TzfQ3(rm4Xiv#^f_-yQuPt&_+-o90`iNb+N-)jajs5_`3WWj68*qO76)wez>jSjE$Qd&=zWWsH`_zbo)vEl;B19=UI&e@#f0?7C`(wHkC)|?u%X()%~A}tHLTJ0Jd zh(Sb1PtJm<_w#vqmk1u(t-^t6y~Y@bup41<_G1-{xRPL&7X&O08V+zyM7!7e?>;?ci$zQ z-zdqhT1`i;KeF_#lR-r?Z6hqtnD6r+LVEran_#+__>N;&bs1;y2LaxVbM@t??^7ce zMKHFqy9wb?RL0$;rTZ+Cf$ula{v(4Ksjrwx4UM@@-YUzk^1O1R&5dz~P6A1O5hwYWeL&6Tpml-?|83iX$3vr|&nCBr%_|>AEG3Y0 z1_K^6wIp%W+$JA}L&qoDL5k0vloN|km~Tx#3Dq*v`IvwhHd^}PW#Rt zJoy{#*dUEZ7Bf2`)mpkm_h`pRIu}=Qy9&5gxM9!Q`oU}phYVg>`crZj{ZOU^QnSS8 z>FTBr^ck{1I9FF42La$h@IoIwsEGNsvuBZ>%Wuc789{5{WaO95yE5g`>HD;BPFa~AIxz`-axaVE;!56w5X1ix$FY@6RtIZH zV~0P+%(#PtFtdX9@R><2fVS(}9H0I>tt}a68yoGGG}=7asXI#~{~Pf7D_~~Lx2-U1 zgeEW;E1swy2J_oz{=p5T1>4@Y>M&|s5 z3p?r(ZYsBgNpE@k^t$O3PWJy2VPy`pR!n7+Wc#Yupj8tthIEmtcf2YsH35%U0>?T{ zw}8;^*(^6Sfx@njAxksj>rA zg~&4BEjM*#Vg@_L;aII=C5~$-CGUtK;||b2-6KJil)CP9#zjaZ)SqkjW4Zr2OCq*G zsHPNw02mcO3bzEj1wg4yC)Xev!ktv0bgn+G$4z2Vr@pHrSfP-y*BL&adW&X}oCk&5n#!BbUOE8E0e{ zbKSqfYP%1?qjz?7xiZ)F^9>*5!WaeA8VE*(UQ5?3GWJS~w$yAi)k6pdaSY+O_BmW6PBYE3}s@ zQDgd+r-sr(K{3mK7PTdMR9z#-9Le*gUZOUfNnjcT!(iV2y|+dIFTr^4{M9?sjUqY$ z#-LU3BmFlf#1{dz*)MbrlEH=`J$9Cv=;@t&{^CUlYdta9GbjUmWnIU?JYRmTskb58 z*J#Vc6E#{<-PF6LBcmLU*vvm~XEil?mF{u9OdByU8hxqn;&f*HYw`3Q{pU015H19d z8`>6=4%{BgJ<*_8m!xyF12k3AW|3spw!sJ)eE$2D;lnut$r{%+d_Tl}!woNnZqH)a zuLnk2eDnb3d<-=pruTKfZvKOIv=q4y_t-ZL_J=G5E9&SZsf@du1ED^Zn^2psZIM$!Mx^88O~b=<)4oa9C^W?g;0#gjY!|PAL)So`O@Aljj5^+_q-7# ziG}6*n3A7p%$&#Mr5;M+J@(niYxrKqmoq`#MXNP(}Iq-BwrEJ$+M`cSz#_DexQ1-`RNM z1ff)CbXuk`EejzcGz$F>p;YsQb3rv zLWC9(!QTW~_oV#Fm;az`qGZ%tt#+Fs^$aJ-83T7=<=~6 z!40p~2r^1}c@Lm!wS42F9jM-9H7{uJ2s)A5f9%t(TgzOX>e-IGeEwXe@BYG(=T}ai zWJ_5Uw*#gvnFgzMCer)pkt6qNnJ-U8AG+`|Hp~k2RDAsCHP&O3^L_ucG34H{`Ku+| z5PJ;2(i#)RRiCZv*t!ce%Q^h~-?Ay=v_INS3aVO{!8tB#YZ*iBtd}c4H=XVD259$N z5H1QzjPsO_)}y(Kzdd%S8EE!)1n~>R_hFddKSE0PhB%kcoVF0SnMhdvPe1d6$Pb^* zH87ceaqU=wpbr2^xNtHaG_DSXjwK~YqMqYKI7Ma<6l4f_4#DWjloZ$GcnstsT^Gcs zs4G+eb0wTE^IN7*1Vh73FO#E-`l108Y#+p5`!4wn$-O80X1lZYE*`6*G}#-0FDkB& zGbdX=?YcIa!?wHrf7|vfQ`%OVwa!`6r;W%p*G(*u&W>8S?7Wr-IdQb*v zU#<&+=NXCo<&y@6cu4GI31%?X=lSZ86nEkU#0eJiE;LStad8lI3I++y?1X(IlMtDg zjQh0@+;p?xLPna>h@23${h1W5-RTOr$W8Iom{SWLUiWX=dF)(t1C zfYw4rMHr+mE|t5PRMq~52aap@aY9|~>3;UFZ-%zT|KZUKfikJP&Yt#I|Jz+=={J(u zU>G;0hd))HPN|?9_^fTXmv7iI9Cq(kG3o$s)#u^Bs?ya<;BGvJd{AoM4LL2a;68tU zD5DjVCJ|Xz9TwfF2~JKMV2x&9S;v_G4EX&i+6|K|)P$WcPO)4+)lQbOf@7(Kgpl%S zmRYkRGuAQS84j#)e(FxEN%{|(lu2NcKPEfl?-Mh={@Oe&Xr7P)49}ynRlVyLnj??~ zSorjRZ$9MVzv&e$=;^G7o_Wrw)n7b+{=91%prZ4D#=K{pIB68I{6CaSzLvS-;M}w= z2(W3=z5%#ei-{|}otKV-pcvu)O4xJWG{UY2sYeD|C(Odi!U{dqef~;FD9Hfm#xHov}<)u7977xSn2nf#MwyHA|p zWXofTbNkmSW$i?^zS5`9G1$0Il8JzT$4;E6i8b7Yg>>aD(;fv>c~FDp=DzoL+yOQD z3bFj2aMIKbumZJ*cI{;pb!h%r&w7XAl4(x|bHOSsAiFKB>vldH-6vG*h=9$j^5i$l z$a5Afa6Wbh0Js$KFBPl>;O`Ch#{6+U_suZ&G_c;2V@0k+Mj^f+Z^u{9YyK0A#0G6` zI&Jid^RECoD3T)~DXAFF zW;d+SoVj!DqtXSrxv7H0jNmOn=57X_{W7EjRlXHZ+lisACq<8*l)&G`i5#6yh9<66 zW_7(nK0dk8Ut9(cAR`Cv<1y0kPRpsa)RztyTxRb3mI_=V_#(J265xAS>^r_~>N%3| zVBWi??e71sQ^d|7R6@|_zJiuooSg%n?#r&ddPnId&(4;ZTQmUQAnGc!H-HLaOXwi* z>uK^-A$3DNJ#LNc)dl5HDJR`GLek4$RbskM7^-~ge7y7LOG1%BY5fJd0p&B*j`4Wp zKk8B572~}ghXvPCiX|$fc*<-YB(QADV^c=AIT$uY7g zq;r4rL~6?+Fv=61dJBL?355E8Bl_C44MCsYcjGQW9&m77x#JV7ydtvy^>XfC(GXe{S;YOdyd zA~xklBk?BD&!^0s>B{wbE;(-c%zXtnK%x={9q!;Qy+1+*u51(zVH{?YpZw(q+N-mXK0ET*Pb^MPp)_-!$= zeBqkFFCh{M=*i%()-@mj)mQR+#x!e=|D5$}*B)yf+%$!{*y&>BE$S5aF$kjF zq~d$7C+)B4J=JTqj~@1cF6q*C=T`j=pPjkUYK8PfGWCQuSPDGO1rU`pexl5oCBOCI z+8ocW&h%{3qJh}>etFjMJ9Vi$jvAp%ihFzA!XM09LnEUzB<#C&_sEqIkkkyFo$o#4 z{Pp`cSd*@YSFL-pchCWH;Gr|tv)-0Xn!bx!c)Jc#0|ECcc({i%i!e>v zBx^hyyptT+J|;6cU7-r>nuB{PCuiIj=I^jXO3HwYNDv&#XmT5HIIrHBrGpmj#UN2V z*j3zz&MzhYGNB^ODedgLy#O57cx5hn>6h-E?-Gty%~?iS3$P-IZv8lyVZRu+Kt^u4 z?|`$uo}OEcF3RP3khR!^A)2Q>^@quM8f0sgZ1iz=1}0FEsJK*k{`{*@(?zl{A4J27 zcCFDLt5DMl9-QG5TLEsBphQGcQj)qg(So{^6cbQ0^Ky3JYw!hMqht5XpcB$rqJjaA z_PMOU9TsGB>z2Cxs9piycfzwDHw~{SJ^nK?G?ca1o}Nz8pR*2wy6ZKPOQw*15xZSj zex(MhZBrE(@{O6Cq^TiX&ieZyVXlmJebP61*jHGF?$sLw$+d2JJ`l-L`|Q~>F%c0F zhyOI1txbv=Q192_nS>k_U#uwJz;fslK&KA3ngH;->@iR~K29%pw*R@dy{~{pd^O*d z>$1{cv{9EblJ7`BJ6QtA!D%(5Rv+ZxTj6%;*Fc8 zYCSs;%i{~8LJ7r7B7@gCv-|`ppjO*xKRe{Ja}+4)^?~oOYJ$$CLKok5RSp1dDZ-p8 zF$IOn0gpXJW2#LtZ7{u0@bvz)^IfxTpXfm-jWsmu{buy37*#7aeaY6JC{8S z`a{FJeUs6$jR=;PQ|T)Iluu%|A|dIc=n_U+i8X8xjiuLEQL$_l2P}?(Yu&T|L30MG zz#_3v2C#xf*uW@{8#~lAm{z;$jUYH7l=flpGZ)wh@bd2R)3OV@M?E2mT8Ny_!6&5r z<*G97{47oEV8MYk&JBJFZ!3vV=An&_`I(6T&4xUYQ)cu_#zUS$c{Bf(d){A4UU{1d zF#+7uj&y&GH=gej^fBygiEDG5D~YV!DaZ%crD|Xn(cTWi2}#X|y_jtqgG_}e>dY>% z#Xh34XsfcJR;TL(x*`G0T>zQ!-_5j#^zC{vSI^j3>9JOeu+KhUps6oF(#|sMoVkfam-YdYIa{n2@<^ zGffnZIVjkYwIk%N!W?x2=8 zMhN=_zdKxM+qE0XSZ#z0`sg)pm85wHk7)kJB)bHB>D^<0-`os+TX=o5Ad*obToTUV zoIN|dtjsjhW5f3G`zvB60c+$@v%zP|VQ??w!I#9ImMot57P<+t+rgyazeUFtyqMY6 zjzb5YpX4F)8aX}n+VE}ELH4f#VP@5%X%v7g9p{6G*(*12|*(2ET2LWN+Cughuh%^tSscchS8t2)MOSP$po7=6&0a zo(A$k2DNlOi8Uj)insmL@!58fWNZ>_38D9e5%B*(q$HykOH|S|x0?a!t z=wkl%Nw&b2OFpZfk!le}ON6`Hn5dv;a-3&hRnk9oDx_zNFb|r26X3ME<;e7+qT6Ok z3$7)b-@Zu3&gCv|B^4QB=VT;cBiy&Id%{@sXec;!wh7z$GY%B6mm}0@K1jTIfdaCs z=zVt+0N0!FQ5MT$1nK5wEQT7r+aHDAq=h3N7ozK5Ff8}u$p>6hVZmE6{b`2L0ghqY6Y(!nWRaLDkZHlR zaHZEJB?@59_g+FEDHLNrq9Dr%n8@tlJq^P9818L3WI(Vi&)?fKo5P|3w|qAQy^TLX>$L zQ=iA04)KrNMP&K02SF6Td-BUKd&`%6;B_t8zVPzY<7N;nFjw}b==7a%yFq1L($6;t z8duJNxrysykFg9DU!BA1plZUl0NN=~ox9NW4o!SlkY;ZW9{`Ka5JkCXhkc$^08c$w zTy-!=l^G&Tq%uzwq;H65Fj@Z5K<#q@OU|uR$Br>W*U#gvGYCzWNvSXgA-doJ6X80Y36_=5SP0C*gA+Ejk2sJ=+ zyi@m3g6kD{NP=Od>YBq}dA%`mz(sYIK*V|x$g}O-wacDV(DXZVGCdZIRL;*|VKTD= zg-*91moKR|W@=2W7X1WALs7R=()$BLtswOtPC>DY@bT#}|0IOLw+1j4l$%@yG~VQh z?1FFTf$FlVRnhGZmhx3yilkWv_+u}>Wl0gq4q-Ru_@^);#_^3YutA9OIx>whUyb?# zOR(K;$(l>%=jMIU-h7bgr)N_zuM}t-&T-K*FHNtj_Zwb zSp9no9I!On29jwam0ytDg-L-j+cWObdfnm4ov_36%rZ%ZRuwN`?)qKf;p;_`_P3bc9r{1$b$z3GyY)D2*#4I;-a0!Fz& zZ5!HH38z%4EljD0w;I#lFg?_OB(MMkS?D9oXbHp!d}(QMc=vtTB#4qn=$DzDtNj^! z%eNJKaiPsibo%31T8W5>>5{$)gmgvk^+Bs3JW2FP%QlEM(|9A;e$l(y4 zy&UCkos1cbNC=j`U1tYlXZDb+^uzVIzp77enY2jP$C9@G{g*53x1~FNRw!)kycR(} zJ+ZA6K~127>B!3X{V%RgF~Y2Dz~qF9^DGL0)FohNS8z7;e}lrf>Hapw+i({=4viDUAce|+FVERkeFyG=x+|m$KARyrwjDTjZl2s- zS_tk=13%;8+4weLc}1UOEtv2h^o#AhBsNG_Bh(WjGTA=+(2ND$rgApDsSNtb03n*h z)I*PU4!V7=@Qo3XUywxGmsbG^2p;k=p5y{Z5UADaA?u|Gx-`kyKxV<~7pDcT^H-)zx%Qk3BA2+M5Lt+L2{NFDa~s-tKNB@N}W+E zpwBY-64aA0SNn;js@|yWnmX`c*DjJ5vPJ0NEU69zNil2{T+b?s&pTU~Pv`2?C(A@+ zWQ=f;mO>_B70Uy9&Y~U1g5Yc?bL}dK7*y?}S-YC|3=YcoS$W%bW88*5yjb({QZn=x z!I$*FFC#mbAcRE4Pmgo<%02`d&;z!7L@v9;`?fz03T0y$-uU&{pd#}f<-y~@!P}D; zaR315nycbBl!{@`FPXGs)^0?q*>ybb;KU~V-yPy?mL!Xs>k%^UnJ3W;bt3hV>N!Q4>`;FD^tm4+WP^S+%LhvKL-v{5rDu*o?cg8pyH-Y6o*8JGLMft>E@zMMX5$a9ht9In`iPkA^wNU zak*I^|F_D|gmV{SAsjep;l)d2HmDH18NEf)D?b2nz6l2#-}^~LP}xPM;P*ge>+9}+ zy5^K!`sMKEn%Ky50f!s7zU%DjUcGuXXL*cYPY9$XOXEJ^=A-N5(b|9cNJaY=$ra9M zae}@(FK%F^ebJ05-IoXhoPygKM|Uy~^gWWca^$WJWjsA9wB|v8SJ?mgN9KF6w=glA zR7n;Et6zU+J||%pB82i%Kj9}&p3D&x+;*>sDA{B6JR^32{k#(O!kus4oW3ue3Yh7t z(*A9anFetTPCxd%$L&@nq)ez&X!1K;O`4+qTjX%6L;lkcCA$u3Gk&WS*5&Y}|bWmM1mC1JEmts(kyq;j8q4n6%Y&vN9O; zOR5u}4176unq)D^5-)&d+_KNK<%1c)GTv0ETn@{kA=?JHMI}X_8Sav1K~Rl{5s@y2yqyVvsCDEPC$laTfCU89?1pGB#=G zds~j+n#yt{FO<&cI_?kToei{!u_8hUKQ8w@_t5ZH@A865ZZn7(vcy*S)93xtQ~o<{ zN~F&l*}{Y8p@$K^h66fMOaBS;p$8(*y@IWWriEZQ8D5rnl3-WoCyF*AsouSNuBsf^iJc}n z7TWjhN2s}D-ukX=CF(>`qM{bbP6tb_{^{v|he{pAR_2z5Uu8UyGhtgN3K>pjh2#yq z9#B~y5G2;Tkr40ElH&DX_INGwbVYdI@w}qS3 z4Zxi)Rjyu02$5xI0Nr%HEsIXaM5;3KkxZ;5>R{$~%wKoR)qwKTL&x&P!G~>pJ20Wx zJ@>JqKsDe95`n-tTvy^oF#&xZ0>2NQ+=@Z5v%bds`IWTW-d;6K1#^V5;lxU|sU2pV zF=9LuN!C9i8?Qa-s%J2zk*vS=tSRaAm^uo4y3+`3{@G}2A3tr18M|EB;|A9_mz`gtx#OT~5wZ&q%@0%#}S?mwWnb>*S7sRWwkAtSP1z?1F z@Fl~BsJV>80q@&SL0A<=@2sej_O*Vd z|HVe&HBPe^{+0UBnkeHP7R*V9!=yGFK*3NHRGc2K>wNTmGIa}rrJo<9;P6ZsVcP+9 z2pW-EO*jnfjn>k#d2DqC+MhDfPYQVlzF@0ic?1B=V59#@Y(4U)@K^goD|SFmhn)o{|Vr(5+I} zE+P)PLH7Ko7>PAHICPJTT;wJJ3F1aus)Ib}NHM>aKlk~5>Hu0O@F0_!wtl$z`8-8a@ngaDXIS*N(#`}EKv+3 z9gB6PhHXDscC31PQWTX_{Qwf?)v0Td4Pk^OK_ zDTo*tVYfpzrZFH|sx{nWt-VCsbnfaX=RHVLl35A>;f*8TU-Il1p#T3gHKM6VVj6W> z%cC7+(g*4Q+4tk1PG^ELN6Yd*7&RVB1F<;s<7W7b|6ELen_APYQK@nBo!WJN=Xz)@*jH-#BKXOK`43s#I* z>n2uL`zH(Bw=`x{qgkpy-9zIMonIzmCmaMbc#75WIu}=lvU9a5;_I#tCl+G3DY^O! zJ`g2%(oTJ_y~gM)mBTUhH*n@T{@Z91KxbmmaO;h8U(pZ#cC!hHf<%B|6U4SED)mLN z+S&mWP&KZgMz7+xHHM?9Q)^f1B)x%3JB-tsC&0LF|GScnkPseC4An%8&yGs2A20rE zhg7{dLbvp~0xE%Hc?(v1m9;S=Zd{jY{p@k)0wTSNH8sdQknkZ5nr^_7Q={N$=4!HHb8yX|0+EWzfdluE&=ENU5*BOlmEJP`+{F z#!jopw1d#!?Hoo4eDR3{N zowC;%mO6{ncOvbsPU6t?Z?qCm#e@>Xmhn0w|LItud?0?laphida%<}3p@7G-q&oWg z^^VjC))JW1n_ww+%CB9^I6>QpA}tD~Vw+~3_Da!4C7bj{NYYS9O+XaUa9XE@TuV+C z+)62M(%d69x+dO5-I;UCPJ%Sk19lo|8E+V;iqSXye}f*Y7o*FB^i`6krRvTL^>zdl zi*=+Zb7r)k5p@1{_H4PDugCp1Lt6u&yEdqTk?ohkM9IaZDt>n*x%IK#lo9i5P|qso zJ)Uw7FB5X20o!do#O}>PkIc-1q_-rixZ}UiAhnXuU^R zz|{8uv`?Wy8W|!5yK&j$nU+sd2^EYUgP55lk>NCJ0w3g8OljCAu(E zCFK2+HE>^7uY$;IbOF-R^OS#Z39FeSXKJZmc8Ju#vi`F}-sFyy)@l`ux&cI1>Qe>H zCV=4?lx%`jo@HeB{~M`n+!zFgg+6pE);rl9Alnf1l%32yL8K`rEnVEk*`MBr@-4s1 zyPY=m1%ZJ{q61Kj(1VWeDOGj(^|5XgU<)h9{Ca`7+;)@yx{v-lDD0T`U4p00yzW6^1rjx4~G>4}UN;o)@WW>fZpJ=uWXz%F? zDmgC`Jd}F?G_WEx1QP)|>!JFp>5Jxzbl;#F5Ks;~OgyV{%WYs0~Y-s~Oonz|lmKH!rwUsmW@ zIxw-Ku_8Dd0tuQ<46DUVxJA@FXS(>uq%$#PM>S>}sq_+caL2Oo_@6tE0vf)1U+c!( zR@o1qzkJDGxDM!}Gyx_oebKrh9$TzUyF(dC4?;g48KASVQ7qZEz=nt~!fhx%avW>| zv)cgR4o9962RWiq?5$3%L|fvqIS@8U$a*pnXRV+nM`vfOQ4MNh`6h#pLomFgRbS9$#(wv*X>!P(eT4{s2O{E*y`YZlExI!u8k z2`83E9t4y1b6a23IjRHYite#lY+ic`KjPu2$FbJihrXE7NqY3>Mb9I?)SEMnkT!!7 zCldRaf(m+lZq?&@a714dIcZQ9*jOk7bS77$1Bs>eTHan4w&;KqP2SI!LIKGqnz`LJ z0APQ?T-(2;7Io!d^t)F)V$bt4M{_Wc{GzsdHTl;E57@9epv9;A8Vx;!ay~b<50I8r z>`(Zb<9htQT-QP-&W1=ZEb!y$v@ zIa-=dzH!kp`r-Ib+6{eEfRxStc%{nR-S1`=^^3&L4M1({>4=-HXhh zB9gejY&bc|=}6{i9lZ>k=$p#wl`A))ly(zPPO|Z{DF}qR9pOa%moIjc&JXusEo`Uvj~iPeJmVomfEa02YP1WaUjxNdt4l4D`IbyaJNGte$*kniwpm+=>H?Sb7HK z4`S7~o_|sC`4Xre<^Cw}?*^E+3GJbzp_)(LCQrn0=YIO{QfBVcUjX8~@)M8R)P1zy zq_jZDCO=$YQAiV$vd5b^wjoD<*1CDc|DX=)nI~Thrco}a$C-TQpvsN zCPFeZzpUJPPtV^yGBD=to)t5SCVWqjDKMpl-#;<^_^W6+e%=dXh(ry0W_wC@u;%d_ zNSMOeKL+%_-vaW#K(Lx`|93GWXwo~2wv~;KO4Ja@3=D79x=2MQaWV+Le@lqyyr^6uNP9yrnBg0{$J*Yv+7RIl@`ZcPBTxn&a6W$ zxD|8f&elV2*al`p226l~AP%#|joS$cq!`w;weK~1jyq-x5#4@5+OJ&`F{Sl8erOs^ z@BqDB(^|PPnh2Maxry}7(ASOpVth^HYIFoc&N(;wwxUIo#QS&#(!UPYm*Oqw3D zUCK#UI-*Qf3{{$44Sl=UXay1Qsy07E3uFNkQjRFnw+?2d#VKDSm}Fn#r6cq33gKYH zZz5SQGC7uw6bS6oJ;%g9EON-SY4S`gj1^@j1Q_kyot4uXL*Wu-EK{`sitLcLn0bsO z+iQ++c`@w*zCtY*%oz9SS0pz0@7g zzG9$;aVFi2AYXya8}_@qJ;V6|TupHSH0%~Q?ai{*85iB$M;QqVfl89-2E-CzY4p*V59Wq@D;gf#G> zBTb$>=`#9I3BZ|5xtZ_+MHoGG{YC)SePK<%>aO~GGx;w(m6bmq6(s|xQITnbgU+*S za1=e>b_WsouRQq8D0t47rlt+F=%gXbvF#xg9=7>GNTp9UEJ)}&i0bq1PoBVe&B0sS zy`XwhlW_>dhup5vt&9d=kwUV}A6e|xr&&C{SQ==WYoE2(49g9cxpdShW}*(sVkv4! z5B{>2#HO?mmM^-Q2&IhF(63j>9(0Df5WSo7dp4X!GlZ;CjY9d3P?ecyFI>Hh;Jpa< z)UO-kO(aahFNzuZ>{3lS=&0QX=q?=Ghu{<~=)@5N6?6a1b36}Koid^+Au1}mKGnLk zD#?n7k6pj5GL?f4nZc3x9c7$ok;X(sBFaxx{wjAzaon@Y-jrx`^@~EaO_tjZ!m&tq zET?FYlNB^$4x$o_1?ZT&<*vmBU>u9I)w#EVo&{q2%eXxqZuhMd=Cd(J(olvqnl<<% z&@-*;r+nb>Y4nP}Oschkt~5w&?{|a}gtWlZ=NUUW#HmNLA&N#yz;S&3_bdOLwV!&* z1_I}D>3*BE4Vf(Ii>yU6OTREP-y_vZ!K%M%+HAXn5Mq#tN(m&1zgMbCnW z>xCK;_MGRf2D1QqcTabGsu@;QQc|*8t)O>T*|K>d^1DmP*14=Dnz$dH%s6LzD4iot z195Tg`SZ&ceeS^wJAG2SG0pIBshT~0`Z?&s+el}5*d{PVB{#+&n`@B3I&lrzC|L9V z+;~1xh*h2OJ$J^5NiG20%m%_5j#fp!pJw{ll!B197NhT;WQRMPpt5!mlK;HU|7M(i zi~Lull~BA|xKBOWpQCqSF;R~yx1G6z#1u$}8cp}112#-{yApSXb|~9dLv2^%`73vy zMC|=M$`(o@yv|jfZDaFrnO884)-74Rx~`6IE3)svuqT3eL|P07QH_M*jBbiRF_u(% zaGztRi0)pxxD;FFT_xSv<9i|!hD#Cr?){#WX_vxl3thVg%|s+&5(dull z4*N*|Nk1vKn|8UZo8V=>RS4!OdV|o@`(b5EojtqYMNzOZ{6G6#SFNr&ljO*|I& zTA0nFtver1o1pmzQSRWmRd=V38-fUDN=@iNhy-AUVcQ`m(#Qp`!cv>@k(8deD<@O4 zBwrb;tW;bwTM%t#zHGz=b{lam2Yx3fm}4)(%|RNjGZy?GVN3bQPM*^pGMNC=Ho+wRdjLWppIRe=MzFW2N(>hJ?U^IIY zmzo_Ap`UE>k9I5@&d!HpYtAlE-Dx0Rw{Y2(vuX^Z&&_5`kdW8Jy+C)tSh*U2OdIkO zHi?XTj_Q$R|xiTx$R$gdhXgGj|5-9@X)|6K5D zdnfj^jBSRtxA8cI>$5V~9`WUk`=L*9ZUQ z=Gu@sAC`RxmFjD8MEZbgR@efE7cXACMwUEP8yf&f~FF{m$aqGMeYlt%lpY#Jxq+<-W9G!q3$(L61Tc+&^C6lV4YT=}b zWO+Sm8JorFCkHPd%bz8)`1lc@VCUIE6y9o#$Y#$-N=#I{|6eXdVLa%lnRX+aV|VRV zW&8Rd)>=Y1A;3Wtm;GJyz~m3$>j&559&Q(hRF1cHXGlCx_hlL=s`jALCuT#9>6o{H z2_UMxoH|VOSX%I_=d|~lHu#7)b!cs)4{1Y_^p>if({#MZ`7t0-%pt{F4DJJMNzj=y z|Mcp8AW;Zmj1fJ2)G|)F<*vUI#VF3;tPJxIZ5XKBSQ^J@cJ%e3-(L^&0ee;{j%TcV z=V<^yc7vMYot*q+fVfH1!_o5U7$!hQ#ywl>n%^HznhB%jY5%Y>hY+rWJt%VV^_BZk z95N#8JfxNbHF79KND@t7w9_s)xG!Q1U93NSA{v~IubKke@H`*{5sj>WnN%48FRBJKB4kOalqE`1BAUp)WG(BFCM^?6$-cCZ5{k&KnnKp> zJ5AXgWM9JXdLNNf`=bxrmujb@)KJVqeulrgEjs|g4c>9%!!A=k`E}tlcP^+l< zphW{p70x5@U&p{C*atkV;8dtBoro}7vDz0=4*4rhR8%On(Oi z$O054kFoeszW@I1*B+a#-#-Tx+IC_Z9(q(Uq4CV8LNcBmQ)|I?7pRGQd)(*|RHSW2 z$2{c3e4XKOz*AqEGYz&Ry{lP;52czR=}h|W({L+&@;+qZs%O1rdeNiTVx@6!VgAr9 z2~HnNsvcaWf1G_!#r?Q5Tn+jJFnPN^JJFWOB?WmsZVbSU&L$2W;UuJ54Dfzr@rf1D6kiKchRGRqE+YI*H);4CZo~r`TIn3vPA6#DDy(A3HhM z)EKeY4Z=?O!~S?x=wcF3G+BN9VG*`zp$^m&r-mE-c#>oMKcB&-q~>Pbru z%CM$%&xD*xvy1Vp#hcs&-|eB5iMX9vl{9uQyly;L*fJ1j3+*Z@7M&naJNQT=qIcU9 zchSHH9K@hn!;pSQiGI4nrp&Hq&s}t{>9x%e69Qrh!&?=E{^2*?JryG23C#2!0;1|3*9FpzGt3B;1R6w9{@~9d zD+h&2JNGZ0h(2SIXORLzE^%Dnfm2xic^_H-^CDr_>cuGoU|30w!M$y@o#l#}KCb_t z(t*B?m5`U}uNmuaT1Dd+lVD&xfd>0V8z8{ge`Ji;n*rjuc zeO62*X>5SAi(ZnL5bxaVw%l9R&TbWw3sj6n9xZH#As?d29)no#3+o0^oUL`V9muQv z5kt9FZ$Ve4|0oDl6=IWq?hGlpJN#DSr}N$G(a^`80;M;cXxl#K!A$g~0~RDT2a9Y} z8Gu^co0|4;cj3B!4tg;iw%9vKY=6qL3$#LfX^8y_h9Q&RCz4tlz6P1aU7TQ8y2Afo zWI57GKxTd%kNkEoYv;ihHXt^8o0A4Bh|z|c%=fF+$!d^N-cwnKj-<%TvluTj!D$bd z*S3l4+!jAJpCfhY(_W(bcC_%M&L^e*vJWb9Qjn2n_e%Y(#pi#lxSug(-2jhzSLPc`Fthjz3ibJw)lJTAL56`sX zg^3%s`_gl>ZC^aIap{TlwO$i%aDEwp`nmkKi30~*_D`jIPC2jd?~cz768u5<@N&1o z?>NG?N35j@6>zylCPvtn+lS$oe#5P!G+Jqu(8)rVweXiBEdr{bRPl97NF^}Naac`_ zgiA_>#HqzR)k(E+i*B7m^O-M_mod$nGcxz%dgv2)tWfJg<^p|yuf?5?+8{^#ND*f0 z{o(wdf2vr=pkSI7xj9QA9M}YTEn+Z&<)2>Lry$P!Y+pULPysp(TS?QD$_BNq`K!eQ z`Pu%ZC;1D6T5V@mvesOSlbYOw8U;w8ewO7%V)R%6{{_7B5!Fdy~#l{QAwCHe(KijE}Zj zlrLL#GZ)=+W*0D&1!~-Wj9omPVj0>|&Sp*!i?tKxNH~^3)`dV%Z}F*ghZn>UvTc>? z)GK={5>`PX5?@!J?Jl;Hlfqg`+^L_lXtDtyw;%e-H?RG<>cYYvOZa&MlX@{I1v!h0 zNCE_SQjWbk-hbWX+`bijfT5{>WAQp^3vC~U8nT;3go4SD5y#i^WQLBii@s`A3wJ|M z^`V(LWF|L z+BIuBtYD_!7Kl4G<;Nb`RD?d6?N3mBiJ9=uBF9qpjgQ%5NG4V?jV` zWf-zQZ1pW)HfXm6*IkJf+P(D0eh!%ENcQ<65w1-%^pf`CS3zVpa^;t7MSKgfd=c>H zTk$=>UPy=4l$Y*dwaB?ab98 zORZf|b?AhC63ks`Im#mBw;o|Lpo#@oM>Z>DJLwcD40p6yML|Z>U~_RlLX zQ@tEQF>ZJB?YV2g*Rq$`2n52sZR4g*fd`?KX+=dnLQnFRNC`nGO52q@`?zTPq2M5# zA5Xab_^xQ1!BlUd7E!9+iB^d^Ad@BOYn?7~B9NV~n}rzJBZiZz9?+De@yg&xH;2l> zpC_LFWo$S9>;tQ=%lETbmmKKV)o>u^_Ej>TP*4B2hvpFe^BHHqgDXeoywAAyS4QgI z70=@}ee2MOxb{XvxKT<8Tb(*}%3IV@RM&ar3QBr7q;5i8BU)hm6c+c%k!nXu`<=k^ zAz3G4V^nh#SOrT6zEblz+)w}K)BN0N=sLymfG5+}SIiN5@!*tE1_ITx)31E?|F!%wHYDi3r4NK| zJ`na&4rL$%u`i!3oEf4iOlrgSa_iTxmz3yu7Z)-mU7cv81}$syG9z1N$h{a~_q~A# zgLn_<>6xo}8CS&yHlVy)ehQ$VAMt4cBon&dbh91WZ4wssAfgXw+2_&>Z|qfNa@n4G z`R4^HI@8)GQW>snUmUD%?OaD+#Zi-F;)e_;enpSj!ce!HQd!4*Am>kVW7Ow*swLa|4sbY`?pea$?iLpezPXz1O4 z%=5?DP9>WM5_<<|(0Z(s9n7owj-ehK+_5Wq_Uyk$BoR+wiV!ei;NWp2!!=b{ja zz8DR&$rP*loCNk15rRDtUh-kSMqy^Sg0oQmjZy`T)-!vF=iFx`>~WC&E^?Vyvy~DQ z8e-_ofdf3WUQ2%sZT3l)Re;9gI);Y9EU~)Ry6GuK>$v0+|FYX|du$5>-LhqcLE_3M zV^5vint{27!G#M!C1#b+HsS5qKeu7MqJ|}m!1)&Ivvzh#shzLDiPH+PMF~RuFKl)0 ztUtIBabYe^uv8icbJpp@U?w0{>-1<_tryywLmznn$DUG?58odtk=MF*!YOZZN4KuX z&vPWFiy)?Me?5f-X2>$*4KMb$%sw*$m!OdT7^*o}RH7{FkII1#M&(impwH#yrhEf| zMqzh?Ez|OYm3OWtYl7m#2!=Ek(1)z0bfbHhREJ-Dfvk|+eG^6#RvUqQ0U-faa9Cw{cGEFZw#N6pdJ{|Jq3G7l`xsp zcz+wXRH~y{i0$!GF{r@L)7FcYpfPck+40)7;o%!R zdpa6=y?JuiqojA8Dy!zMXBD50r_2d~_)d|5a>0Frby+JTq~BQS1ai0GQhtjQ|FP@=ZfdgQW@em zkOdy+F;2pzkU!NBx>GN=eR+zRdUN9x8WA;c6b-5b8^YoXa*q7GM92Bw*XO2p`X`%5HaW z_Ke%-6?4N4VtNf)(crc>csk@Mbmr9hhHur}MU4n?rg>Y!t#u-1ssBDcQAS}{?C*JA zf7V&-x*Lw_#6WDCBYW&R^l#k89r;P-#=hpsE>`(ur{NgZ3Ac0N!@>~-m<*8Cz8y^4|d8kNwbj5Amr;4Tf?t!6xZR_4iGC`m}PAmYhp9f-Pfi$9G zX7_a-wExWIlu6JOe?kT$DSXuhyY|x4ZSRL&Zb0dq<*rMwP(S8lB=CvIDZuIUuWcsk zOyHPey7j}dHULyqEu0kE;iu+$R`82MID6uJp@z5ipT1~zv-T5P61}dS5)1Ea^HR{f z$VlGCuBlQ!ov9cfzYWFX@@;jsuILp8AdC9O9NP?#djLwtHc2;(Z3Lc1>xzfoMw1)N z_d5-T=d)%YYaaM~abgQ8SwNtmH&Sqm!{|G;3_03fnqWk1xD1#4DIL}Vel|&Zt_$t} zK@VEReU9uq4@cR;c9d23p;{kz-4(psVyD?|(~7)vRKhVvL>0$mxEFSGi8y616yGFp zT&;UkL$AhJf%!=R#_z_sMVC;Y7@q&Rcw6q~7_Pi%-qBtb!?P+4D^_8&E^$u2j;5lS znZ|ELKRx*^rNQP_r+`WKwsE89jcM&hb6fz^)uU(vbVvG{t@g%(16LNM$~`!Vb1ENI z#8%Yez6B44_tM*Xb6dV4&W9aI_32g)1+larA#7>L9{W!W^`V(@-3@>`{a|wKoTj24 zK7%Y`vITiY#sKQxY#RE2AE%vI0E??}mqkW8U&zdjZkyC&BJ|`8($$ zlqm9>mjYGUC#G-24NLatEXnD+h;|%AF~W1U)dmNV3=~Ja`|7^vRs%>Y*a0l_tPqZD z`z;6hj>_`Tcvmgb9z@)Z!))NUWO8RBhO8x>{))i`>NgosJ-iyt8{T|28ExmQ-CZxA za~?uUvm9MTu=|V!9eJH>4dHf>JD9%9Ba0J@sdjBbb<4yfA34+P{PNw^SX8zRg%2fs z>-P7OSOg52(-ULQ^w~0MfDRT$ zZv^^@z8NqM@A9frOE=4%wicS+`}qhgZk5r` z4<0;tI?eLt+=4bESV7fr1lLbc0g%ojd;x10t-kU5!m^;>Pe>pMOS;7lj{>1rMov+d znci#D`y>)>WH4GKa6L}DUD-2uMF!~B$dsb|Lngx1$Ip7vMtclDgnYxogrPbq*i{3r z)MfZY1-ai^+FvPl{rSvtqjkvmx&txwlCk2=>*$(UNQ@+j0kchf>|jx?XHOupwvS5g zKG?*k5cO8iQ{VuvRHC0qTIH(!9$elFGeOitoUTq~s0&?xm%;hg*SEAvAwnNqz%XCm z7WJ!Hhq}yI=O>@m#DwPgah`bs5I91FwKVu*wyvgK2NXvJxv`eTWL_H>iz{{~pi3Wt zD)}&nu%z3VV;@ExSZHM*3U82LZz}v=2aS1;(pFf1IECpjsOgqz?t8eM*fl^mozhbG zjjc#Hr%;=5+19&}Fl=xNacz_~;AXz0C9go`vaF7bS4>{sfo6cv3;KlHKAK|~a1Vo{ zpj|^z#MfzaN#bkLZ=Qh`%G5i*DRatW$y!kfijy-4KgpX1`QbhQhbF02`IF+^dJni zRs6AS!S<8@DRy@DO}lrWeE8^*thVRuMC1n{ub$hJ+|FTMee~vs}psP8*kX#0iqph|G+3UwBbiaOteKVs&#J8p5F5B^&1_@t9wJ- z2{gBO&#iGR?f-GANz)VV0~E}``Ic#&QG2Okon1HUUg#=_?Md2Yh*r9&olE}JUyeGV zx4zO&tEETfrGGQabvWbrt>OMXVcj~JVb3pF6sBSz7d%HZ+QXcCcq1Ca@9$z`K1-MR zwhfjrMECtUcuRSCdC>(x-3Bc=9_aDbs0UZGWi&}Xexx3`Kgu(GIrWDetPd!4%Ra0} zv^oP32DpbNX+}$wA{wQ{>BI3kKE|n&Sh9v9Ka(uSj<>v;&MAJd411fI;Wetvh^!3r z1&hcWANtz&ROG}wBK)Vd@x%n}2pZYIb|9DcVX^xDt5hJZw9Cn+=gO+Wpj**lchY1u zQ@!}Td}}>EDXG(tZ?#!Jl-t*e>43fa{$hE)Jeo?BlyMl48k0;bm2lp3p>-D& zGv3_1TdcuyS!(uRu{810UeXXooET#_BtT{WF@Mo9^_PEsc#OGj)t0++ZP5Q%ivMH5 zg1i+4KYHL_yIUp9s#L;U29Ee7KMWO{9O^v3$F!?7?jGj+!^TH{Zoq8HHAV4147NUnP)vvboy=D0`vyw{DhJI&tA;PRmi;Bv zZjv$%Y^?zQ$`iC*Ho)MOU|Q0n+hJkbRR^>~OyciZx2T`B!Xl3=aMd}hPKyVu;wb%i zRwln9t=fy0)VK_foRV{JA&45g@`sU&zPr#iy(}GMLvKiAVcnVqMgGIL2eqy_lx849 zZqv@4Wo~0A4O&S`W3@|MZ2k_~S2oR2niI{mLjx=g7&bG29FX6yBCpT`C@JLq#+ixg z>~C+EtQ#`7DLw>pvsmFYY$Sshr8U_-3az)tn*C%aUsAFeeLAciw&r#RI%w_%Jen!w z(tCM0)8@p9dzZHtx_SC!$#tp9yK`DsFZuzi`E5XCQ`G8FQLvlOpsJ+yg<8bNb2SkD zsrP8@c&%Xj0$4+S_kU6Xm`Pe9zjJ5pLOn%!z=*JAVN63`mDGU>m5Tdq#*Txv*O*xj z4zFY=S$?@}_uS&oesMZ6s&h|14cBLOA$FZa567JB+<6?s`~!sHEE;_6G>Bj)MP9rU zV`lIoGnOJ}HC`^J>gC;gh);qE%n|E@D=ev8=04Z2TT5!aALO#Gj&L4{Y^+0t(K*D! z+8B=Ndu>{YY)sW8+Q_=*4MsC*O`=2i9*_fibNnmVEbE{GCo+xt$*=SI;zLoADG9~TLAXHbd;zr zO}&IlbO^voTj(1tXUITv^qT_UNEV>cp2~PN{kFIqfa<-$YjsFS?UuVS{f*WwqkT z^P;m0Wt7YI2tviGKLnVF#3hVSZVPprl^*t_!X$XN7iP-ESHHpJNLMQK{OpEe-r_;5 zuxWJQc0#lOwPydPD@E(AH+jG?OAnlFv*pTaYO6DAA>uv`3vJsc8oXI??I!9FF--gu z30s<=^Fucj;Me|YU3_Cbp^mx5_ZbaeJ9?%=CtPO;@~(jRMu3^G5ZyeOx;8v0$h50K z)~*-(zP+{)@E=v+k9d1hM?*+;8CENeO@e~|UF2bKk{mtZJGk(q`=M=j&eOHoy?}YN zocDl^E)U|AKlKha+m3dY=RUDcbBG}}{s+^Kca^Fa!&6R>I4xhSRGIY!zCmHy0=#M~ zaGx-h_o?G-#)!rNh+6kW#VE4IMWtj5GsFFyWg;2+XP*!Cd0nfwuXv`ZJTXG;u96#; zeTI9iCGIOURW_BHTD8(|XHdI7l(^hg$}IuijYSqGFRw+~)9%vdZYifYZ}%Tx*Oh@t zGMMV1U+vvD@jNk7O$sJKcU@Q1`aqR)2M)>3{Y{*Yt0N{!8j3`to!=Sf*8k80<#UJ> zA#AD5FThS7SqQ1h#n%?T9+z!%@@&)}^;%mI>t@$e^ZBZaScRW6Q9lzvmq;MJeUIY# zALA{^#RYWIK0sz=DJ9BbDeRHiT{C@d-5NC5Q*5sx@1AVfeZWFm^L^~)zy53t346bi znTw8k)v`M-PU0I8qh&T)zh||n)^$wHEWsF08LXBbwasZz@U((iE-?tkX^ov$b)*@V zj{A1aXZKcZ*RJ?6j_J@w*pDWT>$I0ebJkwzn{ax@+dR`Fa33M9MDmXlbA*+sBSYfp zTv%Usd&RjHiB|_?_Cmp*VHplNLc;;=Y&TaDOT;pv6?6Q9#j>NcO*8+?G)y(5o7XLz z6#q+Wm%~WMx=a;}Q-pH*el@1rki>WPq#M_-i|)%q=Me1EqmVs9`Y8nK^u06Xp((M{ z)#(9>`+h?K-Lr|!dbF>Sq}RXCPQf+(P$GDiwdnriyBE#;92)F2~Ex+ZSec*(dB>x)(xG>b|I(Ttbon=r6Nu%)i8 zw_Vt1SMQ;~^G$0oUpRSkO6aqvC!V`N&KJf0L`Y$=Bv%US#evNDla&BE2nA`Eo5DT_T!Em&tz&mfBrmG;u6?$Cz1x!sbM=f!Y`_Qbj8^&?zyn6#(CmX$Aw zacJ0v*zNUA4%utCSNfpvR00gPpWCbP=eV9yfEz_O>RfY4eJ~fyM+_a3Y!S0uB4>ze#a0YfiQZE>9Ixxr}cz zxcc%nE5`Xj>vg7+wvIL<7954%lwrmuw@Hi1+k7BtMJYI85CTwkYx9Th+Z*dRbUl0b z5NviF5%xvxxXbTiBvaE~HEf={{cOf5qWc|u4cpv2fSWzMjl+F$ZXMs_ykWT%xV)F^ zcnT|PX*^I^hH?9jNh&;w*bm+Q`)|8|J>ue(6)y>AMNU_7#CssF>fJ?%HFW4FR^4dm z+hykkT=N5%F7KIWRoJ($UX&*26N-+nYmlfAB|~%Yy${%@$Zm6>VWNUb8Y(#RG3K>fbw6&Lvaw0iTSd@1lw>G#X)1(P&7(@Lnu8s;5rC_?1GJNEA%zZ`h4 zP)xM{Cz!QwDGXBf6Oca@_DL%Sv-jmRrWY5^vKHXRL=l&gl3H>I4Z=56LW{s>+)c-N z$85=;tfm)G7Q`o6)Sv8q^L4pT=+F%g&>%)GcU8R*!u+~zlmwQ8xfE0)uA>*ZpYe#A zn#8#=bQ?G2O!j$A*TQ6ow@D#gqXB>CF}|DQ;1XfTuk0Pv5GXkLlFPIa88sx_6~ry(1x2b2(Q=D#tJ*1q6V3=efSMB}X>1(t%A%`oh zkTsA)*MypVS9rH-B+3a&x}ZXO>VBHBc0DMy8~E(iQumI!U8-o+aL5! zgGDeS;=TFA)>&U?@3Wr>mbza9F`Wywc8k)WG@Hrf5T>{_?;SIp}gU8vZ{2>gzbX;x0x(7|_7^u_6X zjDsfU_oGYgph5kpF8#iqr!nT%d7RVmxj;7+^&lWeVUvp#m4njpDM?B=o1=+;i-WL90RB3n{x3?oZ2 z)PCr3cy|7+&n&qt*(g2(X_O$~VYKeOVKF`DIZIe&Wq{MY(e*wdE%!lMwgM#(e zB}}$q8g+co=$ocLCfu~Frf>ZHw^(_nsvsK7DCHlh#5Z%v%m6|wtVU-ogh;Dh;YMJ> zWWVRK8MUj~lY$(peora z|KSGV5y3GA49T!GV&5x_E`@rJrRxy<2F#L;P}m;zv1&|vjkYX6f09F7id1X~-Z_{G zspML*?v&z&8eA;&#+s^?rJ^s+ru2LTM1zAk`Be1bt@|Pxp!US1HCm2VFDs`vowMm)mz0Nhe1iJmto|YVKJ3zjK*@R+X4R zUpr@KJa)+Q7Op5_hIj<~v$M%^GJ&y!oKbuBp9Q;e`KH&#pZ60w4l(CAm|94Sg@%6$ z>nYG#+b}@9b&H+)dvSt4agS3F-R*d(N}EH2m42F*`LS}tp@6@{pI(NU&){XSLrGf0 zS)sfUIc@jK@3ltZN6=;46z+vRtF1!Ja@IPtOFHT4&U;AK@YSy^&9UP$VF$J58ZjdTCan@78~+jvC0swZS-y6VP);$6x(c^9Zqx6Ui5v!} zb#wVEM|=oh1VfTp0$`4zPV*D-XB!*(|49gwM{Tu9R#sN=+=SIQny?pI+c@~u<>@Et zkc6=}(P_jQuza&HY3i$=m3dP)Dcxh6a*k0@7=oNIX|L`+s~;*yk0v`xSH+u2jAn%S ze^ELI49t%RzX)vxw^5rGFDUvFedV&Gcwa?z(Sy$Z^UQLv>E(@Cp!NOS>Acj{HReQ& z{M3D=IWE9)<8ujTem;6$3XTVt^4ZZSZPF(H6n)EzN}-ahp9KNFp%e0pC6hnL=}O1I zd_!53>mdN)K4LA=c8T?~N&hkT%H{pZmiL8KKklQQDU4gKdmE(Kbqa-Q&Z6MjqL=03 zQI+@a*;ZgVJ8RQ2i#n>Yd!>dY>9&FvUuc-+&M z7`i>e!-4ftdzRFP%0H97PGSO}s%2lV8tv2zF@dVYr5A6@GvU#33eeo2N?Ztt1D&e2 zazGN}mn#S4!?(RODHrf+>|k#gYU8CHR^%aD2u!GTPjbOGXOV|F4#jbYg$jpR(}PU+ zvVIIGCr;t$Yrpjc>*GG@A#B5)y0!%Fv44i*^P8FQQ5p%iKbs<#dLA&{Wo+%JXz&fk zvPDnYotB?ztZX?w^7&^`tsCaKcqKEV2b$76a12x)*qw>Uz!ZkW(_ONk)2>m zWq^0z!9w^j&^CWbxY)GeTGJ@K^z5`fhn>J;9T#cCi`mzGn7r=%g5s#T*X`lEdJKM| zkI`9tjKtE9`s(E76tjR`wW5JnMVUa`3CgCk5~xEmhRy_XRKt1p9Rc?+5={Q zhCQUSXZ<^E*U%PjNI~yn{P;z!L>0l8xN2|3Jt7oU6ssJL{yTF8Hf|&;rowjAl_k|Y zmLi{6a285=kQ8|m7uof1zMOyhiB+?TBgzw817{`%)OqHCVG0NNqwmkuX+&?@cL8R) zHrfjk_dB(&j8JJ53!XfFoCidvh=+)&s?+tHPVflQI(kWt(ulht*ni1wSYndm!0Ng) zR-`4?mNX(lC}>`}eLr!XvW^iyiy(X^UYtIrw;27(MriHs;S?N;T}o{rE=*e>$vCZ$ z{;}JSb4W|etLgd>VNTUq@U{=`k-*?jtl=!0J9bJ6Z!-qg=oiPs9qy(ST}FN(F-7TI z6tB?S?g-Gb(ngA`c@=p*MRPT?f~?m+2~1baQ_Sav%`QOx8?{~)E*K24C1Kfnj+DJx zFaYw9VL%|tM)=C@-WLowi5P0-o=h(G2GE`D^5c8%+LBxb+BVN(FU|RirUFD6^w3QW zKmK9<&4bX|VMAoI3S4zp*iW13n^U%~?Dr!UHn`E{c0BLwj*xr3|9v}LXGSy_$Io2A zo+pz9-S6K}@O=VQz7ZJu(2eD35>z&;WigOCodgWHeu67L_uE?R34uRmAWy8#76YO| z!ldKg>|TOZ-@mlOPdFqq`ueR~elSO7==)eZ$4$OOI0jl$vk?chBcE>-a0;(?nir7l zJ69dlGENW2yXO-R?JL`xy57Bke)V&XI?7E|L4Dfc0oy+WeX1ttN-vS-uJh24zPOWK zkxx#piQkTsn_Gy>&Jg5<8HORI5=e9Fe|Tgu)tz0Ucj*gbd_zyCayJTrn^k@0#@91J zgnwn(xX0PZVQSZzluOj(?hpb)9TYNUM?DoESpj1d5>Gi^y6Cw@hhM1N%n#cu&$BX~ z7T%VpFn5@FWjPkgni3lYk97k&tMJ*KeS%XG`5@ z9YwHa54ayPAHI|6?2OV`rI8TN!NO63PI1d#M=Y2GcbuG3$x*yb7V9u(@+X%a0dN2X z6UoZ+UFz%LUvRnwd7^Ev1xBADx|noFC6x(tXBNXVyj=NAn~FL31tzTec&W?&4*P5F z@TOx}dRSgTWDn@1e4vC4XmenQxRN#R@3pdZSIvoPdJ#SH+pWJ`fpft25^rjqy@n?> z*?nE?F>%c|TT3x_8Al8|?{Z?Vj4Zvkl_rwQJ$%{zkg|DZM{5d55S%pzqZsGju66y|4D)mM6oq>JS{mJ4an#^5IQB zm~+oq9{dcU351_reW8|?sDQJ043miT663(R94M4nr*K>^>Ar7>XvDewdYPpGvy=f6 zvJ18}f=HUo)WIFt{WhNfpae{bFDf{IzmIJzY<90S=t=7{Q&gQch>?qajf&y8X>}Yg z+hoMycKW&-6PQ;xj{OT$rUU8EFinSz!i3u}LN8Lr7gN8vjSm>2OSy+adF=L)W|0}d z%WblQz+Q^d2%)hvqPMFwT9g&j8yWEj#ZS~U|Bc$Db&#CP1HYGYUm0o(YIpHqvQTRF`>+z&M}h?%n$!sA8?h?>`k5{@m)F4NLRZUqHDTyzo| zoijg#wcr5BvwnQK~rU2L3_xhNwd`Y|g0v$d7@7Y#w|dN|`L4Z)R= z?d*^j!Y!O38z;0wF)$Ul?d`q$?FjB`XRDPLwzAQ&{)5(`;v5wM-9wh?)MWaY8wXb= zJfmFuv;;mVpVFbQxZLHtd@9`re5$bw^V_z@xx=u|*%RBUG)mHCZ_2&+0^oaO@cp}Y zJ>fG*M7o2?X<7TEJ~=3OJ;2_$)fC|8+;LlM{+V(#QDns_U7XvuWWCNn(NEd zYWb%u#&3=-zP$%-og#1m_#V)LW6mE#A`;(cfR1nemTg*Hs@@8POe-FXY^p2NCP87} zHAb)moSrI@CFcLBp#LpQ^=kmHuxVS_^rEH@vE8T5Uc@|oqxTKz2%$N`Onjc{E3Bz^UFu9B5_q}%y?nhgs zc0ZR;>?-V&6>)|2>S)r3Y)(aNBiv9BwnVDPmi1@M|c%~}qQ*6xA8W=)TR^~dunJ+VK# zmv-E~113V@F@3lV>DU&DS8WfXk!7&0{+HdtFG8808#!k+Js45`s7Zrj%;pMn|Id`i zOcr+FR5V?^GJE=>``Aldnj|w{n!mfsvJ?AyhU1+QGsE>9$U+WSO_$z*WjHMH#lneq z0s-`V9A2J#&-5T|%?xhb0TA=^G_`a$>89DOoLXalRzdpp43s{HyUG-sXJLznF^JtRwut&r;|W=Q;gk%#f`2q$rc=6ds4y$C(2s(c6dK6cJ) z=Z4E3KUjg~))lxklQ-d|IG&8^e`TE%1QcNtAjobr=5&KHh~C;>w1l-fq^8 zY@$Tsd|Buk*(+P#t1cXm)n>vpG>EG)^ya zpoAvq<-qscb@hv7>+*FKWVwP;%SZwd3BeH7t76)`9;GZN>u^U$-RtKpwX;KC5HYcH zU}yON1n5btV<%r-r8sC*1{d1+Ks8jrZIyBE2G)USCL@&?R*l#P~(i6 zbg3=IU`A3 zp?o49@Q`>vy=!s(j)|;C@Rp01*N6xcF?c3O|nZs!fCRL2A z@1rk&Q2AoMLp;3!}rrdT5+3VgkJ$%M8^&r!4fAFD~weBi~o6F^{m}vT@>#Ssh zoa7|#XK+H?sCdK4^RB~?;Z<*WoP0c4D*r9qvx!8l{2BOPDgj_=9PPzoCi4%-qDml_UzTuTi4ff`U{I!lsb1rw!1f$Oseh9 z4-xe<_#|bNRbt<|G{`n=Ke3B@gFlx0Zjh}GlrzO?d#ph3~gicQTi18$L02L6YuW{(x}PFeuIt?=IU zXufD;uF)b|&Q}gpZT7a$TYJze|NesByb>g4)x0Qx4g%xVU#vot#+H2=ftLzBG}vp)vIWYVd=3X{Z{3S)PA?=5$%~RARU`Q2!l@FnK7yl> z7_Wdz9`&a)Ml>WHg%Cf{OmzCcv}slPY^|>Jq2O;bM4UW{(Fy!66MafljodqN^b~6h4(F`|nVVOmzHqqD8G`0|q7KFr9ULRIILkB zOE6JV-fh(s(mO7r6*uF&3erji!W;3qIZ(@W-EZL)k!8wSW^%BAh?T)9+Ma6$p-D{3*{AA}5rtm+$VXbQl(g@<7c=yn z|8S$BXM3%6>cEU{JH(DgB!;JKyUzP$uDU0f1GmwNU6eUhJQ4THhwWpVL?53U1ylOc zlXC7G4%FsA^WOealH@e}qh@=#%bx=t`Y zb0jFHE-s#M67<8AUr#upGu=5g$?fqw69a$$0&Q(35vQNv-l=j}G5DlwPkFQt z_*DGr3Q^sT5WtXh2`Pu3fYwW(?(Cu)#iVVCq1U7G|j@ z*R8-;Pw%AAMkI_7&53#pU|{rQL=(r55BJX3Hz%NAQ)J&=O>sV2k8-^gIw2+Mp~-3~ zP=!C9uv!N@96Q)IN58jTASM#%k?lBI2L4u~Uo6T6fy+Ant9ib7;k^a2K*dRfz@!ye z>t)y1q&p<^hXsZLG*=1ORkm8Avb;z1FgTg7?BM-4yLfXdX+eOHg*nAugf57PAk&`C)wcXix3=w9k}DI0F}jiyOyP)@uZvG$patunGNUkXKw-)=K;Zm9}~Zm7r>&sY&`$Mfb$>36Q2H$348t0p62XkhI-J= z%%l`wG&G@-h$zxi*w1C%j0}U;0F3d)=|+ni^P$xk76S?yXd@f0%x7{GZ z?YB@<Wqq$!$8a zgwvOW$XqUyaW`#w3C~uB2CCcJ{gT`5h(Ovqk}xpC#e znIhHtBm&#a^i*H$_>C@wg*XWgeDPWrRQ=59(P5BRNH*17LAAAs6#$nCpr7n|V5o-V zNt{apj7wLEP8t4|?1=SWmu%7f;AIE#iq5-1Y5Mj^`n`cUF!rHt*1b}J8`^)K8x&hq zCerQNJ2d7V2thumOj7dy(kG_Wyxqr3XB?6KryhCl(A1jdu5^vI$kkiJ|uOzz{mnsl9*5 zG98o;r`vC9_NTi4>e79HF$4i<+{b^F;rC`G>CaTR4iXo3$?CzSoZB{6$LpUR})LXSO=l0Bum z+p@t}N{@AvU_P*WXsb|um$6blho9bI`QKqMS}P9~zNaO$lyK(x%T#s+&?Bomfk?*I zD!|))-#~lGy22PyPI`WJlKfT}zE=--#%8Xu|}@NgP+iqbVl3tNX009x)|vn=!dGjZV1mXmtp&@nJZ?mstH6 zayM8MbNlY-q{R=Q$ZsG4@|o5C_ZKd9hQr|gQ1m+&_`7@&^b`9MnW|x&WFU1EZHOUK z>hGe*r4(;?9@?Gp`pP7}`t53!@>xs`B(`2&a;fnf8^GCXIqEgGB~4fZDSvhS+KR{T~3=jsAcDpyrH|m2!5YzrAP* zdv)s&B#htG+$a3hrXI_709Wz4LbT1eb0$VZypk4~DD$b(s|7`hs+sH{4*~ zvQ`5WT~3Lj+RptuR?n_(9&isE`B&dGS$OR=ia4rV;}~}>xQ6wsBHET~QFZ@qP2d%G zV4->f*S1TyXr3bO&EgZ*YB4thcV;~Dq&f&M=Ka=PV2x8;md@3(LZ93c+oempvQR4K zpKTA};H2m3p(3~_S6lqlWU0c6zy6}T^_!Ik=q#TA)yS|Bl#Ap~l}M6V7$ELk9m2M+<4Z~Ij*Eq|Eiy>NvJ7g+znr!WhQspA6fPIyEg!=(E;@~Ga^=Z_ux2il6d_bE@%&v5~m_q+!tloytk|x05w__0|)I(WodT$nvb?Ijxh(RE)S#nc_5njfOBRIo)&n{YvYo z98!5|UzW9a4yF%wv=)h_9DF!*ZG&rQP}z|ErBB6NB%=z*?>JgJgtTw9s zRsi@9PzxKrY%g6K=dmtXYz0+Z-wrr!C^;cnlJ(LZifn!-7E>T4T%ks$AMoY^Df2Yg z;2YsprYd3eqAd$K?20e`%3tq$OkRko`+P&aStGdN`Ph$^N8_QLAXS&0(W9OuNR10H zvM!352+~~KyM?;KeazFYt0MnZJ?@`8q4ECi;t3T=efQ1q zeA&ViMiNU8CD)G&n?U9(sZ{k z5jm9*!IEsdSiL{~wx41}4i!_00817ys_q5^bbK@1F)F%x4BVt|B=!bw-ZZ9#DIm6- zhK^$x)yC&Gbu4mam2>-X>B!;3qF$YYucx!`MSXFYl75gpg_#g2NcX<(WU2>>++@e` z#a3+JtiE%$K)_l1e|hYzDrGBzHYa{TSCH?VQn0 z!W)2)>RN~Ucmetqu-28!v-c+3Mh^p5PqD-2cl<_gNqUhgp@Ove*W13#_^A;r z&|Y0A;wt!X50i1IB0Ij0j1adBG6j!`4!euSDBU$R7F=ANZ4qw|vywQ(4>tFm5|1N` zmN_|nYzJH36a4nmiQC0BNkL)~*BOt8Wle1&5j4cs+hw9N+Gec(oR1~4qYSscS&}$~ zl8m5~(aU4L*t>?tZC}5BKd}fDJR0JQQsxM@!1&A>Pbz69F^Fcet^4~wKHSVT$jnK% z5N2ebJ5n*4Aw-#Ioh@xNninaPu7*>tUHAwq3A8``r(7_eAx;y=5#v(*p4j)Hqz+y+^DgCGPj&;;LbOEJZ^K|UC(GLBL2900(rxc7%8iRv%)REetnQZ`ZF8Tbb5j}IN1sM+Af-?Ak_LJe4S z`PU`H#2ai!x}6N>TM_{CuulVw={IqMk}HXrwaf8#mv|C-h@Sh@>(1kPp!83H-gM!? zlce;E-%uWk=QSmnXb`hLlz_S68j&QZ2>NE8>+EV1R9`4dafD7MaO>`gO zEF0O)9p8RPe)~J_jbLHp=NetaK2wnA=`_dO_DfQsWy$$XX)eR2#R*Rtm;DdfA9HVXmU^$` zzOX=<$Fy27u=U5%tG0V~|0^UNhSV*i1h&nLQ(fYI&f;0XTITcv0>v6y2FGant}dV0mr! z#8xlp+Pj&d=)E_Zo&sk5Qm|#8v;b846VM<)2`KiZ=sjquPm(9JVMRZG8)KeSxt-cjA|D3`cHM1g%k|)mx zn_q#M%8#0FNY87C3?LYe@mb`^LP5_^KiFEZ`kytTC*Cji^fRk$Nw(|jx`T)y9a~bD09CqDllpbLRe+^aa zf1U%vm(|w0&6tf7Dob75o+o;%m5uQ6@&U_?b6kNb*p#bEfG2z+!0i8H?7icu?*ISs zoDfNrCS^3Jga%PYr!4R=<#U6@Nlg=pl0QTYqP~oS-XChP+9~_*okaD;d(`$njO$+< z#3U+bX#a6ao$Y1VL`bIa3VC^NnJylJ+R8m^n5Mn_7Rl}~vVxwC%enc&LXO2Ie%GH) zRE;H)eK0uJ(X`mFs(K3)%u7kW9r8Pku(1^V9r4(LBOBG9z;t`T;yWC8eDep0zk}_+ z76*MO>oWR5UX_`^o+iA2=?B5B#NEfSXR`iK)3DDl3-jgshqJx_lg>5W(D~yO3CT;n z3D*{}$tiniuBmpO%G?qVC_}$xg{|pzZ3I^;JY%y*D?VK2+$?d>;*l2ug^epT; z{X~!g{8CNfc{cCgMh3y;*gy5%eL|p_KNlrEpP+V+q;jS%4i0UulPKo|-Np7z)iEE& zbSB%kraa<2F)J-L99k)5Y{M3EhMQiyc@K+o9|}IkO{}0*pu{6Cr8){>FX!~-<>MvV z>3F`VnmF~40JQNL_Y0Eek~L*qj~)h$q^^%kFGIc%2BDhfqhN-u+{8x`mZrEIzR{2z zlD2cljy>RtZQm%eYjUPx5UTpS=o2E7zrZxga~OFDuC;jcuPG~BMLb-})^zI@8R!8D zB>sq0lY_$OMO0*AIV8j4n0D~PvbC3%lRB_iT%RzVh>KZ8#u6_ohyahB(6ZSnlZ6TB z&BfH&`x+$|faZA%n~Y*`KfcC-zC3?!v7O!GrB$r zDArPc*`1QlBgvEqrE9?n3$%TNodah&exbTFE2CrNgcI|xBKWQ=iY9)L!Q5cia4z_9 zJS(t9QE*oFJri|5X*w%A%d%{(s4)7+acBlxfF@iAGycBsdZYYl7QjiVZ)Taq@_!-@ z1TB}vBK^_vd!1c#mAuTXYE4)H5F1s$?;x?R#3j%3Nnz1s#zq~9osD1wX#59Bf|AH} z+L?|?8U^q`F_r`bfl*m*`?f@tu%*1M3toTxka)A1!lC$g7Wp~Qu&*O`#^wbR6ug=z zubZvYVhOy#_ywz9K$qlv zTz_W+3K8|FYQnrVls}zk4`6hI)Ljb*8m2wv@BRHAi3$SFxNXXX=`0ey6nFn6-ApuG zyuRopUw(i1)O7Oqna1*LCTW3K>r!99zz+mY;@yEis!fyf5mUpqc?2lMHsZd(!9V!( zIW{i#GorID&|*p5jfRR?aBDCcse#Tat_`ei3-&-&3l@DbFj2+#Weg2Wc0(Cb@h^>BvNs$2Wm zzDtwLk}W%{82u!eDjFo$X8ST72~14^gxvELa6!k%aKPG#fHBnGoUA>0WUxsc%1fF)D15RR>(iziYFBUIhP_4Ma`-&Y}-jEkbdUN2|$5?({wWo z#IISdbR@mB|6yWe7)EmiI2jGQ+|Av-{d4-lsMtFYW^V^G9(^RqviA@;@B2bo`1s%u zO4>g18reT>!bfc(c8nQ1tE1snR|FmOeRz&HpSh!hgY6Za575B`H?*J?DQ-vL_Pth3 zTl(+k|EYyZ(o?a6z|(&}{VW2&w=e5zQ~5U56~*=Di0!icmx^L8;bdXwWoU#<^bK%V zJUqA-?ykQ>Xs&%p#bAP~PP7?;=dA|SxYO~_6o1}4j{T-hL_U=7CALc3Eb^R4deXxX zspz+QDO_0L|7;u^w;_m^qg_&&klBc5puwqZnS_SiW3Oj+U`DaB=G7D59FfT%>}zll>zswSJfQl#ew17W4!tL_Xf-tBskldrNRH2C))XmuXb#` z#^jgHXQ2RLB+RC=2r|DP zV92`+Luq3Qsth&;UQ{Xer&4tcav#*Rfxvy9d_%MX>W zKSRC)ecjwr9xs_{58T$p8nCwLB4Iu2<~}Ys1jo4+YtLU{B){bBb|Tk1C(n2z$nepb zcyWL3C!w4qrqpk?y;cYoB_r0tE@!>+QQJ?T3T=Sn9GG}^nVY*@?-S$AS6j}lF9MZy zADzN>ZvDLDp;* zq&)RSB^QwFzPM?T>sQ@+@)b)3pNpjNZac>IOHwWVh9%p3fCf71PmG?QYh}uqm*(gC z7@3kekq$4-8pv-UL=U0yaI?g6ng?g#dJ~ino-l?9w`dlz0dS3{ZhZn6D44`WsteTy zhx(ipl2!1DgcI_Cjhmoz6I`|P$~@!UJc4Wfp6Mo8JZq18_m}_s;5G!(l++5fpPD1+ zd~%Sz$Nf&2{~{su;xbGm?;INFS*%KfZm31HtPCbPX zi2$$^;Z(l6wihq6zk>6Rbl0*+?*k}=b%o|}dHp9i*^9&2&!)vir_z&6IyoKqJMqcb zc{Itz3dFkWT87TAYmI%!Mt~Qrz^<#z>Q9fjl?^ct%VD}T-2Q_!2OuZ>v|Yvg3zE^- zk%XBy3vWmN>#|OO!t6R!C-)DcZW?EWyVmJ79@wsFg7J<e7h!Q^ zw0SvqV&~vVaEjHi-o@jbhuU0%Q=^uw7~S$NOv`TJY==lnOD`u6$`OoZY;Q`{P(BgAj^ej=XxEPsRB)%P1^ZseupPpWBR&< ze<2~2VE)iDBUe>b)!={R-*p*MdDDr zkj%5PD0#ef9ANgSW8u@jzMkmBj*k6U7`yhoGjmmxe5LsVMG=wbu^Xkce?l^rzNIpe zmso|%%31d1p~|z?xx3ieVAAtCPs{C5gf1*I8vNVZAF0Z6PRWz0@EretE*u&qcK_{7 z^K%o{gm)wpA{^2aL;GgEi=>deXfPXHRn_Cux>Bpw^x&4_kfM`?wNVx@KJ3qli|nO^ zGvn*>G6q-w6`e8P)=?Qws;#mLg660HQ-yWlD=xu$-ZAKz% z?*`O5yEpkPDwwQxa@$KV083hSrBv*Vg#Fr(pG9x?TJjF;nOVdFcwf6ty|eOm$zn(P@>x4lRk zGX(6qgxJCo?^o9F@G~{RD=8lHONXVUtBGHEu}7*)G<&UW%i9*lnT}a>BThFMVoz9< z&War$!vG?oU179jD=5{ROny`J2ug#xPfgYMEUgI)QIORfMFOXc&mynq}xtq9OSsiH5 zL)@L3_w9crh;=*ZVn|nk)XZ3uVco%l;%Qbb4xvw3Aw*e??P`|!d_A;EUO_bW+SJdF zl?wDyNz^Xp1kSWejF&I$0Boz6LJNTN=OmGl$rif#wS$@VJ3 zUWdR?w|yOpw+U=I=?{@d$hozeYK@nA7)e4Ox=&{`J(@DSCGX@(2}~0ogDw?K-B~@n zr7EWU`V1a+JAqol<~U;I2UWZfyVcIYTRd81${eY*wYiU+gD}@r1%=Z*yExI@Fh z*y}mG|NL9J0=(^FY`m612AKBkF?c&94@+>^<426Z)SF9s!Td1%rqvm1wz<=wpCBMg#jiy)024-~8BZ9NqTqf7ETJk6$g+TE&6Du<_ligc_ zN|R>=&1~=4z~BC^nuq}RB1us{)6!9LU*pYDfTU{|#>%UiKgij8Q?y4vJ4mDB+5;D5 zOH+AYNF|T3^9YvMx@s$JnQDM1j+qy7LtGzxT|AYS#Ic;Nb<|x0``C$>@At?D&ouoJ zkYP<=7)Szh$hEb93m7GHM{Tx+c~I|ZG@ma6qf|NMpDkJ2%y!?M1SSQRt}VH2!gCY5 znD)Az8*Fb+BrD-UfhUslt2SFXeCKc2y*O}FJA2M(syX_^8|G|j-u=s9i|MWDM1`;i zGzA40Cvcd*MmRPUZTk?;f09LFF6l$x;w?XX>EoK;{FeKjJ!PtGpS*NpMh=2cwRd1Vskf|8*vxna#375KtPU=!N2)5s)_ zT%b~?kac+jqvbtJzO(0*8Ue1UZNX3-_>>VA2qn|DjQ8 zgrLUEPxRMQ2Y2GiaR7dLx*+~V_}_U4Jv5&j$b}gAcdCcWi4d*e@80pTr2P{St{7-T zj;Ef@y0|OlZY4(Ioyy9Y^M69Wy^=?vk9Ksc7j}vjEzOe=V^ra_Y^|_?A^WJ7PZ(;% z38xZkrj2V)y*O2d#mZ_cMwsoOqado8+-?{K*8tg8u&e_8#`;|MkwN?SGA1!Pd`@5| ze1(5&pB$3XJZ^xfG)-~(@<}d$X~IU|p?J^>XOQz2aMWXDXM^XsI}kx{#u#3z#UBGc z9j1{8fpgs!Xco)xuisqFs*gbkSKU0K5qgP zJ3WJ!W62h~!g(XO=Y)3Lj!k*2e6@Gs_E9p$p+!nlhy!cy2ediAeha4dF1KBQHl#_P zj+Qf+qT&4G>v{-7drKLWG8 z{O_UAljjsJvSE~d!P5OcW*Ot-yggi_0Q5`LvNhFS(vDE$r+cwKnd58S$1r$Zpyg@`YaOZWe5l>-bOMp5VT`% zBlb19ET#HN!wGD<%s2O^r^_u?bV;e1e`{hj+jn##Oa~K6#r1YuG9npIE!io=Elv25 z-9IL|4U*cMhbU|__W-Z>ifEytLo4@j7edPAcLO=ed{>__`%Ehz9K0*^&HNXjzG$qt zm5wff-TvV-!c%P^m7RWz_6uszHF#s@bJNOR>?17%)Zw@6e4qp~^kdQN(r2+oSlu<{ z^WC}`H!f1;I3_e}@50(1SE4Ob0Yv+Pp08;Yj=>vis>7e;7BMSZT2P_ zlU*yVn+>UdlFW83KVEX)`*uue*AR6&KD* z)Nvx8jSV}D+m9qlZ5;Zk@1*8-p0({(fl=F93Vg2jyb_-pD|!2uqy#cO) zNPh%$s0q6DZCec?A+`1EMfFCfFWkiUPa^2!0Fd_{-X8AyhtL5VE=6#R$@`*YY?g%8JOdX$o|bS262-PlToNZpuFZ9FOl*BL4#=mjnRXkD1>kLL*&QMo3hdyl4bE$)^xz2|gvN?D0fG17eIk1AezTe|JInJ{biOb9Wmj>Lk$lE*j> z+bUVE-}vvBBl5y;Wv8nXVV#5p2_~mTZ1prGLEBKL1;8?By?r=#I)q=v=);0Vdo%pzkLA1x)QiN#>UyC3llXywSkF)e3oRpGKxqh*UEREl+`SbIdMin z2{4rt*6-f~IPrHwq~H6{_2SV~Yoo>KhGR?0@>5ans4mUdq+8VZ0M5SzY1`HsW>^2t z)_Zo^RKEIFOl?=^46{!I*|2PR$>C3P-@wE*``*WwC%Ts>LqJHbU0~R2>T2k8Uj0S7-a72*w7EJTu&RdZau@_ErCKnx5`9^29mmkdIxvYox5@5$oZY zkeu7#B!R7a2vqEE_W3&h>mh6-@Z~&H_J6C%(gZvEct(nb~XAKx&IwLc}~4!&eh z(0`z|mHG?Z&(NL}JdNjG4IAUn-k)Iwzi{DQJ9hkR+5W%a3E#P;5#D4+t820GxGTmJ z;=S#w%X2gJ5=}F+s(u=D{a@GLAwD29d5xXjXA*)h{6e<9bG`k`polMZ&s;RUs6(tN zayy}pQB?mp^Na3<@W6}-GQv@}?-y2xiZWl>LG-@|4`0GDe;{u9?5S?#?<3BCjxpxx z+3z=YuF%p{Z<<`zpuVM$Rm_ItZ)S~vxj`Iq&w@5}`0@c|0o2m#SlI1F_f~Pond@2C zbAHwkcr_BSJL#O65=c6bwyfMkEQ+y^3^*#q+U$^bwtR}W+q8%T$rnQ4*aAQ(&i3Qd za|8Bkx#{0H+Iyv3`1(LxT)Q7WCJ$@q4^f3{IwCRpZ{$mPmQSSkgF{!hJ-?-6 zm98e9j$xvvfy>x|Lv9Dv+MglNQ?ZHCGdsgcwPFE<$!vq%<43U1nBFFU2zn*!D{o?X zxS;+NGCo7@j=%p^j*CSUpf>Lvhoi}BeTgduuIZhyJn?@gC^vQY{^_#v)$t>C+sOp~ z%lx1%C*Akw4eR$#7A;{T3jZPI2hXwP2+PvSe-rhkZ*Hk&BLB=f7*e;qD89A&_?n6B zQ?`+|1jS=Psb#lrYW>4GHp3e?)n{lnAw%tn8+RqCFM7x2WVutx@>#SpQFaHjyi!d( z)oNW>pyGt(7w*E6B1jiyk4`N1=;1`twFg>g9$CVVV(6Q2UvIs}~> zLjc&%*)>rtJy0hU1AA4>EVpa{!>y=;*H_`FwOcp=Wvt+ zJml>ncwgpqUY#P63OAYK8~WzDss2+LO=GE@8NS(e7e1L7n03#>?_K017Niyc4o@-i zU-2eq(KPaNu(Km*N!I>|5fLK+I>5FffGCQs_voJi(bbwpJ`eUD3mYvGyL}?_m&%*X zIB$hspU~^^U+u_nxe8)tN!KEF6nl7lboslxd;9aO&eq}%;p5mRb&z%`n3906CkV2(Hxi5mLFsoUz08i2f=H_ zW@;R)J3$J|0igua{hFw&#ljrvJBgLl5$ml4wO`rMC^o7C)3^F3N0PdnI--M4VDLBe zv#L(Mqwu@$rPrq%l@X78qB6up&s(o1e9Gs_l^d|$QbAMX)_ZmN#0S4Rv3dhuB*@Qn zHHSv}z*Lz#M~<+0<=-ok9QvjO_(@J@+#pzGxTwu2(|)t(m|JHGM)ft!XrV+WuKi2o zY^bxL!+5z8+sN9J3Gs~;V>LnJu>nfxL?d>+bpvJQT0SsB6ND^*d2aq<-I0o~&2v=f zBy14%rUj_t)9{O@xs&GCA?JGWTZ;{wD838G+DkvzO((^Ybk9#DOR-cBk+qI2xQvD3 zO^mH3Im(wJ?^KY);kbw>dn3s{LaB!5wF-B7TXE2SJ2N_7>KUd~7ecDh zm$ZT8lO#MBtPwx*Kp50~yOB;E!N13>dM_5$5sB=!|E@3_wCoPM^+iSTrp}&QO3Tz_ zEB9w!3l)sj%QZWhd!)9K$7JAT2sIVN6P1Q+XY1-5O~vvkw@3x&9b0V}gA4HHce_ou zKiIyIzLvv0`XqOn*oqawPg6d9L77llCCYViNv9_r#Sz;efE~6m5mv#805Zme!Ug}l zYkkYs;cnsk^uC(BqJTs>#PeW7fgbAjjnnT)UlH($Gj+z;ohaGqx!>Oi+?5^YhI(h< zB4vU@i+hi-b!?}bqt!9%w2fE#P(Il;0IkQaG*J4>zt=dO(7vrCS8{EehSACVwS59L zUg)Z}JEJdhQ~k#VJw3d<1tPjKd*Wx*KQPg>FRXRS9V3>7hFhB+hmuY?8XSDtCA*YI zE!!m&db{+A;ZZpkddY+AXse;4QXQV2Glz((loVx+uYiJ-a_$$ACv@;mlA-D06!$-6 z4Gg-ZI|GVOfGxZHR<-_CB|v)_-Jx#m3F(O1U>|P$qUC-H$8syqiABl2=u+#)-jcH+ z>MCjU(lMu`_+Z@D*1(h>4K9hKo<#BFZ<|Fj(tpiA=JBtMNdvF=bk@EXUVx@WDg62B zDk^gmXpfFE&A6Xh$<+q6?i;in&EIm|6D|`sK?oM-xriHcxq&t zu0Mt^q-M&G-`8~C)}?N_q3OzyN?4Q7cn<=fi=9tXh1ItUtFjJk?hMc}yiUAf6SbB1 z>aqcBc)&(juQ(d-?D$EBE_#OxE}>WbXcF+)f6x#$4^h-UBkMR>>(&zEduNmZg+MuY z#ysWny;%#S(*$zfR`w@wU~w{di}^DeB#pcCC;L^ogGR%D{I2}sh&RqRrM*);pmW3# zBly1}fTo!^{)y>V*MgjTc2!i>$HUvdt={IqJ-6k4heJ0S>TKhMa95a{z#E+Q`pp{^ zef>J_5Ary;-)f&piB%L2=yOL{wG0W!$UK?(!LrIBp~2%GRGNlRS!>5!GItU`)nqWP zA4R3p9tEh+vAId>5xw(#2)hG4$$huAh~f8X(L3N^(@B0K2^Un2{Xs}KiocFT5s2p3_VJx;<{1S32yH`oOzq`;D{?^&8D80zTYQ+=u_vM&Xm#9bW2=Hf#R( zrqmGbgu&+bczm&3=GyIO`a~-u*Jn5RrFIOZWxnga7J89rI)i%r|4`zXcr?)eb9$pr z>Je5`ZtUpOv8@RTNkUESjz`DB&py&*8yph(0C;1k^4!H?QUQK;@<#OwXAl0qU+&QyPu z@uV~jLsA+Ujf#t3+(%o=LFnmkJLr}m9BmZRZG5m&RP>7G-10Ty{A(D!>KvztN&69B z1~tJWS~}rud%~Il;=ZD5yd_pGX9IhKOw)d4;X0h06O($HXyP=i7HxmYJF7u#f&-1p%!QImLNBjdgFAzlostm?stL$A+g8R$f7V4`xmPi_{zem6e3^mR)JRNSg?{?d_K5Y9of1e$WW8AyN+GM5SO4zew$1Cn@(sCf6Zoa)lCOLAer-vVJ7W=2TMLm3XGOknO ztGZIl-;Q7$?|ZPPQ*Zyr-4@Yq31I3AFJXnlkeZD<>TzIkRo@pd->|}8)|~&G-#~aB zm_=~P_0{2g?yyk*K%l<_OG0Jhw(yd3-C!ya=h&hEpHKcZl-3oPjut7orOy)BRPv>r zlTWk|s<^J>QbTelLA<)#uWrF~CB6zooYcZzC~R<-u*f3J2i$#95)h{<+GL2PP57Oc zF=-t8c&p*x?>xT#cm<;@d-q&Hpvr&xT-s7plG^VN*NOdoL-3mDks~wMVtf|;*7jf~4&<|b8q9hYmCbXwg_mohYe;r|BQ-j% zb1GNA|5n)Ilpo7L7@29FJc<_R27W~y$!(77OPjK=mT6i+CmT0ns=+s{g7)Wl7}y|& z_3S;^Mv2{${VC4yMsu*#=C@u$XjOyKaA^0&%M|+?O?6 z{&d5iuYVFj67@qt-kehqHAl4?x{vxq4(NF4k7k+=_TqYU3UA#vzZWEvP@WN)!pI>X zVOPzhbK`!DE7AN;jIQ|kBkplO8nACq(injCt?`;xi_}q6UEAqi9u{oM{1o*$!E$Hr zuGM++>TIU&1=WeIKmONw)me^G&mF`JB27kfsvg@1r8;A6c0GcL&&fh z#{2X1QbE5^0bz|pm#Go)9tE(DEoIu3F};w-9g>T&bl`Lp{5Yvv5J8<3-0pVqpW4%g z7?7D6%9>t-{YZ-CFoZs;=^2=I41=;@7F(pjlgLVnUgv#Mg8{_Ri)H8)ud%E-#ajMh7X z{{UEsE$^E0?y)&wK0&DWtZudXZgaR8appc1xa67LLGnNju(;>#k5ALkAd?`C=wZ^2JXd!Z+W{bU3Qy zRt+-8W~oyZJZlH^L$lZpQF=2~xQ7}ZbbPS{wkmkZoL5_1Zu8UnCLw1tNpGD-Ec%Wh zc_Kw&yW_G&pableWu;%G39zPEoHYOl`% zLw3(`v{^x?n@~SO8dndbYOM?H*&>7d_7QCSaIc9ADnn4GdU4j`xmV-XUG$^4ypv8( z%zCAhiY3ll^a;+Vhs$ohBsauSHW;0Ce(z0-)B|IOY?_nm5peVO+w=0G{bDhW{*On6 zERjL?SDBpRs6N^RUUeLO2rs6Ny7pGLQXY}hm3CP=^$uyEF^V?nld5c4Cyf>Bi8PtV znr_2GPGtqL4eRF2pU<|2A~FX|^owpoHD-awyS`|h@5b_fR#Dxed2}N#_;+fN*v|~$ z@n0Vo2yzYeUA;s*$|_wg2oa1!^kcjrU}5kd2_Ep-6afZm}Z4Cv~_{?|{@RvW^DOztIerP*7JtN3LsSD>N>czb(O z)z1^Bd3y3Z61LKk7m}OZyD-pb?IfxG98!c8AJom7*db25B~9#PN=?54zK|Iw77Zb5 zx|jhv0dG^puONU0Mu7s7hn|I1b!W#}c04NBo@|yiA(wEm(8G*IHlT*FcQrH+NhtCe za7?I_V$enEI@T23EX`BT2xSD|DWk2(sO08)UXF|TU~CZMOvBCtL{%3X>9S^#^2S}7 ztkv3IFY1DS@b*JUeO-vuQKiG{b*&%WgP&77YoOFoq8a=iOa({N1au;nkl-<21+*U| z0G;^q$F3h}+%`Jwzd)BI$AN!>g%$2S*033!ePpe&YsjLdm|fRI^=|BXAGtVe!S*tN zUH|S|l9qmnIdk1V4i_ErEsvr% zk=rE+OF%Q%23_M=^yh9I;itB#XJ03HNw%iZR**M9v>U$Yj|D~`2HfxT#XPckTx6*P z=E`ZX;3nMMMwLXDE;HIqxHN@0VH+ZJAy0}1)xaTqi|uw{4X_L{Z(eOUVOC|QwFp};q@V~wHXNTt zZ?8_Jatk-DAyZyv_*!1dHg}4Z`R?foI;XI+xj`s!@KYPPa`kG7<-#R? zuystyv@{h-xjNl~Z6|jI+$e5fACa{Er$dZTIf-Ast5J9;R7q;Kz$R5}au(*Ud!(?I z4TI@&=zHgnx?WG~P!lE>sdi|xc^gN2*JrGVLKtr~)o#}!$grquMw|X2Q~q5P;s)l{ z|4vp=JQBrfpuKFl-dxCxZbHkdNqo;7@4~0W!z2xzl{}(-_Ns!j;$CGt`y4#5c z<=-?Tx0@>dR7laK(#u}DDY7a?sM4y%s$NtxugkLnjytrA>L4WtCB(rTYYz;a9<)YE zD5|T7+rWKdF|4v59nCWwV7~$}rwR%ubvyVwFw$8C8{!y*X4O5)vu?~S$3IO@F)DjM zr*FYYMw>%IHR*%f)wBTKI5)gl6lb11XabG85|Z5`e* z`b=|twDR1vd1{<5XH4Jsrv=H60l<06#W;Auz`K z#KnJt(fN&Ou+D_c(Ngt`a5;-yEJh zbEI#lI#xPCG(%#_%86{|(dC`#deoz0U0odUF|ziS$q{|`vV^8TdOt#WR__o-R%(J= zWpBGQpATQ1(Wxd$lH?|c-Am+}=I`*_3L;f16u&Jxp*gIHhB=lFhdx1v+wuw~Bw#7I zyxcgk4iI*t@SkOb6-YOEK(NYYZM16&1kHxxu1(~R>D$EKgSr4;*=)|$mvA{cMBVy; zapgtBxjZII&czy^`QoCGcrPn`|E1_4g(cYo$~}mN%^(m#W4>s_NDK90sAO838I4{_>X05Uf<%H z>o&3@4?Zg;!?&aqFV@G_jjk&@-~v&O;({8ujgp=tN7CaDhh<(;K?e&U-5YRE^=7|s zfdb!VTd!dOQFP!6!Pe1H<`X3>TqglaOD7 zysoPPvhTBpxBc(OBRrUs|Mii_4ezB>=U^JeSQ2%#L}=PtAr>hL^LYZha>{3IjNR5w zDIVH+U}aSvm(IV_JZrRESc)6!x%R*UymCosJWp7J=-O*fS5N6%P}=q$*z_e?O8jmp z_rZUZkv~PGQ`F_95|mud``qbP-mvWUeVChDc3Crz(YV(EKBFXH-f|czuXR{I4+w8T3|KX9xHEMEa%E*=)hE!3!f5P>g?^9up3lRq_pv zY8|c`&ePg%J+IR8BQwj3y;>$cmt=J0y+r4~k?xR?sJ>4sN>(WL2n|7(G0whV07Zf< zQO)|0mmKkY=0P$dd$~TPBw?|7rJ+y7)|aLvMQr@PQLdK{ zY&O8~m>==4`TW~p?7|(YAo}+_k%#inZOT|Uihd(SsJ!zA>f)($b74SWESx`gPM;t3 z*s;5u8D_tK-73$z=u7wqx1YDazD~jQe*@2y|pN3`tqacIaF;(;$qU zD$`_mZx^?`deG(z*J(;^m%6Mh>zi8%gA@PnB7lx+-Uj2og4oO;ykNmDzjOIg8u7VS zaOF$TZ5>XBCHa-yaWp)U`8+*8<`7R!;!RSprpgJG!cZ%ZsDQxxAz7jXB*6xlrpQK& zx3O?|((YKlbDMR{mzcS(hT^9G%Q0pfhWDk36x)Bb#0K%m4!aE`MSZ~jOi{VZes*IT zvXBm3Si4G#wyjPys%p>ShZ%5}UTyEJn`#jMtntAG+iCAl`JKPog#j^VmXK22y%$?q z9G@L^{C|d2b9*c9?|AFWy*$2r`SP-1MddWz`cY`I z0s&wIFZCj6F{nM?NMJj zJ~EaH@1taX*>7iOSKY8KbmiLFlf!u}F$;VbZM5v)$xsLTq34$PYlS%+kwhpu;lP)V zX+4COm8`I&qJ;7-N(~&9A7C5E@WpD}+?R3X<;gR>0mbWQknIQ#>Pp?`A0Jv!V+gxJ zhlg(`*3}_wwTD}^5e>u#(~CFKtiMA17_{ep+Qq;O*aBOIAiP>5H{}Z4=daa1 zK)50SCZj69+HQ>pp@o1)?)t5atycaz)<-IPS08nGde@`F)9iQTP9M9fynE3G{&$Y> zbGVl9t^VwFol6sh$I~y?GoMGKVR>Bk@Fj^s%c=2dJ;{=j26oFjk!L9hVEU7Qpb!CJ zwD|C#%UN#@LEA(dK3lpF?*@ib6YFX3w+o-o2XJA6o{_xBd{-P?E5eLrUgd&nrGuem z&%-BeZv%>*2>-y1VGwhO(#3St_jDvk?}!TL=H}!+BlYTbN5?#`ou8 zYG1?rIdf-4)DS7Fq)pA}P=99uWPUvN!3S{b6!(ybo(x!vM*VFq=+n^Xu5cf{RX&ij z0foKPU|ei_)RQ#xvn-#YO|xk`^P4&7tZr@eN03^*o9eT*{nskpS<8-RK~K37 zN(QBye>qAxWmGcdE3Ejxme|?zOAlmerj_xkV77Ljncmx&cY9{p?3@PG+NBgGy&fZ+ z!h*wD4yP_(xpKB(na+g~BTe!2t{IQ9>39g6*SqNVJSMCfh&wot++#JzvC36r8^#{( zr^Sv;PT7g3R$$cz_LI{730VnpsYn(qgbR-tS{Yfo!>HmiUbT2D%h&eYNmkm5E3*MB z*!MT)*4+~DcHaDWe?8}}_zv7byD(i#!G1)VK72Ln%!t(~07m<`GoM*jy{&WOJ*_t0 zW94t)xS_CmY_!*NAMChaTze(c6#+LFxGe2q4t0w!-C}3+E>oKWy-1TCi^Q}$vcFAE zGD8nG_Qp)THxAHWo^FeOS@-X0og{Vzfk7Acia>YDUDqx!&Qy%Hm@mM65W8Tw1)@kG z>{8N?({g3C%`BdpVU-axQ?Qyut7EqjP1H{WPvPL!t7 zvg+CzzLg$WHLlE5rX3Ewcvq%07o4Jg1M%a`rycJ%f`M?u^j+v)C==iHE@xT`NhDL4 zE{DW>;h^_Xf#)>zaZt~G875+>RhiSlEjgw7APbG2htTrirJZUlFzGYARPxB>7xq)) zWENudZ_f9i5H0|ULA3f+TGnXdoQ?39?wemKP;AGzfA!kK?&e>?MlF9Tv>e&&-%MO! zJ2eUOCSSnSq^Hj=N~bllrMQG&{3KIqQstJ=&@+6wOaxzfZInQB zPH?FsEICEiAOVWjh3L4#ggzQ~?gJ73l`IK19x#0Lvn8ThK)XeUjy_kCgPovEVIn$_ z(w+}cr7H57G6Z&m%POIJEy9$CWz^sd-q=3 zl~z*3!Ky*snv7}@Y|fE@A=2ujPZ9poa{P z#o_9|MWeQz;?C~6M#byHm(belr->ff_U8EpY9(lrdYa#e*Dz;lY);V^aC~kNv7`8N zj20&Nj|mpof2%$SP(r*cdF#6|N@nqMG`K+>JH(LYig1wR@$JF*t%Z3-DY~UQxwf~f zQ(?Se{KPVFl9{BA!_@ONzM$^kEw-J=6IOhibpptc!YNIy2BO`XXrY`494=eE9?Go9vh39Id3dG5o#gE#r$ zJk~k4maWmba+w8ikl%DH#X*IE*K8A z9jf_dD|)l2#CrT0`#N|9FVf~4xLHH|=nY{DR%UdoCy)#?ja=3qi{rkKDgP=O^)z1O52uWoyM-OeFS3kjoay18I9{t$u}%d-u4wGV zkNDeOd_6p;Pnk~4d)(aIGOrgP5z9a8;$`!OIi;`Ju<#~RRoG5;qCh0^+wu$Bpw{<~ zrsW#)gHQ{sO=`BED}1_kiuaWB+U%w-l&Oi<&CoPu9QXl$h6;_l4rWTL3p&-;t==|- z9%L_gR)okWZ*a!&rvHVt0+tTFXQfqa`&# z6Ru-;=zIrQd$wC1L4Fnb`tV{ssM<<=MULFES1}KpzJa|Cv{_?|#@w7!ZwjdY%KXIN z{XUFZ=h+~;Ys!;JxJen$OzBlyImg!nO<-L;0SzMq=HV5QNaj>sxp#CXH@Cfu!VK)} z#yQQ6Y@yP<8*q7Jn!i6UX@+hgnB49e_Hd>)%bOZ0nLaPkQ9TLwlC&%9^H-8GZ;EKup<~D|zu(rPLnN`N37m$k`Qy*YlPDn!yEu6_7%dUw`Cd?7i&_tfc56cYS)}9`KZ)j zx^!PI_I-}(`yEf>x@dtGMMh*8HkAg%hOs;Mka}gk-GJH7=_6W6mIpR;#mEbG%ofDW ziL3p^!uog3*fgq( z3Cx)zLR`4{_`VEi&$dycI+iU0(VsY?{qVvZNHB5;Hr}Sr-i(1Fd)YcDE_G7OufMb! zMdZ_UfH)t-k2fy^lC^Um|CI!6$WAS|(itp${}&jU!LJvCOjEo-ALw-4t$LWD9gfHW zG+)zs=_YUT+|mmkfLx@w9lAaobkKzhUCEcj=X)UFyH~sQ65(_Z!Zu#nh%xSjFBQV> zDi0LplWxjfO=20ps^;nE2Dwv>NYj!(tLlI61~11nQh#jtLjJ|K(HsGxxiZ4yMf?ru zV1xxta@b_?vEip;y^&mMw{~q>kmzTT4Vm=gNZZEz4fPO5@kbS;T|H(uYIn& zpZkF42a-NT?m3-wn>&yYDC!wtqf&q5)kkX9MH?{Bo>uXQi8LinxcEhy4L1J#>EyUy zwxH3jLap_2{I>7d!JVkNl)GRIL~vpVBzfu6Vdi`F2Z|=^GMm2o%J(EM2^;$j0z^(t zsJz&pUX%AEg_))A^USyz^IuCRe-E{4VnLsJ~~MW3!L?GLG3y zbmI|`u~jsg`wyE12vM=A^KNiy>4AP@V<6}yGcHLFv)XB010jM0N=ocM!XRR4TqNHN z3znd=8O|quQrK0>R>%}XDn5P2?0KU>3lu1s0+*13(0HrWhn6)a5tYSdzRC$+Z8e!J z;1F&KNJ{0mM_qneH3N@hHOpv7IW5Zr*V6vkz>pmnncjMiOUYOb=4G%jhXZl>4P=7gVZtGf2#+2J}=k+i-y1F zJxyP;%xmuS4&P4wftSu^LO;7^{2=BV)z#J1FeO5hSTfVRPxrPm@iviey0=ZlK=|fX z&#@(jGEVB?JzXJ`CG1{~Z?+ii(>UMF1RTlwO=`ky50*nWw;VXvJ(Opbv3`5Pja+OB z%HDP_4tqxFfz3}mNf2_&&}-3+e{7}UkRX^qAG$JMyp^5LeVPApI>D;_e__8{;>!wn z&Ngemd-tb1$}=p0!T$z+^aM3LHpzK#8B=xuQq`gY?S zjyW+FZJes*wEZ}Tzi!?3S>AMndj2M=+a4{M4J|7YG!J75(f|CBrs2etxQqp4C)a=x!c8RHwfrF^dU0(%Oo3c;uo0 zE=|iW%gZvR7l?|AhBkHpy;JR0>%G8U=bX^PVl=VyQ&<(1#oMVausAH2#}J-NWQi~% zX_waIO^0kuRH+Z4;!}enQU>wneQ4a%8SC00UF}-QV}#I^NZ&hDI^__&aLQDQiQoVU zmI-dDKvp+{<`5WbPTliz+mR*DOv{aad2#Zcz~Ks<(QZ3{T7Dm)Rf!G!zIbE;oMbTr z=CR}~l|P6M|K>+VJ+aqvN;Wv3&2P>y`UNs`J%v$Vj-H`~n3h1ZQj}o3 zc@az2ObD&_rqPg73 zJtWIg?`#fnQR}{=uA5!ELmfQ$^*^!+Xa2kgVDoN3W=@UWog;w1B&6c*xO3N5oYkVn zk6R)QCe;!{b^um8KAO}200%!I*h$kX^SB)%@q{>D?^P8(`{#O zhN~WS{8DP<3T(CII+zx1_M@^GIu7lJ%{cMD$#klU&_t)z0qa1{RIRu}uOkj`UO=Z! zu<_hR2N^LBe*rHwh&+t@MYT{rZ=kI(ECEO>T*$&zgR=YI%kOkN71a_+)3g*KCh+}< z6G<2fXeocs{*a?b{Xj~&9wqZ-6R13EKaktEeYW$IBq#qisXqPn$G`o1G)e>&=5vs| zLNn*J1QkFuIWfRYL4$3sE;&~Q#PNFX_U-3d(ms3&(iBFfg#EKxnt}%cUSiHZ(5NW= z0@dh=$O^)jSVDosMw+D<(^=?J$=?HkR>=m+t-cFfI;`xlEUrMDhu_T1i%O=W+cxzw%Wt1Z z>_Op8;HHZ3>~?SRY(&gxpTd-6f%$p(%sg{Nzun)zj8;%&78EFtMw zflNU@)S|4h1gf&|A~rZe8XLNHSXF{*vKOqKjqBS#&ogj)Q1H5-AgiSE{$9SPd@mq8 zxY4!sc;?T8N5xD}@>f4|4y!3(Zr@W)?!t5I(*9=D+PpA7KDmTiQyn?jZYua}xY9du!KdJ|bRnbRsqH zi_0ghz;*2yKko`Hv;29!=~A#|H-GpO%gzB@Jj5->&80V84%sF9g-<0bwmgL4f~>|d z?5SBrCK6;HweVfJuv#`BR#c2jE|4cO{||(z^RJ{^e1_{?LB?( z-o3;jx(EgBW=D!yr1LIfW8|3mrFtz$8%gZ76-o}}f`)+Vp;)!^T_AC0`a}Uz5RZDj zfFP$Jd%v$dgOCAj)>fUK=fYh+E>?+}XVZSeB)+C%6%Sl>Q>|LXS~4t|z+*cJnX zld|4!&mVZdMvr>lZ@2G~$4l<_yt(sy2rc+CvByBOD-UG#eEh0{Na@=9Sep@lZmrpE zi&!bTO;|6Bnx7u*ANh;CM7;NezHbBJCWF*cas2S?Lf}Rtiz^I?DdW z;(hB|6e~+gs-}imf}{h(z>(yp5Gveb*+uu1^NT469>0NuX_{#XNpXq#mc*Vl_kGl) zn-Y&^+EfI@Bv~L@NDL)907AyBvsa1>Qmh#7zp>wXoO-HO6Os_UpkK}TB@{5j!T7o8 zy?`&-5}aq5=fo)_f5IrtXgM9L&bQbVSoBE`p2RlAN#_~Qa=)x{YF+(Mz=bZeo)N225rsuc^47gLiY5pmxD{lphUs5B=!C82THpgOu35@EW zC3)a%bVrxU<@o6FsfyG6ukHqd~`zu-jPe7Ts_K#2dOCk(7jP{aal84(W#937%Y zBj(!4hH@^aQS&*8w?Aba)B24jc8vXke3Sk4H&Gjn9n~5uvm7tjxH`1RA(~{e8!*TF zGow4f?6cAWZ$H0FktC9oQMRHIB}ryhgGw1?l(IJ&g{(+@$>b3A(L{@&O3yw3A;envNmTEUejR(qT?qT$vk!JsmP zf4XvdpkH|dL!7m^D$d^{gXW0wTz6JLvk1X_Qz4!(G-REK$e->Pf3JLQKeW^fYp79qo2_p|Ej3k<0AmBeikkf0SnCm7CgZmlFnuZru>xBB|XwV$ZW=!fYp+ zSj`1j!X1iUyA2py05lJ`7CZ-7{;*Sgbg&aFUUk^<@Q{7Ngyg8%6wIE8>ysb$IJXKb zFMb$!{zH9*O;u0o?#W5r^E z8_@xa5IbAFCx(LAwZBgXgtH`_!`wb#;_oZP*pWvre}S*`3LCAV@>mh_-uia@GvTEh zWaHrRn5^<+W;Ri$0>n^JI=lptVdyJvt2g&gQ=Cjh}tgeLNV{ypx;=MPuaIRfQn&BnuY#LX}+pS8~gf3 zG7nzu$KxUtPRX@_1DPY(nv-`!Nl;D75@x!DbGO1Z1;)=A#S^mhbX!TSs(@(`(H1}W znn-7Ly1u#KW(G{qiCGYEht0x<&pe@`3=h_d!K_pYI@SS4yg^q$P zsoK+*p1g-FUnqY4s#Pbi^pi!)ilwGB<>gN~Iv2y#!RXUx^)~IZr+a%(V5!cZmq#A! z5v!$T&2M7<9406afo3~f_14&@Gn!|O;X%hdOm)>Te(vzygvTTdPceqxYw7wR00_4{ z)kYY~zzJ4yaB%Rm5IKi}RisDCO57`eTC##5&PBLx%K#J&e!efVu3e)LT21EJ zk2S5Hl@1^^E~UVb?)a5{4Buky$}BnP@amWDTj!uCgGk@prD(Z!crU)Sa`OpE6_!AB zbUJL?jJ~Z@m?Gi!BYh2rlC%;(k2oxm=k}X#%Tp#0e))6F71m1*h_HJ*z+`t8-hSJ8 z#-SdR;xa<21}?7RYok=%jtLa?1GpxIrrcno#-(FtFU7r{t1ZQP3V((fjG&^VEo07M zxeHF5dHwHVJWb?YCxPBY&7L~@jo$pl)ax6+PfF1bJd54uRek@QrFrypgriqV)QgbzrDKiVps%fsI ze7b+qZh7LuTxK7f`w#BvKz`Sl!SUGIdF&(`2YWc~3SBlq9W}DF)_Xa}YlATx-f+Sr zd-rO6N@{n79kOLfFcesQGM83k%@T+O&y>wEgEbHmqP)rbz~v0v?a(v(I3K%yeQ>%X z#4?r1@8jgSIN8Nv-4+C&%$veaHXmThVUo1K7)82rNhj^af=?IC*$jmzU%UzyCxrFz zHkhi|e?}mN`Gk?%^d(Yyl#J!1ECE?aq-_Vmr2m`750}yV()LzyrlY&(Q&nCWyB>8A zYe_w}nQj~{9w9LbfOKF}{_ra8d|VbV(H7drehYk#I{T}i-~2fw?!g2SV+yJGcU4h* z@QjLbgWql(pKsf&#c~p{rcLdyGn>?a3(mtMj{3YF|CE0x|p>rAUgxOE_ z(o=8wXe;ffynaVUxHoSue=eW}_V72`V#&XcrG9V;P;q}MIj_!3$D>Xu zE>$?BMzxk0hyuHi?tg)pwz!%ZcRGeg>ni9NDNl<~-4Di&!K^P&{2Za)QX5-hy6dAdFr4FK)=l%?;#`6^4)Uf?0hFC%`Sc;9!mE zCI*`+el1#q%({PDM5Ln2x-1LmP@|ePEE}m0iQnijR`lLF0f){IBy%x`=zm&4G&9Yx z<<(sw_?GqU;=Oq#+KANgkYOd;G)}y0Z{6k}()-+eyZ6*SrXK*3wLP$D^gz|c51GTm zSVEexnZ9Rb)S;sms44cl{rc{8fPyXNtuLT1Wp{4~lRr24oJ2fM;6Xf62YTXzFrzY| zIZs1YiXOJ2WL0qFKzMpT##Wj}q3;Hpi?14|Y@0z(n@aZj&#c{yJ?g61~}mR@Bz zP9)`nflalN5*%@$yaBJ`|DMeRAQGO zwle`E+8T5<3BRIeaCCGr*jLLeT{AlJHs?BrFCoZzd_h^xr1) zBuzm)=`+KE_Sq*sAM5-Ba{O!O+{VbGqCGFPD%YB?j+BUz&IE@Czj%Bj%!NX((+diV zU|Oq`z5h}jwza0O?t2*A5gr;86~j?G&q#)}q&&Ut4Toz}5+wXqb8z(B;fXc+f_f1| z)G)*f^jYy(k_@{d_fHB*zaVBQ#W&&C1sd!U#`~G=V_i+!ey8;U$A3N_v3~=(idcVY z!1lHo+)ibfe9S-tR4>&)P!S0&f#QnV1456y2qPh$fg^msQ%iGCKQwPuHeJ``$DNSX z^)9L$a`DrW^{A@%xp+8tT0QE?!BC-!3NBRD5W3O!iHD(niM6wOsjjr}3n8u#-0{@^ zE9oB3D}r9(DQ~>f$MOGidV1@6aZi!-dyzJQ{HBS zh4?|EHsG01Ky4!%s9o$V8+$KWVkU2`3T7hDT!)^l=z@4GQ@Wj@Gnw2Sw)0iL^Vm0k z;FkJ&tKixAOBQg_Es}O@yA$RRNN+^!OzGO>{F|UjwY{L9%zh#~mOjZ*qv4Ehr2`L| zsaM0fsq_tK)N0n$k0(N~WLJeFPDgC8(Ot};vCcU?smpNbJ-f{4ia~?)*!r?EP_Pa^ z6WK&sQUUrrX`^Gu?jK5hr}Ve3=A-k??h8F`@Td0T!C)4!YSu3{yO*#{HLqJ zF73L4R__3IE-vDGgo)1LXErS*&c38NJwH0G>dB-5ZI+}z+=lpIe{c$#+Up2&(7xq@ zm+>JgUgi0ijE=@BX>xMbH;j-viZjrXXo}%NEo%%cWXat@5DV|~K*_1Vq6*X#7Sq;C z4Tg{?EqouoQ|}aAO8N|vXZG*evnNOfd=)Xearo@Ttc&-MPw7QuZm(JwG>=9>!iHPW zBxiCt;}C>CorpCt%hCVRagLXGM^S@ z_qo?BXvylG1f|vtxY-npr~n6Rz@RSjH$$=TZK0KcTN{5d+qJ1*dBN{u_y7sikpR7mN!p=RT2zp;MeD`k1YR?X!|CuC#8E8Z_hM7 z=de1uo+YO*DiN)SneHlM-+HQoc-;&f!zX#Sn(iy&rSX3VD064$r%k(^My#8<(DcRZ zy}6vYILDXT$UAv}arH{;bSoUwg2X{E7v~ud=yFN7 z)5Ww;sLKqZ3q=IATQmQ%7Df+j8|`!CYwzNVCM(U+dk#do;w=FG+!$<@gyv zjR*jMN85HG;qvl^i1r!?;v3tu*1L=xKGTpIdZ;Amp0|^9OR6`8*p&T{=1cy7H;pI& z5vsafp!SOa<<}8;V|!vTVtf3~fK@bE{*rRN89so9J{ot#d_oB&i1efA!nD-E{=eK#4-?Yh`3#qx>Kz42MWcZ zU49^Pd{2;U-ijNZO^7A#Jn94d_|PIO4YV^)IG2ExAm#`!M;XV>lQ!Jx*6n*Z;KA`2 zo4*6msOk@C7yL$o(V3fwnATnoCt>mD?0#~$R2CDHI7TZv>Vv8zYXwNkV?Y*ud8hc> z-+H=?2R}7;$I>oZx}5+m^O;K8>9$$7714df`12s%D%U9S2p_mWOg|mP6i97upx0}! z*phQkRG7M3kzpY3p=Wg5%hyO)rVf)F?*Q~o4Gpy&lQ@L#u|@c|;LeM63`=FW3A$gvl`ReAK)3>(@3#$|LEa%#hO9-{-lP(%19}~RJsa|4I z>yi?AeG#1P+owFX)Bic}MGNo>oU>lB`hQqTZls$}n|f_tz#FlC((;l?(i?};hsork z+)R%RYyiezKuAZ04x8xNnqNyIp zI6m$CDPFV-$r>*l*Bw}6m8KzdSMg@+i=#exCv}U8Z676>3t@I10abEKcS_P_kUwo{=785Zxz2j`mU<=$~OIfxB%h7 z2=04>OI#>z6>gRWBj=QlClwVVI2RyWX}D7?&?T#hW`8}z?g7?jxlq&lI1fK|BL@Yf zn|;|Cp;?zo+5XodA%P$}8ipHhfV3(2r{hQ^L$6#~H8fV1*+ zan1^>@p|f)yx*UQoEP%d=VGeeoqfIM-z3A`Mxgzct)soyew~SSVA&6vg(hM%xjF4( z=Gql~`S9$lD^uurYgoiLZrr;?JIQRzPoO#42xmAi=?_Zh8@Ln1Kz274wket*c|sKN zgh?{!V-2h%C^)5$x5X{haK2-l_Qcsk?dTu~5=6XMpMLw2*Oz*a_&1{OeCo1QeQ!}K z#g_dlsAxxEz+<`P1Od*}$)oRXSmo$`aE`{Mw z15uY7a79N~W}vlkfILzVB2v+K;+`eirk+C;$oBF6=fXpK861e3kKHeq^5<4{m#4V} zKAtK+`*^-Mcj7AdtmW3kLjyQzRHX9noxprs!9Enj8=mP$LKZZG3ww5tkIxk!FyHuD zlj^BN4(zA(w{eU(^Ecz8J^YJBNGb7 z3n90Oc{o6}hs2UKVg+U77b%JGGm0UVX-QY2_wLaPeouP#%z)Uq8EW2!J5Lv71C7-p z0!OG+)VPAt(A8XqNLOkQ44&gry=I_JM#)o;<=*m~oe}}^ZOyJ$t1AJmn*bpUx zzNG_GYvRK0g@t5~u0TsxbayY9FP@VD`HUote-ej}p#*5A7{cTxD?MF=T${!^QqRUi zO>D_$@1qZ6%tlPBK9PaI)zsdh9S7&WhBLUVhU?cVZ)l6BpA0ca^&JL@&U@zaF$u$Y zKS7J~79NS7NF!tj~eR{Yx*?NjNntu^Jmt$D^0b?(W0GxY8 zV4MBJ=fYNUx4F=5T^pUIFk;Vg-Lz%=%i`Zx1+LLo{V!c+AMF13Meo4bKh1DQ^Vhzj zEsbHKKWRp;U5aimazhudq@!FhkWbEr8Sc>sI#6 zV@qwT(7&J7)3PT^e`q-fiJLhjMum)x|3Gp8mr1G7cJ_pj7^t zbHOyv;s?maqOceIF&Rd~DootyT*6)O^HHXAqjXb2ghc7DY$^2^3yUE3fYf6IdL7rNLfP>{*zjI zp+}14IEQGp;pK*i<431!+_PmDHt}`$tLGRd%dLY+L(5YVJ4%v~05bU&>l0Zg2TbZ^ zzW=x4rOm?!r&*cFi&6OVGjs5s{x>ml>wRU0Z?wPzL*X&oG0j;pD@g1>oW%?2ezMAh zQ(4Z%Tcy4S)zrjItEnTl{`*uR!wev%_k?r(-Li&=Tio5dXgZZorgE4(EV?Gw-5y9~ zU$drfg1P2j&+JY{s-ZYhzCSI*JdYN#jmj?^8E~d!$w5Gl1ohz{rP;;Jcr}_o?zU8S z9U(4QD0O=!aXfTQm;^oV!5^l*^kLvNemS_105Zh<2d*omzwi zCBd^#>qh>>8@$u|5h?2SVRP=bQhYfV0)JP2UbE5Mv%xco=j)l8cy zve1FPGF6`;{P+6FD)dX@)$#u3)6hw~sx|3=^2q^Af+RC&21l(YAIrmlt$Ka}TAj@2 zsvsyis8^kI%lrM+|KZ&F&t+H6)j-6^=CeP^4XC1scP9kC%FI)pA2{&FjXtoacG zIg3Jwxq`_)x}td$|C0)E<{3tVM7L3HyBB_auaWOrW^e{8SH*s`k^*%Di|&W7|AA-q zaLd4CNJG6H^k$opho0=!)xFClWd^nXff5IZf2#`Ynn)j_`NVKGmUdVD^pbBf3=;Lp z!QzxiVc%b2_`Ab~(HdIgAB=x|QOQ?E+@?1~N%Q`gNq*?Nc2?Rz&TO}Jn>+G_OJ)~T z-N4)9!Ocb@?rFe@z>?$-$ooD6P{Ja8H{UnSXJ>Wk2NZtg9Pb4j>#if+U>z}ISwBY= zG2U^yeGFTd1Gt$#-cb~M;)bDeiC6M*j@?)tgnjP}$k{=Un+&!$AsR${YLMrnQ$Rw0 zVnLX_i?m$qx+98MkLB4WGUX5fVJy>`q3Xj~hQU(S-??3?l-Q$t=~GBSbQhkn40@maE?PCHpv-q3L; zdo*GbwB)K^ldr5VyqFGy-nSwl`>x~sT=xY55_N@$WeMJxNl)y3j<1ij3ofG{jsQZ1 z35d2&`(;%ysxyJLy@AvYX#|(V5{MMA-zi5YU|qTanBNk=*;dWL_Oh%ba~%4d;^8-w zoH5{DJ!kv=(xv_G?@JAs*0tv8@lV@r{=Vn`c&)z&rg(Z1&j{zMy5StyaO}s`bg;e^ z^m(bpMMsmgR5Fijr0o{PJ#N$4=Tn;NKOWAR1_kZunOgq$hLY>teqE4+*=cce4JLX= z&{bn_wR_n0-Cs&iRHnqDy?c-B(Gbt8z!b6LyVSYThl$=J*x2>sH|q}7+WC=W)D!f| zyYv>cwCy&-^zPN}H zCZna}y&ng}i}K-&MZzbTQcl+sK9UXJi7KDFpIC=*bL1NV3hPt?`ObV#Kc)!&x&dnQ z=isC8YYs-|Qh{dXk&m&la$hQ4m^oDVfsobf+pU6oM%WKv!ryKlc)yVL4A?2Q!F(=h zhTi4J2s4i0f9(5S@%=%QJ&Fh&#bG?)e{}U7Pstv1LEIE@wR49@-w_wRSR=*kT;an} zdtor;Lu(H%^CCPf>q@?r3pLGH&g&`(5jM}VPq9f-;7r-Fk9Nq0QeaLZ;qVb4FUpwl z+9h$YAB|e&-f!gbDLceqw;$zkQg+|x=K(0@SI;o!Y>BAKLh%d6%u4OqOx6f$_eEaz zT+rnjLax_MS6vC}$u`(RZ?AVDo$@^T8J-9wGf2`mfMS`w*7`TpF|(ax-`^wMh}`*n zmh+1g{|P12v+>VOxQ` zv8@0^SMBMy%MqKA_9R5mFo(}fG_}CJ>g&;*@(nv+b_c_v{D~&G`jNEgU&O%U0QQY< zt@cmWV=MlnHA^pF_OyN$#->{XMUh?aY2V;4MPhWw-x&7nhFX(9h1{4$QO{d+3iQwt&_b$nd;K&&*-Di*{<8~o;S-1nxAmmM5(;B8`% zS}>*;Jo#lV*$;?L<$Arn{Mg0Xh!FUZ`B5WB)%f_WWwd4l@0S}u%<;jg((b?gE9Ej^ zUh2Yb15ss?LPG46DrCj0i9^g5YUlp@_sCBUE;83vd1dfPqRRqb|7H5ka8Y?M4)TT- zLc{9aa3Hj6vnuUM;7|{FwzAb{4?XBxaY%*-jZ{@&A|XV6 z&7~f$fIC@Up4STpl-3Oc+kQGIY zLxMyPH%u!>rMZb$m{y*f)Tw+Nw&CcuP_fcg+l&m5WMn>*&Bj^XFtW47n!%oSrxyAC z;Spx6eZt0*0Fd*gom^h{;#G6#B;^}ftA85zdjF5D@%O!cx^fpRc0uqe9d^#!nq=jh z)EqO%^T68ydJ{k8BC=k@+8{x4+}c)%qI;1FYI4Sxh1zAmzHBev1e%Wvoie`kFsHF^ zoAJ`wy!awiN%V7skJG-4aKr#bcIu^nioO>qMloQ`fpV<7>Tcn)@gbga9Qwn|DQ@tC&vyfu4|`X`#;Fqfplf#?{cH2 z=r|kNg0DBy;Fb3@3a?mP(EJO#n3!23|i)^IZQuVF+23N35#E2WN*3Pof4&P;c z7{{n+4LwQ7{DuAPl5L~i(Y|CwDI*#H_NgN7>oZ<1$P-l~njx}^rfrWJmE_$@Mow=v z6$F;x__mgHD9c^PdKSpc5wB&3vvODFbWWUQ=^J_a-o~}rt#~+3QyD8rn#hv0lt1^; z;`H)A>ShrOpbhgdHeEcQLrlZTf2O1ol1V}KThf}+a7lS?LPhCXE<|-wqrsQRZF(;s zrH#7uXr-XeThoSUT2ee_vK$DvNBWzOV#3?HEhe%||9nCHm#ZYN>1^|}gCparC2=p5 zN5+|GEt-}G>WwBAk;-1R&c7l02ZiggF-29EFwUz`!v5}{2(?%82kx&Rz(i8d_dzjq z5?{NA>f7fS^=FOxu^cl$ruI-rrl2o1pDaO-dp+THJKK0>5=Z>%FQ604IStiLj)@>p50wwTF92$a>i#lCIbqn+1u!FkqTR6`HWwsrD+tYPvP$bR>G z^TD{jdVBTuS3)B7p*tRj2rt57C`4wW<6c~EzNZuLe-|$o%S#T)UDFZnr|-IMBZlpX z#xDwM9kJqFFACBpNpI2>ipnppW=)3&M)uD0pIR0R#C0a$-8ta7mZksmCkY#ym-4lx z7=Alpzw`F6+n?t`{82L;M)4^U*;$yG#a1<6@>utWhmF(w|E0F2uRnAsxy(GBdYExL zV$gw3wv~#Rb>oc5TQi$2&cOuwiqZ^{eTbzWMbgn|GYzlk=X<7M>&KrLg&OC66p5MA(3v(F_adG>Qs+4NP@AG#uS#g z@A7EUOo4ylcMmJ8zFIk~3KZl86Z(FfZ;E49#bv|?h00esFZM*CiKI_F?biiW9lnPw z4;g&1Dk05i|J{ygeZGmZ9g_LSgA7!p0y+aG#|O6oy3Q!hBRvbLAWZ5 zRQ#au0E2?23jfAy^EEtdUOYgXOvx@nKTXVzNm5dp0x{^j>~2|4s3xveaOG&Q{L;RM zl<4gF#QOQcZs%vYkA=r32J#1wc(GE`gZF;0+QxHSS8l0Mfvt{u+UjlWcE8Ldf1zFw zjQja+iBvE7XB6=|;`_70!hR&X8(?-U|2coA;|y}*tVU7&fVr) z<94xkjSCC?tIJ+l9h?|0r$~-0)6 z0XTAqoBM6^ESFdYubjfKTVb);6TQFm5T8(qn74S1>@3DS!!0P_(HCq){~YK)fP)7y zvepj$yXCGEVNH%UDUUjnEb7Ft|D8lxS{ z$Pm^7b}>N)%a2a%*xY#5+-INNSKsl@Z?l)TkbuL$^h^G%EOhxypa>{oY~>Gko5=;& zwJ5gz_3PK==-sywYW8$<0QA_4%p>Qyw8m;Y%-(pY+;X?*^#cn(l;3omRx=h*f7IsK z%9~_MB#a$u^2UALR-BWv%5cIaTt3M@zl?ufxC|_TsJypnKRef~v#OE8)nnCcpUP?8 zim3+{fA4MlK!x{fY&6AnkeU6^EdZc=(b`_VIvrAa-X zlkna)UHW;O8IP#!SrPP9TY#G18`==a7dJ{_dKaA0m6u%J)%jmb;oZx&4-;EbSGAmB zME7#lh(u>6)};oj83IHsK;gB4{TklQ`L|8aZnegr8giX$;`}#W|4Rd-Wyh*gX7%p6 zx+stAUPE0*l5_y@>eIQnAqN>%F_Gc@c-^RD$Ug=k{v*hLqg}mo?<)Dwu24=>)f2aX6kkyI`Km>Ufnl7ALhF)}fy-V_iV<8Az z%AZ`P&iRh02rzc+mA5~m!jv@#rdn*O?F9(oLpuoH^_r(=p6!x_JSO%Y0bRdtB)y9* z+FIpomJ=U*C+J5r+XHF{wswR5vON@X7`dJ4^GuBG<1+MejDe(X25)Cf>g)eZn7(8r zVdVXvl0~_Pp3Wq%c`Q8HiaC6Tbwr>|)(K(SHC`k~!M=tcU%@-^Mi>jMu+IK*A{Io{ zG91sniq;(ZW@a(SZ@-t6GV@);45MvZl)S~NR{lc|-SY*Sa@`68Vp{oW1R5*@hxZ1L zc%ayhj1y&A$B!zxV5lGR>XdPazB0N!%w6+9|@s(*@N3#F)g2Z?+PVFrSPl&QOAA6 zzC7%ll=?rE6zo#$kDR*tr3V4i5Z<^_t8D`}PvG!3=d{%%$kI=z4QTy}>8BR()`BB- z+J4mCb9d|z#ip`=lOb#hn9*WI!VK>#9wT+CT6%0RuoR3Sv#BJYDW4w%Qy)^bn^QtO1)u~y zHw6J{Bgs)G)4`(yFjSAh+DLL?^g>edO6g%d8;BYC{^6A_<{sBNZjO}QNHvlYRF=)F z7#W3$M2t}}Z)hzOy)fZ`RuIz>%t7`}wj^f_kGlpOnmzsMS-ZGdDOkpBM4qUK=FR8N z?sc4R6x6R()!VIGnKJe2Q8QR4VB^r&yJzr~tB}InHGgD!v5T>yJ}jnVAewnzI^cN9 z>F?M2fAJznpAA=+F%vh6h}+ylvEffQNnad&@edbZjtO!S$>d2oXB(DkLPz_$0qgmj zRz0CldR_^pIIwYX^>3>^{)qhXu_Ogl>1sjKE!#)J$G2Zt=bv}^ME2ULUWM8QcwP~D z*t(uzb+~MCCpYi|I3F9#ACx6-a!gtI3>8mYw_4BqawP8OiQPn>CKi0J*E8~X|P+LCH8ZqYB7EabVU6$GM{aBiLkBt_rcJY~WK%mv_ zpGNp*2M6hR|BfK6Lt;4Ku6D(%h3Brh9m^4DQU{LSMy|9)IWWH!*ID9gy6%gumrnp2SQ+HXd38N>{L9Fmx%_0vULa}y z;UrLcizaoUeQ*bLeDE%zIhi_b{NmnEI?M7qr$XjRyu&dQY_Zm2P1j*q3?PnKT=2jasV6@@c?!PdM1_58x@-TOgbWaxpF%-CFLT|Zp1=6o5bx;^9wc&wz!l`*sPl6(=|74af)HVPoR zUa}4cT@o30n<9Aj8(Qb#ld07vBTogYXm#RvFoC4G~i z`{hB#C?53nO4!A3M2ax_&y85&uta?n)5ec-i%`w#qZ0RPx6Y0VUD?WYeL@)@B0S15MI9@4`1A?6)ZVm zrWNoj&myo6K)dqv1yK;zaIxRT)K~%K&^F>f0Mqar12XcsKuYP!1{&0vTe1!M5-BaR zSQ@?GK$&bZVi<7yH4(otR5o;A=+^{u*=WN~KUCi`h)2{Sj!b>RHV=kICGGQIxgUdF ziq`6{3J|C=I>^&p^H8ko=ouz|>7}>1*?*ifuAQqIUS!3RbLjT+KR1Sa(LOxDbGBmi zmp6f=7mQ?xI$evC#wi`z2^x{}!X<0TO-HXRU%Z|3?tA$Iw3b+pC+otO5)ZNC%T|1D zXf@93W2_fo==~tdL1AU}hZDtv&|R6U3debwwi)o~3m>gq=N~OLAkkI$qf$CS)KGj?9^L7!X!sy&Zd+6Ugl*VNKGaEa48<0@F z8XjvW2VF++;JRcxFp@2^cP4C$@z_u8l`^gE6`kal3ADaC+5WO4gBM!-Jx?!g=pt!L z0ON^PT~zzv!5(O!U2UL`JDqm1k~T;V-7Lb)s&=w9b1SZc|5`>vuCZU(df#>X@hlA6 z*9;0AN^Hf>)NCZlLrmhmQSo5fPMKL5h+9)&F|uj5^O(4FV$8X`boKS;0e&+*Di>Wr z(mx}IK{hD^qATQFLtP^NbD+m?Y37mqfuVr!({JGkx)1D)hsC-Vq)Y`>x@9(YeyL-}2<;B5(i?hGR&ug9Il>cz6 zVDrJ^d(eDZ^Rjq6Vl=L-YH|pk#k7@JIFPjIpd#;*Owva_R${+w5lNBRmcC zJ#YHMtYAFDe=Tv)*dq4$IiyA(!9p~{+bcflKWC?w5h8$UJlqDV$5)q;+ssonK3OQe z%h}mam$r-X|2rrPQ9c~a|2`eYpV%}uNbHL9Xa$#E1?He)@0706L9Y}n<2YOf!w?<_ zx+TN5wU4b`QRCrFKS_5QT+m0mF1&gax!wjM&$q8LXiNzCB6fP>_l@Gm$EqGIx#m#Xx^(X+p}CJC+b??QQ%?Am-Ck^XUDr5 zO4`32xd8a;0ju+y6W=nqh@a|UeVTD=&*(15kSfD=3!>py7a+#SJ@2Evn4VfD6yRNs z%6G?duWgo$f@ke2(=8?q9gjd_tjYwu;78l|ij&^>d@n; zabb$=lo?UnlG2@e4($^z#)-96!Pd?`Og*sm0-||KC*u85soyBas>TB6Y()I+7k_-> zH-jbQ{?II%7d7+J6=_u>#8BGifPC^~+^>UYF0mL|8>X8m{P;Bp76U|vcSIx0;b--F zc%@-L3eA{avS%0`q&YUa;cHC?-%niI*vwwv`VhO;dxSl(&Z(Ox7v(&3Y!vs}0pyBe zxC#91ZnE;X+hK!EZ(i+71b$vDc$Fr+=e=sNUL!Z^A~kgp={Pe^9W2K-U*yxeuLN}8 zg~8^a%b|8?{+IaHUr`2Ap&kh*0Nga?)+xu+#^j-{>_tU6x#o$k(QJee-mb)$G}T{n0L|v-S$C|0Mbh| z9yGxM4c<}Pyox!YD|?RV?^L`<3TH0xbJDG7zR08>B*GA~Mc+CeqNo5OO*_-$GDa(_HKxG3KfR|v{!sXiqrwnQn2Q959(wM;o1-PqbQumQ z!}ts9SE{fZS)^0-y|*o0yNes2Bx9}j!1D;Y@$~fcxKBS&~uT%f=b4ke;qBLGy8v7>Rxd#%$+FX^`$X!wtVXGIvQrKWi@_ngUj4Yi#0oX zL2){J7VG#-%=xD{d={(Se4AmTrF&2@66#cS_7*0#6<@K(A6w;sWTOm&fEe$D(mQK{ zQ){g3PDKZ{BUjb1~Y8;_!sxQW5c#5&oo@ScFS-ctCqK2_laOan|{Tmck_Nx+|I$}4Y)e; z8M~vn4YlBa$oBK873%LP|GTpGf92$O21n5!&wi5LN0u&gAJI=iJ~_sMF9SnLIX+$A>zaYFTD%_1jPLfU8YtAc*nW2{0prXLm|#0qgI3Th@shVrZ7t^I5~C|LuUX z(F;QZRtRJ^l3=fo2%dzzY)i$m0PsqI#C(lDY@_?HfFB~v(inc1f9=3etu}}RRgb!W z#i3e*_@-PKkY$V>uY%l%S5K+xFvz8~&F@~%J(u(>cTY`X?%o4io0QU?{+DNzrf@%- z<(g0*4YLn$*{ANee{zK`ndmzDW0xpQ|%JR>Ij7zJnJ>@u0(R17}HHpgb-23JX9q?q7MW- zFmaZiv#I5|<3$UH-CyL1u0Jv|@r<|v61Oqmpe2d zz)VturNHu}u}kHfJ7d^URv>h)FTD>&9s36mZrPF}?lQTbo3Bn5iy29f<_<(-FQ2FT zA9^a6V4p5-$`wQT@Mf-6Y1P!Fo=evY6L~|`gOLgOFIfRJ>;#Jx=(M<6AT-$X;0`8W&>TJ>gpWYM0~z1}?>%F7a;TNL8? zS6f)Z@l>Q<01;PyDO`5+AHCrHfTG|!GjW=@A`(KM%{)-d$ZUi>XKkBH?s;W;S1Wz= zu<`x4YU9yCcYCRZR*d4p;(<-Rut%*?O4d$3wWptjQ{1}8VF~JlKhWHA*nSEr`g2}^ zJ!e7++btrQA+Z^^EMml6!Y`sGomw(k=)Yh%i&!0xIC_w~fD+~I8W$b@J;rc#_=PYY z9-b)g%bPe?-0+?E^{=oK5hz`U(F?i?MD#sX{AE?Qcy2Xtlpa1J{=^Ht0!x^9I35+R zT?$_++}Yso5NkLvgZ7VBFV)FfeiXghc3Ll-p6D)nzO=N|TjyZxNn?3-2ha{Qbhl1j zdxV<1Zskv069<)SQx>18A3&m~=ErP|HK&fNTV)g1O?KnU?L(qaG6XDK=fIuqr7)Yz z9T7POCY}PZS;nw*|G?4e`Kt``Z2hqc{S^B}5{`T`#wNHtL?Nly{JG&=ZPzdnQnKu9 zF_9MDn(zeOqwSX(iviq5Vv+WSYm=@oLsb2{O66zy&WrK8W%wcn3t*1Doq8fX)1^;6 zA+Jq9N~%dSIOg}6Coj=MfD+jsS&r}eU4-$t!q{_w&4$VI_Nj_N~EFnBr&J zc)WGbu|18mU5SqORPvH*sVdvF4O^YnmsH{vEeP+mwU>G^WxyL_jSH&+#(@Vequ1i& zk6~D5Dy>b`X?mP>rgq;5gVWp&HjCB-R>}Oh4NGb&W3h&0y&gC&}P*=>unR~ zefvCndWbk#4Mv_JJI}AH8Sh3+ykCBN+!yo=@)zRXN*-seHnA{Dpw<<{18xTBkPvAAqYJ1979!E+lDoK^W%CgBO;>^)ukQV+7f?*37(ebn%z zmKALQ=r0s8_#iXK-7*<-$+EKzd$waTNspS>xh2Kn=;{@?-AstLu-$XZ+Z_Mqc~){> zIza|Kf*_CgBI)sQ`W0}`Qy}DAM-Yk*JXX#r`0tv}pnP_~Cxk!rJZsFmV*&B>+Vd20 zW12|NvG|+k94_A8G~$~;qLgD5x9f4i*uLqjHm*rW$PT9LPUGSqZ>#mM0vEl+f zbm_zp)GI=R&wu!o_Cf7w2=k$}!xt_nAhbl!)+k{bgRyLA!tt#vSqo2eNrnr9YO_n; z1a>|p8?>ioPQgnC%v|=0Dm~+enYZ#SYr9ra-$w%52nuIlAaJkh7Qdh%eqCMN32JxO z*U1UVf6N2!VGuHuXLg_R{Bzdi|64@1Z~HoZU?Q&r8@$s}Rm3f3_E**H4V{VVbIk&3 z_ccx|C1=9+@>Ig=cQy?`5vTQ1nEBR3-*V(%{ZDKH+&hVz21vu4L<@P zvnowEZpO~1H_qQOv|EqU?wdh+TmVfhF7|)hLJoS2uHJu zFK6V^DY*$ZL++@pgpZR(-R4yOF>wi0cBv)i`I&Z*26T#LAbFD8a z)N9GEk7sAdnZJT5|4kymnZNk{!o=*qRQ4x0$wyk^auLr-97Vp*zJT$T4WtnP_pewx z-(=#VzC>Bz6BDbglNa2BzwZ0@vT8)pnjTdIvf~~1XkAp@Ad#=-pgS3ub?`1ZC znx}Agsil*HQR`D^FDumcxuv%80#O%8apAZCj#_MT17Z@FN<% z(~+K2qk*0YN6A+4eXE?_v$H)H=yYDbT13|7Fv>6?O^5y>bN~B@b-8}&W#ZQM)#88p zJd=xf9d^9%So~KWXZ;i}!onDEh-~1@aMRa!XHvbP%V<5x0tP7OYd%k&fe8|xKy-87 z3u?s~jcfMh6vSMq+&v2n=qU`vYUNaQl6BrWJeq4U9}7fCzchDuLG`@8AlT238?X^8 z{M?Vxu?%%j<$|pGUStV*6pR7xI!_AVZ*zOR^Hd7dFvH*|Eax)mguH)p7m%kk2 z5rf@ssYQ>905Eq#Ol#kl4(7f(45(C*C)Vjv_S$dyUWaOXTX;%J}7@TKt{1LSkt%!^ik+p=N$} zAxv|WO^*r}Ed102k7B;9Ti-Ee8Ke3BM4aKc+oD1B^5qaK`KkLz^rY(E7jpJn??>>A zf&!bf_3rzsuo1C@C_QWffL-cl4%6UN#=s)DO(@xa+1hA(l*zFAf8+|VT6edW_GS7v zMNodhBzZt!wbvRqGb#i(=H^vdj!kC1BX`n^7@YnEx_lt6n^_M;c8k+c?dQ5Lw#eTdN zw}A?=Qs13K*B{k>WcvL1eo%OhKp=k}8a$$llV{%xeb2T{iE^fdZCeMV$JglF#cuSA zx4XEek9u!}GlkqZFk9}Zw{tV-mWmNv=tRA*%y$AeK zQhALo7dOoPp#R1Q?Q?LU?E3|RTMSxMtH8~?X9nKRr%PsTlxT6qW;++u#l3>%4<%gW zW*T11Xv2$)wVLb26&E=;tx4zNy}07SF}aP~8g^$i%dvjuXPBdoS;6$KP$%?M0}{Tofy zasBhqQO_xc2fx)ry4ha)!2j7EaQg|!=Y*F2r9hJgm<*3A-nM)7tzVI~pjc+`xGU_DKbpNaZD7P{A|)6S3EplxS5j`q852`%1Exh{Sy((ydh=5yxJLF z^8S{;eJh?4WKg}|ep@0ER8!cTF8G2{>`IUFziRp$Us{jz5GaiAsR!pkv$Ys>bRZ^*b!orOzE^QCncRWE?Cn^qD7iUhWy-2(=4bGKB>qn3S?2gFUsIR2 zf8&f%*bJ1S5~VEnA}nATPqJTNe){z3ZNDi%Ck3B2xfnjy&ESvJOgloh$6F!>cSd75 z25yy+0`@^>&$r#FyB=#qw`=z3$J>9n0DtCv)NTQ^4zk-X{0r-vM?VW$X=U`wqjW4^ zdlpWm9!xfoINMm=V6}@Dv%r0W<`@HN8CxDb-8lD^sm4)wM4Mq~ic`*zf2+KAi6VCq zz1^bhrGRBWUH)-Ula5NaCplMHS=n2*q5F!ai_y*hc0lPmQ7SicT#aPt4&&YhzO23B zLK4rzd%{Id;KAMD+9zJ;O0G@dkNZ#l@}trTUz0x$PmvS20QV``7-n`HNT^}*1mPkW zyY`3b+V4cg#E2xuXmh3$$sy>br+xD#{1M(Kfqe?Xh;&Doy{-Mm|2+>LgsaG?G)Y>= zxh8Th6qh=1;*gG9^`S$D?4^wb8_gp;`$N4CR@}rPk}smL2^(x8iD_rt^xoOSn~N@= zjca0?Ur2}rCD1@0vOluYNLYk0Z;xuGM!uHRm!?$z;>Qx_nzUfhDFmozdm&mGSKf5? zn}hG(v7LvB!d|#h@?tp=>D<=XriyAd4DRw8=6j>xzoeWAG-tU0Z2nzy+=(b2Rm6+B#|XW8)vhL@9fO zt${$1SM7VO_o?BK!q!x+#3N;;#q?G6Mk+Gb2HLg<3Ac$_a;n!M9H?(3F7OWImk6qn zMCBX|1eKCiJ31fHV(!Az!OD_0@qG?LKs zWKuF{!0CvV#-~1|T{zTdw?#gzOID7({@87+DgAf<`j-QQGw|Oz6V|y)fs{qN zNh3?#*Z}Q4YkKW7Q?Y zhXdE5q@$qg;TEUYS(5F$dix&YBBRNeBA)zm40TjWT!SrFRYxc2`OnYZPYE)x7an8* z1VqQsbH;y}r|W9H`k!QeL=)4pwJvNYXHvG;OrfL@Sp7VZ)}zW!D$o<@?-eM!C#3w6kRf3}9857vGuD z&$8fy)8@#8-ptxv5Gasf(4NgGf}&e&K}f3)7v}vxe7$!()_wawo-=etib_fmsWhyF zl#I+mr6rrT5m8366AfDfMMfprWp5gilszIv2+1m=2*2m+RO$NMzsL8#?(1>g_ucz^ zzuw2|IG)FId~N`RY+2+KHdIQ)CIhXtS8&$P&1^OmFWo#F!TIkUKB!L}MD=u#_C**2 zk0eD$%;@Q*xlgd9Yoh?%Sk=-uJFTxSQtH6s(>hjpgkg@?x$?q~a^A6=K+g`F(fdFX zm-eIgmdarrQ!jC&Dtf#2eTgV%0Lf|a$5z#%SH;htU+D{O@40yUirdjuGY4e{l)BuD zHMh;o6IV!?2ynEUy(I%>z{`T!2_&$4)nL9QhuOBAr;(QibXzbH1>x+U|K%R9X;vTG zD`v(7#>xxpp6?htcH**2*lMioA$MtRJS@a9t9xsAe+tYU&AJ81B!Ngpyec<$S+x{^`o`ejUk|ZrI2cNf4s_Ond;eyWz8yh8fvaA zi6H&8gpyF~vs}e>)&bHijWtGjSq+IlG~#RNn=ttDJ+JTleK%|K>|>WT_te!t`y`gf zq4P+49E`|;Mi1xtAj=8D&BDNsIDI9jyH5TBrFAcM^j+0*Hf-K~vC#$L|DG}`lGaD$ zc2zBy?n1~ZI|lxi)Mrf&>3xD@%MT6lV)z%EWQ}mqs!`RZ?c&`AsIc48fh*psvE0*j zaK>DV_GoT-OJ?j|njsXf&Jgano2$K+Hx71xB8G9EaymM<;eox*u&t}|9-J5Z_jQi- zBn7!leh)7mb!W41K|kSLntyV4-0Lr+XR^E3-aC67t_VJIGH;eqvhUQL3U@l`*zGc2 zh5nlds(#@}Tf<~YMmHX&u5%fE5=ZKWwmJd)+L4<*kyBUy+1q;_gdM(n-G=1eXt^g7 zfZO?FtVZO;eOcgAmb!hp>x^TmNEur;0{2)Sjhu(&d-X0upKMIuWS_(pb?5nszsSuT z4C{6kZ%)R}95FX?#FnaDm`34w7E{dX;x|!z?b+w)C&6s!FdWIwuk(B=uDT9a?*^3C zb3G5xk0~Eg#T8F~m}kqD!>9>23?Dmz5)kF(Ue<_)l;^O%&7nz)Wp48`IO3Vk*g7SQ z5%Hb+qY3q&Mc0x6Br;C;>U%nB57ujWN%=a+E zEx3t(Xsg!j-m!CEyHgg`Ti67|3Ee*uX}_s(E5n~QYT-#;1^4o^Ao;@q`Q*Yc@d~d%L4ofNyOA8YSdAm-Q1@n$=KVBy$NgR`|<$t`V zy*I+B*0#Pf&7xVy`UnNnW&HYx@&e*@WXnA~ly$YI#HRIHpGIts*k7kS{2Wx|?2H(F zsrn}sR1pK1-(M&CRqApI6~w6+d)M1<)i+lAF5B#Bl=G&~0T%&@!8EUdxy&t?U^bkV zn8!gkJ{QrAhTLFd{c?k9O{*_|+=5Tc`E%JaV&l+GE+0_)NK_+nT9wqCeHBCDhQUjQ z_8siRFzBW8-3wpVXSMlCz0Xf7+R4%ogj4qX*p=t=zg_ILKj#3-PzQe5j9&-Qz5r$< z3=~53csQ7DQe7NVvu9@=ztDVno-QQ()+iC5bB}s>vOFf z-S@UF5M-YZJG%rYTEB(Bb3}XS;$*^k680MDnCX9>m3;ZnK%;RKRhVG@GuQk>@@X}4 zoywOdF-!wUp5A3hfyjouuC;0&&Es0Qe1?55+ z3a9+n>W6-Cn=NUJuzCCn)Mo*mgf#R9#a7ur6vOYRRq448Cptm7v0hfae@r^ztv>Vv zfqF7W%WYWFJ9iHuzae1xncT`J-}mg^eG@_n9mj;44@d>Qw?D_T36rT2mmB(u614KW z=Ntr^tF1E^mwVkZ5k9L$Fn5A#n^+QiNnt;;>e$)bzk{buMVN&3rdT1>2Mh*s?p0`+Fq-;xX1h)^fOjo6%j zpvQfH=K>uniyFS3#(#_#_P={q2msWumVG>qCZabKpDwCHHlnY_?9DoP`tClBV%zT( zX>U+y{8cRKNWY!Na76rsOQlAhcJ(zH1^~mr94FmpXLWYS_|xU@%-KhD_sBynZA%5Y z^SFRc^3id~wvMB_k5(WFo`ac?v^@S)v1}2=m!qOt5=OPAUs&1M*BmSMCIIr*59=#t zjp@YFSx;2Gkae3B*eKl24TjdGIxo`;U*Y`gJvv0>OQf4Pefo67Lv)``P|E3}9KxL^vMt(5^hdhQ;p>fa4*pdqhVH2|owCDgR zOhWdYL}C-M@%}a1o;XJwS}tl?<+UYn%TN5(wsLCVd`0-=5I;e~1YR0z=H-D-ru<+8 zq&r=UT(X3m2W*R?P6k$~D?*Pw7#f*w+^7bWS(kcsWZd6kf$7#++ zl8dG7y122asFn;&3+FoG9}piszZ|RWlRw~y)|e_UwRLfB1mih)&gn&MlI%X7;F@@| zLOKl@3wsF{z(0W4$en$6BFH}P19mVSAhvJrOVb>v|5#5-hdzy;4iRUkmFw>TRL71Y z!KIDS088)^^P%74!KD+LI%yNo>POetg&h`aPc#Gr@W`^297=^2Bo~eZm6T#o_;$Ik zr~JIFtwf}4PP1k4A3g*fTZPjqZO!GZr4iQhnbPaxtqJ{jy7scZ!m;7|**7MWksB+K zc*?kA1UBB|AJ|lAizxbog)sMbDMM2p3$`)+&^Bw@56!yWEh&FY6<^*O&eTn2NYA*A zGI-@-@?9aZ+R=9UPrq_hXsI|@taIWl~R!~>CJ*-!A3ahDqt-)bjQd%0Ankp84zpbr} zM5*it?KYgSDni%!U%$?W<7{>30@ghb;5@Kr^^vzTO&J?;E~Z$lIxqv7P!mvHD=z2` zo1Q$>WD^fMf=K$_-^XDuk8n$3`Ag!Z1-R?d84*3&*0xaC4d3W1;!ctsTocd2y}co( zChX3gjksz>rK5oXDzo~2E^yU6SXWwl_qNcsOmw3Y{SB{|0S6c9>%kZC-7oj^ZL{NO zN9YQcaIFHiKnn&G&>E~kVOb3`W9mfVinA{;;hcZpO}v(51XnYyu0tAf3VK<6obKlaonNf#IU$LO<$l;purNeG@}$W_4;ly_*)9x zl0g$*FfN!}HfzZ53}H>gsv4m2gVN&6LI0>3W)+4V7YfW2Iaqc-jE=s2H>URK)JR6b zvX6L`!7tmy8s7SHO}@Lsl?Qb)VLrd~h4YCmLQRZb2@knQL-~GSa-!cQXSg0gy~IGE zFi}AT8w(w}W}jmtU*8pe+`>>T8waK%+LQxgNLU-f{63@_`N!pygFr4q950$!N4EbFFH-EO1>j!YfIX+ zcjgV=9CRv7#tnPid+~j33M2B5ETU@<9vdclr6+kaCsATVOI%3GFAb$aMbcN%xjW2mxb`wVnVolSw5d#xqjUGTT z@?p<)40mmzxk@WRa~Qoaf6hNGrqLmCYvygH>0YOQfx;*F1q2<;mM$d)QSK6R*U>0= zj$iRyfk$1|nsVa83$}`ixXDe1cAAxPu8gz9s6-6X!*u__gJne{z&1nXe?ymb1Jnzx zsHn*U?E5)x_I=1}>TSRlR1LC&2Ut7Qg~hX|j9`DtzD%e9q?!)kDf3IpU|G!mbNu6! z#n1!h%Q%P|QDsXDM(MJsP=LzqWFS1f%CKdy6w~U;CIVel#Y@%#dS7KJ-QC^Mt%K;P zIg{?$CuOt_RWa3oS{{)zIlpUf^_M#MZ+!1u?5k9`kOH5z&CWr!9y?A-2@rcQ?6R({ zAYYWd@ad~Lul`9$ppdXo)@wA`_w>)!vJStPZ+5dfA{qg^ucC~pG@`ODYgK7>Hkg8r zRLR1Z!80;)+LdmyR>Q%dy3|LWuQiKD#3wGuc1ej5=(YZ!Pwo8x+$MlqPg-~eSLZUSx_m7^y$r<8lizIp2oDOvwJ&XpdN04w0wGAadr|*#;{1Gk#PG|%= zu+e=Z8{nGb;u+waDx(atSidIw!OjHsb;E=5I3Q+ojTvlNHccS|E_!x#zo0>GrUt`1 z9L=qenl}xOZBDEeNYF5^(B7Sd*?t^11 z5?bw8QbB1b458T5+39CSm9uX*ygX_ZQC>NA`%5EOcPDb~e0_cA_s`m$nCKN|^PbaM zIQF(w|Ae4j&r*LcISY%#$65*naG>k1j$-MRcM-y7%8UO`6M(kK7nns~uPn}_)M@C;U$zAwqPcdQh7!npFVBIt99EuzzbHy>ou+Y%ckpbBYIxzez zS4?0J=#j4thK)&Olt=yJGcY}%GW9rI#+arnTGnr~aD~xEI;XNPZHH#}Dha+FkXYZG zmk0sIhxu*TzfX6OXps~z;kvw%>7)LSGsX>^2!%&)(rD8N=nlH&xRjg3W<830NxqEQ z3noxvD@K#H0jK~ zXwk8s+Q#B`3GInH?3}n_fo_3Cx@0Ta_LTrH#LW=-12;s9#@lap?`39h$0o};n50W^ z+vN|QPzHh<2({KDowQhj{{|f(X#})KlwWVTOEF5`en+B*>p6n`bsB6YatYe^0n-fh z)eBhf`(#(f7L8q|#_nkBir#dPp7qK)x)j$O##`Z-GUQ*g**sK}2_a7K2mto+P363& zX^vZD8?S3%b=7PN9b3t(R{_wNE9L+Eyu5mn7?^42o`1~t!OC2x`z+#qJz_mol$4e+ zhl(BC%^c<`w7SaU6z94ckyZ@YN(y@Tbp*csy!E9wGDk&^WFikJMYK3{UVMqfZY7+| zb~TP$Ta`KVO_an?*Hdm6{m{f0R4R2lrGbYZ8yXsZ$>n6c zOqHFOc0~N$EdO3HywIBYLb0NfEfft6^>yLjqqy<5icYoZuufXOQMJAb$SwUg zu~}JJ=`qIrHmg>!iqSPkt`iqe)0*h{CkYF(qVHQ2R z?u9BzDXxh-T>fybi3>E2TP_Y{w_IJa%`HA&;3rJB+QCU*%wqZA!Gm2GjHNZp>y?xV z`4~haRe)}E}xwzmSX~5%_k1(LR6&Njb zsL`htZwZRwhT5JzYqHN>bzU1IG4`M~ZP@VkW_s&QS28NH@>M`3Oep7RG&G3Nf7VNb zx&J)#k0dPOxmo_H8b65oWv|Gcl_XyXSy6YI1cnxn;D(H!UzgI7zkVO6B92U$4Yy;M z5YO{x>?AqY#O`)r&Qtblg8pG)f_O=y^1Yk`ugx&zElCl%1us`#9l$4Z(>Qd)7O^EK zy2|jA(By_)d`aD%s~7R_5zyq(>G4dFH8|gw(RYb(;wm-zT>756#AR+l$fVd0uJyY+ zV{eN_prKJOC z437&VW1_?PI2;|bxZ}!ij-5LMy!^_0E?&_-nUvop0Y6OgMf@fk-!t6taa$04dPd|< zrPsr{vT&DRbEM{~8q?#63CqnPGJ!Jds%oi3APrKQ4fiu({%F{ThZ{&pgeE-O>d zSca8Q3GOe&@Q)@VY!%HK=)sR&ki|;tMEKPooA$GO?>VNe@EUxsz^<;YRpoU=rr~6w z2+HWQFxtr{0@og z@Y-N1sRH(8w7`ARic3-5^yJ_v( zwV52zcBJOIMa=c)mexTxd!n&GXmRbe7K{)~Fh9yXPRVZhibm~Q<5kV(e%P`gI;W!T zv3=1y=t zRlQ#u*YpZb4GqhvWkd*1ec~##>b9g+l(7~-yiRSFTu`$Z?dh%iSJSab5!j3>rD0ya z%kFNLr;ZV>-C~OsCwFhWZkjxSj10lET65;F5OKx^H*vRyXw4Q4MXW4NU^mE}6ko7t zwEts4iAK)dui%*Xh`@-znobe>xo09$LQr?OEvX0}hMKI|Ohc@q{y{+@^YK%sUgPuf z_KiFE=xFYII0VQHa6Ga18*}hrY#vs7Rz6msR>di1Y;^F9a4Z(#YQ8IFEd)d>>i11l zF|=}e`_)8;FIqe=DQD7d*XM+sHwUp)DG@?l;v-j|Z>30%rg^>61+ahl-y1A+d^>~W z$Q2SbfsDKrZE*eld)njn4I9)NI2fifJBZVgrc0pSP?yWF2^TZjKbhW=m}kcrEnay@#oKpXXu~fN7RQ7?XsMy3oFngH?NI#u?7geyM4BZ z0_ojKC{W;U9RKn?L7Vuaz@b*K zxbGLUJ@C+(wHMqP3DuB>C2?c@eW`C;HJqX82=PHuyX{P;EpwqIi zUk#tq+)H{z#{+nN5P!tHkrz&RTT<)IkSqV$WN#;1T zyrwJUlk*yGgkF&=Ax0os;HI*r6GOmAp zo=4AY8~y+Oe4j7_3Ey3QYNmsc)WX4%w3uAOHdp_Lx`Ji4l0{K;>lPNDhs+;lM+;y0{Icul6HwU8er&V86hOwXOvGV4XNV_)&ZdfyA?(`jf9t;tk;lYzB6&NouqR7x#6B}L|2nL zIb(GtSLlh-WPZN-*U~4Gm5Nj6KQ+P&^@~lMzO2x*NPLm5ZS>ZM=dq;sq_>0Qk!H3= zo0F8=7mIa<%hOCAQPsU9pMB1`E{_f1TF5}LgnW>SLN*VzF>*sdN{AM}C zyJDP6;KHxFlU?^(x1`7Ue03=QiYj!T!g+870#R_++%Zs`y_t|{KFsQRH;7uIv5`Al zqWPwhJ1bu0fT0oMq(p(}`|+C&IAOssX(zCXL7`8_CIz7Ui!Yb2D-zG%5bSc6E5*cR zoD;_N4-F8B70OA+msXHtobc{rY)CQD;?(osKV=DYU#`ZF9?iWi?cdoBL&@-q6R3 zyQeH+^|SC(rR7#qX+?=oi1ESUH>IVbVH$w{yymGWds0%U8Ll$(H*enD>^A(eK#jR-fQ=E{f~~ZDfVAw2W5rL@qHflz~1fi%6pw%hmjAk&t%&E=L>3#8(v_Y-H~9XrmnuYSty9MuV@J;=4C$D@PDO!k851`#9zE zXC*n=%}oU^1&^06?2ok1oVhH2H{2*}$^VHo`$XRNd%-v16lDw@up`J=Qsqi?weo_MK-L-3B)?p z$MoY^{=0bWK2%9d-}LjHNelXgC}tM&-DUydQS8kVcbe}Fy0op9R(?|X8?vB;msh6# z6iV1FOw3ya+CD{5C3pPcD+V(*q23GP{HLzrcrMxcLF({UUx{CG7ouc8>Ym%+I_uu#N zJ_U=f^=K*LZwTtvIh z)Rta=HyKvI_8?A>I6RBCN~3WSbcn-yYw1S!WKUNa&D0Aynm_A5c3NLnaGEN!(5uUo z^`3#|N%wI@5mQmX`NJVZa6SF_avC_jb8c=C2s2|ZB^wx=o5&u})BGcLYxPk%FjGlk zyV;8DGf}Q=i^EApBjA9(voiJG`jj4nXV=K>q@qxA@inN2%%`kbR3SGkJ^KDwc9YwP zBh(a}H`B$b+M&^OTb+6<3iS*$gm`&(q%MrFzT?>_`=e#{PYfweQ9D&t10i8kMQ`l1 z?L+Atlv{NYG3Td%7uORxgTJoTvu(G+1!&^zi#$Z!evj$C z%;nE%sHU$lI{^_{OFevFjs6!$MMW352F-hFKzFQPf)C*e_`HoV{cOo8~6U{l%|XAtpCS^VxLlN6s_q$9iRDwKN-d_ z_Q?E#vFS_dIviYmVqkB`zrsh3mErfw#3o0cxWxf`+>tA)&u6rNPCv#P%BNDe$?cxw zSg&vQN@b5~+dowy$FpywHMJhGBEou^8Xyp^(W(5P8wY2PeR;n?n&i-DWxd+F za_YxrVgS=tL%5kgU8ee{ls?tqEbd@y0Cy3wejm(7Z|8b}X+mZuwi{;E>;In9KSL=` z3qh1!UPu!0_Vn`?4&vkGnqr+rYp@Hw2wj@k?0$Q`XzxxqSr5n;o~7U#3c_g5&Kbn0 zcwqnjRk34_J6e|ccQBBkA7X`IOs$G?c3I-&S%X|}$OLbO)nS@LPwFQN`3r~TThUw%OgA|U0==;?Zh ze*b|3C*EgTMKfQs_Rd~(Q79O5*xv{G^CwO07%gr}6-mxa3a1IyBav~;le_v+vgZzmRU1IF2!l!RJ2pIH&c>65+&<($tg5tJ^ zM9s!>lMWF|=byjspFg?YM2Dl>Z6UJc&-;L=ohVRVm>>23`!A``?LBl){9s(G4ku;L zq6TzOYi@|4 z8Ut)CiCI?%$_CA2F6aP-UgI z+s^#3e@;#;PENvwQ%gDio-@}Is2RE=bs{3S zd6EH5$5C^c6-fg~!-CNGuJB zsl+Zn;~>2GmMSFMgcnSX#g*L_S3{Sl-We%1Z~I8YvGluq?kYSLl#_I$5S$UuMXfRp z_Gnk9V@x(=vMvvnuuDutSVwY^E|YdB?kieg8$e*Ny-CF=d;*+oo2GUj)&~i zLS&q>f5FbOcq*<{iqf}T@vD#}8WOTC{Pu8PwE8k)tw7nTBOc-@cc0m~LT979*&*8$ zTRih?T)j#gW9P)eqedMcb#rz#!|R7zJ}%qt=(eZk|VRmK%jaDn87O-o(TBT6z_JrDdWr* zmNil)FX@}-o@gm_3%q%A4GQbR1c?tBXAB=ffyDEOFFOff!czA4wH5Is9~%i@%PSex z=hL|`khOJX^8&43tw}3hIxMVEiptiiNlP=Xl*jEeYsKGh@At#4!DMK#N@fpn1eyL& zEu#qDmf1tZ&&}JmCc#s07Z8#SSj`1&+HsP2LD27Pff6mS;8%xmbe@TED~xWUOKn`^ zyUC`Wdec>t3RC%j?hZ&`jOd$|iy5<4w1!IA?IGNhx`#ryOwoVIC9!{b`y?f$1CZLn z1W!Uwamf1xa-Y!H_)hEMF=EB<aCv zQ}5ruzclIUe->HfZoamW^_QiCl}fSwKj&8qqRbqnGu|toZ9Ch3t1j0?Jur_ z)_WcN6IBSO){Ph^b%0kY?^Z5q^w5Gdz`X*vJhR*6tn49Rr|JE3~CKS$$X2D~HGf&it#U*#2 zl*YH7ek92Fa!Y@y+lLwA0Y2X~1+!?YIJR~E9F|kKvrYhaB0D&0=$Zq>Fl*J}mJbg7 zH!;_hTVEuS@(uoW@aSJRi&!ngtR#Dw3-;Sk=guz`cW*X<#*$<*TOW?O=<}tw=$2i- zthBU#=`F#HXxW%1USzGJ99dk^8Hu#grL7~FDRyC6ek#c+)T`(g8oB~#ubN_BzSN+M z=&AoaSK&2s5&m{!nyxFDB5@IpjrxRDts~Gs$D+;!* zf%q=AhPY;t46*b@6|5r&&`^JwaHIr-l0Zz3m7?j1dXoDE&$!Q@8%ep_diH)VH$QP2 z`^tw^zWLYt_ruQ^tL@y$(_#_c#IcXB_Tz$c=gu{Mz90U$`;>XQF}|77C449THWai{ z@ked9nFNlJuMZbC%|HCc@gL*F^#qwadP9Csbspz|dfd8l@jnjpay+gST-Ud-fD9Q~ z3e7Fp1jHYmap0OqPF0vJ0Pj-=mk2fB0$+n7z9_-kqCWc2^_2irx8mEITr32~lFAJ~ zQS(xJQdeDgk9f0%&5v9?UBei#&*R;@eeetbOJT(f)J?q|(>AV~|X~ z4z%bSx)vLn5`_M60kYP_+=Cl;@croMY<&fVU})BMrJ{vnz-OinzPf+gjp{BzqMTm=gfZRKfTFsrv}LtWVPRVf;>JDG2KI&MF z7>PHlKUo`|gun7@k_HQ?J`jiRS)AWn5-VH$o#9P31)t~Zf^ecIA+~(LE)t}Sls)Cx zD6n;n@(R-9nBQ#yRJqI_Fx@X!>Lb@?gC2!z&tCjFX0)@0`UVbQp4REm8Bu);QOoYh zABVJ?a1-1B%9flfm*&^8N`mfJ^umxar7ytlPDlU;9m`b^#COx^t0ljKIR_L9Z3*D) z?sqc5y1VKdO2aN}Vccber4F5|)yT<)YK-^eiGh|PIO&W=NLfLZN5GPA7)a78luCny zg^9^oSO2IO{nvFZpuC2yjouqBH1@#*&>Dkv#&t9JX)L(h^M3{rMOWOk z)Xb~uGbSQDsd#4!J#UE811l2#WY}R?058|S!DRS5aE1)C?kKi6dJ&r=UYe$c85UtplGqZj zA`Y~`MlU`0@}f6r!8VzFB4nTjy@Z)S-#uQV<#bMQ3x~riKQp`suW}vk?CU_M8&7i1 z6Z=L#WRu#`e{6I9!G-&*#6o{k>T#10i#v;K5ZfFkdsp8KUrl{%8AJH=$| z(MU|U0SYwFqGn2c-_$y!O(Lc6N$-0I&7uVKoTzshS*)_IS4idpl^4x6ibR0wa z1g2{JOXYXFm9kxBUVf2}A}pP;gCXHB7_fj>;?T)V$Je$Cjhdj$1<$|sPt)HKT<$>J z&f)W(VVdDX0&&~LYbg);09|p|1_ApT0MR~np`HD(9xqyk)oupdyL=ZmWSj~A+MH8w z{#GYTe`97fYjQTt!VA2h0m(8%qLx6Kz*=PjS86#d^VdQMRaTJ5_+G4QNn$#XTH-WC z2*1N7RGjCVAV`c`3(V0z+yaXae{f+s77YBxUf*TUK6#w{b>1ME*?_}0D;;~po zlbA{bP)nXZCu!FgN(?)x*@t11_9KhQ=KGeK4}dVUa6c;fPl@B&G<5h+!5AQ3U9vhW{^*X#FL4FUMCUVtu*Vd~ z@`_JHQR1Zgk>r4l@Lb|*1Z;H;pqf-Z7A_K?h#Bp`6J{$3ip1hfV7teUAK$5`7dmL* z#=tF+dv!k7H=-Ybz;ak}oX9STWoIlO>@?OATa#Z1SCd%=<{9i=CUr)ut0`)kHd%k%1~W6Gkt{&fSPV*W13Qj zuEc)i-Kj?!y$?5DCQU@^Vl5~}_IWfOfHM1*H>dc9P=$F-Y2r1L#8MVI2`5ekT%&9k zu+d9VR8sm$Ql{|VD`KrsS~~V10ZtO4#uX7pdY&?D)XYMh$rGsY787*{p@-}3@`0X8 z-v8cAI7_Gl?;T#3&AhRTtFfounY^RV7W2D>+a8vL)H5IN4ygL~b_0BRDjebEK-^uj zy*#wd5Iwkk>eqK7v>aG)YdSpm$Laz2 z08q!bZQ?BNiPr>T*tS(NB#Y4>l(YL51AmvL)Ju9s7%Za>H8H27HQ|)9OdeR zFX{eyiNEc;D3?3oE`?6>y)qmL)?pHTTu7xw9kZ@*gN$%Fd(*IC3gLDB7O&Btnl&^{ z8MJgGc6VfDMr_V|$BDWbtvchcY|TCm1#9e)hD@#yk_hJASC}vRss~rJ3%KPPf%=dD z<<(hKLMdjqcb-Z#L)uesS5%t?tv{fQ?AEP_Dm|oCT&%=4pwfaRU{nr&wuFrPca?x+ z{|<+E57dnBOaHt^pe>vG*M<9imcyKY;xW;e;Hm%Z>0Abtq}pqQQ&li`(@|1;=KS6u zp3Tv&ejyFtWB-*jCJNTqB*n(Z6ms2_Te#3SxD%CS%FE-F?WOoC$fqPd5}PB@3~Q^Z zdnyaoA5PSBP1<7@z|#Vb7i^m@4cH7Su9g(JT)_-=uj|q{JB`a6VJt= zJX-_*-BW@+zS%_n3C{&cPz4ZdCuoD9k&;y z>!Eg8EIJUa9st=&Hj64eAdEV}08D%9x@;~*hN=DY=TbC5N_M;F);i2udAaxqp6=g| zP=cV<*O$K#nK{4l1g+jS`ZOpYRMy47TIzVcCJ+jfiU>Dheam_Hp^TQ3A(XG-?%lf< z+djh=?VjlUNj1<+qJSqn$9eo-AQp-?nX3UDkV5F9RuK^6rIH$?$bm5V&=8|8>$?T) zNoPlM8vM(W8@ysi`acRISu2QcHskrQyZMut$JA3x)3cNPUvFGCCzDDGC%`@JVBOuA z7Ki-z6P6ge0|#PxSZGH>`-8v6T5F?wKqG?=(~W>$vM8S5i9!;-yk-@d&? zYo>wmWJlF{5oBEMKGoPJ7nOdOscCHY4Y8Jo>`nH4UN@xPZojymtX}wP43bSU3F);c zSHOv{Wi9EYiRHv`$k3vbCx%_<4Ee`~<1wC^ zzD?~RRmj?wILb4NXXf{2%x_1U<8`=D8k(OQ$zp!2}lK=)NwRK>hBjT_ZZcd z!%Ofqzsb^_aa)$0zEu6xRw`2jVB$U+KLGFP6?9fi`bu&2rpbBOkL}3arq9Q!O@S15 zNdjkYqfUl}Al`{r{43GrYDD!&93+loEQxN*0imj$;H_QbI&rDEY`i=r^mReS{Ft-@ zE!s`OxzFcz8rqjNIo6XPdZL)El>$?!2fv1sT!tlIqm!$mW}-jX_H<3KK?JO2zJY`u z0KrnQ?IW*SsixC0QPUmQ?{SpXG8@g7&}jLb;SSBCA17TINxjbHQU`s5=DfW-Y8>^E;RgWH+{ zJfP!Hd+My^$Z-QH<%*_a#(uydD>cO$1HTZ@aLHOg&BxOe}jcetv*+Ym=+j0qH84l#}<-s9L+_x;lV+MmR7; z^klv8v!Cln3M4(z>?!adS`UVw^XSXD)E^rnS_g>S3Xm#C^#Ra1R+9>YX>PpngqCl$ zz9Qi%(>M2kfezFKf(SX-MkV9 zdljq5qMfiyL7ljoUm#*eA`ZwEwUC{i;s573X+uKik$;NsZ?K=at(7zS-Q#1Io2U?H z6E_m(wvtR@AkC_W-xJ2w`nM&_Io~r^N>SJZjMB%wG{fsQ)F9!HH=ARLeTkt?hXx@X4!JD{O2D{ zD}s_mxbtD2h)c(>i3+mNjzf7OA2@`j722*`^ywDO8#wdVH(0A&!d|fP$Pe$zlay0$ zLj%a|h~$7H+s-D;%L6&K>2i*Eaz28G__`iR@t!w>4{y44Z{r~ZuebGT){Wh1#G!6`It&xsWtIpTEpP*)cex*gF?)jN|G>l)gj%MC`r5mRSNST<;^_d# zK)0{Z*n_DY0K8G+1RPXiZgXm_n*Jpkc94Y| zHVW+$HDFV)$)`MHNv&K8aQ!&_^g?DIZWa2fdcSD~fJ^T~{PYmZMW2 zDB5>AU;*yIxMI;FK9C}xl&@ZjH9oyTVR6AT(^`Xs0WHw@3v(*?DAdIZ2?CEnH|LQU zyfUG@@LmENpRVSdjD2t3#{)c5ml^-MxzeS#L5vy?wrF}*Iy!PyP%5|{z6jbvfXFPZ-Hu&%B|N3i{$mHZ!bog>@z6z1s6O);t#{4~74 zm>dGQjp$U4CS-gFL|rA2ERqxJEe;svQX5p|6uhv!vRQs^|Ng3}Q~ff9cj7-x`F;GV zJ!1OK;f!<1H|BK_C5!2_nPOsMelYBK&-BUY>LP{{>n@hukY21PcZ;XwgW8Dall3>I zY{Eav{(P`Y^}58a@YVh2^bw|d_j~B~3sqv~GMzGkXmcZOGrOlH7B1SmofpU0T1rlT z=O*(;F_H*p!_Qh?B5}F_aYmSFz3jeb->Cvm;i82Fuz2be9(gWAEeTgE6g)ze@ z(!wvXHvnQej!l%%xw_6xESZ;&1vhPNF+f<)GWce7J%!VBD^G-!KFOOn5u5!?DN^3! zshjK8nNFYf`LD(<)?rnJ*LA^`M6Uz*as&`*@0`aS#%Cn%27(g8Y}G@LoG9_%ft%q} zTBIoVpL^){rR;@SAfv>`Xz5I?D?*DbE!kI#uA&|1QpmkF0zQZDE*@J*Vk`wVT6UDO z+XETw-zvlM-T1tU>?%G!rEnJ_VV@j|hE85f*>^?v*=w2(gj=PqaRrn4BpdFP%X$UQ z(tA4Tt$rQjvdDu(<^TZn4%-S9C1J{u zPfNG6CWpET-Kb_b=ev9M1;=LXK23&NSFr}vH?53gZ-a!x(X2K*`cXa8(KG%e{#4lN z25z%4{obne=$-w1oyasY57HgRZgy2N2G0XU`YwztFOA00(VW07Fw$hgoZd94FuQMT zbLQlu-5eLbd^hr4u~oiVf_0nqnWop{ioGr4&>#P@te61U9SUe zZ#loyxbQPp?N*F&XQIt+?j+<&|ATa$mN}Yx{SeDtosjS5GW_MxR&-b-Dzzh!bD-L2 zuYArfaEcTd=dUo1{nU7yakha&ulOUp+5Hcn!jZvp0o{_h)f0?R! z-21}Gl8gVgYqRLczH5cwY?iwQIkvmuY+^E1u_2H%o(3}RVz->1L3+UbU}T-o$#eYq z1Z|4!H(=((%<1b(*!}2}4Ejph{#vnhvesQ1+E^pZWf<;lIt;J2$@_cUzq657q91w| zE7hQTL&KN8UtA)>wsU6-da@f>H8l1f!5Nk)8UcTHU8F_e@OP5Zhy}ov$w$5D*iP~W zor55fQ5(y_4MayxSlB(8S&|et)*lE9e72!M1~5;EtV@2FreV^T%jtMOszj*%t^HMW zRGvhqtAiVbLA_9V!-fs4886S&2O}`A{#~mSFXK)fq(QLLG|E%?s#0gxpK- zY)LYH0g23As&UI8^y5CG73ggDWm|WD+I9HV*)r0xW0hi&l)x-E)bqT~nxE*tN>j>Z z)MBKy`<8I9FcKfD5T?$eY%MG7K}FFmN~Il3)_>NF=0PtrdEz_5uSDqVUWRE{+s$eA z*{KWQw;co8CMjupwQ7dAvG*}a-R22KMHjzSs;s=~IsQMTki7O?D2I2&WZ%v(U8oA^ zH;$aI4iUu<)Uw*Y#xlot3#9tmkok6N&z7N0jvsO}Z^$(=u1DT=B;Z zt7Wh1&Ej^PSTe#}tZW#C)nth~{Q+GVrD9yFl{x;>D5p>Ue$fcZRF3+t@Qq?Eq*)*D z9QuJNKg8t}%uBX&kSw-uE5<@c-<=A71>%xkaje%zv6i=eLbnQh<{`!J|4iiquykzx zwB<_c%u+!MKIJ*XeRKH;If5eC;$=CGfZ~ofTRz?Z5WLxuWeAm+zv2Kbg3q-OcbH<_ z0VxT6e-gI+l{NEWA))Kw`u80T1`txpESzg(|AO4_u*v9v%bZnl?8gGJ_IEM+_{fo# zzJHs4FLxzVF&ell8(Ws1&T#q+yU_W!n;mWm8w!C5b=_%ywwb$(tg%|ywlp$Fko8i( zId&-7Bt46$US19r@SkI0lq5_2*1L+g1V$uL$^Lx4ekvVDUwmfDVThyNo$`k zo~!syWEUioaYE~*tAppfWs0+>fCi{1C$(>H!D~7h@CDWN>$3_j0kH;dcJ`a03T=&4 z`mjRKS<3dD{GYjL1zLgc=l=n23f1s27+kcXffN@h`Aivm??~*1O~3J_Z=L1BXbYKk z2u5F$vt%Yj57In{UWFaq6~=GIR7qxIs$SfJm-Qrk#lHJNkO197=J-^dCz`qihpWGo zWzSNZZ483VEy86Mdv8DTRXeC!>;@)g9knvQ9q^EJgW%{jdXe|@AHpp&YNe(*mb=$6 zwZFUEx#D!ar85@Yxt#fo9U10LCuLQ_H>Zx}Na%~)qZ`FbxKMj4VnLn98LZ&z=VrH@ z0`&e>hpp>Q;qXNyKsX|c^>$Zz^;l#M-;3wZsY!9}eVU?1|M@-&`w4Kfr;K6dV93L= z&LO6G9}WIKFWeGmIgZ=<1Ts-h&Vn6n0FgS57g;hQFyoNiGc%pM=B%6eBpsWpSS=S< z6rKc1(WdlR^~DJGAb0v@Nm&LYtp+B*!rTCG{DPnm3t@dIF_Gcf%yq}}0BqqyjSS&E zD9J=}D-q@!C3zs@Lh=N{Fm91}8<~@xMh+lYEX=!pRc4MktjRuP94pkf+gYh35BvM% zVug;xEB7tAN?}vAJ4XN6k8CprEGGH{SwHre+B&rc{GA@BzlRn9velvg=WZ~-T5fcq z_cNf(Zmf$34rS^qc%&Ckoq$obQ$OUyijMt6jdv&A_-RT|Qi^{#7y9u{@JB(wjw#uOR(QlX5 zY%j!b#?(cer^qww7Zj`baGr2Uw49%g7p`eq7awxJ=?CHI;y3Jdl0=xQECE$O#8Ryi zmxLc;JYR&@Cu^(Fb6(!wH!$Dy%)1fr_q+ey6B5V4;{^=!W^g>72EwNv_cf_dj*ByG zP~WKXC44LZ^zzCrrQ{NE6{ZhdXi;GQJ$i15sV=Ss>59a1ZQq-loHp&54!odx%gGmw z5Q`A-C%A%(-nVV|==j}-q_lQi0U=lJ!f0Rb;Ez;dWp{_0{#BEx3)Z*nWvbXZ-_Uq07-yMx8%l!7!V)<)D4@)Ft@Z>+%oO zCm9A2WPRQfuysG}7FRVZ53Gc4`7HBliTA|M`Kqt)|3}%IhjY2MQNtM{DWy_MQ79@R zLWX1r6-gN~RuqyUb3_y=6-B1ZQbMLOWr}8zOhtx_Wy+5-h48IQyR`T7zQ^%?|9R@! zd%N%Zy3S#pYppXFc_^F@j;T5@Qa?VOsu{Cu^6R6{DE2xf@+Jp0$hKPE_$1Bi%~{|a zYokc+K9M#p@e?5WcW{66uZb%9E+cfDQgj7MY%(B=nJstj(gLsQ(S5Q|RjZ zM5km)%x@&B!5K(;&h0EgOuNm&bNa0W956G0#SHd{vi9z$nO@F+Sh;%}Den#8tA34g zt+PIJlOhQcU$2n!`*-@2JA#|Msl{M+vii^2XT#&W9~(K6fUp~Yu={ve`=N;n>l!TB zm`7d2qP#zsc$^ADO5gMGQG$YkLg=yXCzv@O7;c8U`=QOC$qEX;<_KaCwY9w6gU#|;s>^a01t%hV6b?&>0IVSD0 zsilf63~Zj~XQs66t8(m;(NBDQe*ypMe^t94xZE&zo%>Ud5X8JfTBgCa3Hq?2gI}5m zqY3$c@t|2Q2H9Ro9yx7}2F^p6=j=mCj@3E5j=^OAAnv&7bTgP5hsJ;DMOoHR6G9(q z_(u7diaYK|0K^+9v&m#la*l=b;U|JUQV&hvQNHOkYZ|<-YnZqlj^D0mi8yxBVgvSm zfWDpKi&(oqBfIj}yMtP9X95-p8m?#V!SrPuMz1D})lqE*BH`8NJ1)wd71dI?p3jD& zFFbO~>FXZ(yRv#D*U%vV2n5(!ExXI`N{Pm9uF@k1qMekrcmCGE{%VI;v_A9yMYXYi zjM<7N54_T-)-s0>MfUPR-lo(b!IraK9Ek_-TuP*bqknxymg>PcKR5C|wDN?7pw44# zNZJKuMzhw#$>Wfped;eD+XeuxFRqVp@J!HJC4if+q36^&9N%tBH31Z13Mv~ zN6V*=7234PvG(SOqWd8{Sd3BJSC!$$p1_b-z>U>rj7co=QerXSb49jNi5&15_rXQ~ z>0xhkLjL&ch=@b1)g|;dlKSU>=r*e*b6V&q<*3))Yh>>mB?X*pu{L$orAD--d;|nS zDWHsK{PpT-5tbjs8$j!IZ7{06aohzST>m2W^;5HV?}y4!yyWlo#{Q+S$!Id%oxH`O zQVQmC>9}6+NXL1*t_b+jE#$pVX_6~?#z<&hh1RHbdPD&**yToS>@#R6HJal)e{8d zeE|50A-dJZ`>|uVdXsM7LHQ+IkR#yFH|05Ot{6chwH{-(w;- zSKm{$m~jf^RV|m>V3Y})$~U-qid_S#4p5m4U!1+1l?LS?5v@&l1blfPnoKu4DwnzZ z@hgeAAd2oj&lEOyj$~s9%BUMLOLhFfs(d=vfUVK2oAh;~Dp(<)1}Mq2P(^q>DZf0$ zsS)aTa2;q&U0ori`_UQnMfYa!4y3m@rg&i68?jr!#?|MiL7_pi6fmo%&kcF|RPaWe zYjN9_(h?FnJP0zhRh=kFpg~qcLC>wp1JT_aJS`ec$s&;zMK^=e?u z@&TL7il(fwIS&>?Cx-Y3PLF+&ah%T`$&t@Y-EZyw^pj`O`rU>fm&C7kZ?}4t$3~V?>F3&TRV1MA=VMpKUR2p?LKfMGuh6Ct*N81@32#L`)VHKnDW6L2cCBFz|HmE zW|fZs)W$L0|5+unuvcHykj>nj^ZM)!`GE_iS`2PjpOs{-?`QPEYPB!yJ+IL>690_~ zr$yOVf_E^=x&4a5NPk*jtuYGeQ3@a%6m~&Ggr8hykv;?B*0xx8rxcLDzGDRD`hFwq zc05d}CnS$MG0_t&Ov1Kv@Bype?8@)C%7(!lmygTMHS7=R4ErD8%X8VP;~W4n=lORv zOGqX5K1P&fK!-}KD3CG7^~IZ#+1SO%AnwyxNL3@&M`|rZqA@*hBkPyXG606Ad(h9= zkI{AAD{*Abt&!6v=JvexMF4Sg0&6)RYn>h&S+pjPb1%&hVFZKG;zFyR??^;hSC?(k zsl3y{YNvkAhzZ7B0Vn`B-rH9Je`ROd;j^Z%Z*aw>Nj8hRP4~bBOxr#0=$?!Hs9?5t zAxt58ZN@loEa{yrM*$Xegn@HDWs74-jETs$5dTYdKo-fCqK;-p`SW$P*mi4}>>6LX zo530Mz`dv6$@`i1JuN`-KOot;@Lxx9p63mqKWlAsZZZCW1wOFmx{M^5<^BXkEC9vx zA%p!bn`-xFvAe7jI__n*T)>hT;e&eNBE{IuuQ$0)$~hg*W!pXtA$;~dDrO97lrEB9 zW2Whuzdqn;(nVu^23jAFgtk$DG%9G&xd9dN4r@QQJ&}lYKHW29u|zH{jOn;BvOYtv z8Y7lViOsnq?a+Jc$hFL4&**a!J|ts)5B5EBG$TNPRrc0Jfaq#PYo9>Nock*0^ z2rX7Cb?FRM2i_~$vfEfe&|TXaqq?=?Azf+77QXjHRHPMr;O0t z5}{_?doO8o_K9BH=5BHDv{=?slRQB+h9WO7GF>3I3hb4YovDD8)R0lz!v17ysVbm_KQd1_fp>Pl38fli;!`fvna=)GBd^x~1D zm(UfBl47i)QXmusfnZ3Y4R*pe;DLN;k8+0)3BrFE}&NC+Poj z81>>_jHSynbU$z7=YMl&D8PlKZ8Uzt#K2GNB040k;lx-e_I&t2qt8t0-gp1}Ygrai z>mJd#_}VXR`|t?;R>1A1E10tdQ7ra9x8L0lAGC81?;nFn*mrn+U%4bAZ4NAZd#qzu zWV)0@2oe(K4>~ZmH({W?J^#~V3*C&L;Cu!`sq<<)lVYC(r@zAcY2yZ=wq!>37(D~+ z6%Uz^$CI~f(_VQw#xVr&3Ge^!0mA(A0QK60xjFC;wHVlc5UN@twjBLLW4YF$0K7QV zN!KN`Hs?Te|FPg$a!~m&^IJrky+}2r6dLPUeaov+I#0UP_C^uk7s~bN-y^~k`}HwT zdV1g}S~0R)mvH=+ZBpm_IWJTQAC4uS8iB34;H(|l`_#DV)~17Ugw#W#-+`0P@Hy^5 ze81pk?)?MdDJ(ijBVPGt>o?-S7`r*<>Q5{eT{{rB(#^fPw^LVKwh;|y`&YTPm8ao( zmBW~wfD3F^LhL^<`B-M)aZiEH;AG7JWhJps!>lN}Wfg7z9S_g> z$sUwAn;(P6LfZPCF6&a%=vmOk4Q(cY9r9z217WTk`>?%2>{{P!m9 z_psk@BFrk8tTmr-T>_nU`F62a9{Ckc;6Q#E+f7+fV3Fa#lcCMK9*2xXPVhCN1k#hT|0zd6`xqcPyKxZ4Jx z&4ccC5q-igS~&$-r>!*$D3lAa*?gx)Mi;IU4n2?fJ>tZxo6+1zJx}Xi&5f^QZ~^E? z_*t!oE84OXsN$A#a9BEy)f7K44w`_7q7?Qx%IVE-#DX)tGi8CxkqwI{{7@JMqKEbw zZkj8+{wZ#s0#9Mx(atb;Gj}m|k7Cd@`QS9fXTHn$)?pb zJKK3vi5pW}#v96nNYStUUf;m7?K3BTb%f0U? z)})SFzP4nmvV64}&NDd{)riwxKE*h{{hDrepWi4JOG{ZvKEhjKVe3Xo&gh+Iq1)yJ zCNl}+{>vS|)^lMiAj?$E2P_B)QqXi8`w_PW>iJ`WHsjw<4C&une#0T-n!xwEd&eA^ zFZT}U*(+^lCen8Af{^J?N}IDAZ&M}`-ha&^{wYKOR@buITWTAtLa`5Z9?NGG5OGiP z?S3i;@dqtVlLJftucHBIbQ4G%D+kz({{VRxbYwSw0t?*;pK}9H5yC_d-TH9qBWV!E zapXye{EjI!&$tHW+xxq777+*AiI+vjHI{W*8XQEakzM*0VG2(AXI>(djV}##*#5EG&qil1^bF4UlAWCmL_WAB61E!vsN2pm&-%EV#S~6 z+K_qbyW~JYhpn@TNxa*cTM2GQMsmr7ejvoWI$mhqgk8iXQ_yv+-*asjpnbZh6-^^? zM|@NaucMdeuJ`uozLKNXHHpCto6Axd>ql7!bFy&%!jC=?*jb(a6=1X?o8bS*+{m?k zuoVbY!=?axqoA@Ve7MJEl-n};n5p5~j;sM9~zsOKuTUGO2$5N%nn(Rh36-yi<{_ZD3KxPDhMP0U| zN_lf{c_>ChET5?1{t<$cQ;Gr1LNEG*1j#@QU}a7;eRHey@SQ9-1tq1%5;XnBNslFS z$mkOWKx;pxm#_8QwzRVOn0-mST}|Dp!=B7h^Dj*A9|U*dg=8!EU!mTrSIo(pXgDK0 zcDr_MrO>f^I4Ld@c z-G8*ruWFfJe_KGR=EdFykN?fWu9bE;F@Q1iRUO_O&-tm5kizP_TJFTTergb^+prr8 zaYdghwW9Vo!~eA5Wa?~T{&s?zvHz10wkP($_$Gk&JLqI@KsngIjv&R@!57LuI5rU# z7|%pMi1C_O8Dc|+zL1jN8ZJG$ogSI`3#g(Obg!SmjsrE=<)0qVKCkBZbK*VSZFH0) zJr04%kBAZ(Nb}bar-j*l?T=6(M71z-*S&4a`#-#}^*}i{F7^9McO}L41MoEg-2)_@ ztXM_rQsTDto&L=Q=o@&ye*OCWD-FW6UZbbDH$Dlen9&q3Oq zAQ+2jIuo@uQg<-48DY;vJs=u3dN<$Ae*IIlyR3D(S-W246g0 zzE$@yTA#NK)WGGwNwaQ+J_%u-94+z6DZ^hrgF?{_7D@X$>7?xi@Bp{7;`piR-W%Vq*{GG zd-xjYUES1)K)=GpRlJ#(S#?ZpFz~Nhb)NnoXD@H1#~7GVhkj zuUtC~R?}y6gx8${&~n=5ulAux-F@FAnw|QK9N&UuocF_F-A&QB&|E+c}yrZXnvot3%^JHcHXyDX>+a@~Hkme1;(X%>1IT zYB{oP>mFGqs_vnfjxoWh!YdS)lNNdN4$D(Ys)x@Wxw@{~k3BmWHnT&noGE+KsGOLy zEkvDW%`*SVgTG&ptPMF#6_YRT|2|Aqv;hZEUJ18vwCO3?H^pL|G^;FU~}RrMNPaauaIKW*rE#w;F72Bsf@jN zfcFVp$3LR$%!Fmsm-4WVK$#v|SWzg+KJ%QAYHdQfKD73fvca?4-?9LY>5&bzGHyN9 zJcNYbEx;ipBs3PGjy}A<>j?7c0-QrkGq+7*uqS|r$vR&x(K?Ok-{Y?)$3)8jMv{Q2 zaDKF|%L0ri`X+~xY8VHd$U3$i6z^Q0Vz9SiuG?@u zW1nwtO?!WTaNGkz_7l&MjmQFrNc?@*@NK|jT<=6#(xZxD3l@(H0SOQfsrV1jJ9oZb zQYEX3(hbz6rj2gZAXd=&%bsf+1tVV>pZ%ig`eWOwk!qCDrFTS{1GEAaoy!(AFflkI z3&Dn`U8-*bODEmlMjzW*1*U{2g6A95>|Z+`(luR0|2F|={q2Ma@cCs5jV@Tx^e>y4u=Lvi!1>8_ahDo6&Y%3?9Xk}W2 zDq9Gsx1kHV{Umir|A3b4_!T}>Lu&R)i}c907qfiK955hIBy-R!8Nz6L2Mt?M=*Q*9 zONbfVkCJh7`9DoBSWwC?&AF*E*C5eqAb@dZ73K%$zv*Y+QB%2U_B(STX9LOD%3l8M zGliL$rjV$EbafZVX`A<((@PlasFzO0*>*M9+j;x@pmU#F)62)$Nl7 z9V+anV58%Qv4D5o%@4VS#NPHNb^=r&5SkBs1S99FD{)HPrT=kAV8rxXV}*)KFf#j0 zGc2pjQP6d9*m8q>q((fHh>K>(8RFrH;oRxR--L;w)!Y@H=UEK=a`Cn8+H)gj1}@-o z9}2<_TjhLlJ9e0XJEZv8;$2&GOL8DUh-(a+jDub18^l?KXlruVlEw*P`W$U$TtE6s z1KtOc&%4!xGCNsyusojZNsepV~!c&GhPlV!WRPTZ!r$e9N~?Uw;e zVs7GXjZ@@?=RAsLdoq^8Bp&xV3hB%}^=2Yid1_#@i{2@yapdhbBQ48p%GXseDHmTr zY{$rITks}sV&~KZZ5QssL+lW$2`Qplw`56Mp!;l0mX}R#w8BEc6X_E><&CT>1C)pv z!adsoa0!|h#i+;1t=(!{?X8aFPB`J*?-aJUYmU5sVSo!CfU)iE#mo^1WF_qzOr0_L zyHSibvp?<3hz`gkm@Sjh^Orsu^?oQvmo%f?_FMBMfZY)ZGiB;~-fAV_z%-(3Qvbs% z{Po0S!z&eim+f3gE)hhZnm2aCCf{Lzd4oKBC)qEPYX%Eg#kHTt%*WEpiqkU#)1xlDB3a~oxY-J0@polo*$}9m8>ON2wz3a)fH4@c_4~;tM0l4m# z(=<@O^X~1Wu~=$~Ck@K>2XcWC9v!j|q&dMD=+aO*}qwEKmT-8mF&D)@6H$&6#P zH(%HCA$CWp(Ca`JOenNbZlgyayRr|MyhDR9B;W~48?wPipWXlna4E`m8&zJ~J^AqX zWIYYV#f`>~-E#4etT~$|EpNyNEd-CuM8!OFz*8}PTI|aL2JRf<8lu27 zcZh)Hr?&Tk<(Ljp!cYr0k%T&u)3VZ8-*;Is~6`!`~$)mcNz0qGMAWiuuCrgg*D4FQg%;2@wjwm!HO+r)WQV9KxpE9 z!;3Zr8v0`u@88_iErfMM?UmlEfe2U5bg71g{CGLGVX_&=UvPsDTOygkx%x4sJoa4| zC8@jbFiAIXniILY8npl)5dOljSgomkEH5Ct2@g}>J1bx_Icmvj>tJ;%iHa1!Uctra z<+zBwS9kjvOLP*~S#2=WiYJTXWty{0aJQ?`RKjmYsLmek?h_(RJtRu#h;#S#pPw)Q z^lE(8A+vqoTVfCqqBo0^G~1~!Yl;* z*P)0=Oy`Hj@maz=PJ$vF4_IV$LGf;3gR+GPLE#TE)C&2w42)3Qt_sVrGr}xLs*%Ou zRT1+x-uhI+9?cI1jPi72z8Ii}gVWe_>?>1eX16H2FOH{Cj;H1Aji|XVJonQBaHN~x zIQeA!^{tV2^Leb9E)u}0oq>oHF#NHa9>DdootkhMa!N^kpy>*9H7KSYcre^}L_FoYJEckD(DM2fG5Z5~uQTpD zl`f45)u=l{&sM<6H(+}@ab|}-=5Sg|a>>Ztw~dezV4$jVB9u$Q4@I!yJ+(-F$bM`j zpI}l=ws@b@*e%XY6)2tvVC*#}@CGi&>Mn3UwcSa*n{yk0p;h2+H5IuvUi%=?3jMNQTzQuQV+)wHz~GIuV#cDldBwvj-?yNN`sc9UjlQRngEYL58tt^ma6_wEb^Leic13OkQCSR=E z?!vTG>N@aNgx)bmea&4lv9r9g&|^Bv=fwf3opZN>h2aEFMeI4Ju+@L!g@+LaIg{Q& zWVetfH`8$M`+Z+3A}t193Du|0d;~btgMdZ+VR&0p*THYq_HnA#mD+T&W$Z32o_KZc zbk*}~^)mXQj~^m?L=VToM_;ykf!TW-gRkvPnM+eF=U=Xjbo*YuKiUbrNq$h|&PdL4 zsN*j|I8}+Fx>Ty!;ri9$?iXZP?<>?b3Q#=5LTRgY!M96h^EAVuEKbXL7a_3$9qN}E zaF;eCF$N$--u8$6%WJ?uZ!451Vy~)z4Se!dZRCOBXZYP)v`w+(Nw=RMHf>xn`O^AD z=OijjMkHd;5VTPhZ~0G((8p^SiutRw{hI~HGS3s__t$86jz0;oOD7BJZ$VX+cTM49 z5@ABdM&K%iiM`A6MGI5;lkiavhuAO7W!s{oUIf?pD*jufV^O7I{tW-U*C%Wz90n+7 zH;62!7Te6M*1P@=VVf7;r*GT^%&Uq+Qe?l%P_*nhf48Y9l^?a|DZ|%1-qS+Tvk98) zocZcm55I$`(f@1J{`WwmX zboM?`xXUjd%K_+$2e#;5z;7_eT$!y9bU?b#4;olxJcmT3$Adh(@6!r;Zw!zydkY7G z*FcB5`knMxgw)h|SYu)jR>jo)lIE5uFxQFd)-8AnW8}v+&!; zJ=j^T`1HL>t^vDEZEJv?Y#|04aX}ZFv+!BM-W|-4W*jt(z(S8B#K*jBRbH722J?m8 zSL6Xq)zjH;yiS*)?J#|NjU6(XG@kSk|>9Ywp;v3l%CwPtcSMxr1rcw%fPJmR#sK*2N5O$Lr_W>1yg^ZT2ptn&imHT(6lJ(@L|L0~j05E(A@&cKSCp`UU2 zvSy!88f+mOod;Pfy8@AxUWGYhcz#5Dt@~oSlmC|2))Rf%(f_>%bb~f2n-YU~AbC=Q z2!g%%pba06^ewWk#sox!IL%L)U;|NV8y=VKfzt6DzYP!^;z7JG8ia?j9tXL?M}QGS)hAIdSw<(xoQH|br^D6*P;f;k z?(66N7?FbCpcW3uX8uQA z_4}`(Mr?jnj5|n7d<1B??N2tlzI@H1{D7cxpUHln1dE_os1V*X=T9WxoUtU1euyC4 z*^{*I^q#mE5`VH$vDWP;-k7YYu20eeWuuIiAWZ>8N(N|xt2H%_J9hQEfk=Tx#Kjj_ z+sl5HJWg|fmAsvl)SjVadd_w3KaRb_JVj8)knh>s zM96YLtr)X=wi!bH7AFf-{xh!G4ImLJ$nSymjWba)U~dfFCN7y|cpg2hvJoJj6lwgs z423lQJ`l2;>iAdEIL-3@KqwHkGzO!bKAUYR}TK@rJ;t0H0#Aga#_e*z&)3cJ8gVB&>>)+i6HPby zb9--RpQcfWd9G_|01x9Lx#)ck-#qf~we>{1PpC9tMflNOS`xCGBe7oV5Z>=9Q{@tN zt6f;>n0W7NlaB1EAf+`OvYhGE;9v7zCVWC7>N+4Wjd@d;q6iKB!W)Dt{=0Sem=-u- zB)KyikTsEqTrgdF?Qc&4QdK74UAVnbF`YX*ZN!l_&*@0=@!r+P*)LQtPWg~}zIQd{ za8M@2&Dey&nLj3|8UjHc@Xfy50z177XXa}H2DCcE8!Gz&t=;3#(BjAzHBb-4yBKHu5r(W=3WGYIPynV z8$ncP4Q1u;Lek;=G4f(R8MH`&(dW6Ye&$J>mOmWDjAd(tT2tRQ!NV0DhKNeGknJ%X z)!W7BKfg*U*1NoklFnbYS!;_qhtKPeL}h~Hb|n4i?g($CZ>oZzx1f3Az*-uu0&0wu zgA$@#_&0gk-~3E?L@1WFcf3!U#<3@w+$)!MXVF=F9tCcir{`21+uY&YjEo%*r8iD&+?33V6oU zA7jrww_NcGbw?>t;6fT$rl>HyVrPPWp^GMQfCN73ka&8)DwzG!2X7e=I)XtedCv3= zVB>29zEvXX>|d=h0$PvOBlWaC2 zVgpb|mQZL26U)QBxz9rW)xG={tW@4w&K)Z7ud)GrA`cr$f4V=9OhsFOAs&Ti<*Yle z%B%%t`Q zOeTEJDes;oKyG~dCJcUD`0ei_BH(ZcTMA5N=TC%$WVDXnw=={qtIM?^9gH&e`M<*E+ z5E&@6tCoI@pKV;x3HJ{T*A>PYfqN6|K{+00G}*AziLxb+$w#mO_+~lvK?80PTr4Ad z6?m1gC{Tk78Vo+g%T*agj+upqOmT_Z4*&In$cb5pOEk8G8$i?VGR(^#lYzm)aK z0ott?P6gs!G|C4;6BmTce^pDqP77%M+2JasK&Knu^vSAmqN^q2S-c3P;p=CazgW~H zy%;DM^23Vdx4$Mat%ii~6(^|#uk`wvT5mB3G8i@s8ypn@w>At4FYr7ziaWVcYP^++ zN#E<&%B!FtIFh-{Xf<{(6krz&mC&J<-&_F3(ePU|KbKe;<%EGtNn+P-7E3WCE)Pk?iW(DCvRgN+T4A*Pyr z?j&7&(qptkA^57iLz@QN&N6qIy>9-n21Y#RNjF8k7fGEHL3e5KIsq)$8Dv1q zzOx#}bbRpakeCMVG2isXC=i3%EvLRa4JqYH7YX^u8U-LgFhNA|>hB_V%k%`QE#hl zYh9O19+RJC!etL;FQz$^=2s8$f6+ac*e0yphN_ib>eWitQYA`UwBw;}x`fnP z@T2|eH#IxV2O+_j@z{oA>KA5{?_`L*Z}*uBCVC-mi>yvKAP9mnYf5L-tx@=ImO}re z$~JK>5E`X;`&W-~3%sbY9zI?0bPlr-TV;>j&i_odQLQ73yqm0eF!#{|kT|6oog;|F zGB>9U()07_0dn>C4in%5 zj|V1~^hX#&mD!Apr@*L*kQ&6JS7ZC{aCg;)Pd(6}Dg$Wf_fUNBZtaT&LF^-*s$=vJ8RAIMTN_+tuHJSUBK-lmBE=Vs~`#eIyW zk~5#a(P5vhCDJ|%GiO8g#=5=5y5ri((ew3cIJ+^}x$FF`T>}}eir;?Xm<7tUTvG6t z?AZDe_|`H0R{g?4^i3x>`XZp^UnWkK!x92T_m+Fm6t13+*{WNsFqU2ohIz7v&EpW^J%HtI_c%bywL0kl&LM{Nh(oG2%~~l3VVW%a z8OQ5nI?vu)WQVOVchM!H$gfIIAY7w$aCbcmg=C6T;7U{&UYQ=38nT{F0Aq;99E`{} zc*KpEIZvSK{nR0nc^~SwZFv?4q(^Q6ZQ4=N_oHLp)Bb7oy9e+sm8hno&LDwrAA#3a zsD}&GwiJ~NGz`QUXet!-!DWi=>_J{$Y2ayJl5boFVEfiqy&dNchW^{7n&k@#xId|i zhv%+o0hH*J!XupT$X;h4fyFQx^FuVS;PiQ#g^HNQlVIJxv(h*vK(?TuS|w2vR^i1@ z7dmbby)J@u|3y`p z3EGG9a4V?CqLOaJaC*3F1fXTOu_(hXv^`aIlLVKtrZO0Y#2`qVVM21AwWAk<_3kAwc zFunflr=Mt_INDeKGXEwS4<1&@7S$^@NUpaAq>oi&oWy+8Dbkj>vbNqWM!nPtn=}WB z&A5wS#wCQ>hA>mReRL8XQ4JdOq{KkM9_GE7iUiS)rb z9q|R-1K)d~;d;FrjwGT_u`TW0~OrT~%S!9lNEC-6(F@S*y>V(-%*mZQPx) zQ|`Kqh8O$Ey>c}qW@*q+7>@M#Uj&&@K1c@FwuvsY_dA9cpAjFj&vy%`HrQ94!uRiA zhdzSQN#F|z=!>Yqfnzb~?ym&_fT|EcHN5yv#C*r$}J@&?J)-+wvX{hF){ytUd10Gu>`a4DUV=e zy;8wJz`(CDJv#x{tdrYxC2~P^zNed?jo(D&zP4R0=OprtqEmR~I9Yjy9ANrHf_)y6 zR>-&$#$o$s0sPVpF_QaH#J>96&YoRWc|AxE?#pOwc}lp7P=MM(B3%_})sSOt9pzJK zo@Y^kq`_{TUI@Tf7&q8DZ@4dmfQImia$9+S)+YBpR6Se!H*-J|Iazx&_k^mn{f2=?D;C*lRjaw5S`gdeQXbG zV))1WX#LQt6iRaJK}+^Qfy4K2Oug*`(d_jGf2pMbm)Lvjj^?KbN78SGT&^fKZ4oK( zk?>!IP0BBp=0$F>(f zVK=K=tj848%=F-UuF0BTRkl~Mhh@m>SL1zZa@ll)ZM{$bkXUCgho=qMVOQZ4J-fs0 z*FVC&7l9uqh(iy4egc zjw)USRi3=BI$Mib`VZF)dIgE?$WCHeorJ)ZkeB`NsF7pdVfI z&=LWrajQ(7?6^oQ&R%4LicA=2mw3<@`21`qg{{$j=*+C65*)-9IHjPdoJ$2R z%06U52G_!JQw2U?j=nHPU`W0tpZu0fZoqUL59-&OzY3NI0~!JzIVB4C+9=Ba!w>xBOX zng4qs6>|utiJUmNHjj0$EalmV0 zsknM(?~gIFH&8cMP&uXCXhQ3IK+qzw1G5H!UDH4An2nfPvY$SHD;Tf*?TJGT2A1X* z`pIoMGfDd4D>|8#+|YAIrzHf<_fReV_ZYnq+%i?rgFX(_l$VXUMmwn8O%%E=~ikOvD2&1{p24xWvj|xz&Xu$elG69i8kl;vW zHX7k}#f2yUs_{$5EU>q5FlNqNSHI6u;PG!?4!mws*b|T}S5y_$vtTSgthE@#*i}o1`DOQJlkc_8DJ*i|n7L`Gl=!D9*j!uLA4esFGf%6$iQl*#k4_G-dX z%{Q(|*8mBipxc|wEiCWL6b(d0aI2GsbRkBYMGU4{e3YOw}_~BrkX3dW^wDAjVRG{$a9)g zPek0m>P@^8CWqPzUCM9q1xihH->FX0+#J2t18gBIh&Zc&nPB^9wXT63ly$`XDqc1C z(QI$CWkXDwBAQBLN9)1Np7szJVBLP9Nqb0IvqPNrskZESs}C(S;$m*9iA+8J-2l@D zq)J+9K=RQasUM5-1-uIGR=UB%DVq}XR!i=13vABVYd_ED*-J3k%D4Fwjk}F3|(OP70F>;nU8ymN3%eRA6$$Jz;DNDKq z%eIv`HXmFcd(V0pbo%5kP(M}~sy;&QP}e?((d>o&veEmm~x7i>@GZ9fQJ+gq!Z{}h$Y{pF)}k2-`v$NOGdA^&>rOw2|rS`zSE3#_mG z)j6+1p4_;hh%H10yL}^YlRhtGHZXrpW?<7xLM5G28Smv=un&Gx?Q zD>ki_<=8C@b|J8&gTC^ZaAHCFx{&R0Xc746+|Fk2;WEZ5H;IyPQ9vT^k4FQUS(QFGpxFKF;AklpyQOR9n7c3vmdXlqoNZSU<| zCqp)P&LsLqj#szAR(H*MOgJ=0UE7|{_!myj^H178 zxy#+ht8(A{STS=?g)`$+ftt_bgo@s|eH(eOScPk3zFAK__-w_J216+U9 z$?_pWqsHMJ7p7~R(7`tp492kIGRxD%QQ<=MZ0ThPLS{>n`g}KA*pQ1X2s1yl_|TwH#O-S ztM#vWKsAQ2I^lLLfO4PXi%5MD8t12pYc7&KfY{WHB)GLFwi7!FzGLU)YfM5_yQ=HN znR6#=IEtRX5Tc@9!X4ARfmHKe--Zvu#+eVuL8aDxHp)VFk^9@!%^W!kS3id|%c9^5 zU4Ho84`fVOGXkzz6~k6XsC>-U?w=)ku((ha+7VvfHJZM$2*TJy72KuG#eQpJC54Sc z@;~(|c}oXD0GIBKrk*$V%6?$8V6%3{pk-RgJMc-^_++2yxaipfCZXNa+A=epL*R0& zjj+)VZL%%f$|DncNk+7lva;K8VXnpeW6Z9noL<{3WcGm2EMu?|(dj05i5)YWHIuN& z1zdr(>D3P(KD@Sw0#(GButPM;1n(q8!_im9>uKW-wn8HF5V-C7eRXLTh01sFb$4@B z75_lwF!=JpqYbS9A6Z2xY0|x~1oUMgL%X+^ii+F-E>x%Ji5cB9(VGoBs~Mz*%D2Dt zHrR>AYa_7~V@|pUUh_W@Y4$w)Iuy#phsxaa*2vsT_-9crjpID#c=K&<&)h=5`msS8 zPL+EF(lOy%CF%H}@rp>LTcc%8&`;SJ$%~E$KcwF^j%mcim&=wpcYd5?o}i)yivv(U z?|gCk#;lr0J2Owce-px2*sufpPPMLTD}<*;4iuYKXPm+Uv{o}QinY+-+R zP(wqba%a_T2WyB#3Y)OcohyH+9Pi%=CQ1+a{EGbdVuuolCxgSY`i#rls0#H6*_3CO zk@XnQOV@g+MHTA#k1YCk44NG~VVw{|PGj4agB$+*rN>?TkzTL;GQD!xY|XCZCc!IG@K0&pF(T^cIggr$ZCk#wn&f@b0LvUm zWoz$l<|z0$2AnVmXlP}3eoT4%1JIK0W=j^ue34OrV@ z#F~Srg#gh7BEmdAU4x#9?2q~ND)d_m$36w3cw3<*VOGi6gK3I-a?}pX+Zd`B46Y=6 z$siOj`J3n4m1D%O{MyieH5;4h8sQx~J}_h_#K+SQ4CO#ogIT@lA-*F$%A;wE1F z+!O!)2|KdU=Icgu%!P`2Lxf2;wKkNkCxAj|Bpv1>QjWF_TwJ^11aBGbtatGd3}1kEP~G{OqpqO%%C*PLuksu9 z@|S!0)-z64R*=1lGi~TTiV$ssBqq6jBv96VM}ut`a*>_BSrM%$2#6h$lU^NS#MUD@ zpE)-a#Gq|gc64;SsY!ak`%as#*k}a%;4}|g?I+&Vr>d_$CU}|uh#Rr+22sJk@qLP( zHl<)l&A&0@?+vQI-@>ous$GBol?-9mFWFKaZZURRt;);#Ex)ERe0&~9Y!L(3N{eG^v={hp+`P$!04LyM z29KRvf<~W`uxr>bkdW1=;fq7mO7advYTaFfF*HFv}1H8PIq^ z;r)B9Rq4l`1?(>?ntQ<6pW3hG-Tuu5SV9K2)N1SZ%_Rzk6jTwFE_S3XC|>P}!2ub8 zGl>xor|vsPiL?^3n(nud#f=m5B)Dw|{wx5Q7%PqWzX|O<9ODxyT2EPNwXt>We#p z8{H(zsvcQtX$718cz>3x?0|M-g*3~9Wu6Sn$*%Gc|)Wp+>EIDx5>?}Hq$j{|PqS|&=r<-asHNQ5Lwf-hLz!P`?RDJX(HQU z_Nl4)+4t6#uAmwNwWbta4h!Bw*g;4oyQX>$$V3KWzPzGm0cgSlxcBeuCJxIoitS*^ zX4|h)Tn(zr!a%Efleo+9eZo($eZ}FlGS;zw zdM)J}S(##Zqr>VaT)J+VM!W53I$?W`X@S|G0}vB|Adm+SEM;Zgsw2e1<>8SwOAbRA zT$$f9Ce{CmGJuCjTQkYUB27IJrPtyr>4*2W7r`)YzGu*Xs^m}vwyrCGB?AwCAWUww z#&#I>-X%**6(z^k;s~X?=hHT2l}&)&!qis;IquCxp}`34yO9T^AJjPF4UluFHwSyx@p7$c>9AMe6Wuy#BuY;l^fWh7ht$w?}wyzIvI z+Jh!5X@!M_7tnllaW1_20_<2GLS3t`uYc-G=&DGcL-mEy3-@i4?u2BH-z9;uixNt= z8dhU>URvy;@ocBX``+lHz3kON;B@An3M6ds;8f^?j)UMqmN*%U!e##kF|G!X-80lX zyuJ#$($$lqmJPL`A>=bIW9a<+xfEpHYfM!mlx-6S2iOywE`IA0oqy!7gHC#(*F-pT zq$}|KpJ3161>uYG2Ijn%&z~=2O!RI|Uqel$$MCf|zm7q?SE;KCGQ6{}TC)6> zb;t9zzs$sa8%8+7l7*R8Po^Ae>}D5K0cl~{#m2^_&0XApqWm$edo0h$F!@3_!FoF9 zed3*Z7A9iAmgzbPwb*s_Ntmi%UjW3lU8A&RdQ@z@%xHRP`vSLJ5r+5e$i*n(dL)Dn zpE%GCus%|%W$cbL7?xZ7>i;9`z2muV+yC*4D3YR*P!WpCXb?qF8HI|LY=z8(jF3$*R`$M2u}(Y)^7@7L=*&f|C<&!K|A0%JG; zRDw52!+l&A`xcTAP)-qDesRhXw$L^d=0&5ujJgPxsN4B2+RcY02d}D5B!QGL z_u>Ei=xT%g;y*t@Z3X^k%b6#TnBkrw;u-1J+iS+tScOp7%spzKek!|<(7dDW->_lB zH}vsD${(wm@ZkETUq1|gz~7NUs%Mo&&X?$CnwOvEAb=J(=wk~`AUk;5n%qCeE{>$K zTg`562o1+Gm-#=4!8W!wH$Z?|Zoj&$Kc(c=;-&^b{{mo~+tTy0#u#*!g>SY0rXRAH z?!vk-J3E4p-aI>Uxg4GaY^=Up(VA?f85Y`)2s!~xB>7{JCS}$&XVrDiO?n2CZ?d zVjFg1LzxpnlP3owGr&tOX@+}@*1gh2z&>eEVJ^?82q*c@U*ca!! z5DkN7dMxx^(5-yH$770jc?DdVpN3cikc%AMbYq7_ePAYW*ZGx&5BS!NyGF|{*r==Y zdOJ?gR-x9ycke_54^uKEvOlX?GFIvfx_WyrI&k=~-G+@DHXHz?ViU1=D4O04xFH7M<#etrR;KIuCOc}6qS-IU&wOZXC>l6$_FI{)H<8{JKE zXVJ62wp{eZC|`~7Ggv0iEUuO0jgokB$YYFEslNbn6{D^X*Lvj$X`P5RYfy`DmpS{V ziW-{L$d$Q46iYCvCPBM*ZK{+{L&rkm6d#G2bZJp4w=sQ{Z3UH|@R9;Z2JS|Bdirdo zH>q%Znn#r-Zi4MT@gic$_8UEx>Ru1FwlK!j+dwfK>Vr!EgL3{p39a1d4EbpPIxoLF z!*|>dOf3#l3U~P7iUn|yEF1lB5lzg7Fsd=INY#_XIio*Fh#Tcjq9VN2#`DjA3fvp) zx-8~1K6k@|?Qtj^Nia>aK%k9WxQlx>RC#L&-}_T%CkJ)C&542jR!OLh%o;QH4txu< zvq%_sT#&`!rtO^su&iR6BPQ@dEShEKc`l;4$Xw(CrhR%_(~ZuAj)c_hbLQi7DNJ@@vu~ z$L+i0np*JHXAVfN9Inf=)`_bWb|FNzw?3sf>O!VcJ*1JM)V~&j60?V>CZQ7E@@O+d zx+&jhq>U|K^D(n0?lvx|ACCJQ`X0vzOpVv%=wsL=(cMmPGZrSs^P^AQnCyAUH$ zj-7gvrR&Hzuww~h7gCnBtS0)>SnbayL?>pK7$@u!6nvj7lg01`-|N|`Z%>OqQah~m zoUh3sM7M!om6F;sVFLK(uaY*6($4PouWtlhWFPcw9Mjo_=>l1pvth~E`h=V8eMxBMt@G$vI?4M_oNE&t2h`Y!lm~l!PLe^a z)Kj^57$5HT)vGj$@mD_fuC>6JOJWfepCfNvQ^v&a=>9vupU&0e(k+w_tj#X8ge}Pm zJI3k2C;C6{Ezrr}|6?>K6Kd`eYC?rZQzj-P%D76rtm`|+Sv}CQNP0(MK>@#Jrn`pd zS56;2h^a^bT%=c4U72|`G|0&p%f#4ASDOlHbKxvq=)cd%SZ)-6IC%Z`#lpV(rgCs$ z-ThouBb+7OEj9JS&p6nDbs=LaF7bvBJz?S#bU~8#M}`;kmqeo7AnB760#_Ag+D|S4 zYDoTWfk?Juhb>yjC?LY8o_bvQPbdC6`LBeYWo|P2?O|}3sRLcUhAVM)f~}tZ_zz&n z#l$fQ6jBvF$o)3(ERSBo=&Ef~bzH@;HC@-H%!P8kHcXeJ&m?|r8!C=W$}+FC&|E-j zf&?29(4;&!l^;R@V#_<%*LVraf|nkb7`t+MdLoa@BMo|1L9ZU69TS;1ifQts4Sl7- zKG&e2RfIaA*a3a-P23mt7P9`cBE#^d1;xd;F`H0U9TL7#!O-zn?(gph`~;0u$b!F) z;&LM?G5Tzqt8$p##vR8Ga=jFmkcgx=FGm&UHzI8?V zDc}jd(h*>h$&$u+cr02|?X={6GZ^Tkd&HiD4<~bW zpUWCK@dE*eN^B=C|=htoF_a$m`oUMKaZST^F6xrQ<58zSCO zP(#x8V8%RQ}c@N00hQh}2FBvD6!6qjO4x60|}TbiPUpV}L61%eG7Ba#Ary8H)q87SuQa zJw*hC}Qh&YX0UrKxTKY_Ka2Qd5d{ZCY{ZOBrz5PYt1-73I> zNlCFft^owl;SY*^$q&1pR#E%Zi@XrW!P`x|plS;iQ zDnYv(tNEWINa-7x&FbMV!fI{=1Q=SI!7@JnpkI`hFzQ~mp#c|@0Ex~hzzqKo6a3pq zumRulY~Q~9q=!BPf7A8O^Bqn!^!?0@f zMpBUp8{O5ty5GOHB_bUyU|+YXI^MRuDtl{vZ-$0WcTu=6?^lPh-oH5B{rFqH)UPdO zqE>$=8#dCz8Tjc}>Z;3UhsP`(3^)HziK9hJVK4O8)ipbTWZIjX$LSjwuX8E&=& zT9TGPTvjv}FY9h<5Up)~rYan{iBk6jPCs3y&VU!MI4!)#`KQzQhbokIc(NBzg662= z{{1&V-Wr$Wl=$nPNe+Wd9B!Y2U1>3k{`^I*{rEgrXgFRP6BU2`;PI&&kDQhDxODBP z74hBeKW~t__ zEf9?O0X8pvmbu@b{t*>3Mq(zp^>dC_p6ki5Bh`Sf<2I=EnF1tg+j@2CRJYGKi@?bQ zX|#7=s@ssR<soQkn}DT4o`Qn3IOAP*lsB3a5Y*^9o+jT@e)U2$J| zYK!zq5^p<)=j;EDPn)h-)c7Y$vd+ElOkZKFNb%EM(R2}N!CSX)AAOifyh3^tiv`rT z7_4noYeh7iKQTn?b0>pZqeD+@2;XT2n(NHsFgYsEbAm(3BaP!vl=JA)(@bj?%hOz3 zDvms-uAW+gIXZ~39M;2J`gXOdNM-Y*gB*t+Jh-%b+qR=59_!sQPR@avRe8O*e^N0SLIFz}kPd$1tt$&^(azN&Ip-W9}pV!793{(5_VJMzS^m z1;dAgPS9tXx=f+jv8B-Tecr8`>#~$B;qQ>LaHd+Qc2M|I3&Mw;(wg1=2Hd8rlncQa zLYDmXI?h~;Ugo%+jVt0_flT91CaPqUqP@AAtr*|#pxbW}EG4RURh?|#&kiBKH2hih+D;_qvA3bt}+wf)#??>8f41j@~PhD=XK_{s?J~qHPxL9Db zBsJ>lR_cCiysS33=sI2~xwhK(K1wWxp(_`m79{R<6}M7)rr;@bB{K-QK*eyN*Ys7v zIEQczTV=mK<8QF6V%O2=cW-{WkCM5KDdE1ft!?V3PoGxWN$dV8T(r~E3s$zS4#kN73QOP4S5pF^K36nxrd45;079NWEX2bt;oa*5dk z%9owvSJ3{7wCtK#LOzO{0HQqGF=9^=s#xO?D_R+JDRf12_$Y9xH*_fv+=_zv7;MKz zlaoct8AO8Qt*jDX=jTr(r%IduB*GA!&|X^w8)O__;963sN%vilXvv67(&$N6YtK_` zKRuY!lRO`5!i$^1ie-L%XLay9M1ZqgQA->rZERehDV#i_Esn>W$Bxv1q%-qkR_ z2_GxBk6%~KbKUC-dWRb9Kmq>Kv(PN0t&Y>$1W;``W736f#Q%#d9k9kxfFpt!#ovg- zX-OEBU7uv|ojdD5%Zp&maMOE%&WNCbnY)IO!_5U@(=l;{_Iq^cEM?|>4y-htGcW7* zKbCwhgN|a8lMjBaDX}~jr>TYt?+X#%pI3GIM?$1MIP%x8&9(>G8EQ2r1OafVeQa+R z)ZW#x_Nxw6zRLt2j4;lJ2VgKJx@Ru#b&p|~h>_%5^kVF(pG?-9#xovx(iFqb*kshY z9y{u1_vdAlQwFj(AwNB|VMD0>XSVXVe!x2GTZLjyKy++O&VEr8++e342i+AHidP%@ z3qwuKqPa=*_m6VnIwMg^Kl^^+SpD9z+|DVODuMu)9~I%7Nhj#rMFbmgICV&TZ-+Ju+b5qttD{kV zA}lmgwVO|Uf~7XmzzYpL>jq&Vp+iDh!$+RoRnnUIMw#}`qJ=w7qx=y(aBa-heRHqO z^p{*Ki`!GHWVy}U!1g=6_mHgg!i)=p5iwenYJ)iR9S6YKkoL{vo&L{H@oh#RPx2yIq&QK}+PoYHDh-zGN>?F7%hSHIKN21H1pT`cS~2 zm37sn*LV81A^*eVgx82?An3v5&4a2>+iV%TvDL=Iq2`&^zToL=Aj5eqH{JdGioTcP zaFtg}H46kN=O_?`DIfU-he_CwjN?}u+=g44uUCLU*yRiQkK}TbTx|Ds*mu=k6O0l53bsR`X?)h_ zBm7i$J)xA38GSlGAqTv-i)^sh@tBXbQ!x5#FPZE-+l^O8Z)-%~WuGz% zm6khT57_76dN132q`yf6fbOdC2my!J#7heB0}rvRj3rSOcSsu=QFV01UtjDmdNP7z z(dFau%MMes^RnlxfBiQ8tl;)LQUm(bLEdZ(ZaBP#BS z5BJ6Y!w3EM%cCobzWsy*Pvz{aj#=9tzjRkh_7ZFQ%(+R-aUUk5?({u>kp+m$w#$7v zKfif($AM6M3s>!roq`QKx@@kO{}lc-C9UO0j&Y$MC*Es>k(YO6f#aw0vn132h8?$2 zOdT3`uj0_x*Wd5p;LsLsbC%tTh>L-m(55_u{g(=HB!JiKmR*P7xMctl&7N4-!nyBy z=57Do1O9&bCGbSjUa3XM%^n3{Jn)A|tL&yT+5!rLC?h;1tCcVyv6ty>VWWOSZMy#MD2bK`1V@#klMc7JBc zKk)V$UJ-w?-^i8OQZqHck`ZO4R?K7+=GlBRm~HP z5T$3pgy*c_P4oxYSDshf2Yy@>hVwld4In6zATt;yt*Ow1U9l|jgL8Piaz6D<{xBU! zhnq@REAm*{$NZ-|o%_1E=upkCxD@%%o!gtppxKpJI)I@;GtV9Zp&i z@ojn8p1iAiKHZ!9C;sP0d4z{4sc~jbZ{Vqn_n+C}^pu_2Z(ii7pP}weB1%CwZb&C= zO*~AAQpGqb1Qf@+GFGGJgUyju)Ok!Rp=M%+iq+~NBBXb&^w2%T=SrePFnbPsw8FlK zEzeHE7wuj7;x8rPPFWWG=$ZHxKWuiw9!(#Q<+)r?@;3d=ai=Qb$9@E3kuXSNiBYcseGng3p_CdV zZy*L?^;c22BDK(^#-Dut(z+ir6i41D4)pw=wMw4S>9oV92Xj6L$)opvh-wTDtD9MhEtzXz3UH<_O4yxacKh>Ds`1I-@*KYalxBt5z$q!A2G` zv5n3TCT%@HNtQmL=6D^c2KRb~6`4Rc%e`uXJZx|IdU*|XwH422|5Bwp?e?DeAlvUJ zV8L__58)?frkfz+J)o#~{%HnL2ZrsLrxELRdZx(aN`c(`0sHYN0JLwLm`Hk7iwt2W z{rwg(rQjSyj#kRIyd09f%F!a%VsH57_aC6yhf!zqvA|`nUCUOAnFleif?w~^VZjg< z9%XMAHGHlitT1^%-=%lAqsGSWCgFL3@8exE293{HdOLAe4x}~09gSyid5CQPA zdnpEvuOhNS>0&8NW5c-JAjdhq^Bfj6`jCb)x3MdWulEvnMYZ#EuU{n(MlH}E`9^iM z+15UN;VKDRCG5A4f2Vii3>(N9i90af^7rUHU0)@My$VCM1O3QTu0kqc|5dz4w%^x*Vsq z9cUIrD<;&jZrwUI*1F#vBuZZ*t!;nf28XuCLo-Cb-HEKFU;cARP-CUMi_2T-@}Eb@ zbdWr~ZnLBlG}OYIL2?NA%7YeEVq0VuEpo-rf`HVMUT0L77{zQ+Q{wC$K@F3f8(6F< zzzvhM5Y}x6&{w0*3UA!G{&Q!im+g&`;^IvonXqmP&~`A+4cTeZj8aTYHIzClr6;h8 zi-O#mN@D%8wYmnbsEP%|?ppz{NF3gd{GzC%vwo`n%DGLBUjg8GHDB}ki!e3)uXho{ zzdTFjG{@X!N3#mR^N=-qYG+#FVFojgjP8D##>wLbIr~{abi6_&vLd|3+i_ag6C#b# z$y;j)AK~gV+*oJpx73w)5y%Xlk+PBvfHL#}mkISKDJl8mIntU_wZook+9xC0w&#ZjtEcE~nneh?Ri%X!ny|nurZ%mLUI)7v&qlYT zt$+QS@rYbqh@Oz2@Ah2xD02mUw~=`9n|SynJpm4N$6G=6^~in2&KTv!4+==zY@%0z2-;;$k5S5xbboV4z{n7buH&(0|Af1?JC9r-^?jdS+lWi1788pzx z8h5-r)OlU~_i>Dzqd*3;6x)a*N}JSc;p^Av~v8s=j-uC#&fq&y*v z$>mNG-i2&cyiQA3YcoVtJTmg z`fERFllK1i!J$4ZS-Ec6Uk}cUJh&YdQ(B!^OL$99;4R`66HBugbnP8y*NP}lQ}3&n zfSe?a!5Kh&$6Jnb-n&oiNmpgqrg4x3FE`uL5Cu_kYyoI6NG3uVb zKQ92L<&!G~_fdYCdcL*S1Wg~8%$=p%h6h?&`eYUBZ-Qx2hcgqfl+%NrDdCxmt;sZL z=m*J{MMpkOl}xq(;8Yvri{$MXEsFg0U=lUZc3WFaAgwk#OQWstXHfk z>BEve;OE7&Psg11&D#Nn8HW6)UDT&iv>61nUz~&pve$M3B6n4gA-;@UG=sT5H&HBL zQTXP9)^-lCe&iO6Nz>em{gefEL?8qT4Z1n!W6>&a-`mH|!bJN+L0!Ldep+z`j_}qa9mZE<5nV`ZtYc$k;CI zYF$I0*AHm6m;gV}3k@nLQmTPiB^C<}nM~|&>_Rz8G;i7&;PpY|0zSl@hZ@6h8RRE4 z0F6|#rbJ{j_su(^YeA6K=8e|zD~SY$h1n^9F(;w+|FfG8QwC&pc>dgDYhWOxN>G?c zO-dxG1u(WXN{9s`7%w+#M!T;BuaJ{ldfc%nik1Ep!8=dg70;W8$5OCR$N5{_9?=|a?lVGiy&r;saKr8lrKkKwX4A< z)YJWG78@amGe>8m)MwR6Mx=r07686mfT#(W)GPW1{!+&PzHh_``s+~XB|4cHQk1)7 z4}dqH0LEmXr_=&CVH%uNGyUNJAtNk(u)}8*ESV`2- zrB5N;{L$?<`T5|VY>G>d__TnbV$n1PZ2P3<7FlnR=@c!k$J4#0t54({#!Px*IHOHc zVd+CBa8M0EP%&qfK%>C6)A~uu<|p%^_S8RfrU;%?TG3Bu?r`qoNB(EUI$KFx?hx8f zx0y1-pElB^l$v;Il2}5RRT#kkm~dHmF2-m{5V#rR=a$c4!=@3=_U_Visq@-KT{hR7 z-$EXQr>&VGSL-1X_#&5}6}sunK9bW2Zl|;^?fT!Hv1o8Ikb1dXvZ8g}W#oD0d`*^? zM2hJXt(M!He;p=pP{f&%NH|(XocZMq>i3Bdn1H2Gz6_ni()pLt``vUhZnz+R^T|zW zY_qzq&Nd^XtgUuuMx{Jr{xgptoyqoDF!PtWt>#yCU67GMy0p`qfPVaSS8Kl{qF~oz zO1OoKi@m8yR7T~)9GQh*rhAI_PlQ>&?q0%wJd7|5m3z+Lv^wn1b5 zzH~#!zsH(3;^)%8Eq8FPS^l}=9x7n@x*Y(5ll2f3)}i(JLtKA-la_~j<78ibxA+!- zcZb;|xS4KJJB0hpU-f>kMy75SogoSobB65-H@q#)PGed>Aa}X$Ka7<|5r|JlQCoe~ zk$-!x(f$mA3fGuQAoO^UJ<{%R257&M=B4wei!zQW{HTL0Pen>Kh2ukPA|ZvvKjNJy z73KWaFp3e^4w6e=UiM&G0|nE=Traj-#Jo+{*O-lAS`9VOEj^UXdUXaD^5EP8YvyHc zh1aI7b7k$EkzMXqYIgOaqN1gYa`$||Z#jU$(dV#nE2&%S;)1dHp%45A^&OTU514oE zA}!l}LgI$E!v5DW0d8EnHdI+(&q6mZ7f4nCjkXPE?{55oj)!P=txuQY#KV+U0Y+cC zPuY2%u4K%}fBkx86OR)c=n_k_Cj2PjO^w9GZd#QYp)Rd6Ff1enIfU#gXvYK#3k$7n zeZCkj@S2vLBv4$my`M>Siu(ceR|Jp0FI)1ByYsJ|il? zOHI4`*LOYp&w|`Z@oMWPZyJh-i@i`?)0N z^FLoaX8$e;3tSyt^qmB>^FuE<17}w2(6MkcoubC>#~)`y0T_WmQXQR87KVy?tDH{md&Z z&Jd%Mqm31s&Zp3ku?XDqZ=1IN4@&i&2Sh1O(b2ghoZ#j%pPz`>2$!ckV}!(%eyQ$v zdE-O0n8CCoshQ&zYwGEzwWg`#9#TK^481UED4@7`HBBd@5E87P^x)v2oVd=bL5!OT zzS44X?qn>%imvTQK@B z*DjgC0lj7d(Jxtmu*OO4aPzRby86vsdU|?3pB^CbsdW0+&A76ggKcBv<%wqyLv*E7vl_*qRfBe@;?%2Y# zvE}<~O8U?%+=OD$%l49;*iXhZzTaDd>#p2Ed~|jRF0d<7U~sCPo|j%ce%Z;e@ce$x24AQb$9;M>*Zw< z_1y!qK@058Jn#JR&}6RRz>jhjFjB@^Z+}AT`VYe=FFNNn3pa19nC|UqWTh#ACIMEA z@vM@oUiF??5Q|Va0)Qp2VSFrw)CRfDS`wjfib{e{$g`JcceypBgn*d0K(H|mRyFCY zV!#^Kp$MI?dwsMo^Gg4-Js0{$wNuU1+Ie`ysj*OcD@!-7;^BTC=HsT;4Tds)F18yh z7>q7WP1rv1a)@^iO#P-o@upSqKnKeVrK$G`Z zx{ITAhGbt}UugqYOB`5;ZzQ_+fxr>N+i0QW%c4&%{Cy%oTFP;*VyFpf+1E4h zTCz!W+s-#9MgLsSzsGH1d^b+z*Avgu%gNW#8)i@~ZQaBteM1S*IkP~R^LMhZYQybY zKeAIwM`vFaXMJ}(E+rueqk`dZk2PCgny?401VG5UZXHXV(7JVR^uj)3tL?{payLj6 z#aluye5B{`9yr%&+t;gwiRU!ygS&Uv18m-y=p*L5Dih3!L63F$;jTTG;Rw?j%oIFU zDwZTDS{b)`G}wdEd8W|!ZSx7%G6pM=)-^>pVyX^4S%MHoqXZ|kEOOTX)o&cEiMv!v zY_am!32S8@Lw{goW(SF?B8qerp3j;wy(_Ks0_w>HbRcl6B%zX`|5)>a`rh2K{vRri zg#c@gVaRGfVsFWKz${%!VGch1zbYos8FrfCyF+z#b#hEES|e@GEO}j~QP(4AzB-@m z8bJ$N#^`RUI)<<70Kja`#Wf)G@bqdmmRV3J;cNLA%O^O@$<>bQce&$FkXhNxeItp7 z5US(pv5HKj8+~DUUT;*JMd;%2GiZ%#XNw&47$Ocb8c# zN@ZQ%c`kPnSN_{zZ8W!v_V^y6Feyh%EB@PuEN5iE+zi^H!vb z&ipNxKo>P>3FRZ~FRTBt%qx?g2-|Z-hB99ZR{={H zkllgjS7(-)If0~5-k{9y9*NvN+_LgB@dA)bD6#K)!{ER?ZyLnORi{1!G37!h`gGIB zqlnD#w4JP$5bH`ut06Pc|B}wfrJ3Fc#M!rbBCT<(+sBt$O#!Fz)}>_IiEuzDY+XlIt`R0q5+3kFy1Yvh(x&Hk)}gq_8}N0%bhJ9O3Vi?vZk=lV|=$KN?3_}6da4@#$FSnyB`Y5y~> zZ(mmSHEw<;{48WBcdDb0D<`RX0S{GwXdq%Onx#VqG+;`t!dE)L(pDVrSE1T?%JbpnVS$B3vWe-B5sxI;42~cnnhJ}E!7AF3Yjxe=R*YCK97Z8~pKe#tlE&hnL#YWqa z{>$>d62=xY4-^Oh8dwOrJr2?VD(3WIWU|Cce_6N}SW5omLvez0lq zRQ0K9R+_$6LMha-y>|WVh@V4!mR8P*AbDKhKAmE(E>Vw-=;KkQ!o-?%n z4P82FO1k61RMRI;*xCzey=;1qw6o>y+|qJiX+C`T;O!+CEI+fwH(wHyXWLhl4Xsqg zSpX>})}NQWnJ8@S-n@-^l!Z|0x@aS2q4|7?HYeA9FRgk9xNt<5ySqQi)r{ql0snv-#Sg``MX-0JO;SVfGUXj3%d#GnRHh#PR) z#_}CPgM|yrY5Mz*gv}2L30S-F=Bw{`Z|q2R1hHZ3mCbEhuz$O3?ni2N3mvdIKz%HV zI+CUL9x#dl?vMyO%daBCS^Lo$M1fFCvs3aEZR?Ojeh6eCEP)3G1S;SSn1(lQGRD@R z<++}RF|AmW^=)Renz6_Dis*t}e!aT@SJU?XqvJ_3Xp1GA*9uryS@O$veh1|CDqBktAm66R8Gd<7o6n+ zKuy3y*N|@6uDd$K9?oyx)Z-4>P%IHvrFU4=DJh8r>w{?Y4FnWfkU7%(Gkd&s9iav|C!2s4=euB7d>ULLnI`R3 zoP`8eI=EiTc0MzEF^xdhx#E`LT`@xdN@)xW5qfgJ^i*qDQ{6~-a9Wek49{EgL|kw~%Dfc!`u2|>CCxbtIhf4Fq$p@;Z-H~CKDOk%X{Cz)T;|JJlFSPrJr8{0Z7((rE%8=~Tacw_hNke!&!RDvEXWEzx z-oL+tfVd3JRnJ&izGy|x^1O9dPX{ECv%c^HgDe(R2Eluu&f*|5&zOrFSF!wSV}0h? z3q04EHu+WNubX=~0oV`Sm)*CExb`_r7_}hX_{TQsP-pgE#YIIMt@gOhKPnP-q_F^< z=VvSC@$;otAA6}+f(}BMvhiB+gTfv+$>D`<*8=XUbqmw*X*jN zJLbUd&~~T!W+c2GBkZ`1;m!oE!I7c>;Q?dS-JEh%Sx1SBpaE88kB)b(K28ExH7~ry zV(sg~F0E}a@Ho9ZJU(_jL{0d~pR;X4gA0NSct7i8RzQ1MOI`Qsev)bveER?QlQX@i z9?z#`Oft1A!a_QSADjR|;xca9V$^ueg3_53SE|UEVVWL8`f0mb_=7e`EHX-u!Yw3M z@Mf{I!1>fZ!UPo_-Tu7`L3c->X6-B?z0*6Co4GNrvtqS+`n3lzsTEgE?- zmNGBqWIc+lff&blh#fBaw{8nb{m*gHULMW5v^zM2F2!T&qVkM`&Y9_D67G}kuuyE8p zOmQzup1A!uyeVurBf6<^ePLYNHM0wY1nDe!M8tWNessX`zwx z?w;%~%KQ@o!FVK-GmfGIl{;gL0@K|}tK4+opetv!@*sK3zjfl_ovTx68 zgFmxA*A41%4;n^Y<0o4Cl1kECM?RmdcRfaFW1*?>*!nMKAcNL}GvhA+t~2g((lHhBvX1y)PuIQ!3gT*W$G@Z&@ug3xiqO!gAl1 z2SK5o148%x6_Hx&NXw1mzDWD|yIJWUDOEHJjjpgv{@5?PRA}Y+LY^#ad(to$m zvoc%dKORG^d!(=Q;q_yg?CRm~vejZT8nbauwPOK%TWk0RY?pOV(RsGnUR z=H&ATu?HSz4`BasE$+Sju_wx|n{5h8F8^>9Y5Wcu&dSir&QcdCtze=CZtSR%j zNI}eilcbMhe}+7C|FZkaal;8c;M`&LnlAluR8-)hD)@Vm3?iQ$D_vR31|r8Nk9lbO zt3gHH-gv($i);b50^+IQPJWf0J*s2Zgm3c}+Z?vcOR?un48}h6BCUqc3T{)8?xBytJLRdv41MhjaU1p;DLSZTUgULwuZ7f@Li6H z5hy>T?BGG|EcA&VYoW^My&uJ`gcJU0Fz%l?%^5At>55Sm`?T z8;u!E)}z3P7=v>1?fvLCA}Zey}_s0A|xeFa&UtgI^ncw2X=8#4`xw9qJ`{O!8YW*k-<4m)79w5^$g_H@@6 z4`Vu-lM?GpY>wHf#z2gt{b=!SEjPt(;O@J3N~{c%yF-J51jbe5Emt>;OvKJ_z+UtE zhS>)?J4((x-`_uVIf$#O;ggKYEaEGZ>SFuI8>KA00I?z0&3nX?w^8QX$9{;dZ|COL zorf4-iEHB*VKv-5`W+zr1 z+bFp8Q%RgjKJ>6<2!aoj%!^qrVfgfKJNvUI%t^Rr)7JOF5~>cvUCgoGF&tzk%%C$; zqW?eb$e$jp3%+`5R(A#-pBa{2WNDKbi~uh)pFBsXVjGDGHL}T;_Q^%N+A@xIId9tw zZ;f5a&9w5xg@s#ormq38g2`gwK4uOdZ zc;>BJ1XO|BFU_C5$^Ygp{C*8&vT^JSr1E2C+2jK2!}g3`c8Sw7dWDAc#9b8Po)V@s(BSLJ%g$r%i zwM)WuZ_D~W;-e8)nBZ)*PI3vm!RlP;;a9t(3dZPt5q4r$Yi2}rMIgyR;^qva00T^< z%%-njGI?54Ijyb*5y?^|ZK$l~A1A?o;bi}Mt}?0Qk?zikSv)g;!NLN{IA9XD!72^- z0vX6dw9G4F?%!Gk`oG4|528IqKJFci;@2((8z(e9P>!_qsJh|pzLxDKoN@2yz*abo zA+s~Y@e^!f&VLfPcZZ9~m70x>jZ~^~ip7QVYm3NQ!Fr^>F6psRy5w>_*kFFc_wry( zG=NqdVoXor{OeBphTCnd&vHx)+G!JQaS&2Vx%|&$kqqYz*)-Ft#lJ8gTf9D*z(f;q zTv}MOs)njFTxwH~>^|#re$|Had#0Z%otsPZ9@z&;*ea+F8?ygT4R0gId$Eo0EJ;8` z*rGL;s(f)|NhG8ZZ#fsQtR}3Tz9HBLAPMn$Gh<#wnN)3G?ekZ)aEv#RDA-3&9 zD_FndL-^=YY)8d7pn$lAbAR$8i@%5T@Is>-AHkv8y0?A&eq4MfF)U&f*RUk=hHp5N z_wPPpJ!JfN5Cj2@=fg{DlD|sHf9ki}e&@oP;MNL{qo3|qPfa$*vOdEtTPi-alU>YQ zp#G-TtG<5s?0%#Hv{OBGJAm=+Cp9Q)oBNuZ!8nBn_KEKd52=68)!fIV2g0l%6wtG& z7m2`|_Ez@w|CGGFL}%b%ziQf6n@r^2b*TFGXW%B?>xU5v@;CRvu=A9W(Dm5oIQzbc zwIJ{q7>nEw0t7XxyT;>m0v1is6CZtTTv{)sUhj-=CEXcGN<4S!n78zDI&jQ2$$FCz z7d87W&V%2i0Q#BWGs2QodvW2pu@iey&EkII5n#|WmX@G=wP7S8$$sc_AxzA=Q{Umm zIursOmvcbgC7kCyNYhFn_CQ6$qQ@y|#E<*(@uM@%+USZh%G!Qd*%&a7OZ4CxsB^SD zhQy)2uQlCG=wnlNYAr`@+w`xWSV82ZnE5$ePxj^Z8+UOo6gl<`m$Q+(6S)98HCa@R zp%;Pc*L#CyeTm?}H{1|DLaA8#VFTL);5#2(M~E}KWkC5@=7gylQ1`flq+!V_VyP%2 z{ErAnebywd>ZD;ec@hSB5%;^fWy%#t+zT;oIxkIDz3SVtg)=hS(<1JOEp zwK^2sGdV3?jd5Cop;+pq4eiF<{teRc?@pSwG6=LVNROTz6`i z*2!&KF}XTz$f!0U+%j$7{~UsF(#UKy_PyeAO*-52HPA4XgrgI)WviR5UY- zdHC?*g+))lT&lP6Jtc+jZB)YW3=8_sLP&Hqcf)%9_6;422%FyKEDc!I3Za|#S=7oD zzxUN)b~6(5+kJBa5*b+K(ODi}g_?7HSs8;0klRf<7YE%MD1zes&REYY;^r3c!5DuG zUTCh0K9IBA0Fy!^)7JU=`9*2@cdy^{PKzHjyw5$+HTD{eA}B3)Q)Sxjz;@ zcfQ|KLf2BgoZz153tvTvPX=mG(t6})KRb;aS&n{h@*gUb6B>7#ww(I|v*1OL=10Nv zIPySmhJ+|BL;vaX=OS?Lygh91Sg&F~H1f#NQN~rK{4@smw}sWd3H5B%gFR`WQj3O{fFUdWXjj*ZN2n47Sj}*sdfH!;dnf6p z(1GvmQ9(G!)5!Bw!^EDsUiYehHwH1Ulju^Ki~Cbt)02kT4Qr@FA>iz z+5RV0AcRM<{a(=gg~+)o6C!QY_WT)`&eanEi81p}r)W^-AARqh*3`g5&AX6wPx>ya zLz&Hc_6REzW^9+UV?)X=COhr2e_HVLeA;&|W=!Qj zjl#>&^(%vst{NrTG|e_i!cbiG$-v{}279a!&oZ0X#W0DzXZ;xy344X&Js$9VhY$bTl??HjoCg3+Fyjj z0*Zi-%ddWo0c8iML)zma(G8>=>|0L4E&qB8n05fi<>}N+1Z&{;i0>-B=gA}#QfvHx ztnE6Wq%@qqnxmFDj82vWim`B_ye(b2RMI>;oPvIeUF%u0-oszvrJV ziqch9v)GC8)Nez-v z*IF4}-06gF6ksyqNGj9W#D%}V2kBgG>hbfMI6;^|^R(TL{&!a-Lj-A_6$RY0h*d3h zz1A^_17C!Pv)C||Z`&IWCD!1X^Qq4R0oy(ZPWUI_SyMH`%Ru(r7_!dCHtF=~(-(K& za!(u)Vk+5pWyqnSbN@;}JU7NKU8RNXBYlD?o_--1>rqSnKjjGUV>v z(WyGhlCMvqe@?Zx4DVgKbnn2`=Hoxxk1RjQKuyg}9d|kIvKQT#>k29Yrg^l?3@elc zHp%v$-SZhW_%n3C@-}0k(wSRITkXy?ciLZ2wnBp5i+=sB zfj=4tHdGwdaW)mLYi-r#lMA1t?fv@=ba8o%?|;mH(;LZ|Aw5@+n*EFvs96L#emX>) zn~wQ1Ff!UiO9e|F#fxaDEvEWzCl1Fk4dJF?xfPSme!jkOWyZ#eGvr?wqvp6b3A^nQ~@aC5cD{TjwQ-LKS(o=AzSK2=LA3=umQ0wQFH zSR>iUAw|QEG1k8VZ>lkslR4RI%Wev2$aH;d?aY`m)>CtsIDwykbt66nL%kvp#9dZ( zaSPLWKH7-+5(yCYGkO&tNkM~`eJ)S%J=CUST7Yv0(f-ZyPl413C|AX7Lt zS)r{_zvFJdwsnNs;Z+Gf^=b3P){n^UJ)$ZdD91-7yZD|YaG8lT@FAivNfd&gM(Czj zeVN~J_SGTWRX(HY3l)DMTHeo=yOmZ_(P;98iCy_px>6%26plX4FYZ42eL1xbQIC&a zZ%;dNF@*lV9PJ+12c-QHJ?%bI*OXrozi(o}T39S0oxZ$>wepU0V_n^bTYzalM) z^2m<)<>HPsz+Kp}xWBWL4`A3xw=#wLEU+$UJhd)X9D~=Mq)@B&*2cKfu~))zs!tbG zziW$q_x^A_30blSe^=JI--H8ZgAl+T8MfSqJ!Z>_GLFaAogp6%ItwEXEAm`>g2Uen zroY~;TrV_rj^%IkH_U!PqEw9X{Vh2ipuYJ1_8ljbCCW)D^UZELWb(&_u z0!845yc@ram4%3azm?j zaN8&`C?P(@>Nf*PQsi>_u7i)%^RlcfR$qjL(#LILcfNW4e(GTxsq_6f#Rg2fg)Wav zsGqDIpztGu=&yc;OKF{07*nB~6qSSSp)tlQ7t_N(_yPz1j^P#L;KxSVno4t7z z6`S=Qt&Bv|)ki0T-KBl#mS3kEQxSh?o0{3OtyGeS@cuBS1;W4a)4qvNmn>}R-jZyB zE+3VUG6naBc|RvVb-gT(7U{#8DI_elOD8S?_>GW~KwcU^OV^h#_g;ew7)8S0e0(Ca zKM0w^zf0%@(X(!oQuMOjTmIlC8UxdXnMS8r|0K7~qJJka8k@U4%Uw0|?c~N%vzwO| z6(ve|kP-`5XBM+YhdVJgRxkUiGuNEB_rCBp-}}W(>g8E49*N}}bv@cjk?N|YrKMep zQ{=WTAn=tQXYWnb?A`jmc5#bHUwY7>$h~i#=2lh1SII&<*shR0xhrgBWQjb7eIv4f zv-howrMU;p0h?Ou+8R{}|HbK`EgdK9g7Nx_qxVrTv3?Z+8F17Y%iHz3MwmXLl+usra3b0|Nu^PKnmbKT9VocTOGYrbtTE5=f#g7h* z{rwj&{^B!XSU)FT#I3m=mY}u(taYGE%TF6O1i#63%+2`0H$|z!@d@R&i zVf$o)$~>3U-PV<@p?9Ju9_a_&J~S399P;bBV`dSjM2)3;;h9kA%Zi{(IX7fV=qT_{ zd-Or?JQsNF>Pr(c1hw(PGvpz zP)I9tzpk!s$AZrN|GhOep*d`N6SioUUst`fY)Pi5a{Ifx(d?}s4_-9Yl6qF+Zb3O7 z?>+K4s_N~M)jRdKtyH&4W&eU6b=Ns6_JvANw)Xb+Ze^%Y7|7JJ?$&Eum(X+a?y&u* zfR7cIzu(VlC#UerhL*p|^-)Hlm?C-Eu4ZdxOBjCzSHMv^bPFJr+bj`BgZ@IrP3Gh9d zqQ&sS-#oMD0BFrz|9RrXh_z~sd5u>0q(F-P`dK@RY_2d3e}FMMTeodHn4q;UOoT?0 zgnAyomA&l{;1WEfx|o;E7^aOYpWHmSX!5Hi!EM+6_#nv3D}xJ|m)+XVuEAbJaeVi9 zj>SY#H*3+9>FVQA#>+)Hlq1rd#B;lUERsADpFUIt1$IJOjgo&Prkw`Y9cxGdgpU}D^|AJU8zMw z^;q8%OS&^b*w_@hv1*^}*usWNb%}L9WWkum3t{#&aO2a|uYsvgfJpCRf%-t|M4jl% zw%1ut_NgRf86ChRlBQ|-hQ(ZGZJTYH4)yv!9~Jjs2DQ4yDcp10C%PPul=NO$xaD7y zJ^rXDd?m6Tz1cCV$vO5+8e|{()CLov@yxN-O8dg1G5$Z>*wv74h||^i6#Xl)(j$w@ zwFN+el=z!ZB)uFhr*-2Nd=zuD@qEs?bCYGBC#*`tJ}<86P+DNK6WfAh^QQX1eiClA zfST;zaLBJWOGfm;aB!*98q3Pz46m{)JW*eMICSeemaCCSNc1-`A-8w#Fe$X4G(Q$i zaMa@S6KD_=&po{2@Iw>*D5@Q^I~ekAAE8z^S__%4wPEguSTqfXCWYuW{`b@N<1+7G zY*R9eb62gu0TVi`fzp1sJITmgMMiISeaZXWY$DLGi?jKEY+ZLe)_eOuL>Xy`c4<(V zWrWO|~|1r)(l+&y0*aAuW|_}ImfGf z@B8z;KG*fW-orkLC{iOLB0_d5LM>s+B_<-0rsAGBp5*&1o#nYyV}5;bNA2W_(=3xx zuis6$_kAtxwy|Qka6o?aVoKh0VgJ%dg+4`jh%fKKab)6w|7L-YhWOUlFoZu?ui%|! zsl;8_rxm)#COmKT`HsrC1%*HUaag&&8xhmD{g6kmxZ~mR7qMvSYW;nk{aut3i0|%o zoy(HHQ954+(O-c90ZurbdtK2lZrZWq*@2U`+vthi^4ndiESPg9xeoL3A>l)3i05IY zfP};mypru77jlP9*@a1G_ILya<%PZT-Yj&Fb9gtOV#ZnP9MS6w?(x{ySw24OvHFrc zGo5Qo`2pefSXfFXlrVA%h)7U^b6SEI|AUV} zzG{7h`!x?o-JIc){YB5YxDFdcW>xd$54=72fYVYA`#ddXFE`j?Cw~3D0La5l3G7Rk zYJM#TC6AIZJ|K|%>b<|-;p?5lzXbX^-pI0rzIbOc$kGwz|Ezel@nGP|^z##U4*rs3 zUU)qCO!VUJu0eVbD~OGI^zOdvky3Ib7igeUZo0m+FJVDA#|S2NOUEFzcD^w9)N@@? zLX7ld9O&4F)*z)D#+2(XPv;H_^Yg2~PkoDWo7zly@}Mv-fDy0T0za#%si{iv zbp~Cyen(2rbZdBKJ~Fls)Eu{(eJ9lS5~b;dbY?a#5j9||#szDNN2D&n7Cp2e{viaUNgoUKSMK*Xd z#+pFW;|%{DHHcl;FyE_RvmZeC5!jcj0va%RwgiPqMwlrJmeiESF4vw{9hc7$@)Amy zKQYeVUeV@)CX8EHxKhBd^-b7=r$UxKwquuHclIw{#_hhQT7TUB`n__l>A|n|10|AU zHigX2pWe^8A2OBKmug~Adw}{PCtL4hzS83Fo9GhX0lya>g8^?SOGYo-MQq;vdXw`W zs#7)_bS<$pz=DcoMmdjy$Fe!irRQS+wVAf7sQ>%$eAcR@$< zrnr9YJ$v?e%${`}mM$tcbZRgYm~JuJs%wgg{0aDEhS^q}fAbz^Ui3C%YnR&}l)7Q& zQ+%!_AJ1+v{F&GZCnsXXK@7l>_4rr^=A$ircs4X)yE2>8gqAt)xaSjZZ92?S1+2j6-9)_%aX~*V3&%fyKSR$_q&_ z+0tqJ`SLT-i;RJ&(I;q+4*pzkVx~5qB7DmMMyq};3$q@TCMq|~6574e%U6@pL?FC> zeOGULLPEmeiziaPBtHA%#f#GPi352`POk<6Hj%4LUW}=${~B@S5lMY(+6W$Gw6*1xK@5hTY@OK?~)!H9fa`*=P0QFIk82p&>gW zVqkvi*i)^P-gE9y)fxc;PHOCtOTo_Qv1xhp8Ue8{A=1M|vd+`dC(rFj-g7=Tq-cJZ z{=T&oS+$)zVmoecwN+z~-Yswavr3&T|3VjF5cr0oz-~TzmG9fHO%Px5_UBE%Xr4p1 zHS9bpHg5SWL)EL2Nsuq~{7)@Advi?S06E*uUK<|9jBuAYh1NKN z&QVWw&cl^Mb~-jysWvJJ4Je>GQrkCg;SR4kD;ECPw^2D0YqWQG2+JVFJ$pz{gG!{M zV@CT>TB^BnT!NAWx76)Z#TDsk_XC54cG0;V-n?Od!wwdI<%Vj%M>0K16MH{VgQ7;m z{42xOy5AbMzo%Vbn0ESBl?5p&vDIn;WoE*6db3WvX0c84%H4q+En+;NpCg#t-QziL z?cG{Kmk-n|a5tZj4VIvckQce$IXJNA+aX>|^DUe01fFZjTYqf;zZ<(bzoRFdoU*pM z$BRo=1JkjZexczSIE4 zlgx!0mDUxW7|!I0Z&GHwHZ=?hry>fH-+X{z06Fl1bx)C1E9rRI4@!Ts;omv??abVS z77Q$`tg4^pxE?f^ro@;%og=V-edWrYAolIEXx;ygyVxf5uHNC2*nZId2#L+%HPw&=(JEml%|OYR~YqCH*aC9LnuC^{4r5Mauy0b+D5L*uaXVFhXfkvymM zxcDB_FZ~O8$%vW)yj5*Ge-Bt^Y~|T9jNtu7QWtmkC2brHxF#jCHCqExiq%YSpu;2-6?MC6){dsrv$ldQ7=F_;id?AeX z29)6=AudBtPfxRFS<*j?%j_K; z$7197?!Km6U|%bV~Scl5hYQ%o2UuV@@_4t57J_~*%(S{>HL5cX=)}!eg+njrJf0#}%oTeTiieH*sN|h=Tf4th5ay`(r$RS-3T(0PhoiTY`c4UM$rP` zGEY43H=xr7Vff*u@ES{!1mGYY@#hKtyY3u;SsO(xX-*pHW5ES6VN8E%0~@90VT%l- z#E(f@jb=kBMkyHE;ZU27658_>XLT3=p_OT zCnR1$v{Aow?srq|;9S(`V-jn3q=^Or8QwczUTO=Y(6 z$ZUH4))H#&MDXB&Xu22{3l=pDMTN*bFQQ&}b9;?NTz(aKV-GHU2WgVjy6)QwIaT*s zRv-8cAOGWho_Vuvh%fr6(VWvWPwjCK`HqL>_IzY19MMHZWCS zxXS2Zpmt~z?Ae-avKzVvV`Y0myOgD>%NHvVNA{dg|5^Nh*(|Mzuf z!Ty;NEc93O>;$)rabRFTTZ70q91o9JXT?g*}78`|FQT) z(`Mo|Y0I zi_|-`dqe}ry=l`cUJc{5Gj-;{VhPy$RVNwf?N(5z_(Q`WpKpPh>e3f!e0=7ok7$s2 zlA+PQ(c0yA+i4-_adbV`2DBH;j~EbhYteL#)FsB@ih$Wh8iVPsAo>L_YJy$L(Uv((`JSA}il&}MUu`DjAg_KJ% zfdPSqYR}%i#f;1J zxz20cla&)Pd|vkp;T&7g?RSR8;`*sX-X!ssWLE0Q(sdpO9e0OGHLfW3Gk30DwK@03 zP9cAkfiT-DiW?MF3+)I_l9eUVT6pYr%?4sQM?xk(+*bOu?6!~YvOCF@&cfm^)*sCi zy!ZXP&Cxu!+%8oW(iP>iGlICtjjlIC(muB!0Tw9_v-rQ#6b@~#>BkLkw}fa7xUOyX zJ?Pl^C5m6@#drRHkDuQU;rf+5|LN$CnVU&WfLILU@|!w2n(pc886})D*VvTlhygx{ zn&d@;e87NZ#S$Kdh8oHz9Q~AsAEpM|Z zLvn$GmG-&oK5B+rz5_~7MgYN@q;Cj)Cv>GWua^+Y^8%1P=QMxKqL`~5+DGzwlPH_E zJxkoPP>;*a^AU&SbCuSY&sQr={1PluZZ>waTB>y^xiWk;dCV*&dB>dxl$4%2JLLX& zfe*tfXhrnQtrVW%!MOo-jen4_Ss+;>y11|O5_w(zuGi#$X@kvcRl`^KeCCvV-|Y#; zG?^4Wh_{K=tzEjb{c`+ir4|A`txAp?O^OW<&)1BsPK+08PdaWlnHd3h6zPiM7Y(9A z%PV_?nPaMS>4y)VvAFk=p8Z6La=r0XY4fPUkEa+0?&3d#^wjYSNd+TNxb-U<8#C1{ z{s|B5b`o+f?yK@p`smyRtGmj3z;*V8`F=Uj7B2M_bh&1q2`pN^K!JOpa)MW6PvA-6 zkJ5aS*NonUP5&|>{h7Wn4_0b_(NhEy(cz1D zYH$9*a9*i4v3}MX{9-!F1fU4h2GT7GJ~Jb`KIv!PoL>98SLIav!o3aNhaM{}O>Qqa zD5QMc%DdYUZZ-$Vn1S_H84`T3VjAVYpSGcmhZcVfCoy9{xvxda`#!ZgePOF;HZx_) zQVxgJ@M*`}S6dvFk979x3*Y+o^G-*}__9dsfI6rp?e~4QW1q&Q{((NHssgvm4M#Cv z=bgFNH26LZxG9PmF?iETxy_bv@l$3M0bu2Z)@FiORhe*9t$&_n~r=)+-T4HGI@J6`luOgf~iI;wvp zbNiCBMNe1+L@hfsB^^(tNuGwJaDX(F$6OGJ%qO}abn*97o>+GVs8h6EGiu;0w+Uq8 zfp%_T$Az3k>lYKVCGBF@r{n|bleYzre#mBLMosLO6G65F0YSLGkS!uto1iBIk+6=r z^P#GjZA^Eu|4gF^;SyNgDi!o>lq*-RC_}jL3RR9pe;zstz;1OK7VV?A+N0vzm?-spwElY4!OJ$c8na%^t zCA%x)2CvwHdF$KE=<_B=f|)aVKWyj_i_6sM_Z3*W_{8dwTX{%vBDn$G>ir}A`scUb zH|n>3GcnR=4FPxSbTIklol-sKG9C<(IBv@fE&k`ZY6o9rm8>DBQ<&trA%RGk(#be) zo=bhtkp+Lg)Oi5ZI`94CJ(p)BbMK;?R6jE5`5QO{erw9s*xjJN_0XKPah1O+Wy3af z-nRAu)KWy&P?1kD%fz!vtTGqU-3P#&Y%h51xGQ{ zL&n=3MEqJ(;_lcIw5zR~{_^F^1O!9SYkD@R>=nTu{{vwBU5IJ`dFGDalAM*7$!;Vi zIE~wU|Ng6G34xc#qtHsVKBu;%nkUxDI#Tt2uwJ_#@F{t}d|#B7uC8H^mD0p#!L8E% z0_)szwgRPNsX_Ea9C+0kx5M|DX!@Wz2ntpogBj_;o{II$I%_1(QEDia*eSUz8 z$Qze%tLp2t1(qy@|fEw*0%OYbVl`yuaZ9&UW=x3lQ=& z|Mf8z+M|Bt+_H4BoW;R=^|PI@d=2WF&WAgXXJ=Ap&&q<44U1ga4d+nl=;&mv89YYG z*!sevhmWt)V8`y=yGzblEDRAS_~1f0)orpc!M`eg-2+^4m{QLc1oX2hrZ9spT@h-2LuzbkBbEhuuE&~zvPyDnekljc?G?HH<6#;PCFLd{Xuf=KVf6Oj=1R~R) zJ+tz@45-(eK%D%#9K*d2ya{y7E-cuaf1OOBPFevzBJ{X%e9@o>COs8*-8A*-Y3b^( zDF=6H$2}2TWj1amkp<<-f;*4q&}%QLgK#CbI%(H2lc2fvSJ+ma-rc905&D%v|4@BX z&q4Qb9}H|S^`E?>Tc~6j%*SV6aL&P9U`4B}@$FEU`;m0*!(VJjbKAyDs~pfcz$NGA zhi;%5>Oo)-GAkdyO?%X}T;Wm?Jrmy)r5>9XEYH2ii%Ve6>9VDNEKwHOP%T_scgRr zDKF_}8nF<{iIsVL`tzAm9+HvLfc^9=!2XumRB=V3X_Q{H`Hibr@4|23s&>Gm^=-HC z73Thk8-Eid8o<6}$q7!qiJm-Vn>4wsQ=d#0PHl?L3tFFZ@-1L#TGOQNLyvdo0hu^u zj7?2rn3*hMLW`ZnoQ)-Pv=~UXXBx#Lk+a@C>e90{UDe+uDcZ_!91kuVH9#K@C#UzZ zC%egSW@Dx0S$f(XxZKGPU(h@%LifMPBnCmVHBRE33PrJftRweu7 zrB`fsQv^41qu>6?IOX<5;}BoTd*A2P2KRIOHWoEcSpLWpg6S>50=>v=Tq`)FX7np1 zs@skiMTy&^`)#W7dpQGN@$=k;yE4RiJ4`q@IE-1|eV3)Y7F=2N$JiOO7=5GI%Mz%V zXzeDO=dWKE;xZ=QM2?JUEwLIMyW+8Ljy}@gX=!`=XI; zch!H{=Xr23Up3?Qv~LV@f3IB6Jr+HpbbKoNvn&kr{Ykz%E(Dot7qdy{C&*r2OEj80 zzQFcs4>n$1sZUqX+U0z4M&jCyo+>r_C(14%3;djznBZ9u|A)fxkA9lmBH(hbeN`-uc zzyA}24G5oW-;dO|XN6OC@}P4N`D39bsrEgHG{paZ2gTxUF2sC9 zm`8kPYy67IV2p{J7)b5ew@(=s?YF{$*=hZ*lRxp^CB6b*Be0*@W4*s7kG#$Qf-ir@ z;e9m99Y~nLJUv;M)bHieAF&%ItUB4Vfw>O%bUD7kM%NdqW6JV&wy`2Tp}dJ=9ifj7 z2L!JN%heCu4=po(lwB=iLok5b;r+aI7mhu1LUiV3Q=3rStE^<#ehy;ZMuX2trQ=2( z*#k`9oTFgAZKE5FkQ--YOJ6p*wZ1mE@5pc4d-9u#aTEMm%Hi8Kinp&7F0QB(6e`c& zKas6`f3$`Z12rbIM%@zY!+lq?v$K~7wpD!VLlP_jTNglOqKbbKj-V4 z1uN-WwtUabn^axv@@+dsx$5mS*sZx|yZ@Dwa%b_o($XCT4gx$HIgoTIVP4v_VZ+Ol z9}D;VSr%gi@p0F1zt5Waew;i#v}J&fB6RhrDsI+DkVFhqg#A4JzSf)hzC$=t1T8Ti z@FJgOMi(kncp}Pj(Kma~)jEnze6$ z*oP!jBc2npANl{z)l$;97yLeEI~dc?-_*WWVJ^(Ahrc+ct@PxZPV#O2Qpi6^2i4&+ zg1^TuawuS2_73O#6cj3_W!5K-D<$5r_VMWA>`3bW_9%?|%N3I+Tq5;Wa%{SSMlbXu z9zT}(c>S775+)3IS_@$m$wnqC${@@5mE+N(z_Gr46E?xQ# zHHUlSMunk_D=i*NIXJXLHq#y(E{Gf{I(wo_U!E6vpluob9~?D*nh+#SXFmu}Vfyjo z-!M8_7Bet1D&gcQPDib8i$@`J9WHjE<`4=0#XbsR(7^$tu}>hEh+jR$su#P z{n2k;TuCnrB3g5_P~KYsH}C{`Xo4_XDt2S{QEvj1UBT*31#rdFum}_83L`;*<4lz2sY;T-+wvTibJNMlSk6Y2i9qeY}s>j=Ro3-@(S-XtDB1 z6UEUwd&_y->a;RhK0*QPY}>A(%(Rq~vly)lC^~Fk$cj zY%=6n53Olk^BOJd^OeD2(mU#`7*BouU6^JcxvhqDn&Shh5;LPl$TBRg{lH|ala^OF zrK`w;=6sB<`x=;3_)tFI=v7p%T6l;6_mWVme$X--ZY45LZayn$az1Q3*j+%|B*GK1 z-l~zir$y%KT)Omu9Pb81o*g;;6gYUSH13d=TlqbUekSL`CAVb3su3&AN-Oaer^odb z;kb54e*8CDk!j)z?~mfG^Lr_{wYYduyW^`-JwAr#y+H(F;@i4#lsu8JD1bK38%_ zPY!i@&26+dS@<8$5mOyVN2QNvP1n{fdske1AB4R9yLNf1GRMh{|D1EFqj4#IWKLl* zJ$kzPdDD~q4qgT1=s;+itm_xPt`c?l|aYe)xZ9OMQJ2g_shN(6X zWfB}%MEc|l8uG2n$np~;hllgR#ihG%uWkC-9(;#Y`wvql_3gM&I0hqN!cM*>LvDf^ zAxUV_WTW=RO<%P9gI{MM5`x0IeMNC3{mLg5$0%0rmhmLW@N`MQr%GGD)hcrNH6D~S zRlX%Dazo)uj|@nrDt?3FMw(yMbT!0I>*sc6RjTTL$GNMWv;LpZgwn zl%@Zdh#P|U(XpxPK09L;myvdZ?#}9&cY$^U6E=qTXIktEjPRhee1F2x$T#rtn!R?R z%Iqch_YE0C5N9##(phh!6qIH2gYX^vv_ek+@`p=UKyayRersEd@j%^4?L zFe+y7ygT#fv!oyk#evmmb<_+5D{s$26!L0evX+BOL0I?0n5x;?yTP+2EhFiFG-3^m zZb(!Oc~d}KGsGKrq)*&LLS)@Im%0Hxq=h;41`1(SeHmzOia=ET;6Lnrhj7ko?Upa2 z%^^XIfK<5o`4iq4KGqpLw|p)6r}^IUAaTXE7;5ytwORb<1Agbkm(_BP`zW-=22C<-)9ROpknD^ZA(Ju7K|gY15W!@tDETg|}pB`XCL+Y@kG> zOv1GoqS&fw*zG!uFW-6IFCRPx)kp^u1^6Otk2*~8Ztwy@%;ISYCk6~t?tO``k|@@7 z7N{luV5=7sGDi+vq4vR^L(4O*oP+iN2WXirl-e#AA&eNlP%!bS-oe)QU-Qe~|JMq5 zB~{x^Z6;?{{sXHi_dE1>_0mu0z7=Iq@<{la%xW^kkH>y!pZnbT84-Wgy?}5h_aNc2f}L)8cyobDw*K z)%eS1uN@Mb)IgjVKvzA;^z@=Uq~Rs7OiEw*Eb$|87elQ26Ik$B1t(2CuL!@L8yxpd zHQ`{GECE!Bmq+ssN40M&i4r5|ZLEl@!g z&spYr(DeHuuRb@oCw0#!e-r=(%9mn|d&$Oa7yX5Un zQr;6~j-LLlL;3xf9#;q?QqKA|eYV+%$p>0&O!ODlFB;8tnT2_I<01+x*U^Qcv{QZj zn-AYWvYH4-BP^DW*&0IGcfC(QH{E99IeHI%wET(Rr2)5XfER;57;!p3k1R;J?IEk3 zu`*A4OGd3|wOg}&ZPDHJ3QQSr7~bwymckHS|z#_JqR&-&}XeWgB`3o;(w zoL%V{Ga|M_2;Je1&bL>h{c_K!ln^jM;Qa9mr*w5Y@ZrLcF*Ex!;8%^Oxp*eO#bem4 zbRa+CWaQUD@M4PKPNN%pQu5tO0xH~xqk>=H%@$3arREEnnV-Hn705_m!%quJBRwKu zRfn=CS}x!+s>YA)AapJ4k3zA<>c6@P{XN*y}tVu=-_zMn=!kDDE^pZQUlV zEq~)JNchc4$)_w3GZJalGkS!H=YM(5GbdG^4NYS*-6^#h0Vdk7Z>}Cljpx%}^A%vz zrAC>)>&~qgVC!r`PmK)rUWcvW)06w&3yhN<7&u--hz>eaC}ZAGL*Cw8u@NcntJkl4 zZ=lu5qnUHw1(f)k$VVnFyO$b5MV|O~vXbDoOAVGXj{f=vXbU@#Xc7su*N^-ub_vg%+(*eXbjVwbthbw~JhlY0+I2bvnr>J42#_c)F0qqk!>Nrqd`)-DD zX~Bfr{T}1rhlw8U;FffR@VPLvu%y1(gCp|$C7dm(hFmzMtb!YqXU07MT)Jy?=1_GP z-w#(&9PYZ~!Su;tEu;40Ei75{z)Nm(#PTUYSd21A0=O^yc)e^#o-F8KM^VLL`$;r` zxF86P;(c_Xn{nJ2_fnnwtio<}9~k+fhE zIK})Pvugkq!`$cL9DkX$v@M~!t~~3a)zVJof;Tz2Va&0&E&Ahf@6UOdKvL;vpL8y!+}gi{qiuAN1AqQ88t~i@**BqU z#PadhuVZiHZx&4#f#RPekrTC8=xI!Eit+hnP*a2||H!trkeI|4Kl%bJ3h&>$cj&oW z?$$?k8D?RH#|xMqEcuDmm}-nGmJ}TgB#)1{0A1C#s`W$SpTnLlaZ~SZ#Ym@;iia4CsA z5%IroRvS7KD__0>X=$xvfRfLFYgZrQ1}KJX+6dj_idNIaaPMZ4137>BwtS7P(&jBd zOF7v-`?Xv&D9pr<-Um43RDC{xpT35hWXn5$d-_&Iz1fh0HL*$2GRw zCnoW|A}E%}F!4J-h4<27b5ubQS_fsk-ord)H_2nJTT0lx)$uxaYQM=k^&J)d_fZ6B zfnu`4r1ZCA1ORJAyo$M9CsLPYGLsBCk`@%)S$m*OcfEdmmfT>8$bwEM)QoqK7An=f zeWY0DTfTTb;q@!=zp`X*D4rVBi(|!Tm@_ka5aT zA^U0h{2KZkk=s-&O?CBSwx)7&a%PDBB(a<|(Wj+hMza}Zn%+R!c8?34-T4Y&JRvO?ot=*;Ex z&-RK+nkqy0(wSoKq0A^+w|3n+A-uR>z0};@-TiNu!Ep0C1uxWE<{E);sJfNR;g)e9 zL4`3n2fLsB0G_Qo28MBQh|!!X-N`Jp9S9obTY1R{PEm!HmPw}V6 zX=lC$7+Dq-!~nn`-yZIDoJNKC;u_ZTe9=wJUb5VGk*0#?LWE+{HNpHXwOzwMj5e44 z?}cGHLMARoAr_4p`y|qwHS@s>c6E|x8qRSrLDAcE(Mcu^pGqHOJTSNM#tUJ$UrsAz zFJ$Q)UbE9~KgmfSTz{@RYC4H-G(4PZFp|h$Pu`K?fq}I~HYW~&FNTF;oT%K&gq@s` z$A@t>8^Tzt*XAcG&U<2-is3AGkD{XFw}bN-o*xQNNl}03LX{lc7xwm>SYlGVcvIIc zF5pUHWhMk)g#O3+)NxhXV+bxOx9ONc{0ga8;hPdcxwte}+o2+M1*v)8C4b{N*J~3Q zPl8a+H7>3EC#L=v-6&o{$2(FcGfb@f4r0TQxgvr12To|@hpnxAosEW%Do;OOC&^prRM)HNOWG~IJNjbBt%T%L)yeLV8TC`Jn z?@ps*NLn61lT~+WtSW43)A(DxM)2l}FV)@nI8GvD;P_aohpdQRRT~37ij?_ilkJ_@ zkku*_J!o#}5ZXmHo`1W8_wt0~c98>iO@w6B8-|MKB17xt> z+I=E8`)oUWbdAU7tucRR@S6*O>)4!vd-CE;L=WmsdQgfs$Fmxk^T3v1?k-ZaJXu&E zsSj8qe9qRkZ*8o2><-AgE^e%%mArpdGyV1G1URnWoNeZUe=`&XL|7BIRl(7=;`@Ab zx%z-ho9+E>YHGLn>KNWb9&*ofAt#p&l0INcCM$|C*E%z;o%YqijKzaN&|u78Em3X~dPIUgl5xoX8I|)Xxu+yR zFuYGv-|RY>ECJO!I0mAdYqI-t_rVMoYQud$zteH7%g{8qAjM8TXoux>nlKvFA&{*; zxO9(8rREYJF!nQ}gM;yHU9;-We?GeoIrWz}oSZol2%t>d@z}c9#KdG-*)pML#z3)f7Q?F_5xPQ;Qb&Jb8H#84_!XC}>XD<8V#l*lV zllhtdnej;yIS)D#|C9;ayDn9!Lx&E@ZYUC_9aH`F;gpf?vZc9OHCuaO4KMRZStnl@ z=6OFK$U9SxZ@KhByLMGCuxQuf%YPO;u4BLXVKbT}PhJ+%UtO{$zLf;%`fN&U9iEX@ zKvoR1CyH)RsJLhoRarGYr4_&44u4|x`yOw>8GnWNmNHDAcn6EQSy@=_>sjY&k&BLf z+wjMzM-3##4F2abM1`*L{!GjBZ08cdS-~j}G)~wJXwz;0uqKc3CQF%PS>OYA1tZc* zr^Rd6H-n-9ZEQe)JZUFzU$0?%Upq54ZrMo80SM>w)$7+v$BuFBroGc@EL|4oT&Jqn zsAFkvSX0|`{tNGar?Vz9o#jr2%)AGl=8MbQRPgs?-24#E#Kjf$c@P^98dMKStO8mR zLC)ncB)b3}xba>#R#tQzV|xfvI(qZGPp!g2nN7-m{AVTNQ7i%_&PFgtnrED|HXDEB zdML&qzEZNvjxxN;Dr?vHNFRt8E4Gb0B@!5zB({Hbd3UI{D*BG|R2H(%*4T>~wF2br z8bp4_O^rz!L*egArM0Yl&B4)c^&7`Cb72w!18VJ|(@y^dO|wX->O?Y~$V`_)j{5g) zxV+Xn6a*xJesTE=v1M4WT0;Fa6?f~?grjMMU-sUh7HJXfaNK?XRP9P{ZLvSxRCl=V z-o1PENT&HbwhZF@7kav!KuX1+*b34j%)01{>#v-UKvQBvpw zVbdNs@=UeOQYMN~wTIGMF&TZfe@GFe@5D`$$!Z$ukXVH0O8^>Z=Ix zmtD38&Y#aIG$wBL5O;j~ZNj5X2xY#o8!Cc76!_g{%{duxRMNB0DIxBxHrXED^~2s{ z)z#JK-dZ8TjD&1_d~_ zSP|1ARr2Z@d!Kh50?911JN)!QbjjY)l2_P$qAyczxW6$o8QIaVFXbgRiB?bH{k*Cj z>$syji6h$H01N$P=;8Q;?qsi5@1rl1n|}Tr(UB1pMG14b0BrYdNJdVuut8afz(#faXEbp8?UjTYn2W5lPh z>(8-`3;CC>iZ*(EL$U3AG<(ZjVa7}MJ&JP0KqRVnR!#fy)pdZar!Mw^PAn2#6~2jX zbf9C{qy=6Kgm$MFcpGKF2UT=$dT~&iB{q#@q=BcFQOM3ySd~THr%YL9IG{FU!-zIy zK?YGgTxv)L7#=Thd5lZ_3mW}bK=XJ(ez$d^0$68C`UF#DNJ>anw)yBGgR`?)%B z?acSd3FB6)M>h&IX^+3iW|IwZWbZs6RVnz=42Y$g`4 z^BCS^u$|8FZS5p6*f@n$fE`k|SBb0P9Ikom^`Pew-6*kOj}TuiQRNL~3EHJ((pm*l z#Xjzfub4)8?s$06NCYHr*xl{$$`;#kRPB-nBSXviUIAj`i!9KVPiI8m$sT{n;EWy4 z6Ra|KOhg0sjqBH4ucL<@5L1@agGkzL6o7cwt#l%@%M@TW5KxS9?Yv@eI>M@3`k*6qQ!h-YI6`ISd!} zqiioU_{J+JhNwTyGY6HG(H>l2qAZShl)hB?z7kr7!`LUw4 zl6Vi(EHcz7xh&5jmzAT}OH=mJJ|mQDmg0(+(19X~DA^&Gd$Uj`g<+_(4bC4bj3-e{ zx|_1oQ1&PmJ43LWxS%ONDjpZ>x(`#IrGr*#&CuL+laryHyVkjKrJnht^xYxw?mhoo zN|b})JgwJlTX`iR^f+>mOH#7_!WOgm3|w$=k#Aj7^_o4pR9ntK8jTR=qM$=CIblCyx+==hOI>wT&U!@AoIQGhfyqyaZIc11j0JP7K74Rw=3WSR%kZ{>l5YZ}v6++F%b;n_o zy|kHo1GX+r3U(LR5G1*@?%T38Yb-B{xVedOd^vmiGI5Z>Wvk^G5qxI2lb!S(fYT=@ zvxfQyp=7)Zw#)g6%A>#SZ2rF4XPe8dthD(Pnoo$4iZIxpnQID%9{xjO9~(=KE`;WZ zDN}06=U%9{?p|4Y{+%X$Ez9whA=RDVB4}h9xKVAAmR_BJjmwc?pvRfcuRty2(QVF+ zQ%w%^ZX(9-SOhvqgv>n-CWpmtDi)=-b*+c4zz2=JcoOsr71PPM_@r~N`D;j5LIlI7 zlyz$seLqd)HMTxC+@`<5syjBaM{PdTsN2O?+ILsJ{VAsGD*pHE{gaJce- z*j2!yFPxBaN>mN8RN)L+Lz}Kwvv&0kky{hF3uVS=1ny(#k&?YTyY2Yv4eii2gx+>Eo;fM7R}YmndQMN{{75K7PNrtW-u z{TUjcVo+GxTc@WomvZ*pKD0r1jiFZ#0A`Lgx2KqX-pt1`RW-(7x~{Q1M$}t7ITvY^ zrv}=K)Gjv+JLT3ZdiCM8+F`kI<3>eC%?))_k%cmx#JSkX*Mn30Dm?#^rI52w)X!^Z zZ+~(i0{;pBLjkcOb7_e}z=vRv3BpLwT+=tgRKuH1rTSaw5! z@ZuC?8#!1QEadxe8f8HkRh`^2fqvc(l;^Gy%5EnL;ZM$5O^Kq@_iZbjGQt=)M{|4- z${jjP+~`CoghRR3?dNg-(s8W&3Bl|Tk&#Eg?W>OUVJ-!2(h$?Zx9YRH_oj$_&bawc z2i!_(w{~r2xS%9&v~k&G+E`OvIXrR5TDGE}&sCuBOqE9oT+XGeut#zNSSiN>}RVC*4GyneLqeoFtwY*VV&DwDRzGpjW9BX+xmwv z(!4O8u6tNL&cPPBqUR`Ng{BRe*8N+Rk3VE`3dM(!OnD-B^e#31ERWqm<{7qiN!Sdqd!90f9O15{KuO@>l)ia@Wh=VT{9*n^0!#Kf=9r*FfNU! zE5bLRY-3|{tLz&4hBjWh+_PWEZAl1m2cnVGlK=~cD+|OPiR`mP12q6?y;RTF>RRSZ zsn_iqp?2?k^{ldAOGn+%1=ah9`#wd*B5?dSefsq2Yb(~iG)LI28+8P=6{31F(HjUC zB6uuyH{HG#E_{EQ92*&e;e)zeFlRY)E8!uxIAxaSjg6^2#^?rE(i5`YgSz+s^{H(zRrCiz!J%F%d2lZBuPBv@YCktwU!Bt zq|yq|E469sa+b1?@u-8!(Z|D{sqj;~Q*mZAM$+C4tQZ)gdZO%qE;2)~mIFdzT|*Z4XVEBO5T?m?%(ZO3;93e?ml9NkzZJ$Q44@;afvWkI`l zhpY{|&E(`mB5U{Lksxl7VDYp%d}umGmJUVb!3OBpc@-l#Hi*?(SuEpTvkj_VhDJUq zw@9AXyJq^ctRwR7))jGmSWkA`P7puWJ#h$&3)>&_my^(u6oK&9b1=0X{dyyZ-ACKz zzm!1_N5Yh%_P+0-^|;cS@?N5Z5qLUzeGnSv>tSJGv=0vAu<~ftU>?}tr@eahYCjrq zV@&*7Nli(+4o$j^O|(u6B6%Q1IpNV~5Cc%M)U%tpZyIjD>K$Ya$7*&De)IF}`wn#| zOqOe{>s7oXlPIVy+=fXn^F3ODZycP|BbOTT&CDsHDk45tAj$S#p(gW0wFJHcd zo;JmzGxl@RddJ+cM=`{UvNG4jvBF?0Q-;(BrF}x|<=ZGN`4R3wjzSGX-42??xMKaO zw(ey7WAKx7mV=^GRojm7V1LZzH3*nZhKT&{O#(A$YJ4S z_~c%A$O_@d-+$ecq3+$X2s?XH_Wt=_{RD5%t@ZPz)qJNI5A7!v#iA%>4N?GUb?E}U zJvOrth3Si_aSLKHN_f>#OL{GmbG0LFDB6L&q&P3h8!VL)(`F2|p=_3=H<0TjHqL4- zAd&uP~X|xOQicn{#Js+vztZ}4k)6!gpZFLl$%W7Eq=XgFlKJU@Im72 zSQ72qFr59`FhxdGv|5vt+*y#KWm9;v30d0X_Fv#%1A8Pw{xel{B>x`V7bv0y1}9#~ z_NODiF+Je_S*t$>fsHb1sHaV9M%y44xL$qtiMRQIOf0Md1j4}tj>|_HvdVH51?u>& z>gUdbajUIr39cq(~ekSMG z1SA(1*Q&*DHBH@GFk)kBON*EBJi;LXtNQrQ4=c(Pl3UNO(ZDj75BFHYg3E63Bn@Hh zvToO1uj*r6t+|H;btSA_+*#{O{lklzYZ3gIN7NtG&Fok`w=i#E$i#>1k=D&th=9IB zi}?=JdRFb(D__$}@++mBBwqHRkxc|AP;;q;a>am+8s8lJ0(e%vKu$`CYudp?*|W-ToH@$WaE{Lo(9H*dQxKhmSs;iApq zy!mkrYZG2tplBR57aM!Hgjw#h4dQj&zXn+(oz;$`1)MivnzKah)PAymalBF9i{Y+{ zLdJWAM~!`LTwcn_h^z^ZJC_F<<_pVTUVU*r0;cWt{G-a%Y)g6b(B610=!e!nHP|X=>j?!NQv>#8q%CaB zb9XNv+`=DUBynCr_OYdKFNwPA!|;#_Y^6aUPfdYqEu-7im(b|=_j-gcDo?4=V(MCy1Wqb za@1abT%PA(CuBnZi7C?^1W(M0nb`}rbom`JZU^>MN5TMD7MetNtNudiocm4Kw4AFd z_}9+U<2_CFlCq6&!txhKoCQp-1OMN{S!Z}pL8C8IfsFwql_K@O8Te#;aaSsi}#JnO#AZf z?n~1)?!p}r{Jav`(dv%xM;wCeQjw$@K4C_Gf4BIj1=S`LpKr7Dowdv{OkRdwrWw0( zr-~9f%EDTCHDit;V)yiLfpm^x2&d-}&T_uX869QpIRy(bn~m2sLhS^q-T<`d>ky=?VhJ>{I;`sxSB zo>|2Wk3_Y`!0vr!tugIEp?}YkrGtRzu1D|<`n-F{e0;@IyY9oIW0+O?pfF(W7-G)8 zHB}Y{Gc2pmz~Z5isc7fC9i=`&`c0i!S3tw-*BmZ5qSa^(EVt2+ZvEv(`wvUUW$^3n zfBU0#i*hr|*XTKUJY0ZkNp^ue8j zTUFY;I%aXfNQ?oa8VwR#^qw9Dc{YzUwe(8kx=l=Rvs{SRG|rG|-S?O0E6#EjC0Lfu zcd`t3QN%3rQg(&RQ?V6m{sx9;H}yq83S}gdL>|-FAXm?Nax42W7<@kJ>jcMajxV{< zE==tzT&q7hXdMlOA3e%f+2!l+A8chW4@8&P0MaS-#T2}ob#eD8P`}qbJ!xP+GNkGo zwbX56(^_HUChHibB}5ryy_!V=25FV)51vs!k*ISVW&8S-(GTxntLcM@dFl{mzF*dJ>Bfa9)gHwi!Hwq=u zbcnF4VXM6`8Qa`q#sJ$&BJ-R8fykA@ zyC-%cFX*8Oa2jRXBU)qH-!=LgERr*@M}OB-n{183an2|h;V-drMNR4F3xNR9Gl`DL z*Nmn$+9h%{)SSAcuF#jmL;OGir|r;-t~&5n%N~~L;;DMc{Yb5DI>155XzM_#2n}tn z=k&bGpqZgH`Whcc1Nbv54>Q&toA+^=L$x>ydQ6c}h9!riU#8!i3d3TeKvYuE=PEHA zAm?(?mhhq$Vpfc7j9{LeNb7{%@6zUawsV%d?uw7YZb+a@=B3d-M!q3&8y>UGqqg1^ z|7;=TPcVgSPrGn!`_jFO=U}sQvTZ{-BdI9(6V&g1klWO4rkSW)qnYjPEg!+Mhp$O6 zPu6ujtGu7vU;hNgp?6|i@sYB>`9KFZE!N;|$1f)5b$j)lw+h8=mc6o!6zq7r1aW%~ zo7#OcmyJPB^t2{ocwY#NgVNkb=cA~yPADsTcyvKjqb^oF)IVNR__Ii7I%v3(R> zA@4)K+bpgmS)DRclu#Tp{S+A)>KaE*%M`~{nr+kP*EjTVmJ-05 z{)jF^V*&1%pl17>FIK1E8`AN`N)f9r$U~rwC%h%NIV4$n(zL)Y~J~s3!unuba66QYH}o~ zDLD^`MZ(q*a&fcY%S^SWRSplbLzAAFKe+A?AuQF;gsfPTH^*r{zAnbHqjJ%HO;1zr z#(uPp;M(*f9ZGEnbO-uAORUPoj_a>(BNDDe=;CW@hYCh;L1nkuNHn0tT7t(wRX?ww zL+8lo<31SNdIWBY&9ycD=okazHi2pTG52Uf*s{27`T*Z_*i;LQCshtPi3T=?I<}bM zlVaoQ0+bvt9I6$JnuTO8!FF}ZOR2b)bxECG?$b+CiHk)1{lvFWKn81#iu`)rKo&NnQ z0HJF0ntGQc21MnVa0u#4ykFZh+LTthlka_B9mcfJ3i3YsLyj!X^LCqc6#I%KO23JV zd}K-zt^N(a6oDNeGnOQ|ktQO(ddL&+eYUyIc+A}pUW1B7`%jS%72h%SVnN)J2@vSp zgV3xcF`u0Ji@=ZF6{*I`I*KX}<4pk~UpkiK0wEp45#rTV(#Sqm_9xAhGR~>*$ka)QL&sFM^G)`G^IbIV$;`jHdM1*?Q-xva zIY9J9mHXG%VONoD{^9)parPeISnvP;ctmllD5N5!k|-`Rb?Thc=X-wF|N30l=W3jD-0%1O8qeorJrj+0-88ZA zlzUDgvsrx_uJB0D+s7xlFdv=1a>^W~3zz;`#_co!0Q}UYccCvXRU+8M7hRj9VHHPgdUQ-NA-|i4CzVEa~o@SW;@k*Ol3jU%mw1c zr#^iBAW7vNylYb(zT?W-QxZT_4ift{ONEG$Yw7BAloVzGUo_DFRFyGFQk_PGv$|XP z+y<|bYp>6xt3Pbp1>=Sdi-M|TG1}paLP502MmQprvqPTFq6H+Bt0YF!s%X{mZB_>H zNn!j+@+FkFlQf`!av&W07tsKhtbp%a0+?xLGl{ zDFwGr=2*CR&aGoFIUM~yQl4Cd|g9j)iLfd(kr8o@>>y|JV88yMh$NaIMu5 zj*)BM7;rm%qt$LMAP0LOd9b~a2+3g=&88!5u2or_QBU6%yLTlL?8`|K+kMr$4qHDX z2C5NEY#&SD4r2~dBe;EeeMS>KkXCdq2FLbEfQCH}HNJk|F_m_;1vU9W8*GbwS|$Az zR5){C`d)BO^zjRE$8mU{v6nYCsFE`zbor1UOSX(_R)O?gue z0P|h&Qk|9e6wl48msKoIZ^aNoe3wsycI2~4Sk#rL*wOuzjf9DXwC;v8liS9a>dHDC zuz6JW-9;vTUw=XZH21%vq@SrA97~@t*c-2xskZ(I_rFSHxdJ4wbe#M3s@ZJme3TI} zdbfQO0QhT{__nlgoOi*_t#VbhHtT*NCYie*KT&4nt0&#`SdYnxJWDC?mEQI`quPaU zx1OAldHw;7Cq}B2cvsZrs49hR@N=zMb#QqT@BGKNWzGhR!52I*RLYX(VweHEx(A2( zYa;vyTzTz~RYaM~1<-s0xRvfm+m0IAvwtxLq1zKRWM{ zUZs>zD!$<0Lvs2evO?2hyX?sDljty~O%f{CZX*GZWjJQ7W8z1(Jx})D+r=qWufRSN zLh!eJWxx?jKfJCJqo)t>4d>4me&BKiQ*V8Slt-mcpq^{M?fquLu-NWK4J3_s+zmfk z)7W%zW{DW&oY2%uPFwAqKkX?LSq;=@w^ zJMjlm<9lmbliAR{0Onp^-$8dGl|?jzKYk&n{RFCC%l))P=2LK_E4!Yo65VEm}*87DDs@^Nmya3=EUN{G;y8>r3Z zl1e8-R5s};jS>kkzpoI1+EO7=ojGfV2<<5Sa;$Y@EhChfX`mi`H%3uAIn2bg6ODE@ zCeQunWru&?04}jI=D*gt*I5=tOn-YR(lZ7PTpg-Vy%4R!wzY?zWzdRh^&Nx67C=fn z&x-Yyi3QIQyz2O8`Lzh|=?GRgkikXN19;-1&JoU@ohm9rjG|PZX5D5omN*47hL=Cg zJNlm9=XT8m@_HLUho6ZWlF?Khgv&gWy0|hOsd3pMj%#P=9#05FERU&OIj%cv(EgW7 z-d7dVGdANaFvXQ-#~K&AwKUk%J(83!s7DTi`LOp|!Jf+k!Yg!hY$NC6UZmJvd_HIK#_N#>F<9Z4$ein|_ODIbsBHcH#zK`A_c9F%a~a@h z)+wX83JI?v7-q|+cW!=g;?tX1GEud!0*p{NrY}0!bNO`ezxX}5STq(_hD11?jLRH6 z{Pj)7q&-olojv7Qr1Z^p%e*8WcCSuQfLG!jmz6~dKfy{$f*vTlN{A_1%HkHHtVv*o zemA_vE3fJAJZ8Zt%4s2n!+$JG*aG-gGb!~Z;wS@M>f0@0Z+(?+Z8&1ds0cRc#`V{h z9(S>3buqSXos$L!`vW&BZ=}?#Mr(bpHJW@+rM>IB=>o6JHV%a*YNY_HB5&9$``^XHJ??)Y*o0l5P)}sO;TD`gG zMdRgDcsZ_~osfKc@!X1#+SQ|XPEH73-CxzplT&+kG}}k;PUjH!BrAKrbm3XH5;e~* zhfUJImtg$6(1wLGyfFR#haV^3=1ZLCSSeo;bf1yl7Q0m-t`BHPVw~L6_VMElAL79t0!)73wL&D z*Kz`;wH~^jJ2H;(ruR+~xhZ|UQ!{CgaDE=Y(aIU6mbem_wvX^PKFa1pgOdF&qn&OB zA#!wDvMnx0_l3!8d{F43D47d*=Jid=#wE2e*5{7xHqeb0&eOW8&!?Me_Fk}J*}-Ys zY9D7mX&*ZN`rD5Zo-K<|XBY{6Xscs+|EW>8MC}L0p?top=gJkt8QtgX9xSIg1n9-q z&e<=ivWUtStmdM*&z0|=L=J-;rt-*2Irn@YQZBciK_gUsNz@=t9<#m|WJFZ)72srF zGBpdGv&?FQxh%B!sVdf;!UbKa1apM=mv3mRuyPEo#-MEw!3oJgw%TcYw1_l^UY!`Y zIpZ(0_sdvgq`4?4d)-8%tp#egr}^f_#8B!e4p7;bkxWyr6I$;#Pwon+ml4oCqmJO; z8me(^Sv0xTuIPYAo4N?`f5pji+db3=`1}MDSH63>>)a>Tdmmg<7_jQBa9)bX1-40! ztH`q-_*Z-o3h`CAMz8q9$ni}rjClrfp-%|_bx}R^AJ<&$l!q-KYo?*ILIaE4mf^aCR?pAXNth}Z4#6>VSULx)u6kaNZ?=t?G*OVIVO@4jtaSFE zhZ3EmPs>n~dYcf2(4E(qf_y&71sYilD?ZL`+pu+zwvnd2>|jt zhB({4FDj)ai3c9eNG~=Yo!@1bpyXA|KlkiX96h%7558q>^q6qX#!1*buI*J0(kg;E zP0F&N+NWe7Y~@8An#RiXl=KD&abxk7=anP3$fMsoCNvGP7Y#_4e!IT5iys)FgwLjV z_oD5-5RM$ks)KcoNJcPK2A1wzxbPgX3mGkT4GqT*+D*7+iuA-&`mtTy!R`n0NiYvr z%ZB10?+azimKQ{OMg|dNx+vg%sodZ+ZP&!;BpyoQPZK@=CkBbR`8AZ^X=8gzcB(~CEjjxk9`I@rWB;~u~FX`tG+niEzT zUi?$l9b_kTz4^dh)2Q%6>f^ou_|P$&X8dd7B}Nrpg+Nppv)K zZ;0wQ_|%$LN4*wo5-Kpbzh^O*ajgRTzQK?;M;~+T%GVOPehj(zTwiM4uKe6!=R`tk zrF1e)p^2?u6ybh?TIE`b0xaeIu^Kz+gEDqn;-I0iU4% z<@=FqCPCnIZO;E##Da#%)M;&=O`t~TFv!tj0Ds=zkaNwImRHR+03c^8Qygf)43*y)7Jw)ZycI$h`oa@XDNNu$J&Ecv~(sJ>>I!AxF;tziQ>O!F;9UiPT)p53Fm z;peRKcd4F5IXdG{bW??^Cpw32xm%ZaiG7>HMO)PPD8SR8wR6&wcOt<*b*+Y`pXpH6 z5ny(GlU{;7{|>^M=A{iGGw*J#lX<_OuVM@u9L~s4w#pm@J@`~3Q-8HvVlD_p(Pi;Q zP6q3J4st4w=%C88gaxSYu49w!nS{}-(FBSGcIu5rVi;@POiPM1iYsbH+To=HXBTJ+ zU=eY$lJUuhB{le#!tAe2lvIz=5BJxbRz^rzmmhKPgf^?u+GDKI_vO{SL&JbY>yezt zj&}#8;OFgfehX0D-$Y`Chib~kedvZxS90Ujym7Y2d4$jO*Sw zKh&N|i-}&@6z`j@gICqO_6@4)WH41vs0Qll)KQ{RE2FyUP}`{IHfr9Xt#%)-KZ0_K zLCZ07HmE00DwBJ~~|HnSzZ)X@BE5e$z0IRWo&vj~Q7cSbzO$$2N=sz%~&_{6{tu^_m zrh}$6*5-9lsKvAOe|R;|fplES+%13R*X}chY0$;OaEVVC>;)TjAw5qBcV1d&PVoeG zIG~AU=Jvv~^c|E#hv%0xfmRNnSx~ZIG;d&R0p73wdKP2y`1H@>>q?Y2hN+EVxNM(% zFD+xiF1(jJ)_Ky6p$`3Z@Bs&6w+gjspk=(*%|iOw-Evz~(RUwNux~fi!oW_E;~!VL z{YTeUqE1HUX8C4ME;}$e=Y!+{w07%y!!=)47H=Gn4^?_3!4S4Qr1tTsOaXvI<+ArZ zY4EA)f-_0V=5G8KxG;@goUn3&qSJ$Z9Xn@N;1GY{lFDJ64|fmQ1bKT#XEusZX(p53 zI<_3+IeWRfgwssx&=Bg58L~d~W3-p;TjpCvJ?o{l^+{3>sZ*V)aatwoUfpSl)$-N5 z0x}1!fWwW3W4Z_S)_kKr?Zfe;^e|%AsGVg+*tXb#iY*M+w#$udW^7!iQ?ZrZ#lCE* z%}oha<{7{|Y(;GzKi59E^re__;PKWN=Unu>68Wk}C0D4-dl^f>FInl!~@HN;>F=<>afD{A2S zmMXsyfIy6XxfthVs(yCAignM#c)v$F;LRuRrg6}OAdd*J@fm4PqcI+?=0F~EtkHe> z`IJnIS*gi#?C146pvqVe+VtpMOp^~V8}!#-z^JMbEt?+dFnNqN^3E?2aFsPo4d8>R@Z@_r6ldpz|3u0X%#<#_o$pfF6+ zs!nMOK0K`SWX2Mvqn{&%lePL z0bFLR$M+AR^lns8Z8s%klmL&0*kP&y~ljUSz#wW5$iMDw}I ziBMyg7K0T(oZjHngiZvy-&=8s>d_yADkE&p9oub6atU8MUfj7ABbP1c?Cj+*F=O#P zmM1?N!e7f=j$fFxia)bquPO15a~nFJ48>22{5Tt1aUMqOxb*1nV9Ypz46E+j9*O#; zHkdnHZQndEHQFv)IKxGyrZG412r!5qgj1bA7n-m?`7s=J3-%du9L`5cyL6t}NPodk zuBfw$%wPseF(*2~0?hhru5ve5)UONooT^aV$JiLXYoWW#e` z1W+rduFIamIou{&zR!%3);-%=QY9X-S8C5S=JUXSK)A$(6bZBhBnv?O(eTj}m=Se> zywmSFjvRnG=(Kq*iQ3FzFxGCn=>PtL^Q6Y3eTBmpy*Fp&udIu|A^ek(^^}WXNLl+9 zr&lG9K|(5$h=Sg)#IQRvT&%;E_s=;wyV1_j_n*3!yzFA*>_M4W&6!oHuS~|CH=qpe z1-9|RE*1*nK5gd{2}8+E=Vt#p(trNSi)0n?KH<6&KXo7$2a~GG0x=VjM)xpn%MdX= zA-mLj^w&C{k|XYgjfa=8zM&}&0jsYS0iD;Kp_|{!fVdutjXS-q_g+iW~t68R_bRzJyjXJ zBQ?OwraI#P192TfPv~$knKN7yT)%$CMK`+|r_)xvhbNDHzBTu|A3^IjeEc!=L&7Ii zH+?##kC93bD(Z!XiN%nQAT& z0DO+MhKM#9nS@K*zLD%0*dJDvjXpXzcjtOK#zslH!w|M?JrnPe-M0{~qO>D3-hTJ@ z^E;3T`qy_91NSCyoUS#=?OD&*B&nnuW9`J3TYIctc7EdyEhC7;MCsi^AvY zD@=45&}tZEr;jR*hIh8a<5vRPUX~RF|J>VhCXB>+h)Ja^rAmX&qHb;a`CJtOz|PK$ zj>Q*sIYTP&nA%eoi!1mg5(qdG&uI#lni)q5I&>{^NoZawwf6F_>+dhJ=O^wnI5pRh z|1o3ArcbCOraMRPlEGJX@l#8cECXA~Wt=KKM}0gRLFAMZK~$^PIP?ouAkg^IurE$e z7Tekt<3~4~ox7A=SMg7rPd4cm`XeoYq(OogZ-yrAXw(f##qHWj_B)POJ!_3^&APG?0NRGnZ27ii6AX-!g_wjWXO~fjifvq((>xB>48Od+Kd)Ss^Ny}yF~70jO@l+L z6Wzz137k|un;Nap*~pxBq_<@LkLAH8L(=JzP%}n4oeFmx4HByBoNIG1x&trNMh{U_i_EjoQRhbK9Vs7pspqFdmF&~8?HFfG(sc819RkC?-$6Dav zpnGz@wyT#^B)QNg)4e5=6^UG8)`f*Lw@&ktqifzFaX`?ms=tzwX3j_uO{|(7lV-&Ky!qQlh1PSD(L3oz&;n#9G~*B@GS6-K2gO|< z<3eqO=hs!Xn!6{!;+|9;H8)o;(=M}b9P%8Cy2Jx?Pbwau%XRPf`L92(Ls97d-kNcE}6$UbWSbDXB#@(})EAOp(O{Gsv=nndt^ zbxs@V^s-pfN~1)j64Yt7h275^piuYLlpOKyll~eNl4Bk@jS*QO(M6cuZhM&jQucMb#ItW8u_kApqmmVd`EKzuXA%-b} zw%OoblV0%YX5gHs$y*vRb_MG=432Sh4{a=NJ$o~~|dm&RpqqHy(& zg!a`+31wngodSp{P}SZp4l$%ICdKw^<8n-al&}ScShiatw>poE;H0gryAHIBs6}uX zP`)prHhPl8jOfQ~$}LLT5zf4#soB5$bc`u$*e|p$Z}T~{Gn5h)kj-U3GTGUiP`eDb z?TbMh=h;!U&pzl1(e)w=RJuC;uuHa@@Dnlptm;dx`71dvZ(>}z?AG3pEsa65l1@&f z#S9E&n{JShMg+!>M*Xi>!$v&z<$-lShQZ8YOzG)`d~151ApqAH-E>hqutT1th;`gc z#vHle<+!aFWKHY7K=ONGb6oDc_5P69I(wrrM8Mpx|jA_sJm;;OLnHJ74_-_^}^|F znxz)2EpFbFVH??8d18Epeuv4d0JivP*}TrZJ#O*mZv6qVp7w)Jl=@Dj?UX~Mz-gn} zs!_4xx|$LFwKdBa=7HpOu^0V>Eztucek5oWupQhX4o{cgQoO&;*7YVTuo@0FHT94} z-5GhH>$Zxt#1!2Xey@rwYm_I4!1TYc8>D2A5R=m0HwR8aK~#gJMq|pzSUR}J%&y+A zpZD&P;EiAE_FJ$S|9(bq>J}~jJfNfg*D%4X7_#bHXCFi}ojvbm@(O|W3qR_tx}GP( z)}Pz=!fYB~&b6}NruU2n)<`8^dpq{8Z{JgHkgWN#fOS*M>#`8fn-l}2QQ^2eo;+DQ zcz7o`ym>aovry4vYOn0)vXih%G$3e!AbEWzAhv*Hrr|!@mbaAI<}|s4i5|Ok=b&Jo zaAov(pJV=5c*+`sidq6hG8N+ia?uP>*qZFP7?iC zp0LG94Bvopg&?X0jF--arX#j1#~?q=qJC|aJMxd8b9B|V znhXUiLwdsF=BbZKMW~qzz0_pF~XcC23&M}#WZOykIIL5UbKDJAJKVsD{ zbvgIs688}@q(SCfOM$3XeBg&mP6(Q%@olL3gZOW`d)^4u>cUSmiM@uco?J^~n z%%oAbct7z{_6zt?VxuKimvTx zSvsCSblmNQITTJqaRN6xg6>cM_ksnQgv5E-^S3%khxg{|2F@u&!GtlTsTb3jC& zoUjEWvDZZPWd+W3Rq}MFCy7sE#a-9Rk@oaS?$<~WO(haNusfXoek%(1Lc(JO>TB)z zw@TVlkl4q=Uzx<>Z})rAGkOb0*-e1PT@B|D^Ysa-VsiY?n6-dyO*^5U`rSver@qE_ z+vO0%3Uon+fo`PfXwpwD15gSNd2a8-}!pB!Ms)!2)ITU%kS+?;FZWoKr^3XI`IkfhR8Rogh zn`P?&S#5rpe*=X%B9;y!K~m{-;fP|pI=@!vBqH4-79IwWXn_vn+$Q_Sr{(Gx$Xr)I z_N*It=|&Rg9^?N*x$&zW19Gtko2W>C-;D3_{nd0-ORXW@$;c2RJcHj_h6Sq~U!I&| zL|OZ(+PTiDmw;O$>eZTM{wf>xGv98Bl9?!%7R#*9S)mdZJ`PFz%Mn}?%5R0~eHw?7 zV>F`oMLykcMi!F%1f+9Tj4bn&1)>W=g-hbiMkeCyKU7-1zbQ6=Po@b{3kSQhm2MdL#*3lORjJ!QcTN{|Sl1Cd896kn} zT?*Vn8L&2M>!H2d3>g#9hV{;&sf|INY5{SH&7>8An{rVIy_PvJZ?V#r`{aNJggu8T zbxg~W>l}SAS#G$f8bAn{!l$uEAo}8&jZjTwqtK*ZPt;ySg!UL1eG(fYFC*ggGS~9A z#orKse&qDOA`$+zC)f~G8nog^f~hncinNnrCqCq7d-qZ@h(6>2SwJ15h}wAyQ3pT% zTxafEIHl6yuGOm0f<%k!zK>|gt}m2B$hSc(ihiMkY)+)n7^uWJ#8qfw+E=;ibp~BL zXuXOKnMxc`VSwpxK-%vv_nM}l$Uj2=0YetjW6b{8)cpO8Goi%|>iF?->p9dq?Fzja z9e_7VxXc$)D?swPzu=nNFBFmiBNU%Qb<$)Qg?j}qJyf<$g>Y_-Izo;G>7G?GJVxyk zCQ5b;)IvVUSYO;0UmBs7EjSx%;}I|BnQJb7`cAqsPFIRJE~+dbLzLD{IeL|f+D0i@ ze-^t}6Y~i=N0pFhT&R6>9=H7K-TvIHKmNkE9Oo(f=;yUl6B4|3GV^S-F9GQAmKS+| zj`vp@=H(FY=Dz#yko(D|fPeUyqd3`E043H^t+YUVB!Jr^5lrx?U2O^yQW}0$7DlS> zEfb%vcv9XP+;EuO)oV<`L(tb3pmn>kY?m}&I}RZILt}#~e(U;RjSl3yEjxGTS~`_k zH706*H6H)?u)lum>kkKfFyHrwc(+e(>j(fs9hj+AYJ|Yz_BA30euk(VtU1x?#9-LkMi<7P=jO6>xv+>V7{@$Y0zgA9L1kUxJA`4w?0Z6V?N8 zUuCsr2`7oHaz#QX_T6okj2J3JOjHX(o7OX5GZ9mveFpz=sz*|K0#Km?VVt5}X-0tZK^^n9YD2@Q@4x2NVk8SU#);~mcLYQlHa+qC z>|YS_izNKxvS3QU?*Hg)_v^{LmSM~$@94G`3_n0pUL(hx;RfKUu6LzOD~nMF9mX=5 zGajOp^d8`8FU${#V3;c}^U8J!FO@Q@F1fT>J4)Zs8V5EJMLVGR7d*Fb@U#;KE@jZZ zPN>wr18ejEUbP(wO9Pp`7O-u=V3U}-V0TVt`aW?R+fMp_cTm5!8GdCeiud_ajK6tm zOy1P0KbuE7tmgprO^D!=WzzWtJiAFIO5DJ-gTQl!E?%RQw(rmw39W(;K~aVX>h|76 zSjNq3*Ni7_G^Bb7GTV1mKmC3fRPeO}>LfaTmJOfaJ8#$I4O!y53hy_@c*@8;r(XB! z(*2tjtoV=5%5(~rahDUa(!UN6xp_ngJSq@Vc>;uk1rFxCOSl0nDONF@Vg^kl4_+JH zfAVJSd6u6r5)p)AU`G^`9G=D!a;c0^#rQc)s zaJEz(aDMiBzhm|c#)@qKJw)r`U0f5fAD5&TDdGnnjCf-IW30)~b^DKN#tLNrXj*Z6iq@uKAU%-bEG|e2>`kr-d z1Up5i@O7NuDR_pG%)aJEplNdx!%oc%Gjf4KQHAdh)c9ZZ?)UW~w+FX!hsNdcsg-|i zR~ruaG`KRQ+L5k9j^^f*Auju5XD?VqPfnGETNY~E9v|%85>GHamj;PDbgmFIRSZ!op^G{%bfzPj-_WtzjrrzT|y?nn8Ok^bBtjcH{bMw*=d- z$RfDhWqhbspNZI3@+J^_->UI-!}xiA+O;OAQ^#IdyR#1*+5B zzpjPPvg!@P#vcH|=kiy7MfUM85`zNf6iK7Yp%u8Sq z@AJZJT+pEE-^5Na-jffjJA?^(w{ zJ*IWf!KZ@T)$dq90xQr^>_kS#jO)XMn zlrE)iemO%rzAQal=(4VzE4B$^4E!)gY8YLYt&QueRWZQPCc?)9SFV9um_JA1yFn0n;JW+br3C%Ns~wQJvk<(2$I zwBCs95}q~77+VrD+XECA2_IBi3p@}iD0chmtXnk*(A;%h=&FhEtf}!s|Gubxt(UNs zs0;!c0>4wBq(tLi!f;Kt$sKtd4S?J$^>*Wa0*M<(>|kRgepdEN+ev2I=99CH;Uim* zwo4bH`-1e7J`L)iPVkx>5Fin-`TnE(p2CAbg1^!QA`eZ%-1$XRxHkRNCVE){D}o_L_bY3+ecZ(4)#( z5rn*Ma{;#U#>4X>e>91ywFVMCYvW7 zM0}0tk33&x=zVGB+tvbKyxkU=|R>ElI=m@y2s8E0pGrzEDIU1)J_bE4ojCO*-S5MGV7(&7-0@M zM2x?kCO90MkHP1j!yLhy(aozFsqBA(d&c-58?@h6xz`5Bta&@Qe7|S&DDE+W`dAY| z4CGRMx2NbTU^Y?4Yb%>3h)IhCi*g;-8u0FI@rl`=9GN>Y+HD&D7FdHGqhkW6kQ%?r zp#jLts}at}QB~^>jmCOZU+SJ;K{>=5XV-fBG)O*1{&O|S`bG|oyYiJwFMU))V5P{r zLCFa>uqk95Mx^BF{$)JOUP2T=5Y3HHRd798cTD)dt{AzteAFLKg5P09U#|ktWIZUu zNd>)IMI{yGW7ZDHH^j*m!?p9K%@`3olJKgS^7xyZ>qz#M3y_f5+&McRXv0_r3%=jD#{vBLp*(5saA+?JeS&C?*agql#u$ylIP=}{?r1r`wxPlBc!Dz*+B;Zxg{l717WnE zLwnOF$=C#R&y{Q97UODZ#$c!Rh3QGiMS&Nu4nSmZpwPud|EtITebwoa7KD*Ed+MQ= z#gm~O#J~jKs%|>eNK|3lnJ-Il4=nRiWKF*Urz=pv&FYM1vegKc`;cskZ0t)5#08d# z__%T|(o*Nwdomz=7vkyUDxLqfhz#X;0; zkUY$EY4e(?TsB?Dj)er%JG_+cVBp_`T*HO&X1-0v7pErV{r0K<^k81kaqkbzn#ypM z<3CHLF<9br(6#P8Zb0RY1VC!Xvdk`H96Wh45#;WA5BF?3VCk$2ac1pggm4n}{V08F z=q7d!E3FcJm94guW1UN{Y%&Izen999bN70p7DsRL9PPnd`Vn-!l2)=DR$?Gr`g6dL z5;vnRTF-|KTyy5P(gP=%{UvDY2oqzgDO2(J0<`-CJC8gUkd^<_p7FmQ%1aw;FmH_3 zX~cM8?Y)ck6#l|11g9xsp33^QDmZ(UO%F;8j6k0_31BDj!9 zIpoN?XFbc`DY8FZE)NK^Fq|+~_B*qXRDfH{60J4ek=3YjYT%xJmiyWs0ObYxa|^7r zHl#x+6WNt#FhEP~ZUyd>L`L^=O)Kj=PC7|)e{uzCWi-d|x?=IvArACLv%+EXG2BlL zIOR-Gd0<>++Ugg1i;m!@xIwS@td~<*BN1fSeqiWH$3@rg5%nVQ#&Ed;E8{F@unv)J zGPAvMILb}#L4|PN|G7FMyUYPyr>ziv|9-=UA45R@^mO0#(=oTo_xE*Iw0n5wf4su)XL*Fcz8IuhX!mQE@v>qd#EE2J!+U0(_PaYClT zJ469d=e*jHig5&mKHU$SC4!+(uLF_$UiYd(O{3)1m2OpEI9h5?AXo4p+O%ZI0vd=n ztn)A|*ndmDlKv!w6= zSR~rDY%9vWtUkI*Lu0FGoT;qG;bL|a?r!@_Qz zcu~lT!Mz2l9$9qWJ!ReZ@8h zkm?;Y)z>Zi+2?LXY$*2@_Z(8xN(7V3)f|X1My`~ZtBk& z=sC9{xTHe*%&djRq`QxSD^C5RevIv4Z(}V%tJ5=!?$U<)RBVLzMVvjRw!sMrpW?~R zPmu4Ze>a!kJ@LU!kcrTyAED@135b2HR#&Y@!83hNM8`oyTPr2f3SkBAE{lc z*v#3h_a_yf=?3U>drZvZ>jf-_RmNXPfFD#^Ws4099VX>Q2{eWmH0x^<5&KP9--r>; zO;{_w=W++*P;Og}qnwInS4H?4upO)0c;N3zUbyaXMuJFPyk~X;y2hZm%|1fJru0ONT@lN;G*z;dMG~%!~$Dk** zrb}n$tO)khd|w_R*!=$j4Xz^n*ZUZS)~OW|CK_UvF-6Q;<8ogmDJj`C{`wS7?>qFL zc&xMvJ|&fkCZlrsVuQm?Ct98}3fez*+i!%XMupe=GMwLuIA=Og!X+LFb`mTd*aDZa zD1U-lx(CTYiP;mFR}-gOi+R`Qm1F$->yw{Qtw%IJmOrRY03XnZppB#+^$4ji5a^gd z)^NAk6pHEIqV9l;ZLPtW{%ttqg8y~Zh<5I|5LkegJ{B8}ZUvco*ozpyvrXru|2EWa z*j{E}lf8Q7L_5t0IH_)6h71->n?uB!+0oVU@2d(mJMn-$6^{igS>}NY{ z2-ZsKkh}|T_$)}%7Hu{Pl$QI(g~+iu;o^Se%Lb{|yvh~sCJdFn^M`v|$38(g*#HRI z?=a5?sp|9GEpFL3svwgEwCnqr)UyODZq$4tq!Hyi_6=@=2Y8^<_7`_rq*%9ZCjG#N z@CJ-DKRLXk&{bv6N5M5YxIrACXx|aGo2P23%BL$MhLHxSLQb*&S0gyJ9Zm`1##R)< zS%(*~bB-6FzdGpcD`#oeoPt672G6vM^XM4l=bf#!aluNp#E~zW71Cu_bpsNCg+Px~>PlJReoVWh(=$2vDol zE107Uk8Zy1ZXQ;JY{aHWN~6eNf?$5mtaAj%aUW}J&C0VUx{l|!ufDd?aGSu$qT{Xk zNGa?=`8@kjr-dI2oxUH0$C1+V&_t`m(4B~x_wLQdp7U~QUVv~jnZ-~I$bAp1|NV>p z=K;8r2{;b3?ZSl&Zpm`!T{IMP3|1}|h{`O$5%)Dw(p|Q;A!WRjs>_FoY^0S-!$4CuN^uDIF&MJ2%vTecFgRc|dsDg}jca z0P^nYcV*Mwc6TgXZAXvOB^}(6bQ^;+?1y@Wmn4mKSE`)t)N-a~ylLDVmmj7L~k;Q&>uG;e@h9+}f>^-Q8jozcr?mQ(S z@!dgBBFd;)Dy=y857FqA$!^%>b%K)a*jZjk0#jQbk*1uBOi9azK7Qcan>i>>F{kF; z=mTudMg+FSZ0|9YlnviQbhD(cCfST)r+6>Z)AHa5zA{|KNHsuV zYYy$6f_bLY?);Y-QPp+G-}s=5VpPx9m(&L*=s&Sp<$rl|!4gWPybHi6 z+yN;zB2Vwh?Tje&SN8}Lp>gROMnuxNeP+GceJ8*s!saVxNFGKgaCGFfuc+WGUztylM((hxUmmYK%}T)_qS<=K!cu! z?J2Q>571hAE z^UnjNt3YXOYo#ruSdq>&#L!^K!KW12iDoD{BJM>-ZofB)Nmp?nLL<+Y7^Du8UJH;y zSmn&1cVJ>txvg_5f)b#E8OGQ$6Q@3mJ9(w$lm{|5FT~}hOw!iNj1qK9+-^9?dQcDP z=Bt;pl|)Z5XMCGZtm#}L!HmtmouTm<<+=O+y`52rtOFo*uzg?oT=H7Ha^{m>=pL)5 zu$(r00Xcn(IuPNyfc@-y8yD28ZeE8U+{;gh4jTg|^I5|l>uDGfZ+8Sa(WOBsI?{l- z(mf!CO-FA*WWd$nid!odnE2k_Y|WtsD8*&&6J=A(@&1-(i~%T$8hVdvEfu1O_g`FP zod=ni^gF&7_1q3Ez@9mPJJ`NpBp-?7B<=930{;&BtSjc*JOM#7HXDuzHZRQ`Q@^~Y z==)HkKR#+PtzhB0Qm&YwaKov;ze+R+%+$;02yDgXNDr1FmBf4uX5-vKuFky-Zq~)y zr+Jl7ip?_gYck2?f!4MvVCIkAK{E+l@OxUpd6>lCRW(^ted@L(MsJRB&fZLWa~x5z zBte2mFNwS_O!Gmr#{%rTks%V7)Tc{q_pKAd>3fr(TV{;Ii;x1GYLnTx$}4u$%I$#K z=}&LL91ar9la#ckPmih7AcF)vg90xP|IQ<7&M5H_{|-t0qZ0r9w{jN5tsK|A^}8qd z^G>^eo5ktFrYP)ZO4L^ z7X+i?bN%QQZR|1{=^mNT62GgDVj)~kV#~qTdp7ps9~GzaUva29MVHV|yBM1n9lguZ z%*;$9YXG%IJ@#zd%X?izI5tZ^=b&}ZCfB%?Oz#*xgC?1*-0$|tyvnwaPQtM)x$A+UkmE$S^U9>^!t-fqpu*~kiPZHsosTcCOvII zk1V2+dRfFDZ>{|x0Qymh|5Z^hjh~>!5esuYGR6_F{s4@P_^yqUGM9u?Rd25;1RKI_ zW0kNrd$XB$1;KSZCcY8bW_NRT`XwIe%HHsu=35Z#I1dd`}XZ?I@XYXysxPq z!L$KmCy$+qn1?XmT!@F)b>2RnuaTGw%s}Z-kxC zrcB20B#70f4%(hr%W8t9s+Y(Hs1y>rdW+*TXm+#9?ns&+PH%S5)yVpc#w|c_<%wS8 zP7#Hia+w=M^>xG*nMNjU_k6g2_wp`7zwu>2oKk^2NzW$fES88Wc)I7|m*gdhwr{r+ z9YndT{T2(H=T0MG7Cbjq{_DY~dEF)y!N9GvbACY<#Q}1$ryBX3JC|^a8!HBcWOy9a zTk;VC`0bZeZ!{n-TN-jMe*{T41Zll4h5SUzt2y6#G?+dBl!_zgQ!;@f@-9g;AibE| zi+pDnXl{G3+|M=K&S9S_MiGZIq6%do;|PwpdN9@wZUpHr-bua@u3r9IJtMpu`huJexCihW+`-v)<~Et>00xLD5ig2 zTW5EpG_iH6@BB4lQON7guvdWz&RY?GfjUAezr-GUgsU-;N-rt=0O70k=VHsN6&S| zsh+gd7&Di|?TNDSVylC2zf6|3xXJCHMtbmg@JFyQEm?A^MSh23!1-o->+RDNwWwfQVUSz*RoH599lGm3Z%Ro)cHy-+<(iOF=?vvFdgtIgU$y|qV_ky)+*FN6>RU+qXb@M}A*zg$_xiM87NA3Dnf_3N}dm$P2dhBxp zA#vyj8YHS0a&jKZd-be$(M491s>J9SUs6p=3~D3dP{SgPKg3h{5Jpd}MIE^A6=Wr1 z2;V>9|5g;ryC%7iIJCNUFx#EGe0fgErloGa;0g&LueU%@HFy=^6YGe9M0Y9pahhQ+ zct78{x#E1Ua~0)JPQ|~!1EwQbNUvS(_j8l3Ws1-7G-ME7*EE4h-?N&QwQDlNIdOPc z)bAq^s`;^v6{ZdjX*n<*2v!H*xzo*q&7z*yf8H_`h2TYR z93*yZ$VTGwXMj#lO;_}}0m~&{^Y=H+iZRH|Vs1iStvb>BW}micECW_5irACn`t8

    DN6nic@F>BLPaFPBZKe2t20v%P5#d)Tka5$=WAbahAkHnDb0+0Q#cF`^Q&ZW z;N81oP{IL5yjcQJezpE?E$do2qUU?>m_HVz_2d9nc@i-Hiv(wE>WPM@K zcS0MYv(5y=ZYc6`P>319tkbe@$|C1b zJHMX@<{h8R_uMQvNnK0NwW+9!u?ZEX)%T@cID zmdM~a8~LPg?~6RNKx7(WG-SuejtlE1>v_n-MxzdA?>~$ zh_WOJ$4?-e&D?Tx^AC5H@NlPMrp`4#zrFwc@B-WMZ5Q*HO--!hSGy@^WfjkCwSC8q zJG24k~`Cg@Rnnl2!&t1Ze5kKO2U5U-b#-K2;$n(&zCQXMD3EG5+%EGrP3Qr zUfT5N;m~Dkq|3EvnC3%5TY7M?vqNXKJ6LnOk8N9%b5A!)z6-v6TZjmOs$=(8h2yVw z=B`i)c-KRN)1aMzl7>HVKaT9p0iJ>}LLV(K9@Q z^Z%pCVLPjc zJ%9B?^?oGl1Fm8A!j*i3iTzP=@!1*kQ@hrXQzLO6lS#%nVzaJ+O(`Msk=0iU39T{g z_K#X7;UHb4aDJJs!hpGm*E|8+iIdH!?1+ z0_eP*aC{D)NYZc%=2Y3?IH}(poIM9Y0L!5QU4Q53dxs|~d!duQ3MhQ0iKw&aQR+9+ zG(G*1mm4I4d9LpQ!4X|ANS{pVb^U-N>1MGsw+Zg&Z$Qr8>8iHQ8r_MRSvyz#=ry3&sz+GlPY<9vx z1bjajp6tCW_Z3;uD^N7uX?>j9bpp8CXHe4td>>w@UA{wsJ&E7hfPwZw`XhYq{=0f1 zP`L?SWv888(%0sDg=Vw!xe}82qMXEEntI_|DJ5?44Jm8WH=jPrbbWc^kuu(Mmo7=( z&5`?m*b^k+W*P7CS5t+xn!FJpjL1>jPmy$mKxX&}h^tLu5NOJ?d%tVpM*FCq*8EoK zGdL1KC0v+MLFly7z0Tn6-?w6>Bo8PPOOHjOa9)pom`~c{Z;)Z7ANuxrW5u&hkWTCF zNYlTEuw`D5BmbS3ui>c?S1>Cvh)Flk283`A4X#%pboghSQHgBi7ST%t{wC z$kDdKD7mN4pOY!)>~BPQEo#lHpiGOvG?LAW!vOF;13I=$R<=3Z9X&^c$K-@vm5P*8 zN^UdvYIu+L-_uu-Xp8R!vch`ek$vtGqG>+-4HUwigV%k1`3V%)TpF3r#`$HiO7%UN z+vGnEwdQ`)E1_)nX5BHpi^y}QT&6qQ9{f;H{^PFw{kH|I03F6XciozL=Fp`fUVCTz zws&;g@xa*S_WVV>H6a4u51@})8RLNQ)^6nn{qahtz5uA^&jpYpXI3OgadQ(L}C#vaNi z&F#SBsN1&}bm%?4!Y6ilS07yv+eyZt0yO8VoP&g#2OnPtrOw#w>hJ5pI5?V$MC4;` zM{8&|2K-ihlM&ASlS%cj{_Fb#67`_O74GDzF$z;aQ;5_)Iyamrj7fztY4EU-ABl4+< z*ijV+%M^IRzC!30G*HgXmICz&g49fzdg_yR1gy90q8En<(SPG{VY#`>e1n2k1H-#k zR3x8lmg{uQ(}f{u+A7YU(3s6!p?O!Uq!RxykbWV;$nWp%{C&*xk zRs5)jBQEmw2MpcX>5PHph5qN6-O2buyS4(lE5kKy?*Z#ACr|*h?@VM?7 z4-0!f2u+y4kwDw+1(ERHXgYzId2wRn6|xEw#xNy9_-PeeNonc2yIE>k{~v2#9@lf$ zzE6rmWQ|Cnh0=nORLT-U3nfa6_En|$q`j1oB_btlmiAR?-)*f*Mf*yNv}#qUzSsG9 zX3Wep^NiQ;^?Ux9CsUL6=e*Ck&wXF_bzL_hd=7#$JZJfO8jR@{%A-s@4gPr3+0M;> z)|O?zeU#r}y+7_he2Pri{`IX`BSz(rP+!;n1m}QO3ZsPa>rn_%Je0qE_>%qFwHMP- zEs@@V)7RM5f_fKI{EQYM#5k4joWsoCFm6aJ6()ve=6; zM3nomT>fS=JaZxF!Gq0ZyC9sc_t$h^Pzt@Pg?^nKRZM=8Y=FKX=%cR`{~d=DLQZ#Nm@a;ISu$GAV1&g0{YMm~_kkWNK^cA~ndG!!`*^3B zo0>+ep_8}`Cn4fQ)cu1xv@Z`3?`vJqO7(e;9XnQP@fno7qXps$y^sgoLl@e&_5Jav zf^H`^yPjuKvM%Q?skOjLMBwYUs;)2GTR(q#xKflRWKQ4LuU{)b&b!om$7+83@!y~I zAGTq5F#6{6FFpIC*%HOAo=gKB2M*@%%VKJc36p0gA${h-gbW^LJ6y~OXYy!NKngBS zhSe2?p~5(I^wI+U+enHJBIFhIO4jTkT3zBDr?09ya%xUr9ohiwwrVsVh{b6+&v@PY z_s68CF<&Z!gPVJvG0Tl*uV?^Ec%#s)(Q^mY@Amum@7V)I6%$YAF0rWYcAHzzTFsY{ z|48!RK9LmrT9^@Bd3j8i@yA6LK8wwz$i`VJm)4#!1;v5_v0U%8KQfOxg(nS(bYrXm zs6AZoW3~D}#)Kadm>YK5(J?#GHp89A4$Ysvy{HWseZ3{;TDnb-aLtPGjg>W@`x$kh zqNv{#7w$yzB>S_cleqX~PgFMHAqC;8Z!N8g3&e7EZ8 zLYNn7eem@#G16&q46Xyx*p5VS$4etRoBU^~Um~O0zz(|~j2VJX})ht{ZaLZ`f@!8=fYR9mct=*Ic->0pENQVT2xhpUd zq76+S{iCd!y(89FmG6hG9{|W%gwYzGXug86SqvCwvBE0)&$9doi+6FUS?cJnS}TA5 zFLC?7|CmR7H+SBellUWFpmn))i3WPNo5ckn$!%-hPbw4Cu+lGk!DYD*Bw94XN=d_7 z$pU`7!41$iak@ip6~tg-@_MwSPiSD-9mjks~^3$hJX-#_p%ibk<##iF|(((8#=D^Q>IA;!BTrPSA0?g{??-bLr zfh7F^Tl9oTy!_>g3ouo8D!=5GM6 z%k3q=akpLZxJJcsYxr(sEH-?0t-6xYwd8#9nBsZF32mDRniUKwnwVZR2obv|bBxQO zgOwH&=s6x-Eo^*m$PU(aUU)`L=va7cY-~#Vu_jW(q5c)JFYm!j;o9e&=oBt=P+P1V zkESv?RJ92gQ`LF3i8rU~x}I8HC`$&x4}4fUe1J|Okc81QFZ!Mrto(+z+lCn(7xug> znw~IP`25|9cirD`CAPzgk8|ZCk(G3Vb05B2q1*AV=MtH_TfL|lHSTOsW)~AX4Zw%l zX9TE_8U*#rp7C#4JDawMc|fRP_nF*TOE z{g#%NhkKr!a2fFnso&}67>C2RP5aeV=eg;{)n8{;s%}=Pj*(?u`)CmG*F7;tov{Ju{x2^Lhknd!;721mO=udC-i~eKRq3b)_^Njkcf7n9Q8B zj=9;@*>2p?l-eZy@7?={PoD};uhQ`!&D3W!Dk>_EKR6u`iLuAPwBD;1v|6!^vz@tH zN0BNO04VM3i9R1cMea2q*vd$b^k@cH+=x!BxaIX2nMD%OL}>8K`l@X98&5*R)-!DB zRs@8_xV*(8*l%4T=*tgV&o4r>r@%k=5O_v&gc;v39G{)#5{u}oUo7HOePX8^Mhzqjxm$jM;_Q>*Q6?N$#t z{U)Shi)!u>chpRmJ)T-fb5>6xOZ9pF{5dttRFvBH&i18RR~7m?Lz@|&zgvdwdgWE#$y`v4@?8*4?6Pmjbod7nD`H8_24yl_D_ zFw?@~VkS%l;QK{+sF9gFo2J3|x^c0Jlhm=E-5D8~ZuKWVA+?Y!*Kk z{;JHlI+hQ|;W!4fb&g%1_u=l{yRxsx8XDA?&t&y|F1wxrmEIvJx%cyCRUV#S5+tb! z8lz5j7kx^1HI!npM>rjvYI~b=G&L|St1@fd5VcH7@^eD3XG(a>)ZAx8UeXr&(9El+ zr)O#64Np(zsjzDA7cX8cm8^WY{%|wXvR6lL6huH|c6t#jk4=`f)Mp({b0rJ$>5WUT zO8+$#|MMw#3z{`n>(;!L@zDwlk9y?#T8SFPdsYyOCo&5!q;h+ixT3bUb`R@~CI}_i zX>2QtNLPa}A6Cora&vQXp19ZpV5FEVw2t!r}MmYL? zdTsN&_r^bl&KjcY)K^HSo-cYRENR401`^gGZ!4 zxPmdoKu_<1M{!-`2P3|uxB#vbkE2e~Zy2hV@k$(T)@NfBH<`7KpTG1h8~7Es!K5h! zwtDi>vkf*nF}72XEUdotv2}Fbx{FfKJw0|V7l&%S^x4`E4@WxO&`qH=U9?as4KZM` z?NoVabr2%veAz>iG94fQZ=d`uyF?RAp39>KIy3Z!Cmdqx%svd)#hw_&MB?_KysqC7 zlRww9e~6q{&k%swen4dx@-?O|8r5rxbNWI~BmebZ;k>c&>c~c>`84L4U)|ARJjSxa zbW@r5&<#T=Ldg(Tj5ADiXe+q04Fa`9^F~RhPa}idb8OTsll>Qk8w;B=?o~}f<9am` zzVD>$wT(X1cn);u(BnBfvRrb{DOQli|GUU8(!uoKb)l%_;{vb(Aw&FXC|G~_-2`!7~9PS$W(fXGk_TArS{twi;jRftz-D-F;8omJVN zLj${l8UUisIaEmf)%@@1nULn7&&V<}&l<%`m#>5q?Y1t^h(V;tN3^vc+XG$DxLhy% zKDL!|_S(tao43l^e&etlc5OX=J6jgIPp)Uro^eh@Du&%^fb6qWAzFTp^ygC0?7WHG z>I0w0t;|9?36lV!$kgQ%F8ebd<7~${#*F7;81U_kY%l)E%&i zm~y1;H>IuzQ!EY34RJ)n;z6)mRrS5wEt1Zt)4L@&E7yR$8*9bTJhH^2p1!_BUj3M;{XUag&=^Jd`ic(w2p6+bwUlX>#eh7_LcFe zo}n9dzYKiio~R+3nj8==#oyKbdrtQswzCxb3*tFgGut4IniI_|+XN^E9!pfiWho^H5u15sldRmTSS!*U^c%X!Gf262}h zLDXtTLoq%?e%IHdQs&2N!5(?A#^k~@&PCZS9o|3P-hco8;^-p31JRLQQJaAt*l~zw zQZk_Nle4t4I%0Yk%{zpA%M48$wi)$1Husy7k$yb>fF65hrZ^Rh;bM^^-OGB15zm%e z9yhZ~DvdQYdx*8t-W`2)2$)ZUgLC_g9!`rtt1P;xx<2kAIuU;U7phduI-j;CqT%#f zV5mwiE9r=w+lK4z%}nd!j-zPUxsrpV}q`)?l+w;AFnq)FbLcX zVA8BJ34NK(Jdy7>%RXJO)ebwc6G}vl$7MA&r@AnWqyAh%LV_+h=j+Ns9)o*;VS_d(=k2I{m!DJ(VQbVa89&?%27&utjDLt8O*6^L&aXK%eg*`6V^%_xuEN z%C}{J0Zzoan1z)c6ta)y>q_?tQ9Zoo^r3AlB{G(!A-mdb;?h8{11hRjZ!{cGp~bLB1ziV@>xb!k94Y z?Cr0%?&}#o)txyadbF$CEqfgymcZ^KxMaK^sh{K2$VoA|**?4NpP9fI>GMc|dQ?xf zwO(!4_+u06YPi3(GF$b&KP~29|0S&>wyXacG5a~&7nqrym{9ppWO!>|Y?n=JehJ%K zX0a&;rSGCQKYT|Wu?h6|f&BMxx#_*f>Qc9eIjjrLsVp+Km96Mb&+$v4Of)>oY<93c z`=L2(+PEouM^(2C>MU%Apq$S`tDJ;1dtev3k%581EG(pK&B*u@Nk4(Oo5j2v6sjf% zDKRhcKyRPMMKuaLOk*^sTt?`Z3V9ofUe=DP&bziH4Z=}l?Y*j31t=5K$83T;p7ziC zTsKvY1Edq1pM9~i`l;<%%j)k_6Q%e)WqX^4tg444lpGf4Q$Gc(+V{%u(H#aO*_rCy z18qs?R45Zo(l-6ApC>aX9OKBjQjWVh(l0pSU#VW%sXp<&So7`O>Nm=iz)XQSx`o48 zHsk{g_urZj5we!mG}zfBl4v(QQFmOEJIzF|)@BmF*kqteuDP=^XGMm|#Mp5M_1?IS zUK1VpCLe*QZ+BTuzP^?l;+W95kr6sR%Ym(s?X6Gsn|24D=hL!MR;#gMbw;BHn-#6A zi+Ja^cKc;Iob4&>7Q=^j2#C{h((K86t6nQ?P2CBTUKt4{eNA=a_>3-dj6nl^ zJg>E0`xN;(tyqVP+MQ?hW1<_paiXe9eHy%3t;VeN-v-6?i`$%4Q*J7|JJt?LR*+U; z=8oiqp*Dx{GiA|fb|oh$_^+z1o3aJ^dq*x?*liVk(c2VwK(D{EjC=m{BFTaMc@wG1 zly5HF^G7A+vK+itERtW|khLkUhkL$TeXnG7mcz0}AIX;bXY*h5R(Vja)aQ(Mtbr2i zhSD{U`}edK^zJ+#>bZ>9KxWiKg=@Hneq!Ff)W#)BRSI68LOm50q;#{*!ST`ezka1& z_^IBCP2d}-?>oX`&)-C!Qa>8Mjg@X+sslLO9dBGQ{H$KJd=io*!P&@&LI`?khCWdC@!S zXJX!zeXXyTZJ<|mb}Pk1=0&ewkd|A0%vt)B(-}-=DU`1U-&`y*l0@-MW_&h&y%hn^ zy2qJ+{A?9JepLO(kH+~|qX>^_#NU_kZF}N@)W$l03%lAfZTyRR@|z-hN?2Mc*FWuT zr*z-_;3Gz##b{VR;_f0Dw28?q&Y!GgOk+fYS?|&w>pYdq^{iTHMUIb=DaSVNpXt7W zhuG|0FP~xPd!9J(YG){$r9`#&YVhRG3|TLGbwMd@k-J64lNSL^E`8xbsaY?>c2*?u$XBgtr1m9k9+bZVmj{&&{&G7o9c-&%@3t(z3WFj@9kPVH3njqx9^-* zO2)bqVUrB*7L%AGt-E_%yWsYEGs)FYAM;ih_1b1<1GDE}5zLTsQfbJk-bXL2nvOAJ zXQUC5FB1jnW+mRZU97E??oWHM1ec4jW=i<^jSGNfKPg83D)I|? z#K^n&n2J}hTZQ}=KNp+)$xS=8@$2Kv1o9G6y7_L+j9_QhL8xlv1G>q60=7q}K8bz5 zTBtgCnV>;snAdn?o9!T0rDPYvz{GY7Tbw(xqg#;I97-Mg`C*N{#8bD>ixKfa4Mg$=gg$1c~C z?Br}PJ4+Vg5C67`U$-h+eYl_PRu1R=k<(FIGA#HD4yQIwn6fu$j9UHIf|H=3i{C^3 zZp%Qjyc9eZc6aNjgx%=XX|2%nm7eyo)DTkaSkd1rj|VPBVbV)ja%t`NPnT3*n486Y z!sMx~U8Hx7fJv8Rd)tH!*EiKT4T+)c_#n?w6?U_c4QW!T^3@_kSt}LnEA_by5Iw*2 z-vv5Kkf!z`xB9a-heXB5e#WGG&Ss~XEYYTkYqKdrQ@WQR%Q=h$TMs}lzxqD^A9Pr(W2e9)sqjUP{^37>lm?Zk$@F!LT(5PAfx#$L-cU%lz+X)P9q0xIW(>BwujGUkJ? zs}fcQGix~9Me;yRFh0FkFD@=#=CHm!t|KNugLwqWg^|U+neiv%+F?1K!*yTy8)7?* z`#n3Zt0O^_O;WX%b^SVRyhzM?>U3?F)jWqqcurx%tT*4HY)rydJSdJTi1L0aeEYL! zXwLOvYp;yZ579tnJ|@W( zSN@#umP2Q!B%-SiSjz^*O`7!Cs#i-zWQ11hIjn0pBz&~-<6{@Z7r$#M0yy4PaWlJg z;AA_+VY=<&x=Kh7i!Xfs_T^+|*N9r2Eb>zUWfAS#3)602y2Ws}JKQ{8XAdBTl=Y%R zCEG(##wM@z0uqS<*8}Dg0+u&CqGfV|rx~3jKS8{rC;B{ZEqTm7XF5H!J7pa($If{B(*>LF6JeC7>?dEHfXlX>gXO`0h4&4 z?E1IIpLD<7UDl)YCeCvB<>`=3Gfzt(33NNbnnbHHANmxc&qZtBL0?-00vmA(Y zl80ru|JaxK3kLK1AKknFQY-9IEun%{xyrL+PMtlWek5v|_{X28%Vhk~Nh4Il%hi2D zm-bhSsT(!cQ@&rH$6;Q*RPjO^0c}%kV^cm|OxH|>z4rmygMvBem+i{~QS50iGG6iwtlGVS{CxVZX zzBB=D76@c2Jl}9J>HVnJd+YS-qS~ltuVuvsep9fm62MrnEEimHC~Z?XhEbte&84z6Z9?{6jN<5-)RbaqV(i$;{lD zd}#vAS{}j+tj(@!_dINR{d(3%NuiwT;Rw)Oo^7g>O-xRY#;XUg%0_jEg@njJ zE?Ly?%=ZhQhlaTNwzMt$ZEPM0yPIe3L=#^%xX>;pU;qf+#RIS@q9tz zqC=y8DeZ0U}cl$O^I(jchqCd5By33 zGHHnPtiGf13m>TmB1W?-8ywh~?$AhY*qik7s`&60;%bF$0hLV=+uVisG{^e3^4^MU zJQ~R1jPo$7$T$siUa zX!nlS*m@3Q0k87&=LJYE^H}Ht?O-vnd|DZGq9N((f0Vq?g05lGK7mMH@$BCT!R;~?7X~3 zNDmJ>k4@G_(1_kf{5_3YNU<;3``I1@Bw?vchywNz;Q<7k9)@Q|Kxl|qsPSfh?q)&4 zQ*T83^>i8!C;>U*7~IirmOrZN^04<&>jlFZwGG&mh}jcpiY2_#NOL0~&J4;TwRrf^{Q zJqXdk40IoRiO}$UzDuFByR&;FGoLC4#By21mohNQFLt%+vn+Id@60}aElM2yZ#d9N zgBi++iMS#lJ3gOBC?LOw`M>{4%7P3(DE;(;YCZEKlwDF_-?5{rghvuik06qJm?KaN9^;3ArolY=J@?v%L9(>*9=`iP&teCw^?ycqRWqDH^ z!s^xjg@5z$?fj7q4!jAoTSq+%$Ia`J9j2$Kd*(#gaUO>pI7f@BMgEr;Ig4f`p^N+oc%X}jh@2#1{Df)5lf$6VZLGR{ zc_Y(Nnn3sZm=1rXjjHRqg1DSAgR{>b+0bCNCPbcLvSh$ONczL#f z@yU+kf36l2Q4So>$#&4HnJ<5Xl}QTgu&cq*=n997%vH*gBEC&t`&Qc|ILhDG?eORM zIutf9<^Cfdq36=x78!guc3W?=8#OI=sv}JxLj2Z5jV49(I94;~ot;@}2ulfgP*Vu6 zg!R0|>rC^RmNXv3#cSG_egf$CQ$%F1+qap@*Zsn_pl8OWXtm@}nMY2R^GOtX_Tb(9MbC{hl+CMGvN}xYU%~7%GK=nPSCHH#O{qB_H62F09~gqMq+8;< zb)D=4EPJ=X$fh>ODW_J$Tpu2v{s5!vpG@&4+$lYW2*aO2z++1|&niFVP3Gf7nh3>e zF=&S+^25v4(x+Pa{e3L>8L%)}maxmjZ*7dCwyg$^pMfdO@l&TxY4<~sbO>vj)pMs2 zuS(9v!@ZtWM?m!ZvUb+DM9N`Qslnc7`xRwa6J!kMaNaf);2u?BUX4JI=ri=GY;&Y!$e+9=OQ6r`(nNnU&rAI))g1hH_ZGeRop!$ zKkw0cg>nl!W##(}$unqS>bp!YO731o`m+t-De(srSq===c!h#pE$)MbBPfz`N;qpB zG5c3r^EV?z|G56t$A0u*x_}LPbL%ZKK0eQ~i&!gh$J{@3(OF(s{_y_9)vc5u28X^D z%m?;?#e$!sP{9}aXP}`DRlvJ5Xfn+89aH$B)G72&h|IDOEWVPDG+;}dBMe|7JX#R$ zo;dEds=qW5q?$qykNB*sp5&-C`V=Of3Dw@y@cOR1`|#O^tt=}R@( z`L7lI`B-q;iNQT>-d?l#_aY*9zxcX~sg0A>OSexw!1MucE9LYm zhcEkiwMdUB)Dz_Rp=J0&B5k<9JEOx zeZ}(SzVfWWHvBCZiI8O&AMo(B_?YgIzum`|)PoQ0m-9(}^s`#nPb!{6;$NbFuXyN} z%$9%In>K#gvgKmnmgd0q+jG93Q0^-bb_7ot4Xm3QW%p7(qvk`a^+!r z`^;fDj4Bx}8YQzRwoAuYtYv04$gYz54Ato+hcBERBJg4Y7gVJCT~Tixp;#e-J##3= zwQzz09SSU9J*aKu{wa26hJ#t)P98G^Dc~%CX>I>*Ap)gC>-;)ooqx^ zAtNVuOK`>gf3Y9N%W|X61d&LNUijNPp|^3VXr;(AD~VIRC37_~Ztphy zTTf@FQJf8ZGdg`{Zr~smgJbxXOEpOy>NesB^3UZrubYEo8o74qCpVNs>( zg5O!PzpdTha8A_V0AZ#4GyK!WNOf7*1({t4aqL~?Grn@=HU9z$PCL)G0zY*XuX72x zrppv#JQ~hPE3U2%OEdi3SPjhlnX`t*KDO8W5<;IA6L4{z1p1($&b@Dk=!VZL^ik@>}}l4}!rjZMH6V5xBMVfrX zb**|TLC0|Zy+tYH_CY4a1%$zx-w-!(1!Px;Ra)R1)OKTgsm1C^WWo1PSt}R$@6~$; zQHm;5iPs`YGLiDgGOa`G3409$3X?T{>e*rI|80(x|Q$5)r8$mp>W)L1T@u z@p8xOJ))8?q zj8})yW1Z9Yb3~4WgwE-FMM+6_u5GsPXj%(OZ@R4~hQYN0&KEt%BF#;!m!{K$1``i7z_^w>!k4`!zcu zkglkx5bt)5K@wq3lkHZ2;kawiY3>Ep>$VPcH$Mr?+!-ApZ-wKsEJ$9An42Zok6TtA zgn?}dw<$`?gJjfg1ZL^UJ6vfmwUs~U9k2F4Md_=B-PaQkTx(z$od9kK;bt^D2-C&Z8m7lfS?J($mHY3F>0ad*jzFe9Hyq@-64M*3o>)y7h{Z^=A)sy-Rhs zA5yRmDq%>OeAPKp3W5YtAwHP;!E6FNbqA`rf^Ns!t>@_uUxCkn6PVaUO?d~skpkj* zwEK=U862;No28?HL1_&XT1NxLYxPp2qqms7iQh?2sEm1|j~`bCJwKM-l?0)6sLL+< z8^1!!x<-;^g9?nOYs%dZDX6 z{rN$?ce#**e9LSiew5o_EuQG4q;${lwh9?JOk^rU>6(;<>MkJL0T1!x>4F6I9KRv_ zT^@g^WYsc~kS7$Mcsjzr9M0rxf(W$@fnoN;ec=o5-MO=VLM=M_Oh!5}1pURsWKSaV zM)nLUPt`4(jGg6ssjr@X{@mP6`<%R^XSuvvJ|NuSICW2Wa4J+s|EtgWLtbgtyTM3uHq3fcy8kkfzdi7(GlQlN`wI97=)}hVWA; z@jWqU7iWMD%Z4C#j2nF zm=C_y`Ed;?u4Qemry6xX`&xo9%?W_JWNc0>h?_11HvW4L|t z2L~`VXWDigQq;Z^K|RYSNS<@SJ1%R~Z;M7|jm>le=G|3*;gvH7B(cJ0I$`F~=bob^ zDkMWvb39p%=itZ}!7_6{Zz{97akxm!U*&y2(VU-OZ8!pyQJ2+RnVL16S#JR)1ISw$ z#qvZ#c2M-GZdCev^RtvFuj*49Qnk*IW)P9cYQfk8%`lLpX zHwRO4rrv&XtP%W9%d^z1`hy9%zgW&!hvs||ZqWe!uKrvT{5-90-8VDO9uIB6w2Nd< zW;s^l+{Uk63tOM_SN&ufE2Pm#PxvKRhUI=nobGJ9a_2WLz~7Vx3bPT^SLA9dlC0ci zUbs^q;?6l;eJa5MGBt@RQyE5WKh*hFrMc8R|(XbPbW1^xV z8toDg6RTI-F4WVMW@YeTw?lf&r*BWTGmaWp-oB`&=0C0)cMg$bAm1W+m{>v-As02B z@bK`kbk~>}FLNrQV^%v;yz2Z?KN`}-=E2a}O^TsM?_h&ECG0~))_n3bcujZs zb2)!J8rKq?XAJ|*N`7H*0XrG@J?H9M1!|I&$BVpYt|%(#W(pyNA1bjEN7cIIMp78_`Bq zTPspfBdi=g{6u8=XGWfXCz|3eE&^R%BalgwI*#uuJ(&~k;a=(?!l*~VyxoVo~PH>kfyJgwNC8PGvX=&BT3r|x_Y-~ z00t0?o= za;ozGARJXzLT-xda>hK$Bvcw6H9QHbNH02O?<3a~Qpu;9r>=9n{F`* zR_9F?QTuiBb2kZB70d@RpB2uLe?`y z(~#s1lBTqy{jnK+Uc^uBR9LT%jZwThTc>giaIXqXcFVbOB z)cVni6#*AAKwc?A^U!#-JU$aqb*f9=$qTmF+uzHt?_leoVRQQajQEu3c?)C>d%=ao ziDBr2k6NH|9Fon9V%aSdzGn5wF_5`R-G$0YN@w{Q8%FDtW|ft)SSNCs!S-9dRcMI@#qrJUlihAme|xXZbN;X-_TvIlOg z(kgCv^5hAXuPc~NvCU_-E&%L&Wmyk`K&nxPxD!YETjF-Ind&|xCmFDdio5yRv{q2PqXYWoaAG*sLp>rw;uT1y60B< z+Q0C6yy0`3WjVE)mFy|@tF*{wxL98BGzlryqMyd@$EmnymP^s{`1vVFx4E9~t)8Y& zG5H3c3l=rLrs0V+j8h+q0gy4J(FIOcmLrHIZ%1E8B{xGoOxz<*c04jLr4?TalXl)V z@YOA9tIo~2axlQH_5es+yF-O**0Hg%>GSG}{=&mja4J(2?`BhzslBRa@KU+#Rni0C zxE5+mHEs&WHMPe=X-&1sK0?Gsin#u=jzK$xF`A2me!=|t`{Q!p6?Pv0W8+b2N#U2r=!pFO z9?;Q=ZPKIC(3?%H-N489RxcVszX-=;*=_Msn#RhCRTC9QRz zY2xO{vz^$YxR4^}j9sc*eUR;!&8HVdy2GP@oiW`&SGNFW+~}3d!;*i#!3;5&F+5>% z7C_0$taFDRD(6-A_Ja-(X7V+%mke+sre?_{cjcG{!g2vp@qvU-S*?wmh9s#@i)5Ss z_rw19uG>vS#dy(sTWG0K@ubV+#~W0T-+Xquo&rSQx2S~baE6?g=uwvyRGCP_3&;Q5 zo7JR|;J#cAf{GAqgyW#t)pxKG7enI@+h$vz6%`c?t;l);C8s&R$ovQ$oK11mLsY9z z*(Ab7t)?K+F1WW@(e&X)*7Ys&E?8m4{zK5IgY9fCB4C3#NA#8Oey{&=y_4ewV0Z z@wQ%S+3b$n^RfpTU<+Ft@D!3wyvG3e914{WGJ8{X263c1RI3)c%-RNVseSCrX~|$8 zmGtuw#Y%7z;pF1tT7F;Qk*G1%g|=fW@X*s%5>J0(fd6>!v$sT{M$@FLWuu0YXxirq z7Ft@57z~XLDe^9%8tPoZ4~%v0C9`f))gNY9WNfU-#$-6+#j;k6g8C-YcoKd^#BI#q zp5E<-6s$km5#~5M>M;?jd`;(z7z|W9H2k&OaH0mj%SoSwoquvQ{&L*@@JD9>q=pXV zI+`RUAy0>4fy4!8+QN>-tgNI&=tDo*%j0lkI2xwft3D^8ZkKi6mhA?mLf#GVPQR23 zgzPE02mFex7;v45bn#I>2;t0?SnU- zs(!q>`C&8?M#qFcQ;*K?Slr*h+_7i~fV3tCtNl(%Ss9Ose{vUYK`5i)Iq8 z&YNOFOq*|DK--w>{>AjPr&^$_jU)0a{wIr82}(7g-!!Z2O;hW(?b~rH^6Aa3hodnU zoNPxI9X9{@+yC*aB_y?byjb!&^|qisZTMAk#8qKZkps?rsYkEshz*)3kN2ps&^+Q2 z1n+Y-Qsd(1MDGenVnI^-&d!J4-g=jMZTEScAjZq@0l4T^=fC=eFnLK4VbWq9vpzBF zV`t)^Vfnm^7(7`c&=a?r+a))Q;P9x2_PljmA6CbXYGMJ8;M>3)eHZ25SiKSMg3&kj z75UPC+hT!sXaVGzY7^uC>Cld*%@lo>3K}y7(po}w6b9m*v@P_F??0}|&u?gvyR>An zU@;YS9grh)(TIm)VQDFaq5$bTre$BZW=&v5-gud;+Lf)lcWVI5eR}}a=28&l8nh67 zy}&y8J_D$(7=bVZn$JNfdoRBp&)cv;F&Ot2p^p2!?v_0_(Xjr#-|n$mv`rr5jRG(^ z4Ev0JDab^b)kiD8!*u2hHdB|8eQsT zDM>MgmtUu%>E6EZZCbwvWNK9Yn}4uBCr?)ORXdsbWV4sO^9`ik8w`Y$_yU_5s=kCRie<41wx5y(JOur8?r`|2MSG@BG zK@LuNkmJ6+vZ7)yMV-`a_9*K6ngn+3s&lI$mT&HaQ3syPYrQb&{t8iEI*6_6xhcg& ze}hH%aG=w)jn9M3?}NpIosu)6^!lG`mqVCIfIJ*jpe4MR<}?z$J^2^Jxl*|#kne7J zMx8h-b#VcHs{n+;>e_cy&!yt`v}Rc-!iHRGh2)j804Z;wCqq4xL6%F0s2*CCWV7J2$BFd`GZ z8$ztqrtMU3J*h+U;iGVpkXW!XrB0w|EGSG8G@{)rj|OriZR2x>6d$KULNyw&q61>O z*-0mvh;T`31X_3tl|3Lv=^}Yp|7;s$vN?PJhI5qpL`79ppBpY&YNF-!^OXMMSAXV- zP=g!2GoEqqPG`x3jkr6u=@u}RAMO*PeR1Lp*s~qt0*!=Ui(15BuXZg;Yc#Rb()foy zV z*?97nb6_(Wk6YYAc(%i^Rk7r1e;p1cFQFm=1AA&^o>gTOpLN)~Ws;Ur;C=!BKYr|= z-&oIq_~o`}rK0pK7y1>OmM*cBUSd0-vV(@6_8}fJ!Sm|In!cL7QOO6TrDfn9B?R{# z;sP3hYBZkpc!#TVHI1yF&>e!W)xgE^7g;}5uHQUS z8~w}9J~S}y@o#|L4ZmIY&2@L|B?i3if{ygRa{}^RLU-)c{lgFD?!%eqd_>|1Xw>rl z&0APaogfb3KxMd3eaAlb^R$EoK_HW2H`qUMA`UPHTo$B)#D5cs|MUo#fQ#7OW@QTf z*?eQl#6F#|HYJ|yu)wl(bUkA?5SUU@qTzy9f$8KPx&{V5pT8kz^v36{74v1x0(qnW zgq#o*FFS@0F#p_q|NPZA7!71NIduI1EEduss&j1Lu85kP6QWzK)V=pnN9!SXWF|y1 zOr%l7Or?*yJnKwJm4wNXt{%POH(n^WNY0FVerK~AqY1sB(#iN;WZ^=CHhbk#18I{B zOFRwN9hwtS;*lht$#Y-VFC^4RuXVF>Oo^h3(RIjTL;1)s|{L~+i;-giL(_j_b z*L&i`i3l+=*%>YWnAeT`>!pGfXgwqv2r}>r^}|O<8Jd$q@V`55^>^?1>pOtujAXcI zPMqfr8Z3)W1AuL#IL;v5foGl$TMXWN&1lG6>dgoe6le+DUjKyYe?AjEQ}`a_=1=xe zpV@f5AgXMW~$KUCmetdLg-Qh{mQ{cW&s1E7} zk=i*vOJN|4|#Ms!=DTpuQO1$vs-tIRaf6Ce$wujmFk zR(9D&`Y34jP*^P!qK4>mh2h3qI5Mf~#ddI%* z1*k@kL46igjKje3e|&$`Z{^BCeOpFDebeEWrDWGX181HLeKpzYdW4>76RnH(0%{Ju z72V`hsTQrVy(U0LI9h80K3&~->*_-nhPr!>mLmEIRF$&UTz z1q(2qK4_vTCN{Py$#gL5VdmC296Lr8kEDNlHmMjow|W!V_PyklZ=$$xw54JAoWv?W z5%YCu!d-k;`8i0coSq|$m3t$@4doLjq~SFA39#q&I2hm484MuYgvyyVPjxmm<&9dE zigIUL73wCQ~JzrFE23+PkWgaXzu;0J?i zXhCB3*%f2cUye)>Q_bw2o%`$~b!`4}+f)Z2k6&SW_Xc|}%f!jrz3#5F-L?sMp2);I zpfM&rzR)oJA{~rAS91rPKhBa1hR#~TW|Mo#5tOTdnFy7_Jh%SkXwY-epnWuly2=Vi zTp}YQFT#>ZF-*9BH^yYL!Y(eReGC6aDfS?``N9p;n56p(*5vD;MX1rS^Ahao3rh;3 z)EPybu|uvsXtU;nTuU&mm%$A1FPRJxn|%cUrkxb5(yvjUqb*WuFvoVL`Scpbe|)b} zFXz*zh(xD+Ap4WOjIN_Bhz%s*quttY0xCygCf+YMPD|e-AI$W!S0-43A(?yjSinZn z5Pa1y9wRY6K@P!$4$~%O7YH`CVTx$h!O6lhH*jP`Ff_Pk(-t{h^W~K5OaJ%Ll#;-6 zRBw!ppuVU9TD*;ANA7QtF^PstdpSA~FHBAy#B;1yIMh0d;|_n#`W)%OvA&I>5#&+U z7H;k>y!N3mqIa%~_KJ(p-7q(OE_PbNAi=U`tv8SJc#tsdUP)* zxyo*H(_oaZ9Jq>{F?HaQ9YEtGP?&{@4mwC(n{kIXr%U{kuswc2nGO&V7`?!8sJ&Kqt) zitkzBC1o?%Ov@;-&B5b_v)#V_OC!Ip7~PHyX1Q>pO^}P;o@y^~|{B3^!_%r2HLRk48cGlE{X4NGe8Fp~si(4}9_4hd9R- za40hKdyQEZYpfg29du=x!ob4oudg#3sBLFR#fVe!Uc2-?3!bm~-xoeE*C$A~SZ6oN zku`qJt#Itv5_ACMOfqpdZZ)lm|2U_7tILL^;msCygA~E?O}}vgM4Jmc9SjVjHFI`P z!;bIiGzK%9d&*b`z7O=T%eGqU_^mZUVKO2t&@X_dWN)w(E%ArD*mmb&MY>FrkR{mm zBBy*1x32?lt4h@Xr{ZJ$%S9&fwp;f9`ECFAs(#sr#?o%3w=(1h=>%@mN{gJWyH{nf zbP*W~lQ$NZH+T7=gwh#Frv~Q*r+My5O}W=6>I8nbuUl=5PHKkd(MO|L_k55BZqHA~ ze=8&=?R#0ug&u)`%Y6|mOX0Py3{Q^t;Owk1=4dX)ZJ54mXw4Y_w`;*RGYYqi-uGY6 zsE|uDZGMfWNiBvPqaP8nU>P(l;QOOo6ipWWw*~uY=gYJpr}03OYiCS|SYPVKSPbu+ zYjgn>`!o1g=Z(%SPp1EuH!YNm7p>FpJVFi>y8sPuw-6bnmpV4uy7x;cW<{t;36x45jHU3<5jl z`EJxE+6Lhc{mggM$(UTsX@mo}Ep3C^ej0dg8K^?{9o5_FV;}tY2*6^WCI9=OI^5dflQG?fAN+?6(1kpO>$$I(->UvoZPV~ z<2Aidq!c=T$Gc|`F^*i80}!~zAmD;BhgP+zXMoEn`ZuDWog}e@$OA@h6(*&{}PuyWut4z(2wZV;5(0p3# zNmKCAqyKeU{=D#Xo54xBT_3rb#DBw0E;uBw&pKLbMujzEP3ipt6WgzzD5x-`Z)|MUk+>nvugD6h9j2H&`t+Q?Re2EBj{*w z)nP2>Zd|pH7khV;(`feSMz-;SSOq&=3Z|=P(_COm1-AX^mRR4Rhpq78zqNorHF(kX zYI_9A(})K}MMXE5lh7?+VJhF$p#AS#V+FRx`+yJ3)UDwwWtnb?>+vyAw+KnpYmCXs zm$BfdT>M`2!W~kE-28hZ#Ab*U@I4=&uxZ49t&_nLm0=P+jnZdd^b|?})V=}fS;+KS zTsw@{wS;NtwphGca_|+j`$-3{AUs|JO+U=B)4+~HQUD^A02bF?aExx{xz1aVY_O)u zo-Ey;U;m%}&21~Js%Q%5{0;aa7yD(0E=7+lIbSR?Z)EAFxh_XrM*(K`?<$`5PoL-MziZyJ@;of$$ z?d~e~g{wEz1YWRN_MeK1&&-96pqNe7`@dD4zmGk1y4hf77Hj>L47D zX~V^k7=-fj97b&)K;mjycjz4Lp!ykcvKWJCV-C@ju=Y^;>B?$Qz@?p78(n>@NPxR_(MnL$1*s=1ps5=yx!r0R9n1 zhI~;W>Atsj$cz7@>^k7FZr6W3QRuB~QASdvkjh?9k&%ojdu3;jtgIeQTU1m=+a|KN zGE*qBS4Of!JhuOJKN|0QPQCu;eBRGFo$~fPzu$e`*Z6+F*L5WV6W=w%K9BDofq=7( z#}2RpQ1t5D%K8dhP02yDSAFR?4Gm3vSUX7KvMM`Zv|2Dc9$A)|ZpYQXzmeYXv%!ep5lO8Si-}&c14H(M}#n<4}cwFFG(1*V{mI$;{bO2TcqTQ<~&_Xk* zKb4~39!1f~GIOxT40yJR;;4#fRqgnlmC{Sn2_)obks9NcZvV`$p8Ia zuqja33=Y@E`J+FZ(lS7q2>@rZD~i%!j8DMhxOIm0l9B^x@)tSBSsaQoK`=o&V;0n4 zG-%`9V;GRHtldm-RsZH8st&+Sh-}+lj(!MRw3RJ3rS^dUPbjKBKwskrtpNk>?!)ZL z-!O_cJPR@#usAXu*H70btM&#zbwVpwDq&U5xre%zgzx%qPu3p|Dbx6vuOIp$C>xPL z6Lr07(LoIx2rhZh&E*ZdatByldEsgv&uJX-R@yRvr053*2HcOez&;vTuUJ^|n64NI z+oS}czn%&v(xfzqR=@j5@#(L5;iLEeaGpQEmV*Wy>!9YnL1oElpG~EC; ze1UBQUi{B2FhnZw9hitP*Vw-X+Is9oTW_0MVD0(LTafN?W8M zI*%NSdGH^WjjJI4>O5VcoW1`a!H+r>Uc%&fVJ-UchtWh(&Km+LK}avu%u%3cI2ISJ z#>WNMc@IlR7x|kemU=r3l-B`(zg9wXWpU+WF!w;Tx{KEp^kv-p-JWPqUC-`>UK6p$ zpg-Co7E6FG{_S00AHg-FTi8Alj4X`dq=DJPWMJUHwd_Qf3nt$2pW>q3hh=exH_`g? z7!^*3TvpMv7?#{OoDzZ_f<73=BKCzcoJ*S)qU{^k;>(N2U*_HVZ(IJy@AzRM0VLtq z^d}-|JXcbw&~)y_&WUbNY9{IC^XFY0q6D1(pfpB|ibEF6(x*dBfhMg4geHAJ4VzweSgH>A#$7|3MqPsl$(azp5s^%~HBW1g~wre#7uH(^^zrfR6D|)@~%cI?g<7nbg zkb3x@*lW^Xzl^Tv>$MDFMUk-#SLn?f*69ZLpB%vWt`xWX$1a4Dq0OBMwT=(|?d1|4 znK}Xf=11d6ML%sXof{mylL{53`7s=#HlhL0%9!zzvN5ILwL^Z+ky zLbP3~$6tTR5Dl-skd4}p?I9BFt~#5t???Ff6=OmqF)R8RyW9SH_P5Wl3xUtrLORI* z#$WZ}ufP6pABbfF5PtBz z>47`wRLJBFz`Wl>1bk(2N`Qz=$6(>xQ2ch=yrJhDkZ#L!=dwX*L<@S|Ltkq%WgglQ zAwaYo7T!lSDNlKNg7Ba*?>$U(mjZ122`v1`EULWrccT*&+!*_nDe^)7f1lRW8F*97 zE(-4mt|uDKSXjWi}@NA0Aof$Li=Gg6gh-9e_o>s>VsE` zNc*Eopji~buztmWP`EdC!D7J1_%X-=U^YEqj!>}Q>Im;p1s*eTQRfe(|NOol>+AEG z`U&3;h717!hiA{w5x!U-2FkiyM8lznb*Jh?WZ-hE#ES1CBIyqYd-fU&w;&y*o@>f3 zqJiW>Zj+q&wNJP$OmQ@4r{cE(Khim~C<=fH{Sh{hGQ)S!{lji!_mEI!wr zgId3=nmwjK|5ZQUmC{N{+}8yE9;$~%(s78-i&3wM|Mr1@Gr7MT$~&;W=0P65HkXnWg>(2KxBUi%wPTz2G0TOMu(-ZA4nPAuy%) z$+DnWHZ8~kPYii<@N#V*=7&N5>2_fsngYq7v<3ZnBS#P0=%~bQ+u~(sR5d7c0FUtn z=CjPw9oxGRGs6nS9Z%B!eaf~N5OJwQy7v0g4|;>I>dk0SY#(fc0@NRh;n)fTcMy9# z0VH%rt=RWJg42I}5o{U>c##^#kuY>k98MTO?-gJnJ{ek(UC~tSPe?GCv>>$SyR((F z|7r<{rg|Z%I+ZwZG-m$v5)_Lg;+7pS*P63M59V4-=Jmh3Q2n6sul1jM9A3JUz_Cq) zFC@rX5FnV_g#0eGMS z<{?-_@{?xOMTrQ679R}+`dSJUF*}|g!vFrL{~nU)0ZtU7C0NHp95HZB)PQZsYx9w| zGTN6>Y|{xGAR!mr3Bl;f8OI&C3JO6$Tl;o+&q=oRLNIv^aMdgEFpeDiN{I?(Y^*huL;Yw|^Nw|xCiv>>{3Kft;xBG7AmhCvnLo7Av`2c(TLC2*9zU`)jyXbF{jR=Z72j@?vY)Y54=FL4tFXcYDb5N|#K-L=`32l_2eYnMWgzM$9=|#XP%n>8(WMGB9%Qp*m9jC_7O08 zyRAms89w*fSu>vAL#ZmrS9bau0?Pi(*Bll1`oio#< z4YgO-&3>tV)C~eDmC8t$#MG@|sj20Q@L-h(Vk1@hJi#f_zfQ{3<6w>K@M6(Q*;nsM z@Ob@=v;Bd_?!n$GgWigsDrH?y5)wFRtN@Ct({P=7c@UVK;@CeELq9IoLoWo$oCF1Rdq6dwol@|51`OE;CKKDP0-;*izOIpG zcoNka_OG`IG$thX-yVSUR|deiCD`&5Y!ob(rG{r5JqZcJ!9j7%wu49$SO#r-V;Lu5 zrAp&m@akM}Mk;&hER0@=MQv-} z2(TzZpTyk46rSH&;%0)4z6S2jS(S&@`O;W}82HvqYxIA86=tG%)hkIS_eio||LqpY zc=#Qh?y`q45>ihX^iB?A0sJgea`*Q=h2^Ziu=(z(-UD7E>E!5D*n`T0GT=rr5dWV5 znbJ`a;t8|6KQa%iV~kTHQf0tUwLY2(rV3P3+h=X+jlZU-)RGkZ1*;Rjn(S%i4`g$fIy zWgzf5>;;AlZi_K0jN!V0o0gG6Rk-miOn@^RWq0!|yGaqRbR-Ah?>?9&-DTTdjjxRr zpNVgDs;(Y`O(Pn^jrjg;dqIqR69h>o9oiPmBosxXd!4aJ$=kX)?bkaw$o!>*7n$cm|x@FCiIf;Lh*ud@SiYfe`(-$^g59 zveEA7_z3j8WXed_lxAEVno*0gax&uZ+k#Qq8?p<{wY0$gBR!_7(FZM;>-CofTYDRf;< z#|r|P8P(y14dvcne;9*81cGd3wMT38R~!Jql>n_+5za7kusIM=l|TcnI2 zBAiea1rEyN)LTSjvrHh_g|!)%`epCDVX^DMfD^UxSn6X|>WsLm2!8P^1N(eSr8q4# z{s!`R4$0d?3*>}L8gf@f3m;RTr^pv6rQ{7K2o60BQ`s{MBwS^k*X&C~)7`nW3`veZ zoU3iIW(`SRzBfHlwT1^se>Al#-8`z0WyMpTDf)T<&q zN-T}wUBxTiZ4mWH5yDXSt+r?J2SMo zngKL3r}GD4jZPq7t%5T%zygQ{K}xw?n?H^DG^?eW8-jg8#uk%q2dqm4^q+;O$xLmI zfM%T7iiJ=mj|dSL8vvQ5AmKgnwYnP+z;%wS{wsKhZMHTi2|uX(1WP%r3#)tEMxbLN z5Wub5yKx27adlzsmYYD3_*oFfRH(!R9KP`3Y0l^SmKKiM!}o#5EQjWyh7_e&`04^h zNC}^9C2dSBvCi(K73i>&Y-6aNs72VsttF<;X5=`5=;c7^96*n$%~}csX7pdb=idtg zA-0gKBPg=TDn3+@cCdgxvCb!8sqxnLH$t5Pss8pY!)qjMbP{EG?FqFL8di3qG zA9@yUn%s%ZXA)X5%3%ZnMfHVIC&tR%j;8^QKb}*V5;D#nLQF7TUdZ7!pt-xvs+wJ( z@v|yRy7Kh{zp}MIn@N@D}w4H$Hd;u}|F&Gx{py7c(_R3aZ z`pW^!*y}c30X>uSpm3?ukaS4DC9fmV;1x3FgTxoUxWdhOnHA)_{&!rUgXG=Y=pf-4aGQYrDFICFJxIPb z<<*rFIcWAkz@ZPKV01kjW1KHy4dl;6&YT!k!QeDrPkCU)PcORh6x<=;92%Zg7 z6ehsKNF=9YS4y0DU!>uroH9Q>^almNb#Ih|edtO-(0<4CEz*V!+tWh?+eav%xl;$a z!v(EcxHl3B`80fbypjMzBx-si1J}Ge{ov5_6C0vUPaXU$kKhal#=^o9WV*M;UHg zwlPrifB@WM?$eE1OIEEyv-Ea#mz>t;A&9n1V{?`b8asZn@^&Q{XqvG`Lw?@_{vf*| zM4FRr{+<TpI<>H$T+b+12vI!`82Z@=u?Ccq zE{&Q=_(O^`J~;(cLmw!*6g|hFE69(>d%niKUDf!1;*bVu~8JN&_N9**7e@hJrcjKS-vyJry zTp|td&=Yyt;0NQXp7*N zK^j45*uM$TfBDovjj9CQEE8fP`vZ@yA7VltK#0lBFuDYJ6lO)(s*6-5(O5f?uvp6DVnJ<|N5mgsxDTy9B`t`T}!XkV(3dUp)1Y0#&RO-5*YJ9R_Z0 z4rCAyOzqzCR+b%1EugHPki7DHum3miS>+8MwbU)iNcboUQfNaILnCRW0g222KePF- zogoYDK$o0HMpMzsN#snIGm?^zTt)Rw*ijJBGVdw3{v-YKb8e9)X=QSThPZ>4H|ngm zv3qJ~1%yf4B{AjW_N1V{;z14yw$(dn^&$5I4!PSGHULW@M0Trm_Id~P5DPD6>qVo? zpJ5}!6P|PQ!Tnn$MMOX|@RacY<&Yr{5HuC!#dg4A@+0Lgpt(Wm=|>{g`+&>XXvCGy zZ|02o@roaQLT{+H?G%v>3^bklEKq!pqW7-04I%C{TSB$r4`sASX{XUo=l-YgJcTIG zIss)6auTuzuwizvVY?0X-01_iuJ9v6M_;dpf173jVvO?pUP`u@UvaT*;O*l_5Og(vCbo=TG*zks%8*qo9 z{xc)}a17jD&d~D*y-37fp$<)!)PN=qr8L7dQ92NXP+Q@Tt?PI&NU8MjT_YKKht%06 zK;;;IdUfrLo?g+GG7z{iKvvIXv%8b3Dimb~MSn7ekUMNdNe zyxO`YOdQ5-w~g&t0e>n~wSh(gx)*Lj<%J*sEo)@q6nmvnbguoF%z~L`1I|q;|5=j< zMO;cs5NsqD0yXx%wEq0@yn~9uLr)tm!7&E(Z_`$^stfNt$4;=vf2jur4};Ncns(qL z{9x6EA3CKYO)W5OaVIFO6q{28F}aBA8xeV0)R9NXL<-H7%p=z1;2ig;Mafnjo(E9oF_yPcTvLa z$8IEJi_K<_%`s!Bj?V^jIZ%?4DfMuL7@cb)YYfz1D1g~dzZ0nBt=vr|v)f*3na740 zL%jbhYKp8C>&iecR+y{*1mp*@$f71<=(+gvgl2nf10&_%a zDLVAXbyZY|to03XiBmIDRr$bA(UL2i$-qd!Zrwh}SKqXFPsx#>QVC$TM&B_o?L%7Z zfrOj#FNTdXqy|q?q1#M=<*4tJz+3|(ketxF13d160)3q5F?p6<;I>8Vt#0F;~I+>O;FNt5N>< zJdtM8H6~JH1+Zz$+xt0LaiDFk5E_i6f)+}(iWF}!>2gx`Nb>55XUMtV3Lw0%-|Mo>Q$+r zMKlfKo1Xysa_#g(f%VQ7`|vItZst`7&|t#%&+|NKEet)2*@AYa5FA}9>lk(1Vs+%O`n~S=`Sz zK=?(87x*l^eE)a7g8|T=yujxXNWU-dH<92TLw$ubge9va(7v+O{>_2d#xIkAu2jge zN0t2)F#XPjxzZwm0Gn4_g8;s@qGfGx`0L}1nM@=I$JriHxT$%lZLTCZ`Wp60#wIjGP$P<6VvJz=dnZG2fW{4vo8W~t<>T>#V% z3ONZ#n}*#?8mOwoa0oa%*9f`dJnBm5fVA=!QD?AV@6C>bYA1=(4}FE5*D|QJFgBosEdE7Tgf4km1mDnR!x6C>`q-GMfnqRJZwRNk}u z5kiip0FqSzNN+UNU(E~6uS>RyTZm@&yeKwU1i>R?YS99xmThtEoV?0DZ~p}D+YOS*f|O5J3RtUm8|2}Rnm}G*~2mK?q(SvxK`X+ zwTJRWU@lbm;fEU7q1`N!XCN^Qn~X}S^8Ux7bm(&JcI&^z=WO4kX;u!!;ZWJEXt&wG zdS`&sK}S%odxmQ5s!HP6T8f}8T#OSfDgz(GwIlz`5!_pNsnG!^=m=r}!B1DIEUX-t z<|Ze>fJM>@>zRp`*9!zVY1Glh=3296y(cI&Kp%><5f&r;9xRtvFPJ|!CZX`uL_`p->8p(jh zI!N4efm*pz>wp@%O`Y?vCKiF|_di-I_@qKwV)|ZP*^^*#24MJjJpN)_A3_KO+vqa? zMvLSX&?mR=1*D@IMILT}3QpiiQBMVcF4sQh*!V#~TNsy>Z+;)`Ni~9($2Yr}Tj$A* zI1X@FC*Mby-~Np+{b9yye`LNJzIBCtHYee?Ib?B2cG(3Hl))WZ&vgIVd6)&Xy(%Hg zmI>eMJpbg^Y#C@oW^)Ug8MX`DQr!~}rsW=2Wu)lZduNyXBeM0}fbtF$c`jR=BK)B8 zTMT?wAh6jWVhP2bW=35+NPGZD1@F-Ty$Q^d%r+_@eR*>^l!$Dgd;hD~?SEJTf>y&)A7VbWyOA42L1YS9Qcdab9jP_Vq0A$aNMQYuO*XgG zA{hi4=)KoXGIVW11i{H*i^yEr-HXN}^L}GS)Gr}M@JA->DC;2^aYU_t( zKP_Y&+4|Fjm-5hyIF#Ik(k?YADarm3WP{Q$T4*?%{N+#htAT^i+q~4-y{yY7@xYRS zz!O4v_8ALImjto<@A8hnTM{S*H?182wvY_zEzoK_$m{u18UTSopm<@^c?V1@A_T5K z7GjX>0jS?P0BHUgdC*~sAzc%a_#53eS6I(_0Otqvg=Edg<1W$3`iud<;ty8Sl+(25 z#%@Yfb;Dq-Mt3n<7P}Wt5js5+05-hlp!**TQ<; zk9}AL=i|S$v0j|;<)ds0Mi`!|EjSDg}}`Lxw4x(lYgXJZgoB?!*nq2P}{tj~6%?hW2?Fa?AiAD(6+_nRShcggON7%|`3zYHLp{ zPKuhp(Wt+SP)c&=ng`Mp^S;iK+1v5Kp8_ODAIDEQ|6%_*ulu1 z=6)w~1e`)YB45!=vh7DfdC2PfP$}#&YQ&uQ`jpN3_lBe~1|D^}_5Qsze;jv>0HbWg zBi$%Kz@U<5%FLJCIOkz@r|wP5r!fs-H;Fdckcw8^kCi!UnBzYa?^H{Yn4OmKriCB>5rO@ zhM~Snq?UP}0wWtF4Pi5g&sh0F{g(%8C-&#$vELV-Dcb7xk+sNxy9wJar74F`O9M-$ z%1#blhqT*pn-Q;O=dg7pxCGRns_bd(w%_6}WB~kx1cQPDw^a=R4|xv&dgCsi$d+;5 zHS+l1p4dSb&bZk{)^qKLu%`&sCIBozz_v*~g;8pjn~=cG(+|n5|JhTh9^}cAyR~LtImDsZMVJ7?2)ZPN zE3%4q%)EwD!)z{Bu#zaJx}D)fi9-p5{X4$qGSCSZD21T888lw_>3YX?c{q~(M0mqL zV=tD1l@CSernG>tr(O zh(c5&J?!wS7k|JEqqEpH&H+4&KPoL7VJ(9HJg+th`6yV@D6nx8fni6+-eUm{4_CBo(^D|LxJ> zqX~=@eC&0~xF8bxj_V(?6meToFsJ!^2=Jq?ikab-7y!TJ?;Hc&gsixN0W`Amx=r;* zK!TETCm~vtW)3!@GJ^1>Mm&-EumP5U$DnppH16aJpaC$~iA_mFjsHJ9@NYsw&nmn` zcZRjEjPs#I#VNuPfCkp9_q0e^BfN8Ws=J}_OBK6p1CVSeW-ORdgdYv9fNY{OWdw}@ zLXbH@TidX%ww6U13r>JI0B1#>%IRM`jCq+Q|5lpwW?$Y zD92GVMKH2)P6^V>0I&0Ufj zF@i{ZXlbRf>P~&UbscjAOZ0#OxGp?O5LERXJQZyqhN_nS!D{9cv0-;?})} zAQU)o1Llbx0JN(wRGu4=6y?x$yyMMaS|yV|5-9|`*8!!w6Oyju?*^ZD(4l1B2sRBN zbjOoc#AEJj4uXn6;Z*CY3o{*|vH+o5hppB>y4Zg2?r~aZ+!Ey*lkYCqiy)wYE=(rK z^cN2mfUYZEwF7dO>BQq7`4dWj2n<^=z6|fH9NH(gC)`C4e={`HAsOxyXbeG}d~r!h z0pRy5kbV@3zAb#I4;)m{n9g|5Ww_e8-58jK1j_3VvY63((o-|wRvPCPyy)zHLKT0G zP%JXYYg{zC{au04sA~WVGvXU=2>>ctR~;G_9H!dQo@uF$Klx6X8q-RWT|C$8Pv~qe zKrQD;p$xP8#bzd&bsQA}cJe;vIOPAR8eZ^Go5Go<#$Bwld?>jlw8J6gwGm`b^gPfn zah+W{cs)n-&=qCcE)z~`Nrj&@K@1Mv&A@_Gio4q&j0|{EvHb!CK28CX}Ci^Xl1Cw>m%3Q6x_AXiM%(fr*rvwL%iaF<=$ahyIN{wiD zP#ulp`}>~)k(755bsq!8utVgWgCt2KUxzp}+T@I7wW~Zs#rh=l?h2qtrLOCAZg>JJ zm$DsRU#}n(NHW7H@X%JaPv4BaVe3H3a;*p8!eubmnAt4SUV3=jcGypFyu$rHFk@s{ z?$htQrVss#bg`(;d@@Pi4F~&L!bt)CHTzJhPf$ z^jzbGG5ytr=Dk9<#O8A|V6#mCo=qYc(QD9Vz;TRwd40!3Gz*m@9{c?VPqL%=I4l<^ zFLrm!zIu9t(OCl&LeAddmkMtZ4O7~5LlYBceWd6OIrDjDD79R~^pVv5^t~hd_PJH< zx$#s_UeR8_LB9v4TKN;?q=2X`(=Ogg_1Nd6ZBAI=einFrtv)xu6SiaTF<` z6|c2Ht4IDwUVp}H|2uy01QplW)=-g;XZ}Bdwgf`Sj<+=*zx%F@WY8MppdR6>Keq39 z1B~?fAlF7b_t$Q7`7OI_QbEIKnOf-F9J^V^@f{z6B*pF$S}eiM%6nQvX%?^A71%+A zx&V+=`DV=WsM+H3JZdZ^WJ29@6#}#7{UAz~EiB#NAnVnIAbg0^QSR>&Z~ob1{V-x> zC4?OjS!%7lUY24anC{I4$Kwy7;iHD@_eeGWF~Z^{=V1_MHhNSK4TC_{9u{4c!NvhY z*c6zlWd@}T(%C#u8G~sZ!(|gl+&JC|w4e^irx96l$r^&gEm3!A8xl5KW!V#BNZbav z>3DYBbe)8Rlh$IFtsxS{AJR-`>s$62TQqT6-}5RzL2Mf; zAc1m#MoZ)zkVO3;NwJ4*FTkC0Xvb#$teyTcA|6p>mVGsLuL2}hMt~Gv;Mr$ujt0-6 zUb*hvMx`I``p>>Z&;W9kP5T|!x>H$TdcenzAJH5Rq^xC&J;vS#6W#+MdeL4QS!fT& z>b@F-jY$E}o6Z|Lc#!lk`*A$b-Nrh+q$TXB>_{6uiQ3YjtT**$km~_HaVz@VK)F?(+)hTvJmC-`{laZp`ofgLOfmjQ4wbp%wQkMrC;1} zJ;o!Jv2~K9dyuQvhssnTV?;l{TC360##V1i%U(~bnQ|iq`G5a|Q<1xTmek~wNzF&| z|N3*>2Q0RC_CtM*#S@a7mkIx1RnYyjfppN{Ehxr&rPahE74{dwnzO0|wPc3roitV4 z7+=43(o0}qaWFQol@ASTw-LDfcoYoQrIbbk?(W$2T{czR8k#!o&}`QNzQLT?Ywl61 z8btYaXuDt)0fxZi&JG@_4ewz7MiSagC9V~gU2&;1U%o!Nx_7p{EAO@5{1l&WJJql! zBO8X5<^TN;`6+C#bLWm<|3(M~W9$|K(^JMkPrhnpY#`mQ_w3XiYMtY;RYd4nBo@Bx zh0U&3Dhf!bm;@E4T$JP%I)x3qX!DCT_?IH(nbFn;82{)Y(id>lgScc)_=4=C>S^&8 z2laM;UI~S7EdE3(Z8dozrfh7|`NbRmwYT~I`)_Ji7W;e~vR}s|yAcNnd@GQMTchG3 z;b;N?a;iTnIOxF_#0>~V;Kp&R^m zJ=jEzw8yDNlm{+Oh~V3E=<9MNkDlv@&fZtIJ!gcxJ=Za|Y|Qs!dJx5b8_%DAhXV}9 zxs&{FFPRN31Z;!B;jGcmpdwICJ}^ZISI{Qu7!+G~nFnukZ7I^`?PiJ; zO_1HZSFx~ryS2OBp`-;JA}Q?u@Xr*fY)8t2M|ek=v+wTPw~^t^6Z=C?`?FC>gjyx zT0SP?JpSUw{@|>%7;)_{LezS=1e(OQZI!xaGETxr3_HgoT*C{GP1E38x!Ajm^FLad zUy06b$+>PunO!-mM)Mng^k>}$H6Aqf(N4+ze7);I^{mLnRdx9yXZmJ}`#f5OEz4s*SL$ARYLEAM zrK+U)W!iRd7mKe(Pu&c>H|x5xnxEOyzLHg0)YP+jBqO!utG_}t{t=f}Vbz^aZqqRv zgSGH?uT7LMc6pXWFJCM;=rYEu-Y$PsKkHiJiW$wDb1ydY?P`f>U&#($g!;i|sIM+7yIRGoCu;rT&$=h7I0JWy?de;@K@}x3XbKz*5q6{s^h)jq0Vyw_?&z2`v%g?vXR>nLSohePtc{_f~s{A_5Z19#KC+0Mx zvc|;y+G7@(Td6(mra0Uk7P#Mw-0P>v>29`lZRD5jh_1JOeC2<7JCDgja&)t=|42P9 zliViXC{>51Y`D%q<8A)wamXVBMH*a4`C`xN@H5#j0z_dA6pFJBIVDUg?lAeHR0b@W z381kdA{kKSaBnKWu#kl0Iok(lDCIS(%g+R+}XB0I9c0gS(xq!Tq_yr02i=cjBh!d&1yDW4^CMeMPjbnmRI zJ9gmY|KivEP;4LH@hi4-?7>VA)@8#4yC+qNdyS>Z1M3Sx6R_{Bs&3O>IR0fw{a!+K zTg%u6lH*-RjAdW3RAamc?x?qcTA)*i+%Sw(FUx;JBoyhkF#qB9GVIMMN~`BFwm`ku z$?(WU!3Prz;sguy0x$7TH7+I_g>5H|5@GC}eLcQ-Be^Z-%}2Ahn!zna`4g%SZ63|k zy{pc2xuJL{eH=`+F;iIfR}fnNI9bS$+pzqbd6SaQ!Cr?k=<~ig^2T^r`b%_JSlO9?*`&8^o-&}Jp_g8NX<&)pas8{IVG}86>!Jgd{ohji1XOn4WD80&o&py_k;yG|> z(QSDuCt;U-hnG&c(P)-oOaZzA;vqWFHtSYB6hT)ne@x9Mk|AJoM-oYdaUHuc`fN^PcLfWS2cQP;hLuJ z3M$N!-3}(|^x%uZuX9;H$G{y1A3SpR*AL?U+VjF`M2+1+|D|c5HFV&mXzj7Wr{}6C zYw@KRookVR!(V=RDvPcA8t5ioFSD3;!|X<#Sm;N666Nsbfb+`ypf=z&eZu@|=Zj)c zt#t0t>U1~1ZN@!+(>Al!#g65xW*W9(?QPMbgZ7DP@jWihaI@0~xwGTDl^mNbG+sUm z6q_Kec~>2%mEDDBx{x@nmS4Be2H$y&ljHwg=|EIhK25}C!?V9WFW{FKo!j@qsB$|n zbWv1!fc~~loSz>^I2&&WC!Ov`bFjiQX*By{t`#uGmUXkEBiHS*rkL!;&>V)LE0%OChmpKY(#xc}X`qliHmD!l}F? zn`T8`UuUw{#7(7@jXlV=$=Wn7T(;7-5-u`cTa?}YK5B&`Q&Cj=Qpc=IdzPpALzM41 z#ccn5;rfR}QFbpJP6LU0EbY%9z!{VF4-BAc$r=u2p0!0|knPDukT@p;K$zw?JS_;h zH52>cm~!^h5e6thDTE4S7Iup-hz_sP)l^rfLF~+r0ftmyylAOLnU@2ZE60nAGJS59ao~DFgD;^6Z1n0 zK)NwqI#oNnmb814scBj^t_%__y%VpSoTad9_Bd|JY-#Y&gXM@w}=Um!yoY?vDPNxM~kry)?iQh;Fy4@BN zTE2kK{^7`~_&xIMu5Y{a*-(AI%Iv(WW@5pwQ~woA|AZf4hxWtq4~=_g>izKNEH$J{ zup&~izX;04=1{okT98N@WsyDNt~3M}<;aQ$crc$?^CEb|N*5Q{Le)Up77H7AmlTzy zS({+xn8>$!$+4WipqFSb)0^<%=qS-!({xU6K|pK`vbt+m$9AhibA7h_3CQ9*4|pwG zKVv*P<+^COsIQh{C6vF?VwtRzt=l_e2iN<7?(`d{*_8rapV=qEj2B#H3ZG!pyaNmC z#TUB=$8A?T@YMOAzns5T+pyTR*V?Je0*^21Tx@~bQa$eN?fHh$g=U)W!O%TEmQMv1zlYS8a-!T&u(E3eAK@;c&id)&FFTQY?DtUC5vQ zTS~{WiO`d+FQ@~X2v{v;Tj9RZaH_&SI7`?8v^k60G2!A^W`4Q`O15SJ1#AO;5SKYfny~x zSJ&ud`eT9;GDLJluOmpd7lj@W#5aJ7(iX;%=hmK<+`&=t~Ky>72JciBz1FO!RB6==Q;) z*qRE+uK~5q;?hhn%d%=UM6PqwcEJ(^=fc{nhb@gewxzqHsL1Qjq-)}3ow&_XNz3igUZ~mL zEzDLlTm}q{!Ds~E?cFUt-%qs&%b$CN3Y0YknJ(5J=QikpEn6?3GGccslG?uAbANp^ z0g-;&1$){Mq&ii+_vX8JTUZuOrnC9@(rZ;_r^nM{B3YG5Ctl{g8;w>SPtVG=CcC3s zVCow+^)()WVkcq>k6!fQdvl>b#eT?9(rO_%MygQl%KdFt{qcCs#fmZOt|>R?g@}#P zVv^PsGY!cW&KL<_MOG2deBbR?=WqJ z!9c9tb=8YEb%P=rj;IR(=9&bhV5ybs0ZW=`6%V?%#UO+*hAiA!QJfxX1`VPyNJ=Kp>4(+Z9v0%Ha9P8+E#JJ{v`6HGR9z@VHng+WaT_Huhvjtccs6=4Y}lQ1k%TC_LQn%84IP%Q znmidTx2PSW4QBNCTAF28o)Yl(q^6v2yCwM z*6zO@3Ki!6b`P6hVAbCxN71eiT%F>VBH;CDg|=uGdF3iBIfr_t&B<%$Ip15(nip8K zY}Z$NW@r*#Ug%_FDf0B)@uqxTo`d=+9*vj0Gy5&W?|H89bUzsDxFB@SvRyAfGhIY6 zuhZgO{7}%7Xj_lzy9!IQ*4i%|9xbQM>`2s3PN|vlGOm0*20%#e=+|h4#g)D8u5XO8 zjK?SwRUY{{S$!y#j=U6ejzfLV9{a_Z_N=zJ9n$Ujj$PSK51NE-dGxgfjzZp$Y>O9{ zn~_uA4m(5>+{IDbLa`iW_LgTZ?^HUAK?iV0n<&5pVh!tU&zKssTb`b@N`Va@i>EZp z8n%{ljtoW{rbzd0p)9LP4=)LpSTTo0CVJ25K+{o8L>@qZR>syAPZnyP2)ejB&_q^0RhS}~# z!jR&!gx*DO*fK#a8$QH1^u&t<$xT$~j?q<%nw;1!jirXa48hW z=A>sGfd7ZaBj!V=w@0Qr!CKGVWb7loJ&iE}j&LCKX0lH1hkdvb*pSnMN$s5sCMHwa zuq*6+uQQX@O;fv9dqrQDN;lD$85ZOq+^Tt>)Ji8bUKZsKf_T~iGblFO^4cWxz?+-n zBuqg~3ICOia6@N06Bgd-s2!34h={S8I z_vXd4(Fe9g2iWG4A!rx1Fy75LNK%nw01KPv70y$ZiCkvXBe`z$7E9|fQAy<%Hp5)0 zryS6;gI0q6;QJJaB5a)*;JtD>DXMllci30nslv0U>@6_E;O$_PZ`6~&jxVmR;3Who z_BZ^skuiXZVj#8+Q16sUGqQ)2%JnH{w4tChP+O*s6dqT7v8(Fqr`Ni)8$Z($IehIZ zWwQz1Wmdr$lCm-reR57X1zH>9#!R>PKK{I)e#>bZKRK+pf5gr7JZ#>Ay10K*5m#t} zXy4Y*Lk4e6THXGN*-!7^a%KnutfRkJ!14W1Ezpuyu zZ?N>_xTegTZ{l(?%Pqva#)w89LJvX~OfWCox5+R$;4-~)l4(Kda*43NeuH}@PrSkH zy{%_med52~P22A~yCsUn_rhxzmF=5-4YD!JG$O9lCZLyf&Qp4mHgbcx5HlF2w6_JX z=sM!6_wWGAMl|$h47id^=viy0c^!j`-cq<@#F@nyC@T zRi$CS2o^IKX|Z!V9n+~#(iyc-jYaklO+L~;K7^=GIL+c@=qKkbAJc5ZCpZ&fNNQ)h zy}j8#_jLpR+aWY{BG6z8;#4xtmqXl12JY2 zU>4@Xls*zIo0T<`6C0Ww7NoQd2PtZ9iBN#cE11Hd(NjiL8FF#~)@0aIJT&f@F}kT* z9Z|t@|Kw-X*Y36b;H@Kq(XKqbc82E*P(N+c6;ktzL-J6`Y^K9LR_h3Bxtg&TL4K|wq_E;~;Qt`eqJ-A|L>d@qIkMfIsI8|M%C zbk+@x>cjtfPEdao{`|stO8Rt3kkO~>8h1`Ie~z298qvArYie3Uk)jV`#@gUO<*SU% zuL8O9NlQ$E%6IzAhch=syx#H5Abd|;46#0jgT#E$ZI8YC*M&$n;zQ%pJaU^|_1FlW z_3L=xW3Af?;^QAa9*wuP&MRuaAN#Z@^~iF-&36&rFQS7!vwB!xW#pPn1S+Zpl)BJu zecCp3nC{vJxko!iLQhYDn#R$S$pRiOT}gbtEP2bd{UIORWwOtT5}nvo_#V#)V`3(E zr=)Ab5P5nZx_V<>=oBilr=s^u#EioMR&^ zZt>etU)gmlmy_2Y*ww&)x;Kx2hT6f$T+^8Xd-z6N=dKRQPvJ>9QPuQRsSJD;Id9d| zKb&M?#Gf5vjmS;jCtn7s>&VqF=+2h;1<@a^Fv*82742AdRm7Z?vFyYxy4^FMAJ__? zxyZk>HE*X2jfvHelxdDsfcYib7SdD3I+aS#H*ci~x%`EC?@N-$XN#rz3sJ&&GQ6R} zT>Hp^n10@yJ&oIG(%p+=r!E-}vtUWyZ^N;|vF=?Dkl#BmxJ9MT_G0W{)$z$4J2i*)Tz0%0XOLwV zxIb?1;x_us-p>8;-<02u-aYcju%}OxvusT7I-8W6RoMQ6xPDJ-~i zQgIr-TIUEeulpx@Pblv;Y?KN(Z5CkCN^$*iZs;**W{@mC-&${&E?`!>Tf4y3{!QZl zRrcLcO?~Owl!zdx0i+k{5v6x&(u;&9NCzpQ7eOR|fb<@a-lT}2fPzBkgx)(UNbe}1 zgeFyr+?|;_-~48MYi8ZyFIF_1laqb+dEe)Kiaww}t|8d&NX@9?nnmO4>RWAao~_aC z#G3v>neu&P`ma;?B5jzeQgm|tOOIlnCJ0;fOvlH`TSbWj>+zqOz`$g@Nm(3}mFswU zN={6&@d)Y@KfjZwyn5ip^|jY@ zoxLtzu!JWABE3tCUyoJ$F7AoxW^8M`c~%v(+1Tf!@=8jIu>4r#2@yb=KMi~knr9RN z-NhwA6kxksd4M59<@@dAGS`HF**-MM^zM%nH|Jc6Dk)B+A5{7yK1PRQb#y+Rh`=joXAowBZba!<2lVQK#*w% z`U;fi8Kt}#pw?}Sl_U@Rdhtq|+Ml4Lt|&yCd(X7j+8h8?acvZtBfa`meaG3aV90Y? zLF=%WYCULRR3quZqhi1@4?_glV|>tQ!p%5`=Q7ZW2nxUHX)y2z)EY;2ZlW?DxFW7> z%+`Cp(`K0X-8(+4l`=o?nsXAZ z0*!ReVw3Y8pBC1l20k@rFbL0_(bE#C)XI3bcxgV;1=G(*AwAj`(&@=$v#|=m`XSSw?=2mTCi<%i&fFCQHT zm(ulj`YV!IG3g%H8v${fkJfbgaPdGGbC@`51FRAFW;i!!aK?J=%gC}aqHSjGcgpgI z9_b%)QFDLaSE7ex)i~AgDi)rf)^k-bN95()C3fZmSICnAriZ8R#<;4q!@uGn6@B2rkQ6FJpieTr1gO8zkr zYQ{}3f)0Edz!PRjZ**f1S_fZV*Cq~E>;NIf| z?3A9csXo8>QItm}FGiX&I|5&i>5ztr(6P|LBDc~WFivRqi1udy8@v zovN7;mZALenY2X49wx^rfmKRNP2i2HG|mXS5&Tjedm{jMiVN~fU8xBiifY9Thx$fSWr4YmM= zdGMacvZ8&q9|$c%_%rCs2SSKl?D*o<*1^oy-8chaN~$z?J!zZIg{Q&Nd*Kb$;C<9Q z%lWuuscuVpoA>Peq$0`gVSN%?QL^2=K0~h`K*@sr z)~_e``=A8PK>}xtbQlX^*xb@MpyFoCd=Rc-cZj>0yO8*Yvj7q>2B;A!aTmR_Beb4B z$4dCJGJ@}BXOt$V(r6*REPE^6nsv^=fPQVw;%7DSIRy%#HFTBi79bP$qkr~uRy+0jPutQD?V7vkdvGFa!=1)% zM&mC_j>W4W9&`OKshM33vd)_PNN)*q5~W8xH6OCrtq zS~r?7WXaV_Bq(~({$nf6`BCex4z<6n)%QFkG8q%-71g?mh>0MNeuY(N_z$33*1?;z`OU^u(-;`Li03@0DLF!+%Ai=lJ#p2!FeV4! zd#5vQ5LB{OwvCp9yr7-m9=Dg~_i-y9BA;kYq;Zqj1*&q#Bm0m8=(Wp3lT4S}#O~$# zNKMDzt!nyTRGUpuKt-{T*$u7}Lt(b}JP(+tC$6cGJ(;wMtQS)H%|;6kUrHz#zU%k3 z=62ls>G(~l2OiTYc?EW5S-|8BQ=bP)gK0O+cau5EYQ5(Ss>v-tDIfuzZ54MVBLpmQ5B$IWT4nx|6_?%3FtYQ7vN z&p8||3UpZ*Jn7Eaz~RAj^kOJq3#ursMKC^^O4n${;4o&`1~*>=NAX_DkI`v zdtIIk4J=#VAy~Sc<6d-LOYR<0sW#8M;%%`C)Q%Qex>t2<{V9oQYK3XKi{uDyb~--S zw7CXq@`uBuZ`r0Or6$6+j9?yq?k8CXR|pWh_VWNi*z(5Vv(B!f5=T*aX}vw0kq-p= z3pX%jzV`*TuD6u!bknBT!`m8Y6pnOooRX`w0joZzIvj#UR3K?pg3v z7zZJ00zA0WjRg9ICpe>GzNK=6Du}~Z4^!_LHiYRwKIN||ENZ=0G(IGc;&As~J_P#A zaoYrVcO7?BBS%L@UR!h?&R(@IT3x0fUdb*1B()n9s9Xg$c0Hv4{`j4j?3i4dp%fUw zpuiM{MQ9$_%o`XZ9$$bV$1F`qFfF-tRKc-1Xwd+&VYI%)ytAcylGtqLd_^e=F=xlx zS_!Z-iTqJ8#T=cPeDDlu!2=IcXj$ufCFc;)%19ms<9orO^p??Dkx1h+3LEJXs>pP1 zv?An`7BgR zxfBh}B%49um#Z0P^%ZK4vv=R7O?F|61*VkW=3x~mK~13LpUVhu6SXEp9gP9NC&pj4 zOVXPwaM&+B`qGHf^W&VGf8ux83@o9UGvxh|^o``*G`3_RhNVWj2)eL6RJ0%?tfZg5 z{WQ32*;8_?#tv39_-#vf4h%4pSaeEUIGv61gGJw^ILF;yH3_|PFgN9szF6oy`Zn$~ zkYl%UHB&u^e@RjAYs+B3luX!NrQ+6Nuq)0)R2HPbBGz&wfw5mLdpOT2@uwpQ))y1@ zncz1M`s2-luM%HzeTw^5oRUeqS@;oA^9wMzpf)OHEvLE1HRDq$7bS-$k8djNhoM~B zM#v7F>7~^}GB%QSlYaA^qqI53jL5ocgXMgIlOUfX>GMs149!!mFonE=c(el9Qb?)j zYVYhHE!81t2(&Q|P`|WZXlGlx`7gVCXUgs4Nvg|XO33WEky^^aY zXyrEtPWyHW1~W{8z9*ztsPOQZ1=N+~^$j^Zq|P<)Tnl}}#tqJol%e%vAwF|(w>v!Lq_L-l*D-|f=Xf2i1BO_-C`Ngz2R~AL7=zQtC zH??;C(%%7shng(Jfiaw99cm{1)7;%AbT%5}Sb-*Q^lrSGYmT~FZ21(X1pt^ok+*GO zl26TOH~MCsv1BX*S_FgY>RjtXn#Ln6C4wvDRr>2kY`+ECP4DEXAP)myS6_P+xH9Jf zpsz`Am#q3{a|Fuebx6~;&|o?N3Ji@K)>O6Ar>J`beY1MG zlL>cNv*Vv?FO@Thxnxk18@$u+%W&9LI6%2pfMj`kah(SOp)InpMK?a{xd?}jQrRTN zH5waR>%>EaRIjdP1q{}BZ zDv^N8=Li=EzbZrZp7}&tG8l0pepb5Ae@&z_Vty}jQJU;Bqr9uM;c>1F8Oryg8Bj~% z$XS>c)*Fi$Ci=6KmoGPRdFLxzF?^xlK!h0_t(5}jubm^aUy)8yl;TM2ZI47$<=0_Ra#ExgUSz~c{4RL4R`KyTAwSeI=;+?37P$I9?*`KxpKJaubkyF6UAq;GD%tcr^Y- z2#+3sq4=t>s5OAUGUwKd9%Pqe5p}MFbXXqWFc!8wlMjsChSTzTN^KM#j~kB=2Z%ek zite3A&xyu-TloWq2yr<&BuPsaq`5C%h9N5`#|vKuc;wzoU2r|4%>TnPq!&{O)7UZr z5|C<8Kn#@?S#y}mwS-p8Z*R87;$^K75vUB#gck!$o3H!|dp`L}8Yop#%|f4kFNUby zR!cK`oRckUAFu9CNWvi)0^5Cr9`E1dd}?0-w44(lQQF5aUe=zb{}YFSi79WB_)TZb z>~&CErH#5&!~^MTt<+FAkSm)jXrNxXK4m~SrrF-aKVy(4^syIEZ8KV1%xv4LlD-gJ zWj_l9=5ESj4`k!8n9CGpf^GbRUQGyGlB4$u@m4Uf;~wDDDTF&L%I;as>kT?8p4)Id zuLE6uoKg%L%M$cFeGUJF3FfwD)fOf~*MZ+n+Ql%&!q@4W6;8aKvvD1`UAl=Xz%{2q-JZzJZPiEOA ztQ6u}D!WLM`Ke=k#C-9EL1FLRWA63!Ard6v)pumf3N9t@-Al}k+ot7`bMaK^4j^mG zpg}+vGLg2f%>X5wvugD7nedS!Q=+J)4C)G?dZyjwr?+}hS zB9o86L7cO`9>?zd6%28u0{FRa8q*aQhIl5sr!yn%J#{f&?r(rOa=kb4`M0|Wz0a2+ zz3w+t%Z$b)$u^Q=^nNme9l%)W)olEe@n$Qj8MJ@pQ07S))7W( z^62!3!m(LK@80(xLp%~_1ZdP}nM(q9jRlxn9be$QGu>ok>N309bXLwm0kAFC>4;0d zI;FLeBJD-#HFXl8G;V3=q;|$kc{&Rr5!VzIi1;GiMdeUKNeQLd=uIp;3{n&@&2~j1Ta@E>MOJq-MEwTBPvn0SrSr=LGQd_o8gvuyC4 z@SZW4m<~0{@_(TBxGwN^@wc31SdsBJ3&pi1;N<&KQNiR#P0V}y2YyWRG!E~4WG&al zN#fhqP5B*JMxgr?`EC5A1+PxoLWLt1LVx{oEUbAUbl}2~zk0sHx!dXuka@pok4{i6 zS;$R%uO`$Lkz)GQ%;w7(5lD75p2k1D#MPkb&prHonfb|2(KEty*9e5EkE7ZZ98^@K z7%OFa);$LXLk(D@gy(NY!72bf zgYCFaU%C68zR9|RwMdW0?TntNnDKG{=j+1jiB^3?+>#(W*h+u(O z-zAl&?!|REc;b&^yY$BrHxn9N?n|5^cF9|#muzk9U5rx5{h@a(gZiM99L*Py?i&Y; zQAKZ+2-qb{#~T|qJyt*D1R=mZ(Z;D$@Z{>obYra7Mld4Ptx0CzxBJmy=$|Py>W0zT3cFI{jf@3lv9I=ZV(#l zOX9<(D-RDVzU9ARdq#gO4&_KnylXLTxoNcmaYv42>D#oouc4c*8=zP9}sMAg&#MDz@sHWU&Lb64`yLKr7NpHJAB?Azz(KC-AU^u zP#C2Wle4|IQh!vc;2C=b#eBFP7-CBtB_5siTy*)cgF8&=?Yi(jPv3m=Q8#^65C=2h z5WyJ8#W@qDltT6h_R#rUx7}b@63XBbu;E6BDeXqy#9li^gO^6v$FNPDA;xR_IrKAsQ^k9#ZjCXtD&~bmgE=u6c?jg7~U8qL=o2e)A7711_b#_Mb{xp#Y%i1Rs2hb*IprqQG6;O;7*jt7QIhyX%(;b*hhG3 zspoX=)Eh{j!5lQQ{(eHe%)=GJFi4}~&x^9)@62y48}<*-!#o6>iY!G=yc?hDn!FxQ z&5=w?iT!|9uu;^e!!K?eJ=9}$vk#7BdL%%w@%obKQpU<$IPoRH7#>=PLI8CYNZeJK zPLrZF-!Mrm)xMonXD%CyH^<^37G7!#6sumUGQf(J&zYZ^&+VuN`(4<7c3#Wc!-7vS zCb^&p9x?Xj_#G}>31jIR!ZB6PnY8OK?;aHu#^eRYpxtNIpF20{J#Rd^Y1f|W213>e z2!xR2RueaqRDDf5lB*fm@6d0!19~5_Ed`BbZEdgzmb@{gI{@W&B!-gHKf^5GK!9QG zXk|(q2;jFBs{d7FtY^qXa^u6&GV*two-*d!aB|ExlEVYD%FQ`Z#OZ6R4OjWq2AuLR z@4{kdrXGedsc=Z#>C3&pHJz&!TdAaRg_<4_7ZGAfH1axnrn)A}tOarU8Hi)RHYB^y zleoG0;GC4wGQ9z(T^IEwxMgE3;(_s}ujswB?MY#i-1luz4fdnhIXI?FP^ zN3hh6tkTCVCr`=G&%uE1Ni1gmaL`g)e^$$Y0bRg~kOWy%WJQ{FyY3)Wh%(N_7&p6* zWl6QA2?mQQyF$8=*kn<@2x~v}^<(sy7+6#j`!&4scmp-rfMa_{hbp@b-c7?}gd?Az z!NbuMUoiTq0SPm^haX8hf15_KC=l2e=pompOWn6S|SvDjiam zX`CIs4+k;4G}%#M+tSwTBm3}Me`N0+^^sx+IDbra*JxEsj@Rfi%wT*CH$K09>E$*) zWk?8!{^8skq;C{vWq}n|`X(8>z`~6AtsB=or+{Tq{XJ#+4unkagIT;0dtH#^Mw3CK z9c0VhohGWOJr1Md^~Cs78+(!#R=ws3w_>nRiXx`)y=(=(A+S;;6WLeHY*pagf2?Ju zfO^^%SIF(%ELZtb@42)KlY$7&qeR4_xZEZ(3XCv+bxR7XK{D(6)^uh(C7s^0QBXz{6q3 zUJyO=eKabX&;640XHPK7%GpY1AtBhnxelGx41==uM?eKALDnvqK{mOo4u_SL=8%zx zRAM_K+v=6D+pGkP_G&e5P#}Z7ZTJCOv$*;Q4flx{O;2a0;{vXwri(_8Ejw?L7nh6P zF>dTL5&$}ZblX&3^FD+kksZk}dfSv-eRkM#9Uy4cz(H^g`+|dl*p-`<2*I6bdmW$P z0W>R;epx>kKWcWtXXR?``Vl}TCjmjo6-cFq`R|Jb=5o_&Ny;AaJhdDHVZG^ev93YB zj%eam!ZhcdMr#H>{sHyF1U*ggNp0qEGHqpipZuegV!O-1?>{v3%P`O??nq6s(dsQe zl^={RjtZjAcFPauZPaLVT_CT&2HM}2HpCAVpZ2{d-fADagpv@CF2FE0e=Dked;)@; z?gZjXN=045r18vuIYON`@(w3C?gGbvSqZ9BV7$RbB+23VoayB=0x+M-VBBL`{lhY& z=2Je?cKN0YFavZCya1K-K3px}=vda~cGu>C(^w^#ZkFmL$BzT*G|cHmPw(?6#k|(b zjK3wee2Od~Pbl?QjE}R$ayN=y`k*@}6PObeo$#;l9~CF*WFokkv{Z`srA#gX>L^@e z1ye$3_0z6^6h8O7m3`Y;p=bLJhVgevJ!u|CVv_P-y?+}cS3D9T$i1fnu(v^I-?vIN zs^80Zwb8QN{?u5WE~!iRxTFSrx$=~E_pP`r!pmmKiNff&(}0FUikxIwnc7Q$cO7AU z{p9^9U`NlLrMz-H(>mtgm05l)rxQ}1a~fnx)X6SQ>7(isv4a3fbbKBO-uE29Y%3r^ z1C-+5=6M@jfo2IO6mMS7>0~U8^m$wT^^4a+*h$^4S0c0!;FpK{quK*KOy#DmncK*9 z>2PmS`ID?72$m?i;BLMw?{+z$L5)Yx)f?7L?7T^2B)TwI&k&6tD0U!%5+5i+3tJ^` z?dhyCU6{QRnfeJNbW zH**hbIU$J@S;Q0C(bd zr|*nW!ed3eumeq;7r`XR6*w*n>9>Ujt1TZITKIMW8$OeTYNcCpL|VpxeJ{|@()*Fs zfs37a)mCu%NNvgy1k!$2;%L0VPB%htk)jmQhkhX^;^8L*X1%(%azyQRG$L+8hCX8p zleL6GRu$sfgogc5*muO53Rfe^UVC@$enyc!Lm6_Y4P^UW-;ET{MXbF-2&J;}_yC>Z zoY(?@B5ER;pWX7LH@WYmu=o?0ewsn=;5$C&85hn66Lu|$FMvv-P^4)23q0W(DlTnP z$xxm_wY4(=h3=}en0w~b%xX=w8}DHaGq1PI2Bl~ip7ixI+RWJAXI!9w>D%Y`)LSh! z0u}H@Wk$z&IgoA?3)CF~PdC(B5-20SRT8V*Q*l;CpELZdl-O?EGqZFn2IVRC6lSuK z;S7DcO>+5lD(Us8TRBx|%vTV``V{}zf(xToX0@~hVyFd>xn!bAP37e@d|=mR$81L< zocTTc(2&ZbW20pxQr51Pj>il~l*DcxDLM1q^nU#fy-|l~p2^?4k%X$4&-cBLJP3T} ztg&MYP%N_$B2=e)zVimkcq%pO72Fs}NqnRjW``}ZO-%9&|4F@ewg#6DFQNUn)|@nnjC6LZGz4PdJF#1R)K0 zC=RdLN08Azbf}zeJ5oG%mQJ(8xP5cQ4)s0bdYQHKGBUnk3Sq|49*G)IicYFd4c-T) z&CBTSNW0H>tQZ^ovmsG`4p5s30+4~I7w1_(Hl}W?RgVbk1$SIk()tr2cC;rX`3aZOAi{~ zxy>~xtUzsSHsKLd`m^2{wLAS-S0NZpsEr8+ol%PBWvNyt$y0cS$~3mDv}O z-vB7$!&@AmHSgA(S-k(FW$(xJGB-5JjtR*GhKz2-Jj%Gdi ztgZ(P8RY|+Tn(@Xk;uCgFm%xoHz!BUXXXG{oYgo5%%?Sa&%&yg=vBmV?XK%4@S_E$ zS;B^ox5!sJ5-C~`njQL|Ga%NWZ)_O+FxjX6YWhz?&9j%I(#Yk`O90;1uNHqgiFR>JdHN!SXk-)%~W!2+$f+Rs=*yj8c z$pe;^iW*@!(>7d2ueh$sIOi><6B{@Ek1_mvGkH@JJEw&bi@zS?KmXpwDTh|55&@Kt zI#64B=`!2~^T=)dYWP0{g+R8+B2R$RWF7n%?cvhS#SXU`%z+u))0r)Bmxy1K5>HJf zc>^h++lDf#>>~(uH)wFRp12@eQt^)+X?XQhuEXPW>-xS)iL#V%-6TpVL5gb;bWa z(N1j5*VQlMlp+=9*Gv}_xn3nBsGVgP4~|0RaIV7dvX z&jw;t;9^$~KS9j%1Fw0Nuez!Kl?4;fv)_W_T$rf-<%?cS#LkXBR0?q-z08gNadlXHL8A{F(Xs!h zpdOrwEu?qs518LifoCOlG4wj0ZJD9xUvIyE{?Y$%ZCPZ123q^NVa~&U91XV$TfvLh z-PhhZ{>umbKX}@3ssMX43dN74f3@R6+yM%5jhZ#!wN?rW7EV(VbMwC(?LVB||NAGF z@3_;v`yfZ>FK=X72QTv1Gg~w~EdeU+ZeZf+bQQSs)yJ&&|F;pak9T%rkf3|8>OuH-! z>|9iy%6Nmi#%EiMHJvkgQ@sGY>c(6o$1G+~bb&>W6T61<-zqa>pzrLKn0bk#2+T_| zb-LS|1H}1LdGGH#RzD97M(bOHKvf~^FlU{JNb8k|qe6=v?7P?J<6==FZ12l$MbVtD zPq-Tpe`x7OigR|CjR&oeL+P#qg1)0yON3Ok5|5xXJbPVl*@NBi!Q}W$wp!)9<$71z zuHv;p!DLPQf2`pQtl{NKD)X1+O3d6-GlM>+?Dw66&Wr@#0C5`*?EJJ@c36KU3~~ zEOc}-!g0!NvByNIyG+oLvuki1AVOV9C(O4c36 z*=d4K64!cbl$u3dh-)rvuBp#{K56Yfo>k43TDJ6KStH}!-^!bn5zP@w&JyFmxp4z2 zW*O9Ww;Ll#|b%*7TC*`v#wI4AGI~W&k(;ipVsh%TrWU2E0YSHQxP4QA0`)sNl z_rYzu1@+M<6Q~w%x-fn%GHlOCu+AE9VUgJQnS8bVm6*=rs|#oqZ7CbGMoMa4@8hgU zfFl{#rQX?UcAvU%fi|KnCZ!fCbA@t-or^}1&Z;Se2N%qbqm)^aHXK=x-(jkn@Rh!t zvA?|RKHb`mzb#@1CJg^khn4>MXE+u?EJq)B$MMzASRJ%%10E%Pt5Y5tRNBfGd}7JP z!g;rgoeTT-qE@=CFJCY;$Ne}PM<0OqaWcMBRSu;Y-#vIFNyWlL>tkv^RlnS-2|8>u zp7_(7bNe#r1v%{eZc~qkqmbBZU?k=kwW3TuJP5iwm76;2#cQdPSD{u+{gAy_aQMgW zLw{>j3O}rKiVx>~j50A{cATXaH!6aOvXCS=42K8Z?Y2*~8LHWxSg;(RCb1~AVB8?I zn+*H&h6TJ#>9;A9)rvb20m)PE-*G%>QPhg|7hl7j-xs*1le$scXuJ<|vtBrqD61_& zrz>i({Qx!jNjj&Li;IV^{Jm%N2O;nrMZpIk5Ht9dQf^|%39Q_;KUi)#(w?G|g55_CT^Ap-Oog7a#rfj{6 zdc1HzXiJ7N1pPW!lO0hTP8h2SR*%D*rW$QYse@z+mv24Y zFBei#`wx*>K;#0)WGj?(gt3|+a!bd1KGd5b(t0gg7G?8R^$KHI*|RA9PXt|h^!K4QxM44z$8@u7XGg;KtMpb@xzB>y4^I!aIk83a@t^wkA!_s(Y~VkeShy2zA$7dQ}$SQ2BZ5Y z8jz5jbsc@Zg$CxMU&7SJiYjPR0TG4-yG3y}<=3TX4uQko{{K7dV*hi_t1SeF!8z@y*x_ZCPjWlpsMp1))&^ zAHAz%R6$(k*Aq5+AM)?YpG=dz&Ec}Pn@RoWRDR>D=o2ym_ujf5Jc%RiFBu0;(|1Ok zeDNR7^%d0t10HAUzC#rtQ9lWWbgWgJ?B;4UsJh1M(pJd6mM zs_>2hyU8G^$@_PG57!rc-r3KMo$a>TTsLSq6`0|2RTcHM?JXib_;HeU7tRf(UW3w^ zvsIK(_u_h3l0dh9nzF~$H9WW~&(^20Ubtf~OVERDbKAZipmjfFf;7WJY&aMFYz5XY z*h4>v^4A7NC~@W$YYKWFB$yspp0tP=9~S9hwAOg>kE@;lr20SPEoAubsMtIYEOfA& zs3s?IR==q@O18ea-V=H*Uu)Z%(d*I%PaS;K0 zf(&GqeC#my;0x4^$SnU(#(25n`N_FF7j$s@y~pHFVSDaQq_d%yqj(Q2K|Fhq8dY!V z?ZPu`h9y$0a7J+m?`3T6d_kO+{elz#0R?>m`fBv zYl#+RRlMDAm0X6+vfSK7)?O)gT;u)gs-ncOMx~s1O;myg!G#bUcPmre4h|=VHdop> zHnWRsWm12~s-SHZqSfOC!gSw$d#+5}Kbaw{nn+waD$^rrd4NY?69 zY8kuBPB*Mtw!bOb4MAnN>*Zbb*7DYLTz9O#4ok&x+t2ky|#eRmxBT>hN zPo_PSrMb0PZp)xFuSfBmkkNFaKr=bM5LddaP}cz&{#9rk#eXUMQ~8R>ctXNS-s0J+ z5eV0OHTs0xf?`F-v?6?wvlR;}D1i&JK-razmv#!J?au<35DJ#Qhr9Ma8x!{!Yi=Fy zeP{rcZ*EVITA2K`u{uJC(Gm&Ez5>rH6+Tc(I!Q~=o)6-r+SE)I_5 zxSv5_GPghlCNPB4%9ygnZklwSJLgv$Xe>P0B3G}!%6en|_x_)Nx`N%$tCbP0mw&`= zcPO#y!j|-k*Q2xEyxD(w+QOM-#d+GXY+o!+V!mb5m$7Gfc z76{0*OP;zeiPfwx*QcNG%vqfpQM`J!QxvDn`K8g*hXIctd}Dr$yYXTOc1Pbli<12@ zbIMrZV)X2|ZoQ^UaeAG5cf~Qaw~6tg+gq~@fTB@^uty$unljN92Sy*!#}n;VG&>R? zNq6jhw|(6H%Yl>GKCjwz5B$S~L@$CnQ8n9~d5Lo;OW5*yl`1sbL9C+J-J(|UAk@4{ zb7Lef(mO3eh$NHS8l~)Q@QeqYJvT4N+R~Y52XV8+W$BKWde(?yr3&H0v268+*bQ*k z)LWKiFKc#P%}&_8%XQX&#Jb_4_+$(Y9rbJ9KSI!8uW?r5M(GZpu=ym!t%IoIgFX>2 zQ$>a22YAn9f`+x`MA2|W>T@=l6@^4UMfvhEr;hQL1_kQMi`?IjHH~e+y$1DJM0;Y(VYHa;T40?yi@J;0m49JQ z8F((KU%otSWM<)^yKz2mGD}NStBnf%yDh0i4+2_HePA?wj^3v-$gFfc^OKCQCOb;` zRwv^$BdwiYf>u$1d`#$37rVVn-w!nHixR+o>$eD)W(1vGJh;)-5T*}Na-DM>GH zk}D#^Vd^WTWY(Hzdv2$HoqaC(r85uBHvEq6?!eO&O7UohVpj=p!2=rB@3^~;bp)yG zl4v3_{e{Gm7iX08N58zLvsKg4 zVe5?eSlEhAB=HF^Kf04&@dq_wS1(bhFLYXQOwKo@zZ4nyA{#SYv`T4WI)?S{-|$6B z?@N@y^kIRacOzL%+RXCF{}#-#SD?(eN%QU)RyOeyis|~|R|J=O-)g2r$yW$1d}G?J zYoqa8%Gm!e1<{+~adUHXSPj*v`wlwljyqDAD|94{KgIdt_J$LS)AQL!$11w3F#Q6B zhCVz_*QHNOBOmsRCn&YQmc9LRZH~35hyX{$zgC{{sN|i>d;Qsg%2bD+WBcTFH8rU} zPO`qTkjIJ+duEK(4Lm(~1lyYpmue8jFf>Oz>PXiXODg2an<}u{WyBSR6%nB0g3!sI zS_v27Qeep41@;`KtqE@vYQ6Be*X|`AcOdd!1_F52iEPTBF2iIPBR}evJ%l$?=QhHFNn`- z=W&tU*3CBW+AVOFg~j8z*ptik5kexgO4ssJ=em^KU$f#UQK}daX=PFUDb{*6daCN1yYCM0-r zo3`F=j?yi5LHd@b&zyZBzq<01~r`=Iy{kFB)ZsZ}R@V!I%G@ zmWAAE8sqAk^w9NWP0D>^ckUi)eWLyZ_#>fLjPVfDF^(0TwOY>ZaS<>vF-fay00ckG zb6fr1R43ms1$2nsocG1?1Y&83$-XwSiP*Kf%j!YsEr$@C#v`=g#p_NYmW};%TWA8- zneR{O$}`SBy)ZxVjq}OgBZqF@yt!{oAxB7!&BCI3D?_aL7&*B;3$Xn|Aj=+uJLueg zcmn$t=@J#@wSwTmrg}c6_tm}79i!D!oXbUGV^~UE(Fw1`gR-nt?0^?E#FgWgBla96eYi0v;&DK{ z0_VqDkWav_sI7g>qVT8ci@-ohadGi`W6kl6LPXiTA$49jU-zv??o}XQg1T229?}p; z_{8v`YKH~SMgehZU*ECGHd~=U*)h3@p64{&7;S(Te>KG$Ahr5p-fiFDJ*ki z{gV!Cy)c6;w3~9Q6-Dp$`s2Otc3@%l;bUZ}GK3DZv$qKCuay6^43bcusjB1t#WWy$ zK)*>qc~+gYDNdnYb7Z73CdO*GjGZ5L93VWw%4eyfASf5sMP{OB^s&$*w}G zg^N1JeCs;QX()KR@KJrwZF>;aA-)pAb>`(+joG_q$N29(b9Z;AJdnjiLYzH3c=FY0 zoXBJR4h&9-pbMo=Q6>B#sE~hrr`zzgc5kc~qPp3Y$9>ab5u4p2@oMXK#vB;y@z$~q zi{fLT#MDtB7C@1-uV24r&FW@iqBOUlF!Vrd^A8w_nnJyiot5(wWs~acDQl0Z^vBM` z-5@x!6hkMTEOy{AZYsKEt3Xb?WYwZNu2%Dsm%ZjFzcH$+Tf=$x=(uyht zVUxI7R7*=g9q@q;*jUNE&DlVMxya3xu31f)XXMdpJ5taIhY z-dbG!zOeGhDg2L$kQc|*T<|8hc8dwcr;r-C;2x?BFI0^l9r zE?>KS38cM=d2HKx(26bptf?0TZ_m;2>~8+#akak}Cz^*pR2xc_ZdmK?RaPosGjUit zr%)+Q-oB*(!kpPteUwE5%H~3x50(8Qh>`$M_U9hD(%8HGY5Pa5)_$aZJ7Tm0g(llx z(!h)dHqLRg>IKBVQHi$ku6*0Qw1O98WM#EpCp|fPqO+Tn_1COSNgTf40g*HR{f6EF zgm;NB_e{ge5_?6j>PJNdkhRH8DisG$>Mw=czDdxU#HwK1LI>W99x{&Pw>D8$Q87y? zO-oBVeExtE69Zc&fn(Qu!0A6;#O5vrJiZhB0)9XQ|!u+ z?C0m#%AST{AiQP4w|AlL{92PG82fkBtT08+e}jCM`{VS=;98@h3XA z+W#iL@eZly-1+ZHq_7YqX*}xI_V)He84Hk!QeH9oI7yJMLTttZLE`f!Zv>ZCJ|or_ z|G_*p%;H(G6$?^!+i0~uE?--pzIsikdsbW>x3WUEJ?b=p-?`Q1cqM}$ePuM0#YjxM zH_~vLg@xrb6Oa<^Y-QL5!QP7|fm7tl96>R@qGG^ouiv|}*}a(7eSW0RBW4)0hvx=A z&V1HyP#-v(VmVla6cPi&-)Zu|MhzOGE;hy~M1~F5#$g~?%Ahg9*?x>68NdvW3>nIr zW;O}lLBN-ON=MrQ$iXq1+NQ&?%kgOs_C^c2ifiZd>)10bx`T{@vP=1iNyn!jc*iwr4)H4sYcnUmp`FS7k4Jv9f`~ zgZ%=y1|GcXKz1J(>T`|pSe)$O-3|GDW#!~!C!%bs*{OJ3LR^~@j^*%h{XNEKz**8cNB$-R0$&>08g1Rb{ zvaZOW=#@Xeg@XM$o@tz%huhO*l$k9p)^9p*bmknMc}U0Ac5Ud_4tP<%^?K$f(K9K5 zvh-Q)D99JP9j6Ns$EbL1Guh6K=(C_eu&25{SNQuvSo~fbn8I9w#x#3u*ENyHEZtSJSkw#F+O-6s{Y`x3wcCRwt@Ak^ZwW$P4-&h%|F%lFee< z!9z6a9KMNalBcvJ?Gcz9d8>4%jos<^leLw$$Boba%u`@v@2sXCLV?-+=;P;p`QkxYoZ7t?iv9=jO5)oU02 z=z05vs0&eoRyJF={cyOHOV)bjdzb;gdiCnT!NI|0l{+jdCp)`k8eZbUVJmVkZHxC< zsFQkF;s+y(M}{LKGXp*ZYEvR);y$ynzrmhf0beyi{ophd1#dzIN*6ZPSB-Sa5MY{{ z8pi>qGth8V_%USS^(R{sB_UL<4X5!h_wulo4QvfA1Uj@lN|xOWqar8$N736a6esY~ zjq1H2uPaaa?-QcDvN{-Q5Z@%+frceul^=C9sE>tsUkWa$hmTh0S$jZD z(RQsmgm(~0bFQkWPyp0j1s9@ohB+eLx#4;r0ustnzf-d3lLw|Vp_q8?L~d{CIxDlm z*D>v{)ZOYj>2HwcCAR@p;pEmp{5QkUoAM87&gqE`wPaiL)U=^n)rg~tjuRvMGH2_e z25wJ?Yh8bH(Z)m=aoaA6boN|^@n$iLoa1@7v$bWg63+r{OuI2CUHbF_(xr^jgyNYQ65 z>nqM<0gtBsCqKO}YJ(YY+{tNF=Xvm?1YsiY%<;RHj=MhWMGp|}zHMMcbO;v z?ztyR5QYs`WsTaeOQ1gZL6mT%%M2QOF{6Ce7i`Ex9f@d5osq^12<3Bk-M;jyIRaKDHX<6;# z8X2~C8f#u#h=1#llyD}iefnBe0E<>mXtHzQ8ci4JLP(&+>*Rtq^|}@VhndAr-l*soB0D{%+fSwzH+vTXY(*yui`C zsXJELbJxFk+GeETc*Qq&#~_$EnJ%8fLMk*OG$9FXHcu?au7S(rPs(eZgd84NaT*q= zP4kx4)S+Kq?RlSE6k=bv)aUU7rq7KoO+2=Nno}IO*7M0zUHL|M-IZtNDvOify{jtl z(-B!7U+H1m6z(`sPf|-C&pXP?*T}Z~c>&DthP(qEr{NW+AU>>w)Pp)CtF%T?jW^JtuL1Js5 zEWmoB#wfb)rPgeM{$K*t+r-563!jUG8#aJZ7$Q)VmaeS$Fc0TOF3*mAOE(${aGJL} zRHL(5|IJ12(xhCjAKe=xk|HCLGO%HOtC021Tq}c(wPm_ugmI~qwyI=VcIXRNP&hN+Zo=Y? zNPpioz{d92bwH6ad4WlCII3gnv|O$0ZI<GZR6# zUB8#z_s3Ly)2^G248^YFiP_P4d3h?nes@+VwQfJ>lQtV^c=a5=&7V%#=P<{Kx%$bD zY>NPXV*BSelKoOvA?467_dLP@Wbab%!vlR?wmr24l&qS~%#)|$@~2Zi?N6;{%P)na z8lgn_`B>xG0(C2*1dVh?W)>C$AOdK@&oAR=UwpV*{MM~oR;=1wa{xWHs-`$oZe>6Z z>0Dn;)WYT@xrEB>I!6O^HyxB~L)DDzkmE_LF3Z)|-*CJ+f)ABjAEd@!6||0LbzIkf z*2GT$$6)>>I9=g+nD0ycR{to6EVad{F0I>UWShyNhn#fj?zuudK3}ZRUE&*dugyW)dcIvc-maBz9uT2^k{qyexPnuv}FBBnk5Gn?;Mgj{Ce0ZuB_9 zpoqmVZnN&Q0bqh)_tDqb%NU=;Xo##_JzKQ7k@r6EMd?@9wHU8=%n>*Jo4(RPi|b0% zx`pd%hlDF>CwahC=wG*LS%edDSQM`>a5&75e7&7s8*=`&qn4uH^6cRAM_v9=j{+8N*^F;t+8NfHzjy@w?gpQ> z*1m{**51YOw?9%R6#$yP~t|V2eJylDDuqTf1m)%pTfj!Bjdy z)`P4rKRl43Ff&D!yujzNt=YnpJqKuy3QXnnS0pnubibAj zG}Ntll*q2Ar4>q4$P~B2^lEV+b`d$7#V8ljoDjFRIMR4B3sQ$G4eKPjOP3gzBJg|v zCnD1yle*|VHira@pgZ0dY!u;EytzL89KSPkd<V5M*VijH7Fp{5RV1Nohu;BE(=a48p$_x-+~E& zHf>uks9$-jI~k=TOEPXXoxiv^AVqxL(Ty9Iw+$L!2A{BM3EVeN3$)F*YmWAy>B>PvjVO zXGv2%H_@sU(-g#Ermp=TTXLHY&vS(CZvNd@bPts zN2TJCP@er9HnQ;rCX?psMIwoc)YQ~?ZSs7kS0{`_LW%NR2U&F8>RmVH8X+@gtiQF@ zncKDpE_Em5Q$qI}n-?@#3p(LmgG`c9(zOlaZj z$%P)*O{5kBmYC<3JTJBYLee=GLZl3(WY-DH41#2$0#d}2L^=7IK;stPyk3h98Hi7q zorP^Gr_n8t1oP>}mNk$EnJP#B=$NR;PdXEuW&XbzvinH;%jsU zJoEVe>8T_@Q_QdxdKM0!Fe9-9nn_56@fsjs{HZqkWC*isk3>(Ab4OOr33ct9LP8!5 z4=nz`(2@i|m42tS5LOFIBADgk4eOfCNsDy9+sh*{SEu$o*D&+*>2m4C?19!E!+ggJ z7QSx|f!a21$%}d#zNLeeRG5`j^DA6#Tv))suIr{lj}`_pot9@Mav^Z>1fO%9Z3kPAhGN?*q(TmV zR-<<`E^_0-#6}fMGFM*nKye_u>vHwo=Btur-U3r!N9;Rso11cE>e=Su3g1kq|MTc( z?d*;&V8kuCvXGM)EcWBr>c&_L!v~c)$#l+1(}M<^KYX5@5azarvhOYsTSgxz>ILVn z)C6q9qS7C~CQO*|?HA5IUs-snE;R}kU6@J%8ch7%pjUp=Lzt~h3U z9q9`-&gI~Y`QckqA&f~dr%|~i9PkDb=-{3D@FW#UXz(&;m*M0^QJDZMTC(l@Sd~Jn zq%y{*+;gt3TC*Wamd!0`QCWzKHNcjF8`9X z#z!7^O0IV9fCzO#>;yLXKQvz#u z;86xu)dn>^o85im!=JWhW1xd7M2qBUIXrxsg|E~sE$3Gh9bphb%z`&!2j&^1AMTR0 z_6&19`m>cp`_@Yz4R9@j%L>l51Jx9aHA@7g$q2e#H`fy)vjUtPT9Gz0By4imKTOsl zhvmaUhH&F%0gPwYhbAgw$JXKL2I}|Pv^iG&WYdy32Y8F!k_0B3`?xa(@z@LJuXRGo zj~ICc)WS5^s{o5cgkL#><=&oIH>VfX>&H_N{Bc=uzCr9R;8i)KfYha#h=Kq2^w>+H zJOR0si}%onTSa>fFavU*rwiufVXV(p<`hvjlf~4coAvU~l>beqkW?!KnPmy4m&1~Q z^z~bhB?tgAFjGVR%(V5_|2SqolFSu6EDs0_t8%FqS}bMF?mUE0_~AY+NfxbO;-wql z14K1ow?#kqEy84S$VK|)>4hgW=Ff=87)$$oM7pDn!0=V*^0YM)Rtgu|S*oh5Y3>z& zz&aMh2pbHfnl5Ahnf$g>VMJNBQ0{!aHJjuL9kY%@1ZWVyFKPv(Gw;)AKCHhE6qhvn zD|ipG7pccJ%nCc}S69$hZ|;oC?$qg`0?vW`ZeGp!q@aH2~fv|p; zS>xgSUdDz3Joe%>%TA}c+Tf;6U~jsjDgnJaF7)2t)d%&h7YvbckLWzarW2&}iZytg zhBeQY=Y}PVUDowW?(e*M?b@}PqxK#7|2uzzl!Rv>ocx+q*>~uz7h%upZPMUhN`N-! zpDBwbucf)j7%}%tkxg&psvosaL(x`KVaz+w4yj-t6nEYyy)T@wIuY!#1G9DzrnBt9 z37rm!i78l3L(V(2j|HIZ9{dlt9Dl2;2dr8nOjfPzp>8xpBAbN8f7sjnC7m-^EwzYISj(@$?wuvk42`sx91j}vFP4;>w13^m~byu(K%y^kJQ zoy^wtq~T@ry94DjW{pZp*z3E3>x$BqpmWEq{Pe_TV!MD!uLmH&>AT?o=uG< zkf4TpK#2e}pViQ1$kt;rGBTnZudZz(la7b5yA8_x$MMI{gw07>RQ|=wwdw(b_;cPT zCCg`s$cS~umf@iQVM9*Utl6cI16xiF-`}2cQ3n5OAvNxPLh>gi zz?y{+<@MaHIF_nk<{suj%b{OdaeNUWLx)%0ZS~A7dGvl{p-(Rpoc1l?up6ogzN!_v zwz<4nh>(6l4)do=%wMd*{@T>$Lfyc;Q-IJrArRwq-z=DB5sK2FwtG)8q% z?3q#~M&k_H7mETjlQxDU=|X9(mAhN6>t3upV;~(R#1}8bmnzg|`q}sR-T6kz3TdWr za;@8`;z`-i5f$A@d?l2JbNs4Q|M=)D9iIj*ir-3AN<=+yp81vH?;!;V<(hat!vacTE$&YuQ|m+^k#^8i69j3ZlmzzBYt6HTw9jg3i?m zX4uXQuR`aJ{urKZm$lj&;D7c=j6N zcENg%Dk?3z$H%{=$MG%>4NeW}y!Z#r%Sp^I{Z<4B9D}}6H#%44use>Nc%j(gBsivK zsO@z3EFeNcxR-Ok*Mrd|r05-or&1sQEah@KbUYIPqnwB-jPxn3gK<*!VNkz2LAUc_ zSB>;kWh4`@;x+M2=3RL=_fuc^*{o#HVU}GxN{cgI+0cpy6XzU`3ll*Cwo?+aqrd_( ze(i=XU>4iA6**+Q1up{kfMV1SyyBIX99p1 zX5Srf`b#}U?_%ejPy2$~Vx|2pnWKP&yITsw^k?G24(Tp^q_WJbphp`;#^Vxz#26SU zg|t7nad7qLIMuG*d!NC$Le}Y~kXmRmcY6lC!Hwjd_E5X+GV1WcKb` z=cSqNd|d|cK#nq2-?im5;Q@rQ9Deltk+7fdY9&k=!v;FaFCIoe{{ho_NWB1zHk{u& z<|#f5Rc@7v%dyOA{D3b_sXlqzbuvPrh<+eMW}mN09;4V?su1aW0FC*6Zvi$5A6nK< zopSwg)^j5G#Doo`&40#ZVoA@cC^acl6H3R@VFMha!i!ZP$(C&G+pqO+WXFmj5d zIlTO?KD0vTKPbOYw56%9ONx}o|!D?EqH#n)8?vu+Z>=iIgk@(br-+f zg-6@CF-5@WR2Q&4n3sp7_R~mRnyMGsbgGkOaAiAnd{JyaAH%RC&cFdOl2{uWxICW^ z6GQvtn}ESWx@bska`VjM5b`t>S_|(lSV>?#JQ#+QA3zk8LnRntpI971ZC*SQ?a>Fe z+k-qUr#*sU9kIPF@{auX@g5C%8a5bM%37<|oqckgFMb`#25Bq`ICOxq4;z#D7;O}8 zt?Kl{L$~Hu!9^tV*pCsIF5q-oAJ?r=QV@J@FU56OH->1em zSAq}0shf@wGnk$AhO-Ms!pAxTbRdP9pGvI5S%ey1rSv4wusVC`gar|xJk8F&nN#%U zNe85Svo)g=kp+IXbL^TKr{|KPLq2v@aqk~HfJX%lZ4U81FG$lqN#}67{lL+nCP7vq z`KdpAD!5T&6V|oJKa&LkvD0VbF2h)c ziB%G$i(E-XD`QKt-b|mT^Tv~c6;~k<`8Jfvf^6$JfuBfq5~S@l7x8nipOo~52X$RI zDbF|f0!}$p4pJK6s9J@dFX47;f(8ddk`kY?$VvnYTbS(dKl_gdN{B|W64ddJC)ka= zdfJx*gd7Q5PL%u^NKJDEP|qUs)rHAZwekV@LJJvF>zRZmRjsm=4s+9{2f7e6a%QVo zPD1h#IL;Zle1);uB57S?!xvD;ioKiI~vK~?YSAKZAoo` z^KhgMm96m|C<76`R5fg1UnU$r@PJ7GM=P`ELc-9a&-&hugH)y@f)GG|bWOYPKG}aP zgpVKrDnx4;h>nxmskB%NTB8WEDx*l9Y1K-nyf74?79Hy)KkBf#zSxgES4(8=`vIEu zpoyQ4EmF%ULHF@-5!3+qRl0WqAl~$n;UPRP;{fDl*~0^t3*U??iZ@q_jXpBsB=}s) z2w44qCX2YG`zlj147b$WnuONA*~p9XI8kT|5QM%Zzy<)Al20$m9gYZ{lhjI{HfVl( z^)5)n8=nXhE9Fp(a$0plO8}V`XRIAYA4k{J`9p%_HI#U;!Gn8_ewh_tt0pFaXBo({ zwV`p|hJo7)8b!TVvp{6Z*3p6_;Bc5LmZP!Auzk z%$BJppCQWFY;#>#gBkGn?o5B5D≥|Na_a{GOkbY!&F<0h%O#P-5XS7mC=Q)r!>& z3rr9*4s2v5J13HADxpbJdxou37*MJ~+v7Blt^Se$XI`^H2=BPm6@m?E;7K!QFu?Rz z0Kyxqo`{C_IZoYcA6()f93rzSn*&*qjq7+_boGL@49)ery(EBNT9ckC+7A!)R4T-Bm1vRP# zvjcNE>fJl$xw$^?V*+@`N#V>S4lVz$lWxXJf2KW5_i3$-sWqClX=}YM3JD3xS(~ly z9~RlPhXakp-Q507ZuNY_VNg{IjU6*Z7DlYy8@ah=blti|3loZd|~p%Z>55sG^BGo!qR{{7b2f6wFxE=Ch05KE~Khy*BzMM&M z=qr7@R?Zs@Gywm;g-(m&!}Cp%Su*`w9ibb2Op#7$-9K%<-3+XWFNMJk^+JPvNOIMV z4>>;u+3bGEx#P1l2j&+z>jgRG`A1`Ml_%Cp#yoL3+KgfXl3Z;xQBAPB4(T+4dd~7oY=L z)!(^a_x(MdifF|Y*rMzwY24U2#igTHHlAGZqTi>U|Kc=oJ23IwwNyEtYXwc#A5D=P za9%Nax*a@<^VI_QU}Dj$B6xBNCYoZaM{fkj5Qpw#R+5n1gso_)?U>3UU^N9ihhlply1zj{n7>dS~X zmi9628o6>xbsjS%xvvQE>DmY6SMkr_L9WHt_7-d~-Dx7l2WT6lWl!Dv7}`RqTx@%)i|2VNb4cU{o&is3qL?YEUx z0f#hl)7pq2nKFIU4&xqjf!2#-EwW&iC*?x8?&h8)*;+R_`RC7{eSwJl49DIE;XiqM zC*Iqn95k%sU*ay1nbq zqPCV7RZ2jZ9e9C{<}!A*C4ME}ri=WYAMOrj(^_|9Vo0*Jko`$+^a|qG;SX?R?M56- z<#(z>$3i0)(h(0Oq3RRJ>VpW4gKmC_l|FCLEf^@QAhMp}NzLu9(Wxzyirv5+c$ni+ z2MWh7?}7tEgMuRGY=U(&fo#*A+)w=w{WU`RUe=u-C%gS(X}9+QWGrCvbzaF}=yEN- zG0~wG`$d+m`1+xt`o-?@%Qqm~DWCY@LCI>VF&%aB;f?u`#%nMz8(5vTb=~{cn8E76 zY7h3J(>>0M;Y|VUS!SmAoxl;?DztowQos((A&Sp+buXVidv>Uck%mMF#CVlmKgxmD zHa+PfutYI^-X`fk;$e1>UEp#l2)mxskkL}>x>{>m*hrHI4Iob_o0{whveLiAD={@5 zc?g`uMCPQ@LF9s>7k3J=jqkd=Lb=cAl%U}C`Tt^|`y!*POzw%Yar$0Ky!iO|G^2W2 z10Ea3Ju@-K$R5cZ@1%Vs5WsdE*Y=)~nhz_X-n#Ef6t*$J$#>4=#jO|kGj6jHoC1~fj-g2g3Rz7!W^3#)jb5%C+_=uI1WR|GuI^R4R(*`uiz3(DWNuRfw zP=}ND9^*0^cxXeqP4T(1^7;DeqO6RJd+M?9+(J09cj(wLvvHev!Fyn0Pp69FhSAHp zFRDmFYJOm>OLiFRX?Rz9MJg-(zUF7&h!ob29USDhd6Cx?=lEKZ`jOM<>%al1z~#r` zNs}9f_#Ijq#@_=buMr_Sgsp|nJ9T=FLMTt|s0;@O$N3wdN$oe5hrMR@5}+lO(Gl%= z7Wm=?!;vFL2zYefTsd+JEVh#O8S9frJH9XYeyzQC2>pFh!oPR_{wDDR9ml0>fvha; zB{O$!75(?HVqaVECkfBP$6*}ST2rmR+-ne$U_Yp!diu?-?c9>l2#?NnE!FcV-!+Is zgBj7L$%U%GKeO|P3gC(;-~0LbNlO?7tgNl&?lShG=4KEUE*hXNeR)X&D%{T#Cj9O= zp7Q7=h~CiNGf(+P^b%JB`GU=&qY+${8JM3vPD)i7X5&};)e_YI!|&iV?;Od9*tu)> zVNL?IM9r3%$<*^(A}->4(+V*|8!phc+rHw~>(tcL^Y=y+?T3Pm7z7179rr~s{xNpA z)#($y!NF(1fet#4`=wutzji8Kw^;ZAp`A8>Uz>D1=^t^n(4~Y9pD=s%lTOq=tR=i+ z^DVM|&(Lk_6lsBhI5@w zJ*DKa;*b^p-N@svS++5EcJr1UH$($hqM-=|*H@L+d&>y^xPa3(kZ^oyt+*^3FA zzxQpf_n}{rv*W?%*Y;6M#fW>jvt}CBQrknRHwe^=RbEnED>8aQneU>yl_kt5V5I#S zE1~8TH}bou3L)H}W0pa-KP zd8UlP-RWLeP~f^nWW$L+5@H%iFF++?*%!IVHF>+K<^8FG!|6^pjf`kGGmGcH$XX73 zKKS&0Z747A%iJI3G-A7gb&$|}oB?uQ%_AK8kDQ07@Saqz`_2fa=!G zU>>vB4J``|^L6OVoP_%71!$jre_JC>0u2BA0cWR`6iBdT;CNcS(8YKO&$Fm{BL@$` zi@o+*2GZCoFp0fM`!)Ra&+VJQo$RjmLPG*E2ZsYKSBXeSI2jM<;q7Gqs1%?Dn(Wdy zK*I!Lt*%r62Gfqu7O=4%KePlh9O2(2`!dMp{jx=|##mAvJ&*nD4Ff|RXYs6&P%=_9=6*Jtj9MW8&X7gGXz627}bHh}rm z&+)dv^Ea#PQYci#O9Vi=!hR`M)LM|=xiEqO*V_=*Vr`z#1mo{PS@~)>l6TS|{8kgg zLc6KPwfR<~|XxaghwG`;8$<0%IBS-88(?D^U)6moNm_X~9l5pGZGsy+B z?xhtKPua+YB(WwcdKsPraihZf*c-|K7PXf!sU&4*cR`hK=`p}i@z;G^IH?KXPzNG3 ztBf;B=pd5oUkkPT92Q@O%?*2;CGB|a(Ht!J?G(&iIWxgH%gdgyni-u}mk8`3?TCeE zqOgq{Y@r)Cpn8V!^B?PXdrNjcJ!bwb?ez~uL#x!UiW^osUEonZ+rleI{R z%a;$QX9lwC(sJUj$$$g>A9LL>5{3h`XN`*1vp!$?ud(sV?Mcl*Czy`#76c{-8bEz_ zzU@E8f0%PR%e<@ort{e?8z$AngY5DJP@>B4RHwm|{>H|}^2KLtlGv>grGG(?WzoY1 z6K9;=&jNjY>EUG3tD1{F>&hTp)Oh+9XG11~t^R zJbSCS7Wl^#NM->U`Lzw)PGm^EcfuOGrF$!`?+y zig-k**`G;41}Fltw9R|`=O9qvP;cu_gi0Mz{CK?H> z%a)K~GBUWNWn}znYOchD%s|rIo)Q0oS*6O~M1yK)B*_x6T(G~w(--!MLh8D7>_?BY zST#0a<4HrTrk`YO$0oj{Qg}witMUu`sBg3nnD~gWsn9xno;Qkg-N@w-n}Xw16xJlA4Am4Hw04 znB*;cQMH99E|1iL3g>G}>L2q|6K8>g3@Jx^R*{H6V*P2GQ z^cyN)(QwjEK|~;CZv9%)rLRi3d*+f~%Q0kO(y^o$LPajY78b2DlQV>@zk?*J8;+hg z3TM|h{hH+y%A*hoJT>ORp^LEkJ4{8DWD8T!=otP_qg&a>dc?k!zac?*breUqny+8- zuSrvUuz``0xcO+7b*}-`OeBZ*hOF5giM_|wIJGhaoB$N|FDIz>al%>sk3H9--(j*P@^iTLbvfHJ@$It>6q_nQ#pzIH z7MLVI3}VO7zN$ZL%fI=%65U__gce`_FTr?;v-wMHec5?d_Gj z);;FY#6kde*@4gd8E><8l9iwS8Vz=CSR?yspG7EUXS8#1VvSCf}{@=!(6> zY8IGGMR@u!Y)5(Qkfofl0wm-~a>1)kK-x_FaL=%nk5 zr%$iva2tfYdmV{tRiQ^p?;|*$Unp1wI-VqL$>gi9bM80^b= zUYGTsLBExJnVCaECx58z>WAoP>ek9&)o26PI5iun>?%MhAxuag`f>ShPh1xdQRrMZ zf!jLL1^9O=ug8+R;2bW8s@mC|=hmX-jlI=DU3(nv@kk97vHoO24Ng|Iz}1B@*^cJb zEFoaf&eCH-bpJ&V7BraEV~l64>9x(nt?+K+OxGT5&szbZUZ-=?*S6H6bPvmP6IPnT ztYOuraooJHw3vcr?CR(do{f2XQV8W$4q$BLer7wVoo>-C#Ci1tmG8Fcl2B}e2Q!Gn}>DQ-@(?3KLZiA<)hm+{LWvJl#=O>E*wF|84*lrV1rX zDN{kE?dW&H!6Qn}uN+c0Heq!mN&&t_id*+~?R^XUg_SObwny$fFf5B3(W-xqN)PbL z`B}#6zqcRIgZ-)FOl*AKFGEhZZ)cvpW8&4h)@9Oi5lRXYk2*=o$%CMv3`yvf2>Y

    cY|Pys?Z~$s?g*h?*PXPlt+<->uGf%ezXd1tFYdjt zw!>%}+nzmpbS-J9*MGD}(F3p*S;!NQ0x0@#ND7?rCXm-%?OoD(?ss3h&nikU>NWcwbsyO%iqwAjq8u(a3)AbN}LJq1{CB z(Z39L-?z_fW2S{N9vvOpqPHg^4oNtDHBkb+q!aA_JofdSv+|1fm9_$;kKA`zo)3K| z2VwT%{SPTN$3tO*yfG%I;l}oAlM}7jE+ikiGbSoJKazAf+evBC&tDansEs#x^7&O% zWaL{Q1w^KK^#=kxes!jsbN!)-0;I9n%&&3kD*ql5=}Fd74B`!hl_kE68zS5MId}IE z!o?r2-@ZK}>b8>GKxg_jmSvISnD?EakgxFv?!#E_S;f@cd2a^Q}^y-M3hR=4s(h9i2^bl2=*ie$7~vCVZ>+cUNH z3ZZ>}Zo_L7m4vKPEo`<0q6T&;G69~c zgHK)*4P(@l6Ti%_>K(OQaW|~byBc~)Zn!>rYWOM3RQx?nlenvK?DWEzlP{K+rfbOV z|K|NSs~dQJ^?;S#%S$1ef}H``8#BA)P(?HJV8Mp<6pb$ ze~Fpl_KgoW##KDrOHaCl_=J4Wz@W8KQ1s=?E1w3z+b)rx_M^YbRS`1lsv+d6@KwC?1}LneS`xC=VLVAU(5J#gq>XhHrvjEw3+P@6lyc8znqrazB5QKJ3NOAoxz^TA^F z9|p6tUVsOF;_EB4qML9{khMn_YB@o($!HZf(0v&kW^YzEbbY7Zp1gVa{y87IGQbF< zue?`%<8^kum=0UigMz9yxE)T1Gsy#Xv;;LU7Uv%&ZQDaxd*#Xnd4r0>KUIGud!Fw2 zZ*v_#&G&dcei|RD{bYRA#Z~JExiNdERuS#0n{}213(INOg>Sp}ka3?}etA##2pd}& zq*vjqm-ph#N_Eh&;2ms%oUuC}EZc8YsVrOq!92L&GSFdB5{GK9Rxi)dMJy%hmOGZd zPHJFaPznGHI)r~&#*Nz{CArpQI;+uqNoM&un2tUW0JTk&T_5U8=OXz|AcixFnuB9NfrFb?pZb zhUfgS^^w|WMH z++7Fb?(kLZ$@%{(sAfyTU{EE^4VQ@bbA(7cqTwGLuFRfVBXivz^DzdsxLv%e33pt<2k?|K6uz*f3sn&fb zw}~f(2Rx+r;EW6n>C$jaB36Y~AWX}@Vq8aS2Eets7kMBGOMPK%)2&BMJV5AN30Ry{({?g=l!d@WKt)?yd*$A5wscLQd(x#4rI2UqC_mcVQfmti6$c1v=zgzP z^41LJ4VRU5R^DdZ5?NYa7Pzp|J&>etl%*q_3i$;9#CqPNL;o0oZSt?U&Nix7$dF51 z`FoU<2=Nhh(JuqO!7Zq=g`3~C-~R0m3Sb@`XZ%#-+z?8CH5t6-ZB5u1L8ssUyS1^_ zj+{a%SghYAt`XE5W_=y!ZmCOV=8zQIoq_fZWI?4+xAUsxjeBF4*BX~rZ3qxls7q7) zEL2YXK@XmG*0jzF-xPCeqUWOx5Erw@PAVdk(}iarBR>1VO6xj^SlU2^T1lR{OhT!2nGxxKG^_dw0UVXosal-zO453yA^TB47ipZcDPD zNXpq5r|yu!1z+N^AF;IvOU?hPWJUCW!wSk3)!Gi(kBSn=eVePa9XOKh=61e2H~YH& zr_Z-!f_QD_$@mT?wN`J~2A_bNw7^goS9QX_gCqD^!{n}m*sE}WbF^n#2pp&g$w;Z?K6d56^YP@~>_HgqF*s9Rz#9l130%yrY0&I`&#Wefv&#t|K3u18XM2Z>P zv*XIrbF^dSH6@3^YR^a6Pov@j{Cy*4Nz{8A9K|~lnd!`>?1!IMxc@Hpq3;KV;_-j@ z!t?ULg&_-Be8A%aKDdyw1@Dmbvm^U5Lb#~8)t;^e^(&_;+3iWbS zG=Q(b1Wpq9Ckn;PsX%bhZw0+2V6w}2=1HhY7itj#H8t>re(_7S<|sLG%~XRYI3Zby z&H0d)CmR&>`ts#$-KrQj_z}UxM}x;u#4r(tR=G9p)?cek560X6STT6V=aZXUfX2-) z+d(Kvb5uFY#lR-@7@V-cU{(b#fN@7e)rS4f>u=;_ldEEB0BJV%x0xjcLa|3P2Rq6I zqzc)^__W|WR7?Rh?Z@g*$X;y5Iz(e6xz!V?!bCL{q1Iw7aSfrN(3&un&9fJs)6^5i zX?{Q_pxnD>fLbCPbymrW+06aaq!qP!`!*(qUJ4JlhM(;|boz8*5Fz=g33uRsccAv-;ZDPxmX|Lv5t7`0T&T#GcLWaMlTL9TpF@9eDU`;-x_^T~p-7t-93B6P z5>q^?Kl%iBaRSLznu!??Jd^(45G(#r~8Qq{vVl_hOzb5H* zAC$WY{^jpe1Kjt0EcTyFEhqHECVq6G^bvE?&NAUXqPiA zL%sPeIGp0uOtWTXwItoJ)oWwWvsMaz$NP0B^jc0q8StQ6bD=Y6c&)^j`qoM=4zjXR zC4tIx`9c)hc=b8NgY$Zvl!@JSEniva4pge6qL1C%ALk(6}3C`5I8Ol7*Cq@-?BN`b3=! z)M28(e1yA>yT+$wj{F?G#tV7@P|TA)Z<{IsgqZyV5}AXO3PvUli1^co0zqJq5T8#P zI+skMy>wCYo21F0f?F4$@z;lVm$%9S=KE^R_Q7Q*Pr+e`Cg>%}oHVX2yd6aeu5n2P zY=3o>^4c2TY;%brQX+;2)s=ory6q$isI90mZman5zU<}S{ZR9M0f#v4axJPtXK3uf z0qUj$Owd!%ao&NJir3HM*4$3U6Z+ET3POpx{Ux`ywGKC7;DmG`w z2z!+*^AT9)M_(}S0=69;ypkS7kzSsQ@^NhxSJ`f+JJJ-~FR>ynnFX#IHv3QiLgGKw?%FwncV=H!}7cxHzjAgRYW$CE(xOL)TVUeW@r*`*7L|ZK! z0JMTG<309Uu6l(hg1m_Xzyq+3FrjpaZJ=VZyo4+M<&b0yNDyFH0^4@F_UeDZun6|G z;+!(RVj9kU(!cqS9{?BUgQfI*3nm}t<~tk`( zq<|b#O^#1%SbtCwK@R}9P}RuiQAK4r#9;k^@BAZpU~#JmMnzF;Mh|64>%|`;c}07sPH6*JknX^3_e4B>Q06!YFMb7_$gr2 z_i3!tW}-v%SNk*8Dd=vOhXjq(PT}(?oncJ~gA1I_Qy{2A>oEn~8_i7f;K7k>KHkJn zqjb_WAvf|sE_Vu`NcuRltYsj(L<*$gxgh*4dwoL^r~;8uQ9f5eX7lJZj&+3J<0AC} z#M`n)Rw{~$+-EKVBKm6vIIgf6-jvI1m&--1dfXBI|K`5#PGHdu|9NAbA8GOFrts+lqM4Yy?e6hIc^F7=tN`d*^Wfu@0uKP9* z(t;oe%j-s1Ah;qq1v|_GS7ZElK7;(}fu|bV2qtp`QPYK2M^eTMEZct2{LA?K;qvba zcY>XV=H7#BBElMa2cA56g23ISTeE^)uxi}NiE&m)0PGmtfb=4z8WoYDoq~TQQQ#xo z2cf_(Ai(p>7sOHA)Y|H!73qb;Vd1$T7D`Q*BwJ7X0a-_B1RO#k*h$cq3pDnHb)vEkPbZr(s9<}=RiI}w~k-W{U4p%>9KI+&kbvLDEW{<~3l<<-|2TN{e zcWC#rKf4}@>eoRkS{eS3Yl>6XHd~hz7t?*S z&KuH#3&55x{-V*l!y*jwz8!QhfEnH$Cm&UGjup#0= z?RXP3D^@`JjzL=uIza(5zSrhny#?%46IDYrajI73^bU_6v{Z+FKhxcEuj?jG1)yfN z+;;lPtU=^@P*8!(buQS%Vb^#k_j1>5nKqo|cq(4ZRufPP?;Y7MpqEGmVh+jPacD+) z3j3Ryq*R;?M-DfhxV>8d3RD^7Zc{inD2*=Be$x?B_|h^4J^43|(QP7J&g;>Asw(mJ zT0vGA2+^x9bZ}|BO#u-QCLQ?gMq8%!KX(|$I(Mrbo%1VJ> zcQYoRx@@MQ@$!UMD_fBE&9CnUDuK@94~HM^DyVSEY3ANe*=N`M{b)zx=@}p+^w(78 z8PrTvb#;@&JE2m!Py_zm<*KwqBqhI<cc5(7t_UPdDu8GEbX7ucsZDbWgqt8I$a|Lz%|yK)e*w8y9>~l~Q8&_I z!4xjQ;qc^A8q1bvTsI7VcyL|+HuG&zH6n`;fbHif&JeO_I|5z%fqUtN`qbZiOGlMG z6kBFPJ*U3tbboKi$!E|JL~Ygpfe7l!(tl{jlhX-@TvB9Og4ugO5>c=Axxr;nItt3Y zJ_K9~pPofX0}o3r&s<&+0tJ%8kcL#Pu0kO0l}~y~SQw`<`s#%K!$W`|YRDO3n&(W! zk(~0)#?PN1jBg=y^8N+YVjukgMl)b2hP#=YHYbJ+PNqPkA3_OsVdYFD2pLH(1oO*6 z@4M->&w!8}L4I#{Mw)3E>EJI_jWUdX!n)b_3~bWkp>%|GRqXBUjfN74YnRO{C`)yr zP7Nic;lG0U33~9!u4&xHe*lau9;lTM$VJAL(my^thhhgoj@^A7B1Dmb3)jF7?3IZ_T!i>HnY*#LI)4wxDN%-;E(}5(V-XeirdSr)=lxOBTYQNmlTv=Sie${MkMJ*VM1dX@6e3V-+h;D!E#~~YsG0wa`#s*n6!m~Z z%Q($9`~m!c$uQrBeY1N!KiX*B5kRoZOt#bys*8G$@oHL6;=f8C<`R5bTE5r2z$p5s ze>^4Ld)1KfmrklOJ6-4KmHgZbN$NEVzjt$T+7xjol?pa%_a2ai-2F=I#g8P<2B`PG z9)R*BLuNTNreCs_*{3^MJ~`fx9oS+Y9dQet`xZL3O%Uc`AN)aOnk2u zAPOZJoSy{NtB%1F5MwKcw%E6TSuSjOL;|*mW_E;&1AjucErC2=7&;&$7G?ASeslpF z7;8r`z@IJ>h^PRU_lC(dY#sU(R4rN7QR(nl1p`6a)~}zNw3oa;t6WTbUQ0rUf4@3i z#n7=aDEnM^(QW;xL?G3)Fb`r^Wg}V3_RNHMy@IZm%r5OF&H73O;x5)M!I>$`6j{UV z`5k^&x1r^=hh9=gso@y?wJqZ4{YdwGF)hp5hkB}-<=w|+ z4|A`aAj1dR+?Xd7{ar;?9BB`s&}$*{KGWZ>tId{^tIgbkMs&Y&!jb3+4TX)?SxURw;UC zAvvWSj@Gw8+$hovyS0ym)B{$z3__+0zfl(&t%Q@^#hC!*jdheZ-g8LQ<}4g5#&$VS zr;oIBs5c`mw}t^c)*1G`}zShT-%4V ztk<_=Vp7JmEc4jJE~nt24fOdwtLETZyQZ1k@5ee4-(dHS#KgqVyi}^{6pDWLuAGc- zXRfdnQ0bPzK6bPS$O3)en-^N*b}RZ%>{js3a#}l0!StC!7Fed$ypCd4&{U7k0HfO zke?Q8NhEOCo3n-jtSy8a#d@zViJLL01waE*2!1LNfAnr^d#~@@EIt5vUBsKVvG)mI z_iFR5)LV+s7x(<7B3?1um-STQLS=c1|FapN6Sny3p0TQ%f*pw;v3s+e@u#LM1&WVV zUz_?gDrSbS?t%s}j~*m{n2lh^bC2K|#DK#6PA*Iws7%IT*C5(4{CfU0^H(C!dK4IH zo%R#XrQ!um&HHd@v3->vgb&_V(dH|6ZFq>sG9@9PAgZeJviy}C`f+#Bi7AvE}fio zXaOvvR@Y{MKFIkNA7CdHx)GsfRuufBjvOf5=G7-de~tn`W2aV^rcqmnQ?xSIY35oY zB2#~|SgWFBHbOjL2APuQO= z&$L24!O>f2U$j$$P%uC$?Od15qJpTpN@omg2*3}#8V*%d3=`MF2`#FlYqYa2lZMxc zxv|+wj2j$a=B*d|JKu3&7Zp_1lMXh}>QCj19J_Z-yH-csWmX=tnNSSy6=h%x7^Sck z=~e3B;a)S;?-+`i0QA9TX<_oaaQP>?@RqAdx;i)Y^}{f-Mg_I%;%%2sr6@w?8UE8& z4R|4J+1W*6eVSv2fc$xfoUir_4(mDw#lrB0Spc7IfjZ=icGV7I;F0h_|4mV5+{HI{ zuRu5MkkcaF*=2pXIw7<6FlssM?rhs5mU?bsE>VE}Ua`Vy93r{#=pK_LVP5c+ZrJgvb#KC`EEYMR3Wp}KgGg$NHH zOiM}e^|K4@i#J~2Vq+_M@lGqn_M}iIf4(?i1B2$NSSoI;Z*j3&u>&@II>*fD)}5HH zVT`(Ub9MQGveba%4H-*ZH>Egtuee11pmnkD_a|X-Cp;NzX0tXwR3JC|`)lI&#IV2< zp5X<9j@}GK@OgbIJ-_iot=V)@gN`}jN$poVGSc8jZGS+NX7k0Q!Tvxav;`_?oPB;} zY&rYB?2DYo9|&EM});M!%YRghX=UZu58%5={h))*^UVS zz7m~1dgIhcAgsHpxmUb% zAZMJ9S1qw(WR_-GA|pt$I5DOpFqV1Mg z9E?geZRE;^HpgfXXwdzYQTyl#3hzOI^C|E;4v0!_eTPF*g)_0*m#o$P;qZs7;t~%> zPSk6r*xoTJsx~(_hcE8z6?Yhgay&;j@SgVBFz_X6qSe}G#&w@=)ynaiw^3toH)Cib$#xUY9!YSt9Y_-# zig19EWYTJjC5ClTVC`AdYMd(>V`tQiWb6QfJJZku!6!t-2Ld($0D+QF(hHqb;a!j?JR_1fXJ4vg^RAV2sok{@^ zF}Py4D9DTnw=?QyA}eb0(g)JU%+Nx$j(A>O@9>Q)dxcwP-NQMsZ5Vaog*#{q#Jr|a zC+|sw2-^2^2oDKw3j@WZa|58QU?g!l5zc$uG(Ue%cc0 z>A>P_XZ(ue7s49E3=mW^>Nf2bTXz-8mZrm^_tPS~qhy)R&FZRjFwl?uN{rh*GqY5b zc%JiAN`v*oxJOm9xpj%VMNiSvsU!?A)le0}}29|XdkTx=*KJzK29 zMQs_@n}8{Mud=A1R<2w(((<52{p4E%whoNYxq5vYxYo%##WN};T6d==^rwCvab1)c z8=n3!Fk%=G8|&OP8H1!{+|H+13<(G+Xn;+DgjN`q%KAQ~YTEY-odKUAKkA zs*PGA-2Tx^2dR3Pwk|g=r(mYdYuAt2S8pY~FSk^e+dJmHzR|qX2`tk^PCY<%P(-GL z9=x)?z8rQ;H)vi>sw1Oe{L-?oz1ocHd*8TGt}$O9`wlE*yf2kiBb&?Yb~)s!STw)A z7v5qL{-x32<}32#k<%_J#l`5)n+8gB#KRuT2uN3Z{`xmkCoF~%zvp?7%Q)?d=;3I5|#TJxsjJ<3~E0+s^UeFe zRSJbAws&Pds)?VETe^hy{UqnBcrdDWkldW=->c61G0nS7V{;+cs)y|MFo8qfv$&5~ zBl1&-gdvPKs(ks(5}svA|1A8{11o&C7a!CBUNqp&7}rH4#69AVXB3&uhf1ES@v(fk za`A8gMkAY7C96|A1bw*Rp=mvt#wHh_eU`uvK*uY9{TsJU0RK-DiJkAm2-m^0tY~tq zKag;*I84MCJgUym%6Rx!;R2DgA4f@Ct+RBPb~K(>pDDQCp5S}OlXoC7j3dA^r@QU0 z*?x?0(9G=pcsTpPOdRH?&txqh7KOar)%#GA(ZCbJZ`fuIQs23M1aQu)X^f>Dq(IS~ zMoTb{7Az!$-xi-uCh*79eySY(!K-FCXKOHkk#5)O{!j^XTDJb?;~PJ)mdn_cBt{4% z41p9U{tauZVz{;_V<8jwl8i7+z%IB0&AzHRLshDCuUK@&Num?N*@sqFzGm%-XPNQx za&6MC>PSrceZY0+c#-{}Pd{SC+x=M1rR|u-JA=pBC4MW`&r?Cl{|(?CWGIm(RO`oVVEf7xc~jMqV&rG@194*N8ZF8~INze9Ep|N0<2Ly+yvxvLIgWJx9Pu>SDW zW8cT_b%$3W;3kpxoa>T!d$WhvnxrR%X%L+_-Gjh%lXb&A-C zZK;r3H}`jNip{<-Fzu=gA^6RA$RhqW{xy?CK?u`7$u>J*!<cnZP5|Z*ju%C40=D>H;mPQH835;D zd51mS7osUIUzIRwhA3*+p7H?qOk5kvKFfx^RquqME5bH%m^?Bb(>ysd{Ue?Nvns=34uMB@(J!`UO=)e3(@84bRFd*T zg|QQqQx9+S`87Y z7fVoVuY0VS($q+{sp;%6VOWm6Kx zEmvopW&NJ59gz!7^i0*Bj199b7`eJ}>t$t|66M`L6Lm-8Zrs|tzva@*()pUGj+BPr z*-&bfP#r`GiUc|5sfsYCk(_GJaDn0MD4il5@#Ro_PF)m%vYbk*a~l(b{-DNZhV}eI zvyRMJOx%~D$TKY8Nu@-bhDIWM#JUrXT9vhcK1G1OduTp3E~JLe6t1Cv$)g03A>=NJ z-Ec9-Ir^E0VZM82mt<@7L#gvvFbC2n&l$zHh|PE>J!Qx81|^8qn|Ioo4=?NYGIcie=ERLu z=2)aTb2;&_jGvPJ{9KGXPq!g^A^$nbg7o!K25|8IPoe}II$4>_uA^F+=FcEuIuDFa zAm?z(LYkRa@q1*Ux^rZz%c@Zfo?sp_nl{XTk|W-H-U6#{XR@cO#g#-Y@uP5s(T%&f z*y$0l=;F5x4dd?FYNg*Df0~LUoej%;8qV1 z(Rd$l3xFyQe=1PvT&u0$zKtpeUg|>2P|BeXxM7?J#Kt*=Fp!%(PI3w^?L?*aS6JC@ z-sw_SKO!07p`DwMn7s6O(U4@ z+>ujFmtbj{HI_4?oj>&Ts;!-27j&l4TaNx-==JM|GPr#PsgxYE0nyB&22>Y(gz2ex z#nOg>Wj`?G#~QLn zauASag0wi}qnk)G#aBXzq0-^9l8=M>4?=XG#nL5oj9D&bviZ;TUeRBMOkN(4w_9Hx z@2iJn123|qn?k;=iskwNu2W}<`gpNTv za(60TkbUq6kqYT8zb{F!H*hUv}?;AB#A-Jdwqb#D<|8JoP<{Z_IDe#;I^ugSR zbMFWkI7l(9$^4L<_CRGz;AXKM&U|-ecvb~R>|4;Pc|=$XYIr=TbP7bpuOv7?wu(l@ zH1~lePCO_CR@z%Q4vOCa^^sRy*D+eFsJ4k=?gIdDy10GdkU`c*}rjv`E z(=+R0I35@GF^eAHa(?BC$O^Iub$zpqx=zq|K+B3EfTG?%p6CBGH0vhT%ZZjNwlqtsEab8krx_5vzAj-b0#QiyzaQEwXfb*_j3aypEI8uWL2 z3s*gO^e75d@oz(;ai{(nuI;H`do>{krni!%ZcMrP_Y`e}(4U2etJP37>z~JiuPoRi zZ|XdW*HAg!OQ&ei5$*429%8`I&92EYFRxbqZ<#`?$+0*OmAzpuAe{zeeOkEsgXRo< zKo?Y2Ye~Eho;U-yh(7NIe$22uka?m3EJj_Mz1@CHQoJ0>p-&+h27ai`N-EM-1o5F= zKEw>C3o#x*Gf@C#kPE_Tc0;N|O$i~LN)el_@Fdb6-roNpff5kwpfPcQ0_aBTABDR_ zR2lFmlc1WkY+qB$`(IB+;0Gq?{H3IPdo6`X;flZu>?+~rj%3gj{0t=sd~SfTD+>GA zKSUHrt*(F9D1rI=Q8i)`OD2KQxs{QRx$@vOaCL0uAhb3~)tD|Vdn zHt68^XtoHJW&^aMf9`v(swl7WtCJXWq6TsM;UkE3qxD#fGBuor{E$ek>cOrAAK1?@ z8Ek6?j;Mk9k&N_YyE|uJ#<~HW@GvTt04cLdQR^KY=tNuxl2bh>`!y(!jQ0T1{S4Xt zt__lr`z;S>=NG;0YLLx4J?HQf#fZ`&*QT3syaIgtlf_bRTIcf7zBcIO37SX$y>yCfe7Q8q0 zZC|VM(KTb5VafW$#>-p%G7k~u-V{nRZ5|CT34sZj3K1?U5&FuKUh@sQw8fs}dRZRZyB#4tFLg&=8= zay{Yf{7v|XG52^@@4s-xrQcHA$Mkig5CIWrzOHHHl4#*h_ro7aTZ84%$a&rRtISJ? zG)oJAa?x$E4T+))p=^f=AV{J3J+zQMnX?8d8YC^$U;$N$Mv^RGmGrZ*|EJ4_$In=r$1#o7Z>WQIfvjG#4r>SS z|JqCu>~JY^-_>$cA47s%3UscL!_GMY2hy5>_U93Ga`VR&O3=Sc_)Z43lilVmJ5y%Kt z>AS-6^1ux;e#N*ng7>2(a99oy-Wd{=fi7Gef*Yh}%QZJucJH2(X0mezEd|e+7~nIc z!buHGA*I@xK;MnuDr6#D%oNVU-oWNb*AUPNnUkQ?pa-dhNcJ1`{xvQvP^)o@FPt{U z#T-jClhAPEbR+9)haW(dk4&27)dtXuBS_cDi=odPpHOq#1xk%MSBhe&;&j3G}$WPXtL@b3j4+hn6D59h29_ z!E5|_>qVE@d>s)k!!UY!Qs|oHHCjvnHuchmSx@*Bf_@FsDSSu&THGP=6x_g-Z*ov; zGhWmpo;ke$_h$9!;bV34a$v80&hkZFn?!d&cdIjK(fm(oKjgOmN7tM?u?HmRb($UM zSOeD|08%cR8Wml#Y9J|G`5hx9&|ai9)|L^6!tyzxhix0rRhUEsqBZQWx47%yq5dM+ z9uR;OC$%Z+uX|GILR$~G9j!ITKJNabM~aAK9zO~^3hDn%FL-Ujb&(jRy(-ssDc(v3 z32L4@SgEHwkO!T)`UmDM^M4haSRxsimgF02J%x244AUb=Diz_xFHM334BJOUJp3YIO15XbmHxZ^Dy+TY( zeZ`=AuO`WjJq8}qnH=q_qVuatuMAQz_?K07h>zDySIRKYyGjn^N>1MouFM|T8pIqa z+&cGh@VhJA5^JhL3*jS*`nya-H#zwij!i(#y&QOeCIKE;>(10$UjH0CUihVTpV+$N z3ui?{)$Hu-`ZqGWYtFyA0NY)akP4?|Dt>;`%Wo`E#98<6*l@Bx_SzLbD~R8syda%v zkCR9Sz=-PFm!@F3Y8M~GaxeXIdJovM`~&$eG8S`Yf&V@L;`7g5MxQ^UtL zF**4RE*yMZP*4z)`cxRyL$1KX2Vf4}*h&u9pYRHww6%B*#UDq@Pnwnjw}N=xylY65 z&sJ4l{&DWYcQ2&+{+pvue&dtJ6AFR<&5Ou77T=q{XQ3A7>(?VpY*{z7RpQw%YHJ@u zt+CIaKUcU+MoQ}c^5wy}XeCJqN33B6c=A8K-ON|k$8!6_j-t`>Pn&dW!76`MN`~q9ouk zQ~~vDmu}rol0AE##l{|m_|Q6_bPuBBChNiM{Z0_sHtMy2rSL3l#t`E)66(zm;CQe* z7J{|WKzq57j_kC--KF6tzuo}q*A&Pe$U~ZWiqqa^-RT$B6C&}6Q_C|ALZZWFVaUh; z6h0OvRkj{z^k4`<6n#Gp4aXv_#?{a5?OH%oM=I}~pE%Hs3xyakw9$9prT>~R0W^{C zIuEODzF(+K=+r(Ayxex81l+GNNMy48t)ybpc{J+3CRQrr9U|R z5mFdJXC9lt<`CAWD+-o!esGjy3uuV=NHk;r1GH?omyc&d7w!Io2V1V2;d{TtsU`RW z4>*v_0$o=DBFGN^1ijpJbuS1(7AG8TENuJ{9}&Ua`(23FG>*-<^>c<$T^!?p?OHtT zE=STgFn|s#ZQ#_l-O0F&$C@`+k0O&O{E61hW%rY<&~4p9BUE8V9dB-hP$VbsySqk& zhKFMW?2V0M;hN6(EHCWZMd!!6`H%|dphX?GFEpQ(!O_+!geBa}Kz4Z1%_1B z9y?&HJY`+CvRE%^L&JBMT68a7yx2b^DJi+1nwpJ;g~eX;t}S{v992YCClBsH#I~)k zy&C40wsv+Q7Tq3hM5Hv3NDoQg$x?j@y(^wwEA5vbUPICgK)BKmuz{u!184#OWw&0= zLw)O#r|!|j2l#Z4L7P%$*$HN5X&{VpE{Z+g)X?yyJj%=a0u&lV;h4w>*tL7NqMcp( z!mnSV7;8gBobHf@O(5JtbY^|B)|M3g$0`>*o3HS#bDN7@*gy=VD_Q)ztB0;tcEZu+ z*IW1R9Fp(_E_j6Y7?J@(Y;wkd)1TJuNkg*-aKaY=7Pqn&L3CLLSe8Zq*RqXcD2BA} z#}5T?Y=g4>SNHPq@xe!YCaNi>nZB4rm8~9I1Bx9Zg8? z3l~Wgf4Hfn3K9Jcv}$i{eG5 z^K$_6G@aTbw_zaC8H6;v+E25xvP}IZ=jVlUGIkRazd@6&p$1b`f#G=q98WDWDzC>u zT5|GMn?rOTf_)&oe87KWtPm@!5rVYGGl<_pUS0#85AbKUaT+@NE@!-8Q#2k zQx9DX;LuVechLgBR*vjq$5>sv%GBnN)<)uPk6i6omp|?Lm%zBpJwAxV3_U7q%LpS6 zG{dnXft#Qp4(OWu(D~%h=DEa6jbI5-OiigjnC|QhQML{plNYPIdp7alKI5@vR;Q9Z zq2dn8%HgLpF=z73v>_&mhUD2->v1qLaNz^6h(5xPYX7!-Ua`&fO8#)jl> z90_D;+Pu2C#&0PhdW4>bdY}-+y_G`>UeZ3`9h&985d3Fyb`TmOQ}f23tK59w{r4V- zi%`$B()IlO{BzCN(eUDAy)_^f$mn@9_d#9^q=|z+$r8>{+JGPqG8~vJkPw1U@J;^l= za%LvD$6JSxm7WLm`IZ5|Z9(|f%z1SF7_cRweSpWwYc}2#LqnidsP4juJgX; zZ#}EM>|jXu>iD;M@_J4X0tW6M9BdL`31H`2uoK4Kp4hW+@ygLS^`sXN)^WwaC6mFY zRu+2s0qKm18OdLc27cajrk?@g#J`6G-AKf_uL0h%V&t zCfc>@l`zX;gq+i9xPPD9wad_H+cT}bY9@jGNavuonGO=gAATAZhU9)y&dcF5=Z6{| zY29nKjv{B0JO(7HXXu`qHrlc50Y>1wr{BMS|Eo2d^2X`o@sMg^zF?IHOd!GT2~xQM zEnIpV#~6%jrh&eCW9&qL@jPXL#>ceClJCS9n5d6e|OIiVcUBhzNtiWP!`k% z(aXW1vwcVt_X-z8^D3Jm-KMoEqEMsEf^AE^u8@Bhg|1q)q>;7Z8@fLnPfNwc2wKF)hn ze{;8%0!GZn%^mmrFdXE7gCRlsiM4;cav04L*5NI^hro2udzg{nU2AHKutBkv;gRax(w~AljEIGciZ+BN%IG|XI59zJ843@NvG+zB!D79lvp6)iiY?hQ6pRst=s=S?f5`h`w7cqW!V%@+xaPM z<_hZ7sw>LN*+)lbN|iMt9Lcs#@`U zxDZCs%F1eI;-|0hH|_%vvX41BD;IBk!TP3yg9zOe0UZ7Eu}(Z2D9J<2;?sV_^bv@F zawq_(X&M^!lYoX#_c?%HZHcyU_c0qSz>hj5Y7P`dqqFP=e}q6p+UybIvM-Kl9zK8m zd}Hx(<67pZm%IS<+)7DB(pcy>AH#ZTqsk(^C+e{UnKtGPcWZ;NZ4h$jTXehv*Cl2# zciD(vIP?GIaot1qP|?s-z^J$oq8Rw>*TMqosXGczDMNe_f=pU|gU320mpd>tl)Jaq z9+GEAkGppXHIuJhUGW9-Z0sb0URBZ@RgA&E#Lb16e8Nt7ZgDKaF=m@z{Vnk14)R0t)dGK5SS zDilg6ktx>@GK+-bUC%j(Tle>VKJR<~xSu+e^BtaNKYOpe*4n>&b}3|ZGtHmBK_dId z(2(PR#sXQxluO}4br+pXjv-;)gQeK$WPE8JZNpMGoV}m-87AGm%P8WMwrlF>kknbQEMiwj;3NWjj*{ye$ko>%3ij!H9iX&lr$Zw{gGMtEx5L@2 z^hrjO2zdBue&RAR2l^l+sx)rW#PAt1BQU3B3KYOL*b{8nbO1F)t#F`S=T--gZ7kAT zXbXd^j`Aft;JSsmW9q<846{37-$DXbIm_8lTEvRh_d#2Cdz9Ct`|YE{fr04rs?j{) z_OXxzoP@zGTk=a4fjAa7YV6J}V?bo@L&(a>>0xmAJ2*&iR7flV%CRn6^KJOLZFA-? z)3#J4k|Lxh+}r!=N*bdEzf4W)!B!9rz76X(6(}6VQJbI7jby6OkWGTP4p8?->)6ne6i)n zsU_@jYNdh5ET{LS4(Po{4k5m5A})a_U+Z-rMTz-e;Y2^H#D#CdA-u>FmVh? zg%Gi|4NmEfTC9(0;LkaR;nX#~pQ1uTb$bIy2Oa_!E>|gP!2JmP;>S4m`f2h7^_ubB zux<>4`xn=k1pInR`})|ok`fV6K^XBHK@4tRIrY<*1hKSB4-hrg)Z-zKUDn9Svl02g z_0`{J?*0?Uo3gSHfbg8b2>1hDb?3Z^A`1vG7mHZ z`dl~J|3vQWxpU_IO}T372DDT27;DA*WK^$lkPepGkBrVe_0L95-P=dh{lF!7yBh1| zri=fZxli51wJf%U=TtYuSR*QZb0(iRq9NVUQ z7kW>nC{hl^f)wQL3ZFtg&wMZC+%97xMk-L&?z?pr|1}`ZTz_iVf;4rlLpz8E6x>Ip z%CkUiqD(OqP0UnrE{Ds7A4fhOWBt!bn9xX)o3-9J1wTXq;=|&q<=~J~sk7}h+DF8W zDg9Q+xqlzvW69_wu8|RoA_<#Q+zz=ptShx|kIF~8Uam^)t;@|dvk=Nfi>wqDndXPx z%4i$R=i*`v;eM$2Yv7ek2oWu39u3UMaD65A_A<e1xCAkUAj#1ly1I@}(^x@P<=x zLewJ%3c{_di`)O+@W*x~c*2AI(WVYLydOb-A=FGW*zd(QiuLlq2rs0z_8>FBR(PH* z+um!ge&$SGgV)q=wIezJa>?X0QpS12%Vy_>Ih#H1SxxYlaBKB<3*lHrJGk z%hAu!ii=?isqkKy%!GOUYF$|@Ij~|Q>OrIN7oRW{unj)T86H;R`fy4Sc70y_#IX4! z5?xurxikF*UP1d`KOM5%24gkLA^vGTXSHO@lHr#%2@+>K(XJ!1y*1^571Vbum$yW(5O4kWxMKjAP7}!rapq5 zUjMA_zp>*rY!&tEnn00qM4y3RtH@;=j$mF&eDJCzzXz;=DURIA={b#J+CMmCW~r6U zvyhefJ)p0UX?-ncQb|tkAR_Ov&k;(3Dd3KkLU0I#_~C|j^y^B`GcQrR;H^mgxAqUc zW!_YL8R_cp6akXs@&>b>yQ_Xq*Yxa}&RxMewTZ6F60O`kJh)w5Sy)(RQxK$ron)Ia z-y-C-=_B9XfG#&RDy&{j-Q{aLSR)8)Pyg~`u#6pO@nssVEY3TU^gti;&l zHRVYrw7nA}llpq=Gisb%w5W++bRYeN3m1xcu8e%Y7rdB_&2;IriJw0|dYYC~9>{|X zAhrLg3hs16XVa^PlCMEH8{2i}2*o1|JgAS!0^W(UyC(G+O ztaDSz!zF7QC^m7hA1KbZ_f(KzY`Y;B*r38Y;)V2 z-=|_R(Z_s{YM~HJW?*3Wcv^}IEX!?2xQ&-e{hN?rBH=@JI5?DMfY5?5<*uozi4DFw zgh)wdrosP8|N6c2Y&#@}wVBwcGZq+jy!jhG+5G6S6fPihYU z>SB0}bnC+H=y1tw`&n39Ku=~_k&(P23@=gtf z?EWwLU-V0Y7f_D=T@1qu`QhgkeC?V}_8Gi$_;kDz989KAgOwY}lFi{c{&(PH%1ptI zJ@H)r{Pe9eWh(PYO70=17O9S?Az>k#$+zl;vpSvU%0Y~^DIp_IY~3&(iFD9QboC6| z11(u;?8*~sE8uPa8DqONZ3rD6jkg^0w+xi=3nmLm|TS_VSU7V--eTG(ue&Bgn>S_e_qmq69ir$;boUW z5N+a2Ae$S^uiN1moqAKN|I!e!It44Puaq4&pzZV2)mn5{b8oLWQ8&Xa!2Q8|OR}rK zE&;}T+C!~y`Z%VfSFqz8pZuZRXyfY0mJkaMul}uPMz?jIO#nj(j>@)y=6;1cSwoqJhs>u=HDRT_ zYhS}>1}@fEQO3NsmtME)+RTbk`Gd<>NI#V8&49U6g{hJ6;ewBO=>+D9ufnX}! zgN^ZRbr7cC0#3=0*Hf_dy>Ox0QcG({jLvi6lfzkiNup}oa_Z3pV4|VtLyzOP&!s7bbSm+AMq$EZ@CdQF|#)5?dTACNNWGcD!dxP0~Mo-4;uJq{Y> zs|hY7-`7BJ@X@A~vC}`PL1z-zyiG(wp1uG?Gb2VZH;z2(cUDU2@yV z{5c}iN1lH?y$psvZ#rAbY4_nXL@`D|NU2M=NZL8XM9 zxvz_RH>jdOctXq;*K>Z`pjQr0*?U~dc;m=P1vaqc=sCnmO|!AmIWiDuIB3K zrVzshv(Ky&lq=iD+Ed1I* zgh`h-0S}U(g`JciuXs?||1-w^s($&PCxc+2DtT$%{Q1Ksf_q7F_Lwva(nrI3{=Ae~ zbXVCC$c|=26;5A_&t4zkTV*g{wN*X!qh~FaiP}6m-+4rhs&;Jx<fk2VV5dlL7tVlyfHYBWkZUk( z?}FiLN7~@7150*jY283F4zDY%tdF4HuO_Y-sLKq*&4(z_{lQi~v>#9onSbA$*JF7q z<`n1#ogN<4V&Z>V(Ukn5xe~9=WB5miB6Yto@$un3pApb7-bFH5XE+JCn~c)4iLDF%ad|8nxa! zEnnG;rcGsYM*+!{0Ze;crI=n|xYF4n!fIkS`d=x&xj~_pF{P4Q4u%alJzu+dN;a>2BQR~iT zaiGlUV_qp}Xs~f}i@tdA;sno@7nJq)(U62=yg@+>RjSrvTe@^LI_b!|j7N*8J^KP@ zT+8hfWza$WeT}@>n!P$L%cegqxJ6%=VyKXzw}L>I7}jFFM)SaZRyW`nZD0T=`=ujq zA3|Hx5QnVhwYgiV(WY6LF4v<32er+80{~GDTbEH`wNvz`D(w)l+S=Oo-;4+g3+pV> zvaL&7{QDLqQEWa$meHp(A>x0%O4K9x`0arZN=in~YZHO!j17DC?8z8&?G1cl_+=Ru zK{FalWYqE)?1OD@Op#&KAWAuGKlqqNv)MI6v++9u;CcwSOMP5Q3Q+=hd$%%DDR3oU zwXDtchQ5E7&Q5olyXf_VG@0LP!hz@V?&-cl>W?CqKv`tkqWIjpsOSal_uk&-48xzk zf<_Sn?_x*!F5lLriwut4){MNwk=ZS)K+z#uPjj2xVM>vSPNF%8{N@@f@{_GC=u^3=)> zXIz)HV&H7*Pm;P@K+w2r>bxn;zhQZuej3BRkL~uOhRw-6$}IJSv;Rb0S=pQLV*#c( zP!H(>&>$j(=%-&HHCT8HlE>KgEO_bk=h}A*Q0$N~(P`&AN-FAalDTEYPV%roXD8q) z*aM}tDMuSOs#6XpPZs$*NKw zJ`Pm4x2VitO)&Ax+EwH+HK>!!<}=HxKdM*~LhPfFV=OE*6PekQ=c&Bi{YWQ31KVk4 zc8@s~5=m7;9P=9gaA*EyP|r#s>T%!vy^!(-k|PQL*_jcb%l*m06qUaGsWWBmyHv=^ z7h(n9SyhU@xTCmB0Kjv#Nw zfJ~Ge13_1^t}D4G9F4LD*dYYb&P6UCkYCEsCAA%L$NMtJXqp=(A*$pb?qMf-3gE~B zzrj2u6V)VCX-pUGoA@S0$`s1!XMhJIwic^eFeCIHbwN<>b3oV!?8Fij<09|I5*{TI zLt|1itKSTw&<4CWG7|gxg?akF4!V#jqQK4{-`sGBTpsTldsx5^j*Nst>*;pz>phCE znzjMi;iAQZ(>t8D_wN%j&C+^RkXxuL2%jI^7kyCm`M0n-bcL^IrR&eyTTLj@Fn=md zIy3TUT)g-*^>1hT6c8v11ed3NW@rplAz_xi6vRro6Oko=L!>T$qG6PB8dw(UJJ&Co zUYN86Yd~7l2kN&<{c!<&+H-wic#V*J#ilVky)KoQB)I?he7p#hkA;uyX||Jn`~ze( z`s9G`mRg4I8Tr38qug4UN11|!DHou@NT^O^o+U=6L50a_XJ_Y3eaQBg$XYyN#`ed1 zAb;XY%DzUI^KR6?MtK*?(TVgVY;+1JDdm=~#aU^Fy2BB}Hmgr^mDBcO96frGH(=UW zz2+hfhA~{u4T>5b=XFj@BxlQArnkkvaxnlE)Xq}Wb=1s?m%{V%&FVkz9si^cbfTP` zUZ%l+-w8pT7%+PVjEN~&O{?Hv#`p`W3Y(xAIj@QVxL>_0~OX@OzxFfE`Fk>ub1Q{tb+WMe;IxVOIf;~H|0N< zwjVoLVb8+pHC5om01X>w7Q~&FFA0C|ng`50JNSYgzGl96|Ne5r23eb0ZQDMu@Q6aN z3j;M@b6ulQCA`NN@-U|}3y`uc{YoI^Hg#zwrF&iaQAZYsK+t^$R9-ibrRte!)D+&O4};?5_IxIh=HR zd=IMnO!Sxz@r$6_;Lio#t#l>~M zJP=d@7S(bwxt;aqc$TD}t^vTJ+v-C#%jPuy91bQLiOF8i2hhYmVn=&>fVj94+F`>+ z8_HRxs1==@tc@X?+a)DvA-I_|Ja`_K9G?D4+Vz|ez>cf8Vf2}~!UZBh5fL`dgOBA1 zPJ`FKAX_Fx0GxRopR(DR@o{mwT>4<5nnQh4g`C%wEMPqk7DWyc(b71em*aiIxsfA2Z(C|CCQYbu1v7@5D@+ z0E3v0jt=f6KY#w*0aBOM7OvxbCUidNPAoHQ@EY$Dx^1JPqSA($H`kFnAL83bNpe_| z6ABQ|+i{va-PsQzZ{nbY;DL?&lDLWjE_#^G+&F)pq4K?6CigArLaI@CvUY$j}eD>Qxvq3X#plvJ->HZ!kPMlavbg8O8SJI|a*+Oe?zF0P}b^7spA8mIPO%ME95e71 z`RlS2oJ^;A5=f~ZiUe+T4GZcu{@T+FUH>(l>h(cyqm&GcV0`(2@(nBa$W#O*${YI5 z9H_QH(d*n<@q+HrI!fnZ7X1$tgD3LY)&GNrgzvx;SYpc&^XKQ@229`&m!eNE>E4s_ zx?vSBl?OC%nDBQAb#y@iT0cTxyryzHUIxiyi8jxoh;!VB?jb@QP%uF0wi;;^fT9)2 zBKxQd!6YBg;D><&jc+{t)V=)>uw^TcEuN7Zlg*xap#WmbD=j~ejJ(+gPkd;sUHmhd zD3bvSq#40ay3$hiQ~)$X3BzpY#5PCyseHoEL?a5Cd3<1m4g4r#XaCQSiG~Vb{pl*{ zwK`KD|2IOrZETSH*OHzR?+V^wPq}_yuuAdIw`4C$w#XZFEXs;DK=DCH-3CQFsd-0~ zfE4;KV=(KmWot^a44Kcf>7x_h8Y(p9v8(IHoIXX~;tHV5hzH>#w?tOYb zri%v?x=SKR1s{GGZz05v@1Or34B(mP#BY}Vc`_-!PtpC~KmE9;8A|bBl)#^N#~M0y zyuB$fE<|gS9-l`v$3(TC+J^1Wj&8KmG2zGL*bCPufenXu8~Q5MUn`%xJGGw72e0Sh zcR@GGJ%1<5WKwB0gmg0@1;6sqz&q-&{CoS<3gM8R1JgjAxVckbW%I9L;8}T|pB$~e zpF58*RgmS|9(zty|FCCRc-ZeD`MKQ`)x$LDYIS;eF4h%@<;M(})>BSWsZcDH`*jj$ z|H`dFH7Dq`N1WWWQjt|Ez5vYvL97B$bp(Zl-?+KCJG?sK)VD?_N8bdNIzwIYcP>vJ za#0*8nC5w*8DbY2 zlS1shn{Uv=wI2FHVW=o|i*d9F!HpQQs3jS1eP~J{!Z*gc`|}|9-%8VjiFDV|6+C`7 zCh~q(=%zhv4BsT9d3a~fp51%P0`wZk)+@4gC&lJgi;;;LcpJfFVC#GE26r4e5(7D4 ztzzk<2UKkL+`oSz;)yBT*vb`qisfhr4UubCsn64)}Ek<7T?sF>o>ne&(9!AYR-h&M-7IRLY(b zwluY)t?i>J$Hby)7O%9!;ZnRRV{6D)06cYf@F4j!*saYPVO&J9! znQcy_@UpS3g5WQ4w1Fh_KbQ+KG;-zSz+5Dw!44`Q4YWOsj|zs|s7@AS*SN@9NY3mO zv6BrYDqxR606b#zkEVvos8(1%6CE~`E`41bdN03|-eruKzJ@TanX0p?iM0(yFI9iRR}SeCgNz^kOsixv!vS!ejt;f`vb*>eN#7@!UN#H9+AP3z0Z zr;C2edR%mAN$b$5KCIvQ5#D=u-x#i}s}3OnFVnw(@C^}0Q<;xLjlSM(z{Hg~M2=i( z25W@^ecZi!*NdxSx3g6GFVD@*ZCtf^nl?*A6T_i1F)nrAIIx`7jiqggC{nJ)_sWgY z4qxwhCY+w7ga}quP3Ucr`2Gcw$(XPSPPb(!%Sm8E_xIc(mEeMv0k@w(i($L;X_z9C zJCQ5Nri*hX8@Y&%MuS&>zHxPh%BXc>mRe%&5B=lki-<=LgkeOX5x^~5{xzH+^x)-O zrYI_ux#)7`hJYXv6&24W=OEaaoTj~tNb)Y~*VE55bEuyu6THUby4;N5Tk4K7#x+K4 z@oHK#fE7acmSb$IOc{2siRKJH4Z_S*j7ncF;04gCEy|!83j4v9?L-G*j$IyW ztS6J^otvCo;a0ovE$@mIV!&LV`gfq^U7QWExeHIyT+2}{ac9Y~)Tc|*&w1>;=7B~> zZ`AGCq-<25M|uhf4mS5AFs<@ACXELkzMMrab{CVyksPBpo&EiGey4X(Q;6?4(MF#u z2_2n|iIhcFAV5C8WV>c3?c)Jua{6C#QIk*@o;?BcB#-DhYXv~0CoTcPjx}dreN!XZ zJjj5+ncK2Wxb53-U9KzRNY&G=Fxp#4JQgj1Md(x{Ud;}-sbpXBD}odamL&H4=ULor#S7Bz_lsrXP3e1mfR*BNuE#)u}BM0$>zhbW-cEie0Yt zp_8u7gA6Q=lr55+hnMu}%hC0JZx}@)W4PMj57CtC1xO0C9&tK;Ke!kH1q8 zFTDgO`XVy(8ZejF-|A>3i#8eXl=aU=?!&yPcj+G_KFGa))|yM9wv*nDx9njGs+H}u2IKRrIQ@hcfJGltfH?TXRnbBoCE7b`_y z)N9CIqfQU)Jd|l4qdBBMP{Jdq_+5VMCseFNJ3FW^juAzNv&XadN`{-!GG|>Wiu7&=BC>$l^iFeb@&GOQy^^#sU|3n4P10mACgL zofS_EGc#=K4?Iyv@BM9r{Jv6`-!d%C81oVEE3F{6r(%_Zr-k0Tr{oY-+nTfaZBUZS z$t@TwK_&qK{n_UKIlaPgrQls;Y(p>DuAam~ry(Q#jiLX8v^Pq~HanXVx12lKS)`84XYb+1 z`95r*#j=WfCs{oP8G#6uPUisVjxFD`g=FUsb~mGG6oeC~?zDB&b9Z8VLD81(n%BAA zThO)mVR&@jnJN}WTFHA*2isS)Peh&y`_0@o6X0NG+N(x3%?#v2bs17!0m@pOd0L**1XLb;r6v!UOsEXmfQ*{OvxLT z*h))SA45r(qw9L(`OLjh7W5)cyxCWGX5E`+ZQWQ(+%hb5EI(Hw-Q2|t5u$vOs8HtAwqt1_ru3 zTCsxbEkVk2vW(H4aQ+5m*Bdm_#nF!{&d-IL9wwbFZS4jglU>TP0*Il>;g8Ypm+%l2 z5@(wHdb6)6;8~Dp`oVrG?(nfw839ln=t~*wC58Q@khWt?hEdxG)PK-p`_c?Bcad7F zt5@)E(5=7;Md)Zlt`HfePBwG$eQ%CXATTv+PcZJP=eWJw zSn~$pY`}@;MBXjG2F_JJQ3B+=VX3%PlAFU74m)d|91b^+(u&w&;NkjsjYsYgeI+Sm z$pD$+FVgGR-$NfYZhJQ~Gc!?Sb4SrSzgN8SQM>Kx_`XzqNOhJ^HZ$S8Jq20zc1UV! zD(bH26CsX-jA}wp=gD&m>_4~dp{Ek3{=$`Nk+NLrGmf3 ze_Hrm|6?Amy=r#)uAIDlvHB;ucq@dJr-5c%nd!-qmvxqg{tZi(EVZ(?wB7K&xWShA&DMf_B)Yc zU18x#`#wQN$%=`+ZQLsWyADjXe7eQB^x`P8u(CAE4-HbLD&(F-I4f9$Mn;Z93p%)5 zqkl&+^<JoUfamH#&P6%RIpI1tNtja?m!w5X=0=A8Ks9y%uwV?^|u^B_*H zD)3#veQc?EjupaJDH5G4EvtC+ZJwS!E99*JN{WdZ8k|~cS*`rseC}W)UTFD=+9W~H@==hQc;Fc8Fs&j&Tl;qsj}># zWjIQWl)XL?ACZPaViQ4J7Y6;;k&b<{i4VrM%b)yqeJN*mB>j}^a@i9$OEWz@JQUov z-=}q-BCu$0JAJwIH;Z36dJfVJ_scVT_7j^Nl;&Ay_r25dzfJgRPgG0h&@EykDdXjO zJi^{!!e6sp`Y9~n@`Ya1k22Zmu28WE4&JoX$z|db6Wcu;E5JhrYLelSKgUUHl9+1z z)bD>;2_ufX(T~u#RCC~T{UY^2Yl$d*B4;M-pNQx|g!599cnjw3B`ykN!b|ZHfi=r9 z*r&W>tT$g|2cUCsli&22zY0BfG1@|<3p<${G|dH=j-~&l6E0#G78AP;Y_ZNP>B2Q| z)0$5|kpCL>2Rb!mCeeE9PhzcK$avT>(3`EM=vNSs_|h8)f7cSZV+t`H9GqexS%JMQ zU2gq(j%Pqn^tf&r2|pk@EIt~V$DnvW)6lNHrRWS5{nJ*bn_T%&U`0Hw6G)t43`^g) z%;ZDc7@?eQdwGFHt>Z^SLqpXTZ2Mh{L$<};oKH8pv^LFhpCx}Q8Nda9J@(!zgPIh= z8Ts}7{jNPp2WvNz{0GHk+`p=?aW-F#486G3N5dAY$q6FbuLG<7NJ(e3U;@PyH$dA!aQ_~wo!v6-acUZHo30F}a+IEv zt>xN(iDv9UTYt*Y1T%6!HM6xSuk9r8BlhqbD>EkIwBj25U%Go) zuaaqk+9BSPJ&8TXi^+`Ux@wX`Kt9EXDGFG*s{P6bss|{PpSd`QHXWuSq{;>21P?E> z9<*g`~BvL$Mbm=Yx`!^JTVZ0cfp~q zL49q*g9i_eyNX{9@bgQ-9Xvj)%#w~`4^{hXx#lafO+*60Wt;)NJ%(jp=@$fgjI;5I zSB=*AxSc)|Dccx&7I!w~=3rWPT0;y?Wm507={0$t3swQmqw&~#fARD4!^B8;{M5s( zXOHZqUjJ?arsGo}ULr~&$0Zyo1r?bD5+~Hw<;;;dgPHd9&qvg<26nDo$Z=-kq z4NaaJP6!eEY&l>2*|H(09#IVB?p;B(ck>=$xV*iv?3CrT#pEbF!=GI^@eIB3WM0BAEoqpvtsZ=i+*2Djj57+sGmm7NSv0r~gEPlMFo_ z#$?Adg{0ipMP5J8fl9W_my?4-1H96%hp>4~I_&gr;}5MO2bXykK9-=tblz!K6V$t7 zSvdiQjE4V{KJAAEIGKcrt=zj&nr)9N5sg^b`@DU-`))E2jp)*JsN(LC9?SCOb!P(B%X zNKdoZDIem0QaxEbt zmk>^{v>nVrbPnI!vJE);TCkFbq}XfjKiZNH$ivsAqUNlWXD4x#(pho;6^uxhZ?xJ! zp6WT&R^kY)NREsfu{p?CS_^+QV#qF&k_+m=uK?FF9syy7$3j8ZuJJ?YA>-H8eG^^H zWs9aG&PPMQH`(%v@f)~fdwT;A;5(LdS_wPznc#wtQbCw2`cYs={@`A_fk-PfDB1f;tA zC2V`6pe!|z(w0oYIa0zlzY{u1`#AZ!G7`4REWk?(3lQ*9_eYVKFv9s0MaTA>A3zKD z4=crRq+2_9e0Bigr;O;t5yD4|gSb|#iZ^MZiy#7v5=~g(vJj9t8;glw(R0-PNYZkGK8={StQYFB!dnT`IkT&k+}oAOBsA7adPOA39@lI z*PZPo$9#c(5e8y=xkA6Q&OI>$oo47TmwI*%3=IX7!`kbc+fa#698@9EB>uHCq$xZ# zVmRc|fC(&5Pj(-;M|t`LLRr?Y_v+QF$Y*OG!dBAn9y$LJX0FkJ-y?UDf$ zq;iD9VMKT9lk4*7l3uT(Hpx_oB?ye|4J?0zvS(WVlg9CK5&WuWhc<||qZTB3V~umf#TxvUWnTHM zfeL0IYxJ>8RpJoY#YjfSBD)gd+-6~6k;QWR@Nz!l1h1PFGjDpu7n~vz_1HyrcKua>d7sLH0|38Xqt_Svjp-ez z*tNRS&>xMx02K)+QD(3~3_N@*>l@zyycjNTcJ6#Xj^z+mzW!+Od|3G#@EmK0gK=_f z0g+9B>yffklV$I@bLXCfuLlaKJe!3=T(*%E6Weg0N}&XE5<+r*ZAe!5Kr0Xazp0{# zp!zJNy@#5=4Gpxojsu^H2zH{zIf}sv&puh(pKWCzn%+vK5C3#@99MK6?yc7&Ov%^c zg}Z_HSosjW;n(s=>yTG~G>NYNe)$!cP8E!i(+!EGX{tSupkeKe(WOw70ic6NsO1>dY=*se5!MmoMuDwe)!*ilCuwZ@-6LLp?mj+3$ zY@xa$!`G?rH;b-Yw=R)6Ko=MBgkke|r$83aJ6qFn)Hm&c3VrsE4l<)()nMF=5g72u z-ESFqKpVL0*L+%}pc~w)R2ZOFFNpt5f<0Cec-)Ea*eu}+<55B%Edh0ox zma3dB!~pvQrz9ORkqH)>5#T`yZO;Wnunl@*-oA>^;$E94?z!p+o z$ozTPIP3SX8JJ3OUD>QtZ88zpZs|5HJMtNv`f$7{hK$*7+@Q`n(KmZC5o*cqNjZMQiY71 z*0rl~Edn>XWA)9&OngDL^n?x!$F|U|6%ssGH;-GGwn}+mD7psGtUYrZG!>PQa4EN| zO^!*o{7?*T?m4TgA+!^R&y6m){#-`u?&)1g%fUEVf*Sf-{9jQ(_J9A3lL?)V54>*8 zbV5FLOWJiErrz0|Il5%cZu=LPmRK_pbDVckO7%CL0hmWf7VQ*@G=rMi-1LZ)0RyYB zUNq{*`yIAlw5wfo?Sya%J|+xMOxS{6eghp@cvZaE@Is!pcv$IiY1_PaEct6O0m5Cv zm(}Q5bAB;3s!uPg6H97g!EputO~hM}ZQH(ftqW{INQ3O4vVN9YzNrl2tFC8j3wzx_ zABgzYo6V6>7Zn`b@>aKcpE_D=;8_OLXGyQaliMAQsC~a<-WSN9oqBOHE__T!$x%xe zSLDvEu5-7bE)-TnT;kpCJ^lZ=#3O8cSxUQ;H%t%Mrv7nZOaYEE8<2BF*QKI2dJr{H zM4`)`2>X}JE`UvnV!RdNhhf@O3*&_5`H7If9Y{T<+0pSqOW~bFRvVk^!dp5BWrYmm z!(B&NIK+f2zofk8wchf3cwb?$vO12kGlX(%04wlJa zVce{eUI+I>H>Y_TtHYH+3z0smt977V@%<>nQIl*8+2AM4{P@cx^^f4iTC+ka_6*{Z zeX%)0`e_#btR{Ui85MzD4JV-5w8QB4;XICyPYi0t4(T?mJk`l>-H_?f(jo<1J{g>& zdh`>FR8}b{)FW#9E<~(oW&+*n^`}I`?j8n!D?9|){hk+0%U9`K$y)5|e$`1^v(sh5 z*`;{OJN`Hy53f!}WB7w-q}>LKih{ZfyZ%_6^*9um4mUrzDad%n?Rwy8(DH2H4EX7h zo@5!O4XMR+5ZkfPWtE5}5rrD7p3_6EnE?PsKJw=QyDbwvskUgq{nH!q36ZgyzUHvg zm0VyNg2fNEOTp{Fek79%t+DgQ$}CILcbq^(6Wmnx_H9~3M8v=%Z(iCJN9)tC&d~F} z`mbjS^{q6BC_CmDB+YM~iQV*^;aj}&_8oaIyF-ns;VQ&Ad~QByjT9YwcgsBCYag@V z&WD#LD(`AkP1(VCr&J<$cyD~E!eU-J-KwcFUR%F{f%TFerO%Iy=78y`JlzK5 zI@SQ8Wq^|9Ah&M~<^T5m7A!Bsjh@$X`6jHdfhXbE7`lqmf)7Yg3#Z32N(1HR$=fzg zv4hP$d0Uaiw=fg3G~5+?TwBlu$NI@Ae07B8u~!&`)x6F*W!YbJNc^j2Jp8#Qimpv> zQg3d?{V9f_^}EyovpoSQabm^#qbjp}yS;@Uj30U5KMskGaG@oTD z4fqFUl<~j&T=V_E)pi2aS|u9&e)j$+hPw5?FSwk1Q&KW0aoxX1xNF+5fSw)8T6=9E z6>6Sd?5vm8BGw%J=D6-4b?qdqhGV@A^vUbryZ(;2cI}`2jw76~07}CwN`;-5;56!x zcYQ?-`mp&OU3sSH(3G!3aseaMw$WYHW+S>Jw79(w%b!YQQ$D+*r@K$VT-R1_#D%at zE~OP9*R>%kj1NzYJoa4y>)*$t(r>_S9bKUG2Ws!-Mpl|KW!hpXGMxh9xhazZqL(fqgSD6ePbe# zg^5!Vl2Bw=V-~@XLKnhTJv@K>j$($HEt;~!9!5Gk*Wf@YY!jWZ{Po-(b9YQNG9gpE zzOy`k`9u5O5d;fj$MF7POCD4NAG$BAl=SLLwflj;QolAn!c_0D!}eL?jys~s`gCTi zS&C&?t|BeY=kfLC@rbE4tjc_Y41f@i3Pn2az3I0na#LtWGi)@ZS{asB{H}phSLyTj zlA19S=b_%beca(N{oZxv)E8>1g`E|iV>bUk(n>y7y!hEO(#lmr(TgJCTiUIuKe{@_ zBX432;~Z%bT@!0e2KcfseftK0NVT^qOy3C#In5nO(?`E`7=9DrSgu z{POA*A?oOE)Mvj`RPB#VpZ8rl{vU=N8iIC?(!$YwdBH5NXj$gD*BSd<}{n1CR16%i%%n$IKF?(d>*R!N~ zFW{yl7+5L4smAz?VRhfp6qU$?9*=}o6XiNPW5Mh^lEb@!*a0$#44_qChsjjWcj^M^ zaA|OOEzgp5dfQZgi@)T;v_pZ9l$BYct|uo{bZ4+NunR@G#V%O6c?IhE9m+mnsNQn1 z7vWi*A=G@%XRT0xx651N`fA&lUHw@pKDHwFY}CrM+Mt>HMM|UeBausBnr%eAKdeP8 ziCIB%RM5bOkMVlX6RWS|Ro01lk8Zh`$F#W!8u$tT(K>-eJy4$(OlexSgah;=sSl?D z1K)RqEw0bKU&Fq4!OP()A zJAyK71@n90)N;M^$vqcOy^XSh#S<*L&5e1UIXo~M*t!34&#u>N7aMjk2ER>eJ9Q;K zR@(zdf#~;c<*$b;M}{`s9~1p-SkjWWvwyO9$qkl+T6YotQWtQ`FpM1Z|G2D+@DK)= z6bB2Jm`9}!=cNt5ytnn-oX?1IJ}i5ctHX6)7{=6y=iU&7HA;$xt3C76U8IWVWa$AL zA+0&pS@HW@=^w;ms7T;AKq_rrI`K1~CboI?r=qCRHe?3)LIICic&$@oh@V4SS`8Z9r* z2iNRBscEe7{Kv1yZ8o0n!Kvpg6&gB(OAL*p&bxY!{yyX~85>(Vh}=D4c-zEKLiODB zUm)}+dq+%M{M{Ju6^*Vst2201<`?UMl6Bl7xj8vbx1J`EJjT)|IO?@hOovSF{k2>M z?A!ekn2Cp<4B)bk)$en?&*TkP?b2kK%YJlq=alhrk&@r9%+50vULqNQ zW6Uzj38MUw;kr%aojd(D9lc|TswlS=CU`>FcA%@h|LZbcb#$6GOkI!nSgTHnY;i$ZX`=6eRmrQfKb%cp9-cbSJ79wW|KAB(yC zdHQQpUcnrof4*UoX4Jh;OSI%(s0A!r?7zvs@fezVeR?~cA0YQ!H(d%*7K#o#U)+|2Uk;7($nibh$zhDZ%Sx|d zI;v?lx_ZZiOk82m(Lnk8Ri8Q#rV~`Vxp8Vf1rvB&NpI(Hf>HNQ6TS5wnM>}8M(z&a zmNz~9v*fk=fKHZ10IPYEA3z}RJgA0SRQ_Hq&wsya!4O-X0i!+ zy?!|e#WXG*d z+v${WINL`T9wH41B}^RFwefp}B>W1!K3~#>q4o=t7h@vrMGS^}i{00)p+(FAq^$~9 z{~Qp6wACk*R0rx>&lpCwf(i2VfII8Sab6M zKe+@CiR?O&^m0IcgDR0WIR<+w8n=sEF+F=UXTfs0`aEAzB%sG}0C4+A6fo62*5vA zD@o0R^89`Rc!I4+_{~EutP&I~N*maDQGc~ECHJ+sX4`dPTgI0&IZ9K%zWe#U2v~e+ zAJIiCc-0In5VxtE&=HR!RW&X{nQszd<7&QjX+VRR@}a%5#yrI{j#GTB$B`1h{>*5; ziLz8e=Lz35)HNN^4K@2wwcydWo6m-SaH2Ww5ZvCq(z9vDG#B9G!`9O}p1DOHNv%Dv2y;=y&OLzBP_4;*}%sFL0AYRR^abinv+J^`$40I&30Dlj>T2#IP zkH}j8=RG&bl5;~FS{uE`_<=1k!)NRzym`IACstUcZYfl!2aRJO$%4e(FY*hb7^t$(h*3ix-^kg&` z%dm)aAKkzl%tuwk1pw&PZSSVL3F{|NH|?7LWZ20Ta=BjE^`t|tRlW1mb0BZMut6J$ zy4#_{^8rM?<8(m@?AGxddn`EF1v3}He8`r8pZh(iYY}E%7ZTD>aeOYhY-pxZyn7o{ zVSx8!V-ik+LN`EYjvk1=M~^L>4`CIENr^^KO}iL%rypgRW_}EkH2bu%@iA)qlXkc; zt$vJH%Iwi~lek>4j?&Lv#G6I};4Qbq>`c0f)i;_nHYFP8=Y5Y%Vcl?M=r-sj9=0T-dZhOVKI=~3 z>d>2Bb1UHs4x*rg^x)r1HOh_`;~?$@rnyUu>6pKAz&wi>V<_8{@74q!?ODOe%08Eh z9I<{UyWp3g8HtS3_f3A)&K%TG-bzVG_@amrrSTJFT0U!i8ux8C@atuu4`mh}+gsA7 z5wV}1NIQN-#ZIKa^Wld48fobd_$ra^a^P|1Aoz$o9LBvpCVa=JGBSU}`!?f#hu@b) z6O&;EeaiP?o6CC%u~Uh<+g-L3O8&hNt$7br9+po**<=f(s5}e!S=^PCTbkZ2-Fihc zX#sJTjdTi~A73-42ozx3Z5QV=CunM+e63~gL_G5A*!Qjt%6wZtMwJu=1+_rs(=0Y$ z@*1;1_{l4EVf43So_W)8*asc!rWXS3A+Uy#r_ye2P8A7HiE0~dxAv0D^XnPEsc~HK z`YQft+g7j>^zMt=3VZ<@GJjibhTR<`pl{@hL((4HA=?z<|Eq-qU4)9mlv9A7lpUB2 zHhyQou(83Pmrp5t4L|xAJse%$*U=Ix&O`dS;j27^iP_3 z6C5fC#6;e2rk;13%cv2z+P{I2^4hf*AhUer^BSy4{C+VfK>_x~oP-8WYhw?Nx%{Kr zC#3}wb(bc%-IpPX5nIugkhoXp7lRWNBD?j2YZVftrx?ySc2Ya`T<~=qAew#)Pbqfq z+Bv9kijN#XZi@l-Juy64t=m+j45Pkvxpz<~7vlcwKAHS^E3U<1;{&pbHOwmA1KqafG>(X zAmZK+Fh$%1VcNO7IkdT<9j!{2&T{7 z>+T6!AqW5oY*R8DHYyeCMy4V+zHi8cq)(a8h=JI2#$V2f5@qj*a0=XLS+%;et82^^ zn4H#0C*2czjH7Pz-n|RSOfXbJPwF4Bi?^hXs3>ZNWZ}wY(Z@$PUiL(vQ!o&aVf=4+ zD$_;0<41(Dq!Vwehb%Lz@oQV#L2$b7`Ko%+Zm(GdFWAscXBkBk{_jp#9>E4k%HtQO zERXYg&2aU&&tT*^x_*f!PtMsn zwr>OG`lxaqOfkLi@T^Cd1?;ZVF<-ILJ$%~H-{M>-`JTJ%)0GtMxI_9w;OImNp%9{z zY&k%N(`vQlZU5 zh}%QsP>-J6t~A2pKAy4~@uqJnMt?j5Q~I_`+P==;5ed(%<0WP;o8Wkg3#YH1Bs1i) z_o6J!eExVh5y@WSBG#6e$dkCCp|wV*j-R72 z4f-{h2kJ_VO8UU3*sZGa6$Sn};Q>rYr~?{hL8|)_!Lai-bKsLF)flEY^hQ7i^H74) zxqB}nQTV|g?Zwa_V2^{Qj@$0Jj;S)TZ!!RQbbjzPEJ`ji#k!7wcPy!A0f69mF1vT)7g@sZ^q$F|>-9~Ri)(6nb|5@EGV_8*reg8j_*E1FD zniTu_H5#ht<|J%3%s=C)_de_eKdTm9~U#!9-`6P-|e^VcrkrG{BbIhB!-q|N|0QttgQ4N`9N>pgSv3Gy3kAA z+zAa$a7)p6{Tyjv$1=e$-?kYFX5y3{@FEt$_Q4G!cDuLCT{1rUV705~!>0=5TQW79 zadJKRjl%dDDw8$Q6TZr?w|GsSKF;5Wj(l(KXcNouhMJWfw;Ry7F$KB1JX~l`RL^*d zG<-6do)m~@G?+>P5%*L3fXUI3-UvCDo_llLu(;*`vW&nNc_muusN8^Bl22g_Uy3(BY-j?vk$Z!M_M2>s8@ORxo6Mgmni0~#`_z|Z0Y7U9eY-9t zE$p&8hxMVVrJVEGaxjnMMrS%fP@9U5U*l#}qII~GpOdSV)C+e1&(;31zLXy@E?l{} zXZ1&shafKTMSl&gO=NJzo>GyFR&^DZstn_ZU|>UO{}h<~97kbFsk)f`Co=0^G>V;F z9I`rN{Z&3?B%~9QTVD6J#oY3aW^d}QxNO`1?ODE9j+>hw!r?9;J?j)r-tCh~fUQ1>wM%9i9MpC5#}-!+jIOy3Aioavc`pL6u9b|u z{AYBy_Qg5L0SZl!h-MVhaIB$U>Xow=WB%%`09=kNl%wPpsbo0UN%%E%nPcRzR?&xV z7hN*{4_)6Kj`iQZpF7HEAT*UkBs4V4x>E`v#hqPds}g>mHLmNt&hf3OZSunwF(^-@P&+0x-8)e}rhMvv zvhs+}2~dszv(3hh`GQf`zQuMFH^{9X#K$_`ymMz&FkK}Jg-O^7KsWA^w4v?(Un4>O zDt|09b2!Du6A1DjA?@$I;1)#Cn6;vdE|NV6vlk-|h#w?gKBRdg9Dq!OaE=DY&w*tI ztAra07>7kI&WrES=lVa!bXV!uWrYjZo3};@(6fGf;A-bY>6sgKm_anJZ?h9Hcg1=4kQ$YVf4yg+4;v5bbIOnLyaAn` z{U>9_)V1}MW>yakBZh)_!#@bq%!LTcA(R0n#)ib3%Jmbyx~-CD5~emTJ0nCa+W~6Y z`MnL4KZprk{cCT!)xM?_#gp}gCNvw3$9aB|f$aku)JL4jpkcM-;a}l#TY^llulV3a zwV@})Fg{}v>d55>}sIVMkh**xacang}ms;#9THHI->a>nrRa6=GB)byZA1J(OLd|9#npCfAe zu#)9RqZ7+#M!-Ayd35~6@el6^WqjItPw1|@9nDODE>p;Sg%{O`0U{<2Reluwr+`YA zw5MCiDJ)go#*cr_O_jyepoR4JB z<+CGZ%iKyhD%(`jt&A{JbfFs_V=K5~xIMAtT#`=7@xvc;E} zH{iFC2Y;<7gA(7Dc=ec~Aj=kT(ZbyAoWTyB>$vPW=E$7%+fFvy5t}hl5 zdH}xSbya7;)wY=Y`Q4z$do7#1E;um@g19O;K|}V4kTcPaxD^-}n63J1ni4L{izk;~ zV)lni_xp9=VJ*m$_g~#Om8Dxi`JrzIxn$r1)m7E;yr$@`lwYEEV|3Th2j2jU&qwTG zf^Mm3(hPdff~JNmJ$JLk3Hv!TZoaASni=V<6#)@?KO9t?dmb6RzP(k&K0dqk!O=q3 z^>f`0N@9vc8aIkRR#^BtOe(8{ zZT6gbDbVz-#F&8bhAUS9O2?P!ol0_d$IS8ShX!KVBa_Xhb>ZylD0%1$z9{`SDc-{# z)okYkvlxlH<4LE)?}+{w*L6uKZM}q2;Pcq#725XNyNm7=p&~hn_sYNEU>D&Dx-*;t zA2t(x(`JhVb}O_jkE;c|dC5=}a7Gi!EI9^8 z@Z{Dutj1vJA;5^usXRd<6a&^uXD_?l^_H8$E$v~3n~APfN-Capx=5l50=ZgviPvK0 zxcdG7WMe*NSFguDhcq*w;P2eorqlICOqIs17HH=zzaOR8dxlaSo5+v(nDxzT(htZ_ z1usEBVHh+RmD*kWN;ED4a?dM?$cH5iRIq6uBEu6hVN^GP3KEHchd z4&AY<(=rJZKkQ|Z?thJ|wKr$q%f9=I%3%YT1g28CgJUa^<}1^#b@D@Hq!9wEWqTLJ z_Zmc+WS}#PbA#Qh*=}bcCY4frG~x|7qG<He!8Rkb^uF7<%3R3Y)(Z++ z`OpIG_%CCG&MHI4e@O6j&GzBXInWpxta<~>!jm{mRJOKL!*_Ct>YC>MQn&5GjL!f4 z%F*?E<}#Lq7hzCiKp2^cv9Ym_i%;xo0nf+;x}?#SQF_9s3McG9h^P<>OXvC!_b`v^ zLyv=!*C`Gl9ADR7)M%8Sw}NNC^SUi22Lc-~5PPif185{qDg=9%>}H+)@~TnddxD)J%OmoN?~^neMzt>1pnd zhVvU9IXelw8;4eIIQ#*(p!6oRNz28KE2+~#E|EoaI^qVXluT!=<+9E9Qmi|=c**E>uC zds?Wlv+CsgV3Y8{!~P?}b1JR-;drs^wL#T(6sro{5rdbr#g zI4UDsFld&_D^%xbe5+X7SW{hXXpJD>Kkb6yUL0saIqC$A{P%K>5W=%*$ax(jQ-g18 zs!#2lm*_|ae0zhE<6E$x7^+E)DT+|sNlh)m-cq%fVIMCCnhiQ(PED)^dRfWTjX1DsIWPgs7@NGCADzBm7Lz~`Xs~a~{7$^W z#-!(u*vZdV8NCiPlM%speE)eiH1mYMG`hY7*wrkzFHFJ!%F+YvdVAnLXl!KU{@|GQ z-dS$$i-<5gEh0LywEzCDfcLHB;Dro9eEnKRDLNYt93bD5^6gNpy}Z9#oVB#*wCl@ z?qji6d=5d=$?Gzsnl^Lf9x#?5wZn;cr34qom~PTSJ(CEl!%dQ6m#2e0QU$Rtg^z4~ zM#kg+9L=h6*r|c+r^!!Qv&f+2A=>PKpreY4SAm!};=Js%YgK|{PNYBt^8oPYOkD5u zTNr7}4&VQPQ;*(88h|YI921Gp0!MFYodV(DKt27yVO;g`ZGixK7XS=bGJaWYokV~5 zIw1c+<%PSz`6PF?oqo=Z10c)Fc7GmtWQXWPHlM^rA6!MM$`5b5itq0>(PYd%1oy5= za8*C(al{nfkJZk5G(#$+@{tDi-Ztm|vI!aYC}FL79IPQCAl8F){Kpv{GGxX(#`~Rt zuGbiy4luSgk}8sb9ZNV=M=J3lZu`knJRL_qN+=8n=QHi`I>u_1RRof7-vt&?E85q3 zEt4=~a7|9PtLNx(Hggi=z#q~Rl5>UloGTeAo`MmVjD(AnOV(HX z38A*Sj*mT%!*%U{sy!Ze92!?x{iDgY5@e43k?Z$Vnp1Ks2kpZeGnuQ4FC~LJr%zg~ zxA^9Tp*4=MPA_x!Yo=WyhwT{4In0sBA`5Ok@7Mu~a|)ThY`ysF`OZlLl51!$4dFvN zcy|)Nl1j#i>A}`xNhf)xIWH1QwcR84vwwU{2s3gf<<0?pG^Tba32p^{gXqEpd-Gt2 z+s0$`KN(F2EwCzQH_l%uPYwsS5;k%3<9$^(#OtMQ9#_P+(i3?`^wueGM=zb;pw1|3?!grNlJyqHh#e&3sUQlttr@V(z7_nFOzyfB zDFAdU$FHNk5BN5&2xe{Q)ASjzu>Cm7{FZaJOQs?_{w@w`CD#31<>$m2925t*6!fZ} zSjg9_#&k#VCm+6P7lvWoFP|P1-VBal-w5o9D{aw2Bev^)V>p_ZrCA%bGxA+6f=9zi zM6#{hq}OtXI8(UzKZWh4IU)QxgK`jk$9Z>Pt?ivC#rKNTHgYrhEBB7C={K?_1(Kbe zT~RX#%)=`a#$Gk9+jm!J$h_?J-O{1WYJ$aupe>hID1P19c}=WY+J;P>4LFF=O@DOA zDWRGt&<`Y$dbBS%n$4=vl`EsyQn*VFgtjm}RWc%&S_YUAqLmvd-6%T!lixqSMEUVT z=H;bMAxrtc0}I#Sw5_AyrzIg;^w4!6zM9xl9FR?fAd|vyAN@rncz_ss%hMRM@ExQ z*SOLJcR3Zg(%nQN>j&L}LcNDZp3d+W;E&HwI5Upx6l`Ex#vrzqQ&YW6Q1|z4$m25h zi{_MM-0CAPXk=91nV=TqQ?EH>?^NqhAGvuWeFv3VVbu9aaP2!wIRg5xhZSQ(E{ zSvrRsKWn}E(8TU#cG13TnxOA-4d=p*)6t9n^I~SXF_J^yz$%w)nhUI|BZf3KR4O`D z6BF#^m-}(qF!!8YK*ofNRcl`(O5;|LM>q>+m4@ff{F0hYJ6>n~4oFn!FMsS69DLV8 zzHefq@6e-umRUuxK+O5M^R{ccPjdmRUu_Chv4<#U6zWFD>*Qo03WoB+32FztH!=tw zV6*CePjgOM3tVp8LO-q$vuNC+#%Xhjy$Mi}Cx(J;kisvq(zzjN_4F#|C|>4!wJLI6`j1|n$^O|d0A>k$;eDn8;u}Z*eIaRRv z+KkP_?}hY-dA-3+#pnJ6BYV%ojkWHq4d`G2$QG+BBtBFf=|BN7RD8l%_2)`AaSqLN z(;EOD0)w>j*Pe&5Kob}~NjNs?WZKsC7C!t~dHS2Lz9Py4>gRQws81JY-BIK#><)Lz z&#N_EeD%so$JkP5lFarH@lKjBaf0<+E$X&V*YNGqi>j6c^hK*~)p$)CJKm_=fztU* z_?2c3#TWI40++ZX9JwUn@0L^E48#R6$j*u01BjoF-8{?jQLXF}JnXCQOb6)Hst6~fHRDzWOXXVfkwuuE?*8)eQjOd+vv@t|f zyiTU_9tVj3y%w}Go-gl5M@zm8^<1I7Bps~;$or|7G(9E)u@@^|al84lBU zOtm9lN4CBLhRMUX9WeYEz~Cx+bDEAQM<k>V(dm(Z;^d;~~iO}RLZ#Ge{esf?bC zMWkMCoo~F*(h2{V3`>TlqmOy$kPt=Qc^Ehm=Y;9JsK^Gh0NKu@; zEnyvvASxXdIqRn+qK8P*k39M1G>X07*H;-Kj-hrR669DE@`|^7#j<}(P!$L@Qu6bq z1yWlUky}#+TBYJG%fDKae5P>_p+fDP6EX>>16=-U-?4oc@xgQ`q_VfK@-=x+iV%eV zmDKG)<+O_#X-V#vl6N(pp3Wi5)&VSHe{|K}|ME9@SnuK8?0P))_gLr9(abbzUq?np zD(YzPZ{jywD7|Jog6rRyK0 zW6UYuZ>p>4J5+*Owl9CEJi%^Ntr?YN4NN8+OmyRIKF2jCZ<|txU_4`cnE=%v-Dl362vUk zqLnt$Jk+|5&>o|kvJtX8a^@w!UFo_Q_mdd8Ub*IXnUrJZOy3SK9+<12FgX6@b2IVvX-Y;U-}aij0^-6oM}?)8byY& z`X`5dzwC&cgyr}FnUR1Y7xCM7FI`bg8SC@C%Xj9$S7$=?0TV0>HR)ap4}!S$L!)=S zrqHr>6!kD^?-pg8uG$2MYaexNCsG+VY>FVEudQc0=TA)>SqhaVzy}!U)O&v!c!Xs^oQ0&D_WWJ{@Iadiq}YPIi%ivw09=Y_2(6ZGx&n_ROj< z)96>*QyGRI4I-H~6~#sK26w+_Bp5J8(mZ7l`=jCLQ5DL8JQ?a=^Inp;k=9 ztH*zSgl=a(;gJpn#@622O;K9ISdvqOL6!y3T;t<$$WnRpM*NQR_ZqeP#=%HSaaxG@ zOKvZB_ODe%_Y&5mV2Zq4$}TZ2K~wIoQvkUV!2vZ;T#=x14i(cVFc~Rj!KK!Z-I)Tn z#oQYQ*ImO=7j^qdkO~7=YE;p|y7$bpn>W!#ydP8UShd;6BkXL4=dLX7KF`~EuQ(pj znw&;H8iT^UKjrlq7?zgYaGh+8b$VQVS8hK>63#1L2gLE{0}S7xHt1S?UT3hOXKOyJ zTU2M-;nQpI=9+aC*Zx;AnXS=ItRo0xuiWkfNe2XDi~XXERl94Lb-6?)46Z)`ekm9# zm#Ph)_p-ls?LBf=^B9r5%~VWDES=)3lg;}*HEkt~Vz;%F6g*@$++u!wOuT`uJMQK-^X%( zWTnDWqnYxRXC)zDUP*Yd;!iz0RlUxlyTwAt1uBO+VV+?QDVcIkR4v!%c#e9E`NpCB zRO?@Qqxp!1>@rfk$O=Uyr3FR=goWuvE;E&vx(j8ZhZG?`sL{%+NjjPUlmEsT$74JS z!q^Yxk&#rNr<`tQIZ1g#7-Mf~&yKD@oo0to#T6U2*C@kGP|3#QD&|T~Ty~DnziI16 zejg{<&v7!f25DgVc-5`p#F068WKCPQ2raPw!faAt`4R%x=e`A6k}k+Pkiz}7OP1#Y z!|-;F3FQ|1Vl4;%YM-->PcP{W8czC&O;==Jpy3F+GW*}%hJ$rIJ%~QX&MUI}I$aqx(_-KI7iq(y&N8&7a z|It@#wU?-(iYZcgFG$}ZPkre_EOgAOFj9HCih!>8=sVww9nCp&-xC~|8}hm{tA;Qr?99IAFSxbcxWE0LlPh&{t^X_| zCAL2=rh@=W;&~BDf6NU36tEt0bk03n;Aqwa6>E#jc)uN-_zpWQ127umJBKWzLIT-j z;7*cQm2UUBHB7Nc`Up1ENeXiK_6Ohd0a{r0@+Fhbox!>e}%-u~Tohg=k)md_j>A(Z^xiU^oD-a!l?BAyhj(}R(^l6=6VB& zSnD}J{_$BUtpr9P{+kOmH4-)7B}Mm21!3?VBy?r!#*bwf&QC*zHv4PyO-AI7Z=p43 z#B^KmU;VM)m&DAWp%fbUQ0~sIL-ist#WH{|Zet>zEjy1kr+&Zy^B==KMG$mKIpM-D za3*rWy2A6nB7Q6|Ipefzmz%%R028fHgF#D#%l9ot>Z{%aO@wVhEYCPzLD=qqJ)iS> zoH0y{W?&?kNc;MT@muJ_0;v*R0cw4~H|8+A1+iDEtOMM#h0|(qv36fArbsCpo_Vd4 zo-?hyKE0mYUPrXo{+IKatr1~!#tAdfzU_tIz5Ue*d@Hmt^!=!i|7jBN#+vRL?=AE$ z&L;L@G`sRet$Q59`r_EZ?6Uf}*)wrLZno~Pe{fXxRiUK6dgL{~N9o7>3RNG*vm3*s zHNJ+so41{rPUfgIVCYunUe5W7EJIV#X{DuC8?pmUe<7em>&TJtnwVA=c)>lXLr)@f z{T#^Noperd;&IRj{Fh{CWf5Cs#fmhX2n-qZSM7KEzb?=~3e#tC2Cr z1fvh&3bWSHEf^mTu8HVo5;^|Wn{3ury!LOwd}5wXbp5AphlG4`_D(W=j0PtSsGlZ2 zYjeoPU4M=sDix*lkofP$`Ol4oO?1_j-9p_>Es$@-Ek9mp-KMX&ydFYNpP+b55=>e9 z5St3m#%<0-A9nswPJv?R3Nj)1hHf*#FGNve7tQuHrj&QXCe;Q6M~xr@iayXc2O*kI;erxaKc^F$0KoT(%!;-K@TkmJ(1*EwHcIPchX znM|SAw6lqmYanb;Zap>CZf|-DzmSYU`hzy`S zPtb|j)yTf7_S$kzAgO+jh~fVI`@K%Eteq*k1GsS8P01X7cc4>MCT=^hevEMdB;SvT zX~Jb;+3jR2yXsrQg_H~LM?cD+5ye_lJ**FPw2I$70SNg9)LDs4!Oe=X5BeYlyePd~ zo73?t7r8N+9<0WcTDjugq-?ZeL>vaD`tz+hD58s|?tAziq%-E)Y&qFbN#fZw!CsD% z{78T+_=!E+9Y!&o|W}F6tH5I(#TjT>+rcv zrjKQGIAe^^VB1KO`dJz!KK9JXi zW)qYrukT^mtlf~yYg^^Q^0us^Voa(WqaIDzbc27A=eT3ujCl>?74)g^RPQTKufpFe z&rOJ>=i(3Id?4`|Fv-_R-LA`%WAreq2<()`U**|I=ggXLZxd~)vVsCrAK#Qc!v$7C zMMs?V!&kwIMTaAW4sM+yXW~TfhmAUCcr5)g{)P^ntvWt-*NYIdXognhoG0DL=eD*u z%D~Oi7-Gzr=A{K!YR}W=Zk~3kmEswKa-MzK@717|@5ly)M_{!Js&9i9iG8#V%e?+= zmbG?mElwC9h=+)uHmqDcN#HM-nn-q^*wM%&&opoq&WH`l+gmtnnnK}}GAI(kH@ZGK zJMtAD$r^2dTkVoIe-pb+8_?rUa)o}(P?cJQ7@=oBb%SS`6;>k0C@wucl{ql;Q&((R zuqjiBK>%v_fpcFFrBidJqUJQ92|JfDoTN>7dCOGCIl1?oamx56z7*GDtUA?GS$$zb zz|>%Xo}w+Ec6P91vj~p#_{UCVtTxN*l`%)J{UTEvwElJ?yLo_Sr@}Vx6C7(7+f(2# z5<7Gx9d)`L+>;vsY<1>J;BKxVhBpMx$bZ=xIRB7ByW*Rjm^koeT9<>ic>;UU>T+~x ze|-A@lgN@K+fHg4KM@@oM^8sMweKc=DV`i_)`C%)UY{nE9lVs^%DsH8;gdQ|lKg)U@|Xl8?u`<0UGR5!Gg(51Y>~r^ z@g_OJ%D%Tid(;O5cD;;r07hIS`;K~nS@7k-z+GsqeIqD@d($i!!BSg>Zv&`2H^Fl#UUWeEojSL@Q)JY$_-+aQbCx)&wa!K| zv@06bFOY!1ZnH>F@0&P(wJO93uj#lYE0xsiocDNpu^v;eVkI;haz)1)QE5zkuQ)%t z@^eT-@-GJ{rh?-ilZho&j?(z{9sG|(hfcI?|Cr-XE$XM-w~wjrJS>$3tSa<*O4Ejw z(}NQ?4?-JdJ1+T$jrpelW!Hf%fv8n{Rr<-d)x@SC0g~;dzCbQt#L>sZ`!>pEWAs}q zyC$bV`&=l_a;CKr^!ITbLRjAv8oXXYVO1<>j6~nf1yQm3Hg)#kbX_oY%-qc!p_=R=|mn7iys#SU4W6tzK?{mM`)vKX) z0n~UWc{v;qSr46z!+HvSz|yLq`=ca^)f%TpzzSwWQg8hF3#@JAt>`#kd_#ewC}^5> z1(XAU?0GfU`ROLO*J32})_AX%0-+w5eY?i_=b>2{2|#Snb^r8#j~O~962lF;xBT4Q zfgc94I~RO{L!X+Pisu$0ejl41M^F-Az#0~)h7*+KXJeAXLs2w;_4+jde%QqZ;NWK_ zb&@nnRu^4`maOl6vYoDae&^MgO|gEcC!PFgWg$9_j=32YO?5e3^pqQ1s+&j1SQr3d z2K-P$;z!wUa0ZE=j+6miwN=I0-nr7rp}+31)-`l2sPy|+M0c~db^DV^g8J%kaz6_# z!rQr`CjVqRAav6UAibw(kz>VqU~%fE+o1yKZdH5t*7J$=7czXoSNn_`{|!cYD$9UPTgP(1W@+$> zo@=vXE}_87Y*Pc9ky{Zs`JZydt(~yO%DvO3e?Wda#C4mE3bW3qE!U_v42Kgn4G3*> z0;i%1O`cy3?8i!l@Zod5-0?eqfSKKLLK#Lr?Jf|WTEb@JGc_a039`R&fhUYpmMF4o zBb;pb@0io6%T0L}KxO^n$Gz3`KbZ(okR(&A7Zw&itqFoa0n$LqofLV`OpV#u8)Rzh z1Dgll4&Fs0Fp5L+=G&HC^(vfgGM=$u4DoYi+(B0fbCfSHlrMzia*JjlX7eByt`nQv z&+)z4y5i|@^OAEXS$alP^H%p-iohzV4n*#TaMmd3MSj19NW#$I80?*<+x&SGJm*l> zU8%Tv6Z7y)hJf_g_wbVcTqXf`3$GRMA zlbRC@Zd5*!xI~ccG?*&f>`g`^I*K4z&*#VZMBNXpI(lyKQj67-`K`Y?L)u;7lt3ur z1%*2KXH%77tX{%MdtJAPNc>PvNj(;ekV2(p>;@iWD^{=Oab`!EvtaEQI+$ORxy&$} zWjc{`KO&+?$_takRK^XLAFSK`=Na94h;%~lyyMI>|9(bBf3mqR+}FZCY(_^b1Bd{A z5@&f7OdspuNz7im<(Omjyp`ld@tC?*KUfYYlxU+4Xto$y)(Y^lUMm8>x)1DC!PDj_ zjxFGSM;w`MG_RazzO^C;bRi2OP+G4|A4P9};Ah3JpV#%A`ZGqsT@Vj!mbn|&_^~eO z(}X3>QG@0}j)K^$Meu?97L zAk9vg2)6o^ud@BNqr=`kh>}vKbg}Ee)Z+WQtRE9V?yRmEjy6LLeGK_BLHgdzdDhwF z9(@!b)S9^|e}>5Hl|HLbxTONZ)&jyWvS!WfCG?TJBzO<%^v|J>FdhD&-i=DyLj9R+ z%r8!Hh;E_frIlAaVj6(>;r%GwaU9}o&d13Ggjez|ZDal%L`EuZ%+18D43+s!3Ec__ zZTEc;V3C17GTY69-`jcb&Rc2QTg_j+JCcx8rxqv>BVc0R_rI9_!Su2%g+?IkIT`6d z8v@`t1H6MD{Ky?7l41@pg~{)ia;nOeLW^g^>Tw$+hq-;2)2HH_ZJfWoS(W#or1?d~ zFFqMxjG-WGed-_In#^Z^iHql~-*PE!lFM38Urk)h$+@-v4hqq;H>iuixbEq@=c)NACDU9av0KAG%91Z$%5rNL*x zu9gOL{fCKzQ_ZQhf4+NCE!5(TKgdN`>GVzT`%Wlv#ctVTbz=#P1>I>>rheEgr=ymq zH5@=NxWCms^V{SfVO>wjtx#hyapvUU5U)7Kr}ZXam>v$bfl`;N2WW_98oc|- z`Us(Mg?IfI>ev`lsc;_7p`|>?`LL|Ua5=@zl(}cb68K)ZY(6-BtxQzp zdO9t0j9rSC9eF9d~ z)<%rAJ?FL$?S~9YLY--VS+5@88nhcAeVIXKbe0b(L8JQ?#lrZ9|$=f zj#l$!=p#iV#)NPL9b7ec_MiI;n^_MFOtbL9wg37%QX_Oh1aZ*E_sPpFc*7J22~l`3 z$2?f5MN{4`BO}A+86*Z|Kcxu!A(VTa;yx5n{?ZD2G$QgpMU~XS!^O%u(#cHsZC?Dj z^=t&|YaQHrs=49Fxj{LiN9YP#8gSl?7{52i_r;g)G%R6UzSW$=oh+dY1~SBP8m`(` zmOex#nxOq3?H@IpWo#vFKFtMitET*rLhr5%h;}BC z=zKUu_u<^Lizh-fSE?<8Xm&egyeI0q;+80e-ARZ7i8A%VC{&smmX$eC|v?{H4nal0SmfM69U2xPm;k42FXI39Hh9DX;X?PdUFyE^HJRD9zjKsp3L$hwQwrwQ?4Lj6XQ=lMklR|yl! zLlVMaPx{pAMa1?=269DAbh(GDRo+k8yB%@p;>_!~x;_!B+*7Hz8D&ce<%iBuhuXI! z_XPHQ3r|~axfM&vjUi1KIS_RztxkL&*Iab?^ZBXw$X$~zJ~1=J`tv+{@H`$HYanmT zR+>Ux4DSl4-!C9UFtjhXyaV2mBc_#Dut?#uY17_b4M;R&o9WdXu;|@BG6LvZ zXorE>Ei*$nBHAIfjTU28E?2}>DY^$j+-(Iu-@QmG(r39pmj?N@FOV~>+@S-K@XW3v zfAWaLDm+*c12GUd>^Q!Nu0Fc|VTQ5Ps_eZZXDUg!u&*zrQ5l(VGON4G@BKQUj~t3o zxKxA5J}zWbMF~WbcMS{|X2Fn+Jhux23EqOih*R*fN8dVFq)-l2?goVh1wtAcz}t4A zaf0dAu6F$IJ`2}IelVKe0X#f7qGlU*5XsR$9}`y=N|?IjC7p7RPBF(CoBn>XjM zQg$(|khFR6mad}BPB<#oyBx42t-#&1w+nDevdCN;5NspyJpv`*Ngq9;0Dn}Gm@TI66@l%c*BR0 z661QI!hr^ZJAv}aTQ*Nhdz;MxeG zSoj{_ynTC_rP{II4)aWcNJFs1CbK_&1Z+u=t#(s{O6mj1ozIX zHs;xW;yUVYvW>=0Y8mA)$y#K%oe&7Mk_{~H(kHYcx`M?!kV?bk>Lr@{0?2(qiJZX) zyiOU%H|d>WTwUK;WIn(<(~^*z;#aBsJ@^=pVE455i~o-@q39`|Deqgy#w|G89=d|v zH7mAz8!Z~5uTz0d?exFjb2D$mQ*F4UY%O@?zzZ`e1*-$F*eTn%be}6l@%VYfc$|bq zzDvcDjry+SSc^WP%$HnrVCRGp$xVU&uXR`D1rO{$0Z~RV3b;eN>YW-aI)xHUDPSc0;8EFSoML7J0=h@yF1oRY8%uv{A)OMMi+~JToF8v$Q=E4=u!;5>3^$zFOg}Nk&H%z4 zAn|_HuWxf7Y>>90a8;JCCbcj|a_VP&CO?qkj;oU)vD9t)QK)B0!+U*w(jQ6lG$^=7 zi=5dPS4T;WQSVenLD^_AZc{w(BxH!#7vUNn{vt4>cW#1D1q@L~Z|tA)*)w z;!=%Nba8n^>eL|^BRD8k2ppVK2u=g4ilh|tXrbeF5LO2CsAOyC4|Y5ycw%E!)Q`}Z zlcBbCS}ITN^bSzym_RgC80fkbpOtWRN{t>MUoFQXuxec3oI;6Ab8Z>5wdig z^DCWWCJ*Z#?Ai1NL8WD-rLwS1{B!yh@sl0#UUuVjK+m5e$gPsJui6K+AsXmm6f{#? zRp;clO(sfp>n02T*H^w(<%kZ0241!JMOj%I+QDEyn)F@zMs(tG=dG^ckS)jrwp|UK zx9-3o%14z8PS7e*`%kOd&|}b}JdOubvQ);9hT$)SFcwbZ1Svh{1fYnTl|Yaw_5~>sEY4fF#_>N zoTKB96V$qIgFXA?F4Zu}3XH6ZiD9!lwix(a@mh!i5w7qi%p9PZ<`(}#b zkD9p;6$fhOJ|IOCn5a_r1L-&*ZyF$FI|;>|V3mWR`DCtT{fW>=w-!&S!1C-wRyVJU zP|PJ+ih5SX4BPO4HCxxPei0yXKN4f<;7`sbb{4VfGtvQx0gSRzAr{Q59+KcmWq{Z1 zN%+OAbBo}<0J1I_Bzt;4>6?KB{y#q57;xj5J1bR=sjxkB?B@6#uD|smuZRN=P-bJn zh8Es!tGKmG?lTX>zdv$BwYX)XJ_E1|Y^u5^-8N78M!N+qIt!XaKS-(T#7@z=K4b`d z5H(SslMk_BO~F;!>%pjWv@j8k+RP>S*Q=9}P#lUvr}ONm*9gxu!iq^{d1f{J@!f=& zg*8)(0yz4Y|FQEG$}D+z3i7yQTEgLA_S#Yw{%n$mh6=oSV{`VZ-LR)7Di{^%!9B~x zt@N8KZZS=rf1o4b^w~-?8}kPJDun$e6Fr5kvd#0Bu$CbLeCpr~gP9(^_p#{$#Z8cu z2VE>w@Ia@o=IQ@=M+WNB$?4dLcNY^;7Djhh9vNtp`Fe*gaX$g+S?%~u=O4ocFNUZJGx&R4u04V(n#-kH1&DR84oC#VfUh}DsJH-)1|iU$jq&*Q(`SW* zA(@qe{`P!0P2l~+8?^%myS8*_xGyN27}b$_=e`IeC}?GaF!~Dva$-!fip+@>E~RXv zZA${-1Lu6Mc=d|@uSSQboP617ETuO8J^|k0Bw9bI>!=E>@``|vSYQ*h8bHO-_?9RB0;h_qMTAlJq;)t75NTk3l11t**276^z9iMxGH*uv%8UWuai>6v%!$f85-gj$bz z8@v)~U{fiwdVUZBNP=WgZI1%#y>+)C-$885iRtI8b;y3`@3>d^%lzFjVA+X42bqK) zznNK$-$=PSnQUeyCTV_Lp*U#XdLXHy3 zVpYm8+B&5+=iRl-X$4^(7H(AbW*ieI(Lbch9K7W{Ni6&c|LRpNG;zu=pJ6s_`_^Nr zN))?*B#8dRVdmvjLVyS%MfyX~5YR?DQ=Hwl7y~f)? zL4mbZs5MfD#=}lQ|~N{e%)o494AM_!ZUiQ#861e-SD?;yQ0ibP+`brYR{x%BO{a zSGW~{=&S6-wf}iiR;xKO1UxP--FzvYxo1-<=`s%xUS$Sort!*We*Svi>P)q#8GEg2 z>zywztH9&U=iXWpqxo#JT&lO;iW_WBS9bjpcjZ>y#i2e&-DdBKFLyiBcy_RKXztth z{BnAwn*3@ek=0BJha1oLkIz~Aa)STf&(eaiF_{yoK{uQ#-i}*~e%JGJF2`4C&-kVE z(*n64Q)|(5H6lx{|810~-lXdq60G$;9icFpi^UHcH~}9*o<`G-1MK9N^7&D$w(QYQ;H1M$8Kq+{D1jx`%0Aq2V#O6W@p;G&7~?R zcoIWgQTr|sWA3CTILXU10zzsRpg;-|Ma-`PlEOtF7luu|Uu|{c`0m{o@!iS|rw6YA z!g0#)=FPRaJvaWcblT@3kRxo&~X4Tk}vj8nEiLn zOJXKuo4syMdU|2Kw?SDwK&0-&u#`AJZ$sCFV=BZrLCPB3>9KQ@<1fW3wQtjCw7qV5 z+w^|kE1XH0LJBuKUbxnf!nXf;;lGf$9<~n??L^*)OZ~aWoQ@rfD)Sw_l7iUa!%Vlt z$r;(iWNJ``RygD-H*(|%zDQ3`-yph*a!QBF(hORmH+R$9;+%;CW$1#uFBn)5ren{7 zm@V{)LSL}AO4}w!x8HiFjEplCss1eqmsND}`q$D;Y)=p8seVWXG+$wDkYmP?o0>-U zo_CEC1Oa`ab5j4pKIyzo$YcFzn`+kXR~?>mh~EPB)O^Y26c)-Y>w6?`(fHA+^=nGA=neTEC@m)$E5e zgCMe899aM7t|8g8PD5t36OnJT-rTq@si3795g93qo^AE~`SV4iu6cPy2|j;3v=3jQ z{wlhbr%q59MZ1ou&y(T4c-gg(nS+a~6sP(g`#j6Hr+`}JV08X7@N&Kd56J~X94{eG zr<3FP)$OfibF^3isoNaZ2VXmS(F$H(-fL=A9i5$0O(J7jn$*H8kw?cz-sIss-fv}< zaw&=*9rM&Nga0`|BFoGSe#|`3@BinEC(?a(7?{BE{96{4MhiTNNM)P)O&Z>h?N)N) z*NdDf+OyJt8b#$DTGgv%Z&BaUWXAX{st5tTe8kBC<;FAPAKDv7!IRn#2yf!Xl~4=b zFA(dzKyH)XUMb98a{#xU^kX6;jC~C7iBa}Sa~bqH`aZ5h@MSym>aA@;1hc=~}9edfmejxaSVTc{BLHd_{Ft z3S8jL@lvRUZbBrmFET1>;?iYl3!xOFm+V?F2P*4HD8N_Lm`J+KOyRhyZa0D(gNTk-(ARSBu_6XT3K1CFI+-K z8oeJ%O7@`C@#*O}2>p-vKI+c0#Ul1c6s8#UfgXCnpr6F7z=BLAU z_OCpVqreM{&nl6uL{OA&e}#~iL@Yl4plo=YP9&i8^=pgKx#0Hsf!+H2Os~|7uU%!v zV9@T}b^e6%FHxii`4=woab^z`%^?q3*wpQo+jgQC5pCb8s!?v~GzbW|X%O zY@Bs%zX0P|opz{vZb7V=yMibrKWw2`9$@TT-M*U6`4$mIz^=3KEh8~^?Ww1`UBDnD zBy_FDcKA(R-R)D15dzkvppepv{Cgbq_+d5bb#xy8pVgRvl(+tl&hW6zDFG=IEG)OE0||9v;Q#m7(#x2|5My?;*qE5i}gZ6=4z{jg-yD4>3yd{&8gUY{^+_T5EOEQ&yQ%I00$e}1DBNb+_H8O@1otQ5vr z*BX_Jb=*5Lie!X@6fp~0t^Fq9SICE>6dV-~oyYB})M!5GSfQR?Ue@#6MPqfq`~Hce z(Bgv)ka&{YPNK|xUWV=YsYA8@8HRO8;0XFn=;?!Dx-mF%hddkSS=g|?#|U{7{})_K zX{u$>HQH)wYako)i;s`rCe~9Eb3K)H6XKMkgW0#u+@G#eq*jbs`@i-QntM^klqoT| z@w6|dXg4Rz4Jd~U@Wfr}zkBztiviUS+tKv_!^cmbyjjK9J*gLaH$Is0P3Hiu3R<7F zsi~=t7M3crB_1t20tyxn>?o2(V?VD%J6WI$pyAZAz*DR#K1GF-BO4qLc%(bW2KZ_z zF?tNs_e75-Df}g*?dRSd;2RwugStt5vzVAv^WyE_j_89;?|17~{mCkWve*k3FM5w{ za^*^&X#>`8pp2%!`6g{wn%re;Yx@NwwKUc=aUQ#-vwUp~V5B z9Ekf)5eel2mm?1R`RiZA=voGcF%I2sx5FZdfu8<_++saG@C!v43|&UgeLIm0-IA1} z?8Pl_Q-u(@4HAebe6YT1Ec?2*D3d}OK_ws=9KUc2cOmgG!{W#!*I7BaOGd`V!CdRM z*jA3+1lzRg!P|eT1bSV3xN__NsfpX=@zS{^lK3vUiqP9!+1#@3=1d`-y}O;{4;^f7 z)%No7nYu0!=-BV`u4gu#4kH4^Ux1nVM)>fgXoKNLMs~Nu48+r`Gr;d=KTI1wh?UQ& z@D3LS`IW~pUQb8)K=$&D`m+RD-s-C`O)FYhzud=?c=X2PFeRa7!^@os{G4Y%=V-Dv3=?m zsEE#VdT%d9KYyYt#dAL0b(WsT*KsrFAl*V{2iI)u-ER6;kn(b%UR9pmW70;f@N(RG z--=MMS06$?aCn?FQy{c(b>_&0sLYgszgTet@B9!fJhM!vK2#wI9R3^~>dy8hn~G}( zfs*xHd3la2F4Fz})s!69Nhbqb{E<@L<{0YV0Owd!G66cf98i6{WyzdJgPomSn0rI< z@1bbr5i(UfOjvQbx(7t6{Fj>6EhaM~BE#b_h310~(V^)@VKYk!BXcL5W|j{)>i;`e zb+hHzFwF&EY#=GyI?71d)^{LS6o9=OFJ8zm6}RHq8IbYw8XFG|$1khgE?=I5iYG#y zMpHoPwT1Bo%3^dlw%wy^L{J2REzSpCep-4ZW}76B^rp{^_TSIigAfSJg<9>ox<-V;qn>v|wMorQ~bf0!z>T-JX9 z4F7^~T1(Gk@c9+D2Q{6ILZ~Z(F?6#Z;bg@q@16!4uYG9Kh;;XiN7GZASr;_&|{J@qCMlfF4Y0KQ+wZxOR`OZce-u4&@ zhRj?dr|P#EJf`nl46q|{%@?>Ay@Z6?g4qj9WS(iTKQ&QbY5K)d}2jb=PADlg+xa{uq^=LCx> zTR9AJLKv2^v8@KC$-Z={S%14{`Fcu5Mh51gTvcs)8P~4OyWX!FFO^Q964B>+nJ0sZ zW$*eq^DelmF$~*WCdQ&W<_;j{p2)aDZ*Oy0tuN&UrIO;2^Aome%^-z7BG#{&WzQAp zK8;b~J%2mwIN}DjFU5@8znX7)a)>X)i(KGUo~wob`-QkA*nUhI(2ku>QY&5Zio9R$HV8(o+$#lo80rFhYTtO>)5Ro)<>%L1g*M}7Z9H6eGMVoB080o_^tWR7 z!~Fbsp@;dkDg=0wGvcZ*yOMlq>TCcvfA6o zty;h(4mGxsiAmn8ji|c?trjvfpUHFO@+O8XdkqQ(*dH)t!P)xMsw)fFzU-sZYu;i% zpj*WtEYh^WWsoI!)3M7tANq<>ZnBf;cH)*C9b_|D@5jGim@{GLoG6x`I-=6z9T6<7 z!`z<#+!C%afEULCgePW@=-(&UH+9?$cfN{|M3LXX(kx0QJ1it_A++??rspLkOQgyi zBa<{!WhoTOdq7&F@^l3PhS3M;`*^>gMDpaS*k(c0m7%AfEwxi{6KAtZFG8r&T8!N{ zcYT9gtPEj;pL?47eRXjbqd~pua(zU;M$KZF{u-vJZ&x!Ik}=Nj(Y1zL$ z*3_wFicopG@CE-asveK&&D$k{xhr=gt>EFqLjcbtH%r&^y1LFKNp}Km=Z3rq#Gtu{ zoJVd4doU4}6e69Y@QQ@kSW~-%0mexz5=HFMeR=O47c%yYzrsM$I~-CF?+17L8V2Z0 zbN_z8jilDw{lBOE-&*fEz0JOd@cOvYCR?IlvUG!HK>F*Y&r8erE`S2t?@fuVu+K<=mH#QR+-6oK{xp|dH0>|>w?cW80w0WZA|e)bWMD-g zBlZ<5`kvkBA!B3mOMQIpAGzPj|IB3--La$fTcP%nOhn+4+pKID_~U!{lLSs>S2`R1 zp3fE?qrijk2E0gve*Ai}YLW-k=&udgHo}nt^{7p`^)w@5>d`IjzKECpXPdfqkznuU z09G{IGdmZ5a+Si*?XU1U^R%BNMtcfy{VU_k&{t-u{|(HPFRE0NvN5OuzQQjp9r|Fb zJj5`|=w8K3^m9|VjJ>C6_8^@4bMD zY4Fu7!jIU;06(P_1m{!O^Q#F@=pAr{e%RkKPMb<$sE#($mgfCPNK|zR@ICvV~3C5yQzN$(|m^h+?2S) z#6Ht3SS6i-)FH=u$&WL>t^=py83shWiiRf)z&j$|KMGVTHDT!qx}VpUiZx`k?5d!T z6IUa%O8?pfjWQVBcj3IUKkjFA$yJUXqkSU?XaSAZ3-jvfK6IIIoa7#GbEsx;LfFLX zR=1D^QElUupWS-KWd9jAFlx%-tV(!AfBN6A1z%h?4L{F1Q@xbp!(MqI9R~sY^&fDL_PGM%o!K0CwL7skWNB`UUaJRyC-%oed_joyJ{0ocpz0!9Q-*UgoVHPHv zwU;qvs;j>99z;fw4gcB7Jv>d$(B;}H+#B2P@`{CWeQ#S3EzM-aQSjzX5Ek4UU|0Nv zRko8q{!Dk0-tp2ii?WSrJ=E<8aGi4rI`sV&hdwDtbhm&9=~o8#%FbE(<}B5QL^^jF z@L2A(=Z#~dZokO*^Dl27EY6OQGeE3F2gG(37cwKx^mAv=8i_JQ|K*vm^?4#s9~otz zF?Fv4!idL{ybs%(q8fFd5rstxc6@NdD;$Q(A11!kUNexZ#aWkPO1aR=l`G%thP};R z6_xjJp+X<^4_e&$PSIz~l4|D&hw+c~j*Td{<4_6CCrDx66KX_GR9<&>j6;zO@a5y+ zrYo*s669~PBva#qP`lhpQEHF9+6-#iPpSFEarYZJDtbLLjh>V{@20%EdigTH$LD$U z*4o5v-^ZzBm$r1}|0eMnBn{@$klT{GlX2K(i(6OX!-ujhi@CT~1K7WgV@k6{N0J^s z-Z2mKG>F2$SSH!(fIiGSnpAUFJ#uQ*BRGHsaSA1rEPQ{YRs4j7@n@IVKf%E6j zzjrQDr2kc!MJ1n`LA|&+*W39@`FVChn`?7!dl*F}C+~zVR)|a|D>~z#nXj*-bB)y9 zkl8EnE*cReiNaqbD*|;wk>#n`Z`;e1nVq>E8qyRozLcpCp`#FGOk3o7yEjIDH7*RT zXw}tqC1Zq`#sN?CjY2izmrY4d6a;awS(>!}RXWo5hf3~i@^J2qOZXW4=5Q`vtc87C zbO$Y$RX8UOvU4mTZvmMaK=l>~YT|ol&*yoy;6{XM#=d7*h4d~95c)d*KiJUML+!E) zTkLvdv_tIK`;2|TO$`ATgt*U|M~!K?WA^c?wQJuT^V+tY!EH{PY7jKNr5_qdYDV@M z?d-QAZ=j?Eo{2UsHaeOOHsByTD)V5CRsZr`Gjec0m9q>GSkzR(zVt6{Grr;XlHKF- zwQw23V-=LiB)RL!txaj)P;c~h8$B}tsPO%}V-2RfiV!P99{GJ`e~irlBBbC*+zj&7 zeYPuCt~i2|SqKyFu0})iKdtp0 z>!FO`9?LdkYFi)0OlCz^W@fcvL2t)zUd>(Q92dc$&b4-ti9Gt^ZzlOi7xC98)ZzO- zQWSZLKWezF9AZ_b7RAd5S{J(_<5LUPIdiTYczM=gxtsjFEJC2MzeVjSsdIGGZYXsG zOKuS-XLG7^VL~_~87kSF{F?9Rk0V}gnIH+o!bns6;r)jXTbCY5kPTjGCgckYn6f9y zq+K!=JoQ2tcw5KWUtnf1o^xXKSL^rtrXz1Sf8dEEvNKOtI{0R1%axX&uQl>dc-rxM zyQ57DN< zD#kI6lHyq-{#G?u{;_EHjm}ohKTGAhNG#=p5V9AQMn7uATy)2Z|Mp%GKW$&JefxI* z1_LQcN%z-HA*#7&8M8ChxwBGj0EvGGCFz2d&INI%lKyK;g5e|VV;gQz5X_Un6W&Ar4( zPJ-H=dq72&(t=Cr2htw{6+d4xD`UHof`ZA}g)4d@*O=R~SUC)1vWNPZqC;$ZQUVxM zmyzetc9$8u9xF>q?fr50D39GxmOu!wXP zuU)?$a`LPBLeF>dc=HP+IHE9C$eOJQX+oHAA6i0hPAycj+D=HtDa2MysOytI04fWV%9`9C z(w1Y2q<8c)BYBJbm!C=%{|09bhI_R7^VUU4NIhFp*+J==n&adqBlT3i!RB*``j{C# zhB$0Viy))wk4Cct${bQ`1dI7?>*&1CLZeBN-z z6ltMjQ!c~RJqHg)6ExWOV(e+^4`$LHA>*FaTyA&04UyWH`T36~bzTF1ADWXz|Lvt% zbhIN4y9Vlre?uP4>N#?hob`#n_<5$BH)Kc1&e?P~ zvq5*2^C_w+OWS*kY|*g$s_G4i6u+Gl+39ljHNbrV|8i_IF$r5GEIhM?pP}Kv2m-IP z>tkT!ye9YkOawbgQS!8_wf(@>?Ei z6o)wPZ%NNJ!&bNoVBjOC76h2d{1on!r6#OxzeQ+|emMVI^+Pmdild`UmnSFwjsH>8 z4s3K@x#ZY0SZMd|-w$AX{N~N}FAKyZ56M1u{p_$5I|u1rwiB(V>0^qJkdW4i6Hg+o zH;FdX)*9^tLPzG!zFSm&l8i9j4x<8N4si*IU|@Z;G<`Xotc`OKs|?U0)ZNn7`V!@g z8mkLPW@cO^&sGq7#P)?G>k5I>w7ED_|5Np6fw%LzF_-lDKOG?4%Sf&JFd?#e`Z3Z< zB5!?`kQ9>~1R@u+wMEs1d3Sy>!Y9mq#za~=SRnDSE}ErCRfoCHzD!BHcP|LKB?F+T zmTz=e4Y(!tuLD58py(Eurn%vC?B4j;)BpM(M_b4vd<8JNxf;4AZ1UQ?1q1Hhx}Pg! zKCNpEP}`rw37!1j)6xyMPI)&9$jcj}g!lL6ShOe>5y_7C)cf&jgnkx2x{7!2dP{7g zik`@Ynb@o{aJ@VJGo3C?YVzD(W>|8I7@e<3X@CC_F~z(0kR_EMys+NVB?HWi4;M!e z6vriS$e;-nY74zkVgw)|Xwa(}SDkWg6 z&xR`=s&Su5wIRX~g2~x$WJkh%8SyYUVQZU+DpXTnoLM54{M(SvIB`D`3E{E-vkVC2 z@n`eut&_ir4+*Qk8~7qIlv&KoTCliUwP8bP_{);ug-p(SKPZoW3q+YprXd(NKY0B9 z`xeeIS#vKhMfD>}<(6hl*{khAmed9X=MP-!uY-V^66094DXZ=_V>XL9(z^Jr_n5r! z3!9ktmP=LHy$26C6|Ljx$r$PNf-qAxtI2NicJRGz2z_L}aKPp1cg}Q4OvT}MazN%k zu6C0$aedf$G4kchmqO_LVkCqRL7q3OskCOKr|&@Zr$zTEfk5`8I~;4Qzu>WgCnGl6jc0f?|nP)$SQ4OD1~(mV|lK-e+{ z$_z;&geZO*Z(DGAC3H|4a~3QZ&^41;>VktUpQeiZl5_)B@8noLW#vY&V@XIQ5oBj_ zk&>U94k4_0DKN|nq;fMsW*~&Br0k)oa%9hojx)QLPQGp<7AWLpQ!olOhNX+pkBOv* zSLO)k73zY)Q}PRP|A31T!?O zJYMJkJ$AUrHnr^aAseYNa>n<+IX?ZBE?v)S8OUg9DiQcj4m2 z7n31y`MMnxiWu~7*FjzDx4L1(ln!t03xRDCSP)<7EuE?nW=m6e0m&xax3^jH5il@`Ee^^C-!jL+MrtXOh`%g6~HQz)>T zNp5A7^75)@tzyPFpEl>vI3nuD9bKusOwI@DV9OsD8~cjW4hI0yWCZ1XPJEg{!c{-I zpoH04jkYRL3GLImGN17^8w^W?&C%A3zfZ;o9Y=lir|jW_2RbMy0~)F~C+A75Up8vVQPSV6_$XY4Ml)ZM6Lu!XJIDmJ@R#nw(Ii|shfJV(@A}ykQS&kN= zJ4Z$bp9K@2frD54tQ?Gs!fgVX?lM0LQ#h0*BFN7qC-w-oW2L50Ib4Sp$Sr$?om#FQ zp#;$(yFU;>H@LL`Pfj(Eqg+b6eR~T~Uw_`ZKFj&| z9me#Zs&}BCTc*deQm{nN7otOwL$r5{vyF~gN|;PGMO@j4kOYGW_BvM$q}M+589ACo zc=N{6@p-UF_?V)up}~`9hcEglgETsUbL@bQ{ixs-B(3}4NZ;R8Q~vP+%EfNBo1p(G zK-&;6`t$KGh=r^*7rxJGMyoFfjMR-AH^#>j-f8h4Ds@KdDxK9+wv_ue-0i~WWl(cZ zeGcj|JltTSa*SY;HN%Ln13=ui-rD|iuMoX|^grr{VFq^NYtrW1Wn!`poV;k-u`&gT zKJbZ_ZJtS$@`SO^}9$y*ylsxFZaxt!9PPwZOiUo)a>;qM}LzeysWy~ssp)) zIwn1qpZQ3#%o8He@pBPGDzv-o!M8B4ff`B7>@+=_U(MofqT(jJLh7(TAyDRfV28JW zA~fheZ_iQ{{hQ@izt$dsZba&%&=j&e7)R+?V+xoCJ>}EQV7x?*oGazqcd^`LLW!y7 z=C}eI3z+80@mXsqk5cbY^yig+78BFa+rB+$XvjSyaO=4-_B%;QHwYD9Y3$DrnSG>z zNQyktNIIz>Dd=^~x(2;w!c71uZ{w%Hf_~2}RyYS3?e}OG3SLL2V|ld4U0&H_=nEEx zKAJ?9Z}hp{9#CkN$;V}Nbs87DWDG!&CG#U-Jd&3ddrkVf(;p%ghl{-aNud_ZEpyv88^>A7i@ z!2xpW$DziN#=-|@wt17+&9r^tAVG&-lZAzawNX5XIi(ya!Qu2BCCsvC{XQ9$P&A8@ z{wnA*_v6bBo3ymF5UO8r)x2dgI#~TSA>3O8n|cY?hR6q3hlfs!q3ixvq$#hcoY^l4A{yoNZ6n_?xUuI`9s zxXTUVqO*vL>u|;H+Qq?22E#UKHb5zZA@WPRzfc@4t$`cGWsnEuS6=016ys>^h%=VOw3cQ&h~yL+Z?bcP)=-}Y#AKf=th zmMVZZO931TMUkpk>c(?iL6yyu=O7lUWQ;_oS1oYzlyqYPsxAy$+vpEfRiU#^fZ))A zQ7?mf{QH;3A*%!C6N`@UyPYsx7Xs-C9JjW-wk4B|I2!Nkt)S ztIW}{u^n*7c=9)J2JDI7nOG6P#njQ$4Ps?{E+H!`9Gl1$9;{gpw*PTxF?4QI5ShNi zVBUB`vv^)CE3cEIqY2lK744hWtl5VCnb7Lh@!E$R{<4oqNc|H@;_IBrS37Y&{*ABR ztD}4Z)7rEHe^-7U0QVuLevmjO`8lg zE-f!idUz?qi@xo;MEXE)DTHBKkK_=zNN=#xY>Qu+s5O+7@B`)m0^%#<1naHPZ|{*+ zf4*6-^-qB~gTa(k6`f1XPW(^K5lC7U?0e+YbMG^HG!Fu`3k_Jx%WJ#*8!xteh2fG( z=(%1rD)I+TFRAX6av-T^{rVaz1SZAPnMSD@1eY1Di?h(y(cu*PPPkD&nEItJkNh4i z0#!OZc=^)J`&IOJJEY0~M!aqD8Ey4he)XC7tGeVv=ZcEk;aJ}J;mL-cjr3t4!Vce8wdVI*}F~9e0T!e$-^CRQ2oL})|cI7q! z@S%Hhe%md@e1WG|JIwmCm)T$(O?y&quF98iO*aQ}%T7#W;?Z$fjr)g3{p?)f^EzBA zWAyTcp10n>#xnoBEwlU$$9wyEr+R85LPA84Ux+)Esk>(z%O@0VKKy3N>&`uh*l28{ z$}(x`JrN6Y6-mr|ePuse-*sZ|ALXnKxwIX#Xa!Vdo10 z0WODn2imv$wW4#N!!QV0#cP{_~8@XF)PiueTi%fqPatJ z2T7O&^S)Ln!1eWAzaDhX*AC~Dr9y^KG<2f!jMcQvxsQ<2A{^rO{?8)$NB7F+Ck{nl zhI(&^ty-mq0S(U=UZ$B9C64a{LtPc_$B=TqJ96Oo#)!&~Uf{0yyG53i?0A^}(hQl? ze$pB*M1HN#-Is22RapN993ryZRDd?mWF&@!#7rSR;-^#x+#k*z(%%pFkQ?Y_3m#M4 zBEE6se+Lg9RN&VMp1SKw2$Lpa_W#_mCc#n)tc66B*{y5`ca5w}>A5_?zRTTCFYiz{ zB8w}-5hr@)>tjRMrEjf)g$@SxytLdr71y|wH0xJv`H4czxjc! zPr?`H>oQtKYfDSWB9aDLeUqQhaDVQT?{7pU5gHBLvxho}mInXU`+K)(LP^8J9*3%2 zrzK_X`gr@j`=lnx?2~C3H_4*~WVWtsT1}uDa`Lq`Hr}w!r7|oZ>0WJ_P45M_WfQ*} zxFBn$@@H93U@)1TGpiq+Lr8gZl9{!caLi&B&YyoB?t5Cmcjrre_bx!VL;sJM-GkTq zn_)eaX70P2(6Ex_nvrz`PEo-}ld|$-zLalf3}3v7WDA%YBiZ1M+_{KM-mS6o@`x1Q zp#WRk z+~~69hWOhfHL2Uy%E(l%z3m~i;AiHiv&;Mil5Y?LiWF424_`g!$Lgh4F#m0St|vo( zHbYqcAcFDRuaI1f6IvzP;Cxl26J&q_aO;lJeC~IOcV(+2LnlxmGOkYjW3xw#a49E~ ztWHAQ7}+fF7knE}zI^o%-#^Zgw%dZ<6%xm2`JBp%ije3MUV9f|lZj8cXOehkunj~H zNg(^8XF9GMk_i_;GH(wCtwOA zP))hz%|HJxk)M)}O zELyRmx4zl9u#2#`{`8KG_LeG>q5_ti#)N$A#4wejN~Txe%ExaW;te~_%-OSMrDupHP05I7Ff1g8 z>;bdv>9`16UjV{tj)NtD2f-*BcgMmI%Hr9?xuk#gyT928xN!oAH}NH?qx>7{PMtcH zxFr4c!7>iR)SHTMT3BNhiKzl@davkz1BfFDm&7i|r4T%|jDll6zl{sn`tDNcQq<0# zZn4k^rKmH#u1670(Bx~cFZ|FRzlY!v3J9U^2u)7U4iCC8C zR*Y=wQs(n17&^Okp)Fu6Y$ot+8H3o7s?V-_ZQ)wr2n*%9N>%RFkfByoU)ewA4XjRU z+qUzzKUUgLdFx>WEHkjY@nrg2S0*`o@roH`838IsY3ZFw*1)>b3s0%g;Y+meA!`6K zX{T!cqP2!#Y@c47Nx=}8n3C_OIrRE^3kS9g7=73e`VIcu{5FVeqMIsa|H!?};;!0c zIyM~KCf=P?OVl|e#0Z~_(`PbTToT=D`sXt@T`8VKgc~j08I9>rBO)?mBJY0t_U(V# zNcQ)zob|%@egDTZBzyRe30}Xl&x~!2T#T6cl%yFB!hMav!jo$BP!yG&Z3G9Gu0=22 zpDFOjegnAXce-HHevsF*&mwD0l_LB-D{;^Y_ zs}dz&4fZ)!jd3O|E=VAs>b<8rOd&C><$VyRA#XoH-%bf-%dyk!+4cw zzX2l|FAZaPi`**7;msl8;bJJ{L8*N&pkN9O<&=80X%UL{ z*y?DNt9-A0(K`Cy8+u6XNl83&VR&g(3Y4Du$PR3L4G@L`l}9tXFs!n|oy=q_BH9eU z6J31G=ybuo_Dl*9%d%`vo%K0hU0_FaGs?&FsA;{Ov% zADzSE8@MSP-EZn!>1x|M(YNtAP(UZt=2kK$dgZhyb!UIc>iKNfGC*pk$kBe`VEJ^u z3-YU1Ym5%PR(=D@VPe?DLkG(ntXu{M;{8?wWhLzi@FaMz3Zn+07C>0H8u)ao_C*Y~ zDT3gBCI=%QhdT&=7O^?@LyG$}xT)a{s=4HAhTbtvsB&d-v`F z6h9`HLLwr>0X6IoXf-?q#&Z$e1!7?mS)mQIyBUnO#z&o6Da1yyl5 zU_OvEv)}w`<*l3y@NH9;Jk&0$pJE5|5Bi;kn6mssitV^IL8P^_IZ3{L!IJeVs72}( z7#qd|Op}){#40tIxM6K3md=COKTOQb$CcM`3+5nZr5wzgd-wkRqZ=cLG7ha4k@(bC z{_N<)51pcl%iWT5Ir4b7u+B~XVZXCf8Z!Y`62e_?q2VD`7w+~^#N!rq@vVp%!NI|; z-$(9QpYT{@Vr0Z49A(rhcjRW!% z7^wl1vur5_31zM0scOi$8WeQm);;eYB881+wzW+|ZB{6jQ7-_}ky1eLb8-avaJctA z9c;$=F3rUS_oYbkV(WUk( zD%7@<3SPz0Q$jM8I)ZhRF}6I2VI2M8yJR0(tnFt+JK$Iw)2+tnpYF;I$4Ma6vd&o7Mww1?bk8@S)& z%p0iGV=7Vp-O%gZ`lA`J%PM7MQ=Vl%h4&;G8yenpSQPf~W8#TRYBQ$9(@mtuF6}6pNy!=R5M8?Q$hBjP99KX#{1Oi6FTG+( zKLxFq|3ISl;u4-Y?G9TJI|jqV6sKOq9S)JVy5h6cKU!1nPNF0z{p@Iqe&sdvkf4G) zmWF7&8{Pl4MplhRIF*pMMD z^+@BDw4Q>K3TxrO9N9Fk(-BlDv)mbT=Fk7B6*g~LyETHOU_bKxr@u!2rkOZjy{PXm z|632MiEyL_7#6f``ow$rzuSmWSs4CSyZi?R00rSx+z!O$3D2@qE)<8KR=$|s5 zv3aoHaehrfT00c1Vr_jF6z8G6W#)D1DlzAoQoReYzt)jaN$n>AAM?=C;e_E%F;sqy z-fv4vQ;zj|z$n*2j4S1^oCXCqncyZd<*^g^TQ-C|>z#2CetDUqQW8O{nD*cL`+sb)| z%FD|eHZXbNh0ll5x)c5l>ezm(0u={t&KFp%Cdxvplj}ebK3c3H)K?SN8jJl44fI!_ zL1H}+QYpzImZ`6;eTY4{%JLio=pP=8oScTo^v=^8#km~7K|EEjW60@vDLYZ@o*-3X zaRPM)+orWqv=lU^{7B)nZqiyE_KuZEeD{ZtM;2;Di zu$8x=u_!WxiKV~HUsHaIEZRUE8{oBJPBtlMiGu8kabKeS#8cdMsr5QAD3-PW`MZow z9gnbWL-q|6D5z3@C`o5akp9$xOJayY?YEOqJ{EwEHhX?n)UA*^=|RPhR? zsJt&2kQCR(C}Nr#&-yv^(h4>?;ETBnX z%;Pesop9UfDxt#d{u)?Tu5Encu4i*GOD`7K%QYSFJW2a`sa6nhxSLElumlVNf3N*n zXHOlHkX9*Q%luW34!oT8tKy-z5Tw)VM{3Xs78v`}s_d1t$JA89qa#%OV_ENF&;Z?r z!V6lp*vL}(8*4HNSvq598T-_W*kRX6+Er%5=BLcshUC`Mvz&{Qa}^dwnDXPx6NjTF zp|-|GMX3<-@Ii6PjLL{T08D;-eMcN{jsv8r^D^}u{>tOYlIp6e2O2G*Fz{)y2|>NQ zy$Nal71)z~X?qH@gB+b((uIbr)VD^( zGNAxcYor9GqW7l-FTT3iUl4Y*5HM%=-o4AJ(2jY7p4BR-R2#KM#K(}pU^r9Z# z)!gBxKXcCS(A=#H6<2{6D(Uc9Z8LO|BVu0PZ4;2Z=)TL9dQd{^Y7AN>$_K*_ zJ*{)jaqAf`R41a1FhP)C?GqB7*ou=;C`QE!UGB55V0&&3OPo9SIDyRl?hay(y_l8+ zf$Z;1JZHy?mfQ?Nej;Wqp(jHVUjLlr0Nv+Y5r$0{(cBc2oegYm?s0Q3EX zP=ed>UFo66fi8^m+q0U?xv;6vEakMr<~aejCxP4p zfOY#}O&z;=Qhc=gx`s*sH2nS0q$g_N?s3=4(7!Y0y2Iwk&{wT@;AAC7tnO8`0YY-w9>a?Cu z0U6BG~#^VQ{=ddp24NX*dCo|N=X-gyq8u>=nfET!#KtKF+~ zI5O-!J;%q^?GoOBC<|19cfpeM4Qji2$;+F;qrO0Jikfd8fP2G|Mq97l8cIs5*(cNAs3pw-Zxwg$FM&$9wq+AjGJ zq9sQ17!d{nP6b6_dSnFbI%ng4X3spIlC<8{+ ze!F(=TnYBKxX9PZWJiVW!nQBFN-D)4Al z5<85MGM1jSPjZM#S-DW!nkx7UOCo+rLinH69Hd<<77Xvw zodJobX z3o-aBkxgJjwVDd|61%$ecbthifiBLzDZ0B>>maJH>_fD9b8)e#Ni8v|azuRn{B^xA zHhK~1<-ci7#-qK}EM6*|(=% zXW2&147Uq`q3mtfsNMl3FK9P(eVTar_&(lM%9=AC{S)RAiq3bu#*B~%t`!*gIg*00 z86s=fN+$7+n+$Hce&$K`nyBK7;@j+M&|MJ5i>7pi*P+l6has0c;D~79_B5O91J4m? zj-BW|ci6`lqppi!dDtp>h49^Pb|$5RXn@pEgqS+gsEBxHGFfY zE%g};TZsabSc60CciBNLjp(?@xGBPwAgO~njL*Bv$|)by*m97he23%$+c;^znuF(F z=ByRIm*#w^tb7CC9v#_s>v@=JHqq$v9pivR>nfB$^+Qk7;{8-zcD55OP1wa<`}Q60 zFGH`N9OZkt{3R_>Zgq$2`0ayM*W%gf^Ef!=#QLD6DuTkj<-0dUAx=KCyh|*Kxs?#W zUztgNOB!XJE1)6Sx8^|a>+@5i)T3B@^c!JZCnu}d@mFv{ zFiQE(S~0Q3VmHA$c3k=j=7Y!n*muE?=L-CyGek>}<-V+TkQ5QoB2brWLwSYY8oSqhc~Ldq^9Ibga;$=1EwcW&@gd z(3LBnb_kVq+{=a8xxadmSZGhueOec(c6^xjd;hZ7mv-cO(dlDZEnL64kNI>eFIn(* zH}~_W7|;~|w%^mkL+&l~i8bvHep1x^zEZp*q`PI{C__rtNf_e}PDL!xan;}fQmAv$lZ^OaU*z;RqZnY8}cB#4TX_=~SY+;zs8|>Xy zDam%Ru5RN-lhf2XCd?-?my0%$U!mxc3IiaT?Q*&CR|_d1LVb$abH;rbxf1%RQ!g8~ zDTAeF;uFRA%Jm4X05TERX8ywqS&=QNfcG34Q1;kT|IqW>5%-8!#@HgdX&@>K*O2~+ zE?~a|+d1?5jh3OCoetms;emh9Mb1FXs;c-33?}ycW|=#eIA>nCaG||_Q~f`wGD!kb zR}&@E|6tH6G-k{xqQd z^9xAB*U(&``47VYe}l~RHl6a~KmcEd4E)k>^~{Tmh_E~1b9s_DJ^snvNw%hcr|j<- zo$(w_#TR@PasvBDhml?kP~)1Ob>Jq7VW6FKk}{b67Vt%qJp6V^Os=Y*cUnx^h5w3i+uW<`Y=0tOnJ0$L5M%oivsGZ zRW@r3#TJX6U#xkwLhezmz=E*zYZg694841D-StoF424~)vY8YAyQZl6VlGqA`jowo zM+1uo$Fy(R_r80o)syq^hkNt$%*NiO#ZFgG%){@~uddJ2C%U`}_Nd=!YNPhvN_QbK6n<6?S^ay+Qj#2sX>y7nVAS zG7fux@_KFz4jd0Nj(0_}0ry=7xnj57lW!W26x3AoRl}e$s)>9KAgcw4McQ$xi(j`U zft*MDJFwvIFY-9z?>+SE*YWd98m1M8`kegrJr^EpL{3kdgjua-cp;&WeqGmT7X)t+ zb{{ZkJ#RmEY7o(Jb1e&x(`($g;}kcX5fj;+13|j5%Kwyj;g z(zPP#&YksoTBW@I>5~;7eLzO_aL=GplqQxBReny}vlgqq8k17pdGFHZdmhTS1GeWHot^`K=iwxPBW*~kR^K`y1HN4a^sT5 zCsrk{V5a4pvfE{Z1hKMPJ*M*6MuvymI+_ATg-6ZZcRw8_{`-h^QJ;SJ{Q0s1bft%| zyiCly-8NVVLtviU&c;R9Rsl^RS!J+MB*K!kwc|vMzMZ}>Nq$`&{<}Zgw*|J)yK%C3 z?ar4vn<&hi0}=IM`QOA-8N~cLX}0-~S17peKv`w{R9`l_6#zpW$5Svxv zEL(w@2dQb>ljy)h-%3L5B0&Ayo)WLheU?jEAF`~cwJtk|L_YuS`mb-G)ouZk)Xw1b z&)rKXZBb+1hwrvsupy;Ub#=8&#k;&|2MnCBSu)&qU;aIPxl1f|ANq980%>`^&k?2X z1%i%X)5@KQMR9-!;1N{wDc6;Cxuf`^o0oX?+AJz*u>SdhNm1nX@zQc$qfl*Yi$BIz$W|RsLrvw&KQDJ zok;PC`-dQqpWbs}U)wm;PGj{jDX6Hp9W_P#NDgfVx7z~8>4IJtq$fn@ry=k3_3afH zpbYXJxoYouZYXmpLnskftb&C_b1gU`+R&Kly4X)ZdLIR%Sht!&VEFiDDWw7m|5f7R zNwA_q*r8y?K!eL(?wj+`UX+j!~()Pb=mN_4lV?R?MDXq1ir;& zvQj0pVR1+5^yy!j$#koEfQC}8hs(lmdk;L0bh(qkV^q};2g(xZTRqC0`G+{F6JP4m zO7!$afyVM43I6-=!0(#D^Iculk(A8N&Ms5&Tz%s3@}u^6-z%me;k4xmI{TuZDHdu( z9$|r+`@}W@i}~H2gyL_*>$-b;k3IZ)hu%ZaEn+%y^k_i2+S?I@1e!}R^tWiEwOGUq zJo$wDa2v!L>SMO=On!kzLTW*o`8xVO#QCDF-gxcs1L%%d;fzSXt4BlxQ?lgcLU{h2 zDIcaI-0o4i7@8B%7ci<>h1!f1Pp(Vz$TVayZ#Wu~zhgj05EdZU&pmtg@W`iiE+|2N z;X5qko!#Bmyy$ifkz2bZ>Oax|ywLNf@=4pJWN3%BPE1sa%MXH*EIkzf)7>;+s863-|Vkn!eVP z$Xf4M8s#fZ^r%XJp`G+HKW_!}ou;hc|wfnbyfq8Cgex%Fn0bovP?P>Ux z9jGr4|2dA3Mmj9SF%x+snSM&=B^`RbK(Hj|NX6RCtzk|NHroDldC|S+LgozL1#_+i z2N!`(qSHZSo5<4^RJ?mPu|`sIkzTcsx{OGhff_8AyN1EHezdIoygV%s{CR7Yu6x2g z>|{xU&ri$P{Ak(_tjv0;St=5!tq#zK2>(HnEp^v)?45?b;DOo4&XpP`y2E!V#kqag zisXZ^kS4XYT`;HLQ~)?-(kYJ@e=f=DSHf z65TWn6}R?^1`mA+g^aAjN>+;*+&D-iZb4OM(@_Z%<5i>+-;fxpR1rxWwusxc>)T+8 zYsiy<+N0ec4^Z??%dal$gvMJ}xPRaChKOS)j-)KbB$|Iq=Me;4UL z8FCT@AEdCibyaQWWE{;S!wsQG;Gw8{i#&69!=3*bfR_6X=O67CQ>kJg zS4rQgo_<%4_S&@j#A_nvwMOgssc0o0_52~4TG}A&e5=Y{@&o=3&NO~Qw0DV(a91<) ztXXfU3^V;3_KD<(K7!?bX@f^7x7V?GymHshT*&#IZr02qJqOr(4NC@`IHNzSGARDH z0qwnm3nB2Y>d0ryE=l}$TAh2rsrYFJvF`#_HoM;SD;NLIhsunZ@yXRKZ1Hfj7$c~q z#Arrx`TReaMxJMUwvaw(h3SMz6C(Ik6vlo%9t}^3ZA1Rutv!4C%~#FO3lT;BSBA;= zZk>`N4$&$Yro3F)`^nur0QO(95)sDp+vPdwi?)hYO;ZzQ%NJ@c5s+UJ5)r@f50T~Q z0Ulmw#X5h!%ZORq1j%D!m6b3cbL7qazhtn3ixHS|oVFG#n3@64CUi$hHpQF>`)jSm z5`uK-eQ1n~*$oC!t@`xK;$nS_*cL?A;V6HPc$z`o7CIc)80_*bbaT9mLm zzOEx^ynM4|(;zC&%#d76#WM#)eb_S%0@*Cgs(qIepWujL1g2;+`d7)jbeJ>M|2%$X zI@0ET4=+_eeDm;>_6kAaO33w({4AUFRNO{BP=9;d z`_T+6*>)f`2>qU|WbCr=V1b7dklrB7a$Kj%I&a=J)V-y=*&-7!sws!jL*OkKv^MFd zc#c%r)3SDH_zX6o$++tQ%9qv*Otv~ z>#>Kk&muGza6Y=ez4?nf^Db!Flc*druSKdK>qSy0m%sXR$Nt{;&uL%bSM@=|w z#Gp8wetUnK+2kM~&V#$y%zIEe&Iw)ala6DhAmOe8Hak?kx5?g#Ayg`JRWSh~TVOHpc{(65h=mTn+lnVqcJ(l7rA)L>$h_y^Z2-w6$Q@ti+D zBFC;lAhMH8vPc$QwWT{i?;S6O~-=98T&-0z68M4$j2RdbAulR3q!>}`S!E*1iPk~@u#j>T4E&O)sh);Kp5E9Wa6-{^!k{ zy2mlu<@aZOBKkLUYX%i24mEeA2~O@5pm=lE`8m7(;p z#5izl0PGzxw#=OBX9Yyv0B^%iZi6%H)HDxcHV-l4m~wj{1Q+DVKk4HnWM}FvzZ+am0e$&<*0PgWsh=r>+Y}l|)^+&oa znMRwcPV7X5f^zvt1cZ>{c_F~>aE*$Rr+$Mx{}Cf)vKV6ZWNnG zLlNBq2koDC)OQ}@t6deMStNgY^Kl!A5ZMiB4K8huw^>=;$@_f{vTrQ*#i+wdeag#t zKVsJFDgl8PhNm^AJq^Rh^J#gT)o*FgKRZz1 zPmc&Aga8_Qc+qG=e9v$zx7%xqIt#wdq1|x$xE33quAJKHdMa)!7je33LE60f;X)qi zI~7erv0&WL7{Rl?49~3^mNddX`NChnvObBm0K|y5wbt%lFu%$dcnpUlVz=**y`5ex zy~@iw9wyKGZ*h<#rdCuX^XXH^`v2K+O_lgi4IUnCVYBD9EqDl$J=okLJlsV3|EBo}}T+b(T5q%VOOe8YQW zc&U8;t|!J(j~?w9=xsbExsB3X3Jjx{Pay_2Gp?-YWgqVnxbyYXz^LNOSku5qGV)={ zvG+}s<1Isb%T;Kj%PITqyjzDLIo)YIKfUus4AfAeska+L0dfhgd(b^%=X5S>3TG4> z!hR;%H|ys(Prs~^JBnxRKDIp|M-1)+H@M_q-_-~fr}(oipBM|}#zBm&kV@|Yjj8@f zRes}Wd5arY$q>Lc2sgLrX}Q}ppQeyP;Z?u$Lgs$;6ctP zXO-OlKDkmhxk4ZLSh4Di#kqwm2$*r`^#C{yeu5ti%ALQl%V)SX>E=$zC2{yYW#Umg zy|uS1PD_!+5TN4w(3z7VYMf(`D~i<9vn5q>4fh;~oQbWlRwrrYE?(Rcy}xuKWfx-x zN3@wRc*w}6t*1uyV}7BZCjjwCwEW#+$5JY-$G*37LC!E=3BLuD(}jJr=PgljFWcM5 z>A#FYg3De#)2k$E3o%@Md=Ky%%9^6c3&?qas7uGe_YMu<+W zywk`(*n@vF3_m6WQU5;UAD>%Wg#|VI*+#BUoRIgK=gysLj_K4v!1j_whZQ@?=mdh? zAka2-h?grdiZ3o%AD30kt$1Bizx6grY`fXrQE{20*31|G(z82^*G~D1zZ5alI6OyH zRn;6gfaB*^bMS7G3t|rp5OyT*$H^3mj*?@H5EjK?+EU9Wlkt?ETu=j%Dh*z_aQLPk z`?O=nWH=!KR~K<}3j>a~De7MEtTN=&0Lu5hghc!JP}vz* zj7Pl&`-?rVm%}EO7!}NaVK6-$aB~SzNF0rC0k7Fq)D}&b1dzLt%0$z=BVnNweL(|Zy+kGr-lo0{6d5|D-!o)LO!+26;?;4XOo{>JeiUx`s` zUJg933Y!bBs-HT1Z2&BDnfWT6g<`E(Q8%TQeTV=GRO1xtvjg8IyVll#}1^F*yeGJFc zd!|y!_M`2JOy?CS;TP~;a5rT8-`hmM$-Ro?)w9f|^siz%SB8*+(I$IJbhOdWk7}#C zDUiWnm~v6QXT#nQmOF?go+N~{rvYiw28EL))3fk*9Oz3ozm#i(;9Y&UQTyx71N==^ z3?ut*`@I7{Z0x3V3w9Caz+Sm|bBU(g%OfL~7GyNK*4YyElu_3?B^sur8J{4Nzoe`A zFjL57oyqv3pUj_!P9ljky=jp@y_Gf;h080#oX<|8+WRG7YQ==pALi_X#sF} z-C<=YN{<7dpeQBb;EJu*Thu6)`p(NpQbgCoZT^O=V^9nbmubTXy}dqTG*ss|y(ru> z+D<-!0yZ^ExgHO)pFj6~!2b1^U^EdQ|KIQ(f731;2jVRW4wJ_L0HHHy&NzZ9xeZ8< zp9}yclIJ=C7T^59*7R;BeC`pa)-8|)o#Wt+;=TS)EW*YO0-s>$XaT5-Pc6>-BP@sU zlUe13usJ-G9=FUcbBj2wOH#Q1g(Jtim)+gn1+sx*EAKiS5VNal8U+W(Jo!!Veh)1S z?=c_vi6c=(Dul99i>s!R2$gJwNLDucN zCN>B`7o!_xO?KWoS0^Q|8`RD%?0RPzakv6hY4qUBxfR}*;j#_2uB}6W_cI;v{Lmk9 zzT;&#J;{4QK|Y#My#CAd%K5}@Tn^Mzcscpok?bX{it}5b`pLD-@4D!Fx4h=++q(1j6V+$zYDMNPGkXXw5+%lnws!d2NM%zT&^mTB%&<{&lXp{3 zw#*#4cRwkJP!T?_|Ih>@QqGal8ilqMi2eXw$Y_JPjJ4C6j!X*MabKFc+~HHQ>fFan z{e2z_?hHQI{3HJ3BD=x(8uN8YY$e6Fi4$w?EpISV{YEVnCQ>#{`XmbMXAu}1h6{$? z?va^m$eP*dbaGbxOh(39L#bfeDZ*ihMGszmFDZYZ=5jvQQwoQLzV*Jucm$)e4yRXT zfB6NBKU_(`^Gsc_^4N)A=(CFri~*&%W;)WbSN9=Ci5lXVC-8yupog;ZXxxYPtNN#= zhS#PmSlo(^wQc{TAL9q|Mr`8B)9$>!mCQI3{Tu8R7#Z6S|nmC|<4crL`F+d=WuY9s@_c=pGP?{G5- za$*pAt(u!hB2;4c_MCF~s(NtXNU%q(cof4^C?)+E22ow0_r)=C{qtrcWIDSA0i8$9`Bd(;-SP2tsc2HP_m?5^!@j$!065fu@!-r&)Yt$Y;6% zi|0*q@)KnOLShb%_iEk2jtXs$fv)z8;-zpzbob2#1wkBho@C^M$Vem@FUutaq&)pJ z04LnWO}cm#%WII5Z-Z8=JYRL|)MZ7bN|1!^%)Z0^(=RV1<@9qc%L3QMC4v?D3lpsi zcDy_?4q!5Mi9{uwsfX!Gbn&qS(v~(RsF$aVCdHMlWPR$a`lCmWzN_SdUV=Cpv9ljI zS9#~fQpRj42QM!#zj!2l0mozMiRxm*Z0EZtVCHuCSR@7q!6i2S>3No)X!oT2OW3G9dQgr6Q#;dX^(leo-b!tP`8F{rc26Xa^e6xj(96GaT= zTi>ofQP|j(>&wv->?TD<(j~OWySP|vmNYU{GDQSry?oDE9qNLmt!JRHzD2nf_3{IU zDf-_+u&eje=zhAjG;1Bkt87rA#I8RvWZ%mxEr__7z(U$gL=!^juZoL{*>!g&gcDa>f2t=Y z@aFMsoKc;2bgz8cwvCwc!NCa^L!;df54;0+avM;Rm|JoCE$2#~XEEIsE}~~VCLE<~ ztQRVy%fr*JTb)7>xqMX_Jl5&DjUSRexoTSw+fKNR&RMunR{Ya7R?T9*X^%veAYUSH zpXJ-hZ!;db7Lt|ct9AJN0*+0N&F6_{--m}|7m6=AFF2GyK5}j=aUW>@bZ*5BLM1|n z_Qc1R1~Z7pPgGPJ)JZYd%_~=KfqqWWVw+Np{>UGBv<%U&)QE3tzN+a-EEzITQXURK)w#+$SNMV6~`DbgoG$W&ET^*<`zl;oHDYje%*a?O^h z_uO;}OU=u^Y^mgAhC%;CO|0bdfg4L>Vwm7}tUgoko!{9|V)%Y%^nCs+|EBrb<BOilXoRd6jdH>;1d^KIflvj?<~@ zdcB_G@wh+k zbl3{&?_j}BoO#hHzr#~ob3Vi&3Tk%ySBcBz1&K0AVy|Cu9GwD3-KLogtnk-gFgJN+g>Zv~wI0?a!wxx6Xd519+;r zPHrn!&;D@)dDu1|SJ>TPB)NISqIT!G=XW0ec`v^imN zUYc8QW4{AX2TAM>ABcZ$V-oWtky)O~1uEQU;w%> zKYI?XlKX&&W}+MvSnc*-2rlVl+qptw_Q&lY-{R7h6(O$}R6}-enzx8oEGE<- z;MLn0qK+8eMJG-78RM_}z#uqJWB5brG7_GcV_vf0Nn`;)z7D7WNI?nx_wes~uzVfW zn4K7ckPPd`YYxcycW$72Ix2HweP=;7!1zHIQw048GNMw z9HG>AEkb_$w@;s^yb1eaSxUcV;}4LMPZ8;O<^_Q9!mO)OoR&6GL5#NfBm}~NIBF5L zzZ=t3r=d2OyXP5NQ5)%2C^pzUlGD=ihavLLB*g$Kod7^Gsvlj9th=5M8vjUdxflzK z&VN82XeFTtTVW2F{me^jrn~yR^S(bPy;z7-q33^3LuUIV{8%JJ*RAugE6!*oAkXeQ zYy_m)(*HmKiR--m`~-++4XQFt1HY&6{_` zQ3$>awsv)fe~PD>jnwuF{p*POtS5%|M<6wQ$+!i@EcA_OWie>PQ~(HiGw_W2peVaHdts1Ij6I2E$1VBCWeb;)Vvsd)~{f=p2 zG|YsY4SB=H%v&xpJdn&CK&DDJ{W3BbYKx%<21vYEC(yKPS$GQY)7SdbUPZ{Qd<-!* zYCGHKJ+pR){dK&=gopc>Xn--xEd0EMgE>VH-s^`(WvA3cFfu?IT;ursOe*SEV8S^1 z8bDo-@{j7SCALUp ztPLNdiqIJDcW_UB-P+nJ9{lJ8Ugkm9(m;uK7(7ETmm>ek8SI1(PpLt6=}oVXk_+OC zuIO(OefMF<{~98Ym05lPD`AzyW2Tt}^Ji;GkhkLIv)8XlzYSdgiip#dWw3dkzS=r) z-fJPbMjeKRAS386;syO}jHIDpyJy@wAC2h{Z`VJ`3AfRv!3ebe3j(>kVkS;t`C zd6UG25teuiIH)gsCeH)CTF>`9n!%<=(6#yA`i*uj)f&r`28#NlyxanQIX8o$ZoJ#w zFp;D^t%(iU7k=uyV0^}2be#;da~)h<0tuX-%n~j|^S;Ix^EH{T-f#Rxh=|O%vp;z@~4C)d=}6xXiZ$B?1@@(p;9*UD0;fl?rTT=K_)2c z{E=C{jh=g>8LEUM4)D4GAhk1Uk1^@G6+UC+wB4d*H*w1+VNq_kP8vK>@XS=(d$dqT z?5SYUgXcr)Z=Dx8o%Z`l|C>gatgxK5)G3o9$OnXE!dkuB5^P8TIs+y;IX+*{RWyky;5Jg6xStM1I=+ zXg+l)??Pb#b0)pVe@)7->q{nL{Rg<)zMSX^XsQFho-EKN!~*~+X^Ou%qsy6j#L$>y z!Jk)Ardckk*fMt>56AVFZ}`l9>(dBmuYnjpn_)Vf+#1cLOm z#q3qhL7SL&DwE+HF*?AO^m+1R<9TuA--}X}eJAmV27zhWuVKv|y8)g7^Dp_5tp~rn zS)uX`7R&x*Z>$hKw;;MCMd!i4csKP!{~xP?=@0Cgqb(L)d6B2%Fng_nY}l$@i>WOMZXX9aJ}NQUHF+dosd%&--#zc0zh&<#P+p zgB|e{kD+Cgxe@RPGRq7$p}A{yx8Obh%^^2J^DsTJ_Xd}1P&Woy8m$};B`iWN;eshN z;w2SGM#j!od4t!O<;Z2baj3~Eh5@6y7ZkLGpPyfNVD%m9d1`a0jd=Y4SyHNhdvM8g z^1)THhZK6>eeI~`alYr)uz3Q?@3peOCd#CA1!yTwf6lw+lt>)!)>U~GLNhCXy2-+( zunZb4-u$Mj;6B^oN|rU%4(QI!B%&U0JJZBFufz&&-u#)U z(#TXw*f4m*Vs@gWB20!Y*U=mR&Od;uX4vl{@UUw&P$nrs0s?QoPsT+yrY5*M zXE=r2Qp(roJK?{&7+-L|Lr{x@cXpJ=(f{^J0suWD1Hw0 zIypY?*d=6ka!02quVuDTKmcdi_n$^_-Caj95%D;-Es^&O(OrNmTt4h3FIje#W-s*%%LM+heEeYE@htjjYJkW zGBzwRw}=muIwCt#B5DPIGb%q1w6+ev{GXBXiDHL;Avw;!dKCx9S}e-b=_WUx9E-_i zv~hh4(_r}Dbrrt^|8=uN!*6W6;2T2&kGVz+N?J%dJb|2YTM}yM9*e7DSGU82eJ8b{O2u+LTbN@K1Gcg}~x=KQ6vPR7gu z{O2VUsNkh!7b%pp(X6o_xYg4W1X3N+U6@|koPY1_?H%O>YQZf}&+$Q5QK*^a5Wles zyjd77j&!)r<29V$qid$@eMLa^v6nxa|z~l`2!TBxta0 z_n00A_yLtBtnd9^?(fN&@qS6SVTRt1OtQm)^LPj&$owtrKUY>x0plh)nUJtlJ;_JZ z+IExLEw|j=tq(XJzwHu%BsZteZx^F2H%yJe=;qT@ONLZp#E*`iF%8)4I|Uoc_=4rw zgAOlxk=HchLjzf$Av#FXC0JA>Pp)|*Q{LWE^V!Vr(YL|vy+tJ@_n{`BWT1{1T zQ1y3dRnZz2b6|!gwKy>cdQ&)uyz=wR^=q3zu(Cr0$&q7} zuF}A+#5qQ21V{~Hg*?f3Q1g_T*S@#+DR+CtXcOK-HdRzqR81P7JmQY~acF30SjNF> zF1+Z83fG4pcB8L`sZ)UQCH63yz0-9MUd}5{xP@LwzQ*=T{>D?0NrSBFl~V^{hGV*g zkBTn;yJMK`eeqq&0z@v(mN4)c5Z*6Oc*X*{#e|T6elb0<8+_%Y>`hcqwIIs{njF{; zS>dX7AKV+K=q!u0qP{!nBeww>V1rq7H8;7rIL8KJNTRLR4$8FxU6)sw3xOeZB*M)@_J07lBiYH-UL5HCk z2~?bznArD?jFG9~$;UJhJa7iSp~S9%n3+|hvC{oqN}uKa0|uKNINZ+N@CUUA zqT`lB23R(EZ}5Nr^YV{4QMy)JQHC^N*{m7h{8eCI`&LP9v2y#!V;Jt(({# zt0_Jq71^JC_NY!`V}^QuVPDCLZj&vL!uWvAadP?P8--8I@0|1r&=9lw{B~i@JE%h19O=i##z2nVH2Ex| zOgN6j7`-E&qBaLDfBG*88fInb_uaB5X|CeWxgK@B?^qv?EBICimE6O9WSTXNxzv4N zrSHFaQyIMfIn5MN#pD`pUqSQr3#g!&`OLv_p8CzOQ$hB^PT2j9cfD^-P{Gta|0I}ED9~DTRDvx zYgq}FOKc?hCvGq*4+VxlCPv-Xp3{@yb)=cT6e(cNtkd9Ba+>(Unb1?Tgx~_CjrBFZ zK;z}(!UH^<@~J4?gyyXcV6nDbmYT6Qa!q5wKDrEX=i1jbnkaN+R>1uIgQsb0o?eLk zN0v=nwxrZo;KtI*y_kwvcg| zkP!?MxYF_Y^YXGSgyU3m3Ih}pbN&{-FYh?(j573wYV=xBRhQI;3tS+e3IT(%Or-u9 zL=NwxVl;)W+cuC(lF(IJxM{x2Kk&>SWu!0tICHv1ec~Q{`*z0Dmq1S-n?~8*-roHS zjLu1O+d&jtz;Z2AMo8!q42>Q`xM1F+7|lM+;EIe2WeoAvoOzdVaVcY{Ut|LTmNI5r z(xUFxIn34VslxUm9BEAEAjNZ)-OsIa0Zf=Ez%1E|{Z!Su{tU?gkurXGj0w!!Bjy-N?X!q^P)fdq1*A?lkWY^n)hc zADz{QFr!bl-1D=cQ|%xvlZ(ro(7<_29$*n-N=_iBeYRO|QSrPGplq(wyN4l!*~@^3 z4>tn18UGlCl=9&<1aA8D`UV+(eC>Eg9F9MB@7=ri3}%Jf9lo9sSz_=nW=~!ah-tDC-9D)l z++`|Rz*b#EBDWo|QJ0t4$ozx@4$4OGI`wvVGtB?Ox_STOrUxtBXZc^+t|--^_?FI`nv(@KAcfzm|8 z&180}t>LhWj^P>ch9=|vq7%eK24tEFjwP2O4a=QDQrPfnpd#W1RK;&JmM@2NKV?nW zNr6$D6;oL;CqulI~EUX=%!L;Pab}d^DyhHy4o}oS#Ec z;`h1&&N=SZNUjkK01JhqwSP`c-D$3?s;u;oHEEkdV73p506YO=#y!}c6j@vz;So8E z{w_m548c7%dv0YC-Y8^$3Cq}GjqOt%df>2}NN0Wj50bgpOHHV9FT@aehpAUwpPIabWnFiLkobgp(q~)*{;^ zdvI6=HDwQsX$DqxDE%qyH()k(AH&rs6Y5;|mHwX2^9-9jb{yCy%7L^IT%rf(Iw-ZP=PF-t{zg>Rz~b!)VIu%N>p&+2a&sla|!eT6CcVh zZ_v=QeSo@WN3-_f!+azj7t)((MO)IynKg(>V#hXAE~rDKiWH;Gk=uix5#)L{l_^)1 zE1}!^{^j_K${(^R3HN<{)0V3O?7~3#t&ZDU=++8uy9nQ|O|Y1}RH;d1Eh4$2M`J0# zhVuz=r3C~2n)|}y8i5=;idRaA={6QRz0B4VvQawbRfL5 z`yg3r*xgAZo62iR;`*leJ$B9E(lE2W2-lSM`xNI)f~=W46Dr!ef|VI*P`1WsmX ztNA+g#zcPxI%+XC$YYUn1o8Eohyo|=FihWivvXW>=`2GOhf$-(Orsl>9S=-#AV-D1ks~uNZt579kiPf2tmfQ5WI=6VVP+mqX)iyC%;Fm^Axalsu}QooKDE8gV0in$xZ%LjqerE* z+c{|tTZU-?cs)@5I8abOkvWwYY+lKg0H!ao2 z-hq~2$BGshxe@JALn66vcIz5|jYb+6_-UBMt|iU&?(zE5k616#-r&qOAT&Dehpp2e z5P9a23lZXGM@so7368|2h1_C>-XP3nX<778IS*4*G6ek@pA9Pa+=a8={+L(7j6oXR zRHi&dqE7K@+S2A+J^4XQ@Oc+oi2&*6Y&PV>+_4qoXp;l75Uu<2Tcb$LNOHM6P+4Xo zEz~(m!f8*3>zS-aijA+xNntKsOIIGRd+{_g5c>d}Kx%>8CTTlcAN)M@iZ}p~%(0OAf8aQ}Ck9ZtYc9HvU5+jFxB+l~_A!tHN+f$0ea$g#VMo(baPnyG6!gEW9o*2H(1qVEex7V{Mi#2PoGd??u3gGUa-(9zXEy3hTuEU?BiO|b0+%5r+ zT*z)Ma=1tpgp$Sfj7AI(%`3ivSNvo6v#8CirCbn*A3KipZ{Oj_LNHI&pq&+ucCl&R zS-$P1zRF<|P1#mOkIF6SnQrD$kgPB}K2F{jUbc+c%eKYC%UmJDTl-o6$dOZ3-Yl7o zuU`Z1E8jCSSC3It^RdTPB`FwjX$3o++CrE-%{24!e}yE$ zj5ZSOU_WuD5-9*OX$P8?)Q}aEw?6FDIH^5|xA9+Xkckt3@XN@^h!FcecOd88$+fsk zRqPI?DLmq*=rKe{W%gOGAlG?fI`MhXxunwY{H*(zrswc$P!F60(S8dt4A0G$ccMA8 zm>*(ycd7jUd`O()3Y2AL`Znj=;R^L3bNy37E54*mf~ouavNW6p@gu1OE#+|_Z8YDf#t8D}o|RiAD;NCXOGA>JWm({Q=` zq9Qn~pQ&_czUu(7T8QMvi#Xp`acge$X5sZp5o}Rk_bLWI~K{3Y_ua z7FQw`ZNz${?$vcH=T(GhV7?lsXPlD<#B1W+$>}xdAgth> zQv|V%X_gn}t`PP@!}ys%+p2?EpR7hm{5QGOE#$VM)HO_&!}Q|In7sS|+AN{LIzN5yGiKNNrbR4UWttuziZsQgTAn?Q9d93!w0 zA{t}s(!bHOwVHURIaDP00p2#ZctA81153-D`!HGznTGJ`e3~z@Vn2A$=u1F|k|;U> z2VgcjW(0>O35aRQl&0BMYAD8?@TwZ$+|{O8rA>!0SqW5OZoZ)Gia#!(|Lb{S=62uU z=wmn( z_&ckP>P*6~x<26{wB?ZTouyPF=J(+>L-E5PPoDXf_5>;PC9K_7q}Wm=WNv6$ za|50senlCkcpm!_r7_I=XqKf(D4tdr;A_PO)X{(n?3Ni=nm0JA{+WpVJ`h|43GTW# zc!x9<{VX&O1*el6>>X*djiZFqY3L(oZ2S~*Tb^$ot7Y}U_chD=1=W~0Y!$fcWWTpv z{fcwq!zB?eGC~^%&vreyp(;}mKWJ~(PSLynxB?2ye3 zJLwPMPoEZdE}r=DgU4OXrb2(;J~wEWpVT-aaQ}SS+ojIW>)5O$A@AnKN5DN9Ly)VFf)4GisE(~YOGMj$rb4EqEo!{s9=qMLGC)s?Y zLT66p;^K0j{!oiN#>L1q{u4BH2Q`m_2%mwT9EB$y3Wf`(aG80m?I+4f7m4|VT}_Clh(Ys48cu?|eD!cW z@p6C?O^ z>$|d?2JgkoA#;aS=da7q9Pu`qsGD!F#1zc?%_X)p)*oH&$mRqqra5#L97Lsv`v<7S z{nn{L3d!|q=kNUdnVKC1?j{^zLl)M-I}L}14#VjA5aR8aeqJx}N%Rp-)>vb{X%L7W zy{Jd)&b_)ej~CR#<;|6jm|6y0Hd8*C$w|j>h_NL2wn6D8!~r8<43NLV}rpCJO?nUoICvW*~1O_-Re9KFmvi&Tj>c^?PF{-UD^5-dMquD{_` zMer}|_FSWf9^_o#%0QgN{9%vSy(UCiIP*ns{&r}H0P8iD9G=#XLQ{Gti=9{ zBtjAV;|yRRyH`Xz)iK;IS>5(=h70hDr24^CY0S(BI(h!^E^lxsP8Euo-@9`o{jZ}lkFB7%aVMoy?R3g1_jx({xLOGxXeMpj@plgTD#dmop) zp)p6NLx((SP7Ty2Mf}Y&?~cR*gskE?eb!>pL(f*)3dox1UDLJSppZU`VZq0)H)_WQ z3Oo1BsyGUS7%z=DzbDv8;9XVPJ7G4KGPDG3{()ocBd97;$+Y{`-0Ff4@ct0s)@{sj zu)fh3K~J`C4gI9`eWvEIh^(xJZdE|L)z#H0-P(}KVJZ;aGlbK<;$vAn@4SJv<-Bxy z-AA;wjTsuoBEDD~v=z7(ZeomkfPgtzSejh86=LZPW1g(<5z=STsC~uGJ^-@f-&6_~ za5scEKOPr*F*DKl=LP-K2GU53%a35suUhu`^6!U`qfGUgM0s!s#v6~Z60E?uwl#F& zzU&BQ%AH*y4xKB=>XSOYn(Ci6xZ$vt)+Q9}U$Mq{Tw6Oa6nXmhnsD&JE1H{h1Q{6_ zkCNmY3rO{{+5D!z!%kbheEB&M0Ee+*tdcf#`%R#S-)mD5$kdQ+)AQFQmfEw_*vz_Sc$#lNwhm?kUis&oYd-K(U)T5z6*#nNtE7 zAlli7MqBwCcnmF`{e)WM9vOgq9lO$4=m75feqaim;<* zW@fA`Y|E2IR$HKN8|HK+o>K%2$_g|-UBTA~Cuk4Z>B+i$^Q4i)xKAyBI*7eohHhVS znod&OnAIu*^mx)wiYJiCiU~JU?Hmg%$)r!IA#UNUZrXxb9AhYj4+&Q^$3d3Y<@qW~ zO@B>T*_=D>+ebB=MA8TuZUyU3Oqm)lngqt5%)69H2r+Rj5wfvynn`;Bag|49WzNb> zA;ps#VS61+Ry;{_RG8wfG#6dQHJRwbEs`&*dBy4HW&x}!g8A&+2ks7}(ov%5I!@BBEhKdj?l%WO%QwM;s=5%`PeH-{SB$_B2Jh4o6r*j5MpC; zfbkStD%ZlZg&?kBN=>K&gom_3!d&-md6rw<=yJA%)o@5lX-HIeO-;e?6gXtG?3CH0 zElysmPj@7;b{zC1rxX35Hi%Rb{V(Y128kJ0zwLOSN#A>2t=xDBf?rC*jojidzCQEk zwb;J8I~`n*eXKHUx7^UvkAqzzPF{6obXjz&`EECEIMx^w+jb}qZ=CK1Pr!N~%ITb4 zT)SxMdAWj6wDv!$Y7B&DZsR}ejh8&DZA!c5|3wX@R8>{IyUh4z1b8@ma*Tc5T+TC+ zh?^C=?Gst{=x~Ei#+_Z+h+61ShHkzwJK_#%gVb}he?Y3SIU(okZI!VaV$9rI6T4nW zDDHK8%H9j=>b?s5_63|4+r0v8km(?RlrZUA68B7rEVU~KoW5*4>S0`cJLKB<+n0B&nO!mGOEuKm&CK zlFYn^OHTjKw$#A(o9eaN`dbb9?}ed;yW-pZbyEz<1O@3XyY041>~YK@wqJ&de<6oq zC+AMP{)c4s6Q9+E)dfM3yLPtQwaPe7V`%#pig998TAO{uFzkrnckKYT_o+{RgzdSy zQq>$bmK&C*L&N+b<3fb)<%tgPJ^dca>A@NLP^gR^u}U{teSPjAZaFU`!~L-P;z6(~ zdo3JMau{)2h~CcIfWNoKRp7VM`K-z_zU$rFx86WNv&B6-K4Z%+W6A03(%-S(;aY7( za5o}SBxCLSPzO~h^-fO5<+t9i9yO=SI#~L(yz5#*BRH8P3C0RKm?bxAv)4e*)Y^2` zjTRu2+lb0@(ciJ}17@Amu27sb@zQhouO~22$GSvxGepDm>_sf`MS+Ze6QGD~qHCH4 zvsoif)N={z8ZuSS>4Y(-N~&G6Vb}xBRQgzbFJK$D)y=*sIDWpn|Mv04wQPHRcc72$ zsY?hIa0_3AH&Y}1P6xWU$MH3jW8wLs zeHy8D<2e-u*-TCD=}-i6e#kgyQ3#5-FIonz{K&xO(GeH754Kf04*Dj!If%!#I~CEKJ~9Cnr#({C!jxn%R)j|zRjXruJrlI{f%LJ zGRO&PoB$E?wii86hV2Cf@7#O-rokxzFLkM4ka+qV)721;Wpc%o+pw&(bQznMQPtC4 zr^(T6b#HxC#J9wqj6i*r*PGqYJyy=f?mH)2 z=HwPkv`y7>j0$w+dp!g6M^;JM)vtt+E=RQM5Y$8u%jkWJ`>#ucIec|E){r+15k`RV z!1#{aO9xFL+}VEV`*5XQ*%z9p!psmnr+qvu`|%c<*@PU*vyt7@g6*&?Nm%>(;e6-{ zpy1~o@?}NTqA8j{0!;}&adn01PyI@0@Y%%j(RNot>^w3B7h?|dZxzP|p#$+^@zx1o z>bd;$%YKgds;Kt;X0U#Ju3q(Rw0cxh9K-^XbZ+yyu4`$8gh&oIwM7S=@j>M>nY> zK`AmTR0R@+h_ukMgU)4DVcF~Z<43BbDEA|c4(GyKXQ7&q(NsJ`oUQ16^PEbTRGH1{ z&kU!mF{IUs>i4l8ojN|Z)3+@vH{qT2=cj9RE2cI+l;4o{aq;o(MQjs|>!aLZvgwN76+c3yimeO{p38%QTeN zHtF{&AM51+IjnTUm6xs(ar0w`CiZ)-Oj7403`-P!x0x2@ejrUE5v@LxU%D`Z1b`5y zsEgL$y?X<*4_>S8IG1#JL)eKb%3za`s9>%#MvERNOKO+c*YRbo|30X6of4cM|LTYo z2HBWmyy^6Yv1(xNfMb|Kc ze?QqOG8XQ7`TT<_uhp{VgB~B_YLiayPd4ALA{eBzBhH9VzwW6?t<+-%rDLy1tp-wK zn`JTZdx)g2$Z2to5OnjuIB@}`_(q5C)+@pK7f_sa|&$p$esZ3F+L)hg?n8vSK zXbmn8Y+8~f_X+0pndC-91t#gTeDFIP9Dm%iPK6~)GTbs&JN0Rbd2>U%_j$}ozrY6D zR8^f?oW)dcyK+kVd)cJL3&NPDR2cj~b=_y_PjoB*1Llb`nvli(=Zo=$F{GSP)RZfI zShR+n8+$PfOIR#aXJzW^*9uz5G--k};)@iU+8K0fW^KD@;5#{9 zf1o<6@}OfV*1;=vI7wHyh=DF{qr>E=QAGmxUlli|wFDQL*xz@P+lo2;qGz#BPFz5s z{bztz(cO*?s8Lgon!}Sp{6Nf!^CW)b*oxYd4QR(V1E@c@i+en|L?z$&fjV1W6`riC z97j2|jF5=ajSoMsT|_?_5)~RJzQDp^=VUf-LSROa^yp5F&FQNF6=DMBe&}$57P|Q$ z{TfduqdRX``x^T;mRUdl}T>1t*rc$DzI$J1qEJuWWX`I7dT;AcW>P3A-*6V*> zDn107WZnZB?wP)RE^hm%2lY>4w}`o6hqzFoVgYdtkuL73d5;@;Ep+w1m|1JR0ixhR z9CPzc_|#4Y@*-2OLaArEmO6%2t~#8}G&eQXxJD`D@}!Y-;Pw#$(gw}Pw2RY0FD=Lt zYQSC6eskHG&$;5wy#=sIPQUfS$yOc3MEDG{xWU$Ai92S0Ry5ec0Qo*WwwdiN$k(v^VWIJTsSQsK&0JpDEUw6;v6b7B44l`>s5H$gCBd4p6HDa|8Rb~@3|O*Sjxk< zWo3ToG~N-aDe9ul-zI#;T#;X`DAs?@=)}|GN$NZDzy|${tL{r!iQ$?1v)P2#5Fz#||-upUU{2&U#)ilL@(;SYo0bSkWiTwJ6PG=g+(QdG8YGn={u@ z({qxNl7v}P^!Dx6RwR{g^}^{ci6I@;)f9&CTl-Eu`tzaqqUQfV^R-SyBtgNG+>2IL z&w-2b%r@^KpV3kte?E_W5UqSXpFHPp4O>NjEztzg2^lX-{g0cPK7-`;d!2$m8~xd( z8_hCu@i4*BSSZ>69(yE4KEii$;Nwr|%97)VawlmznKt?xdGBK|kA3j~3>;-(TgT(H zPl#2UJ7^vnUATmFv_ONHRvv?Gj#g;oKufL;EaD8OFTyX9SfbOLs~q|bUb!A#O6Gn1 z@@{XDO)_9Pk=|?b|-~JK%oIG;{I7lS`<6psIqVi!&>Ay8oLdiWH^yMY1$Xg<-{P-cOVl7N6wGReaI&KQn z+dT>^G(YrE0onV4q$ux$B2Sd0?saUpBg~Qen~ps`8mS~a-tT+^BP+^RR1(GLi4IXw@2T7A6EP06S3-TeC$ijla@y(06PGdEB!Am2kV9?HGVZCX`9)-!u4Q&ubFF9gaJ?bfo4Ij{C|LM*iio_#|CiwTx}=ahR5i zNM`JQZs24vi;TXsUmwNJ!xoR zy`!z3pg&L^4k_hVu$g0$5<5H}Q*OM|C{z1}aG4H9LV)?#j(MVUBM7xA?m5U?b ztaUOn`sTS~>OGK1tS-5?>CfR-fNf?b!@-N7BLxpI7YI*wH{d%L8qg0Fj~^)&SbWWC zUTv`k4#0^?(Ti=&B$X1GJ*J}Vm?<7r*=Z@fR@9a+?1e3x>JWt6D^Dc-rO08PkKDU; z+qYL zYufVZFP@J6)lz?RW?TP$;hLoHJ~MNt{JFE4iNDhx2Q97pTnwHoCD#D8+9928)~LQ& zBfkIo;+`dRt*k!*##+H6^dKnYx2{4uLgtqUxhNuA)f21X8&MW+w0e)piAw7G=VEcS zxv;N)9>jgP>&XasYb8;1`&A^Cd+W*%>pKM$icZu_yJ#x>2JieQseWP~unLsn zhV$Wj*n>t}AH_(e2PN%LmXO7rb)ZdpBWLLvb~(N_#?i5#nAdfRhUcB@(QrZ=&hWEA za}GVHD^_OFCEkiMcPieeATijp>iqxq*lnaBZW)WD%r046tx#U+s}3*Vv7{PmVjFxY zk=nMc;@VatW(Ic`b;D38N<6vYIwcd9HS}T22Jf=Hx1ZPHwYHHHF3}Acj|b2{u*W^s z%UEnq`RP#)a1V-&0@HvGDMmi2OB~yi#p>hs3}JHxI_oF>b)Dpbr0^1^n0Ad`p!u#0 zco|;#X!Ow6cLS>86!qtIE{3R?wHhP+8cs>*%y0qpH=_kyaNG7dGXpy_uPceT375ZN z%K13ZYYUIfmGi03)>Si%CSwvTN72qBJ zx85v>#!=x^TxvkKg;+^oxRs){=XaIQG+g`;%#!cg2GH4l1))y+Mk($>)K6MhdnfNe zn5~s#pTuI#WuEm#&Z|ZpjCCkmYc0H1N*)Cyaw&IZg2y+Uk`K4$?}+=U9jUa;gt4BO zg@LhYm*AlsjgKg&#el>E5e!y#L~}Z`i72-QU6pf~-@S@uG=39o?mS-^0XA~JOPu6v zY-}7<{gP<5J3F%^UNk?YNNcv|-oH)LH%5qQ&cOU&$0~8d@`B^3QRFOn&w$38AB)is z{JrMRay;ytGASe_iQ#qsi61q^lO*9UC}^eiGxgfK8)+zNieUo%$&{OJWD2$1TjR(F zjj30%cd%tI!n}F({R%Nsh^}U^nfuuM+Lk6L$sc2JO>dR%bdmFC7!{V`HieYT{mzSnwC{zgLxNcdaavU@^4 z9!S)HLUdvv$bUH+`2;!81#_mx8^6LLys=$DZ21ld{Rp0*%mIy?)YHkfK;IZE<`LDpJV?pO44 zu^it4hS5~bp{Q^#SobS|bL#!f zARsC^Fd!khR-R8Z5<susXw0@ER=osRhj*93*F%;;)mS(!-rk9sQ6bz8=!mi)>;STHH3yH6d0bW=ntx-|t zSiR2c+;1&{RG`7=|KmPbO}^BpU0Ydae<`{}kRg2Ay0MutRSsk{uz+5ly92!NJ}iO4 z^rhSZjMOoZqyZQ{=0MzY7=*Vo&~}l$VpW2?0-_t~B78>T899}0lH15T1{jNs8{=Bb z4}V9#O=;^;#;1j#-6(5i3#X5e(P-*8#++JRmOwIao4dzcNf27IX0LXN;VFH`gp7~# z!NS{{S?cHd`?O;|PEGtIBX5klEi)M6YGt65m($xYLZfVx<1-`x;6UWrQ?pJMIYWHS zMFV|hy~+Y%;Wc1s1o~*Fn+u^_7t%Yw65zz1O<~IlAvqEzW~hBtE@>UM5r6%CnokSnmIV>@Bqm{!_(4M&tRY7*U{ zn`^P(yBUdf5eIWs)Pq7>juO;hw~zCDTlW$#Vly^OlAV8Os0he7okOIKk#U-|x7z77 z9%=mx-Lk^T(?TkQ_mVCqeyPoM-ea_YUlE*J1dWkdXIM=WsH~;IV!JQeb}t~u9N$9* zby!&=7FO!r{c6Mytb?G7_wx641MOWVzx{~*eOa@R=zqQw`*(USg=?Gt8r0nn%3=2f z^Cv8ZhY4MC!;_~k-jTuj{yW^_B^o%YulW|_PmhU^ZF9^0GJ*6#n%WNS9Ax1myWRr; zAbFwUpL8=U_uz&v(J%vp*c$~$Q=j$5(m9g>Sr|}OSY}7!41bZ6*Q=pyQWbTFB@KOD z(?4A+Sa4cPC3g0w{LG^HcKvO>D@RaMvr7PqxGM9O}h}e*z0dRaO>8s^{N!?_pf+=AEu_Ey?cz@ zmyX=yh5P5Y@^O``C=ibL(-W})``fcs873;V^j(+<>OveIZzP*lKE6dX(t~+F2Ipuk ztD>D5&7mV2oeq#-568m7mXKC1n%)LXuZ#Z z8m0XMOxl63)p--0JjV{U>i413-~Ds=mGHN}UGXQ%84)$-1_B*Kry5pVNwhTDCfRbD z9&PeHc;37t8QT5FTCa8?>S;XFEDJs3y@f9sO0)uum)XT^HcvPe!)aCF$5*xb5o{up`5&j?>ED^^4JrN1c@Tv zfQ{zar4~W3wL3dG+G7RFZBc>X{JbucD!B=qwvVx4J?di1iU*zXvHg`+|TL^9NUQ< zAwgwztclw&TxOc1yfAww-1d|DtJ674ioikSqQ{B1G`CN^J&K0{|JTo4Bd3>yuMG=T zv5~KXy0gQw;$jI-hrRRM9{kV2^_d)8Kk1Wq&w4Isz*;W$32}H=$-O2aCq|~&1QRdQL78)?XI%FepWH$-=4=Q^sWT+2V$N~tUz!vjr7%E zP^*oL?`&|yWnWx276NOnuwIH0x%~OTgfq^$uYmEje=KBW6+Pi0-ehic;lhQlAT6Fi zdH-pACE!tkh<$gKi@=Ys{oJ%^)OtdJg2FpatQ~A%HMX) zmYmE3*vR6iE}5Z>P^53eW~{_i*GouVg5eTyu}3u?s3JPF<48ehS93z+AUxkonvHhX zkjlgXi@)EFc()Rdj%c?>tMQ%X-iOMHWUY8=AFG$01_X_PpCLy$EdSjixYbXOr{_zq zRF+6Knv(}?Nk5ch?(DCHZR=t|n&H~OidiRutM{^iOYV00We#eH*^ z@n@B`mb+`inht7hdhy4Sz`W-jn0{~y!0%_3*yH-yu8w-PB^Lc*TnjvJP`4VqM zXEXquQy$?eu?uuIv-Ne|!RX83b0v}Rz%Jp)y4?vi4P&Q_CMEYwk%$v753L-IDUVTT zz3K;a1hXAYbQ89?VFp@|z=({dwWR9wKMkruB-nJ9r70V@zSB?YOW@M4$ey=z2E1pS zzM@4#D#1edZz1we@lw!752$7XU+f~b;155N)y=8s0EuJ38J7K8^1;%y0|yRlJ<%#u zs-Hn(5J|>fdTs2fZ!cXbY{@;Xsa7T!%{BD~`YhgP;R;fxBuH|lV!Ld*4MMsAgfMS$ z1!3^v)9A^NCn^$8k7EbDT_eUIbFO5$5%i1(LW9o9HEb71f%;xg*19`N!VIxlF@|TY zDFH1PIx*r%w+rWK7ORdQ`sG{uNRhP%9wKNY>x09CLVgf7Ck#-`JWZ;f+|6`r;ce|< zkVNHqWv|@OcoITO0#n66axmQ(#oxw8mzzw42J1LB9I~u;!ufR;j!r~p>u{QTlqRJChL0u zjxC$WoAw&spb~H(PCND4uXt<2*1X(_Y;~O)xln0citlx%7B3n*yPOT0Z^(Q|o>lu`(-A4e z*BTZya|}SrK&*5=Kvj(VzraRssq9>Ph(Sms@!R2PcJn&REH}ng;!~@~xj%}ujMk#@ z)}YuAg5awlSZ#9M-syO(dMSsWiwyh5HDSxVU|_Arvy7ClWD!gYh7Bzy+Rz-_H=R?D z9!CxF6U_qg%XQ{D=H_pddU0yyDXr|w@h~#j;WWh!FVHG|+gHs{gB?n&s!S=)Woi_v z860aRNCr{Sy)!!c(e7cFsYxbFB=)E1>hO zb(VD;f5vjjDEYW~9eXZQZ*E1(8dGe||3}w#$A!4|Z>4A$rG-L+_AnY0)saHmXlNU4 z5-kl4n<#CShP2a=QW{FON_!7Q(N2k$^1JRhubgv!|Gb|*hx4AE=eh6ixW3nQeK{Oc z!zu0U2nErf?bK43`|XrH9$Gb|4XWo5 za)A+Z<@j>|`ENkfr9`BFG6FE4c&%sB2J<${%Gg3XxNgZ!vrej=AOi1b^^uJZX9EJPl*yf0E3&* z8+ty?AoZA{?&C^(KKe(GfEP)lhWmQQx$O{){O4s^&Tl2vzb4a{r4uxw0P`^CP&o_` z5er0Nu?TaU9S3ybZYxQV2`95Xm|r}dCAH!vJw>f`!E$V}dlf!6=SZsLwvEm}0DGXR zu1UeS=CZbX_V}lgcQrRC^v<^Lt4Yoz$p2*n?BHHjQF99Y#Bk;#ZLgf|S#M%4wOi8U z3fdy^+`rHq(f0aDo$R({6jTL#pV3GYkAz+4TQ^9|gsNkm2nrY1licprU;H_4-T|y_B0tyYG}U^Ct<7t)QdwT zeDvx{$@dS-h*Pz)kew3cm$qZ1Ra6l!r7`sA(^{v?AKd<^I0@oGqlwo@;nI0a@{iZ3 zX~2m%cj39j&1f#`)V{$)OL@cdeHX(Q9m>9zd)F-ebY9^H2?n#IGs$gncgrOILAg`hE#Awd26q>Tc6z1^vSVnt zjeOd^yO)gLhVG@lByVOGza7Ms4A% z`Y9G+>h)b;SwYN;@4}`f`IY>Xk?xr8dRHI_#6hMsZ~s->dvQX_vGy2SVE4TH=_zkZ z2S9>_Hq%;b|8BLDtI~6PoN7^cl6}aMm(QdKV${?hYh2_WL-7EYgY+`*>%6!oYCxVZQ&U1Hjs5Nj7Eby5^pJ#xVR@mw-5SpOM{yHYant;v6!0IJ)w@A=xi9&l<< zyCQS21*s&p^D9vHEAGM7>CNIDk59Bn3f)*FDbZ-OHP;ymhgSrKM+Zcql1QOt&fY`m zcuEz@&jM~Ds}q>bj~8+Z8+~)EN1UI^tRhl`WSXbhq{(eH{di3%jpmxf1B^WXEWa3R zjWKSSzBGmtI4@A0F_2%Vi}>_VHtUU(WtjE{0P^-{lp(ZCT4a=MrS+wf(;!GttL$lw znoubSs9HqywG)8nxFdbMZT@rRhS-W5KyjI*?|*MHR9VUdV;h+PC8-S-85id=w5BYj zUc?OAA5wlbM|dvE$v*O^z0edJhR_4mjD{wzyOCViQnxEy+ooYW^SzqTbJil)*Wljp zkxF`9YV6nnpwKr+ZyZw>41(B!sbyOM3+_~xf4AFS;q*wn6IIPP>uSn4#!59Og888K zeb;FT6;UpkqHsBdgjVaG{{ls1LNBD)NClrWJyj)*B!3$k~>aqsvUiH zd!!@@S6SdIyr2%Jg=?Sj_3>dXRC-G}qAt_DVD8(5P!TR0VP~}2K8#y z7zl52CtG;je5AnBgVy584C*D`+O#LfG$fZ=S($Wg||08zSBNILm!YB?kPqdaj zVVnZ~a-7g>1C`4ewfKzH(Qv0-%I|QCW~~I9^uydg!g*;6`@=DW5OY*o{qgDYC#Kxf z!#R=jjE~V`h8v9k!bs$rM7CgOo(>+bqoYfN*Zj=|cr9M2=p45kn=x2ip*_zZSACxKJ9z5hP>B}QvVL~VFa z%pFH3sk)$VQ!XDS2m*7V*y2|2N+i*_il*Yr2g%5`yd+C81Z-rE92es|PO}pzFzokVj&9+a85% z_eg%4GsY&6LJ(}M2?J+mi<Qo6~VGXqpi zEL0QS%%qc+zfLtmfRmw;5(~GA8Wbwd`f}_#HsznY~T@Iu|JZaS%YF!TWe(CvxbIjV!nf z+C}x8VX|c1<&U(WWPmNh_DbJM?z;Fx_<85AYGgc_!OIJee+8j00!Y$c4T;ninvWJYIC-6{kYmWB?QfLXhT+s+VF}hI4+!Ay0?gi^Rt{6iv70- zrLwb7gN5ev^?dTieiWiO&Da^ei{fn2+Kncj;>Q~`r@jrA_Dfc~dJamd-wlS)B+*G0S&wYX7-*kkkz}2m?;u zz5##M|9${&tQG4@)((upMMnKC8UL&TVqhesie(8||nNiF;z80j_2P$^Tf6lUj-r}~60KP7}H2%Gn< zJ#b9*kKb>uby$Jl{IAnohZfCysv$Z92EUC?GPG4+#0+vd`y0~PQmqVgEw%cveePnS z@}yWeIF3f={m)gUl_ldk@^-CdXBPr>-@cpKXXKpc8}L;|{sakcG6nX%)f=*Gbwz&t1`|QW#HVSw>_qg_ZN0pWAa#}k zTpHG~GvEBLH_vbeIQ+uluuVtjKiX$6d0hV_%YQ1B<}pKGrP{MRHC# zC4Y)oi2L+1Tf7i>$r~JsZe(eYDm23mq`p+zy*oTwrtVtlvrpglg4Gjn`}S?_nT%5} zPiRZioT50p<2DKpR0A*e^z<7b05(qR!9R?9(&2}u_+^qQ7 zkN=#XEuf?jL@6aN#!>UTl$vV?ErO0LO(d#staeRZh|g|-m9iYm5m+vJ7dXJ@#M+{Le5B~PE0R|G907ewW(EMK4+r-+Ces3cZ) zncAW8$?i?6+k~=+j-HP&b4W%#9{HdkvdyJGm8=-JD7h?U{1G9gOt$J*M?itawP+3- z`Yc2^kb9@bhvB~}u;HzW2j3aAjmKJZPq|At@&1EAfSckaf+x&KU-#e-qVRGWi<^e$ zcdXWI@N^xCKimu!t2D>nlnkpgItrhuns?al+g?cxCOfA~68%hQ&9$K^ewE5XU>rm* znuN|T#B5IvD@CCa;JN!0kFexEF}|XP%4<`mUbHA$XX^m zM?v^m?ET8}Z=l(5oy^@LIPdDv1U~RwWF=9V<_r7E%MYqD^0c$oXBoX^OAUO=WFxjg zciS3wu)mm2H(VQXDRtG+2MDUVG4P`y#o1K6z`Ny~Xk7@=d3c%nFb&mJd3ALkh-@*w z`+h_l8C{f#zn&F$4ViF@N4$&cO@q%1bYH+_j0*!b{zD$#Qw zaCq6J3U8^4&YyL&YHVvaWEOr&HnxJ9(IK)?-n;j;bik&Et z;@DE%lEZt2)ue75Z_0c=Wfv!>qPOZRHiUj|d$v+wJvDmCvM;BAbxQWH1H4DJw{rEC z{8Y_AJ3yic3I{%7C+#;oRcL zMc@%-Yll9xPk0E**0Y9%kL?+ADf1LX?_KEa?{6feH)xA<@(=AE*7k$LJr*E@0KZZO zght7BE_89=TuXs{&N*${5NI_~NvzcDKb(o#WTdCflsZ;Bv~5pbJ`<4xP2Z5inwkPvMK7F8CW{8EB%fsY zmi{!z_<6Ud5WZgCR_@D_#O&B3Z?$QZ_bi9CgwxEn`eK)hbS$wrH|h#?fad+64^lx( zvO!c-9W2u~vR4`84jAu7k#L+DG!-rht6G{w+!2dP|6?hhlXn>cQQHx24p_M}tc zT}9Azl;3fgb22=mB$G@GIK)1_W!xZYO+Q%w4Lfd3yGY;-(6ghEj*}<%98B%mQ1h= z>cU3MYR8u&+{77i8#aD0dgJr&1?S;2kRQgX3QkN{W9l@%4vC@e&t|thS${8-u<7mX zXqI}7GFRp=f;V&Z5Hq2b^rB61R`&%Xx_B|Ai%u*~cgyvI56sj^EOy(t@Djfmg~+1M zWLpg+3q7`U#AN_X>aYsQe*<&!#UX@CkyNhx$2Zjagi!WfD^y`f5j_XtyvS zjN}rHpDCCuk~09@Z$)|dT2E_SCeFyjwQ6iCq}KjGM*9t=g`fZ9>7uvebA()$K05#K zLTxI3CW%6IcPg$oMn2}}23Z6TetxsPr&f-9>6Z?lzY1etnijSvaYibX>7WEM;YN6zj*5;)Hgj(QjFSB%q+H;|W$k`5uJNUG+Xio9IP^))iu zWK+BCVGs@Dh-UAj6W@PT!DOvTsY>LjKjMuLC9y|>qgT_|8gRFE4(eU?2jDa(DQ?k^ zyJVkr?sTWjHcXPdwf8&Lk9}1*|2Zp$a_UPg*Q@txDN|Ms8mlSq@DlWn7{>G%9#ytN zvl9%0PAOW_iSLY78aEf{4P!ni2p}a}<^$$T%6Q;~780r~(C(sz@sj9r2i4UQgos1= zo!jMDDl0|^0!joY%ghsln#pRlgcK9K`G;?=#%E9_ziF@41MPYBC8ch0U2!j_C|xMR z&EoVz4Ta*Z5)BucWmOUsNUx!#-3rr)Zjk6sW43?5c_T0%u4~%&YKxN}+gPl843Qis z>x#;26MCzPY!C1x@B1Q7E8&IS@y+dRcB%_9V&fsaL6`?sgH~c~J-a6*C^dmUri*?& zkg;pK{iNS*fziQu67a9Q!oPJ4yB_@m1G_5kqMO+a$^leOixF=A(WQ8L8WW<1cWLqZ z`LQK>Jw>5b-lBReW9Zz!RZHPBs=AoE3)XOCq8!Sq1WkTzSVLQTvSAy?15mWS=pD6O zeL7tyeQo&B*~R{#nIcU;-~u^RMCp6(#S6vAaKvG9G~HvSwA1CQgM!duFabBMH_$!S zLEmGRf%1ev&*}Qo@Ryv7NnZHn9aD4D)APWT~y4 zYGRSmnGdTg6P&1_#S_wtYcnF#hwU)FXpdM>I7iAnquPOg(;tWOnvJ?h(#6Y{OVMhW zf*bjtoHE#yA#D>!p!uHZ+nU_?(FTWH&){L=V5_oPeU&P$)0MT=8K|?*ekWiA~ zBU9nCGlXOZCZXIhg_No00>pWCcLx%Y3r-z^sZ|lf1js@l&Ndy-mBADe&M*~bMxYb> zVdML)H$&pE>5`W+n~U;eQ7(M~#B^_=gJl`fgV4}=k*!dhO|Pj&Zg1*zk+JXLME(lI z^GW0L{$u+TDW)MN`Bt0{+QqMu8Rri4);$pMQDnY{ua`?TyozpaH1QiE2tkEd;M@8e z;;Wk-58il`ad|^m+TnUlbZkExuu|>Ik|&xktfuZ?%IJmAtpS^rr`#!RcpH8)r4Z^~ zS^JXLm%({I)#PSCJ7P%Z4-dsX9^WxN@Bkv$FPv;9&bSi*a?tDO+VfO{h&EtL0nj1@ zM~vztcj%u}NOF5FT*m|4d{isUJnsRDS8PSiaJ)6Q%B)&1+c4!i4i|Bo3}tvHCLCSC zw)6srjANPUEfCHgG{qA^Y!p+^;`oGw@Ef}Ub%Mbvf|195$W`TyS-Fg}$?5{Gx*1c%#v5 zy09xI-A#;>o?ucPWTAv#2mL?2%W~F#h~x2CUSep-KBsdD&8zf5+^5qyxtyLp08F?m z+BUw}$KEXQU}FV2jkittzsBCtTKdTR*screif6Tov? z9Z2&x(XGoEMA}#p4(ixI(-z%Tx;ixUr1vM{#C*!B+a5&sp?f)w2W0Fi=a6?v3x7!K zX>Wwx7};q5l)4S_w^8iCRU5O}@*k;`lYvw=C0a*(<^?z^KhIfT`_!qFI-dxM9g?sp zMP0K&&s3QC+}*dT6Oa25#SL@b@6o3?J5$w{t@qk6Ws8jU>TeLJr!{#hd~OM4eYd+< zZjS9jN;~YQc-2XDGPiTlUS;L?Y1FgMt3rb=Q;qph5hhn#JCQ;_s2FisDTW=jL7eBT z4{{N25-e3vVqIy!${#qivrEPLq;IzK7qi}XMMdAgwVYgbISlT`su9w4Ej4#M<|UM0 z;rN%g!d~-vPsXX~?|Dffdv)d|#jh1=Vd9&-99C1dBh3tnG*$NL2nF@`2iv?kg}V}N zn{_R}-EwD29!cpNsj|Y77PZ*f*~J0l+<#YTY4}y06m2zvfP#!@Y$AN^5O+s>G45X% z9HAu(L2uH95?Ev^2-6U+4bf57H8nNfs(SCF|k4& zR;-;dS^B6yDk2+Hd=;EuH3?M|8WZXA@X{#5?s*K9ML^j#ivhzI8sB_wr|akpZU7D4 zjoN6q$osGv%^6)2P{!ahn897xSK%d#UYFq(CE>Bd;wt=g|8)4{A64J=0n@x8hHaP# zE#pgmGEPm;Y8$fZ$K%^&|3>jSkT*Z|{*h&jm|m5YiEDMDa2oKbLc>mE0nHQk9L=O) zn4WUA{<``&fi!9J@~eMIupGNJeg0bDb(#Ug_96>SRkA;;3zm`}D^RCZgJ$;S6aGn9 zU*d(?H=UH5jyx%VDq=4IJvUx@Gxz@rF&ADrHujXv}!>@mOkOnv=+# z$(&-mvhq)UARYy6ts>H8>~vhhv9+>@?dib$&+x0cC&ot3*Z#~g)Z%4nbsA9c4Q33Z z9}IhwNb1oEjvfZ`F&7sI+>DAkDLK5AE~IB7&uh2TXeCAja@4ZZ16vMZXGQ4k_QPhF zRL2ajYbN_e$)505ph>gaoXswJ`ch#(hRwM_0Fz@?SC#-KYRCNB0CJz4UcF&S1eD<$ zT)j05Df1pVmRz8XNq_F6henyCs#Y%FxpC;vqczv_k>rwx*eqXku5A8>A=qSSHliO& zWzmdKQ%ku9Ypy`$#JABC?xCatzj`A;S%46=V8B8=YV6`|TC0|B&-1&C{{Vmmphky; zn))sUfpPNaTeGz(Dn|cXw|a`0%*}ot@<5RMG-I4}gxbeM6ptmC?t3~Y zPF1i0c||{S%vytNn2z_)k9+@MEt8ZZ;Ah4(uI5KSYKUf=d&!`Vsv!f z#Mh*VdgH&iPWaSIaSUuaPW^#*T>%!_+}gYyOC1GvW2q&rD=MLu-uoP$p7}UpZ7f~i ztLZFsdyuir?)qLjBEcV9*K$6)xBmxrqo`6>mavB-;V{?sFRSlgHPAnWo?20;M$)qS z+0cGaOgV`e!S^@Hy1hG! zXCYdJIOeTRL$^VG*b72?%@zp`g66^9#E*>bceF<>t7P~=xS{c}K`qwx_j)xBn2K@< zN3*LF3u{1h!9+d<0!{JEy^Ei_kM>gVl7&!q;|occi}GC5GB`67i33+{uKh!QpY7Wo z%<%&juRS9V{8;Nf`fIK|*W;>N!E5J2xtO!#FplclMR79VKlWQHDJl86gRIMi{ON}< z>FNeWU1I0=_rtV$YWvSiK?2*p(qEPl(=LjZ-RsUCbf4luqW`2+F9d0oT#8< z-8Fn^UqP>-7&^(e-sXf)!~+E1LT#h6!l0gWZokYM)yFp*t*i|03a?VxN+sW&$xtt z&T=<`$0?6f^9a@HRa2D}yga*o0wG$F-ky&cB^kkE=*9n(|MtIUJv3Blq#-JFECVCy zf0s0hZlLwi0pRQdK1o{5*?RffCla_i#PD8bx|KIBccsKUCkWQ<+)mGEP@iLBqk^L; zuK=G$8jc+tg=d!rASC{=u$zsU4!VjM-}QN(!oazu~eMnHU%naiJr{_Bf*$}b>d-VX1V zwex@;)WC}_<{WR@ANyV(RE{`E4&wDd-}Ydr)GIvvBb)}XaxQn-lThMqsQSwA>Cni? zNPMz55PJi*i3*R|qk>@{ySszVR09i*#S_Qx6vUrx7m9XLB{?d)hG-TqNTz6|d~EXS z!5_U@AMMmwRT2JNA8g992q%ljOqGID>5r$9vFN$1GdgdR1wzwlPzWb%PGA3zY&;Q) z@F$ngsXE`30@?~&UBDAPB4rYua5*sah!nM>KZR4rHA_Vk-OUEh0`y_TS4Fg3&v!Z2 zEcWUy+sUa*owa(p(m8!6fY8@?%x^RN}ZMY8T45qu|Ex;r@(2q zTL>lJbvi&t$;7#;(sbz5h9Qh4==wc|=Pe#HqP`5ISh$F}Y00sZUHDf^!7e3oug9S) z@BT-KbjKXAO+#!+%{-g>VqjgUQkH)=HwJK`vrR zeY{tJlbI@ObO5khHw+u{v*}XX6_wW?E(F_VDqvFZq2p0&7}$vn+gSfDI5egUs%*4(a6rk^r8GtFT2-iHWHgj zrDJw}_egyB_AI*8hY+Y5l2u81kLKhN051~hh`vbjc%#XK@5p3!A=K-(3pft73J}99 zGLr7JAhSMD6{by;{_~d(Ccku^QQ1$i@y{^iOVjhC2S+Ri7Jh8K8Yxlu4^;9Tt)zvl z0se9Y=?gx%?&sv=+fDd!soI7G!=#J=RR~;$)_|vZZ6Uxmty*R!#d6q`7R$2e!kMK2 z;}J>N4+dO;vDRNZQhk!^G%O=m;MAbx>~jvFAimMsxp0u^4k7VSMw?liGX7(rjb1lM>)XW0^EH1l zvM{jh+BI@5Ah=Cpi%@B1Rqf{VEk~0;ZC7pz)C+z;<8NtdIr}2aOz?rnfkTJ3#1-+C zE2|Z7M!#Q5{TCI>rIsIuPV&fIeCk)a?eh5TFKrbcjy{3TETYD$-zPjG) zTZcRH5|4sQGm1!9W3>YP;OOl1@B{e@=Y+6VZM)_mM491&8nw&~YE*sNCd7ba_-;4S zH%CHvqotKSlNX4#-lA_F)RVy|a7x~amyThJ^X64dzbeHBhUnZjiI0B5|4Tqr42i*> ztZR9Bd9Shl2tEnm6Km~ytiHZ{PIGIY=X=L3Z|OGGDao^KSOYr3m}_n}D=RB6$bbwQ z8Wqh;bndz?Un6~t`JwUJyHQb5_fsU7diBv@uB#ZY8p@5@C8+&lXXoL8GkF%+_vu`y z!?!L?u{Z)t5C@>NVH2?d$v2klS&rEDY7Ip`y@lUbbisnx?|L^nY?3MeMmg2G8H)tH z^Sg~#t3{O)r8)%Z1%nHtcmK|zfB#hcoQmJZ=|1g-HGlsTJaw|5?d*5wCaAZYx~IIg zMK0CG>{(5j#wmX)U#N_GTOb?OO)`jZHVk*xhZPkS_1M%;7ww4Drz3n2*qto(Lr1Ly zJE~pRyuELjXO@+fWv*!@cC6Sf^tn+pIxFkon5!O~U+avpeuNusa{y8LUb5{!pv`e0Mw@maV7WU%*28YJT_Q06}_&^2DhO6!E=uLidjHi$yDn<5;hlS)2C5 z@KBASir%wYFeff^p-56j?R0TuE6cOP2RdpOc4K=O&K3`Ww(eg6UF7KzSrEurL_C+% z(Af65(XOS?VViRX26UWuGoG~p6g*`&H#dU_&+iNyFBZe>=Eis}yqdjpa&iQYoW968 z=4_yGcLKd!YWx<=p9lxJ=jwl2+ir!7#Wg8l+Ky7H+VEtD+cnoCXup1r8ZFv&_%lq8~%z6Db4}^5m0zn(5fN85O_Z$X3<{KCPd{FPFgYNCU9T52XeTsB_ zYxRl{z)$T|MDMmGPU+sit2j?f+!U$ugABji-sb*BHXFaFsHEdaIks+N2`1)-Yjztq zL;nIeo?6n>}FXxK`V5AND-Ak0^t6j2QMF)5r_Wyr?fEMT{e z3vH!v4>}fj#m268hE;zT=6jja&17_f-5SfTT;ZA*zW)9c4J-(44xfU{e*amkY6q$^ zDB!sDDqYF+Ma7#{q*e8tJ>!HL9?6Jyh&MW4pIGXm0KXT%mV-kWqV<^PL*K~i@fSN& zMpHq3Si!(xl76_i;VRYRiTCtGRD4hAUd1L1lIL#i)y+HysTlahh{X$8IEdR$w>592 zj+}YL_XnNGx zsCgT6-tJ;?1dwnuL7HbzC=o#Yh${2Q_?xiw^mO3XO7>C?u311w_o}I-Ryttqeb(`& z>a_~h2>~=c0$cPr9-=7#zR7g*KOK3X}?^H`Ryq+P0gE6kH+SGT~A&2dC}Gd&RrC1cmCe02e1q#VcR* zVKXWktaUfs^f)9WWF+$0vchF&7;o8LLC0E3JS7o4lb@b4`*e%S|Q%%|p205sL*=~)8;0^+c8V?TS_QVD74JaxzAM@twI zttqax^t&utS(HX?Pf?4Whzv82@axgQ`SxheMqhYWAi5`47Cjb|fH2wSL-qY_)LGG5 zPU3YJ*$5~CmJg3++iN*gXcNO=YOlOFNG2BB0yqV69D_V(^XCjDz+$JHp<1-)4JKr; zq0H1iYP*GUNHDs>ZSC5%E0E{0+;ZrRNkD;v-$$Zj-eOjk(fkgHKos}LA2vxZct6x< zF7Pqr!6`f8rMAQz}*)wVb_P96%1k)I+K3$*77ky+r1N$^n%%7FyK?U1F z*P7icI*Xot^R;GTB}G9&@sT!c4?fsOO7Qz1^o%c5`Qbx&I$hWVkv)0K{)%S`J@zn{ zqTtx&otfSHnqRMLEi-dhUsB8VBHa7e#Dzib`{(m@kMXvxgkNn^xSQLye+5(% z^2JVwD3h%Z1hq1;qL`70x}3zbek)a)s4a+Q+u#mRM~{|3kO(OpZSHb)q>;SdUlx$F zfkH%FWA9$Z8U1(c_Lm3H<~6P9$6Ur##@<-=7HhrC5x0E4R|~XQDBb!%`a6C-K-etHu_p{{5e@X-Aaj96hd@7M^=ykMf~I+F|Bu@;t-DJ>+ZR_t(!E= z#PVjD&kN_v)BVOj1Yrl45#|{wFAl?Hq99QV;D0_CA4*3#udx1AKC;sxktwL=&Cl17 zlzHs>kcixGu{2e4>NruC9MmHw1))ejqSVkV9p{fx$~=`cR;K>9ji`T?QB(&g*)J{| z6~XFd!fIWy@cgaa@=l{svS(eI-ev+qBU&M1DOAq1-VZEBg*m^!NnmXvK5_5(Yzjt{ zE;6s( zzkVv##_MlU_W#+8{QQR*cRgogqy+@_!gpS9jiOWWjjLD5ep?x(oeeZweepbRx9IHZ z%cG2oi;JPw!2(R3^-1|JoqDSk3knMjrJSY8k0Y*B6TYA~EJ*bE$cCp@Nc3U3XhBln z0fB0z;zDZBdT$(HhrhxBiWt~Rzu39b@wVe|15J~Tnmk+4I)uuS=frsf^=Gof`xiRI zCfXhAe)SEmJ70ZXQ**%ROeZxN@(9Esk9TLm^!T4=vUb1c`)_)br)B2-$v0Nwh>r0_ zRYVJt^1?J$FN^z}fK%L=qH`m3C@Ce_D#vfb?&Iq9>*9_s>1r}Ri_FZOY&f+yVN2I+ zUtY+|M4J0!sE?|Fbij=~U0mAmGXpqGnLV_CQ#eF2u$q%td_OG~hQ0G17Y)Ted0Uo*aEpE@x(EhKF7R`!})n~|Waq!hO^K38P;j&Q&PutwJ${PEg2MakyjipR_inDA+Xn@r?)&a;t!diK zqswvF7(>$L{oX(8mgu*r#L~C8ESiUm;9Y?y(+w~($S78ku;5rcJUsZ(W}L$jED&Z$ z4D}q!Ov_I-Znx(Oid?b3CKybdrluwq8*`niuxnwT9s?A4jp1T9@fEU;#iYdaNjXNS z(vAZbktSDBl&A`91ep6FHhENyt#mtV8LA6ioesQE)1H8F8ZqConFHRxy6 z2^#BCHi@5TJ_viv4X_?btU;)Lkowg}TGtH9{p%gjw7dz=>x_yx}Pu0E%~o6&p@+0NNP#iY;%elMl2;!iEB0 zPDn*fqb;eNQrmnJxBB0Y@+%Ia1eYa`3Hztt^;z*n>a3MI-gIBSd=V;w5yk zmpo748|U2MDa;KiCRpCJK(Pt~r;0l6F;7p=)#ne^J0ZVpy%_r<*}?AaP)Yjp!?2A} zT7XFSqGbCCBO@bn&qls{2|&?7Y}5OA_b8#YPgqfTfRiu-xy%e}Q=Si^ZF5L=qXD*4 z#uHr;jX{q;#Knh}TEVAxv)xD4FH}a)_l%kE3Q^xP1!JCA2)%>aA3;L<2x8AtS&dV! zEPjvv#dKdx(^J20?Xs0G4_!iacF647*57Bib*H@3j=DBthavnC%SXQmIX0c9XZGI} zeTm#t2A`Hzz39ZmJ?J=L&p%AJc!x+VoB^^ktKNrVc{bhI9veRlDYE;*!`JW;LD$jU z2ik7@7V|G0_rBbtIaKOi_T zwnc@KrZ%FO$PtO8p>Bcwoo?`>V}ZG19j%BG5W_eEnD=yo#^4WZ^r_O;DKR2#H0^v)I!->jir6>Wde<_2G072gI{(_@)el?ExH!Hv9K` zTX<38+{-^@?S19SO=N=lJY&P$Y;>gpqN1Yxr40=Y{1=ujU7G6f!`{T0VkR<~`bb{> zX{1i2y2;wM5RdWvcTG~9F3?MaFi+G(&92uwzU|Cs6M`tKeB84i#f1l9Vy!|KM!Z+F z7h{)B;C;^Yhu&KUqxN<4^r#P_K;0x-86b)lLfGhDem*F8`>Jbd=Dx8Z*2T|z8uFaF zOeSo0M(db!zO4ScnIeVm11tx*K5{pea@GkLTs*sg$i7n=;w;@vPi-e>s?73FDgPfF2-KQApU-Mg6w zf~1Y%^6=v(gqsQXIg+0hcLqk0N5@A;6Uq$QLuTDb!?*cx$%U{bhm&2iqR-BLpHxzP z^5n_rmkK!*d;2k#O=hO1t9V0L!;CWTGa;vKC<&V!^RmgtBu`cc?5JeF zIH=cw1vFlL1c=xnmZnt9NIB(jNLQEN%gf7WrOzfS0ZlB%9au00xC+}Gj>Q#9z;zv) z%j0mjvN`-(e%*%RFwz?LtlRPR((_|F%Dn=ALA8-t@VSIu+jtku&O*9NLrRxQwRWr! zdkEH<3Px|}PF79!T=iJKW9%l;Yo58$^ICei=*Q!pw}Zq(gKRDH4-PgnNby$R_SfqT zMvK<}1fo5|X){97!_{)1R(A(=Z?sxO%CY4203w2J<<8rK=9R}-Y5W#~`}*>Z>(@L3 z=z*nlG3}X9-w>TIhd#47=?JfGKcyax1aNPx;}RD=-tsW@dBnGq7I=qZ_OF{In zup4&sExvwyh-)k`lu$M?eoS4I%vT2T;Qp~^t8}dN?xj~8 z&D&VDzox;Pbyf~r692B+(lA-z|<;Bn@(f$sFb3rsdf1Q|tM|2bQXc|kXgnG`5g zls=5G!}3FgLc45PFbb@EgZnp+GM7udfqugjXCubWHK|u%GZbbFNSPlL(0Ve7F!Tf9 zd326%_0Ru9gM$PW$V6bEYqIpp&t}p#2)rwtiV1Zo8qL)BCX5EbWA(Yda#M-vHdu@< zc7_*+DL#omGDCZNyHckMOr@@yKZFKj)uaBmUjce-oYiMj>7i8m4{EfDBqBq(B+s+o z>Zp!t%ID9Y1DH7S{rw^D60np^vjqG}$!MCN~$BHpV zR1h}>(vq500?RwKEDtmwmqNu%B)+@zYh?7NvjBK2mLS7{$JBbdtXS$_ZWaGw4e)n&qqsdx7 zS_gE!FgCB}*VRx_NwGJ<^o(>Hrr-+*o7fJFZN#hlt|QMzmkz5kVwpk=aiPm)VW(={ z+426l_X|6n$#^;aE8gCA`QzQFie95f>PD5L9i>k+2_IakNn)QD!sdSQ;ztA(PMhS` z`~7EpES2ZJq1d>_+G1q&`0-;UuY6x$-vBekMw(mts2S}lmRD^n@?_Puyb}}`pAcZ- zB{O{LW7MbW>iuLV8u0^VVHGr3dsbfFQ}|HkE=(*=&c&uvHe8F`d?yu? zLNXM#tctm)@=;|!je#if<|UbmINl=UV4CE9lN=YF6LDaBHcPD#o2 z|5#H)B6Y4mB3YVvc-QaovWYT<$oHBxE#BVVLeD-850gS^i{t48E>F)BBzdLs6>@1B z$zU;*cXy}SN82;Oh<=c@oDpKNtF=bAlTJ#@6Z-YXwpkRo^?J#gbmy>At(jzurrMag*w33qc zp9gROg$^sCT9A22>+i#<$`h^Vq1WM_WTCN;o|e`RZA;CwJ!opf$QPEp+jUf%$b(*i zPZXD!`0B_NJ1M`(f&n+z(6Uht@R#rtYwX zq_eApqf}LdKNOO^W0U^m@Lci~%>segIBk!T1}$1ZI8_g=-s?|I*-bUJYVW&*QYj4$ zjiU{YI&#_a9>JU8RYhvAx&|dgyJOFZj{FW)l#B@ zsJ&6Z8Z@8l`u&mq_mdO)CqKS-#Gt-(RMK@01pShu2RK* z^8}e(eZhkbTOBS}-MY1smX0ou8)CFMkoD#@Ov>zsTANe_^sa9h(T#Kqza^r-{C3dO zRcsrC()XMeW4&6Go%XKZhyP_4`9m01P-IY;G_K)j* zPoq9UEL-lD9N{2WRgaQbT@=9oLTTSLJomIxU9k?`oT)Nu-9UR`i>{labInBy!#w*_ zy@oA-w-iV>TPIKx;6->?#3Aj0n#jmMOW_U|%Bc_Z%Nta@ulJ#={+9Q^{Mhe!I`@+d zDGPTSuUp51q)zpAHglqYAan12^~I+ zl>s})Tv?Z5KD8CNH<4xU3e+{&HI#36TzIN)yZO-ugB@8I(5 zr;Z^4#7zr%Vu!)+RJVYFjSLhN`GT`l#WeTt=f*?;i&U&PX(PO>X~p%|{pQ@Z={sDU z-!D-dTs@W&?(?RUec9equY+Wg9$F0Wm9tOowe|Eh_^xsPe!%qodqPgi!eS|q@d`6o%$Z^){fiPkfNhO7GgN}B_-VE-?H=HLtiwzX}F?wEFWCveKKL19viDX z{S%1IBPhfI$c)PWD(8|M=E|M-0s{k;y#s_>)x~YfFE{2czG9Q|(yPx@)@_WIt zfi)sscfy~>Ip`MB9ZoR)SUM%b*ZsBpW%tg%PBncpUcG|n==83}4Qhra8$tZQD64QE zb3^W_qeowUA61i+#jPaPe1j_%NBlZx^5t`jfza}@*esh1hlybhR`2uS)FVp7T6Huh z^9LmfrepxqTi&-9z&@V;t$se&aW25@BFw!%z0XN4P@GDgm0{>h-$3|YwBYMlFZbVF zEQ}8xZpwS*sUdY%;uM)K2(yiE|A%z&b@lt zP~tMrs>#jvlj;7q-Jj&vzbsXF?3Na8e=X6Y&Nao(OEv^ct&I_+%m$*e0U! z&9+W2)F$$c`#puyA5Q)4bI_V`6{HE;!bCcR-?qW9A%91{TIML-jihVG-;0Gu6=|PaSdg;a;pGFm*l`t^_0w*C zr!;<8E0}(5^wD};B*^wQa!39>`2o~hrw1BO=9jrTJMRT<@$B6@WB9JG2NCX`vXcR+ zaks`5gXwyMy91Fg;d)ebn?5WNwSajFaS{}Xn|r{nPsQ*Gv2A*>Q^qnXA8zTEB|3;~BoJ%t#kwUMa0X zYOx`G$Z9E@<9!7>?hdME-+AJMUueV|@kl*9p*wi1;pEC{-T|3(L1D_{#5CoF^-mP1hO@wXegno;s!y8t2*EM( zycYat&00um*7QkU{ofasoz}vy5wjq{!5eKYC#ckEP7X(P1KU{dld z@L=IqLvBw`0je?AcjU}IjNW~|55fbYXN$k$%gK;V(UeFO!xZ{jpjE{gZ!{csLx58YtVQo2s|`5101zrqgU3ieXaG6XnDG zEmaesedH-`Dw9hh8`0+Fv-dvoR$L)tnGzT{D@jX#>E)YOkq*Wtj-dD{vr$=ieS)pg z;Q@p1SV*7@(;mYPmR)oR?w+Q9kIBDbr{61Vt68#!GM+8hw)0%ixvWt&C+h~o7Kd?1 zbDJMuw(50qx8j@5;=&tA0yYr*cnsonB2v7&Cp6q;J6q#)^HfQVwCc{*~dnI+3g@NdZ(bJ z(=+#ms?!d6-hIl?t}#Qlml5=fkf>NcR1SN2Ot-u{2CJU;!^6hr_cxP;Kpiw*@82H@ zg<_nv>?O8&^kWcB5^EwKnv0tl67QomS`5rBy=3O?tlcG$q=_KI4RcEE6GXpsvS8%W z#MD%M<4yMedO`yQe58h3yEA`ZLt9UIc-vtykhb)GO#k{~JKjLjB&qL0ySv>wSDl_3h3VhFB@}vevF%t!H^BZ%92&@pE^0dku<> z%c~2&3^Q$Zm^n#pJ}VpP|FFcxFL=kf8pEr6>bLnxpMa*_=x{W3xL)pFqG4z?>;QTd z0wJ^Bv5BYaW;wBb&(?{1R4Pe+-#))n+@;vb92XlKEBppsLBbA)4r0;>|5II-VE`HM zP_O0hKz~Paz(4-Sb}zo0(fsWb28zT7wDB)Br|a3ZaD~A{m9&PWCzfh(V^~UA$3m9g zf@P=Y_G7T|{@tFmVIM2&A7^*Q&*bE`A;MJT+72ZzHxJJyqz@)iiI(i;T2GZMK!&e(GxFVPVup~KwIAe!8P7g>STj1IKmA5} zkD+5q?f7`I^X0l+JJ7H)Vb5Q6#G|cT79PI2EiEnjdG@_Wz7L|UhMpk+tAEp0@30df z7ch)6Z>uxN?Jp?1F@9_fgJM%0keWmQpHK)Rzpya#%(yCM9W`CC?39R=O0#1La))jl zViVw9zy1{nwV%WvG4juQmcJj_^C-G@r+ZRAw~Nlbhpm`i`Sto7&9e)Ot4CLdZKbv` z*J)TN##f+1E&LdM-0*<>yYodqW?k=|X=!K}zqUR*cc%Jn_qVsRF9YqW#X3VW56im7 zrx-L$xpB+b@-=&LXdICbGD@)e-;b|h3=pO>FmjNNDSVV?oJT;`%cZT&~!)(Rc99H z_B)Oq=Z-GA)keBR8_QrljNixxSIJf0>d3INNaQUqgNzt$V+m>e7&H}Ri^$b$*ETx} z6x9;Dmb@6Ku)cQw^E3hN-JB03c;nq+;c$#hnU1eSdZ zH0E^ViToMhTswnon%( zAuOcHKJB{vzmuwYf}(AMHhqi3%Y!PZm%h2$k>=TYjE$o5Ivl~4dUXp^$Pj}!;hV1OkGd=j66!z^k|ZtUNkb6*i>meik!&ILqvHYflD`k>0?K-- zvBoLDxvv0Ni5S&K|F!V$f|93qFV!9Y%;V|#l$0+kB^Gj-*m(hQ$z1zxoi!={n2>E!%JXaGZGS#An)P9PlR3cq_NI(wK$zV5j@mTRh8!8wH+F zv~P}gq7SVWQ!d!PV?CVDl&-Jj0&b^0P5Rt!;F?Twaz$3Y<#^Z7p3(NWzQ)2t9oQgvzQodIeo)j|)2okW9fe=;e)*TXU=%or%bQ-vwS!ZWjnd^DaYMQoQHmvv z$Ax9BfdNucQwLpSUAxxCt*m|Uy@ztwi=yKp0p=buO>vRw32r0DrFtv5Gu|ll7oIhq zjJxOixZ%R9yq7Yo#)lyinG@(1RAEyV-Pt~yK{BpJ-Fg4bhf`eSqj|o_-Z=JoLaeuoz>RdOb9Jrl1~d#vuFuOOJiJs4S%;7hL-7+O_er zyrpFl?5MnlmRKiEPEV@DNz~f}vNm-A_aNzdtMDbs!UX0ub_{`7ujvX^s+nlO9o!P{Hl29Fge@3 ztJkcLT&ttx=Q0&jfO2BAK8LSMPO+%_{qP5Ye!drbeZM_<@q-9ZFlFmL=`kI?uksyH z9$&q>iM6ixZ6c8W?yi-)RYi~DD5%iGq~Q?8u7X`FSFI8tKF2-p#Hj{EG%?vKnw?7N zso>1AJe<#(t1q4Xy#4;c1dknumAvbr`c7^CM)rS`^1eo*;rFTk6$3qasK<7%=yvz* zeAT&%-YXfI)<{brZ7#6ReF+EgEF!y(6NnFvlVkmQ^d-U)g-YHfYpRT<`)-xZZq&M_>@K95UyGh}gJ4!&j14h{@^THMPT*>|rxQM1PTw%?@RTKbTV?E`a zo6pK;iPMb|~Ci9!5OPF{c|N2tjTH*_2@=%#m430wjPhM;WFS zj<@A)Y|_?m*l>tLQ{y=8vf061Y!9*^MO1-fcQ*#+_gDM74-#vi?*q?-nRavhj(> zB-GNxIegAMMr6HoyqHIwj8c2hTP-KrvDWjxp%4le)$d-|$B(v-l4MH+1 zD8Hd<+`X+Lp?`C4%x}#;UYOjpN^ZN|E{q;Hv*Y)E z8?u+z^oX;(M&}*Uxw7Cw-EIz%{9iY!NPHzI9IQ@PuC2UcMdYc$etmI&+a|cPvNb4C zLy8W3wTk(?Bg4Z0q-R?GsILp&nqTfhq0C`u?1Z=x#n>+fQGcbmj8pd;&)htF!camjxa@{;q}z^w&SZPmx|G;&&!Jrw#jtEA&(u z^RNsq0O*GkK+olS?&<-iwxO@^N;&H8I=~C*zXZ<*W@0XiR}*?r6fMraMJT8#F$` ztR#@_A&B{M0v$|8L}xZ*Ah}|vW2V+_&PC)OJWWG(U2hLh3~Nxpf-#ptB?UcO92=H=V|x=#J)*`UDN-Co=|JTbhX2db5XUgob%{u!6;00N2F|LW4)_ds|9bqm9C*q(I* z1-Wq5)&qokjtxu;-Cds9CwZze*VRTy@(a=ToC)Bmx>FTu;~wCD$zrCvzn>QQPnYlj zmIZ6R-wpS7ZMKl0pbc{uuMxSCzj2GieWEl%WGs%&wb_>ph&hq4nFQroMGQglnc(JE ztzbPi-M4DcwawcKVD(#Ox1WVf?IlWt?FEcv+w`B9eS8}>kqTPooz%>4TJf6W#61}7 z>}hFiJoep}m4V@a-+dwYU{sMdc*l$P0@Pd-t3!!9q!0;{ZuS$qfEDyW4MFWJalX?Q7Cei}Lp&_N0{pid) zp8m-t9ZQ2Ov#}MkWFu3mIl;red z2dc55OXHa@PAT5g>B^pPBo=JZuA*RNXeF8WRKMh2GyPd-onJ8myHMo1D>6MRv0*7S zNCD0Q^N`4#P-!D=nteDTm86O5Z}Gm#5YG|Hop2n`8``cfU%rsZlyv~h-F-4LpB8pu z_S8cLZoq`xlD16OjD-N4#%l%~ZGuSyh^nG5%f-U@}AyIQ6ST#+b~5lNt=A z_ar#Dxa840cdrVI$P2iC0V@)jqZvso%*>p`7#-ScciE2{%!Sr1)O*MVmG1Wom{BfW|gPd7>ptGWk)_B9GDpU5Fi4ms><@)oz zipPow2FfWBK1RyugKtiBL1AJ6+~NSH%+I78)~)v`;ER=FX5IjklVk)MLB18c$K=W} zuQc5uW4xA~gCksUw@}_kgApRV4HLZRyq{po7vgMk0{mZWV0eT^SIL==-Y-yvaTdgy zd)5lrKp(bjJg9^Qd^-%f#=F0Dq2Bva0xX|KUs`B6ujR^-NJ;~j@bNK zf#COFzkFe*AOn<>3~Q21{lsCsWT^K|unU9iyonC#^oS69d9XK(-?C3;y_{Xt_QRDx z(CxK3o&6CS_rz%|<}UT;20&G0o@T7C0mktmG2Di1 zLDVaBD)y`k|82Ly*u3^qpKk{ z1}MbD20gb*F6EF7xM(rzhjl5MsYe#M+;bY&0)LGg>Hv=!N-hANyH}AW3uBwJ5lo~OTEN72{_I6pN6;SJcM75dlgb%KU7opEK`?rvf1xan8 zpu{i7engE8F0I6(rTZ>Cfe%TJ4<0*q)keTPs}g2w)9^ETCl=$0a zG~7FD#7&77=5k0hdgrv|=DS4A_xANI#F1(ycrgHFi8Fe&ME@B_mGkS*FvNwjFc0&l z`3qc$7|0)5t1f%iEWLXO#!uI~lAkEL)j@sS@a!n4H~?*os~u~krkwKDCARRt-K#uS z`Y5-6*l`jXjU6MK%GG%&sT2$h!j`hIs4rK&w-|e(Ru4^*6+zi}wp|_8mN%uHpo(ZA zyMMt90BBZ;C#8t@5qF*S*G%2#uhIa1oeUN0zSn{0?CIuHT_qqJ^K*0dqL>}-&j!`P z4&G8X{m;M5kiDc|azo?N35{D%6T=S_Ul__9ZEahemjq561?lhRCOkh6!0otCbC*&6 zg;duZ0QxyMZ&q1j*R%u$`Pp0H`7c|D=8P{yD-X44I7t!@0@M#6-1ynpLWeW0@%9cv zzEXcfqy}=C=6z>fH5*<#^K}mVjW=QHoF_1Ifm)bKSHHK65UCT2f%F$CH@biR+;li} zFJLK)NNzg%alvKhcCw5ihT<~1RF$`VbIcw@tv>eRPRzNkx1Vn`o=IzFA%jZs!G=rF zM}2JaE0;`-K+@v%2ndinm|>w5{3@(?5@zVu*nWEgb*1$!Lv$cLBcCVgzb!|)^6)$C zs0DWZkxI?B+0@UOK&FG4nHj&_@C?TBv9Js9W82_hLR2I-xH>!kh3@_7$RcAaUy;Ap z1ATlKdDT3 zFpHLLbsS9%kBHD%uHpWdJ2?hrfGjpRk}~#lke3iOU%dI3-2}?8@MgnY^&85XSG8XR zjkPZ274J?!gCI}LmJq$8)SPOkl&WLdJ-od+P}Q*3%XlpnF>?%N{Zyq&lHIrWgfKdJbe!vG`<4|9(;F&~GXm|4qra9fN2n|! zad%tmmB$S6DLG^&NLXPs^_!Ha)5Uc=zRdsNujXR_}D$ zD?yJNFaoa*ShYbfP5;Mq;--T8X`J+9jfB1I?%fw_Ek7uVy1OizE~94715)_^(l#^b zaM=s-5(U;!ty#XD2c8HiZ&NLS{3|9<28$x5gX@kckX0WLM4rHd$u?fCXO0VP5p9?3 zSobU@9>74dTSCJnk9SgG;8z0sS=VhyXep8Z+s6X!1f=kO*iGwAIhkVM9n zD;>%upE&HoMvo{?_rQ`~E6b{cG)8t8(E}?W^-a&R!2=|NYRgmGXPO#HXrKI#P(czT>8L}xvx$|%5A|21QwnzsZ@C7&{AF0 zFj`{T{8HJJK+eeiBd}j#($Kt^Ki;xkr5b=T=6S?QD@;01q>_0nn&YSbFH}rH*vH_j z^h80&brCX_HAGNXANjbt&JS=GRA~v-RhIt(v}1FY(j)UWzu}uRc#s3@sp?|%Y)&M7 z+`W4@2Or-PnXz+BvpWkZHJX-^dzAf^v*2QdhJ}q!&MElB4k>?{kS~7Jey&8~*EN>X zNl&R-4dN3)ilJefp$dc#B6BeEHPyBSWuj+L&?%v}rKJZ*zI{i7>Ykg-2QXUK>9l}9 zIRQb|oYLJst8&dLqdqm!W^^`h@=fGyBlW^Yr+5Pd>1Q zAZkJlA)?4EmxwoCx8p7g0jjYTm&Z5kcH%ntyt?P)5<(z4Ucg935^6cwwhMRglX zt0?-f2mcx!_yY^3x(Vn9$P@V(tc!KnPY4)Q9_|_*8rr5NNdw~V06FuH$$dASwP+m) zuNz~v+>C>XBCLsdCyur_iYfOjKF<}G*>gi2(zK!-zn$fSG#XIb_yWgQWkAuF*TrzJ zIB?Y+^g|yS`G}?cyqg&;wjjc;s`)BVU#SHUE6s%z|sT zzP5iZ<)W)z`9`6v{X$RKzO@C;RDYj(&mBzp>$j#5!<8aD4Qsesu`dzWuK)bJUA2R! z#Yy=-ATG&ve+hubyYGsg);0}CR#QOL96i89W*z1R5I#v-CXCTQv$l46CtY& zW^OVM6H=U~gu{TQIJK_R3ux$EV!;PDzk)xR$p(cYjGwJA*krV9Rrp%@WM9k@`5q;? zik&iY#s{B6@mLvJp@%yp+bNx4&K4S?pM#A^Lh1vXsmbuIy>;Slo}P@y?q3*EZGr|F zg?#3tboT61$VAAI9w2HAT9123m5ZwzRc-aptEk9%P{%#oM<{mkLT;<`6yH2DDM`W9+?%6qb_jk}p6G zttWT;^5$b~N7lGtQbsOS6C~NdMLrWW@O7o#1Cj4LQu20ihV&Mf4T?J1hDkx%(X$T=Z^&jvC z6b(6zxrpwAv#B!+8p^Bv{U0X@h*Rt2?bPX%EJn8T-Z((l*8Hvi979@JObi2MJsz3T zqnEmB8lgG2`e3d8+_nYRrB>4us6SyFf*#|IUBUXhp&9xt*^hNhmTKh%X5Abi0Oa*D zHy}tycIU9j1A5NUseTfsFhdEy%tze>77<`9~t}MbVfW* z(-bRIZ+IsW7u&$co?O#a%Dp1}?@Z%G5f<)hp88UX(7 zBDrmcgN#h5AT3ZQTxf`dtUGe+CawXeCwW8eSfR;yYRx5-fUl$(-r zfD35$QkHzWyb&k68M4b_R--g0ceYFv_fZMRE8+}*vopW_>Xj=*0(8eS51`l%VXHG>a^x&8wGs!B8k)CY zK_Y86`UBqd9p8X0y`@)6I$>h_eAbJ>ksNS@1ED8FTV>BO%e@59c!UHDAQ zmvH*814PGUyo92(>imEf%DI97@keet1wKa6-7N}X4<4*u&Df}RP|9iiNXLgSmQU-z z7-82*(N8mvJui!x;)8_nuBA~!$VzY~aLy`$at@)U2{hSGH)rY{Ni}#9x2IJYj8k7* zQ&#u%*gnTEZxv{%XkyX&kEmTw1>cm3bgoU9l>3Qyzh*iI_eYIwze;=Y=_-8o8%*CPBZ=Y3+K<@Y`y3VYA>zU zp+g*y7W0McZuz${z`Q)LKQP8V>Q>$tuBi_`J6zG|l9`c4uvX7>6{Wj3G&NPzvNZ$6 zu<_(JEmigeAzKU(Hbwo*K6mG1G|vJ4IX1Tz7{=v)!=j{$XRF(-TRz0K4yQ@+?;&hF z!!_dc!!ojTOzdwI5x}JGZ{xDi%`TY#tcbX!X;LCN5>0xThJd|O7(4#3vQ{@jsz;5R z6!wwUGNsNs5c^HdtRJ9~_yVe?5p_mz7JGf>>*VN>cjOnqMOjmjqn1-Zd(OgwbJHe| z#+u;sYv!$`+J}O+OZIf$ZXkY$2M^I1M`aneJQTApMwIhJ+fKYEf4%71^Kib+yB+0| zl$yGA2v<8w@8^kLsrJdh^^uxv2!X9UbnPiNR%FXVs5+62Hdh^Gd-W+b<^wrbF+D_=J*4Sk{JRZ2ZX zSbXEiBsy6GSOf?w1rwf$$vxf4MtF7#!BuqLK_)-N3CdkF`JMbWJ$Gj^Ny`stA@NRdloBCBs_=U%!ti*{%jh2z>n>VDJwU`25&K;80oZVO&ts88oIVFBW!KS^+TSu49t{+1;+P{s0GJvt)QaP zp(B7s(sh%SR^ko-tH?$bz?3&Ed(@-cu{I(O5SW)Fz8@jbG{U$iavItfEQBcEV1$nN zXOY>=Ql$?;8b{E?Y{pH9nzwh~J_Qtx3)YBN*)egR`{R~P1(t6I2sr8W$yuVocMxQW z$K!$=vtW3C7AML*b>QeQVHKxIF+DU~xu_+Z0 zusM$I0UE@rC(lxl+2rn3DIXd9`6W+IxZ=~E#S+KASAfKBF+#h$Wa<(BaWzv@(Ygpq zz6hU268dX_9U_IlRNCfD_Q$@qGZIgN>%JF>TfA;rM2(S|4EqRh9@@TUr*G6i4C=)9 z^SVAV7|?sC&cUpzD*1Ha!3~baE`cW=xDm(NIN9&elk|hQ^~a?J109vh8OURbyn`PpEde)AyLhU>h#c~?4?~864~1RRQCv=Anbjpv&wj zwEFmU276#Zbbm5JBMBvvrlVO9jn-yPnLq|0aJ*w> zWELo`Y#eU`r74ox0iq^F4M~DPGbFrUDIp<2dLLrasijAwnsw*2O+Qeow_c7$C1EjI zh->DM^p+yPcI2S*JAt}iSMJkC_H7#l(8TI6&B~LpwBOR>QQ`N>l-R56-@m^|ZC}}y zK}7S!;o7iZh(`bz6xSX5Q)A)f|A=UNNa!+uFSlaq3vY5GzE3ynLN|VT7k(?dt%Ue*REx?Oc8MM)I8g zl$iF_0#d0^nHqwmmx)yqYy)y^&4~A#!1^YFteJ|Qvwn()WW*7+3#RG?AJ=g# z!JA&pT^s#ANq4e|)~Cje-4b#~V9SLc%Q5(KaH-l1A8WS7Z;xF{zlW-4;T-MwkKe0NyvzW~0UA3%i!{Avh(S8o-!<^oqDV%OQ5;>^S;U_ag)sHq^heS%Rk^wqX2g4wv%XY2M)@c_?mz7 zcNg!umO1<_3ii1Vv~%+&d(Wva?%Ycm?es?MnnU@mM_`iF^{MW4p85lnd@NN*&Ve4i z48a~k{v~Y8_~1x$3>wr#qrLQXSfKHc^O|%+iu}LEkheN=a@WtJJkGm{p-W9A!-I^g zIf%iei-1yyzVXX+HxrEF3=uJu+(}pxt2Ms_%#0eZ-$Y4$a89-Ez{J{#B7;qN&rdF^ zzV%&)qk0cJuc_=;-{T6YZpV4|8tvh^|2_P2jpsAYXFp7>t6f)&7WFutj~&@*QBnjU ziW4nC!YA$Y+~0^_`|(RV`Bh}M&!Z~D%@yrV zn9s|)`)MkvV=zo;`LRm-mc)JaOxtdM=k)QhaBQ&EulN7pe6Y{m7a8=!>NT_$QwzqK zSb?8%j=@&Pq3FSJ_CKB@y3y}T%u)trd`=SQ~GN>!Hwa@KkIU^6Qi&AYpKQVq`8!%mAf!}*t-tmJZ?2QgW0jgz0HBP-X;>#~|He0P0 zE|{ggIsIi2Bqo^HYKx<0N|u~2)F3{3!m&88F}r`Qw}e1di@DSsDYjd*LCj{AhQ9n7 zO4xC7>~URi2m9GaCe4>?Cf@qF(q^glkET}l(~=D@G~pS?5*{h?Cv<3hXIZ}7=;aSq zj^2-tcJ(7-YHcVfDcM-&Q3q$_d(k(3gqXZZr^Mmf!)!6HIv1}I-}GVtS_(8m7ESr= zP@53u-qYV!_KMFI^J&A;!R{UacGD&<9i{!(H}nchF-Po7;l<>g!bt zW101mOtew;}}u))+7R8iCfYKG~? zTZ|4Hbv2$HmrDpx)QMDic)YFjz9+wipnD|&uw(93Xb=n_q3}v;MiZcp{ebPV&0I)N zxiLRaxg;(~*?E5O0KC`l8pTWCFXgJLCyO%+(F#RplykcEIs% zM(P{5d+QXj*ahey_t4Xn{^kc?oMIS$$CVs)7l_R&Kwj>2R_&L{hia*MJ3CBs2ilm9 zf88j8xmw~A=s%XnJm1+-a1JRXBomD9MJWa_l8^$4BB-v#_L$79>`ZBl;j3VMl1G>z z_bJJ&;UV>~dlA`aKjs;`>XRC?KVUQC^5tz0H*Z)80-WsWR6UIv;Ef4mw)*2UtX<3g zI`#b#`|6mFj)Y}(FzhnvR{O%QeiV7x8Clk-PZLcK1I|}L@u5z|eV2XVb!c(PwG-g0 z#zXfq8*Yz7KmXDGK+$&w-!Mq>`Rq6%P{v81v|LI-ZMPLp6jMH!5=#|`YeO6AKpwML zcb7jgkuIfU-r4j5CH@rdk9`wcMgck|@*`1uQS^xZc!8SNoL0VNR)YTHJ|1>9-?5Q) zCcIvq2R65iS$(E)nG=|;P3Vzqs!}b1p5R?p`puP9#Jvt2m!qOjjPfs(hVDA+sH}YS zni)`cTYQ!z8Pg7+k9ad$4^$b)nXG=_p&yX%c?(Ag0eI;!#CQ)v4|j=8*x z$#hu40)#>R_Pj}Z_ESuy2Qr@jaJ_OR;9V$s^5jmLxrdv-n`g|aNixV7&*HrA%f4q$ zdv!uYn~b=rVjPh$9U7tgkIqV00S-r|5{pkv3uoEhbRNGng7C_ytDJVOdGExF00g*L z?w>fSg+TnA3h|%w;eql|I!H(me=3J9`LWEL$HZcc!~v+GQMM@U7#$sL%KBCBh1F-3 z`12(Cc_}ql?kF+D^ZkTvhz=pB!C%MIrrz#NN0LaWKbDI5f@CP_1uY6J>?r^C98)gRx+BPsb#A3H;pmQ zCAd%jzr_FR>k>mJQ^{o~u1uYb)GTLp^YT#BQG{PXUX}1`HF55=Yz>jrw-=;D11l$C!K>mP}7t%Y-0z+*LX|3O}OF-eeiS?+@Als4w%cS5hZ zCc^mI|B-h0t4?K~V!>^~Bis&3r=PU?JbJM$rrrj8+p>~1^O7)*DGZZ#i>@a$B?}dK z=zMue>_pW()i(a|Q!DX+4cW4O8vL!l-uy?sgvEZ_(Uy)5esXM`CYmPpq*OLMJpck~ zAi_k(!S{Fk=0)pes1vpeQGKj74~y8=CbRVJX=*a@LrT}u)qN<>Tn#bsY7vGDh0?nv zzO^%B@|Spe)1>RbPg@sEI`0;C5;HE;E^)f;Ph0SWWlIi~46+%Q>;9nvXhcYaBdNNa4r@tZFJeR78 z(p4iWF@sOkY9dDq6+n&(B8G)p?{7BFqt>QX+hc)aaxEbU&PDQQ%9;tD2Ny|M^NDIj zDDx+HIh_zvx9qnbyM+@g2l-aUU}b3R34~l#S7F{jAT0GOi&u;i~p2G~LvqSF8)K_(`q+ca& zdti;^d803(K8KUe?I0J_99}urC*_21XV8-#k91q4sJ^h)2_~jRo)E$3VKsO9{`Adp zl=ofF4@DGbW2Hz8xZQ*vM5T0`fit8ApGIs@TP8rR+ep4wZG8tgGoEiOKXJS*`_*~* z6V{Xu_g-gIx|f;os*^DDVBh@t+jgsCA+DeL6PNz`$d)ek9zNVJhgsgr&?$TUBza_H zB=AWmmcoKNY`72^L%8uqdP8{mpT*_ilpcro0FW=9{-6z2U5+C76k7|u?dSep<$2}Mm26MQ<7uGM!e!wV=e%?!IA(p z(i1o&6_2LRd7b#)77T)w(S`kw1~DJx((IPRcM0ytXMKnY;<{icFk;WJrKr?l6Q=Ci z%+qtwkv3s_EN5Pec&-4zM9_Bblb36(dV^id`^VmEqXqPb(_}?t$H`4Ise1NL@!5DW zBZ1(<{XSg{KGZf{wM!Nj=AO~sQmnm2CGNFB8Bk?Q@eP!Yo?sALT9tbC0VaBT63;mp zbRy5fE$=W{wy%sWwR)5Z)G+|xw{tHi+K-?`{~BcS;NAmy-wgq6O}G&oS&jOjDjrO` znTe8)M3(qVI3z=ZbMuR*R~M{UhXTgxQ|9*-#L;=v#Nqou_jyWQuuqsHakK@Z5{c;{ z>!few!@8LVYX{3u=_~$?;)sB~ikzdfKs8NeCR-m8!#FldiFq!MKjufc)e1+u2ST0F%8}L zR6WD`^bod9x#$$$srgHiXDDSt>k2jhxrPd!hoD-DcnYncS0ONUG|h2S?UThk=p#U=-&g zZEau)eZe2|sjH)-B#s7V7K+qnel?XH|N%i&(CBdD#K;m zVs256L&hk8TuqS?Ax(3OSw>Azo-_cua~GSv6^_!;xEpkj!?eG zvM}|ktE)B}++dU;rPQ=^mBZB&FJDpXzYvV^Fuv$-_y0QLP|}>A+2pUnI)BumlU1EU5KDdw52 zu^7C#V&=X4@e|11unKv-U^*q)Cg*?<+C13Z$l~_Vq!T*8hfe?c{-)#`gSjy-l;D`H ze-IOmS#2siU|C)}#|PIJ8x60~i`Cs$fN9=PKcsI0j_i1MmKsOU2fG}t1s%J6 zCh-KCWG{DfW8-?GH{nOK|Xmu z?@qm@tmNG0?#zj?n_+>yM7pP}q`xf2X<{6z#WZsFB(wHZO1Dm(v8n4b`NBM`ajZTR zhuongs#WX^oa-cSxA{vhkzx~~ieY61%(%M-D}283MV!g~sYX5Y7WNt{cP~FqJNx zi+7dChF<&z6b*MAd;*nl{6V+cY^R-Nq=Gy4q;C?>nyK2*@Z!>=mv+0~m2oF-U0+*| z)ezIEje6;cHj+owXHc}WKC-hPalL;wxA@$2{opWPH``HL@kxhl#2qFj>O5Soa$~%=v z6;3b#q{1q1uG*#oWrxmMS|LiZcYaHE9?~QP2*kPd9)LUoFBYl`3J=k6odbKq;^ls< z;Eun(wj@?ut%VXpW_|SE$IF_9t=8=1f%NHdLZ+hBs|U!`OBSZ@OF<3R{p;5+(fJkF zF$i+uhUKoI`*8Mg4ssq@!##7Fa7+U$^5QY5L=cVx8(OEcZMtpZXI%&|D{=VLsP7@% z8c9Ar`A^BG`7tz7w*2ctG6b9&mQY@~ZDdaN#Mqf3Y}_}f$8kH8v&47kaRbZdH|}ef z=_#POc!=G#nb1kDS*DM(FUJ7pQ)W9A?59yMnc59V-RFjS3_&LG0WHlwiPjCMujzEN zRUL17ZV$X&3V>gJCpG+;z$Y(^y)grj#0P^Mw{cko9TyCF3J{G2xb7V4A81<%P$3ug z3d)vCSVJnuv8nrDegEcdN@%up0n{0r;tX=EimR-?eI%wo8M%=HsQK?8>G=<}6#Bev zcl{S9Bg%a@-Uw^^&U;kCQ_=W$pi=f7QCoW;NtDA%zV3)x zy;v?8kHPxb?CDRKcIKnOKRu^x{un;FAKc5h>`Mq49@;g@Y08u9nx6|?pny&S(_I0X zJ)Ogn4}a{^POH;ix#@_Mr&`^IQ|t?-%cS3l`S;0IT87fd64a|dk{pBi?~#|QFa_&} z@w^YTcR9A7f`#JVzYXwIY+61p=clD6{By9ZwQAFh%GM7U_fQH$Y}azK24ksCt>ReFXKi$xQ-$=9l+Fhd#iBy7!SY zk;@vm#guC&im_*v_1Iw!^?gug%2MV>0N9}c0JK+~nAqeqI^vcCd{i^h;`|{8C98~b zil#Tg=o{tyHb9*nASN^FYec%@j#*>u6I3xdEkAyo>Fw7gnJpY9=L3l!Po8p^r<-<8 z8vAGgFpRE!FvRO?yj+!G)xm|`>C?*izD5oglwSD=9Re~CMvgo5nov;g{tQEQochx)fX)Oo;-{dG-&?TW7NPhwjXGgJ8cg!3HBoW5IhzC{x^9q@*O-v zab)$E&lCls^lfEdSy|qBal1Da1$Y(S6MaiGeZsGhPk-R#euw!+{U3<>J4WwK5S$HT zu6>|`v8(joT?nIFzQmJxkA>0jInNx}D;NTM!t%g4S10B~pyxoj#^D0Q;gGf%5(fdj zB+5u$o?U5h>cJRx4-NWW9_;-6$k5o`UHOSR^uIanAVo{87t}{0b<>^^)O!fT!4KVf z^XFo1`i(S@+a@tG^laJ?CdZ7Lm66o^`<=93NFe!ewZ-~Wf;Q&t97Se5N!%~btE`Jh zvMKwk51fEzgm36XulS&dQ9u(~5)afP5#gp?XQ^DkAHP0ltZyjKjPx3a7IH_99Jz5K z4Z{Jl;SQ=)_d$QNA917=Q#zdaVY39_>9w z#)o2i$;lO91%kN1CldRiQ}GE>m|VD#%yprJ|2`SPzYC&Li>!$| z`HQ!VBE2;A7{YZiCn@YqWty6k{N!^XBHp;d0u`g!1GUoxMDc-*oJ6S>K^eJ_Zik+%rBh(u} zn>ar01DWDDNE9>+Rile;k>@)yj~Je}6bGAf#Rf)+Z_2Vb=2X{ zb^<`5B`Z(+!@_O^Xkq5B|E{@*zfAyd_VmH8zs(bHWZu#e)Dsq)IPpvN?RFQe{C1l4 z8AY!ymXs6aA#}ZRx13#H62sv1(gO~t#Z^D7{*~@Q;Mqhcf<^d=MqCKSDx7M<5|(Wq zNNI}TjszR+9M*pCoDo6;e{(!SY)|Gfapl7j!;B>|@Lu1c<)_EDDcm?bu7l2N8+15|7usi4}y0E$;T@$s^^@s=1286p|Rj#~QboN_^ikau0MV((`S zCR1d_%_oajwSSEC3Rk|jMrtu*sp4h0EqD`U!)WeG27r%=Q7m~6wS*ANd8qcMrH#%9(Cvb`k#;J7A@S!<{^&gkrP72V{m>tE6 zz{eHBY1F8P#MF|YH^YmY#w@{nrR4(k@b=}HedNA$=xbvqY-IXt196R-rUZY$ZXPiqq`#{}W%F}k$Hf;(EfHIp9(~AUjI!ZY7*3?8jx%zoKzl|d+&z+-UjCz3saX&ag zKMPWby(c$4_?-!hBt*$aPZxSbEd|>{739Q%L;Ld{g2ES z<&#NKlh32|XAwhZ8;eP`!PIQKaal4*;l#-k} zQSF|BXY4W-jFx1wF!np$e}t-EcJiP*?>rk_VQ58O^K#i5F;y+y%zBiEZBrSRdK5>ZFHl78y$2 zj8wB>GDXEErdAL0XRE74E=rSg2!4{3A%o7+-R-5T=d|>m<%-VD4evPXIKEbBCAh=^ zdS%`2MY->P#+=Cyiw8ev)|((-X!^nHd_-MO2Ikj`M^NgKH9FCB_vTY8?5ucmxs%_# zw?z@ig`2t=)&fdz2nZ+62P4WVo1BTyMADp)X?sx8Xmw`e+z<|j8*FU%wCtK>hr<*= z(HhnUOD2LiIUNE6tXDP_mt1O|5FBM+d;X_Ob@)sY|HnuCj`&x%=0@L)hXtkdZ8(Q3 zpx1TBw)}G9x{Ns$aMC(zRYznvpi5})v(PO`u=K&c#e{?{Ajk^9Gurw0_s_HHu7y2U zZMqeI*;$jySOHSgC_aFkj*s~6N7R0B!{-n?E{V{SJiaHgQX_~pypY2Se+GmI$H z&tE1O)YgRgzrpTK%(2d8(QbMm!VJBuOT=iyU=bXu{BTybo;QQakSE$6Rd6E%+BAn( zoc;Lt;He_>!4F3$t9wam;=zt7vkEo;bB+L$%%k^|q&X}r{TP$a+!r}huUiqVbu7iP z{Xd4unL4Ag=mu{NW!+pMOrkLdnrx^Fxl_d6MDY^pS`OM3?InN> zSi2APpN}24y zEGBRFb>)0>Yb7@Zvett^L>B;KwPxz{ZZpJN#si@@j-Qs~ZC;(5A$CCMztVc_`6YK zX8=Zd!BjB1ncO<9d*J4JZD`4cz>llS5 z28`O`OX`IxsM9~t0-ZO^q*T-Y4o0&?Jr)Ww@|Nqglg46F>OC>yf7p3^MV$aG;jkj4 zJ@t1W(1+--uE(_4r`2S3m0;p&b?sz`T^`L(Knt25N0!1470>1tb-Gad=ZWzYf=Ed2}i6Q%%^2T$41(N3nOD{V>#!aWJQqv#?5ab@Lvh%UHYZo;=78c9N zuw)549LtY3weKf;1DsHIqig@9<(K z%L`O7i6g*8YwqtO3>u6#BigA6<|Co35i1b&)^6xz+`aKaS)%{Y-D1BNBz>P@EH&w5 zJ(XhpUM5}Kkh8-=_4S*LY+52VDf>O3_o* zTN<*57k}Qgrit^_`L$UNVlN5<@h|&fbmGwVL<<@Mw$JeTN*vM;uKU{9WJuIIfhZy* zDwg&8q@@dx@Qd=|q0{Q$aRdGbO)EABMbI00jP0Bla?jnIWMGe(lAgg3F$_Ns*>o~S zkLo3;*Li7T$gi9&?>NYvRc0ja$wk*$fhI^!kH*~#{E^Fg(Y>C>=l&sKIlnm1!B#%r z@onS3eob8SP+)ZI^&Xl(ViDUe20&fkh$Ff$@$2qM|0v3T|I(SBoUQv;UqB;mvMP2- zT)GwEiv(L1RUUxhjw7B5MC4WBluF$o>!fS90uAQ1UFSk+{$OJqZD?CeA^ z-tDPKw8rBD>=8vSyU6QxK!Qq1d2G}73-Ub$ApRiG=-vUhQTJR+k?~V=(DKOol}I74 zV{2J0AN{_XnvAtk?QbcLU$ObP2X?sfF4VL^5~~CA$RdyU$%Zl4#Ux=o8@ST~@iIB` zFhysMfq_8v$Q%#|sAE2RqLMmz!HDUT{VA+C8rUx)wlHl1EvO18p9$3xXX-OOrWGS* ze?5drC1!Lmhs@?ozh+%kLNyMXxVAdmSo%|FC|hNaNCKJQc>+mLtiXYR1em?#?0xsz zU+A}SBf0`1z2^KouMU}3@;wp(>}V69(5lVij)54^VwUty>x1mTR-n2>seX}pd6pRZ z;`iu^S73&595VaWjpk&4+aN#<@!JwvymkVIln@nbi zh8d9!02%P(Gy0&D3%qr>*lDl+&aXst5T}`C5wVcnpc$Xje1UK!c6U|A9ZuO^iG^u_ z2m7A=rITavpF2rKaregq(#3ghz(CjsYan_2_3zr(*neH{A812DL4DcT)tBhck4G`t z?EFQba0DkWV2=}!(zc|9$Rp?Ip^(Vv@KOl0BRhN%=P2#~xUFq3=9tg2fd?tn6HZ3q z@0yk~Q!P=ovq5Qic7tW_6|=(p0O5$YD_4UNLL&?VdG99O4%jvj8Z>D09CiYf!BdD} zsLv;?-1#ubO-Mf^VHE?=3aOvUyiQ`C_Pt#sdU|pEXFw1?gktWhq$a7RC%-`zUud}r z(~~eQptZ?DIHt}V`1$a?Z1Q_~!u=Vy1$MF5nlUjg%VjJz&v30(4iV=SJ5w)`{h(ZV z%gv~r?-^tjsOpY%gDk1D|0tRm6s+!vLE6vq#u4bqVh#JpW{w{YFi%p<&jP4jPX8@A zBhC@?hzn?*`&xptJn5-mS`~kv3^g%3Vz-~~8uD6Z`nXS>nBP&YRt;YwLvmZo^e(ze z?g->-dY}=#H4CgFIml4G@vABDH$$Uxngr}y85!=waZY0dj0nE}swE3=yaRp+MBCa6 zT1B7#rh)&X1_5>E%0ugBBgiUQIxz>7_feJ^m|c)XMN@5m$wSv#1#g}^O-U5Kcxpxt z4v?WJm4IHlNWsHHj}Po3u5v_ipiNHL4*glrntvz7rjfGGqK zpK)7)a3ps{dv5v%tnjw(!=JPWk~r;+Lt6-pb2$F$N5imW*I?uUF9f2|JjLFCL2(bK zD*`>iuUP&ljr1^Fig!5x=s4zC+0m-HFtuY@1U+X#E}njaEA{X%3yFt~gkpu2Z4^Hb zhEN0qgq^HazOw&lZGhgPi@%i9xl0q9=daF!JKO86XC&IQs zu#g4O4io`REX?W*Ba5cD3x8e*23d@^96a~Vu>WmiN!_;h)xD>I;}2|cjwZHtrMUcX=V z?^uaF%&vH>`U3bO2#7H!M@l1ruU9JPgbP`iBeFH>#$`W(lF9B2i`Lt4iYUKad!{bk zr^!vRL=x%FDtgUZPCXy(Q5ZtG*^KMYi2XE$l28Lg?8yR8X|y)SUmAui zon!q-=-9(xXV)quU?U+H!0q?p3;9_yS(N4z84yCjM}O?KYL}Q1anmEfs@{`9lv%@# z9E=BwT5qGj_$2ZWxrYE4jm91St8!e%c#Uz%+GTg$uPR;nN5Tl-OHd_%tEPL`7D|vv z{+1NbY5TtZoM(JZFDfurD}n38hJ}frL6qt14}Axl#-Ia4-o602jg(86QT_OtCIm5- zr9AM`#(U*ZB49aRs7rnbd6l~VF!n-ROSfMbw#0zrh-dHnZ=HAz>3y9wekO0^OwLjv zCaOp&dyx8yG&+xtnp8ydcGjf$5us0jnVJFdh;NsiEW`eB<;gF_<#2wuB@`?EAqmT{ z9``6ie}VQpd%!Fq#vJK?#WY@G-MZZ(%N-ETdmp&!Z`nln7#4cymKCqvbamb_57Q$l zgdqc=X2dpGtYT}8c?<5E0*8*loJ^mkD~e1GyEAvzNmC?xhzluZJzkk1l)~R(URx{U z!X#p!@kkJYOUIrcZg0t`QWO&gX}#=`%=*5SE07@?J3G4&I_RZiwY%f%xMcq8oh$}=sq5%s@8*AWX`|>%GFr14 z3Bi<vy_1e4Z3kme5-5!O%h03Kla`)_7Rs?o^Sx0I( z78jKMZ{f{Is6ENLf@Sxu#~i~I#l9io=8yUlehEMQ_o4h?@i_Z;*M_shu=VX1dMiEELfT5b3TS^w6Kq zFJ49#SKYJ(V7I%oJ9{lR7c)9A;MJ}Vonjo>9#b28?^s{ry#GKuu{FFSd2pyb;ZK5m z&LuKAYk5_^$pIh75CyFe{YR4`cv~=x38gb56GJnN510J*-%ruyYdtlPE{Y=~C2)(1 zoNPKjsS&VSfO&LbBMr=k*7vfye{N!7^_zGfIqk*?(kvE1y`&3NIbu+ZYK$8;vqwfVkux* zJ0u^XzyXiHCOg~c{6-q$un0z3Vs1JC``ABo5laC&mGGg6!Mmuix1io98s&Zk{sw}+ z1QZzf0AlQ_1$@IOQi3QIlYQNO;oom)j}=c`4sy4S7mH5DwRU5)^^8KsVfYR z;TT_9jkcE7NC^Ns^HObK-+(^!UM+jt8id~i4ba~pn}4n3Qvqb%{fPOS+$Nl9LMRQ$ zw&~D7LT9S8J*gToscta+dS;@7?RC7UjdrCQrfa(cE*NDOpgKFYDRFa*Ywech%&Wic znUA1387jLulH?r_+nUfP2+`kIl=x;*GKP)1XcW1$FI4*`pDbB3gpT}}VEMOB?OZ*b zH@8Z;lFEq_5yOosqr9#4@YKy$3-V4OsB8_Q#~5x zOWQui_g#D;e#5lEj;w40F8w(m%iTT`)(reksVL3o15#N`GzMW!NI)@4p&J~NtQUr( zZ_|CG6nytPErOvYwzmddAJ|O$9FC$XdWhwTCw9}ve-$jG+p2m5^C_~F*IE#{s|e-7 zRtr8eAzyXfaU4kk1UuLLRXVU0VDw|e;y3Zk=lT|hRH%y8s?OozGSefJ(H7}L zkt)(;E0f-yuT5w(+t@Gu*RFxhg8-lPSI_hm^N1tP8gW~OlesWf!K~=J^!yFbh02u1 z?H!S92NM;pZK?A@!JoW7=Urm%;$+h+-%wl^;sASwF=X!nLC!e81SiJtC{a#uZm zFlWZ{pTWy%;5d$H-*+QSWLrx}P90tqy&xT1LCnr#P9Z~FL=8zLi|WrO=8Ab!jy3`m zXQc(mULcXVqtb|Z(iI$lk&tdK!QjGW*3vA^td7%E2R*;*-D8PJ3&!;BElVIGdtt9I z;T(lCIEXbq42a@vju)6RnDI(~Q_i$Vg+-9%;suzI>W;?1Y0#HD@ckZLg)8hi~@2odoS$4diV1m+|ZD zZhLX1d|I|4RWMdADt#I|s`rNO z0w|2OWA?=wHX5JO^PxIM{cr<$OR!!$>i$;tL7nc`nNYDs_Vn3 zdo=>n5kPI%c$G3gi^4rbO-7S0*G5fVcX_++o9eJdc^X$s`w^Oo1xS=1+mP|`OD)z#IMpA7K$|Yyy0rHe`;p1y^Me2%_ecp zh(9T_|GU=Xgb=Mm|MLw0`7SsJ6fMCKt9B>|{a3u?jfVN`M$lMY`)&buRAY=}CSnQ< z7VW=t#SH4f;lly2y(!*7G^)e>O}gh73)5&Fk(Tj?vF&qTe~(YxNf#If_DMdw?urGftryi60=38R5Ve2RU+TWHeIHBf) zA#*7DUq9+5J%}jGT~<`9ZtAA}>J+bQJ2cpog4yXMS( zbvmvP?mVLqiHUAx_3!r*>S2c=VqC@{KnGtMRw0iDV7hertl#mWA7Tj4poSmK@xPYx zudfagprq>ixxYpv%%7YmowpLo_Zi-gv}$414I<6) zx*DuI(-o9riEQ)-H5~MNeJ(bI3uUIW~m@747pY2~zO&oLxLPtYG6aGGH#j<&( zRP4_`dNzNnCt(QRZ5CH1a}UVuP?qyvx)MzfPojNxj)0}08LELRZG5pWCFI;K^@R|m zDw69Jc)*J((1ZrTb3W}zbXaFKx<5qRs5QE$3|8e`K%s9Rxt)w_MGgvwn$wa(|L(6$ z9=eB=_L8@Uf2;VLPa!O8x4R>id38+e6KMW^;H_oK#>N5lRU!Ij7X=J|ia4@Uz zO7N;#;_fAL)j?G%TEv;@kg1jzubbU6 zr`^On%E)HyYYG&K2T4%|IjvK|AwCX@V^SXass>1UVM%~}Jg|FXFEN-Rl3Iu+2@yms zv%HMjp-_H!e%3hKBrtARylm7=IlIM=VeD_m^KStNJNEbzw1bMM{~4q6){~p{t$wxi zBqEZm%&7{6OKAi^diHEPizQ@EVtZboZ=U%&97Fatu^+8oPM+}$a$@wqEU()O($kz; z2*C5@BTwc`MBW7K(~Au*8?-ThX}DT)(axT_dwsx&UvZ1AWPj5mA>KdeO$)> znp4cH$CK2Xzw!PVqun$aIt02>5QkmQ*cz_S@ma{hoMBT^&Nqb4k1#$U~Z z!il~NAJC77_{c@rm-{d}RjyLpWW+XZM*^?y$SAU2-)974XX$`3CrR^{SALKyK!RkG z-04u_1b3RPgmX*?o&EM(j1gDc9KWIxs3 z-d~9p6Wfk+pCQJ*?5k=rqR5yI=s={{!?rhmq)hWP8j{+3Iw=D`_G%o+Ywv4^M6 zHDI=;7MKHQ_g=bDF8q6gFA3Gn2l33es}#~K;-1xERL*z6L<-NeV;6OMY>m6jf&W>n z1nssD2cLG+hPD`mSL4L<6rHF7c>##t;~q6YyrLesb7=4=sVc9V=Ui(dovDlym)bO_ zG)f5K3_I4`*JouFIu|A1b3Cs)hNv8ww5m@A#!wFHU<{xsA2JQo7;g{+!%d12pnMfL zG7<~!a^lw_JhXFyM=|1 z^#MeXO!)5r{lCsNHLB7)7fjx5cd3l&Wj`NE*zQ5wumkLs>=2v&ahO+?L5?b|2 z6mk;m3vaZV!W|Au@J2u-)aI-%r4lY&&LMFZi0?aqamB7(!AqvI{u3YswGGQ0KeWx4 z{%1m^XGi2O*E~*tCaO~w!SG*?{Y^;>We?^JZUJ%mAwrj@+MZiz-cWaYW!#nHNkX(% z+iBOg4b4HDsqmiN`M6%!k}I@R_0@T#S&^pQO}V)Mf!>s^f7?4(I^fXEDIx(Q7*e|j z-a%%Gg|jgt-Lc4RMe$r{sidWT1Hr^q; z^A8G2qN{3qb>N9WW;-wMZ%y>6!_+;ZVtXYsy7+U1=B|ZC)&0Q3HHTx|$Ix=Avlq^= zj&yUe&<1HA9=V4I;)ggArR`CMB%eOr2mH*-pHN>Ir*b7~Z#u}$w~-id)F$d*1zA%Q z{|vu4^gJDoxf1>}Yes-|iuA{#Xkm3Wt9#Ko`JJ>Q#oFFj>|7qDS)&q=^XnD-j0``n zM)xW_w^AUd-7gXeA1@JcR=B?QYJ7gCj1P&SU8lW}I0+dX2pPSPeJwc=DtxeWVPzm& zOgrHc#(E_ARIHjArQ{ef-bXeoZoW>j>x4`=KEFViv7T;hmI-k(LMw){_Qi1+w2;*H zc-LDu)WrU?ALYJH%%BuM2ASD&B!;QoBgX=5-i2AlDxzb!5oqu;UuztoR_F-qVw1O@ z=q7`wMNW>*PPI#I>Io`0R@fp^rLY@d2Af3hA*JhZrt~1P!idIm!2t|L%vwzrr(7dO zhuvzHIWQbTWnWBzG*4g0`t~O}V2lyIW2NI>5!mBrmswX*wpRYD$NnGl%1E=pzU%?( zF9pqhqJ)mTr!%GYgVD+?-iTOmh_JIvNrU-^| z!gGEXq>C0aw|hD)olU0x;$8oiV-0LVX!)Pd|D zOi}r0pBV>pqzKC_A52ua5aDfmIWs~5USsN_^lE@;-x)(bWN9`7cex>M%$0IEC`sDJ zwf}+{AcQxM+Mc;gI}jN5jo|{vtDe3-5S6ra5}Wi? zeh&isvoCb#GC$lBnUMSrnu;9It_`p%U%aa5_?8he z0FSVTA*K}UU;7Pkz(F854@tl6nEuG?$deU>DzHs~Clk4-8IBBiOCHy7u{A!_ex|pl zqOhkfNzMiC?<_r+gwQU0ytVxf`gGj^x$m{a^6zN!(#o_kBZfY?f`&-c4 z7j|z$SQcNlr-^Bp#vMju{>_$93m1Di6z)TJa`jHpz*%(y;12g+I#c>c;N)mW!evpZ z`bv485Q1vc)Q%LXDp^+C$#v=MzN>I@)QPs7?dQey&&q>Kj}zNx^jtXG&oGtOO7odB zHJ*i7pMc+6+S*olnZ&XKc!f&YU1X*)AxuD|79iI;5pmL-G0QYhB7>kA#5UiH=^8QB z3*~9Ra2Lr<<)6?X%e>+-1_N?fns}&D4+Hc`WPj8Tr*y*q(wc?Q?K_0}qqEJOFXL#* zu#Zk$`fu2gnsNguJlCBpU_VKRA*lX$CP5!7_R?sa#_*@n&fV8_hKK)POh4ed@9L+p zSNR=2cqzogZw`>SGbn6^-0Msxq-Wu9F&)SwKeh5RfoX&OGS3f zWe-_YGc$8xf8T@o*!@Z3_`j;EWFvkv7SXLU%5~HCuDqd>N6wf*!Q1_65zovh6 zAa^#L{sGJU>gEY_V-)nXbCV_<&Rb3c#@UqR0*gBC;thSwUGe=k6A@(*;N~4gp*SR- zr|Ms)mF-adXj#ar@_*oN|JYl7qzZ5jUL*7i-&o3eVSM26oNdq;p!?0pfc6nV{{RE_ z;1C@~FSB_D@ve_27F5Y81X3)qRjNq{ODx7{| z2C_9FPzIP2QW2WY$#t!$+P+?4)7eh>TI5qk!)Z)s^h_mp!CP}uz2d@lzvQMs#eN|d za@Bp!5);D=0Xxs-?Xw^JDsa-yne#(lvRYRuanwn7QToUkCU&y33?;|e8O_|`b_a!F zn+hqVPT}efTtlJ#j1&69>OHfHJ!3%h%@o_p^Bm3_XT{DfARHxnBCp2VW8 znHBr;{;Y44W4{EMBx$6)EirPBIpce@iG;pWU&vcSoPZG8{k)Cd)Imz%7n};_7-qf& zcd?>1c#QOIE6c!@A@eAo)wM%t69KA_0EL{j=1nD;w8J8g6K>VqDq;FG?fzoc=<8DuW9T@<1b@Tr z?zVAnk*%FfJ@L?-c?UB2+ON#BliDEYHW;pv|7D8y+tnt`6;B}QUwmS>1q?>jYH@$8 z$Tc>4>3#e5n6$$~SUK=*fWFtBDGa0%Bv2e6O34lHC#_!aJg0DNZKCP8)r%BB5ZKO( z^CRVdgo`rLq5cu8-ayzapxFDn;6B_;#DsP2$Q9+U)OAD-Sx4!eih0?=wZ|RDwGg#4 zuZt3ojA^SWI|wo517oTsS{eO2J@gGXyfDt37j$ZVu_Mtw1B%bsNYR zPu%)%D@et5nD(G%xvr>7iDI4nUlGi}Y)vN9Ky+c!>=!Yb57d`AOsGB_*|}LwOS|ak z)cP8p?yVvDd|L-KmTNCjr#*6f&$l-ov_+nJdwOD{Gv!!1H=ggL*}He?hZ)NBc~pdsJB)=m*{wNgm`vfUJ(gP4amD@%<|k1XJhyY z8N4AR#JK3~>({>hA`S6t$MpO?z7bQ6jByOuSqC1)Xl>y9$@sL-3}b@8TZZT|7YHr? zcuUKjQ1)Q+kiBUDPOU|_A=lfTy16@)MtC^h?!gDjVF{^<1aL#rb1Acv87c>56;k{c z#P*js*m)!+2@|ixBvVSMR!0?pbK|C*?66O481VuBe3ik$L8q8*fy20uW9`eH+5bnZ z|HECHW;L@p#nVcJ%5PWquaf^ZYq{t3*4dh1U*FBhX03W2`4RP=vJRqstJif1nBPOA zvxQx{O6}OO(a_@ zJ$DJA6a64oOHN!FUrwdCjXZksnF!d>=*gj6=D5&2&;IM(1CNA`7%u%rHQ^9t7YkbV z{mjpqYF|HQDxYY)zV$Qr>O7j^#cP38ox4f_O2{{%^H>*ybJ{|;I(yyrh-5q8sUI00 z9-iOX_2vRzA*;k}#D7L0*+@6){NB6tWzjzoJ$GdWqi1nWra%elr3g6SZUoFy=UWgT zALcgl=N!+0X36V{@V3ZYYmqoP&@H5a#OXFj#cF4!eAl^T3$34A((XsQ+x!9pc@e^_ zbeCaB@@W?!vd%o!^AfI$ERi`F)_TfX5wGZAIzkmO}uRKFdo6?-2rb*$C z+Z|s`NuEgS&K9#WH0(b(k{B{MgYJjqE=2_ek@l?kh2MJC&}RSJ8`+`lCRn7{^s1Qu z9y&z_K72a$^k>9&Cao~^ zst6wX4GYuq-6j%TjNfU?e1vKClI$HO@VJPKi5F$OX-sQphMs6FnohzD915RQ$Xr5b zvp!7ics@F!1K77^+0#=+71w^d^w6Z_8p_x`4D9W zpSz;v`4z^5qEZyS%-Fi8^IKpw{wZWsH9USd+*oU2=Cd+KZM-^?kNqHUau?~!jNuQ5 z$<$LrZJX-pme|f5iJ@Yll64yCYCKFsE}YESU)0#e%pVaCa8n(J0(ZnIaq}E`$eACl z4=J#8c$uQsI9Ba1Y^H^VyR9U<2BWgoduO+nntbtu1r1JUZ$Qg7Df->~D$O(Ck!<3qu-+sbwi-8?ZC z6B|zy-IZsgG$dxgI1??xIQJrC&D3>#JmN~taNSJJy5S}nIh?qUFaYz9NS7IqmdTqp zZ&(*AHCYG=3Wh`Q(6WQ}?Qh0Vzn+zg8O{)+T=P!+vf!r^bBCVsJt(#ct!nCATmk|W z&lxPzZUufL8{U>d)-g?+y5~%=bIKHqmN=fWALQ3;5f&G(rD^8R?0GKtJr`m}dr;;Y zi>l+b>z$f#Wf4axfNu#OBp)T^A;B~NMb=P`J;_>Cp0cnoK6|vzEpmc*AEFK~&ZsK` zlIlDv1S>RquysoW*|g8!bpq>So|%vLBW^N0q7!qKD6ePQU1tu!EukliUI<#~Yew!E z09=d7bRCYd2@mhxJ9V))UjNRuAmK~DGWEIj{M#ST;LT7<{i{J``OIzpuA#v}S?b#r z%Xgd~FgGwkJ{l#xuVwV;k|!-^IPYfE5Px={>e-otPv*ZZ6jjg5##|rb?_A-QncK@b zJARemx`yX^5AdX!t`ae<7#FJ>yLfiss?n;4HU2@!pTh;pLT_KH z1ez)rB~J>9)LkIg4)The>nD!SMcx*!5cg5ExyDy}>O_b2-*Px0_}@_N5L$A(Tsehg z{*eiBZKVwrXdp}rPmefl1({w9^a}N^*RHNtIePRoc-ENck>JM3MrcN;-uy<20Nj7} z};F# zL#0bp!c%?4LS+xY_@zmbP_v46ljO!^tu zv3AJX^IwEs=4*?wd=-hoejER>e#|yh70b-Y$RBx;5v2QRV=s8h<5?Re}y17>1sg72|GPh-+Wh?=`FO?Ka;0_e#M-H z0NeccQFC*t0@otiM;zwCU`QhFNknF(&W{#Rj;pQ}Srj*$p#jBiEAG(LY&mNT45L@g z+1LwIi4P%%;K%8dzMQ``X4G57^2cgHy-cKF^yyep? zZasJmIQ>2?CYznjeOLNkr}#ICWnL$h#-mLRp09Q|TL?;#*x_D|3X$m+Pxfy)(Xkh9 zEU$Wr5j%SA+JZttjT!9bl&zhZ^w#Iu0+jhKCPuu2nKb){?2s=Pn%x&P)LW`rK$D(1 zg}JXxohh&4h5(G$X`htXvgQ4v1oW(}nw-b3)GM!4T1MaTW(k~fhy4?E+`vtEu=$=| z4C=8pRQC4v&(Xvtkr{XT_3qCJT`LyW|7J`1SG2!IL>PBpB&^u-b6+;AgoKC7E?&Ju z@8T_XzHO8I=SdkX%&>#EK@vF^xoY7}7!jdS+nQU#YDwwp_0h7rj{aLtq3w6jg<6Ss zM6FJ3SFh`2eN(taQ;w?W?XFMd(9$cRk9TXOhsW6YV53Ura~c{NHcVc<2NKp#NvuWTC2@DA1n9497k zRQy^8Rt6*0Ebzb`rgMNXVtUy6uVlTVSu8Of3%uJ0#OT#I`sFB6GOy_;djuGdd0`f- zld1vuDt<&jmVGEYO|D+N{Sk|*D)bk+d}tj!_H#s7&-9!D8KX68s5G`vJ3oaP>HG~I zNISZ}y}&tDCsf{W@{ir2BLYWoFuJPkaIVN$*R{2qe#`^@RbBt>T>Q{bj&2nCQx4$1 znXP=l&4aEmRYg&JADppPweFOMJ}vY}9(~Iw5Qsv~nSllGi;IVAu4vF=d~(h73(T^& z#}V0p@x2-&#Y8_8P#xJn;(WZlTd@2FV^Xq3la6`z z$j2Ct#q~0Iyyci&RdIvAP}Ermq#=%tcqJtS?N^7rKv*{pHh{=l?UHH7~-> zDy{JcSJoS*M6RBHO`FTl|@(y&W;>cuAC*%{wV+hX=k%X!j+=(#=$l%mEnG+tq zL1;eXBm{n6ss%YjJ>3`*(+tcYOJd5ZHSBu^l2cQn2!O!+aq zJMQ(HH?`^F6GXiCxAgC?^J3`>MDA*@a^%msH5EM19LLN_CBh~R(k>m}zW!Gi{nj&A zQ{7!{p4)tJAyG4MOeUOtrtNwJb)L!+CnztgbAsWuVF2;grfsnb#6OU7BNlSREuihh zjS8r}`GfQl2+6-BGRcaJ*y(inz|bd56Cp3P>Hqmv7E++0=wE-gdL3cERNOgQ8~KtzemhTl$dinB zhq(K}MXAIGKXgwO(!8|-SL@< z!#wPD=s**%QNx(T#KfbR0WdU;iJ{y`J#NmYYFptk=TVO)Ym@0|v}^Amo?mUbwsI+S zbNi(G4GEh0{@pv^B+H`YZ`l9ad71mW%f|sjU32gJS%@)5%gu|st*)%hHId-4Gg(dt z7+b6r-PyUsW0m{Cg{ivdEB2ASbj_n?22&QB^=Jz?8uxS+9DG7 zsgI#8^I{{KFn8hI?9q5ZMj!-Pi#>)|D^N0KKY#vQJcdmO64%?yr|u75myV!9t((zG zONjY*kO`}2NG>Fw@Fm?cR@QUeiF$vW_{pRHeRo~ki{o-6tylk!GP-o*yaNz@ygzX!ur)bLQnx?t%i`S0 zlY6lBrD=f}7EeCn@Ji!5Ei?Z=P6PJNE<$a4a!B`YF^oL%$@R>LPY`b&CpL8&)m1U+ zRDGxhZDo&1&7$OQb)6k^Ejf0+2ZRqY4ZSF2&!zmf#3hC9a|SEmf4!h*OwHs|E_V*Z z@)s&picvkJ0$}kxD^0dPX#j?+k4aWM&O2u_OIeovLf*>i`T36Wm;E*;=H|x#`w@1< z=bhwvWA)qTU9yq6uVs`7so>@2tGYP8>Mu*zx%4X>d0U-_7aNP2UV+!(8X-;W#uTUYq!{N_nAytIV+!J0t=( zcl+r~eS4a-OAa1Bd>>KQVc6y+E!#URn&IKu^FTpLS$9B;jB!$`3=0=#Z+gO3N;2Mt zC;w^5g;YwL^bYTZbN(}$x<6Y=S74c`){iigvW$&Q-6-PZ05tx(@az5dY;f3aJNr9V zRL3Qscd{{JHy8G5ylm|3#c~XKxlX;3e*qHaQZ}|TIkS!ZF5D#lsEjI`%0CtYmIfj2 zdR5p!sfYfK&-OI}ulD}oZpmDOF;SE&0<8tAsAv#W=&rU1&j079`r9VIik!~w-R;xt zzrFP!s+MKu7-8ZA1#}VW=n}3Qo}S@JNmZsk8@aiQsF`+iAtauB-B${<@%?(Q-Jdyf zV>KpG(r<+x`+ALiU~!(!OoppSLw`(`Yn^e_dqxZn6>NOAjVgtH5yt5d+M?GCK)nq_ zV`H}JJZhcNCFT0jIL_~&ad%dX0S_kB&cA}(2EPZ9U$MLg$&k6vhUwq7)Man!w9EBP zs83g7@~%-{W3`-|Tvkk~9ho^>8rU6womC$VuOEtz-m@28XIEPT|>cWqhoD~bED0GBUG+gz#%IXQfR=NWI)GQd+;WVl7jy*#1R^h{r(o}@VT^%kk!XJUeKJrQ zbT~baXzzNgK`^IdPogDkb(`Mn_B8V zQae%rse`~vTfUo#w}Ni}=f^KZh1$NB7)|cj6LL&8jXH^Cbc3}tm!3Naj{ywm`&aTa zvUlX7_fD6lq(;*6b=o02U-iP|z#D?=cVJQNUZMTimcpc>qGA9|(Fdsh4z`c3m_>N! z!Wf3_QeYXz|Iwfz)_D5jl%fSJ?$hUhB!5y^e1~KIrK73l+HlwUe&w;-Cy|ptCUn+M zBIFXm=gA$XJg}owx7_jZ;YOBw_u|Ei3}UhU?G7&B$bX4h&0hbXsn7r1P&<_LfVgjJ z(8&RZyvY8(!G0{3TQF5Mt9kBF=`K>4g|aGZ#{uh%^+WyHY6VntQas?D#x^Obru7G7 z*|dziA@2Yf%lmv2OP-PX)8lhqo+pG*r)pV7nqef4RpFK>n)3CrT+EO1xPzV6k;AUe z4b^nKJuj%1(!&g39Vrc;GA29hO+i7x!f(Uo8~&f8v6mO!(kjef{~2+Qxl0=wMq+la z{nlpfqIla<;Z9W$)nyu1qADx6S^WWk7d~ILXH-8?O2ps-&;c z0!aJHDp$^>4dWe|EQ1V!Yv!wmY<<-`J3-0)3bh7n-0?mW)T7dNwQ|t}OT$qSb*ebK zx)z|~Hewvvd4yN%aT@xX>X;Lv_vK-JLM)&@znwNQD}77rRXazKgL=cI;!2a-%DZ1^ z)e>}g0Sm@ZcAqKsU2E5H?&_EJG8*XeRHUhU5drS!=jSsR4`<_o)P_~~0?z-q?~psF z!dNL=F1?m?7=I)|>_p*yV}5603MvOEf>ew|4-zy%nuhL}YML`(sL*OJ5iT{+ck#0E zUA^DFeG|kuxpX)-ua_#5ToV-!t=7MF-sG3|cQ*>y{@KANRAZi4DpNGO`L7gM1C6~vf7x*%^?nP6~0 z>6uL`?}Vfv`7VN);B>cJ1oN{a&F}86zvu7YRsDrD8@wbZqHk%2@&JlccSiwSvCE}X z;6}p3hYvR)gI`E7-p==5QQCbo+`Bkvccp7Y9go>K5o1Gh_Qy;S_h{zh$tK?FAxEj@ zHO%JRLuF&7H^1s7WwVi`CUtM!c}<4}jB(exCj4fmk}4I2R2##R6(DJ)=}aUwA%k!GmR%VnM??Cx#)aBY z7R$5L9WUr0+Mxzb6YP)My>JHC){6djvCY*?B!I3F$A3)K!2M6B?+zXNK@9&cpiACs ziCFOJLe-qj7G0clbbc@TEHAccB)!ugU^gl&DuO|}v&2WY8hCDQ%{VKZ+8*SnnDf1D zl?*e|aH>yrq=+kcLHwhLb&60K0B<2zGnP&A*9y1J+-_=FvVD*9>gCIpUAQ?6Ag=A= z4Z0e;MN8&o(jdXw*FT{;x_5VPCR$YY?%r*2NqBDRIQ+Bh{CU`a1~F_NF6=VuBl>H8 zE*n=d4Y>VnBB5ZDAA|xV|7`doG8iIy=e*1x7Y;0Rl>ziL2VEw3X>2d{3JJIGpm*2^ zvQSLMdymeC#J0vB8G1>Fa7`b>1=CjBxaPjEU`XynC1+Q>OkZEWQT0XgXICWWk9OO% zEsvxk(Ge{@$D8J;RRz)F{WA+wrduuHa7@(VQ;&kEXo<*r%tHcz^At9ab>qb{bpL;6- zwEyaF8czVs&@S#(k(yJ4gh1M6E46DaC*c7Zj-zvOr-`Ena3a16=3LRZuL<+)%rr`J z5BuK1STNt8Ngscj*#3 z(FUT-C-V(t`|ms^z(@H2*A1v88T~l#mT@oXwq!zeD?O&e=rEX{KsEqO=p2_;>L0V13`P?jjp!gZHbn|H% zkZDn45Q1;p`2SOk}f6(l-`P%4IftO>r3?oFUoNBP$&>r$7{jt< z%ih6%g4`9Ty{yp;M$2=|H%ln#=__q=2}75F=K?p^zaI(u8wTpjQlH6rv+d-HjVJBw|uc)243zZVRY%;NQ1}cqegAmv zt_EYB+@YBxTi(~Ux0EO7O4$R@ke#iLbRWURcVSzYcl}6gc=+q7RcvhBOcKL)rT}qx zF{os2B4A_@x-y0tJgdwp<(X=hb|#et#keb47q8j0aiiapAnQ_b5_+N(1MIK(xqZt1 zjONj|72Y`yBO)UUK~`@?LzpAC5F*voE74%cV1L6N>6E zw9a94J%zIqF-Egc<_06NBQzCJG1r;y11yw4SM+oqew0p zL~pGKMYlvsKSN5UOAS;v-yt4bIj|zkeqXkcG>@+-k$hQFM8QGmg!(efI4R#1ojAWR zo(4$Sql%uLe6?D_Vw3tb6)xbVj4AD3zxuvJgnmU+2LgHjxo=@Q8=e&0!_{e}yUi~s zh>r~P>S*LczRx^Eg*y8IxJ;P~V)~OOrp$1ejxz=QH}{514}%T@ul~}!Gq+HY_7li% z_9dZU&))O(UD5JFe;iZ=;dyZvXYv>F`^I#lJ!a^Dm0PY%WBcep8#- zS|g?;*AnDyc!JS=j-#O~S;fK0$q%o*u&Hleu1}M6mp@xx1L&Kyu+4fIQc(`oePb;K z3d6h8)odc@sTT#&w@`$l_39O^`yKiY?Il_XCnlUKcd2xApEWRpxAgO~wSr@(CTh$u zrP?6&nLk_pG@-?o zk;4=-kCHSd(N3kes~h;k>PmWb8o;N>1JkuYZuDgOTk79HUb&5^QmL!PPG{c;o()}E_@Mq7ICE<0cQli~Ym4u$&wNbqRI@uf2$n`sh za?$Ci5Hx7}kI{)(IXxWx#h=pUfA%FqWr$k6uUV^hC4@y+Je@1PG3z~~lf9V-D3CAM zdDIUYD0SHB5OO$c+}Sk;TSp06j4Qafp_|d4FF7D+`5l>0b+q?}8iilP$3jEBQxZY0 z6}CEz(MoEA%bzi%>e{z@TVbr!F8}UZVxR6nDHkA~k>88W>7!|pU0pF`XjRR<{q#F# zGNw2E&ffl=ON<;_z10ELeuKSRAyDQuMq*E4A-acwa21apJ$kX{O7+kC>9=GF1x7i$ z;cRxN-7@)_T9pkAeLd4fJ%45-Tnsd$5L1ALJ?#HP&Epp0G}XLF3}v~y&az;Qov&OT znkmh#7&k!0kZO8-9G5GhILkR*l{#1`K1Q?e&h&TLEj1JTLXn^k7D|jYtVguoqwM_r zd6XN9Npxqdig;6Z_;=w2+N$T=M&gxixejIPaJsZip7}gyg=z}F8NnekFFJD7S5VX` zfdWKfjJcTo)SVtSXq8FN%T7Cu;yaX0&{PDRwxmBCPl^0Y%>NhqT1SSkf9)08|I2{w z0$oRMyU4h5P9Uz~zOAqC%Ze~_YLqtp$+6!X7W#Wl#QN5acq4Aa1q^TL8Hz!2hQe$($IN1(xp8 zuX@3i@`eG~;ldMkhn%AJq-;LzIugC??2LRLbl@umPF?18{_x(F_Gy0apAEoW{>Eei zI&A%f4ydPT_b=X#8NCO}0^X};=K&HdUc;NjxKdCS?0?Q-uEm^^+lY6P-Rkli_m8Tm zTZO^{4dpBXDTizW^BO1 z)O^Ry%{{3l7rWCtZd=$w3jB*mz7^bU?EM61m!4FMw6otzF1(T(}MPRZyr90IJgMrNdI{fbQ7 z+p5D%&N+1;(Phu_Ar}RRK+JC za0LD0uhv=OxHn)^i(5x>#|p(&MBr8MXBvgJdL zvtw{~=Q%Hq*~>AV0tpikT)}0M}O(gid@ygrR#B zc~``4&`e#*R9^Mg*>xF|9g5q(W?H9=at98EU+_t~kp4th@T z^YPgRhZ%dTIZITJQQIVJtBOnzXr(@9TOv~sI?qg3!7I4Xl_SKOPjjSJWPyZ*RbW)N zsY-O|6PqlD_#=LSIXT`<{X2D?<;R_RR!i}LZsaZ4{oV8So;8Hwq?(b%7vja5&2reF zK6R&dbn>}79A)_hPZyVz7I_4J~+hl1-Auv zcbIk}Vc+TybZqq0Jw37Ex2r6C+lMhzp`_t_@Rd+n{iyx}-fMvp)ZTEM zvt7;BVRcBt-JDNMT5RuV1XBt>(pM?!77VY*S0^Rh6G@JkD;!p{ zc&gnE3~K6VFPe~yNnl}Z^oxByMk8Tf^`$^LNw4%4&#v6q4r}|&w#V&8-r2#LwVmRR zgH}zLI824KA9`%!U8{QD{AsX$hvZQ8Q%RpxQx2S-_5%(*-LakR^LCCY3%m9_Exk3e zLrFKlDOowViPj{F?OEp;mmGhWzKGzK%j8Ldm3*>y`Bsnr_yseMR;izka%C&m7t>Xc zYG1bN!BqAa8;Y)(Dhy-6;PeWBeI9&(?LP3bZaJRt~in z^66C%Et0rRx3ALru!PcJH5G5((Tes#+miJ-r;`~oaW(3dxjtR?Hqja(?QdtC_!0^N zCdRt(xIMy3p|y1QSE(x=NpIFb2d||40k(X*ox2O41!Xr?a%GQ~p_`M)bg^O?28&Qh zh>f;Sm3EQ$v*f0BNIFmE+di+r>hyEl$(J0_+W7xnZ#ixTN~Omt8-AP;&yC&O&t}wD zxY)Y)6=$ZjkSS|xd=I;0i0#X-@jWXXqlHW#@6N?qriEtd;@9mePWC!j`t-ZC`C0F= zp>}I~P*}a5VOglBwIs_6cD9TPS^;-*UZI+$vzcibU8-j0)d}gx8LyaDZ?2i$%{a_; zgZfI|*cGV-4EV9JI3oq_tMxn?+quf!QnV*#oUSRRHS+b&jP5<%E#5ff_p(Z5(x*Ds5sPjenCP>d&H}lw=fVkLXM*Ehe$I(r zcsj_K_=n$3SewhIHKtq*&kU26l4TlZ8n-RU+u9J{Zas1JSazC1fNGky7w5!Szpiog zP0P%Ypmh!Ay?fId>)<_{ys*XAlr6vaBj4rvIBoJ8z*QVScpu+k{QGyXV2d|}m{IIS z@VAG^&p$4Hy2LzHl*z{M7Jhiw&mW#S{c&r?1@ZE-R%(gGkeciVC=|jJ=1E!D>Q2=% z+9j?Gtw0tvEq=x11B_VXJ7%70`=qb17Y$b_5BlMJH@z6IdXa_r{yp-o>#qxY9SW|m zGEduMBGSe6#7Dw{qH;iPp;ysMAAS)#$#N$5eBOrm$Mn--hG|#pMeeB2@X@osn*=u0 zFj=S?aXb*s9#a>N#VxjRd@4Cz*?}k(WwaYzcg}+UFg{YVu|Y?GrNve$0H~~gyPsO( zd5MH6hdZjz%b^l8>f<6t7@(3aZ?Rp-j}OJPZYy5W1IEzFTJIuo>5= z#jc<|>fCUfLe+Z-&o%eqzePRQ-Dm5r#)+TChS9k9zb{;UYVm$7g~#vT*%~8hUXZ?j zJKOy6`nIy-hhrM6{;GClC#qYX& z0y?vOu`L~q^Rdp7`Mt}H@S!;mkx#DGVmqy+GCQC(BcVdsike^ZkeGQxjg}Le(a1U1 zpzfJ%GFXZ0f4*;@sVOJxisJ}qc+u9~Hh6wVvY-EUEO=bh@#@U*U;TbysHJja!M5}h z!IqHH*&BEQ3zY1*;mpURkgK0m>(yUmY|lf8#TkuVYR=tY-hJjiKA||CtPE$twtdaq z+C-60{o~}N+F}~S+|k_V8#CrUKdE=8kp<*&9amrG_*Y-;U?1ou*ZaucH7;~jrNL6o zobcwe?Wt+8c0tBBmw7^p*6MdA=$oU@Bb$%4AkT9%#s~0=upFJc*l9I$?)30;-bFu( zW!?IQzBmKBG;OJ~)>kaUwluhaedpg*HzSPj!?VPEEUAK`;=HDMq4+QrS7sfM!+nP!>Uv0;fubxq>RB^`H` zN7Feg)CRAjC_2!;n^Ub&SGiR~=2fply?Pu+Tu~-_%V=IOgL@qb!lsas;sG*$7X zEdAU*Ea%XIDS$(ldm4`MXHiPN!v@^bE)jYCvd=rE9GW&hKNGQD_)ow?k z7}dhze8{S*^bhEof$IDm5dGu=-cz?HhsVp*V>|NQq^av{6b@1R+jHE@U9z{ zIWn!Be72J5^N7qI-Clr*q5M>jjWik~fg4L^eiYDDt*BzM8>W5woMlwmS&#WybVu7fx0?(?>_XlwXY}t!rwlzEe`GI|ue&52kiZa){RX0{i zy?Zzt7O6c%_g0aqRCv54)_8kvsMPBDyRJ(2o-g)ZbG*wvaQ+#YYTWWneInznv7Mau zg|m+f;_Yelqt?nYp80NK5Fm}tNZphAyi!WE zgHzr~#M!KZ;;Ss;tozO8jwti`oydep*EfxGwUMKffPbF4Z1pq zqp0>&GgyoqXORSj?zN(>?$*h$NVT`ywr*v3Q(j^!YhddT6xP1WARs5GyE`KxvP{W2 z$Rp;v{uvvWsQ$1Cmo7YB-iX(DP8}GXU(rJobma;JA*iVmE~aVp->R}td%jNT=pA#A z)IIF#u;+GyQ{(Q%HoG71Jn&&Gw6L^dII-)wwdyJgL~+bQB#pIc>09^i>>i0?n7hTH3vqpkvf)@YPf=BPDbP&M`q zyqUafUg&6b#2Ozg?Ap6D?wMw7%?S0`HLjce%{2>}V>=}&Qce#ncD5Ies&DqPr%tYX zCTHNzG_v>&=VE{+*6Guu^$IraU_Ztmm2w?Tm*m%V>=hZx8i!S6Nw-UMP!#G7YnQ09 zCC>4eLy=TH^|I#4EG+FGzN8noe_71(=s@iKiHzuZeagwwy~x%o$C?NCNbYKDad1uO zd8Ej`hjv#6Ro~_t+;1h$2SME=Vl%?b$-7a#C;`()}*~mTyAq&|HVY4 zY~Q;ib6-5a@nC2d&n{OO z*6uS`BR`;9Auh-DR;{~3AT>vQ!sO@Qd9KlCYQwK7YwcZ;I!Y4H;G%jF+qp~|zen;| zyIp+x0u#1kB)w@1^wnpmlw!XfcjmJwNK0mN?b*6BH?}8@x5~A0prEv?VTUh%k5xi( ze5kd4_Q3vJCy`kE1$(NLEo>C^%#oUX+UBWheOX8V}`nAE5T(tE*?}$o5UE9W+*Li;3_0kfXBbVmW zja;%|oP=4mU^!o`b2bD&H4^hF`(PpGjCo_#lA`n7+*oJ`OG0DK{(6wMugdYuj-DxH zAE>4nPE%_buX|pqx-YCb1r4!;;ot6H~X*g+x4Fa=y`C}ylzjg zj(AZOu(ayhhjbyczadTex?JU!lTbQrBWQlr%>-^>MLYsFPE8x13SMW)ba@bV<88nj zP+K-aY~WxJdwF;aY8olfR8C_Y^V;NaYno7yad%cH>K{;fqx&imGP@(?D!N%05}#yA z0P?d3QSVZp*J9>t`{%`Nk5;vP+IRHGN150%6NA#izAV;T9>ptv2l%2{xki^IX9iuL zbAeJ$4=nf%;guGlrvW{s#pI8i}_C_A3sZT~o_r+~^;m4t3KW9zpXoIn=!#4%M5YbEr6I zc-8?VhkVWlh%>OP0rC4F&mU4!@muEeCr1HhlYxMtfj7SYa^(8$Nr5_(#=?SM!YsVA1&deTS+mRbLJ5JpLB(YI zv$3$u9hMS>tm;}VW9O5ozJZ(S#5W6}O+a%*%2%P;b@YK(#~X9`E_@9;cXYhl>P6`S zPA4v~;dVS3kx715nNO%f*6R29R+;Ax7V@;Be@)N2etI3+t`1Xn7?dY83*(c6NR_8k z%D)tX6IZ@1!Mh2-tLtPo-@k#LxDDL`& z``%FhnTVuj-xKD9wN`JIdWHJ_%1d}6sp;YSyFtq{G}nmuXrsP_F~u~GjCUJlc#!?# z%IMRzHWGZp)t;W7r_l}>1PeCc4R+rqsQXjw^oBj8m(hbKPy{(4FHdUsniPLA3-dn1 z|F-G_Olg50!S1a;VM=#8wjEC6&%oQQHeC)`^}W}xU(*Gzc|}NJTiM2kE0tP9Z}15& z{CMr~-5NuQa6>DW>xT~A_uW|%ku;FDti9*{y+_VRoz5mas`+;5geWhsLeT&5b>;C? zZe6%el;I{*G@>L_NRgRSQkoD^gp|ru5<u`GP*$sh*q< zy(iEhf(c8@8vEqwT!1bgGS?$e&SIC559`${SC$9~<+~m*Gkb+>afz_-Mj}&+YSpS& zEej<U4H6mR`B{Z0awLV zLUI}hgF{*2459w@3x`i#b%#M22wtw<91IVv0pZwPY&W8Gv6>OkC10VB{;!+Rm^%T6 z6_9Aeya|E+?TgrTDL(^ct!rdU6oz-albWJ}0rzv|?adEd_>SV$Hyxs)`-O4^a3>IW zbO#I>Ud^X(#XsC2{_i{Ur-=MA}W`;=WzU49rtRx7R605OhP7OvVWS%y6wWrVP= z03n9W;B%sG-m<08e@vejMY5sK5+0JY7Sxgk>MdqVG~c%wBw`$UT)RBCub6MW=b^pD z>{rQh43Rn}WSDDF8pK>TbPpzP3%feco#;??V+xaoLi_!%>-W85I;|ca9!|wYwiuu^ za|zE^o_{|z9SUzE8isYsW5mzD9XRzZE81x0o|(0K%Ho&pU~0z7(=ft&``Gl%neP&IYIciL@$GMW!qd}t0k2$+a#Np&&~``5;cubvQ1DkQjOt7M$nfAR z5Z|Ae`Ceo|(J38-LDH?lw;Hw9%Wd_!Dl7+!xH;}_6o7$(@w5zzY`$PoaN4Auy=MIT zv;Xxx-@uQ1GwpZZ)34PMFsD6{^DI4D(|4_xYj;BQlKg!2A3u+l-qVi^exH$JSamaE zNkPGmhaE4V9Xh=K{<_RI6!vb##y&sv6ogv3H*7!Cj2?VN2Jze>+vBKcE4qUuyc(oL z8Ew!2&QmQc;xe?hEKhCiOMDlhIs^T-&nB6%IQIO9(AaJ*xYUT0m;PR_l4T7?(raG| zOUI=uO5OH0bUUb1-H$$x4Rd#F#07KRDly|(H#9eXQI3oWLkA-<(VvS>D|O|eZ>l~s zv0Mh2<)wG*l*tyR^|2?EH9;u)ZUt2BmH>bec6wZ_qU7M4D}x+&19czAipT$ z9Kl2{(EdL&X@ky(wU1!-?>lGg1-FZ7Dc6iV>hCD+^m{lvko%h7%NeiOo}ZRkvqjH3 zLSI}`e8an~a;jH8o=kGzoUWwEcL}pkFQeV-#v^mx-RP4DQt`-vmd+~0=`Tds@2(Z_ zwQ)hghdC8vKMF1i_&suHC*&1>qT6ShN^Sy>FRBEnyiBrtOvdwTpYzdCQR*lpnKOm$t!G#d`tN*fnoS9o3whu^yB?IVZUXJ}0lLep!=46JSK ze&_>#c>G+Joylctb{Wk$AhOd8zQG>^$J4_Ba|I^a$)8Jm8L}iwrM+_+e-9oUd)~)d z2##GW;?$o72-#+ZSG;bym!NrBh0UC=`!D9S8QaXa%+ORGh;l{aceKP#-Q9O85+krI z8l18>Y+RrnqX-6ZGB|*$TC?%68oBPnpFl9^Ho>fnv>{xq8dbAjgZIFK?ync<79lep z5R$N$9xkD~`#&FZY=KKae^xT+Q~W`=fG=76yq+IXlOlYXM=H=^llg^oW;ct zTiuq0v+ZJ@{5oJbMARea3oZQZP0Gh)ION=i(hH`5l@x_aak-30D$3m3h1kv0-QIto zG|PRcw@x_1-y*g!P>AvHMm+Q5a0N1D^5O!y(rz7;;?AExFIle{uyQR5_B{5Z_9v*a z%>9_M`|8zIQJv^9$%x{FRTYW6RB%fT(J0sS$N{}Suh5h@U&HSrBW)S)^A|5JBgX#` zdxZ=cg-xtJ89#Qj!sOHv^6OxLxSh z;sIxp3RpA3v_|xbnf$dFo5d6npG_wM#%th(d^f z=!*PtYg^|kGJCDVU03MmA%;o!gyw~d@yA#Ch0U-)AiVr2M9e=)a?Rv~5O?h_>Nz_z zW#mjXE6bMs^(9>2bq=OxeapAj&ylX)Dsl7Z$t({?nN112X0Pngl(J2wvNE@a2!RpO zBbi@weMGhL{F(hd$BcHnx@Iv~Kd>l!X2huESDl*DiSS;F4D~2GK)Q7m?fKD_U;L&J za-4e?H7u_&Mvo>&-1|Y0_{GHs@u%7!7T&(Sf(*FzFGu&(;#rE{sJrH@Vq%Ebrb_e| zTehRl$rn`KXEZZCQ~Y`SOUZj;|GIsDzbkwHHq4Lk`7KSJH>pY}j9Nfgs@4As5yv%ZrL+{%Y zcc*C}pJ|x??0@blz%^!VSxm^ zZ&zjj^SBjLrI^}kGk0P?+oj9PG!zOKid>vN;|oYJ<-+Xh>DdQoUbd6J^-_Of>x<$X zG@-k>#HS{ZB9hCBuh*fo-@hdxK!wLo$=aN6wKUoR=-(k9xHP)yA^IF7VQlaS$1terQLrmHyH?ZR#-;f5+GF95>cF55P$n1ayg6-XtHSUvnOJw?XJ(6_dgE1u zwix6!xlVtjVW7vCOVbTzKa3BW-rjRuKL^RxtJB9Vm}K?Ifa*w}o>FaZiQQ@7om*6= zit$b#?4b%w@8IQP{q5N&!~$b4!+@w&$wYpvrR~?yl^SBq8`?v0VTd_z!vy7Ym^?Q6RjAAARa;s6lA zXdfi`o40PgIN%Q0(YEe*6Jxo|azXY)V&^|A_#p^I`avB!YDCFosjppuspyV>1xBrf z_(*KL11M@l2tjd83@?>WzPq|reCE^`W-_CYp}L21$tzGCx}hUZXXlzV@of6u zv&UtI^ub^6m3*cGDs*;bXOS^aNt(_i-K}wArHFwZnPoMT@G+t7Og759%AR33E zZoT@VV#DohvvUV)J3k=|zmq)I;`s=nh*yN_UE2e#fNS2gnTxb$Q+_TeQ#ki^A(!ie zUs^hcuhpwXEc>fs`hUcG;w0Yd6KMRc=ry8gf>9X8Jo7pZmB-H}or=`wj1XKLZ4bNg z-6vn6P_{Zo=;f8OgADXH`VOX}2x{J|BODMXwN|Gky@s&tuM@?C6V-{9u^M;_<0r#p zf-PYSjt&u7kqhDvV>d^`IwVR?xK&0wYWG8xEq?#tAqHAJJDGlhF#>9r_*FXW?7+#A z=AE+hb1hf=zL7&jZQ<|R>yNLR{K=DS3v~yeZ3hG37nZud zM<*MRz)7EFM0%Bue>^YzTK0i~3$f6V>$|PbpX)lSv~t>CyQg|QZkO*zKkz0ZdAWL) zn>AR!22xIZEzx_8v%f|i8uS?L9DRYtLEe^aVBhO5Mi20TI)yEpH!rI({)OVGg8v!6 zf9rq5EmIjNh$Z;~=3D*tID5xp$)shT^E%+(bSk{BO2#1Dp(%xR-{n_~^v9Ju9o zedNpcZ{Jc^wLIooy9m+pjUFT3Ve{t?fsLH5KBaxfl_>h}F?8fCK@)9!I{ImSSHF?H z`JHVSg~l}dn@o+dq2US=j-k6I=!Rv5!%%|J9=&#*SKw*6xCbxLoXIU68FS&5w)WEZrCiHB=Crg80z=mW7C*LUt(?BWybdo0uL zv(wspE;pjm=Nun?lUSPTmK`p&LH_!Jr8?JGt^37BwA)Dl4M}GV?Wq+q%T!ee58FJ);)+1+EXFN}IW}H>) z6fV;5GB7akr5+Ncal6wJ$)xjl?WZGG&wOEBomyyrhgaA_-Eesksf}?5rQ9kazC%hR zVcV(G(59#sORM30*O+?XyZy-%=NLGxccw%APp^BR(b8bAQCREGth9t|*r;vovG>Q1 z#Z)V|-cF&vIWpm7^dbHTP3lxZ0HB>@{LPUTm&$x^@1%Z|A<_^h&`)Jb0KK#$yAfrZ z_dBMD)f=Q)iy372lB2o)DwTx(_C1foN=vnojjh?629*q4ZYP=Y}N(!&6|j?hPFW)L89q++Wd zLaO%w=HMB-HG5u8%rvY>UL?O3nEw2`qT%kw;?3S z!os5XEaJm0fCW1TE9PL!1+=bVi4!)sK(7hS)JyuFS-wv^oYM)p__+1k(4*DDJ4emZq;)3pG!w6ZBbT~nRK>+H+6 zeTOE2Zf8S{}vQyW-va`L-EX62K8Em*XXYZ?B%>Y|Ya*;lF`_^}b31bM9kz?&_!=~Hb)N^Bl z)G?c)tHo#>6(^?ke^JyEDR93EE~Bdy{_s|iAicdTO$KAioqOBnZs&6V7gHn*Dz$SD zIX>#=vKa+5{W-~FIH9`qnB+AG!dkjONN>H|>Rk-M%f5l6{rtgu<5uZxIG`73rEhy{ zu{w!~R|GQUIAQ8w4c<6!tauHrX27&Be7hm(`p2jL*_-lhBNkU>^NN4;nzC=F5H*y> z!otF9aF04ujS{Yf0Wjo{o`ueGgS|@9(zTBeP=b=DPgd!rbiW0_Cplt`^ws&&xM z;P5c|;iUFFS~GKoC8Ud+t4K5Q4bYJ`rW<)A>e@*+xC59=+9r;nErKgrSr)V~G9na= zj7!`C=kSgFckAw{lJ}3>+SURLq8(cgQB<7}R8^o5fr4K1cyOid~j z2;gCyyNdc;vFJx|{Ldt}hgX9>C2U@{X=eSmHjGEx8j{jCs64nuH!e3tg~GtZE4#*hQFW-1kxV`XTl%BMi;JCDhA^&1PJ5U8 z;2a2}Z4HzX6|M=*38i$P^Y_hyG#|u<`Kb1Dpc3(7#Ii}JI=A;hQob6m(GJceiEW%B z+%(kK3cyTo5bcY-dC4mm#Y)f8lkyj~nqUl83Gg9vR30uLi(WY48Gk=4`64`m;dJ%< z&83PHA6URwh5}i(7mq7ZT`aQP9CN|3^_|#AbJ&RJ5zE_}i`t;4b2&2gwYcX)TIMqmOiex|qk~LaHnx zEyZv99Nu$`FZUm>LN-8X3Ao(rg6`-}d|y8=Doa|-J=7%I?BpM~KKEVJMbuST9$iw_ zak`75ZwdN*+B&VFEkSCOeP6$!N4Wqj-Vmb{w4JZG*#B<#k^HpW;r4}n?XH%CB&HG$ zvDbc4X&FFOW*zI{MM+pL=4rQ51N6dQHkFp^?WaKA;sSaB+ni*sy)^~_byokvO83RHJ!%OvQ`%^**x^{4L1?q`atUj^UaDbdt#WJlt&XNQ z3cL5d8mrD*9I3#nOy>e zvAUC*oV?1V|Kcsb_rB`y@v($$>}{!$^OUE%B| zWCpxIP!2!C*sT*&Xwh8k*7fDieJ5OgTFPe+Ku+bA_|^~IkSgr3E$cNI#2BMS0DeBe zF3t96?tN-+>oRZ8&r<)77(!xOcKG%+Cid90yn6+F^F4l+g*jy8pq2Wb>%e#Cq7UmR zgMz;9*0`!A;u8{Dvy_yUNbi5{`}J*H*~p3yd=qVVqBVq{V?14b!O8ByhB05mMY z2Z}?%UvvUQ8P)&7Kl3|@@Vi4i=7bB#9?3pZz1-HCkBDgZ{#l!Dan(X7=0jVk)JB#i z(MKUPYZjB52J7cG)^=W^WkYGM<#m{q?D6ds|7+$fUPDusH@j&FyAH%Wh=H2dyyn{V z%a$*998!EyeTIAd2_`<>uV<3FfG0?~yW5X=Lzr-JIuW6KqhVcte8-L*Pb1FqRi(2A zh2W>h7Yo#cX2KHcpg^pyGOILpc}>pn(_W&y0T_WFnh9!va)dI48LP__Eoy9@%sh&w z@1_@*mYaQuCrei_s!P+Y&y}2|MC5gW46(=!^E7V0SL%nIa-oQQtW4b+t-+L7D?UH1Y z@}oKnSfXTg&#CL9l13%WeGZr{QAN|oKls-QPFzzHO&mRA{_#hqE#}^ZDMwLU3Xc59 zpEyNC9}mCdoJz^SFJ&wpoM%1i?=j%-gxXxn`O@s>x4lx@d8Cik`w5%E>n%Q0Xo|Dv zsJOct+7(L6l@Al;fvXzwqM8YMdJ)VBx8*QWE%e8w?U{X-H7xm8n&e$_91*#%T)ySs z&o#c+cd*xG&bz(od%c99W?p3O7XIrc*H4=rnKriH?E>B^JOk!y=V-F$aeFRK_1MXm z+{BU^Ggy|6!K#hWr**bFa<7M(z2a0}lX72%6Gjf(C8~EmFUC9#2L`rX8{;WGx8r_h{Pcj)S>{p3pr z>EEbh05b~~5cDj&>F6R_EhDOC^MSyf1t;l>%?xAE_^`Jb>E zbibEz{*P~e*9Y?C=-4Y=GXnIr&GsYaZq;%_E6!H=NM;oi`?+)Qh|eH?Ww!$P_?2{! zv*&PBNYKb716lE2rz5b19eR4sjy}Vj4qTI&`duT`+^lH7KHA)7s&Jo-Y~0wHHQ^^_ z120yi44$QWU(`{E3OwV53AxoU`f~{sFQAaHr!ggL_|ThDs6Ra)5u4A@yO99Wk}kb% z@<-aC4%ppU?@>_XJ*@vkX~MR&ojozCdQhdfX5H`IIYG_AHQY4F7U%QFI`oot@V^a{ zX=!QcN9lec32Xr4t+lDYAq3!$qMg5KMJV5{fxH>Y#fobB4@4NC z^)!rOsXgM^e*XRi$n$srccJ#k{fc@m{D-762_x)+j6T0}pgPOZxl?YxSos)6Q_>(L^@=_~YBuI$W_$ z*7+SDdI_F$NueXX?J@V(UeoLZP{_U~;~TX7dYaTofv zc?fy7_R^F_gus!wTh(eZ-XT9Y1|LIb)AtS_uiEB{*M<}ABY{3NzOyf%@iqJ324}4M+K7(I#1?&PUMA> zXIn=%IkgqO8lOWXO*d$qZC-C2lg8Wi%*uNT4fxTpnwGI~s8WrehK;5vI?=ljNXkIl z`0}pg{hJ)(2jS^HVvxgmkDoCf-#0I&hUYOrkZ8yW(zv$qp=%Bs{55~g?YxKEt#z0H z3CSZ`yP?ETjYwOzyI3{kWgYjocXXfkhYgWa*TRjla3ASE=DtUj_v}Ik%gbh{fpAW5-C`1yzBEuhs)%_I~;D<+Pxh+Q~O_8ZLj8DT-CqLU=@tSe@ zH~h0_*ihS+BdBymIZjxe`Qxp*b?{aRz`3`T! zy*L`y1DRj;+@Ix14nu1C`jwZ?20_Asg9N&bnDt`*u<#y29`D89LONZAtusDf56%E@ zbPj)i-i&z%wq4~(C8r_9Q8q3_i3_BEFYlcwa{O@?Z4$rPjoqe(M^R_4N>Trbw;BYBHx7Fwl7b-%FJwqM%4jede^eM;2^*;~cJcm~>Y?cF-(NvFX@-p9{ zDrJXRsUCfq_1-|TVk%ONR2Vkv2`D|cg~nG?_h@#fn*=!zSB{B(eug=sSCnd?EL^R9 zuvlTtjOngmf~U|r0jJKGZn1eOJ$^~Z0}`?iIwf*x-f-(xX-9IC$}&RXP>xGz#ee7p zF?%U%Y7+9W0zN`J(N1?8Oo#A(BUf1e`nt{t3Nw3bZXR@u8lh_VBI5(9T9+V*-PjZM z{F>ULyWoBVNL%S))VVx>kLJDaA}e&aO?aS*ffcQkBo!gq??it+zSd(3;&J;cogJom zC#II5`+)O$2~KGKGA+vwz1#;iBao`qE0-$RMVSn~=`219l{(gkJgpau_XvsEK*>74 z)4eZq!70Fw14c=wjpsH;^>@XF77-!56nC<=2wPIq3v#ev!;i^F7LND zs{lF*vZi(pvFjXu)C&wkQbVcdt@G=zoD>F@O#;KA@6iP_7U&%CS*Wn4v~LFFssX>x zA>k-+oX=9g0%mMPd13Rkb^ibM6~DeieS|oScZkQ59-3*X(7;E0ii7Epk&cD9d{R>( ztYvp@<=D9#;`xeVP0pi-|JY#Xrgc#h-l|arFD%v-sq^Sz0D2Sx6qK%W8{Atl9toJL+ss zsoAN?7Fxi!6LvX}quL@kZV*zwRF*81?PSeT5$0@!Yn^94y9|aSpu*s#RFi|z@hjev zo`_CL=(={%njE)a`_fHa*OFX?rq7(`$3Ooj3*4}wK=$${z@CFvcb;bE`UpV(@VB0= z0V=So5qS77!Bx2~p3VD5PqE3H`-jaMDD&J*-~O2bzM);qtxg=@x|Y6{CcG6Y-F?$+1Lh+5OS!TGx1uqeViiiY+P6#s6dS_ z^H6z5%me;oZ@25;9Y%YUM6_5r>r~1yrYNoqD061M+BxH|Iley}r(94CkB(kSkOT7QD49%xWT#N#XmgGw#5x0Qh}!{7mu4OO&gw8!qe!T;JANk$YmttHuV_A4#iT@ zTu^bn?UQegJsF2cs?8wg*6@PbZl48pD1}t>zOt$^Uh#)tBUe;(xH#X-y3(`Oq-ZSU zyfZ5~7_xyx*z4o+RWy>IB6c=K--}DzZOt&{N`=*jJ!E_qn-;T8>KZ@61l4jLRnbkb zZN*(!SzA;=Z2^h_k$}AJVl}m-DA%rCyR4BGqT=EHP6tGjWUfPwDm{wz^GT0=veqE( z`;;wlnPKljowr2vq8CZIez!LNRLV>dn^+0*D2d0|j;s)*udgD!B-p5?(F{v?S)sFl~n7p9d z&SR{)44$64kVIIo9=C&J_%d;hl)2Udx9*aot#{IRPFJEJ66jfl$yq%{E!%{XV|+q1 z8eUM9iZ?Bx)m!}YI z>f5CX|CDUvf&-sYZn<}I^He3~c{);#Zk~*beNTpt`Be?qLx_tmLh6_LP-`jPy;oc- z_CqhpR`p}uFqAb@>c-=?=KH-Nsw71%TGt-d|5Uh_?IX^+mxc-6vr<7j%JEC(aZ;{? zGH82u$Kr~v`voX>`+%AMzH-~o4B#{;)Mq8ko6L>kWDrX|WAt{~`0AVR(=*XyZx*7= znSPb8?@`Gu2BuGG)CkY&dQ9F8r-;r)+#5h)MVF_m)&6q{2( z+~0p^R@%@Ll_6C!HPt&c@qEw*ldg~Xk{%;NZAR)X^H2bM!Dka28*3gId3!>F{SVJ+ zPQlHzl$y#g{&)gm4BA=;Q7(}an#rdqTPm7I@G-Bo;aZQ|Q4lR$*N(`h)2_mb^?^sj zH2!m%fLFUN`?yBUN!>JyfoZ{sJmg3`Du``t52iyh`s0N?Lm#KUZhQBI8?^V`gk=Wv zOet7JaA=Imd40S;PR=TA&G^Uv!$Xo#W)UfotSebSw@nIX1t^JILlxx`WJ4HmcQz3x z)_c6~DvdQ(>=yC_6JDAtTiTJ@htg=a3ve5%A070ta}alv(0J4vQoyls!DY`XmELzsq zo6%|qkEV-Y+#HDL?cR&OWa3CWfaw`DX8T_I&9M6H)O$+BIWFo)Apof# zK8%9Vu~kRT=Qupr7OqSo-W|y8UUbxt=-)bMH(ks!Jh@Dyy?}cDr>4$ZAZLScU0R2_{RKO8?JH+Xe}V4lAIUd29zs|I_qoI7rkx4)vLTss!z2cOs$>P-dx4KVVJ;^qz)B{6yAI7UJcme z)`m0lt7PqGMS3wm|6=}s%;IaCyh0W*w;WGZdn~SHA6+B@Mk2zss zpG(lr05D}AL>(c_jhuMa6cYCP6n2OeE4%i8TTvXUj2QmL9-H_@RDn*$OBiS71X$6w z#TDpzV|wGISA##dWaQ;v;4K&$_;C|{M-qmn9X)wELJilL`oTd0Db|Ds0So~hPbi{q zC7ItK1``xsQi&0=eAq1|53;g^2eFrAZ+!z8i z;UNav?ra@*a?iKWFuG5Tz+$L0AJ-3y#ItMh)2ha_M}44D`L?N7$v8zRFXu;7m9={P zmb5Ue9OfmooOr(mpyVyFZ%_C~R_1hhANeF;=-hlua_{5QrO#fJb-Yj76P7(#fE>;t zZlx0UwYuz^z`KqcWF${mp1=2TEFLWs1V*6Pp*LPaGl^N0_*I{Sw&FB!=+~r82Xk$6Fdq@{kq9 zIX}LRr%b00+}AikjbLpPtI4tRwHXX^95Jj9--}#$f$j4}l?9Jx@CUo~+Gs`OI=|Hv zP+=_1Z2fEQswJgOAqC?|?STIM_*FDi5T3%~ZKZzpw$E?AnWJK7L&ux`yjTO_r=yC+ zoA$N6_N5)?I0W~(oO90=K1L$h7SV4Fr)E9#%lxy_GYUM?yRKO0aH$|%&sJb z^0l6%*VM5jo*rHP?da*NDRl~Y#p>|gSH=&nuO2Q7gHeD>8=R)P_8UG zcd*S&rMmdljU*bQrKKgoYD&;NJV(*#?pgKu74PjQZYBM>$dgjL5U}wU8MlyBm;4ey zI|wOV1p3`nQ~fKIZg4MbUWy+|rR71SYA&hxy*G9dTQ0;{PSQ6}`HXoC>*b#23>Q6a zEzGuhCrm}DZpK1;t*EkGN51B@Pf-^7Z zroST&sxhklP2~YHt26+;$X0nh4$goH-WkX{?i zk+C*hfRRg*?n6gMbY19Nfc|xdHv!u8yPJm!B?kzJ4wtAuGjXwJojwql+k-6nK<>tv zv$G~GR$+^#p$MU3qq>^D%`C=a5E4wm9545%FOn?d5^`3i!KZI(K;-BRJW(O$766^) zq$sq{@_~snY{%+#fTSRjKmT$?cvEtO9=%P{8ry`4;K{FT!A|7>0BdS}6MNwg|KGbC zxMgm0jrs{{D07r!#29r3(UbqnQdLYU)AT{o`dL3ef6p6aANvsN5yyG65|xc-1a^nV z%byjlI{Bvx64-5VV%#s-ZTw-vk0S^SDyWTzQDo(T?J<|c>b6UjKl|x?MD^uxKV#vp z7^-uz35qYI%x{p?j0z9NYzGU_-)G`msEKQFaU4*qyV(m1EDpvkRv35W@E;Fl&W)&P z!(M4XNQDA6BLhtZsvGT6 z>K>s1;8q_bDW$qcq7?zezzkrlZWU`?_s1LjaqQahj>dB*o&fK$VZ2+tpnz$+AzzbUzLD9a(fm^?pu#kz;m}Cb5y+tq}~_8 z`BXHrV5aOjkII2S=PZ61X4F$M$Esq0SY3Q&{!hV-Ve}$ZV(r5GwXTq2t&a zV?8|{Slk7K22$%7qv>cq-8D=wHWYB?{oelyHQc>Av1WY)`2>}33PHWOPh$zz9=f`i zEP=qVvI8nd&rqmw$iV;bbb)iF=KQtTT$WfH;XQl_88Lisj!Kk+feSiK=UE?JJ#l;g zVGM1cmvk`xw(+|cunbvHA{~pO>H#sYBKM?vj4sKXpF6@{T2b(PhzJI>#-dQ^w@h0TL zrddvG2qMt#TC+mhfKIjf_Y-JY;t6i0HvXhXRBu&Huzr#lW)-|#;aCed`iE_l4%!gr zOW@9i%=%$#9=$B&%*pFWP4p`+F*14jIBN%0hSK|?_kQ`iQPdciFBZ>NHvjpm{!>cZ%N%BWd0 zO-j1}*U~FK9`!KCg$K6l@sP48X4q&7-m#wi+)SZ8goDpsLw_I!%h|i2>;ihcaFdnj z*Rr%Ddn}2exWG`d>K8L|3fv9K105~ptgWTO_8~O0ox{7YvZB%>Ifonf0Ch`(n@bRo zylY!0_f`U0d+=9(ZqB$wKePKN<>lpFWL)>ptRL#Muy)}^{&UVdz*JV^H!0OCKXVGO z14uk#2=N3tPDqyO5wV2R^VSL|sow>?=+GAoTYZWM^Cpgx_uVU^e_UpN9+eh^-NyVv z@9Bql^A3|QuW!Kfdj)sQlKbTQwc?)X`FQgnkX1-g!!JZzcq*lukzoE#XdAMl5^7&M zW-(KxuTbT)v*EN#Zf)`3VDRYve^@{dEFdY#ua&;wLLzrT&~!ozzpZ>HVgy9VQ4DJL zx1OLbLQuq8Y8`iN3hg|X@H5GR1y`q$8Zarb-nV+sR;tVrGx5j@$AAW-}o zXQ41_>UH7qbMh%O5AY@zkc_%puYozBIAot;?k@;?M`td*`dR4Hejf}dzBmB@` zs)8?Y4{~GTPfFw3Ex@nYfKunt|L}+0=iqH=hx}I2Eul~d1F7FR0Z_Ra9evQB)8K*S z?6V6Uc17vb%!J4KbQ8a?+~F07d}><*D!rEonY(FA0iVmEEXd^)|0*CMqxC{W)oyzX z_d{c`>MU>U-Fs6WfBFh+-YGCF;W4r^r?l21$!Yq z;_Eo;Zw-%1fNLn;G0;ZJ@?d4r^;H+@nAxA}(0p7! z33h>H{%MCJUaCL^qXnBR$_I4cAu%#VdQjOnQo9iukSS(%4(Q&soUk{)FRJk`EMc5| zkAHu+A|Vga?ng9x6lQ?b<{)YN>3MctCk0O}^V->Py7cLoh*kw5SYGm;FY`r863_-Z_f&t?y1g`TxqnUFp~~Q;*I>10&|v73u*!?( zPKfMy0T{_OAGE&x4Aq`73XY^(l5zGv)F!v<>Al;vCD4D;$DoE!#o3t8UbbWWbkp|n z>>{=ZtT84Z%d-K=uVh*x;58O4Ji!#1Z7&!$Ynh$za$IE}k=lvA3=N8m>$XK;HSP6R|R9`_;KnR%e~@5B8kceuBsRspj-wc6TSLA9j7v?am|wU^O2 z$1V~F%RvB1b_{%|R>-35aLbP9-c%hEH&mQT(8?@6zLx**mDLDd`7|g&n*O?~tRx|< zb02IEw!oBGQeZm|S0dGYtxJ61#zI@5I6B93umnpwTukoZGMuln`zQMqbP^HU(TkQmi&3SqFXya9lzd|M}Rk*W~aAdxZ*o{ji-K@A!U( zM~xK+Ntpn#jB0Fl)E?$QVc&Y#@j$jpyr9-gO2GoVty_a-CC@gzQRuvgc`~>CERySZ zQJRDxV$IDbpj$;^Q-zK&{_8ya4*awZ;Sc7g-uwx8?C;Y<1J9?Hl{SUu%H3a{rftoG4yg4YxOXv>$hOmhP(_GM{gTXm9OGv9_aCGiDYcAb z%6HPr|Jal8^CVMds#=Ad;%XkaLvu)F{jyyVK5ou?kdKuMb+_^+VYCSGJt!v}OVu?t z=4*c13+QLIPOI}D4^RKBU!PvF39s^MoFzK$p1riO>mq5oIt(lZ4J0^igfvu9a|9Nv z3&IC#@J4I<(p2(y?%Y`b#K9EFoJ$t!*ckt{0QwYFVFzkdC#=?=A1I(DfF)&2-u`kz zsuON8#<8;Szi%)N90i$`vCT~EvL-abk%D;R`QYPpCM=uN$hsg>$Qw)1F^nbTmjAVD zYFOKw820ChvMT*H{y*oxR~0zNpWIZe!hi(w^ih|nb(C96{*K4**8pklFB%;xB4Lc^ z(We;7vkx`2?K)TagcIBdmVO4n6?hRs2X5+5zN4aeAOG(it%RUY9;sNJ(%fBW|MDQq z5|Y}Qvyqv~tI@PDhB{s6{~LAc{~}Tlh+jE}v8Q9r9t+NcTBPDW@*~XuVlkd>9|HL5vNV(Qjh3mWaW8^8uLx;FX4Dh52{{| zpI7jb=&HmP;gh%6O8AmF3J!+|U~3kKhGh0;e`mhURlJWrc(JLh!jc#4R9Rd^6!A{YeYeC=>yYy zO6Y&$WESB^w6QF=%=&{=kOEQx$&o~sV}{ZVuX&nw`WDL$cW z@7NpxqpEz-jwns+YaO@d3F-%uKGcQA1yChfZtuxeW>e}e4nTX7h6^DXe)Jgf8Qp&I za8vhv6xRsM@TQ*7s##P0@!#oFOaJSDiVM`_I129kZ8}J=e|#ydY;L!R(sDsHCKBD& zk2m++wL^kE6X&+>TlB#tRFir}LI@?430rFdJ2hhHZDk)bYyTxs={K+p#$2weH6t`J zfYFo=_2x;p1GY|Rm2=|1(7lsiY#szSQ%o|oT+ZiAxxY=ohb)!(YQJ^i>lsT=d2C#8 zl)y_u8yn122K7nyC?u4E+E0Muaa*FC1|07u=3zzse7}P1@F$kHQ8PmGe!t+vFHEq# z4ibOzc0}Z{<&o9eGdVIBLnOJdj=5!sL$(43n0s!vX#0`z+r zZr7Oik2jxy7HUyIVev+9UOxPsZA;FNHwul(uf&(fy7%sA!;vxt0zi=R$mUIg3@qAt z92JZihrRxPaz-;G(Dk1M#0l>qLQ8V}y!_~UBgfBgUEglsn7?P_yZ_0STZ#K{jQ2e{ z$#~DaB(iNuFR)oDgt$7~*%l}1hWhVoC47Kfjzx7Z|9CTaSs+CWR)8mZml4s-e6)=P zg&fQobOKS1&|WKA7Yw*RB8d!|n+T4$@D_%0i4(jR_uGJR&d>kjx9Gd|eHU66d}KCS z{PCf8J@BD}O<%+*3~YuCsBe2CwOe5pIR-$v^;S;X6Mn<20-${sR(HFRQHaha40DY{ z*L$I1#OMDw7A)wL$o6&AY#;wPP-fNl#*$Jh^r~5I+XB1LGRJ3orkb`0p;A3op*!|Y z|G}Ccc#3?u2SaY}H^?Rc{peXq2yVP|(cX)2y#DQv#=m1i975m5!oOQP2A2?aBPquV zZMnWb#+41^exP>uH0{!fV;KZEm?L43C`9^SHDo`Wc7g__UG!j0lQL;6k(g(B<6xNZ zu(AvRrEqy(G63RyIi#u%C-PvD=F~qHa$>9n^5k+v>*+2rw&S-JbuANyCrc5I8H}=e z`w?&h2%vR&ofh2nfT*v=C&auijVQT2ADJ2BkpxQ0MIW~|(=Ja5*F~uM^u~RI*ik|K zaBY2gYbXZQC?i13ayHuiUhQ%FjHgY27kgD3FhH;oFEY@r>Ue(Ba(<#;ccNlkA6h<~%OF50Vi{%&b^S1 zCd}Jo0(4Z;>fP;N&r;Fi=I-7xd!ddn5poDd1p2Ad^3l-p6!gjY2*xe|)hE^dkA!_- zA3q3us}UVv=K%sa&sG6A+K)u}hS4CbQ4Ms#)~qDlCZxFNT!=;2uvQUJmf;e(>q7)I zwg4%wf041=jXwnXAE5PH@tYm0dzBC$9|^ZwxchYZf1H%fBy?SpW>iLB=;+y?cWjQz zYwNf<-sli5_6)dV+x7;J;iS>oqd${I=OID%B2;E!-y0go$T+$X&st0=XXhXOy0KL# z@No#?x23EcfU+Mo&k=|abv%XY8MB9d!!IS_FX;OZ~7iH4xkCwsU_-pvCo^lOmr`6f6;5l&dm z;!5?y^q+k<67al*I?pwogQ)55>;Lv)%#He;rpm|lo#G!ddDn`AIbSqDzd9YFEsfDZ z)?RNy6bjJ#sV5Oc%2P)PoB*Hpk(6(;JLG&XoUWd=z9^f4>Fv&jB99R}2TK=cnG3ZA zranqMVL#u-v?%DN7^i{I6#&Ae27j{)Bqg(h9;~@Qx8w=WOAi43t|QB~Xiu}I+fm`t zyRa-LWO0$;uEv}pd{xp!ac2!Hm%z6@6w%m`j3PJj!5bnPrg5TYM9=OzZ+OJ-|T%7$%1I>OpX_3nGkp16Bn6{XJ z$XC4Il3+j0d6`ev5aTNOthTDKf~^vD_R4>d14w9(2y{p3yG6c7 zDAF7sY-(JqXZMh8UBUp$2q)>TZWS3)&eJ%%(CO8Mjs_to>u)Y|LVgWX1`Y4R6{ z0K@{j*OHa*(Z}5(i&{pXfsK5=6C$dT9JfJ&n5Ae9zA=TSg8nx}#@e!<;P2a_jOmc{ z!#cM?SY==nnGu?47^Y$E0d>lhTo<5BDV>tU%I2*Ta4Xt0tGP|Nl(~r%m&swDd2j2f zqIShl%P+{Y!<`uogvffDO{72Z@i>a!I^lh z+m#S@OXSUp6z}7@$afw;aD&&HcA4)JmoFh$BHiD2Xq3q0Iqdw4hnR+0v} z%<$^Yd($D9ePO-xjEk-da3U@dGT~37+hauP*xR=+66TF5t0f(Or2Dc7enVs`{2XV+ zelhwReBWjQkg*GW;N=GI!2V9w2?D+!XxxB6>*5i&*4>xuHZ4**ojlmwQoVdL?G5R8 zsq}DdyH~IeF~m&mwl{mbNxQo^N<7m7ccu@Y=&wP3yO2V>c@4}KMQhNohX#r~E&=-c ze65xw`v_AnyN_0tspooNFmTkH&f(+be)}doC*8l%U%^WcccFQjo+pNPJxCVtDc2&_+3#l|JOH%aJ2;Bd+o138>7ZOqRC9(P^gO|Pu z6oE(;VB@xJ+la8`QK(^6mv4$QT!C$lEpZ4W6%kp!{1s~&BANi1BgTj{?R|Ps6cZPJ4c0z}9qfXe*9W@Y`aw*>&(IesdfweNXkMMLacO)Gi8q6JaaYbL;^PFx#{m;NO z>y_^d6$hK>R{#~1hYNOhlfq^)zvbv7M&3`JmCwBAoBr%>zK4ccrFSUWhPCZ|?1~XB zjG_Pa9)ai{&#p|P(gSl^DGv#xNccA+0(kCGG|l_1xzxcdbt+H7z3T#L*G8JV*d6Up z&v1h~#C^QwZ(POE;ff2+6dL9|@!yHy$K&hGryE9pc#LS?KT_}RKd3!tHDhbcwjdsK zW4wB&T%32y#w9!TnHsi6RX{1&4nC&7TIx5hM03)3f+2OA3bBL}E{9E_U{i8uciI`F;zJ}h6kvR; zGScN!FqZib<_^8eeTsgkg~a+%%NNHb$4|5be9%Bl_?bpu3_u2SI6SYJp?8aT#{Po$ zVStAEzsTg?7;b{dKmk!48ZV;AkAV4|e>km{2Sfx79`n)4B6l7#UTc;U=0VO1C}v<_ z8cNIaM^6K34-0H0RZNmhHG)QH?T~=`JRe-J%mVp`U~E96&I?K18kcMq`b+&bz6oDw z1wj|keIo?=PhrS-oyQ?|?dR6pF|coT&ul%qlq zC6a;(WWjED{vZ|5whL6}wDb1zE{7Y*{qm;oq1%njh@?BMj`1WOAw(o}Z5;V3RERPk z{bB$0Mfh4$E%Phe|NGQI`-KwQ{PYXLr*>Nx1WcqlgNrUjrR?EZ(CygKI(LlcFK|Gb zOo1<4=3BF=Guj5=-7_MJ0qSmp6nu9aXUV)k#MSM) z&r!Ftpr#@X-e_eNNElT*!-m55;Zh(cLLmt-}F8WN`=4e@Sk7MqKTx# zGKI1T-T%V@dXi^m@z;f01^fr(0Inx#qw3R$8r_q8JLAILKU&59F6;%a!-T+5 zv=V$;ajatR*?fVIV?Zm)f+D=fBd}Vn5v9+u{z3 z(N_gpWTZ)mWWdi2moB1)JK^+Ra6EEsL-;)gx>U@O$3fTh6`T?!CXi?um1q^Lf9Y_w#v_GpA-DF; zw~d`wzILq&GNfZJB3+JvIbuNfKa^x-w1WwMCXRpKZ)6JGiC{)IC(gEa^X$Lcrs<=B z`u@*Z`n$}>r;GfewSSC9a%$5+4-#P^)7@bbPaKc}QDukNpp1v+R|s>j?P3a`#7E#_ z1VZA^NB#`trdkcwN^c@~DzF)*XD+zwK;0;J@4p_b)6h_)9L${fNkJoj5&uMt03=L+ z46EeO$~S5{3S%3G!E>@dG0(r?E-HpPkk1l}hz=A~pt0CAopqB888l*V)pUuHhwaBi zID*dIS%M(gv`ziw&k_IMT|fz^k*`*4?%KTu$fKcQezy*V~R-tS{kNS)dJ$&vpU$lcSdF4kx8}ZQO+e2M) zlMkV(&U%Zl#xlD+!z7Qxt~@0iqkirHV@tpB>3=Sl(M320;%|9)fa32sLQXS%E(n9? zXe7Wt@tp^5iIeF9e=w*ilBb(MQ)1V(A2T4R(g)EJiIgNNhpGn)eq<;UfY@c4Yq|gRT~v!BEsG=mmvtjL5CsS6@pQzm zhAz`dv~zG<`=c6D_MJ9Bx%$IZE3H{#EHAtQzCnJXalB#_ose$G?nMMz z(9606HG}%7@mM3&twLKr4#lT``}}9~_f4DkNBk_R{JCt$kHWGY?Uc^gXGGw^=`t>5 z1&y~Bfq5ucRepoQNUv^MA|@~b=y^^8ki_5SPYg?=?qt-z+_M15L+5lLGbQpb;m#7E zW3Ys9Dz)&T`l14D6P=XBnxDh;q@Llub_S?@Vf-mkVDu!=1wzU267&?P%(Te=1-Z8G zxDq_Yg&uypU!gFvP0?6zKH4yp*}^>AUcSMDXqXT+O?|jO45Xr6M_fOocM5FBn^A7` zEVyfu3QW}x70eKRSWhPSFE`y^o&`Mb-x(8#hKOKplo^=2TgJGMyBte{)4T;EId1N8 zfJ@}dJ@Nq{6stGRL-_>|UQ~Gjlh}4~M6iUISO7D+%%=iD)y-J|xIqhiyY?ptqW}4u zctg3NRMlSLCkq@NehygXN$Hnx%Yd??Dil#7cfqk>g}%cR>a1J%&ilSisFYIy6ISw~ zH&UCi0)!7;b{{wnl$LkQFxvS-6#fpOL&36lzKSFMmyahp0MWQ}&UCWt&o?o#2FPBH z1ttubZe}OH@;V1te#L<`L{jNu7l9-UXO!kG>ny|Engish183q_q%%&T!JY5lM@2;F z^ZrD0FXbd5f;cE@EUbONGcNh7DgFGc9}ANZfi7W3%;Hbh!Q=aX(u-LaXCx;>Vk!Q^ zDP6n}O+aJ@<0{MQP~a-5fFO1-L{au3Oz4gzJOU~TZ5UAlIP0M6-CJlt>JPX}48meG zmAh?1D%~}c4|64dvjlp1Z&ccHQ)I1*Z9nrPf;xT;Oj4o8(dDN}dSB56guhyH`b$L9 zhUU`u+oc_ZfvTV2+T)}iFks6T=QNQLWAI7L64*p724V92y{p)>zVoP)kDxI1e@@K5 z$0HnDE)nJZH=l@u1^&}tdBvs+_t3VnzViqedetA*gf0aFEmh5WjSCRv=6Q>J%VA?%+D2 ztAm2vOgoi1Dt37&AfCJz3TB!Ozx_s^QB98ISK~FohyYquRKOA74e@VGociYGRL@R_ zkZWbtU)`KoJhm|q2JLg&c2$%RW^k(R6h9!$&Qh_;x$|UTc$egU!utp9&bL(Upm=+S z^uQ&;OIpt*Sf0sme|+y=fNT7wRWPX@^O+CQK_~j=g&f^$9pzSH!X*qwmg9I&$tx%- zR<*ac-yEsA2*Sa|KrLRshv1clE~E$65RgbXIXUq>fP&^n5UD!x<;xel3#sFG1a6%= ze*6lEb`&OO$`;cAH~T+uTBBd|PXqIE>H2Qnjh}CF_aYt|8S&oHc{23<`zyxnnXz7V z5##jk?o7Z{A45sxP*8DAMT?2fW#K9h0cjp+(rw539q7qN;#msH%JvFpnwpxBOan)v z4MF(LzcD)hjl%quI^^amoFc)$q+f&-b%CSp1!hLuCs^vrm4JwdLk%%}xfiy1NTSc* zP2`YO0gZ-X$gp#XW??w&0~kf@9UD*q{_y_&saxZ**O7J|Tne(r(c*vmxWE5%RvG?g zZ}D6$^-nRESxXOa>K~zVlv>wZU40o?e>nH=-%ra?v9NE}9KE}Aqqf(XaHKw#4TiOo zE^Q;tH!bXmWCEpKTgqk7gd*O(+t%Py-u-`Fc6WCbAk|;~sBhQ|dvFAQ_~^jk5k>tl z*aUY%kDws3jzX)a2Pi33oLd?iZc2I!DExGE$a910alrKF@Txn(8L|CY>r>#Ml~IHy3cI#79QWi;jKMMQK!M9<7h z@BI1m%>CGznVCDs46nc!O$H0ROvq1*w@h{gbhn`xssKnMm0SJSuU~&*JFd{=UUF_2 z#0#xqH*At9cm12?p>M{W4pJSSi;29yXw5x#Q1DsyyXzSks83zPSWH7Rb-Vuq>^?-B z0Kx1%E*JWK0em>l0WitfHsB8J6ej3*XVtw1{}9=C*xK4!x(Af79{T#`JJKB7daU2S zs&EAJk2RE#`f2^!@Htom0t2tx>*gyVVP_B_<`A&wZh-%qS!od71wDI!6? zv&sX}Tg<^6OJ__Akfb9k*hNAjmzsugY>MqWvGrGf{|YAdAwzf`Y0HasXx6m&hkc!Z!^Ll?mCbD%||wqCRW_Sflx3H$#2cE>Bn+^Uyk zuw$DKR)So2cEnd-ur9 z0}3#RCSc^}T_roUjbP#$8k6L*9=hV=a`Dn7=tSH;3YlVB>mg8#V1XI2Od)ZMX}hj7 zM82l2dqV%?tB59GVOu86s{^-o&HOkL{_DuO=~WdtSwCHTSC9~opj$^5K1Kmlh{Qa1 zpAL@Xw*fuYXIFqsq1(;6b{ifiC6Fp|!kxsClM3UF7mBdOlM~PK^lK)r|E;cWT~U)=58VAT3=u9aWL2o zn!~9`##930!ny(=Vmq0VlCllFM>NT^=g%boN;U-Nio)=Rz&+GBExpJ*_{95H+BTvV=o=&4TwodfT!Tj27pR1_p0U(jgemqy>%#n&H(@I zqY1IlKLqHg#8AB>`4h`8N9Qg@6cQ5hpuD_X>e2o4;LYceZbV-Q1uD2eg7N_>JM8vo zUg0A!*{MwDOih{P);K#BxjvgWM3?PFaq+Wl++&pgx(x8dW}q=Pdf<;||Fu%HS72Xg zi_)b(k`O}T%nGUX3qC}I9u?b>Mp5c;3-BjF(a{>yhrlgJ$jF4cyKmzR(fj!OUH}a#b4^}80J)8z;9xd75x|2Jzoew3 z)QFW(QVN0NQTSQ<@IOjZxhIi~xrn<6xdhcBWiHD*@WCwf%>=(b*4>ZO#>)f0*j2-%eGJTeKZDXT6x!K;` zy9wZc{Qf@pxssal5SNf}>=N5LmX=36K<)HHef?R6LV%V_h>E&T?)C$XL{VSx7X0V; zS?YKkWK({>G8%7Thfj689D4M1gR5>XKsjIyO+hM_?$m2+4}E;d>FAcKtoqK}4LtU1 zg>fwG*UubKyeFq~eZ=e6s>`$B_28WaX;Wz2DmmW1a^(R~VO{b0p*J0CIGF zW#{lPylPUO}%AG-O()oYMjz9nTk#PuKFp_d)9mXh}P zjxD=tp_hl-338w?C?9-XUgmwh1c#s&k_l2+hLYDuPhTY1IF=xoefjcbDOcCBYvk){ zuRtT4-+oHf*BsC<;Sk^XXa|V@&C&efjenjNv?GS?Xip zruBG7nN0MFiJ3VnRu=-Iepk-Qdhhi73BTZ$7b~O)7Dm%I z`fBUy@&yKgi&P3!h{m+8r5{8tOHz`nq+Id0Mu78`DqO(nmdtc+>2Lk=V916%g2EpMf0|6bn3y^TqZBf+7m>-o4fMcm$dk!G-yp zB&ZbaKi~n&ZQN6w54ywcsWKqj4nm>Qa56ZMWz1QxUl}Y19@dJfw)zGwS z6GH(d5p*|q0Lgf(G4kW+bgdL_l$fl;5rEw#gH6UH>Q4P_4gcq#y5~VGI*AbHK{VXx@BNUD^>RHd7>zSG`Pk{ta%GfxCVCPQfh+Uul>xg-z!k^-& z!`bfSr|zCpa6nlAv`wMW=w5>D$4*XaRMYb92HENTa3CMhRv+!x^gt@p-)r-fZ4K?Q zP6L`Y>S9|v`MXyYN6_vLrk*y~+WGMP*)MIJtF~2ER@Uvo5_D@Bd^q%g62hzHCshWi z9PEv`hH@*wWS#E!6<7cRp!r?>e6*q;=j-B}(5(+mxQ_hsqcf#jYweJYbeQy@nW>Di z+)F}o1`h*fu~%8wgs3pAqRXP3-3fCa-Vx;i`Y-CBY^D#_SSF9W_+57|k{Ez~&%vmW zM(i+@e^{Wm6ACa(s3bh_GCg%}>v4YnDw_!oYuG;jEe}c$`W@QZaZsGBGpRVo&8-9! z$)XiKd!$n7`*(Z5#8335KeVP#)d3zy3fPv|fKAIvd_K=(8@@f!nE4b`;9scE!>ljQ zYkPJ`;+gyFV`Zn@pZ{BK+;UQ$?Bbm(Cq~KfB9-%nC^;drXs{iNZ z%>V0TiJl{(5phKcsR>Virr@WEJy<+Eyv0UAnWOHa_u+Hv2??k!i{71v6l28jasC{{ zKT;5P$~y6}vPyy*D6EtiJQ?l0@R36hnxIp%_&mhmt(5@pa17MumD4gnE)XU&*}<_< ztUHcRPO?EcCkzmwcYXfh;@+}5m<|IPxh;d8IG>P^P%)*RCiq#Mbz@_Lxu2GbN_}tX zCkO^0_@)s}xK0Q>#76dJSt;q7MGCO{rl|)gC?uVniW!-it#ec=IS!U?WL<75dJ9Y^tqL{`aOC2lO2Uv0s()XdiL#~#oM$!u~rQI%IFp{DLRxMO$4y6%b7(ZRB9lK z*t*~U@ELKSz&4<@XiJY|WML`!Fm;IezdpSXrDZCrgzvUCq~8u7q}@S`QHy^DBFyp6 zIZwZ>t~$jMl8Yw@gNJYTV!h>*Td`NLazfd;rm44U# zUv`zS2cBip{T;)Wdm!Qy(*-oZ3+H8XsJ@1PzxROz{7lqyQi6T^_CwWp2N9o~E{rK~ z-Tr3TRN}A71`X_BpftGx*8-~8K*l=1Llmb7i1W9%Oo_gq2R^#gASLqnuN87<+Xbx= z`8So7OniKw4|-Kc?6cGW|7BicySuxJ05p&|klJVK)qImyNo|KOgc8!yAyCtP=ReXP2nki5vHRnBeaDVo3d1Ym0R1k!gp!&gyPf7kjC#&{n z{SsB}xc~OQ{>GNQP&oOv`Zdm@b3a07N6*ku%FN8H()J3cJ#mN+(HeQzrPlsXxV8EC zk2nR0UcDOFZC%3-#T5LsT%e%#(Sw2@+5Y|4?@Yr@LCaX7^qWun%emUh$+iqiH%Zjd zu?R+PuK^B9`oSqUMUdxC2}PL@IV6Gk&1hl_rVEj-!cd$uHV{>VO>QF7Lb4QObab3h zHTA;Y%biK!nHp?5qpU^(0S%@&vVV*V3{0B#NHW zQs5~an3>V>p-Ay|Uxv?Lj>|Vl^dpAiyf^mU2Iv{6-#RWJpblzRR)ZDzHHD2wpt(W zIY%J8I(Dq-NY~=%qx|Nao0pM9x~5gtL9#=K#%RfJhWur_MYRYD4_?-4;rpMWViGE( z3!EUuiTC?8@p_8RK>;6>cV#L8-V+QSbkzQWDUm}2*xOzW`NTn64`OoW_rQI~FgzU9 zo2>~@Kt{lJgg|-W0Yv`LjMw=fa z{kJtpxB!>_6@by2Y!rcTE))X^cj9Fs>Xpbx5LKTArRUc3Gkdt85Ky$(rcu?`*Oyir zA%wGMzkO2fSE!@In{*lHdrfGemR|FdOC-cZM9Ir#W83glpqYYAWveWt64M3$^hD?W z{rk!#?SiyuSO!jS-yyMQayWkiXSHzR8c{g7WVi?SIzA)~!Dun#gNWOOQ>h`?x8S1L%HlGlp5aY+W+=(aR2xm?35#z!*&sbZdl#g_n3Q$`A;_WnZ%MaA9$bA>oKll((nMZ??=#^GZ6yJi~;iyc63ywYb3?r zT?2))X~Q?NW%mI&i!WkxooiLmQM)DMwnGSJx|p}g{pbBkpeX}em6ky?i1Sv6;-HHK zQ5-qxk~*7*hetC2Il&j(Wb^L1Tw#auV{GRsu2B-;gOLF`%cCg$pq_!Nx1(u2J-6O^ zW1G?bfAD|5Ht{zF?rr#)%<}5$tmEV3Knt}$O>F+_*FeC0Ntl_Xk3mP#AqeT2JufU& zg|P8PB9G08w1k92AP^KeHgiXk;J>)NV!cwnxhA4kWUcQ@1x&bUK;=ZK!@7)7nLC`%Zdef%jmoKB8qt;M2l)Bf*Gm8)Zhg>_ zr6Uq~`lcsRztF|;^Z#Jz<|uVw4|{kX=dJw_?%0Xw&`>6**d^yM^i-YW=T}>h+l7xs zMjET)pQAy}2dwNu8{Y=GoR`d^uk00?bw@f*WE2zzxg7u5eg;Q~Vmns0*L)@i8mZIQ zbhpqN{n?`C=15CN5mF`-Gas$)BZ-L~;t=!oz9$h~mZd~9o6^}XfZpYK*#mv8NIt74 zns%+%Wa+l!-fRExyo*pQE-kxnOowBml;p?R*+Xk%jeQA(+zdGOuVgSv}u zC!*oEzR1PJWriK-O;KclV`l2UzljjPo?I285h#<@K$%$jDY|OG%Z;~XM9&L6W+IqS z>j$ojKv3CvqZy#22;k2&G<9kHfhoLY{(%uK&Z8|K?B{rmEwO(@gY&~b?CzBm7#b#n z_lNZSpZ3?!h(H+RQ9`%BWnVgsARe)I+yzlj^`WP0KB(`g0yL+`it14Z2_bC$UbOZ| ziiM|M_|z$R6b9Ox?%lIz>B5P`|MYlq%wSBPltWf&peWgNuj|;+qtC!okhyir?SsY!IA59gPCD z_+7ty%)k81JqaZ#A)$J-I6vl25LH)?qJi(P?hi1fW+27cK|`#?psS_}lX)WpK7db& z+ywxRKnStXy3>onkd^Spx0|^dYrx@Wwvvj>I}t$}jJd!q*e;gQoyf4w)iZmq3X zLJ$m&>U zP$>!mTwfc1cbP?>up>;*K6~}5J1^<+AV7Y?wDS3hGj_p{uPjKFu);7!Udn;}`x$`7 z@;*uxfV9Ji<)K!6a~uOJj1Yy+DJWj6;cws0#K9p8MN2KS zd%LR@31SYL>p)~w8!yt=XjB3PvKIz*RP!@1T6o38BsD4fw7+4Cp;C|`DtSc%5I9{7m`_$OcZ>)x$Ugo2CnM@g=|IB(U| zq-SBd-2CYiyPtwsJX|9XL5&RL>N;SL_NQB}L58I_(UM}&iK_WP+banz`feD@8Igm& zI$|P2fKTj&O1@ZnR7fBfuR_dY7csXRlaUS^367G#nM%ZFd>73*V23kF7gX&>Di@&fUYslbOLjoMoTC zuLCnlS`~ zgdNx7C5d8K`yW|4LsW?-q@Q>gxVgEZ2>Ig0ixHW?eZc_CuV>xbeYh4*_f*9WM50uA z4ghQ)VKVdt)a-NlC0sU&Vb*yF5OyII6{69L{}u7M?+O?hM42!ud*hrL?gaN87ctYF zOaOAUU!*#6gdNItQ$yzA6rriR_>Og#>3twuftg?FTuA)FV8C{gaR{uq1}OXMmTfUu zNCjUI(K07c@(BT#1DD&z?T#Xwq`D5mojYp)(lQK)%(D$zz@!|`EEDzl|8umr;k)h1 zwh=VM|I61bbjS8*KJEt?V#zA_Y>j*qCV*Mnw0F26zTAt<7p zBen-dNK^}*F9rV|q1AgLj=>V(u#r5bVZ`|W@aW)40Xj};;M!t<`PAg}tOm6sg7$fn z4y-tC?;p1PkG2y|^5!9aps{}zR^wTAc4Ow%d-v~01~>!GN^3D?s1$ugx3y{B$aBsw z@md6lP;3m{QX8`5-iQ4jJ81(T#GU^PgJ^Xt5>`4MfED@xhB*Wn&M?RUN|>!-WVi-! z^~V4N`-Jk6QV3j-KfNWODF1$Lesd*4eP$0%{DEi;VHVN{8}thB-6uFWUYc@4OB6t& zH!oBt?eLp6ahIg!>^CZe5xsF>ni3zhZM~-Q0S3sgH<J6C$X>TiRnMg|^>=$| zRdjk9IdDxDce#HaIfn-j*zHxjk_b)dpN9})C8KODvBV|M?r0uU1AB=?diiS=ftG6^ zdaDN}oLB^Btp=!7EDow{pY<1BO)femR@1k!#0#@|HmbWRDPcHKWC*<6nb%8@fpqe8 zBJJO)X5kxeiApBgG0z*?-5C5|Ek}&M3$2`1siiu4nExRgEQzl(22T0lubfjs?l=-56=fWkEds*_Zg za{&+vC>t)jg$q95KLq)l_GED)m8uUh{5C_-l@BFnk^S82tDSzz?DMI^JSK2*s8gF; zg>nxp4zEVyj1n&g?=B!C+{@RuJVrW8Qq&p zht7z;j4~`pC%0J?DWqT?d6LUY-5A)r8Qj83Hn^aKwBux7e=J)v60Uwr*g9vIa(u z2g2n_>=2U~u(%m^pBT9Km3YOrXLPP7Y(~FpW7?W;Gdt!uKLZ2aYqC#_;sVw7K^`gF zhri3NSG89cSRa~v(N^Qj*?!yHckGPxJMB5${1t-{y^k!W!l62!Hrc_vtfwxpRGY5{=e|ZUjeIq3mkvDN!x5%qzrnis-5}Gft6av9 zV(4Q`v`)whTVKGnF1Pfi?_O4YQDy&$;CC0j2GK&y-k-+`9Wdy&Qdx^Y-QGyICr+!& z#@d<@Ae&HuV}fQ$6t4vb_&jqS!yOvV9>w>%3T|~VgT3;^8V9VTB*g_$u&3{IN%NZk zg1lgWu0~rB?%44WhQnE?LJ~nM2!6~4;#UEnkgEyw2UAq;!o0}qJsFizRgEBa(O`w4 z4UjIT{JOYq(chi9Csj$k-1P1v?Qa2kqXu0<+&se9;;5G%5x+7`kt!@re^Q-H-&2p<7=mT0C$n(<&aEP$elZPg4Or#-5U-_eZd3r8A)H7 z(}M{n$jsx<82SPCcjqH|9-eD}7QeY{#LfL3LV}MF;Mbl8hZzpTe?^FGK2cM6NEvBVvl=l;8`D^$u{dOkqEO`Rkp=o*pJ-kta($?OD3Wt@`1B9T*mpV zl$CMLquVY@!~5b&Hx57C{g8Xp{BVatC%38A%4d=qouHz=`n2zuhG%Dnrb2R`4ZGPJ z_1WlUom?9RQ5xi|96hkW85hc{T&fRji*uKUdgA+nr#l20D>y~f z&l;b&&vc(_c!K4*v8v*Sb8&1lo2wqT%Qi?9H(&X!4=0xKD!p`cy0P~R%YUci^4Cxd zw*8m;2Rn60{{gdtz^-*9>5ILyz00!dAqsDma-2QqW#<}H%*QUD!sfEb)*SHE6wXK zb67xvW71VZzw}MeQU3Xd!l9cRPE!iTw6t0ov0^J;Lj#AyC9X;YI!-NZ6nr?heUsWd zi!UKBU5VCl^R!y=^~e?F<+h$7-^~@3{H3^c>%>}}70;Co9f7?8!_j4d`&~Rg^zD2U zGTT3EvS`TetgXGi(P01cPE`@`!zqCO&dI}U2P)h$k<{UK)@Q{%Ae2+WKGU+>fS9Q{ zUG0no^;u{c(?)UY zJ=u-5Dr!Bea%=M{I@51?e1ko-I0B?f_NJzrS`@lywK+vDw$6i_eLw@2T($g)lfi?5 z0*EQ~{59vMbmt?m(wlXk^$m6|r9L-N)xv1CyRR)wCaT45|6=bYcbE$2I{w|FR7|48 zt|#csb)1{;)n#3%PzQyFW18>T?HoZ!MCJ=tRym4q($5M$xlju8*4-cjWpH5}t~Rcl zMW95c4}?T^RPDghqYqs9BcA~#q6j5bwIqAKmY zY$t%uA^b$^juof_d;qXc-7-(35DcY2Xy_Qr3<4=sE7c+!*Zmgf=g$aMK@BN+ z_uxN=fp#VYB83kCiZHpE?HIFwhh-H#6&SS8eoh9&rsw1BGB=^_d6medk1QK zyyr3N&5c}Di-gcCdIo!Vw-QL}!dhB_F^@ANUV|8{J`}h|;=w3_chWi})CYg6SOB7A zMz6heXKxuLYj1B0=_EFaScj;U_p$wYxv53dW;756Jk|vI5Nn8};%%1+OFy5-n2JEb z$hVH?R;Lmm6yL&#ZLj%sCZ_*0UJ-;**2gy+N(jcP4kYDcIY#ZKI1Q6xm||}TdT04h zyP8s)x3AXlvWL&Syv?bxe2e_ZW!EOF6DQbn1eW-D%Z=VC}$i) zZN8jx{u0gt{4V0%_YDoQ$P)hLZT$!ENMD*(^e8l)GJ!@mana>Vmm)1$t9S^fNDE3v z#!5|Yrky^Xb$tn@n<4~x zS`0g0x|Ilht5=l}iMW~(J=>4~lIU8}2;g6}8Q!hMAp-kzTdHKg(>b&CxCRt|R|Q z-^(}CV$M43gFF4xtgvAGE+&@$`1I~7Bt{{@zWJ|K59rPj(d#07(b2yy&ozQSQ9fy_$J2yL?5*E$bbT-U=@@pNLY&p^oqk77`IDPt7R*K+{$h^5 zarq#n`DLj%*=jegAvmNX)EE@pRbd#Hk&`n^c76eT)%j)bECHT3=l3A!O+@1fQawGr zh*N7&&t^u$s}KmP7o-WM=>VsKH8A16w`TOlPP*xI*Vl#vMf}}UWm)~{`Xe2X3K1;Alxna9Nm&_h$B;04g2oc6FM&7F*AVshJ&XsUs*$za4hkL^jHv?rp@ zCQJmdFJ)}91P29OoGI*29o7+f#nHeXtMA#)$|YV#Gp{x*KTTX<(N(VHSvK28f~PDr zmw)lTxLPds-MMJJ&mtDdw_^al5O??y3GP??jhktJ<}tQovSteRcNG%&)&6u@yNgYY zUS@(X;doLauQ;KD@YU2R)7K#)3H4Y)eZKlw;2As*kSDz|j-t1#vV%*uF!;a*BQj~} z6VOe9;xek_G<;c9V41lX_wCy^NmY3x-)Xwqnn04cviB`t7r%z~v1}-)^~G7Pd1|@6 ze^A7Gjdp&fTE(Y4zPweKZgZA+WwyYdm5!xbo3lpl>EHau|NK)I#xDhvh;WUMUS7%r z;wlN4aX}Ucqi|Eg>KLn;rl(##iz#CW$yNP*ihngNt1O7K?AwJfP92W&&5e?CUaIMz z0Bwij51EAZCq5gyZ3WZx^z|j|?O#Iu6lPN-pK58&t+&w)rO3sHX?bC4cuKuKZtii- zdw0Ts_G8fNGg(}AQJy@Z7IYh_FI*uuU2uIOH(V~_(tlIJh{{dD+1YO@P%7?-=1QqQ zc3m_mibZ{Del$;K$ZrKB0e*6Lu)#m##JXUdv%fdhstm$+`182aPv_K-ueUf+pe0Fm)Ald zy}q6?lihvljLnQT2twVuT7$+c9s(e&bL#Us0M9PRsUGup9dCX<2X|}@VaqIh^W{kAEz%n>#70I<%?5+OFH_sP2G{(s;WdWZC#s%T4UA5*YzjKW z>>gh+bXaduP*6YWU$z->a(%EtbnSW1&JQh*gXL1&YzEYxEapj4ysqY zTBwWpC>$Kk^1(57RjTGe7}3Ym*0%@5z<*v=@#r)f{u zd#q;Tn`E0_CeNnpT7A3z>j{khYdI2`^|4t4>%RNTk`D3_F@57gFJ_LZI-4h>M)t z#v%WzymeM-yUF(f-c9bu^UW_5qI+IGG(RS%BX~`qS~-63a=F{l%>suD`DbrDy)o?5 zBvred@4wdTDq7Z8+-#!59-S8wS(zwhay#{V&f4C?r4((giFO61-FTzbv0D)?Bh*w0U zZzOYCAOcbjNePJ$5`%zAMsrZS?^Sz>f}v7g197vS%`Pfi&|Hc^y!mG*oviOesf661 zJ+?z7L!AjmAOfK{%BTMkh}yV4?AIsSv*HyyTObqTKMLqH1@+ZFT?gncy?ysiAj99& z$Y}XX&kMb2!?~Jz9j0R}ihdL{p#woTh>3TfEh)r2nm)c=AeLo&i6;Gq>xQz|!Um_$ zP#s-gSbAj%Vw1NOpwcmi-;N zmg%EKd27!NFyFlArbiCW4b1Te#RYRP;4w6_KTZ?kH7h3gM%W_Iop}p;u2?S7Z6iHh zc1>-UH_0;zOL7U5xZ}%O4*m;9Fac-z2^WBjd%k}ya$z7`7rg2xJ#m0B+wkMqEx&)W z>Hu+;d+-h)NXq8) zd0X2&7!r!=nQcv;@M}@gc6^SCrL;4Oc6ZR+`bo7H7ttv4o2ex2D_@A-87IXWyqTKl zOp>F!9QDG%3~n~!ml~|a&Lwd$EUGC(Kd9@;cvj9f|N3d#|A^P9E{Tfd((+mA`nr&t zTZBA+toWDzA)&YeFb8_zw_9nA{-7dgyAl=|c>;NOWfp+I-|OM|rm^2?`B}vpT%fGL z%-qL1nt?Y7eQIM+M&}_RwKlDAf&45eG*q7!ChbFjrChdNVDhBD022l}jMQh%l9z^S zB_;?dQDYB=1TQ1zCMVvOp3cRAy``#OTAomzv7PR0jr{bKodCcvrmN+{&xdWENog96 z)3i$nRNI9OjY#}IxP2^HAbZ+epK(KM!klv;pzvv;k+`7bQ!1A-?qfr$4gf~vI1rQ< zp$A|Xs&*MXazWAd5>HpVQH-(efMYOMtP@t$~e;ue1?E~Wvx8Rhd%(d8mrs&JUbfyWAecjKoIt$1q0d; zVhhV<0Ezy1*f53xWCWk~ly6tQ0z!VdZ5$cnTZt!Z{C$1vcKPmN9k=QJ}Ctk8-w3b<)o zz2Y7Fd2ut!vjcc-EjaEaXFb8}ZrtV!Lqv7AzJL(6rjAx?YELSLuW^%_s@NjAWIqbk zp}?f?y7{U7$f}!?4%=k?qSH=~d-v|C*Ii=sr{=Bi&N;7xnY={NnTUPmHqkk^rki1` zHQ=sTIi0kJm5;vAT4k9dCw6$@?I)%(W6isddLpw-sq`vr2j=kWg_0aHrsisZv=5>G(YTV!uu=Dng%qjp$4V*?^S>eldBT_DXU? z@WK0*CG0%31xyJH((9#HD_@6s@8E$5m>qFgwCN10Gh5n3HBr64n7wH;y=Wvbe+q!H@V^7H>p(vO4X5E5qBP z_eLVjI}TRv+Y_j7B`J#yEWcK_D$>%|__CzPa$tx~>9G9_RXi&+3nZn34<*%?2y3_V z*|~F%*yAr+$$sq~vrqES*b}k5zsI_x`$pp`Z7uMjK?~nCN1zvVaLYFqIT3!&S@xCk z%V=-!Jw#*oUje1%gVqM3{Be*mifACFo;Z4QXJX}J4o1*$RxSeKl1rSb19bI0?#Alra+=j29zD?TP}^aEdmzMdCUO7Qb9s}i zPJ1*!;A%yvEAB#J4=vM#DtV)CI%*O&H8`;!EVUc}>AnC!6S#k)!_&aSKm(1Hh1kgG z0!9k}$On6#%VC&>0jyA0zUccoDc-g79_vDC5J+@1W3|R@4PV1EWhG`ot||#-v1^V! z>|Do>KL|aa(1yQgx6$TAPtzZWzuKKtF1-nWH0Fz;5CB3sJ+1PKy^CL6Lqm8{oRcKP z*t)HG7WUkYo2$`QF(f!3+B>4Fq} zmX)LiJ8zPXl);#aLAU@rnj?fFZ9RO3)s>i*OdDgX!Fm}~B2UYT+u$&JN^)y_q&hI2i}T0R@!r6nb;jXpYEcgJ2y zqLd!P@=w<4K>xKITV4>;THiMXgqvtWz|h__Hv`(i@1ZY$)4rz! zxO>eqbLw`)%Ae0zxU);;h%Balsr@YNlFqy=^op=4U)4LzSy|hzqDY;& zFq67utg3;k1zr0*z!cRc=(Dlbw|O>WGSk~n(@49T!8#&(*VvxvVh{f^$|sbmeZZD9 zvd4((M*H#=+guOtQSlx^duR*VH-wCem!u?*>3KkZKbrK+!a0-D{&35ZV2{#le#02> zSx#RbetMudQW`D(cDXTga*{uNVBW0m8`99>nHV<|%3M7h>cvq~EiEMy-)@$!-I5mB z1(cGt-A6QZbljlvVsK1yokmqe<2K-7&KdO9M_iFXHe0`MDdFtGOEszyqmCEPZ^LE# zq`)CdeW8x6Cr4}hPQWGkue?Y?sojW-CaLhP?!rJif~AD3Nw{X}6n(T*D-dgtYLPzC zY76o8ME136(Af8KL`gN$VXP0cK zSycyi<}dVh7JE_+WTY60CTC~QK4V4qW?M5)C~(D`5nj*M>^t>hROTs&I#+hfTL%0djtNXrzfc1?F)2M-Btc}?L4w0_8w>7cX_i{Wn&x2y?VM!lB;Yr8D(P)bG z{@&h-R9E>_6&_PQC9x+5stFfNzItanYvIpO(H9&P01>6WI*v=%e6a8IO;zkjLrm!l zO`6J5J$uqNwCJcI`0Oy&itj_vmz`vRpimf1V%3$Hctx@RV&cdhnTu)J$+P8doZshX zsD|1_v@*u-e?;&;psc!?<;Kjy_hNL`xSsMMjR;tUhZ7OhO?BIE>?kM?~35E$l>()4&`#8-fVm~=S4rK z$;Q5RIh1hF-jWU0mMDFOv6dqydEr`}1g58G5&ZOe0g!Opc(;Ev&si`(ccu5T?c}h{ z%4?M=qNJ?r+%d-EN3Zv^YGE*=`7dfXliEq;F+p8`{wm6C&nW0MvD$$2Is^u^YPx;< z0SUS+aEw`#7msxRxM3AA(VdFVP-S(Z%=4Dvuzkwl45aJAH+tIcJ)Pi4m?54xvIDTP zb(zsluA6|v0$7#o#NuUv`IrIzrb)S^9or#9+wpWM)o)^wUwV5rl@Mfo31|{fTmPdT zwX7&cuMhB&#F;8X$EY$f4Pze^Dq<~54AV0{89cU_n&f0CzN@1eF}zo7k(8bERO`rD z;)5zfER2lrK@>OktTxq!gj7+N*z)7Y67Uhw&f=Bw0mFM;XU?3d<7`wfTVK)uB7^PJ z9!~rD7QZt=F}GH`-KfedlFG>y{3&~Vxrxz5jA8N0Nc6PzL|=J1aWT5?Lj`*~?C3*H zm=ZjeVQG|H$M=}6TCBUaJ`psqgOugnOS@6K(g;WqRg$_^R}uxw#<3&$CsyYbbqb8$ zYjGyni8qxf8S9owcwLbw=BPR>)4T&}!;Ss;Wx{1aRDGA6m=?JOOD5xAzF1*xf=yI&ys)>03Th$zc!mbtg^Mp0@Q<#C{s*(;O>pwwtgNvhG^ z_KzGnue3!Tc2?c=Cp^YQa;W{Fmf-aUxN@6r$r zG!afMxs3g_;Hxgy=XjFA7I_9OWxAp*ni0;7mO&y1Xc~3qg8oa=qY0Gfv~8O%89e3d zk)CcTN#J=;FZ3)}aXXf|J5!|$$dmfS65n&1uqBk7m@wZBh)Mo&dD8rJ)tom|t14D@ zudr_&AVQ6te?F0sZ)+&iGp;3eMIBKBfIw!Y093DcW*#qge(IS3oc}sqC$9GS5KIhyUpy+DXd))+_O-DwvFtR^?HEQL z>0V{BMJdlqEIq)e3a()(vR)tPVOO&_ zk<<`;pqijXv3y}vx~d_{J3puGMO&_3R`s>-yL0W+vC>Zqvhxaz0qt6J)LTC;Shgr`D>5_fWvsaXSf_22v+;&a!t=5IGcU@! z`1^((4G#t8E_a%qbB@h#cWSpNof$JZXv$9(;7(8+Bf4BreE((KtuLSN`tM<(vsd`+ zT9VPHksf0w13DzTZ29rpKWc64N*9eJSU46&T;JtQR$=&_nc4OA)Rk#~1Cf}vXZkwR z(a^jD>QEXEz*iiH8^&5+vn!jq7@*h#U#!|xGDCfCEZuUqHZZB2rQTY8k*DUbqebc~WrIeuGb$J*4qlrxfccr-4sW zG*-;8+1%H#)p|EIzqMW=C>M6#RdJov=<|NfOgvHoYE_=j*di80vyU|;>knEPg`)5i zVV2WeIXUKrq|YSiqqljqM;w!l;XA!C2Aa2f0bb#KIKPP}!H#M0u+3%ey##lKVWjwG z<4Zb2I3u#iLT* z2Xe(bQS?6O!=PRvxa8O!MCZZv$NrBLa$W1DrcgB@KU{Ro2dOfL`OVs;F4xozv3KT6 zN-j&@lx@9>4D1Ui;+t_5MQrBWBp_gYV+WRMKR&12*!qO@EGQdOhz*-y>E1}?($Qqs zo%zjck-z9@MRuxex^SQS>jG)}Oz(%|aT-WnU+7^kl@V{ru5L=VO|Zk-kNGg~ROMhz zjS0TYKy*dmueU<6+|qQXOBsRavBoFAChABWY$loq7>MQguy!aS&)B=XPUEm{=s%~e z86c0fBkMeEMu;%#CcLvP5@9%j4*4`=Ur95~k%O#Wk#uCpn9KUP}oC>=^0sJ+rH)rqF#fIL#k79>K0s-9kM(^CBXZQWw zaa80?!rD)1?@K<&U9N<7-Rivwf1Wy1lA)bH?y6Bbs$MhY1&Q#0|CE8hSrhhzd*%B> z?VDrPE)tcOB(y0NByhf$ql z^r6Zb>;xE$ z(_g&TG7iS_6EC||tYT(nMnaM1-Rn-Kp*jziz-hs7uG8wJLe02n;;!aG>GX$QhEhqP zLcSJ4eFA)1@mLq*n1y6=DlrE`sHHzs#^B1_NLD(|@(s~6GJ>EgY{A_P5CVxZgs%Ex};U94s$59pBwKSowvHeToQ4U@B>Qet*S!~Qu@0zY-lD)!!4(m zy;$1D`ds8!>1wDCNG&*i$^BFfLQ}gBpyb}La|mmgI<@T9V?LFuK2azyGW|q|sD=!= z%_FVmbhjFEG;vtYtO^|;x%U3f)WA_3u|cHA)ij}Z>DSFeGwAgkh}0&k=^?2J@dF}; z*;RQ=yd)*lLZZdgxxkIBq7l)PpWAay-g-S)v80<+q{66+KC|HOml~~eTWS5R zT*2M$;4cu(m=s1?8ol4m3H?Q4PGjG7$gAH9{P+$T79IA(+_@2Kn?I*66N%UxxXJh$^tvjz+P%FJzE`Sm0`c#MZ0BGtKg)g?&fzluJTF(keT^B^-rV`o&sowRe9F z(T_3IeGkAm3XynApdIc;L16`Y#($DVVc)`mELirXv=YVzp2$ux81su;c!k5zO*|!5 zt6yj|P~QPNQ+DuPb}yX_&gV%)8Fj?3b9Ky|bo+Y~u12|v#mnLkoUei!o0Y6fRzs>@ zZlMf$Hx=BK*WK20OteMo*b*y_qt`ba>TEC3;vcK#-(75JwH?j(F`zo*+qSN)gN7=1 z1T&&K3aW}^@?Ul~CM*(^mV6F$4A8A;Kei`&rD<+Bk#u*?G&bEf^P>_@6i-*aVx=#j z+SlHp(;C0WV!P}wyOWT|FWD>wDFMPYLK04h#r=J*oA2GSp7?0GllEV2pmMlxbHTnP z8ro=yP>fC89A-~cpBobM0-ol@k=>2`hyCar;t-S9;$MNWGS+$igLPMO_Nn?AsQ{7& zGQEu1xiOW=1Qr)#{1oCcT3qxN*4=TiI*goY*1)4ukhNJ9jte&cC~x7$0rvs$=ZKkP z&f}!Dtxu9e=?+rcRSan4-Q>re7vBz1q{zMgZ20toO#(8Sgn~tp+XG|oH)<>5dM&_C ze8hV=(4v3eSj5N<8|u);%l>xy(w*_}PSn0aZ^XVrU(W^RTa)9}w;`F-+l&}dUlVD=`l2*3x=Fvh!h7a&9WzXw#p$uG^nTd(9b`nqg0G|XLxt64 zK(~^NSwIA^(O`rf+%PrrS3RkJF?as!=m9m(33S6TK6Gir>3HI3&WOXR;-H)rn3n8 zo81MUfDeYrrfw$uNlqQ;4ym)hMo6lN_(Bk}KO*@tSH{e>C8tm<1R$YYpkh*dA5GSU zU_sg_KM*jLZ{}4o76WEQKCWc!oL_QGKifmq5DkwpX43T8BfM8{*M9byng0RPQ&Q08m4S&qxICh*Uzk|ivIqYYf_jt ztn(cKBmFHA@n2dV753EIh~BZ}$Jt~(_sJoMp+|N_;FpY zXsd|F=Iq0E_s)S0Fj8+kjS=*i8fpEV6M&f(x{Q~g15akJ-$+oh*bGze4#(pR-+OWN zMQ>P>|B3T~-%{M(3q(PHrntYF*tf$n?wGn>X2IS1nQL7$<$g~E?bGjCbbR?uyb={h zLO^tl%4_Go)Z5%;Oz);ly#Ba7YIeMKy3UPO%``bpmc@y4mWwXq(EKNBanV;#JD8vi zGkze}@>pMmr32{fN`EaoLhstW=)PH=I{xfOvn77T%c?m~Mw{z)nK6n0?K&2}a8M12_>8@;)e!BXECE zVfyffTMHYz4ocQ0mqlSSjz&bn#Izion>_o_wS}$x*Fyklk{Lf^@M^<$i>ms_wi@u) zCgNpt($LtM-VXJ0KlqIGH09GAt(zzc-;iE&ijU(SAB)+@9;?&=nF(wkLwTISsNO(7^;7F7qH4+tK_UBKW5f$yeBT=#Z3sN zRNS>3`XEuP<58~Gvs<33+e#szs>B4Q-QFbPG=`{v{?lPM<2mWYTh%;TD5`ScH&qKL zd$CLlM)OcMNQ&yO5Z5`;01`Ev%FN$&Py=Y!j<^6JDsCs|FW+=h(;j2E!(D6{gv%zD zz538^T9vO1FePfwmGAXB-Ma!g>a7GZq$bUTp8U`uXVPCDsK_Y5CMEMz6!oUrg6{=XXPNV2q zU$Izuw6B-|kT026bnYvrV08h;^aSTAR@r$gc!_pR$Ijx9{IuOkxxAO7lefUKFi7}P zq-R$nKU0G|CyiLJ%oC<}GW#M?cWz!H;FXR#?=`xCMukF$^(cT#uZccYL+=7OB$_)^ zM7It+0VZT$h}?Tkc&Kfe5-@zYwDd_=J3gM_mXpa8AfNI;z5~FbFED&+wV~t8v1jeR zUM5EqO~|cHPjRlCVHBp%|LuGaX>Evfq`?J9N?yLh;A=g^fmpk_8C&Yu{v)-b*6hJ+ zK-e{3Ik(i~aass$+3kK+pJefqzo4rGGbIqmD9lf^A(Cgw6f?`KY>Vp)^C)ioQZ?#i za2*n@-3%<#mOz2{Mq)sb(Qsw<1Y2-kPMt`I5e5_|QeSccItrI8K(pRub6EjpSIdSt zoi0G4gyC5*;bGu=;ukux62>+wZ8&!YxJjaHL=R~;tvRA+@PfT@Ip2Xi>4}H$o zPpbTB7x-$o5ZX?M53$H{s9;D&ujlm)a5`zX@0*>>Om+bWqH)8|Z@0fvkk#wD_Uw9| z9XFS|DLUMdZIWR){Dgypc&n-?r`HXaRD9=3Rs`Q41C-a5(0H>(`x#K$*wXohzdf5Htxx=MzM-E({hIKuZUu94G; zc9Y%{Vjg2ljO_%)r;Mz&R)wx>bT5V}8fK&3$ORwKLaf4>)YJH;i&aF$Tn{@y*6!}y zdka;#p8f~Y9MYcGWo6faRbi=7kC7H0LUvAz5p9sml)~R<>bF}*?Mm2f(SzTvFO3_x zfRH4;)RFiLm|_VT(-iHZtN&|O5$Tl&$ z18D@T7F%qmk*~;4OTc!pyPcAM>ygQ#Q4@ucX-jJ7)%w_O01!|ajE_8)0ao{lGH~fl zAkIgUNOaB6L0lkB=)KS;R28BenmojWSN=0!o zTcmDes14v;Xc4vi>xZkSdIRB6rp2#`Y5LVvX^oRvRx*au@<8t^3>3s2e_ z>j?SG+FNg<4#0i}Iokx)ee*U9120vDO>633N7R>&&dUo~NbcU9o40kYBj54^=v@yX zL5b>=`3#VT;C;fA@2RzN224Uxucr~8)`VHuKn=Ob`3A6e^rQxWk<#$5^$9ke-SgQj z3P(>`ND*@CD=*N&HN+(Vx~xZv+hUH<`dD&6Z?twD$<-pex05#*aeH<@{?=;AR~lf6 z=aYen0wRI&(!+K61P4^i!@s66(D{zi99-te2NGyS92bvRn zE>oiE><0=nQ3hi1;*1&!ud6D!Ih^*s)OfdK1bEPmPRmew?V6qX8D8i4Y%ro<63=>IAskU{1MA&O$`eDW84hb|8@|r8ki(aR^PxF_ zDdK7-kiHcAjx+4h<5IN)`U*Quh}rp%^n!~>qI-(7gO328oe)6taZzjIHo+c9KUa{=RB`TJJ*Bl{8NZpQZLNumfh%IlgSj4WOx5oZv6jQ)(z!3l0z z$(chxuXz$@)50HLnIp>UOgizzejI$D2OoQQ35jA&+h?URqJQyvjaceVCqlD?$c}?X!Ng0aM|{IJJCE7gETQ%8c_`3?*+DD3qRrg@;iA zW`mpiyUo=J(h%ZEr1Dphd{`BSbxp-+94Z3Tv-%*-%3Y(X5??Wim59}9dUW4d_ZK8C z>TTyRo;y$4m8rfzI4{Z*$02dzWYx`p=e1X@tZ(&j{88%fcb*_F2zXyr#c$>~eqT+- zavTUa*^_4eLXFjdd?>nmcFiX9Ju<~%t@%lhrg3ILf&`DCG+4XJm%!m7zAFLQg2f;O zf{s2=$1MVvYGNP?)%QFtiuf%<2ylNB#@DmT4RaNWKF>XZ=9A=N&kVU^$0zi3Z+|E7 zz4nJdi=Kc0u0Z<)?6CqJOnWJv7qFDs5_T%0!`>Wm9oJ{P8fEzF5%eei_{0eAJ}xXkhB(`7lcP{zb-Oqx2KS$efv zmz4-Y1H((p555kQ=k)x- zDfCg#>Nz5HBC>tiEk-#LTMt!l+5g)t?NO$AHT>eeikc!0Ve;H z&IBE(tA08b<@`?A+E+!*I{P0MV>WgQyl5yR z;q+td_sgswjb;Tn|ttB%TfM zU#fWqxo+(SxqD@w?Thw`KhOK@&KhsF@-O%&WpPFc9ZJf@*bHVM`iV4C9EG2n0ntTJ z@l1TTBuq@)k+f_^cb_m`F}UsCG1W{qAWTB5aVsBd>Xi1xQbl3s4>KXWf4H_R1U~R1 zReK7~+OvyE@q%bbw||ciNKu5!-DBa9KNJr4b1=P^?`-(r;Ii+`fQtv7e_%Z9|-MMy`r7pP4dW+WaHgE-A zE5nbK)7odr_{@fbn}6LOM4rx3ayAsA8U#etq}TME+mCE0>N&R&@EJF;u$w4-8r(y& zON=EN^+G`wRZ+{uO#KTG{8)e;dN;jA zUrT*x+g>SnV+JKjn!YL`{By}2i7qv%TefNHAq0L5!ZzXxb4kPfv@Y9a4ZV5tnZ4(* za|M5*9nHsCf#~I(w)}c%3}KSPiHEwgGNk7?<)FvLe>;AfBj8s2(fn4^MC#!7<&RW^ z_&y+=rNrzfZ6&Y|tZs>byo}jx)@mnDEpy=Xy#zeZkR;NoofU&^<3O3JH*noZ;w)Bg z?!}Ay<7TSi9|6(6w$Lk$#i?Ww3s5UhvPnoK-Ex(8Sth(op8ON}SV=W?e>sgq$L_+> z&PTMJD@09nCpJ3M=TPS2Xm}%oJ)XDZ2*smbYsf-IZg>JRNjye(1QKPXAu+SNbUAW3 zk8#{v!Rp9wQ!2ZtdIJgFnr0a;l#ZaUGzmkc3{n@mnYDO1NA57z(J6qytD@ zWM)%jD;MW10!D<)Sf534@=yTuu*kwg;pGpDK3Y6jS_XqAi{y#THL-uZsZqSPJJ}B~U?eK?y zdb1~ufYVY?31ftucYy1miTq37YKtv}A6`uBtCX%z8JwSdAKD`2;!rFf(&Z~kg;8wl z_Dqa@E33Wdym?%|)v|f)J%YT+cj1j`6_7h1+3O?C)Mgh^Cn%t(6sKT?U2vs6W-Bz4IH}6wOWfaS2sqAz0Xvjp?tK zzchoncIjVX5sJSuE+q0;uC2w7)d8WRW_>ycQiIj4kJSI5#JIt!&Nrh-?O)&iM??R5 zDXUASGdG`7@mX2*kI#1k@9hOapwk5lwIu>#{|Gf=!bGE|8dnMt!<2Sqkx%Pw|G2|{ zHT-|>o6MFB44vnzN;5=%etttm*45AR2^s_)wpp!Pd9@UOe&WA>{y!V%l9zRDd8qi$ zr-OYv>sjzJ=DpcAkmc(J6jy3sRLaO&?eNcU{?G0G_1_R9@FYyto6~Zhb*7QZH>6BH z$^75X{_iG2JfIW}B`Ya=Z@|Hyz0|Bj8adsSbv+zpX?d}1+G_bW<3I1|zdG;Fd(a66 zL0(JLzuU(pyul9Q{k66Uz=M`K-E|JS0t$7vbYy{?c{j-6$pgCld)}#*|3{mD50igf zNeRZ~)DZjcQAC#bSC5;{JA7&Nbq5;Onto`^;60%6Ooh$tn!cN7|8wB|qs4!|{Qq^r z53_AhutAG8EO)%T0gN{fS2<;9fYXU-;L<$ze|Uj@1#B-X{P{%x?q$<$5N3CSlf4!5 zmuAl^K%?lgqod>g9ySmApR}KM74+p~=$l7>P7~R5axe_0d4XgdNf*%Lv`oQ(%{Jni z_gqyq>>PA4bIG~zE%YQcJx*NG$RGjtF$f56Q+Ou(Es^|(1wCR z9_gd0fA7!FtFe!)Eo1KS&Z$mzfVFH1tmoR)g66W0xl_>P^BG9B$Dgxng9pNI*b>t^ zociCh^}l8a1!rDkn;2`wpA#kopAEdRqCQ*wNF9hJ2l%X|K9C2bq%J@M2awCoNU-w+ nkNO`=$^X^*Ut?0XhU_qiy*hy_r{0?v2mGljX(^V=n}_}{Nce9p literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/reeds_shepp_path/L_RL.png b/docs/modules/path_planning/reeds_shepp_path/L_RL.png new file mode 100644 index 0000000000000000000000000000000000000000..ad58b8ffea2433525e814fe8bee58e985829f285 GIT binary patch literal 277432 zcmdSCcRbho`#)Z`Bh zP2_2tHW4?HY=!SoJt0+r|7^Cnbnf(~_=R`|*mG;sCgx4& z&zw@S(Hv|gH4IR*mFTF?q7spNvF`R^zV8xOJ74DVSaFCPk7^ zD81rTP>t+pmkqnlv*qO_GM7|(c9PIkZbq`t+>KNs^FLTpyLg`Y5iKxWo7@Le`Wpo zes@i?7;vaJvK!z`9J&}rTYAL>b0_0W3X_8t2b1Cpe~|ulRSI7*pN49)=k?hLm#%xn z^WKn&js9XoU!32ySgoGis*ITPVxh=OH>KWocz~ zla(~xXQ1MW;9nnEi#+mcR)Q7kkq?naP7k*-_zM`hCO9t+jDGuPSK;$R=YBk43oMD= zZOZ%kYswA6Um}zkQS=pTdQNnj)+kCK*+j-WQk@5NnA{|mx+I?QI?tAkx~gU$Y+IU2 zD`se)IlFm!tVtz?74^9F(_VcV_AqnH@L9BeeL1b2scjE`vZr%Ka`qc9=Wi3IXl-r9 z4C^L_(4Hqe0m27v!ui8NwNer;_Aa)RyyZwkAgz-@x|pMEeol8<4d(9}bW{?X-YR30{`Sa&Q z>yfsZhGKErp`jtcxM{1-sTzFIU3(cB8HY}Ct;Yc(*4~CWw12looIWjuaY9e4stBQ? zuy4UJEp%)feY?x?R+F~$A{%!9T^0%fh&5%5L?0$R zOkLKae0;mz-QBC>ZBtF{GjD|tl#zY9{y!e}5gta9ogsaQ@L{#go-*k<^!sY0{w`2+ zItpXnX~qvugfdn536E8F+QJ@$@*o7tg>$6@Dfz}Jkq}BLQf_nSRDX-LG8Mtc2|vWF zU<>bfl@`HykZ|eBtYCf0&2g6rmqhp>BF@WTNcRL)ZxiZfFg+1?mTNw>EBg*Ra+H#i zKP*>j041KaU&6gWwm-|0ghjne`|##YtLbg175`qsQLW7;O+g872Ebet_P}O8rPIGc zNs9f&T~qt#!LtAS{QxlJBx!Ve8h#OO<1Y3Z7#{h60m`fWUcuTI)G{E2%T+xGP(L6$ z2r{Hlxxf2w2Y?OkgA8t@$w8mq4YeiI!^qi~TXIdOZld&5uB8aHWfEINcra7HJx7=()g=q%AdecQC{2<@&Df)Y{FgI4ayhR`kof8 zd=+pk7Kbf1qeVujNz#|#>{-$Z-=TfB2B?n3t16GboF2B5=4YE*!mHJ_?Y- zec7ZlC^>XY!LJYRM12?aETxBFX1aqRoPE=sSed~y;)x{>i1TZ6Guh`4($C7 z<(-70juZd`&~G-I{Hy&aM8W!AWhVEd9T;MKtPF7%{;=|KYTw6?U)yR9@U8z4_XAc+ zSKn-i7G5A6)h1nTLg z=U{Kv1-;k*{`Qwo;Vq?xE-p&B`Df15C^`9YvaGnGYO)!zz9M9ixKE_8zlypN)c#QG zWeG^irjHOQko1}V4=Fr`wLdX@po{i+x{2C3vw}XnB`oz&9XeE$ zpU0*<%4rDyHH=~b{(vL3GT?rSdTP}1UfKM5a>(?_f_l~I+K@Z+eZyy65i zixP=BLU=d|tgs*Dr0-w;sxiSoKxkY}ZZxP}bE<>eOPW@_^H+sYLX2y2Fh!bhdss=t z>2#-Zx)MqQwLMO1*xn~uRX)P)MY4c2q?=?@2tQ8vA?E+e#c1HPG&lQ45)n!Rg$qc| zJTT2_Mwu7|y8*m8sZHGNuSwh8{5t@O1h=3UR0s0b&2glaM?aR}yl?~XG2^X-t5evD zp~88F2{z(f{)s1bcBs)K$sYixTygS@6J> zX_2FUx6=1V;U(l<#wvsY#4^jn_igW;*#7sI(*jy{#0hG@4G)6w`+~ zPEeyC6U<2*${uarO!Hf23NPTJtQkDC|Ho6q1_NVWIuSk@trYA=plelaOfhIgeiL#D zYq!7ZJ~o&Sj(|&tNg0(%MytR9>ZfUT{`KA5FOeA4?QGsTwctZCfs5fCd!Jm+u7@`y$ZGP1Mz(V(Y=|SlL5gBCenn$l}p<-6RV03hJ zjtL9XCiX=QdJkHsLjmSDVbrqK;M0iZM*_)i;=l^=SmP%ffQZ+#{CrVyjUA@I| zy7jnbeS15TUS*(rW@ct&LPDjuT(0rLxOsx(2U4&dfCP#T-Wo^%HW9Nm@Vx1c|y2Ee#9Jxww-Fm0~sZ53?{?a}XD?_<5 z*;CUGA3o&X?%dT|?Z`v?lOLtDzjY#b4DrIw9?EDhjIbo{(p1fezFg|~@`~%&i4!ja z?uyS!vxQgEQpk5s{qtxiO>B>t{nQx?i}9yj@^r>psfKEX?YWLc1DRP_Au%yA+6H+e zx%2N56BD(&7<^HO{agO*I}mkj*cS8qJ8NI`a4@%s%b)b2WL7we+p=xv8E5BZ*{%o$ zTQZ-@nyuTm>A<^))$4~_vvfv(6dr%JTphG@BK~TYm15A;)Ko*NQS;M!pc;I-1ul?->{rw7xvHdY5k7;vx$V5*O&C`QN?HYV#uST<%^o7B|T zSK17DI8B5IaYTGuh)V$dy`7h;UmHEBH12oh%Jj_4jOyTen_cURqSlw6wG=aHZk8nLP!%(`cs{kUZORo-zJE$+Mdf zRf1ZjcA?ZX_yKG{#>Rr%9ZO2Kedo?1_XKL!KpFK6b6vy6B;6vJOC|F&qg{$~gKaq? zw7i<4T`A|D?R)b2^=odTpws<${_0)}HT%T*aL@T04PuVjlj8>U@sf67PF_LsX+;`x z&+^tR=F3kJ>*1$$b#-cA?d|N6#7l*TzPl%chlgLU_WQ3a?mrOLzkm#zOI&rn<)454 zdH!ht%vM~UY2-s#uqD}r${IU+`>tP|pVfRUciWJii%=CFy{cf>!zi_RhGEMH$4p>( zQ&ZE;>|f=6$Ia#@@EnfjLOjdBa6XPvO=z=PnAm!s;qx&5!SqDcZ*4_=@xN6<_n_y! zpB&nnkG>ZW=g$J<0ZzAOB@eTwWBKVa9-#V z@&_puy zzgwXY0;F;_I4eT${|Z59q*;+$G0Ef_8Ro22T*QyTdkS|E_f`gZP_fCCi}xAXU3l0~ zT{_@K$NOv|F)HeITUW+=OX4+`#!P;JEh|Ai?TAR{Rdo3LeFEkHo-4ne=S3^?8AO>a zb-3NI`-zTdq*FLLI;urF8X9sl91AFD{r>$}S6@b8(N$GdAD5qscOCh@1&Zs}vK~Eo zau1&W#0hGA+j*wysFB%QB36U&f^DJ4e!r36i(q|(Pq-OFBmLXUuYAF&2riv(T3MOs zMgDr^A`MAQJT{y)lBsD+{o&@h$pM|#%sa8UI1qM-s;GBpEwzFr? zCUIOkDdtk6rymj$GTNZyA&Y+@b1R+V&K|FPLkw{1YTq19O^>R?YwQIL4IF*ZEEb>* z1(9S;k>)E7|HT!*41t#k4Zr3`=dtymlC9f`q~*0892V?+#fY1#gG`JjCnpgKUyaVW zBOezT7xz`pPCfzR)?g()PMX37kVisZr%qBJK#cU|rFlJ`5eQPx=k)(NCJkbH~P0MxMo4ewp`@7Z(bf$Ple% z4%nXOFgte3#KZ&6ME{1;ag=vi*Fs;|uZvNnIe}r^#ijrkq1yZ`ChaBB*>mT*s={O% z4YakjD`eEujIYLOl+js2sv-4`c8nT{<3O-sA0` z!6XJxOj}0V+bKTzuTqV)8a(->b#W7+oHyarK(F*zt8n>@q+lQ?A>8$foh7R~ay9b= zdA)#uK!yE2y4}pb@-TF~nolb#Ds0U{^W3;pVoUA~({DIZN_<>1Kl6r%vvYtoy=dC$ zhNjzlAoUSfJ+??%F5A)Z@qXj&p^Q|Bp|=bS%H;IqPhDY??B$GL!nF_;6&HtqrP;qY zt)-|Mx84&NV!AoJzkFclTPr8FajRmK}$X!+WHE-MzDimq7@&IJex zEh$F}w7ptGUDT=g!Pdy@I0VTEf3ywv{*>$?Hr4PU;-9qC)SD3!5ekM^uU@5*;S9+C zME=y>UDCwFBvddoGk@7o+i-g+w+e2aF!9Qk5 znlAI<)l1+~jqi4NXV0F$YyWyLfN;hl;9ZZoxw(6>Wx;6wfpevk+Eq7hn(f+tlXy3? z0>Tk~nxhZ+z0lP!*x$plaJU^>$1sbFi)K@Uje|FO8Pv(rBJ$@h@LctmyC;X6>gnlm zJ$8`W{q*>XritD8hbL?W=U zmlF>P3kz?8T!k2em*u28qEXV;&3EkiGs>)tR>%y$*VU;I@0R{EBZj*~1N?h!Kq87r z!!onMj^FrN9;E2%>KaAz8*qE!w+36Y1p5aDIN)up82pLp;o;#yem=ez%B>9zd!}2h z+hZ|!cRqZtl%39nt5;iN7ymQKv4E66$jv(!C3$Qq_$i+j@5>6LW&{cP62MV&e(i;{0@Ret!PT zS*yVYN*Ql%jway?X9!*Hy32ZnY%9Y)=69`O4FuC505$QeYxXH^8=I3AkO1O|enR9M zXpf4EbDtl{lj!g7w*l|KJc8k<3H&samO4@J7_#kdNAWFxE{S08Ak=4XZp>>!WmQ57 z1cioSr*BgB4GfgY>B}>j)C(9jy$mRcM_$m5fegj0zb2}0Xej4)AG~Iwo5Y>)8NW}f z8`u*uCfAj+!bVBbf^&5I*e9#Of&)CS`*!N%$B$}yhWh%h_9Hpgbxy+Y1npc59#4rN zZ9pz(Wo2cjkXJqSyOMcW%;;dwY*96957&q=N^v?=a1$D3^xVi{DVQO+EiH@;Rqm-p z>eW~0ugcbjcl7xk*ZTo_BIFbBX$VQ`0HnN0_>OQ*?5UC0J(cfzSicqg`u23;ccxUIxd6r9;oL}S-0Xv<>L;b(|J@;!D3RS429rFB>niprb|I$=kCQIR`6Qr@CX-gT zQ*s}aVL!zV6njU){RV1SpBnvzBrp~`Qjj3V_5n$AUi>1XAcz!v&_uXm zbA_@?qK0Lnk_FjCi#@t>X&C|m|&+&h> zI-Dy~yh!I!rr4;VAfqG5Q8tZ8M@>aV1iHR``}WP3^VceCV^l@HpJd~Kcd<+2CdQBC z__5V{+5;w^I?n6T@*m9E+QUq03HQDJ?l{+b&lp8$A@09Uth3ZNBTEtan9gZTD!Dt7 z3^x(#3gpYredhA=QJ3?a9J#e}MfLUdqd!SKC(wj-rx|Gl3)j!vQiJ06zi0p=DHnV% z?c+SzUu!c~%BFMu`gK<5Qhc0d*ti?on3C)2fq;#Ri#t7(ERBa! z1V0JFM}g{wq@`KcnM3B{w-^h-5$Hthc`}lpKHaI83Ay~2kHGe92fdUDRc13L4dLAl zUf#o!T@Mts<*UMfj^Y;(D9V{`W8mk1=Ev=_mV5s7hDdxZ<2Qya|f~vnMAqXm~>mh@To* z9{(zd0B(nN$7#vANCfldFA!H%HdaT-7lZkU?bTU&8vjRVgjGZ0cAMrc zKrr}0mscx0+witD8l+#~b{<#Da4H8e4nSl_XsWRZPAB;Y$C;>=Gy6mm8dQj{nZh?!1c-#Bq};hidlOv^TZ2I* zP&XH2JB;}64SE3$H>*IGW8{vzhevUgV#JSy+3|~tid6PfgOpczM|e`~FhtR3kQB}g zA^}G&#F~-Jfq2e~3WqnG$-mCziz@8KVY=cA$^>wa!KN6x)q~U01R;O^0R%<;Bh926 z=b=aTP`l#Z6;gMM`&(nueZl({)(Fs{w(MyQ0Vmr_rS>l5N$!xI_l=AMB@R=&UWizN0*eYZDSDWq z5E3#T48qtX>s11qaxPTxII0zJ9TWeL(rIkcHL#c@iY|y92OY%~4UCMwetHG~Q8_$R z0|{Y|uybO+y1nGj+I?2E6E5!g>W>Jw_F^{Yp9Odww#Axy!2ADnb3oeWXsl^>Zu_oX z#ot5D>D;+CaX)0T8Iomh>G-3*8vl-}oqUM2~Owl;tjz0OID%FWHa$ECWFm-tuz zq~$^XCZ-BpQ4+=pf#a&&EK`5ddRQZrqRTKMB`qyYk8PTaKl3(xR-qA6G`abyA^)lA z({qgPZ&x3VNLQWW30}p&3iKE}?mB;1A~iu-EdMkVdUz*x`l3mS^h0oBB0pkYyPbn9 zrXf-1dwaWt&et6~b|mVSc}uZPt#ES+vzTqW_CEy|R(`oJNw+MieMj3brP=BGWPg(5 zWgB>=OZyfs0uu%i4P&wCi#vZscUM8;dD3?52CxiYFC%^qDO6pAS|}^uO7924QRtdD zz2@l%yf?%F{~{oF{uLq#HNsGtrk-8nR-~o!sl;S%9p`pgL9N}uGKp0N)0}AO>$?Rl zi&iB=j;>s?Gy!qxScqIE?oQAxaR+g2KVZ-~kH|mTI{P8`JL~wG_ z4U$MWTDL)D#hge>^^dPXZzrfPh&nCId=OKKy-bO;(r0E0+aQnfypQG2)e{W(;RJAi>Oi2wYEJ zU*F>}$P@cAFRY9o{5)hj+>&w9anACohex~Bcl_5&_~|lG&@T~3x&Bx)#6E#!*Qc-O zGA-J5`9l~tmaA_@9!jExxYoHx2poAmI66p-#Tmw~{;>77^|`AApmfXJzqFDAx#BQq6ht_``4A_D)R1b}bnMZamFSbmZSLiS%CxvDo0G$6^il25Rb`)QW96(T)q)8Z~{O2zK0;C z`^obkt>kIUJ`qk(_+wRHBM$-?z5_{IYIm!ouMM z>_2??Ky9%1|MZ*_Ix#G)k@y}zH+t>+;M{+l^!daMT`r?Fit>e!TBW`Lx*u95)I$-{ z8d>L;Q_KNlPGGeS@2}k#y!q<$L$yPwC#~q1B+|bxoI#3;AUFpw&|byliDG(yllQmn zD$2YwaDAvLB`i;yYZcfCl7KHSDs-buPB3iC7E+13Qut^SPMQ{h+tNoAj8I3riLj&% z-0Xq`2W#dr@3nTJmbV}-MvQmoPdw2yKt4W=3|54+!Sa(^T3eq}RjrpLg2?xjM?F>P zxLXryy{lXMdrmmu#zar=3Jh%XgSwoH$$VC7G_b}YFS=NB_sgD2I3?GwpTBV^I*Vn7=2swW8PJhkhK@c~Mzo5yHk#`4wY?GKdCA#qI z^JwdclVD5&cr&CXR67-`C&r~Y-&9`|C}#g9SB@B2IMx^g?C5vE%|77poK7J;UU)oc zPs`Ttf1XxQMyl?_{;{a$a)naR&!1UY9NpFsVmOGwxv)Z6Q_b52>a4{BTFY}YKj`vK zcFjRT-z95er|19$YIlepNwKx>kkf-|)mqv923@$IXqe!g|A3#roZ(Hw=)SPvSjczE zOy-e7V9E1C&+m1l8BDiW$a7!$5E<(VsM>WKlf%*djuYPvTVa!<{i=Dw^G#4PJVZ>N zhfMDI(1+lm(f*@08|XwZ2&1C%yaVc^08O5rYg3Y^Z!vBIFb4% zMo{@Yp{57FMo2S*G{xYNZ*TuO#>Z#g?2@3Cd|1G^<+7%WWI=P=RO-yQ#PYadEB-{= zx&5{*koEG1JzJhjSa$6d8?lADrH|u?V$hsYb`O67N0uGWe>Pts2bv3V80XO!MX6J8 zBuGv2XKqO8CEs~)mi6*HLB{V_>*9rsUy~{5f`lv%LrmCRAAi*iT5e{Rrt_F!SrX38 zVGcj2f*#lBEloB~D{gXvMlJG0LkmPS*e5I22%}()VqZfG)Oh~XU4z>VK!vySYvKvQ zH7Q8pmX?-mW;!2r`L{3Jq&>MGPAN4t74Yu4h5m#k{p^LGydK~qg?KveGc9O4^c)ZJ zn|zJb_JnhUnPd^_+J&hLNPdLx_Ju!INuW?G9yK+U*6A3rZ>Rk7gnSp+fwjPxMd0|G z!I9bvMwXT*sz@i1B3`E0Twlm&{+3YemCBpd?@4?-5&nMSgBLiSLF;aW z^E&1#L*S3spc1o!CZhK#S}G_=I(E?XSI0-2&kSu8&_I|oWP>Q9L%(8>DX&kSll=fImc)-59AkjNS64J?O9%!Sxg+P57y z;Ni9V?)D=_Yf-;$gm-z2x9h8k(|Bxs---jTJ#ZAlpjfSrgM%p7Nimumki33xYtv-h z6pcziSJX6EAJiqrYJi4taI}`wQ|^}Y(s)o%z`LC5g|0U9&F%Xu;Q*2;<{<t&=tEYSYda8R;r&Zmv-PuNuqK_-A$fGNG#%$y~i^u9f#*gN1$~H zvzBM1TMbww5^dh*DMQhlL3>9k;@ zk#5?VN*o6@HArJLgotAv{Bh}m0C}<)33UzoiZrzP9g}VMbE%J!yBz!esa9DwS)MYf z|BP>6=n>R`Mk^tXoDO2%mC%fgPTC9^X!%$3TQ{9gUz8&rcV0xOpLy*}D!pn$fNPCn zuLAceaKr(WxzsvtguhLO-@&??5`!6)1a9T4_7AV3G6kfolFt@&A+)_g;Qk+%`)9y_ z#gm8rnn#wXcc43Hp_@%8sAZ|+{;nbfU&$|Z%m0w%wYzwcjK-Lk%%Z|8)T;?8&4JEW zYkCFld5#)aaXmr2JrBUQFgNO+MXBUZeA(xLN6h7g6{3D2*?^DLyDKy z?T*&a_vm9vQwG4Ik3-XcBmalbbPZO};x zQ`3cyBo;dR1_z%alip?vGoyoZI~W8CkV$XDL1;~VQ~V|_#B|>9bm6=c6zBH|nX^)29(1}lz&N8xsjzIMx zWEMRG1D*Dr@ITq=UF;I#+fDS*p;raN;pqU0Pdd{6c+!+vd=W3Ncc7K}>~c4o#9l^5 zMxk0Sx&AhQ;B|t;aq*ft!b5lP4+fCVDT4C z)W@Zbm}X1P{XqPKN*g2{$y9>|`uaDyr=iuy*3tD;SX1;0NIEz-KaVtkK5x5l@@hY@a>*)ubYKDc(AVt8J!8ut(HMm}X(uQpc|F3FrQ(h=VRMF3lF< z<@Uum9By!8VRUqqLx)!_i6zyfeLp@oy4yRD8yKqa!LJNajz~nR2VjxLV+%ELtKk+u zKfoN7Zo8akK3muwKhLTjy}~?))9u;6{~5H2UtPXxVURG9H3fZ!&%C{99}sS4EiSUF zLt2v5Dol>z5N2tlt~FaWO{nJ0)y@p+N%#kBe~lT=o6pMguYaOB`$e^Ad7*N-pgM5s z!@#u}5xaN=QOL-2TR6D)Td<&IWpW+|%=gs=( zJ%JEd4R=3qAE*3?{YF%89n)J=yM8cWw!zx)U^8u2%#h$j&hX zkKdLz#+A1l$#S~KXSzI!>2iO$NXZLJ#Q_zT3wICbMx-08NS~PwH&Nq3Z5p(2)qH>- zFRRPZ(N6(U8s3VLQ)QpSRkRxyG)zo*34Wz7}!i9Z$)M|^fnaqN-WQ& z!^ptzDowgFvzS>#L_}}u(dIN0j|pm;KNmHAvOx5f%hHV_R4wLR7`zf5oT+YvekFA@ zAat$Q0ep-1=(3rY1}m4icO73Ip+r~$ z@sHTw^$4uk(wvI0o`7?qu^F}qLWrGFB>Af1=&w$Jwh)`5K)ScQ$&2g%A0K;Mi z&b!$=9f0L!Xr*VRiu{vUabz$Zoe=z0X@y(;H)$=A?AW#ZYgd<7(83LfpL*9OpaD!S zW6(fr{>nnd$b#I|q=!TIq30NUa*Fd}y|cS@b{C^s+AgPG_eaNk@*KXf0>oaX2A^Ty zb7I(VoGh*Kuw`#M69a==$T{fibZ5{3uFP6Im~s`<;Ihe}v~^f6NL*~l7jHcc#F1D1 z?Djv$?9&jl>7?t@2^9gz0w`J00T>>C2TWR1b8}amiKBt&Ovn91m~nuNSSeK7Uf9JE z1~s6K>!3@WB85{@PB$y>6F?S)NYg`X`wf}ReUJ9rvG3e3>O1LN?cYX?!0PMJ2;6x4 zofdea9|#mUI62=KwAhG*o{;$X;b*TNG>`b27HzI_3KL`8x37Ha4j_>4EiD=i=iS#J zbh%paT5oCQ5#r|Rkzt1ge}f8gb955F>QZ{35+%OtgwMYR0%_GIoH^Z0=Pu_xCbnhj z@6ytyQ^OFvE50=9fsl{J{o|kLa*s}pv8Mq(aS*ZRTl@lp(|2S2;lcOUSLjEm%ea@DGb%MT!^;>ndmza_6_3H;=>;g1@ zkisy?C)AA)g|0e_%k1FUU0w*HW=St=*K&1uC5 zT0-s%&p>t4 z8nZRNT=aUlW~y`qx>;|+6(kq`OjNELKQo^EPHS&urh}u?csYUYwv|Sv{eG!? zVTO^+3>Y<%RJy?C?W?hZ9fS1pkM~v6+9P%^*~uNT+XcVA_?LcrnFcGh z9SN#Mby!6Mv6wKYzG-dKN6+EnO96ff7645)PXd9&i16+xAll@8Yl|TMn-oJ8TcLrgMwf{r&@3&Sg zFB-^-yyT%g^Pke(YDwJ{Tg}$!9tB#YwGN?JTdm>{jvjhYlOhWb{^{Y77vSMvT2z%$ zNH!X2&|FptS}pKXF$fqwhDvsYGxPdc>mEWT10U^TdS>Z5eIt;879zEi@SWu7 zdICwg4D+J=LH_Z~DoG*|YADj@NPP=OpDr0x9mFN-krRAE#TKuX4gFXR>1JIETP|<~T|h7? z9?^h_3z!@$cf_i$$yk@ob4d*8H$sv%V7*_q&i#?h`ui)4?tq@}6SnM2rE9gQ6idAI z{awb6=(QWD6ugmfPo#YAZIE{BPx{39dvJ!py{*jIShV+pn>lIoOB=|3`HaZ$@WTjb zhT_&&N37VNPI}e3Aok#S4)!m4ogO`_&Yp|ZuzHY-lwjsbitU43eX4OQJt%3V(a{`& zHLQW>f1jza37&}wrhh@;D*(0z0y{of2c2|k?-!w@Q*G6T6us4wZ%*MR)_y%&jydNT z6yhurofhY!W3GPO7)05Ha8Djba%3p0t+v&b#K0mog?6CBFg1+tJKh`xjLhBO1Z`=z zMUeCn`c0JvjgB*|sn1pnzI_*>vlB$V$}uX1P|+{buJuOEpswr`D+DEPpYdTe^vw_y z&=i|T3YFfjeB72}Cr_R|I2JUeit_kAV1;mArlqibPd;OjUV@!VO?g z_;$)a_X+&1ehg9JZWq^vaUs4|oHZ){d z=y7Xir#p}(UHX&GemM)aZJ7GyG)e_=c!)O<(QhQ2#i5n#*wBt-Fa~Z<6;;*VhwCNj z78Rr^d1|Pc4w!z$Ily?uFk}mpV$YfX7>UM^v2)c5%q{^+%AHDFN0T}UUK)&yF`Kj{ zwzajLbeQ?|p}FDPH&5d4Rp-`0=TUzo4o!`?K6x_XtkBW|Tym1Ls?FyXL)TnX%j1gB zp@0i>(eJ`gfPz`U91d|gjrIQh`(`k>bX)$i?8ju72bQ$3uqYjROT6YFd8KSIiW-rMpq#*Nox|l7eSXm7#m=aO$v#Wx5-H7!gT9Z>-|*bLx}L zKt+E@P0e&(R}TwXq^=DB_GZ%n;7%PNBP{k;uhwjAzGL`gkTcwX;_)KcR8lE2oN~yxKqKl7c1y{KL&6 z)M4dUWt2j}7=n_0x}!M*G+yq3T===1vTR&f7%Re}1l)*NkNsmS_s~IekelVZp*SAm zS*ww@fB@4NME??S%7PL4N)W)pb)Nrh-N%D=RBG5hvkSR)FS+{hRZV6EM}o;PV)uFF$#cy|AMr zUy1nav4HY;o>(ks8d7((2h7AX41I>&GYIK?R+yOJJh7}0gH*?cSBb6l*Fmco4q_mU zVba=lgSZ#eYqb3}sB=^4sm5Nu_+lWH9aK)qEgyQ9Xf>RXCT*CIZ|ue2)&d1Urn~j8 zMWzc^kJQ7UtBKfXD^&}paTd+Lo$YY{2NYa3-v6+loJ>EV$8?3nfqOld4mr(yW-3CM?Ay*e>AX0I%LEM@JaeG9 z>gx#88b$z#4$qH=%lap&&IKp{TU;JSb0ePGK?3^t-iX-?R5^uKRu@l5gNoi~KN}YLn3{&-Hl}LZjKq8km-96;y_*%~Z^q(#{T`jE*BqE{bF9J5 z4yEWc8>P7iST%7tjd=xy-W%CLe?n^7e0-yn6ym@e)_yTUw+1j*V_bF{Ba~eKqn|)n zkSFY|oQNo~TT>lfq8ExrUU%o`4w3R6W-AdesEg$*%R-<$G4HRbW|QKWgj{+kDlSuv z*5zp+Q8%0m|9<%5v zuVIiEU!16};g~N~9m|Wj;CCs`p>(lDKPK+_{7{+)qjk$M8XI}JPl6kF;<*EM(r8Lo zvz{!hg<}$>%fW#Bkk~;=bvRVhKk!X#Y9Xz9sAi+_x?f9@)NaeR9UvN~=huHpmMTIc zpg!ygLoy{aIOs4cRyWCcMV7>tmpj|z|6KHpQtcsIW)7jR^YaOSauOEX+HJ5*pJC*18bYQ~oMznGR~OeTd|)cqasDjapYslgNWZ2c zVSeskFuWKiHY7%x!?vr4jV;%CX}0%y_U0qiA(C#iQFrH4n~nX2JH=*GfR^)XD_T?F z)zAffFHD#}2wMm)eNuWk_i+M(p<8PRB(sIy>c)Q6({cn?0GC+ffL1SrR*)`yM9?!j zO`8L>+?PGSdwZqbU|};DdH;E5V%d?bP`RdIs7aoket&tG^g^JhP#aKZHXstkU6)vv zMP`pbyx_so5$M1glmla*f`Hq7@I0{_CTX#op)-oEL$)4u`B(`X&S7U7+w|>1R~neT z@CGhnDz!F2OJZ_vM)*#DcXeD1`NmKz-+f^)6Ef$r?Ju|zZ*Ts~@ zg#7468&sf#T+%f%14a5%l+fcGcBQd>12^#m24IT8Wxj)e9;I3euJowEFzz(LQ%W#e z&Wm@lC#qzkyc)G^f4-Xe;l|5X^gTfcW{3gbdyyu9D3^OFn0 z>p-F-snSL+xsI}`C}+U89U{%)H)#_M!1sW~GIJ5Xps+U=o<|(sNcOl~|Fr%q#?pVv z&p#HMm6p3H?_^XLtETI7M-2CY2(*Ku6hD0ao0x4Eb}SEQUH`fihSwiJNeXi3hZ(kP z-7e+Qwqv74zJx)=K*=Bve#(nnZv7Y0#5ytVG+A2jr$vSJPP^a}xNf5pV8goQfnp-i zvqI%KH}M4avKineR*nSjhhakutcG+bA#cg>Cji~s6`UIv@(mLcU_c_gUCW8M~(ifwniZsSSl`%}tQa<-ZzWvz1J4rWA zjk9pOh2nwfR;y;7DX_I$Q2%nNH$Sk!6lQ_13Y3_>#I_pF)`4s=Gi-o-EY)CbAhzTH zj)qI60GfqlV$;EYJb$BMh@81P5zr5G9^!Miwlj%~YJ$U*T4Gf3L-bSWmLTbek+gQF zS888Uh?3;Ap>8tziJZ55s$XR#koVQ``LI6CDLNSD8>-IeqP$0Nv2^su5nT!oL ze&F^2nOQl?5b3Z{8vvH|VP+vNLu)xW_=s;N5lgE%4^EUuO3p6exSrgT*2&>k5hRdB z1Q@t&!f8;jb8@;C@3-fExP!r4ILs0F8k!?n(0LxE7&+aj7o-%N1D9FQXqLGUnV;7N z0wyYW9(qj>67w-nP$^EQNuHFB=pnV22R#Qmr}z!(LgkJ_ z2e?}FXK?;ua#J!+HU{fpVeCBftP|U8F5B!9n^2V4Y+&(|p;^mElc$;IiCIhl5D$rpf^S0NzPOg7tO5^;L2R;%qVfEDW&%J$uIfI>}NUebQPwIT&~E= zSu!2f#_lsKpfoE#R(vMMZj$rEvyBCk5@T?$gSisX1gRrPUw|1|c0%qPCoDHb&Zl&j z9$Xyunk*B9wX$rS!|s_Lf0OGl1oIta>Yy*fOGI)b13NY!57ob7xZLNtuw>>zo%*ZR zvH=x=L&uJN@-8jbEoQ}1Z6rGD zl7V-5GJ#}g&6w_>I0-TpW}nYP(DmR7u*lnHM4<787u00_`PioFzLCZc=EK07uX279 zhiX(!0%R0Nrp?ujQk3^O{Q4O6%Mdc5GRGWppeNOtZDVB2U(7$IJOp0}7x0T}a1@g{w)eR^y{l&d%>1n zqMpKwvw-*5t-GKG;np5@1)u(Pt{Hu^Mr0`V$iwDdaF2@N7dR5f;rWt4 zU~xtLAeasAPQ#7~#0s`M97p7ZOw#mP{*$m2{5vPZom{g3#=_n!vaL&u~ z?V}KUioqu^0`bCApIiEwtMnhPQq|p78#90sC&W7P&T*oPIA17AQcUOJRQSwTYb=akda`$u^L;8%w>pG zSfMK?(NfIyKu593Jq5T*Q!S-w-wp&*BdA0S@i02{(S`yrO^A`9fnS%wJZY(ce zI)Lk^Mg}kXyL%AubL?ihuenhx)YVT8zW@9KnmXODS~Z4g)W5!P7i&evvTYlj_@U7P zD)|DoAcsrC2fduxSRyjmmNgNOgIcUI+#8^ICskzw#9z_E=u^x-pN85U#$`EUm8%-A zyYajO09?y_b3J3hPLZ;hr1=5(6yCKNS|>#&e`x`kl$@YV12>NtVVIm3%s9UVI>-VF z9&&`J6F?T{v8Mw>485a9G`S#CnEv7*Va zTnBjHC}3S0u2=vP&)=j&fLE}=R7xx_G%3u(RfN@B8zAre0hE+1u`+0~|J0qsyO}-b zAx<6jkXW+mAAmVfF6)2bMl}03R!z6fV2;;&{tDf1O94M21d3U%b_E5CC?YrGG)U8Y zXd9&E4$8{0$jTk&UpFw9Rfu%-+G&8w;d@R2R1A^z7jTgdF~JbCzK1hIx?X++EidS0 zPu8jb>=zSyy9o1+&kj91`A(zW4-Val?CE|n;mMH~Y=Jfhdn$vp;t#_;q$4LGBzL8E zJ>#msb9jT}_1ufB@#K}&`MG}=A9(<$0mLMrMo21E-YEd#sRPa``hZyTdOS@!r@fZ9 zUngeWwHdf=LCBkY#0sMyY{ESyd&(eqWWP-Z4!LchtBg1Ag8fi;r_Uh|Q9c@dc{xMG zg5T$2$8rj%4@^VC@sj)&p@a|xKJkAR|)a{kc0Dc-?CpnYbz3#h*Y+SG`5KJ1c}!IM)Z*PRz5oo*V1B(h`?Q^ zq=U6zdOHP(FEnQuI?wh?%r{nE(gK$$GcQawsF}dqC{#)Oefza!E^saIA z*rm0b4?S5ia7WA&dGT467s2y$AwY|L2T;QurL-4#!LuD2FMqV0v)#d#@D7y6up#utmWLdGh5`FdlMV zY~N+b%Lh4BfL#pb@f7{Q2iNSRgT^7bvD|!SciawGlLKeN@Q$6gll`RbVqarGg^l~K z`6DedLxNIj`wp4jjuSk!znGAXiu<-UFz~+47np?cytUCf;U!EICsJc#6(47`?3SSto2@usR>O zqL5GpH6RW`OxklV!Yvy8?4S3;$hsmkX^O;n`SBsP%mjx8s2%xhk@|qtxKi&6 z6g4iI+7~KY{nXPeed4-bUVccG-k&RTdbl*N40=C&P|Jji2U;UgRVRv)+c?ARX_WyY zg1HN0WtUU*YlTxw&ucP@Se4&4StrAYq7}8Fk2(<&&FkuiPc=X@m#QAe)Ilus4jcqP z@I6d$Ya@N~p%>2H&ZBNx1+%?DOi-njAE5U_tSA7}?leEt96m+1n)|WF%E7a?yoOQ>rWy5=XP9+YyDp z!m-r^di$OyBB}X+9eaP({DuA4NG7DD>~ZGw0*1b18A0G8kfc8Jjyrs6-P}pekfhC1 z|NcMNX;S{{$C1R3z?d3&5n~$p2}IHh;ldnf#QhHZ<={5u_0*ZUj0mCtEikkkD#`$h zFYVez4-0sc4;cIhq+Cy-<{hqlX1BgX*VE&dBKC?ziSh7(I7?3BM*bN_*pVx>wNZ*} z&xCq>(}CU5@i$66zbf!GFG-z*PzCLdIV+(FH%Zie*^y;+@i-0Yk}0?e>~*x?ng{Td z#UNK{z~I~2v4Ob|@b};0t^q?%RURU;(;bl6u3U?SWW6eRr-yDI^E-1F`;2s9am3jJ z7&t)$mVe-sZ#!uL7@(L&RfDoLk8UIRA`R7p>C*puuFxtJVG{Jae1XXJ9<-b=~RT%OFQ?C^Lh6rC_{LB1nY|h>$1AmEs~t zvIdi+qqz=ovoOBVVf-sX#NJNOJ-8Wz zCq=G%+Ygys`gny%7c>GlbV!~aVqoFJZNgzFW?=k_2JR(S6@_biZr`zo+hdDNoadVx zZbt-Ey*AmsZg9|0hma%FBC!%1LIh}uXD^1I(OCY|e$4{`y-a*VYaUPS&`~&*8E}bi zwTgL8i+$A*9*XkGJ#ri@^~5h8Nu7PRZ!c7Ln7SaaHff817w|Yhq zmJ*>$TfifX_Jw#DdxpSm9A@7o=?cLr``SYoYG4Cvt7C3QNU+771M7_HBm2#rE{aeOL0r^Pn6>(ZH4VB{0vWx!kwI*nTIRoe-+Sr1Nik$+7 z00-#KQ)El^nFxQt#K*GS5&(97dWd+e@f+NCLPLclnm-`be+F2}&=d!LFJVW9iD}Y? zqZ?BK4VE{FP5sv^tQ_WBlA0UoVnX~Ugv3tlJ^x;eG~Fb7w8-Ujg8Vv$awl;BVty2S zWyHO~^Y5*yWd$cauerC7`uBuj%|Ds$&R^({Nf2mg1LI@#(J(*%{}J})@lFJ6DLoPxN#?jT$el5E=K}MeoQj$*Btxs zk$0oEcBcHU4bTf$(Y5N;?aT(A)z z!=^kW?@Q_IcSMi1G72Z2hAS;9bLaCt0*bF#{_2lb1;HzD89et%D*RQr&Z{4raIYKb zmq6ux9|YFB5N(glihIb7KhY3|qo8`@k)==yd2KOXipIMDS6bt(utI}7kM7eZ3Wt%! zy+}J!00k1lEsSyV)B`(@P189E?|Idsfu88s-o!>xf<;uOOq1&W^fBBz?d>-dGM1_d zA2zr;gxf!pFd%o2ei9cZhXzP~vw!XR%G%veA`N#%qqCDv^sFeZy5AOy9b6LcL3wXw zkURjens*VqW8PSe19>y(=2I2Pv^%|z)Q1`fBFe@n%CppJ!P1EAU(Xa~Lx7MK1w<<>|hTpqnKkHl(*UYof%WemPMyJmGi-3|9v zQK_0WDdk2U6X8P$Z+zW`q#&aPZc;9(T^@e3d&oy>;K*IH^Yb= zQz=ji%^fGaWu?N?_kwPOBPtivJJ`#PKx|88t2zDT$7?YFpC1gY0` zTwQ9j6IXIl`G^F7OKe5@ODb{GOfGvJD^z2`>hGM6+O)?pEe7jiXK^FBF%9vWSv@=wq8GyR_eHC?w}fcQ zz}6sk-*(!tmX)a2n0Bx$HMa%HgdiY}E>o6xDs|L4q@SLqqqKu9^dr|jxEq)2jn9cH z%7LfED-_cmdj92HxnLf#wT)uWW4P+h>(`wJh`|!4F;m5r7=Yhb`h30A^Z*y;&fP}R z>=uUz&DGRwK8-w8>`!hI9OWU0M6!%c%^v_b?2>3LDqnQT(KYQ4U73ZEYN}?Rf(kgB zG4cnpImhZMcgj&QeeeM7UFqpSP$Pu8Gyg5YuNEv6u zYK1!GHYkprI7bVo9@a1F(AkxEq_tSiSR#SpnOD>F@YZ1 zPyRYBrYXr8b86KY8=CRdK`uo<5@u{VzexKkZbvXrYaw&xr#sWOZFe^WDp2s)qAuHR znvl8c+D@AR(;WNvg@I!MsswML-Q4vg;L7?FrK!1%rY-9auld*yR6$4eV>VP{+cbs+ zXB&74nfxE;EWtm(7$Q5X`3%(Z4kLl~0?38;t}0fCBy71z8+QN#bmc--<@`gx-}Zfr zDlVKQzFy?V$EN+2+KCzOKzMtUtpcy;U2gGjC&ycFc4?8X7CFJ)=sWy74_uoT=$|Dw z16#)wW4mBIWKP^RRH1AH{R*-XLbY?N|Kj+S$up8Bv62ysv@TA8UZt=Q#F#`~FT6J^ znf_`@SupV)-a%!ap1=P11El#hx96aC7{ORhwZ-fldrvOu^@A4xKhllH5B_Qz*5R&K z3!1TY*LLK!w4=WvmOQcB@OQu{KA8bd@$F|^)cz9ly4R5T;zs_VwyNkIjHC&>=tHsuGK}+8>u=-uT z__EZ#XLAqK%=ZDli|o|Ltxh>_Sp81yb(%eje{GkzQv^RqE>H<^gWmPL#gqRNv?i1*nMOkai%E>r?FQJ64^wTsKU#-X$! zjVo)Lh^PErpnr2$H0;+WES1OWWTCtbT+y`Yjn^7OP?Z@;Qx1N8vf^EDh3r|tKRJ)z z=f2r>DR1a!*E`g7r3A>OjOLJH^`N@KTK4^&5Yw%s8BTW|2By>k5L^1S1^=Xu>U7I0 z%;rci%l&hVAGavsaFp1FZxdQ5*Gs`i&&lUw~rfkUqplI&7ruy>zAb zpWc>%dh^|J!a=0IZJFK6IJxvSFe7?nO3>!RXpgWE`5n5?_@J5ci`)Z#fgfYI%X(!` zo^?Gy)=ZpctB{{F^^074!H8Df?GkWW$Am)#eBO+%`!-cj!r zM_N2d4t-m$zC7m@)*rE-xspWdEou|HFF6<3WxF)3b~snPVMA(4s?HAfI~gCRB6-@& z-1)73Qdp?S(wz@Z=5;0|w-Cs;vaM{v*&tlD4WOthv%pY>9=C<}mlA`6zadl7`b(4x zf1}2Ay(7@M<)hDDMMe#reo^;#i;c2l^o0A}Na~zL`vW1#RNSXTST;*eNXn=eK(nyT z1Wh0%RA?%F)--3;tc#aC)MixuYjkw%#7FHzf}`2Q;500)K<@)bjM&m+vLv{}mCVht#tfa3L)toy zTXdX9W7NG{nt$p30-*U?unF14J%Gu36t1=0K}!0SHl~e3I3rXi%~&epjKo(Bbj8=# z>#WHZ>$;N+T99N~o+v7{hC}nq*N&SjK!|=MBi-hc3__oj@?<}gj@eI9c>Z?#|=Tc z@ZU?*;j@vbFS5FOvK zpEwJyZYlU$kE9kUn+za$KHK`$o+S?qEj}spyrnXQeJ{x{j|%gjaQ9B(CfFSE>KYXt zaWdI_{pi+>*t*tiI-KwL=nrq$lA<%4vk1D#)$H89{avr6;gk5Er04L8y=4L`ErDs% zY*^u0rZ_%F_(08$SEiSqB5J}BnQFm(H;{7d`_x3Ro#@I<9JFQ1$%|`zeZc0* zpRp0w=qjMllRO5On5dwiO(2YjU(uc)BHZpzT(JR&b5g3zY}Upw@X(ujn_|HgyJ8ST z09JT|g2eUvqm76mYZh&a;GeZv^jADe&B^xWsgZTG2%g-7Y*$Jm(>w>Dt}@e zx}dVJL=MLjo%Y7@<`Y7di{mj!Wa2Da2ERT#i?}$fU<*7Tmbajya|Io;Q)|ik58D%Uw+B;4<|W-zwE55SHkj?^?!L*tx;rw zY|l!d%j>+h;;Bhv&;Lwy&ln+(*;R(MSsiy<`RV$usA1(JiM^yiqjh(`j1{iAGq#4U#TdW?ZWWj zCfMHVMsi2`OX~v&{6=sa2(YB=bdAzq=$A|b+IkA`^YmY{**qzc1;JYxUr5g22d zyi@;30unFDd&&*1yu-b%<;#4B26s*yQ2cu&X8Q{{XTSP57r>N+l#s03ejiJc{Q z5JZpXPS|oehL=Ws!uYgTh{&oo=OX*KGk)Oah?==!&(M@DT<)Cz{(@X?eoKI43mEi) zL{YjczveK>%B%q+tSZVk9W_j>z4I5*jc_G0f+*tfZ^E{^0a2O%xq})DsT)i~XW28Y z0x$d3P;z38gOF68roCIos_Mp87G6hk-TNtyVegUN9x zxQd&8e!ThY3_P0qv!^D1w=kyEWbiX+*dN{={eKm)@nXy+5RTnC2ksrBhhf0a6>!?YLj^x#1uq(G@5*P zS^T@({I_DH@SEHRcQD=65QLd&#Umk-34q|aXvSJrCOE{Zi72dSusxax zgl-)U%0=^`MI%PieA*0^{d>$0ys;$>1N1aWYE1un9wEF|*XnbkRQg2xV)Z`-(i}C! zR^yKm&+dNuQiHu+jCIpU0y9W>O_6aONP3#ljTZ3e)-8D9qRiD(JUo=w8lp*BhQ?dC zw_iCydck+?IJGw~lGP+KfAMFi{)Z&VMY2qZC7y8)0XH8OJw^O~5%aYkcJfnO(w z)$RK4G5OIG@VdOTy((Lo(|3&b{`O{fCTgg5YI~raoMPj_clYi+cdDhK?@Bs>pk?;? z@Oul(*{Ih#M2_$V_nKHivw)S2n%Zslvyrk30=Gj1&P=hnvtc*qCk-*Q$fAUKfuj=G z$2KxE_HZgyr3MDJSWOI9eYG$N>{lQD+3NM{r{r}4A+`XhKXX0iP*RoTYz2D(oZV^o zOUY5mmqtFk*OHjJAf)qBt2RY0x8p~|?m-eC`AsR4IC7G-0fD-PvGm`aHVwk*p6GQq zg3WbGJQ;Ndl|`4LPcAFhY!A$*Vh_UgGyAVRP7)++9g?#pbkNWOLog}y8HIqRt|e7u zvOwr5Wu^?EH1de3&|F_56}19`*5>f4|YHoX@Gm_IE)7;w44{{ z;;;wt@7M#moFJaQnneJ{ow;=@jAW^bb~_@Gi*)v4VbiMh3&EK#o2oWvD!9F-iIUxr zD$=-Q!-+|ACGsy-uq2e;!xsb!`PfNwX26YNHs}zo-?ZS? zo)@BlN%|Vvd}76CmB3|s2RKhACzSXBJ@D8gWnK-jb9E?y&{B%=eHi2O3 zakeIgxjQ+>YEQZm?E2kJ$q{9e4fL>wzmTD^2Bp5_Ko`ahNIbBilm?H$EqZUlWl%8$ z6_4};j`v1m$uPqGoJX76lzKj(&mFlgQklW+3q9e5ESY)S7Ayy_WQ%Npdy=hDQ?(|{H|Hl{+F9=c~t@Zl3_ui zl(XbVA44GB=TBb$MeZvjT@bwQBp;&EOjUR2gk^DQg)DLu)8J8SPp?8htUXX|PlT=? z3F0L*{Yk2Q&-JQFYWdyU6T(m1V<_BXXj?Ndx6=@Yl_8%BHD-gO>l@|sv!jf2mb}CY z(4Dgt|JY$7Yegi%)D``TnuZYjfs2gU6h7RyHIqhcit3@h8~OJ>M!7Kv3GdA6pY3|p zs=zZ_;98b_FA|iR!a!k1GX2mi`NYH!R{8ls`wBAAMpeBUrvRXv%znKGr$T%|H zRZin>;~~m(^CuH8W(=5wQ`)Oj@S>{M0U%;RCAXXqeiKlqpd!<9EJ+2hlGLQNWPIA8 z3hCSjB|?@_cehKkdo#x^cn);*JCY9?(T7mjQ);+vd)QMwLUJ0B!qyvzU(Pft+5R_v z8ABVE)YZ#745IrvZ}9jhOyig!1}}?#faKlLoz*aoitb4_&RwEy&iIXzrql4>(yPW2 zM@nwX{%22~8jg?*!SO`}XtLK+@eVZ-)|*mw$E zq>f92H`f=r0MLq4Zh*^`?f6Cxj1#*`N6GD~97Sp(vlKL_iz{3#;ERg`6`Bh}sB!qL zU26iJ-*L^`W7AsTs!8TBT0hO*_jp$Hk|n8CXI2GWP+MUpNo{;T z!OFxq^2?TxC_(Wh^+PYzgiF9{t?oz$5by$I=&Cz{#;Hb zn5%9wF3$|*y*7ysi+x={{(ttpQIKuJBo?`nY&!D8nuSW^ix*E$151&8Og{+nYB`|4 zg7XUNkJx6e*OPN)fgzD>z|KkRU}JjJ+2emm^~o9pI4#ItNQSlaS6iNiwVBE82NP^d z1A?-n9)y*6qkhu2ZmZhdFk3@O4rc&$1c2gS?EAYGT=yNV>qH%b;#pu+OB;b_U3e9_ zIt7b#8ntLF5iEkElT^evAwklaKq^>CO#jL(w1K^o+1w<7N0J7KUoXSlsSkO%j7lb% z+T>HOww?0|>knL)?>q8-lbq+|HG@mh-o5aQ8XG#|c8GHul^=fzxS@+5+@HM0-2N8< z2c>iCvvfWC*b=#^nZRu%hK+yy3x#o|ATmVD{}$({>Dc|q2wwhs%q*%%eP%cpw_gq1 z`6zTr$xk~rcBI^JokL~9ql;f=qMHL@K}hvqMTwXSiO!2QK4Ejg?X{YZ@X4Hn!(LeR z8~s@3kut#3uXbBg%V#`BJhQv>g~Wf4+>btS{NU1hACQ0_66UMnOJcvV{SyuMm{Fg_ zRZTK$PD)M-K*>o_l@oXZb3jN)>&g1aP6iw3HKU2PZ9Qn3@oBwqq#rK+18t3ho;3n8`mflTVk62+1~e<|_|c_=v4ltzz* zd_usi-?J%f5PC+LZ&Co(K{HGowKg=pqQGf{~3R zbqWk`0gx&UA4e*nV965gx@!dy;R=%^$?98C`&3mwGyf&weyHgHDQW|Y#^Y&!yw%9Z zV{I7M&ZtNX{dnek;gP&`>4c{1KR#0zVK3U3tB!Mt4Ef`h6MfDYmJL2ucV2jBH!yEE zgzhQpE7|#cH_qlxxslCEal(~23B{gr(})!2VCZz1MH4M-8jD_zjEt1~Il?FQflI#4 zdD=F%bud}%N+3K^C6h|ZreB~vK}xdOT8@y$^BE}B#|&m}m(Jq6#{PpbOHdtMV&FgR zL|h~x=-dQtF!(v?_@}eo)PwvG`;6H7AzWLtlz3!jH=^p{YvQY@PFrMa5}PKAO%@4V zPT)#Hiqh$iGalJ3k;9{Uh8up%X^<5Yien=~e~ey`{DK-1eP_Q>RH5LJ$8mLf`+}+na*{4L8ff8)Hw_T4a z%Vm4cBDzUTkQip7Yo*2FdV=2&Z|@qCR;|?bBCs;Bg5p^QS8%5TVIYuFxu71~%n)u= z#LPqQScf}sRu<|^G5=aVlCJlc&LGuffL0Ae?BCNCU8UhhgU>iFMzXrQ;&JH)vWOq0E>8Zhh$rWAZuAZ*$ zGdTl!poc&L%tfCN5-D8VN$i;~u}toeac?aUVDL{*!{SL6i_cvB7hA*`A2HwUS)X>^KlUg1aygo6+JQ^ZhgumT4@6IrdD4g&-p#NjRUGF>j}nbCaX z+L?gsmwgI0oIykChe%s)rOsOqbR2h-N^QMbilOC#ARkUxLftHe6q?RGyLaiT81)MK zu8F8Ju)R`fTiuj8%{d)XOcFxCBQG_I?xMaKmh(Cj6@bORKbfvFAtqRc1o-H*Qbr=nf;U1fY=Z|kl`(t z`Lf<`{e?*O$w+i9GE{oSi$ROsGJjeJyP{8gt%#>cCfwHeS}~Va!sC6zc~qNoSdC!A zgm_A^Q^MQ9=k06y0sT2Lu@aaSfnb~mT4t=laFPyza=Q;owR#D!)7r<_U7_@>u<*D!u5>XMM+rMZnqG!VnInoX*(7mYA4col{MIoA zA*JubE$3mAx~8JO;VU$@jafEqxEWySQ+O-wc}IcTkRZLMxSU z0Ueu)B-s+Hh(|f-;32@$%mCjO%IrrX_5mpVTSt8-fjAc58odqzNmcHHAyB+u=fS(> zeYvTU(oT+Orupo`$}4|6)3NIyWz%==n@X8u`dBVOX;T4s>r%H~!p8E?RoP$0oaCSX zVEp2!DRB5*Pd%|j7Qzi&BB4b=X(K1V2;zAhr7Yi{5RC>Q;dzb3saHaFNIolkBS$X( z?-g1&yp1c?FQFDon?}NSu1Isj-Wv@dlo#Q!fSgCNN+-G_g^zecx-@;s4fT+ zXO$E z$kUK=x0!W|FAJH1xkKv4zr56x4XgRUwo6*8r?s=&9o|^WNx<#oCPj%YpL~bCCK~N# zZ=4_fEdk0JRjdCZp54%6fK~huT7^(2Pqp@yVBGg6Qn-`;xq$@NsB{ZLVR+s;1u+M- z@e)VcK@f3?cIy0ki}@NXmKRHP+vrkYQp$ERiIhY|q{GlykMgGYrz%}3q#9Mj@iSpN z4Pxxkqoxn;?E7ou&xD4WNA&rroO;*$6WvOtZ?oAL9YCo;fg`x@^XqL@If|0C`3!r0 z^&@Rh1e4j9D`HcrY=b!%~xx%G_v)GgidmRyF18ZpF zg+uwfz-QLGJAkkw?*nf(#U+pR1H{7DzRTf1Xgn%@a+suik+7Ot$E}7Fa!73PJg2Pk zMTzvE2shuM;$I(KPnM&#>=YCkdlL?z`9cJ_GH~vSo+^|_BIYh|^~x91UPK7!uL&V7 zSz{zniPhkafsQBH56yaOf=f+ZuxSHAjpXdHEG`^5tRf-8VjxuxUjS=PU*7>AsPmcp z?fo4z4on^!K$3hjYI-?0i}gpWE~)Rjpwb{dvl#OqT0-@8mc0H+rqvMQaA*1&KxeGJ zB~CG@lHJhzZ$ke=v=^8nTi6F?Q*8(eqbUat81e9r%fqKgFi60}l#61^FL2d?Q?>o8 ze-hgr78hrb+VwA>e%*NxbH16C7Sx>=NfBSFjzKiEZ`6(Y4=ibHy}~3PW2Ibik-h*C zSg2UL=i1KgPXPfRKvRk;%V7*;5<+yezm}g6D8%T+L*G9Q4}Ge#`@%A4@JH>^cXOa- ze6PZS;5%>ZfNh;+nFCr3_&Z8{&(}L7DBWg17q{$ZlyRvHVHi6m46vwh<)$a;>*ivix(RJ5l!ZK z{dYi1cVocyQXtI>2~+S6u2Q09g?xy}V*oQd!Q4(vM*;tX^^;WvP=XwXR@)*^s1pHY zZ#`|Z>tVF+SlHu(NIlM{*oxA}_NF4rd#p*71bTc3O2)%^M3a{Gn!Od$4h34jC`;0- z2a6%=lAJ*8+K3R+pYV~3K^Q`$O^9sKcTrOM$SMjuJxd{g(3<_m{424&6>d-qKq7wU z^z1n9(JwJ5WWrSw+8ym~bZT}tp6&}cyK2Y*Bo|HLOwfBdMV+}!=TggaaFk=*L4 z^9_~8wE~pW&yXYF>8jE19Z^RTQ%STJh4x|&)y|N*PWM7m&%7V$%X%+#0178%83MOu zlvVBEi|9DZ=HB>I16^hUClMlE5&AOSu1O%N@3zant3k#yJk0%uQ$}!{Nmv~O+&m>e z4j3a5^h)EB(be@5f`VFwIkj9WMsZ^F-|sH>H*?I~*qME;HM_JortCY?jSqL6m}}HI z#1Z;xj?jy&VQH7aJqw=|kf9Ep(wj&FM;w3}ssMUZ?)TOG01TjCJed%nHSe?|hS5;v z;q<}D+S(i>|MVmh_^}UOlA$pxb>JI2N||Z1wF)DO#CC7YuDkwsvFN@-#vYig9gka2z;(J zgt)$QEJ!+MT7%DG=WkgZUQR)YW!ca^2^&-YCuo*f>e<_>gruT1f$ZShR&BF=h|YCg z1cUOgljQ3dCF2G05R1Rnz##jnY5DqS^yhe5_A~!h8EVReKqq%UWqX!7me{|VEG1(X=VN}Mo;Lyciw7?d7u7Y}u;#?FtOl^!Avq6(m2h=}I1ww9uMq>-7 z*Sta3FpY)z$am_k;jzbop}uf-SOS9TR>`H~SS1aJv%qYKXI9f6ghOz7EQJ0gc(1()I;b{bs zc!wNIAnEf5*lRA3mnAPg5SW|PGar#c@c(h_?+;I-XA?aH=p$TdTi)TL$3}=g>8bOZKxedrMhqX@v}slT_McF-gXg zP#}m>3bng9n9&YRr~V`nZtil>2>M?E|0KEC&UC)q-7VI6i$v{hch2WrZJrGez!2AK z%3ZYM8!29CbT&|5p!{UH@~iB)bAyGTpcMxz^|2%D)(9pcK-3`awFY^tM1{~M2q2c2 zYc#t5)5-o{yp&8y1+@kJT*!pX1rVd<4T=B=@8s$d4~Jyb2_DWW8zXfskY_dcI{Mdd zfo_ze^$@;n>F&#ijU06Vr&ka8spmDQQA|LH`8S@RxhoaF0Zie)Z*e_puLdSP`j*G+ zG^9NB8?p3W)h7f$=THBpx`lh|b}HojzJ`=kasPF>Mc5PG^msZ)Dn|aG&!myAreyOI=@p^_}uvkSkXUb@gFeU6>YYPY?H{rT(xN!gm4z8GQBPp7oaO@P^R8Od&L9A(f!nz zN}vCz7n(#gbpN{do&cuDf_ zq-X5rF~!y8<#h>vOon*RPlC`>hy+m9Msg214&#wDe#J@}fA{^^Fz%p%;m?O(Rz!=5 z9ecihOS{-H(KNq|*c%^3MQ)rt!aaTa^f>X465=$zfQj4&f}w_61Eh~gDF&qYNvZRI zxIjA=Ipo`Td)P)ke}4XW`SVMfzOMQzru9^{P4)6hv1#8M_D!Y#GlpwQ#%(4{p%f|= zC0)%Yda1&O9k_gc%*a3D9ozVy53B@1FfmcA@VN_WJ+2Dd@rd~SLu38lYc8H#vwc^E zM*eH`bsi;?W)!9Gh1#r4adUIy#}xQqtKJ@1e0fH~dh)ZZ-=>S4Wuk+XC=plSU6PB! zk*84yS9sbT_8a~gb5;oR>C!%Rb{Z?pPsh1#XENFm~`>( zkM+BD?Rta+gqlhI-gvuSxE3>?ZA&wM^TU7H0_tgXd1N7UutH?%$tXm$t+O1+$aGk@2|6%z^i4hV-M)S>wflBio7% zPT>VXcFXGF!F~DzASIdHIhctkx299KkF))Ej8M&29dk(V%-^f);@$Jl9*nd}pdl2M z0l=B#8RL4pD@ILX^uycfO_iNqb$6u2#npFOTQ|gffU^(`AYk*RO~>t|3#>apx~lg% zEyX!)@iZoSam1k~$KJm7t(8~6gb6-&jEl?(?8)d;quzH%1IyYL?JOAh_p-crqE>n8 z5iyXs1+qK8px~~rkf{Ns>js=HKX{FK_vpCy03s6NbN9Sh=Y9Ba!v!&UdHq^+oI|2w zS?XGk1>13?nd?<2QgZlt6Dh)Y6ub5)ulY}yduiC2{!N0fImc!!C{phn5pd>zq^ns9 zJm^VfXke>dIbDDzTHlj$^WLh_x0OtPK9K#hQPJ0-CgVyd%H;Fz=W7ikZYe{NsF{^2 zn%d@|rErCfgb#;pWNx`iOJZoVyY}4O573 zn-}aaPe@}j>8An%r8<5ao7}Y=Vs)`CvR3)pCT+Q?4?s~Og*aKLmqTSxu{>h zjQM$95*ligq^hWB1kiXzZsWPeZXF)(1tU-6r^(kI?c8@}1$Pd*U~K>DAX6wF zz!A|X5j05|U#7+QOOF1bz2?R^83{D=TsBuX)l}g{-M0@e$Ldn+UQVMPna=z{``KvJ z^zMVx{Q2`=V#-aM(7tH-NpqAwN3Oj2?D87R0*_BV(ekcJlrCsCp&fcSyYQ>_P{Qz2 zT-u$v-doyDcAtDjU3p2~Db5}xH`i%XTShJGU?vlOjP0k!!bJ@9_g`XJbf*JMVvE6@ zJ36TM`pxF~h)zTy=g&Jy^ndws4v1{Q+Wuk5W%K8+CGn!wlUau@%h?8)rJmTyQQfOyGO%9cq^ydz1Gj7R_(_eh6ev?|9_ArekCx~FqG}Ffj+$QczEjx zP*Jz5I1@G!P-ypul&|Ao6~n@3>D zRx#>lo2^Jez8UE{Oxqo?+%9CoOt}Ylr!QT_d4mP?c|(`?R%z-LN`B|bX6$}8PuZg< z>WKu9k#gin8U@{AQM;i0glbWI9ogT!FFM#cR1S*qO-F{zW%zk)GM6B%VokF7L%5K zGIsv*cfDX*oeI*&tC=!M@71zxO@5!k&W`xXn}< zH+h~E@}p-e(it@B^cXJ%pAQ@*J!r_}fdsw2!q*564Qm(5t>HYY95!kD2LoLm>J@5} zcqr>K1)y9g$?))O$cwI?$a$Y%GM{68-qx3ul}?W^Wj-91==PzGmzXo-EB0-ww50nqQ2b0*q?`W%LT`9(hrn>XxZjCzR?5JvcSj3C(Q_rF{%B~5kj@q{=JJf{JkoM z!+2s`F~mjY=Q2#F&NT!5N=!;Bg?S&>;?O$I`(51`(0}D9!_~G0@0{3`?OEQ3EgNq+ znZ3z%xtv%8i(G+>WlxB^z5un)&5vl{1>Hs=u>~}ay~I8g9mzS@D{YgxT+7**>(HDY zyz=KctEKjX?#7*!mDLKzsPvlmkKXF~oRh9zZnhm~Dd7`oc4Q!>S`Le+U5QTY8;%@3 z8om8Y{133y=A%*1@kAF##}xS4osmM9O=m^vP~Yq)#7Ah^(x2De<()232Jh2+sAsi> zcc-xmd+AD>VTI4fMvSEnmZKr&EPz^FmKGGiS%uXaMrf$O8#Jl6BLhm_t<%}&Kuqlc zr)Q5JFAr1P_d%+>R$187 zrD5r}3(}1<*U|p{x53@6>NNFS=HdUm{npj;&WaLvj!23-k*jui>_uVD;+O%%Qn$iS zRNTIP-MTmgI7X8^G%ok`?axPJ6I)pPgdZ`e_VEO|6s0$AROT8*f?;Uy3>56|2(imY zhtzPA*P1=UnB(kP@na(bX`J7p*71MZ2rCc?L!zP_Z(6`juzQmgUoiuz7>(uXVa0}N z<|a6rh0B&LlhK#-=j=p`h->PAC0JacXiya36UT8_8W-WD>z*ogZKQsYeRG)iVY<9( z#@i~(EDV+wT`glcmA$deMKpM?=Rv876r3U?v>3zn;)^nXuc~8w49hn(MT10zA3*L+ zI~DY(trlsvquJTny)1Bdc$4RL&CU+GAOtraX$+Ie)Roqa!+D6FYNu2SCDBk`Qdnr% zvq?FerSr7%w5N3!czF#O75f|>KY6mO`wbG|AO^8bTCjSxh0pMBk1qoQvi-A`kcSgD z_p8|Fi9PZ2;w9ICkP2ymmTbZ4$zPhZiP{4VapV$@xy~7te`-PBra#X(i~n(PbI+W- zX3ZK+pe(r$HZ11I4?|BdZ}0m6RQbHRAu1vwGH}=>UL#Cw`SNUoWV1ZiD=4;3WzGV? zCEo#(U*hYBt<*F6UFS3JT6Z7W{W2s(K6O;=KFs;2(+G7ercnPmx~2RyP)Ya;C%WiV zM$gCOz<4~o|7!$b3w4Aya!#Mec*=9X+ZJUVU0n`Wa=#V;LpMb7+$Qof7!;w%BtG@@ zUpkFCgXVbJr4=q0U_ectUS8wEkJ~%B6?BZi@JAVr?C1Qv3Ady1;A<0k>QmGP$t((v zj+VwiY#1CCYT~~~$ZDejI zO}q^~!OPHo|M08&{|(5y{6CR^CyXlBv1ZCH89`5|}ufw{$w9W&Ng3g>qn*O2=eGb3@< z)IA+DR9HWww5i$j_R-FU^F$rM@j4T6aVzEhjN#%HP*+zEM%I7&_ngbVLnbO7JwbD* zqip^H&qsAg;3fwEpzejaWi$G#?QLd`(Z2#{Hsty9=j()UFZ-X#P8ap_+s$jP^F&X@ zbrHn{2)%pxWAKmS%ULF|XV0n^O3c?=vPyT|(ZSZiunBM6KW0T0hB{ZKo1ZLxJgBK} z*Cc*Vo?$#4%V=()9db+TsZIM-@--JQ=QecvHW9KM^PaPVF-x8o`}+O>6J0y7t19t4 zGFesfLQj%7Te%9);Hf-%1=xT2X%f-UFg1-dFFd3$aII%X$EQ!0dk(|ZYw6p{MdLXb zK{wrWtIu0<^Xs0?<=Z_^mx;{mZL8h8yCQ(!M3K2kY^9ma?;*b4w=eJa_D7z->ib$y zpjonMwUBJ;)%%57!S4ye5HI@~{j1ASdZ6VGKG0gyS^Foq-Wbjf$J5ZV<2<=y2s*TB z=NE6efSB7eaY6+p%q~;mR7vlSbmt%z*cLn5tdqT8vNvYVgE~6}RT*-_Z34d3^)T(( zliDRWeN->3R6jdgqP%M8bWp~jtxj()*m&-*HOdc-wA-J$^-566tUA+2#!9ztWd2}T zX+H%93RcvC=kk3V1jwR+Spz8(H^@@=@Sia!ShzQFt14@dHNWuW(u%-zmlwspE8~`q zb&vgL_{)2``Ek~&UFD$^oDbX+7vfxWN^l&Bzy}b4kCF_|`*dW#r@}IimunQ##f8_r zGVl&?d;7LUyS$efs-17G%KEmvqh4JeXead_T6mNPv3@3PwJ#?E527;j@%afy>>^*>X?7Y zCp-kzwY9_G0+g4PEnPj9n|t%YgL(QF`Vi)qLpx~i;~qDz0_=@Acu6{mM>kUfiaRI- zLdC7V?z-x#C5XUZr(4Pn4V4UUpR-IE5iOxb5mD;z-w_V>JL2-;8 zW)?a{IshQ=9Vi}dc&o6KBcOhM?hF*Ul>lbG$=`HhLx zD;%R_MSQws;>x(jFwf3@T6Xl4)6?kBxo#^ow8E^~rZct3s>kubM8aLk-+40x9m=^s7S`=a40< zF(7T5H8cXWJ7#GFoIdT|z86zi=L1K(DhyrJ=&6R<+mFwG%p~s~(crN*G_bzHi5=bl z88N3M@>h=KW8aHYZ(#aE{BM6QzcPw4Q6CnEqwDozQy=-Jj|-Q!eBIvrrT1E?t8~}# zipjFs8P(5&j$&sIo@NgH{`DSR#uU5Q2!%?O6;4iW$33pfIoO5sh((q5JCEf!%u~ek znfLtp2q_?841o_wti&~LpIS~x*Io)M$h!(L+O|rv>KNzvC_{b$Yc@-`N<3882HKX# zH4;r}sDv(TmbSLGDQ8++ZIG0YXs`cK zhc0t*sD_&q5x#cR{Cr&Cn%YpeSUXZ|{qYHz&%}a`P(Pn{5(^Sio*Mc$uH=`?yCIw08vOnH^jTQ7maZ-{F+PsVSfg#l>`Rp!9vD7eH(V2U$6GlrqM>w`2wA8Z z7d$Jma9PWzhnp^a9je}X_kjCc)kE1xTD{)zIIX*}H_1AhEl15gwCdWzLbOcDI?!#p z#OzkeZP{}_sr56=Axd{<{4HVhSOe}!!mAz8OqB#)0T?!YE@!HJ|em`uFZaSM?eDEfGHjGA8I|mK?(Lhv;))g zUiXmJP6?~fmEu5j;9Y6~jF$pn!9@Oi%n55aW-rTk*axjqgH9joscF2rkxx_QSe^8; z7vmv*8G+1|fs-B`a~YUv?a%e2yvL*NRI$qoA<;Lsd&jb{L-BJ=Bqdvs>{Ogv2e%zf zbhS^Fwvyds>!CJ2bBBR%h)PXz?86Ka^-6wh9L4XO|LAIrVw&IAt9tfY^yQa&ewkMmwip=#0KjfaEv z{$`c%tXUFpZnEMw<~8t7izW|yn+J|f=-Bn!G~gR7Ydq|fR2Dk)y2!FkRzy|a?1H1p zg4~DO1QdO9D>`-%q?swU6!&tb^4_?PAK$+pggRL_f%B8hCtPVcUTEw2>OK7YaM*@| zHvywIb1B~x=QhK?#UDO}M26?rU7NMFa}uwZ=kL`^w@}q|pGpNEOlR7br!|YlJ8YTt zj{E1YvXHH*aXSq5WInu{-5z`AXZPw;iTqLv3aZb=q)G~TO_;SN{ZB_5`!DMYhg;P?HHp%c!`;CROtP!FI{3?#g}qt z-~IM!`1QI+7rxwF^{_ZMI&AeP=a8UbVH@*LGd#2QO{{oW$vWoPJq%=L^p8&#cJ934 zq5hIj>-S)aZ`Fk&>S*~*O;ET^}cD@IoFlGl|&xe_<|y#9A%Y5R=QQrvVH$` zZ6?3r>KkP{i_APUVj}XlrzH#z+)J2!^}g-hlOI|>Ra{uVvE>DU@iN3?h0bCk`t14N z2D`z)2|-P$$(&QpqxU>boan~>mQpaU8>VX}ETXO(GYhJ*!eBoKJmFkJFTS|=_;Mhn zTKAC;Z|I%09_hNnMl%SoBW?;2t*i0;UERHV-^vrX=;w2d!hh8og|$Drt9aCAcVJ4x zK8wa*9U0!2_p1yzEglQo!ePc{Z+~9)`MiQ!7$50AutuI_9(zQBqoSnHdOeu(%zl3VuI}jg(LFrfL(LwTiP*x05v3@K ziUM@fSPd7%zp|>+^47xZ?wZGW1PZOxo#n2&r>ZXG9+l(-=PG%zf$;l-$sp z;pFS-*`V?|fw6PvPBBr@doPhAXKP&7i_Ciu^m}Uue`kHIvDMsXz{3~J$gK`t?2DUx)sPjK5m@DzTyhClE0G_Ofx z*=r^TeVF0U-Dr`hx6pdv8<|GubIyRWN$uRxRinunaC-oIYb^&TgAsntNuhNt|l3 zX{W<+jkY}AyF0?lF|+qUpi65PO6f}*&SsBn4AY_lHb+;x_vA zGUA_6|6BozvUO4l{y7URTe}XqbR4OO7h{XbXMW;N?!9WVhzc^Oy~h1*c`#nt`+G)W zHtf{+2@|pn3p#TAROajbTvy6Y{9fzp!-o$8 zi;Iin3*g!9yvhN5{QUUF*Swpw=|{M{*EdJNQt5VK=l~KH7bgZB$8G)?4NfX?N=7&n z9BT>GS7g}bfpt{@G_(ZYYoWhv615Y}0@xd!9lQAdcQNX852xw|I7mPxOvWzwEA1;I z>iXgF%s0ip#fgz1`)uB`XV0mmk1yi`2NCBdSYJNWxx^C)vgYzd<2XP7Pu>YSV0g%F ziNQzW??Q?6Wb!0&wB(Q_*%~A zrtQ1zue*fWA`wxb6EjC`75guG;&>_%`C(vSARN9!g#v86)<(6_^$ShSL;Uu!KEKjH zTT3fw!-fq4w;zFdv<~d%9V$Jbpvr#!v2zP^%pU?R9XtDEJNIb}vCB@B7ZclnQDKrO z+;QvpxnvS0DP^$X(bfM_OB{I`dO3Gie^y6`@Y8cV9~%qJ2qO6J)EP6xK|8tN#)%L{ z-s~61gY@|3TP{t`N$9MtqIYGT|4ze1kM%DHp3S=WtcfI#kd=^meee&=&UFiekjfIY zB6dm)p^WQ1EPJJ@(8gEn~3r7AjUr+Z)ek^=%iGD&*W<~I;O?eGT z0>4L-HQ1W9?r2~o1 zD`R3}q8La}xG#5W2>fC>m16NWS)m#%Rs@g93_15#}x^`7J&b?nZ zo(iHkTNHQwdIdO*+OG`KEw(4&BBV$tFtc~uA6vPM72AThTrw;0>FDY8NI$>r;qn7a zDeXW)+Ok1=!Ja~;Br4QPCs2{X^+^9epd!|x`E+wRy*C03j zPs6=I1oRDpoV+qfHqwUKmfDthcj3gP?_E%z5)5uZ#k=Q!xYqJqK7(J>K*J5RTZS$Y zVW3zTB3q|weI*@yYVK&%9V;KgJulFm%5uVO?hcX)jF*PJ)Y|&?pf96aR8%q_| zWfris0uw&rXwpbZI%9ba0fB%mBozI$FqIX}Q8^P|&Wd+N?tZf(4JJPnwDHFVNFOyy z5?QEAIl7MRWHG(qbbvato07tjJ;fFuJO;n;tkP*I96*%FQp{BJL_fNq2=Bp)la@By zzsOo{8SS+k%cUrCN5rY z0djgG#^A+|88=~uh_KK1D~X@!KY#W$fN??qiFG6*1whCX)Q3VE9+k3Z#0_pUI?PuN!b zHfOI}zgLLof#Mfx_q&l(oLR&=!UF>8T3P}V=e>6dlQ0Yc<8iuj1@5;Pl0SXcL*G!f zWmcQ(V%a)l|EQnz*_>4a(~IJ-2tlP?k7szImO$0xZ3-2kty)LqH)@mM-!Yiq0G!x? z#(mEoO{Fs<={R27;i2KdCcI}v6kx3 zmtt9LfsC`Gis48cq%YQh8P*bD5MNDff<2KSvsZf$s)#f<(#-F5HMX7YWSxD~eAkaP z%iirQLo)h}R&~aX^>FY&K-wL8m*9V_OGXD%KR5j3>7%3CkNp?ZkYI?9B4Q^2+}g+h zid2Cz3dc|*JErgY&JriPalYrjt|_vbgT51T9jKyqI}yv`K+wm~Kotlo+sCQ>S8f%A-=ai zCSF-ey+Y~CDH)=O9Rv6eBW#|{y}bFx+XGHlQpc&Qe=Sx$87E zX5j;CHxXi^n7-VKjx{1PXU0ttx9(W^~%WBVtN*ILrMzIY0R}yw;pZuMROY?_?aDe6a{!iIHOTJj=-|4X?7kkdCgU>H1nMmSEo2M|~ zzHCN9E4Cz3bKI0QoNB)5D%uTI87_IzzP&EDo0VN4PelObW&i>Y^X1M zb-{fUgBaWri%SE;S$wh4!x`cL`xeWINzuc`^>#%xKQHGM>dvg>l9QL;=n>P`->)za zbeB@KhEzEzsmF3ODgu|~KL}>(>A5vWE`1BlavE1>`#wVGjAn2B>QZBL2QH3B$Z%k0 z_*(LfF4L9VJ40di>!d6_tkQL_+*8<$!p}to@4SY-VLm}Q>R>*khNjHsh(YWWMuhzC zN2pBQ)w#@P@F2;9W^z!O|L3~dRH%|p=d~EaelrLH!!r2HKrRqTH+pbQ>RM|4X!-Ic zpF42^yH^*RWyxGVM;KgamLdw+OQJ(}4$E-sYB7N4Zoa&FxUfvzr7~J6TxPrJ;}`9m z#EVF?G!0cPD|~zr%;h}^!Gx0qpvMbaei%~q+GJ{r}&Iks5rU7rqN@4*Mxbalb9V}Y&DpM=;)4uYtZ|#mX^?MzLeg3F7`zZOz9&rL>RzB@M z)HbnjskrZKHVEH0$R~S8WZEJv*N5-*|8U9AbN7ipLV~64aniGnjp540?^foEjq==i z0e(N_`(Fx?#zsIMi5c>UxelJ9uUmHnOkmBy1=r#S8|1sQI+Irxhx1h|p0(q^#OrNN z%3}rwg>%jhsd?_-zn`Jd-t%eJ!8Hdz$7U{Y1K09&bmP$@M?UJwv(}#`rK_8#Dk{1T z2#=QS!_v}OSFQ~@L67qb3AH_{h*KPuaiOW08j^vg^=}NGpw=@ExfmI}g|?iH7ey2} zo%3ImeEFI2W$dHaPvgczE*E>WHSP61w4UaWUDOjHGx#&XyrJlM&66jcXS!w`aCvdn z-vGoP_~Gd$_aPjuD10uhb{~X8H1jOX3A5(yc464a;vR*i>O!KzG%J94iZ ztmN}3;hmfC64hrCpm6SwU$~WzV+8&9_`q?~0L^iC(&tl)V}c25QpQ|4p3?NWB;|HX z{^_AnI8chuCh+9h_l;-9MsB3I03*01*r1?QEqn&@XLBbF)kWuFgv|#ZRi7*KT3wX3 zxALq@@V=&rils!o#)I*ZwXaQwfGLEW4wm1cCtsjv&flJPdu+YJ=QQDc^M1C$BvkzP z+U8WsGhsp~>7o7q@%85MSg!l`ctnw?sFYMHR5FGnLkgKfNfI8ZR3t;D$B?OAX;z5L zbCRgcGYv$^SRR=xg^UqG^jnvr{oUvF`JF%Zan7q@-}il8?_s^yT5tJ7QM(zB2U43Q zGPOrBM5QdB$ugeaPq!lij_03!kt!>IUB+TU|2oafb2Y-cLQPg-1}QoB$@8Lgpm)owtng zoc4o$_!+*og7z&vJ!c4!bcs$S^Mh^`*3?!=qc5&Ww5T1k4?|yGVuVELuYO11j#Cmh z0W-F1m;l>DH*-`xY~EF(Kb$ba%$!ITvLX@N`yb)UZx#L#_2-k4Gh%YEjlk0o0JXfG zgd*J++U~bsMgIyMxCuuvDsSQ6d@xfl-NXR6&+KRk`cvxis<1|f`Bcl#eNG4IEz&oS z*b4Kx3kK3AsU1{SU+)VS^tnFO#A&1;A{;+-thsp-6TT7^H+k#YosTHFbrL6G&KL`7 zLoNCn(@o|VV9QyyagI1oZ5p5Lq}e#|ETRVU zeiIz7&M|zr<6_X?A^suqsIN|WgKt{2j6tF)c^%bqS9KU~+VGrjEItA$X^D-6ej0@y zyoV1}taJmGw8dp&u-ozvf9}hrW?GWrM%V{??0x=KtN7pp-6ziS8{5MfNWB>N@Gc$B-jW7ZS>YpnOO*-!)l!;=kAy9=Bl0Uc|?j|yvApm$T9t_t{A>$W^VfQuM_h7RC^x4 z+mX2wQic!B%4kn*B|356fB^oova;->1EFz0F6l0Aty1?5$~%-IUVBE5NVs34*wElp zNbu5bz9ZLx9a+rM&V#Y|&kD(}G*s8doh!?jvpRn1*YEo9;X{d*18AGkzn*B5N{^c_ zlA2uFiUL>=*p)>16pSa^;npWU3^|Ms+J~3>Pl$ob@F#nCdb4yEvUWDte5dy0^^!0# zP;q)q#nZt*QK^WL^j~diQ8NJc--h_HFfMY=GC4H0GK?rM{Bygl5gkHhs9KcnL3oD-XVU+gj$kZTbpki%U3!<+~zKCH)`H!E_1C_A7)H7_Mw6HXM$Vb{4geUqd zmFYbw&u z?z2yBJ(X^5V~hSO1wseHst%QN)q^`W4@Agfq}I2Ji_5J@!o|X&JNd8+@KFhyJ*md> z*e1t5fkFA*2bwYzV~P-pXYBTg5IcV9Co)LQgM(Wj_s!5vGB_x4_rbJ|PvI#2_@sWJ z^=E6BvzofP{@*4w3Prj{Q}dD_D=A^rprfOk^RGg5-!U(cNVFh+vD#69O&g5HCWk*> z*}izDFWBUThi8vG`@f2WdKD97i;}*l&W0!?m$W}=05p3idM#?75YN7<-x(RU zguU@bmA^=K!1JXa3P@#=We|%9q3?L$C|x3=5SBEO#IR zEApK3gjkg3cy)8AYHLgNDcmkJccO^gs$Sjb(1Cd-@y)gIe$$P zDBOwWou=>5LTSWoSp@vW>_GFM*4emG0i+fH3~@a|aXezgCF)>HSR?39n|{IP;6-a| z;l6lO`oYfzbA~42nZzQeHFq>2ApyR29Ged%htk4Xmf!T0V(A?91kEjk>2%%0%@|Gw zz&gJaZsEKTO$1|`Jyb7yS`QgJE0ZN~*7uJ0&Rjx}G}u?bXdPRhG1aP0VGAUCvWFBz(yFgn3`$L|S-f~LkIU^F z1={YA`M1MwA@Ljctg4UXp9O+P3XFC*_Ly;{fH^S;e}_gpfs)y7`v2zVx-RHx&OKBS zE@vSgJCBN9_@pz}%;?3KcL4q}%Gld5|9G)8)e>auK+rs#ZYzDzaQk#asvXg0PkdXO z2~aS=LMyRV{`MZ^^<|SQ{R@ZtTaN(PKiv6^fT?g*$f%M>>#_A&pG$}nYi@T8QiXDz z@_f`{i|F$2?h#RX)fycW!-wHDXkCKDSBF?Ql;)~ty}X(*t6@@zv}Z_Be$f$pAQL>p z?|sLdL#8GkwwzG)SUXb&gP^ev{guSqpuaM=8Q^1~7goo;Mn``}0yX-L)pkkSX2F{E z1CX`6g7vT<1`Z{@b#55RSw|*K`;#zit(B1A#;vz+2ddgW~#=3)w5#f zOHAN4f_qijyA#8o^&U5Ga7*jJty8z1draoS#fvLt^18M9xg2Rc1?~_ciHzuzFdMfe zl6s{+-!(JgG6D8YsGxNZU2b^XFJ>73t|MT!)&ufDT-fMiBlY)ol_T|{+X5inK z=ry~A7Ahy(A?au5#!pO4XqcEpo-IcTX}`3}YSZA4yw#}wgIC!f>bQLQ@@^kgfv!(V zL>{KrCCSKju;yl3Hr82v5(k>MeUC!FaV%Br)pYKhhNj>WQo<%{-OYF_Z-&+g8s1-&QT3;pQ4S0mM*oR$893 z-RoRkcB@Rah-8`LRI0WyA&ify3v~|N5ZuK_#xd27n7_=hfg-|+)vSxr-PMFUp zVEG23hvJ(}f1`;q)6Wl!JZ_<6sQ+HmdTm%s(d8T8?33DL0I@iAO&odQKabMBfP1IA z5vY8}*a>qFGiiO_^?zspsQCy37fr>A#5cJXt|((qJiEYb9BpD51O?86&Wf^z-9Y|* zP`)Q{A({lrwmurmtoP-4RN_W=`t-X37eb#oW; z$}aytDPhD}62>n_NDA(kpN>;qOy~eWLY4iT>nXC|L&Kc&i2j zvOI;S4eSn??HILJcJ_31oa$*xPC}5YNj;@)@lSm=4Pyqv^Vm}_i54^B)X9^}E$#&x zyQq;hgPmeP!F_S3R=U|s6#(U3xoZ^rqn26-@7UmpiK;|VGR|issNZq0QzlHVXT5y! zpa0U6y^byD?Dxhtn`>S7k$f&2b8F6AIfhUnlxy!lmj8FUHisT+&x+972sI%}5~iG7 zT&LBp{(Vs5qM2g*Sv?yPq&LaEL>>;a6&EkhVLoBBM|uzSk8(#ob!5%5Shd|I@;-Qb=dGLfrZqiXjZa-ZF1Fwt!*rKDvCv ze_Dz+S!+OaC9IS4;nFG)zqkJ757;~)a}&*9T84>wLhliSKFgfhk#532^LRd_p{kA# zoWYSvD?0r#+Ztv^@mJ4OMS4B)dw2%}-`{hCT1KLBh&VTR1t{yPUn}#mTNHfkTLS|& z$7znucS1&v&`rLNkqN{Gwc;Oks;Za2?N7pX;VqEV3Tr!j`>4DjG}#9drWI>plFtLo z@D}kTs~X3!vK=~Fv0-yyERfvat2&Ol-{Un**m=;8Ey;gBO7xR-KOer8z4UPhS;>CSL$y~F?CI`-?(fMHaekRhL-ClujuxJi3=;LpK;Ja60|XN5 zN&aKA9ZJ!8+-eq8`@g4WrrLkWM0BO3K<6^Db~Xg(Ny86ucUp%vVB$p-EwJ9)a{MBf zJ5^KrMGr{a(0 zE#YjaawnR#v!+2?Pbkfu7>5~||B}*??;{u{l!8}iX>hM^MKdtg-GTUZres!g zVtqcxwM!0m&-%bj2KRw+nyzTgjv1vt&gV)E{-!?7Q{m~e;6n1c$ij^@?1CBz#*m-1RJCtAd)^wZI{wl-h3va=XX7a{tdz?Qud15B@9Y(6nt_=3%U><_Bo`Iq&OR78sb^X>UzaDD5FJj($WGUhhi02v4&y^x z4pw?h)!r3G9t4KC)uv71)SV9*L!H9?E@H*tReVM#94#}@nA+8CiUG<9x9^k1Hmm3+ zjqg*1YWlCC;mm!L5HovHi((k;Iec;KgX-+TTw9tIldB>WUOWR={NF>B2+w(|hrCxw zs=klhHCJQBY=E0Ki%vN=W_$cZS65ewq9K%zJsHn4U;wuhTEh2_kN$JipGtFN)wQ_g zf0EJ$Yw+l!RMzb74M@Z2!xbnQ|Z2A9&WwRS+)g zoN_eU;??`Z1#o|f-l<|XvSd336HA;*SDoAGHl7yu6yCm;7(9&okdcd3W~^Xba+L1nMa{4?XWTo_ZUCC?)MW3 z6CL^qEyj!gsS|nH!suN`dX_ZPZL?>LLJ~pK51$@ij`72DON6)FiOMdeEfohqHX0LNCCeS^KAOqXKO}jqvi@L0; zXacTU*V`u0u(yMjux%Uasbz91NMRR)hkF|j2^(dZ)T)RKlxEv}FqprQpP%cIWWJ4- z$h@d^ZKvspA_jB*&jE2CMnGFJh8ERKHlEX?{oEpp)`EQa$+x}>P?%NB&!JzlUesgi zT(yT?X)7p2@C(J+3o>x_3 zZXTVRYVo?FVma$oi%nUGL?}O(CKzR>OuvlWIybbc@z^Q`^OfqbzVxy2ado7d>y?rc z+;S2Qt$yCorQss zk&#UiLZ}e^VC`O;Y`pNxb~?8=-IYIoYEmEfLGuyCQ5heW`F5S3Xa_81wgSB5mD34UgceAvjfX2!Y~D~Wq_ZK zwF{@VPT#g7xp&+db>=zjqbjj#A34*v#wtR}I{cwwW(7|*%RSrk(Of3(ec2s7YQ_3& z%kPSxy18Ut3#=~QD4)eX+uOw3e8)uT?F}a|e=JVkM}1Q_x*QZw|bo6x}z{SOD zuFYLsx+Rj+@hf9^1Edhb0Q6JozG7SjSVneK8X6_{zqMoN=1A&ASJ)S79{37J*PQME z@ov)@-rE3CG=;lb9bP$8ZqKA!t96l?S??kZrs|LkH^bEDwgn(N-X*J1)hROA2RgEL z0VLL8TO(_hYT=4JyWpo!M>i!$#=BASZSsea(0iPFKR3x!{^{kiiO-HN!lAVLrw?15 zZ<98jvj&?Ja)l%StO13weAb6Nl-~GbVf$)&03g1Q#e%bWNa;w#smk#5!#|LLZZtR8 zabfE2M0q?rr31x@j1|VMQ^y+N56BDSypTkHwbe6K)KgSZazENrW=9<}vAJoN!rap^ zwE5WIF9ImGL~$q0`)^ah!2sEd;1Tz+xF`OIkFQarD~l`!pU?MOUSEq<{})t9li6D> z8zi2q8CFzsP8wN9xr3hB5OVdKk!~A&Wd@;~-|;X9Ak8Wn>)OSeZWaNxxS=qCx&H}l zNx7#;211y!AL$zcDj1`2Waf;K*-mHw4w$xzvc^%1Awx`mx%B!hAI%6dCK(YBx@PL( zKR?-6;4@mejc-~*#~`@CD9dISj2P0J9%mS@h?U8X0F;D9(94}c+Y-8|n`hO>Wu>jE zTH36sMYW(&8q>S1dUGsf-ncU895|p%Evs8Ips6Cdazo;+BH zSid?@>CMci+JjHk+-bUB;J@dP=`QZ$&;vZM^2C=$s z$MvH99~@b~L|}Fy;dG`y17pRI$M+F(+LAS=kKnpU&PzQF>93h`Iv84phsw*#k9{D! z&{2MN@Ae^PNrD(@baE_T&W~8S^?VujnsvL6wob4yA$uiXPChDGXQNZyD5?TsBy zR(De>*UYDYV)r|BMgCoRk6bKhIe`q&_n2X}Fq9(AZOKNTn*RwZ3Kwi-9zo_hVDANY zkX5-Eq*2vBO`^yc@{6V8XnLmd+2_4ndLq!j^=WmXD_=J0V{M5_ZW(L1g`IAeoV4^| z`Kcer_lsKs$H0-cKG%|DD3v`_A=9h*!f6eEq}M1mZ+@BAiph;fNAkOqe_DCn57?w6 zRZ`w4aPR>yRw>^0?s^jXkqIN`>a6;89<|rjz}(4dNaDlD$I_a=((WQ-dR*o}hzlAP z9wH=_eyNdQpR+S((u*5sF>m?I|DWUE8dhHbID6(t$C}9=QgX!SDevuisw)|DJ5G zK|nHGoa@Z(?6c(LEVdsGxzr%pl&m>@zRj8Zl@t_9xwL42>twF`5Ooj`@KWIP zM>=nfQ$J2O`k+9@5D2*HIQUKi@E8@H>T8!JlK@}^e23?~%z}#NBFl|yR)d*9G4;q? z8SloCQ^wh!D0QdnC8sN%1tRZc%0648t`_f8Ri1%2FxEp|wLj(h|4ux#2#b5^Nq)d# zI_$)i(M&-$zN@d7iL~}mcx!0RH8#x~txXiS38wpDyHnq&)?}7OJ)4*<=6Jw{E!&~Wr z{NwL`jVa^xW!)9+<5hL{G*@-KPmMpoYmc@kpAvFO`1!MEw$w96Q1JYO_qxF2n<(%9FW?3_zpH$mJQz<$#dS|w#AvAZADaJ0-J zi`T2HXw4m1V6z3&EL#3N)v2prdLb)n0I*l~*jd&{ETdgJBxE#;MQ5Y^|K(caOP?e2_|p2}{rVf4`h4SkqESq+ z5e+>j>lKUIfvkBti3bz;b5i@^NMYr@@*!(ft2fMT?4Ca+T=a!ln>E@7G^30Nv>41J z9}=gPYLkLXA2Ci2%zbT$Cd-tt8_td_$ovK0?Av6mVrD>5QBhOGDy}?__S-5Cg?x>f zaFvOwo~(0IJ;swUt=XG1Q_pDJL|fj;#Lt_u-vjey_Zin@&nBI<$X)Z4 zfi}nPzPR9G3T{Z^`%HeZQ4TKAIFvNC+ek1Fnp9ao|n#@@MEbZebrI~FUY2N})XJ(3lo-1YGC z;lEi+_Mn1@742HnQ0BA)SHXmpHf3A)pTQp-kWeDN+UVK!_c#2x7Ya(xd!=(ZI)|vRmoYmQTlBU)ZFu+UdvHEi4$MaI*cmj zO5cbv6u_TirdG$?F`72OdAXXpqE%)ngNXLvOr$O^sxk}efg>}=3u7l$LdB^q9iMnc zeCs?{uAH4FE?x(JjF}pAHexUs?VeVQ?3j*q`Hul^|2A>*T+K-Qv@o&_7CVNSx8&s< zn-9CIo82^GE?&CCMd#RDHt7(A7AETI_SHlm_3>0%!z}+T1oMSG+!2|C4b$< zF3K{ABJ8zkCqjj>BJNpBSRPN$xeP#J`2mNE-2muvY7FJXYS9gfvu^|+ne{&~!q2s? zqjakerpvjXt2Jbb+W1|oQ-^U?bWQ9P)hBKLcwfEzYSFqMbB4VP+&uL99Vyu7OuR_s+ec5s* zB61uvda&7IG?xK(zP!P=POJ(}(?^~%ov&`2OQopnL7~#cQRN!Uzx{N*p5-DI7QfCO3}>ZccW@GR|Y_pvzOQ)MAik2>?4*a0!!!2~Qjv_5&~TB0@79H))+ za5SPrI*|axAmpT)IMa_nPd&#>-n{PhM0n3H^Yq3lsjGeGP1XkcyJ7IV(X|iTAC;*3 zk1q)8zE$@L9!O>u zbq-ry*m^O<6)AqkYqg4j^$)D7pul{qY0bXCkh0m6H`7++(+ArV(%xDZ)Y_P>(*%*4wFE79(IJ}CGILN>(S+es(jN}u5zddyfRL#>gF^hC( z4bwNl?_93SdweQk4diIVD2#6cRmlupqP zKxTp%hTD&!_q*b#Z{vs)c0x176;ke4(=uQF5BXTG=)UM-u5D)@x66^#8(_c?47jy2 zg8A>r)c zW-RkUC;A!>{Km#IG2_rf{r%Xs(7mPBrh7XLB26@&s&DTJpRf7)EuiyVVjwnUmnKct ztf2Q2j#MN3m*{sd9KJ>ExxHSQ@VLrqI@kNB3BO=wWxa!un?*`4e}1>(ugVFHPAz4S zi2Ps&zcJWXxZ+9EugMe1<$uZAMIH=T<-+NVH5c6c-$8ME1<y+k^yj z|4{!KM~t2M$A(Zs)X|-+3~%PmFpSoTQ^$DgLl}pNE)&D!BE%n4&^6X@bix^wXef{O z=B9pt0Z?O8{M&XQ6J^`voCZvsfmSrVm$UpA+p$g03#8gtAZ3T%e*+5yRU@O&!{@Yk zZW(*YFf;oWf3e=#W$80CecH|$dbT^Z7Pwyr-0(Mz;U_OoPM&PJwnD}^3Pl}^Si81r zC1%P&-u&qnwz+)vuGU8qbwcY{qRV=M-zJy!W<;s=1~*wTH!qlk&#ab(R4Crfnx$Dt z=1R)S(z4(Qbq5$@qwabHO^u8s=&#jbvUTCoC3VO$4aXhQZ=(~dYl_Eg^GyQo6i3qT zBUv^_QztI)=XP&cx9({}T3-vc!V4bC{fJg`7B$(br0~m13{EZH1@7Zr8;NXktLZ}f zkA?KK4IB6lEhy|B>+cDguJ}F0aoENRW`FDK9}+=6XS~STe-M3_I70+QtfotzWt^TM zB2HAIgRU_U_62{n4z9Oa6}&Kbg9@7;(}SpA*qoDEscShh!Sa$}iOsGyz$~^u298?P zOaQ7SHk!g|1BHr#f`@%SN)wk=fR1-R0kI{uB7ZgMbPiqZ$ob?+v^$^$p9&U$I0gc_ zX5RE}xpH~TC^o{6(~r;r;_X9SMBX-UX8PB&=c!HWw=jJ4UPo9%m)KT+)l@toD9^um zbfQ1{VB?UK<=5jIPGwCW?C_;{O23@6|8*EzgHPT3>4iP|oHa{-5LOBz(!KeO4|;>E zyw%LGL9Ze%15`!|0Ew>=v4XBro~K~i0elg0Hg9xWWdDSZ!k>h zzgV$*ONPbgk@od4Mnk3l*+vzhG8Pybf6IEr|HR^1P6;ZUh_Ad3npVFk96P3hCLnJR zPx_ko@^gRg6N+lIumj}Xr z;9_1ec!Q-=33cIo8q2$B>F3>mIPhV$iWN7VCdyq{S)I?}cWvY^*vQL!m$GVnv_GQf z@voml+VKZBpwD!Mc#o3OfpT1tKpvnYi25L|Za$n6+v&Dh@*BL^O2N-GXLG}P3|;_2 z3DQEa)E?1poZ_=_ z`Ko&*O!~m?iDAF>a<1dF_Pf(Q)(SbuBid5y{#&@A+}p^Ag?>kUx&71y*W*x(lS2`{ zR6pZP5b?6JKWdmxNerMR9?~X0`_(V3JQDPh?_8GrrpwW|XsvwcWxXx$EOcBUH+^{I z5o~#6v3f=a&QjXO^BTaiU%TW7zEd2W>dS8GaXbTS@vBWa7Hbkbu`FB$1T7}_&E`O#)XLOu@Nzhw`2DEqgR5H5J$@Yu)7H;|vgyN;+r=-R`nYZI=Sf zrzP%15e!JN@rh+dv#vGD-5srAI^6#Tpqb zchP5@e6ZZ&JV?MOVAqRcdNPJfz!4Tb8b~xW;L`hAenkLXPPyP0T&1iU+(UHSsfjND zAd=xNVI-JCZh1Obbr8;jBc+HMZ-xk1-UOGMuG2n#B&vHXt)lq@mlj_%x$6AqA#mc# z!elbv%RL{g92?fEq{%wKKJ3yY=;wrIOqaId^fPea)8gALvx zYL95`BJ);b^|5ai7rmTr1QAtNn=m42GoPBwzcS|U!AHNS4v7Z)K6}GK{Fb@Ct>}se#Ls?mqNDbppNE zxa_d~{b8M4)b+8BZn6FszBZU`$HoPEWu6^742WSJYM3uk5#5s{O_s5n>6pU!vgU>T z&mU*sW68r(0bNzF*iWzv)N;6Bi{V7SX39N&Ch0__i0~09J zsE-#!xbZvp=df)5eTukox;jE;%oP3}u{`xQz!m7OP(L zWH{09M|T>Fw=pn3&O;=X~IM)RD|ZnpQMk?xgL9!IkmT4SFAyYl+-? zI57>)N%K+F;G*P%{=+er5@+hGc+(s89#-~@RY3;MFg>zRK62n5Us}yLaDq6z7U=yy zrAd6SsQ}U1^w-p6&BMduM4fHe5W57=P{he#f7FLRwfhqeUNj58_zsD(>8M{#S?l6K zyBH7QFXY?5U_!fz2Oz8Zi>Og`H%(1=WEZ`cwrhX;?1JfqRHcKK6w4o1QL;D^Z=*=Q7!QA(BXKB1hNHS zq2!gmjI-T!Le<{{Ew&rY}j1B`b~nQ&}?^HQApX>E;>?V1a5%luHD z5dWj58vYyP_qA+-SN192`bD_hYh2c9ZMOHm*1jg=N@s;{jnI)=THLtm=Ck=`)zKuX zrMmjc+eh(}o6eBpDO_X(#r<5bz6ZBkDA(!Vzl-Q_Ki#xldg5~++X2C`Izyd-Z!agE zzm`w)Jb6~5Vve8dbKrl_m!e5}%t^FbtLiRPf@AK@re;O`B^jxV(;Vul7XwOFHW_{# z4P21)#T{EEOEEYX2F|#Y(sO)maGRByqqdblcqTfrs!K?NjKCSN2JiF<0^k4dRT7?WGm+csd8aQcpU2#k z4cA4O@z_LPT`QO)ls zo8C=rC)IW7Cc6BWU%L-zK6`6wM`??>((fYD3dYOIJpg^1cZ3oKW?KBU@IF9ssi`Vu zzI<^?SJ=PA^wsYoZ?S+E8)dAG8^0>{M^x-S@{fUWYfj3wJuckeB_FmJvMk+X5}fTa z{NQkT!l$Z^?+!_+U;A9nf%UDKl3P&m2I#lTrKj2C`&BY^eyjlPZ2NU8{7#~;jW9Fl z^0;GTh}f|UMlccEta=;D<0`MYPk)1fJZhwD{_?+N^CR{usau)Wt$m{WNeU0GS2WH? z@#QeK0&d1xnJG`CK!3JMY7t6tg_R&zi(aU!b8-tst8stG;P#i(FB&A8g~RvjAy!a zTCFBg2&URO6Fz(ilz!`ssB7MWWjz73Cu%q3juf0@%U#lSOjC1fW^+_&O6_g;G+BxL zEhDWvZlXvC^42^43zoT-jxs4PP;IRvRYqsMN&Pj(g!Sm3Q zhtEC8;ooy|69ix)_bRmj+O*TnHw-v9na$~RXh zPB)|UH$lv66Z%3PV}~!ZK9=NJ$sZTU@)KYio1tIFyCn6*gLW&V@fO|1R<6NY)Fccj z+s>+WLxeA6rgOsfsM_KhrB$bV{O8@fB8z)_GV`b5PHkc0v7mW+5i_$|!j^D?A)V8U zbe|kgv25H%`tn$mVpe$K%e1Ql5FPl#+VozIrsk#^B@L3K2Ij#|WvUU4oD9SJO9fi# zyips|=iU}x@nB!nd147F``wzpk4;mLMtk5=n7+uZR}OPNJD*J5+cerU^w&5r&U=7g zudb+m&=1P^^5qUW6YAA?1W1=!{2Wx+8W9yQJ~Ya%X}t8xX{$bu4Sr!?=#${aFbJEu(=(%h5RSNyB=oxZw-oK;d!LG8U|7Cz2z3zH7+FIu*_tsXL> zyO2J26Hqsr`4(Zyi94Uecep9TGO64c1k9l-(-D-3hjJaeoZNa7-!-JS#_sle2ik+>a&Gg^C&0x6 z(A4ug-{jAP!d~6}+X2`)8F6vUCqs#X_4|-CswrR2C~{_Zw{E;#v~2sgkw#nh>gc6( zudc5ZdFmtU`|<2=iQVFQ2~@EYrtm<{wURo_ZVVdY|@UAuLyPqetUBoF-@H zl~}l9dcFwL)x9aX@>n>zfmooRaLsk&Mcq)=gVsx`tOx!EwytX>h~D_eRZsp5i}S8m z*!heeq=Yy9O#2vDu%_;75nv28$zmwsxsA6pMl?M-vQyf&{j%Dccd@ZB%o-w6vj-C& z6i5*fR0QPElwjE?-g#XNIQJX)Hl!cRwOqPc=LPT8ZaFn-p{hBRhx)3c%ufZSgvoLz zt-GST=CN^`1=DERIc+WMC@!`#hXTAKhOt=7ox4;}ze+Y~^evP$cPqgk6o6<>T!ugC zaOxgViVRaHjNmR_J{dsb)laoZs2;Gds7C1kYJ|YCRZ1uvf0{oi=UYZERT+NglcKkJ zQ^}3ZYr-}N?tRdZuc!Kr_qVSqlPaR#+`$xa^Z#a$JVS-VMU4ePXI3Wh>zroPXhidz z`-m?_agJB{vZ{72%~I4QxrXwYlbHo{VGZ8=Yl!Ew-A3hpa_~5r&$Jd$);P7%`3>Ah z<>1I=dm;;!?7fdq_JE#WP9F_HRQ1*FvWxup;khjL{`mI}PyQ1PFA2A9$&w|>3;m9x zD)3UGCwlKIy)KJVFYu=r`Zf$pCRmy|w8AChHE#wEo!oOt$tVg(qvTVHA}6hTvd;Hh zA#Btv-VNjQ2GOd=jR3qjcaDu)%e_ny^#BAot&4C4SIH0C_J;ZiW1JU9QG!4YMQa(R z2N)n%JlC}s+vnsIzK(l*h6|9jbMI~GSe>@76=AkNlQMZfbXMzz?a#A5vU&XHP{NLY z-S*9by^&<4-CrWRv zJ6V9qhySfxw7%KYSf3iR;vt(DQl-QdU-N|w8G!tma;ZR zskH6NSCWE=rFlptwoLPa;w2VgaefM=`Wuz}!tUsOtdz@G?z= z>jWVWkQ%jXbn1EXG8QwLAUTI|5~FK`Q1h*Qjfd#0y4hzCHM(QHD1)#dMPTElMS(Jo zJBR#2+}=igPcPzd*I{Y!tz?vTK4}ZC2KPyVm;4uKC{YTou;4pnSa_H zwJCHBz}~4$fKeCuN?PcVMKdzNF~1!qMV3{4?JfK{crAgx366deHwKB7F{IZ)FTVK; zq#N$2dZD9{GU2B!A9SWL_>43>Y`l-Rz-^E0{z~aM?b`vwE}-)+JD>VpQ>vRktYy># z1kKrHnHd%{Eu>4bB9sm#7R$6?XE=AH)90vn%4zyF41dsMIWF1RWLbbvhs zS78nd#tcQA5ea|i!M_7(+Z%d=Ae~l)4A!Lk_pC1)3M6*f0lXeMXnKZ;A;Xh@#O!l3 z%p(%OAXBs1SSI(laN}JNh<{{yewI89IB?pSig~N#lC^6^U|8%6EFt(g70fm)QPFyn zAiP=}2F+vm?5it+@IkIJ$CI>xdL*v?$cJYa;{cR>=?LeyI!&MFp5`_geryAY_{Kt! zqXJ2FR)uZF1qQjoj?S2Vlhs9a47S$6cUuC}Y;#ZSzbU-Druie;qID@7oT=_-Yc=(0 z0zKFmAYR#J1gQMssAYcU>Ce;~h%m&Uby#{bm_MtdJg9buThc)Cog29F^49B*3X(VU zfDzUx<#M(1;lQ$j0pbjs9pq*byk6Y&4CO&YS}tttwMK^7N>a5uZ>gdVhbgn^gZ z2z-#=gnHdeIYhY*uc2cU&lnk#@(`)Y(A7(ptiv=RJ;T1EVs-afgC_-;!+(*^k3jq> zHwc>qPLXn~c!A%~M-hg*6EiK&=UOhKP6kD(^#%86k<(PbAIWk-_((yhS$)oZHBL+R zsm(T@zMEeGhdsHkscVqI?og7zoiCNtFCKA0$&bZNGkIrj(@KNl zER4ALH|wqq-lvW@No64xqTrpG=UaD~^(LlwyJ>N(!j9sP&36J@?EDQ$|&; zk$m6R)Wh`=-S+u{LbVtID=g`>vy#Jc2b_7YDBKp-!!OtFb&9?M};`veG2 zCt8Uaa&gIDEdU)bsM}P14t`Q6mp2(cSk@1fHEbtO-mK*fbq{Yp+_lSGI?QhRoYCtdMbF6}*!$PV?9UNAvbgG%O~$ec`|@#qHIT!S zo^Q-<=1k^2uEaCIFa_AV+O(+E%=CU+NgP&0Tb1B?+%|{E=#rNP~ILACi_T z8&DkTOo4mqt{~hfb6UH&c0Q{`OucgTDtppM@>-#Ycxn$peXyCxG=ykxJL$zJ?FM;H zXYKOzjQDX9hUg8Pe*&~jaf}_Eo3z&*7j!5cj4QvlRuK$+W4E*8=TENsr(zux_4l3< zl|P(pPs^{x0ITyDU!y)&c#+BQ7Y)``+x(H!4I>ILr+Rjyj@SKZ^7sHbY=W*or1)F)=c+TxFN_^qmFwlg7~Kq`1HeV0Rdi1zcw6H zU$`bT;DGeBkc7vRgvGXNm2dwiEIQIP(;FpD)_YsITD&g_X?L_Pyn20+SJ86J`IE?m zoPXV8U~)Bu9>0p_9VMkcj^FpbW*^HO*VnxJwBjm|tw zr&!vK*GKb7a9YN5=ij%MkK9^{^~wKIEIqZE$$H$Yw??843KPtu0EMD9MQ7eM1%(Ao z1#XRJ-X-N~!Cr2DES(>zk?1uQ5)XnnBvqY83RV<_Ol-^pp$(0;Vy_larz$+I-e8N-Q(U#D<-GC3LKdZQtLI$YBDT8jwmjY z;{^+GQ2*D;_co}e+bbhl8{+zs&knTh8tTWZdjIbpGUv~%l^rY zOYXgh=XF;{)Nbs=Iv?G$t&j~2FQ(*Kt0mJ!K+?<~>`ARW$xG)(=DNZx^}_Q~ssB=YH69yPbkAZ7WL6 zp3V? z&6{-ZFMi}a*)v{Z*}%Jh$r4~Pe3|7B->$VDJ zXqxt6q~BZB4jU|Gs=c}}shL6Mi?3BoF)cf$=_rCBubLB$F)ibrU$gY0hTTPn7{*6> zw@6vHq_G|1$QY*DX>{%mL(m_8Wv?Tt1kK$7L#y0zvUg?e2- z$39`~Cr-8>XhL@@-*p2py0Uyu?7dIOltCAqHR?BJ?L_$x*O9=t62-*-P~jd^XWufH zU#YD5hlCHO@E#~pjPK&iavX?MvnrgbtStDRb~hjB@R9r-a+)^N_C)_b^)d^+K{jPe zmf`N!o_7xv@V9I`f{7w$^7`YmLppjD6RaH>1UFE6uM@uFy_!dS&RcDiYNTq3xEk~- zUSZ*ihJCm}=cdLwq6=5?a^mGvv+XqR(q2%2u)0Ihm-V{WhMvA)(*Pt2*aGoztrV!8UKA!k|V`nyPqSM{EV=)_(o zK6JM2rANbQg@=Kdzdw4^{c6}%Rdwb*;+GA(vABDiVQGMh(Wnh~@ea}i@7GMk12tjc z@&USaRlDpHOmd6+fW6@G_2vAqsLAke2s3H>@e71AQozaP`2LU zv#F*n&4);tbyIG@K=U;W7uyU})VPyaEC?{l-eS2nCuXUaXCc#GKq(|Qz;(YqnWY>) z&?cH+MgpZ9D-=22q1-cTrhLMky@fIKdv2oSBK|qDW9@!lT8Sk@9()t@5@9HGH+D2_ z4_*$M!~l3(3nsm>1G2}{Cg!z9&SiVg;~0-zpm7ggj>mqu&XJX45t#7N{nPg@2?v9* z+bS{ayuB|U!nHZ84MzUm%kIo^m`6pT-AOm zsncQ=B5(klwlolH^zi{lO3^Cbwt4@SfbP-U zLT_PNfqjvl4!b5n*yWQD+-ud6wT=jG(d%CBD~fu87L-^3j>*DwhS=#ZXNcX{!vX$L zi_S{pMoakirU81DqfB3)Hb*+jnftl!_1??3RMTEu@L&pc8Kp?eSchx)F{2{dEPnL7 zMu!dYHbk(`0JJwWi68!)ncqJt%t7RSF9M%wRO5VQ@4J_$khQ#^@y8jML7P2@OcUoM zTh_ao{VYN6ZWW<9=O@ru89xxaZ&A0!b*EbiDog10v(I#YWGqVJNj~V~ux|5hG5X+h zT+5d61slb!9X<<9b*6*7V~;+%HSLW2`g;A%25I*j$79zq$gX<~-=V|VwsGm^&C-K1CR~e@5Xdp$Yoc zUJOn7fEQ_K`-M(dC2cYE!MqKGdsFQ(-WC7lloGvjAL*uPlfgA8P=5GV)G#x57`oHZHH0UI~+Y9j9k|@IKES zP9fVaZnodBQjsw*_=1hUuk2rtiAmH8V8yhf@yW>si$_5V`bMIx1JL0%@miQUjDjx_ zr{0wiAHKEGZWQWXiQ5}CoNphwzVF^5yiWCLEhn5`sy=jK{t)cCZdwbsSf75p!5$Va zSNM~bc}gDDRrFiR+|Pdb=FNb)^V#mcplV#CCS`>inVs)KS>`AA1$7fq9C{ze?q7F{ zV-KlnqQMFrsNGbeX-}A$nQe!@Xl_v?8Cg(JFjD`!d(ykFs81}uB#l}LG1zp~@C{j0 z?mrp@u&u5iL1Ww+pg!97EJfRfR#;|smi`6?;=ZC^h0Piu;<0DxtXKwok7}ku9ZmDl z4DG8h<9W^~EO*6Iicr;`RC=9 zf8bK|wF;SZLo8C1xn=Os^anbptB{!b2pc)7JJE%&$24Q0dL?7uW6Advk4)llK6XFX z=^}o<)RV$6Q@8)Q5SfYXAS>@ya=svF@5VvTki*?bo z$-J&cWg>1XD&ukcN#}l$jxt~eD@mnzIaL2CpuQgp`RF9Vp5@r)sidq_>afvcsOISM zewsGPtDi2Xn%*8bn8+*h=tzF&>8(r2A0b6Jv2VIdW=OJs+EN@Wu$9-=zB-O((ypNb zEcSey?wT2_^H50GxrHiod)hYyo!~IBX>J|L z!YXBL=oQ%f>b|}N7h|E|!kuABdK=SubD^*DE2|iUZB76Pelpxcu=xsp^}6h$-i}F3 zirH63UpXG!lk9_PO9S)UFk#)111|SIpY&4m<1YixWN)HD5+yOia5t651q#mQrkH+- zc;(Krte9CIf;L& zNuE=zrs%S-upwq-V3Uk^x~5HNCUaAP(98Af+iSFUO0PcLC3ZYk;dOxR*>?hdZQ(XQ zvxc+Iuil|r_ThQH<(})){b|vB@?xJ}E4lSQ{b^be4D*Osz*p9JkT8ujFFt;IL2q;2 zgA;IgzJ->Z0GXe0^}gt87F0=<5?dXOr{@_D)EYgwxh`Ao;9hQ6nOH5ax+v@NOPbmj zs`xs%=x)PmktSKe;AuHssgf5Gy#aQre-u3rVO$wpYJ;zAi0Lk0T=k%SeBzc{d9dV` zV)Y&b9>@EhU(c|?{~`dfGlaH!d?J9qsQabAfYzx?^W9v0Jp10>8{NXHSzcG%A5g{E zowH%pI{w?T+qdhZ*1LUKk#jDxPc!9dZ4~V!U}g4Y%TDCfh?)E5?txx^?|E0i)v|I6 z8wfJ*yR52k_^Vb_MwEv}ow8Se>+%Z)e2a%Zc(V_Ed#N>_l4U5xJW=WKu(El(gF2xi zoc$$OBCyl$Ub{tAQ6_)6+4Q^2(?J-0lqa}w!QYZ+`X{e)j;gDct9RJnB4bxwYf|zY zkh}}FFmdK7e=iH z6|e6LNT=51+7p8l6U}Ts&CXG1V@51dB)y2}ShP*%+%YBYN;?(JqAVdM4z%SgixpqmLz*E*?Ua&x2v-ZmhO{VJ8gCo|w7L4MWOL2g>4ms*|IT1e^y4{){G86jz-wPCkvcz|O+>yr!z^W)o7 z&{5W1Ob<4D#M~FKn#*2nFD7$y_g?5)@98PUyf;{)tji)0WraG5rhN1J*ZCN|x>au8 zeKBI;%_c3E^2(RbH+63iui=%($Ggt=WzRn~UH&mNtp^X*aE1B*Y>{i_tP(K67M^?O z;Ck!3QF~2l*cp`dI&xx3qT6AsVRsHh=)LI*6IH#HM_ju2hCYMv`wHF1t*;|!)3=~I zaNKU(TK~@SnVOZhB;Wk?o(ek{`L#kfp$fG#LuV*V77)j#I%ttAMu1VAlVDoW2-%LX zQq;s#MC*#!DPK=vdSe(dnO(Hheu0z~=KjbfTBPB-u-DG1ABsf9JTLCfO9vGR4aPx0 zvuY^G@-2$4^WQE)nM76)!lK2554K5PhTt!mIwie|_O&h)VrMchhgWzG%kJM z#GlbrY%}zAT~CJl;3)gyzYY989H`X>N%y@xCG-E|>%HT-UjP5`!=bdKjFOp*6v|4- z$ciLIrOZMiBU?5tSrLVlz0#mUwzR3pDq9jEdx!A7Uv$Rjyl=nXKj-Fs&O5zc&*ybL z=6z`7uCZ2++mbIM9>7XiJB(Gy@qpn;izStFM~@pmI{AFu`8g6jPO$9OMfxm4Dw|3P zmN;0oCDbyvuDdQEyIbcxvPSqUz`B@5K32>LwU?$Dy2$V!k}z{A5)%L9`?Cl)b91b~;N%#DPg!h*mWE zrT8L+!Z9)wMr2%<&3>kbZ#qNTU`#5a{M-Ec6~o({Tvoi0pfZLoC+?*bo7MAcY$=`I z3wR5>8(cNA8R)to6TkjfpMOx(L%^UjBu0zPKCfwy5OQu`hxpGFF1#{XwAWaR}%l z`vJ^0u)g+fG3NeKlBf3tCMni@S2SG_osO7^rv))A;EYYKVPBvU4_ z3>MU#lgzJrHG{JFAdxbaIj~`*cPIehiT&xTVyCo-vpO;C`_MDKNslRb1HYCME~v?% z_NA#+M5XOlg^Hrf4CGvHJTrM+s&PY6iyCe} zZA78%h)$8DTu(Vsx%3y?QM4+n-q&m12k^v!6w@^tjyr%<5BYfGtNVSQW8d0PN2+Y;gu-1M`BSvl`JPmC(~_qwdWBCTU;&`BzDzmd0KzRYo&x0yR{0eyx+ zy&kF>m+gGP|4k6>(v;DEBz&qgF)`^v47d(NjP89eS9>O11A->ldCm zTVqyMEB13mBUgHE7h<56Vqf?^`VJ0s1`Qa@^4YqHp1{lNz<02Bzc%YqTey$1paD$y zVek1d4%ZHUz7Gd-qBF9n&dV8}+-ArN+``GQ)`?SU9_L^!S37jHIiZhMyg)nHvk0yn zH7K}D&!jWzVs&G|Bm%ac!P&aIr(}P;pl!_$EMxTr`|QMqh%b3|isK1~3!SZr)vw5z zL*vnAzStp`!$0$b@nukcqMm*0*|%oSlPp>+Y;M!zZun-?^w5e_I`h{&YkczFOjk*C z^3Jz&#lXi4*fm-BCn%;I>aJv#=5$-qIcVn~vG3Sl5pOAZ0Fe6!R<^U~Kgv-6Ybbn& z0yCL>_J&1?TSk061`3$wkk3Hz>hYS?6W z8q2O0c|;95-d1eao#m@uS3w?lKT|g(1P<7{2x*j{QiqOo8+TFU*26E3#PaUpi(kbu z-eh5($9qFJY(FO6M96%yc!jVr@{_ACGRiyD zo9ipSLD5UB@Y4FW?Y7^?KJv`O)vuULTJ1W1n17;Dx=s4L%A$p5`xHhuvvWLV7nXX# ze`XWA7bR0hktm|~TStcuJ}9_$-zK`qr17jXN>g+T8~k_)c*zw8cop?n>e08>vY=7X z2?a}wlgF1ppTGhm*!izjP!u3LH0`q&x|c%U@px<$i5$9;=mU^3)aafH{H#kpxlLzw zM8cOt!y4iQsDRg1*ULpz#bn7sXssM!^NFZ6M6}+opYcutk>|6ii-y~o$Uh^Q!}shR zQbZTI^P{D>_rr|))zCyItg4p!b%Lkw$|I+xw`J7VmADlO>E;04=tZ-Wrz9<4Tvn#CUz`k|bzPKi0~f?=53yB3D#Co(5CWtvb=Jf6qRD zKepkJQW*0QO27CypUPXJe6N4F7rf4~*?!I+wrBb%jCNRHw2QZ?-V@P)WVW-p&9dg= zvF_?^5r8%)o-6W#Add)u7FkYDkI~OU46)Wg&~TPFKjxe@UTn5c+xD2^&CO6ls$QA$ zyH;KalUQANMh^Z_1;rJ@b(`peLQ@!q^`)1MzsvH(uc!h{i?`fB?uSX;-NWUTn?XY` zgx78Ehb&B)wC)|@4P=#0+|g;fvVTMluq5dQpM&@# zShHS*Gr)jM1O6(Ap@hbhY2a_)VZ4%}dYvnsP2tJg>n(#!Dw{9?;ieMfR~_<&VhioQ zqKVIXH4yacUz|Ho9+!6!asz0dl`1=NkjOa96_hNiL`wfdUD(Nc!{4*k+o|)0O`vIq z8rFLib&eEm}zzCDYD%bxBMQWO?y`|28+rg=W>6=CSG14P3U=#Ox!sKc`3S}$Crf?AvdfmtDCfBkK{yyL8T%6Xd$}r! z%m0*>?pr^GagcIwpPE-VWTaT){-= z=2Fr01l)P;90D>iqtea6hQ*RH8#M0~E6S6vS3i`db{u(umv$h$;9_i7_d&$S3LzJA zltT|wqD-*edLgkev!{>pMIlus1gg@ovX;7w30#B-J@5H?ALb>3SSeXlJc^9<|DQz# z2jvl)sgS-h0lHxoqI|9n=eyd3;@QDM!fiOmy31q{9A3srki&XV9qO#QE#wn@GMoYJ zDHD-0ToxQ)LpMxIVbJ*?Fb2(}_}A7jtAQU|v0Xm7J}W#B@Z@sBtVf38T_-CbZ~*c^ zDfpKe&fQ~gfrQj0!&=c0G{xlrhE#MH{CQhwH{UNs`31RRgg^V~(bJ-vn|}<<&1bWd8pY;XeND|$nnn&)D^C7{(8qOc0fcpRZb?hWcNfGcv;cj#&QSz*~l7?H_%ET{*ZoDKRB%ez*U_Yki zbOEzSKmIt8Y}eCv5N|BPS2v?YmH+fu#Y1Gg@&3lzwC*?UY}Dfm?@*Cc&=VNa%`oxt zDMrC%^5o((Z{7)!w_f;SE9(62(ac`a^=zT`)dtJ$Om~HY+mVq-qlm7LVbDXD%=<72Ri5FPwT~7#Q?p0FX}M1syR*VH-Tiitgx^%EXqSf|cVJ zZ^8G#E zSGhUv6X+s~C~AIt-Kn9bsm%Rfj@!=%r7)7MV3~SaJ|M;XFe4I};<%U%e=bf!7HjNb zn?(adI3}|$gTs(%K3rthdm4lry}!Z#t(D%`k>+P!>5gZ=xX@EQl@&59G7szT-*CG@ z(*egB;J!yF1mmTz^ib}cJrBr17v?6Dj#Jrjmr4h= z>yV1>m32e=_*MJbRJAIZsrDrm1RotTl)D*udGCLFE+6@`R6+&?++?Y&XkU0NrS=u& zzYmNi4Vdz8`?*Y6bjwd{FR(ODu~Ooq za>~_8cy?lVNCbdZq!#oT5h&|~^CA#3TOP`-`bFo34@-R9GZy3lNt)Qf=*a;pObl+` zy-K5oE%r#AM`nQXbKbgDgnYVZK+4E0t zHczl_Gfm}wJND0iwpd3d;&43VpiP^Hk2$(kM!(ERer?_g?0}g$x(R%cigX3DQ$vve z7W?yjHFy@$bQdV(Ab7SmzRYQQ>e*pOcz>||f$0C+I_J~Z@DgvU-KfuV9ZThg(7?yI z^BpUQE4{k4-J^3W!Dv!I3^!SpSw0Z4?VWD5+`~X#5A6#8bjh31^cY7&k50)zZl)*c z32*}+HXbaUbnSk#Msk;JyuRVHw)DNX{ONgqCiqc)_FJq04f$;MDLpygdbh|}9oScE4SGXjFGgVNlbB z8JJ_#+?J3%ToBS=!iq5DcQ^m%ksymL?M9Ty=8FqoKb{eT`$c{A1Ej(s;$eKN9zoHb zB$1cG1=31HS6F5Wy^6o{wI4T%3=~6 zCgbir<_bxV6x>XT#8NTz)LB&HvRRmvDYb&2s00)0&=ZO)%e*ww?9WpW8tO2^GT1n}5{BtKkUzdKlb=++jCy+XZyRc~=5fcJE;v^>h9IJ4KtA8!z za+mbI#mB#;+)(}+7%ydx$r0cpV9}xar299nz?kV{&rk^(r7)nWRk6iyDt*`oW4(93{!?J(ibe^Ghe4KXr`puLyGTaN4laUT9 zwVvx(E2mo5{`?@t=;wPpj3qz0Z0({X$=v{l4)M?-GKk{8-Gh(MLm%E;Z|o6LFQj_f z7us~QZ`!nybgQ8ce2!T|7d2%f3gbr-p_Fq!3h8EVbz3@I8!0rH;8c3ACvj_Y)hj2B zv!CKPmak=ZthxumZGgIx7OgO8RC?jZk5e1Ypc!L;SCQl&z-Fupt7M zV(@V?MC?&gEQ10=`pJFdPN=PbU{|i384igS98`vv{@_l^ndmGG@n|>U;NQe5sT>1q z5=Ci0S}GLr-XcYkPqEJ+I|DPb1^DKN(Q7ixdYpf9yda(zco4S(0L2js)yxofaJ%os zp$FkV_8_V;L3KzSI=Eo~t*gT1IB%yH_wXkjqjCtSeh3-`GD7w&^#ZDs*=m7XE0KGW zeC7=%F{(N!CN|e>g@`LbTR-&1(W+fOKie&**7YXT=vQXj47fO$DJ;IVc|qI^ZzChK zr94Td5TSQ`O5TQ3b1gm@7aG&=f}g@#+7gvl5h>7@js(x{saVhEkOH91@D7UEdjk=T z7N4AFsYU0-9n2OB?)H17Ss!J$8+nXeerbW_(M?d6%aHgr!tQwvyVV`FxVDe;5fy~p zFhSe$eLi8W!Rl}QE_!-5A--~g*a6Lj@fHGZTl1^=gt5C;qHe1meO%5H8{h;|Fu#NV zf(f*+A9RBL!nflU)>ECJ%13Z12dHAq;Av0W%RG)GZrXZtfB621O_oK_;MK~r{W>mI zk&kbU%D&*Fx=YBTwK`rxd++S>jS7)n@3}ir0XES7&o9<~-g#!JFbMTWhk1re)?oQH zc{5&Ds%s*m|Aw3T$}>LV&UNXj+Ka8x_tN;Ay_6$s2IS|wPPRcH#1`=V>92kq9~8q+ z3M72m{x*nt3)Dz#QzWk~{*qx6UjP)Y@}`6AELkn!6v?Tc(+Tn(p!D{K?!qL#6C#r# zPEngMLdhmJ9$m<;+0M5=cTOh1c{ufys3KgN!fnsm63tucZbGPuMCvKL%B!d9i~VTl zioTt|^P1eN>)VrUJcp91$Zn+#TP=jgy6|#Dt$$Enh6vy7k4|4R23IaNTCwY^-1~ui zWs3$sK)YkXQs;gS2aA|$=cKjYHG7?OuA58(!~K7l|Mn+aOJd087dX+7vBe~VrkJzcof6tI#H8sK_Y`7Y*|YhH9S(9! z(k66|Xu!_a0I;_24-wNcI%b%^O!Ohm?8@9Xk<^t?ely}-{#7!29Hje+-u{E}CQss@ zbu80R5UoR4XlT1u7amiG)%7!o?J1Qxng3$2s(h z>GXs|opy==u=0Y8Kb`!pLpVIGDd0~ssnsDniK7B@Z;e8NZjeTz$@kBLEcdbO?A)fe zYmTj&l7v;rQ*Z*l%^P3Kv-Cd~|J~9*@-$0#<TNpw&Lk>YEu)A?Y2nE#98pCI#I^0hqwS! zW8S7{x`)#7JR5*TW@vq=uwjrvNdGuSG^g(+^&Mn{v(aFM_U)SmqSTvmCd(YVKwA3R%W(qZ;~yquWlgW@A1`UK_{QV6Cj3H( z%=cT@EEpHhitlQ`NoD>F?frKzu@s8;@SVKfk`XrqHG>3E)CLkwWV-s-5z}WRvq|De zOq&K3mIElDzMXYo4ME__GmyU@*+;7s?U?bY83wPJ=bXc;+@p9)kkxgw@8z-TVd zL_fjn{sG&yPGn-*w>_?IU}-C-U<#c2&K=-B!s65V9DLKndi(q3;)B~=&pI8f9{-#| z4=AIZ{kJ+=2P;fYx?tU*F|x;K&q=Hl3AIaf9P6Lxkb?G;U~-o1W_yE5LzXM_h<)LF zOLdI+im8>aDx-PQ(hk@)nLnpxOYR*0IyeyedFhLloy5LIbmN`Df4=AMpGu1<(RE@J z9f~aZ9;G$C)8dRyJB{{Sa$aQY?_Yo`=R-#vZ%^YO(>lb!v;^YaJ2+QIaU&^Y`tUx$ zs-(}%2YeAVL)fU~^l-5@SDkHxx?Lmy(q%YzgjfLw@`0f$C_AlZV7SqLDJKS@TaqE3Q9k*>(DhU^c90w6K(47ukNYne*=~#Mdwjn+! zTuKgmjdrT}y+IFda_=osfB0*}p2u|vW2weMmvf2QsANw&uZ9G}o$VTSgkRe3>TzG8=d>%ZNPFeOL9g~w3KS-RR?SZ}j7?0Gw`W<_xNF(LTiHJ(#N~X`(?mC| z?z7ac1KNt=853TF@O|$ZMU~Hr%d3n`-S-e zlR;<9XTrTX(cl2~Of{9;TrO{_C3PD{r}?0RCZ<9+VBo?iN}H%|Cq8j?^P|&IQBe$j z$!eh}mqk`xh5STUM&aOkjXOiAF(l<&KJ5xy@V&~=tTyQ5V6>oaW3YRh=AMyD2X2i% z+dnwJo`_A7%+cGxo7;D7i|c6TNTfx9EBnmc%)&FB)|TBBo9XB%q0kTphKJ;bqZ59d}~dTgP(zCcR92acDOHcrwZbsXlsITf~~6>S%$cvxe7 z!YXOSrHEvQhqkeD-d?$r_n)0XU(?Ke(6XkGx2Vt3%D^;Z)jLH6g|Gq5w`p(Fc*KMa z!>1e=?r+}ACabDW?_ZhEJ{_p9JMnDWFi{@O#u}>C+D-jWA|WO)&o@%NE8p|i&k>u2 z*x?9CQP@+Ic`P26w6*i>eX)HG-vf7WyS<=F3uZL`w15Az*$j87M8>7tQzQ?#+m5_# zwpKg;!UBK>{-3lC*1J%D5Qi??@!54{Rs_InI2yg{aUh6>7 zNUy)hlGI}^4RLrTKH4CRYStM7z` z$!B!YC9=R|#@|wtDk1j7qL%jr2!qT4$DTt}p>Wy*Smj^roohB+73OSDqXc}hVE1gJ z!^DrH&cU`X#Y1N2T>JyDaX7fLpp$0J&3oIA(=Mr)sY;x~(vT^6S32xUuPwhDJ2r*sY z-QIui_@{L3eZVYk0fKB9&C(HD?u%;d`2Eezvgt>|oUY&SG|w@f-TxW{%9|*y6A3uu z{DG5@%YOo6$=VWLAIl?<%ypX@9C$2S+cXRT6b-I<%)C#%@qkC0!{rreckl9wGTHqeRT|IPe zBbNz2vmC?uzK6M{z-`lt*0PNQO!VDPv@(xB27;ZHo@2qaw2DUV8UcG|t=_D;61#LR z$~Z|fr-`=tpJP%gN~y+^>z*p1i;CHZp#kRSMI&!mXcg-vbfBdqfQUBn+CtcD@k*{; zNx0hB?sruwB6ldo)h0X5V(oKr!=+TrK-4Ga7zxdT#j_c;%P!m&4;KmNO)0h`cOIX#G>~AB zI|5%;{m=L1JdG!zy{m(UiqfDR>jA>W+P%}Uzu_<}qM3X4eBfC81^%Uwm%Jks6aXhv z49=v)w_w+gBwx1LS5tOcY1g?ntAeLE{J?J!?l$vFJH0r*gLgt9p$K*pD!J(W_387&v0)nXrR)FfbAQKwDzb$t&&pWh0}l(DNXkZU?Y z028);`}S?%v9b!l7mB98-)8UKA-YKhJIg&k+b^c}aeWlJDUg4mMI}p<_46FqY_X#zT6|`_*@aSNAanvL4=Tbs2#&lmzk+ZEUHx7id^Sx z-^9k$z=yZ9!H2>giZp3#H{*mAN5!pr8uwO7EmaV=h+GzLN3Hn33W}v9n{4FsZlG5p znVRa?3HkfcszJn|E?YMyhs%Fg`R+v&E@oXs=o|t$@o-&p?dFRiOBuu z=oiYKEwrkyU!S3_dfPuN>5}{4{S6Tlkt}?<>VUz<9Al|`FrAufWUzWC5Kgs0*7mb# zo5_~D*E$wxo#-OFsknupG1 z-sA~$n2dF;>sP4kn#&(7Ct{8_U za$Ib2GGFdip&?yMIxbL)tU4pJ+M2_PzX$G8>lw<0x`>1P)gi5u4J}>1m(=(T44xi%Av@n-93Tny zzlf1nZ+UMx%hL0`^2h6eBD((xLhv}+YU9%PcHb~fg9ayTanU?)CC;o5tHDIF_;l}P z>t{1S#_)2d7i1O=JvSPC$oBlXW{0mPDe z^dfvXSGbu4{QNEy%l}@_?^s!ID}Ase;QrPludW>sY=3n-r?$9c((&i)Y+z<)=1BJn zdfqCT#?+5p84)cFjw-y0r7_es+idDTYRo*odMc*0Vs4hlv5M0_@aoRiP#$;Z^d}B! zKYyL84RaE;XIy$fgZ%P#h3>KviT|TNFiR&w_qXdz^$@V<5S;j zG4c(TDN1WH_4ADjxRKw8b#Q0YLvz6uXJt0O%x^9BR1~VPv2Mw{9r-SD#}0sIhNIRz z0yv2zg^kk|xu!X_ah?Za_ej1pYawIj7ER8F9nN!k57Sh44(Bez?jDWVGsowo(C1 zg4+-=$IN8y_mu(y_NBnt`WYCt{P5zNQA3=T5jhvOgtxgPf8@xGJK5^wHc6n1dN z%cazZg2*i1&Nv-XK5mj3jaBkqh(ljDUcte^VWNGnq_>K){FTk1B+F!2|EJiGhg9ox zSBE#$N(WyU0y>GWVg#uEjkhUVJk9xL0Qg|G=vhJeLnmIIf?3i&xiC%T7e3hw${B|! zG>R<@30^jd`B$CR4x-Djx0tjF+_0hlv&Kqv5>E7XzfT!ECr;V&JxW@n7GLXrf@tFClpR7X~~sB4>U-v!YUJU9$^+g4x1{21+krT6;qdUx{`r6h`@)9vbee+&8m-^4`bf?N7^` z=C}u2INrzO5#6jx4fZXkk{( zF6*(|!l1R`A)CFEBL=zmjy*h^HIixWma7tHH z%R~F> z4OdDJsbarnb@QoWcQx(6%-GtAy2=5mv-KI)KZVI7a$nK&(HK6umeH{tle2+er0kUx zmeby7hD6tn$}r`7{SBK-^6gu_xiXf{UFk)ttu|BferntPxxGt2VMmhldH@RGk?5M< zDkVSL2y8-_M9p`R5qD z=AO+^7s_swx)rmPmzOvFuFQl=9p?GpW}O7z9F)x-EAq1P0-{G*(@{!{2|5#qZQT(nTj$q>A;vC^L2&RFe`*s%s4UzD zgsA2AHl~A!xh2R1ANg03O9qZ&|M^=vA-a$cD+%4G4nPncX8wTG%FRq^>}f zA@W@igFSV}AD?MEn$qVWMJLh)(CV=ybAwgyCpJ0N9DZ!9jCU1CJeKm)s)=nTY_FIk za&-$1$5jK*6XcQ}X|wV;blhuFexyC-=J;`!Z5k*RtE}$RAN>;(6FV`D-W5@0tTmVK zM?2vB1rS4bp^6rS%`VEBd{q|OWcGptHHqe(0;`k`#0qS9Hs91CJqA-WEyvP7dX~QO z@P0hR;?c+9V*h=Jv0Fl8JDdf%cf%&Uv*LFB*0c3VZUdlc>g63-C zj#Bv|FRV0`l8klX2Nm_bPT|Nv2`dAGY3)SRY9NC&BBD|7m04nTzt2heBxszWVpHB;RwO7 zPbx-y?PQOF|F`r?JiKd~!BI=M{9g}`Q;k#R^}r+Kk?xh|eve29z0ofEanBZDJH}dG zmE)9=71g2_wbaa;*RNBefIeg$g$LVy(ET398m(#ujMSo_1e5nW8%=Y#HgL6jQ8r!n z1ov2_y~#;m+BZ#{-MwFU8l(3h7b5d~6Vjl~++R_jl*7C#C_meB8uX(exm?)6I%@0- z!nX=^4y`v{s7nG+29$ip+Ar|G_}H-V5Y+bfT{{0!yp9kl0HYDXtX?AH(}e>v6N1y- zlmiNxw-W`dPujYz=X&#oQpQPXpS--hR`)#QCl27?cCXyL9(n-h@A|~rCd4h*S{u+T zC^rmw?XIQ>L8dP!I%+j}dV14j#&0U@r6RE zFC`FQImeZ5pvfSc28Qj&KKNEYg3d2__A8P$b_Y1 zRDhLn0-r9n@|}};eLps=$+zw@v13gC`usB{56ivhp@J^5CW*tFtO-9PT^{fs>G{qk z`08nQ)r%Pf+`U*Hm^>&1zb1^Q7^pSToDumEeA9degmH@yTu;bh1iPQ0}x38;BjE4f6&7Aw=3ZiWLPZE9>!r*?Tjsv-Z!UMBy?bcyHUWbl zYgTuX-UeO{p6GF(?O3*fD+ z(t-o|%~mXwU=W8Es79#|;)&4duE ztSDMblha(dIW(fht|NW7WzlQyb3XIM+lZ_FVb=M5Bftk12{~?3m8$8`T59b2xe(C| zj^ASVpQeSC=j8j2Npkxzo+Y^YYb)cN5WKD|HC+i8XPq@9#tEa~ z*uD&dY*oFb>$d0%TNy772;@sGC>e64gJUoMPueYIqP!(&Q%~#YcBf$e z$qY&}71bt-t!TBL(uBauxO4@j?#aZXZtU6 znDuo*!(jc!jZvoxkVIM?Go2p`U=VtxyAu>|TNz)lfXZGiI2k=WoOFeCw=Ji^UPBm( zLf$u`Zp0m+lF=8db|hQUs&DuRlA7~ii$#%oU~A6BLRvu^P}bfKNiQJ42PIBonakhX z_Ug8WhlkRaag$Dy5Sa+E$nOap+IVX2U#4ZgQhI)FdTk&f*2BA;4WmUh7Pj$)oS)C2 zunhCAklg}ZWbVip(o^-qS$?LLn6T9LNAX2_##|NY)Jvj|tNeD4;X zTm!2rbbhYuvyt}+$GeYA{i%i>%rm`$Ll+-}&uN4_*VBJJ5fkdcfU6-Uk*4BHXA7ai z_X9(&Wu%PY$^8Z`8OCHb%qnSreiwV=5^N5S(r_y<@XJp?;E;a|?OHi5y9iIBfrqxs z15Ev%;pXsakJ*EGk#~(W&~}?HGL7~|?Qyl&+Auk;L~PLCgI*J?H!kK6x_Mf+b6`CP zMXG3OOp7$-m|7vS^E1nNon}A7xn7mIlJl4iC9*hXACjI{6*ybJzX3=Ost1EJqDclbd?Ro)*DSW(cZ(%P{ zs~hagBIm*uWR*Y`3lWEHVQF`-p!3o<$geS$QijRRFE(kn{r5V5S0WlXdb#|3;eS7f zzYkUtwTO00#$&@g+vmF}WhWpYxVE)|b#CX0wSPs=M_HwSKk~1Y{dqEgwy+@CIro5%{p0mjz(U#c@h!OG|~1dqZ5*|`euqw zv$Hwo+S09j0Yis`{=x##3fg)@^GMt3#zzPe6On4bDNhx4-T!EZ%Jj{zrpE@-xqW16 zLN+-zeImkmXrWu=4*nPcxx0+ml;s?X?5?~y{8279$~*RZMT#k}#Ai1_fh7jx z`O6sK8;(S&{q58IS3&rZvCPV@(D_&`S8^TOuA>hy)>3&Z`VUdZ=L`)I%ON_!`&Cx0 zrI+4%hF4qgU@?UL0{HDA6v2r4`a^aL*2qHKhe$~fEFvW``&dz;xgRLAD4YUAY{p+5 zI8y*YmlM;^Xdf3e@{YK-LQ6vd`T!OmohpjA&fOA@fd>|aBDRG#YN6Yt3P>=%55 z&agVfA^j~Tah(uidondDB)Je=?9SuZF7F=_Ao4o$;i1jxMXp)uZ!`|kH0ZQvT>Z6B z>(gJzl(ogjr;zl!gPNf~|C>98?R`HmK5(bAea42ryX!@Ah>zupo*gPE ztOs@Xu3Kc4`smS^e?5h*TPM1o)bkjI2(AGQ*^wPwq+HyOEwA@9H8wJ}Mv1bq(gR7G zN{xX652n=SHG43Uxrq|+^!YYG8Ca;xq_SrVoqg*=m~S!9%ng8fYkq(z>py<{SZ!?i z^5yRVm-9Tyge5-9*nT)5GKGB{zUnq~+zbR(qyjL&>eTP3~ z^}+!W#6KwLfN&&|9AOynj)|_o$2}QbiZN4|)Qh*TUX@{G4M?--`qK&SR=Uaqy4iBJ z?eea;cn?p6St^-=T?g`x{b2_--G&V6!E*1<@p1HMbj-4Z1|f&0>h@X61+`Fcjx+~0m#op=Y} z^XDbwA_`3(r}?k+6$RA;#z)F_g&8Sqqd;tFyaz1Ih!_%D@76~N?94#?cu69(pblsm zxLQ$%-{<4Ef+)7KyY+0={+gc(CEWc)_rfa7?l;BfwSLozX)sK(%YPjpwBF-ehQ~h2 zEk^$#JEz*<9OZ$Tk$Zq~sk}XR@XjNZCXWha%|&Ax>?F90MTLY8j%&P~pPLP)myHFp z5^6;9Z{U&zBH_@&jr$i7SXd`>A&fGJVPxd^*dAnw;S&{{Ow6+%u7M1v-Qs`VFyA~ zUI}f~R+QfsGU`beXW;@8Cl)^c;43bP%JR8a34E`6r$n$~m-zM#x zXKh3Ed(4(ZwyW8@`xX=4ak{+wGCZM+sx(W%n^TeUDJFKWfxg=Arf>5j;dK_cf$t7^ zv_M?$={ndWdj|~q`Da10CFaGNW;)STxD)MW}fKhNYc^keAtJR4RxHSj=!+M#j*QwWG?1yA>>sBD^|#$3GhdX76% zMZI>^0wLOmq6ohfp{_$1t+@ zxrP1FB_2C2R!)sixLMv#dIwZA|4L`Sf3mft&|}KAbP*qDi~Y5sB0zDJD`Ly8br|UI1}$Fn-}NP~Jo%||{iD-% zh2QDcujhihl~{^4c95hy$f_|lprWI@jygu|ScX2oZhwZNG%M7GHnJ=|#~Oy8h!?>b z0|oxV6Ai%U61;J$+u_59)#B2^G$9e~nk2nr@yaJJ%8X$UNbvFk_c{CsI{_#DIwld4 zA`F>E>JqvS4U479H#_+jmXQ2T?!&Cjm70UYAotva zC<<*d#fzXu=fexx75=tHaL`G)^ftT|dM_)OcglBE#z}NV^Ki=F8*J?xS;oCIxAKv} zk}lV8o5O!qWPE&HQsFUV_(C3ysQ4U^?0g@o`7T1R?@eVlF)~JmW=yTyZa#_A&)7H zq|=i-MaFcf2w(Eh1q08V~3igXxHQBGSqTCRMwOGhj-jK&;~dkQkThg zcbAv<5!E)s#OAMXvYn~`i{T@GME$ZCoS(%q`a#rYlgMAdZ>O^4(By#n!hAcl5PxGI zHDrdi5HyCQ`E^GK0v5HsWupM}G>L&NSdcLfbXOIS?Fy6WJ01W0Lq; za8F-5gp?fjtuzLFL}Ejg#t}r%RDoryH*ykBjj{egw)yE5^qpFpT6W|&9>Yo5%s(%u-4`F@P zQbF@otl+5*2K(Q_zjRj;FoBegJ!NQX-mQ%knTv|aghz1068@k;#%BiFD{SR_$fMkgjTwz+*ocM3wc(zpZbV$8@UzIy`m z55}J@%w?{|-n9DbZmVL9wYvJN5}4}WA1-`)V|G%{@AV6XrFV8d5!F-d&m-k4{#z^T zSpP`J&K;b*>SBY1+iqY)s-HX=zkxq|+g~rf-H@`W*crIg)Occ21|_>EmLkv$*i~`` z3ZS>E59=)4r}oqJC?oG)ge#sy8|`0gB8`+C`&?`usMXB3BHZ=mIZ@~lloN*4CR$<< z1$mZsv#2e?GDfDRBv!UK5scs{yw39FcU{88ZQJ??<62i}ercqCyd$Yiyy8N*{Ux0b zC;<7_oRGjYcE8|Eh-rCj>lOz-{-qbn%7Yi0lzd`QhZdja@8d|-&vh~rFLV;4cmlr& z&3UflGaaBthp2aJJ?m>m>bEeS_bQ>bAy10f(mhM=_ii!wMkyn3^5gV|J z)hRM|7+7xP=p$ZM7BW!^RWktRByYpkL-K^bXcav=HYWPn0;F$%8^jeY?dkCjPOkC= zl2{!$gag{h1G*S0m<00Z+guAR@$3Q@jp^GqNwc6%i_agrjCqMU3ch!X26_hjI$Wgsns>177NQxyUMosaFYX&DcN*l3~L9S@h0U ztDP&q86Tyh`x#d%0l^R?5>eM*cywAIs)jfOM2RR1c}?7WT{H?11OuB`**AOM%}Wp9 z4$7NC(Yh1RdiduIEdFH0d-5X=!YD#7;5fzs64(Qh<=pMA=O}B3GfS~N;=~sco!18) z#{weSkUC$>zVvGztS9am#2(Jk8aKI<*xP~Md0c$$22yHHGF*k@(13ZNO{-Ksvqs#A#e~3H3OZ0XtI_U<`JYRrg1^Fo#Wz3G0lq`R8eXWQ+HsdBzl<+TF!Px z?nceoY6{EOJ}rwWK6{iO3t~|YYRjdCR{LR0a^35`aWnt-sT66Jwvm?7RFD$_78)50(lwl{B<&_1{3Tof>9x+fcDYVl(6KY^^Dqy&G85(PNdJ zF_9@kHb$a%BkJyl@@WLUKWz8JZsGK;`MDF4o0wu84XQc48;1?8`6KGToZd{3P8eE5 z_Vjpv`#f}WTqCgA>F4w`b4=L8EFUQ=+7D37?M_ZpO=c%502un($lIIUxn&?d`GI*w zZ@s3m=AB2oj}A``go&SP`yljk?)L>5mLpR}{(pk}@1K11Ry7pn8Q2kZQ$i3$4q{Or zK(4W|RvD(ryH^TG;b~0uQ-`y+e+4E)U)-u=ae8jM&KH#e5fs&^CJ-<{XLQOD%>$M8 zqk?a@CZQEGU1F;X0g7v{$8-Lif>%$swOH>viQ?A-{^5KrjJL8kE2(743c8GYD{<$Y zkGJ~ytZ9AE(Cv(ktga*AW^fbZhR0uJC(O})d7v|AuV-w$Uh)9z-lyx%qp=ODRSgRP z;7WJTirQVUyt>c1Dq|2&BEfj(OT znm>)=i$cn`iS29A>)U(QJ&GiTtV)GHz}5Sl{R$KPF32oq)z^Gjj6Cg|Dcx$`0#c*V z7_?DX0YdoSH=hW@3(5;G1>4gUEe_H1N$Q&{zJdbgK#bIyP1VXDjCSNsvAClVP zX|@m}HeI?a<@CwhB0?2x8#eI$xomYPQl}~`AlKb5Q5nw}E&X$Co?|~1y8X7z@oQFq z2^PWCh=CPKGrc{_+B0w7AN zJfxbq2=N8SQBqEotdBF-RUK>w&<8x#EU9il#oymPSHge#U7qvfoKGtnzrMgA%u-e6 znasApDW#3oU8{$0ev!M+=lW+><7VCFgVTU(uuu=6by(~QQ5RcpIJpa-m-A0b=rR+YA+Eo|9KubV$Fc}w?ddWj!5G(XfJ z*rTYRUm)~xnBk|b#CYtWiaySaTP2=6-+K-R<{xQ$ zwD$?4;EzdHV7vIKdQxAn0#{dG3F&TwE8V4~Px>b?{kj z)exDdB#7V$MPB^XI;NOs#XTYZC@lzqOK>RL)xjQqKC{w8QRMC672(S+AfeFtF+Q|X*H1-@G2GTJs7~FB~W? zLp0$-9o6e`Q1b4V0`ImBo7@t9kJkR902#SxyuUgNVJv&E7gT|gR5><+JhIcT9*%8U zBI;4;8{p;Ycq_d6M+@Swf@X@rHU&VmN_^h!nt*rIY~G3WT_f~udanUJsv5#BQzJ|t zx!A{@Pbv-Ftk_9322wI&xN=OAvsB=gqL0l-wgh*{^GVlXRsC_gM@Q{uKMb52ZM*R8%}S*6@Ruem|BtQfj>md^ z|9R309Wj4qNCrUPDC57xg+EK}fj3~2330WBxLPa8b6+*Iw%-{Qd)H&yS z&hMXIopU@ah6BSMr~dDUcL%~iIP;RXr-5$T$-}-z z(=#)2GRLw}Zqs}2)xBNPnx8?Cxu*!_HlV7$%ZV4~hPK-m3|kZz4!^wQ(=Ybvk_ z(X5oGaxwkS-Hh+yg?d3)QJ>B`cI<4wgcj>u(|u~R_lY|z*L7LfMaVZ``Uz&jp$zOp zR1pIa*wT|p6-X7lr42`%322Dorp<&r2N}4=PENq^FqcSJO(^>)=&IMR7eUEpM#j{-M8{mxbgtKASqqo;``q?fR21@eNMsBe=cECL{ zb9N@Q=G=0D7Yb4^W7&rF-R_73{c0sFAAd>fG;sj556H$7ZM|)`EUhmv}HCu}ZxbcA0 zl(qKL-WLJ-xpXcj@9*jehFE-krJd`VP6~`-kmSs0RZLL=Aw3j?P_WqFsmiA)MQrhK z=jC-Z)Bhy#*pm|@aN$HoG=d}LdQj!t^;9gkeN%QISDkF^Xxgll-)FZTto|=6P zC$NM=-)fS!fjg4A#6*D(E$9j#Y#Ph(kmErBQ%^ft>2~RE>vAm6KJ7|TUf$4{X7RfA z=}PC5_~c%Lb7N)o+fw8UnpKaQA41A)~^%ZCXF*c!uSuA{?|j#V6`zj zoAV0#WF>UpCsv;l&SBk4Xnh!kni_7kkscJp%Q%?Gk%3Mp2Ee2I8)Y0}^3_=^gN67p z+{34bnj0QyESPzt(6n2tp(Yxt`c>8vKPzN(UKMTDcraWjGFcuqQv5zm%n;tFj7V6B^6 zK0S;RP_J~tVr^%0tl^Wdn7{Px&Zf*P647mnvN_h#GdH`*E7DiwoPh3@obNv~lTD6W zXAkApDGTLxI4*iH=JhEBnxi=G4XNaRXQM zUARgQ7c!~Exv5%FU;aUMAF_w#T3*CW^!>0MQBFCblgPW^Hy5Dj#gg-fP`i03*?eZ8 z^d@8xMktZetJD}VHZC)Hp6Suyt08js^_iO~yD&|T}-jCOf!4yi4 zNavb&Fueklcn~VTTdsQ!3=aX3S`$&+)Op}-1VSbh@;z<4K5{eNu};=g=RP`=x7kCR zYTAojG&XDz8VzYW=Gn@BH=*7U%QN?#&52-Ql%}j?x(%r!KeFu74A69#A~|rS-}#Hw zcc4kl2r;;jlQa4Gc)?uoBk1Sj%Dz|dsd^}IpBMA3Yj1DYC4t-d!~3b#B1+~TuJx|=nNp6l16+(I6u^ikV+QrO=& za)BSww8UIid1xg778Os!*>POF36dm>2iq;D-sz?D1yBKAEM{#*BEQuZu&Y;Sw3Sd|Ftzwyl#rZN^ObE z=N*5%`({Nec3m7&Jq(sSSRCwpuZ#U$PxXVK;BCjs6D&p0_&8tkb~HzrSu)?6ncaQ3 z%fGTJUh-;`em%lzIAw(xiYY+eDb1IY18Ms6x+)9YL-NTKp z;vxyE6Lo&6@Sm^M-+76(^BQa>EPTK}Dj}L9xa^JTMuy=*o>`PO*zdE1oxbmt=aaKw z{TVYQtQ0tf0Hsi3_G1;1!Mh|XJ2Us}rx)rR$HX+s#I1Q1>TYT6W@Ht}7~qO?_IjP*Io!odLAOWQ4@gt zw_(p?$C87e`b$4sZC>vBBktX3k6`pdn)yvfTMy~DCYg9-{@r#+>Y*a7@+yeyI!r;Z zC8LJ~JTlb{qTPqDRzKFRiXHxiC^ar4TSEKI)p$t{1)X|1h5gg%jN5n2ef|AI(NL{T zyiGip%O43#QChYUfEVUHSIH`#IAoyyy!Q}>dco*)@IB=p9uFd2_kQ~_HcG1@8J$1s zlAZQqSnKf6kYdH1D7QXb0jB7)NdiKPsN#%x+*}A*iOR-!du~Wx_os$Gau>3vi>q`G z`YS24<}tFdTlu!WsZe`3GrWA&+F!7so-7$0otF~8nOZLX{$UN9&E+p+a6a4ZF_{Kt zm^?ZlktlvAPGA~W<@zVBW3bp{4`i{R7U;VDWDgMxIaNdg=BVcI)`SfnPlkd~o{tVkT%6u2`{G2CavNN)YQ#MJ^ch-9lPYai@&t;EE)sr_VE` zBA)nntSH%PO1D_y{l~00?d$Ht2h!bRyehUYN2rJaAPz^hwaquD5gLcYzjzKZDqOp6 z3=~ymQvh7kE1!4(l<3Rehj}&3AeZY@m#Uv|$j@Qr()y?OdW+S_A{L+AIe?IyMxQFq z+hF|zGgV`@=|sDEj+LEV5SKpNj2+S@xe$Qnev+x{s*s#*nRfwtiOqz|RB)$h9#r{* zfYTt{>dIUrpl=HfuI^k{EE$HnJYhcq9k7fm$W#GoF=^dX2IE7L7t$)`ELI$z#` z`_ARtgG7-GdZ*28pNSEhNcQ$Q{X&*o)IGu{0ctoxd+H>dy+KDakrb z>>D-+Ouqe0=KZT!_UgeZ<;2DnX7jihex2k24!Gx%=84=irr1RBR=#p_T3ws09|WyO z#6AHmhMBkgS+GH!L!MSoT{ge<K;hjsYD?PZ0z*> zqS73mR03dk>AK^j$7g>6wQ|YwlQeGo_U-dMN&*-`^UOWJImI)p1h%K&Z*F3>E*UCV zsBSfO8rm79U+?PE96UouUbBBZyx;#N(fbh)ri@g?d}w?_v=_KvUj_!O)mXp&rMYg> zxeHd62-18sR%Rcz!Doso`rN;rcp(DQOZYRr?m1R={WmGXoNek9q*lm>j)4arCdQb^ zauT2z70btHoP9))_PqBaI%4|=VA`uE?WhdV__BBPhl7&z4 z;x)(Cr|_zk0paN!3ln91{b;QB$(JC3h;5ft5B)lwN#t}+bt|s__h+l1xB2vCjDRsn zedcG?qg}k%cb4<^-zbm~YaPG<5uD8G3t+lNn!%7p@o{}%V?W)Id<$g!YX8N+Wip7Ku@=Zfp4XNejpwk*ce`O z=yy1bDImZRBM(3xpQLzCf-C@4qm;3q4I4(mI|UG0bRz#rq$n4#2-(fQ?X)}o?MT*5 z`GY^fHC3v7d0t=8jPko?G5|zp`N!lk{}%^{o@t9#{*-Vr*`62cd^nP%vvX)<#Lm*| z+`)pt0#uC-yjSWd;@S- z9$l-uta+%Eff%*7P2zdx%!+an^2z^RFPWFUAF+W^^O7jVz;sg42AfU;m)E-yxq^1u z-`j8BMxaA`19IL-9cLt8DCzx_n$yGvF)(WewwpKX_X`#_tdw-1{j9 zrhLylPpno&(-w=P5V4i!wFBZtNaH2ME-5<=!4>l3W=>K=UjcI2P7EH`FleZM22s#>?B|)K z&evt3-65!rX4e#^1nODF^`zPQ`XUCQvqY3th7Vy1_{BmsW>GSFO2)p9a{NUrn3k?u zl~H#`f89FLf5tPeoXMXHvRo&wbL~N4NdRN@!&}Nl%G-an0XNmjApTF2zWFnaLA?LZ zrsM)>`2)aQ2z#8Ks*OL3#8z3&tY6CRgACHV$+9m))u5@~1RZV_vB<THemX2Ah5rY3j;lx_xnR&}(Ubg;E2TjK#X;jg zyW%I7Y|K3Ln3h_j@j`}R)6?}!tMqNf9n^*l&y~O# z=pr$Rr`_IbIPl;N+B@PyBRh}S88Lnke2O{!*_JAl@}D4mG#T`P@)xtgI%t)bmzQzS zX0R7#S(Ywa763MEZ5qRY)=)TUS0+CN%R92Wm>xs>u4A%lT$L5AkP#`+#o?VH;o4n` zi@yPQKSndN`|+$h?~l67v#~p@TbhzBbtPP?%kMCLd=lN1J}9a+_slf@i!V!!YLUaQ zXV`WCTa7zcDn9=D=fCbyj+-ttPOyGBgd3CCOtJ>G%)4hBZckl>hQWTVSLulZT`lp1P%aX3N zcc~%^DS`qYz%n5*K)$PIrl(=URKxw{Mvl$ieXipnx(9D)UE_6r%UY`Q^saKD(ru7J^3}4Ma_&R5JvXf^^+}~kWdxm+)f+5iH$Hx;(e&Hw& z77^(eJVr%do;3dohkz2?$=?}HvI*+lgfp3jAUeQcEWz9k+~D$&)u9m9AE7Nk@80ic zKRt1_r}jxS#Nx+B+s`}te2UpkAjV{3+M(wSNSbpw9A8CLJDGomP~#-~SDr z^l1?3rUR-`l?S`8ajUZ_H2t{X>+cBB1iR(#_21#k{4=(pG{v?^s zv1QYyO-1PqGwS3@8swsBE|CD44;&CX-!%KpZ@>hn*?N);5o6VPZciAXMsDTu+wJ)-XVWzl3Mi~f7ApM3jC(7^*9zkG0z5C&v+^I^G{i7F5vzt(884-&{?pX%p` zCbAPl3>;Dgj2~yx!g~*m00emp_(7c(fcZA`IJS2Fa@PmZ2%RcGC`6FxGVG-*zl1kp4E<17VyU#Fs&x<)b{dx%T_N&K_CR zG3hdc8&Fk+>pO75Z_i9wjkoNvx!W;NUHV`sW!JCK*yIoxf!DImq9gp*yOw#yTY@bE zHCY$zPJS$~L` zIZYf~LXKE2e@J1eiK?vlv+k=$OAi9IHbt`?(>kyn7lZ^gwF;r7X}2Fcp7VsE(~E`Y z_!(@BX{0EpqI%7705CJ@Xyh z1fsO}_WvE2^ZRd_NSA4cHdPQa52V@yVKURT5ipaY?3?6@HaEEn& zBd_`7*sX~Yg{n#Ik*?6TfqW+=J$~v1hAZbe;WUfgc=x;7|NY2R8EwYDIGR=&jv8d! z^IbH8HX|NO-$1DTc}t)1Q^r}r0NR;7kZ#o+eooS0UVfpu4CPjjYI>-dBa034VelBt zKS}nxqw`-Pr#7G{P1Yq4-JR`9yV9&oo2KOf#-J^Hh%tPr#i5}afA0>0jJ)vrb-VhN zixvU(^N!LIM+`J+*8|Lv`EtPT#0cCCDqVusQ=&NU^74D21xm0dQB@BB;JvOolH$L@HJR%0^t18v2;V~i>SI--tjngj0o^Jc(#jYspeje4HVZe1)!f0NeG{+KH*_^ z=j)SVdXwFU=pE$xVG0(!gx#4#D#I3Le7g?cMT?Q35i;5p+VFJ0_`^M}7hp4C>+*S@ z-&VT>R!#0%mzhI%Xt&C?V z^z`&bpVIYk_l+@a!HV(1#f$M;vTFJbAdQ7cqu%+*B{n@NL|=O)8-b;v{Y($+b*gl19~=7TviEkK%V%?nin5zw;%`a6Xp#Y&YV73eJ^noNP-d! zDXw2X4x+K@jT@Z|6HZlqaD6oa)M^Xl-YpP=>OtVni`S9b!{!4e15qn<0tRHB2`60A za)u9Hej&4e)9!#<71GaXAc zHT&-~h5IQ>hJ?2tH+@N30oKykl;}(ZyJK(p7V`uVvxga+Uq=0HBo7kqy#;ITy9jYL z1J9qP6^b=whem0c1x_Y1CEYU8`$|upknjeZ!dgDY>$zEXtp}{POpGs)8JR4MKKSn^ z5`>Yi3S|U*bP(c0VwCGveLEXyDC^|Or7`^N(UWkVDg4+0Drv@hPR)0=;?f4?qu=?& z$G)dHJ7n#)<2v|0T=QKa_wPcsl1$03H8`PE{`8My>TrcWD}d@Gc+PTpf#T zDFTe2>=Ik8InT1P@WDPuCoMKMeh7;3x6tzH@9{jhzhE6LERTpeIaUPK5o}du`IwA} z%vk|=PZ3;5*WE6GMru9(b|?sb!dF(~F-Z^Yf$(&e zj_#6ie5^OwFX6W;t_{%YXLc!PEh}Vapnos>7%!i;2vO~H@cHElVB#Uw(0en6DW^Cw z%lScw+%&&Rr1yLLmyF$fOq@3p3h<|xg3yyNzGTs&(utvVZZvDu4INI<((bNnKsS9I z`P8Jy>Iw-9`yh3T+(M7)h`u`r-HQ_PSdIpqq-jL1^cL_`pB}BXV<1-w1C3O@DJDu* zYohulUbcWeq5>Xdfe0?s=SZC17AzDN~Bq^-2Uilw{s+6bi=zHo3gI^E1qdcD;?ZJtQ2dOb=T5?q0iXN z9O~ZPa|j9aPptwE8L&Ww!}u{Lqe>Zcs zq3e+MXBW7z*HbI~%Y`pFpM(0=>=^Qnbezu5aI-{B+m|AW@PA)DA^O2fK==dgAqA}z zynpp|1$HFhFv9ro$GOBqzR4VS=W2*(hfdBb3c6B9%8lw0W&n8 zTu^{d-?;oxn1~!~m@UF5(6F;L)0z)32wMc|O@CeI_mO!*zkxT zFn8$3k94P{@2KNQ+hU5{*LRAk+oquX{`2_#@pdvsTPHX!4QN!yT@|G{^zL1b49`on0}TXWBLq^vCoi#%R74Hbm!OH6 zzgVvnfW8|Ch94^1&MMdJHA>=2M-jfgDJ64+69j5jse6}wyag7KRTTz^XS+<%=)?hm zmQNf5=-*(g{goX1)0`xSuf2nyf-{WXbUiI=ukVcc$LA?aBoRCx?&(`&J+`s!+u-TmV zV{EF0fPh%GIbR&Pv|s_p0>uM+j|8!&IBN2fBqo^Ct=lNETjEb641yx)HLHA4zk}eT z_0A{Ym$TI)I^>}pP7}?E5({$e?qP?UaR^9@Ek|EFozlbQR(xqe-@_#9hI(nFLp~5r z$?RIzZB|5H@0i%wpuj4x2;xn{X5hS+j!p2pi((LNWar2N*qzC#UCpZ90ySPY&vyXK z&U&+47rbK^p@}~})cO$(s447A9RJ{j;aOIm!=s{|AWv{*t=;*ocd|TEa;$J!){Bz? z2j+(T3iUIMn1`lVwwZNA4qRm8(*67@(55$Jz14?;rB%GTVh^x0vAEOhU zo`JVtU+z>jiEGOB(1kjdA^%Ge_fypkrBm-jznFKHN@eWd*YPcUr!B@}ZZP7Z<7WgA z;BME+2mp;6_ebgY^hjX3(aRmiF`3O_Pqx>PhtYHp4`bX#^T6*R<9Cr;Kw+hQ5uYiw zY13XZ0AiIuI%uK}FsX>TQ%g&6WI@i=xyqmA>TE5br& zBdpd07A{$7?|)$ZdQ)hzyNkW635phT@y!a_#|#r7_Qk<`d_314yx|z@J;cU<1g%mQ z(KU@r3zAksPf<1}gYYN7*}CO+3Ho8{Qk11WrF%@vDOSAO5jH?V4fy)e>6U7!NttH2 z3m%FVWJ^#@-{qBuCGLrVT=R_dJ5ocPE+ZY&nP<_}w4B(YO<5RU-Cg;`@ZP!U<`-FK zuUq#wsU!SKz`)CH&T|=okuwJe-4ebAar<@5Rd~f+ksjdJ<~NME$gmcW>c7 z?TCnk4+q&(>ij##nmiMPWl%ob)*v;^t=NO}_rj3cc2R$L%GtK9v@hE|Df7PKpMWzM z>FEpXC_d}iCO~rU09jo)A`!cJ5!cb~_0iGuO=gp!toUAhgYQq=C477mpE}2B%l8T$ z<6C^a@6Bp!T_ekbl*NnAC(M9scwK{m1h(Q%4Zw4$za|YU`99`FQHJdHvCFV_en)H1 zM8sL9Pz{SYjM~#FU(LD+0Vs3cLtl>T6JwDJ{LX|GH9Jg1~(< zl?P)#YIh4K>0Vot>X{pE1ZVX&#$j% zF7#!+rL#^vJn8e-{$|@4FE7Qb{&P8oLthvh@^WcE-QVOg+!=IXq^q;x>wEc&6V(YU zO#qP0E8AavueUwk-<0--PRxSy<#xG78hsf9-Bkb;$y zU*h_`q!F|dLY`e?D<_52tN*RPx|F=&rgBjlnqzd`LsdwC2x4Boam%R_IXszF)L-eY zOHwfDRg5yK_t^@rqn}Uq9|-IHtDY5uy);7*ot>pYh*~*pANfA8%Ga+pwduY#^bptn3zJ{Ib5e z7jwrfidXQB7A#zo&25m!f4SlLt>DIt>jRWZuKd6-KTo$< z`OmCvcR%?;xX-JosJMm#^mo$dM@QG9cA@6({U2aelMt zH)(LTg;87sThWtRvrYr)k(-n5JRlLTSlQ}jeYTq}h!+6>V$^f|fTe!3p?l?(A|Vdh zQ%Itr4dF8ue%`%kd52zhP%1xnhM{(zUQCPg>&%vX*sl!rWqjGlc)}qm@!<8qN39;_ zlF2OfkKRRu-Wzz2V7+O#0mU!3wgtMkUpiu#^6H!XLY4b6P07uzwNpRW9PM1_%Ursh z9l?`BX`89Rm3<^uZc6un_um)%ub&wyBatU+CA+2-*HE1( z3XEw%lg{V7Kkw}$du<%p0E}y$W?Jw1 ziYY|Yg+V7=t`6IG#C7MdJE%&HJT0f@_2f+tEBi&HYM8rYc^MCq;BKY`v7Bue2|gN% z;lWHREKizbOd!{}sApT=L{FlvXYmTZc2<|~!hGV6kE^=u6KN_AMQ#aY6B64;XH|1( zE2IdY2Gd+8@4@I<(@Lf?<4My*pSbb06S;26VF8=Z2#yyg>)U>*H?NwkZg{$v;>%Vc zQt9*cJvX0NO=jLVHbVu^pm7F8s|pbTHgYJXNyxievlZ*VwU^%GIFweNYA}N20|-i# z1g@=rn9B(=td?+mOyJqmf+{BNpD(iMF)l>UgvJge>{&M?o-FpG@f@o+9|n|`Z9Qnk z8kT2OwY4d{PIZ3)15J{uq*1|w)MSEr!-Qmy2(1UXIG!+r$DBe^ip?x@AfPq{Y+L~C= zW3`ao>+71VEVm2>%?E=ve8-n>{CUCG~BysriMkS=Po3Hlk7~`+Xeshse z=T@uKzD;yMp{!^S;WIV+>_6Dn3j?I9UCY>oz=RtcWd!;7_|$V<9T?+Z%vyVouw^3p z!|&?h+1c4)tR$2Hj7Q4wZAKAULN{oUu%u;2;)N!3z+vG17p0IH3;3;FndFLdxFDgl ze}BKl`iV-Eq&Av#GyAHzF~VDc+WEVFaXXH`ckOcU&0gRClAQSNWYv3P!XZE@bD3$- z=73Se2aVf+hs?zERA1Dny>Qp&eEpi+YR=Q|b8SPKBE^^aY|Y0e$H?=mWFj@M=DzAE zW&D_M{k_(c#|8q2V-K$LI26=qeNe9S^H^V1a_xJXY{dctiQzh9#*GZe?YBv}XEJ+z zS(d7-{-wRMq4+wfWliuJXB0FD?pP z*36t$D`;w+9i>4QtshJ}&_OA}H1A-m@j0iY0-QC18JYz-0z)9aHMNUhpQgV1R@`?> zkL&!bR(FGZz!Y?Er~uhBe8Y_B2Wfq9fnMba+<+;I$S-o9v^t3P;_mE(g=fYNtEM`p z5QS^xD||~!mbg~XYcf8gHz^dE1rEoa8RKwUnGm4$xi8q+TZRQHUQJKnJ3$0X)x;gdHj-|Wbmsd;(cHtpDx zv|dZ=7XH~yn;b(ur%QP|zqaJc=LaJ8Krtxj+-OQwtbA!-RbtV-{GO@sS3bD>X4C9=pP#R9AXsf-&BP#T?XrHXZP`7dm$f)h2nhgk#MOqS zrKQD%00`vMbFc%;5u`Vp#{#xd_1jn{2^5ba&UxLORd?@7M8)h993-}wKm)GFja4VC zlY?00%LK)E`9~twQOu`57Mi^aKbc(G-9S!Qe~ZAIXcwNo$vyeg zoG$CPxZB298)gkPS{FMMMY}2~t=bSSCO>_Z$@a0@##p7C=aP%)6e|0h&llPNa#`W(Vo`=ULmz-nd^i7j@sL^#{Ox*OW{3^oq7ZoXHhTXlcjIM5v~ zJ$bJR1bcqf5E(De%`fjLJxtDGYY}-1XE;LFfJZ26PfKo&z!{<1&CXY z1=O1)6Z^qc2;=%+CLmgr$It`A%~?uFv-B)#f`@Vs5M#IS}~7P<)-pQ+taCKVPpZ z4=>wXTn`V}!1Wug3s3Q_X|iXib^3nuir3ah5|3=BQh1|oX3EU%NPq`Q{?M%k)s<^F zYdt4RCk$20Rz={i@HRN*l-tvz+Y}MH{mr%f+D4&JcwMjyA>%^*)S!`nrW!5SW9ZLy zZ~*mt-_O5o)K~7;4{ati$9OX&cDpD3k*FvFTqtne+>sB$8+LJV9l){pn)Y*bi4$#_ z$T1+G@c@GJQcr49C$yV9^w>oafC)w_LS|dxat~5yh}I!*A9(7E&~b5dmjb~iD+*RM zJ*8G%rV^s=TuMdWZM8Urg%1;Z19+~40LfCsFfZ3Cb8l1IBMJ!t!9)-yU}%`XtJfqf zuD6z3L{iUccIdL)*Kl+*qGub{4ZMHpHKWWp$ETw{bjK;~>BT=5_tbhgykEO}=G&v< z44g-%@~B(;dkhY08fK{vAB7u3A9_pMscODh!>~}pkQ2B)hFVL{p0&Lzw_H(CVf$?U zbm3LThU7b+hSURtOy~5S6qQcIR9-IYbL{CM^^(I#j`SyM|M~S%|9x8}uEe?4zN!mh zVE?_v0!E;v3ZCVw70Y(~KC&pK&605F7ScxDEb1pA00H#!KuCHiq+DaYQ-=3CDJspx zH9hJA$zsy_^-U4T`WaYbY1;N0<2Y$VNwZs0^!4VpC<;+pV$)-?RJB!E(s}T1cj?XY zlRb|dBW@hSx;*Y=MO69i;@IL{H8~lD8+I8L>P^On#yLkzi?yp+pA2t8je7?7Sni+E zlr1cYDnYMSNuRWnRMBhos*nl{3^o~6j=t&HTf(p#tCWTx>0XnH)BE=)-C)b`%3nXl zE8JrLxZ3Z2Q~zN#wR42YYO8_*suycMA1(Czlaryu<`UlFH7rmV$oW^-9B@)j0%4Vi zUd=!JWoqc0MJ*86AE#$3dHf*;x~LFaNpojU@1Eu~t^0r8Yx?6teJa;o-mS!_A`kf` zSFc}pIC%{O5n|*)`fOEY4!e^l_7I$0dJC}*B0)Yyx6n-Lj{05l7FyO_>H$1OSl1Tf z%?|jpJJJ<(aw~VdyReM)%}3hPDurW3j;_^PvL>6Iia+kh$UtYEYkF(%wwR6mANDeq z-w~a>&7I+=P>3Wjk2fpZhhmy@l6nApl*%-P^0=67Cvbo5ERnvmTQjD6b%5M zBfHImNiS>9e{xGa+K{f3)3X0yxRo?P(9=$RQi6o9w}g9?iu{#a^47c;1uGw5=@HjI zl6gk>!~rq+E_GT-jkfFJEjJ;(yS-=*+ja0PW}fBVk8m3=D}8yMd#H>hH3e-*fKG&% zsoP4m4Q+4$Wc=ap5p`}+d`-4PjF---P*#D!)F9qODHFadeWuQx#|!;|5Xxe+e8I4Wcy*>~( z8vv=~ByKu|g$FKk)@YFAMxM!WCBxYH=~|EXDJ)an9L_gx- zvz>{8ttKgp z(1{Zre>Of3T+e3Czd6nLAfLEZ1#7T&3Es1&!i0z6v$AE+A*o4WOZyHR?1BY zC09PWEoVUN;TK({+x}59hUF^JR-;u9`;JF@3I6P@E-i5RRYN8WDwFl&zxO_gI7^&9 zRP)EeJ07Xa4MSJq_(XZtI-a6vcai;GfsIl>>y^HfFTEEDp-y*pivH(ImtDCO1IdOT zplva-u$ZQt&u16beH3!|kKnI4l>F&ozabh^N13=${k@umlH(j*fL-< zBfS&pz6W$O*F9Ev^ybvL9E)uLU7?jI{)3Z?R+-{jF*@)b@HaQN{w*b4o$SgZK@HIK zTY=uPkQxTW5lV|ZHh##9k)vL_j^V{53PXk2T1p;|O-BhsEd3>mDh<=o9pT^e40cPH z`sz(${CgaKdF8DyYEqq+9Y7zpJ0EzT{V8&_f*oK)OeT{NVB{Tc? z#Z5<8`)caen&C+2Z^W$_32-6Mx@E`YA_P?4^OxSb_tV3x6I06jjszDzHWWHLH5UI~ z+qHzAZ+5iGEJZ(3T&=t!GHh(-m4L1ij5Pu!FVf9Om1jHH+EuU*ty&rK6g%JHV}@5X zZ>wE@Qr-6Qi{aC|%%|!MsbmxDeA6&l$`sCbum?O@h1BfxJ z#3C%70cgt2#r;euApU`LdPMgCIi@0v!rYn89i{T#R#U<=Td>meTdVVO6ehNeN! z*U%)5<)TqarR@Qd=BH_$m=)@6#W@2M&jjt~$|ailo*u>{3ZTQT&%1PkS|oQ1Jv~uG zSIM+%a(p0qBuIE6#cIoTk4gJAFwN99!BRN*n1KtoE`y8K>wUk}*gC66Go%YL` z>%&W`gj7{Ssv!3LWSy6i&6reY06<4kQ7OszhA13ew;a}Lv=)eCh5fwppS_H z*+2wH_z?+2;KBr+ck$&ZYW3~_)*nK0UV{lS0sj7xg^p~JYL9cR9_eNX^7dyI$cSpd zC15W}DgojnCRC-AsIw>&NOer&#=ql5otRF-E9mgO<}^6Q>JkUmP8)03{saiU;8?~c zc>DT2#q#j)hu&_XpBkyKH7%mc!Xi4*{>Q@!wyj()*wnmA(pAQ!b8XIlYD8`KSRqsK z#qdFck;@w&izIOIlzke=3#xk`aouD*Zrd>~?%nnG7i?r^<#{>YvQ2J}lh|ylW|d_! ztO$?QJ`MmSbT!N8ohb&!%Pkr;_cf+7sRXK>Nr6#JSJ%6MMh1p2p)&c*_YDoVsz&g5 z`uJd4jHA+^Y!uKwUB2D@Z#)eY#;tf1GZI0Ok^Hd!3c-!4^?f};WY$YXHgCSvcW~b- zCkBWMZh{A^Xkrqlt)TPr&MAj}+r%qW!?Nq%JV{LuxM&91!_-KK?5-`(4Gn37a=Qf~ zvpY0Cl>G#LGj?{vxNe^2?q=|Niwf*V?pv*{jC0KOn(xsD=tblui{r2ee&hEf)PKL5Nku-L*U8 z8om^1uf6Oy|1#Q`fC1n zH*eqG0<$;ab&0Y*6m^m@=3lX(oMo5Y*J~?QZ8GcVXI6xjE`1FfgK)zZE-2c8K<7p&TJ2&l~>D6EhMJHCI&<^ z1(6Itc*0MehX8rSff*dO@%FZ7+;@5V3yX`xuOG&(R9R>dZb?hbp|WYJ4I(66o{>QN zbLY;*p{0j7REqViys+isRkBxkk?D{sW&&`Z2DEg51MT#sruf+xwJC)G1M;%6Bq5fTc1M(z@ z-8HHPQ_@p4>PB}^nr0@$y7?9!|E=RFgyD!h{xPyhsAisOHAB`-b5dqdWc>9)QGe!~j>8m|pG#J& zOOD`1WfdYJv#?P!@ia;vRPd?h8uyy%HMB+F<<_xwDOIZpKMuevF%jYRuOs5cFnTRp zwW^}&?xc9*h zuju_zs|Ott=cv=u4in>~*?adGCrdU5W~g(Q1_?zs-S7>(?aQTUp%-PDvPc`pY6=*-_=fArseKn2ZOMZ@(Et4!d(!XMrglD7zsjQCvlTkh=C zOs1k4vITue^qhrbLDl^oXCB~Vr~=LG8|xh$Ti~$y3tFl7ArC%{EnK)T*W;(4VKk4x z4N!tlx4;Rt3<;)s?5mgvP`xxW+MAW`_8v6zJ?0^tD*(i^OSvk5p3`hibKrvaBAVt8 zlPI1MQo|s4t*hvK_k4M(`P++Gb^->P(>;mtqc=B&ZTOftX*uj#JvZmUUtcW0c2Ox4 zGnc9S^*~O4>2Dg+{PUrY86>1WY3lua$^FNt9we|^s;BZ3yaME|3}#NM+(gy_rOm~UT^l4kW^AgTrnG%(*HWy($sK+nbIr08C7eFa% z?}Zk&R~XMa!EiQPUiF?GTgxALi&8ns?dHS3>|}iJ&ylXi7h|6(S)L zdVDF3&lRVK+5?%HHV5+hPp}E{?>+iR>19rTAQ~Tq1&LOZ-!v{bkSl$>SDmov%8tc-aVwdL5n@Bw*ozyVoQN}g4NFvAD`f{SpZ z%p9P&Z+V7U2MbyMdf%O;3PCqdmb2lbUnZ2})0i>xbPYUy9PLsoxk7z2*|*uW70|eV z^~$|xPs6vhY0d@MPYD6-7^`z&%ye3Q(qRmQkuU*5^a;iikzd0ve*+75z~|45USBR0 z^?sWfI+#!#OGQyh*^{-EsQ3>INI!UzJZP^eB!>wCBdyKw_?_I+yA&4WM^u>~dK=g*)?GPB) zr51~KZ>?yvrRVO`8wy;i7MpQ4>iO=6(p_%>@JR=jzBZHST=boYpgrg?7M$ z^ysz1`%ct6$#7QbtWV{h$eR+`$$p308XbZux zfz^uaK}-#CO;lVItp#)*kLC#~l@Mi^pNx6}G0#eCivY9I}DwXY3%>a@^oK z*~3dLHW3A+i0;uOLuSML7c_xaFe$HG=~JbKto)7jrOS3p>Nm;Ds-3N_@`gE=XyFm~ zRKkGSD?w~be|o}rw~S>-Q94WSC*`u~@qDXPE6Oj$9-M8^&)D^|1W@1pe|{*u>-d~H z97eir2$v~d5(KUiD{PN4sec9cLq^Ex6mj@=#P3nEW>Pq84GP~JkTlQ2mHZ6TbEQmG zhPU?uu-or-@pG|pO2HTf78gf|xEt%eV#~Ym`cncrX}4)@0u|jJbo4=F(OU%@8HaDd zpW;Kd9NzcKE@IqqWla|i1@xrU%%K6ICxO%Lo)_op(508WJTG_1;K{cIdp|u=hGExw zcE9-{29I3Um3#u}e}1U>9*p4k{o#$Ffq|SlpFl}D0lW5Z;fi5Je3VI_c+E{fsEg9;K==(ARdI##aMZ+!>03i6K_?*Tr%33y7#e89?s!M zCdlQO$Z*?=&biHJ$@+&a{gd~@<`<#sh&yTr$eK6tIyLBF_u&zTTdw7)Nln{J3TfdC zgu8cHTOt{i5_l2Y%{vk{=15O;Z0Tz1XTXnpEI!jMn7iNvQIlL z`Ny72luM{j+`IhGXXyO^oq;6puY2KdrbIz3hUAK$jiJ&h`sP)IcefsWh!i_HTTffF zk`Qmr-sW`6(E8O!eBZKeV>DI5h=)Li87k2%(!*lUM(Tkcs{0pE%2QW5sgdief0@S0&<0K7$v|<%PilU&WvW1sGS$}g*(&7osw@NVPZ?dB~V0xIeleV8$5IMQ$PPw6XiBQ-@_#E4fq-V z4Gmm5o3nBuO|K8X?8i`YP1fE0#aYgFFn>h#64n`x53~;axyi3r!l|qjjH(XZjCTp; zx+yW$TDf~fH&wFzt`AQ!;7h3eiU<40bEj4dyRk7jd3hxSG1YUSAdvhTB4wj~35*}U zC6nmm^-`|Y-zQ0?IY7bG9fDLFUh3NX`xA{scvaXIp1MgW{+RGH2RN_1iz&cs*9nZ? z%%24wQlLrqi=N7MF~)^M4dV3mwLRHPoH$6{8$PT2@ZJ3xQateKa&Q>W?%97#r=Pq~D4Hn9xJ8iM3;{W>>gb zXI(eHTJd~qoh5kpYM)L~V;aSHvVi1y9dSr>NhpAHts_Ly;gF%C6&ctb>*r`{KGr&Z zwkkee;vsJ}@vXsr*6|-(hRR+Lk>OlLV%lwf(JiT^L z)#$S3TtL`63y+%oUrrP@;rKYJu_nKKxBqd3Oa8!Dpr4q$v2gK{C4QQ(; ztsr#)bTeDv^pY^OSasfkC5-h0S1@(xLG*!N?J3)V6yrB>Fa!!?k67NM%mHF0tT+w? zW#r}(RT_z$Af_NGW(UK0rY+Me;r!<8@iBih`}~@~#*k*l>4t_})A+2joeA-VeF0Fw zOqqmhnIZv5EYx$vUxsTKR8o*w9vd1xP*=C>)3Hu4KJ)85-dv7K(?!{%@!wWqguuyB z+?!qUWC8RXPH$G{tizs0(5b~Gu}dg$-u7WNg(wwO@9a@jR}Yj600*cPb-XUPc%-PE z7LYJ6>aFdTe()z00dQPbVaLU@Qhz`1JmMg^*9d9w@M-6P-S~ap3(D7iS&)N%en}zS zy9g6)JepF?V>j2c@iHJQ`h9bbz}SN<&s^G&EuU#97pPYuUN0Ds+2-&z3!M1N#^tX^ zB#P(LJfawI`}WE4UB=_rno?uK;Q!;U>EZZT&-l zame+70KV=G%gtD%x$mwMBa~(k%YEN>Ib&0Jz_14nY$o|lS`FY z*JY0Hs9ib@ATs8lqV6f6y=mGP-|l1(A$d36-lDWEo>OPqgI8KYRU%KqlAo2nTT^!} zz>)&XK-T8M;|*yK@AIUCJh-d&gz>MPqOCfpMOCezt1Rwnib#@`jlpM}1~ z%&`ZT=;^4HHl{yque!GX;itiBRjsNs-gNN6%U&`!J1&#D z68(7yQtjun&R@tH!Chnc(yb0g{U}Z2CKxP0SmpNel=is{I_!l2Y+iZaN#gzPw|L@O ziERa^kPiW;HVp&xEvMdQQxBD-ZW|OC@+Wd;EgH6JK0e8n*&DrsR%A0h;>EC(Qgq7~ z{L!%ZkF|*Mb9=m!1-pm?mo6)R>3nPEF^xsV*w^=A%g*QhE(o#-1PNef`+E}k3yli_ zn3|{=dJ4c7OpO102>xdH;0xr2l5~^8q9R2tt=pLMi}|h|$geXgqos`A9kU7y>bHuVuG>!XW6TAw-KUN=A8ALseqv~} zJQ|16FbuiLmDxt+{RPdmqdz`lD@IndL_b$*`6Sm&ybvc{3F)LnRgJJmqrZljL3Ke}*n9)I zMEm-)dy`MUIbiGdeAyilZ!4W$*vE76^6IWv+vay`%i&jicEVS(3P8*!Z@9&(?!%op zEcw@C<7cL)Ip%w28y_?qrP!DyCGQJ5$||U*a3be&YuEQn(YQws4k}CSw~xJo;3ZW5Gqhwio?7bxiJh?O_IsOdve3-v?`3LIX*Bej z;RabWeOE^oSgYO0B%II+W7r&5*Y0o5%{(vvAf5ku((oVOy63;wvj8DuDME68?O`)S z&_MvcA{_j$Unem1>eh{-X4fS9FRa>!JKVo3p8c#lChRQq2cNuQqACE!yd9iGxA+3D z+>3tp&hr>B>#ukY;_SOIHs*FqrxL466`JN9W7QgJYa%E~J5}80Ku~sPx^mPnZ?PY^ zB5*`ew6S@5_QVZ|bTG|y-Djl-3l@sFPuMuo-O`%Be{I(JknqwiYZ+KrxB*y&k}|Av zn)Zt}1q)z;yR3e)rYeIVmuNf%1iyaEXf3nYmiV2v)$PfVDA6~m^jE0R621#bbu2CX zU!0*Oi1R<&DQ`DIaanV9Cq_>uFE1~@y{F_jl7^Gtw49n!Ali>kQ`C z{&?mDH#IB>;tEAsFT}if<&E|=9!t|&K<>=$sVAgOsE^NfsZp=QTE}0>#5t2IQo`I( zB?`oWk+(wH%g$T=E@?i8FzZHHh|G6P{~Qo~9@9ncI=hcVhv?;@7^H3O*WRG^L{!Bp z-=R0;Cp635f-`-Zo5bI-#(dC421m&xg{$d;9psMY2le980W&VbEJB{1}^Zyl6Q5)tx@}x zmUu&UX5IN3K>5TIIGCB} zuuzM2H|zjzHSuBR_U#{BnB3|W#sV9E1Ydw^-n>o$MJ`lonbu0m(uueNOkJjJ1wO-m zw;o=}{%isHF>za-id*G3t1D}m(_f$Z=GuP4R54K0lWyCm79*^icXI7vU34DTG?ozn zOi|RzA#o|Sh!$upBD(q5vYgqeaGfKsG-~%Xl`}bGEF@xHk##mO>lXPxx~@B%>$ZJA zM1_h-JCvvhWu_99>@Q`8P{{U`U4*oWl93{#vW2ooMoUKaUTH|ShEasyd277y^B%|V zpXYdw_jsPh$9-S-b)DBaY}-XMMx&x6H3X}}&3B$tfA>xue85liuN3~=qjMY3C7tp8 z?^`v0$<8&xYZdb%KfYckhpXcTT*i?L#gY!(x-P)E;rMWZ>oTtJ%1CI zEUWJjYKi!zw1`^Nmh_&@HqLRm$6FBZ*}pz+E@IYw>ULTdY#oRnd5WOE2igQ)_-%g{ zTYIJ1S}1P@I=q`;4w|i24(c#M7!d3w#EaBEx?D+^pQ&^GiI+al-o2dz#Zj;q6IcD( z2O?p|3l*-sEz#>l1Z;U5*&JZ|>nQq&h*Y3D6hK`F!o1!&atyNtd)LJzMOO$;|4|%v zdHH)b!wSzWtP*uVHrdG<+vSKab{Uaj^51N|_l)Eo1gGc5lEqWAJ*20w#1nRT^c6S+ z@sP4F){eF}VVLe=>n=4N|NS-JI*^e-wff?puluK7(TOT5uw7K2%QPP;`e(XK&rl^oeh zLNqhjuHRK;hXfpg=|JM0Yn$p0Q^H-8k~^(_^9wCFAkj|QWq9gZ!M$GYygRy&_3Qnq zZ#I9%vs{6e`}M6%gkEIa=iYK<>Acn1G0)cX^y($mmbc&ZlG?>FCj)p>$ImC+F#_BwLgsFc$5Qh?=k+!#lC*pABHe@bX(01N;4F8) z3TX02aCIx2*8=Lc*gO(rH#altMMOrH<-=iIXr{B4c;Mb{0rxjUGKcrLweeZiEHufj zlwC?$%A6N?zhPf275~hkEf-@(Kx2=GbEG)OY%H1v3JKyWcl<3gE@tX6{EpSPx`X~Ya6Oh#Tr#!i;B<4q02-9}zKisz} z+omn>-Snz`KMxDOzGJdHPPV&9oo{caMD5YPo2v*sK2%rb#Rv)fdw$9P@_x-^vFXed zoeRYRVa{Z3|GH(^3cIy_+SHbdvsem!SUclj zmf^Z0v((DXFS9z$$A+Cx^U)gLH|~X>^!mHr^e!+@-Iig}?@>p$&A&yjq2d9iU6DxU zqBrX)R5j;%4K|f1bF|-68CS=_yWYcO10xtiIA;@9T+J5ie z_Sk5*^ziiKa0%s}w@+7os4$AZt_e~{=*!o#e~#(@gBpL{fkm(x~#R&)?h;{UZCC0G>eMV;H!uRl7J>kPcFUZb+a#& zo-M2YNxWHpebHS+;$^NVjHcw@&%PvAK-iO1hT+6H+ihodi)dJX{RRa5#5Yz-V{?y_ zZCF5RQ;C@UA+`=Cc0SYbcC6?fu;0H?RYrzdtZkc}TBm{@2 z<7cOhe15!JbWKC^&K@1cH_kfRai9JY(n>7xB<=AJ^#0c!$CW=7Nxb>*?s2U?vmne* z6MPqL-7f8hi*6}*Q_4SI&n9+{Z_a+BaIbMkOLG4e$0sMpoSun?sgr1@h=ZAf#{w@w_TbjAxh_wA8KPWU*1;Q*f0Ki>a z=h#5m(O-BX9`8>~(DS@Xcu!4Ue7?wT5?B~7_KJb+X4dv z{g@N(*3m9l;BV?m;n?0`_lFDMq?R%kd8cZruFw9UANXbXU~N!+>I`M?@$W1c z2pcOOuD+cC>0*6>tDX6hm&8&WR@EzN+3bPa3GHzidgMm9-nQCKH9f&j@+B+^U9z`l z#UgmKKq_ogup$f1gX&ZH1`31lN05D_dN=5S124C7puN81RWAHp$Loz|_LWWN) z?kX4nO!;UQwsEa_v5IPR94@=Zx12s4F%? zz{k88c$OTo-U{c(WSImbu1&AHr@zpQ95c9IBt4(Xef4S?%atPLlyx?v`GbOrM1r?) zS+M>hW<9^GHzQq}e(noQp1fK9dtv`}4(-mTHhju|oj{poj22>!QjFTg0L{euk4f7+ zY7$*@GRHIeczpk&6{vqkiRD96=Bhd!*(;hsXPdX>J)r7-7re>D^#iv90s^#$rLqPJ zEXACzEEMk7MBY)|hie9PB;BH74z2b|AQ3t${mqWId2?DG>WVac0oh%BY=Nq+CbdSC za}_yoZ7Xl@^T@Y2)K@wxTg0N7lzt*2PDC?>YR>?}f)dH1Uf`4D?sxn}jt-%JukB?xOGSua)}viPo$* z4Y->a6PZ1go@g~m2O;>wG*pR|Ax+5wf{*I`)~NS+FWT$)MfMNEVz>>HtIiwkmA^XB zzaJ5{iBnH+a?snf!=-s^n5l8{hFzyh6tq=s!-kT52GK*SC|lI@TMdo8x8Pr9l-5bD zlw%81XY10K^Sg1QrqLF#Y-$%@gxeGq|W~>V%V7 zM~q?+@oy_V2^N+1jamEzWhUqdfq>Zl>@JgNZ!S~3&y z9uM&j{V|lJSWJr!{gpx=hY%`w#Mfnz_oR_~RZhuK*tpG?v)n?`?|EHY44Kt`zXc^h z^zaNhlzb#S8(m(V)z$1U?PHA<9bvCi6^A#c>o;%8lXCPrh!WO=!Y}6#IaGgXo+{s8upZKqo3G&cYGI$SD@*7{FWtI#63R{ z0JpAfEZ=>(2CVY9zjUox_xxDFZZk($ny#bPiNe-M2s%>eL3j>oSNTBQKayy`pY8T- zkl(e~>v!Cmj4I<#h!%zI-t7G#wI0XuvpXPF(9_RcCb{K3iSd!bOxd7+raKR6=Y5$T zWnIG|SUz`mD747r&DW2ymm?_5k@sYRf8R0$UV;|bvEiiD@Bib^1;jQ)E0#nhoCSwV zEtB?sN*w1(%lB!P{73H7ak5JGtKRI4lqwr59|;>vEg!)Spfvj4y?g3#%M54hTj+-n zf`*4`aG8%G_7Y6h6-^L%sEL=MUs@hDYcN(S=TIQ=MynZZ&Kp56QH|FSuT`&g8ZGC@RiG(Ec3p?cI3{XpTz3Y(POF%$wxfZ&)i+z_D5{k zvsrESCr75eB3KzKbxJqI z!3fu%!W*VCYFh=8J~h2Asl>`A4J;Hztjvv_U=tQHHqzDchG*|Q*EN8i#>0P?X&K88 zG;=A21|Y-T!K#de6f=pOVxVoNADi?CHlu_s`p28{9K;k`5o>@p`o!YmzFx+enHZ=> z9ANSs&{!SxJ1>Wmt+pjK>}?T->m~f7aAbMh@82sqzc&OW^)~%6EOkt{pSK~s`)hsd z%2k>tzM3*vHk3N9RF3&`nl#8VpmEsj@&BBr>x>rkgUIgqz%S<0T%QF*Jp`nb@aIsQ=%)T+VI(>T%$JOVG|Meyq%3fz_;*I9

    Vpq5!XR+c>&PR&A3 zf4IEdx_nsA)+lIdgC&~0`?8$4W?b&HWYtUzSFOgCHx%L;$QjSmLJG@s*LpjVtQ6tE z_VMwX*~r*gyKei~3Jxi$3a1Mx6Lmq(V`6#=3X5<3`MZ3eC3cF)So2vaSWC;n#;fw# zetC_)C!l=dZD;0v13b@X@M#nI@Jj!fCbTZ<0h(MX2Hv(Pq=rhaE{8!C^ zs}^n8xm3lBsgQtxw=6msyG@!&p?R`y@`0ol2qX@Wy_T!0+Q4yvJcF*Ls++h~+)DFJVmfd199Z^4WCrQ| zM{Vzyi#JQZ**bAT)!PPK3a+n~6S>saO-u8C(fb$Csms22 zY*e^@wV&YP-1rhmg8lhM&>KHN$IvcyVKd(~T9R7^9@Dd-ol;$&KmGW|gK?iB*ST`& z%Q;q_nC7YRgufdRssP?7{cet55v?*MuJosCT3tt__=(ct7$`zZ#7=0lwcF{Q&geGW z3&ijiOe{JEOFu}0l;XbZ{q7x^vxRkR%LqFgK$cwW;h7zon9Ie}nyWUu?RA)f8`eI8 zf8FehgqAsDP|Rn?rcDQsQ5N`a=deDg8-!o9V7a^MDjc0Vx-|Gl-F?LJaJ|hf!Lvis zn3m5pXs?6$!;z+l%jYuaF`@EI{S>yvw+aE3aCLXH|HWJ4!|4_@8d9>Roe}fd?OF_fT)tV`k@XhCticoyw^`Bk%9afxm zjbl#pRFD5`2R<+K#)>nOahQ0(d<_)6DUP%VEI|T4?#$gWjSFVpU8~D&@imV(*E%r2 zkogetOUD9CJHB~PtY0aa(to4?x!WHgj1j7g4XnMOiaT{T3)TK+;o@I zA9G%zRki0AM0rjnqULC=6}5Q#G1+tZW_& z9oAZg;VCTy!0%gJ#&|y{ZDU?nd9>hKOiLciqHaaAKNYPrNY0Pv%^xfchWV$D_7(y7 z$6veeGAxSUq&d8ey!`Hf=30=Wwpse;=L=P-Xd!a3X@1@sedr+97J5REgyV@?_yLLO z-*KTfKU41)FR&bU>FTs@$7a{+r|Q99XcSKEdUm82gaY35r3McI+`iePTDgJ7TB}1o z$7Wj>MRl)=|L3E1_rDs950tuFqS*Il9Utl3{WrsA5s_cA_)`Czq~Cp8B>$?kk zwcq=06Xb^P1ebGTkKtQ_R=o#O)E$Nzde+z}2Le>B#6H#I(k18Kb0x%;mgLD|#isyp zbh!HSScBR%>eL`O%6c%DxHcBEUb(4j+;x4#g+HUy;$54F+*%id^W{`G_1EbA4yonD zWsD_Ct#n0yd`r8olNkvR?>n%hGegYJ5Y{t?Q|)@IsIGwnZEXsy8t)@ef)t zCVMF+CPsxhk@Kz^@bK*y~3{g z!4%LRSEt4QryK~-P^?;dT$Cw651lhMR5{ZUVqBlQ+>~LccD^)S$PGff-vWQ{;dAlK=k`GCg6-eeXFy3m3}bI#ZXF`p8*|XN^Ig zoh-Hn=H2ELr(zIRP#<|JeMa#F8tGeFvaF7DgK~Gqyn^(!p$>|wbp)Iv=D2MM@|E;;~)6-I4FOTlHW_*rXT}f^5FUo({l1Vy7kxtZ%V5|5Ux{_TNMD zXcM6-F8!ak^#;3ws;YRBwDl!t_hI~W<%}BQTC9W%c(e4Ce6u73Z+s%ssXQ;{yKB6) z9n>gJEyW-1*y?#?g4=bUVYIzEN?Hi$XY~%heQ_a58q=mO*YEbFF_=#sYmPcd%s=ti zoi{0Tqz&6iUin2BWHzNV&w`5II@ASQ*E>5-oQD^GsrQlo^D=TYlwBl)+Xjv^aIF&f zDr()Vf-TV<+ua_N*l-Vlss~!#&Ouy%z%Q0ZATNC#=l2N5un9|Mn$T;sh#43D^m0{f z%a;$Ewrw-Jc`W7V5ytE5w&dGO?B2b5*uH^|Bpk1$U-h5!SAaHRM9}s8uKyl&NVQs7 zt26|n^o}Dgb;Lp(YH4`CsE7uIQWQN3*_FzypG87m8UPrQ8bVztl6 zl(`ve7Z_yQAQfPRhXwr9SyGnS0Sk8r9^of@+BM<*K8z$Jpm{mO2jw>4>#9e~(2PEL z`Vg+UET=SRW_0%=AG594tGH@0$f5ki^;+LH*g-@6neg)3pnphGXB(KWFI%?u7YtgT zCl79XwP{ZOsG43^L#AbH6P(ubUJl+HO1(Mw8#UlEr-w1lM*Pu5lX8jBuC(;5-Uw4C zu-6QeS4uY z>neye!Ut@b$;@0kGwluw&N>Poc7{25$5ToTk)`zD2Jem7G^LaM2PhmZd?Q#BgKKrTGCG=cKMpB9;?ihz??i;^ zeAE#9HB~&Phb6AaV+rth@AOcHI-rg#X^)$aNK7LK*XaJbOB8*uh-Hmj|Dz~$r*+#M z$(y_9gVP#!$1{T;LesV=q@3u;D135eW%NHFhHq&u04z;f&@<5@OY*K#=jM@=T_ zJDNJ$=!SOiZ1{cXN@xfx*JmXU2@`;%EB+dPV22Pm>P=UcWnG;@0HW{gvfy?VHqcq& z=D;*nz4QdwQExMFt)_=k%-?aKbQN6b-1_W)X3OvTZ&9*X*R8WIy%*x2AE=CwF`DoAas!^yKdH z0d4*nGUj_vPjO6R|9`hxUSiKcXg2t7Yl`RQ53Aj(S`A}ZqBSh3Y^+&FCh4;`Du&<8 zE;;ToB8ab9(7o~f-?r>m-7DjYR(u#1W7Ur9v<-VTnM(4QPCgB%rkhf1TB4Tv`1pt? zdlOs%eTK>AJ6%uCG_2+^DmshM+OsD}1touuC3E9s~q0E3vN2xy3+o1;cZg1YD>eTF|~PiE9n6P47^EXH#TqnCqymv*g6s1eY5LC;d?i% zzU&OCn_YF7%D=Y1pBN2oNGsy|GG~*teh)<*8%AOOX)VD6>KK8G7v_zjCLU4<-wKw-YZEV+rjF%s} zA-VUKz%%_e2fTfIoQQB;2x7Y}a19Nmul_?Q&P>R=^v0y&#O}r@`TP@dUZp*n9e;Fg zr)PG+QlR_fb5+%+A^^$1XO`eW_qQ4*v}uDY%em!Ndw|q8G!c8jj;U{Op6^Cj)zBBX zEIz2_OT4Ct5^K!qA03hxs0@BaTQG6hgDXy+@QU7FLd<_?gjO8Qw7A(9YN<@QEePV| zs?_!`Jdz@LGrf^gtYU7NFXZLc(!B6r%kwc@!gbee%+_m1gJQ)6Xm94X?HtcadVZmf zXoWu0Vt6ln%bQM@Mt~q|Di71YnGJi@Wcb$^0{H!2?^_x6_DF$?Z2=Q;X2P27LA!7W z{jkFsk45-3W>@ZU_C`SCed&Yh#bf3^*;u}6E7G^0>(4X)tzTN8eRG-^3Q8(0o|-{h9Bz)4*HthU1LhSbFE zOuKGFCr1NnCdo(zb+f&3YHb3xxus?%|2bG2Xi}O}(+V`yUW;r{W?}%0tt?vCr4ybJ z*kSi`wm{Z@1AmTMgz#3OESqg&a@Svr4kANAZ_4#UqIa zLHrxZ_Y-pDYkf&g|K;NO=PZ>}(Ps`!;l=gqsqg9OSyHDiP+Mgex$d&OL&3T?D@1y|N+cC=lcw;i~*Et>2#nnAoX#^AWk- zHEi=%xTLZ{;MBU*^Yh!MUrX27t(I47U^%6E9I^yqm}Z1`!PR^lS---v_+wd|q`V1b z*cDuv57J^!RV3E@vYa8mp!woHAMvnGNc)OA)~BMc?mVt^|*N4 zuz)FasTdFKf|Jyvw>6bRogz6>-ukkyVXYToN;+gA`qY3)#-gFcCoz8Y0B;qFfT{I@ zM@65q9X=|Nlp4PSY#`7pG1=q2`wG3<+R>kcb8m+7J>sPtAb|6i z@$%Kn#k;hCy~aBTuO{#R-!;g&b38O28hUI}CdS6=X_K&#$$sPKYQehuj6bFULq~pt zY!*syeNP6w#(igVW?$DOX~G2~bIMUEsCmpjC4qEpQn68sK;3n72e4p}mJy-!lugAQ4M~S}V(a>vj#4C?1vg^%~ zL53%`^T#v=~4H8cQzzuc|kJknl6@SHCt_+z*=a$dwufM?e)jtsf z%cE8MzRTP%{(c~pdF^I){hVr-Mz{1Dcp}!9;@~z`1rWPA(7#2L9oNH{z-@BGc5|9_ z!{l4)nkruI2(xx%rHe16QKlt{Zrd@~MxOnuSfD7De?pZl zV=OonPpUFb)BZm&KiyeFneJ7dur`=Cx)y+vYJ1JzZ+>d0CAsqq?y0k~ZvHww%F~xx zFhm`2UZJg441Z27y-5&?<82#>nX5nT@;jD*tAkKFx_4D+g;ULHyPuQbZ%M448yU9@?;E@*9mDdA=vc~@)Exf91^6`) zl(f)|Nd@7>Xg`)sUA7*{vPU+Tgp=1v!+%Wb^h~;|Rmg+5{5(fgJIhgf%S+C-qz3>p zy=S+dz25zmj^Dk8x)$Bm)XJXta;REzQMm%^lEoDY>icC^9Nu~S#l_v{xzF#8OXlW2 z&&79p&GL-s^U>#NRJL;QUEOr#Jl)N^j#EXhH7P}u$;70FCao^^*}*eYG#@V(dVO+g zVz5q2p?LrqPAN#unsiKgk?Y? z(Lf`BPf?RyABwqucxjizxr$@?I{qIlhfl)iO{bj%v|_E{5TyaiUS(!4O8%XRKuS|5 zxDggfHXpZW^2~zzrIfs44kuKav)Q{WRWsTcB-sW@q4(=X9Z+m{F4v4}YsNI?)m@EPYeADm|(la!VTWXt#_% zlpREOl;6Z*T2V~-sL!S!8I50sUw-ZIqEd&NkEj=z@pfYGc`JLl%?T}CT+mMqX6v^f zeH8t%X0Cg}z^U#~(ISSyqsi?B2WsY=e>T*dPk8^pdvF9R7+u`$`Y_QG&**Z54k6K0 zh5ao9{uo?a(1O-5oSg7JC+!`hMvVf3SMW&vq`)OP)&bfC{G{TTc2Ks>Ku{Hai|GZ5 zhq2pf#s7X7P;I}n9TqMyRN9(XrnYszrs6P)k`w!N2D)^(LAbk&9hJCyE^^zpAIF3y zKxs4sk5$@?ohKgq#jY7?Ei0XqEeghv@MU{UyGYEWC%t5y|FrMu-?$A5gtm@^T)k^= z>!IBZ7X?C3_`J@{CwS#*s6P7LB~6@0I@^|BR|q-$QpI4-!bM=DP5om+gW9jJY%COg zKbYh|RyHuOhaPkAG4L2~dTe)CaA+flA)6@)hts2H#D|J&qVGp^rrHkZw!)vIYeH+i zX2z-kHFn3t?9Ni$Osh~Ugn3f#ZtIWu#S zO?7dO@+|DqS<13eD%yBW7c7>gaPCry&-)e#h6_FAbegLi7fmOQDcIGZm=y-_W4 z%?~YN=6EgpV3k`^XDXw1+nN4+*cXrmOvfzZOl_E@##pYSPkW=JP#T1Vhvr!4rn}1}W^kRjVPJk*GSAa2jCCa8hz= z#cpwHa@2HJ;Qn7bzWut)68ga1c?R4+G-C~z--$Ypt+RV_0)*RdJ&g)-1`3u*mM@90 z3o^E=8>Pbky%l2Bmzh+9bY-H6LF#*|Ue>_QhU-&$H!oq!h#s7I^GYAzbAg>LDf*$} zRo}4RFr7M*kZ^!J=2=lVvK?57c8c$t8PnMF>8@jXmXtR6X^#p1DE?js&iiR0dD&X0#GunpvcFua#9DH_^UK$+&3pp>atCscb{YU{+F2}L z?pE9XTUwmAm53j6t=)O{En+gL4 zEC1x)68@xtDOl?@%%%m_Em&|Fc#Yeh;mn5fBLisgv-wkVpUo67UK_ZhH+6WQ&hgsw zzV9qbqy6sv6y&+Xx0P;r%7Y3QoRGUXw(l-}ccpVs6zj>1Q z`taPd{;UcL$Nl@!!-?txfa-_dxR3f*h_@|9*$(KVO=_M*f7XG3Are|=QZJVPnMq%Zqk7w(7b!YN@#U!~zQ$CMZuGrWo2DLAU_vUjnQ`uWzjN3 zQ1eqP{9Y9iEq8(cKLJPN)|A;Vo5ZkoWA+r?~*ZX7|kHIAX!*vnGNK{ZA$?h zsrB$^9Xxk~jD?*f;)ywgrTxSzmfEq_B;jVD;u1WLqQ;1Cj;nY9L!ZYa+O@8Aa|d}# zShZ!?W90o-zcVYx!b!f>Q`EM-ktfRt-NK2`lirQX$*3}|8X;;KIGD+}!N9f4`2-Eo zxJ+(HV+=`T&CdykM$5dZ22L9KFizIEbl&qfASJVmsZWoh^{g=IMh>239`!BCvix}l z8N+@1wzac&H0-fH*9QV_l=wgD<-PWBM1EHB%yjo$b;N^bhQE=--)|}1^23LogX0*RrOliz=AYn6s}anrpkrZ1 zOY~zUi-ewrrw(WWZrxdEnu2y()9t~)3+yR#(2L$liYG6Q3?C!OPbZLYsO)3d9Y3PW zA88yv$J&7jc#X@Ml?qE~BKEimi9+~lvako+o!Y{LW!fi&#hlJhe#MPT#}LSoApQK9}%w&jyI~(ke%?sOxa~@E-g@1WaDF*Dawx z>C&8P+vGN>YMsnjV{!ccte^8)wAK?Cs|&hf(%z(+>pV5vupU;H1RbPCKtj~^(JGc% zx_lV?=s3J@I#e;n;L@qB86I?j`o|%E%*J>rVUjdr2OZkV%;#Z>#0F-hTTJ;SGK<1G zca1Ic-nCL;s>g-0JcUm{iCUwCPsT2A>u-ZknibO(yP$T|W50EHMq_*e8Rojc!8$!quwikewu5vH+rluDMj*jJR!&MLoVN zQgt>mNO@@_SQRAYu#uy(nHIcc(V4AIUenNw(hJm%6XlU@HiJhIo-m<6gLF{MW%rXJ zI{tPT|BAE5RzA(bkMJyaePD-lTocfWck%WcgC}6gX}UQ_{@su<`IY~Su3P~Dw3xA- z%Vm>%9Xst`T^hc?Axj*3zJ99VbkSWY!?hBi$g2Y(wwKwy!{zHCo>%JQNP{7(D_AMz2eH-hx)ZF)s($_Ln z7#H_($SDpJ{?7(Uhs~xpw6bQv=&+yMDQiYk<@wOn25ZSH$Y1#{Dmi}yseyLB* z@7X}{rN0PN$mLN^h&`D5V%hcJRZ3; zUSv7?rf{TNuy9O$4_MnlM=z&tWa*|=L<@IB+`A4QH3`di0dHF7Cad|*fLn$gA8OJ^ zdGPn6HD58frfA)cW`NtO7?O_^w@?cF)d2UBIRBiWaN#0*HUe01Krz&@kL)D)JbWd zR>G-%EGSps4jVM5St`Tzn0_HMhYf0(eZ=9%f>LY>(jr$Gz53TQp&#oKcH1ZI)OXlS zSb6BV>LA-Oa&pD2?4T6@dk zJO|sPI`cZmdUS+G4_&g7k zOQ7>}6#0oC(90UW?SEk(u7H1N@y3NJQ;T7~oPt7Y-)&r6KCHh^^pTsI6uZO>O0<%m zY6$DWkk-^(P=<%^I#!oAs(!TWFH)-mjRDJJw|3!s5X>=YU>{+F1qJm7j95phw}ePl zFS}k6Flb-?q5>xZghcHcVTcI$}Za46fQ$W7lpSNuNuDAOh(mq&%oSoh~F9-g0`w!E)-TsCsjXO!^W`1~0ba4n- zlcYt(voNlyrF__+RyYjVM{;^jyG6&f@hS8Ff>;XMW;={0*16lu1^o zK$0Q9v9~|D-vr(0PI}D{gQhmESgE6ZB1zaQj!4py7J)yY5z%e|jK?;6K;G62L?ybN zEGP|vsC=AonVNiII{L4V`He6zAEPjvw?Af;vBDJdZK?5%#osYibZuF2?U2D+&bjYb z{8#UM#-opbn7li2$EydHjjwrVezc$eg~hrgR>uz8oSQw7T8D4R|Kpv@dYERdhZ#1- zIYsSSc@8HBo03D7t%R^DNpn8BHIF{{^*;DBNNjCU>zmdcy`-tA?xRY6B)_V=j03}2 zYzilU&YBHq0{)|DJ^vtv-jdVvr+qTZ6_F&Y@sllEKIFe?mQgbTQO}G;$p5N z#~R#^XxR$E_|2UfU6TMZs_C?(S7tl9eg$Xm7*%RZUkNF<8%+H3>*#}Y`d*#@Olkv| z&vLG_*vktv&Z9|DoMZpG^Xdv@*D8*{-^`c_AW{XsTM@;fvXMSN>?-d4miI@LuZyc8 zPfuz{yD#=w!ZSusx1T6p?T|^F7gP!?;5>9||3BWR*=o(hS=r-MBk;FYvN^ml3~l$} zh?>x&Uxmgn!sf=fXnBsY<=?1_&bTI+U&d3x@_2de%m=tZ!86wQaT|^P-%jPg;;kF) zvB)6Zm5TDV@+tf{6>~qeFKSNB%0kS9wN+EPn*;)NUl}b>?FPKik`0_UEVYmwbDqP6 zpuz(gg78_FFpcf;8`MhCYnuHQHFp$}s}J?wa=)=cnISTR&S2hCDM;A;?jqX|Uf2pz z+kSk46s$d{zUu_$(C+RTM`zqURvYoRNY0l_bwwG)5Nw;pr1oluoQFw4jQV81^?Bls z8NEnQF)XF0a!cgtXXA1{BR5rp9=?!Ty5lRGn{I;dQ4ArI8M`XUF_ILFUb9tHKgm;* zQm3{8iSDWS1AL*4o@duhQ>_@mY!wdYLxKP!B|!OsPzpHXw_ZtS&cj z{IfthY6UgCGu=%!q{vFEb?MJhS|!H9cbC^a#F_HcIU$K}z?DP`Cl}@9#v&xab$5)^ zJ-E_k|7t@K8`oL8+w?(l$MIfKvsu%&Vq=tC{{|BJ$qh;`v}IZZ@E$uf?H0LgrXQ{6 zX*1Kd`*&fbTlF0kb%=yVi&Q|%CuOf3YkYU9^p6+SiASC@wj`UM`T8m6!4>B4zz$}- z%~uvOXDe-qT%9w_EUMDL>-=5AQ`%0e7}c5jd=JFS z?!9-+ZJ;%zT7{!;Di|16I@)rr7~@Dx1jwb^cTgOE5Q#(*`@s82xKcQH{Q@)poKBhh zi?=2!h-mj0@v^wpJ~UOPELY+RP$A{Ap-!c<$YSAsEq|^11@}?FM(${!Q91VBJ=(Vk zd#o;-wPDwF8I1S1jyP3L0=UCEfPMP?H6fJ-bAklxmJ+vqcc0TQ*>zACU#36V$4@So zF8krEeI71_;9uzKY1QV?AEJS4%-6}7%7P* zI|ZkH0{%;wpD*T&Kv~xb-mhie@CvY!4YG+r-$>s+os{tWWT-(eYnPhJIbS2)5iWcw znN+5&cRa@W>QW!6Xdfsq%jtBuhEgQJpZwT{b-tXG-r%%DNV0P)opaSG;o~L$NE{ui zR~8~>97&Ia0Wv0;nTD z2L(gmPC=8c^&)?MF!TTKP8uyMqa3P1tDyuONx+cdaFN8cc!ac#!Q3HFhBd`>wL+G@ zz^u?E!(EuraKq3zj@e@&I1`D@Ab$-api&DBHJiNFTaqCH_GE8}>Al1}8Fea{jNEi-Zx{-w$r|i}9BMQUfd!ZHs z5_MN)F~-<*(t^x`XAce^DDX^YbvyALJcm{woIxQ?*LAf~N<&nHs5p@uzPKC(5k_5& z=&=P84Wys4>J@4R_at4MKkYf@Y&3afkmGD^HNQc- zBj+@yTUk=1r`ziZ&g7+bow;>*r3S>)Ui^e7eQq&C!f(13TxJUFc+S96T`WRFeZQVx zkF2IQ6Z1zOmlqa9)bSrQ;&U-AdFGKpa+_oGm1~$j^Io`U9ofjDAWlx<@Ks)IuP26n zNsGeT^@M(CKHjBwPbml8qli|TzbO3ddRaR|`re>ZSCDw_hJs2U0d&%>y5JV?9C~-XRyb5 ztj0^uIZ86`@y3IfTfwC25*+`jykPzK-XY*nOdU(`aabS!sYe9bt%#zXPrmu{VbEj{ z0r{BBES~y};c5Lc<1%@&0gL*4T3y@yKwS>(klf;+@fJ+&bRd7`R_9s28{gbZjAnFB z+K?_4OgJ0onal=NM!chgb6Hzlsc5zL@7T0sLYnAlI6@tR7PIt$I%l6+6$t z#>Ak}@uNGk=!(ErlThF{(L|R@BJFg(+*DXUZ$V9Tvu$rN`iCuS{M#1E>|JbeJTmeD zomta2D-B?G_YD`ny}oS2&}B+^=dQPYkBdwdt@pav?ENg;d6^*P#A+$0XrZ`u@6nfd z(Ka+0GcT72VEw7N$;lFWMt|mIoHKUL>Wn$QJ*Dhx|y>+K7`?uh&2Lct6 zB6t#8jIf0sz5Po0M!d?M_kmx82(Q zZVxr`=0pIsi<A!Saq~Y{=P4p z2|3=!Ye_%Ne_x=Ot0gG7wpfS7Ngq6fa*zUSJdQDp4i_0Gi*NnM?}HD_s{2400%v)* z#s|?ElC~Vl?e95|7(aCH3P(B`N!gQL7}blCHC@_HhQ?}j`c_;fXzGiI61+ge!!*+h z5B_iga=KmE+vDL)nPk={Q7tujtf2;sN^{I-V+Cs~c^(r*%UO>}GC)tf7OC0A5OI*~ zM-!EJZ{DUQzQbr{PA_}XY)@=5ja~e-f6Me`>KO^wMf}Xyo`4yRy7Ty3xf@m{e1;#O z<1zN{B{vq1A=se;dN@lx9iKPSolZf{48q|9Zwf}U2h1byd@cS&N6P-P4Br~bKGO)V1xyJj44=LyVNUgIdX2}KIRQ62e>LxmCf(? zkNNKg7HVm_CdGh$%$eyjPeR~In(p@aIe$0ekKmEED!9AlZiI*b5NeA09 z;tAPn(rx?gC$ww(#9$%64!T=gtPVIl#*SFSwWD=eG14jHd~bK=T#Qw^O0Vf-G?`>b zGGP{$Y<_Vh=H{;o5_78rY#v*<8Eo8RKsF!;wLp!kzlCA@HsQY(J)&YKGC&>bVvT zasFNIqlL{NgOC*(c2%#)qxR+LyAtZV?Fk(Fd&75H~Bk%v+Pl z>q4%(oE>wQ|R4n;j9-o`a|(`Fy_Gqq zt|GJG5rO2-)FdUvPAwtk*uIIi2ESXJtFAOlt4Ua|?Yn1}Hiow+YHS(Ah!YPdaQLVnc&BF82cS@7*t{qL@v-+H5Is>;;YI-iGj-7#PC)sUKoNirWLmk$HrO3|g!6;^$* zRDebVX&9Nlf&ukA`{DF{EdGYk$2&EMnTv^rJYj7ge?Ui1>kZCP!9@;y^W6`0_F_w| zjn43qy2^1hJlV&e($=`^@N77x8q>^>KOZxl7N+5JJ)*70+Z!fmvQ6X ze&{=13t!Ivy5?MkB&(0oFhtL!bpS?7s`XMVpSH_zC6kh%<@YgzJG#O!sl5n2gNe8X zxD^^7$Ixq=nSVQ?-(tt^s?`7!{D=+v&hAp4*7mBA{ItFRmCWG2JJf3#nfsWy&&k-( z&9AdF5sFZU4))f^2#b;)49vr@U-Yi-TTs`OyoaV#kF%`lie8YaWq0W6CXH&uzm@JQ%VCy*=_V55>Sf0EWr0l{s^Y`m7 zm*G;Sr{Z}d&IJa81V_ga{nn+v^a;ZX_u715c@IXNb>Y?U{vecr-*+v`{EG_Af6}te z(U#u`f~mrACFySB03CQxalX8tmeQKZIqZqwugdrYxOl3uZE0>#pz_c_a$0qH+{LcY zq};*D55TpU^M)|4n6PH`(*!iq+hl^0)HY@CeeJG_jiy6y53elIaH~e$A3Y`mANTO;6rNm^A4Tx z)Sv~5Z@;w8DRjh`o5F`SOJ6FWGqrdyQsx&%&XRa;UrMk5i%7r*?9|QxwOc6JJ zu~>usG(H%sJU-qFN$pJH1@rePsvnl|p;2O4d@*i9Gs{KG78JF&#W;kHygk7ssE;-k z!P`d6(W+P$G#!5cTHAIi+W|55F~Bg-c%K-0&5XzS77+78bJ}7~bFEZqEU|D5@gK}Q zd?t)4eXnFo)LG-C!1x*j&Eq~N99p0ux=TJJP4rx#j0`OtICIcS=ktYNk1&3z{?Unp z1<-AE9pARenVvwqkS9#uT^MZywEM@iPJR_skuC%J+&A|>Vr03sp9Z?0O##$8unSM zuKX!WHi>t@*Uz zPjmEEo|u6>0_dWPdI+OZtIZrg_M6-ZCNEFyGS_2HE}+{9{?Hd16|KA+_za90j#aiy z&5J2dle$AnF8n-RxlQtjmJLAtcT)*bLPg&<-7f;4v5Y6*2yD2KlXL*W+g2Su^n_Rf zVa?~Ha%g|Celu4&K2&bac4&fRXo{25k1;ML`X=hib6D)Ox!S2oeq13Tb6+utx2WaB z)1H-wzdprYd+(maY2Bra|J6ILT)ppX?)YeTx7g#pavlB08g^ycj*|jYWiG0mz1d$7 zBcc!fb$V9eX}vRGZ&0(h9GdExKoCP2gwSi%D6s-~D`jX`8J@o90jgl?OC)1HCI;Zi zc!L8;n)HM*_fQm-=&nxZ zjiB~G%A;j4CXaq9nsjm1cZOR#)-s}N7p6}2G709E@N8TKtrU+yztbrio|vtP9@xeg z-PZg#XXiB?z9&lb_<0$w2QtUcWrwQ3L4&O~--r9}?7D3SEV&Cnu77xZe5H2Mx7q|Q zo2b1d%O1|u5ti#3enF`nV>eZnR(DD&; z1cG)0EGzaKlmrXti<{mEe)t&A`0eq0NTxRCc)&wiqeDavZ^QF_pS$y&lL>v7*S6+* zL|kueU)kZupeSght89OEBO>YaP*=g^?XFK%;VoLROW2eA;s!z<`=TITNjcVYQYS`X zIX`}^WoG@#A~Rzj>xM3H?(xvYP`y@EpRGU7s9RFe7gq@5s}sNr1pisOVnC47WXQQ0~I|;fhV@>yw<< z%B~yajtXZ<-1_7eNLrovfJ!3f9S^8lL>;1N6JPH;3~X=U1FAt9W@eI(E90j7*~J z)6J_6sdV|-(e2i`X1Z9RYGful*jX&v0=}Pnk|(Y-R@X=dWVt$bt|1RQqS7>b@Ot~C z>w_WgGW*MKw)r)x)f_sNbs<3i(ATN53N7adLM29$Um7$_P|smNnockK_cZ5M60DFg z-i=(5^R3K*0cJ<&5YU|D((^_p=g#NSyPO#67t6u zjY1OmD`uE38f=nq!Sg-)GFyGkB-=IiE&0czFNQ_O_I*h`eKxuGD-x0JfSA)4SZrD) zI4U>_er1EM!+^i?(5jZS<-9g>_sETBw{31YjJ|Nb`~C*oyBqXh(Y}$`=-E6FRbK*2 zIJ*Ouu3wzaDpVV4tF`7``CeQ>KOyz}_e0)q;5sH)(svnO>#gIP@j$*Hg*$zQ5r;)N z;``RO6?U>)0Xe!}|?>A7-LsJ>Hu&-@o2< zTW(4sst*9+D@{iau%93DmA#6UmTr*0>gE6N%8Q04d1<>IbB{Y55PmIt!HZpN*z#!# z1j8+IgXk7L8@izCGK4XoYbTBt2-rUnNPT^+6M=a_Ob0$0cvrxl z8f{-9=DSt9|J|!m`g0jBwb!EU`9Kg0I^F=tY+2-)G`8j(wt(SJG zn49%TqS#ZiawmF-vYeKZ2fi7JZBFmIeDhkPnmG4cA#Tz|yv1vH?3o(Nork==ReN;( zf4D0pJMn2#No% zYWxG^d#fCj7J;8Jv6hSNO1Z_eELi>@4te>_Gw5WHfoNN%UH?Pf`9mMg6eD}VbR6}o zaGkYv(lCyGSP#D8nddG8Pc@pQbLdRIerglf?=PuIf0xFT@kr9UndXQ7@}d`4O#t{k zTCu;$*(+m-;E$Y_`uS>hb;mr>S(Tm5>VM)R5c^nwJHKJ^5G)Ta+TP@3#P103sWv~_ zrej0H;{G|yqapAl;X17|P6t`s-+dC!5*$T*L2*m7o`>v>i^*ro4(2H7rs zYv52<_m#D~>UG-tTXJr1W*0XnPs=+cxtv9Lrvc=IdAF{$s<{j`jyNpNa-5zOx)oi` z_DxdzCo;xu+nV=p%x`#fBHAWimVxRBdUu19pzgbU!Lm$h6mc((aNMDLPGhEH z&7cT(nMvHaDIt2XMS8RqQ^wawEOpx3%os1*efzrh>dE$I#nCIyWozsWPnlGlX1VaW zz2M+W>fDBz>|hG1AHB@tr{yM8iRGBm{X2$pjM;wNT)~7_n@wHwC_+zdjYR zPC_zvg}6-hVDXteuVXVE-FQk59|!r(<5A+eN_JjD_eZWcFLQp)E^w;z&fs1B3$gRz zv*yDMhlD<{9KWHKfim+VZpV@uzotqX>B*;v-=0G2GtC)OqooQTny3tT9#35CH8U<; z?_n-o^Wj@e+o-d5Y(df?J_(l>{Iq)dDnBULFZ)^KUwLp-k2^Z%?1cccN!ROAVb^rq zv6Ni89~NDpTkcXXQlT%ONTTPc>}x*eH0cOuwF-XT8n5ScO}j({Ou7quncIJSGuxt> zn1cR}n5|>!NV>W6y14EJ2l;K|o+CFpI6qA**6bWVpxzg_wKiq`Wt0M~CTt=>J^b{JMoD_ZU$Wxfi zyrEdKzG2gM_ni9&pWA=gSJajC<$~;{$PP8H9@z~Y;gR3YUK{7WOn)K6Xz82JPVq<# zd&?iZ2^`CPxfYq zG32Ouq2D=uE4X81Sk|$$kiKfTOUR2eA*6%zO8OJ?!nb|1LhmaV@v6gNw9WF>t(AFu zl}~#hUp>dSeW2|?)7fvnsHj?%f@^zxMXGl`n%UGU`JY2j??ivBFdiZDqqbvdaH`G? zPf{82OT>>_mEF?fK8059z1-BeK}+muW8WQB!w(n?c9trJv^xtYCBL;d2{Zg8E)4(D$ngY?#_F zkpJ=PNjZPEN8slpPp5Wdy_oSiFRinUmZxy=Xt`;%Wrp?v$I{8ML`RR$HH!oawTdMj zT;vQr_ZTt+DA`Zm3`~A8JYbZvbdtC-m7#*)piZG0=?U4vdE@;`X#h=}{YR7&Yeq7J z1*GESTy+LDC{H{!DB@PFz51qj+gcla!I4SdDTm;IKNnxi0qeZ zC5xWzxU#E8uo)A1f$)w}vy(7NRK z_7P90s=TnJ9|Q#Kf6umqqiPrg=6onc+C%kj_nFqwz22YH_h#znG>H4#?cUUsZKF20 z?JPQbLIMvI8Qd{@h)tj{SwcFcgL8%C6D~aV|!_u3;9O2h$ z{`!S;XN~ah+c67Q4M)7tqSXq37w^=GyL&Tn;Nq~3KV(1P2L0aae=$TB@JD6x}uFWx>);MKsisP6SmVCkDR|G1m#wD0xRp5|24 z-ERu)jP&G<&RQPW&4*XfjAeeC#_isElz(sg=(gpB#u);IHWkWVMPI8WOzIDCjn8<# zF*sICciFvq?Qx4|LiJR`itQ06VLa@iLc&La4de1WdX@)B#wz*o_uc%zK24amihY>x z5;uXfDW{r`WysuNPH;?hbLgxo7``ph;X&~_AvC8}^=Wj;n-yZFEN*M-lB}VjpJ`*oOznEGjt?p zJmX3Fa}w1ew6Q{UP6nOLmjcXOA~uVguZ#_B-%vbL!Hsw;Ap)f0g+h77QFAvEOoxP4 z$*wcO!aD!I7ItB!CBGMnk&QeS+>!O>xZwo8=em%NtTkp}V{Y5-Nw&$JRK#Bq?-z&y z3{mUw&rfzdv`HOzA&kZJ;HEN?PoLkaB%hG!?~@OU>iX1d?q>?0;4q@8%gv9$UmZ_Z$e z6EO0m8vk*nN7thUl|^+mFPN5m>#y55M9)lqL<@F@qr1i>TF@N`N+zjo$5zU;9#iyG zC4j-*)-||}4?Csb-7UZSzseeV1lO`_oAI(j9NHz@A+khhKaP`FnA_V#EQ~ z5S#SV@;x4neRrh9Z?6=1_yzfAQR}YppAzQZi^Y>1Jw&fQ&T0QF^4X}y7&nsps{pTn z>L6UE_kZ?gKyXyu8@7#Ga5wWncu1es(~au~Zt64q3*f=WBTQzh?oFC$0-If$j0`$Y z7L;>8`=srlLL|MlRy1@sw$s>b2--^o6iH4h=LWy|60XgP$W6Dl`f;3YgV&A+)VRJb zN-V?cJ%+ZG4kSh1>#&o&+W7K3=$fq%EA|O|OiA-}*>@vcr_S))3?&i~fFf;_Q^vJ2 z%XQ3~y&0n)MYQeYh?kp?aduhWR%=E{Ng+*{HnbC?;HJ^i>~L*H;(H=ZmQ(1|igZm0 z9~pZ(tN%7kJ}!2nYMHm^L60Jltq4d8lq-jYa!hDP>inV`F13}*uQvj5^ngg;uLf`z zWr=iSoSS5Ot;jux+@n97qX5ZnS@QXf(Fp^%`_E)Obp#G|86ajKw^ZrBx;dZ5RkcHl z!EAD<3f4)}R#K&Mzap~=h~71BzDQ-})!UAoPZy1mQrj~or^ibYYjxUGG}Mcz<_^XS zh-2!JMZq3X$z-O^3iPWdzk&s9Y2z`Vr^^!j^vaq@fq*E&J4w^oB5p+I<9&!?`O||; zrIsQ@(qPP8ns!fNOX!&lx^}`mPp{2lbKyC?UqxK3;I?uEN8osq-l263hnHV1nwe4 zlIL*k$2%i!WoSXPwsCGz(2%*{{Z;Oyhb>IE61d}zS){$m>?^`#jH-zpIww7$(Xy8i zkV!I_1wuH0oSeX<(-(7E}R&@KRVC9ML^a5X7 zH)W(%_e;jo+@`Oc(&e@uAInEZ=0roHEuDDh5piGoJ!6lVcYq94SlK;0A#Q`#U_p`S zOQ5!cLpP1=Pl|M63xY!qLeA5Z2{(Qt(eu<2@buI6cz_N;;4#X)n|$0sd&r-w$q5XL z!T90l$fR$i?!sS{yT-m~gK0##`7p7j0lA=NoQX@H^leQ~zoiD(#-y=b%wxhf5*jxZ z7rhTdpytbYu7`!E3+-rH^<6shAHA;JZq%arW1|&wBf-tirqEBh5*Yke)S-yXK3{sF z|CUo}$d)GQ@-g})Rg!KNJWyWdDZSp|h>)h>q-RU-lS0#9Zcs&_w>_3*uz`~jz1x?A zQX&Giwp71E3^(iQU5*xQ2NZd$?|0KR53a5&SYfYk*3LKEnMvx#(rMZGUJTcL@0j@G z1?rN85O5s(&f>du46@G_Xml;mXpM^0DFuMP^2B9OF5uCIi^<@`#2@!a(g{%#$aec` zsn?{dv%O!>4qJKp*)G37SK%eOSkO?{(dW8 zp~_*(ehO!O7;^YR0Oq?ar!||*bx!F$oF;5suTTd)p!v6kLzXM($t-3NYx+zGq0SM( zt&62WRXlde^`^ZI$fqa!E?ZKQ=1ZqHEv1h>9dv1rAYzz0a86|WhZxv=`Xdo`8yT;A z3w)%WUMmExOH-DKM8fbrriK0iqpA-nI8c+k-C;12MtieR@r|YY?)#qkcI>YCMsrYN zIEife6$EFAcheEXb0_-2T}C_?6vy`vq3x;mgNNyLe9*<=I!Rb^QReb0|3hj~qpnxK zlf@@M!mIKr^~QtT)4XBEM+oP)^#X3O79^5`OkK28ju%ed;TN4>GMoDDEFkVHPF!z3rRIC`W=*F~%t43t z?6qTjt=JU&25dR3_Hr@arJSmM!<85qZ|xp2=KH6O1!fXVN713EfXDOe`Us7oJflp- z5PCuNa^DS+F5^9%?Ylg04Ii42Z*%0xxVv|Jo+j>n)(0X4k>T(&V3QN7HX#OQufd)< zcYH@J`u!zGr^g4(Bd(uA|L-yB;^bUq%lt#oN6hfq$yB@8UiD5^Vp?FlT(X=hUn}&f zDz%yro(3N;aUC6Dn!wPn9?nnK)=PJd%b3PLmg4pP^neN1A8~hHgO^qJe7gB$F`SuF zo5r}xbhzCRCa~e$!lA`2?-tw#~^=@6zt2 z2OL67V0M==f5W1`F`4Sr>&(5092xO+*TATvE4I-Qjof)MfsAR+yl0@6e`AJ=(cgQ7 zUyMsB_uOVk_eRTwf5ZgJg*gB2CL$YfAHlpr-G;!-i1-myZQn=5R9Z`PQ@j*j9!e_s zaJS|87gm9R*}1xzQV<$=U91{3+rPF?yI3?YnVh?EK9zF&u9-7DZJf3w!+9=9A$eH} z^7MKaNU)xjQq&0utxOrpI@tVX*^9Z>wDi~XMZ=DK}PE5bOy`$ndk_pmW2>` z?AAK>^+tx}P4U=uT?GOS6+}sGA16ShHe5lH6tAa1+Hq~A7ryWC>Z0hz{b(_C=I-My zOlIgb7f3C`Mr>{0WdoW)77R#YY{rNFOpYOEl1WE~K{2$2GsSqMi9yFs=fi}YiZ=qn zjdZn)v~l-MiBy%K^tp4U!Pf2;XYCdQgO9;=4|PHhG@7fGzK3D{#CIvFJfUK0PWS!| z9=+EUd|fn!*+P4|Ag?O&t#vIDC|%0bC1#~UJL;~%q#i%2HO=@t4tOS*yo!QiOr z+`8{`KGNShvw9t8)=Hge@oXNf2|Ua2?ZksOb&Gsu9!}v(-xJcf*#Fa5Z)CY3M^MVZ zNBAk&1M9j6D&uyeefK#tcx=PGgh{RkwL}U{czGnps;|J3OJBU9qO9VJ8|?xSkFTT5 z>E61fQwxf{ITjQl$$|#=9*69!S*g8h|6JCCR#Ob=q}I}Td-mu1^)6MsVU_dFNsRIo zyoDsR+6Uz=QSrFYbsXlU*R6*&P94+21XDuu1=9CFn|TAZw)`nv)f?KgQuib2x*0UH zX3yzt!i>rqMpv(pOwhBE9*>)gu*p)2oVt6c!Yf?hK0goT6}6q%#mpl?bv-=Hr$LtJ zT*jGZ%eocoV2K*^+F;C5MQQk&G+NRA*L$AS?b2@d1|$}_Pn>rD1V^rTDp3cc#oc8AZRnvtWAUkr+w%l$ zBa`4#FYTTraPbI(CmsJ^_FMQRLHP81F0zLoI$!A$42!CIRV`=w1ky)}Q3*SU#Lanj?O=cvr$||urpQW7H@Wtb^ z*0XY@Bb!xrX=K*Z%u0~_4xEe9cH61H3|3sA6mt}M(!BXkRX*#JZA3m9fj2^3FdG~E zV;}E0zp+9{%7gg~j5*07N zbrN+2a#z9W%*Vqz%X$E9eB<@dwVIP=lSLxb7Gee2izA$VA*$}9#grhB9q zmPj{IL+*VFKvwmtaRI< zGaY;e89@d(Vzk}-yMum`ta@(S)uRlsi8ve)zAx4lhc@6tmZoJpbniLGVm)_Q%~PUC z*?B-DhR35{LZ^A&aT$z`%}rir+B}8QfPW3wn$y8QXDnBV7w$t zb-ebTiK>=kGg;_rO@mY#8=h7$?T;AMCeLPKf%#jC0n^K*JuTU(d}-IBm;E{>At1HN zp&R2Cei1o+zBAFhs{YuN2BJfe$HBjBrT;tkrRBl2*9}_ohjflEX9cVE6iYjfV5E#B zeU~=xC$!SL1>*vO(-@Vw7)SB)&!$%fbWcD)SHpSc^Mkx4F%V6SIH_0V%1uzg?CTgh zJleHaq8wjr-hqj)p?9+~(;U*i6K#@skUj9V5%rluruW}mbzE2cEG7(t?vfpK-QSWe zZ~6DtifKZeThG)acEzJdL1~afUk_$ITHJTNv{$OnnLwj>dW6+(Uu9S&DTzRI%02cNygas_}IxtxsUbHk7pnH>Cv*)#7Cf=!IXvys`p$ z!sm{gOPa*&J8s!rOHs@PYwlNG$7MtA^VgT}{7(p!2QAwkREFdJU8bG7ly5-Y3e)Bu z*iyJ;PVo1rla5)y74|)I@{R2Sm}#0O`|#&t*QTKie7?{3*!29r7=w`dtq#zWTvTO2JKU0t#Gp!V`F!74&IU{NJK ze#M&VqE_1to2(Wa^!uLuys=s;| zA7kPh##Y<9Ftl?1$UQD3Tx^pg9x0y!(49S{WK_k9Yu-s`Y!z|d?Q|c^ta>9q6>^>& znzwsj`v`4*3y%)dG3W|3%OsVbnSsCjrsC{eoROAqge4t(RZT)Co?DWr+QCec9duz| zAoYA-x)Msx1QqKOaF7{w)@St5W^93!A8s%8x#=8oI%o)Ko5fxG9SImWQY@!DbpLeD zafd>^{$0hE8#exaN1PC-<55~b9sf_*;9^XsL_JnOqSoe`GFcWQ?Zfc;2tL_%Zb&R0 zXMYEVQWRcCzp@31es1C3H~YDk;!>!g=;i6SkQPuADK4y4Gw+7l?d8EVv2(Iy9IDn9 z!NQIs5iGp=WHhG>Fs_fL8(T#XdKjrGbi&Jlb3N3xX+A)Mgs4QtTCaW?@}F>O(LtY) z*J6wP^|Z5$$>7o@>lT7l&`}>Kh}u9;Q9bJ}e~-1GYWu2rVcPtw6qCs$Lho{I7IrWR z2Y$j7s{7K?KDhgju>APiR|wQdDm9sV-F6GV%^Ldga`jWNqISh)- z0Q+6NdrsL#lT1Pg-T6vmm<;c*d+fI|ydah0z|m$Oc- zC;?66EpZWHGVHJpV`{}~W<3QlxO)kp%bdWlOp zY+vSK@!#taw2bm?mN2NT7O3OYFJ{%loA39D{J)hFhQ!_@A4G$toyGuaGl5y@W}7{* z8s08cm^XMb0zz-dA{;Qa^^I*nn#l! z2$~fZ&M}EEY_rx=ZM#B<{QMiE&)cL6Bu1kmnSkJRiCw7x$2E++d^@%O915ReYVh&Q zab1-n2yC@gARuleCO{qc&R9YW3Y$>hu((LFViiwN%*-Cw&8g%X8dn*RG7$+Fn7s09 zaq$UdX|1w7v)Mmr-|M%Vfy#*d_elP<_=D46{{!I)GNo?FV3>u{Y`k}^O zu5v?ApC#*o>&ztoK6ZaQVG1c9)b5X;BYgl|c7Y)ql|(dEvC*|9-d&&6yHUJk*=n=2 zw8(9u*?kY`g#*vL&loV0xls=-f;njTCbiDhJKryxMy>C8B7_=C=c7;CU%GGc?Qy87 zDb@fLgt_;o-VuadOOz@3h{rXr9YD90nV`m&k8!ycandGY-QLMNQ|o@gek9nLQ9_~d z^$cI4jX$P}75DZ0(UC*Rfl8fo{WBlkzn=qtTNF)-V=1Iyk4*qZ!MW8vDsSttNJ6Cp zjbEYV@k88%ZJ@GeLSVM5U1s8<%xB~dnm^v_ytvE7U)Q_Gy;H#q5{4^ngjKLI$2 zI<;@fI7 z%h3Og(a5>0si1YVQMTL+#$r_d*1pKw7M#3yYoc~FgnrISn}9W09=>s#j-JU;f@;Eh z;NzJ`EgLb-4?f_hK5vY(*ra3EJhX}(h9@K0xz)R0)>!KEy`Ti-l3RwVXK$e)2K=@c zI~@z1eDRSi!e>gSkFRo|2-(@-8_fSTxv_zOo3jZLwGYdzss$rMAFZnI<`#k>0iIp6=29_*D@r7hHmFOGN zIDce(n}$JK0rY8>h698FhI+x$&V1`S9UtgbTcP+^e=0I9!KJ5?f~hGXt@r_k7Tmv`!%Ucpw_=@JReSeqcc zG3iUcyx5`?vHa50ij6^wDK9asFCfl^NOvSB$&d}wa#)df-sImyxv=DN1VOO6d{1&= zi_c%g5)`}z!iUN`RE=Wz)j88K%JQz<&7wh?<+w7{$=Tc{OAG(e%2QWQKM8_l4wdPm zr`Ib%>CZ$Nv)4!)R=*9~Nnl`1t%O=~7(PfR(;3!F?HRJfuul4Eko+@Y?ZWfoV$%_% zIl4WVL`&Gm?HF>>cNHsVi(UM(b$^cd@8^21gPpeGR@c&12w8gV52_K%U8$}{7{qk6 zih0b}(th`_do`9Eb^5)9=Jzh+AWB=i_SF34wi<)67jG+eXhpyZa!?Rt-53J0& z^GaFSOi%uE;7Q2ojZkiCJ>779cL~(;LFa0TX&2_bsU!;3=>lmx3LJury?P2oBA)Vq z&1>SenH=S)EL3>46YJ_i6bzZnQ_fka9vCuDB3(=Ql%z$h7Ka0RzMQ#^G>D}-A(&BzZA+cO2b4BLF8GGql6r< z1JAC-{F>wvZk+w1d95PS3m1@}YhoIIXFEM*i9dcn6Qi<>|8NOs3r3_HWuSS)Q{?pG z&z_jZt90GW7kOMTnH<)q^pPXx*cw;0s|&vpfg}3RmThAQ zD)xHDC*`Zf{Uj}wxQu;CN5K{`uBv{A0RS`2eKNFJV3g;=0I>!@-rb;RFF>7{haX)` zrPwFD624)brLOJhHypTO2)XBuH1{n&l^P;17td=BWa?@AG4Fbq{c^{q2V~Y-A@Wjw zlh}bj1$odA$@`~QCY}9v0nFH$JCtnu5|KBMu#@$kJrmQdUyFl8o_!z^uN9GAZ-nc} zYB*r{@j){%({+)4#d++6;h7z3fo--Fup{-6W4^V=?VgHtci!=kyGgNbAHyLyl0NkE z9{zdMC2*c6Vzg(X1f|x6VS0lTG!wrzez2BIu4pEz@mwcjfQRlW|FLHSEDP~D=rMWh zu?Kf-{(bDvXUPP{Y=l(UDE`R6jhpns4qJfd61G^?$+fpTFN4YSQfK(ZYVpofAtq42 z)^)9GzZ_qQ1S}JCL-$VBV(@N**%Ca4rXKM$NlKicW#(&v$j5W9HuQ-Y+kP0@)Kil* z^M9|m)Z$aaakXaqc?b^p$_day=S4sX{pfv%$nwLIv#w?-NNy%37pJwV6*(3xFwl$#Ir@9 zG`t5>@jlb{ElzTjXjx}tS5ui3BA8A9!Bxn!)0IU}f~BR@^{yxO%mk*G-V)d`P5Zhh z9v(xs$-%knx82;!HAaQ5;81WoG5$P#CHcw1roS%pl*-j)aNbveRgj}@LZ9}}g~R1a z@&S{x6aTa6=YO)56xNa6O82M0J|AS_1b#$xzABbHOj;OaSM2g)b263P8Av~e(Ct@$ zRb6L|_!3M~7^07yKr7rbt$MZXK4nLe0%YPU&^}omyaR%@h1gB{t3FhdFg9&LgYg8w zPL;rm4a$EaxeqZIank&AL>IP*j4W}-ti2?xz#)xV5nyi2OwHU+^{YeIq93c7Vc$*^ zR?GVQ~@CT0&*;pLi@Xwz^5n^hFWC-z59?GUe4<|1WDexQeJxdG(vU2R&caZ+D zfQ#h7)E?kXS~n)lPC}T}j?Pu|shOmGG>P}Tr5<&Aj7mk6pre}F>gN7G+RR@c<8dlB)=76WtKVajfBourW_=`yMB5v{D)=dhgZDva z>>8B~3x+L;!mz&nj%kgVXhH8~Ben5-`@V47P3*KHwu73}xiwOQ>Cpgx0df*F0EU1x zI7(VQXl4|g`Qg}(aa}l`xW8`vDjJo8La%v+qC0)$;sVPyE(reqxeogn_bc z4|$5Foy<4Gix@Y!g+#*mQi`*bXjA3B6e``?|M0gs^?Unjl?^1_fOqI~Vv^Agqq|y{ z7+_v+a*wH#zP<6}g{Sx;l5>ixtytqpAu2-pQHSZ zBuA9UjIZ_KVfqgFtu0Jgo{eu(kJ&Sy)4U7Vk^%EarADI?B&az|2cNh|syyGRzrV^6 zb#Ng>q0g+FZ5NV1?p28D(zduF?1u^d2&{|k?M?kZ1LFR8p~y@8*^~INT&iY}I1_i6 zIBsQI*p@6ig5AzdF4yNiNs%;ED^C;ieOx#UpB9{b$1s;`CoAfeOEUsCAsXH-rSdM2qsN_-O^*FNNFzN(VxBD zTlJQYd1u7K1ulRjn(c3}@Dc-wA&#eOhJ;M1(BGFY{czLBcSj$j8Vo;1$Lbl{d}IV@ zHyO-e_vQkFFu)rP&%0vGz-y%y*`0}|MDx$X#rinNzNDzLJoj>SS_h|n-13y)+akz` z2o-BY+m+2mwH<1T-&e-`3H2QWmlJPn<^QvX5Xt0tvRy|_jR1f_qub&%lcHm*(RC)q zFXFi}R)QX{(?{vPcGwXK%MR$wn=zHN%>dSHnRuj=jj|EJT9h022WFFg(Oy9EPnTij zvyPhBC6c={Qt*Zf#LuADkdN%3^bSZo<{ak}e9}@GF^4Z(fz$0VX00DV40bfZC7G{t z*Hn_FM1B2AKYE`)Y_m^Ixq#-M$hTXO{E2MvTY@GfjiQf2^m=PzyG1u;VjlIuzr!SW zNHkG$HyijjnxOsl;wox%)dWII|t+m5S8MBa1itvlRnBA4at*nRJQV zs!Aiun%tTyJqYWCa3rtLG~ zQl|u^F;Xp^U_)X;7d@oVL6e;7zinTza>isv$I*@pkF!B4azEF3Z>B!j99>=c`&of4 zS=#Cx@i4oX9H=UQ(Fp6%3g;~D(kqZ7(N{M`z#YA*LxR`{JxUtYa8V z%cKw{hGEV9g-RoMz~*k*671vNU@~uP7$c%YJ#TIS#A_L5;t~!o457`(%s*k+xr(J; z|JObYB0ag-R&=orR;cDq$n{R{9xZRWQK@+SUtJ6z8miD*RDBigD9I(8g}^J?;_%4B zo5sO_dg01bJcuigdAzdD_D}f3ow=8!)nt0Cn@c{5jyEY98wK(cANtFzUrDp^bIsW< z^Y_ox9h6R@Jbb+62^D}Vd!lN^z$bR)rioP&6tbr#aqA*6cb-P3B^ky++Q8uEcq252 zQk@!>vhUcL4lDL=nDsNHi`_cHq(45>2~es?$@(meSTfKW&YD3oaA4u$C`-B;D?Mhakv5059(wmKrFPyP zz{g@`?W;2?VM3~FzDML70<`PwKMYhx<)%;r!{2vbkJXx%Ir68=L(-?`ZVM3A9@mVe zt!XW$;EYF|SnVN)%!4`3(W7Hsu<`MrV1XOGvy&Bbl6n(0YVWnU%)eMY)rEIZqzi1~ z9v^#uoQ0B>JC4ekH@_xA>}7rtG9;Kb_GdSLA{;lqVhPidHJ5uQKxb_x7-BjY35McI z_SeETs!1@?2*!0c0g$}4ZdSVgy*D`2PAJ>5BA=wbi{=UuTZvJKA@|`wo0z>YYL&nhr z4afUl?}lYmvNXiINiuS$WAF2ADl9N_=WPQBN+XT0-ZPiuy1qw8$Kd^(9wiS&@WFlk zWr_;>TaiT}=NwnP#QB@Gva(D} z^>a15zp7vC?dS;Zh>UU?ag|o*3?0gyY>V|&EOw2a|2CR*{r;JTDRGHO{7HHCoe_^G zG^ZTd7e0fTD^9_1`MJmcSmSv=qPlnQo?J++qmz?K)`4q_?!u(}k?w0pMwz&+*d<}| z*KAhOtnfi&L4{195ZbYOx8dy1ujKwgR;GHv6?fw@5G)&>d>h{P!4b2i5kS2K zx2y^2Ful0uyvj<4TV#|wuZT#)hqQ6IU8+S54FU_3aeE>wVR-TZofTeFZD6s-!LvDW zu71tJ!Ii1hz(Yt_OBgI$cne&X6Rfr8CvcmEe*cKO`U>xk9dEiW^SC34EydD%@gJ3; zTD$o(7Oe`$(_jQc;S9PSYgY2tc<*Hj>hUpA7I;!s6&GghE6|WTDfuqfuWbNZl)HBAdTPTmFfhQY)`%(Dn5s!@%N6*ml=Oa0eJ?ln%4jM(JNp^+ z{2!)FQVXBIT_pID2dAnXGwpLYDnO<1S z&b}FuH59y94GinMU-C2{8sFhv79%qy%a%ADOJu*oaLL=ejWO+&?hxm;`Af+A8)+bn z?8q@u-&5BvzL_$d#+3WhLq z;>5Jw>*sgxS1;pe^i5=##l_-HnA7iJ& z@%xn6W@y4JCkM{Se5T{!;ZZzu=8XTMDev-_J#4J3toIc&*3O?>A112c;NZZ9gLH-< z$6ldaGBp#jkQ?IBDu3Y7oTUF}kKLgX4TqbfWN>t}owlv3>^B7!3g%^$D~O}EPo#TS zFpgSa+VGPQzr5{9d_{!qRK3K^nS%K{@V!J(YlNOPD>o7d65}(sn0*!bk5ZR$Cu}=k zg^MU4!Polkotj*PZ_fu!aR^Ad##(kBleJ-YJPg_Gtz>t9sDffuG2lhh06hvf14YFxs?>f5((PXu0l^YRsM z^eIU8YIH*VC;N5XTExy8)qU1adT^FQKAFxwUhyzTYI;bd7(FtRtozWB-8=Gx?l`U? z#uwSWW-GrpSIpu@+&X4mJk^uRmye9&QTnXQu$*J5iR;y(m75MxcrMaXk7;NYR<;Hq zC5)txC(K^``rzKnsYD-0^6~8-_xbP7#8EtE7D7&6`JbL6DWs(7doTNa71%k&?*Eqb zR`ATzD;tjNTPN++0l$`Kx@;%r=N7`7L&FF; zd3lxzNrYrk80w|l3}Cp#8^+p8U+C3hwrozo*JPh7h(29^LCnQx(?aF<_nz=4`~9Sz z0rS6$LH5{Q9!z6$5}(Eea1)kSw^&<1`6h$!qDmcfbw?-}_I&mx!25^$=!Ty4kKHmU z6VB+fh=vTMhNrcOg@x+FAsDi2q>`DN6t|j6_N6_8jaT5JyTu3MbaO^{uc-QC^&wd52O)*Mp7#K~1D|E>OoD)`W`ks}`^;d)g|Mc@oS z%^&>Afsn_lTNHHXNuXpy;VjqE9AuNSDu}qi-II^sHq~lPdyi}LDAYwy*W7;64r&%T z0|kZ*4-AdCq@@onS+RB#dJ9hMDSV|;sB+$zQq^rZsO*D#!%ymQ{M-uBF-`TYm~e`m zKh#mqSOBTl}2<)%y-Q`4BC z?utVgVW9Pn@$lip^}us6X?fGIsPV4}q~1rVnV6a74?U|RQb7N}z&zUws=w#ojDch! zIqGu$^Dp=7j@d}EkU;S>kvO4%H=G|w=%X;!zK^$MsaWdc*8>|f!Hn}Bv){?EqCKc4 zd~OAAJ7?U3%)t@fc2$6{RhggwxQ?Gz!bqoc#{M7L<<0OBo>s8|#|$MF)#fe43Kn^W zDkfKK1@8H+rMqffo~8%dh=IIlXc?%*N(pLcXb6SDN8Q2=89JRb2IGc|E_-v)`xxoh zJ;%r>m7x>{#({kz@$vC7OK&gzwc&QG#5|kq{>8b}sukUE7Tr7kKQdx#LL#HMfB(g?{r2!>^_4pLlwW2y`aSa-dh}xp=zbdcojOE`LT1ysUAC0J z$*2$KG2*tPXerp07x4|`5fJ?ZZu;HeV%#JY6dAdN^lmWNvi5YGHrmqPdJoM_g`Gct ze$mG}GLDY--rhuJv;Y`haiq=2XQ?Nc)wL0l8g|Tm!V?1KN(7l%bCUFvTLqlB^U$LF1j7XV6`?kcmSoc9Wd?$SmUf?w{F#|aH z1vOdcDoY$#`Sopa?xm9wr@!jjP08*Ta$F62nuhg`NO={pCYzYq!XJTdL!zS&0FiY1)pEM8H&}4Xf zRS=o_b)}t|JlP+A=a$&kROfJJA7sDGAS1hfUobv&tPbBO3oou(w@whcx742gTbvYB zLu5#Nr)##=Pwe|()cp~x&MyTEpMzT#ov*KJZs3!Vv9%bwcndsN((3##X?%G=K^pFj zG3$S(`#F5#tVkL)+X)bvL?<(@70TlZ89P`B^ymtY>&zUuk;(umK7bh@R?dI?&Nr~y zUZCA{rS1egwYgckzm3|4cf<&DZ;!;HlPl3zb}BcRszErN9+FGek)wg~ zuTY||{5uezUg+|+3zC7D+u?DxF*WF-j2kT(4WQ^CZ0e)dR{>I4AaXX_I~&Y+DauX| zC%lJ2-9`Av>Tt_|;$$AR5r7yrPiq1W#dt{9dZplL+ zz3vSgyUHnP*abFFd&UKs;Vp5=T%KriJ3q`bix$yuJU5_p@hI^WSQAWi90*n1_X7Bi?SaLsxdE z-6QF|z#UN;;I}gSFXH=u{t9fBg_?aR@6`m4dh1cW~uS`F}e=WJ;a5>q#5998KD!0gA6 z=ek*X3+e(kBChR)FpgQ$C+YNHM{#a{)nXjyf|=b0GEeBRrPa_<-4ezywMxzf)0tml zZmCv|&-P#STsM_k)XojS#$0yA#F#yI}>Cni_oIA5Rpmn_u|FMCg8Qy5s}SbZ_dG*!f~U z+lN4wmw6ai&l}&~zx+7t3YY83_|0z?H6~JTtd($i^&xoNl~GdX{NJ3%TgDA|yea34 zSO2DUK{SbX?kHJUSOjIJ< zo{!EIB=GXf8yyws`pevrg}=b+92iX3yc2+am1b7?l(j-uwEPbRE^%=^y5KgIG(Y__ ze3@^ulJ!xd$`TiqSee!Hz;2}`@sPicL%3!eAsT1`hgEr^@ZbDuRI}{#oXSIMQgPh% zMsNgc9`LFQ{fqTQ|6EGQI*66&mxGoo{`s}FLP4>yCwSbBT3D>!()3BtQ1u>Kg)0v2 zdWnOw1&e5Z!DN%kGFU6zB#;=++jR;M{`nyf5$cRHz98dGt(&30!5v}|LmeaL4uqC9 zJ)2f{*;BT*wtfLc>^V4k#!|KKttAcF$1svMm=s3{Izt5(@8+-8&l)o6g~`duDhCb( zUel{5GwdkPVCh8PbrRrZWC_Ke3~z6JE?2_D|Q;yYeg*!n8n^ zfI3`n+Ee;v$$6(F!xg!l7fToDrWlu;O2s6q@bJxs%Wcuds)vzxrF!);no!N23v8xA zkaE2F(1gr46xzC*jut{r5i+{EH^;u&&Hnrm92(l&^d*nu9fWH9`z|hfyO;Lv<9;#~ zkSf-j@4?{YW!!yByWbgXo3CTSsq5?OdvOUTRNM`196z;Pa+mU<snoOV~cyiesMvF??y0OX8_9tNi~|9j^rh1fyS-d+MA6 z3+0DR4k#=y$4K?0sYdVC!4K(Ot^4mr6VFC{HL^sDnM55AXYOmF}(|Fy0?sqF*^Gkf{S)V@ z@#A$N(pCVL$SAD+&cnf+U(l1kVtn!mi|(N%W7LX0m?OJstZS3h(Nm}LH13q4_Dqo8 z_dCiv@W1VepN2> z=Y@sPFfV)&S+JcaKQ+PXclmM%c3cCuXnYxv339|oshK2kxWS5dF|uXe%iW{s19)P! zPJu~2?ynbUJch92j3uqz7JVVc=7p8Uyy28D+YAMRmLp6^5W#IY$VD{p6F zzAUb43(fp4{nKTGWXAfrz_7IZX7|0LDx5_h`2JQ9+2`@0ZniA>t2qWx;YA6M z@H(>nl4Zu}rH`LJZ9AbM2V2tuf*sv#-(O3!bHCZU$Npb1!>8D|1_KzCz&LI?I&;|9o!Ul>{OH zk*N60J~06SWdM#gHxBwQrl9hbK~UmqvAF5y{e&9jIS;_X?eeM8Y@XQ9^%$B$pUHJd zPIl|6Yfk$NaCYwlNx4AZ7<*kTmGJoz_}39|7W?kAyi7>jwY9srQSvx?7+{uipuk97 zU0wMy^+WR^Wht#y{>1n1r+0b%ENa&os9JBBX>!)}&Oav)d1r8YX5N~|e|Wrj9aSn! zdJ;@cO--`O->%=Pd|~YZ7XZ2@`EJGezu*IaF%LH-5e7<{P#(gKCWQ!(py2Dq4`4im zfyLq7$LNFf@+EGgqi`{IM0rwVqNApEm5f@d2laGgY8gl{D>Tg5e{Imsar^^Mo;>mQ ziaps3l8}w|$z-|{@*}KH<`jN|vjO1oS5r?q})J*KO=YC(60?J&wb{PP`?#~G*Ew^ky zKOya_ZsY!KWTMMK3PRrs#dXLUUJQutDPH0;^Pf=Y5GYgbcYdd(*w)@THm>4mqxr${ z3y8pdRx*ajxe z{E1tS@%Uij^inD*DUmIEO{Zhy#*KGC_-Eqe9()%{I01qr8K;5qW-)=d8kWN(qJnt ztH`YJzetJ(pQ6es( zS2ApjizHpioeQ5UK*?V_n2HLseAIS zVSbuMwzqY82e?MwXj*;w`t<{<&xEEHvBS{~+L;x{bUA)s;6Yvi5Mh*r{p>#+0ikX|IYGCRBykhBH#IYPH* zp}@3&PHl(Lb*G0-=Yz0C*crO48Z5pMgSz*WbLeBC^HciF>sMfssidQHr|X6>8qcI3M(_grCfnkX>kM(0QD{bZO0nWB;@}X?AKVBgtBslfyW5EUtpCrTEJR(XP^`2}pp_AL$x@|6lc zjg8vG;_@gCVbT^17w03>&#bmnX8xqg^BsnDH!p!TH3qWd381G7C{=vLgJ>{ggb_=lA{o(d+4xujf7P`?{~|T<4tYlk7t3mgTXh$AKDz z!XiSTEVY3Oz?wsfyu+h zM-Y_~l{*>?2Zih*;wpj0=fF7=?zzTy4_@l)tf`I{zT^28G^Ah@bk885*)T0pw?+Y$ zvCJ$i-`hj3R?Z&KO9#G{ZLZi=iBA>m}?r?_m?3p;}JXD=g44yPCWLc21 z!tOx7(<&9}(wzvP)V`#Zv?0sH;>Ql~oL`Ki7NX8`T&5nL=aI*QA~SqgfC?TzBbHb1 zeq^JmOD`PFzSF(`3qLYhX-!9*#-(WK-3a~Cx@rh<^+K$Z{wIFTqof-}%3ox5o)=G{ znMIywS|kaL=KJ@n11y!B7IyivdPVFO{&nQddvnMXF7%DeD<^rwX-5+OCibSx4kWrO zx`b>dvry6-BS9Dq)F#bWWo6q*yaB)dv7dz4e6n9i+%Ns~vR;8R|kK;CF%{lHN>^A@8-HqL+swZ zjXpxe5%j$Bb7F3<1xd_J3&c96vL2>*2Qt_ejyhe!gy+x1X<9Nc9oul4i6BE?#x+dz zc!n|CLfWuy`fkoS)|5Q}2Qy4wv`l-N1(>_J*bcr!E>rLB@=V&LAy$K`?UHs1W@&6fcQ7*NJ_qIHaL|)i`hUF$#mjZ#3^S zk~`_GEtRcM`vilowJ0bPydA#5-aY#lEN0F_Qy2mqzw8SHF%HF!eXEjqGkkkcP>^q` z1P)jZP5Z(4&x1>nD?A_0l2%1lDIHe!6A?p&MIey2hpvxzp$#7g9p+q4PR>3R>dd(U zrsmex(vqMRzSAR*I5=p8A&u08XGC|Ye;*Acv*{6?(6cp^Rqf$f%Kh+bLi}lR8ktYLU7(o6tq zfNmp5@H5}UQdqNsSIOBlbMaaYF7Q0(UN0B&8r#|!>yR6EnXA#3m~6H^ocoxFxkx2I z7kTx=oHRdz3i_tz7un}^{!_%zl=nd-MAu8}b-et5U&3zOG z?r9BlNwh<>=QJ(Uk<*I+^mu={7#5o=z`{6anR-E8Q$vTO7R0-0ig;V-f;br#dggDy zFiLUQojK6)=j0oQ*KO+sm9i9`LyhUL2#(HSY_Ifqx*7wMfvOqcp(kq7AMZkn`vYCK z3QWsm*=&=%9psE=M7A}ao~!DS#UJ3yL^rz5NNL`zpQ~mqhYV^=!We-uSl+FbNe!vU zT{m-EQ~Lq;S4OAav5Irjv>l8ma18074X@|@T||)Zy$N&$QED8Y_yarFFMx-zn{Hyj z-7>^l26{|5nXjqp31sxbj4uj5dX8f}An4dDVQR28aIMt$G-3tXa;?MjBKm74kXo62 zam2PM-pDGa^ObHc9sPp&Z5YQ!nlST;;&e4e^QDAaL#f1C- z5EO}s+0}1Yw9fH{dIXkMX=b&_Vx5BoP6fwd5vz*pux#I>v-6%zH5``PG7CB$E*(9Q z1wSLTFw2q+F57{M>MmTS)}>d!YA@oy7xPfW>lD+)i($%>x0VCgR;t)S+Piy7?k+sp zoR{YAhD1qs4cXqjQw1z?v38lH&u7vwBmo%)^bf1}Thy0T~*-Fl{><&ZB(>m&Z!iRk<3zIilFUo&y12O28` z7a2Nvs@bVfEY#W`?nlpvdjH;CJbtpJzxVT=+R0eF8CZrHTE7*LI)|}xdZO}oK%-{Y zF~&Gnt->vB57!vg_5aZ8k&EeDeq_SDL?@Uc-*_cFyv@liuvXaGIUL-SAA->s3-ErJ z9G#qciFc}TQUPgRIegTgrkgQ^z6%Yk*4Z?%mFEoM<=N^Oh}I(|v&?(D4V=ZsIXzn( zMi9wc;K8z{Y}vA97rx{Yr1kLgUK~9Zuz4U5;qtTE4bLlYJ;EVtvK&@Bro>I@i&w|n zHBB!bVGLd|iAMb{jv|*S5wP$xd0psI`Q-=Hc|tV|#=eUFOl?!wp%_||d>7RQ`rC!7 zNJ*Cpeh|N1hWNIt2~v#D20jEsG>(#=B84dufU(s}qktEGI9Ip?ld#+gSFWKFr?=hzWEAu=7rPqjPnBsy+aMmn;(+%9`dj)p-vKOE4=zq zb6$Rin>!jOOIgbRea@RTXZnIj^>o?UxqygwnxVuB3<%hhv^(g1{|EEY_m2hV zE4i*uJ1~J$5jr2@?f&hjCKmm~zZ6}hZ@E;Pa<(&~(F9pIDTpuSpl>8`O>1h~PWzVYX78KCqV07mst~!<7fW19@SO;kr)n|w@E!xE-qO4s(Ao|&y>cx z$H%nb4#$H8T<{L8z%2y&tfpw{Rc(6xQ8VbhRL)hr_BamW@@xS@Njx3tI(~7_AsBsn$h^Z(z5f{F;t80^&JE&s2dVIRXL; zF4ln(m%2^n#fum0f$v8P_-9T+Jrs(6?Muzy<>l{9_tCF;09f-4F~K89)}I7CPcZ`B z-U4Z6MS>PL>AIIDX@MifoXJAN*2$yjsmLGxc!F=m3ip{RK{dd0 zJ8pARpSdYxpEIY2?=6?}7cVZ*w5O%LP!u2IKsQ;__58P5=-0ha;usMBQc8Rg5vAV5 zoqdTMRyz4GYz@WtJYZ<*Zg6RuRlaF3eJvrSw2k%~UGgA!56kdCr!aW}gHy}VHrqPC z%u5|P>fO)ZfP4faOsQ|$wCQB~)eWvYKfQ`t-Ei!iFB;l8zNfX93LVRxAW*8am|I#d z(9?KXT6$!W%`a_0MLUlS%G?A+PtO9l7Z{>xYdkjF@?=9{hoJgvntUXf2wu~_AC{t7 zTX*M_oio6;Yzo(@=~(E!jLm>9`C@`yBYOs68;h+WUfMv}eILB~yx0}#>#85)uq!V{ zDt6(^1HiD+R&gIL+Z7m+rU@$OP<2-N>;yje~+{k&yntGp46 zU6bzaV*3gJX4AZ4miL;{b$nP-l7R$D3R=dp9xTZN&mlC|#_Z z2lpL_A;apMvH9aK4o^AWC5s~9#|kl6wJbArW>K*PXh#TaEsDf3X<<$CjA$qP^TRf5sgiisE*rEAk%iT@;7WXnN9aV3bp*jdottSO3hhNQ^=} zs#W(L`5wbrik^9O>a4Da0Ze>9KmQ8XHP))v=$H=;Z)_Rh$=P8r*({~BkcM7uC>!Jh zzxVGL$4V0q71OfSst(m0?Ld&wK=$5ht6u`%7=cp`Fb;u*s_N!;4|L#CSa9(Wzyc&* z_hb9Y!q1TLi?3tJln7V3s3*y4o!BdV!<Si4+wdCUE6v{US*$q)dLUQ~8R~9FMHULBEaN5tB=Z1B&@x8wt4WkqR#qnDW|cgw>2F^+ z*ZppTjm<5a_b8*n{p*`pwRuf_%1GH{OchN>-k1}XMAPfj-*&-1EEW~M?VP-uJzd8( z>rHG1JR2I-&E#98n=`@Tk-V!{(;siGspzwJJ8pA=4*z01Fy~N0B}77U!6ag(IC#R> zg%ohJ^vk15K1MW~0ANQwZK5a7{~UfWY&<14HdYnHf}1`DV|~vTo*=FS zLGWFDk_L($jHdbn9dg_AY2)}_gJE<1aR-_1qnum4P~Rt71e z)f~|1_VE#O`7&0#_yhiI*7Zo`DJIdC5=dcZKOSqpjUE zV#vt9xgPdieh;~2>=i*@-~Co=o@sw8SMsn4T48?Gm1w!r3vc%?OBuh5{$u+$b2sao z3tVp^(gU3Tqs)0rv``}*>;W_cqDGXgB}pNP=d!}X7g~Y4tF^Cu5uRcikp}D4FQwN0 zOdI-NYm2*b&)=0b!3F3wuiOsxygvr$KH%0~$hxT>jW-o#1EoZ;5=lc4VsfKEr5`cR zd48=~h|i4f*J&@aK|dGz1GPRaeNC;Kf;ZZ>#kjk6a3105;il6(Pz z$Hy~pP;7x~yr`9xRlMQ`UAyY(T+qlb2XL14bTc8T)w{MXZBi;mr;qT?KYZn+HW8?| z;WS@WLn9bMqEuzSix)*T98+~}2I^Or!Pw>4ys}MBqjhnT%$=yp(rrSV6Sl63)_o6! zpn7FLD95SCFdq3yLll_wT?HeyO|L$7!Zs)j^zsllPto5U#w!BRRWVW}a)N?tFQLQu z(n6Y>C3hn_2X4KJq?>KfYcW^mkfC^K3b(4Zv*_c1*v8b@?6d+sCGh$LB#7+FpzrTnGO=Rc02To&{Th8zuL-Yl-D|ITYcTdB*r*W>1i{!Q?;S@01oL5J&c&~Tgi{75t3=f( zEcYA~yDiX)i1gPQ|4tzo&I28^+!Nyth*GOGML#uC(yHQ7f=$~6N)Q84NSC~Lu_`?l ztsl4kGBR-O!i?^Sw<*kBzt2sQT{CUNPCkC5!EmzXpiE^%g>vDaW1l; z3~Z{VBfzr70vr1qx=2P2uI8G+O%qTG_HhC8ff#bmeVwugU4p0QYci~sgDhq{Vzt>u zZcjkes|^kn_fOH2#_QON`F6vcM^T#}%wDGahq+eo0>a6De2In~<2{A>fbM0GbT6y; zojp58QzMqdh;0OaQCOd-mIi5K0NNtUrV^c61(5D>jR!07+Jxwm7r-TIC+R31SQadB zj?99Jr`nVO7n2$rLmLv1yu%{N1O8ABhFF_St~j=pLeY=;B}?RFW#0|uh^$_nsyaPc zvMza-bot(SUGK4G`EY`)RJnGxXZTvkEx~Q~m+qG$jFhHp7k&I7pga?~tuclFC#mP= z`2v;XRNX)F7I+n63A)ey_>E=>zExE8bFIRW->|(>x&pt2414dqQoW_BFmhWhr zl2RcZjk(_Yb==>)LHoq@!%2=G(sZa+C|dN`JRzh7$Qs$^#gTzCzqD|ye|4n+pr=4k zl>)^+28jcaAPdzbWE^}~(WxkPE{}D3eaQVUK60dr;&lvm-fm)CTB9s-Y-6EEGI;leJ=j0`u$3 zMR3sO0g})kFYNI<+oQhnorLcpw3cR}D;BMzAGQoH5Y$7iJTv{Mo)RB!QSmbls@3^R z^&u*dV!&}_aV0bjdnt8lg*H3*k^JkOI>dH=d*wBzEuazJ*l$26cfYcMl?tRW&RO!f zH4BxK8kv|r?JLgWdm{GNI3lBZO#FvZnksy>73Wn;dFS(7%Fj64kc#fdw z$B+{93kb4D-G=)(k*%rW>}VzxBM6MO^MfPn@4&Eod|D|@B=ek8Tv8GMD$(-$BxN7E zgY&imRN|~An=0ap{C)mLw8?ku$!)yOLsy@m)OK(^U4ANLSnU4U{jpQzHs8W$x#ShxK4Y zg=UZkE5lcEOVfU7tyO${o7@IE1heYhYyx5vf`jLOCZd^#7a!MvzrLJRuFpT=8bKv~ zC0L4#EN!ojgN_cd276XOTe~MnPM&A=g6df2*7a+Rj^l_byzqj@drsNu#eGs{qh-ww z&YImTl6y_>Em*ef`;$1M@1{ZTaAf=X-MDe1VpfUn#IL6A2nto}&7|V|YYC7DlOz&t zXMBKt&_{Yn(h}j@Bxa96a8qX*cmbM6?*%gG1UyH!;)&@aC9lS{9-PUISL-AOJ^`=m zQICi1j&kpky@cUKpO0W9fj{DrYlP3M$&SL?P0_KHi$~c#kp=pmaE>_2(C0nPLu~E( z^|`9shbf7AEzZ?_d#`3*`Iqgj?z@Tz^ zI~ssa0gDZj@l?`vs#DP1Tg^I9&g{%-^DFR^eO0sw$ItqG+=hQi%%;#Q2_v`e-ZhTH z^1R;RN-{@}*ilFxdjERRI~&HC2*@A5V^qxwtkzzmTUt@_Dscmd*RCEfU_93Xg^FZ< zHN$tzw5xAF{2M()(})`avMUcZIcqvqvziJYSam{A72YkWGr8rB5x`p{-lNSNi^ict zSFLPiCJFW!fBCX?4XIRqg-%E1$bhT2icVFju&v{WSkrTf^1y@!^Kn@v8y{-M9MdPtTMs{46t^o0c0N(%bJ{ z^---O;(3?fr<+CvFYmxxyHW@2uZrx$`?7f3BKilX_LpyR`=eapFrGwOq1i&kJGXA#8t^^;=9S1RS47aWVo|MKcL1Q=27ynx>EAx> zIYD83QAD$sadgR&w!-XU4Vt>;*M9aUZ`!>E7}{3((LU`;Mx$i(@vXT00tY<>NW0Bj z@z}Av3tV#dRQsKhBX6(<*TPYkAU_;rr#&Mx_Ba!9d+BfhB{-Vtr#);FuXqaGex?Ju zJw7L#HTwp19vcgXb3@6O;UcG`Dtt572Bx=63ymOHkHcwd`?Q+jsHToWp({r7hSUI@ zT$=V4pt7Bgo^$m@C@${lb9R5{Hgb)mX)od?WONa!61qg%f0ssV_DK{y*8H zJs_)%gXERYyAI6tF}e!e+VTEU=UQGwr5;-zHzbL?{*jTkI)^)OUTg^nGjUTRaNY95 z7NC4MRBB4QYV7?gbL0GMM7a>qIxfpgpie|NT3aRfswc~J9y2CF#@V|!W{3CgpyW&| zpMFTa+VoUMY-_XEn4OE$v<1)P+t8i7NKXi_UQ!;{!;_}`^bT5PB>8olk!Q4Cqzz1# z#HDjhV9maL`+TJpl$Dha-lcy)2xUJ=U~-P+KGx$cVv_gvwPB(x1~ayE`2`HxE^y;* zJVuvXpAA`7Q$vuzBjQ-2!noP_5Fp?fg@@?=Xn{OHe@YUH^Bh#xnoY9(ga=em%OpP&8n_0&`+O!n(M`ZI71>^zxr zc6@lm=jC;;1wWkckGDt77ZYS(#X*B+!156blZ)Z<^SP6G!IkBNaqNzx+}OWB5Y)zf z$6VHpRm;vuBINXyL@wF7UfFMlegd?&+O4O#+*FBC>Z{{rQ@wdO%5M37Ykd`l%F{@) zBrY1@pN9&+ldz=b66@-etB)Q(zVv`JC0j5>?6&eR{y)hrc-S`48|CcgW~if_4sX~u!8`RuvuKlQ9XJvZ1I5RtLt%tDdUKta`^|A5M!T5{tio~Rh zco!}T7iv_{YQkXTAHgRXppuwn<8XofJv6_|(HIv$*;_P~wHW8m{*!EH0Zsmjuv6&# z=p*JwMMaqo?f5ayBA>8gx$Cgu4={IP&VFf?mYXFZE?%*3$uGkC@5ub0y{QmN0o@%S zR+X7Xvut_mM3Q1vo#)b&os5=zHlMJqVR6(*Q(n7s0TKNZ;#fWkM>`}f_U&`%=K z3EM7Q0I`QxZL4?Oen;S_*~n44q}#a1hfc#nnmc|QB+6$Ap1Po6_k)ed9*L|X4_&YL zXwo)Br!ie44Ukk2ntc%;U11sCa{DRQ9gQmte}F%K1XV1W`9yx>KH>dMuIn-rv@pdW zh+iP$wdK~(*y`3~x~(T@5EHQsP_O?Ehly<_UZY3DmLlStA7h176N1vfprAN}Q7%~( zKdx2iJ4y}1;7}Wroz@cjwx{jS?mWa`H*-uiiWfxQzA7U6H$(W}XGL;NvQc!MPyM9D zBfA-<{~lp@a8&GU*(G`i%~S%(St@Ds=J}=b<|K8cgyH#y&BU}S8A1cR`4F($YE0%x z3wz+Wu_%Y0SPy^(bVlHK`^Mw^ax)zYiom{X0evG33AT2Gq}5)-B_1xM8x}u=@_--l zGV@?9!=K@rCSGD|{Fkd6bsZKB;9_#?AHYhplnf3UHb;2@2ByZHxB{wpJx{L255_x*f-jReZroCALr-&>uC_X1B5eDvY}(-E}# z>YTJYiln&{=K+5hk^rWLIuI5_Z2?$2nCB4`s{(Rgkmk*dJhD7W_0Q!aN6kX@S|?V?EWZeK}U;>u$?xjl!J zpg+$GET66*S&|Fc4N))STD}1DG6QN^;L93Vg=G{&0 z6_AS})|m8X*(9K)uoVykFuwfaxj>UdiG>H5xqH;=(SJC#|Gu1GZgbB9f4?z?E4-w3 zDF1T(J#btB6tN*t1E|Am>B?PdWw}>lyIHCaISE?htWLE;DJf6vcO0Xam2J0A^}pr zFKTj)Pkf?m1XAK$tU{#Y6Ysi}nT)#D*`uxh4k+i`+N)W0Nw9@~#-r#k;`J56Epv?D zAgm@eh_2;{+kGkMgrz*s0L;BR2Z%k&3H z*uI7b8h1E)Zvw-l+2IiSuoalGu?S7@*JzXlv=1KL0W39$jL{X%ZH;tqh8%d{sLb#r z*6|-Nla9aFpOOG}NnaUB~a3p)&Uk0bjBS7`B*!u9cbe2CMRJ7 zum?_}A!tjgsj4y=Q}5_8HfL+7Vo^P@lw3Ray?%QPpFUlB0roL+xR*3!4jn8zF9r z38~5Sq2_@T;e}>D{|q@dRPly{cShw*7DH?+1=766JxPGc$v7n7wSM~q7obKD{;oaL zqSv06EvcjvmR%VKYwl{==6zKGI>pVN^1XV`F6tY^I8$NtK~|-oBFY>{QC8z9ywmwU zX<@d!hCS@T!j%_8enC8N^k!ZP{~ZATxk5#rGk6oMF)u7{POh{!3yMoigJ6%Y4L$C8 z1|#69gg=>ie8oEaf@pe1pEWriU@G<^6X&?KMMY&R2rwU(q=O)2)X66nzrX(V!(OvfJ#Km8E@V}WDOy(9?nyOGi_ zlech?FPgn36P9)ptx#V*K>{UZTa=-1$1l+<&R|pr+O;cOHL^;u(nLGG*|uinf=Tc zNMJAe51K6VvqA(=Lsn*v`<(tq5Y6_CAD zfT(~QJV%mAgILD<6Kbrl*$+V7<5Xaoh2}Zb0-tUxEZw@AsFfDUI>dshd$9UX^M=V6 z`0LYl;tH)Fyx|*7L_;b8e&-L2oCpjH(|^Pd(%TJVI49$7RvPkz2i9a75q|P2(r`>l zN>UC6f5a71QIc@h3Nh*2P;_#-n`D%^6}>IOh7;d=6V~m=P?QmR=L}!pl5yc^Q+2T8 zkgE!AHt5TU2G3*PE1K5BKi5f7+)UuCIbWXBm|ZHa@kTxU4lr*CoU5sv4r&jKve?^f ztLHrU3q-T-64`b4dG_kvS2syOBu7kRg+=5A*0Rh5 zO9+RR`S2qmlO~h}8mHiYPwE?NWdEMHsz$qig`(NTGkq+-!YPOt!ku8DE(BjiF@Y=& zdve-}dyO4iq~MwNI@L64gu&Z^qqw-(pOE3m$Ohe_SF9>tk(Xfp-F8z_(uN79svEgn z8tJsf25XP_?XZeMb~w)MK1jDzH*?J6hnlJ~GaJ*+jotaj88>ae$01m;dSwig@s9f} z!&}&dSI(H>GvgdbpU_gJ?XiL}E0?Y0;gJhwb5j?CjJLjjNyBqZafwSof+fM-Cc@_f zJqF&591#eTl_>nS#jzSZ6$1P0#iRtv- zOKe;3dn?*9BSl@PTd0p(aoAa+6X79@%muN$SFvI`!`^-Si2G(>czF08J9xhPLq^0r zd-h9j!!#C}Z=zS?(cR=jzvmjQH6k9d{rM>$oU+8k(RBPB=wGrtdit~!2Wir@m6*L2 zyxO$>yZ1Z7G-qO?d(cVe5N#N*&jgHUk?wnBoibPL^*c6-9flZXd_GAVfJuP zRrD)G#+p13?|h=HY4hJ=fXV%iPYy?X%?vc4l~$K1fmVGCm8;$s!#y& ztvpjxb+5Se6B5cP^e1YjHuBtgWIV5or6*Lxa2Zfre`wbtBDR>D$2zvZd2xea99H$h zY%rq4whwvz`t{79BzTV<-p^}t-mUxgKFi4~`1{jPBHojiTzV39Ur--i(F%qXlYF7+ ztXvrpHkij3i*W?%q!my;&KXQgGDBdFp4-BKYsiO34#i+ zNC^#7;RBFi4}A;_CuA-ECi<}@w$=7GPn}o~lh>w{4lyxCEM4F2BS_GA(C8IExgAQG z&rm>uBoMf@A^uTbVkOF7K{Cd=DmD`OUb4HLHACP1*9HChZvp*roc?OB~J2BKQv7`zN2xxv*-iBI>vc2Pnaud>EO!j%9_27+{HYqQDk`t_-Y5nH&xJ~(_i&5r+h z*>BlRdMQG_LVR21$&zFYoyg9nC{5?O=?%1>>C> zZ+l4CcQNGw&FlsAwX5?7vF`-9_vvNqTUz1M-%p1j7ORx9p+kh$GoN~$<8yE+BTyUi zL3o+IP8Fn$V0dFa_L|KlTyoeO-b`xV^o;4XsV2s2a1^OWfm_KL@*dV9SDU_BoR(eQ z1C23xS;Chy2#!yi6Yo(xA3T`g-4B>{D@G-1_-%Yz#O4A#s|8HWbfXSfPZES@iJT?BH6i+6F)KBTl6|?2m8__EBe}(SUc|8gCBj_Or5ink}35#PFyhOen9n&aw zXT%&H5rQ9AF-!+`j6Qr%{aJ}S#&gIJx>^u&^+vkT3PrNPqyOpAw#oha*VnTt^7J6y zPp@CIe`0vy?{_y8LQyzbLzGDGFt@DgE6JxpihPuMaq;=Dc@+83zBM5^?4rg7B(37* z<&BJDaPL_}T|U5f_(VlTA6_9wxo`j-xO7x($3MGe@+I{gBKyYUNBAT=mclv%;f~li zY(8!=%)Vqv$MHn7XISKvL8c+~>`^Si5bT*<_knkA&#-ofY1`=%`BR4qWnZH!g5GCUp7H61f4;(pMHU>is%e3%t8C$VV_D$>t&xmmBc zS1j;fPa0?ehAEeQI9sxfj;s7+)HIo%uSk^=0!v?`rZ; zFH*o;8+m%z9DIj~7bedaeg84K+y*bQVJLE<#-mL}To)Z3E;=u!EQ0ue@?>+8lbxNP z_zQtq(oMHtAV-vdZieaRXNiBn?8MXrc6pG~rYxngZ znswKvh=}YazxMA>E=V?V6HYFo@h!Xbx+o!lU0 z9(@6qEg@W3VD0M(SD%lphs15grnirx82TP$!{lyp$a}w~>n$_Mm`hbe#8In~B>pf) zur4gV$$rLj1hFT?IC5$3Av$7C_!Z{9wgLxqQ%PO%R{C?*VIZC}X4q78K-q;-h|NlYj+O7_T;t~SoK zo~>7%YxA5>v6y><+FSw!R}vH91pw-@=c!C{`X5`fm=0T0mhxPb=CKxwM0;mKhjI4& z`FXSQFd&)r=fKGojJPg&baD-0Vqf(PeA{iLS`1ot@KY(h+qH+N2+au`|G9!+Tm2Gj z?_VeHs@5@G$J?lC*81{l1>C|CZHZElRJ7%vj?pZke+wOZHLNrBV+a4_43XWCv#K%i z!vMho9J}tm2fi)@rA6@}qk*X7^ltiL=$=x$7RE!C@gQUq#o+*58 z*?M|tx%Rj1LJC4{Lv@mo6@M@E-y4rfMp!Ys&QSL5zezY!pep+jXu3qnh)Z!y;?4&I z`#|{Mr4y};qNW8Rq+M_;)27NvA{kThD)QZ(tk z!{YBgiTQ(}KY1BHKlv}k3wu`{LrnZ8Lc`BbE>|h5Pt|zAo`yX85R3Xe*B1Cjuq8)m ze6#b0)88|UhioS1MWicyewBX8l?@oOS%D#tD0HfzXVvZ7{cj#>J3$eq67yhC zyKB}pzm54TkN@w0MXoQwe9F z_s3bX|E>rki7S79mVk&LbY(m{_9@wX&Jp;&sa!Md|Wyd_+W8bgHsw z1oA+B_$GI~pVjp9At3|Qne!oC(eJCc*gr20`61pZ*L4fCpBwc#OOMidS7Eo`3CtzN zW2~X1d zV^hq&PrT-doilWgEWgU#ovLvObz@IVpPz-RGgk(bOvcBirY6TChm|2SVep> z&tJbo>v;S3#qgNzqS&wZqiM7-I4F{tBQYTcu;^Zi&YcSTZYn>E;!eVCq(C(9AQ0Fb z262aG)l2do_trq-DiMopdFM4{#^oI*F`Jk%jw=AZ4q*fLpQJEffRD+In5cr!Ylsc! zj?6*~%uDH{B+s$GUWBqb76U8wmV?b@Kq9ep*V$_{5%!-$!h4*V&9=3iWkh9+r)+I6+;0{? zTn!Wovh4ORDR1i;y;0dbgZjpI4(4m}z$sE(sAJ2fP1#~XmzOoldgCxF0fsH!5skDd z9j)Y7oxuVBE2E5NL`K>7VgJ|3hc3(OA0B>yeMZG7s&{h2UY@6I#*KfcnBqX@_>K(2 z0=|n+4tF8RB;##|Mqp1Z041&D7-1+8RNho!fy2JTsQN<*<@OZ1-ylLc%bY~HpavW- z7QmDELY_~=`sP15y7#U_-hhX}~%WxO$Gcx0+;0}}JISMnK#}(&}x8=7IOv=h} z0?b=p_ItkNKMMf|VR0lXyAId#$ys`sNXi1gAOjz}&(cJ%g7d?|eZyMn|G9W2Tib_$ zD9>Rv0Gw9Q!N4boFF*dbAeLCL5XR1rUE}hwD&OSP(#IMY`4X_Ne)3t%FQ;}9R8@<`OlK`!3ya46 zZ;CdNg=Dv&XTW|0Z!{LD3D5IaNqw=qpZaCU8R6f}T(IBPfljtaZ}pnaa9> z2RWg0d+#gAu3`2N1OhPgj2Xn+=-rP|;$8d>GrVti1C`m1A;KTuxH7yq`!b5fziW41 z{L{wke)55H`L{A~GPn2d^G=9#d-mlbD~`J?*Zs>BEY1Gr=uJLaU_cwOB#$sf)J>lG z4Dl4bgVoPEFA-O-U?E*0u^k3Pi_~aIXE!^`CT;iBE~{iEnuA^v>Gwe>J{-qiK`bUQsGzMvN^^|0+&EX4KTTJ@XEn9u#>J z81kfQBlR-tLLVYYjDvHR=$tsTDv@T36z-QiP*>>Xb$K7aB;BoHqK9ruj)5&y42Qk0 ziZKkNMz&Sj+fo{b+uDg4s3Ku5o$sZH&WKEoBIqgtWdD}AZ%$AS*4@+X%5Iu1d=^1Q z9ZdtaNopr`TmAV*tq?N6NcmH&&(@MP) z{Oz`|#6!r5Rc;vV0+e}xy#=@QZmCmG<9#y4q=_JSX=G4omEh2e0bF+oLFKU>e5KGn zQ-^6wo4p4_12Ay^kOps$9t*mB|K->m*359}2mu4=dv8TJbs)#YIXt;SsGnS}0c~8p zVWkF?tiN_Nm|z1P@0Q~HOShh@|ESfDY|% zRuLY_SI#)Cqb=IonP^Ybq7=ejI1p0% zT$7quQg14IOVO@}omPqJIMbE8IO(s7?eW>QK<-y2qP`E?SW~ij>HOe3Aq$KnGR`js zC%!u!!l3f?i89tmX5bqZ#a4Ti;ql;9Wi#||urcQ+W=2B5iiy}(;w-ET2o^b|4G?O|Z>~2`z*!f`~Ll?D*;kgB?zKHvr zYPlX013>8ILK|3Mk?y5-lQml=EcH}$T@R7`8eufz{hP4$hwAg*F=cMqvgNXg3Iez} zwgDMUKuw@i=?SUUYwTN;UMVJ@WggJ|!v~%=8dAeLGVTYRU4iD*wvl(y0@bRKYYc1Y z5>blVPzQ7&vL+XlXCH2&+zKq+M;rutGAOAhYU)~gpapvd`jzj8bMpm>&3+&$4!H_I z2v0XJnS0&Kk4ug)4&t-=<1V6Sm=1pbJ`eEw7@8IDn@!^ZYCHf{>=J5L5aY%z3>PS+b<9 zU#mKG)mj~phZ9RL%&08Y!7nb%)Ujb@W}cJ3P+j=`h`RdLtz;J0GX%gEoTBleaU9bR z^nXTDw}@jVc(g@EJcLJ}VETC%GMP<@_x=(_{&mgHI4*5fL$oKj0M222ziJuk)Av_v zBrLAiI{BFo$Bl4c#5uG)Gx)ifckuW>=p^VRku1g#b|Op*Z0}0;J8L7T;psno;cJ= zF$q3xZ*L!+o@V>kRnz{}{thCa^l|Y?V$2kJA^WB$v);j+n_UGUW-N5nJT%ulIx-lB zNs|lRRvBgZe-!lYhpoS zt3XtP=duJTrI{SP`(7znEx_hy%!%j$haM)RX|)`O7Cu42lA$MrF@Ox) z(b@}@SXjD6snL^RuzL(-Kf!}&qKTYHfmD0cb^F_@y1x7IvIo_44r z!>Y1lmWti~xMIbki@0PiPMW>xLank$z)cLm{E#gt4Om?y_~6rXSJC!#jdSOFez-~z zEJmGp>Vvx$jEpFIG+G0^2uw?|yRa+cz>e|;DU3cp;-&z9#vpWbIBRU)y5sXUzmUs| zA;x>!i>ZH>vW)rJ8h$T!JJ<0mDJkX1?jG=^ydqPpUS`)QeOl{2aL^S$>fy9ogVwJ2 z@7u{!2Rz`sl+|)FFKk>vRe}O*H8;?-w@;I_eqF4k*XC^zdydIV z3}cX88AN083e6MH@F&BUP>hXpQ;bcn)vs#7Y|ao=aEX_&qqm^W;zt|tWs6}tDo#_y z?jf`G2Uk}_x+q(|yz+Sj1G#7(DXPJH{?E=?K8{sWj4gABA<-(5!v(Gk<_I;ROK}Ej^u~^b< zlw$}5A}Q4zSpXMfBecU78n7k(vJIX5Mw(9>1dtK!%a}O{&#~R0C+Ik}S3_#yooJpY z{-ldho-#N{)YfAYpS^f-?VHeu2q7gUuLd9Ghn>JZ14(tITZ`!5eY=08smPk_bZQvG zTMk7i+n@6s3%djXI}Yt}Vyh+y>`Ea$O@P5+cO(3313+`-eYoLSu;6myrj?eKW*o&m z@2~Ck$6p%=COh)fpMCN{yIdkU1$c^_AvOJIc9w)+n^q&$2s=y!ar;z7TQo~tJ}_Rw z^f8MyZij=`&T%T?U8cwUPe*JVu$L#5Bt|vm)Ems#2&4F- zS!%NnZ;W*NA_z9J#woi`rD0k`HjRjthDnm5EJV!nN?ljwf?S$4Mn0+yK-O z%@pS;+-pYEqmTeWD^+>xp~CogEi{5y(ckwkr6+`7!jpSJM4xl=FEjqH<{O*6E*@N> z&p{f0rC(Wcj*x#P_OA$0yu#g3`ps4O+Il!DA}20s3~*|_*r!`d<`_Wv@=RCSuJ${i zKnpxBJ?+X{ol(bn&!Pl(ZOXVbkDhM1KO}N)<=Z~Jfrl%2RELXX(uniazv=AH|JHK_ zG4s_s@yT%jzpm*ebL=@)|09>Debkd(YFmA)omk~5U6p@pa`&JiF*PKijmg#Io@0rF zjO1IcxpM=ropVR*F~^*2Zh2)NUQb|n>&qJ_&=9gI2YSP|8&q}vORKEE6x@k^rMsbeM|J3JS!e{;!F=g1#Sw; z!mLmDi(xiU2&?i&3}_w0@@pa0xxEa)D^n}Ysn=LIMEgcII^kgW{v|Qhyx5<2cJ)0# zsl*zd4_5EQMUc>q9v*7Lcgn87ZlB(?EV6GEjLkq}DPmkH>%8#oynn&dpBn9VPn@@Nt;1IPm5FQYb zcKIAXKH5cjjCk;26m{bw8+TL*u^?*BuKo_he=ACyr32S7XQMffViGI9|K*azrBMoA zCXmzIy%NRd{y%vAbbmZw+OW^&LNCj1YYNka4RF=K$jrSw3A%?^0WzQib!J+_A*osS zZP*-Vh3MhM!FgF#iq`gS$6ZcmqS6T=Tyg9JiCqk9_ zhwQ*rB~z_t>leb`V|mZj1sAKg=jqvNv1Ffyvn;v~n-Ysgtcj7}?I#eP)$D#iY*ek) z@WvYEm*uV@gORO!-3HGQzkF$q$4UR|%52agb$@ZqY}w?cjq%t+3X%hyuKC5~>Y%wuHI_ToQ^<;vAIUk`HBM%&Vt= znsWU8OxaPmq_o|pRYYH6$k=VwKKB?@Vm4k#thgj;m4MG$j0K>TO zF0C!7gV3x9zhhn!s2Ajh^4tQni+U+Tnha=SPfb2r`4!k*t+N-+BPHOkKxXNU)bSZ| z8gY#^kd#}$N&5Vv(vkqN6fKr!ooqRYotWGK;IbIGG)Q{#v=DQ zo%5`V?cHp42O%g;+;MXhdpZV zoL0Vfu=&{J{qZ3n-1 zU2yXxu?!Pu!sG~bzywhr#vz&#hL63f$96(BJWx44e}1bt0Y9Wc1vF47%@-C zhwW}C%dx(fvxl$jiC+rGd1AX(o@;i%rZ)RFQSU=9vd{9!@MP-s&nF583&W=DQQ{YZ zxM#5R6nNX}5G{5-K7IP;Bn&hZScKKrjDj-MU-Nw}kouLt+P=lbiRojF79}ujSY(?u z{jh1Bs;l$%S%M}q&)Z_?dO-LtK~Zs`aDSHOCGp2M&ZVqcxl$G9l$SMzytFn09C+E~ zFFFXqQUG+6FPW%)_SY_(&&^+RD}y9ZD6#ijFGk0c(#@Ok zi{5P1Ix~&QOuR^%LGoZwaIpCa+YC3rDXt#-K0c=!87t8_pQusabV4mLVsnz7m#}Vg z>S95MzS^U*j-R>*7gQL<&Hdhz%MqdKQeP;{XbK4RBDX@9PQO!~$?76_-mQI7@eG|# zEgLuKd+5Nmye*e??z%GP7IOKRn;xJj>yY8m<<>7hw;rA_j> zdPdjFyO=gojOK^P<@S@q!*R)=c@UGpb?Y7PW`PCOO$Laq%_0MsfQ>I=WXyQBf!u|9 zBkXoET&0hcq@#kLBtjGl8)3rORW_`SJSd)NJLGyi=XJdH=_J-KbQOgF3A zolVSoLOWsd=Lta>XKFUj-d$yx;=4vD+eVm^OK5t1PU+AHT8^8hhJ#^znAsVa56O;7 z7aHZuB?}FcHi})|*Hh|Em+K534x@Pzf>XUqo4F%WAGU82ZW zfBuGY9#ku8pV}?c@zrjQcjO4+RhfiYvNhf$T zi|RgL98zj24$W17S$4*%&LQkfLdQn8)U2bo$@jLn)BQb7-8%wYEuJoRUg%YAKLW`m zKk&|$;}WQx%Ab9HFS#jF+Rmgj9PO1bjA~w=?+4dSGNXJ$U)jdlPlw>S-h7-@UQ9XZ z-YY1XD?hA-BHp`*tt@wK?3YfFip-7$9Ea!I`uX}w`E*)2KjL}Iwa{;s-sIW!*NM#b zmfmx*t+ckBhMmQF@R5r=8PZ^V|K~P4W{kUY+OlN1f-KKBuXXzz+bd$Tk8Q}f`*jeg zge-<$gB&lz`QY^+vHXz*x42wiILn67`4Enj0Kli}I3#Z#u2^T)}N4Cv7j!#I%0g3X&Z8;+Xl2^pTO0oPy^F_}mCyN}7I)4P9Y zZ{|O%Y~t3uk-%TIcW;y*HvFr#PcbFS%%k;dVy|DxdVaz0p$v>?la^F&w@u~TBV&^5 z^nxj?AuG{bZBr0jAgpyKGijX83EkZ_vBBLT@eTeLkhRQ5b*;>d<_Vy$q zE1B6VDl4)wf7h+h)ARIwy?%f7$!EOZ?|Yp4oahrMGonteh9#W=23|ZgUn6{5v5+dN9rDlP{Ozxw8SkSuCPra5`Nm_754uwG-*ht z@>>vJFSR1kQdnt`Z{jBP?gZ9}534vU+$oGFx%+~*%9)PVkIZMv-h=)#sB=hKXbk`P z<>|kvH1?!QtHSO(r!#Cho-;H78jMiQ14TF6mb(%yNJJ}ILjiF!T3nm$nzIIXYL`z% zj8ND5yNPhQ<=~`g&(Bv(AZ$GG7h^cdvhkEMN8Zn*ho&98snwLe^lP=DRn^krj_4vy z5SFqg(xs=4$E&ewU)JPb{1%XZOJ&?k85{#^FW~t9+j)^VO>jyLMI1ODckEryO&k(a;td zz59+6CA)Q33<3Oldu7(_)fBn8SZA!!S41Y@Bh}1rCD~#Wb?4Kc95x&QJCh9nvj?JR z&B{0&N4=%TKG=ToTD{BT^yg!oTU4|}6{U5=$GX=C5-J($z&7yn zmxa&$NMsNI+c0bBWE`8_RYgj2Nz-vGMWLE{f&(B}-nnI+Zg46b?@Y;!_i<3Jztr!~9c^{Y1#`qy|e?2979r-xOud}lV@zg}gu5w>j2 zI*nH|wxy0E;7m5*Imm?LM7;mkV}U|%LE<@%v*JldYWW@CzC8a$sAZRBS5ivM4&}5D z-_6c7zWTnu#XHLRsq%BG>~w>ggmnZ?#Dc!5aV}^-%4PQep&&uIUf`@jw6$vv1?Kva zQoDOIruF`QKScjOIOL!hJ@lANNkVzlF*J^UpqKj71Ez7m=`1+|%9(qMA!a%9 zT)Id!qNtI_ab-z6p1i69xA;Na23h1tD zk=+^ue`X-|??IE5c(21~%=(eEEauO}+=7$#_SRB1QZ4(k69KKWqgf0M4NWfEOg}|3 zI50c#f51EQh5~_`)$gI?&lEgl z5QoNlo2KrS`ReRDA2?)9EVB60J$s>z?z>u5eJJEimd^v++t&Q0+cO4!FaLLFk{k?W zv3jhXH3XZ(v<@w8-UlSlQ6N-#xx?#Dzj^wXK?aMZ|H%ZAHkD-4ZJ8?l>mNXR(aXzr z*btkv7DLI!7+2EfO=yMLbSN}Ni8*O)B;zcHV0Ox^{_E9OVQknmGo){)H|!OL`9x_P zlq0t@T1Yt`jZ_on_StrfzyqVw^)9S9uTR`KvL#qN=U#(ir5P>QM^#_C z4uVg$(pq0HP;h>H`zjLhBQ@G=q2OH?eij(&(U+Q%e8~amF#a!B?I#jCZ|EWBdacmu z!!xAK3?Uj)pi63^?Q>Uf$cqsTIN#-yWkXli(k2Miz(=uQ3-C*0in7m&+SFRZ{10CIG*TsD?Rf*C1a9Um(Hts7Hx~54HFsO?Osf#Fc z!n)uj&7Y%_W0GrO$UcGr!=I*}V0eb8ca&wFVtQo&8t>AS#R!(Sg&+K$@filb3G_2)DF6^6CSRdB18c<**>4PA!GjEUQBHa%@WCA3X7-6rDhj?kl( zL-F?85&3*R{&4{NF%KSG*p_uc{>NIsbTV~qRSbIw#ev-5x~{Hr1e%0|$J2qjq>s;o z{9Y!~jZMUiiNbv)+=2wFElwzkR@?LrAo+I?Zg}&zAe*ch>DVb#t(Tx0FA8t+u-_gf zSVyNu)Uj-_JVBe9aPxmLbH`B|Q)}z8k#k04H0L1EFjZFggq}(F;5>b73accXrX{PW z0Ewr2YP15#(Ynv%){*AIbj~2v7gsSUeX`PuAoaL z8aI6f$igq}E%Fyl_pBvdIWHd%z)AGjjFM9Ww3}2YH-@}iPO12t_`pON?c;Za%zn}@ zrz?26TiL(%H*pcg)6CA@ zb)=3Nw(`cg3)Vz9!S#u1&wskm=?o3amC{9DZ(V{&l~7QU_J^0fVX@L!ef;B@4|5e;t*%G%dwtsqh0X_)Nt+$?zryt-|fi_z1tD|Jv!BDs0w z&sLDNVK&hBiHW_+iAK-%3{+|u!NQ?&)dTPji|;Ihg*2zSRc^zxrpNYiS;@N z@Anx}u!(zwOiAu*C|%6-Rj2Zi)I)dE_jgRhH{2OL-(0Vd9bMgfV@_W12xpG_nmnbe zoh~79?IR1&>eFonr{XFzN4}DM`}dP3q}f(0@stHGa*xRgZ$$9DV_a_JnSx=3p#|`^ zf(6|#o%e8)Z-CNzrRISxp z#{SZ5e076p1_NMT589jUUwpz-bPggG#0H93#dR{|KRF#L|V z{u#~{`4?AN;9qY7y0K!+`fTXfVETjy{>WS}MHkmzkHh6+@twp_ znYLh>zarGrDGOpjtV;yi_;R&kW}rs46VLF47Yef@2*#>z*T)d^RQ)43u1~Q!7cq3f z;La@(C$4 z);g?er=U+m$W~n3+#(_(ncYzcQ>76|zg%qwmLjiS<@P78_Prn@s`|~H4exSrKH&}Z zzU7QODI@Pc0zKx>smss*kMeKUhFEN)gHPehlNy50b*af8#gZ%>uKsft&qL5qLn9Y=}-zmCJR=t8#^t8LOsT$WfTE6 ziK&i8*a<7%oqiJjHU``f`tS_t$>I4Lb_K>uaS3piaGtwpT@DK^(E?#7cjRO=b&Vim zBVJ|_t`or^@HxGt3Tt~EkzWIu>U?kmMR%@cg)6B!29`v6?*?Z?{N2|PHz}TZAVem< z;!1KHcFO@eJc;$TtJV7W|)V9aUhg?xf@BDQ-Fv8l=c%97#xp zI3mI9G^&`WD!BF0AJ_va1;NzS;nbqw9*5S?V)|0<@Kt+6GJSUVbsI3kB|+!)sWWI@ zDB;X>E-^>Sw);YcS{sSfi@$s>j6;{^L#UM8<~>2`_u*e{y*Yv;nI_nI;%jRMKyoVV z^6SJT%%vuMz`lLgBfT@hp!=RN{~`K~{?Xkx_lCPKByrs^IbQg<=X7AukV>SO;u!06 zkyu8n3G?pPo{abz@Uws|5_sKJc;Mm23lR#HB~<{&ogBJ8=quCOU@%CfC`mGwwK8#W ztEHIRPfRwr(yvy8@$;>%73`QG98j2OC!0r)9*HYhhBrn0Jq8oIyQWU%Pat z5!p~2`}donZe&Fgmrq>hd`AnCmcDV~dZeg}`7`v%F7>QN=JFg^7}$9MXvh(j7{a z=XB2!Ssp?^T()M7{)aAjdyp`>!0%%J3dss?%SY~tE)^E$AyB4}43zVyEQtKubYX(- zu?Ntx&3RT!Dym_bop>&hu5pO4QaU!@S0nJ%JhG>yER!n=9ulNp>efYdf& zMdoi82>0<`ZYLf|edZ`eOKcHcC0#s9Xyy6@mB}0`%Z!2eRb+IZi5~IfqazlhI0=;o zQZIjh2^||ov-WrMvteNFlO(>x3OK_{QH9Gl@VwDj=CWoKlQg6g9Fy>?V>3_%RMD%_kRJNK=a7~>-f_%fQ)BkS zsmZ=#J0In;j&qnx;-S1m3LkB`9x4#?smA&h;7$%01|Lx!Nt(I{Ld9uSnI_y3s6Xrw{%UV=8{tb20RxLLLo&UggwBmMssZX-2acW#DG}awp+*<#ogTUZ8|tjIYFdQ z#Q!?F-+K62nGOG;=Z{!^?9&mN7^Xz~&7hHdG&Ef3r&}qsVZ-ZB)o9*hfjt@?R}#{O z+HrRrj7Rz`gu_=LmHO({D<`Q>%45RToF`ud5F*Zd$UkmY2)UP;X#O%2Yl6r&W^=uN z)j4by`yLs@&kCb~J8~dL%&UTPPs4eVauVJYaT@^OnVeCgl3h0G*?w0)yif()EdTe-l zlAm_l5otH>gUsriCnkzYTbQ%=?a&P0+m8&3gWtCx{)MM?gH=PFbUzM~8iyp+;lQ$7 zY<0@#;wLvD6>3gX3QWb>;ak;?>k+fe^btjckV0gxf+N?SqgIqBdljUrcml&opB*KH zK0V>U^>X3jx4yUeuxeK1%6Gb|S5qwQSv+gtF+4?eKdIr;7)5CfqnX~jwpSP@B5^`8 z0rw-3d&=9hqk$6oHd$iR+kmN6Jq0!Waws)K6X#*|?pK{6BM-Hje*2`_dJz5esNb~Z zdur5t*mupDs2Et99yxO4zE0<(b4=3a?h+efjteI@KYQ(aFWtsc!tJbWbe|HMXdlT{ zneD|i2RWg7XCaDa8HkV0FA@~l49Y@0`k=tv+gi}xw|h_289>aC!LM4Sd~KBJZN&iU z-ts`_Q?2?4iEt-}LFGiXYhf^E+sA#=v_B3ZFk_r}w)aH8f&g(WT*X=)9l>K-57qS| zBRlM#2QZ{%y?a6#^1{?ot8C>@(*BP_I6)PekTpkNby94@cv%1WK{51#svIVDy99xH zsdM60Cvk6%sH&bakACx1EOS;Mf8_Ws1xkndxxR{bX4u@$7TPDP4|8Hg6INI76&8BU zh~vh{@h|1AkWaTC6|RNi5upKQr(JT#QLDs^Mff84sF8Yh`S2O2tbxdCV= zm6c&9qh3|sj8K{gA3-7-ndeX6B1IPKmN=^P?R%DQ7W*Q;iX?KeM?V4(6=z7z2{x!t z8^4w*^&fkD(sHM-ocHdO=Wsty|9I9?O1!ZX2xSx39x(ov5H}CHGKXQZ`LUP=qQ`S! z`eYyQT^Jt}xpH;!8Mo^m>73Pca=Q~%o6^1~zf6QqG`EBd=biRZ@I)oqV)O&GU+e)r zilmdT=ktqAKq7>3rB-I2)_{AWt9{j4>%Jq2mi-|;+ZOuk5YYbe`1iKL1)gV^7k*9$ zm!=m6y;>CoyVprqy7wTNJ{WxS7tFgV6`?AEuXIbTrb%x*X~s<49*r|32@361^NRJJ zljz}AUR9+obdC!%6Si0&KrV@?=}L*EvV#P&B#iAhO8X-%ePX?=PzqT+kR^uESwn@-xo&)Mgd_O!o|Zi*@p zzo5#wB*?(h&I;8=Pi-g0Kh(J@npO@VOLLQ!fS=x*|H>Zw zm*E?SQ|fD&JRuySwDh-aA3=M;kOzlZ@Tc&CGDEA|%Qiacv>ar4xcSk>_N0^u@AHE> z9v*B?7caRmNmaaU262&Z%QB(r9i>27&pe+as#D5A+>`~YcgaK1NN<5R2rWc*4)lZb zX6_$NCkAaN*dfBUWB5Y9x#}sD5q$&**_$)I3VmfqQ6o_rV3ttoXh&+<@6&*1da93W z$*@nd(MPFxr(D+GEcCDcZ4jl}ivaFD(?H-U=(~kcB7H5I!82i8TN!Ae%(E5B%6VfK z`dt>f_zS_Rh-8%*^Q3r$j3& zbYwnz+x(@DQn9V^$rj%NRT2#UX8TsYw|`~cz?QCOou&7EZ7SP>L(&!79bH`qb7~4I zwePI&RP6uE{%Efg37Q2XNs6eEUT(*UjvZg!fT(Q^G66MO?r`<05+xzu=tAMp`}gi` zfJfO^S>qd9^2Q-TDAW`z&tgM&b}vp-rmvE8r#^UldxfTw|7zJhu;`8I3iB25-<@QV zDiZ(6*eS?sT&=h*C(LVG@>Lo-DF7NTYh?XP`V(uH7pxGn?tB)>_EKkfB;(jDA?t+! zku)!L20B&?m-ojyj=dxSMg7vU*x2emTE-&!`gPqrzRD z-k!$v_;2Fb^R1&@KY}R^yU4JWo;#WzAyQTEau|vLQb=p3*U%o{vo{+2WyR7W*|59hS+1UGvpsEvV z{i}9VMu?7(0!GN5RP$aRUsO^d>^b;s%_Wh~wsDuXN<{AOi}D-T-2ylE9smpGk@s)B z3MKs~rFXrhb2`5X37>dpY@c87p+diK4~w4uleRw3(Bbo4=ksLOat|AODSYeGRXbnQ zou5Ma*7Dt#QOK$-TdVL$-x%ANVE=({gWr;W7U8oKP7Q>p6K-sW%wNpBWhe|mVd@Pn}ie*MSK z{k$0`-&EXAq(y2Y-@;R-T6GWN&0LyX+Qipn-t~?DF|(_)-2Js53Z_S!Q93@ETi~uD zwaQcaC+~DXWHIlzqyqOgGcA!4*67xV^WW0n^nA?s3M%T}>-xS2T{wfNjFOaf_G`Cx6>N*R12+ie!*gg+|3pk+fr>i}l!cs{G8MF<5QIGvdOZ z^#NtvzdYP@$iS@od25)j-zAj$ZqC#G>==zm(NgmZ*7|;ig|{^+%Hi*h4D})GXQ69N zJ_{FA_~s*bWK?T4_O9hK#R(jjbVWjrx-YIyiQjtvSA<6_7Ac<~SGO(f<8fDrK3{>X_*U+gcLHyG7S4Sr$c1k@vMn?{ zSJo%9Y)r7{cu75{lIquIv-qt2a%y&%L-)($W6TbpGn`_dU1IT*IDl?88jV@s`M#dd zEdSJ-cMNgE%B-PUMG*-1l_)`L`$*T4F0YWXT_0jg{FTP;DA$ihoQ!(R<2PPgt|1|} zx}R+Ov{o59#j2{Cg~!w<&QX|78ubOXAS=Gd^ly(j^B`R1x6x5J88FK3lz^k0*Db$1 z-pFTa>F56a)nV&vK>#z9B9ugTRifZBh=r>u%-1Fu(#;-Q+nzOsz;Q9xB*tU5xUfJ$ z4M2>xuT8H&9Wn1%Pk*8VlKRbGsZvQgP*txh;@au#!t%tZahFc0NAN7PYBaTKGb4hV zM49VQl+MwZHxgaS4k~IpPm;(alD33Pw!H0DzMZkP@!MjW=HW-z(&k9pF7+K(2h_r& zKK6p+Th@5e+S+Wz3{_j(;MkpON{VToB}K+K2K8HP>P!^RoIAYEJ8hkAJHLyIe|4J~ zQ@NzEl&v9r%&PJ~Lm{F6$SL`ipGJjvXo< z0}0Ur+`@{M`Fo00qDtx|TpSjBI=I#^X;oQ%VwA9u^_n|nGzr7s!i(DdbhJ8tBJ;c~ z)qot$@{acjs&oJKJ`M_LH{0ICnSSX=j7qC3tDs;_jhzkUxGuCZvZ!Zxm@_nRZO9kh zyZJKeoI*(rlIjAMA%8h?wq?5%cK4aRNK+dm_FR;@!Z2(?mNzHSIgqotLb;Mys&9NpGH#rw#c5FoG(9(Pr8L+UTIxY$)Czq z%Rj&2F{bF{73PohGVLlJ{60A-MQhfqxLfjV!6}Bt$r{@%ZSD>D1*P_Md=MN-OA%@f z*Vv^S)K)sIbWu^JD67Bb-LV2%;7+$*YrVYIWAWG8 zsQIrtp*ssPDE9Ze*%yXBRUOjko-K<%x^8YXt>*GuB)WtW-zl3=8z)VLrgy^k`FK?@M^fd>cjhJ(=WDCFUitIj*Rs6RiWHMh4 z+l34mAHS*M+$l^4s(5|1z=2>oom91umcZF$xu7oVCivhJv{MrByCU$D645)h#ol39<3eO9! zHLau0`lY@>Nu38jctrZ$_YN|@4cH1#9UaY=hrr+s~<--;Q4ZE8RN`h7kaKraY9CrZmZQUB0*|~b`G9K&D!_Gw*Dfh|M z^4lO!ggRhpGyijGC+j~z8u^xp7HnYRcGh@4U3^`1{m*?d!H8tY)K?}jOTx9ySdt^^ zk3B8!o@*Zn(z5xmlv3o&Fh6k(8Om}0V|-*`cbSk~h8v#VWwvVX8}6n_YDH?#d#^}S z4`Gm1vk(;6@7$5nc$;jbEk7r9f`0f^!WhuQyYN^K8K%wKyz{GcyzrRHkZngTZGy+S zMA3%x20Nb|=ACzS{T2>BDIK>=$%R492Us>5VtVr+!jLq+A7`YTv)#ddKsT zhms(F@VP*$^}O@eU!8v|XAf=1M8EY|W5US=Rwu!zs_8ZfckEQFA51GUPH(Sb9W76` zu~9i5q2@NH+CAMzPMqsiXYOjr3&zL}-yIdz<#j7*boal=EN=98*nWAvyRN%!j@-o6 zO>Y_po<<@N5bW$mwRKgP>i&rd5XlSG-ZQg@yq&1W@+(iR%nCgPYfr8Na@dkAV@jh}WW0-&TP9jI-fLtLpV?f$sG+ zX%-ClaPqwPiqVPgIL!*Aw)(o?#P4*ojXpfy`I1XqRjVAIOxIAz9nsIFpi$244bsuE zJYa7hGTLau<95y76pfU_Ww%A&x3a)bdC!lZsD2h^l$rjxbv*XGI2HB0C9Gms{+dO# zaorv2b#AsN<*4Fw*#s>FzP}l5S(~*GAGnu98mh6;)@*8?D>}4yHBz|>nX8@SfKZY00`ans~iVx(xxfv{`0A(A8-0a z78`4g+8(Rt%V!>)yeBV8m3yZ7)cBoSPE0z>DRP^bb{U@D5M;cw-C8eZ_tz%n!T3>s zQHK?gV%=Fvhltk(JW+F7|`nTP`#$+AMce~WHa_@|K$8kKLGW-Qcp4c z%udv@7+>zxRhMqpwP>h#V$t2KqtgDS+tu};tNOh<(aS?$6FOez>FlXsH#q#N6M4Pc zK+uEg>y9Q^19Q=SA`jab9Yy(ZJZ;6LQAeo7{4sov`*fQDz_+X zV#syk7Dz4<(6rwpDfX9tOnefE<5DDuzYoVn$ILp0Z`9WQCb z9we)5<|%sj2E<_x-UM2gt>G%X@<=(yZkz9(O!57H*ZMo2Oy6la*tG_t-lv`0KJ;aW z*jFR?V#X~vwDb)uWP5%YW-$5Ur$;v_mm?lOUXM(q!n5Hx`1w0l)tTQEDQcKKYnJLVj0z2ndDo9_BK=&#N8(K{rd_WF$z%<%9T_=2Ia!KaHsZeKly8N3N|Bq^ ziv{eUiAeeqGE``m=DyS4rzH)v8wI+vINGrC<(>`_=~#BDv~q*&SL)^L+_LJ;l5ydwEq}UfvVXv9;+W)|edkF?>Z^ru`-s zcT^cBW@Kq)(&{c(S7}@%`~*5T#o$8rwdwJqe8+!0WgNs04YbkY0Xe2`B-dMir%#=l zmu1qXf3BXH`wv+U6SQJu#qW=8!Dd*da3aer?VGQYT0AB8m6XEw(A;qv&$V9c15C0Woe;n-^j8u{yI57d}Y zFmOS9P%=T-V#D798yeEiTtc-w7ZehQzMM!`zN)PJ=ey*@U8?d_EdOoz7jk_?SJ$U! zx}e6n6Y0|j3UZ)EYNU@1NXu;#h0I@jOx@*q@$5mH(}%x=YWvH0?SNW|Lti^;*rH{v z1OzdxoOe=+Ilgaj286a}3nwQZ>)X7%<~#cr-A)~-;!NxHh&+I;E5#s%B8}e%>BnEh zVzH`2vp$}ku_)dQC!zFjx$j)>p)^@45gdDKxX8P~8g?5}e0}DmK=YAh z2KCDqeQ=1IqztDA72Px(krAk+M@J4DWjUNSN3XTK9%yMXy@pM1viZ)arx_@VjM6?} zS@qjy~H<_M!>r9qfIV z)t>g%?*6HmB1ZLz;filuHGU~Q+ThGYfmP@nv|8P`fL}XRa#bqoEIwE4w_hN+R$&cz z2TlgIBh}2@1^~c^O^kHL9;Am>0EaeTm+)9$Ni(SE;l-CJ(|7dS zj8aRT5=%&p8B`yf9&W)U4~4Bv(K$?1H&D*{%Q3-+we;l87yNdY7sR_V@@*oL6)_zX z!;upXYeyUAGH%ZV8R#|yDo zoOYoyt#f8R;YlU=LYOweVE3E_t6uP&&T%5g;1_XL^&f|FOJ9>F=>XjGjN4jUBXjPW zOY)?TT@s#=#W3O?MzhAX7Y1IENwh`Z(ZZD86CRhhvScOS)&ZJI_5RI zF9kE3M=xU)V_iQ+?XaOnO-aeK@nZ2ohAb@Y*SE+;r$_JC7xMbE8V7XT6YZuyAr_c{ z*0xKCRQpP4@NkJ?Pat0jSVYsiu0~B!aV3Q1olxEV)Rzcr^?WF@*$F)=&oYZ;1FLuH zog5y+3PAA!6EU~DPw?(6eFvO1q0yfCi+o)v8PbzT*TsM=GyS`ftC&uuN(Fb zYHslV)Z^QInH|DUi6?=aZeRzvKhi~dW4^(^-fGdRf!ccka1bzfry2*!sG= z!$*Fd?J1i?2GefY$|V%;#)697(>F$;h8FWOgS78j<(j#)sW|Ei3f60_BOfl9-y)qL zyqSykKKm>jvJT;0~}gY5!gqp1mw0 zCj(n=uDf9#80(AJ_-_Det1EL;*Dhmy$4Uiral!{J#*}o^!5QxPEN7dvSLY?i)a9qQ z$=j zoAg-_1wZG0%)R|NcUPN_aTA=&uuKnQJ` zQ~o|I4E=d3Hs3$?)OOnlw1=RKO&s-m-!U71FyODeCJdunYssRB|lLRA5V1#zU7}_8>6Z@^b6p0-N*uy~e zwN@Qb7xQ`Ev;^*o#zjsuQ-O(SLmD_ToVmG}2KL&VQ zu7OT{Xx}K@%6wL^$gT2y1egCY@DK|S$713?YdrG_yTf+KR=g%^DQTWQEHzIg79S^u zT>d82vsDyZ)Gjx{rb#N~y?y%_JkQS+lEFa7nDLQdZaawgye^Rw^^K|t66t?#4rA9I zO5Hv)^1n`!m>S*jO%snjDpqXant*fl%|PxrjLMH?FMowf@|_{--WWX$;%iNdkwl^D z5YNR`I9A&oMO8X{XdYC;Tykd;p!kTmUF?W@lg;yH^|4*vK}V^m=c}DYl8lE^li(z> zNObh;A)B4#4u8G;^l-zB%>&+Xpg?%$6FZkags{w3)ubKGq`KD`waiiEz_8m*&k<`l z0tmSoM!cHC%csiEr>+kC#=g=4X-TCO41cP-i_$|dS>k%X zxTtqFzc~H()rb7LiYui-;t;TUyit@)Nse;{U^~VKDn^p%-?;^5ZDp=@>$K6zFIaD~ zE02Ilg=%VQER#VU3nHiCp%!zf#x=o9J~tfRvV8B(KFAkUV4dJVEj{D$W1=#^f?@I> zE)9C=mw?E)Nm_k)8Sl(Om|2mNgY=(Eg+LStzBHpi(&IyJ&e@SH?JtK|Y2(@1slh1U z$;7V{)3f7SBtVygP(y?# zudIyrS@RCm7#AJdH%eR*rhN^VerLYIU2M9a&-+yKAoirvfb_a>cb ze=?wvMln)t4T?90v-jKCs)melHCY zSpkraBQU&_ZWa~IrtLbV!3kYS?Jq-!bV~;uLz;4DqkmoT=it~~UJB3efv^1BA69gF z(aY=Gom~_^F%X~bjI&9Ee={eiBO+;oK1o^WE_lPSsWoJWtI+xw7YgMxGf`Q9DR9pqHqN=xF0&#)YWY-~>HPWsl64>wmghuo=#BOZIry z-!6BD)9&nocy74hRp^ehY-3QY!LH&|6f0gtqiG5FAjVneS+H12Po74ajOSw0Yp0RL zyBe;TgJh|@Cx}^qjjT1zKkdKI*Z~g;)!Og<^S|W6ysx!x1UQSJN!u_RWeCJ26Q}`W;nVw*ab*wdh4AlYi zrdIgR2M*Xol|@fce{p&*XjAM-rk!4Z8X7Jb8Cmg?V|W)JMBRNY9r|wF&^H$Bl@U z9w&K?xzq?(a)%qnq8KnN>9bv*(!Jk~dY<0?fE=nm=*H=yY>YSbGpdsL2kNX0xaZDX z?62$7CglSaG!Dd>E~rDhBby!VSC>f27f&A9HFSELYtkUlLjRiCk>Ek( zc*8Py);Q2ofw4Df?qJcRpEhK19F*MGxnji% z?F^#00>>J%JuV1>*at6Yk&V8Mh8X^#Z~hZLJkmho1;!7De(a;nL>RxW0jxf$lQ_?> z3#hkG-$f$Bln!7)mI$VhA_YZu^dsQGAy;dESRF93f+L2_RsnYdGrHk6K| zZ-GHrWJ=1Oh4JicwDIbfiVseD8v0}N*%0*6xUr5PGJat90y_v{w)3o@S0{RVI*<%SvtDlZV#)2cnF&4F%rw=;n)*!mHunoa3aAUWD1VJ2e^)>% z+Xv~q?oQ9tZ!b7DG=OkW10!Rz8a-&|^w5|MEPj3FUCrCrj8fhjIlD^}KjG#RYid#JC(#;;FjQ zuqD`Kda@0eZr2i7p>6HY;RUg#!Q^70XMEkA!%~b$S>zk0Umz8@^za7;NZhkxbolt%lbY>JK1#JgY9VTrDbwomw zLtnuzZX_T@=a5EPH$TEm84}sDC&A|M8s9t3>v5kzExHvt3S?gaQRzAdn zM9t>=_xq5WuuEAI+-*1l>r*0TwM-8=zKiyImuX?dB@?VO4VA6bQV!Gay&~p9oiu{^^Iz@m5l3oI`H=G+XY=4O4W`Wxho>)ty?G%29hk4$JHy1^P4X%9BvR6O534I)Qq}$!7B0U4>n!Vq zqviCx=Lp#$T6)?zAm`FjI)G}{Hr4R?By+KjuJl}jHBv5jeZ+lyO5vdPZ4KOZqsq5j zEhmyAb~#Cqv|Jh>0iX)XZXzGsvy3^7am=rSZ}le z;BQ6+;>(@iAnHhV;D2s32=|j4d30gX%qP6(UH@3u)!EhPC-D)@DdAYEwjC*gEBh(ZmAwPH7MQ^D+Z z;Ww&L5we=Z-cYg%a&6HZXlXO#Wx4L^qm zdS^&Qj&L8Nx0{t{YA~`qXJ6m4=gfaQGgJjh zo-P8z@W4a?#YRt{t1?OkoK=GA)ckn#(5Nd$ZGujuo6lQ<{k{ogk70L5%Oj)a&7H{| zFQsGK%w`iSqHr2AC>PtqVUt9ew>>uP4K}35=e|bS-k{S}h!nW>x7EJ- zeCXNCaQt%#iHXd|anKwQJPnuza8M(&u@rOh_R~gMnMF)Hf;omuNXXZ__p~%T-Sheg zKzfbMN+gzP)qhRh*8dJ(cqI_Tk~c^y-XGV&kOkbMag&QUnReM?&fZ>o|DUv7^xmkd=0tk^9q;Xu2|1TgjZwy#yXkt8D+y{ix^-ozQ-PC(%4>;2<}(Iy0A zd{WD2K0yF(eK}c!`b+;nUyN9{BeWc__8nmh(08~5 zgR@EEl|$A}s4Ic35IOX)R@*b(Ep zEUD%a;Q!60RoX#ES>Lf?UcRWXeiyW=x%egv7N0l<#qjkmlm;L1F)3Fnj#N)~-aD|+ zZlLA*kMRg$-;O;plq+ZBW>SLKfz6^h5S#oz4L(pC59DqmHWci?k`YIUBOC?q>WxxrStvo!~U4Pm{ ziTIsa8@9t$C+DKLG*Wq1hrM@hbCY|${hzDz*PBWNzFFk))MDlndg83Kqm!tz=Z3#x zuvmVs5z?l03+OP+s0MTd9Mg6|v4m`WvGsQ@GaW%$cJ%g1*aP2K_s8+4Hrj%9a7@;H z<`X&eq>)Y&spUUQx|U#bQV}3n>OcTRG+Qzu^?;gq)dsPEz0@R4xeKmKba@(@B{XrW zf0w#es(EC_I{$Mg1egBnrYT^jhmiZ%o zVnV1c@o8E!;p~zr#9y)laDOp6UG5`8E-y`jN2(-WEUZ&Y%yHg60hFdxq=vEMvFy7* z`RBY$4HCAX-M`&t-bwG&91!`-lOP5%A`zH9Ns^0&6B@ZOpc+o&3mQAX1zYVGt?}yb zFtGXNy$c;E6K0mwZ=0UlhzpC(_~`PPh#`lbL}rlL6Lj1tNMnqi*suTNB92^19F)Y5 z_ruP+FRv9c>&kcjb?f}&sqPqK41C1fCr&eG|4MTEV6cC{Qo@9;fx9D`<3>(5AbX>?0D1gRN!g2Iw~`f zpn?e6@?3mH%idzq|Mrie=X??x-7%BvoSy3+FT@})uoRbLji-W0xps|V=0YX+!k=(% zbyohg$^X|b8M;oecH&V^tse41{vC#jCe_-3U5s@x4cU{&0uSc~>mh~fj0HAVZI>o%^=kAV*hM~vr703eH?cFnQs3tv`cch?M_h=H*zI? zdK~t69J!RNy>r*xQ_l(^ZtOoEdFuW-c4M17u0FbO+J3eqXPh!f^{}rZER3j9c<0$r zCid%o7V3&0u>kwp??Lrr%=`S~ry)Dh1I6X@$LoRX5tRa1f6z# zsnnE-lBcIaIj9Rn5;gmdA~OlZ((FiI5G{V8G#(FS?Rd%+fzk>n10K->nNq2942AAy zqu`2fE062{jXgaxqb+ywWfpz=qtkzq+CR;W9!NA!_NY@oOjPYWB+1ddSI4CIs+1-!$(LG>X}`DG?fJx$$MC+ zJ?Wjk)~_$*nK8UopAyMd_%Z%s3upL5zJPOYuQ98Mn!}fL1D^l~^m;Y4!@Sb8Ilc=f zA=?_b3cw02k_y(UpL{?Apq*r_j^`c$;S8ArSL6}GwcL{?PnKV=J2kzm@(XbTI;Rt7 z5-*5r!O>ldir&13AwZ=FX`ke&xbAN!IXNkD>^aRiO9rf6!v|KmkKDZCWvu@wQfQ=hP#vlNQ&gNowseQc8EPS5F3S!Nlw8 zFQ_5WZ~^V;M{e8O`xgmrXn&4I0(&A-2b3@T;Uf6FCDMqI$6DXs;s`BSarieI^$VoZ zaR4bCJ{+4<{>j5%cQ(M;X_&uI%dO`JT_c6!+>Vt%wF zXeXSrBMO8~51s45&HF9lPQ3li1Wez3)>hbp{Nzx9fBvd`3rxqsw7;u>*sD>y$y+U> z)L-(sn9bM|?LQW#rt@On)S{VQJyS1O@%V$gf4y(=&U{78-RXGQMmU;xGa!{YmH-;l z%PmRp%A2uIi=Ie%9JRK4+u}bf#MWEr9}_pVC*ji125c*^B<0+12boxV&_&bgtemjtL zvRs6^R(W{j($-H1xF7>hT0A}u%YR<~Y{2Us_aDaN!XYej`_lNG)9>3AOyUj;8TfTd zZ%x7xdi$ZwBu(<7vC9*X6lsnrk|>oP0M1p^DqpIKll5~&VD(OnQdygwzzOh!&7%z(xxw=aeg%K^t6)~^e?Ui7|$~B zdp~t83shhL_BjKU+W~Hj%!i{bV|Iomo_gOGt&!r1R;egUpm8WSKvnr8UNF z1aRQfjz*{W4_*-yo<|5ig!mP86eq`75CDroN4E^lST;Q;zrXlb=GtQYc9gCWm`jm= z_M8Q`fE~6;dc1|L6SIL~YOAmbwg(+x$q?9;3<%v+6r&~!5=kx7nH`Ui0GOGKpX*@q zFTdRA&smkfMTH2(5rVLq9%;xVyjdjFA%APzb5Fc)f}l~Y?e$7L;5?ebUCmAju%Xer zld*@J0l;j1tSTW5yr0!)o z{~*@=+evr=BTFDBzEuDKSCaHf3{s}|EdJ9CpL~uTFL1Tl23I~#Uv1vyqo>ibG72u^ z)_b#N&p7})aE2HGV1TbW)yP}~`(;d4eWB>ETqak$OLXKzQHX$N=*(~YI&@?k2ogih z6a0B*a7)Em1^0dTstT#-IKfZs`amG!PfsZwH#VpiO_M`nmA0kZ~0h z!KKO@-x6}!=#3Znv%$kC-{$dbWZu^_s{*DTRHFhKJPQ^z4lsb_n$04rF&!+D!4GKHHlRm`Rxh!M$v?u%o^lo zm2zSTpe{c@_yO?bjd0xh8nJ&4?#Jgn(t~L)OHpN*bR{)cQ+Ik9GMFfyzHD=f1CGevrQda9^PIWnf>p;1e($dM(-<9gzhc z`lf|U2L0kMS7|aS6FoRN8{BcjjL=bQI_sj$QF}eOXZi6@uO_dyT=YLRqBdgQqkeG# zeq6K^$U}9O#(Wm9Oa2~{ObRZA)*{G0jo=AAmdT*)a-glB0$Afc;eUBx)V% z0bD=Vj!=BU2~U4k`1gN3{UpCrqc<*X2=d~}Q9}rE?w3K5r)wQRtN<_pfi z_XyuPcquA7X!W8?#V!t4Yo(dZU9uz|Ip2V6H*1Cu>zP5-Gi zgmIb=Ydb$w6;JwIcnP$VpJ2*Lc7;=d=Xf6{Hn{-;3mLV2gXUkvKZM%K^uxe&P&gY` z{A#@J+PYKnI^5)x>M3)(8+q(Sq3%x#C)9)Y54ah&MNI_7cSG5JKu-gLB0!Tw3!ZuM zJ~KG4K;_s*8j|QY*zc!6k{5WMXVKs#kN__%*zb>a4-B!Yu9Eno;?lwj2>&$eP}MPi zvw5C>?)SzrIXl`&=BqOxoe>)`R`8!(`{pEwuy2SuCJ%OQG1drRPJbPf;nT8Sa9@@bFO_BAqnj}E=&J-5e!>QhU|B@ zx3hThj8JA)L)aM|4^*-OTk|<(|8oegf1n+1&cPWY{N-<oua#?d>YJQ#Q*$*`AKB%}+M?aB>RP?BMX+?Zfp9IMW>Y|9|cI=D5q6Rg5k3^w(BUQs4(H!>He^N$&&vV()-99XML2Unw9Lf!_7 z&;E+SsOAe}?~JCsvzNCmH{70Yp118${!D$@uQ$P&6ky6uemiuS-}^hIgAAuHjHraPq0kU_d01SYu3mtJ)m>643pRd?@DwUs8$F?bL@*3+Sc~Jxd zk()sCxlPO?<9}YwB^&Fl{n2VeR+<$tg@Jlc8f*zy%D#m~J+XRxAy5N4lunY$IRw5Q z)ehT7li~h!g#0Xe zx#sJOMVHXsB?Io=LO2Ki`JWSl`MQQvC1rfk-Ax0=ZSOIPyaaHi3vG4!a?{AoB8pkg z0;yDF)_}kMwG@$K{YzSf7a9v#fZ>k?mXD*c#OU-8#ts2%^g7oA^s6V2Eg0hVO^!{Dx?Qsz-=oIw2+QKIoD<*r zc8R|4`uSnfKR7@bCjb0Y8ZgfB1zf)H;GEdMwVW{vBJf@)H9lTnxB^VL*b_;kFoY^k zaTjMF*%;!)is1mne~~e4WI8~OW%o!E`>3n=If3+ri{IN1K0d%pV&5%{O+#vb`C@!(DIH!b1xp^D4&v4hNkz|{jB7A)c(twT zAgIWKn?}i%qd$BViC_U=f^{h5Fnm$@6@O-uJ839K(fELnkjq5DCIVo{LZWkKKpK?J zs=NNU0&6X+xX{dtH@U=mWEZg|5KiudEpr|(0$OJ<%V!fLw4DO`4>5+9NWZxTh7RVS z=pNd$0*5yOS`MbtiuJ{8^HKg^`j>Ti3)t|%d(@qzB1^LD#s0%TGFAaP$JvlD<8|fm zjJPbIV?Fb85N7*g@b8z|v&Oye1^oEH9vlArBZe^pT^cgb4)TFlK3F^Zk?AThhm3^{ z7L6xT%0viuo+bnVWV_m>6@e3C^k4xKDs~h}L}=d!4ffY96ma}faLK#|jquak`{RfX zG3hpz;A@k>b2zBarJ`9CbtTl&wEOB=b{QM*7uG?=HdxFTH0dG!#9N+#Z@#N>s5v2S(j#K)UbyR(?W*@3Tzx%2^3jyE-1WwVgAN`V!CZ@Njz z3|;Rn@}~YwJHuY)tz3#BuEoZaBpV$HAaEV`ZYC!C z_#a%5=5@^2`Pj!7A^Sl{pNP21@xd~oO_jLD?d5wdC}LM8Cbrr?`Vw zU)JrRPYnIyKeXn@V0`iFZ2fjiYjhTVEH4$h}~wLnbE=6is12KwV*%9w|@#%TQrZdD9SvD4tLA=CiYX zBhJaAy%&6*NU(UEwu!tCpmQ5p6;I;QTwY<7*|dt=K1!xc(aX3}Qr8WzuL9d)y^x}!Pbi{L zVPlLEWxIhdk+|>?QOe!lwfqAJ%hTrFKE8wOU$h^Q3JT63svl0oTHbN{$sKQAFMQ(f zR~X}{pc=sGq)~{33g^RSf2t%5j1qqSq)G<~ed|3^cm4bemsk$?*Ik4TrrN}glvVbe zu9Ase84g_v9f!vf%(MGsjlb3?Z=g^_%v=vtxKc8ueVhBJ&I*B)$>J$pM{l8*ojI~q zjrQci-SdC$SuSQAm@3x9M$$THS2?ZhLZe-yO}j?eN!EV!D+2rV6Da}&7TnML_5VL! zw|vj2HSJYy=Kl^CSP!lANuDoIt9Yw_!`b!b?K?NJL?h>@pqzY|5AYJjh|23!(hx0C zEpkMuXW=KryUiQ=L`K24s`S5Ll4cYCH~Cu7SXLy!nqkbFkiSigDDL3RtaF@hTE2&e zg!N5`Z=UGb)brtl`f_MgD8+8AC19M{f&{aWgycKir%Hp;NjaN2_}LlU^KPm5+ZY~u z{gaWQqkgiaRjf+NQYP9}#bDk@W~Q~wqmT-=fJ~Z z`L$GpYy1RJMqQUHKQ*iZ{X)zF9)t|=qhou~0h)*~PJW1)%ofYwWf)j9ME1%;_pp3@ ze7x|7b3Edp{!q=FJpL|GdgghS{3O9?x~=mL#oe7SeLB=g_=mJ^xK2`xRP{XZov`SG z2ZuzZ7w8~q5EoAdn+=EK^?Qz>6wPB|42+R8CgUW|6#Xoa(zc;v?(9DdG!F*aKjQgG z)-qBV!`g(xIo9vF9nO)8miZrf{$qW zND2<+aFl!lKf@ zXYPjC)D$Jt@MZp}+dh?GAgh)$1!xr#bOoDB8#ZBY{ajHNRes>^pkjpwvd}j=#99Xv z+$U_;m^>a~v7+**ZKr(^b#4AT5NBH20+%znH^j90HFZuLyk*}}qix*0x~%cd6PlNsI;!$z;ZFyHYm$1F$RgYkDS23`w1;4{nhqpPBat)XGu-m_QZ!~?^_cj?Bv z-#Zt0aT>p2yn~1D=~JhKS1p<~+B0=gnYmn2v!TR)brRXliOzasEk5pg`PHiAPR8rr z__;kW{Y*zHF>##CHkzwU{Y(d0)%!|LLcMJnfo9&=mX<=5VEC@v z7}2;>;Ajzf;lDY_#&s3CRWA%}!=ktXgO@`plE3BcteKgkjKj;`{t)XZcxuh8DAB8f z-on#nv+0fo@EFru?_utW3K)cV78%vrksAupmgzWIdH%i8vRG{6D~2~@Sxe-iT8GQW=;bk>3D zwXykKuPqV%0KIMgI`*2vDfvB|$=^fG(#Ylu$D$JsqTpw9T)pQ=@{s1=9`eY%gTac` zyHPMQhem?LHWjE+g}zHbG^c!44((-buBvibw?oFRW%P_SaXLnxTM;>?^AnC-`FNCg zNW?ZchgD*!V>>>%+>$$w#jWl;aDINcOA3Kq)6cVk^2?J_(T}MTY^z??tE7($km?}x}M_>LTVg{LbX~w^UvD9?4r0*Jn4qZ)65P3ZM*HH0v{pQppxJd+# z%g<@ueEJTMJf)IyS&))D7VFF66?v@R3u$H~1or8WtS_v)(Iq8?c``Tfzqtdpf7U`_ z97mw3eE+Qqv3miHX!xv|)f_baApM2mY?tD~9&DKz&^RYA5#zqy0Pf9e#My<5^cM}~ zm?FFcbc;Adqx;FM7tIv|-dx(Es91p@&5+bX_U+Gg(<3ux6z#n|XXrOZ1nwJ^FSB* zB+iwl#goZ9kK`OofCeE!a)eIvwCNk+u1bP@DB5MsF^_T$QlRa7g80vEYA40USEN4v z!}HbEvqBtP$edO)7}ae$-SFKGJnw}Dm?Yc8BEU{eM=v>zeMKZprv3EZ;*3Aw7Y|Wg zRQB{^uP%P%o4;VeMF^6Yn@zCHHf1zlc>277Um`G(gyD`^pW}kt{uJTd@0OAiV;jx2oSEAyxZtqEv*l35AYuB%*w;riAu`$UT5C+ew9Kvvmba|;E_%k+_aw+ z65k!S#2$B%j%QZ!Z-g4xBjIKo_!MJ~jsSoAvB3n)Zh7JMy{};BGz}3*NQ8EC(V~~K zopo~q9`g^F)T~*<_=advxh!h?0G_+SaRyF#e^V82@SF(f;9FG&-mU7;?O|Y@12D@ORHWuJ=-_mnn9c&D0!=);&dB}#A4kuX`F+0wRA;RaS z)RhXkPVq_6{Uc7+b7Mat=Z^^)?2vfPOcf1{>!KoZa&j^}JBEWfA?{MVN)EdkO%M{5 zo*O;Ibs4m}$FX&0gPz7bEEzGOniR3DS1Dla!w6B z%Nnf%=j9I{KD=mWgfPT@R}E325+}k3*&1FMVF3a2MkJH^-rK@)g0mQ9#2a7p7!!j}O>b-rG~wJB>E;v)j=bhe`a#ZZPiLATO16 zV{gD=tzj1PqXfrqIPCD zi&^G#k}Tc1@6)^FmT2o5{~NwOK0b4wPagbCc}hMTx1`y8HpT~drsAFJVW)CeDg{~I z7s6c&?fgY}xE#XyyiVQY6@E3JW89iA@`A@+EOigFL!6$0HX73o>N*Zw)2v}#wg)Np zTV<7Q){i_kl|y@a83}?~zF2&;9R&f8A3vTO^kgOes7)7i7BeU|YUUD(M1&`Qq0ws~ z`C^*<{qd~aMC|*AQaoo_Z*7wqBWMA~ z6fqcf&wB!P+nzh;t71zCh4idvo?BCHpBFGw1 zl^GLG)a<&I06Bvw14{WPs0NFEyLRJ-05OqPniL*TPw~JtljxeAwrUE(H#lKWI|Zs* zQckHGbOI*0OiZC0tG*4&vKk-YhRfd0-^zxDB{DEQb#tKIOIJEaa}cF&Zyq zR=e{)9l;ngZRHc-TW~^aQ#fmRMY=Y?8l38=JKJPfvwh&@J+@-$W(JtBsH?)Aqz3Wk ziMw&*hNeLnlytA*9$aU%OM#P%m4sB?N=4ct1mca!*<>5kytCJQ-CBn^E2ZzdZ?Kc_ zl)N44+MoUO7qgv9+tt)2A!`m&BL)B{qxy;%YlG!@u8n@tONMgfa*_8uDZ|vHYY_}F zjkNzzt>QGqlGWL=hC#c1Lgl256m?9}zz(J2l-kw) zwUVTCSTJgn(Hb;A4qU^@gKu73IcqU~V-4=HjqsNZ3^=o;BP*Ha@9)oNK;FKkJd#)#q{e^M;U}y>Iy#6)VBmJ)SJZ1z}Hkwd>x6UR(QbenM$r-+GK1%?8a4e30cJ z``NfHDPl2Ae~hQWB7ASUYcv+~#Z*eItdVqy?zKg3egz7$^gL~|F@sZ_<$V~~3#M_s zVNVEhcJD=rBl397n|wr-v&6;2Kk_;uu#}&JS*9}zyZDy!d2;QW3F>iQEC*Ep0aMeA zj6So?p8@xO6l^Y;dCtV<`n5p%>Xdyi^c(8G(B&T_I1$n0L2s(feNa^JoG_`q0Bx!l{oxAXT+ zc7`$UKT^jI!5uE8qWu8sq-X+Gil1uXUha~LTH_44j@QnjdraEC zybmlYb{qGR&DP_$3r!_IbaT7Vfu-Z+zL=)7D|UIvU*V$ir1R`6t7akAQoU0NGm_a} zCu;-qu@@d&zs{36NW$AVpUs{nzRhqu6?9p{Mi-QKqm*kwY*zmtLjXl#@}_M@6Q0U2 zs9{ZPN_RcY=CdDT3l4b_^uHfZ`dnu6bhcp_u+TlI%zU%lWMGV(17>{>Z4U_y3A@h|+W2Hxe*A zrX>IzZd9qRb`@+d zkih9hRI*ueaw%(D9rl2=_gU>CIqgtN5m06~zz$j> zxdhNm2&QQEGrinNj1dA9NeUi+wYCY3In)wbsC+URNYUSoM*n7yYIE59XxxB_-#4XF zuVbi_X0rYIu6rt(QvwSLe|QgBu3Bo6kB@Mup$7O(Szun3KI*ZY=fcea)+e)l09s*0 zDn5t3^Oj2R22RX<=*#A+%J#j?^`=44&G#ll)|1K~;-R)0sHBLBB_r7*V%^i{UlU(1 z`+8h`8*Hd?D3|73;(V~J9AKyuL8|UC--$ksNG{CSNQ*5M8n}ut(-1w?Q(fLSj~I0V zWL6CZ!#wwug&^U60>7?h_9vGijH#Hj?=EBtb4V>b0+*#UqTwobf*#zh2W0Q6x3_nc z?9@NhLn!f-zI|>N+fB5cPDNTRfRiXt&0jy;3+5r?_G3u6Ab){aL7iK~L6(+>d(WzN zpJE)eGtilQB+DP=w+POKA?fz8bX4bgjUsUy+9XW`geC;<1h&WMm!mP3QyspP`fn+IR6(Azf>FPUoP9|K& zwl%Tr!=Ik_5IwJ@FuQKu$CruwV8;iETw{SUENOjF4*LXPVJ!kc!8OOlc!8fG+9LyW zzh~PaGHrYvOZ`d$sxkZVA_UpC=YC^{5qkrYvdp$|8@1R5SdB?71>otk!{hYn(`2cF z>dgqCJyI}1_gZ&8R2^9-lOTd7b?Q>+ffRPh8@Awoybx_@PU92~_q$LVbv*<9$o&m@ z%n_`5_Uu_2x(PINQU)dy12zh`*DogG912^>Z?00$t=*Od2mg4j-MCiPxJ@VeU5nt< z5VRTJ;Q_G}8L`b~f`L!%aj7~vz3CGJl=jvaMpFx=1+w6WD4r({o;e6onz5I?2j8l> z?lQ2{rV5^($Tmj-k@|M=-z!&!GCr;ovms-bYuxhpPJ`;w6rnDb3@oI72u7aqn zl|@gG@|IoT+vzccaU2Jy@_AL2VT_Nwls(W%8UFATEP&HcAuY5`EBIaA*|*?*@-QEx z=SuYX@gx5_K7ndcsNRVa_#%ES2NWfe)X&D;+@q)tYYZn$m(ooU*XOtlvw&8#8c2%`d~DgHu-|Z?bCVnp81yC z!rp~@@3q%IPhBk zdPo1`Ld#J6m-+f~YZ}|{)R@+(Ib%W*FWX}7&!o98Z5%rB0(H#HKy^bjnutYu4K zru?C-#<>hYvy4Rcwp_MvXP$HGal>P{s;;D7KV5(EG4cXmZ2$4Yd{qbCSmpT(46p{pX)_g7$U-5Qd@WF4A9UtUp(y$Jc=m+{H3pXSmBzzJuGgx3kO{ zXJzcO$6jF16NcWw7dE&E1QJ;~t}kYZunp+4&BF1Kc3^6G{$1~#>&02z`K_jMMC(@R ztdB7jgk^?t! znd{R7EZJUUz^~rP!lUq>qrRxHTLb`mddAVPIU)(CDSA0Q-HT;0T6T>;Z`(LV)j9(v z4GIj{kT-`&z?5iZX8DInr$rTK|B=CBZ0|>u$Cm$yvgui9__3ib0Mkccs2D_120$@fd)uS5d`QK?n?C#F8fz2RN z>m+{uk5irOS*y0+1(5(rL3`o#HGIer)&p|NinFh{q4$0U?K^>v-Jzgk#wAxSwV7XV zoRV+Zq|fid!;e3KS;Kd#6+r}kX(ronAt`l}Ke4{*pz6AlYzL}OBms?E^4O&Y2X3Xp z7GggrBHMTE+I6@dEd-sWTjtNK?AWn{VN43)7T!GF7_K$gPzZq)?Ug}`idX+EJE-{3 zxL}#~uDpTWYFGz6^?@L}ltZLW|Me;h#3DewMp_W`AQSct8vvmrFPBT4d0YV$yE8=+ zpCYb#L~&3r$XloesJHY|FFVx6>dL~UI?oxfghYL*Bz+K^bs*pu7XX*~Vn(G=4z}xZ z_N?0rfp{cpR-$_#4W34t3GizoX3GnY!FAu3kH04G!^6NUCp4@AjR}I^d;;~#5qELE z|L6{Qq3aFNJo`!;$VCf=Pwh$6*mN3{j@rn1Z1B zdXzk(75zlo?4OIpE*YFZfZb%`kzF{ z_~R`yvaqM=j9|S~(g*KF(Kv8#DKMdh)7?>BMa5JP`1M&RC9;H3PaqdZkg!QcNC9%t zB~XC4VkHC@4CpyxFPQ(Vl{5ZuWQ}h-4cWawKYTxzOGGkuo@CrS$#~80 zB6kYGZHT}=bP+Sqb8@jI@})S~fapPnr7id!JtL@gvvUxLg!#k)B(V1Hx7Uv0#0#Cp zUCAdPpeZFCpOj?PSh`|o7QBR}5;l29By^pRJxAuqf0^|JYW6KEFcluTU7*HXf;CE> znMBm!+XCkU63rVqYv}bY7Q`wKndt?hEpSq{e|Uqu#gPP*yO2h`Dk2X+MNHl#eohbF zyYBoO9aG-B zhg(Sz24BUvXSJBUe6(axCAfchG`INEYd`9^SnxJL ziR*4)D#?CV)jxb&0oGsOgU7u+jlEY;ppx0PTICNDjE(y8>!yYECNtS>wz#c5TA z#seGbXsMruPPR|~@tUM4tUB-{`X|sNz*9b*oBB;st0uF^2Bg)?lDq58^mm)_u;o*I z+0U;+(F`0xAI)PI_FWwX5n<*A4X7DR9kqfi7$S|w8p}Fu8Z9quhgtTv)mZKNZM^+N zCG|Rv2GHW{nq@HvvaiYqH?lo^9Sk7;3PxJFl z|91E>woaPweBsg7MQf6bluRRtxZ)QV*EZ^`<)>FO(ZE&U#EDmLJ2};F)L;j=X@9yl zdlI!ic%r3$+r7g|M?D)nNnYB!?>)S$^oL2e9E>65s9~%ox7a{$E{r(x{xOM9gBXDS zXig!EK47{|bRMwI$MsW=syusPz(BjTr9|-)YdJ#giqS#iIXUufYz?yh!v#N*Vo%nF z9f)-~%j^*Vd@~J%A#z{T%D;1+tB-x~K!I7#K`R{6R>tP%Ko2!h|Cag2mgQl*f4J2D zVDGtPai9WjYMlLXSe|wv@w!T`&Y!=9(+fm%wTNzXUJrWUN6XqYq2^xOORHqJIeUx- zml4SONYS>YT2{)onyVhlo12@1*P;OW_0ht$UpZ?@uByBCE4SLDO&p(r_+#aTy3XT% zSca-0L?aGo*#0@&nFc-z=%&G$@?e(>yCh=h<84}`*$_ydDa_2AU^gs=^N|MEu4t6qe_qR(@$=*o7^N z<3$v=YzZ#5B9=M{ju3$5-Hk5zQPAu6%<`sOZCOh3<}VW{C}7lLs}JUFKE^)zmiwdv z?Vte8JuIJk&H|X3c0_W^gg&@yWf%#rDJ^J%ub!#7AFuM7rLIG4TN_HI#R>=i0q?3J zEwYkO%15^0Fc{0I%4?}=X~~w$G^vN-)g>Y+D{O8NafzfwYIB@Nc^K1$oVpK?gMCoQ zJy0mk(N6Oo$CtrL=hy+9;0INj|F|Fd9~JMkw6vvY3k48rbN6xd;&>glXSD{%cH~ZS zeeXHmHX#N)B$v& ziq0l61tTWF@D5;6_%M$JQewub4X!R_nJL2G;72J>YgSDdpbve z7aH+8U}#skZdrVhN-Sd@+~2@{*KCV{`PDg8ZeF=7ojttqxyh*r;Q#{Bi=i=vq69-C ztItxqXu^H>243^Y+vg46sQN%@LJ1wUyN}sfP9!Q1qp*wM`pL*l+upAO*io%ii`sbG zj+3m7!9^7_K+2-ngU!nV=Q72nc!z<_+K3@gE4%_*0e!>OwR6##2|VtNhwm)nBOhF5 z`^p?uWs}JNm_QSxaI~{uS2P&h#8+OJmy(9}*K*iEc6p^yMC|8ZynE-rKF}f{=2VW2 ztNvDW=LE&-jAz4LiwYrDD!I#!_Q9$41%-ifW+!1le&Yi^?cC=aE_rm^otC`ka=-rv*Jj&lE_4NUSA z^qeIX4RfCTV#u1VB~yKKuxisO{1B6_2lLB3S6wp=X>x`e>-K*eUin`~V!vKX?##yR z)c0_{m{_PQ(Xq++k>~_fjWV1Mh%Q^Cywf3<+ZJ7{P*B!T+)zUBjJdDdLF!6%dM^>X3H!y;cuDEwDF&`pPE^=^pTl$`3ZQls_8{B|L>r+rn7 z#g=8q(ZX7<*aW8!chxS2NAEOTuB3v8EI66oMOF>FGj4C4?UIatRAaMJ)X18FV!N7( zOnXp6b`P~ASR7yFIvIla{{;5`G;(o7EzG(DIS{;2sG|M?iRGTFrt-Ox<#%DYml(me`fbVJ21No}PFq=ItlGKlg|N%7TAU#&HIm1- zA|4?Ak>NY)HcEUN2(4_?R_C$fHotAdH88jLx^mxlF8d*!vz@SqK<#4mU5|dKFY0Eik$huZm|BmZ90j7e7LIjkDP0gFC)@`A-)ufahqkD$$kMoHzBHsN){a9w( zW=25H0uAxF{ixlmo4x}_JKr!k)WcWMX1swKR{6#c(bf{&WKj(sDAR=?nvXmH0*eaK zkV?CL=dj-%k8P#gO~geLyj?oj|42oFp)A`jf~|M*=KSuj%HTgxSMRXOAOMHrxaK$M zak(H4p%iFN-Gh^ZY{28amJn)(Ws^JRd%xI*ZT2#k@e~@Xr3(Hk{l->@j%?Z{;OW!; zF_S8YfZ+1%mrAg(Gea?#E-kya+a%M#|DOzN+h9xkquQP7ntS+=#D!Xh^o!;OE~8~2 z)X2CgZRzJTfPDfqlpTyr5w3zH1?Q*1mC|@b1;!}xM@vXyOPwSx^3J=bchPW`ihnA+ zA>4SPQ-DF_iq>ORVT@t*`RV`Jp@ex6=u0%^b^$Y zNAx|~0s5ACxML~;y{kOYupg|_%5@|JKhv zgRyaZ8`|aV2L>PLK5En`GLEGbb7Ov{E9WnQ+nePanPch^*zPHYlgf(1FA(@D?M4UI zr3aq6Om&j%x52Z`C3@5Ha|u~(t_h@eIeou#5?%rYaekb6rGSPhDH0k=Rs)O3g-~BB-v?*qaVdbi0rj}u{0wmTqWw*uD#g7naX*G?spDp`YD_Bwg_jMy`&yc z1T0F`-#fv&O5f#veqa=XY>*xLHBXG~Rybqke*sl84O-KMmk%Q{Awg90*RR|Yp}{>j zHda7DAcMHzz~MY?w#k;8g9W@1a@4nB4#WLpiJD(|Zkp)@N?-ww>zG8s$mgO&_8JLl z9z|U%qAUNngS%|QW?XRGgB{a_voxox=b17P&*+qlc=nTpVIiX-=`LT%z5IAwH|*w& zh*hh81VQAi_E!qcx4=~+73)f!*%~jU8N}MK(C$RfU&EXtL}EMcv{e1K{*R%0JZ*E1 z_rvtr#}EKDNM-4yT}K<$!Zl>L2h36a5a$~WpPB#FXP#d}F1f_hrpi2d?P=~d-w@P_ zQbanA&bN7M_tngHv0YU`K_>_RksCLRf!_dS67Zf(-tN~l;!m*PQw?k|#xh!V6NF#Y zQ2_p~PJRBbd9ET!QY+&9itKA8=Rug32JH#BdshTl+V=WY!w73zcdkemq|i9nda2GK zXJ#jQKd#@Ym10LJqD3;2GW*0Ia$^ohwrr;{NuHa~W;`#zPvnKyBRw1t#!l(e*v=dz z(QOXLr>@KO=s(AN!tgRJ+$E@UNZ)Uy0F)LZVcuzSAE+9$ZxnK;qX5vi8FOMs1u<`;Ivr z>h346>AU3r`p^{)cr~^k%FJ0ShB6r(FPp1Ae4rC^c9o8q`ly`s>_i`OE$;2zKG0ouSouydH*W}l@CL0t-3ao zJwF`EF-GK}9!-JxH1_4Jpfe=)nLg@tY>HU_Qpj8sJ*t6A^WCqu@O*eNR zYwoV9_A2IWD=O=`p5WgNPl^jj4Gf1;LmZk9wf9;ui8NQ2{s>-NlsN4DHVj~m{TiyO zD>&F2Zbd7xha9iUnfgJrD$TJjL1H{N!K!ga=&tCXCc$Cc#+!ZaJg%n&K|L`8LkXBg z>#E+zF@U`Szt}W;^0-!$*FGwdQnv&r5RbKjykOQ~P**gxQJIBOK4_o9bF8m0`n|US z!*`V8{&!_Vy4isXA1{v0sdnJ9N5T(zYUs7%s!{||YEP4Z>aFn58_x*hoGMx@3-3{K zhc)yB94$o-oIKj4sNYes{BCjz?w`z(1-J5#5)m@kB>Tn17N_>H6%F4m%)W8~4jc2v z!uxJ&_R>Gpw=wk`aE#gTvd=u~(PudAsPf8sSohFGffDAG@QR%xt(*{(9DUvq9G>jK zbITcBz+!yB@m9?uP^<`dmEtXBD_vrL5KDFM!buIqD?B z>3!zCTQxSvEB}pM9g^31)5VL-$O;7wb+O?(ISL|qAm;I3^(*)#{xqcWx!5X8`&;c8 zOkyOQDF&e6o{*V@+yykrviTNT%R4!1c}>L^FTO%fCICEkEFlXeini5fC4rmVgaxwl z``0R&Bq-5lBc<$AITqkYovd8Pt?H^#cDRH!_AcOS)uCSW+I~VC517A4oIXxw+tb;% z>>q+SVO1d`Nd8tkD4|KCRJ~5ifYukbsgp* zzu*6_pZFZ6EHk}eG5cJBTwhtPdpVf06`+cSUEM(4YT+opVycmf>8P9)#X4xYL`W43 z(Q~GJ0hjaWEeOIbyv+8$9o6-IoWrKGg>tRANSWw#x=n^R>}y)y30O%RY> zBCBpHeZI)K?fcaxoC^p6pE>$7YX?lLj4o4e!<(b~&CnkQrb-~y0Q-aF9%{nz?I)32 zP=kj}kJHp;5IYjy6|~tXO6w30?iDTx;Td2R?GC^9wYj;17>%K^O4-vQKj-e|-{yt- zPFH)j!xgew07EBws@3)4mpxhmWDByw>&D_?;tqAs;u=46s(!d@6leD#!QDKSZ{&T$ z-s|XFfTH5jH=0NWK&vR%3CUXB`oB=;2)>QRaq#d)!HKn(UX;%yrBoF_^ zo`<~T_xxA?ZuhZmkLb8RN3Cb6m#blM7n#CRG-KF>UUe0i86i!(hk0%!1dq?a8-$G7 z@XV1$h8?4)OE2d$l!GeRPQX z%jDXbLgm%<52=T@;fnC3BODTH-dfj%W>m(vdN~(t`S@g>k=#Y)EwWB4?Q;_Re{liC zv=w5nlC+={J+f3}%47s+f&Dx7<;=-M;n4kC3-S@)iYp?E_ z_7>HpcJGTK4L(%tOx$PkaK6C=?dW>J?u74-W@A?gpR2du`Ovf=;n{bGmF)sePg8n4 zI@;Z5&r7o!Av7`krHzv zLWXTHFueBThsj1t54CR`=|nU$4GZ`9v-?QZny@S%XlQ^q;tYL&Bq-Z19#-j7^q-)4 ztXA-f(Wa}I(Gdw4AUM<|L1FZ+RoEa&oJro|OtqYMZ_3)HU1B+>{=VxYICh|u2 z_vW}>_mQe{iN~La``Tofny2s4^9y-o{M8!0q;3wL11;Mo9Iv`i{Ou*B?2~7U-hSP! z)?YFOt}+}M$S9S^kJQ1)uioF7%>gXd8K$dG5c%ydPi0Uls#cAP)fE_RX$HA)zH!@o za-xc|7YWYBN`La%<=EZRn&ONulCmqzP;Xd@65y`zeSdXxPV5zV)r0zK8Wnni(_G6s zmOxvw3h{#;dSis<7N-k7vi;sX+5YY8$d0$UfhMj?+F$J%du4h|>C9cx22&R1*-n&@ z^_bw`xm3)xsKiab+O)eOS)ynB@b=+>MS1#*yry_6N~YCV-HwmX`FtfwS~|MsT1U0X zYLjV2R_!}#8{Nk7-|pxX+Hlm!rddQXT4?!~)cjBYg@Gp3`8yvhE!FL?UnAR{nN#1C z8D-JAc zIiB+*Kd3}w`=hW`Gi*(c;(IRUv<>SRcagV6#{R2^Zo&KKfnI+~9O4O{S*;)1k866s zNq+O@&E%8J*Krs)lsn^N$YGt?x;Ps9`+M{@7TtwLK4xiD|JilTjRQ)^j>*<{VZQhx4{R6z-h0m#k_kPt$IG`roB&`o^Yc0oU2ph zJMom{c5m+~t!l?jQY_9|+{?0E`Ld@nKCrR6`a_08cX@ig)&1Vvtp#V?KWn6Or?l_0 z{n9it(5(ANuUkc(S+_UO=RK`eW6Z1N8kOwixHEfA(#tAoqY)CaKKanBB>8chuAH4} zS3~>i9c6MSv;8Xc%aYRffJ=u?>p)6gB90@gEKvmJeeqWL<^u4vlZbrZpClB zY`JE&PepLH?f#1AagnXJ__DJ*^bH$zr=K`%+xlGnUFYLl0+s3a&8~Q9f4_X^@3B|@ zv+R5c`_8GR%BD&V-*g?El=H$aPfsuvlALa}&fQL~E8VZ@>-o8N?MtnSk})T{`O@uW zL%fO;K$Q)jVsX&jh$mL^xzVA16NfEx12$BMbm@NmYZ&&jrOTW_6G3cKd=0({8!ST*6PC{N#iIg!jBffO!WkwSi7+U0IV zve-C{uL%MZdhphT|{dM4iOq1sDuDUV{`<`~&oigqA6Hh6h{-Q1eTD{azJ@%BU z|HfZHtiW#lkag?<`vHH_*igxw=#*sO^78g-g|cMzk@Mx&ZF-!Avf6gkC#Xw8)y8U( zYjv4h8HMMHB%+=d2T8Y=Kclu2s8w!)^V7Uu?eMH9EQ%-kcUl^4t5+jr*7dB(l5P3A zuQ6w)Nb5PooohkAwMa<#ZjKU&>TmJl30#R)_`{ zb`R(FdqMqP%Y$7=(Sn^dkM)Zp$B_3OHOY*Qjig|q6qpsyd~{M(8eZZSF7mA*QxNCg z3#ni+^$ryD(@2)2yryYAbp~nzu9O!PS>+Hra)$L@LGvdQ(3j*>&iOsdzH7yt)DlEc zqnB357s&5gwmh=)hNUCzTXr1{(}$h>=G^tDc35ZhnAmxpGCg^2P0huc72W=g8PC24 z?=LxLv0Xz)W6p=qygC<8cbyjR>iW9xd$(23#$wy9@L20fV7YYM3t}tcvQIzcc&}Dr zQ94x`sspAs>VR32CP+*Z8l@JTZiZO{QZ>kAeZMCyTIh?%Uw+=7VgvbBLRiL0+U}PdRCl?NWn1_cy%V`=)Nrv5GD^C&%{ZasevaI`ir)jaJ*Qa4m0p zwRWUJbLAo|5)koHC&Q+4)2P&f?59oD$&sxy*DWzv>@2)S0{3Qco z4PT3HtY5M0<(f~I4c-Q22~0MeYU)6dUByW8f;F-F)n0)sMt&EZtR34pQB1q5@x1LN z4gR#lR=1K*7~>)RTGv2IR^k|Iy$0}TTTAUl^fnvSCbzZLRR4d9xC>^z>HrPI4eM_4?5GaAQ(=z2_b@jUwV!YE(S511qXquisA}*7$QS%rrfWGq%d%~P< z)hD07_oGveIeZ&8f>iPOq0&92U5Ng4Zgwg@`quM2FnpYx*0-}7BffnSO6h!W=C@~G zQC3;_<~SMdS3*bY-$(ARzm)TcW~<~3t96s?7r*LhcjC8wB%Iv&d4gxkoMNv)vug>1 z?;JHCqd@4Eqw?Eohg%+QwtMxTDbH}4aXYA|Jhj)e_hi=>tNSLU>*A7LhR0lF zzt4X2km#&HPtZo3?Z?9NhJ!F8IkLpj(ed*^P)T9xIt5!^;5+HL@8CTXk1> zgv#i>mSZNXEZx6z?Yl)`mmY{F92(CzY~zzB38w=tY*M={d`VbKL}AYSvJ=l5U%nj8 zd$OV4Gojbwr66ZQaIk%@PKTx3p6@*uLQJ?~73@5sW^-@}pBggQf8=F3&J;oO~*5w33xq5jIlZ$uzD z*p-v(4l3#_MhgyyysTF`zUward>-}qinc?UA=KQl%?F?H<=>9hepfKzKbu68O9Bf` zkDY({vaobZT=z}ojQqcOd+S>ctM&>{JNEu<`wZoUy0^Z3SrBue#FZXpYLYsV64EU?f{Q1~a@-8=kvGKjw1NAKJz#aZP#r7Fjrr*;lUC@Jn*P8vn#{);9 zDICymj(VtIe_U2U+b}QWF#MyA%7I%FgDQ(aN3Zh348{B1_jKx%CH5~^nyZ)XRXA*QRe7}%x@7lbU)mDuUuUH+=>gYaWR2p+qz4l{3V`zM1 zerTncm4imoUn@LqOP<&|x8|Q$&UX`Xe%93b*38TBgJSjQa=GO-`)p3u!e?1k+RHdr z&_R!3_cXcNeB^W^tJ}5;(qpEWZ0PsWSg-HLr!QInGO~Tt&i8-$;{_Rz2p3^XGDf|! zK_MkO_?ozG=`sn4QFU>LWV}{eg}E=@Q`mxJEf``)^&qtc-z3yBPR8KHt1oHn7FfL7 z00yQp2zQE*B9hCxW4nB3V~WES`NSR}pQ=f12j3d5Zur+e=Cku24PR^S#P+sn^>hdE|8mhj$Dsf35aI_!}1daGZ9lVW>h>s}-_?ri} z)lZ^h-s>FgLa7{l+rup=;uU4f_0~E5 zWxoucw#(Jd4 z*k8}m{hrhrrFd|mR!U4p;?2C+`us!dI(C2V>2j@J99uI=Kdx89r{|l}{auM8OiVzm zjIplIzE@D9X}oh^*0N7JIPo;7|)&vmypHYUjF zCY^{LGuiGcR{N|nz34y(7n$Q9hiSy`J~&OH{)A0=_sC<$!39Mt91|5WP9FX}cNLVP z{6AlBu;^N?^r&Qb^MU~z(t!VcKS8*7hF9dh`vZQyc@mn)3GJRNYqJ1M`DoNUUulTx zJjw@*DdG)n5ByK;fS>_xHfX_FP~7K4&N4OlyO z!9z3Nc}frA36l@8t*WF%qQ=ZGQ803Qp7o*>o?xvz)?S=Arz=GEn#JLmZ&oQC&RIHZ zGOmYc8+zIo9Z0lneDJ`()jTRrGRwg5{J|N93M=IvD_(!vEAjq&L1o?98aXzppb2XxE`BvYv5K0VsC*0b)VN9%%x4Nf&WM`>O>Y>FR2UF@h zvPA1uGpA~pmDj38c%AOQyA3$$#?OHF@B1l6ColE?GZ&GeSx>r9T1ZeaXxS0CV-6J< zc#LzA1=V|+C1*xDoi64{P_TbI(ONgzHXcN{5~N-F)prUCKIaBk|5fk4Q1j)oH(NM? zds(fu%2EvTEokC9^3J$o?P92Z9*8HmJ-%%wZHDG3X5dNqh40C8z59RS~&0@=x|Ol z)QvU0ZBmku+dV%bY)7o=o?y^W80zzVLQ{|K^H&SpA@#TcJKBn~<$v#hLF(=Qf>1oo z!z%hK@&4Xcq_FjvAxDa?%#bOBmR{wPePHsx=oDD{_%nq1p`EWCK4&yeDfr+cFbwg) zL0VSg0)kNeN$JepWU;XDy!`m#i>*)kWVN>+3)b`x8x?0X*P*-cf$0`WPubyr+8{Qq z7&^SDF|kor!1$d*wZM^i#a@Q96>J9VBOKxpM(-929DVoVGpwl=M5K6x?*6yIKoL`S zYn1WAsxV!Pkf+X%ztpJVI5PoGVS2qq?}}9VrNW-rGW(*Wy*^OLrtCy8^TxLmiTtss z2vp_Yh4o$)PJCS7B)UxFpFQH^=f8m4$$3wWDL%rdo=C|J|<#9vwxZ^1? zp=Ieonjv1&WA4uxuw>c)cl<8WPZYu?01>49!X@QOaWW6@b4^$1e`s$S$!JXJEuD0v zC2^9tPVuuF;$}!ieah53b-YVUg%Dc?X2JK_H0QhX6p8fZj`rZHkVN-Vf|qsuWbUwR zj}_0e9)~SS)G@ta^}2Sb$M6)yIi{A>?<3*H%=uixE(sj%XN!)-#_cFjysp(5ezU~$ z;PU9PPSQI=6<4Un>OCC&hZn;kRz8RB{MG#-x7Q80b1MdFp$SJ&wJEY|y!5!J?im1->tV+y@p-le5(L(=>IvL|C&E5zX!Q^dy?Z0Q(%5W@yTp+{21paZy2)oy!zwotXrI{O? zx~s90PS5&yo&=Miq|u73wyo1`LNnNk*G1NC?g*=gx^06?yrHtrSY#_6+Ej+G*xlC3HW)GJv_Srzu zgEP>6^`lPToPic2kBg)6E3D_7Gbz)0&Sh8W+-4nYnynIh7zox0$H<(nB~fqq*?P=p z?l5a{$ptYC_Q#QT6$*<)w(HM-a{7_|#FSRpZ^H2*oUmXdc8h4y*){MK6__8V zXRwf%V6vXn@YE}A_y$fYRM@9E>t<`Ql5iHmOr6;Sy48WhA{G8}Po=s4dV>BOFv=>9 z0F5C3s%_ajsZX|`g&AW8e+VKLzf6ekS%ENgsPv-vi*PZ*$1M#do zR7duBUiho&`E#_2J4hz!GG_zS7%{cp3#C$fm7R&NJ^XSA?ek`2APg;_KdQpm>y$-X z0(u*fuAszf2llcEm__=4v6#LQ*lYnL%Bi4HPa-{fwx}&BHzbX{pUp+Ns|Rs#0Dso*(%Jo!-ba5EiZ`41hStI5ZeLKCj&5<+v(3FX_X%# zB{Yccm%|6>xAqJPwzxiwaiZ6dewtR(10^{bKjHZ(hSzr8K+1`WRu4&;cV**O3|H4P zT1_yhNxlUnthgCrWDeH&4EeF+=#=L*@XFbM%DKIWnG86~lUlb?mB#+U_A~+#T=4kFv|(`eH4%?frmS#m623??Whq^7u-2OA zTzzg(VR@ht-ZVAUht!8e8=zp$CYM%O6_=4+-U!<6CZM#LXau}W%f5Yw4r6i1<7+gG zlu>m9TD~CPwpe%o5nZ-{ojBt-p>YoM0z1ovMWwHyAZ=R$C~}jNJ5&^P125B_v~55Z z%_rOi2dIa6khNRt2K-#^T;p2Qx$&0{*Bq8@)LSR`&?zxUAJADS@NjC56Tg#$lm|?9 zllQaUKzQB*K+LrOxzs|JA-7|1=^dqXNw?2QyDk{(sX@T8gDLr7Xt}Zt56?}*{4H3? zvubp|$#EKyLG{rKr{D37YkVo6YT8@aP)KN^KqJ+)-S^_S)`=rW_HdDPTo?iEn|x3h z@8#FawgDQ7N{n--23bBOboc3m4!m~Yr{sZTz+N`84i)1j2h*ACbMyHRs3jW^7C@oZ zxnQ;Hq|GyNQfqM@4_!UOr#5s&-U)zEi`mD>a~Y;pKrON5-4GggDcGidGjE;E3j_ zlSOZ>;d~GOa5?m$qUsEa12Sza{3X;-;kbC3>`GupN` zH90O%4du?!!B;TjKtHz+T1|~aXKa3Szi?5Ga}epuXLIqe(+lh3eEP=A8px+0Yt$-g zsR+f$v%sXf6k*=k!pN`&DDNzkDBa1@%=P@%@YHue%jU6#Iz2hM%jiPM#v&JJn%rdfT^hHGu>P8C)W9p51#sdJG);&<@#4tfYA0HiS3Jzu_dXOhNG7SlW zA9JDsbExBcSVH4FP=9VkZc1Wwg)`WEZ9~3P>YnMGOUNRo7&7az_7%fzT@h6P&~>`Z zSgh}mp-UXjq!hqlj^LlOL)h3-7TSXRv)hu-pmTHiB4~sefCG_lE)?+U1Gtq{S=Y)s zrh0PhfRcs>bnZ;}R4+5>FbuSLfh90-3lwM4_3NX1J{Ep=in;pX;o(frdgm(xbhaVU zPY!D-12Y4&|3b=f%atU<)8rH-$F$;2H;=+{3tyVLR0#7>405Ohu_D_Le|{%k75I2k ziiG-kSpN@N5#?V6AzL$4_eQ4l?8l#!#Th;CRxDy~bEv{KvH|FAWoxnZDpZJgW=6fC zeUt;Et!-#}+<>_qdmokj_9BdS@7imzJotSK)6MN$u$Xf>$BNdECA4-!5q>Yck6Cc4 zP7PXX7`gW*{seYdFYMaPb%oayxP!t8DSS>~P>Od;8X1;uw6!-Hy1q=p|#ag+I?(PL48{dxD2zJezGU&=wjL^(<(b35 zJfsW)7(Llb-p_Ue2Sr%reR*Or%ScJf4T|!(Kon*h(GbbDL;wJtbdAJ@W3^a#JSAdX`An%L0X=a$=E@%{q zHw$=nXL1`c3hrnZ&<8RA80qU>Dt;x-A(XpoKA7d{!HSa2-%Ut4b}0X55ain3y1~V9 zw3587#Hnfw$&6y#K}i?EOzYoGc|yPr6ejcb5P&do6~4do)np+9?gVLbfP`5C?W)Hg zHXpoH)>Aipt+TU_sf6)|38|&UqRl7(fPO!RU&XF^oVI>>5SsfybEvX_+^{QJy1_o) z%(yzA**Ep8_7xEi^Y-s{9W@wn&>JMu9IJQ5H6N6r<6N#+d*MCY6kdV6gzY;C4E$f< zdbvTvBb}^U%_66>3}VfN+J>@Ct_o=7UzT)vUVP+l+$L|bO0t2^Ms>5KhaAg^Q3}~m z@~Q4DYd8RoM&}{VlL>rM+oH!lf#I)$eZLe9LT8;!@Mz@BlkC9tK#}?l^w=0YXEN)d zn$4On0xag!!-Q2wy4~*Ae|tt9SB&8uwS6}S4_TycCuncF#|^?sf0C>kL-*gG`j=CR zeq94~UW5B-!hq%42V`z*CVuT)-~<`IQVFwxXL9Zq_zuMY6=a^=f|_<4sHx%7NgjZy ziQ@W##`PB^n=|i4{gj(Nv@Q2Ho*D@y-^fsf%ly3uvs03zD&FVhEKC|Mj;@n>K7KSW(ThKT8V zC&9k!kgf4AAXY#$W)l+4wn&dv&#ah6q6z&^f6^a=>EG#Q+wEb0;e>yoPS+0j50m+0 zzC3a;E&4VIp54=e(FbKzt>pj1;{7qBXUE~&qBhvhS)xENFBiCU{ZKz)06?xE zP^X;<30Xu*(f~*}L0!e5zS0M{+MH$l4v?LSfj8yRA0AA*aCHQDPsKo&>ILy68~7~f zj-1LsoX@GQk1bNG*ASxWwlvQ&S7;8RhdB!+Ex8~8QF|t_9H24-^%{kMg=DvR zLIER^sxe3$$Rhpth}Hd2yLip*FIep#-;_7ilvMCBP9(uO-eu5TIvfJ*MI9AcE`V zl42ZP38lWLUxB~X%FcSmCQ=Fr7VGpApI-i|;yZf?Ds;wC(O3*f#j4ma(BQy}?1@c7 zaOwj0L7NJoq0ag;s6YBJ`kDd9hO`WSI_UZ}7~YHWOqr0Q1TU!Y`2E>RKRvo4AJEI$ zf`S#lBj@bNdl56bBA%?}Nlj`*GwnVC4u6Bz1(UD9N1AsA{ucA4C#|F0cl>UAg-!y^ zw$Phz6DS}*XXXK2w}o1{^f10Fb<8w%vsEWG187i~RsNbPpi7^(?hIOn=6*hul8mqT zUZf`6Gx4+cFp=N#JWs|L2OY9rNP#qdvB#>d3mUM)&{Xvtl-K=vLx77X``@W@5$2Qv zZg2gL;m-iGU6kDQr-1vY{5UT;&Xsb3N@%FAE8Yr)ZE+i1ZR0tX7VqW$Ml61XOhdM( z7V}$6w3xu~5V!$-_|V}uIs&aIGp_Smc_xAAiS>tZN*UmfJe8xkBO=-!g)N2#qeWVe zcnK{crL^&~$A_F+ni)9~NJOE(8p+X5F%TJX(9{aX#dXx#GavG%8Jp+ilBR1Sg|> z*!n`iXuW?$f+8eS2|JVkay?+gm7=#m1IZZ*Uiu*>nvkYM2v3{fzz^o#peVTx&4aVq zW5*HtdC6?Fm;+qOVAbJtMqC})lG{1t&3B85ikdXPt*7h*YkhYMACG!Et?SndJ@HWI z;5Zr8+=YVI72p&MKwa11D2SsUKl?nSr*7Qd`L&e!_u^+Bf@*gJ8GbBOPkFv#<&CcG0(|fZ=*)=lYnQN`%m??xh6IP(D(l zfhn$sbqvu*^;h46Y?4B$)RjFocUI^heOMLBa!%2?rHx40jd=P2m$Xbr{y3UPUbbhi zd!Cwr6wm+P1le=Dabq3oWy51dQYsyu50P1>zSTk-P3?{!&Y0*|Yre z$j_glx>FtaGg7AAE()H%rV3mjsGc)ufSRnYajjQqAEnhm9qLWki@0;+OFv_>O@PRI z8v$Zk?~Aqj=F@`D;nY*)E;REh)Ndi_?U~oy2_IjH;zHsmrsLQ~SF~B87K#;CA2|t& z-&McBU^~uo&9yaNdtPGP{7s0)MhP6RjSw!W1-^t=;xrQ9XqnA=axgO!U${K3oHVj) z&9LAt0wFfHH%1~_lb;gU4Ve$vu4;3!a*Y&t4|VitUWB0BQMDZsR$?FM3M=vEHhLtM zZ3%L7{ywtj$zW|IIy)5MakxX%%Q*LW|CuoTx>*o^Nu|_4gqKodTo}nTugHGt73h6^ zvckLtfE>?dCYUu_rg!lr8lff4r{)Y*P|;2Jbf8T2TXdp9fw}FZVUAy`Nsi`duR4tb z$k|L`Q@d7^3Bvm?qG&K)lVgRj`ERLU*UaVl7vx5OM^y+HWq3(*^Zu_zj@4}ek9O4$ zX)o^vdgLOV4EsRbY;rPvBd)vB&7m{XyF6~L<5f`Fb}t&Ih@LnX8J^xFB^tW}Dc{Oq zHVG)n;a-rq5QqA)HU!jjDg?wJs9u7X$Mg$*3;qS&BeLeDmkO;SOZT`v+Ffc88UII*0X@6G$Lt&wHJHf`Ru>=Wc`Ca@uM{%Tg| z9}|>L+#1@Xf~Gkd9^dvB=pKRyTU)6(L`k;b2crG23uXVnMTw3v5_4&nc+AT-nfvx)=B>oMp~u3F9O}7VVDn0^8M}BIzL+;6zeHzC)9v;m8y|4* z03x9@H@sCDnCaW&^8W-&hWTUGB{_CKDz z8q#KJi^wD;rrQPFJ|S6d2i+y+ZL3r&bX_<;WbL!I-4M8l5{9Ck80TLn@; z$hGB80OrO;CgeJ!e@hUZJUwn6O{IP4>~m0qq+wSRF83aKjARjkkR~|H;tcfwCebGH zc7oGMJ*olMc;cas9}>(bg)4IRqbQg(YK(A?e8SW9NEGDG3dW`fSz}N?Xxlpc`)=J@ z79g-kaovRG7`99(STnxR%`M351tv4joUx2D6O6c~vB0&ddgtt*8-DdXsy&rxEYSHR-(MQ}1&w062iZM-3#pU$oo-bS2biIAtBAHW4zu}iA zUm?0I*5Rvg8+x;R6y-Q|$nIYM3goM>rxbSQzWl&X7xiF8j97az^jfnd734U>$QX?W z@E$I4!onG`zy|fbDuwX-Qw{bUN59oVwx#RUoFmgCGOwkig1QApvS-Ibx5w76Bwr}g zk;XIT(_&xr^7f&g-fD?He3fAp;-7Iu|3AKDZh8QdSc4l7y z6H4>-)spNOF=wbVSeKqqr4ck_5rtg19BX^mJff!d)qJY6EG^3IrvONgJ&bw!6WRmB zSn9G1gMk!Q8SVWJwk;3QvguBc+Y=*dsaX}+-M(ZPCpab9xrT*S*%?A@l{89JvCL zSP-DFb)v?gJ~BdFdfD?yY=k$*aK%zb2NalCL*Zc|G^-v$9)cL)B*iEvX}(f{RJHZ0 zop+Bt?GZm&Zu0E1?}uVenxI5;=0lqV~iv z`$nPezQO(1 z1=D6;@vS8rP<(oE+|ZQls>j^v_ro8k^;jGu27%xI(v0nI7Fs z>+mF#s%)6|LbSYRfa&h+@3H(@Z_w(HU)T)X=xi5Y;@*P(K8|v#utW5)Lnqvx#Ka>z z1nrYe;G((WR@ofykrSLe;Xdh*Ax{pJsb|g-$~qm{r>nuYLGIDVuJK;LiFq^u_Pfgv zKdDFVzuaUHUyA|hw)5gcY6)IschMH|d|9W{bg-f9;fManM(M$#4)6VUEXl}zQeXlg; ziW;elRAu)G8SpNYMu2d1vbpU|46B}zQbcsiMaZ5$q&{qgBoVD2WIxR*{erO`D9)#!_T>YIzNqmFpEyCtDD00MeW1MtvCw%W@Em26f&0R}e}@ zIZ+YWVx6U!uvi6wNH%cW8P3zP38^A3nWM15M7gX$wNjP85-U7oY{&H8VC-#Ery9sI zjC==e9;#f&dPN@{ z%l{jx(cNqsv!z<`DOCr{H^(+}Z^AY9Ib_)b%UkT3pS5!1Y43LOIJ5 zU++inXY~M7<+>2%Ve|X$(13h#wnBHGhOFLAP(aZIshP-^fL*`+(4usp*VJ61-o*V9 zHlt`#u79SlU@_~8Fw11L&KMlsTxd^F*_ONmu~6!?xfHtn!35;;=89S&KQk+D%?}ji zXiEtVxV*G*d8wS97=-?AURg3*Zy4pIR}qBA0CN50cib^vZHL+-p89{+X4Qf^JoN28l&4hkPb)J0IHqJw7q4O2!A^ku$Hv{updYe$%4zvtY zs8anQmLq$B`{SO&9rZE*I@tPzRq{si5ZF7Oa|aA|7uf+UdK+|@&p-rS0U^)bLf(G+ ziXNdKR4o~d14j+P9=3m}l?0#NIQUkANAkV`a=}?6jd3w+1GDwS24?_aa*?-I)YKR# z4>sVib%Ul;DGNN%X$ZEZw*x8FY1L*ZHH z4$AtCU!U_#FM0sHvv|Aum+eGbqOEQxFx4c#d!2UhX!6yjO|F5O=2=~Ihl)PH41?H$ zjSFw|a^-}XGb*808{xbi4B4t4MCwaQ=zVm@+@ZPRy^M%JTE0NoWds-CMs`^>F%fvF z(7u0VtHWXC&lPk!A@G%K8f5teJ3y%H9I z6k7nUz{`}@2Z&%MunJZH2TIYWv{dgUTcRf*&yVC;r{)BXYH&uXd0v0WsDW;!Bf8?+ z-M8v|DRdz~WvigKUFHAi>_uVmE)(Q*K4%4HZdR4)c?P*4A(>Y&&+?jJP1$6LMd=i{ zBH2IGr-zV!6Lb4ZEE)l@xZ9+j#L~(U6!*`?OB6JhB^(J_k9eFv`n|`r?xa*iWC?a{KN^miDR> zWA6fP`y4|QwquYj&Elaq{)E4uB!8g2Fve3;i?cuC2xP;|kThh>B~1~PxPL_sx%bYw z!E;cWn0?gY86IqKXPzv#8Ej5V`?K>}_jzpZD9LfMK-%zmV#_H?dgX7cLQ*wD zMb;59it-}2z|%_c4zKJfOJjM!lu`-!m%%HMr+aGh?xGi{o-m+rI}{cu5;d{}rnk$7 zHJ;ByUOLs=oWW~4tK@`;Nas>g)pfrUzSp01eN~cWSeuO2Ydr;GZnm8w!300h4Y*YN zLlu$twLPsf$N(KMj8@sWjYqb0`_VoeY5gr?6MZMet^ z^eARmEMoLdYC^m#+se8$BUig(on7``2wJSU9u9P;OhBlQuNCYKZGUoD|{O#^-AINhys!>gh zds5`nzIMJqRv`s#m5VHN%XLPiqPKmrF3oSzKB{ce?J5UU&J>tQ{8P4Wwyh%K*AKqt zp@to~BfI}fnD2msXs_dEf`U1@pkskvt#dOrD{8>>IFk7QRIL*VMCOL>+5$)w_gTsO zQ#b3nyNFD6j7E3T0TL3H_DhO#+H84+ex7uE$|I2PDTbK#L$l#Fz^c&CZk9xWa}wp{ zJK$tn4ZY>Eg`=bNP0A}9p)Ai7iT2M5IxhP7$mWyNGl451BjE+iQ)!1H_aJkoY@Lj5 zZ1AUFW!Ku8>ib;2Ify&G7iThr%<6$@LRrD2QUD|x+Lq?+=8_hAxcu2}7^Y%rx(e^v zWP-1p=`%C$FKady1kJdMz22{1 zR3O0|mBblJ1>xdHjqylwinkkh)gA~SO#ypNH4s|7O8Nsrv;u_lBc>!`Y{h#Sg9@N+ zn>w}Oa=oV;@^;Br^Mc@~kh$)SK%xdJ(k%H^s1F`IY$#F)B}J!O%_j^TzilQCXSf_q z9%d79B8P6F2Rxv5@tU$`hR-y+JyxkFv)p;PJeu3!QP<(clO>n?UOrcsd@YMI;;^RY zz%N`$lqWCAnlqUA#X?S6P5y$ZVmiA5lc}4*I$0L*Qxa%5cLuDM2O8F+hFi`*SoA1N zZxtqOQ3ErZ#tA>{B}XEC+he@@5oJ<`X5GmTk7wOQuB&=Ylime>?I8J`xu4*&^nr<< zFb|elY!VrKmcU3xe|!O)t1^GPa{ceY-xM1iGV92IL$L#G0`nlp)PGn-nAMV{oS+oH z4&~+e&97TN&VEH<)fa2*aQX@dyh{8xe1vly#?{YShh$%0Ea&~K8HX{mqUeJ>G}2vh zoC1RH-!3QiTOc^7pNL=ilD8fWZGJ?9mHY;F1vKKA+!wnk+5eS7vBLq`sy53#aUUbJ z&+VO#Q&_P^#4ZehdUjsy(kg8sp56U1`214dEk@isG!r{#r5ImB_gY{Jpkc{?{vfF0 znTJ{Xfmc-xn*KEh$o;&uKh){PCmUccPmmvL4)063#IR~d!VvRT^6t#Mk};%#Q^T%8 z>TXni7E=PYG?k=vDP%C2;D@420=#Z}1{<`v!iftYRg<`bcQk9rlttWb2qw%B zW}lp?XSh{(Jm}qxi9ck24}G(S2dTOT)}BHtL|cJwBDPR7@Rwk>0s#_eWv$|VcL4Ui zh1s#1G&Q1GlPG}ZKCcOXlxr}f zt(ZSrN${tvVRes9Ehc-?Q2x_HYv-D|!HNnGD#N>55R-{EA4z;A2(Mp<~4epZuZ;3QMyNC9uc}5mEhyCh0n2?UH@@%vtF{f z@lC6VkpQUT^;d2ERP7A%0F+yH69l0mDNdeGyVl{c0V)|$(k@P(2@xtz>Ibyf*wi;d z$;(Oeq#p=OI7HsE$4NVNlsmW&9Vok)I&QaTAGITwv**5-@TO4eSp7U622{izHQx)! zVT>+Sd@kb&3p~dXIk#=~xfFcDXzcs8Me*3@hU;oQROKOUaH=!EBL}lV!!93r+EnAd zem|z6UmAOYY+SvZV&R_n;Dr-X1FEG`QXhhKFLH%SHGIA4B30uGczeN_&-AC=leMnz zWt#ekT^jiYL8PPH%9aWwTnSeUa6D}gO{>Z+CKOt0pk+|ikB zArVP8tC_TeUH}^86ld*09`I8@as}!@5Kj(E-FgPS#-GsE2T0+3nL0TS;vKkooKZ~R zLt*rwkwJmmTvAQcFKq2Mf>H(}(sIGA#Su=&l?$9~1N>ypkWdA{@YnFKm9uB-i>`zB z0$vS6hPV03=RIapCt5NJZ3p{3_l{$2LH@Ae@|;`qkjTwOMrL=gkRDZPU8>6E=HDx> zWhOWL!jd~SNB1-utk33H-|+K7kZsQJc_WT{3v%5}mhPtzi9U(wb#N6cn8ypMbK^bt zc&-dVejwGF4W17Aw!nOVhko7@H+nEJriCELkCs`k$;H=0%HzYMD`^}kLqP-KrD=9$ zIi=@G`&mxE4N=hCha$&V)E$!&=rq$!~dXL-t2DoTpWo}3TUo}X3KhVPNBb&*F>-HTYE$6I{6I>gSCEIeua@8@+Hkw^OP;X{s@g1+<&A2$7gQT zU;6AKKe^w)I@|ZIMpfAzb`U!1Z>D+`mMN;0l11wT*vqX`jDKR{|fn`x=+TBYlqk~a^lGGgz% zXYs&`Mx;C6d1;Ta7$b=dX%w_bq93&5(@K4O)npDp*y3N?n-x1PMi`8a)m3T#dN=7; z4mlJhX^Ru&1+#g+14rc#a7T_S(Yn7YWAVLmc~Ba1-h+9GH~+->{}Bz?9z+U*c)_>cZF-{&7$Kh7VU5;WphORJ~0cCcnlx}0-7tCzeGty;lqU@1nQ5nood8m z@0xBUOt*&S)M4Ta&)JKNEmgHdO*HndKkJUbbkCcr{YE@pbP9|uODz!lPb4}VEv!1t zXhP>r;_3Pz5WI5orR&7=-nA4>Fx~p|8%xA&MjQ#U6g8Y3SR*!fV4REhpJ`xX1g0e)o;#vM7 z@BhhqlAsJ=DI{2k2bTSR;I_i4FGR@X-Srp05}y|09VG#pGen_OyB0mP8-8D>`tkc(1Fyx{N-ZGbHms?d(_VUF$wv>qtv9U7RtPS(=r#j&sCg6MYpeIs~S>@K{WWc)FaS$k-B@ju@h`cl{}km>b^* z>Jh}#ML&bFIfHpU|0(*wokXU)IML}sJY5u0`9ktQnVERre_b);Uqy}(S}gy1*^s02 ezj8Bo_I)K09;G%t&rJgVyQHM9m@RMY^M3&T{_^?& literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/reeds_shepp_path/L_RL_R.png b/docs/modules/path_planning/reeds_shepp_path/L_RL_R.png new file mode 100644 index 0000000000000000000000000000000000000000..db4aaf6af3dc475a847fb00d1ab1cd67c1818cef GIT binary patch literal 323010 zcmbTe2RPM#|36-$jE2mHqL7i52C_~AAtQT*s3bEZn@&4BvNs_+dyiB`B^lY92qE*} z7{BM+e0P8E>;7NY|8rgU=k|G@b6(@Q$K&~aB`+(nkMs!XjvYJpNnX3Euww^V?v5Qq zt;D8O)laLfx@}pX&YY3`^PI!-gjH zU*MgFiY6u;JxoVdg>!E^IywsNB_JdwXTUt#u@m)2#;G68&9pBL(1%+s4-O8hW!<~c zbU%}4?JHGrWxs#l%gV~SI+ZzfKPDl8O(jj+Df?@Y?7wTQt%})C_J%lj=VEcGpDwn!ltmbW7K`0?Z9 zk1Gd0x3s7w;$o!(DhjMeql=1)esi3=zP7_D%4@O@L?85B4Hd8)OvLQlw=Y4l!}oye z;r~K0;sLKm<_;@={G>>>sTpX1WomJ5kl~AcOc@py_F%e(ukx5p$C+AXHBaQ2u97`7 z!wm@$0;A1oUZ34)X%$E9nb%m+K$BWdD1N=JNtaeq=(sCDRT3Ow6OR4;mT7w3=2W^U0ugxVq($_8{*UotPEH9 zVt1`^-1`c_l`B^sEX_~;9vuzINSvCQYGfM+nGjGaR`|bCN=%-ofXVATdkG~ESP5dS z!^SRSMmk4v9hP$J?(-c(B77o?bzX6)H0HP#ggIqO1l5LPm7d2OlzyZ}N1uE+)<%8j z&Yi#OJ7D*cS%DO4YHE(`x})eZP&(F>qB%r`+lvobW7@yxz{C+gZ9mIwcpRlYQ`$XW zbn(Twu8@)8pJ~q4>>VpLX3l4waW*chWx^9S8oNM%0yVMY~M;a8pM^k{}<7_dzzs`MDr33#U6Qb0$-wb zv%KEtwmsNA$Ei)_f~n29Uvf4R0t3+JtcG&^K z@1X*eV`F1yE?l_4EIH-DuB@!w^6$0Rm8|N-&fYn?w!N|2BG2G`3~Tja?rm^&`B?QT zS5J6YaRxhVYM~sNo6F}(FDf!@IOdfsK$30Nk#~ljo!ugv+WH_OPuR!ghmIU^_4oG& z(Jz0yoUE39vMKeZCVBDw$J;s$ORb#*bAp68m$u$?{qjmZDyw~26iefdR2#leQc00o zcIR2=IQ9=2lW3uYxHw`6TDirEP#51~`*n7Pj`0s$M*`dao5<&pLqUU8Jf$hOJ!S{| zi1j3Pz(Cw$YV;WyZQP%W0x3@Y6&~rjA0D5quR|mRzCni_c!L`lvQ<}C?>!ewxxwmf z2Ja-WV_@hA-xKooD(bTg7I-G?a2n*Fp_$O$-o9^svj5D*i@`ZrK0ZEb`4)FZ0ya#< zKs;tD(|Mw+IH8XZC=OIzXnmRZU#L0|1%~aoX|NCKvp`Xh_JzzG3PcQ)b&ZWVG(d@x zl8nAkBqb#&#%HsX9$hC6W`$H}>F>t};~n{5_nkX`{&S*o(#Zw#5VWCMyD?C#tOFcZ zZAw}zYNsko*h#1x^9!z|>rVhuP*-115x{jb*dnf?q5|Z%hC|g-aD54H6YN=o?{7sK zAO3omknk!+Gglnwmm{4evbn`J0kMy1$W6I_kNsQ|!wvRjQj?oTq(tK30N$kp)sl#1 z49UQ{y1F(Rj=9lre(4rh-ta4L33u<=(_e<&_1e+stDpX4-{%DL!v9~lq9LH=(z-^} zQSZStkYm_ziY4!Rc}vO~`4|ES#l^+@e%Hm+H8|3zBXSWcwz?#2$H6xW=k{CAw#R<1{7bi}~0or!EHhOyEC!^&Hw!{BGSaRhq~ z9Cx1{s*N{IOH6d-)Xe$xn27A|#W4JaMhTH0qN8&ML#LK;TXN)z$?pHlsGS7Uj9}G8 zzpJ3OW{@L#+CFX7|3>CfSr%bv#s$u}L&uMMI^pL&PyPD(tUXR*kbR8`VE*;>^o~`ZNZfuxaS4f-p%bl_8}1zuU#)=@`_n=)O`tw zse;Pp=WUUIG3cy;LVWr}OFAPBhnoCt(l%y{E*D`1WAtsVQx{lv5(u3B(b^hhuQOSd z?zk|eR3*GX9`;{Jl?|lQ2?t%;WhBYQq^;0WTYkIj=KooQYIAvbb1SHbO+$P_aG7#I3EZt^B?k z-}w4k6MPD_7wY77ek;ox=B{U>3#4vP2^fzr%*(kmJSy>Tc&`;-n z1`_j_5jZ(HJsA8J)bjq;6H28ana;~=J4L=H@;UH58FHUj&CSh~i?gHgXF{Y=7G+bYsF1v9@=vxbN`(Tk$ZdXfT!yHRgP7?U z9UUDGjV#t2)6OH+3GX&-B7-IYEw}ddVo^zFIX)j8X9%C!+=n7#6CZ2TdK-IL$b#7) z%DH-Jotf*x;{)4sjXl>uxRGD>+HnpgV2vkz5h3GuW6M1I>H3bUKlfs%9sh;v@WRrhC9;k%m zmGJfKXtRWqlQ7$cU}BnxWJCE6#><9DX-XIx8jcX+ApJ8aRv|*Ix3yOsT;alOip(b4 zVEON4knJwfuzBymo}~FbKJFPK;T1>Cdiu0mrN~_R>!+VL(|Sw}QR-Y5b3*Nl>5O9O zCYH@bH`zm8l>@8i*pw}ziIxS=WX-(#ASTnpdU|^D+fCipKq7*Brly{tIVV->FRtsH zw-FMaB$$OAK7Kr0USkSdbWHG}?W&JaNE|vPS{Dqg9TIA&n!2GR+}jMOwveMg!iOM$h~n}7h?i!W9-mJp&kbolVAk1q~LP*}MPT1S=4ytcUrXqqC;0LDg62=F(M?0_C9~{LLUO|1*IH~ z|10Rk--1AaLhFLp4dmJ(u$Rdpw0nB9ao0|Q1uh;Q9&#w(cn%EARf|hXN{(dBL4{+` zA!+3QO2GCNG5m4V#V(ITMx*ERpbWShgx0BPS{JC{R4xH9l&mC_|L{4D$oUEwSpFA7>I*cG$3Z+a<5LINB z5Rq;Z0>cmh&n)e18pR)BPLM(U=M=>H4LO0Kjp2mtVcHs1a@ekQ24k=4+S>BZO>{>r z3Lj2VP4k3oj(?4nk&%Sv~3>zbsy!gT(3hs zQ*}YB5Nb6~F%Xp^si_Gk6hV-32`d|0^(%YoO)>?Z#@5x<@tgNxpvX0OLwX};7F7Kj z9I$5ozPXj%b8)e9>7%Thu9mBimyl=_ntYW$$-Sbd-IPPTr793uKoudp&>@BwbruT@ z7}Px%E|EZNg(!k=#1SrE-z$FaVEd=bHm{l{EaR#qf;`rxisJ20;M z=7Eqhc_^d2nHy+sc}A8nCCz?Xzp}Z6CieXKg(gpXlweoA2d#O2Nk#(2mRm@M-{d^< zdFsienX8ry$Dd3_=`PBmZV?4*44<vAYefAA(3A6g{us zD}?YB39O_8xHvCREN{kX(V3ZN+uGapp`;pnLsRppX0EA6eZ9iPHBn&TCR|({j!=lt z!imoJyq&$!Wg&g8!%9(mCi)tR-h-e6PU9Xa=yM%MEdAslTi6b45!LUJ5m)_6&zq^j zBqkorJviN9RnYdD8@i-ZT5Kex?1J4^IYH$yck$_GPJKBhj>n1R}x933?5C5Du(0_vd(@xDjU zUxK|breu2~E>d?!%wL^Zn$@YirrMn4+UeNsbi=9Bx}l&+4E6p0kKklW5_S@(Q}es5 zI5svl-Ob*;77#%Awf8tbxp2gy5__YFh>*}&oNAY~Du>Ikbi7kBx=71<9ISs|t5Mjd zsK8ZucEPj5k@-mVN|6}qQ;@SCX5177tN;bV#F@Fd3J_(5?x*_eCO)5>f7Qe6YHhse zv7wTsUq<02;}u8sYv`9gobMjmz4>c6wd)lyBK&je0jRrvlLz5?Zf*)nQ^rI9o~*8| z?MO{c&5fHkYu2m3unEHxBpioogAZvA3zDc^Fze#z3BRPTh`4Obr~FcUVI$j^WS-M0 z{SS+?>9b}lcTeROyx0&x#A=^};GWyZqv;fidS@xY?+1kx!p+TNF%-t4_A~dGqLQG# z+md6Vsidro-Eg&F>%Gg;^(&*3l16W2GVjF6gj^82dGqFTl{5R0^{8UX=BuuOMG3EU zJhdA)5kdW-3I3un?%+=n=-6}w$Wd>B-q6mijG$_^Sal>ar}%*+{x4rLwSa|j&@WT1F?uggn0mbv5(??{?zEo+Q zLIv-TRy=Jdb8xXn+0il%Bxxr34FwWcZKP_opN^mW$&)9P94g6b2aTFjIqeyd`W!+8 z>~)f?+}ujg>;~Cf=jFwBX=$~M7Hg>kmVolmJkDkHgXCDmvaz^eQptEh3ux8hu!h^H z+fpHoh~Dv(?`VB~1kZMp%UpVdsUvfDcmMR^$)5hc&u#&ngzauC={q*e-M80eP=kb+ zfpP2)!MG)%nFdgHAib=mM>nf<(xVP{VAXqpOG;WFA5cQ|Yu~=0h<0>2oa!y?a>+C) z4!!dmcoxT0bL9~xos4NGZh#O6X8W10L%Qg`#f>0mP=i6BSXkh*aObrWVHP{N_0kWP zo^-DxuCQ)uv^4yIxAlab97jp-bN5=K%V>710=vy|Dh4P5+(vxnu9tB@&N3HLNH`@_ zRaL=Xo!Mejp#ILCIDy?4gh8N5{xXol%!@1^ZA;%y;uEYRT(5AiIkysZ1!31m2i3PovBUvh;MT;rfo#T5A^7n;P5u z{rkQ4OqSgx_|C&=IytrvjPdmW(OCud6_$CgQ5K>PvH`X7$r{sJDqBH#pc2DEMOc5Om)xQT zB#XwK1?TS@84a&l~3H?sQH~1t-vP8Y3Ndzn?d#m!G4Dc<_+FXZ7W;}|s5Zh2lDW#3 zmX^0dQ20xCUbeT|`mzAK`P4x5@87=zvkI7cpmHo-xUkD&HZ`xVHw|`UGm#d&Mi*U%;RI} zjPyZ6k%5wt8Z*y3)uWpQjWw3=B5jPFR~6Tc?oI+3qqu=hEC6zM`8?p(v%=hqjF_G_ zBBbQr^Wh0}G%gO;AbEh@^q^5h%dssgsUPHbUa}1pc9^?il%|!>tCFJO=V#Bcmf}pa z{8;UIQdeLg=YC*c>`ki$?p2F(V_nCX$!M;2tCk)~Npo3#Y7`){x{$tTVir7YF3}iyZ^{wytQ9GLi`N!|GxjNiq_Pj%0cUu5c?~tC{W&Cw+NGtWNE1woH?BrV zs@>C)u3z`_r{9PrB(&*zpIskMs3X-;)`!@$^h>&-CHV2Iy|K#5b+)4^ub;Nl3w(F% z+4W%2X`*mRR2gDeO_7yJy`e@?l(jgF=nv1kVU%vOazI2?-X_-xa(Nco?%|;=5R?fG z6GD@xuA_saMdYlu&8A9ZaGB5iuDd3ZoCjV$xjA|VVh^ArJI7bdW?%aES(clUNh^dv z-1Z}iEX8rlz{0N5<@QFS8t{EeshWJbL?K})nnXiaUTXs>R>`=>i76f@;L|#*Qmn<^~)+Qk<+&F?zEDD@nMYUW5)zjBgu6dY>UJ z0hC23n7;K3U|th5(L2w02#aO3wlQHMbqP25FWoL@Xl;G2%iaiys>$LEJT`?2uIb$k zIyF0wr1#1%M4H?d7~13T|)CF8cN1lto<(CNYoQQULrKic0xTN;?tm&mCZ{Qx(vHq#&)CUKL^55@M&w7~Y6 zV@>p%ciDj@pqih{Ej>n$Z>j9-UK#7|`_r14V15V4ujR5lJDCws%wg?g9`}4RED<5e z%E_sKe#I$Hfd!j!;EQ6^sVA6IM2_!I_y!NIhs8nENM{_W8G*hjP^M{Qv#X?P1+|KO zTVvm0$~>z-YFV9j23kT^tYe{WtD`R9QD}`j0@JN!Q2Gq<9k9jVa@~4DxK0Ep5kS|Z zX!PcU>j9VfkA}^sp^BJWx;!@N6Hvs&c%CHJ;AtHbQ1msD@x>GuJJq{__$q#wgJy=% z$hCwmIm|qmXFI9Kj_BReJ42s_c4&@V3`yu*D~?+-{J{N8ivu3S#26Z+t^U-3BTBQg z4@MFwq7oyF?nB^f=Cmc>7EPfS#%jL0jH?vvn)GaRt#uqc+wYg=cxNQ($DZB0`vkie zWS1uCS09A(KRD_02tOo(%ZDDz*W@Hh(}?p?B;eH<5vT<}7>h2u1!)J`nyqczgEXe?>xMfiPl<3n99cv ze>z8vI z=HhYd2g|d~au+*2___iYrEyFH;h_T}?I$+iCEnZwCMG6zt*ruv`4F7BJ%9e((NHXG zYmdV;{FZ~)L7uh4vmy2OQEZ2X7;ll!nwjp=AmYl-y4oIQQ}J0+YZ^VX#S$ z_Z>~Owr@tY3^BT0h#rS^JlcLRK|3AMs-&0i0IOIjVnikE`tLeXSPkA9w zi_e+O7q^(eATN&;9VXwh2oGDxRVO^Cwfk<_C&q1mLudi2aW~RxZ7a@3r=*zFJ3MPQ zxH__ycyC0o3Iqz6U>$!^xc^OW_ z5!7$xvZ8L0Nu9^r5&kU~f)LxbhHx4Pen$0MGww7OeKOL)w}FVv#Eg%Qj=DjxEttO? zd>)|<>i3`7c|d)uU;J3Z233WY<#Ri+wT%}TeIXfj8EaPfFh{Yv|2th#(3&5{M3Kxd zIYo`Vb0+>T$tjf=W{P$YY8#VdW-fx``9tCSj`QY#OZp@sGWEKp$Zk6M#BqRc+0G^b zYDdIKk`m?ppulm4*viHxUWBQuql4}|U`&2w90!ZWGei)E>!3tTSDUqz(fw#ca9wkK zw6%7eG$`UcD$|0{t~UGq!j=_83S@UKmtlLr=RvdQ zLEooWEm?-XzUM6O>AZm+-Wq{esjvgZgMc1X7=wllKu83mGcq#d+ZvE&@}Q0`pk;7> zUX`RdpC4;eZqJE*JeDoG;5)4o@einpXAdyV^3i=Ml;CHu{Cy?oc(QA0kWT^AC7pP|Ua;B5$o z^txNH*S2UtOZ)eqKi8k})`klo<#y~PQ|z6su6S}l4LMVn|sc8 z-R{bA+NwQ!%W)CRIVUw$loR!)1uEL5%ebNvv7YIORmY-n>on<0j*ATuo};OSrV4NH z6Q!cyRc+pCOUs(3B_)MWhnwS*=b@5@@g&|T1+ge8s;JOFr7#^Da&!qw+wj)~c5?`< zpeP-jwY1U5n#w+J4W?XIn@F~F0y^Kj=&u#tH8e3{Z!Gx};B2TpnsI28BM9{d0Z!*s z@-_t(I+i7`VYt}j?4*!({n_wI_xVgwd?v{>^c_BvY5#qEO_rsr$j;Ic1U2+$aCOb5 z4^^kRwo<%+xbk{-a6W77m9_gi#ibs;!72Ge1bg<=y(FXMy54r(!rsBcb=?*ClDT`i zUj^3J;j+_WnG@SegsF|wmbq7n7}2LCRe=(TZmx>{wqGKZ>p8Ic_dx#>$Yc`JvxAR~zDi&zL!dS7fY*5;mOhAvhS51?A%n`SLgfnh; z4s(C1U&fg`h#!)<{0Orj!gE3?f^pFN8wv_Oq%=Pp8wW6VQ0HSp%*HiYbNZu4Lw=|L zR{2jy{#l;`8f%sLzq_zq+>R&Ox@Y3p1V#WRsq|i0O6om2hKlR~2TSJccK+Iyv5ovo zc--;thk1yjsJoZPZTcaMejU2f^y3G)oNYN}Uo5wiAvCh&zNs}p_!V>RAYghJyb0Zr zCM{I>WR`iiGof$KFlJ_EbOIK)>l1trsGXwEx-MdF2*xzBg-CX_cJ;8qN*{MU@0*`Z z;{7JMpEGES-?b#n$ZehF5#}J$iK@G6gpU1=Hd$kAulB?aV<7hm)cibx zl$ODM_xAQeb%*Qy_pB{z;9ZLV!qZ(=SFUxXX$t^cSa0Zi*bQy%@LJA9Bmr-rK&np_ ztp}V~$FlFZ(TJ^cu*6(rI)AIFfpGE}Ak(zp2_|u)?#BxmdiX(cU+|g-2tPF`_3)fh5Uh~hs!%0 zL5URu&$CD7g_TcsV6|vA5sUzndCChoT4-+`yP7hloZa3f`Tk27LaD8+fMeC@BXn}FXZq#H9_2H2AE2^9 zI_?Xnc;=TUBt~!Ad^VSmXsZtpnhr|Pb%2u1LQ^=p-Hrg$%EzX~O-^ib7mhM@15QA1 zBU3|2saLumLM`%m|JD_zG$Ij@j=jBt@S8VpK8^fLib+pDljfix zw3FcT=^xY0F2`89R_54t9?@R-a&Kv@n@js`=!nq5oVQPC;jv5hmEg4Gerw8N^W3=4SO&>zMd zo(=HGWb~I`Y~6zBgtw!4CP0gQa2bdVo|4i1Q~vB;XC}*cNG}Yf)1Xs!uVA+6UH;0V zqmdjGPPgrDRWR6lGz_Ab)s*^ssL0x z*=cKnO6+-r;n}c2zUvNb{#r?^*a24omH(&D01r$7P@eS0T~#0mPVO|JMy%5+G*N3I;TV$N% z;pacZ$;tTufc4ON^#atOLF|4vs3&v~>{^|quY1^h^GxVqX$@rI!*xmKo20s%|Zc3VLcv2?6{m0`$d>!iZ3eeRZerQ=w3_-;_5}w5w4Sm z^miCHF-rd^^=;`jwA5HTEh8f%rPMW9BRN?UzU`w@MPmxgxY^fjuQ-%QPUNJpK%jiR zXTW83qHZ?bD>fxDIh8Bew2;#u!nQ%RUthKwtB4VH27MmFtt6mGf)#*3BSK%d0g^5i z27z>8f&Aq!uL_F_vH@~vq`IhTa z(3D%xmHzjP*Q<)o!kEEI7su2uJltqubVag+d%4=^xbC_HR3&JRHf>Kc{QYDS-LNJG|wGRV_`WBHt33z5NA0ImBRo}GPac@)xG8l>A9rX&F4Il)N~XgnP6I1Fsg3~wjg zR)ncb40ha(5R)L2T7bD3yi$Fi2?OH~vMasx;>|iMciKk225@;)w41ucmi{HPYm3T2 zAHrJ{HeAS5W#6toVHn8ZnK~wyX(vGd5uhs(nCbTjQTh!{?5jWQ_0p&BzIyKVF%XG& zAz%cg%)_Cu2fgjxvW36PD@86K^`>AJkq0ZJnaC{Amh`%+0pnlt>5OhaBG$Tz$y*)~ zPX$XdP6UA@GHYj9>P-zlGLL<9AjtOA*3U_mddgSvE=X?wsj4;8P%yc0vI0`M==5|9 zb=F$Pb7NuXz=Mt#3*UgW$BvDXEUb z_4f*v=iWJVOD#)(TniSm~5=tRc&BU`*hYlTj39~u#y?6-V9*W($^J}jGBD&8w%zL5ol*3naLcE}`Ax9k-I`kI2 z>}eG$-e((N&~=)5Ps8Q{rDCKg9bgE7XRVF77qI2D8+gq#P^F@UH1YJ(bL;KQm*ENl zz`|X@J|GrYs6SfFEjmA6;L7Phz(HO<_ z8M%D1lPmi2so@O~;2D!SOr8L; zZ|SK&gmwJ|qp6nm4kt`llI-7l4!UyS+&fk^u4(#*Ub{*_FZYfcjQBVf*&wI!L_6%f)YefoSPv z%~umez)mVcGcd>QZ_nHUx^{EYk%SC}CO)U$ER2qh)*E+wPXJEn zgn3`sgnPK03m}+(eGQOk7|WHgxc?s$gZ~?OOsd8}l9LNPQWzUm_z(iaRRrTIM%xya zm)pB2-uZXb3q30c(gop0Rt#UX5v(#-==A1^w)d!=8rzA5|fq?cD*XQ6(t z*Rq=I&(uTPdJhW*vcjNH!nPDcq)P=dd;9=|ZdVvc`j}Xx(O6ThLJT0gAV4>+KgtKM zF8CV2T{l#wo| zlf;3@;vS*Y3G@ovL5p<0pob&JdTxPySpWF+A^KA_%bZFlAY|ir=yrNA;er8BUQJVH9L^qOFl4TQ-^hy(mAx7+1w2MpBNM6I#h zw1T|;hN9xxQX+Ma9a#4@B(I50C-tuGWz)8NT0nx-S+$#_|9#-~b$;;_YHc7lVS-WG`|i5_^<0}K$HiRu|Bo?lnplPk?kV}-n+*<$Y;~9vfjHJx%#DWH9>2JWzkuS6 zGJ>mu8AaK5x1bM~{-D1ix#{i$0>U^Jo{qYM>#SdOZaaEE{O{9y9mRr(({BiARNmST z`Qv{(+$HLb0V&zGGJxF16ck)^2~pezA7X{b5o|Y9InC>(03YDgbMC;L{HxELKUU>d zsm9Fg72UNbqb4O1IhLR4ysQ9h7fjo_9hJtR&%nw9DHcJy{1{sL)Zy7T`(O{~)gf(K zT`K5z_*afAt78*|cTDszRZ>FvwAJHByZbJU+}QSY9st_3PJUV5QJ0 zDQRi9XO|HACw7)CvyP+KLHw1A~QO7~(DyD00&I14!KEpz!W_9PQKQ-Aik?ptv z#$6!Mv3QJUlmM8)$Wgzk=H;mX1KpH| z2t^m+LYGzw>Rel;XQ(3n=`IyTD%n|Dii(sF`E#ElE#9t=R2{|w#zqV#G7*|vY-RbJhA{gcynxHl%zqK8tM#E1JG64wr&GZW_8du_C2{xWb!Hm zDwZ>lBF#{`HfA67;$O`z@iwb;p{5R>>k{Js7W(E$e6Ke3 z$3V_aCeKOZIv3g^{O=)}DT&SG8|JnSS0{`iz1IeJ^b2!9aLedO_hx5{wL=ZFr^LxO zRUzlz4Fr1q&ZYIM-UolqhSaNhPHjqDXxopGMY8^xIo9pyaR=5Io*6joNtR>45pii3 z9df{phh_b!3E`8tdGqEtUlh6u43~x$fRhehgNY@_Yv10tD$KY*%GBooW$ynzPQ&gH;# z4yyNj+ar1?exgJ$`@W=|9f#dqW(@T0Spj{2jT!n|x6YBEEG%IL7py|jIng->zO<=osrrQKuf62w^YWNOfQwL z7=_~TrCwNYErl z!sX=NYM`$3zXllJQu14mC;>iAul#GZq*wDzo11U^{61{EK@7tSq$Z&_FbXAa?Br<^DYR{jK63(i;2BbQe2SZatUKXA5+vC)eBR?^;s}8HxN|iOb0xAclDy;w zH+wCtG5l%u9&nhy7ycM1MolyEcP$vW&`8<}AJ!C|4r)vo_M(%-hzN8Fle}Yzx&7hs zJBOxB1(xgpPVG?AA1qNg1PupG{kN&=@9iv&OIBA{QxX?HC{?>iL!ZdQ8en}^C9BH; z0oP>h)1VK_9q~iNaq9Mn)x0z(r>I(5*0~EstIId0`$a`=c|mu2F#RWbT2c&DPSKFM6-c)rEj%FUR7GrcDbQ2gm2z!1YwWjf}INP2~pz;nUQ~ za^e;ij{RoKO;7VH;3Xf+9%e-ykT{E6xZpIvNSO+d$*!}#=vb0?pa4`ob;5fQ_EI>10mUt_t0E?qjLH zI1BKV2ar}?FAfhqRJwdxM{;@P;~8jxd>$^G@O&K}-dH_VZ6Evdr|>==)rzX(>ZK9QH1Nd=FA*(f3&G(>XqEmz0~ydLn4-^tS>rBs;iH<(3e`V&54c~ zB35uDq8SQ5=>tKvp_32CV4k$Zkz#2OKkha%n(EM~1-Vt6^>!&AE@&YIc|d&56?DgK z0O>fTj=i)ezOB;(1GPw*jdpdKd&t+-r{}A6^G#Yv<6F7q(OsYGnhbV2rO<^3d3^~r zVewX%=N9q8STd4<_hrMYv!#9CB3A7Z%iCCl*)A+itP0=BE(WwwR_QO!fV6zx4(C7q znte;9OVT5=i#p3c?-lfWHb(d=HhXnhDefKbrgw{2nNgc|D79I5Iv2y&O-EZYn?m0) zJz9EPCbwHeKm7?bw$F651{H`7GY=2HzLMuuk@e4z3DnHN_cT6aMb*HuT8L}TK6c{( zwgUlYAtiSx;drdSKuKntDxPB7JQ2om^6>IffC<};y-c}<{=RS2%Dt?RY(E_mZ~Op^ z=l)LH{$EC^dvoa>n=pixG-kJ;4@iFX zKN{x=gg&}3)EuwCA_R7{936#0G$6oezSN|th@HHBu4u}yZoa)#_>PHWmE#1X?3Gg9 zj*^LZXLjm~aupD@`l>Ct8@yfV!1<+J#kY6)+o$OL`l9rxI5A&fwhhrJWJY78_Pm^< zp7D}fsjbq!UEO%?tkPi_2+EyhOksfi(=R;~C5Z?8K*F?50`$HiiKi4j*#Gfk!YB}X!l|56&(WA;wrvqt%uNH( z<^)lk^U8GHB)*hh|H+dZT|dZ2yQjn7Ie*hvNVD#8FdI?jO|%(zuK^hTuOnQ?gpWu# z&#H3o8I%U#R~U~DSoP!79ssgXroN$Iv9Rc`T67W|r_6FDyh$y$9xeLtmIyd`QRl^H z=sqUm45y=v|L+^(u-D1xR#UoNkzusPtbG8c^2qJr{Y4@9PM9Qj)%-esU~bRxmvgx# z=cyIaw6fVRblT{=;nwsI9-MLLK578g9u(upV#NW+o~fmj+)f%N0GB1W$d>;J5n1YO ztezOIz(y>$BHf?a445H^pqWOcIv55Uq;zM%t+a{CLq#Uq zahQXl-c@{~^;ez6dNsS|n~Gg$9T%kq);xL>Xwm9^euY-KFYdRcJ^Ddm|Y(jwCE1l^* zF67pLEC*Q9r+KGl9r}Jo#snisTMCxBP~qt#Oc!$Eu_iXu`-HFyNDtz`9ixA8E2xXD z&1EAm?EzejMea4fgMn9j8Y7k@LzjO`D5h~NrmaR43u4m>6Q@O13R`hbg_0q$!{Kp; z&#-&clXtmSz3hMT_mTWzBEK7rIaaSoV~KJP?>NW0$L!ciNRIkf*;52orJ$(D2yc1R%WQr7{=NL=D_3OlD5P={ zAB6{|vcwyaNlL!X<}Uf|6J3y}cF|=Ozjlu!x@G{w^_X}u^y`(gONNKXD?%cfqb|w0 zs-9-8yml8IzVnr`rPJyd&kS>O`c0*1vfycpX8l_(Uk+_jEp#c(5}o`sfFsG(oK>$W zIEX$HDZ%mQ?UiDm?h+kndWpUS@pVduj_;HNJB`Qy+WU2WKCfl$;bo2{XZH8@+qWV^ z5JFN;PQ{RH98TMFO5^_h#M=f2n%5r32H(_um!tA!Wg&tk;5F`d429EoflMx=$mHv? zIxfX8pEs^{-F@CZ`*hA%Ra>By1=rr~A4tY!{-ts1BfZqeW!%y3X7lCXq41Es?+^U^ zDH-H>{!BBa+%;R%@nrqkl7+a?{8^RPY%cVcC6oJJ6%Y6rE{~SXFdO23rn#rZI?u%T zl$eCH=6Wxpue)QXG^y<&)7-cF+{FK3&Qo(iIRe7u(~VXUev(P zCc?_AV5MbpIJcXNjj!`uifHc~#J`6ujtfm?n9eo*I zqH$~ojKQ9G_3BmAvsbfPg`S=3a}$%(plzQi{LCl1`0kwZbck=_ z1I?Uk9kBsY^2W(~o13JDrfa2jBwrC$eyVbfSi0Kgykcp%+*<3ta-zDrqWaH=x;l!& zJ8mtHpFA@!B#DT8;iE3yUX0t20B-oNl~vREmhz9xM%^Nkc~epX z4?hrPf~afk^ENs<_S<`;Pj7hPtBzI(A(3SL`R12Swa3$+J>{SIc_t~x#CN<|+w!7k z`2L9H*)-|fm#{PR!tB2^b7h|ovT$jv#)}^QU|&8K=j5uu|Ig8RWRRm1|91{6mbE5~ zB_t&H2!Dmw>Lz?b-G-dlc&9-c8N9NSiJP1IJ#Fm>fvj%NjG^K3uv{#zZ0BJ^(+lN; zQ4b406-|eU?+`X#u+XoOs1@zz|9rE3#320j`(zHr>s>BWZ?C4_6s(CI^59!}Sg`ov zNkt&YFa_Pw(@{Y|6w3!z8D6bUaZ`*BPJEef3A7TLd}<{$?Y=kkBD21eQ$@m`TVMSp zm#9?_Veyf_e^=WT>ez`LDP1->oS00ddHd~EY8t7zWtq=e`Cx3{(TRv2`M9^q_?rL)l;Pr zw}-wS2_!?G$6vPRThQ5hfMUpFE?<5;Ksj@>z~k1S*umeY*YglSwd7?*lLqleXNib&r$bRzA55PXF}djw%tsNhgQOdTwtP<*6QV~stM~p; zCW=G=Sp~nXN1G&-l-^`x)KZ2CkI>s++btXF9Tj{;a`_VrQ}374VX09MSDg)A`bhfm zldCgw8B1LbGP&BMh>7)AdF0#S-xSfhp+5}rgv7afzQ|_mM@y<2)z0!UxAHHM|3ORQ zK=B@cphNeuPu@&RD>PXn`^&k}NO>dD#x6^*tkuQlioPoi^-Q?Z73p$I%VRtj!<{wm zj~9%Z#b>!)>x%J`nh_XMqx4Wl3&swDou_p@`T7r<9%x}sH-sb1G-r}sTuJ#EDIZAGH`yiTX>#AR- zKt^t=GjdGV87*IbjbKCPVqvNmk5ma^e)4TmkroIQ6C0bP@r80#ZR{O#)YnrSoPP48l3TyQI z=lE(;V47lcLO!2FnWi!=(8yY4_Z8wmxefW&qe{I+wJ$$DE>6na{QUyWmCxwAy?;jl z<$?OPwh^8eC7$qpk%j2*H9f?(>_2og*w5Q^oOohT>&nTm7F{bS=aW__tH+gxG4AaR z-+x6Eb+0vc`d@{y2A}t5+0a%ZPz+9~{?PT}!N3T_F2TzhTYB~O<-^OuA2>g;phka} zFd4B75A5;ZXsD=ehjtyOprCkfWN>Sc{GQ8{WI|`IS(Bd0i4zp}bEWHNo294DH<;}z(ke#>QGN5^bf zF^T~rJ1TL6poHqs=$PL~t&4Vnj?>TKEX1uK}vk-bGL?*v!BJ-`odH?8Q zGU#F_Y2mjcDXfw4+4KSySK-~zbpB~9oX?*dVvfxSS-yyc+thi#^&Se z+uzG-bw&3U!C2{nM`M>$?$=8`U?uBwO?)G(s-DSI{QS>D%wGcm^ok7HjlSDA#FPF% z%Dy|E>OTBCQjsLdXdq=&R;BD!QOOFGJxcZp*}Ekn-DG7ZBiZxdSd~%sifm=iV;qj{ zxxO0C>Gyj5p6B_`?an#haec1wzTVgSiden+jWnMc28;v7$4$H}ex3e_Y3mZgQtS($ zGI7btGLIfTlGKrjOH7mjeZcdiOOi1^OmzZ-nbyAyX)bD^SsW+sM7Mrs`S$`GWZ(i& zEQj~tUjVTZKq?Xz96p!J1ae(L&-GGlOpL^d6DJN3zQ^vppc!`L$6{;iEiy7PtFGw% zqz+efa}uwah~Wgs+@>xjetycO!@U?O%xYIdYbpDc{@<@(x&>daP!P5c|Lben;Qq~o zuNIT$(;1nY2US`1cU#{s7aXv-m=ae=P^f;FmicY}DT9?}A3P{(}dNch_MWBJlnDQ#FMd5B~8c zn>0qwYgS3CKk2k+L)YF?O0VRZA1r71x@LbeiQrZaNR*|*=|V|9BuGOzz*(c_rn46% z4gpm7x+PITn3Ic-?+(%gelBAmhkt2ct88@dVaDTiTl8A_(3wfJz08~+{~MS1*Myb; zsUOVUL=hY*4-axUQzD`VNI5-${yH{2ZKv7_0-!A1+}s(oH75T=NLjA4o!?l$MQ;{i zi#7^dY@g^G`nZnBd%L!yWsC2;xVG&Dew|{ZY-rd;@NoWAS0pbb+}%rouT*>Y5)~Dd z(#@L(1jzMS|GBdSx=~?=n^4awKQl3nOk-XAM9w;}*u^R$-iMvgC;I1Klgc95TLE4~ zfpeS>s6&0rPR}wbXg$7eYrEsMYiMxr`i&bm`Z-?*;TwyG4#JB#Z2$6wzdz2$>C`6? zV)ISRrgTq8>10m76_xaIqZfOP{un?~t-P;vV zTN_7u{49hLVTC;;#8-g8CkYZHoC5vANQ9*>^lPiCo`Mdhj1E0b=;fG=Ug!9QL~&cSWT=y*OMdKDPVqYNKXR1+HKW<7 z8k3eL4}?mFJE8ym#|%RVL`BxY1ei_9K^Qi94KZg7RFC-d4Ga0PyHk&+@cMa+Qms!aDKogCn@oS+#viL7KX|;m}#4Q#3?g}bp7xQZAtbIEHGSCQxgc<1kv9jH_Wsx<-gF- zPzfEe34%Z8E2duZGRPFz3s}be#OkwDQXPj#Luf zm2cTPr!0iEPiy%{@I5NACOC8t%d<7)4xaV(@`A1_IiH1KWc_|mp)FCV8!Z6>RzlbK z0R61noG-k*stV+lUd;aYtn5kIb&c>=m^5#muRJQR_{qkaMX#OPyLjndKmJQZ+(O1{ z@OU!j{66?;yl25)092Fd*QsWBh$vno1)#k>F6R@#nyi9?9i=bgkKi4Q1Ei!xu7T#@ zKxW^Zgv9fBTltA1_D1J^kJiZ^j?WYn@_W8XI9E=gWE`}kaBK!F_3&g!L$ zq@1_FJCqAtf*CWrw^yu0@l6EzC`R&D*M;QfMIRjj4AUVNKyF!?3Q-yh@G2JmwF;*H&eaeC_wak8InZa#q|&7$thJ}tRkBf~c;kptZ%6+D0U zB&*Xu|Q9g{-NCW3hQcB9Z#{#!_$QM;k{8>&;$)<{-87#Tw22}2> zdN>R3;+apZX~ARv`t}(G_|A<2o?B1x->@5E*$RA*&L5b$sr&HZEzmA!<>s#c%rQ#f z*GW0kkaC5}$PyB$A3yHuWo2ZXJ5x1Kk~ZtM&!vF zzRnt(%MyML#61uOLWLWn-qYaUybCv6$H<`U^Rh=IFvT1H;lm9`5Lvjm#Z}= z?+W5f7Ng?Z8+J3#KUS2iND2^7L-}CtI0o^(<^His}xPm~%z&NDS zjPLZBGY4Ijx$9hrKl}M@S;uOdhP)4DLk%?m;RomI?cZ2>-Xf?M;Zw>El0m_L!Xbgc zRBgbu@mGl{vJ#)UsinmQT#x$xSavVHx_&6pWqfs;Ep_bIZ_s{m0k+{!(2&I3@;N=f(*hL^OmO z+-d$m=8WT>v$IylmX;xq8jg*RpRa_>FaXw-?DDH2z#2R}_(?!R>*BJy{^gf(7aTPo_x(57(BP(bRo>=^OPr7iiQ!4GrkAF`rsU}>CCmNMPPy-YpH6{7; zeV%0pNk@~O!@%W1pyOP>Pqr3z5Z{K5?ZVdO16OH(-*q{;pvg(IFKep0`6b#&b_@-N zF5{pd9Cx0(g2O22Cl=Qxi)a4lN%U_*g1YYR|DK?v4ZaBp!NH%r7x7OG^7e>WV(i0( zT$VCGBUe`A_RX8G4$;tfyTvU>OW;h?rKhy)ze3D!`FRgzMzso|mflinrj#P?#6Nzw z1?-T&Cs^?;{^u`21&QX#4I@Bx!2mtWXklyAf0dP2y`*4n;)b=gwJuNZlVsE7AC&Pw zHdeLnL|M1U1!TISNiF5i{@5?f<7j3k3lbN8{O?AqyuCIASy&_iv)4>RB_>|OV$j-& zdSh48wThi`%PT7ji}F%ZWP!Wt$6xf_EYFzIP=|c~e!lT$e`^0E_oyXJ@n(WUK;#Z- z;WS2A(iPu;GveSehP;mc`afRpDNj#NB0(qY`_FGKOn!K)@@A71sq%9+hxz5nvz|VC zfn@51i|U)F-`t4UyN`n6@Q*q0y#oW~dc)D|#8YXf^zPle53xxzw10LFE{^=JRF z2qGRYo(<5wtEi~>3bmQ${?tu*7*CQmGI|fV)YA2{Zs+WtoWsAGEt?nNA-ownxNJwf z1Uyt(S5wk#m@^WIPo6vIU{lKz$SZ|XtU>YN>hsrmImB0TbCqmHBAe}JVp=YLnxC&I zF%2o#eDJZEwq{a(7pT6*gZ|#!psl4645NRAg_WB7J32Z}Cn`kSjlTP6O%aMV@i}av zfF#l!ck&}jb8~OQFfGH%=o{N9!pN_i32u`o@9Y46;oy;k_)@1;kSzbls7k3}^+zyp z*}Mv2CYWt(Y|Kq1J!tPZ^t1tKQ@GmM70E4ZQA3M>y`O@4PzUP*Qf$r4Y6UL2{CsG; z{@x!T2^7&R2#i5BUlZHPKt;t25H5FBTcJXv&`_fxkelHYV&*z4_MsBv;;zffzpPn? zHFfa`36*aZ?%sX-fi}(iA zuMciOd$+#8KQ~3f$qjm5XOKEbEX}@SDVp~1;nT2-6O~`z%vCzHNBq^ZJ&X_3B&y~3 zr7K@DoZy>&`O_z|`S|LO&t41(u&OA)*LPnCE36KYc6D8keVt^l+9=GGZ_?A#qXZ&8 zjjZD0Isi&)YEMi~@9$OhE%ChCcYWZ4afa5;Y2Gfuk%)o3Cn#_v`b-ok1q$@U$ch1x z>w}TKs3LrHqU=1_5m)v%&O`VwW%wk3)M6%@k3B3&AmxaE_wEWdxU-wKi+{NG5q^Hs zO9irKIiQy>v@ap?lIfSgVGYmD_0{-wZ}tdz6LJa~XRAyWEgL^ea`IOlSPBN%IT`2= z$7*066tqwr5nP;8U&jXOr(gBkU8WQ=l5hs$XKv^56=(o3tlT#+xFIX+TVuLVzaOBt z%A>jlV%Q6--sxi_Hs(=9=VG$5lwfm4A_c?2gFo#`BZ?1yY&r56kg>i&UaN8RhQ|Bo ziFT|rfoW#Egm^VEd66LJ^K^tj8olR8$npM@o=GVBb{#vDFOe~5{~1E4j+Ujdt&PpF zKEjIrio(0LnbURr#8*TzV``RN)>5h`pi4~uYq`JVsa?V{91g()Wo?RCnd`LGo zh$=cpOUw53=~Fi~n;4pJ3)LJ-Xv=8ddh16U<>~{y>lVKbCl`6n5RZfCij$@SUGz%h z%~efxH@A|m3~Sh?0+MnHN818pa(7RF5{+-hill?<_z1O5xJ>b#ap4OWSXL6A{P!Q# zz`HtwK;;C%Y*YS&`Oz(%V>qSTJa(^NAOWoo37?gb1qG(#Ur9}=d`!FOT+90m&+x+w{z z{NUgqr@0l82s)~*cVjS6Ud4!RK7f~zem(?`YJz_Lp#LNF#7?U+%r8m5S=R2%gsiDNDw&4Sf<3hUj<9fc?wh9 zbq{w#5u~O4=LwX>f`pp?(R6cz-69K5?ux$sZZJUW+}r)+ZMI>&0Y-aF*ya0J20}-v zgcRClW4Sk?vsKSn)nRx7^OXDg<7&t?175v44%`58hL;m^XJR%NjhD2TjyPa2nCP|n zTGoon$``%gKHZ)G1}Fq*p@*}B`-xU|?_Wo$VD?GiV+5Y@kVTYWoh1m6*ZwNF-E{|> zQ*~LyzpVC0h8wzvJ1i_L*!J#^KR1H7PH6f7#BXe3VtqqcU(ZKeoTd&3X>@FC-uTF&HgvL-q$K@a zJJ-?Zo;tzkf_%0N5;l4J_K{?_w1&4J8WZBv>Mpa;*BWLHX~;op>VdgVfY(7W4@r05 zr9T^6IN9*6%t<>F5005fii!qpMS|8DrzhYKtP+MdNV-Wufl=n#HLok_6i4~!QKu5| zkK+zvgFnn6`XQ480%Bs?@U?#a5yvMZwahj)aPhN8`yL3YR$mi4akvZRYK1)!B|;YK|uVOJOtx5+fO{07Rr{fDZ|8ON6BL$KUb}{QuxzXl@yK0(*_kkxmV$a&h zZ*A1VuQhs?G_4aF${=;*z>?75N`Y1oAw@fvUuDPhO~afJj_dDh5>xmA|f}cJD`a-Lwn~|k-;d`(9;PaNS6L(S%BDJP#ucMD<-Ov5v z;CiDXUZq(cigq$V-=U$VJ_%T*m0HZp^u!X==UNKsZT>}MdRDmCO~of;nC&Uj*jZTe zkKNok3#nmLd)x}{uF3bv(xdbD2Jy=U(1AwH#}RZw{tz-e+{s3HjxL0}so0o zF8$k03cQyF@5%$Ut5DlT(F9YXaTSe@+|OV?7Jsj=K>0E+Z?WiltUo`nU8vb_+1uKF z1?U4QX3*4ehR&kq*&X-ihwEaQj7e2*OY{|i#zRK`&_v%!*PYLMpI+ICSrK$c(biV) z*tUoNOJ&PLf_)-bEQf_L+MF?L$Wtg67o^B)fmX8p5nxhP#C856C;TWy2eUrC_IHsy zpJ$01xGfOe1|+K^_uIX8cNyk&cWX+^%i9&OQD97-+nXTuinhWvNy*Ua$M>ja5Bric0r$wu zV3hy{Mgcz<+NFg{~s&HTnea!$ejUKs!#lLDIa=2<#e?s>CQkqjdJpA&_Z#n>*MS3G{8vIWQy$dO4 zRGF^SQv?@YzveF#iL`r9erE*YRfYp-Xbf&_xD8xPf7UVLGn?N^Wi>!+aF$NH^8w9g>z*j5Xi8xi?2#mAG> z{%~Kr{PF<#kiVz%>NwrW{xFYcJusQ&>lHOU{Q-J1FM8@qMPY{y!s7y$R(bN&sV~`= zNAYk$i5<{Ur0lQLH^zUX84n<-Bj>+QLQ=#Wlh{7?b&5Bfy_5x8x#mk~s+>F8b5qr_uXeBZm>C(p0(|{z%{@ImztVOHxRs@w z8=aL><-_R}ib!Jc%ZGW4A!(Z%xf;P4;!J=jQ_-q#Mj}G@r@cpxZM73EjwJNSBriO6 zvtC?Fp`^IN&dx4lVPO%&Y58Mx6FiqaLE8QV+bL-$Bz&%l7jc}M=;qCZ?eKclcvvHn?3HWq1xBNHty ze*gZta(B;o6VYE|Iertae$RM)7B`-gJ}~nF&Sd)8^Q6S&w6IE#YJJy_R@z@VGdW{8 z5#H$qpXiRP)yOwGZf(-CV?IGHd@a75HB}E7iAlv1++*T)wZ;ro$tpeoF?fsNx>-|g zhX$uqcCN%WR z*E+X?z(Y?x?0+N3)pySpYk2kMe!hK_p8o9qM~(btjlnk%6hr2s;QZghn}`eMjABqB z75E3U>@vIoo?EXbs8sVMY;ALam@T+ZGGFgUo-aX=++c-W%v%V?sWTTZ-pN~!Q5y;l}=e#wuV~IM|vHmzrAlHhOm_`=`kx zX6@oYYdbyzsGTe**Tr61NRq>}y|tfu@Xf@;#1~4`XCNPam0k>B@tG#o?QWn4E8;@# zg{!grHGX&_wJHG9xeVp+C&G|{c&sF_wGt@am-e^lV4DaG#Z!V>z+ol^I@xj>cOE{> zNzp>{H3pB{iNdCXEih+!GFyIix75`afMOpMpCLjGI3_>d-MIjxS7HS!QAI==t17o{ z(d&;+s8i%9h!ovEIsmbCnFPC8jFmeNh2+)Q<>h4yx^rEdAprXvzGUzEM))X#>&GDQCf5y$4cC9hu}LM5X7O;k%0 zu0kFurC_v`ZO&6YSlrZCu6p6;ck%M{3dRqu+&`kcvmFn2&j^KtoK86;6aO;Gu<%Q{ z(x;p-JO?m}_2Q%&Qj6yW0G>r(8u1R_!gdgQvTcz@cUx3Qtd?uriQytzr~7z-?kkVt z-<^eE?cFSj&LqV=I;1Z5%^V+P5a zl6i(EujF8-8m@qium;YKPo{w4y?y)fu3PW(;`qBa&ReSBF>F*2GWk#N4Y*j8P=SyJCoh|jy zIHrD;0DdP4meqA}P&HYcrV-8UQ6qox;^1nOXuy&ur9*K&RP@Gx?!g>3D)A@|hpPec zxrA>qmzqGMK^le`+fDT(z%S{3@aX;V4o;lI=w@JDVg-0;W|*=PU=mH+u5ne(z-Rez z)h^-L=5bvU_+>(`*b73Jg zx!W-&CjL)jj*gBNBaIJMM@QeYu&~hoXbcUdN3}O1K7S?;gey@nOMU~Yo>|Lg&G3?Q z*RD)E#iFAoa)=#f*x!z0Q0L#SUc;#7X|u+Nh+_kX^p3zs>0Tug{aB2=D=ZdUYfNT`);iD2JMxes z67RIl7JAPK|0?S4F-qVo{;+UK_G4D@h($UHM zgjxJYXY6cmptC)Jsi+U?#N=;6e2_14KhTJl9o0I6mBfYFe+W%20d(R9!06(yyIOLn{KZ7&&y&hF(=1P`?kK z;;<=v_9fTUPuID1xNcrMG3ritceh!Drbs*OubL@rLLZA*;hH+&Fg2tF_K?eq%NXRr z4ji=t>v)}X&^i8F5T!8pXFot+6i_4JjFP;8CnV9O*!J%e@^C~XHR7_fTO5o|SwSzj z_E^!h!|>sg-(f-MjPa@8VdQ+5P5>$ znukaGuKiFm!MSaz^z-$74eAZfuH2UUzt48{-9S=Dv4Mr2R>7Zr^Ng98PFCimB%3HF zICns(o7CmCiHV6h4&^ef>lFz}$?}MiA6uhco~6hV^Bb_B@t8pELw>5o?Y?T+F?gDF znF_bOx1-w*Vi^{IPrUoX+Oml2ByL5hzbZeT$+Ed#eML&{u|_eM@mT<0_a#7 z-Wm2#fsEBTDDWe}!)$~nyr=VJ7Na{NtP%vkV3WVH24wIMgqEC_TfOk_gVaF_q_L&y zqeLgpT7XPF3rOL+mOR}j(ALg=5v;PEX`}yPXn!a@;x|9tR^hsTW}p-4NMaY0xXztx zBF(L;tmJlZ*}dh0Lb*W@_|%GxG?UXv1^9MIU#)6j2-0w^PaEc7x=QfdLwAD@5Im8) zimTCeENFRi0{#l}g@d`qfh}T%y+8&ZxV4g!!ikz_>34@PO_kPq(;57Fm+9!%35PDcCk4of8b4%MkZR;l)u9(C?g(oG6ZNRWS4n$iSb?pKE66U(T&61iU zO5z(<(xp>;iLMXL3oFAQH?6C!)oflkCy4k)xY^%a75P1l)ZGhxPNGftWpx<>DMgVJ zeB&QJG2zugvX-<9CMn}%V?Vw11?fc@b@k4G*ZiF=Cv)w4SYc9T@Zm=PcU6SANT#AS zlvVlLOI=|SE!I*61i1f^)2i8a&0n zs*D}*Qpw8(lnC54^4?}%Ahvi+=;4>UoD@XEBO}iGFAMfHt0) z%C891PmRzEm+!N&UE1ME1{WhjhkvMd5dGVm{~efsA_EL*S(v9t3<3{xFT!lPrVaWs z2=f0W|Eh?A<*bS(^I{L0l|`^)p!vf0G$Ne0L3RfVP$o$Q!N)p^>}P=Z>sfYyG=je8 z`}fcb{QNRdWWXvL=NwV!4hDpUodyGATu9t*p8S7ytq+8T{3)n4HGUb{{1KZpx{D%9 zF*zcOp*1zlVzXq@tF4J_t46P^fc=cUplv?|E7F>~x;PNP$9U>VXOH)+E4-dE5#l4( zmd3{Cew{boMagjOrcDnwqwPZ$j8h~1nzl)D{dHl=eY<@XUq9?ZX z>#sq^VOkj5pb=gB)DqaeP^aWH642Oq(}pKveEZoM0ClXMdM7~y`9m-D;rTsiY!mv$ z0wrT$F#MCQY#;uC_wbM=0iuc2P7mI$O24DUj5DT7EA8<^n;SYI=Z#UlXN;rQ;uHhf z--?=r8fO zTM21D(2V#F|FIT{xo~-E=gyssb#>vPTjRR$+>Je9vBiM=aY!>;rm+Gv`XEvn5EW%% z%uf4v)`KJqDF=GB+6Vwpa_DK5=w99p^ClkIfqVGPJ6W9eQWJ(J zd-LWDP(T2pl3k9L1>uGu9&_b=-bHig-ur6q62C9m#>OpnT?~*m1g@O zsq^yO5FkK$1+Mpgk(Ya^8lxRS4=L8(9jV}ZYvV1)WBc;NY~LXASAf9>n!*}PUqwI#ScHT+1rBTJT!AsY24n1h zi*}9^)X}d(l@lYh`41f9ER~V|Z!O#+AlJ0L@R-g-X4lkJF1~Pc`P|0Czs{v4*=U3G zx?>WICbbDnY4tfsZ9^7ky}+B;Oj6&*ch`SOsky!q=H{uu+!she#l(2%2&fIKm0jMx zRY(}PiJh#?p}R$8L`gvrSrgx~(pI{b)jHY5{-2hXeARn0$`C_kr8u?|pGfzBtOe7> z;m8hbxdTORVtl-#W`idPMu6mB0G*DDVz0vhg<6SAfz=f7IfiOrHg(ok^sNeJGFQKb z_B1zlFu(v#B4S9SBm#{CB+CUc$o)PFa&mwcZaaCRO@t4)=`2Z@T|5CNA95f%iHjN5 zgG&P!EiCU2g%os>)b6cw66T4jdp+MljW7T;g7x@gMa8*?E=BvEJ@qb;Z%Ozuhl6Et zEon7hz8r9Ma55<>*}YZ^k{9AjA1T?Y9Dh8e8_cTV=Dj=}qT^QZc|vjub`^1pLkniG z(==Uc@A=^^bmpwLM=z@qhE_0}m5r?$RA^+g_E!JJZBhUl@9A7^!1J^a-29L{?gY{) zgXjUmvp2B=t--*40GQW@|J+Hu`VmZsmR2Cc6)jmZ_d>?=gH1z_<+pZ)MKW^oKq$Qi z8dS6$<6(8NG(z&`;4qa>tU>@h5a4HA9$?xu@{RXg(6A_wvcvS6`{qJRYhcjMoN29p z&k$&x2lDs1D3>herXNmcIC2_-vm0yJ7KNJCzD>7*d2$#v)^=aFZF0<|p`)uQ#`T)Ir2SYijB>1WKI^+RlyTrJ zB7CW&qr(H+3|scMUYC&xgxq*ft&ke&AD4Gv6pU-9tCt$V91|yCE31!|^67~}h=Icm zN_JC?hQA0Kj|tE-$dE!vOtc*?jbjR~oq(qJ%kM$KY)K%Aa!yL>DwF8)BCIO{-I}E6gT}tdLaXxJCvu+a_wUD9Svvy`FgS6M0%iK8r)AM{bJ23H2jkX03Q$ss3Pg@R zIrOd4#crF1!#d7Wx$T4ShY^eG^9|xUy)N@|1Ezf-Ff`N>y^)is+(L=Cy|P$h=z*LU z5#fZ9TMJ}~hTjesq}IeQe^n8tx6ee)D1KI=YYo3->yxO)nIbz)UPQ%S$Tilzx4yFA zro~@D=%@{-9Okp5gWjv?*s58K=!blL5h-jq)dFyq0!V})rSVcplv^^hz4=O~IV{0r zRKBmTFRi5&*|gbojVTD0?K*bm(rG^MESjx6TG@_W_*vWjjA?VJYUsafjOR++Yq(Id zZqrso4}ZCavZrOU166*T$*s{U!1Y(%z8KE8@J?9E4GB|4ces;{(rdSj$d4hD=aC|2C$fYHR$#0FObb8Y9$U7tuJ;}wqMZA2Q5qE zzCM&?G`vC4%Jw|7juSi(Cb}HQenER4?8I=mly2X?*m3d98H7(RiBIx&LA(ZTxR#(R z&xY`1V(VgWDU$(O{RP$;Gnir!G+cccJrqUYt?w+l(kOF+Jm zmX(dLi$p(I1z*7dT<^+@7>6ohw#PFT>?n0Fs2|nLo3@7BLrY;#{BsarsD^-_bIFV^ zJT4*O2z$XqgV;8v>4AaDXtn-L7*c3Plh161h_M@9M$VAu4#@r)J;JL4)-J~+B}pU9 zS(7GRNg&SZv|cCFj_?pCuU$;|(WbL@`Fyl{uYSkvj*f#)^K}Q0(HTBz5v7x^VAxnT`!?76Dvc+o&0$!YUeCma&Y~1kvU(pk-BZa5tWayH zcHDazO}0{ov)&T=`ti^)5lZE|aN!noU0Io#KeBMd%Kka^WormfSL&65ljYNocGRS+uoN;j{S*adZp}Q~%Wfm?pB+|F{`i57=lY zr&ZXh%0j2@@V3PYwv6Zl)jhBe&~4wr;bHj+40rcNroXE!qbpW%;7xLRi8`bEnw9@} z!f$+FngnZc%8A~qSFQYZ3%@WvBvJgKwvi7sM)eEQCTfdQ${k2|9rhYuIbRdXaR z*wa~vZ?4S`)$#XTNLy|WDPghiwyM&+k;wBa)^hIxm1yXMUV?dODRKL6P(pz6lL9tl zKi;9j!HaY5drd`fXC837dm0V04we34G77Z5W8ZB({$HON^;3dmJ(~P=w|z7T_+jp3 zGmTR1J1`#d{oXy_79(Jq_);5=9Ib45P#D$Q+tFcMn>=9jMXSpk)x!n?^$*n>^h31R z+?PHx`C=@)^5l?Z+{Uh2PrELfy|*>JuH9vtUOYS(=OErERK0bkX7q^G9UY-#jZF1x z#BZ2YfBEvD%O9^xZv%C#7(b5_euC#w0e7Qe_E{}Wfdosth)hD;AXJ@u_wKnU?F_`f z8=!8|It(aB2ZV~Re;qm~#Eq7nv!BMUfT!4SbeyfA^Rt4m&%()ByR`PxhbK5y10@uR zsS@AFbb-6zD~W~_6H1)`U^0H)Nc%Je3i$k&7drRu-5Zya(>gJ659#v4aZlI_j^T*q z-lK;PTai&SFqn7yS(jKIyTb6-6O@4)5N^O9orm-E8*X;cfn=miU?{z`w9f&%uy8og z4AwQzm5XB}3!rQ@G&Qr0R`Ov;3eKRp3 zXbz|>VunCfg+1wvi9br-zGd!!739an-MaIqwJ=U0BD3YxR~xm$LBSJOf)g!RXw%Sl zap@k#wJIxoy{)2^d&*Sr=AXMmawsAk$WMoyU9q{TUD)#tt0RLJK z(H!4@fv73+LxKGhpey zs^PfsO~p?TJ7_2RQLBp!)qP?l(mtxC0K}t8t6``n4vp>_4Fni~zt`a%mDA==y3$jy ztD&+TgT{y*K6*3|$&BVk#5WzSix`CMzO3W=O5dC6{g%Qo*gM*g3e4dqev<+dMMcE` zSi*jKTIA^;kLS4y;1ZqV$3yUKPeK<#ZztFFZSn6F3FM)d`upA2yq;`K8gk2|*4G7n za>fMpfB!C}qXcNC2n3;6_RihAcF8?kLO@V^l_}VeYu#hp4ywgrRkq{dZ!v`v+{@h~ zVk5H`|KvR3#48EOFyYt~?V0vwL$kKF78aLU{^X_ooqVezl;5Ge2>b>bY^sOz(IDkh z^6w=c?>F}p-|Q-to;+%qe{2yuTzAlMec|dWd8QJh(v5}mAz-)BKs)uYb?HcyGZ;^= zKG~5Mo3MhLTS0t1=a|3)2}J23G0|}Dh$w}apr9J4eQ+VQUboA9-91#7YbNLLufSIp zkI+7?UaXdtdDOT;l?GIG54JxggGZSNa)~?rWd1ztt+Z7LEG9L(J>_4dl*s+y=!f^O zn$5dd(h56`)m)jGmFzq84=zvJ%K+KJN+~6Ze!>Tt_<)@f3cg98%<1Qq2WPpuf=)+d zw2i<(dTX+_?K!;_Ucw zaHo3)^RiCih4i&65(=1=F$MQCu&xxgxTVT{`uv%do&6ej!QjE=FW1EGtu@F^Qn zGpAl5q!Kf;$zz6Us<_2PyXA3}Qj>kLo=(tsK(Is6jm_{R8nD&xZV$FbBt0-l&OZeD zbFob92sIEC@t(WIZD-823Xqemb?5)3imDzY5?%e62T8_hVjJqlz#G_*aHOb@(0-2! zZo{OjWmgV-WP&KWyfz|^QFMn%@^ekU(6qlE4(@18wm)5G{lk;>pLE>GA8PA^XEZGS zb3pe9q#`Xv={vJ!J1Obe+f96YeGi3CS#CNzVv2D$TwK;7Oipx*v2zP;9knHIj}5W7 zKVhz&x@%$3Zact1%Lh!S?SDLe)xMf5 zl%n?|?#Hqxi_h2cGHwztW>zusUY-{Ujv~c;7;|TI9-u=noq?Riupb2xE z5(YwW1~BK|SyMeYx;PaugHvuaJetDKA~_B*agu4tgG!x}j4W)j4G~%l?Zj^C@qt2W zOkuYc=we%b<#At@c^BUHj>z6zMawp*2;+*ev0u&sVclqIx?c<#SvRy zMY9UQ6ZxK9LlO&0@wJR=?VLH(KNg?v-Ed!=-YN3oJnZERXAHPWOcuGrv++`SR&{RX zxRjLsRB`Ih+nmoCw5(_jNgmooQCr-|UOBfp`0bcag;db!`bf*uyv$3&#B9N>g zl}ssnX5Sa|sER4%&d`tr#bS=}$ssx&&aih^rO|d%n!&sr7VS@W@1wt|^T1+HhP*|L zWk(AwvE8W6GGZbK3dTMRzL8`3<{;BS{P^Y^FhJnPjC%SX?H-c7W6ThTxL9x zQelB#o-1{<>hdAfs%O;)(hF4I!K}9O}_H{(rtp>50- zq6-JHdbf}h)<~}j)$5e(Mr&_50VvkO+(Nrf&Bb=jlK@r(mTs6AR!jvasU9FoCq~<2f?<9kWa!zx!zY}my$BG0Qptcad-%kpnhfZ`%G1yeNtl2a|Koc>C~)Hs`v1MJs}gWYI( zFXcvlg<%0{T}*Fr7EIi=yxOz>m{HMK!1k9NzicJ!O!PNA!fVdSFLTB9utPbTcJAoc zYfP^9mxICqDb9rTx3&3->eIuwdonXKD^sRn|GT-JHpuy=LcPtWZn-f2Z4PqT8=&XB zwlv^hHyucGK%$@D6L?BKC0QkRTMn=97hijzXCS`qR1v%CzvYPxKS}jCrGD0^(Lvv7 z>$VGz+nDp|l9IWnHx$zJPJa}#m3#MMQQT5}u^}*;nH5oTI~`W^Xt(1GiMY(#iS5mW zvR!&6=Y#}3k`-1BfKbgT#tR_L>g|g(m>)-YKgQ!kk{gQF_v+o2QMOPuJFZicgHcM08mDNHsi*UY!xGM1* zZApphQ3oX2HPCjciURE!@i2%D6HBRiD+jXWFT}{D<64WuCgK9+17x@h%G)x>euo%# zvQhitJo7GJujcVLy$$pt4jEQDkGBnCCV5B2)Fc_+V>#YMr09Q``ogFc%2j<=ji#Nky~ zS2*j}Po$yblidZ%FMNFbh;bmErN`|0pnUo=c^;uQ&Vf@zu15B-U6#B_37q3Wp<7pe)X$;!SN%S6yf!;Vh{Su3~=ANX*RHl z;?h!5PiOCNyFOP7*DejaV60?=zUTNWM0`@0DCJoYM#sgKf8hnv!oy+waBoR`2$ju` zAIm(Zh;wsu&zrV!I&LhF_=QK{`rJ#;O%yW7RfP%Lr=6?uu8+E7f8|?y=Ege4y@rCn zTfz#R?vdi)3l+2+dtTJlp?RtfBh@<@(6TrqE-T z&k5Nd#|uIt%~!BvS?-%|de7tH;#S^jJN(!s>=keM>&B0rj={--e3aDYWLs+ZNt@$F ze`02tJkg7;sn$RL@Rut-z@=LZ(Qt6UUz|@{MpUnIpWr&S#XN9%V-+*x@4oh~Y4g!8 z@;IGRH#a{iE3}SF%D;*$5~`%5pI2?L*{4l}$DnJSy~yF-@_wz=U*CcSrajkJpa?MEdKU|dHKCnz=gH* z(Q~I)oZh@1axq9*UFiSV%*=OZ5sTqjXL6Lh7Z~U|o;`L0Bxo0Q4O6(cCn>WxF$s6A zEzkRzN^}A-gB2R1OBgRkr|UxY(`F-$*k3t@geo~~7`w7K-D5iVzAp(x*2pJZr1$^H zk8gr`c2MGH2*>-0g#y38jD)?8-p1AhFzVO{ISu-+&D27IbvjpWc{O0ic_qIEj! zsr+)bB9R{l6QkV%o~2XZ^j%(bxhm>0{IUK&wNV65hSk7T!HuN>1m`^1!hNMvXXb;B z^iZjzXY1?9z-%RD{ZBzE)iKV~v&rJwLGByNhD{Ua!S{5gWuv+}#8xMH2ZUZBb=|B_4;h50 z7(c1^c)nObsz0|~JMgq}0{yOGOzEbZgn?Omn6$jetRygagR>jNGz{t^#y-7G9~Oat zC28naifxt|Y5>WqzWb1J$z9)r_i0-OETGii3xGitqjT-^;=0q6(w8yR>(%e>jVLJ1 zeC@f)#8Zq7@IB01nZ8kbrx$vTR$6g)LD?<<;^1zVlxGYZGoL9dFCI4+GDX+-rkVdN z_dc&%wnL*T!REJ&wLMl|NtUGtOLrwvO>yY3~k3 zev626ye^K81up9g?dQQ+0cD6f^1sQ?l;Zoon5Lfw6lLR*<^OmLQvGZ54I#K*XN7}K z(Z|i@9R-fxrE{BQKi#)d+-+UMRhcsEX#pum5U>NT_Kb6m@7%M0ANHo-iUvga+Hn4c zCG@k3DFhJO$0XMMH{g0cIP|5Vfo@$J*NUAw#US*Mv%quXRBcdF##{zVXw5a)4^gaHc)iqvfFx9kUJ=1S<*(8p^cvQ`58T1ellg;>B+R zg#`r#S7%=`)G?u>M4fMd=6hAfLpzzs_2!qu$y$(*!y<+%z3b{_Ip$q_!k_q7u;1j# zvkM=N{XCZj_wWT?q?vaQ6BI!wW^3m@>3`gGegfpx(@FZ=?q2wY>aTa}#zEnGzW0V1jA>%+ZwZ(eoJLB3T=)~dr zH1KGkZ}8Jf>tg%Dlu=>&sMtVKL3RuK3~;qX(~^1TzkkEdr`{#{&>>)82d-UP$2mEg zYXwuD2KNB|o|TKMPEU0uEG>Ga8nB~pg^bFJ7|RfzHoZ+*n=;Bn5= z2Qs2Z&-rTAy@+J=8lAoVIia^OEis|W*J;v7W&WEy&Zfs8>J4M^#5pu-aV#;q8WOiL z^URe#N=6Y?q+#7;Lt(DtwjA%vB;LD(foxyqrNB?pfl~O>4#cVWi*KlwmbkHx&bn!} zkQYF@ZT@iJA#_-vnWit8@Qj>WJ?A=`LX??HdqcE%Up%GG6n4J5E5&%aUeV=7`F&Pb z)&jSy&L##U_A8xLt3(B6eO=ynV`~q*G0>v<0KME@s}1J&(1lGTRs& zN{$S&IV9@VG(a!>24iE)Ix&hvPDxry#m`K0N80#sR1G^2yG;=|0=`;Dz3I zs0pG@g_enDg(Zp33AQ7*ouZWN`+h)+l)}gg9prq(0G?D@&7Re@`ksQ!^!B0RDULht z82`xWk(I+^Nga-Eh86Xb-QTNi9nlRKm)sWjcTSxB$nQt|BijN;M*I*rAKR*3Gh_eyv+|pN%DNTDw+A zd&7|)yQpc)(SkITX+4F_%(wdJLJl3@y0%Psx0sgb!eohZiwflWg67e>?I{Jq{CU=H z*XrIZGY-RBm`C4)uEeijZ2U})6t`9JTrz7FgSQ#>Ek#Z68riou7db{wwWh2WdP#Aq zWyPsgOs%itaOwy0VH`E&GE>jnA{vWP>DO8n)lM;u4=S%^yX!i64v$2;+bsuauPxqr z@}7=l>Ws;Jl?Bu_+LSL;(lp0x-uj~`&v4i|-R#8 z)6f3Y{yPe>lZ9dC74keLM7x&9Nyx^`2;b$dC>Lt`V7 zEeREJy^M`5J7v&&1=cfL_N*3(=EU{wu@n9Bwo0LQZ*fn@HyU1am$v#0Qc-fCQx$5K zOcLq#6={{X4KQZ!Ipeyw^**cUu(|4J&qJzWfrKh|xp3_z?4n1M_JN$a#%9B4`?i$q zKU@G;HlCuHM?YQr-*1#3gyG`kwUFHc)@m!dZY?+rProh=)bkw=!y0&*nQUV*O`3t z`V*6|Xv556Mgb##=fZI>@sY~jdQ7)g2<87_?7!o&Zr?v}{3c3NMlvEKLYb*#uOhoC zBP%1a_a0YiN=84GRpC0#ZU9a{`|}>U_zTGI7jV0DIJMwpKk;!}ECmNi4suvv2eI1f=Ju z=xjZ^oE}cwKmK-AlK)!SqAt(cjd%7oPVY(S3-#LCcTp^Qbxf?vu;yoA^V8ro#u|)e zTekXIdQ1#VcBo`Zj^-^E-_HSuuP1FU%l2P7nAuZv$&^02Mf{n|!q-`wD9(Pp;Wjc` z{5tt*)Cl})^75flHRTt>j4o;)%!Yb8Vq?KF?MU3P%ziB3qT}>-`H|$Q(#99V-@wX# z2~58p*}nSKMNMo3nIyMpRn_qw6CM}(;vJ0*G8=Z?+MNBSUe2^o9Q!)iS9h(wz9z7`XlhOCILwI5}3c_HGHWr z%Eo#~A8#Leqb=M=tRp;ZJzyp*zV-hi%fme#?c;ObH`a?*0V~^U!fmtcEaFfe7rTqx zgK~TCCgJ9x$@eQ$cx_jK-kr1g z=s1`7K5ZT!LGVL6;s;#j*PH9lIX&v$G5fHikP?aH8VI~x_1Mw3Y`alod8x;SU&$W3D)|_e#{?Uy zhce{tO;Z?#(Ae>WFbQ*3@MBsYxTsdg3~7`4jzZf4W2{U*AMRD<>O@@a~E z{Q}G1bluP-?crS&@~y{76!-Q-6u+*%(`*dnv00w#=;4GvOb<)OZ{#tX%!Ui)#-*jE zXSsyu7U)P|8+mMOr?~#uHsH?tBRCP(#??=rb$j<^er|(&xs(ew_%vG3g`SO63OKk+ zlyF>D?ZGN)BEF{2<{AQyYbWf3Fi)GM8`@oZ&jpUNhe9 zobRAv4WoNsW_nw9rNIgRHsJDEcm7t_m{iV$RQde3#`?XG%YI%qBWx6UvFOe8MW8nW z3`7;E_VU#VZj^lcq>DKX2SDVR2nq`!!`_d=;Z8WglM5R=V)nwYOcWp7h{b z8-tlgAPnT!VZj9+gWHCZp`bY=+|d{|(=wyF zS)hLAMjO1!Ypuoty*DS!X$!E|^q^08r0SW=NpZ`zsG?r4fQw)gG?HO&?!j);KkD{% zeyCIK<8AF&#+Fu6sUYy^wB&;pZHtAM39pmSS+5*CB>tR*8|Z`X6FSCi9nq&t1(WHQ zB~D2iwKIjG2syVu--d3dYqrIYd*69;68}I*AY6LDYlH}^w=3e-k5oPAusx@-Q{t5O z)i7-%MYep5v`eg*^W1Ne%$nCZd=X(`BAZ0|(J~>ldHTTmW2=l{(xP4UbNp4ZEtdS$oncj0>i3F|$pR>r8chXp^1J=T6s?o1TN`mC?G?~xDE zTVSZkFsoJ%l3#FpWpvqAul;hXv4W&aZYu1+YEi+nf?U7WiC>_|(j1-Yk?|uS)~C!Z z+FJEy`pn`$$IEj8CV=eL*tY;2q$ihqbUem63&=~<_tBN<75?h=0CAM zL1W8rUME-o(D~0uG3Unc)S7yb!NQrE%dNW>{z;Jv0cFvrAkMXur(m2g$2qLU8_6|a z7yA5IzKjOySnG@!Yc{c_NI=+L$!mMpXmxp--XK7|WazaE05B}{uzU8FYjItW3ZG-; z%|h9jsO41L^Vr%F*#GxWrYz&0d!%AfZ~}IuIDUM?MsdEju^yhWtmEp;cu;J?y!iUW z*DuZ};Dr;s;Q6&%)nO|+nirS!$sRu}g3_wQ4qU!a011(p7`0OM$Hhg?;Bd#wHu$kXd>QZw$N@8o|w%FjLzDV9b zsbT!SYAegr0-#sxh<(E1`^Q5=K2!dr-nGoqub&6r4ktU`oth$U`cjzOUbe9E76uV{ zNM)>k0;nc%{Q38(BU*BnS;3jZuJCF1$Nr#jBieG@#@%wTrWy~%CdaQ z=we=({(;?JS(K&!!GL7QDAoXQieR!Sd|y~J3t0C(yI21AWJbu-fP^sgUiP>x*Y4iO z5B_O>WtaW`MU8j}sFCXPlS)7pZ1!8|%-!Gk-pVNH@)jf}r!K?VG<))4ij+zEe$37} zzGH{)%gErLhAIN;4)=%5IC=g?CCS2|EQ1Ms6@Q)%#pw-9RZjWFwzd@#^Nv9PNX$N-qGcYuLq%EdkdOGPVRSV=$X@0{`dylV$Af zvtdL`v+3=SVsn_vflxH)`eJ#$n`&Efz3HsqfQ!rSzqeBcn#rNe#X|O*>w>1{QRwF4 zj~)3O2E5Xhc2Uc}c~}1tpWe-@l_kSpzUBaZ3@NPJ;I{%V0sO|^{KC?_%V+WyD3B|( z>ogH`OfYp+P2*WQ{rdX)Q>TrNGCzFmjp5zGcgc1UB^H)yo_$$)n91SaeI(|UvG??o z9pxV&$)!4L`}U+Y*rrgZl-aXz{8LwX!I$8w4*Iz~h;VC>z_WSkqR!rf-Dw>Ae4MaX zru5Cyge_V)+!vY^qw}OFwil&|1_B0JW{W+=YBzu|GSo)3Mjx3H@K;O%xuB!xg+Gk{ za8l&-pzeR6PwoT#7%{+cPf^j`Ulf2|P!!m=IP(xk|0lrb?B``DDr}raC8%^K3`9rly&g?@g=dE;n z2d7i#9A6z1sQsPe)ljhLy*S-x;FN#G8i2|Zo=a9x!c{r{Q=PyBLy@kBkwZpQ(kJM5xsDUXP3$`&ZA<=UAd3K^+(f9%oQHRh~<{X2nv4t z?TIU~`>hk}WcdJvr@kxCvUlHUlR7HxcP0-}6B3}4yik6QOR4}I*%VM5U{8!IG>lKY z$uawUg1mQI4A1Wn!s6e#f-r1%LFULQ?d{@yKP{{!_FdA0{e@)#;rL$YU_AMl z1Ud>}UUk+*h1uEJ6HX&dg7u+SwvO2hZMD)jw^|?wUw5NQD2(mhL9|KY^h-XL zG}}l;T|I(m$IjpFLU?P?Pld^BXAa(Uw+LkBeshb~9{Wmbv^P6ESL5N+x6gGxN?zcP z_7Uayb}BHS?~4?>UL4jX;Y00-hB*1tqDJg~es@R~Vm6^dxWq7v_@tn&zV!SXOt|1U zdQ<^QwS(^_axGd-epKE~_P%akeZT=)+B_!XNeQ=-NSqWx9q2u(Zah4)Jw77~Oa<2T z7~OUc8~ixtJX`@ungTJ=U6%~My}f!#Te~x*0q(*xIxiB3>nmH0xoor~QhFg=*S>s? zDE4snrdShIbPgNWnBuSU%!?Q~x;VB=CH3bW&eflz8u<;4YwuQQ)mh_?`Z7tMp}oY8 zW>K(Nk^E|mJr07$%TZrS+~+2~;v#3TzDqF_PPdib@p@)txtAI{tRfRCCBDt{r8sprY3*c6y`Y4~;l2 zu!mGZF*EoRrNMSnjDzhhfNvyza#0nY2&CMpM*EmXWDIPWQ9@BuGv`@Rm6TBqyeg+jax3`(oQ*Xllm zAE`uZnW;Ja4=tIj46NDvzMW_LuM?FXeh0d}ktDf>iI&$M&BtI(AL49r#iNR9jZNOo z#_zVg2kG~7ZkDXtF*alK!mkFJzP)wJbYk$h$!xOR;3hU#C783-=jOsz&*_X>LVmtx z26jr!9STXkE=^ch+fJzD@sa9*6nMny6jtNpljL;I<*7NKU@L*6wf%TX+Y*W^Ff(<$ zC9;v~i&YxY;pF{WHjG&S#-mu%=8x-|9Yk78qkZM&Bk|j-VPk;x?UIlES2tYX zncAF;926zax20(h(rAM-2S(z3!w>#jmRZJ-MAKRz;&SrF(o(2r?NVrW?a9q_&Qw?0 zhP0r9hS93lpI={026pys-RrX5U%!5>1EwwS{O}jo?)Om1;isVE4F)ylzMa`wZL7c% z$uHdS-5B=$`APUoZd1VWIjAci7k8Pk)4p&svHjWTwt?`IYPz|k$r#>TP&!iO`u}|~ zBZ1VVvMsqFGzzq*TVx8V=eJ%ni9-LEd6AEf1`{X6RFocvgbP0jZ+j?&8I94$omVd! z24SzILo8_;q`?M;?t1ZZI(WUQhhLhOXduokhMeyg3wyUs1* zg5hg8axP;nu7wmARH>(Qqtb-Om-B6UkHG^t^m#9T1mY60m=q<`uCS+#TbC2Op7(09 z`UO-T``PjK>TyOvL%(#}ce`~}Y4Gd}j31a~7C~jPzl8&!cnY?Rx!{;+URVY6uCa@| zZirc0SDkj7F@%;dt2crSyKue-Lw6wM?VIo^5uf9y^2+zEb|h&#d{)xaJ-Kry?(hFr zGyGW>G6%+}khA&a^5(|$rj7l(QqSdj2<}awX59i1kzY{e-CIbjc~k`E$AVkjA;oeC z-+$xhND5+4kBMDl-+T90U})&+hkHyO5JIF%w*u5 z0^99$@LdY}dN?6WYckdk5{ip;Ko#=wz{zz`4n5_=t(ij<&5sW&cM!!EmA-q|5>@m+ zH5w9KcsfH{q8h?+z`f95I@sD*B9!m%7W&cUTMFI%&d^**ZVkF84!?igzwh?bf2)h% zZ<<)tQ+cTTs6fVaf2-0Fle5!pWv+G4aqE=Yy)e>TwV-y%IW}FtRA(Xm()QIM1cT`C zG||9k<>v2d-rgJdZJ7t?jo)DMw`1l@$Sn9Kw+!+gio>!qTRZ4R(-EwDtXA^3uKlXw zGBdy8qQwrJmyn?#hf204%vJ7v@*4=I=K+Dz6=c7+eQ+ujA$&ToQ}FBX)J*3~lPz@x znGy799^L*AwvObMGh*`x!VKk$Kv{0WYxCPd;y@YEVB{+BHfSL)`d-~gmDm|J2RY#~WX{9oWNC@MzdZ~P6TCm=&4E$(dDlz&+QuJTHbqNKD@Pd*({m9a z2H}sRS`bZfL}J16Y{!cyUG4~YeXb++9>G%F7^RO59~jQ(V@0i7k$?1 z^m*W%gqE)TLSlo-pEh>m-%ocY)r%MGrO@QY_2HfMub3NZF#Yg=+Qtz=_;hHSZ@Nf_ zq_ZtrlTp_RwJTf((_f!(S`R4_WQ4xaN_hfRHPWQmW%8I_vD5A#j*o;%dU6WzJi(o` zB-?@+=sdmPhF#^hIdEh90LbYYc1h>gfzM!)RZx7mc4pDFMYy-%#s|)5iX;^*$!MF@ z;oPT3#o(>5ohL@+wzZAra#!(Uy6dBRM$~WFmapfR{P`7qNjH`9?Rp!k{iFWwL#I|t zp7uN>jB@)#x?qHbQBwsHvEr@~Hoe8~w`DI#RN+DWF1GwLZOuOs?Cp=jtJ~}ks;p}$ zW?^3LzwstjNn(2B$%*A+%x9Jb8KornB8{llC7$8+jHhd(J>Ofh)x2_6jnKSUw(F!) zn`@4YkUw`XK4i^TAkFaL*Ok%^xyCwj z`PyQn%4TZLP{r}Lw}#%`^og)-V-{>{?(FuBatPz#{Gc^;2a%aDc67giB4i4zE}P5H z$&(;dWe$pHgA7hCUs02aY0V$Rc9mT2IRfF}lZJn8!(E79v#oHWBNv| z$b48Of_HazN;Exa$ay{{UIytE<7&`0sHlSi%L-7fsU~4Id(Cg8t>|-a-=Sl(voGe3 z2J5URTe9p^!RO;LO(eM$-ViQd(p`T0?q~>HTP3(0cj#Dm5Prf9fE5;&?hxMpEdyHk zjuM&K6zq<$snVCBIO>%D9-^K>uA@hjH_EG|+-bHl0!V_(>c0y_O6TYtOU<*JZg)9r z##A)9ut(JX!ds4-b0Y7$46gG`ZxmjO+c3dS98XKx?2T`nb5Q4OOYCW{8~L25K~0tWu+WgT>H^t ze0zZSy;mAr2U6}*Kh_!4G3eXsFroDdvz#B!shHJjhPJJ=KXY^hBmT=kIq6q{nA^jk zz|i{wBgcK2zn$W6Jc2r^5|T)hHRAc79#wM?pNJANHhF)WlGe8pzDI5MOJwZ4=-nWI9Gb#TyL7)#0(E@blG%IHJN$n8nD`0>2#i~FnsU;L;RHQrS5 zl7l)7Bk9zsQ>T(GFZA0`hgRdyeL@JFiU|VBvX#L5?E=TuDM>Y>W(ei6cc8=(84gV$ zynxJgRQ?E;(F05zb|gJ^(4 z2_r$+i;4jsU)$^U$HBlOpzC57A8!TnRAd%J-qA`|&MS_D^>f>})<>|b6YM40PO?Yv z(6UB1n*^yka&87qbmcX0J~gVk2mLG88BETT|NVr91r;!3>^N7P+skevc&k$G0NqUN zJMwBZ6UK9E=a_v2fYJoH&EVh*tkXyq9)wN!XQ2z>vJ>6a|K-rYolmiW0uXKCF7hy+ zt?heY2Rn7dYZn`mlG}FkGk_q7dy)~CLDY`{oTujVW01`p)L3t3B!+=|UgKeTfBm!! z+YJ&lQ%;fD-oM)mc2ob^X=|MiZc&`i!2qB(Da2>~y;v7=#I)s=(qe$-l`D0?F`jsL zD~LrB8F6ZB#X0c=-~UK&=9CFLYAdcT0L2MaPS(fE_4fG25LymHBHGsej zhoqz)deeD%VzxuJfw$jL^%de10vQG}fZZCPkwHz^XlY5Xqv93*E`El9p?i<&^518= z-wJjswsif$-y_A~=_(kBfr)s+szb0K$BV`BlMqVI&K!A0_sC&(p!#J_t_Yug`w!=( zRTv$B(90xHsJ(a=5BtzP3N^y-5ZfhENQSO|KPhkI`D$wKPdtl!9ueW==m}mHmzK%+ zqZGi1DaPqm?Z6}xyz(s6k3u6TP!Qb&At7?&Q%cF+z=7W{f zRselRLg8Edu;dK_?slJIq8EG3Wun8#q&Z22ezYquwMv-X3;z<#cf%Iw$~_a>eyM2v z*$5GFX{A0x@GAIC+(80B!eiozFH)%2y8XYG6tZwfgfIXU6dhZ8(RqZFz z8^0AWzywt`Gc&WhZF&X&X%Eg|ps(!6O+K6d2`OsAZWO%yaN_S5LxmndaUz+^p74uy zs12(Qul|4ED9JnLam|7s7P1MACnNybzo3eVLVv54>^kTZ&CN9kMAtB} zvI?vugf#Z3&+{h;zx?hop8oRg)Lvb{@BnJ9j|D|^F=K2#+(~6{7^SZDG=Fc();o}) zLJvkPCjYl5_j80Vx;Eysw=~golzC&XT)A={$km{d%Os7EK9Ij}A`dg)TH9}5%+*xQ zkI>GnRAZw%ElmW<+-7e)J7M~03prL+Z2i4N8}ng1eSL!pQ-yjX@tbR}W88l|6I|g=xN8L1SmQuOx{*D0W3waMcyHgv`s(T# z;?(W#KFoopf=^JCytoi3+_fMp;oYDLhsAK$OA-7{vwI9j{7L5(5<;;HcLd)<4MLJ( z>@nj$Vg$>ARa1C_fR2@=Nv3_HAvlQ~nJBW6PZeA-cDF;+TBxt7%sohrj@AD7&izuc zQ(X3UDB*C^S>>}G2XuvF_owHlRBX!ET?%;0H&(_SI!z5b(r_?nuV_<+R1i~R8W*TYv(R*d#MMbG-6z`VIjtm2`qzX(=@#P#m zm@)$vW!LvGmLu~0KoyRF)(wS^`IhbK3-?I2ULWQHHG`B_A(Cdj(X|x3L|^vHQES(x zd+L=bZBtru;IH17TCREo+aYs?q68Ro4pn+DM2L^hCcySn7d9*5 zr5d;1N*V;}HocEHsm-|!HG6XUr z^&15OLT$cqfde}ow!q}_-AGo<0g!eqCyL+3q@UVT#8eDa2MmE4gFTN;(32+-5W1nJ z10*kuVG4#m&Mj|`0cjAXn@|~1+fiJW z8dSKu&5x7}>QFxlo&*FB89(5v`)%PgML*h zI#B8w!mkFueEAXyEmY@STwJ_kps8jtCqW+!#0hZV!HpOK4#&2JE4guTy)Mg=gx34D zr$^=Sn{Ia;qGs`b8&>;e5zBy*#0%wAA|h=#Z)eVkA*Gd*vKr90uOs1) ztseKOYERRRwLcEfN4hJ`00(-<980)6$?CljV)2_^&ncv2-KAgZPVB9(H1?4o?uJgh zh)6-R9e^Ybo9oLBfU@hb@2S~71QO&ULMjdpCzJ`h=?BrF`j$f@m`Xx)*hiw7ah(U^ z;6P2YUoL&T+PEm2ZHAaqV#ZH3R_rQ`$006j_1J@1MC4MXipN~mxRDEnLvh4#9fxZ5 zpT&SEUPDijqnf<*;A7z)x>9kWYg`{n9Ea75CiA<|fNs!ADzKS@zG3A^{*Cg|54->D zKSFTo+s}1I5w>mE>Nxw~GjK3$2=X9ty0?b{#o9N7LrLHlsq%>v6#_#u%QtjFpA_nZ zDqcU7C7}}W`Dshi{7=;BoLRPVjPQIXG0@lF0IhebRZ??xN6z&nG(-E+>!hJNHz+2v zfwMbt!vJdGpjD!%@R;E+rQ|{|1PEd$xNdK=TnIM|GlQ`5k^+IwZS#U|R6Jb8)!lVt zM06FW=<_8b+3*c_>@wgX$vWy@{Uh902Ig%Fd&p8DzXIl@zk+yyS`HfZ zVJfu3={=n|sL9{I0!n5A;OR3y-k#k7Yv&30ExQUEsD`0* zXr;*n5<>Rl?(eoh%xw4ps@VZ8mzwA3gvj&`AbKKXI>HH=7Uxit$c)@~#$ z7#ns;>%&{&JbF61)AgL78WQ!_NIZ~B*s6T$vN`||hZ@h6c&Kn_7(9~};+L?~2K;>x zWK57+#Ix?$v~~L5e}>~h$^Yd=MHsE~RLXnhcb}*vK92p52x#VVpH9D45AoNpUF|il z&fh%$et20WQ@_*%&~cw-MYKe}rzit3`I>TZ4(ig+?@1a}lDLn(c^wmWspEsPy=RA& zGR;(S>{k=PWE z9(9KtnIqZxrc&w5sfUlA%uC+sx+OXj#FTW*_Ks@InTtpTuy6H-8ZxmM;z&K0X9y}! z4%z%c=^G4(q7S2eSFuj)sSi9&qKQu4EzUbT_c}!PzcX!kY`ui60o23YWP(ZYrr?Zb zLSbQtoBVU_R^xD>T%3pcv+?{9yjB*K-2sSEO9>}v>qgG7f%(Pm0?-1^bTpGC?q%f0 zRG?%Hi9%huc1^`A$oSQyMXNVU$|jcmnocrU;12qf(`)JeUvlC`JIREqsv1MhV1FFNI&h@;^F&@Z80p0<9fVaR@oUE@-D=bY* zQ#Jb(bvS@tz$SMBBuoS#2GrEj3PzR|S?4plhH$V#fouJ6rdnFh;|&TUW4)imNvhgZ)PMhs2*}A`O}KTgt9VF@I)F$bS<7s6<&+<9&U_H z0;d#$k&W0|rGF7v7NatZ(mw>YHRQvkrQ4od$DFcks{@;RkO(@JbfC^hU&OtYdQdrG z&}ol4r*$()5`lcIr^C52t9_JH4q5svD~>m5gY=k;?j3r_`qk z^3VGh)^L?Ja~=$!2~2k)5GtL*KNM;+CQcPqh~J8NI@Clf_ey{Qo~kB;&kbNw|JmbnoZln-cu{d z2MN*p8At$KhHb>R$qnd|Vdx-vDkTkOWalMa_$AlcUNyFtv@{zp1e3r?x?r}9gcYRW zmak`tRYf=6z*=>l7*sm~0ynuA6EgY?E+?zL5xBifJ3L#;OAYo!+Qn5WW$v?)gEYKSA zhh%$DuKk!Gdxzun>C-<4j9d_!}R=kb&KkloOG#Smn#|S@!@XcAKvn zP>0yVe5Pr-4Cmdzj-(Q=B!tuDgXjISn2K(caDip(<`nP_k?vn$aZibRj{VcMrEc3u z7)fgE9$Ttu8_bH(Hc;bM0RSZZ-g}fC$aIjY#!L0OW!0t~a_KOtv6@1{3(;OxheKeD zl?u%BOT4mR%^6o#yI{?Ql10?F$4pj7uxXW7*hECGA?5Ptu`IRVfdy2Bx%jr$S7`w8 z$V^|2$v^Rk4=R@IVo6oVl~GrJBIM`^lbY9q=n9sBFZojMJkHi643QwBL*)`^(6>=` zWo7AYIzSBSFz}G8c<&fQd?(D@(6Bh;HBo4iOf*18gvx?gXT}S1-DkDnyStR15RdFe3Cd*5?5EJk_l9JsccSgkmu-fC`0-PqhzUk7h5dcfM3-J6@ zJ>32%R@*jvFOC2dJz_<{zAd$p2D#hWjb-1>Ye2TUTK=d}M;FAfH#Z>_E@K9kD+^Wv zxQj_CDRo-O8HMYGgHN79R?>Tmn-|rM{qI(QI`EO3@!t8gbac;u%_H$M;5ISS72VUN zIj)&zzOerKu+sv7s{F8sS9)#){G1N(r;FPG-NHC8Km|Q@Ej-IfuI|!E#4#+MP z_VouUj{NV*VN66h7`-JXVPe91sLo@cc~llDfjkTfibUlJ7(oC?^!J$zOC*G}hw;RR z@hnhIivYy{hK6qk3UG%A&XuQLBqAwd?5I1iu9-1*mAhY3?t7Mpf^R74?&lx9r^f=Z zjc^$SQ$8q`e5|V@!(LZHF(h(>?3ZQwTJk~fIda#^SmO|?+(1ek@=(5Q>v_*yfy;j1 z=1k?bkwc#q0k~DEX$&JN{;yDx`B%V=G^Evv2oGoMb)NpN2X*nw1|8plYSdimvMzpn z^09DZa7l@TadYv&5~?@%ZEm<8PtDnbjtm{K*b!{m-m0`fR%!h>@1@SHI^pY2aYVyg z(5!Q!?8v$WDn$bW=@Ng*jGS+=kski;%CNB!uiSe96Te!^z_2Gl97Y2Sz~Jl=LXBbq zoPV#6u>#KP6aM+XuZ8L&G2%)?TW`9Li%x8k=1t4#Z>f>9tuN$v6^*@3MT%Y#dW}-6 zRxl|%DBDX9y6Sdr{Qbi}*by>Xr$QAE3@N=P3Y6;3YNC8qM z4#*TpHEboOym3IX7B^MWr1PQj4jmipv$H2BOuwVe;(l8cD4-)aS+r*&& zaQ(XeH-rd_M=|yTMA$syh<$nrf11vy^g~PIQ>g8$!K@q;68&o(`jOShsv^?}YD6cG zXFE2ED#9%>O}l)p2h^Hm9*IUL)m7r8z--I@DCGK;PFXYTov*8}r&*tv1PtJEYruoT z@b&jEG&BpA@eX2r7Ss z7+7_115|zwLn+Mpih2lxmAiWp1b|(f&art{ZVFi2w7zu7DTvGk)XeNloLaV)qpUW; z5E1hywC_Mjtq1eh+;fVG4ak)oK76=;u!S%onM4z8RfR_j6X9kfFYo^h#W?x0N?Tkx zB9cmFL%<&9fGOQJ90uKf;1!<=Ibu)8n(9%^f;5kJ{VJ%2g#fnCINo*unPio+jTOuI z6=PIUuHYf|T^nQ_3csc=w0BvUiFqb&6RDzD?(P%39KMDGcCnvu@t&g%_aN z+^kqXUdkI4E^Ac(H!_4Rig@MM3lJMQ?J=V_Xwh4oH~Z^FVPT=+y;=hK*AQVU6z6#f z6?U9a2m$cL^QVpH2|^CsMCS%XNgUAb9Snj)FQvg>)$ryivbev3^!{}jcW>MB9m zVfHOOdtkrx4neBBoFv|c-aYeSLD#A4jM6?O7HP&ckEy+lcYbChMuQ%}utpl@rKEbV zE=h3;*?yNmx}mD=l0#vaO)C9&OD#5R!!0swq@d1h0{vDBk&ybd#Cq+GGziBSn#J^6 z(I}vVxl%!fq5}jo(=sY9lVY$3m~-{3$novm7ekBiIFNcbSm@w_v@=+*l`xdP12NM-S2%5tUP2$< z2rx=-XLr!Z9WJ|>ep%Gxs`4KQPXN9Z)=yefhkLzG=(u@#Pm*^pE)F=STNq&*k9mQ= z-^roD7i<9CoXyuDw-V~s1?@v1YICryx9&zJT$y-9a4h9w;!nr{PwlnDLu>ah)qNN^ zC&PN?d$zG+;;tu)Mp>YCqYOZy_fo5mZP5@NQi@bz1wF$P-YZVcj{j38q_QH4bxWEu zS~RS!Bn(J4geDk}VddQp?a-pA5&ewB#_7_&2Yz&{Fi)*;VaS&HoXqXSExxoO`H1Qy zlFov@)|KBd*(&gMX|W5?`|Dxa1Y_2k)XK;aNT6*WZ$PeWN?TB1+ounAhAvBJ1bIoa z14Mk9KA?K0T2%x^l|K^{;d>9T+e4ek)v1zs_2%h;WHpN6c<&|ca`F**4z)^xi`ll( z+hE#uw1bS}Fp9rotk1oA!I>cZ2PBIdIa8pj$#f2buNgrJrq%=%3TRG&j+^(IbR*v<0)r7I++R!;yiYmq1=RrB8J3( z%e}qs{OxM;dLWCW&cb}~J(?|tiR&8v`v z&WZB|0gai!f**y^02QKTzXvFqSy2lQR9E=`RRvwYG{2y8_u+$NvPc#JRbIz9JhJL5 z>*e$Za^J^m2Hu?7+S>2QgY4z6_k-<>Kz}j8y+;xC}D9&%yA%$Upah zV0dv}Ne)S<26r)&46O1>zTaQ?b@#c70afVa z?C(CSlXD;TYn)-HyuBww28y{t@~d!_uM;=#YC%LUup*Q;!H>6#f+wlDA-sWOt$g)r zxV^OzG&sF%&$1x%kCsV)aQ3e5rJo>zY$O0zx5M@Zo-K!>8Mqm~fMqNz203q&1o}v( zKp_2@w6D*4y&6TgbIlT*g{v?c!;7h6KnJOm{{)3O!H5jd+TCm$aN%>nRo>NcyvHF* z-`{seZd$dTh7_fF-sm8)CTXsqD(i!$PK{_(hOUQT>G%p4p}q-Q>c_G<)l<|O6_aGt zT2KjLOTLxcl|uz-B8fQ5dj^;$F11$2i1!*0J-Jfl+8xS>zcK!(sqshFfscf=EQUQn zB&s%$i3|A(?>hAGzuL>!h6I2>Waz1bH1d#OZOxgz0o}u&o*9onp3Uc~0ooJQEOGhT zTmYiQMgjs-s0Do*4WQI6z$oTq{z06mNdkl7G|-x}C=T`U9p5u0_Eh|TOGuW1fx1@R z`JYevBS|tC_aRtiY=u8KO(N=FpR3jWx0i6ww{E=OVN_GuPDz?hpiUZ8Mr!~G_$$(e zFv}^C@otdV7&ow+T>?svdVLJ#oNE-HW|%b>^6nk~2t%GY;TrSpsN#k@=?`z86Pai2UIp>gT^KPi(^Hb z!H4DLBs?m&uq3Dl0V`nBTJ;{@6yct`|32)wPk;6?!fFgJCcJue7M@E2*kpR^2Vv7S zM2BcmDUjpXvHBaC8v^+^s>$79pwg@2;;twQ&EZGQn?7*eUqQgNK`BFt3=kCwi|2$8 zviNF>Wl&EXf&x5++?72R_mL`ebGlT_0VIC;RWil2)~)Nck1rr)>+e9lsr4|JBes=T zLJukt$!(qs+S)t-eb$Kj=phYyXi02X8cZ_$^|^!WY`#o-Bk7?|5|bckQ3HZQQ_Z$5 zzh3kRwl97@g%x@)SttzH^Ljf(%%TqeAIF|js7+?c&__{{}~LHs~(Q>Mh}`pT?V<1X9Gnl(o9|HzGtdjNrQx zYlRQ^S)XgJi&1LUF!@^98?N@p%yS)#Yf0dtMWjRB9wX zmXi1rNQn_2K762ih>^wlvcLbSa0d?|ZW~RF8{bXv;<>2U&iCN+1^iP}2@#_jr+LT_ zpsJ5!V9RT3YniI;YMC8XFR0}{@UD5xsIUj@kpT>d6P+p?ynT@A4tndKsljl>Kysd( z+T+x!HU}MDCtr(4IQz*!LjeT4*t1eE*5K>l7La*QoN~!M0;1 zTuxw>LK!MbP3*k2+eucj>r;r=#8vT!l!a zx#?4pe0LJUz!Q+8HQ#8sU;%+rI8X-<{(#1BM(M7js=uW{x4-!9G0(N%>TFbGFYYxR zCL@ufNcg>L?QokB?V;5(!i^7%-&60p@ah_oEZGD08?t9johJ0GMl`~Rd>)Wld~K3T z+07~AM-{r(UREBy7V2tn(0zI+Vp{w7@u(ixMvyO5b?jRj!{u{0@BnHW z7rfiWrGGn@D&!CrV=hcq?LsUnDvBKXBP`4%Y)R7=?jDk_!0jZxzzh2}rspf9Z7_ z415RT$X{`r4v`r-agU7oT|Ks)B&x&^62J3Yw)xoDcv`9*vMiO};4cwd8DhT)xQ^Ho z?9czHi^Gczha|AH#b34G0nrVkNDhkF@OH&U;%Kb>`!GRLE9YVEqIhD0Ubz579ZZ}2 z45+4uG#H?8Z6+EFa|P-_Fx&LQ)lv`VHy0D{%}(EE_0fW^0@EV5-6&_`K9-=@84sgR z_CNCB(}kpQVX~WEkc5|$3OF^8>qR_zXh>L#H!%VWKL5E-$;uy5vccR7{LS6__PMZ< zGj91BDnnSsjy;VCCMOs*HbVjU;$)t|SxZSGKJ}(2A?FlFaRQHYd}wY+55%mI*bfZn032wA^1!CQnf$mH-rFI*An&C+uYa*00H{JOHZCqjm_5M;SN9Z;d4UTbn;Dzo0n8D_Cv|{Q!>F=vWIQm@4k@l$ zw52_}D#t+>e`EKe0uCpdho>*x-k!gB%4R3tc>mS_lfBt_Vw)a{UdkDuJh<$#V&}Q? zrUD2QKYxCFT74r$J0}^S{5<8s8(S3DP4bbChafJw@q=B5LqFGZ2K5}laoE^fxhu!= z6I6Ia%#H!IX%=ZzNoiqt&>88Yczj4)b6{YgL_O_LFEsUxte$&DjR~MSfBt+hQ1TDN zja(AE>msk0WrzW)*7Xl*5(MOzY9>$y1|kE+;`z~3IHyjdE$3k3r*{rj4*n?lDZz8c z(f)n1{A76G4b3meBsdTQ#We&lce-c}ZtnANzONQNbU%r6J4vL7BiacxRO&&fO2II; zOu_Fzs_v@*)XsOvx4A#}{7Gr)axME+(0k!SaFDeF8w}O53#x$THnSeDr{UqI$~xs6 zx84ixAW9`eCDb|4Ky}|cj3l_AVxq%&WdQf`;U9YPkx@qot*dR?1PskvUOi0L@3#A~ z6oQjs@%s$HO2MC3)Qsfil3ldkf+|{bQiBvSq@d+wYPFwNecKBI}lm{W2q0M0**V61j` z6ow@>&B2O}Pt-gIdW4f*yWH|^djN)&A!0s$C_wsXQ{yBWR@9uXrWN9{A5vzyL+%C>4e*DO{nAf-@V(pKPCkqELF@B zgR)ULIFhKjuS`FnHRl!B^(P{1vRgqEF%N`#YwBg* zhs2>vawX5tCFtwr6PGSuR(pY{8FMS+nb({jq#2MBL)$|r_zZg8A~4M~Oia3@%~>4C zIwLdEzlW%FR+5M3O^1aO=`%P4%Irsu#D;KdZ++X42&@cW)^7iQtV|oaj>VqxCQH;! z^lLdeIRT{1FvlEP@|ToupU0g9M;WYNZEnIMHR7crsLLUc`w4Xr1qoOiD(0d=J|~1|V2*a-wf$3JM{+Xtd~KYQE8d$=_z}2;Wnkd$7qs5h$pmDy=6X+&824+*T2y79W-Q` z<-E}!xe!hajHU<(2sp{eV z15Fr&dRqqhU2Q^TriVAnecntIqPB+#py0Chc;FY;&LUhq_#0KE;~h>AFgM)$JcIbx zuP3?xT)A5TM~?Hzk;IOcuFnOaM|hQbpCt}K)siuUnIm%`QbI@f9fn0hi{na};n}li z8Aw6n$ThR&0R$J^wLz>RH@LZN$|v46oDKNH2**k0>TWc59=Jzb5D*C6wL_F_$R-S~ zzR0#YKryo10`!RIFOgq1SM(Ks0{KHT(`i(&JF*4>L-jB@fz5+`yS0LfEY~lNBL_NZ zG8^FHeWwu_+tua2xD^l25 zOpid9$@+fivu8ZQW}i^i^+1502642gV=~FEUETa##Dsi)l>$0Bl|4L)d8oZhv4G61 zJ-)HYcNFo%|HB+ZnaCp%zahMh#hJ~DE|gb!`aWo6AqHWIr|@c`Z%=k)Cqln-EsGKr zC%W91Fwm8bVpzn|eA!#?EtwmvN73U8{R@?EN}cUtpq&tT&tkglotvhU-V_;JjQsQov~-v;-@>~KKE*5uSr}YBo!}3 zq&uujU{LBD)HU4qu13IgLm)gf+3--~C-g!HETa*jq^x{QA|%6H*+ojImPl8g9A}O8 z0bQc^Fq6_jylvVtP^@r8*9YsTfPZ1uwa4+TdkMscSciO8Leoh71%zbyj!bL@F+22=W?Sajc>jikz zMuH*ghE2GF0ilFZU^Jj8#iP-LFD(e?zsdyx--5TCBXK6&JNF0bkefzQ)S40RDtT(Ct7DThk8V4e5SP4 z#&n8qK?X9mwgy;A@Lx{$eTDYMKb{wt(G?jK+P&y7J9+DCN>*KILVu3|b`g#5oeBCz zYB{=B2fFhT%Ogzm(dy4)pxdAhvT)V-_Wk@&PL&N2_;RST+}HQV!z1TJZx|aVfeXo} zt^f2X41#!i?CuOUYVRo+9bo`eVykCNvRkRBpI<2{Vo!JVR6CAXazjlx%hloRmW`D; z0FF`r?r&ZKxQW|=Hbg#I@jUClMD-iU#E%Y~zx8#?Uov@e$b`Yq_yypME)j7fS$#U>6h}hVPinVfN)tUx4)Nl5C$^_0GWf~GCkBR z;Yva{G88lvg|y(fFB-ztLCRju`$FQ3K_Uk9a_+MbBcR|iwHtVhg^AAAHZiyfCyR4E zzt1EqowDiaDC7~4kmzX>rICO)fevYhMn4=tAWcNv$n+L5Z<1MX-chwF=t|?d$H}@EX%xXz(M7^HP7qN{!$X;iA5w=u==GQQUTLwRt}Vv4$dC{;@`(3 z;5QaK52_++SePQtnWFBWWEB|iXA|S`!hnL2%-sGPn8ru4Bg@w7EEdbNFbtUK+{AYU z2o_C&%|S!^;o?1)zMBI$&noxg5<7tlAX8z3(^`alnIY4=z^1qBb*56s=i6>u_G%^^ z+3HXe780ryVj@YpXnLO1|Kd2ezG;WPnbBnvinGrD4_|K{PIdcs4`)Xi8q69H88cN< zGG!+eA(bg(10f|Lnc0nsQc;wdQihNyQ_>)zK_oJzA|z6oQuMBCZ>sxwe(&@B<37Ge zw>$f@Ki72*>s)J{)UtevrCgTKn~lA?SwePFMzK!6Zmu#;xw3fVylSC~b<_MCiBD|a zVoB4rE$`NVIS2~}r>C2ZTe5_9He}n`rTO?QBgvJEN&eGa@SyLm=>V=2g#tEvaovF% zM_5YYF4yPmSciR7H^g!Sfw^`9>KeXWO%`;MDW2Fj@hSh!obcdM-2>er2 z&}f`B+516ki{z6vi@sPF9`ya0GL7}f%Do~)b-~8Qmbzi+5!bkI_t7M&g0O|kM!19@ zSH?jAvk_Jfv1ese7**ZhVy@j1(bcASNc_)0lKey`;jO9bTYqq2dM^DfU-~;8CyNw! z`}ArFfmP9JWoTakgP~PXh_+G2y`eoHp{3^T75lvJzM!PCbF^CB-n&HJGEX|ceVnKg z38?fq5_R3XckiyY%_>_#)K>#n>2M9i7hhGez+Tp&ESRa(`b^w_pB3f!QJSRNV0Cz(Jlhm3rpT?GPVXa2$w3|yrxN1r2m zQt#dA9og`LsC(ErI6QbGy<8jS^fy(uHjfNpKBB7NxPG5V<^Oy^#>AFEUE@EGO4|Y$ zx~pd@ycqFr*tl^8dvo|A&Hj}deQuyAZy;WGSL+%M-+uH+JEeQ;Tcd;idNg7 zI(dKp2*ca|fmpUsH%Hx>o?UZF@&o_2p$CTSiS2jW z-;R}DNj}s!%c`ceG_k-Y^!K6umY(W?OGF^Hj132LBOy`|vT2V8slD_fB$JL)m(ws4 zfg_dN@bd9ChdW<-_};vR?rq++Oz(vl4xS*L6W^sXE`JKGd#v5PoMS~g-rfavA04+a zj$AC6Vbpm=`v3b@%B~?S{EUpKoczPYQ!JQcNRyEuKv2Ka2-^mzDJ9V)nF>00UexsZ zY_TKhC#vvHRBWA>a}voFvU$57gqb`Z*ZVbdazsT%u?_W%`?E?Nd~Idr?CPWKN4{Z8 z>m}i~8&=8$iTau!LZfb`b#&OH8?j!_JKolY^HrhMvqS*|FP^*epEVQAg@Bzme?&}q zxmws!?NZ1-+it^ARBe3wWXdM560H^>S=ao3cx+S$=5IPj>rTsxIsK@>u7e-)i>Waj zu^N76d+O62zRR(aiYMnp@Pzd(w|82V&z=n}aD$L0?7;|Z8JfhB*tOGG`e9Hh>%Y;^ zaOK2x>-eN{ck~BKyqpm!?9q`Wx4Mz`Ay|_+@YmP%g(PeTJ_|%>>qHJ4s>prn?7?)m z=e`F@m<^=Nh~L)p&gIS+2=T98<=ZYYMQ3&il8q0u1@GP$XINVW8?vAf6dM~`_cG%9 zr-tmM_%*kjb&pP(F0|wR%#B_7mmo%d{cHjczDwoGbzsT8b?fxb=>ePVirM%}uD^v1 zS&@;YR|6|7wPP0#fFT;nzmDHieB|jyjwXV4qf#-_D}1V+*KYIsN#+-9=aL=^(7&hI z6Ejhqh;p;9*#QXgvF|;G(=1yiV0ks4#e;;evPBepRYVS0r8I=WM<-+qUn|a&2Oe*` z5E*G-l{`5qiE%Xd8ueXq*~_iLs6Rdh&RLIV2R4;6>I4$bnYE}vlHf#-6h+2g6c82` z4q0X~39U7w;Bsxg@kgmdf7Pr<5m#u&yJz2FML3+tay0&k!1vZ~vqa!obe)|^ezzUA z_sH3mmOSbl>K#DYAwBwy6Y8H8?5+1O_1JdTH{T?~%n&f26s99eMnXw0?xyM~+jy7` zv35V(fRZ|)!9G9br>VJ3=N#7D%$#8Ug5DmBu~cQgUO&jozSy|V^Ii7@eQn3eda!rr zDSu;OIl!E!M_jYV;*EKL`@N`#Ws8P1%PYcJx=niIysMi!Q?=$EOxkayzD=B zke#IF9ReZumr$D0h*?#tClPj?J9o}VFG8LC=teewxDn(!y-eobg%2NP0OS^>@s6|t zHbTjA%Lw-J{#fH>_>-B0fF|$Pz}%6`wMKb+8x?*`bcx=jlUPg1?Y=HwvPa zmz|#CT*~4mrbD>5lI$9bOJTOeNzc2ZYpK7_s=^@~7S^ktwV@iHui}2?<+)h;-?@D@ zjf@ZN?r5yXS?a(D>Kx9Sm6&ldwJe!psZQuTMDfLy6H*5+g`o+(e5)!RhC z003-snseZiS&fQp zy(%J_spw4w(w=zJ5cuZl*un?pSmB%nN*k~jOKW6H#g{c~K*ZyiK{*J^>SNI<)Y%n8 zrn;Eoc_gO z&cbFr4D;tO3oKa3bYs#^ zrn?1Pq=O97#9TA?biscWie!3YSwgIcq9w^Xc?YnqFT}*IpX}qNPAKCMwu_-y+?TiQ z=zr`WXlUIu20ms^sb=_i8sYv5@`cIgwbt~2yL~>5Xrc2$TARsE0OE0R@#F>Szc=?! zAvbUbacP2oci_L(T@FEeZnv#D%mDR(F=v?FIRE2&7hRDGb2n~5!M&BS`zOaNVU5J` z8Nj&A%I6R(8-OXb-TM3enTwvlLc+PSgq6$`2ac7Ih)c*lhAZJWj!~Mq|4n9()z|KD z`N= zdQmn=fxyc8+}_|}b>JD40*Zk21 zR=te}Q;){=L{W|11m7M+$ehw$1M^_w6BBS=v{r_vrt2l>;D)`*dtN<}ZrUA9w~gEe z`)pW$@CSaI9P~Y)kG;q@%xpjnZ6e}$^oPq{<93TFOU*DyI7UBEnF>e@^@l=6|2U+OA^1;P`q~$sd zmf?0TrD10Fa-oCziNM(nS$&Ak`Q}>MRuU8zsW5K^BH+OR$vhvOS<(%)lsqO*$qk%j zSWg@sEl*S4PBX=;{#2MJuKntk~H9wPGpt|9_IubUc@WlATq zH1J3ooW-2(!NB3ehwZy-k`yr-s6Mv0>-{h=!0He#F@sdgX}Dtz+n!$zMv);*v8<^@ z4MR+sm$U;|*FiAe8Ll0YTg3wN;M4D=UvPn0jLytdIH8_WlMqKJeR}9Aj=e^&?1M_| z2EXFh$1>aH{f0 z4fih?5Txr)-5$=qI4B7$C8x9u24MCr1qV{8Kxp>z76DYX(qvnlca#_f(-5`a+>&~c z!tLdRzv$cOhj4*ny&QnBWQ=<8EnG;Lo_6MAsHlfB22WKOL7n3rfo;gNHXWCRRFnp@c{+0|f4XCRGtRy9ayA9U}5P z4*UdQ)|qrdSn7l0lanyw?i}Y7;N@o*!T&%iJZGrPB zV$owOnCD#ufYTZG;6ekjFNWe~Uk51!QW`bH#UEYZ7pKSBb~lVZOTkUDrr7vT2E+K)ckns@w2C}e7*uI*^4!TdYwf#{Z(2)!cKipNa3I-U zl1o6uZ8L??kbs9o3ui2C>J1%XKmv|zjfDlR+tk*s!nI|gO=SRfolWoI1S6F>$p@Q? z*3@atWDpy1NWB6hrNy%sD6vwR7So(KI3yD7#WKT=zUgjOEjoQKBK#w+O ztL;AQg%1f~t?1mSg}<4q!@|wOqobBP0-aa#-29Fq6sGQ0B=e+Gw}VXg4Mc_*v)AwW z`kGvaB37pdhfM-vLBK&LXWop057(effr7hw4n-FZ!>AD}QCi4g1TfdzKn^8{ z17kT7uqhj@b?d52qh+V^01cuixZi{5(z6*@>$0LdF5joq=Xuj8u0%(_PtB-w>QIna zW-N;1Ckt90tH}mxxK;fw^Uyf~Nu`c2;!C#MiRvk!th&Zpf+Z5k`{TvX-9t9Et2aVE zPvkQkla_CZSrbqMRZ`)jeRXvjq)!3^?eR){C!O<+gz>lIWDOdl~;OXrtPbMf1DZJWu# zmdyP&gsZj@sFnmu@}jj(O1U^xa6D*xOfCxsq^q8VP@HJ*Qgarp+(QgWVGm17zA|TaKyY4&ZplyMhsItBJndqr@AXtD#NR9X@g9Or(qhi`V`Pdoc z3G2NgPASAbD)Sv4%L9&yREIYxAdPGq|W_@f6FjRmhR>qR4Jw z9&GG6$s?r?E1SMciR)ik7J#__^MQZ1nDPD%YP@dle#+Rqc6NS1D&ZQ5fohf5O+4%1X+F9oSqBBZ$&Coyd|Um807X_E!xH`mPwp&OZrpapoyAJSxK6nBPM*+Xf!QEDkC4 zOI?2Sy<9Dmqo>(Zl$4cSMj3e-75NcT*g>%elz*S3e{^9El&~bh}js1{)D* zCV#m*yRQg^yUEEjXS{gp&|7w(DN`zXdQmB_eH?wuIU)v!HN;NqVelEN?IylO$>h&d z^}G%vZobeY9MEsr+GFNyEr)FRS|ECb;~7i)tzXw%Z2L{N?cQ1en^l6Opi_sBcPKO#w zri*=|&>*xAVhEeP-!S5z?^jN~aDDD4&z|v(TfV#D@)P`e!WC~9MVWwF-*!__VaNH6 zS1{=oSSdC4n?j;y_%C=%*lPYjCawm3m04)&=(caA0nM*QcVy@>N$2YQ`=&EUCsZFN zN;m+2B32H8(=Im7IP8`aT)H89>1)3;aP8RumZMOtN*btg3t93CHme2r{hWT)x4S_@ z{$i^1Gv60ypli^Ao7-l&oapFzFV8$B6-=Ty4Wpwfn0*^0ygnRBoJ%1Dy}u3wByim_ zaF)T4a^LLnP2>y3SF8;ZmD4fb)YoHLiCm?Jf#$nEK#0Gj+vmpRb+d<6eQ?u93m-aG z(MNzH+YjPZ-6&o6h=G?*URYBZ)D{=M-746~oR_n{*pgoeH3Pr=0()|sjkqj8^?#XU z&T*yWG)&y#sC*gRFBJ)g^_|OITUOUSvmlPMC^^++Hl0V@f6La<*{O%=;a#tNL7#6{ zbfCZ;YTfy?LzM=@A`r0^E*=6kBP@b44^$|gib38e>;||bnQfjOPjb`XUvA*Q1**Gy zZmim&=Sp#mJ|;V}bLP%KYU zKHv)1%slC1w6bzm>jJm6h$V(|_ci8-USqPJ<)pGGMVYtzg^TZpQ(a)#HQkSUYgc`; z(qS?(8mE?Fx^y>QFy&a^FNMvLiv;Mw@((xoZ~O!R^c!(?Btd?Kn6Zc(W|40I+Ou6* zcVf;KXtol`0kq;Mf%xhhVnS5(I*{EQkT$m5uv}@?)icW`Y=>f zxt61kK8P+u=pc%Dw3NWNreJi zaE*VX(uppo5efF+!-M=}gQ5dRtxifia#5)C>+c4-QIZf|c3) z#pM=$N8?69uZ1is6?*m5HY6qOi`87R+a$S~j3bZ7tmG>bUFFt5!* z%Xc1)RXtc0xf=)4;oXB{-2D6>?J4emBHUyQF3ZL{`FSC#^3UWB(V(m!f7l!_^W<9v z`i2f%n@bP+UZwHqFnPVvM)N}3NrBu@5x#YApa^+a;qvObC^3eH7Btym1r4{~w)FSJ z&z+ka(oHuKrFM*iRsp_;{WO>CyJmx!<|avbxiuZRHx#FNkAEu`KeR?V;bdI}-~Rc` z9OL6?d>+5>jh8y>9O4@>JlIoLxVc&Drw-A5PJQX*|NY<7(Ja0vsMhemoj(Z7Zh3nz z){VO)@QI%Z9%q4c(H;mGc8Kipmq+5fti67Hv*vPv-2=57msSFMvXT3a=A*h|QP5|t z*;{U(rj~{@!5;KDzI=&yQkpn}j5!!e z9*iQ_LT7)xtST_Eu&p}=HN*zU73aBo6AYw4v|*QGEGhRS{(#hzFQ9!I(x6bz$t(YP z9TTJ*47&Z4VK7Ect`6BGHqdm{M(vKv%tIuDBnst&I-`JWyJCkw=ydKN{RbaKbepR0 zRR(9ggRP9o9#>)iuN1O?KG-;bs}pne|FeHDx`{=NFOsD0r%? zoLX&5Kgp5AI_sO&0YW;&SLw=KlfZ?XNSw7J5)(y~ul842=jVWVsBt1t4&12=k_55( zEp-;AE)cd57SB$&=Q)y|$4%7OnNIUYX>9NvbA%8tR!5T?RCtP!VclTwT2w=1YXkTE z`P=f>-c)7$PS(|1h_%{{Mp;8RXI)ne zCdZ9^EX3i$2WaPMb=QJ-Gl&p+Zvqcnqym}vR>Og4N706anVuUyyaCjSS;NI&efxt} ztW|Ptu>gRi^L7R2^~^FH@=g>Q<*7tK(%my{mJ2J47^QTR-awch;(MeXAQLAa$?q_y~SVCm(6L8e;4Qk6+ug=Es$iIyWK8Rd%vh0YgoLhMJ@Z zsj1b!BJB!HeNDoP7VXzBLgcH3N!FnqXX!Jc;1q(+3=W?c{P)9|5EfY#`!{c987a51 zLFbps0WS%^{X$F_y$4^zNow$?u_{}M-`pE5WP8BhweWIW^z=Ee8J`6-gijMR-}1%> zW%^1N>&M52MpCK`j5H=Ev@)9c^cZOG;C(A0?;a|WRl(5kq{;?h-dd(1YY?T<-P}h|$rC7FS9qT{%>D4*##(p@=mK?ep9Irc! z(^pNj1*?CME^jeC^ZX}OvGO8_#W_xmF&M{uiZjMqLWS!L)T{mT--D8vW-33FFm&k7OJU`eDF7^vU{$YcnaPVrQeHrI8Ak-u6c0 z*L}unW%K=X)&hMI7(zXG@WA@Qib{GUF|lqZRjqrhl^4RARdP*f7d>U1V1yRsxZ=l1$sq z!wzJ0%XS2CvSzz3lKA11bU(QJj~?{z*YqnJDPEoD-y1V+iqc1|XBE^8v?hLZym`G= zXxbsEyuRn~4pR&Tj?uRjVt7E%a!=O;v<!N+TXgcH%bTMIABrjd+dfmvj^RBPyVd=7 z^*|Nzq4{y6U~-drF*|Wo{`PYHB0i3LU>z%hf(Ei|noZqeSNh+k$>!8Bj9$O)GqDY5 z@&EoT(DH&akiUM4fP(c|bivgS7dim{BJ;`OYuZy+bNgl*oCO zN41@Sz;JKFCb$dP3^QA!3(Ddr{C=WnhdL!gh+*rAqwBvk@fsKCNhW6mRd&X5*MVI3 zcIksK#%EwA<{i`4(!Ck~T!Kbo)!^5^a5Ll38DA{JRdK+SIT!Az*-x++*dyBXDZq^W)=P8PgCQ_+Wq3RWes+FxwdGV zFDvrw(Rw(;aqn`vS}TiaKQA;J)&Bbp8QbC;s+KK3$oNCd;c?fH?qq<)k1X&cI5P~G z2nGJ9xXu;&4+RR0qTuPg?2@(oMjhtbdLa2A%>C4u!4Fw3cvziiWFCJ{2b2c3kb>`b zp{emSjx;U#&rr^I@Jci&42K!-FIXOz@lNM$F1j#ys{3Ik9#d4kTay`+#zm4naqq6J ztu0ZQhr|HDne41&krXkb7ezUz%TVtw#nh*0N!#WW-AYVI_eIR4HLcr@7V&&kl=-~O zHvelZ`iN_{)>E|qdZ2M~GWE4&DL4C`K|_RnG<&H#w{tO0y+4_sW$Rq}52afWleXfN z+Y$Ekn`*6)7?+usqah~tFhd)%F8iiDXP7)k6G%7HDVO9sMMEqwi_lHb6ldb!}XV5M>bbMy^ElCsM zl%{o7M^yu%*HPQyyAV>Ti(sj~yenh8aOd}fWE@yY)FloFz+^7LTvnUGO~)6ZV_!krGS>wD;%j`jb*6 z*t$<1gK10Zre3yXAT+ZObpbxM6*>{ujK0MdlXr>!B&>OOTQq)04d$m5%g7>(#dfa0 z)oV(S?!JPjHonfAs{3yQ)Gil330YW z$7Kq@c9C$QnOs8B3<^S0loy!`S`;O}!4U{`WSNok#8_^oOcrf3%8<``_eVRdTL^aY6nN0sEh) ztCv6aaN67iHd`2v{UivDukac%d3#h*5o5G=_MADZT$}1Ai6YFOiLb7Z*U5Q*5-c7f zv5FwnioX21iP2Q}|9?#`@v>JSJ|kkdYT9&x0W+au0zP&=xqx_0qpeDrtWpYD$fjcy z{3~n{Vq@hnGE*2)wl<82K3T@O1{LWz3tq&Z` zMtp5LJs*1!H`3?D>pwG6IOE7bD*;)g(NmC7tq2(veq@FXWFDrarB$UdR{$(q4;JkE zl|@oq5jV*BHw^gv-5{K6JxE9>;Ii2wq;`l4Z%7Wo3Mm!b6TfZgBsQ}hi! z$P+V&bfDdisc$(~$6JYLAyOHU2K5c1i}QP|^U_C^?0-*W1p^6aC)-ZPgR6*eZz|P` zv=f`mxLZ;7JA;_|R;AcDs;|fQbQMuzc+=TgII>a{!c`=7GpT={g2k>tq#GL*3Li;* zU%@!He$0>02+4wGlzNo7<@o@5Yn{F}6}XoKG00Ke{d8V-xihXSTr%Z)Fyg-O=yCGo zr`W!a204rh+%9g440X-i_lue`&*h8IOZt4`|EkK7mIzn__sZ1Z?$x{EG!}C+XTq}Z zAp)yDoKnb!aN=i_aa323{<~Ij)zne*26kbML;2#@F{$KoW2AUTPx7d<0AVHFecktf?^eYd~;ph=@8{J_`j0Y@ZaOeU{9DS@(m-b9Hv@$Dm(ZSGP%C z=sjI7=az&}rqJTKWvW*vcaZiCqiEYe*(_}lPO@1_ps&i>)2ZSTEU|z|S&C?FpAGKZ z$>0gDY*YtCWFDja`NJ}mHEk7%1{epr^3ZpA><{`Gv!stuIR>Fs@LzH^E{>RwCf{oY zv{*6vL+7ou=g8IEfUeq@y@QVp@4jpHfE`68F5eY&A;X4epG;n=vM!46t$yHQhTlKA zIKb9vja@h!MY)e0q33qEU1eg`%Xc!Ugl3uZ%!ha642M%+9QPoja6Mf?4K};(=kP*RqyKp&X zCgP|DVHljQTQHB6*^=!1bq7y*XZ7);M>pVXxM7&>OFCgzyzF zH=40Sq(d60VH(XN~=%{5o znu}zqg}!sf@1{aKQfhnV2O|;>q~WZr>9qe(pXWx5UyYhKe>-rv3}L4Og?*|?5pZow z`zQFKyV!~MN3xK|eh?OYx|2@C#z_faljv29-w=#0u}~yRxq<;)5RAQELE7b7|8gpc$B&A zmbThWIyH%&N%*Fu&&&3_&a8YfOI?Tl9CBzui#zXxOr{0KX-JeIjlO=sYu&QqV6R#O z2#o@W8W-7urxAgLM)~pM2LTFxpe<&KmyY;*bRk_J}}|qp|KZEh_>5^Kt1lMA8d>0XXT8k?_O43o|?BO zPRw2?i4-n5U*qLo+~Qhj2B)mZrZKHcyrR3@mp!gD^*-Z6m!(sN~u&*-svu3GGS{u*|B=7bBXK7dIucT(eQ{>wRDYCo~+NH9T-ZE?FK z4e3fBm5G5A3)w}8sP##b-F^1i;0ad`%-(ipu*{rE7I}92&7j0n$jUG1#iIkIUiU(m zMdpsNdmh)(osCgN&6=tb^in28Op%O}n3EYC5ZWxiQGfe?F4QI(SzGWpe9=pR?8K1D3U44h3YLZsbeQopD4EMt9+OOhxW&sedW>zU{=>6YCn&2(AS5g$N`)>jnjz zZeqp*4z6B1Fgm3Ln%-xS+^T@+U&VI7c6z2DDQ!#M=CFxzgP`YoUtK@vlrnFUM`%V; zbye}Yz5hO$u>p8Rdc>OdLwN!4{c4^~>Y|W(C{6gGB-b@>Agd}`)8HRs4E(8J}<{65u(I5>`MxG1`LjXB*XXA{LZC{qhGIhJ9wL~z@NcQ?+C ze}ADl_tCdZU>Z!^1z?RiKv|nwKj^m^A!s@;OLc*c2<%J2`!?+PaAx5802e*)O>%elPEhKTCiyWYAzzf&JM6C8ueV``B+2rv~Cs@b7aDfNe&=7ZIRx z$vWEcL78g-^SuE>Te5sHYzfLn%*=iY1_5|hL_;8H1*Bgg&*VNifj4tJg3-CCP z`1Flz-G+W+YNtz&Z}ubtHFy?CNJ~H2@|8Pmh#4Ka)WZ{V1>`O27J3Z6Z8~@1zXNa- zi>(Bu_&JAL^B-VSfvZMyY|q;JFoNlX&(*4;+kOl0w77>7J17zr9#9IZI5)T0&esqQ z4Gv<-^C4!}| zA9Y3CC=f&{mR5Mr={u9zdUie#MUfRNw!**JV5_dS_6FQH|3Y356$^wPLv+F7Bt9Lv zCBBj#FaQ2yiaKfc_m7w%sb=XXatYO4{PH5T&!08*7`zqs?G^=-A`Yv1jQJI;yH{G> z#YUcWx)qM&cS;+S$ETB)F;wI6tpb~Hj)r-8M=ZDPzkmP!aqdU-c6;AT~Bkn^0gCPp^TuefUz z+ioSuG1NV8PYVuZ860^Apx-)he8@cFa2xf8vauqB;#585-cOZEzcN2;bpANiz5ac^ zV$$f{5fURV7E|4-paK!ak9oa&!1Ccn`&*Xs-m#m9gL?hO{qNUM4)%QtMEU9iS`v{^ z*yaOnSPF~v)ECanGx^K;h2qQmAX<%p{BYDkV6fXs!?z^!0I@cUc9#F&_A#S8(tmX0oJ>2w0qVk4LwOSK>4Iar^?9ueiNz+E#A(;>2N8 z@Sv@d>ux9W;1I{SjqY0kq0RuCGIusEkb(axn(5_p`#Mr=gjAaR`)`cbF!kNeY<-~- z+Ni-{Qmx$l+a}+=Q{M-hI#17WB_4Kbqv* zyHp>A1JjWVpZ8mu<7Ku(-6o)x~^_P>^2V13NJ6a9izTwD>w8=`iJZ1uXT>w#k~$+GtAs zouCO|@_@&Q3C&03ZL)QbTm_s_g4O?ma|SL7^(D z!u+J4?=5o^@7yr&Y7cN_Bl)E3(K)Dp7(~|)J3Auz$Z{=9()uDQ;t)Ci&sgyyw@i2bZpi0_MBBF8$Q=>LJGQ zF)=H5SZM?>d!llO@VUY7Q?W3h}_EPRoKhICxP@Vy7=*lYz z{V}lu{=p1A=UsqA1b70|!e0t#9DIQ|=F~E6QURPON6X8j>j^QLjr8upGTjdNjVyJM zSrbmBvXD(gmeYDw;(^y-bLK|st{w2R8n{vRNB>y_Zg|hDw21uzyH+)D5R|yo$k-D? z89hu1F5PP=7M>gI&OufSVD#{1XpAn;2nS@&xO@Q=U&WkNaRY+T-z^=|wja?uN4FNI znvzbuUaf5GpRhK%IWdu=m_Jvb#CgX-A6+nntL5@u&w1aZ*WzIf)3~b&Nz1zzdE|52 zaHQl*TZQYsRvwQo^_gh)cz`ar62g{!>R!N@$inLjQa9M`K7_s>W?yPqHJ#nnphokk z%T53L$Xv})MPXih8=m(~EC9daEXW;WF1{Zbs6j~Z1k=869hJ$~3cMGNjR%23kj$by zi#b!0Z179@nbuVk?!0y}30+GPSrW&7MtUj8sbVlKF;TF#F-L@+zgicCqC%o3KH;fR^ z7*?!fKEs*?RexWP<3fI~#mlVTvHg9i{nbz3lF6t@zeblY`^_;fJN?s~cA4svrQjITX+V^RiT;t5#%Z-l)1Z z71KRJ(tjDTYaXkGDd}L4R=2b72Wm;Cg&D^U(IgumFSGkSX8yrs*^95l2L?Cl>$);W zN>ebE8j?nAwNrG(f?Ph&-ZlGj$Ywd_&DzXNYq>USi(PCyEr0vEo|5ja zZI2(#JDn{e)U#~a^oM0Nem}C``n**u^mq|hxYbpqtL2NW3x8GYt&v-rU5XxGR9*zG z`l44i%5wh|0inX#&$jfx@(UJXn`FB7L00Y|lw$uFaj`-@YC7lj zQ^A2|ynK8r#p+I?EO1xYA_hU*qDFAaKcutrozksbslT@&Yq=70iChi{T?^sVAggVv zZP;O?WxEQhl3xmmI_8#pi`_e`wrnMWACQ$s1AHHSSx&SH#kMZ&HvxFa4Sa9RXSZBU z*3tH8{2&89)O~AXgugQgWz%T-?0d0hF0U@jYcnh^l03dx|2AX{?8-J$#P9g^?BPUi z`BQ-IHlln*B@t`?l!(e*lB@dkTQZF@;D5T6MPu;l3F`&Tq5FW;55u&r30r(Vo9qv- zk6dljdhtwUpTniJB5V5x#pmCGSj%;*>YmK)40k{Kt@XAq*{4>nh2_{=z?*$ylRu1wblTAdhmU<3LDzL#6C=WCQBHFv2`-4%p65pxf?B5T zw@5N;n&)52NIM&?=J~0UEikj?kzl1?Jv$DZjo#|@1Ao7dwVXAE;u1T^+8ez+=H+|y z0ikY#3vgB3&g(^5I)ahGnN=M6wsR$NWl!1!eK~P4D$4O%yzic?TBeEz5AJ_{uEloA zH^sTH7tfM^9I_YrBK%U#ynS3JY%6>Be351y*kemi82ksaV8mr=Ez1Vi zO{yx>8K6G>4~;FUm7uh(&IS1J1pI?73g+ADb1u}}cyv%={L|XBi7-=^w%!H@%)q=r z=roftINvN=exc@w=~}DM)_hj}Cty2iDUF#)6?~%EK629>Sh~ z=E`@!aPd>|R_45U&dAECBdZ+pf$+AP^r*t;u+=*{`vnVj8utOcJNWE9Xc;%*lv>ku zOYBzxYj@vF&8GKSm%@w)3=6`U$Lxd9I5%Ny=!pH%vU#kJc-t%V4HnM{NujP?OH1>n zX8Nr>Ab37&Dz!`{nGhMOyV_EQfSQqa-peH()!!$7cVF|Wt@)o21XM57Rl6Yn9!R&O zA506lKgWt)DXwBY3+&^@=%S3E^>8k|;Z>pUI#;4dw#Vk=^SpL;r)wv`<=etT94zxe zSITn>!L2*VRdcVH5LO8X=i@YZz}~g-W-H4m>MUrxEV!W>@iES15PB4@SYsVHkn&4<#4YY{Tyo~kTAIqY^uZ%<`pSy zJtA=I?B6H$)<)~j1-r$N44vS{`Zv)S(BKWTS7p&j+L*CzpKj3uSAHsjj-RYvIzn0c{RCETBt2ZO2l%!oH^YDfOY zo6*hNiLOQ4E5P*jsX>$%@@C0J!qRC~%br=0bk*y7bbX2tkJib4eXoYa=c;a>`qiAd zH$jkeeOF?F`NzRntpx1$;j%9-2Pt}AXP9Su?%KgndJFT9lASmN4VQfY;b;?XR{Ogr zY{dR3B!O_9`tV{7dOZ!@i^|iJ`|U2i&mne7gHs!p)A(yVjQNIZZ(Rf)cSSW;=1frI zQ^j;|1^Qw&R&TxF4zHy)vv*ErU;M2DvDE9T#WK_2-+8C%>p^UA2Cvql^SjFOgLs~6 z&r5T~PPmrHytA>pDN_tf%eR=u2zx}Mfl}iu`=KltacVkF{ArfK6{GkvmB*jXS~=cA z6ks=?ZgG}-NH1!bOQhYvV{hISuJMt*k1Tex@&8(GJL^)kzckn+Om)e71BS1Nwwn@9 z0I~+1d#LnU+Y3#suzQV>N%rwgsO=cx-jGS&s~P(*BVGwl2o7FPIg`HoMJ&UQfjWfO zl^wsx@h`m+&Mb3)=XA65nQK9Z&Ckrt{N!0)xP)7zP(x?nz&x}1 zmJ1zOLDgelo}^ZZ!S+Gska*lZkkz}QVfH9hsWHfRg0qM83apXAZR@a)u?aEo2G$06 zK^3MFRLi)=1Lw;yIzw7_z3uP&s@U|4>+9L+xc=7tsC4Kecx?jMMc z-nz*=)Z#B$fLjt|0Yt=`7#Nzm%+i>(AGq50tIQU{zf3~wc%&j)`cGCH_le{g>*)0- z*&i~U*AL4vyvyvC((m8C#fm?Bl4?J1T#a#BBKeIe4IlvZm>h7d;II{oup&}I}ya9%`@i?z?YYa3CqQpnBKbiTwZ5cZ2iCL_`xe7+2|{Z z)mxad&F~p}%CPjJge+fNV@yF~3R2fcfM)4%+xXQ3^J( zaT89g-kYfxtk#Fk+kxKF^Vqf4B_#9(8u@;Gz{SHTE9!YIO8pD>p$4lDJ@so~R^H_T z#+@>DU^?HNVNh}MZ#@#o$ttldUC}Ia;W8E$mWv4qiw;_XCw@S94Q#DyUJ1wtkf531 zBBWA>d-euve5|MO>FKhX_SC%yg9drErY8LD&XqrMM~b!SWhv7=k4dJA#550+<@XULjo4R*$|Hu+I3yVbG9(|r5b z=cE@Rq-9C`DFPnMsy_GmZ#=_4z}U*IKYa3rQbkr%jvYIOLb&U)F|aqoW2H`vr@NvR z+%ar&eTC$oT8pa15?Pb=s1|F*x;Bm96E?|ca`!PjX_ek4yhp#i_Td7FtGgW>B$Rfm zj%4Azx7}S;8DhXzlYU!ZY|HrvP;u^*OqX50n@(NdbKrE~Md_C|YHMoF%O>ur1Jy+K zpds&C{L34_<0@w#f5|y;DY$K;Vf3>5C_?(Q10Tjz}OSefNT~5zbGh zUuLHoT;jgBwj2E_x8wlU)V+Zktou_C3e{m0)>3<|RgE;60xrIC)G{rb)5qP2rNl0P zfX8+$+x3=>pInM?dxA+F4wN{{_m0Uq`> zMejUPSW8vf*kQUdeKi{;y)ny$`;Cd=J@;l-LK{R`X|^XCZAj#$X&1Y_yW#dJBQ=1e*mcMW=keGvyZ??P`_ z3fJ{Sk}?g|j^v|g{HWE#?p3*iRouEAoaP)tLEBuRg7R(Kz~uqivT2NG6gQ`;&Fz`* z;=QXYsl#@$0z(l~rX`+cwORv9a+hVg?|6{5hiHa&~XXJR1rL^PPn z%Vc`HK5OR7CQ!-x;0;wVo0i8j4{dkPcU|vZP&}VSFBj{Ri(W1)Z8k`>bv9q)A%&wnZ(Vl{wI^49zVI zq4c8TbU&D`KUTCh+{gcJkNiA}=C6SxSg-KhG+&RyL((X=`&V<4=vi0F%kw2rLhprc zW<$~DWp>Q|Qi(QgdEFYhaadR|Ob9cFzKdedB30xiAqy!>+}sa*U}YqGh|>W(L^N)p z8RL`royyI;YJb~agaOafuOMaWDkMM#o|tBjMmc`(fyazoLL&e5++dkBA$9K>SgBU` zt!w`1{Ildq>e0;-@im;+!*F*mynJuLModf6IJ08zo2E^}2Em>dxz|zL8=SxLSU|DU z^UmMC7yAshY9ydvaHSE3j~66aF*3^O&Z5sFmu&UkR30j^k0|!-0q85N43bX{K=V`k z`shh94A04Cdo1bs#C`}=?NlK>M%Zy>GCd%)a!+I*YT+TnKJ5{Vh%6Bllcqj=0>{AK z`YwU914xCmX}FQXWuaA*)CK&B2%Ge|^n!xMG|oJLR@If2H<1Y*#lA-tz#M7cb2A_P zJq-^p0xd0951-B%g0>^BLHi)HiM+L5|JbQvk=15z$1Vw^f3$^{fW?XLOJxc;4Ib{zK1SqyUJtbahoQW4&^tjEvXxztvLmYRm!FeTM(g zMk^l4Gr@MukaF$--MK)vh3IBsAow#V@Y0L}q?pzdsCl7h>Ky*sGl5{ok2ONC*zwO` zNKZxj2?aL~SVYt(^Wywj^OlM9?|Lc92+B8+T*4(Djr=VOwk*y$^u<BydOkhu=lct>-5)r$M?br~h)XZcwok=U!H#AQMw#PLmnA; z;;YX)+iNNC+)*AsbCMt-hh(-O6^Rs;0XuWSrn%f(PG=eLOzGny0Lb!WuS8LBOX zgugm`>*C$y%sNxZTxlHS)ibJXZ~)i`@%*mZojb7Nhh8&m2qWCj?|WC}nsyZK-MKi~ zoPJ(C`B8<&Wv}s=vIAsRmrRuD)BhzWBjcW)7gdjf(HU=Z$YSs)j|r~r5nqR`%1b3~ zXB;lz|04a)M)RjkQ{MJ#u!7>#i2abv>Lhg*{Xs!#%Dz{anVtH(bA>vMWpJVxRcosD z@W61&qVXqWP0Y0C(Mu$(K;_xrN1i7?5ai+o38~do`b5NJfZT^ zj*=Vd_C8OT%EoC~lalRJ|48gW!Aa}!s8D{M?j0qc#jL;&xdD2A{i377oCD{|VCkI+ zQ<*iVqKz3Z|9VLoMC5xNV-FnfeS~pXV@miM%O7)8rqh2YEBG3yq%P2nem*`qksw!J|{14dqS#N!vl?$G& zffV~ky3J@i6CP8;jf?fq4$2MYOs3On9&&2TOEcK|eg|mJ8>pGH7F3vRLp>o=cVMRk zi%GdnsDIuOoxF>PDsrFGpc9es`#7+H_Uo6wthBV-{p(|4{G2tM8)h=eE5rg&j0jl? zOUhm-l2i?1ROtQZm9#RULoGXSybnE_K-G5#v;=iS(`c^}W|P(}BL!OWP#Nd-CZ2C~ zW@R?qj$=uzcAH_)(X*yJJ8(!ATBGlWR~a(8<6vqNJ5gquhOB?#U^?$O<78763Bs1T zYS$lP5o;sn&vESKD4DYQ%65Idt{7Yjr=dl?#--uZ7IGUGI#?d^Y)I;SbJaMm3b-Az z*D_Lld)c%#QKmDaJTznn$_4Bi@x%MDVd@Ub1n*TwU|KQKLKR2%iu0!iv{&)9r4bs4 zTE`^5lrD|@&i8ILBYlt`CQAfI`tt!VtX9^>_}S!L#I4+1gA1NRSNBkrn9q}fAh&$} zQfn&u#_m!q1?nZ86dFHk5!0QvDCg@lx79_?%3kWadcBkt+^KH`i{wJn@PKqE99*G$^(e>rwRJLvR*=svcT^l{$ z_Z`RYpZ9nUd28?czOHjv=UVI3ePP7elVy-oK4)wz!jFu4Kd;jX`XSvP40>GZWyd=` z4@YNoCrnnra&twa-p=%^6vtj5M^wLgiX`S}G$M8B( z&u~qORom%YsvN2`U3hn>vI$5>Y;%7gJ>=KFx~F0@Kg%T6V-r5v$R~&8Qd8lSRyIN@ z{FQ|+UFX|T6{1dz^kOh`^mGG01TDuKqJ*Rl@#`6iAH*t}O_nh;XU!GSSM;mGY6lyX z-RT24){U?9d1yOD)F{rz#Q96d`-%Bo6f{~YBc3y7&$4K$VrLy4HWzGruz?xC8eb4l ztI@;x@KET2HIKFnoV{$_JBxnefYxO8B1dh|gBXEovO7MCV1)DmSeYHaf;t)Kc@gN1 z($|0g`^!PASui^M;w2l`9kjv-r2C;U0+PwH=Oesog{Vx_CCtjC=5%&-9R^_9V=c4r z3!p&(mw$#W;98#rf#Lm?>WNQ|8jqZfY=yar6>vvdnEyO<$9-UzZls?=H&6RTwtMA4 z@>4XgaPSe=UT$Z=3mrg-qDHQ4W+%PJ4cR`?ds(61mw2G-yh^zU8y5| zRPbuIFZ4~K)cPjmJIm4ta`xjnk6uC$T*BdLM%8cF{^G@pT;L}kE_n>F54l(aMN9JbsSOt_gKk-=_h84U^b2Z`_#k{y z8u5d!#aiyk>_xa#gV7$0wSIYz_v@D~DcLkr^jrK4fBzCE`sKgTKzwJvzk^w5+?O^1!1b>IhMY>_3ANP$tV=qrq} z(L(BR&X^d@z9=SLFbizShO-~^)%%$uDN9}yzFV4xomh|6Ju*;3-`P2HWDGqL+>rbY zzrPw-MK|npq<5@2XR!A(9M-aK9dS;r+MJK=Qp67c)wGuMf|dR>2kJQ9RTDs%k6+$n z#+8F^PB+==rOFIXDu;D*-iw^;()M}O(^G_33i*6Mw%wZ*pG(WlbHZ^6ud;&B?IiD@yaTsmPT(CcYu}E zIXb-4Wj28J=(#7JPM!oD2g=G!*HMPfx>#mX7 zkHOkj!VG>MxgUaOaI-dDS6Y^RfXiDJ9&hdiCA;Yr z6$u73@3U{uDc0+GekFzY5GmP8GPY&^E!m{RV=WZ{i6qS_wPczfM%`sUs_n48bw;h9 z+hR0rK-z~D5#T>T;cVBH6&Ux&tyjDpK)xSSbO;?|JmT6il% zC`)CIx!u3u{aO1hksD>PXGKJg196vFFN)q@7P(!O*S=UqoHU5nD*~n zN4V&avZbyk0_QMf!B6mJY|tU3^Z#%JMfuKoAF^eDQ$S&CsBW*~nq3>|t)TZf?5Ifk zesoSSJ-6i8<4ddU=X?@3I~X$mEpTEB#{iJXZ*I|1yiK6@f(qJnUp1XWL~i0tW_kVm zZw;@JGa_MVhn0H1VU!XERrbnWARbV5IHoUDq#$ zVUxqB`r2Y#;+*v|f^y?K5W?nTms^#ctnW8S7T_pJX zlLnu8JbTXDgE3@DXzyGHIK(tzYbV8Z-}2g|q5r`&V@)6MHM<#4!loDBiD;{^iEoqQ zTz60MR|c{>y*H$eXYc`jtF3hRu0sx<7cNlr?(I8Q;vLk2yL|Y^cBS)4LCrl48T$?t z`DF0MsVrC}C3O!ov$U37CD?P_w5IU0CkRv9HcTNrvJn`%N zLpkPwKd|tjp6oj6gIeZFm-bM|O3DdWw^wEyeLsQzdQQwK9&WN4hTG&@*eRU?p_84< z`kdWg3cw`vqN{=8TEounugm@Q2V}A6I;Dm4PBX33Y>L66i+&(iwRI55W%f8<@)$K& zu>!L3y_H!4Hee;LqZiM$7a#F6uw6tkqqUbt$PZ%H&B7{B+>I{S4Q)paPi}%2$7! z^x}<#fN=cGnKJ}?IY>J7g^zko+J&g5Ow?0a16+PmWtLXWTEd) zUYf`e3Y0HdAhi-!+--(_5yM8}Yn0`yuYAeE)G83I%^?7D*#CKeG_}~lUbd5>VXb$; z#dH*Y^v9w7&+!ozpTCU*C5U3oEzu?P<}uqJmth_VD*9u zs5GqsNhbcTHE}IzPh76Oh)uv-yMEX_=2}YAkwxlP{|8ZZ`m;;nv%5TrRQS8yog=sm zug)5=B@d53=p20IAEuUT;e5WroBHmDrcc}!jFpF2s$>rEI-v4;VBoveZU=%~R2VaT z8<)?9--jk!Nix~)XoC(k@v04+#`mJ3g-7p_Y;KGtJfCykF)VmR+R!cP?v7tllMklL zU)?>!(~EPJr;?&#bI3C{5W<__niiF5*R2prk(wJq;Or&;^M7Kl+WL{s){&OSosnI@`R_4AgzJh1rV@f5>aP^dOTp= z*ob8ioXaQzg0Yq^-l+;ao>H7d-SyHetS7xFU8Cy^-&8vwrbVls3Ew-Hh8cweDe)Fl z^%$QdUYV#vH<{?NDv-g;9zx|HqO_@N1!!7wb7x`xptVjE#mcxe$OIX)K$oL!x);)s zo`Koq6H}-$(>5R)f3kDiLMz=zkJ>G;*a9EWhiCc#DzQ)NaEs{Jn@he;R`CIGS?0fj+ z=rbB;%ADSv+)AccUK%1V>l(fJYdQbS4XP_AU886`R7|x_qurF*5CWJ^A8eota!Q|A zZ>-}OK^xB7ar|vfQ_?+xxI?^Br~!Urq8s6a20hTh)?=H6J!$Cfgi`*kG<`1;OC5mm zTneX9TtE7NyTFC)7QR?wx~mV4eBsY2xw8 zH>q~2Ys263O4X*-H-?-IgvE@;j)3|vSY^&^63UrVl=bPw2ye<|(iu5e z`?P+H7P^)qBtR_5Tz`GMl^Cz%@DQbg^Lmp<-|m%>gAV7>kpag?36@2-G6b`JZKn-H z3`I-b!)ovroaIU_UAOy}%UL9X>l-Oju}LG30G#+=6_M8mH7AejAJDvvT zZ@HOGtCJ#R4AjZ8ArS z->UF3+tQ!gucz`!#x`^i+dbq-6;YqK(|A>09?X#=ZofXJ%MUq{^|;ct{63-{w0J7m zV6B?LUc7Cy<}EePKKVl9b>`3#ThGB(UNG~u>W4jyPbb|v01j!UDRk z>l7*zRsv2qaulF4iu3~#JgwXf{VGz{x6S@-5#BfUV>waWi##Lg_Sctn(=OF&(rn@j zFbH~c_QvvqY1k!t<8`{F0tTefU{*HcC<@o7?`%TVy2 z5I#S+{k7Jb`yG@b)F5e_W=wMlXol3GaXoLF;Me^>Tz=Vw$wjdqhtqC+iE6_+l)r=u z=E~TJInK6+LA1%f238xitqV zJ4BYTlbzLs`(mh53VYDLtBU<C4nY3zYO?mNmyZ8)%L5kYoP z!h-_x9&AcC2R^Rbgi4;)5wvH`+Obm{r?Enza18BvdRgOAJW5}|`+a%MkzUW9C5^5! z&{k(PAA?tkan@dXQ?8!Cclap25`d(a`Jz-cJXZUgkZ4w z0y~#s<@~@EU`#iFF-_w;^5=86}t{|utWJ(Pv|m_q*92njzFe?&gj2hP;%VlCxgrbVEE&D^B7(hCz0 zBy!Es=JxS}QfFoUTsyev?X~YKSThfE3XCUGZ!;b-Wqo&*xfF|{(w^N7-?0g%{tF#y0DL!ZXfV9d z;<4~=_ML<}L=tfgl7nL&PK}{N`q<}1=>X@@tnA?3XdoI2{kOtXx#$7;L# z2>o3up0q#2R^^M>(mpJg=`P0l0kP}lF=0Y8MFue}YJ`#&^4+XUwKNtF^$J&+l`n%kwLd@DE;@@8%z=FOcJrIeeU#` zU}sGbo@Id1l_0`*iG}!LzJsLxPD);N`chmeg9>5wwr%Z=!}n39J@Ad7@p9b5+28)4 zuAWV$vS5;N8^Gd=0$?Zl4}-IKC-r)kQ=vTohiq_h*Rq1gWxgq zB>Z#KB;8+f!D$bkuf9`+1=DwL;A;fLY6ibB3ON<4iJkK9G5vJ8s|xQqir_r38Wi8k z{cEROK)YpP&E5h9byyBf<*leEb)$(7dkOsIg<3OO&S1-5qYtSynOMF=1|8ki+C4RK z7l|_FeUvSn0L9Q!40~n1lB9(2O%n-TZw3bRrqIEP@KO?g`;9zguFUYZh-2ErsEHw% zTFY~JCHBi4jF3Ba;roMq88=1;O4~8epib|JEZA~ftC;Wjd*Ga-C6w@W2``fF{Q?-u>&tY1nvqqD@wMJ8&

    0KPy4;#vL$j1(Lf^L z=2hO5>oomMFLp{;DcaNb=+U2;Zj@0&Hx`mQ$I(gWn}5(zbBcnj8sNa3C$tq=u!avIo;1;EzIUyJrey0xvevS$ zGxJAYUS!mVag!J0p~nvJ%Nm4>ji3zWa1}6COwt!ccuwQ8eUQ;`{~Ox`sJa4{!0yuJ z)lX$mRwj!e7T{OrYB+M}Zl_iDX~@Cd;%I>xs+#81H`r(VSSsMaFC9Q}cVlDA983ta z5kdz5gZqDJZC+u^YJQ-?FJk`jS;_pe8|xxYY~R(9zLlRPWmL;6iy0r1KogZ|^%gcl zk4_bKCz<*@c4B=XJ09(i!x-?Y_E{k4GhoVGacq9!6qfGk$3eUYFh1A$qRm)$_wv#T z*4@@61pza~?ysZo^%+E)@fOU>sA&4R-E_0FJBjC9DpUhXx#Iy>X==2?K^f4;?4Y;M zIg60~4x;e)qTGZ_E>e_^di2dU3ds4TQI;2K8J`0+r_l90Z1fwtWHLPY?8>)yV62i$ zFfixefMok5w*69Hx;vJOgfUND4&pdIjN%~A)Er1&^(Y3f38G7%P7yk6Si%^TA(9*1 zTQ3UB9i=se%h|F1ujS+nDjatHFOG;4ItL7nqvkju#wi*fbcYfkJ!-~u&&a1|#0h}d-uh09Zpp#?(yO-O(bb`CK5Y6Wqni@l;LHmWg9I}rn*ctQ6YbHGwIa3iwmlMSu1S14Ep1W_D$aI&eL2Q4L1bV?5cmpLp zLXQn|$1#v%Q!XKr)R%qGrSh$g{nA$$mhNr(F?W}qT{~>!APik)$$`L~GANo)J##K) zv|~*YJ!F_%9W(+T)|JQtVJ?D+h|*al4oqgHqzAEMh?HxGzO1LO8inlnP-D6RR?)p* zRRgC`NQ`!-3RNq7m^%tq)q90GM!$?a9`U)AUYH~nbXa+IwDEoWabh_PuBBorvQk5Q zjX4)BaYLk<{;8NGL166~Btzxp+y90UcqF`YBQ_=pMcOM0?%H2kdc{Kz72e465RrM* z=YrZ#7ScPn;-nR5G858eszQ2&2J&E?BMml>Lz>0|*WW|FBep|bn1N~R#a8=q*h8vb zSpz3eqDbtDJacvSZ3!$kO$jK&Ak%E1WF)#L*xX$&%x$wE_Vula9XW=B?&u(gL5T}o zkeF?2&1PxPxOf+=K6Dfqh=cM1$S$R|zaL*W{h3KRJ3t%RhW^l{foJ}?JqcS}$?5AR zMcnTrF06z{A`B-_&CYvZr5uK@ciITZ3W}9B;L)g+Jv$2plP?(p?Y}qVPdm>Z{PqEs zz5>EolmB5C-LBy$;ZC)7T(c&-%>`u)${imKeUc2KdhOlp;Exq7V_J7UPIsXjjm*yg^6={v5hUpDGel^t~IZ|L1TVFc1sqIh%{+4>~gqfM5uR^gN z_v?=**IBH-4%)JAuo52Bt3#ftli%gKf+zU%5ezx*)4fN+6;88)=_^7$I{V;v6|C`C z58%CMtYshbPl9FN?}2;aLO}%3hSX!>ExT?k5)A@0;bI@Th~3j^PKtA(kojpyoh|b< zHWFQkWVb@}-hr90=Rc|u>1&NS8nHotaz^3zHxJseV{td$rjJ~x4G&6$_2el+Rh=C# z4!*fCtV}13}@8CtNDtB<+jopC408!S()Gp&Y{tpH7@-&==SQoSRX2rvk}KQrL)3u!h}D+q+O>n9 zCb>{NtjF<;XgJ@=U=Bu1uJ`Rg z{LiYZuNizkUgp6@lJw7icI{)GYztYuoTgIhjOpTlIfqOh0AcE#%4N7-Zun;izL#`| zg)cFlm`|8>@43nbIdpYs^cIvdRwyR5_BCxMD_iS(bN|%crf1YHLMNStG_5VLF79__ z_j#1z8_#{~T(>|$DsBv8tt?{QEg`ad64(-X!LFt7jyei&9Jm)h z+OYbxkyJeSSI*;G77fTQ=b!$Trd))N3yVMj2k8%khlV^fef#bl*f%U-vh{y7pSqkW z@r8nksq2o%J094d_>=Uhd_5};BRa@z+O&y2H(<$ZHlt>|u#mE8)m$9JjrP7F@3uptlLzc1moTmHe)BBP1;d=+1c$K_PZ@{r1LhZ;_N|L5!x?A|cJf@ble z^Fkp%y+i_p25a*-k`2Mk{=MHb zJf!AdStOsN>-`oM0F8iD_#Vi6xYu7^%KC<$x0q-u8nt;v&rsqlD1wponpoAi?5CPLb!?;*L>T38-ndC*v}3O) zxSEX!yBh4t6kC+8-%pn9V)@6y^)aZ~^;{#z)N!H)Ehk&wk{6pDJ9ez#ard!MzSkIB z+z7~Ah{;aSYQ(9ahl}QU&Y$!7QZe(cRmIIgpjj61B3er~%&^wkafQ!HG=gysj>Fva z2hv<$vOYjlcp4;?D@L{t*@gTAY$u;Na8>vPux$gLm3k3m_g(^>+0GwY(VhPxtPDNT|pPu_uxr&T*PJ;?Y< z3YjB8L(_{}Jo(!l!t)JdIpwt5tU$UDx-k(2K7G%sYpVzH?sI>U1nh1v7~E)LC@ zH0cV{57ToQbeA}CNO29hhku-4aCmW%l+u{{aqyT@$i(To;g3l3sq5YVX1779`|=kA zK1t(mza~D9RNrieHveUAJgJXssY5&?@GZ1+?ZG(h9!{Vq>L_(VB7MI-9-%9~y}w!P zmxU z(iU|Kz)hZ!n{ME^OwR9VA|=F({-fAqFUINp2a4PV^zvnhx28}$7#8(?e&6|5YeSbt zXv8b7Dm*$>{PijI+U^mQ9ja`7Lw2Km`9(W~AtF#wjG9K;))nxFvmzJS^%sW_#_ZRIl6Bi}?L`nxd*xV0-{$a%9|^Ljof5bv<^_nf%=RZVMd*PXtOzl$@(oci97 zeKU=c$&o?34`>QZRjHFlcJLa`?|8vM7L$~uR7pMp77^4O;vqw3;U2$7$6yMjMu1ZF zS!N2oqDkNz z>_>Z(w~eL7B<;8ZvMO!F%6Yg~|3Ik7`Z!2l8;A6--c+U-gc`iLaEat*#OJ!%7sEua z@1~$`wM}&&ZSvk5^KoY%^mh4xA>aOL$MAMbk>XNt>wZmuAlwYZa$tTAZW*an|Nf8D z9!v~R8*#Hr9`bFu=UjjL>7oA)H4d@;DA~nKP2)%dQ6s1*PlxEi)grp$0I* z#-NuMo|@ZWJqe>~ZN&@{p%wm`O{_mO_c0e0s!+lJC8`Iq4sOFwkQyyAioa=mn`u%W z%#p&E&3BM~ck{h&C1?1m9^hL5Z9C0`z0GaZW)!Wo#w=e=Yv2!=P#W01G?AcN7y}r! zsJJ$$();@t3rIor!M9{}$yAD;{%-%5jzv{Dio2W#xS)$|6$x3Z_K|U~Fd6K41jR3q zG3ZaL)sGP+psn<|8NcM2p;%y_&%8umW7XE7K#CRn$y>Lo_4g3c0ay zLUPDDrc$zGb9J(Yf1WTny|+Pg%=s2&3u)b7xO5f#@M~Ory}1^I3%>9U&)YBnuj&xy zgYIL+1|X|TE#s0XSM7jpVKzp9H_s+XxfA19dZVoJidwkd{M3(yu*(hWVG5ICmx&O1 z-L`#K-trDcl@UgiB8EOjcH8j3`yCGrwo*A2l4w6o>YiQHKfm|}q+WxGWl-N*qe>Ic zvTB&+s?5EiFX?vm$9H?%8%A>wNxL#u@VB6q)Y74BolYxLIiqX|${d#uTX?3*WDYTP zQfWXnt9Kw!N5B9Tm5TUFv0w6Y|6{iDsug=MU1U*>VT16y#dpy5XtCEm*S%~AECILU zB@VM@b9~(ai9tvJn(?)*$h7nyVdY{CE`b9Ju*$@PwvLLS)hXC-*!`1OTGV^*-ymKJ z7ApVOoqcdsn9@3Uz21n} zU?nJ^67w#j;L~C*nbi&1Y~lrJM4W*MGrJ;~ICWgXjgy7Y^d%Jnc-ne+JM%a05RjJw#e>_dofQVjh=LO>YG-3Vq4IgEt}$f@Ly2y%Fk$iORYar&|kiq1)L# z_CRWaX>XW=>~dO%-H8Q@dW=wm4{ZRtu6J~S(b+%}%!u%wha;0%aYpT`c$VZs1DZK+ zuqw1R>n_vYQ{M-*q&vKrC_47Hn&KJEqvhQ7J7aGj z`J4$h|2M|qF327w2`NIncdnnuX{v6Co zr?}r06%w+dx9k^IQn^Bd&M5Vvra?bJ_Qb3Zin z*X;!SI)MXpN&2R{boJajmP}uNk7!o16w4p&w&azjr1EM%QRthO4QO%Q%oLsEs}9)K zOuu5p*$^jFzf;1e?RJi3y`QC>U10*VV>6_K$wA4?pW zk6yskntFVnut$LP14tAJFD1xFDnON!3Fe3jV%XFT+CWkh0c57uGLF>OAIe`Oyy9SdQ`77rl_an;)j?#3fJ`X%Y@tYUa|(z~=b{!r3E6 z+h0!8*V{Q)vDv_V@ulFC^Y@2aKdv}R4I<;@SCxx+*xKhzd3ETW{KKRsGv6^gh1%c| zO$@?*NsB-12}S(-_2!|Kr?mcd-#&t`m@|bEs3Yh~&dKP$2b>|yX-F7Y&ufyS7~!qh zG^QNR9w*x2?um|Fam49S^FFt4{CbayCd{5=)dche0!}bsi&|Fq8s$cpt`D6MhX|pV zerZ2%Bp6OxT$$bSMSRWmu%EY(Eg1?Tg(tl~hJW%qbKLWoQ`zlkVOm$xhw5YYxi6Cj z8zSoDu5yMSn~G)ViMEQ_9{T9Cbv}2TlL6w_K4YN^JIl^c3R5#Q;^KVzYAL$)w)7L+ z8|aaTQMGOW#Sk#Co~7d1>b;p4*ixSxt*Uj0?>htD^z^~12_++JI z4Fo@1xAWL)l48+2u?9=1(<-}-RIG^S;JP5b=8%pfQA9=73|zT)@K~$dny8L+_F7@r zp}_A&f8n%5c6e^|wLHFJ4UD$SQ9@Rb`bx{A(?6%EQ$1V`b>oGT3nvpfk6JNpRTjC+32o^VT_R$fBL=$)5j4(PAt%fyIWpfe&)qa@6KVE4YWa;V<7cw`O;9a z*JZ^mp&W=A+9B2GZ$cIyu8$wM|KVzI`QuoQgxh6krS4*Mnx5Kj|F6t&MEjqW%hV~` zx?)Sr=KWzmeu3b1MUfW!?N`Mash^D#8-o8-)zvLuQY^0ymL^*T465vZ7xMxP#M2lE z98p&pxj$D;V)C|AX|yLsELS1*DcEaAYdLM3`d02RiSaWKxx~jaenSV8X7v_jGN4gzQ^Y3O5{(#X(0z~@Y~eh z1$V(}{&ywJ*%251S*!$0KTk1EvQ855@6v(W%g$7--FWPgmzYYK9QG4?TO)Lx-EKaz zfc`y^eGjQ@&bhZ1oG~-2SV0;h;|_F@S*YP&hNTDw`Y_ZK$@ClYoomu%7{pp*6si@o zXwjlXhHeqo$@XC(qhF8Hlwlq?v^z?ZA9uws+oxL+g$5Mgo#sFoAL$}pQ>7|RgFRmS zYCV>P1ZU1q_>wHCa?+Oi$`Cd8dUrNCS1J?UqE5_>dIw<`RU2iy{It_2}-b>JZ$s7zMp^xBTsVZkbXOQ6ts>12?zl-bsXp?jU^V<-1$ zBHjH*XzP8`uO?0xipE{YuAwNxuw~`vLC_XP-+Xr(J93b1!PugK_F5;_7fr}OPt@(w z7dAy(c(6d>?C0yCP*$O^>JQ%oh{R!_Evj#at9wWo2E~LQ{-eQz1F$(+xnce5+sCAl zHMQZ4XyQOiB-8^sGQQjBm3>%;aIXYx_7hv+T-&`7yu`K@vp$79-NmC8Rfg1Sjp{~9 zfQD5<*1&{Px%>io)#N=Jj<~$IGE8f-_6+30Ih-PB+mL2}P8cWu` zZHR76OeVzKy+yXGj%nGzXiGdMnbd7&U2k^f0M%(EO@OYiUY(f(wC|Gp_mw*4=y3m^ z(iMOYB3@hQG+Ri7jZ*lq7>w1frwskQ>Lx@ITlSeuv${$1yv4}olOJjV5-f@x_iwm= z57q|hFor9v8jy}t9a|6as-5T4)Gkwr{4|YG7!B{;mi@0KMx*+#srME3hMmG&d_e^O z|8aHRywe&v;mWSg;p%cmRMfeMd2eOizH;f!0M~1S%*HtOog(1+AbG`WU2<`Mc>ie? z#Z%3b_)d3bw?got5yZOTz+6x4c$g#o3=vL)LE+kGOSV(FV#@vo3^}i-w63XBFkPyh zgeF013OHv&Zp+%EPA$w@b~iQLFK^|k+Ia7QPrJ)lBa@)!634xmla$U`m1V@)uc3YI z4aPv9bz=hF1lQay7s|zr*9Sjn>x=7Eos5Du_lYrLrg`&M+aPw@-6I%e-AO8Hqj5gO zHbu>PrN|=ox%QX9;-?QvpqIuy-?Ihf(^|22@(q07y)Ig0y%!!I^a-+q8fVY=D0Hd$P(diY zTPydsA7g#>>-~7y$)nO9zb0=vtfdLgRA7Ii@}ItEgLHN5;8^nphKDgP0&G##OiN7{ zP{!wzdm;Hwqxp^?_w2PZW{AvC-?d%WCm($JEr-*3N;I8x-sfFy$91eUCWH{eF?`4U zwj?R=PA5Zr3wF3Sh8$h|?RstK+T*==6yF!~egz$+njI@cP6IEH-rx`6_*>$6_C1VO z8MDREEe=c~lol97hIY-WyW*apBixNSW8|o(v+UhZJ|mA)^;S@*e6oWzJGmQSkr(9| zeD(p1#OD071&)10gdBC8G^eAZ?Gs1r+X%ZPc}roqGPe(7+i2}IH&ax|7T&+FRcyy7 zIU90cMWfWvtIBCzotCPvKIXERtJip~Fe^%Ks+Y7|r<=9rkIRt^ z-LQa8hKzGDYF=yPiT%bD=Y1&(Xkxl5ZgH%|I-&~poXnF%rW0?CWlDs=D0D4ykcZ={ zhhV1C&yI`foEBe~j9j{KCTgdAWB%!w?9V!iTP*jRLrgWevNC{pB{3G(&11%SOEm4> zqyG8hhGl7I&ZZN`yrYnJIE)`|*Qq}%b8u43D|srO@r|8=owO@yDqxE0Acb-cE**(frXG-(`_N`r>8THP8t z-lU0@YUOxp7QhFTT+eaLV>9N0wXQx$OgAELKkut;!jZBD*=v7k@|=edMSM@#9)F`b zgd>hwxh~)h8Fc6*X{tZJ`6Ie`1{J6d=Ysp>Vt~58FV)T<$NU&(8itQ5PJ)v8)7TT5 z!M12Dr$4aNV0DVuF8GL%j@daw70iv(9DmR;gb!ad$Gbl@`ZvVZE-yk?$MK`~d5s`}x z$K7^oMgAv@C31Zpxp?2m;xpa9@iUfyM@1iR9=1kF zv%l!zqX}RqWTGduvu-v%3J;xFU*|)dwYffSr!fkyT>mwN9B@)s3o0YRL9!z%wKk{d zN}F^ItN0CCF^EOojbx3%+&7qnnE7~rYeH$!3+}DMyhZCwFP8vf0G-{eFsPm0ySvEt z^FG%$dObr%R8ytSHc_E_A1*UCSvlEW zVg1Uyr3yz8gk&1s);DPe=e!2#aY8HT8G_MwJQkO6K3)-u=K}5eLX0*PxrbLoNIgjV zR@5N)OI)hJXcn+LzY-#gy7?n;Z~YJP21EaN?TV}^^1k}AD?e(v(F`m};-*sNY)8zdj z;fB^dfHI1S^5cL4HI3tvysyMncT_BMG*q{D*SKhEI~6UaD#@ex__KR2tXnqu;|rp( z5e-CX2nOfwr~@#>(&4;Ro)~Lr_sP@45w#fnG?uTUzEYuawi11)h5s-POL*IC?@e?m zy#x8T44mwX-s^1m@H_{Y9&XQ(O3AqAeay2N&pikQM!KK`RVf*y=sem+a{ge1$4%Lg z@$UZoMLe>U$^}0w_qmw>N~EWH0vP$Qdd}qVRcv2}pLBXAoOm8D8iYq>K88=K%l>4z zkEIbk?#mG}#spbaQk`$&cTYx?ca?^9d$!rN@8>cw`G+b7sa^c^x)T9I2)b>g%0910 zntkqEB3;PoAiNRW0a_vFXQ6brn4ajnZjL>BO8+f#=s5|hi`u4npZv*h{Kqw%Ea0?V z*=#m5%Nedeue?E)i{gHQ5lg*rfDq|?7UJ1{=R-xU%VmDpk)A>5IN5{X@iEdh`Y=xW zT0V2)I^D^Bl;~)IEu_u=@W`9X=4rqp@vd@>Q`?|XC8oqlGViB_+}DLDcrkgny-Ni~zK1Fy_i3&`(quUC-zQ{3)5=OR|nv;91p0 zPP{qe0l;!gH8ptY0x754Dw+!nZ9OIA<~P8C#}X2Ft*yWH!PJZjdh7Pp-#GL=^qS-e zT-TyBo%@LH!FDf_{LA?%dy*GW&X7SFAF0GH9PI|ZiFH+>qM5Bv6FV6-j0@n`$@c4xL2vC|;4^e08xg>+mQQ)nw0cWlfwK$57U0qxf@Pu4^)Nw z%#al?G=?>6(wuWsqct8iSvL9)5FC9a!$gatFiRN*31mZw+0&lSaXQwbx^^3nsTKN^H=PRyo%N>9v4hc z*Y5)!P#fih%paXZMVVo)c8bz^27on9daF(=Us%fnP|%5%l?=ofFE@83I5PvLW%ZIg zXarSXcRnP*Z5s~4{9WbO=>pnMK56H64JrpOWwtIMCM(=*bgK!Nr}a|PsuNf((tQG9 zq$i0vxhCo89B9F&GaE8`d%}?Ud{D=jz@rip6X0qp6#2dY@~a=p{~)c2ly6maT>dYW zd{wnsIoFe~W}fD6*M)?K@z|uEW@N!qlqNuvHvIa&ycCH_xOTfZK0nT2uJ=B5#K*k| zSSbo@vr`;cmp;QYm>78QF=oLzWP-mYua}jkh7Gx&<#wC~8zt$9XRQIQaim64s)aTNScOfbfAz|DVqA1c0 zuE$qrSQ@*JJdk{09DODtBiG|mM`4TlC$vF-K3`S53ES5f7k`j)w^1Efx zyGu)Y$@YRrbzMVX;skp!z2AqbN) zgziXl#-cHl{dUi}y&P z3OQT;sv|@AdYlc@f@peF2o3Y7qLbmr6?ozkC|0s`O<+8Z(PqfcaCrQdJ&t$8DbK|i1{)s zGsVZyo1VXP2Fk%haXY+4PlN`{^b8d^gyND|Oe=qfGUoE8taT?PglF>C_2`wf)%7%X z#+BC~X&9s%7ML7O(q!}e$#)3(wb?>*KN?595TjZcrjBA&Lrc3^Rp>FY)^4;&&{mq$ zkn{cTt!3G1R+yp~zIRHfz=1wNvhmf!BX$%D(k;G%T=}w2fvj5L@I?S$ek^f6{xhfy z05I_)a67D%TZCIcO-&BiaHF^m-y?Q6;{AX@g-4(8e<{CZ!PQCJT|}Pp+jZdAvi{Abhq6pSsLQQdU$J>IPC21O?DF}~ zoQ%MgYLGiH+_oY}zakV(OAs2q&C>~ygW98i{H~N8yrH;9=dTNDd4NrGOAsBJlg6=y zhjCoIK&kguz&y;VE>fJY{CvbE`!g~z<15>#S!*{h_0;4@p=3(2Nn9i9N6;YTYekd2 z_Rum8|M*>R{MkX8e)X|~_~+T4H5}$~?WBQU+~9g7M2g-^mRC$1j30r<_;cS+GPngO z_G;|#lT#Q=3rlOqdRQ#DYVHR-rw(84<1%~1nUaxCgECNn998SiE|i`OoQwEsv{qI+ zno1o=xa_#;*4zzGr{*?d;3Y)~&z=lylevy2B7mI#>nrZG+5&9~vB<)>`FQ_DFZ4Y6 zVe3w43X86~7ytW&^NnUqv-OrJIp>UaloD}azUpu8B_GfYWOy)lUxOQ~Dp~T)c*wp$ z1a0PWK>|n+9&qw4f^qhvj^r89`W_}w(^Fs08SC3z`P|57ouV*krEJEYkna|#NG0!! zVJM!lsP&7E5Fkr0$t`QUfqh4(flP0bsZq9j?=@N|RSHVii~Xvj#Ec70q^PDM>1gj|;g$B5z zA#04n?|MHL)dKR(vl`FkqPV&u{!@cZe4aTMcF#970rfD_(^ysW=JRIz&P*Tbg??ooqOMl~Y)byn$k~kdKnJGB#?%(D_JtGcD;u znX$xgwnX{B3B7&2Z~<%GB$Z`U&ET;$|ESPYfU@0 z;7QY&y5(0xJW0te#6}k)j#}K$&?eu(K$`~6*k$&d>!yT2SYrMzQi`2FP&{^IR><4_ z)T&6QvuHQ7K|TrNJBpPxm;dnuS*FHp!4-541~JO6#r%K3V{CDa-Qn98?JcW8$|`gse!*;`$AEkg{*cgExhXttM{nKubTZ3h;>I)*+UbKlm*#K zoNB&j1U*%Oj;=U(5HHVgapk&biTUKE#%#0+AFbKxYuQwI^DkC*fbTQNDIlXh?P@Na z7%u`i&T*fEU%S>H`F(U59XvUsR}%PWS=a%*TI2ojpVEddHssB?PLbaOuc!MI>#-eE z5x0!`cI?~7O;Sn~INn0vZ-sJB@)oW;P*Uk9Ugbq%0xhNU#z+_n0M8+UTq#Rj1zqco zfcB12y!loUG~6f24fgGGevz1>9d{u_=I}wI57vr=RB!3ZBk} z5{8-(`X9!?Cf>jmu?;EFPi|GJ(&Kk=rX5Js=$w0#C>`EXb>A8K=Lm3ea`sn?s`$Ny z2;%X^OWF=Yz*`!zg}wO20O(soqv|oY0I65y+&>(rF#uD-jWSiQc2@iRe!wt>J;ceB zOR7ba|2maUQ|Tw09~1Vd>q{EKfN6vR%w&!FSRPa&g9w?apdsPz3>_3j$fBY|vLf*WPAoM-9? zC$MJCecC|^IcL-X60UG~7Qot7C!#@3X%P}%;CF2DE%UsfINv^4c`&+WW2E!#Ew~4@ zTVemwnb9tY;h`VdIO_+yv;F201fCG2RZ=F}qLZokzQQ45ta(vFO61HDnO9F?Bi1>-d zUvuIh8E!M6Xn9J#{K@{69gIyYZ+0)!ZM>6Ufs6C6((|u>L5McwHYnwS}Nrr~us9 zw{rFuhS5!2kW@b`xEKbukS-3n5dD__Ls1Wpu*8GQb!hK2Z6^?82>7uPB{XrkYxwI! zz~M(jtI>z*XV~IjV^Ig~EeU~hIalp>z=L9d{ulEdTiQQKF08NtrGuTkW`=5-Mtvb;|Sg5lja zE6JlWCu9_Z^!Xol&G0Oz{HAReUY#&s!&Z-7K}JEdSjkyV07kO2ae})H58Md4g)xNi zF!SrfNN$@c4kE3SgY2jthCS}DxtBYK@09KaTO}KuW${$aNGDxHemem_QU)5ciQDYM zfP>9^ZGcp`bTG#efH0vKevw8T=e|wMq17L>_^n1o0iS;jLEe-_*pK{U{i7&#k3aXR zoa{VH%P{CL$_gn*=$=;u<#oKfebwaK+=FXbeZXzYG#`WY#?{C$@>K>8N*2#xYEElG zp7)Pior!*SsL{?Se$mZ1qV)MP+Vgv47Np*;VRGPtVx{KxuB7ec{|?ok7R}dlobM0* z>fgfN5E8>`tNG8o1b9jkw!(=qkwt724%5^!aOh8hc9OW{A~RUp_wZM+I4fGx=Q$f^ zq3=B9MhpOS<71>+r7Mlro_Ic=tfI&s`dvFUQuSrW4Ksyd)7}g5CQ`pkRHxE4@gnm4 zY`12rIcEK|ycj=R%hE=!m5IGu4Z3@bSmhr?$5Z}i#NAV!N3o1x;cLGy$Uj$8w?vhu z9LkE{L$)%I49-eD&+e2F<`3y`tGkiJ4z9o7CCPgR<5Bg+GAJ_+9}2^Gw}Y|U3WbmZ zh45j>J{3EcpynS-zhXUvN~__k#hIYv>*bQjjQu)6Z{A6|xr6>PjLQen4I19o3jWD+ zxa)#PX~Veli*`sY)D{XIpG?6fq?Gvie(l-G4<)*tMyKlrreZb~D7W+}!5OGV=xJha zyb?il)TeRwBV3#*>Bpi?vxr0V17w}CVZ4h-oasHH_Zun>JMbFYgl2IIS%X{lPl7b; zOWCNRyF0)JTO;}J_f>}XGeabGR+>DmfHw=>6H~G#tTu2>QblApw3A6{0e60hHWuFz zzuueB;yzm>vI3aKYJMl+O2m6AeFEg|BJT!V_Xl7siU0d_z8_}aia?MXhW^>qax_sR zWKIe;*nN6S7H$#z0lg9~%`2u`=24XK`#uLE?sxAyqcw;845;iC44S%lDblPv!(;i-b~#bh_F z+6Atf5va3zMtTH13jmGh12-t_hTcJc z<#mMuCA6DYRtVl`&i(fp*gXV)>v!8yQxhLY8k!B?vDS5w`bAGadzLFEO^%uqOE0}0 zBd%+pr4c%Ze#R@5~{ANcK?7vRIjzOZf`%-aFH2oO2dY>+EVB32d_ z@44JLqW_5{0P>)5uoH(v`1E{l-Wk31oT2zW@g0+g8{nZ3mtNpz{BtI3C07YqEG^~s zoGlt!!Z4~O$mOzwxt4UYoKs-+p&Ic#iK{S3DELm6+X&4m87J)C^H=NhvYGvDkSnht zAAsiurK#k7XXOp`Pf21)z}lX4o`)lUpqOo6ZiBONk(khe%D%v}Aq&Y;&<CG0#g{0lydFyAF+U#5NnHY1eKD8;U5nxaRX~ei6ZmHW!(p_Lz61HJ(E; z_YnE-Zie_0Vh53Yr~_6lo+TziR}joh;PRL3vis6XY8sa<1jfX2PTp!mk=*H9B-^E~ z31}+acDj2sP~jd+#eUb4?zDsGtu!ZIKM5gujclHB`~8mnrsyF3^D(VURNUwzw3M5& zb~b6S5YrWfQJFb4o6NE%#7iK7Z@%A)C{L;I6fPtO{eML$`b*681qrcK;F6fCl+=T- zk0(3X3nsJCqj_Rsd~x6}(6yT>XGBObV#HGjuGRp?PpYZj_}$662CGxeRg0-X9JY;_ zaedoWehAh|$liMSlRwE~0#-=p6jyvcdUpk4m*CCt7LUWF@JE<1f>#S+7&;Yw<+<(Z zTlKq8l9NOesx%YnRZLDt$by|>i=O`FQus?RpL|)B!`!ss?s|^<=;sc8i?Ev8O@x%w z5J?zL1tHvzIF8L^1F+pcB}4$4*Hq9~>Df)xi$m=T9C4==BI~JKhOa; zgK5)RM5N6aroIw2%#2OXmmv#*gEmkJ-_6EGO8m!4SXW4Ep37dx5kY5uy#?-NGayuO z@sBHZ9#rF^^bT(H8fqm7%kbkPy?uQQ)JV>t4_)I(%1ub%gPPWcioQS8@TIR8XS*MaX5$GXVN`#_|= z;BIlw9&wHlMrc0rk+UY(+-<+nusWaiUWtCC$$Ep$7L;zZLqKT?AkHsb+6u7W5q!+W zEXN4c-=qE<;3b3*#~JcoR+7J6nnf1#EBVlJ*a2DsMpcnsl(20bM*|~aD`6SYGn*y& zNXjn-UTT&=P1_WnJMORBE)R=d)N z_98RTb0*zftd325GD_Mm9L-ae9LyK?WZ2dw+r>p^e*fn62?H@R0yEP41O}!Y6Tv%i zpH!Wy`^EPECBNS&X@X}OudbZ?^t#lphDa{2)cY0sQNc?y6@6H3ktuVGa1S;=p68CS z&00n%KsLI1@iMuAiRUTof zBatjh4~TW|AbN}OD3o+brKzwNdx*32Yfwow7B&Bp!Fje2+gmCMa)I1&DU->QVl^Rq zMPP6IrtgGug1TUkz_b&ur~@}{dd~x%lS7iNUmu7CQsOkB*^B$io`L(7UecqkC*RZW zJ(i@qI4hOmC)S=>9EIwYeA>0kYHmjR{A~EN@Eo=@Uo?Q`d6Ds7X=3=NbQa%w&6%4Q z8)KPFk6>lN4j56uqCav5w{L6#T%YdkLw? z(MB`3%SabH6Z2(O(u-b*btcuFs&9(Nq`U6JBESHX9?IyRJ4d2wv{cKoYdW&A_CCWXcZKG@I z$q%|jRsoXfyOX?#R;+WvzTQ(Q=nsxYeIW`QaGm!JiXkp+*>{+k`e*FH8Dl^Xj=&sK zKNnW;0JvV8Xk~{F5 zUB^Qtp7N4(*33IW8lDxc{1O&*TFF^c+PnJXqt9BkHk>|Ml~Gc6?Jj0J2Zq1JNf;=| z()O8d>{+j7Js}HWc$<^lHjpa`9Ae6n3)i2Cuefc^$}7xov~PLza+BRK8cUbIALJ&$ z6O8%1LuPh1K-FP|rm1qeinmbzT!xA5fX>xWzQw8AOS&<2nGn&#gt zh4Pnkm&JnfC@y3n>Pzi<(zOry$NX3~C=A)6iRZB+X2P>xFMEyLa*Rb1&;Uua)qhy` z46N7ZzK?s9#B;SAF6MZB@@vFYwWr{L?5Q7x=9^?I2k@N*=s52d#21!WkGo+ z;@s0hzyu5)cKD_7U(yjS2EC{x^}~b1-@_Tm+IGR4%t+kFP#kJVD!1(^`_&zjE$i5Q zK|zT{cC=>yIQIGex&$pjP@(K1((yTyNVhUZBS^XI_ zrrT{mq0)EUZghT7Iv%|z6_YeoT8<%2f77!P-QJ06U<=oUs(iUxXExqs!q4OQ#z?FB1q@syDs?DSGxQ5NW|9xe<_m{;9S`etW z`k_L}RCGafoPQE~vhW?t>D%ShwDx)p#ir{PDK>n7&hI!lsoUEQd!pCZ+`Hz>u1{{x zNNNLMQfQ2|0@xwTNHt2L?OZGclbB}EUJ8Az6**-&O>`$@Z)AG-ATYcx|BEQ0Ha~X) zSHr&1+$(PJn%(b(AOAx~XaQwi<7VjOi$c{>-d%K|cN0oiNY-@|=LIxO9)R(N#GS5< zn6(uAMO9^j2K?cP6YeBGTj$|Bjs2L(;!4G}gpbxja@17fK1%CYv_wtK&EYe@M=rLx zyj+88ma7o+;@aLb{_*qI|9QQw+=#;)M1vD373KBT7RhC0lpK4* z1C4)yLkfOD0}zMHS9P5rf1H^L#HOM!>8^$S-4EslSb|09o|w2oEwkdUR2=M69R` zl8@6Hmi4nAoTfj3eanUo6(o@I3?K(c9NV{_{?!p;*?!u>>-c5*Nec)I$YSzpb-5{w*0+_i)zc$3x#^=?;meq;Zr2{(~zQi6Ap4Jbpf=M zB3jaKPk*DkCPYGwP;YS0=qQDK0^3}+; ze0~r2dc1u8QX?uOv*PQ_ir*LceO?iN*Fkcq2)hGucu}7WDMQJby|=vPirB@a0$P%R zn1`5Pod3|(Xq5gaIOe09d0DPJC)#0QQdg+dq;+KOy#BMR@(Z5K*V!jSOr5-msS}<| zFEq!Rz-TpfBf0=PU+rV9Mo~`KreKH%BL8fuA9SYMvuQHY%6B2tCalGvUMf2Ei4kXz z8kJ%G0&^b0Ll-|j7UxwNoosC&Yit5wS8wK0p}5x9!1x>cS@>z>kU_$ZeoB*Wcu zD0Yw6J5%?&SQ(HSD5DI7uii}Neqb^7(0nAO*#*v~)yAJ$C^3yrwkExU!Ck?F#D)`! zg7a1~gn&ZA%S~3>+Gy8BTo*m_)E^xYf3x7=OZwqBM0Tp_AC_M*OR!QHX4Z&*YYpLJTi}tHdoIjkB0bscxT0yLujmlLh|su(R!Ki2 z!~%u)td9_KQ=iLK?mw*Ox(vTW(lTBs+#x$|y*nRmq0?h%bX#(cg??K0@YtKPGSGs#xE3-7B zBr`*1Q1w`&C}jU=WDB_*uIyv%xH|k`KG(q~XPM180_E3o#0kG~h-yh|zd8F7d0;?F4`W-`k!6<865Ct63#i+YZmi?VMIStsm zzMhHhEO|(LD}ZiXnm;{K7m>mq8p+ZgY(5vZfI)cil)AT2k(`yG_Jc375!bILq*r)S z_Kgcg9lv*suuZ(_!Uinl(cZKrT=nff*5Tp@8nLaJ)3v~2it9%wP{^)L-nhLHbxJ6khG;ZGc*Ix5UAKCV?1^2iX^wHTVmTXCBZGs`fE?3_HTFW1W2^Blj5PB zBsw(3p%}3{Lgy+H50RuzBvoYRDpEe94VcMY@`c2Eh4*Y}_9e6ek)?i@18dSs?=6y5 zW4h7W2&Q2|Esc!~T5ntP81JltTYquI_zetJvgJxkep$C|?nTF^D17zm)g$OpohO1Y z=-0@L>DqJdj+aJpk3OXlfJkAZrdrLotOyb1AzOvFr#^LU#W2A9xu*`xn=c}&e3n6N&<3v zADxaIB+o!;Ab9n(vsr|;L{S$Pxn%dX6Xb{X59f9g1r_qg=7wiD=hi5Qd`vX4#|PJ4 zlv&?Sf8t~1ZSY(V?GjjUSwWh0V^j`EH}d-}z-A+hN}^M_#sl6;6!#)=2fMR`N4fzJ+bSK0C zx6n*(n|HAz27Uy`L=C&;?T%+2dWZZxHJRozfzjfPO{U2<)$I7+lTUU$i-t^){ z6`6zD$@}m9UG^_?bcQ^)c@7xqm4%R|M!COOpjxH3=6<(BIVUKT%EMr79a*u6#B#%eij@InTDRJShSb0Cn1h5 zD!M3&e%uC?)98*fkbRf{Ws_=XgRLeRVMXn}b$vE)4U0GfXVUvR-j$?mv^lxcW&u5G z>Hz4S&)r38X1w!tW(p^bXtaw?TdrSp5|uLfy#DFkH^cZ()I7VZx3`Y0xPDWJvL@PM$BW!@Jl2 zkryAsPObU$cge!EG4WFyxF;ia=g&W6cFyyF1$t8oIb<0K!$(u|lqd16z1*+YHi z2=pc|3g^`mf(0XKYq#!wM`w>BcU0+bn!zmJE28Tu=fNv{*$$aSFZ@Ar)GzVH-lqZT zLVlK)S9|{%Zdn?U{bL3>)~X3BX+Fc?l~{RquS|&MYT0?B>1t;%E>}LRIwZa5A{sw)qZg^)Ff-WEc#G=~j^CfGQS~`_e9A$E z%0VCT& zHRn5-q05h=DgYR=7bv=uFf7R zdfZWpK!!WyQN+7>_N!4VbUeZ^hbmssWH0mc3TdE5V6f}^+uZH=C52oz+tt5_r+E9) z$J>|saqI;pJ_E`FqtrWtbtjAaHk`~Wy|H@+MBM@Wf61H3USdB$KcCtP4fE6^M32!X zV`RWb)gmiDEl)m;iadlg|7dR{tG?Dg!76A;4|9Jc4l!heg6M1Q!$h!O?oC1?HKSZI43HZyk5)ZemMF%6AA7w+s!34lY-9rS+)@)K_aI*Swpq^VT~Y@Gc5cOt zTbD|<_5q5Sxw4Olsjatph`a)F9g>clHyYA?GJuX}T9EQV~zF<;rdf?%{HTr-#?tyF# zeyk&89YvHhowaF$3m<0VGk(O~Fu$%gy4R!s#53s<|@bafX#~T z^FQ~Ws6nK>w%o!zA2bwcCc+56wP*y$R>^wOSmL_mlbL34+xjrs@XVzR30P@ce{qx! zf;lp($@t(;n0wS#ET!<4{&+2R+i~}$71Xq4h1f57nwAUV(5IVQ%vX81v5p6LeQ$RJ zuXM!Dfcwmw8=IC54B28ldRCC^;D9rco`N`t(#>#T_`;PvmS$FzQzCKcrp__f(#N`d zd;MG8!!l|dGSnhOnf+Fo2sVKAtFEFl+`eBdyKR}t*6rB+CB5wRIr*%=4$cVcAFzx0 zFZl`CkoaE285?(^%+x|MQRpY2>od-aJ3T8RW}AiGdq^AaSOG zjDC>z^VqRg?=P3f@q+K}ViFd61a!uZf5p#*8@<;1xN2MeaoxI)sg8@RYl6AR+ny}w z|A?b+{q8uj%O!xZIjS1~i)LL2jSEot_VSxnUqYqEyzaNta>O$pENEebMGu_;%d`ps^*`oORG=xtPIb^PU6!`^d`A zZ?7!A{^J4=N%i9IkZKJj)o85&HtnTzaR#+Q6fHkN_Eeq!-x;q)L$v#Yt|LHn3FYQo z^T`9N^jyn$F8lJ~6>cHE^-^_8;Z|e*`%om59>%;obx}!1ALJj z0?6C&`#jc_^s(QD%ATxc__TlYcdDKY6dqHPjGiDJil6B^B zj)&4~VlsVh8=ibMTiH-afm^s%98uVrDK|136i9qcaz zZ38U=l9jdR?*IP#3~Yeqt3~MPCuN;8hCl^BgZ&eHcrHC}ekb{R9z9W6#~~>j+h|wM z)ySI@cdn0U@<-Vu_vJ3@Qve(4R{>9<+dI?dn~w zDUgha^t+ETJj(af);5D%G2zh`#Rb!cJi5#`9uY^JgwMphHI-=xZm^{)S0`3oS!V4`%wvmhj-B>GCqCh|QXb1a?50En!rA7R0_-HaCcYPh z14kNb0X=Zl*^f-^T}XwFfD+p;Sl0mcU9|Jw`T6q~EEC&kbB6Q5?+A@0d=3?*l z!g}e0*AsjB@1V3J8e0kHmO@q z$mUM(w@*6nNap6Wm$o*+cz?~lmpnUk!wpR$T5fY~WjbeYNPu$EklXjX=Yui*EoH!o z%*TF=Uda58I~Oi%XrJwkbnr;C)xBQR|4c$kL70xfUEe;k2@X_wbHi2B5OUdoH>Pda zs5V5HeVS2{&-GakUz79o^hM>LJmh!YT{H3={c}9skahZ(>xA!am*t}Ruk;J)7(R-( z|87!qRF05|%+BL8%7hn+uG?5zvY4=8E#VbA-c%f4wSa27OsDPxLUO;<04QZ-!$jM{ zy4vMx@1fJZ>=pWJ^b)*$h~1RWlCS?<&4Si5lpY{!GpjFA1}A{*dTFTHP8<-<_oeZQ z?bBl&s?G1+wn1Xa^^jEz6zd87V}zPyf7?#83uBeM7N-*NhG#ca?wJeSsL4EdZJlzR z{mt(p%ZRixJ*Q9+s9VJ@iWw;97d4;z)v=kMLw^w+{%p+5IMZy`t*-b<`6bsu+=dNyGj@_J(~dn@K4CxAz_e_ydtr=0&(7bo3#raF{i zw)-e32iDb^+){A}lnVeVChppoYUz{*CE|3=>9UfSR8csXE0@)*9ttj~(Kzk-=l3r{ z4PNPR^)@|L>Y`?g6Ig=UT$D;ew>&IomX~}dARx>rjkiD2n8>i6!K%{Zy}yC)n}DAq z>Aqy)EVCj&;RO4}O4DG!N-Om4Sd8^DGUhaf0{5}mROFPBY6$HTuOklR5aYI_pyfKc z4@It-pRpHt-^FUQa?K>@!zW;ATG?yIm%vKgp6bac&MTE?%sbN@+5=){mV;(IwW%Ml zrejUwzV_z|L`roAtMUvm*!{i>;W5$Nr|(V_uknZ2oKruK`@%I_L-kwm{@_7wQGI8A zT7PDB80NYsiPmCeFL9mpKX?-iYKIN`9?+l7HsN6)XVX;&%N)SJS+4ifdUidGG1>j` zp|E~Vn;6AYv%0Xk^UbH2VV^I$5l8e(XU{DQnQ=aGNx>RUm9lc+=#J15LY%xwxh3E6 zK1zYqrMqn7`#|bUhv;_W?&_*#5X!3W#L@2(ifYqEtjZLd?W7lN`$PC zh|d&#vF+m1Kn|6C3asTcqqss7kF2cRNTmq}rC#P-H^)x z1{Lb}?A-_019IOeBZJ(74+4D{2MY(qy}^PLiLVEN{z{e}PFL2(_`IeRPWbl#uJ*~D zpPedz3!+fOMr)0ieSJ&fyQlg;;w0Jnrog;w*5#MFl|9YUSIzX!hqOb_NFmnESxXp& z94%yEM|VzFiY^B_<=B*UbPMOR!yBW_1)dV|VccK|2=joY+a^46-J18U zVN5o;1lPn8KfNX5G38&fXY6mC8r-5h+X-@{;b2hNW~t(!pe)z969q=!UvD4a|x~Zm)*n*h>&tZtu!ngH$<2bA%PQT z7LAH^)w?K(Q2L%)mMpa{UFja4N>SUPF_FJzlF2Kgt;SB@Req<|VX)CfYpFKbT+(je z1^=Rl7=rnh-IC2NMd_5f<_U_|712-X{<$j5e)Ir^8UnSh5?(x)CQTShPnBVCS{An) zl;_ggS@?&EFvmM$>HsB8vJGI)4BOKimdOQNw{A?fW9$>zsrOt~IPsV?vBp<3nmdVP z28cc!>|jUrv(9rq)s{Tnc$YBS5WNM=_8F~JOOPXjk?0E9cjr1#d;a<$jt-*sRQGrd zQ?_%PYIoh&Nq*FBIH7-BTg*=W{`jQ7EtC5UFK6#IWo& zd}4Hla1LIc0p_pm0@aM!%4zNs&tu$2i~-VOrRRKaY?<^UR9n>htGkkxX63FC6|g@4 zBHn<6T&R{;qFL5qzX$VYcmP_ORP{>e%MHWmF?h*#7aXV3(|Qk7mc*b@HmsS^wYshyhmwjtKR&x6_AvD4zgXH{A9;`F_e23 zs=pF=R*;vm_%JpQm8oa_kR5IHd(Lghbo*2@9-uT6F#%Ka*5E_O_Yj4!70@}(&14ft zfy(y#6M0y`Yi9~BPk5B=(U<5^>toyCvLYY`l45~qNqA>)FV7_MzYX!$s`e))#u zRmm7v2>np{Bzz18XdK576Ayl5wkl*%x>k-vHVA1GEYjcoTH^t(t(m1S>YLlP22rbN z;rjtt0YJ?$Y%( zrtxl_TkkBg4J)L5uclIulBNwu0lP!?652T% zT?$PJQ{SZTqR-t1s*gn{X(GvPh41bJ@`MMt>a}Eak>kXrOmk=3atX7lWf)>8B?9ij z~)Oa%_RvCk;f zFror<>(a8plZLwDP85%^_nqJfWUbwQVUn*76I$Z1k{l7_vQW?&a{;dhvS5k;4ss5C zKK4r$j{}=k>VcW9QP7V4w`5}OSzL`E-O?R-zd814NI-tW`)x}k&@0bKnv&y4+u z5vC(;`;`x)2#+vWaeD6py6XhG*a9f(d~NPdpJ-d^GsHgT`x$+F*prWhQu@C!FMoo0 zB{;m*pjVv98VUl8LhZUzBg13eezKI2OF8N<;X*0+f_z&x`)hZOSBeajt$gS%XE4>= zbR`+jB~`Q>5dEvC*N!_j(yN|7oy4^a?r<%rmi73oAr2crGg#fMTC)da-OJ^;$7mCe zsdmT2TbC9xSSGUs8Yx8h&QMN%Sh9;iRYAT>AN?X!NZ^mZhnmxR!ck8zXlE4{<_NR#f zHo<@MAzWJ??EVM$mE`r2*RLMo`D!rwIBA>h(r*)G_zwB`;(C_e1=LBNn#?We!+-AM z1r)iMcdKBs%V>K-`+SW}L~#W%e^BqPt%Xf1YBH16HjWEDbSMbNAZCGMXLC_sa_AN| z6JP1&C5(if*HL2z$*ncM|ZPhaRt`t%$-3Rs`9^wKfU z|1)AqrY{m52b?x7RN$cgfVlPmqv(=Dk58X6EZXT}>(T;J;QA|X^q5Vbi~l}vu^PqYM=)wRU94;r zMm8me3=&*T;dDHy24kZvE08M?jfBF_%H z&ob39Pu{1B&!(I@kt__mTZ-K7RzCr^eXF>q&}=GVAuD#D=%g&3{XWHw&ZE7D-X!cT zL!~DdSXv`Z!jysCQuaTvd$2(x{rGtifV z_Q~blTSO^ohlK|2;nwFzNnb=MHu&nv2q8yr>1CjGPwxK0CQ2hbPrbo$vL%&BbgaN> z?YRFcGsSZzMnUjBWAiVK;DKgV&7=flai{K6QtyA{&Jslf&QLM!Z@K$Q1%2#2jG3>_ z^{-$MR-Yty7=6tnlt!t8fw>SYBK|otJ>}4NM5fM zD{~aXs)sOlOKsW@p7eb*RH;fFjJTGu@XQjPg4VQ-)SVNpZrZfF89B!x`SZJC2OTI8 zsyDbrJW7eX0f~&-AQPkU+QfAV#1mINy1rVnI>y+AyBB5QYOkLT$KgvpWc&7G2j)KYY~`v%o=1?X9!o`GIdLfgw(t-s|K+5{v%RGVSA=S#Y1+Oa zY_(J2T2;&R{QG2uMn+A%N!pKu@XvIdn}ZIWos96LIN68|DOm4XK^jR9;JBJz_U6QdbSy(GwDy#{;hY)Au)KI- ztzu1XxL?G)GmxtZX`sOSX<93HQ#{Ialx^b^^AdB8xz7O_M)NK`_RY%4)f zf3+XV4o5I`RUhB&9{`5*L$yQobPbW8hj)+(YwMFb*a}u$4hXkLTfINwSHFYW4%|4{ z^ALkSP@jIekAmVvXr24_1}Mq(dVB`-+3F;@Ng0r`2J3URKY|=8stTd&Z&YAp?P|Ev z4Fjok%f7q^o(wAD(2iNL^K5p$s87?cq18Ub>`6C5vW~*_Is{yocz4OIq)2b_>2)8;sd&LpN#6U?~ z36HQD@Fd$m_l~uJt@H81cBU1*AoXMsr_Q^_DBokSM%f%@A$T5Lai}||XUdrhY}G4ZEGE)&{>++hPcgtXR#a3B zG4HOt{*od^ngV_*L2Q^jg&$_@F8SjR9B~l?*(n3Nj+p*k_J2_<7~IubgP?WhLUYd% z5JVHrS#qzQ!qyQ&Fw^naKj#r7$RR|0t?NNFWSl(_ zIVv6apkyg~Jx>Ll?02XJWIu#L6Wo@&!W9#oK_{tyW~NK*Ln`-It|Jf-p)5V7o|T<2>yDy48W$HM;!Z?XF2u?||32yo-mj6uP)aO(cPPFXxv^c zPup?l)7AB8WvI>s0N7$TwNG$2^YQ96^L|e}n%e-M`5&AF z<+bJN+Wo)%wb?oKkL}I#CMy8(mN{j8$$FM+8@6H;>I>(F(--bM$i6C9m&x-b_!yOa zOJTY2Es-l^!U56NQ^~=u?_bJ5smmNRpHVgz;ep8D}m*kY-(7VX;!qN^zxDi%u{ ztm9=&T8@51pq24UMd;bwBgQ38|Dpy*5xw)^7F6Xg7O`4b@~YJ75^-1zIzXz&5!$xn ziq6n&6_v7BVY;RS`Kd*{}RDx z`%S{_KyO9%dj%%$jJ`oMr@aNbu9%n%kRkd8&FIPVx;b`WPnaDmzd<;_uE8{LcbQh> zmr&6YyrZmTGO4uAA^J2Q!4pmLPuM{Tu3cw=^Nb$Iao@M~_b=#|5^^u89=(?~T#=-G z$ZXum#JE&;IAHKo*5fMyMSi>|sChwiN6c2}DKL>Rjw~prw!w-mUGJ@=Ydm5GRWYwJ zt;fMKu8cblSd%|wFr4hfGs4nW0<5bnz8PM)HT^a@XqVov;(vh1H|yB z>$ie8>CfvM*CZSmA=8 zvZcW#CAZ~Z=XG$}`)S!AQcIY#{yZ8Zvt})aHG`ZX#zuQ9GfildyJ4ACU&=dMRpX*= zN<6!^((C#AvlfG!=~e=$nlwlmk*-Sg$2bZpdI~MeGkm5oWN2Gy^7h`+&H8=U=@~eP z*fXyG=CgGbNmAJg#MJ<^Gx?3eYB#o0^t3W8uZCZR#_zKJAp+(bM*RiRd_Ebw409U6 zON8#T_f0LA;<^sM&u2~*yV@2sf+tb^FRd2*^WYW+#NqGx4Mv7NJ%3NSlpt7(|H_<4 zVgklIcXsoN=M&-A1h4Qgt+RyZr4PUU)Y9)`DFyeq$+CIu?5+@JsT;CE7yb2@l!F8- z$eje?yP8^#dA6SgyFa(8!WXDv9?gbH%r$VB*dbd72|2z~2XAhY?-+qS&`d z^hffUtQIz_8$GAc#RdtT5nAf?UI8w$IoN;Hgcb4KwBsAX$Y7gHYYMJP=jrIuL>Fw( z)=@isCH#v1^O>8bPQg}=si0{8VIp(FdM8ezT^c(?KL%OOpB437U4D3jB6}a)KZd29 z;MC*;m?2nlxnnJUZ0{;?i)&o*#QOz($NG=acE`ye-`JBi6K<~P^9zs*ikWqQd8qvK zUP4>|MjyApif4dO4nSNK|8V!s@7YftWY5sH0=KTpW=XL&4Feec>dQ~)PwIa~0djX^ zS%G6!00LcZ^YC~v`N}BiUF8}>uB{{RC-@y?cOSWLnyg|HLRg5LL*=FDpK(Fe~L%aY(uS=kNY!~YjQ`8yIw1L4&r%2=zo#Xxw95I?`y5g^|cw7#}5Sa_hFKcK7QqMI#uZn}p!u1LQ zdvyhEK2YCw2=m!&$o(x<@{`aa6bG(jEeTl7Mi=1@uYpl2aDh%`LeOr&(v+MPOiUg9Y#V%y|%AEtN!R_P$c7??w^R&u~ziykDY z0nE9)`V%UZ`}ZufTPXAosUUPv4bA5NqC`d#T6y=DP0JJoH5r7J(>o`it-H?G0@jmn zca+U$ybZhjCk&stRa8{6P(*(OFnN0S8xa=Sf%?WU0qIC6sJhZS93Il9m3OrY;VS~tdZTdP|l-;+g zG98Lsz8t7Odp=h&bX|RO`awsCRK5)Ll>e-$7MNhQ>-#a|%~|8L!lc&=SF8ngJ}V^Z zkH^#BF-ygxa#ZyvP`S(hd_Uc7azbMca`^A4IQK<2(ucJQA5&yW5lsy2CPf;a(vlS^QT?cn&yo7JtcTWyA9I{$uEq8^z|*|$=>p+w-|&z4rDM{s=u>B~ z|5KXMC&Cf5oeE!E(;$&MzINhF^8UXIO^@6=F9;Nm#pQwYYw%Rx+fU<12R)zGBl zBOn=PcWo^4#gTW}fFmDk?wtD1aG(CwmE@gUS@1!^#NK=P7X}SYu)c}wl!lp==QsGN zOKVG|zHBGULBEc59fC!aVQ?94Ltp$~;3DQ{r{N!|CwCV#kIcF=C{X_Q2Op-}mGHy~ zhoLeuMu8;N@R^)=Vutrl9HeDRy6$<=wkWQ}?^I2$7Na{pDLIYNtzMgl$nDZAxQJMv z7*$&@!%r<-Q6qP2=yLArXptMk#3aQ5_pNn$9z6*JDCDyL2FUJ7cw+S%VeH&DL*g$f z6ps)n>BOPtSzpSIzf3rERwkupm@|v%rm$?GKZHZXM(c)!%!SJe3z&1`Xk1Y){>R%e4Rq3BE+?#7DJCUr!@XIpA~OuWkbC)=sUku%DJ8DN7iCrdU!9 zj-qjTd<)j*AW-!X3dhQ!bF*YM{6<@;m}EZ}cU9-7@yec_9M;&GDf-!`G%av(d&?VX zt72`GNOy_LZNnG9r8Xe)Sr@lx_#eSA!OWu)f{l;NE6k3Ne$d@C79L;6$qE$Tl;tpx za-GmKk^ZOOP;h4_U7PryG1(tI)zyq0y^m8a@#8=Q8Idw)ylyL4{{+qFk?|Q#v)j{( zY4~wKSR8NltOjr*6k16O<%LaBFQWoPU4Wj~554t1a}CAcYT#m(uMds8C5cXx#;Q7v z?7W)>2&>7?Be@JYJ`bqYFa3>btpMQD2NQX|0a@6X=;`{{kM!OSBSxX8 zmuxc5Ndb{i=pn3nBkXI9-A?swf5H4NUd{m+Q64;=rsC57NH{!sz{C6BS_tH5Yr-44 z6yhQ~TMgK;Y`k_HVOjnlX^R{^Vn7gFG&>bk!8dL!Hd@3@UBuG+cbs_1>wT=R4-B^? zPP3v1xoS5hR{VfH#pI&LNQwDJo}3NHexBgoY zGgmQDRmi5%@CQq*=y5S=M6j__GaecCNC8H>>!Xc$92IT|# z2Uyz~=ATu0x64MTXYzi}>3YAC3|a~Pmm&6h!X(e6Z$j?#gn?nJO@hP#ynM7=?3?Wl zLOt}LcRCa8oiwZMH64t^ z9dS_QtLrV32r!Oae)aFS{9_`{m78c(aN<0Nh#@$>6sU6q-{uKQ$O9gr2PaV!u^-iz zrdOyOTM(k2!4rkW`cXL`L`NjL9ViW#?}6iXs(O%a@*>U|MwmtsvZjxwlIjVfe!!Jm zAg3zqA&XEo4rB0?<_}0bwzm&lc8ySGMc@;sf+PCYK@lZu_CWzZ>HH0^PjCb=QpwaH z6A|pewQ*1|z}y&GZlgnzBbfWktG2pcC`3n!I!wuP=DpTUpVBxEB1a+$;|2yGe(l&+ zZy1~60#m^j*ifyr$+?87Wo$Wmt+uD;Go#!-0{4|mPp^2ohA#P>ElJ4@5G0ZK-2aF_ z|A-}uIwIMQ{m|L2;ux&Xy>>_xNACe+^Uw?eS{_JyC1AsCGGz7d3tlO8ya_`X&YE;W znzC!WbmUyu_z|!GsjoP6I;(I;ZIPo*L+0DJ7G`6KOFgj#T6ymH^0l13twj$@(R^As z;*nN@)N}6YXwm^<*J3#G7hJ7P`RStX)B?{Sc`1I708vb#o4plPrA2TQYS|@|9uD2r zu<+y9!${j`2JzAZR^soIS?8>F2xAxGls2GXU9O>j&0KYWm30uwbEM@Bu?GO4n9fgn zd7?GlbKv`Du%eHtIT2mkr}15QE>A@g+h|kcgAP8iW871w0=VaPBGR)}%zxrH^$4M7 z7+n2Hk4_w0-72GLx+(Wx%AJ#VSs04UCCi=`JqVfO^-1Nt&1Y4e{z9~;arpE?F5Y z`6VSv;9g9hB{p#1t{FM?ql>yVxEze!R+~6HAJ)nqJ7wMHzfoeP`ZS}H7sp`D0B}*r zxfJfmFZHldTj2fa7LTmBeeLuufX7p^nyiB+z0kIN&Xs-x8p3P=`0tvfz{_Zl7ihyI z&M69l&!kmv@F+e>;+1}0oKQN4U_BC$QXJh<8smAd!>0*PAyqqJsGCE>wIp9!07Nhf z#>6(3in=LqM>N7yI_nAXPfeh7fI=#ptydgsnkb%@l;r^5??Tq(7qwe!ceN1}v%eMy z(!MsR)@MA(KkPrVJtfZJa|VwZcHM7i@Eqgc_cFcsDDZ{-yBDm2W%e)|p)XocH2zLC zmYJa3f3}Ci2hq6RNsio6OukRq!TELXM;mt(gVNl0bSym{U6gOpNPC@`KvbfkD54{DMbiUcL7~Y);$8eCRHMvI3*Mu z8$n)o!n^<)w+%(~t!Nk~J#*9^%ILQ^aO7HRJSW&B3X@Fw=1u_KHhHF5ua>jm%$6YJ z$Qb^5xi6@tUteW<4=dQGjdJUZ7z zTp}pZZEL&P9S=@S`plzf-zPByMFo)603k^G^01#AKseTpRcA; zNS0zDBrjqY#~P5MsmquoH55v|$^NX8B8o0+zux_mNcYB=s7l>Cx$4Sh`syDiC~qI^ zi`aPRDXF~3?uJ(j@6qlOP~8upjDHJ33)KU`21xy6wM#IENxyN2y7l7V+CbwD7zB>_ z#Bai&zk1uz$4lH-lrf6RW&5OTwzoZQ)6iYpjjh6xnFtH<{(rDbI!HWiS7ykdz47XsTb+A2HXpXOgZ zmD9poA_QfKhdV+vA!#3_iWJFhu5v%CaDmNsCo82!9u{KX4pP4An`=?JgC@DWu^n*$ z2XQ=ll-NK#eCm+q4z0j4vPr6XVu|YXMw8sMk_Yzt7R>%;WW@wF(>uTuBnzWJA^u13 z6C#UCA8Fx6JgjbH_~RR#xxOojxo4_M_j??;ei8jls4i?V?^CH4%9GJi9Z<7<0BRp` zl+^5TLy4r6Ph2=|_V+k7CykI*=L4!+chBA>Y=)w<@8O1K;n*j)57bJj|7^ z>;dGAta=6{aUN%pXABbsqj`*SA7#kOJ)m3L4M{@erFiF$?v^& zoo;DOtg#NA4rU7`a6Eh{R@eEu?sVxHUnDAr9C10HAORZ6!^H_%fKC z`WmqV53Iucpro2Dns7Sf6TICS&k<~1H31=c5FF4k-^~kW-zwIdqH-r|QSaJ|Db0MkU!lE%?N_$<~9 zHpiTZ?M=sF-@)y^pUadU2WU+F?kj+oDR*qSQWpMp$>} znDyr=?nyu_e8KH+i?Fd^LgnXNX~1E}*j%d|8t74fWqc}qf&+88(A*?RINRe0@e=Us z#g>irbgYymEWkj-*WWlL{^!>>J+zgxzi1^hc{qU{l$3hUi)u;}i{#`pEKBlLe}6mt zw?F@wwmNwV;#ZUfU72!wvk=IyNeLd{8es%{pH1wG9byR?4^!i9Csa@3pnI?m5!B+a zl=!f&Ww2<~9DltcBY;bc*#97hji?g)rU`!+l>V7dvuqyy{WI+ezX)X^;{V!aIRqJB zRQPbj`^<@aHt{Zl?PKp1OX_V`tg4QbaaqUBz5Yjt)JCS{{R)*1CboJwYrVW%Z_m19 zB303IJVy{K>Tjz~NlALrr#d5INcjb)O4Q5V#!xa<{L1XtyBL$yoR(IMVd|HSs;#(x zkRAtbO@c3yh1NynTlcNQ{@Lh%c_Uip*Y@x-JrzqVGo*Zd|H%$8-+i>LpV!PQRn8-R z%xzl);;~!v_cJhd_P+sm+|+$HMM}6x!n|0zK^|=OukqLQw{OD}`2X1Y5^yTiwe74Z znzj^8lw?Un38hey#6lE{k|`-e5n>T33JH}Ap=1iN6p?vODvhS33?&Vcd1s37-|wQ% z`M&SJu6^xuu1&*wy~Fd|&pjMou}WZ?7^F^c{k_dK;)jjgCJm6ygA{<|u{#jyj-Ii7 zm#DF%H0K*9KSouE!dGgtKnKK0Z!M$HHKv!N;X-MCk}E zI)}6R#PGSv24Y2xmS+DK3wGrVu^bl(6og(W|4CT24E&%NHC&3$FLRPPQepm|-L$Ym z`YZxqjzdU#pgm1Rks6b-DYaB*a0vc;zqA~GHY_NeN?Q>$Bo3cu7Z(UPKH6YXl!u&+ zCjgAE%Lz!Fe-pp4>hTLQL<7BWt8P-U#~35LEZV;A^${;$K8GLqJF<1^hZn9<%@eS4 zO2wN+ykqaq9irU&=jm$hEfnU}MJ2Kitj&#a*SZH*AEEwvB>yarQUZa1tPQ;TS$CUC z7Ewj&zH)K=mA!(x0r%uTS$|p@bgZNZtzZjVt4Uh0^;ui+4Y!?cWqPS_jMFDpR zo)4J|{{8xb_yuL5pgF4fG;8@O3PyU)0m2HOF-gn7GrC##n>-kWE|U}ZvHc#Jgy6YQ zB^R8mUy9dfPVZg#+}&QQwO`x%rQ!Ev%3^>v4~Q^JK~sJ`CPSOv_u_W@^1y0$vhC|= z<&|a2|8M~mkJI?IZoKR{zSB5%99QZ`A}dt-ryVpwMDMbBFp`FM5=%kU&Hon98YULI ze-8|<3qNvQv`KQ!WKB){EZ97_vXMC}@BBkA^DuMU8x*w5pY5_dfz?B+;4PgGu1QDI zy>GmjS=`oOaEhRHQ-vL1OQs82|GZIW0|bU*S3 zM0(hHdM=4)oWwAx=WMi2*ycp3PV?zLh;7f$H$$Bjwl%c-gqbBaiQ94rGs^C)asFV?ziy72qcaS3v-BM0Ysm>EB7)9j-XkE%v! zPPCqFgxlS`0x^3%t!QLE&7gE}bMD6B@g?e_#^)Z-L)WbnS(DrrD%MCMC*aC39Gh!~ zf=^&clrA^tg)(?kA4big@m3cmBX@CkGSIC09AQT!nX|UB?%Nvl3u~A zO{R8GaPhNlu{@J~0JS8&Gg zep4K?u8H^2&_tuDC3;Z_41pm3GIS2MV0&pXyqPiRI~wvki68LzaFUgL9sN zc3Vs+?gJ@1oju<5psEo?K}6E=+rzgfm`R<*pFyIzk;DjDdDr_a{a(6pVGgh@@$bLx zxC;`%UTR&eu{B{(5d-L|UwDjPkO67PDa-x;W3^^bYRG_gz*t(9)t^q?(@GU{2}%cu z_om$5ZYKy4PYq8pqr9PPD_kA=-B0PIf;Nekip z^8tgfc9;GvlMpcnnV`z>4KW%P+Q~1|8Zr#;vYxPI>tZ=}8!je)_mGn=>@Ja0l&fyHQ!CoN{0-2F0?a1A*; zH{~4SKW1c|{P=;m&pJo(nH*ow^{fl;!CWzikG)ESivXRn86MfUM35`0+`FWJ(S74C zCx`u?{pQI|tW=Q2vAOu%^P5}JI~1?Y@m#!aKRcmo;@6iG)3HCHg;TEqB8V%KzcAJ@ znLUK#LI4~io(jPC%@=JT@4gQ$#{uYmlnXrMF;jE?cr*t~T}mPP-TJ2NHA=NQ`$sS^ zUg_j$oO~2lfHe`wkkp}*br3aVJzeSklJ3|bv=MhOY$-S*3r;`5ow{K>9k``a~r=W!{LiGF79H!$1oV?y=3)8%AQzwf$rirGtn zDPmsC3QUQ339`205>kCCC2+0>WrWVTsaOW-rGBw+IpRC$VX%w)4zoW^T9%OQ^ zJ19|W4%*6QsKU1#qnivY!Spg0u4Z|(0dx_AE^;V+yk>9=L?!;{j_!vi&b8|0v8ykx zW~l{@lIFDIlArhf=NrO{M&85yCH4e_hZXAfPua;@>M_x*#teUgZt($>oezL3p4v&6 zk$y|$FgH&vr~Q4zqA6mVvR(Vl3qjP$G{q0EQsT=W7STm~o=-YStXbIKve^)2^X;Kp zsXkHO>e=nY$E@R|_NvgUOQp*7ibIqzPov${{aOx5j&SE*bq2E!s*-y9d23#ItVeDe z-C+_vBV`-tg#|-Z=O*faZawt8(vH2RX55N`Act#_h^s)tIrytCJ;Pa%$N~>=BoHUI zK-{<>%XFsV@Q(v6wJY2N@=@&7{rm;Aso54yEb$>p7fDBCC9$pXU^qiafSj${4ZTDV zQKu|7g=PKyAV=9G&L2W1N5f()R43n>=|04J7k;$%qII*$Euy41CklQ^;2!=c@gxLa zz1LnlS=}W&w36<9zL0XpQfTLwZ$Fdw3Rq=-D4}_S(6URvSh_mH-stz7Wack8m=w)e ziA$f5NQIUk1CX&9OnjtU^-`8w;;&9vB8;a3F6>SUv+>}Z^dbg$c#66QUqCUIFZPC= z(l1OLB%3g5OgWz){3=^l4b#u_G(+uYy$B}Bfs!)ZDbAbGqOc^n!$@(5*kMI$u*IK- z-oLhAVf6cLyOsWU*$;wXqLr?Zt;B-tgy`g6u)C%W%W@%Szo{Hg9PoH0GjuLJvOboG z0=aO@G`@9IN`(}N`b69nCjJZw*Z4MN$=H9+gYwkY_zHJ3smjNNSzl-)Mj#^vA6{<$ z$sTHiJV`-=!*$Yn2X*O5TLgw77n9BP8zkc8nECNQ2eu-zV% zH~99Dmijo7RfB-r%?w_#p0@LAHgeOqwl18V@$ri#y+m;Xj{G1*sw z5)_(6{~*UfLik64Z*A>A<&7F|gl`iq^_;guj2*>_6%oBvCEWJrDjKNO0Ng*A9P!VE zz_V-;Nv^PEDH8b?MSl~dtczq9!2zvEBhMJJJ*6Wh7&~>tChD?3`-G=R#ZFFdb*1zr zrXGXz^bZ3k&-ijD1t@Ka6p8)Og)++dQa7_PdOyVIb$SvoVkpFYc}l&jAVsWjR81Se z>m#Bpa%M8-{Qz|DcH;{_`2_LoS;_Q5?OT{^T^0xGL#QSu4SU|u%{NZpa#xAHNzsRo z*8S;>>_6Vt;pD0aPGb3wA|nh@bC!v!T1xdz@AoS(C8-w(Msl8vT&LlEX8Yl|dAJ%Yx{>IA!)((}VG-DQg*%0cQ zEIdKT>&26>9w;j@JckiOE@BN%5&OU$7y2UwX&6h9!MF3&h(X*RV2 zg50MmZj%WD4-|H7tXR4Aexw{9>k{Jqlaz~T|Kjo7n?O?2x@>(h+o`R=@o zYCE9xEQHJiQsd8JE?mlk3Hby37z++T-g0Z}sV79Sp01)*dh0ZQ?DO-?rKU(j9KPX* z`t;cqo$_(?gSCz8pOTwz;oqudKfgBkPF*PduSWE5;>PYF)q&p`w&IU<=Z{n+?@#nc zTeI=swPl>FvtmxpN<@CBCQE`Vs7GlmAhDp5pVq)SG~0N3=9*j(CqRBHFHy2eG|9z} z0=Kc;DKT)+3Nt(76MQY}a=~_)wcM5SybvmR2+ct;gI9;6g4o~?6O|(eb`IyGEhV^J zH^O-4CJUwUjco6)SR}bl^%T4j%MO{LUFzBTN_ybr`s%ioi^M538-qkJNyL9On~Gj5 zM)WW7vC%z0M(A^>rig=uJCOF@l2Ns<6%9EfuZx2IWWK2|xDmYW7}rtE?d`z27__m2 zYn5FtAM0unVN(<#rcHJRDWUP`@`(|T)eXLBPWucmPVQ>=EvAKcNpe?l?wYCf9vg9@;R{zXN7p?;2Q;))Pc|iD;t?0}H=R_&GzlFJ`ouN^? z_<-D94n@3ySN5?b{UNC?TX!G5K>B$ZboPwi;^~U4oJ4ZSWp_+PPK$Abeo6C>M?V_y zykFXiwQE|5w(|AW2MhZaM<5lQ7>p&UtTT<9a}%p@G(fj!+rrhcKe8ZIk5S)MZ{=)S zg6WiydDO#s=4hcd!!~dXBLRwy>N9^Xb%Ha_|IWWanNW@&pF{{^QBn%WCNglK+&Bwo z{S&Z8T(>gy=`HwUAHbmT9*pqx^Bs@o7GC0UONrv+mYSWouN7R-OJR*+YRlBVm!z~` z^1ij509v@VvKmqhg&F8+6B@q|3k>3t#B+5W_1W7zh0@ivc55_ zMw&EP?_`02koA}AQhfIWRn@#7qpA_#??rb93QaVhF>3eP+* z6w3p>A3qX$oGd@}5lMnf@~%7JN9@Z?0Cqe z)o~Vc=!1nw+6vO8-t5_$}$%}aU-!exd)pjb`ZQk2Xu5KmBHm1Rxj)ijQ;xK)F*7*jla)Hm# zG+pb{;=YjPG%=flghSE&8|vgKUX|vLoI* zNrR-=Fx3~$A-?qkt_9%h$Lzu|zH~m27BSdyrRbU&{do;JC~m#&or9_s_4;%#I6>&!{j*JROGw?2A;{!i+ zFYs{l#QdTiAUS&nyPZWtUyAGnOEDGQ45s=`w7z96E%uM*4^^(Y8o?ak;j9QLgL3&E zT1*q&v!LqFG#S8(6@zz6Nc%}@u6Xuzvq>I&BM{g{S5fod)W`%r!%*m#Zs49{Ra1c) z!WAl{(rT?J>^Ga0%>YnB_gDN~HTnB$3mgEK z$xv?W7L*~=0tT;f*q8QYM4i+E_wl$6QOco6Km{I{3Jk&GceX+Sj#ksme-zA6Rh-il znV3EAp_jv&SQ{qzZOIL1!q&Tkyg2(y&~*R}^U;~UK|cFQTz01>?{2t-;?fpJc7C$y z0{@e2-D$UTt(ZcyL%{fW%!1|u1$pPM<9?|-`B3w>mm4@ zJu7H?2W8az)A2ib_+jpOe_|;s#awAUff%Pkey2|~`8oKKS^VKF8UD`{+AJiWrfWp} z%S-eB0lAGV=ABQd5hiyz=OIL$8tA49283~&3*c7sqs;B?Qs^nezf9oqoTX4TI@npr z?$SaAhkd8{{gkq}x)7tf((U`|^uyp`JwoO}E{Dvm0g>F)eiSB!{`W?O42krMI8-W) zJL;U_N~U}Ssr+%=m^l@RQuas%an<*uFOPv9h6NG>Y7JPtAO%k7Cd#l9)RD>)=_8+zzOPe;RdS zU2Xq8XLs0u8Qr!zMkQfblW4!<*)v$b{2A{3_LW{rjRaij4E7wXGx+|(h1yRHXuB`N z2|rRe_R9|H@iE%jF@Wb?_@TW{xaO1Fg!5Y{>_Y!EsOhI^Eer@jP1Di9S)Jl_U=eY# zA+yxuhRj(WhzOh|(_$9fRR541wM8PDYF(Xh*E-zP=lSKxWGsdRq$ROp{#%N6)}ZC1 zX|nQtK8*xC2?M_|M>`1S`nc>esZtWytTAga5TD=xE*+s`QN$^v?T{Ic;t*c%8+`n~ z{DIdKbu&Sj`{zII`turEP$0Y@;wIPZJ1y%MF?#15w3H!Eve+myaPVe(R;*?%M}~N; zZ6WdR6iMFD1=Eb3!R}oqcE?Co!f4{Y;Nw#wS`q704!+JBJSxpQ85PUM@4J zmp$xtqIN3*>q-8ERg}KY5g5%~&~SuVb!HWFsAPG=m4oNTnm%>`3(JOA;O69st;@XB zxT}v`NT*fPwi8z<%5wAj&$@r8@MaN_K;cAIgavvhw!v3B!BBqwgD`O5Ycmp6M$(AV zpJMoUv0}_;fnJz1Rg`@>*cmxEnuXr8TC&Ct%Um?V!0l`HSS9YrpcBIvtfFsEW~A~s z@l9TIz%}JfSDG6@68~;)_i*zc{{VvIc9#IIPNfba)g@Q9`Cg@%Pw9|09yb}~F9qZ+ zwZ&9~wa>T($h_#Ovw0|MpDhy%s=X;gHGBiVij%yl^Oo{xO}(D6sP7lL?pwP5&6GO| z=qa>O@SyzX^UGD!=Tf=-j(HK{0Jx5yWjW|x&oJ0bB=8-vzMOz=Vr8C~C8-^LDf6S^oeAg%19r=9LRv$`&x0>4`@E%o> zfzq??HL8L4F#&U(zhBN{?H~wp5cCS`;V9sB7Oz<>y zi}~ch2f^hqa zQ?vUBE4Gwd-b?XTr|M``_?8{Hs(1{StmfuO%$(h*X=@eD0NCN^uEec=vE!HcYDtg* z>$KX}Y8}HE-|30@ZncN@5_tpJP3QSw(G*QK!zK;lu|#ITb)WYsTitmN^piz*JAPo` zj~GcxGWOOoVp1&of+**?H$F*MWM!QQkr+L-l5K(WSrF4Bc0EOzj@cDl0x1+4Za?!( zF}m;JS{70LGj`U~5sqVSeFZ>fs zr6+AZMD0x$I*Rc+acDZ@#dp(X{;{vS$Se-e*RzvcH4iMcar~EmkP?ce{Wetjx(qEr z7Cz5d)K|i!h2MhC=vZQ3tQF9`n6S->7+NoUib&__X^N|7oX276 zzFt4)1cGI8Nw&*oV~TtLaE-ac^Or1bwBRjLMJ>8ghtue_ly3xlc~W{LNw|log64Mu z2%X-_;k+TV)DB!dc#G^!gE^Krj^^PeOxitDcz~Vx#Gyuv+y4tgaWm;%F0o^nEj2E% z@Y-4;(g=4d0Vd$0D{G?oA(4-E!r*)%&wRbC)u8W6cI@Llo1WL^zgU~@m>`yCkgW5N zc744yvQ7OIf;L`7;JmRuYBza|D>9>d;Xi&;#(F=?x*P#Gxt=Ry$Ry&b!oPlCQ*#MT z*Ud_TC&;AMKIY@s%4?5E^_g>aDlm5jn>JP@Uz>HRDsFj}up1RPr5JowqT8k)%1v{> ztvc1<1PLmoCw@EqhYR2+Kg_{i#PK?2$4P>oX;c)z@_)55V%5;7{|KI^xJ%s^t-YVd zqH`f8g^YVd7piyE74w9N1=>Rd87Z*oA(wJnPObfoGC8>)?6_Of*uTNmf%@9xdvzQU z8Ye&S%VskL-3_NdGy>{&M%DSbpsHqKptJpPO6P<1-Ac*Ne=m_VvVYof>Mlx~!lxLq z$tSt?5RrBU&3o;H_8)GQ$eMK^fDn`M$Fz}=X|fz^FZ}0UP~f9~y((Qib;$&k;Wr}+ zNRu^U;LW6(Pusx$ks}B%k%Lr)v^CTNsA*qO&G+q#bXQlHvmW%{9~jm|SVWlVz*HTM zl~Q32y7{_RH$MZ%X#`)(#!*v4bRVc-IcYZvc@}XYf}0#0B1ZsAM4pE}cow|}QH^FO zFP8mTeLN9zrgtclTeK$cozsvAO_)G%i>pAq&1sZvF7%(F!s!jhq{yW&^pOG?&S1z-PAQY^|Src!2%MPh0Rds`FKj+U9%zfhdv2e zqAAt9#C>=KXT*O(ebY>`tGt4U2zLM8gwaIwd; z2Kua{L1HJngcc^rdo%B+E+-O4bPBZ%>ekE7N6S04V4&S8RyYY4Xa+883oR0xijwQv z$VuiCY`yL*r$-r+EK{;!LNJ)(_@_fT9#J4 zC5)bBtmSf`lF$+2L)8#9msd}~31AW$H;Mm&8TB67l@_bPIY=X6UWP2*e+5-iUre1|%4wg)<8`}$@N zuNF8c4>XP$2o;`XX1d*vV|D@T zbqsr#9kEg3k8gzG-cJXlbNyoR+~>gG*J361kyFEU^0X*R#3l?8kM8aY2Y7xF3F3PE zyyJR&5xn!a>1O@E|HXJyVjqahD7n84gyM!zqirh*B$5Ld9=e;kVFa z?F48KZ^4Pm+EPh=@=9|kZqXAMJqC~Kr!T|>=l`b+`Oiiffdk~NLJn3d(9HQ=;~2f+ z-+3PIjUcYfb1;i%?H_BxfU-5=7Z{_E(I>IWzO;zWbDgJ2JvLzcc-1_Qxxg@HlLS@w z@qf{aaT1R zsI%UfZ+zAbkm3PBPU+|AGRNP(WX(!Pzs8oa#@{%P_N{A2uVA9Ufq`K;tLoU+cS>8_93#yampO-Xq9IEkSxZ<+Wwjdud2v(F^hpW?S<^6jO=c>)L^>FRPHXw+7>C1Fro1>kjwzn#^e2sv)G5Kl&7gQQs(`*o4c z3slKT<0J~=!xc&5th@Ck%WKzwL-w*NJWDw2Djj{S0+ROw1q*6MZ!%4y6B!X8Xwc5_{Wg=Dyb0dk-{M*|x!Ae!k1-;2A5 z0|4hGtTOh;Fillk!o;nEN)kssR>oIFgjT?b1`||6Jl4&f3BOE36uh0Cf*Q#aOoSK(dpS6jnpmXC_ZsPCen>9Cl|nFYU;2Bts{}7 z_W`WsJ?=LYHH}qbdjaG#DbQ!{RGZ#Mg&JpgE^D>&xZlBz?-#Sj0Oh5@FaN1aO^`}T zo|CNKZ)DLsu&7f%^c;L;P`?!Y3WAn)lsWx2xwI35y=**EkP9%(e5Z_j#=x_VD5Pv546@ zR=AxeRz0}hDDQshu3vBg-#*qQU5Ei@k>PS!>1rrUZ91;+&gBr25vwi|VRal6yyP26 ztWg-N?tevT^mu*Bav3%E_`}WQz(U2fTl(jChS3`>AGS#n>e{@bh<)Tx`(AuCLnL;? zKZDeG%j9kTVjDB+_3s)xd?RK^-umb!s@-Z0zsx1sS}^)p@oVN$Z%&m6C6uKkwqV=cE@swcxfLfUd~W?g9P zZ=ie}Z}e)v40-My>D>w6r^m}0FAIK1bx#MOi#joO=&oa11s7};E-ZP#Y{yDGNcp!H zuRU?ffY4c*ix)7|%2f98#^q?IM?N+7&#TKzo1jq~HL$ zX@}LZKIw#B4syfe$7dpir?;3&k|#ro2n`!r2eyZ|vN1yO zT**A2!3giDFBa>aK;Ny8zr)MrhDL*E6`LzmhOs~e<`QDSPm@7sHixMB!$Iy_e8nS* z`p;f4U6X{rdf&_$S|CHgF{RsQ-+RhScWH}S8>awJ54R@m5o}=`L>RRe?3B35;*%k?6qm8R|w$Kd?!Y1A*2h7Gfyw%0cYh0bJ zrz}5r?o9Kl`xoG+wczHaqqNMS>`J1&?eYye{6pryxP=hUQDd9AzUsL8@-)?D2FX8o zqFu^5uu`I}w}rOASj_cSBoA5OvPmu?U?CtW?JaHjXr?Z`DaH43F|1ZGTqQek!h6JH zJtzLYPi(K2Sk(w^xrH|F9WhxG@qJw0961yIXL;j8P2Dhj=(pJ)=4pDS|FI5Z_o1`w zdR_)$&0$|gVf*n8;+5K?`gj8h;l|a47h^MZ$EZexmciO6{P53m5Z5T4_hEu*KOBh` zx<3l7$3bW>pwdK=5KTYq5Z5>6lQd(w{bTYUpyuT65ogKQ>(0-va>cFO1$N$oI??YC?#3VV6sV5>^+Sq5?j&H1+Dg6m21g%D z511Iv&0r}7fO+gBje6dkK-ghnt36_eQC08Hx!SgacZE5oJKS@qt;QC$4cCA?lYyfD zB-8bV%<|1A2qQ#c)v-Ne9LIhi=GCb;penhmVpADyN)nS?^l1qZ108ZA@|-bHVl{bV z>K4IhAcd5}L?{O?+`Ys^F&DSd&;0Cd2bIp{j%FHjeWKayaQd!O#(!>d?4wrh8*|hi z(C1SK5njXQpR7$SxZgDcEERTfEQTQMnoSJNuPRJ@Nq_~VB>0oO&ae;g=+n;0Pe)PM zO`o`Z>tde4v_sHMQzZ6jAsIkU{EV4=hp|mJmQyo4h$)#G?@kc? z_`-=89QXmQ?*UHKOz}$|xKENQ7^X2_*&7RZUS-eJQuP+A9CK?yKI3U|*a@gQsoy-z zO(IZ@QN!8|L&CKCAA%f166<|!1wZAtH>3fS?Uu%JG@%A$3~^x$TsrQV+Tvz5~8Ew#{C*iI}pY`e+p7%rx3lR zpvVG$Wj5+DqSExR?-oZm=J%3_QY1*n+cV}Z^Ln`mc4S-5NY2?OGyouf(@C>|E@~{T zy6%p)3q1R!6MeQ%d?$rFED*LxaN3}4?%gu()$b11ILSHap=9aG2LIZN-o`ADz~-}> z6M{SGbmM)Q7SHsmba}Fv&)j{3V+i(RAH%=&G=ZHt*IPGY2F z9~#+rs1ZXh@8WPKbwpkK+P|RA-#(<4kmg3a6F_j2N#~TiF0z>)ldp1-CJanhIb(ZIdWk0irl#Iun$$8G+<#FP{aMwOw~WeDE!Hg3g(x`l2#%sbk%bFRtz!PQ;iJ`1LboWHAL zPAoQ-7DQ-H-JhkNVj-hr!FA`v`B`;2w>Clb>gumt&6mVz7RduPjdpJgi1R8nM|@uZ zYhPRSSH|wVP_$RSwi$fl+6GZeA3Et)(|Fo(94^qxFnUWxm~$C2Cd7bIMYbUHhxnl0 zf9>;{n={-q_;J{XahBCSV%5rQxw2}<2V!k4^AEAeA$oLjXAnzhY8D|Wos{RggrE}b z8xcLH;~VMqEpN;Lu}H2n;p!fBM|ocOabm0BzZ`n}yN2(;jZJvPU4~R6*y>-jJr`p5 zaDaVayBi7|VivM^tdOwUP(?0y;rcgPmvzgMGjf2$x9F#@|M}ljcdsBa=;Kjceu>)) zqxJW=roJ*B^z#By%*I}LPYpNXS-s}iQcjgSWguP|4Kk?DPd~wPbQi^7&DIP#{_J2g zgah?33p%Bo0ATK1C(1Ph3mcbbJ!D#fQM|Llw^`KZ&mtwzwa~0gL0|yP^J;!O5$WL6 z-r1IgfyyiD?9sX1LeNbZ@1Q3t2C>MsFVk)^-awwOEO_T2hV1t&o&~cByx5tsme>U3 z-hU?Tw4)T`3giU8gnK|OOfMHpm}^;Ii~&FP0BW$7PWk_Pa?X>!Q;q~)lecB+UtUW| zBk^Q|J-^mTKs&&0?G?RODU zM>eG$F?_wz3k?G%SaMqoypsJWuMp}ygy&I*EMmz%N zd_UdPP#y@#tg+W)o2q&Q9}E%<%%CtK&PsJX0wqEi)4c`I3|A|uW7BQIe=sd>3hvEa zo@)OC+kspi=b|V3@}0p!rw`>R4PiJ=XqjJ zX|clbhs-db8iH{_q=|U4&^b{dlxz$@Cxv6LVU}wUKJYsJwoc`-Gb`ZJT}Y(nNy44p zH^qFf;^rH0S!Ek1>`*KTIf5y3m%*Sj{qQh>!N_b3_EX=ViQ@ajcB9zn2NO-#)C>k%96j&$9HgoxnMl?BA4_ zhj!yG@EZrAa+!sk=}LIXjKWS75r#Y>3!Y#Zj&88P_h%jA$q}cA}JJF20pArqlV}}y4O>(e4Gt$I4C(mrbj`&a$qqj=F8YJ4MTr#BQUDrrzkC)$ zR0hC_Jso!mO)0^^42+A-aQY->HdP`dAsXRym;BpD2bSBfoUZpPd_DR4f1DCIH@D`< zk(`&T^CQSdC=))ZmHdAW%ye0X@Yaon%U_$Z(PaoHgYaD}wV6*wf#uxfam6x2o(BB3 z3APe#^{(itJw#p~eJN@s+f4LiPS3h&41?XBs7)JDJ}GaSN3YSR4`XH{@_{&L1?N}` z%dr{vk~CV`_zi(9uL$nLpi+}2p>_E`{qLEMgyUIZF$AgIm?mF?hgN;P?p$j5Fbrrq zgK&)A;{xJsyEZxb4MZh#l!@9dO$D1F?4X^f!k<~t)K>9s(Nb{EiGJv~Ii}fJ1Wq3k zc^QaGY_}K2di5rV%&LobFx>|tWB7 zGQB=rvxMTn8j_Gl1G0{_@0-KaQht1(>4=z{veHJFF~q-zi1t82H8OWdRyI`=(PA{5 z>pZ*1n`Pp-*}7Jk5agTpuA`l32!HGkEU&8G_5+tEK&lNSydi3%?AO&R_OenQ~DC+Y31Vo#1dWP3L#)R8OPe4mo|l`!Gh z=T>-pPNiNRT;lpY z?&1k}otX%v)MhXr@$|2ay(P=&X|@JK!0}QrCJ<8e*9(qX1#|$nDrDE9781a^N7d(t zj@ZpY1~JhXTc$>Y0Yk`t=5Vyqc}gM==|>y1=C%w>c3cJxs4|p0+K})Ypsxw}Ch1h# zaK0!Z?hAwZG--J?0`2fLPOZKE{6vWf{&B&3QEg#a@}kpm8g z(g9!1lP`mPd785oMOVq(2?z~g?Z=l!9IuI5$hJ-nv_eg8KPwiqykcm4YrWSYqpDg`z?T0*Z-910mV~TUbUSg zGu4NA{CLkCkA*QZku9dB);H$OewygXcaH>)o18M()QK9et=3z84fj8k#>*<_#^4Hj z+`q2=_#NEuSK_zz+g~)hGWB{^_<1tIF|*3BUVXB*+H%=wpx@LRA-JDFAaBGU<*`<< zc71E7#y;72f73GuV~*|J%lf7f(uy_n#;doY1VAB2EXcg>gA)V=kUc<&)&bvEH0G`DS|yHzDupI=Kq-7r3Y>MECLXxUE) z9cB9^thXy&C+@t)6Mb`cn+y~l7FTCB?oNbN$4+VJG=?`rlNQ^g-l#+@Sr%+CoagXL zwqfKWz{(Ey6WpcXy)xdqk~M` zmXD=-@+~(;+^xw`m-D7y3qd>B z8JO(mMRQDqYXVyqOlv$w$+J>&{D~jyIz7XgY#7dDoc1l5S05ffJwfRpXT8`lDtsA* z=8Hx)J;mInR;MkVr-`0_3kSGw?)P5pdK1Olz$b@5=*V6<8jaMERZP5+9b$r;M^_*`U0}rN{Oh`3 z?374&P0c;i-7E{v8vGKh`>X}nt=peqsx9p=>atQ8&6b$nIJ@_mQWvMK@S=sVqdfgQ!KauzNe}MBWZ)ilOeAuLFCX*r z79LL6@knZw?V)?#E)r4y4(j$kIwDK*o{0GC<_Ba^1G zH+9NKa5riNEOXL5`ZM=~n|QtCK%OH!bloLRXmljtZ%G_NLDiF;P2Vwmw>(vq}Ww2L~<<+#vO@^$8 z;{aJkzI3ruqyuWxVZEOc*#uiE5!~yC`?S!OISs?q5+{7OuW}otS!St(e?# z2exx({WnONKD*SEFnp`S>r0fMwQ=#jAJnZM&Q{u)0VYiobX*qBb(agNMV7(vyu zO=YxKkW$CNIsb@FCexdFk7Xh_&kGpHyPo1%mN&#~U}L>2(FRf#=Tv zx{Y0%MqWW`(FQnB>GFICVg4wI&T1>1I8?YqbYB)pO@nokOI>LP-#YoL^FZh7_I7+m z4L^Xgy!pU|OQ2ibVD@yLnoCXU92L!YEsY-b7%XRPnZ_yp1L*IY+XZ2aNIW5kqK`$9 z516;#?aV$$urr!2M5;2|nU3xWMy2y^3eSIV zQ}Gfccn#(16eo*^gNTvEMBGJy?R-JqM)J3;R&(>gntc(^2T(n}^L&5>&$8s`HURtt+7>`^!|&o%et~e1f8;1BxdCNy`~rC;sXcQl_CHtkmmpwLssVY;)~qLMpzY~ECb zMkX(*W#ExFTW*hztC~+DI`7q)H?z*LgD?&tzwwEr|B*duP1daYSk$!)3T9+Egwb?j zZ59mamI?K}(bayBKccv?r#>~jxUYQfvf8zmg}C8r5C&2FQ@X1`Ibv^nP=;lBILln* z`Ak1-%+-fb0yWth!&wl9RZ)nTm~D1m*+a1V;_=u8@>{~dxrJ& zlRMmp?rPW>B)1jtRM5Q?QSn}fRwHJItmG@%xY6RXHtzl80KPJA@AwvJh1<)auG2ru z_es1kgL=QyQdzlh;+B%&b@qYW#DuHB6y3E*9bP1IH8J3o5%);CC&RnGlTGpJA3r%y z;;8-87n40VtvLKV>>9RARmxs!WI<}vxj#=Kzf%pZmnL~Nb$@jzT=Ep_wmCFF_+i2a zc$)Lw1-U&arN93TAYJJ3R%T-wtr5J!z!G(-wg^4~(vo0vXlhy^IqA!W*wdwM5)^)k zr1sw9jv&&`d;gKiu;tuSe}+0D{>eBOWVE&VxecYMj%R8UT*rse02xuwNO0;n7K>%H zBin*nEgpC4DKoFI>FJ<1(MlowH7eYTxs4eAr`bkK+vZNae=2EZc#^bYI$c#^WcB{2 zgyV)4YgnI54bpjem)Ydt{Do}iE&=t>hFAxmbql)GoJ$ar4mqX{r=(m<&mK_$v(m3bg!wia!*^3+B$w$*Hk z5@$1++duF)e?k#xQsh>ZQB^@>N_$mIE-@4#E`sSlVXXwA^ZKlO9Foq+Xf zD4fIJw(y9R7yuh4;VBcBl~C>zo-+8C0S$d5?`DPcG0lVpHyu`U4^!N3#aax3^+q+6 z!O1Fc>9sqEtP%HBGyc@Tn>n&Bd?0dPMr|FX6t%|BZK9hu$Uh*Zi1~iN))7T_HRoV& z`~Aa4_o#brPM4TA4*-!9t3kWYn8}+5Q1UYD0YL2v=~_(nB0)14OYmFi@{?p}p=wf- z5j!5$pWqrD!kxCpB6QwNFJwSKBnYFUW|BTNJYFPrQ@mesHQ=ebAH#iJ8&YVQ*$HQ^W=K9|s@>CJ1h%qQdCaQ*7Pa<9w_Q z^+IH_F4ThR{(JlN$6Hs`?Ge;vU$AQX3Gio~3!k{EPOD<8LLF+>P1neRK{XVjzqN%9 zIrXOZt+$&B&NWW^Tj`ZAW?(dC;pW^kdViT|AXhW2WRnEK6h0H* z4uD{f-<^nDKmmcV{Sn^$w*&kg;#q4h@ag>rJGjdwdQrJ|Tyd8VCF_3FbbD(^+OzB8 zkKv1l1qCts*vY?|_>@&R|8+BDl zWG;Cz;oTl{VlhCf&D3gNF^A0|chrU*1cQR|qO*hwEx-N@U7Dpx| zzSCb}xzL{PRsxryRo%E}oX;Jh+3Cg?Ff{W}bQ|q2VrFz+@B7Gg>0g)*NmC1d`G<)c z6bPTDRvuqX1NUzLf_26#(MzWE7t(7&`=Vu*nW%dj>a<1*Z)iXpUhv~2GbrZ$z67;} z;a{SIy3%4stvjR_dt9Hcnz^;G7x&cFqroQ&wO8rTsSR-LI4G?2_F7MGTl1{m9%36?UHw7*zdG4U;mZK z&kKWFR-o`I=vln8GPF=#lfkqI!k%z{MIyS-uBtNU@m62W%|QX`ZC^F%<`GLvbbAd{ z+HP@R)M}O@gRF@4l6T;aqUe6nsnUH`zsR+JnqY`sWkEozNI&fc*4lL}>Kpu;W4OOw z(&OQuT}LCk?oSvM7lkA!UJ8$nQ+bI^RzQO_GsaEcUvcwWRBqJUO6RIf@nM#U@7soV zq9=*neS9GIa*kN0n@FtK)^Q;0|H_A7TV_jEcmuq!P27)7#u_m@1z}3GMue~GwS_HMOR`OEnnJSJmNEFRo<9#ejRz;p? zNi#SH8OC|`tKVx59?dIJi!V4F_>nDw%r}C#a3(D&Zv4)emZ*1rEG9|zpJjpztFM%y4Cr{no%l5YJho6n zzP`TIL^ndGr4Z5x9qJLhI_jFo8cyBjsZqEM83ZA*-r1Hwh6yC?<*47~RiqTT+UqH!=XDPmx~qch2(E-=z>j<>S61&@NsyFH z=^E<;f51$FL~|H~ZC;&LGHL@Y&+NHF=AS6iv)L)I(7(@!-F9ZgKJzy25gT+K8Z#v9 zIVoOT$+R4vMz{;!a#coP;$1kfrfiPgpi1AW7^IWwrrhRMu1(FplhvIaJ-eQvd~}G| z>WQ4a^EQTA{LiZG3iYdr(eO4#*LQ|X>b~2)8rvIAkGkt-dfZ>FLA^ub#AFkHF@=iw z&^KLzY17RvJujnN+z0Pa4)YWWY&7#c)U3)b87nlK8F-I_G8$>G;TE%?NOp41kKQ$_ z-y3uF8hWb<3bNGGDEIoScm4Ao-ikYwXLxPoO6Gi>=kWP1UM#zPJb#;6!M;h3tYnjz z-QQ2`8Q;=tnQzHj)4yg`TgaN;p)@iLO+DRxb2zF%MU7%^v}LVmAX(8h&YyE_sd?+x zsjk}S{se@FlSEBu%75$%Qr1Lw4q>Vq-f)-xH6P8WL()ShX_^w(7h2BVNw?zghf?`fnY>i8EfcG+O}n5vVdwr+1m+y0_ZO6uY}d4;oFIC*{_8k>;+dHLwE zP14I+Ebkr680%3Sc3FG!+p8v*7(l6pCoHuuprxl_hIy|i9#I7t7cYKj;CqC#HUDz^ zcZd>0o8+TSMIZNkSBu$R%u|TyMpfeT`LJDQ-bZ2k{{^gm_eTt(+5O|Y51PF&iwi${=+ z{IhYVXB%U?#MJjF_|C9Py3L>cNy|B}3?SUq1$S0H2-XZGzlB1;jK|&4*(T9J-Qdw2 zg%VTs{8FtR^h_$ZPl)LxUsbH@@myNdT*58m}JpXVYnPF{($)8~eV*EO{wl~%PIyd_^ z&kW`XtLB#5ZfktjI38PdWsMHpW?;c|Vc$i2yNeg(FR-f#{^0b!cu_-5%@0mJGzH?<@6FwE!3ZX-{FbPYe~u5x|Azu23L@$BD>C$6?;$m;+)P=50|{9 zX#DfQ^sn;^!it@7lnb7rq7U86bpVHvU3}%qptY$1ndaZReoTms$NmT<`OAzNaqn#f z`=I~9=L}e3`TC8~?ioV;Xez~BY~*I&Q4djVU3x-Ns33a5oH@aso-;0LlQ}{ryh|<) zb@ujdz^B)_3f07%%@^{ID7X)4wsxV9b7V91b>~(}oFP}#xxF>BJK1x^Ik>MRLf3F! zOrbg9yJ%+5`zr8^6VRQhK7+M|F|MoLXmx3Eo<0iY@ZrPH69sNY%$wP}=>FEl!*iAj zD^dRMKhfIQLRF@_UbD8^Vy`M8o>wmp;_lvUAM$QvtLJsWosB5WidqS zMZ=d1VXPLp&6(-=PL>xRTlY%O*|TRqY&refk6o>7J)7==`}S=xR?oC}8F6jkOjH>h z2SS4c8Xk>|_J7`^D1=GT{uRP6IX2Tfwnf=An(Ky94;M*{WJJzQx6V<`vZ`Uvx31_K zxv|aJ=1}2h2Vt||854If?^#V6B=98m)(sj6 z&)U8G*<1Nnr0|GnTJPP!#T^;L1AHTiOWHR&EE9Tl` z?IMiS{*1T_oCpikxxZ}T`C&YP;m1)g=-R;YEacf?_)bzRvGC6gcSJEv!ZkwK{hI}y?!Aa8PT%Ttt*j0S?Rlo@@ z+rm{ACs1zkC>a{WyNGby5;yYhZpO7StjP0Q0;cm@-b;MqT(ICu@bgumA%p@KSvtSe z@hk1piY;mHv+f^WBO~+1VnyDoN0$XogL9_qadd=-ttxp3r_@*AT%oN3<}OjG-SbbZ zukmYM?ex!_IhnZ{D|>~=xavAErz z2pGe{y*U70Yhk%{3DEWM%un;wJ=tIKcvd=~D|55`Jw9G9@)1S(wdf^0o}L2cj8~7M z*Of2ZCgvRq4rn;3vqXvZhlZKbt0WAmc8KrWX!7~~I(#eV`+ixdL5DQMp9XtsaJHT) z!rbH+VmQOTkE2v&eD%6~S#EfVxW49?tlPkM#^AFHw=`l=!i%IzKddQ6$?{su_x3f< zB|LB`i3nUSOQTJ}!A3t&2PF&t3Y0oty?XHn!_4GC5f1VFs70Ae(=a zqJ2%oCh{LfguH-aRbsIRl2!szdIlS;4Q;Ja_{dnbC^a0kwdF(capmRZp@mUfFIEAm zP($BTZ1py34(oar(Tp(L&$$IxIvjW}lk0hlkY{Hjs0Cs>$1r>9dc7WL5R@fO&6VC| z8ta#uU%Ytn#s4GgOTekn+V43|MH!BvBtvGRL^5TFjFHL|l`%yj9Yl)ikW57sQlvo% z2`NL0PKZ)y5;AmXP%0_Wp!8px+s@QTxIC{RJ&yDp0K@7; z6T5#NS`|&7C+AlR=DFRfzT>H8UQsgEn6pz`2i^g;I7t~mtPXB3ZtY);Nz&D@%N-G8 z{LDZ6QG@hgeDM}D{dSfjq#2}WwS{xj0$8zM`q|F$WM#uRn)t}3{AeNpyzPCWi#c%q zAWPMCCEMvct4=M`sPWO9$g#WD1&=ho?mz$cWiY4(l8lzLVlL6spIAX>;nlLSpv2p> z+;7F-x8`q*vngLcQ-1ObH2w&1$r=GcA0FraR>Li_geLa)#7!39#IuEp977U))FH)9 zLMe12bH0fRK+|J{?yTJ3vND;CtKEz((#bAk7w9(f^p+gMX3fIEKp`>n-Y$JYql=i3m zdx8pV#+39AZ>JyTLq0x7{lxwEW)AH{jtcuZbIE@4g&}qd_!URNj}mPX6856!dXmVE zABOg*1@x8P?QwgdwWB8m&8o7as~tQ4CIAKJVbL{}%ls*12p(zC&3OM9p*)p#qW3!0 zVE_0+m_@YByf34E3{G%)zHXe)dl~-z*&JdwSPu&MuX@&|UT1t4XukM{QnZm)?<)=I zh%LCY+i=}B=kyA0za0d+ty$2WPo$<32k|Il{Ldp%O#`D> zu8=nnPfPwABJ7-W0MOe~9DoULLCo+^Tl7SV{hK`Fn-y@OG>lx#)3<^Vwiz|vpG!`) zQ?C_gF<)-z=ZJ4ri_g-zef0^-z{9`TC}nC+oCc$uAC*z(x|Crl^1>I((g&U{h`4{s zpLtnj|M;(+i@(;4yqP$BW;dexpucio^$)}Fc>)5`P`Ij{koB*ADX-^WuRakDg(4ub zxQ8C|@c38cW=j<6oK3Y{%4wFY$W}K~=rYXsC_M7XpqhK~kI!oApEe2F+6Y{A?+~Xz4 z`gb8oShTM2ir&19e=i3~?%sliTdMIPi&{&AXGzKCp8ogAg>vA@Re8+TnK5y}Hc=|n zb_~3sWxhs3@am3w|I^7k+I0{WB(ztYNLTe(@jBmMWo;`5#nCPz@DZ)VSM2$fvz@Avsxh%H z!_0&Sc#$2Z7l1N!X?qA8{XT%UXaQoP<^cb#1H%RfsD_fL(BrybaKxqjJk(-kRZ?PapS_{ch$ym>T(l_CDsye*Idr!(_7J&WC%*kwNGF-#eF1B zIZPdT)I6FaQTJPNA!3@ZBch_GxIZCDyy8+#+MDyT_E znfyj{EmEC###gu*@JZ;c}wCG<&%mWB4BE0f)bILJ*mv z?AW}0c=SRYuyi^4+*Y0n&)#LNwuX1(%jizP6Ur{UvE=0I-?#D9so)vRP!#&duo6Aj z91l|t?{ZF%I|u&YewtzMbk6R8>X_^?^h$p7=8B%fXh{j3;BmZ(_NO!W;`Jh+N^L~9 za+vo6=1jj(x+H%}GEZXg(U@MhA;oP3jw+o=Oqws?FJoYMz)p7RbR^k3IZ5|R*N?Mq zSz2G5Aa!K24xz6h-*A7W>cqD%$u3AMP!f=~RB!vd2gfHc1Ew(-!t~i${gKyzDit_C z?=9H~e(yUF%>w(kkc(xwnTu&7TI1bKc0uE|E-i7nvR8=4IcwH2M3H$T+-kcqjk8XS z^<94x5{WES11$UaVzXBDuR+G*~ER4qm@Fseqf~JKht|b4BfhEeQ z`7WWN7ppMvzrK4ohuGlPON37J|G(A@=>fu#5t_j(mV_+KZzIGX`sG#JnUo;FGm8=# zN}gLUiN2}(NUN*W=}^TSLJ_tLOLQePHQ)rdst7qGAVpADtV81n@Ux8%GI;P|>17xq zt&!PI38v5;K!&@j_v$_tB(C`w7&$=4m#bN;DrWAEvf>LA1|q?+Jm&4~bqPg@o=sUd z53nhf@y=Un@q7Q)nwFL|u;*!xSMRw}mpN5plaFrdNBb&#e;JQH8~z(fCgO>kq+!5~ z#RW_HEyyVhnzGg0LEM=ur-3?3L@%^BOzwSe$IZQC>#$Q<5wxi}emRK}`jxNlA78Uq zL-_33vtL-ZIY^I{-_G8<32QkYNZ{iV4LrY#O@cl9-|F(v6fujGNSEU4_G_U#s6StEgh!a`JQI@dbYj08h30Dj~fSPBGrPm zAKfM$KCF+CTvw(o6uI)x$NGPM!dTnYtib;7XFmBa)1?dpbWcmr)M^%p6keyL5d_bI zDMG~#-o<#3n)3#*eC;R%{odzU!Jcy~ubD5sP300$R0yF`vw=oDF;H>6so2}wYZghfCe8oi4!m#lq{3~8`Aj{a6w}hOFmKf zH^!4Y9J_(!|3z-QKK(}C7Z4CQ7j+n(q)F&_ZS4mJ57qy&U|Mm4Q)xDU?qg{NxV@He zGr74r&1QK5{+#>JHOlPVruBd=aS(C#7%tQTk3JB)sC%8_VF2FjpAnEm89LDe-#mqg-cwzZIsgBDzzi3HEX_J?J|B5+p9qLW;lIAy=#n@?7Ujyq zepW(XOCEudHBLqQEDJjq@@A_x-%nLmKqb8E4_AeDEh4{S2>u}yKHsM6=5D*V4x0-c zZf@1#dH%G%@cC%TFL@`U&?JnGJEN#Sj^o?g;MXuc%Zg3w)RhIRzfB;cnc7$SSI3_S z(~CgrybD6jW{g7vu~NmNWk%~E$-o$GU353e20d-O6+qsw7sO$5v-o91Q2- z>VJQL+Jo*Ik1QFzY!X$d`;h5;#I&G&dGnrCylEz zW6>PD$qMnG|B7ya_5qTqZ%xi}UaBT7{J`gL;*CiG;WGP6y3Rr)mjz@<80$ujoCv)ho zJ0GCWxPXjqroN)|AmG_Ok5=i-UL#)&+wj+Ks$r06v~BFJNhFo)JP5Rp3)ZUxWm~bC zcjP)Yua~7_TsyDn24-tZFs?fN@;2Al9QKM*J|qqz4U|vh!PmcjUc{NX=--cCo55yK z9_f1{FFz9hc^W*1wB3b5rU0nHl?ZO%oQ1tiCvuxL3%^mLRLhGOZfNJ;KUt`~d-BBE z1X1aXfCI-35{4osc53qsActz)t%7ycg_a2~QMrHTi~#f20>Lc7>jnU|Je2-N))xDp zq+PAe`;BsyUxKZz4@{$h-{LACY1dxz<88d3K2|ils{+cA1q8C@yJ=9oaOZj29v4r) z^tUML9^E9umzfb&{-yf+SK#-yTRo_)g$0pXj|DNwJqkl0+w0fOM}LXDyRA3GW*-rG z#<6^+P)>wzEZ*%^fs`4A3+&1gnfO0j04n$hp7n?0p&Lr4O)d(46W{gUcz=eI8P!mn zFSC#DcZpVi=~um;G0i z?+-Vay?kG|Ip4kUzd4k7nY8ii?%&=#`2_@#SC}T6Ng_YW!H-B@^6%56FC*_Pv1<#* z3fbLgw+RxcIU}6Gtu}^f*m(r@$Ixd+Fq0>)X|pt2fJ(Dh7vgZ z#@eB`QTQe3T4`vKFAZOR z*2=)4ZO<68@5oTYmIr!;!_j4+f<#VeV3&rxtLv)4f>I>n_Vu zq-eLTU;+6H|3Qo*2j{Ggq*c7+pF4N!NI=gsI@BkmAkN88oJ~c*1a2jxG|Up8MZgk)ceU^UQ%}kzv#bmbt?y20k+88-ypJmCZl> zdG_n4khQ(djM4_M&c>B4$?!c7y0yq}JRB9ujG!Hy+QpE!t<&Ln`LhTL9j}YQ;7N(7 zZHn^Y2+)l>9*Y5jazGGT%#>WTzU^ke_4a(VSX8#A5n&@W#};+bl91Eb>5$Cpqn^R;4Izn(R0t?&GMZf;v@<7{`9@=x9jC%|TP z$>U4~uJ)CTY1JR7cWWn`a0EuZG!iCn?BtiP_NbjMrxI~PiK23wZugW^`ST4FG>W%% zr2!~E#)jul9JdL`70S)7Z6sRx3N_jS8|`L~K?#HhVLi#sF}c6dhsfL2%gg8?`d!wX zN2-FFgl14jQqeA6+V}Y4n#FKTO+s|dFXH|tOPk#n66-59ui<@}yz>Hob6!H|+`s?} z*Aky=SCB{gY_4`A77}g=^m8K>!SB;r_2F1y{QJ|n#>mBf7B%(4_8vwTxM~5vMm}G4 zUlMVTAmPD01jzg62Yn%XS2iK~3!dE@6@vBr+7^FY87R~_6t5$sy2Ag4(K z718p!1Z{$^h+?(F0zo8w;dPdsJ)lWd|PjI>xUlw592!16Nw_gY8P-8W&{x z_wJb`rC0l#%j951_tOFwWP`D3wHXgVnn}SQas7|9nz2A}G83TPHR)Zx&0{A$8jmkt zjNbk@arLRXD=s~1u=nR&{`&XgnL~oI7Va{8CCn(zGK@AYz2kgh+LC0H4DR=`9rQ$# ziTFKna|{e6rQ1TnNAENpG#H|?geGstSA?i$1?s=$?!T?u#5%iXkT%aFz(%-PrI`qP^F|u6CwhjQHmkz36RJ?UQ>-;Pz&9aPdVW@MK>{&c> z#v?McM)*^I((CkZoMEL>A6zd3R9YX^psX-4s3ezy!G-UCc-vHT{^!?wktEl#hA$Qy zB7GGw{d%&xZf!fS8kbl%2ZdsvfsS)lo%Tua_j6b|`qC)82)lV@vh+dk10JLJZ6wUk zz-z5!&xlXe&ELO%y+Q}o_vzE8r#}p%#(~9kyn0xeu@xO%%3LJ?0|Uy`!ODmq;ILZa zEMGnS5m1~f#lqD=op~2Y{i|e6>d%<@`(o!6e@LZvWs>b8TaX69%b0gb{oq|}njRg9 z@UiR>f_2%!^uW?TfCZ+M?9SSLv{UB6rm!Dh#MvEoqRt3{4;bBzOKJ(+wy(C6ye8s6wRBD!e?la^wqpD zbld_Z&xX&HIZ`ItFjjmhF(W|NWRNpf6@hUec!g+-%Qmmolxiau%Fa3VM^w3ErxCr2 z7M1fpN>&wAYpLL?S)u7~8s&2A1`yz+F^C!6Q=O%%s%uXfYw&etKH*6)o?RcEtB;KV z>qc74vW%FHbstGHjPdLHMV2VxQdN_TDAlXrjL4Bc(16HsSX14!ZrX|=3>z#_bX867 zMnyU;!<}0OwYtx-?XXR%@+!=X?H4p`mAtvn)IM*9G-#1#dEd7GpBkW(%jDJb#QYKf zcISL=eB8QQcH;3dW{_t1fbfw#aCR6>Z~izlp?|KEENu&+XDqp9^E|-GDLrtu0R&?q zV#Xf2&h`q{Cxv=v)Y5tY@~#NeGq6bHmx=xX+ zm3Cgs^xvOU6x%6P*ZO;ZO^uM^T0`KzgQLE6)Rn;W2wsrc1v3I!v_xe-1c0%`eQEWL z(=y4ky+9lS%eH7}8cm;h^VWf4eQ*$5RX45%7&_6);GfQ@ z(tX2V{^X#seyWiFE{zMcH=tE#f;&f7r_dJP4F6#ZPKq4rdH*zV44TOu9114oe2+R? zEodzB2avc%~f48 z@H9lquB{hhEAMzcK|Qb%^)IzZIcpxIg2|}CL@x04hiF%*TQD7nYE22Sjj(p?$(i;t zMBP!BDBkI?AkcX-YSG*Sf(-a9n97_;ge_Rcd+Al^9i*m zCCrs{INwOIo|<5aSE}_zO8z6DsWWfm5pQ7i`8mzeUGoG!aBx4=t`>|9Ogs zto2EIj9ip*pVdgRdkZqhZovq~MB5MVnVL~iu=mK@55IIIrs@Y2$@3y&ojYINIdm~! zW&-Oc=X9K0zWbM2t`j~YLzKo$xP$?k=$6O~+ln8kT_=t{;;taQU^~y9kI8QAj$&8P zHOTqz{x*2ZFr3`KwZq6?Nhpw?r${)@R*RN@IKSQq5yhpOMMj!n$xMv)m-WvzBg4R+ zp-5H{$lyfDO3|;Wb>u)5TI)l`e_As}@GQ8KEA~C0?bMa(K&K((KA+ zraEfI7gUJ*_e0>lb|D%UIY1Jn@v~fuz)Q+`-nYN@p=o#i>JM9~TAlE{csIhZmT&jN z5eXEpVgVoe@?_2Odw~D1rAjo3A8a$d+2e7{7lCFWAIoe}W7;BRJp84NoP}RQ#nB91 zi`L;E`9B;|Ill1bRw3)OcvGhOzAj6*rD6SfKDwh{pP+l4DV?ZMZjUp+lh<0Q({U)J*&P2-9U|7<81 z2ZXB113kqnc*LmAt3;nJf2t=~G|OP`hPV@wybqFPV)i%%9=apHCH8r*$~3i<3(Va* zVE$3GHmnhp*l<$xkH3Bd8q-;>R-h{%P6D^dJXAHyv;FHhn2oLV$Lc4G;bYnko zDSE{xdz}0*FO|gL&+?T4$acGb|132HKT^m>`WtY^^?vVFc+wWTsi4SRYS{q5`INcj zRu6JHn7)J13w$jM4sNIm)3RS)`(AqrUY&T#pQ-e!ARwLFO-(AxbhFgLCWrb!W|2bP zRI2$-B$Rm+nn_nxSldopT}T&uHrugp49xolHoDZ) z6*i|ad%B?zxesdWi^0hULs1S>8%t_Ek|{zr)UI*}3~i(28nEvg1!FC*0j2M2prm_N z5f$c6o`XRT(Ggr~Hm!`Xt_3tgpKF&n15V>->SJh)wr9W@T6EDOIr3bHRdG1$6D^Z) z)_ihu%fM$y;q*rQ^#=>^+UTb&S^xQPX#NG7<({D0KTJfWz3!rW?YF&*>k#&-EowWs{L;C( zxYY8s&z+dxv+IL8vujBL>0ttlw8!)iHBj>L@KpwF7d$#8j&8YV|O8Mu)!VQ*#7HkykFjYPN8&L5*vT;>JB6b#@X;z!8l!PLH)89n| zPuR-rZE;?-^4#+C~ZRm%?NQ=XqEU|-14!DNu8NX0=JDA4a zrAF{0QGo4@0EXq^$oBgmRQc} z=XVZ5U)tGi>t(b^smQALm0f;%*W*a~+{s({KmR<2 zuBKmbG7dAhP(kv@^>-DWUg!Ot)_t|+M7gBiA?~XQv23T+!~K&O6U3;!>y-5LoWUL_ zqDq_$#lS{y-!G>zb+H3jfFg@wi7g*B>H@8zwyE3Z^RFL4C*U$3;>YQ=woE*Ev75oW zr+LS+qc<(bQ<7N0)_)L{;CvxXH;0!*AYuX}ybpt5<$R^s4nx1<>-u?p1 z=efYD!}kApEqo}*lS805jR`D;%KJ5k5;;mNtGhC{eRT4hRJ;5qJWK|O|EW{`DHvy| zzoVoh4_%(yG-%X5#nS*T+83hBzU(bMb|D(HAuPEut&L&jpzz zis__m%$9kH5rt*=MXuORjh9%2;RblJ|88%)Fdl4%AcH2{rd`R-FW%+UbO#~s0+_Y= z^A36#7AFon5`L`XufxnYC(%C7E4{V@V8h=}4^86*y*O@we6vdX#bU!VL5O)Q3 zzlmLWF!8f4bh}k3_MC%*;{uF^9>c-)@{>Izf`Fvza}BT53fRhsSx!ZF^FdaxENcrj zXU*wClfj&PlXQIj$CB(U9 zU^+KEVOEH(n|7D~dI{hE+*5%eZOT{euN88hHG@_p9l3~lO(0>eYgnk#%_zK_vWRIf zM}qpPlVLIALvySN>G}IWf4>64-s71zJPlEH>Rrc|@2|h;EDgjW83pUCsA7UDw8+wu zXT1TBbz!C3it}Ob9?Kz^9Lh@9M;|Qj@!`cSH?phiYx(j&zw9QwSJ*ebq%~it>|bwv z5q6V~D>m!VtEY(Oj2kpVhl?-^y~Lx2v~e|kPQI?ut1JZSL)%Y1Vrx^%5i7N+nkm{j zm&};j?RB<3l+*#PFd&ejuonOR>VI*Lh+L^5)Nr?J`Rj#jj!A`0ks`hkmPFX)8CNG- z^wUyo$x(R%EQm8OiGHOnrfoBM^xsH*;M=wpkikICje4WGo9MAB8j)793!!^I-yg^+ zwIH*HpXR!Pl^7C>JU}2Dam@wV^{{uaB5~wrRFH1Hu@LrmqQ3MFEI{W9+bp}UU(2O;i_z%i>dHhW{E+KwxjpwAXA9{(5X{FFxDBi-fcQnvkVFPoS**0dmv>i9j%FiJTS87nQ+QMaq86h%h}R&k5{+^gJ$HtPSoE+eE&PEG|~P zy3Oluk`Y&z%$^s64|H&=U183>E$}YprdOAws0$l=7vOm}V&M98$J$^r@lt85yHb0O zGOtJLoWL3!Lup2hxbDn&qzL@xl`ASnHU~GAUi3E$w_?efKchI~;AgWsdz;5AD;8^7u|8 zfwr6+%~i`zFERfQllPPS(D%=tRgKru7b$7>4QsAz`8-(K|6%fv@*~&t0{*qt~b zUSA5fZ~Z7wkRT`#b@#kE`?q{UCKW2zO}kiH1+deSwV786WQTjH+AfamS=s@cCPJKhs zI)Q>k(7|ME;o;tDb< zeQRgkVG%oAstfz-uR!7w)J~Q@E})+z*=az~(@5;VHw~0JM^RR7ZKxR& z=X}opeXZyVW7;7y|1?x2%?w?P-9CuHp#u(0sc7Y?jk=GK59EMkd1YV|j3d|W>=h6E zwN*1;#lX8YWsQ@QQS*hb4=u3S9Py_wGB+7+D&is~LFi=#e+`o;bE83{TM(ai+VZ z=xAq+?wHpytKwnbP<-^#jfFy!7@q)L7kBbT_fb_T5=Vx3D73)d10mgv+69?BB2)Kv zHL9~+gFZklYVO9(ZI-9GuTVV+b^>`&rV)Aa?-9K2gAjl17=tCIG8l_(ewM^qs+bFU zJ6p`93qJC#Zb4`Vb7r@UWcY8mrnY_~1DTo-&X>K-kwteu!iDLm=JpLSukR!RCgOCr z;~tNZ+|;Irp#zIXh1*#QRERp~7n|=a!IU-+HUl<}^b42ayVLV2;3L=%Ji9;l9UT4E zu2>h8AhRy=@2nwIfSuDyl8#ED^3FA63|WFMAj)s_dw+L&ds2*VG%6I);91^3Fg4Q& z)E?au!9YjnR<%bCp2rTU;l;Q2JUnA0Wc68O^}iD@6?sN{vT6oH>YzU>i+$DJDeIkF=qgc>yf{4E9Op%w7{r=KK~2=(*l zINaz3DxS)Kej zLDYPgsc`AfH5sfF^{^gEmA9Vv4ok>Mev4PQ%Tx3&rw;;yWHd6J%Yr3@S5mU1{r96? zuS~m%X?937{7CIGYNsySLS49eZ4s==NFD{BIB?u+WN!zB!ic_e7bInQUkH@%w1%zk5n8y7`wgj!1m!GcX;*zEz*Y_D z{A0d<|9+Xai^yxUG@rk%hc?nan6q|hc=#B??u`>yNR0lYPz<1kD4h8PekE!Z{#XU6 zob=H6?=ZRP^*MIoJ5kY)3R@VYk2b`RN&TCHh+VMTY_l zd1MKvHtXkQ+uz?&uFE5{`N*NC|jRg8qjV6R^y^Wa~273Zt6XHG2rBU4WAUHSx0ig<7C>nY9STMXwSKV zK_`aBiM4^7%w<`5)Iuaf`ex$s2zGcw-%`54bp+)*A(cE}+ba{wDH{C+XSMc?rZ98n z8aJ$e@DgmIJ&7OaQI9j-cJ@aP3sN`cF1<~@JMIXeoc9R>df9dhLYO8q87nl^{u zrdK;O&v6s@6M_lbKQG%0=CwvB(U1+)bshk)S>Tj7FztKM{x!66w;LhWh*sVuk^Gu# z)|^}#*SA1H-%Xo)>Tv%#W&8xZFC?tFi60J5)+GW|$+c>)rR|E{ji9F9AiHOi-QTm1 z-Gj?&F7BzFf>oHNpgLR-ry@G`!1+xU&YsCc^oLoz_!o&@G+!mVhrK>Jp#^v}^9_cc zi;$jowQue{nTf}jx1lt@Q9NiSoEtFQ)0mz)r?(F5F0p!L);t7x;n+@Yj#QhMTSxER35d;_w@ z#*Y&tZ5RR=rFaq_{eq3<&0EF%&i@9CB1eSBSqF;vSX_M}1&{DVTfKbjXFf3jn?zPt zHtN%l@ZT#R{P+vQ{GVf^C?>#9$@=qzRsac*(ZAZCM$a zi@BVP*-{0G;rr8_L#*47GxPgax{Ko02n#UBcK*5rgV?8==0N9{3cf-cSr_w2*69;^g~4&644PM<#h}5qrGlP_pR&;S%?*lW1G<; zM>g^GT+2JQ#_aEFo{Xnc|9nAO-5r;;ysbzKRZ$p1a}}Yy4XUe~=ppqbHy^0w@8X!s zfM8mn-1-pz;Pi60>kV?N($`*}Zrsk>5OUMpkm*ne>lBJwsQomm649HNg<%NKZM1aj zL&LbPk6f|Cy@v||4&H*cRiI;2;djxxa{jnZU{_~nkISz-YU2N*`f^kNx4_U+O6aX4 zGkL!6$M`Apr$mMo4GwX|-*48x;f?JL=IBpA1P`4TuXta$e>JoeFm2p=7^5)^q<;x) z@x1COKwmgvymG~*M2mdSbhZc(F783BLNMJqVV6Lj$7r&B?;;N$$(uzrUS(*nMSouh z_)F@yLqD!We5C4GclnR4`pbLxo0+Pp?tR(U+uV1!>19pCOa|3YjW*RL7ZB{nXqL=>$7IHU}BVS3jY z{;yPT?-W0C*4|jN*u+doW+lhR$2I#I)vCf@54}aP05J!7S1XGa5jlIuG}DFS`s4-?T@6W{xk0Cu?55 z^!GjPwe+o9bC;cl(~TQT=&~rO+VCiUE|YJb;AP{fiLGE^;+h6u3!?LSFnSzxUx%}K zU=#C-IF=s+8QRn-^);!$KsV3^8|(XWB#Yq_|3&-U7qQQ^VP(xY{QJ8|PU+M3$-y*( zx(aNPQ!W1mWF}I*DzR&5(9=gEQ@|`~?cnQ^3{Gbm=`|;oTwrbkn$VRf@^Hms4Cj+j zV>Du2q=S`T$$pWx!= zzP5*Z$97IN-TdXmUr6^3Q7?hXbwO*3eYj!j!hb+~#!F83>_PlZUV}j3rHlT!>=*pv zEQLPiGRKPGN_`jASVCpp*m=a;ZAC_68uDX5=CkjjmDh?*Z>gF&TS-xP|3AMQ$=Pty z=nt+;RkS%Vd$u#=Fdz5bTSA6NFX!B|eE&lu;Td5EuUs^VD?3o`2Te$nj?*%t=c|=%@90weCv##V}p82ydVGNb?I9 zID)U%@};kC5_`0eRN_2i*#uX(Eg0i^-GG~nfPG;;oNHeD^q*Ee(}jzFrBi#?b&T-j&{?tKfjx%w1TG2GJ0AAa(TG4YCZ%p8;2yUhmrn%3o|{x7|Be(;o&aXyqCT4MJ79 zOw!ou>`-Lbog0N4x!EZF>c`Lf%TP_mjJ|6+wHF)*@PZehl2X%Y>e)Eod5Q~wLEK7U z;tAteL2gSBKdtQEuD{ewfO4?@gTXX+LO?&TcORiYy zu1~In^Km~t^gXjss65+}391+&6m7Vf`|v=&gyz~QC~)EoyAH7R6m{R)|3XnDoOfo> z{Di#3u+8@;Oo{OCnd+oq6nS5_@b5=Bb?(kYC)&w0X1bR7t&ezLArE#X8X1~4?~Rg$ z{V3$O0QlVS%~-pr0V(!^GZt@=La>!hGBL)&O?`f>6>Lncg2U0ozk&dPhzlGh{e1fpEL=xwdC~=+_z$z_3NrSfA8`fEz|b-U~J$!K?sw zsq*Q?tt0emWOmY>i~J^zJdJ8;Q>}t5O@lf#?{HfuLdZ$+Gng1QZWnDcA2mZ|LLes4 zfP9}ipx~~Ec<9QMPb^>AH7+6?F)9}XL5rLpX%cPB>Em@{H=$*0*Wx_#A5=r2ID<{e zx$pP&!n`9nPjC%xJZNtij3Z6dWG|zJo9J?rO>8QQOns(R=+Gs8j6`r=#rI3V-jBDV zYevz5y*3-WZ(Ob_MaN|uoW~KK~TiGwiqMV0` z9z2imy>r(6p_R()8~@=As>~scm=YeYbh#mv)VFz#19VE?9%DU!wBiy7a2tPrGQ68O zLvx#IfdV7Q3wgnCskaK9*BYz_6!#6e+X0FYkCbP8jcI?;7ek6BKQp)q3FZ~#Kl~C$ z+Wa`Xu0%ZSVTR&St9S4ym$zHBeGkp3`xufF(YO-5;T%6N)!Dg>(U(V-&#a!}-b`F1 zXDhbU#Q-<9q>$QnbJNMz(t80r{~p-&o{)-4^29T(gKEU9m2HTKcZH55ZaYSCQNrb9I?zoeW`)X6C=B z3cI+^6*~u?#dSZ=Gkn0t&Q0-e%jpui{PEDo@Z)S*hbCmcEJ|WL6^N(CETV$3RQ0qr zRODmV&ALdtR-1hH@t?yQzkm9O`WZ0JaEbCiIC%Q>X-K^Dcy!1r2;xIiwA;{-A<(g{ z*}J;&*grs+H;q}}gL?5E5R)ceN9=wak(e*~#E-|>?d)k(&mzIen2G7^`KtKhP{+)+ zx&Y`vPQ#=Rfb`R7d%Fl}vZ3(6=!4~fBX9UKKmmX<{`wse3^N}KcHskbo zz8k?W@f})L{6vj8@*Z0XEHQ)b;t?MX2%?}M*9;7QfUvzPUG=u#8+u&bmFS2BF(l5m z_ztP9B>8994P}01Jx%Q zy~BoW{O#x*4nwSNua z0^DPc=~5RfI>di71Sadyz~m|3|7YB++cD49bR5n#BV&Z8j~MG>7;U^~3A^7l#`l$4 zL%(qON=?mM5OD9|B&Tf(b@3iW*%G!yp!|V&KTpK~P>u(F`*L|Bh7aXfM&*14@=Ll> zvj&w(qp3G(L0-19tR{$fT87?ex<0}9?^Dy0HzZw+%M|;zsmReAqSpo4V3*tpI0Hnr ziKH<`2fH`!`}s~G+l&6S=f2E=Nv36zF;kNvC@%@%c6e? zv!v2-q0s$ef^K-Q)c1#{#g9$@w}$LQ2=&+1m6&j>kfp7pD8~7I?+pj}MHZU$fYl?#F`*0 zo!u8RE|q@Ksx0WV;Na5dfP09o8VT}bv4){yoDb)lKEgpkeKl7@L^q^>`Qwo@V6G#) z#;ZdqggXqt$>&+`Y^_?>D78GqPOBbEV^yHoQEe;(#m91K1CEBS5`nt;Qd@X8_F15E z@3|gFUy2KOoS)bq5?EJ$b>>z`PF3O)irYEGIzquttK7#NGp@}Aw)OnM-63uYZeSV= z2+YzyKv}b>oo*eG;$5I{^`F7h&^`(#LAKL1bEMJE{`&Rn=6s6xlnlcLGK^8h=?@^V zCUx1kIh)D_#rs?40*qKk;hCytD+u?rsffF7o|Kf-m)_bL+l^ho6t~c18st?XIAitBz1_9%0k`dJq;( z*4#BFe%ce}lylfQ(>{;?#_RG@NNie6_h`E;v4tluHou(JPM8+f_1xd&7`}B-+-+5k zJ<%v6ngcO*U-dC}uYbb{>i~7=#HHSx5O)i>EAVp9(~z_4Gjt4H;5HmUuuMV2$1$Ysp}>0wwi#7um$UXZEuDK>~e8Ewi}iQ zD_N0;9|rGOj4c*qXT~cvS|0rB+6(4R6J;Y_gtP+VtrYWJR82N!uee(1ko(FE&CBMW zH8rBW@RohY3x@u2jM+1wQ4X9;+HjX+ZT8k1+BgKl4a22JG`2y&}< zhYZf4YAf5-D1*BMEu8D=-o9$o!dHX7V@$IJ3C9+?8;hpdZHg7qYTP%qzJoZppfFCz zx?f}8pYbY8tIfb}+8nsn&$;dmbxnujpkAO@+`k=zvlR>XDKh?ebVL{xi0z!Yum3HG zKalz9Z|)9`i3Wl(n}|#ZtJ7?eR6(5Z;;h;F#SPy34Vi=B!MN7x=+uU{|j*4vY{aQ%{FRWCo$Dtw~`Dib6(A3X3L+Nq~S zAhIt8Wa{wZWvzdLu_vYv7f{rNY;G~uKgj0KFnqwv4_jb(K9nyQ0Z4QRbyA0CfCMJ8 zr%1h&qZYdMDUEU9J-Qa_ki=n&wQG}>U33zqAB<*LYter}m{uUruu+${6X)zC{}3iL zxBDeQ*)+{j+U7KvK&+2%9%PGp0F?Bht6=&`;X+jeHd_d!B`F|p$Sh`{=dFsbCCQKo9577tmu=5VJMrH9u=hpS%Ja)B+_`RwonP{Xyr7_Hfa#MVsbqqKL$ejAFO zy=!U5*%D!;J!H3qzJS-9f1`sTWdjA^4N=|8NMit%ghY8vXbRnDa3J{&8m51UpSa<$ z=Hm;MvoI9v`eNia)%~c*;%Xa&bKa1;`w)T?vYE=Ympc@O1eevT3d3|wE+YC7 zo0${g>sFlMEjPsouvCZ1Zaw(PDNfC>&1*l~lr2jc zWXJs8zSU(YwRZz0cOb%=GrCoO>3WasrLM}wk0$*T{vIUDm0BG48?!UBmAyfFewMBF zjNqbz6Fh&i#sC}3gtm(k;~f0Wa{Y(cwYxg`5!;BpN@u73kzIlm@J73^U3}77C}dYNud^ka)*Wa9WsQuCD905xdSY5-3nTvQS{Syf0DZVtx={ku zI(Lo;{Hok|@yZC%Zu+`OR%|pAjH1*7T1wZ`4?*pG4;|d1NV3oQ`9l%qq?^%Y02fb=usU6FvLix7|Q`ge!U-qW^P3$AL7t zyaK6{;xPv9QR~1t%6(KisTD4Q_~LQw-wJCT0AL)UyP~bC8`O85MbBkcv@%YrdnW=G zSowP{_WZv7nF#aB<)>zMfA5IupWam_wf1(r=byzkXkc1hCYLw)i$eu*rK+}R=m`Jc_LV(G za40xn3=-jKt0SP|cv!L*X^SB5xD`1D*Diy@@pZ7fv-d;y*;+*W`(TGVD4{4q0c2ko zJ6aEBFI37J`J$W~H7;09c*6}my;2?~@yT$)mifj0KQ7mQ+zR`)x^o!i=AxM`QckcC zvybXv$zvf{1wRPc1zjB)tH*gWDK`S8*<)Kl2~nW?2YRJfCa(iCX{3u37TQO!3z_2; z2Az92&h5ybdFVrWOaoW7(|dsRu6)Y1dM< zGE-+XNI^xwXd41l`_97xd3sfbW>ecEI+^)-ak6ekSSKU)#ud+|J_LY%6oLh_c9c@; zB$bf}W0Qf^){PjwUFTJiWW4uwb|W~o?jATvokw2Ij~D*$h>ZE0lQkSxQI-)8bF7P^ z8!P5Zc})q)ZOqAd(er-R|A2Ql8H}R%PQoMvI+F&*$t8!VV)4X}przO@uXU)zOouqU zFLv58Y?r=#e>DvFHflt^W#fGx3siiAkj6$1Z%k)PKn-XW8XO9hJgK=|$!*_{3mPuP z3F1^%9dFEbE6NBs#1>%89X5kh^W^#feqIKX@Ft0=+Uti|aOu=t^5*Q|DpCaughvGB z$P+gL5E*t^K1Wa$yy^dLx~83^LVQkU2~{kLDio2FL?d!T37)R6cq^J*ND@g5Qwsg_ z|KsX9;HhrkH>V>%RVIKzpJgcA60+j^#PKpJG`U3B@U z1~=7l(iUc_0LI5k>MP#NJC|kFt~AN}OZAx6hVhAb7Mn6zGk$08#VBh`LV!AAW~fl3!|VoMNHq(Fno1 zp#X=R9g`C3vlLyHfjK!EhARvxDTbssSp&;+65tpOO>~S*If&4}&@;BWlJWKgpKh`i zU)d1~gyx6ebATe94W3p>r3l}!DRR8*v^jn2s7NRXsKi10904i+ui6l~h7>{Xm#>=> z6D?+b*WT#2s?$6_gv8De=dP^`zG(VI;$1tm?;x+69cUS%{JZe5yb`Pv`$24hfs94s z*h+ZuwD+CF_BRtk%xaBtL%gCJjz(?s!Q95Ouxpe36vP-=)guHq9KB;o!=d7eJBp8x zIC`W!LTsp>hkL4Y=I5)Mik&T~X>XD%l&l(5Ez`ynXVXVUAdeioyW=j|6RS1q>YC2b z(R1(@48GTdF$xOVj4_*}oJl;Yytiq%8X}(o^$OV}eN;QVfH$-nwHlisT=a8&Xcj_K zSq*zy*T;D=*dLpL8S(_AsnZ#`yMK9o^-Ph?_Ott(t;_8tC8EfQx8OTvH$kPPiwdw( zW*)}7gib;TU#KaLd+xVbJ`w3A&7&x=zh$_FwE!Dvw-;iyHlT{tZtN%1_z6Q|aOk^tlmWeuOX| zea-K*S{ZW_RX5!%Anby_El7kKVu!{VT-o<3Q_i z9tAe#t8GwzR6AS-`NEqaz7;Pw|E!9dZLCLfCmVd)M!9WQ+lXD|{C8GT_E3PPn;NeJf|O1+m+^ z!vYKdc9P4-bn-o9JCzjtB%C?@({Ql92i8l@cNV+rgS^U5L0DWI>=1q><7C^u%8C8D zgKJ;;p3|hxW}!wC=)K(;r2Q=KI{DO!j(Us8-=y9H?V}mdA+H%>HAO4S3rAdrZil6uB`?%KvQNz)V+@x21PJw=UQ3mMh7g|+dLVx zfnxbAV|i{tV!_#hzs?-L^W?REtD`(xWVX$rADwwT9)m0qOP7DWOO?ba2>w_DO3{j8 z?UC;qHtdt3vci*F9X*t;1eJ9^6O}$#KxoliBxbtUNdmE=2&UaVpER{EgXC6E9#4M4 ztPU{+TW%Gwy+#xF1#FtP1B8*u&cJDM69g*v^4?Yp$Iz$`0>>>9s7rLbK5_Rqa0m`_ z^G&FgF^SwKL*m}MYs)8Xu*;Y7NhKgL+hqoiUtg22m1PwU!!&akJD{gW{eYSZf-sy>-sli`JYdukSZewTX5)i zHE|x3m6e4wV#zjC9K4XNAEtK_YlNr5lO+C#jbw=guKd!UpU)!;3~1NhCNp%Hv@uKH1Urp{jaLDb11a>r=TgwO(ga!Dt9IpcXI=+;yTp(0jeh!S(rskLIbrTw$?aZFfxa9#L&<##tX@1Oco7GxZ;`HY zm0k7{TVHcM4ygCOza3=E@9`kgi7Q$dE0ht+H8DqK1Ax;Xha1M)%XwQ!Ac;?SR{QqK z@@(k`aDw@`!$Qdj1cnu()Hp`ld4g>|v+iuRIqmD7N|MO`hS0UG<0lJSM{SYjx5pXI z8A*fgLJlSO42%$TK4LOW1>~oHqhL5@Opmy2smpj=(PTAGHrPpa5Z@4bd@8G|zAOtQ z2ElYbzZ&A}E9?ZLmb4FG?O8vVvHan<Cp@PG0(yDo}P#3Ii#q+^cFMh*ZrlZHV|p;w_xfu*Ib*Ek5)d}s*IJ8MFz zyjeN6?6FobB!P9zhZd=?nK`SUsB$cCipFu;yMwXX03f?>+Q6u7H?R{JIiA+v{SV0! zjw3@AAqKb}OB0c1EmJW-nTmvlj~l9AmG859A02}fUMmSk*XkNDzApbkxW4KigO9|P z>rle3e?^ylWo2bs*jEHlLv=AyrLer<&t(z;(DWhU@Pa}W=&N2BY>Iy+Lo7T4$vQM@$v=HjGAS-1t&1yugGxtVxjV|uUP5=PEKr+omZ#@D|vl+42K*@a}m9lS~& z2De`RjB6<`;A0wl!W!1=Oo`uIP@=T(Jtytq-R3snPr+Px?S^Ng>*kU5hql%chn|~% zvK6?$lrhx|)M8xRQqSh=klugF`Hz^PT#gV|v-unsR-7Cr{IIA_?WG1kwmW1%E07JO z)(!~Rkr_k=H`BJ?ccphLw)`XoxgvdSP6|x$IEbxlz(WCZrh49mcLds&*1U~*j zb^SFi0E6<}A^To+;!*ZB6Is?Lv*5Z5X|ml09{vRAj~&h>(hpw|XojnkDDNSQOnpx2`&dF{&-xm=!a3{2 z4K$oOSPLM3r~*>k7qvy)iRw@dS;EAjRRwgX^n`rQ?1p7X-(g$%u@YgkYD1YaD08WP z1+Kwod1V+`3BQkwK>xbV>`!3N2YK0nGV#4V{8lgz=$dV43Jg%9lCCg5Q6p}1_}f(g z6$lL85P?=kuHvgBRi6RO{~#)S=hTL<*xz~gcC?$>1Bu60ck>*pxAMEJeLE{J^zq$KhC=6snLWN~y9nX=rGq&meC&ENc&|0geEX*tMc;eyGvybO(3iU9fD; zy!AzB&u3YGMwq823x!vZzcMs~>@{(Wr!=FsvqbIIg49O4RiuVIlnzx?8EwotID>5D zAp&GkT1l1TXt>&7($EB)R?JD7#2*0EFkrhgFdTPE<_CEOM8j^M*=yP8*uD=e-jK^u zS!o%6nW!!OPF?C2=ntXpte$exN6XB3mHP1iu7YI^I+YoJmFAZ}edyuaP>$ zXmCE)W$>@KlOP9VoTHGYCSCWoDjduRTX+OW`~AjEs%%mD8st%C%#BLm1&Bg*`@AFn z4J|2EEhTJ0X%S2#wBV{3%;UjX!7VcWx&iu(bQ#|^vL3yHNx4kqI^V9!R_u{kD-1X% zLu}fa719v^JLC_W5}#)}i%*g5#Wdu7&20THH0_F@=d`+`IU zWc!ziW1sEIz&I$%=J$Ppk;F~|fPra2y3nq>JRQG+_2hVJ%9g)QbdUhM;uv)=u@mug z*FNS{X`XXJG2GfoH-@+@6VK#qR~eFMF-?UaI_>g%`~3Gc`Sw1h`sjQ8^3rpi%#fe7`e z?dM32@+bfrQfCCMTkF1nqT2A5HtQbk#GjyQM^+bNkBKQuz!{rF-N*-NG}PTNoF0BwK57(KLhsZ()$jP^?N{cH|z=iJ6k+4C3NYOVjJt&o|q z$om`=RoAb{L5EdHr@5B-Xxnei83Z}RGVmSLmRj|nz#YO6{5oNr??>A#0RnTbAK~M&Y*Au{xRGbTE*^917VuTo; zi)$OC0SMKeg73xJji~|k!Jghhz5qNEBdnyg}7;Cg9<<#lY zfV#Y1RA6tc0)*FWNWEQ8vhOxBKxQG&&yD>(NO)nalpR_4vI}kC4A>u!bWK}GcZ1CX zc9yw}n~2X(Qf+~r3EecOu3Cjr_*(M<9YK5vGVNmP1f5cvR|k=##o;s7zF3SZjpQrfm3_;W^r#lPQf_`%I|yO( zZ~?}ib`qm7`%6n}{H++eai&kE<;ROe49FwmCayhn4*+}{i}x)U2`;S~g|dS^Xk}6o z)4Nqd83628cJ##a|6X8z?4bGk6gM5H+k0ZoKEE7IJTY_CmJ>yP1;>dYD5*0@)_4mt zHYTlM`#3txldZNj6|GQWy@M8sjVqu3C}a z^-PWK7@ViOz+^~~p>n=txEAj=xEY3X6{O~6P5%MJo_A!~3Brj(MaK@Xcs)oD4N~)~ z3)Ugn#ly%IJkMYJhNp5pw)M0}qna2p_=RiCS(A%HXwT((Zt)7!xWAEXD}$*J*a_Zm zeRCVOOC5x9$CZ$(+~o}ZOBaKd+4BYDolnT+RTOk8X)jqroA^1`9-hsTv%ekJ5Z>|c z2k|I)0=qxuvkzMx_JTP|1=GAYjmnVO-h&PUR*KDe%`Lr}!S4=9arbT%!nQ(gnY*b? zr_H4FrYD4mAbUZ|N0xBae?}j8 zhT2R||J^ylwuhj{q_Fhk<0O`02H5RMJ#$NC^a6gEnTWUcBcD=z=sbhqG<9g+1G(tQ z`rE~&ppfX8^dp$;4BRlJUL!6m`J}Dhr3!_jt@KFfxvUy|G8{M*SH8 z;nM_QLfofDL87*pw>TI6Moo3~8(xgM38ZDXw?d5|PcZSAJe*8ffx&N3AAp|l*0I0u z@4g5Py^BlBqs#=(X>1L7={@YBr$8qgWX*&++P*OIIheZayzg+;9;$OFY{QW|bAAEj zqjjJfu6K)IX`=-Gmv8+kwpPJm57bxP}!f)uE z0V<~^XwLdUbSLuy7RzG=<{PKiy$m_tA zv$e5NQwSdhrx4bdiYH#+ZI^wmMVuI1)FWhjc=rvkwR0g_<(epy!juFrwyKX_ zt}gdHCU_r5DfPO*(DAeKeC?TZvNxUZlPx5fmY3&ScPs&He>e`xQEfiXzvM(#sbdMi zA**{pX-$DnD|K1ep!}M>Jf{*Et{Eb2rFiJl5%#okuix89ziZEc2LN8o&|oWklEB@%@3-+N~eG=1yy z3pp9w5pJ^ozfUo)`{23jE8L+r{r`d}R4m2WK!#VlHy>3BW`@3QpeD2XIn z0MGz35|pF6X8Xb5ge!~%OuiZC+RO0vv0TotCD>+2P@~m>v=xM9L1fMZ`2w&EEhCg= zSxN4*8N86`ddB_0#P@+&8^dD-HMz{;V@*#y;R5^sL0_AHi^DczgkXZP74O}{dNJB2 zvTUpq4+00Uoe31j}`JB@^<|kMi&bGHa!k~Gg|;k|6F7^TVN2<&rX^-ug1m? zSaWmpe!v?it0O?9KCt}u_jeMuPH@|1Vc8t9KIbSviE>1qyUNPX{5=_*qN2w^rvyD# z$zf8!8C8_e0P#OfNQJ^=FX6{bI9ypAE@?kMb?F>(1+fm~k>@8NPl=^qnaTH1QA1Bc zufbfX2g<1EZyRso=eT+)(CQG;f; zy57v#+=4xvc;YYgOTGm=QensM)4X`Z6v|tzu%PWf{oe|&i_o7_E7HtuPuoZ?7Z3`_w*6C4s4V6zq-=pmNO% zw|!rr^I|DP*>&@<+Zg!E`{rJOb;9>>#XSF=61?kKpre}M>D9zvsq}E9sfp$OE4X3+cL`UD0H~#|x8%Lvik56!cC6 zx8soc0+JG?unyRm#$~~{vCa+BU3q3z&S!6RWMy*ucq*E$vK8SGo_+dG=HKg#HHc=T zAcUpfPx2eDY1{BOP5&2i$^a0bp(^aIUuBz=`;Z|DTQeoLdn1c>pgC*`p0vmRUinBB zLGG$iMfVwiIiFWLjC?jKwAY>Rgzk|6OtHOik@qQH^Bj3r6Svi`nK z=BD0T+v249>+X{cz9=#nXo53SP{-s0hm9VWp{!bXaqgkIH;=Ejz@?bcbr>1lM+k_X zi=p96FP>?)(u$?JNES`_c*$FSLoc4X4&B8^p~-;+kS61L&onvoY{Z4Q=pM4%xUx8Os7FROED-AxMpF`g!EJyexo8-}>lk<&wPS;}6Ay3> zK;ibuil3p_v@wOW1W4%~Fgq&a)sm!AzJP`iSyHu1kc9rLyrJx2A%TMxfD^+?!8Ow} z0HCE?&aY(|fZkQJ7jv}ULy~X@>Xa`>uvynYyYLLmZ8R0e zhj-@y?t)B++xeNM3|GJsTiqck0FZmo*m$)GmmNPC(xL>aE;K)i zp+nliR1`0P1zF=Ri1f~y$#A|fMETXb#3z(y@E-hkG<@YoY&*C_?*_uv><#yw2lhb@ zb-h0bsay!5pBZ(l;TS}qL9TVWUpW6=CT|Av#`Tx?hH-3)Tpt&M7|NL`|IwWA6jTO{ z^;N8z!3bVtpwjs!MPPh)7-S|OHr~aWsy|9B;c#UsK0^t=5L5&jEs~Zi< zB29GImFjg+RTP1d3liXzB~J!QQv*yR6=hnM7>aNW-n@^&>D>o$C2#bDb}!7I3g4@@Q7M!hn(@1nd?RB@m|$^~yB zi~%km?zC4k{@lF5gHrmN9OuMg%{>cE%Rs!(P+*}Von~xCE4_AyuilEU8K~!E>Meg@ z)~md@!P8z7^W}GPsLq61Rzn63Ptn=O6EGl5XI)fYe758Q<1|jl-(T+`_&wq`8kxv| z^(FDCn!6_(YnZu%3syg5tzpA`{o`e73idySb-on3yfP%a059cMXsF(-EMSqWL6_{C zlIXCbvRe52+rZjA{YR!TfM_k|WH^vVq1lBj#7suhZ5$!gZU!sNU)@N4Ryl;)Py6h; zDBtp&!G#d}-IawZt{Jm?7k*6TJIX6@N|?ENpqUDqm=lEk9nfgr)r1uOZN#EHa4Y`i zueUpu0fvl*>kLb&ujH~{0Lk(tuprO#uMJzL=JWzIo(#)teauw|!cT?>HiBT4u!m$u8wgTBT8vX%aAIpBA1|k+^=MspwGQya#V}@63NAdU7s2N;@>kZ)Q zDDIA&lEf|tEi0 z4EhqUKN!6%iYUMoxaMYCP*;0wSKErlK3{)|CrKL*nXncO=b zyP}>BZ&EHBEzZ2m4dwgLJP^BF>ba0-9tY+$;XV%5!Sq96Vq-#tno|&hb>pFOi9rrM z&^dex)>MebP|6z$bSx8?)%>zOz<^&4Y^aV1-k9AAm06PC5-!N16e;x?C3*nv(PL*euJB{>)(md$Ap`pBPpyBS!L=QJRPZrQ)Q`lc)rMzD@Y{+Jwj%kc z6*0^b7Rkq6LBZ7HchJ-V9YUtv`0Tz5q)0Vhdk|hE^HMX$-c~W!3_{X9!hJR47d}eO zfXQBgQ;2LPaOu=K7Fo*}82s|4+;;)Qaw#hTB2Tsj{zUlz;K?mBwOk(iW?dF2I_(@7 z^P+uZ)nK4deVE^hr;qU*W_|BBI>##lwUH>$rNdnfA$G*TW012atL~6+MT&txAKu$A zKq-y{|7N%L6AcWj*1%i#O^|E^50E{30RXcJ_R1{*ge_x`(r&aPLM}`4?^%OStQe?q z%;nCy`c4}ak~Ic&cZxqZe6;`ke<&qVXP)x=hex;i)5M^y_$&4csBH(-KAAvgh5NZ& zCo7f~fH)DeE#6~KVtBBmZy@6`06$UMJdKSIFIzp|dk)lbxIy46dM@N#3k6io81Mmv zAbOte4Fcw+cp$hYu>d(W3c|L#bw%2y3BeT@T7I^n?AbYou)ud-U?@Rx{s=Qb5MSk! z3_*GkPLr|i3bbV3g4FuO@^Z6=z+2D-zubc95Tbp>0MR>_Z?d2PD!bNEzrFw@;{j0Q z;HFKCH-uwP%JSPG)PHp=EFLxmk}O7=ll0u`F00# zN~YxY1cVaU^FR=9yu38-bsS2%A^~MT8-~l!`iO)-y4`XH)iFQ-qYK7>L+aSQ^^}mF z+vD5>`9QWOp6H6YB?Ab=R&+Uo_!`Hb2&Kn)n}E@thhg6CLcn#~K&tfuQbJlGoY(eh zKvzx`IxWx_qJcxe=4dGa(wJjmkU5;<55VHcwSjSM7XiW`ZV_G(qUE90-SnQfgD(py zWkD#rIqNl24g-AbxMc-uD3t23yz^i8cX;STERA0e$YPxhH-2wp9aIFFf`d@E`&1J@ zC=c`?3y|unzJ!Ih(-4pbihsUNYI~1d<+|fjog)ZeaSdj;LLH zC08pF&a5;?zO)5UTpd+UEbp*|g+=G>)5z%r(5y_G@Wa?RPCWJw?ZWMih;(o!dNc1j z4n{(w)sWZ4_d$m=buneVTWZMT-&)cwcd$xG4TI0v%ab0-ZiV=7u)A`0ZB$){?>{tM zzxUo?P4(XxT+c=V7{YW?kn`i4VEqf8dZ@!U&1Xo#4DJN(5@&wh;NS0sPgrl$P}u#5xDdxW_Y_nvH!@jmh;~qps>112uu8|zbop}GX}50A$*pX4VT`-j{}}vjUpZACUSA7v4ZP_GMXuff2Q`D zR(}S;5VO}$ri`TukRDth5mamfl=j=t1A?wFdhKg>G7M1y{8P{78ipz8ht6iQUcz-{ z0JA>DPY=A?28}b9M{I4DwGm}`4Pd^;zIQzX_90B;oEh5bKf1z8gu`$gE`rBQ^ciQ) zN|L0-ZNb#y+2TY6a~|&wYvv!xflGgyAl`OZsZ&)LeciX$xeV?r0==$#%h2cl_7OUa zVnl#>AZj#w9)Q(yP4-E9{?7(P<-#z(Jj`SH_orBn3Qh!zE$*`Qg0bRs8M%h!V^|+E zSxXVY6G&i#<+qB2ckvFgm=<99!KO5vc)z7|c0ai#`kSKWT~6@qL>}FU2E|+wS`D>f zbOJjuaJYS)qwI5#KQ&y*Q5vVu+RjNMC|F-J7l{VV8s+_jzQG2{Jr)QdQNWsU|IWoE zOK{ad4wXXt_#8XexBx6@kkD~vUl#iX zcubcdf6PXt$+z4J!);$feg}%n&=GpHIpxJ!7kJ(1SI%z14WqbCPD92@D`onQxP3LY8_5O%D7 zl|>a$7M$FB-mNHIfJ5|HRR{=FxVovKCV^qywzW~m_l2pF_VPyZLOy^i=GC2I%d>i` z1d#$MvdVY z$Mr)$*wK(8gdR3fwPCcB{;9&%DbTc{-gGiy!G06xz*{o=*||9|eA*ud+8FIN+pjF9 z7G*~f&^!fQjH=_C8b`r5g1Or90hstfetd#vmfPU9?}%Imh7q)PCK3?hrV2b=r|V zh{!yGM1l~F1DjC?YV%(|iYKdugl#Z9TL~2#%q%_8Y_lPFE;Hr9{}eYRSV+9K!o3(i zYfIb03-|q&65qkvwd0Ke`58ZvK2~kj3&V@e`{*Vg#To$E1N-YAeC+Pb@%(eOWJY;M z_s#$w^9~xENxXF|Ab`Ve>JidRt@z4=u?Xr`Qxr71kb5l}xogX%l68=sylo(z8Mbn{ z>j=Q^bhZ-sFn=*G(Lu zECVo;_U%qy3Mv4n>i0GoJXqf$OiU1-c)Kkg*XX`LPFw+!GM!%BiPb45^{nK_GElVG zrW4Q{#Ir99%-$|h0HS*evGQ6Z$pR1(O&CUH>wJ{5X0U`7Pq3CDL3npsS#R-%wB$r{ zE9f=*C|EsTy8}e2$THURNtMm-jH^i4``A;9uQuOtT*zO+y=DD@KX@Y1RLC@%#Md2) z*xA6vKC)>O^pz}C`vX@3r0~5%To*i~4Fbl_@Bcek!2ta&VW^@O9!R|#d7lZwSV1C+An|N6nL09mX`}`=xDezxco%jv@(b#8zddB zJCe%l;nL>OtT4?$N0iDzOS0@Okn|hND7O#G0&U_KFr0+s_%NE~1h6|7r7+ZAH{hb zDsSeKoKh1Ll=bIEiqH|-J(U~VT?Ma)goZk8(S++?alek(cllngIJ#*r9*{KRSPoUD#$`?_An_=1_@T(PDhVVoHRYnGhRa_4ROJHCEzyPe_ z^W{%;98$q5?A~jej?aBc6cG6ed4CfX$5U@4($S4|MFf{N+&!hV1GrJQXWt<#7=DX~ zU3~-pSmo%j6*#G|=bhJl9O{pu^+?V*m$TI*ZTsD@!-UnV6sLh9=r#cXq2r0uc$aa* zPk8*>K)c~sU;{G-&};`Z&^o4r%0C3thV-W2-}pK5)_uG4x-|2M z?8c>fIjHHUCfTZ({F2$+rN%p9=fQ)92R1L3fGb1VV^1I}M_FBf)T3T3PT5_pHV>@d zTHIm9tjDHgnK54vZW6*Z9`LK?W5g0lzE;64_6&x5jGV%kfuHJ^T`G?&xWfkYLwAwe$EybHqy^`vkTmQ9B|vcg8F1gZ1j$j!{(dtn{a$C?A7~`% zs3ErItZsy9gt91}8^Y}iqk=tM+LOg{kTxCVR;qy(0{#g$b8d5Vo)KN;P`eR#$J666 zTA8?mK*GDmbW1>Yv>C$~3-_@kgu@Rutio;*-)#W<^kW^${I@v!Z*v3d2=3^(n&_mz z9f;NBkTo;Nd$aul^2mehRVGr#ubN=pnh0QIn)N|!XBj(Q^o2>WVL^DsNoLF$(smI+ ziJzhe0}Xl*y;aR8fw31%|K2G7@D{-Ba_FxW0;wd!){OxUUjT@e02jz=MvRL(1VvF8 zAP~^;)2Rj-%0UL)V*8N9H}r5P{XE!S9EIY&WyZkK9%g~%8z-J-4ts<+c>0WN+@hud zG#LVLKj*|2hS}&)#(0b+WY2*bwkQ^*;nLF5t4pg0jcHYtkN`U4AmDA0oG#?<6OuWC zQBkIu^=@DCzQ>ed2HJRLpYQiEt7%0z4d-D{o7|h1_J-Aun)Qz+Z0EqT( zVvbg&hS*(_z1j=wu&(C!k(2&6HB0_wtgMs0Xr_f-6_k;D7 zXlcmenEMu=)AgHDQGN}E^WzP6;t=3B_T{EO^9RNv1|b|lo!^=1_mHsFdwTWnoW~rg90e5>kV5XYz40dVF`L1| zO1~KxGY?AjX&JiX`My%7(4noP8wc*&b;#X_Nkx*hPu|GuC~4O9(T{Zl>FX}Q?+wNhSHkBwy^1^u$y;J z^MPsbNh1vH%OyF1OqJ}UOktWpEu*_XFy+n?A!WJ#J&Lpv+pn{KNG!*Q?=sj74D^>a zMk_!M6G^#3B$q!xt&(vV(Bvmi>%si3;B}vif%TtEZCfVjpUQj=?2^i_1=d|t1r+!( z;2wHrG#_-AJI?35XtE*DuPq`MG%cWNK0Y$~_ zA6pZ8{kdm>RPVu(56+ZaGhj!NH(545;p@E}-1@7hy4=URysKLOd==M)?M3+h=P(y==>X;Sw@;}S?1fDW zDhkQ5!L_uK>+k|M=brR8JkrlE2I?@b(iNvGKp2<`E3L@o1BV?DW1sH2xnL9T(9a~A zz(W4{74Dih%7Q@wnS8DM0d`nwloDLUuJUFq@1TF+VO3l4`9|*ykSgB+XCSqN4eoXr zjy<1zjV`eZa&$ztkZ2%=Mk;5r%mFsCsu9p+ELE#wTQ#MDW!JTD7SHQ%ioY=O`K6U> zEhwaNP!WhmjXm<^whfX07q-XlqSbX&zofBi!U%t4Q;!jY%oXPKY-{@!3!|;vF#r8sd_=SJL5Ej?5thF@3GbhOn^kSt7Gd4yFdq;LpahltKC`1 zzyanY4(BmX?x4)Dpk@Hn8^a~CV9^|?Fj>iVOAkB$2#6- z>ce$`Tcd<7&uJw<19cBTWv=q(Dy$^}j`gv>FojsxUY5isN@<+cz`Vy0Y` zM|Tb)8Hv?9h!5jZb06}Jmk&>o!eaYYBMsgaO2~_FBCnY=7r8l{(I$*zvJ?^_FZK~X z{kJGXJ9k2uu=LBRBS)krvP^+CVAJ0(5^IHEP5XJR!lM578Ya_YATrzq8;-ZY(fY*v zSmpDJb0Wyt{MuoMh#VJod-l8oR-aGEwHR&&i0V*2+aRdlg$DSTq%>2BW_E||2!U@rv zo%f65z~#%FTO?tdZH+2zlr!+tUuGR~nz_EJnP`3cfUmU@?)f@EdG#3Qlt#f8;rQ|M z&g^a4nJmh5951)r_OzYjC8Tk zW~~v1R_i~iFwHt}dCC~x>hG?6)@fr#UzPQrs7CIFM%C;Av%LSmd-wcyovaDdldLmV zR6i`|RP;2E@Crtj)E&c`o65euY9?uY>alFrYrAffF2pS66*LD^zg%T?SD5@RwkN=% z$RxpI2%r7J57~Ch9 z&w{PM1Gpv-ZJ?%WIlmyk*ZDg!joIKRG>Ju8XgEI#TJCqL~MJEq2=J0nGY-P^i zji%QRuZ#7Z?r-*zOzXDjISZkG<;&oT|BX32+(TGkwN#ilpf6{(5#c{js_r=8>Jg** zIAchV*~RIUm~3Bf?_M2sB-SaF6JxL%?le~=pp?0&L`ZgpwPAHb8f1^=;KiAQp| z(|f_POP}#)W>7u^o3s1hIsdtWRudJU5SlpS9ydn-5PT%|KL4Aq;I|{f8||G z;r9wPy!1QDZO*ch`c|3;0k04zR5)=ET9kmu%qvS!Ud@rA6Ru!ilo#JM-m`@{OW3H_ zn9gqoUo!+#p>9PAiIYo1$awDv3rHl>_MW7KtyG(b0IAVi)c$*$G@^EnFa}HQ%lCrV z0+1~2TVia4w+L-eB%!kqCPwV$)xDcA{IPXwiLap9CW?QJMF9_Z4E8YF!1wNNu1om?@3WE5 z00p>4e4$57<93}1af^odc*ez>(7kkX;*v?o5n7cRAF2_XLKbjYo>PwwqjjQlaf`Z=@(W8*JCtV zqbb|Hzr~x7jUW4*k~C|#SsyvK^Hove&2{bX&)uO`NAuViM z(z+M5EVa-;n4B9ge%=ic(2C7+5wLY_X?_6=|_DtSVT~2>; zwONR0VL$msUgKI{2q^U9A~OC4k>L0=kCvGdhhPYWKEnuuUur) zA>#(zPKm2Aq5qcI*n2b^rLF{V84P}39lHY?S~U{5Nl#oq-CuQYz{(*e@pcWv8t>p2 zXYa_=29kgL-t|8Bm4T`fm9hkVxwGd=etbBt6x;#y9%gj<+7H?I3f)O0pLu@7!>U2* zmi*$Qr<&24OT)LCe;zyvezeNevE87eikTxc`|ouJl=Ks``skv`ey6s@H+wnvlTU7@ z)%R?8vhp&&>vWAY-X12_JwK%u&^%Pv!)+=yTw|J>hm?8`F&2%YYGhmDGB15lzo;Y3w);Y(a z7g#(R*Ac0#%?k4$3Xza`M?N^Xq>9V`hU+XbuoO|y>NpNaBVBaT3moMX5Ux!2`!B4Q z2t!kX{(ksz5#p~HRHPi# zTB<1E#9SfWD39gyp&^y;RShIVGi3lI7rG1`!5!UhLwv+dxqzoC2t^5DgtfIEYQ+vtXa*(|hUtTE1B>ltfKS@ixe_TJz>1K5>F3fk zbeh~cA8)poKUlUOK&!~>E6biO+tMO`d}}?mi`ybXIfWGlLNo5?U00e88j=*IU^mq1 z^w!4`HX(6)J79(Z$ie8>8SnPkYzt=c0g*VbGI81%OoW}B@O!0Nt zlkOZ(3E^9dU5v>11wL>r5YGZ@iRKScI)c~48r|wRCoU5eChUM_QbILvs!m}Vav)uO zp4xdn@wQC%#Z3L75^?5N@!G1F7hQRvD-;d%haJhRq%0WGpjtc^NRDNBvpVwzV$R(y zG@Q~`hSY&2XKnsTIV1y2dD3`Di%F+x5@BS*2e^xs9h;QEG@2&t1hTbhJYh)9S*2NQ z>}G&LI9k_QGhRAd!^B0gv1bI8Sg?P%#@0IzY5K1??pb&T+E|$UCkZMK`^4r#7rXOx zLWw9tBNDcHAI>Eh0?=NJ=!>7Ub;RIxK1&M)UT|%SPST0on%IA#O3ZO21xvdT@2L&~ z>{(%U68(%p=7Cvk%B!KxtHxhtYJ$yRkw7q>IY7f%GY2H83jY-SzG{0RphoT3jTv`3irw=w z+#hoIP6l*BhhrD4PiQNj3Bf9ZKVymn9aXYU{ROiqKBN7NF!x$!m#m@M;~8#5lDL?iv%=-JGQGyTG}cg-PR(VVicxqK*uP0W>SQs@3n-Ei>YeD% zpr=;|QeNaZ@}*3=HTql1R@=awj3rSHbH()XjfGIgY69vF%}Ip}%iyhZ5pvt*qvvz4M)C1$xgK1e^PoEPz9P?V$cW6qw9*@G z;}wBYp1<=M;;Tao^~doMc$t%eU>RXMT|P@&!nMdk^7=qgH_jcu9h+PwMfmxn>g1=^ z$<3Dn@3gt%hjtUXeHR40{FB8u6B??P;w_Ym*2n0&n2o2IIW1pq+r)QJ7w(nh$0_to zyeW^ij7{%X5gQYkyu%myWM2QyzMKV%!BGRdjK!m4%f(u^g7{vwgv|;PnydFSm|J)> z8sF;4iZ8~0>M;7A@4IfpTyKrEJBFF9B!y3C+<(C1{;<2?#%{Y7*^umt$#TkjW3m%|TGY#bn{&oswSh#i z#o+EAaqrIWXWILnP#Q8W<3b#wHOysBzy7&>G9b1K{_0nfOaY^Z(xlu^eeO$vLr>?l zoVi@b{4HfmDxnz*?1&xLxG0jJKynt-*=Mr=^*7@f-Gql7xJ~4h_RPOdo{#QwaI3f_ z`#oskoJaf?v%pzQ+~9N9#&5C$`Qk2iZ9Rp&-Qct`zPIQMfr~Ugm0VbIU|L?$xl19Y zX0MyVqgnK%X2VNwv|rW$7zk{3?b+b?k(8LEaK zbGdZ-Qk6k{rtelvQz?b+2kr8W!Jr|NxHQW*54$&e?zW?IcnvH3`p|ot0!9V9%DsoY z{F@81&|g)_)$5b0XiOQaOQRH{B*EwOm@A3z|_-MS=}|;<@dhXxs$|m zDX^rt*?9g;&S1l0V{}&&{LqHMuI#;O=Nz6DW{bNdeXk$Rcv0Kg{cyim<9N{np280c zn_G;}mGRp6feFx~f~>f%rbk0l8IJmA3Cu1H57Xykn}?>3Jb(#A8UQFKB}aZ+Dk^xp z=SC9MZgQO+`;Ty|gevB+a}!6(el?{wKay}cu;HOWbg%PL-#~+!e<;eFiyZ)IOJIAU~{J|?@ zo%g@@u1rdO{Mf6ovvRbZW|G`KIe@Pk{S|nKQZ?%Or6v2)@%Sds+Z{h6btoB4RV`|c zK@JnybdnvD=RTh2HvK_Y(zGo%m{0XEMah;TI}avopH%BX_h`7^133{GUXj1@KEXA( z+NhXZGrQ&fmq%vGMf5%K+f?M#neoh2k7iEVf-ShJ(R+O6=hfKrzwOP{q-3NspWOc7PmjBC@O*tTq5E_L2++iE$IPC|v@6x0#v{#xxz{A2p$)>g8r zWJA3La6nH3f4sxf_W;Jm>$U()yi!bt>D>=D!8;oY-uZF!g;yLIdC4T>_>J)Y7{Tuw zQUyC*E_j~>vW?@sKQUqMJ;napM0gfF(HFJQ7rm~1Mt>MS|5j+QC3__23HVM>Nq_QP{3S9B9>TGp-e>e{YNiIY080p61X^MD?}uJl8p7%1L6*_K}M!5@0? zp};tvF&6%!U$6scnsWMqU#%TB3hqkcW3h{Bwi4sX4}A@oC3p24^brV>=xeA{H%(YD4_LC;LOkHXaIl%o|v2yIp8#amyip=G|RAjhc6p0*8F zrFQdF<0zr*vx6-?b3*~Iur8_k*A{qbY)SAQf)6lBXTai)btdOPc8^AA>1}!e!nUr_ z{;IQZ33BLO@&M~L?AU}Mi8a4(-1REaYGZ~AX?@SZ!FNud9?`|ZXb<}d4~k!}vnNjQsOL!h17vE-r!#6KFg8=--ju-k6(4g!Jn9ZO6vUScG=PP#E^4e zyfG~37qmnD;T7zj>2+2}4{&>uPX1YU<`Qd-=MLM}Q*7_doYB4-`h)r3;w2qnH(*!B#1482dZ zg~|_8O2A_Z(57%vt?0vhiWOS3-)T|GE)0BrqoYY3GANk=$^yeyTMZ=~j)wQ0yQ*X2 zQYQy4O3+2Zm&snm~Ut^tfkrAvLK0`F8BZDsW8tD==VTAM`j z1YmHp1i+?(+K37kvhPVD%rLjY>dhbnD@fk6Z2Gh)ws{UlF~_6D2l6(9xBqG9u6S6^ z=YJpQ+F9|D`v4rZ7o`a+UcpDW*1Mj$(aB{mKWGjjjngeRULz+aW$wV*s2z6`LiTem znVXR;sPZe26=HOXI1L;vFL-X4J{XiUY1H+x*9<6?gtLS6kFWyGyy$~HX zHa51te9JKS@?LaWSC@KUCr4a(pL>fQm7i(6-g6VY(_5>TQ~bmI@HyP1W53dlz#8!U zUV~+3IM<_%%s{{?w)s(1e8`S{yX~p_Jap*GXDIyf!8`5U;VLPUbmH1;fyW*;o(i4eRF%s&+`>e)228Ge zA8i>d^$LlWUsx7#ealqCvH-B;`P*G~Txq?|Co6kwpW=&wMH#l|72iR}3I5le_uyAr zpo6&j_Fk~(H-XZsI*c!UP^NwM;S=Wk3N7e)>j(R;PUK>Qm;JT(l0>E1SUE=_K<{mw zhrW(7+fyMaej)qfjSW2Y@O$VOphaChi0HWq!z*pJc#(2{Jv;-jd58j9O^w62`hYp* zfVs4cpTk_%1yN(b1rRcnpec=&$Cs5au`vcsf?LMV5%zqZqBCF(Ent*#yF(zjwnr@x zJH5#Z%lRx}!{b6iRpYROTY5EZ68)*B2&S)@6}>!0?vyHIi#&dE>F-fF4w)2PclwxW zc}iHuPVFv zYx=sjj*3qd_r9g6ZYeqPrDvMhbgPhD;Nws&(6dWkVuRC0J4bzZ(*pbL+RFOZ>8<}> z5u)6YHcdY(bR!rT%P=A+pSqOf={jx1?;zgr_-&d;u5*3n-n7E(Ya6>H7M-gQhLM(- zUkGnBo(ZiQt6|RIwVQ#nl(CRD)BE{A8BABYcV`$>koU)L@EOPreXR%z)C=P}B`f9j zP_~!Iadv!OgplOTv(JUdb>xPaJ>jk|z10|onesaO_Sqr306trsqMUT^;i4qABs~kM zIwk>(hDwBm)^@v1`d7T@Oti`)KNwRz%G@jjNCjlBxWb^&&=#l2*X9zJ+t4`FTUiuf z(@vPS3z!A)HFBNWeUCJ8<9gPY>TA-b{^)U3ufmdWK6mgW}aP zLMEEfH)asKrsx>QY+__)hZ755^Jk(Hs2CWysuH;GCr3Y=OPlAQUR#HChfStWD7*q`l+N+nhK1 z!zy%4p(3F;u=7uR+6KSFw@t;rGZ&jqM4F3Y6W@)UsG2uc`k60qPk>K=e_d}lwz9JC z1H_;$->Vuw#o9_Zdz(MfXK$Ggxf-?lLvO*18V;>`e)1~)9SM*85`jN!Zyu}Q%o09T zd^&k290U~8%^9F(Mxy?-cG(%aG7(zYyD=V3UpJt4Wxoce-&BddWA%AD{|SG|2Qlh8 ztV5Oy)w^}Y_Y*YrQFm&GieGLjzGoL{o)1YBgZByHwCKQ^$D^iAMf=L@ebH_ZUc2z! zx%Fz*R%84z|L45L%QC-KMUKCkpZ_cxRT5O8g1i2cUE}+gKk--P2ItF96@9%kH~FGM z@w@Ga^MBmckHv)Mf07#&Sb9skNTHa2bc zbKZ>!m$N&+cs?+#*`J?!@4Svqw*Qw!S#=koKMXc@Cz4Ky^&FZ#x z0YixdA5Kl-N}HOx$NS7!4Kmls*HP#>G_d7Dx2gaM{hj!CQzkjlRY4W&`Q@(gN&EP4 z>qX(FZyPS-K$%wOnLBl9^hc&ph{c#jX#o!S=8PRd>2E<2`htV_^-*d6;s7H+qv#&~ zAtemDf1Db%66s%g{u?d-L8Ths8Gt$p3F|~K`NFP#F|#$bZm;bV_MsA5Dk@4+N@;hnLeMe{d9Jrwe(+z* zI}Q!y7C@0M0MB1FJ0)9OR+T*KR?y^^uEdW+%$(}fAV>Bb8qZ>^T4tJ|mxa~B`>*)+ znj|uC{;c1@upgyYfwuo7H2;T(`B4@UEtJE1sXrPUKGT+TO|P* zQq`nC2TYSCt?!Mr1Z##!kb*_mGUY+J_#qW<=ngLzIXh^9-URRz%6`vWv3TAFKfxm= zu1b;h61dTuasT5JNIdXiGZx{n9Mxw04~qBytr)7~XDI}B`JQ<`KBSH!<-iuofjIm+ zSy~fQv_XQkV7NzGNz>!kVqMz~Pv$}9@oRBbKcrWgvS;nhfn)pzs)$`aRi$2#Z;%_D zZfFv_{}d6%K#EQRd;uZAYomLh?XM({$eY}SsddNMLH6r6G=EXk(Zs2JO^RWbIq^L? z2JpxCwvPK+AqxpLw@8g&%gnnGHasu=dvx5(0AP@Eaom#*nue(#7a)G}XoLtDCzdv4wjf3_XbxZ zm@I=VF-){I$ScM2IOsokCHTG?jf`oaRRJWu5y~7bv}32YR|f2@sv$JF5ik6MBW5k` zfD3~!FDtLhoZe2)VjJ{$$$}UrSt|37Jh&80zBN!cGKDMgdpukTFXWmeB@fRq0@^{2 z&WSr#-xAM-5p}Q020&FZOo;e2Yo zaZ&8N<+LYzU|8C3{1%jt8y~aMe|#m<)42j_QYX)nvenNT&`MO>J-{CT+PR7s=I+bD z3n2WfBy+7g%={biHB3u9aj-u?2Qeg*Ql^QB8Wr?aWab0DImE_>4d^TKI(+;r3+R=F z$UdUEOuTjN-dt6v3y5w0k{m zNWm|KY=On5VeuN#z+^97hB;Bget+Z-h4_{hEc0ax~VtM2uJ?5+2xE7$)nch zrl1uCM5~p*N3kfJkPCb117ri)u-oSufe`ZSaMa09_ovy$zZRYP%|1uZXatRn&>zWt zP2gP6z^U!0z%y3$-k24Llm#fx_T(=%g&5O2j!J76q6vt#b|zvqWfRw0*Y>3o8e zLQet)J+T7OgjiN_=E46AGgF`s=PQxN1hfOplQyHE#=i4cHTMvr5zG;ln;2(#Zp@d8_3orl%I_J1POxMz(Jmh zf>$_YsGj!+8gfou6*5C=GTrFy^=Y1E{Zy_zM}c05&pv{fTMFbh#$O)XXZC%-4_51K_?er88b?${}03??GyL3h>jbnfv%nI(|zg$@ssQd>h8&xKK6P&z>b zJL7NKm|TzC)3(T({QfB`~wc|6`5*UsHp0u?Yc# z;neBURVis{($jloJ@l0wQ6+dADNrf)qx#Vw>`}>p@b}%L4d0l`#Tp5nJ}e2~1$`ud z5u5_o9-Oml0p06kXD+dP4Zn2=+2m_RpnUinRNX!T-{#w6s?a$g+=fFcDGLvn*^ltB z9Ew=_0Cz)Z@ZVp3)S|8q60hsLcWel`FM!jZpz32|d)cN}S*ZNhTbc<(>;>_840&%( z3KqW-rluKGQDBFLALR5jD32@=nB4nkQjKpgKvUI_zYw?kgFG>4;3IajKV6(B#Jk6R z4M66^$}GJ5*}C%!4bjR@)I9dTejgBbn0;5R^;+R4?w*Qy#qNJk;}k+_ahD4{T^FLv$-Iv1f5iBm9>0y?-_DN9sa@uY{iDx@0 zAniRs=Vat3OTB^mO9Io?<3MgsdUX8@5iJTr#t3lrA8rUju@vW# z3Bw4!6St-2J*T_5{yqu*49u4?c8>xb?qmtn@UH^mR!C7L9w1@enT4I1M|~wT)}xbdVs1(3RG)J8z0<1p^t)K@Y#zOr`=scYVUw^m&PB?gP`Rc|~reJ6g&?4PwTxN2^To+sI*2?_l!3)(mcX)_wfM|C830*ejrBG0~1tT?HZ}6^24q{@m zQgM)V3|s>D#Py=*eZCmT<(8EokzQ$-8UH_v!$OjRp7=)66C?IrjhWxg);G}|C4RfGI8z8RTm~ynwON%!@lvF zP-_7%7Mf$!AB#iOGj;ePaAeB$WoEQVV-AY%T{roEvDtP2*`n zDhTSK2*Foi5*puShb!GAtudrAwlKDPy!EBzuj?Zq`>74M-2<|(|7&BKAx4Dkyw|=S zW@AUVOz@;{s;2Q9QgF4_eeLyzrja2#@akM}d5_+epZSj-x`f{W%EPrYO#J*B--Gc2 zB&BK45zg}4JnY}eeU%2AxgeZCvp)iG_a;BMj5P1i-Wv%se>9)>*lVapUR6|+L+t|G z`-eQqE-(S9oJQ1D`C>p&kSY%WNWG-Q4V+;iIf7QkX^HsLE6Et*x zNC-MlCDt42h=MFBgcj9kueqE5lx%9M(dU%5#aHIgSMgIb-_}4V@oX^*367-pgw;@9 zcaK%%n5sZs`K@}wC=M%%YeDRtUYTRvr_5t`_qhP&kviF0R<>Q;R@TeX`C90{o;)_~j~Mi5zVp^a)@;tJ`A$L!us5rlt}P`PFHN-l zI?kk6HC>f8+;K=?HoXfxS>AY7SQyy=AoG?4Y{v=EB$xy6$3iB?&8k?-NSSW!w9$TC8rMFa%K`3U zS#bJ!SBgQ~vq1x%tA>f26R)1=7#qL5l_X_U1X0fbt;^t7YpQee$9;h~J^;-|H}7fK z!4oKiNb3dJeT!id<*;tZ93}m#CX$11Vs$Kceh(4Ds1gBo+;i=#|16Zp(#b|kzl9b+ z&v8e={Kk?24q*FK7OtX@kYjB5VtJVwMq}&SpyZI9mGwDeBByEY^4>x*HBV4ovt#Kf z?s7I+No48B`pM2?oIIF{&KyOyBHD+J3GPDP*o{Ws$;rv9YDVQdAEAg8S!zgM?CgiA zC}GJW>%Nba;_iN3CF#74vqfc2G}IS(y*FLiE^1+I?|w6!1;162nNxm*9j(XZFwx4G zX5wKq{k7?x)w4&)I!P_slBIi>J6n=L=DSZMoIw>WdI2COo?hswq`GvlO57EA-=d4xhNb`A0@;)UjkAHBW*1;rKoR2a zpO$;IW|??jh$@z!q12?2?Mlza=!XrskVg(I9DZBe^>F0sQ@VS0Co7gigg4&`nVKEn zroITj#~L{Zh8)Yov%9`Ngfd%{%vZFm|G9i zC5Mf_Qaa@N?ePlqUer81fFdSol?am!oB^o@JJfY^BKS-U>X<|)^ zT`MWa;)f4U-qHS^Djg5bq!8d}f3IA~x^Zw>WJGyx8@(Xfy}?8b$`3IH1_{tuIrPU4 z>?)UlfPl>^^}_BWz#QQQKy>>9aw$C7dGBp|rkPkeSOYg)?a!k}I~N~=MYXY% z&CJ@^g3EGH5lMj|1IWgO2BM z_&08#>fR5{>r=hA#uQ`0=49(vbe~ZcNa|X0*e;*WxuHjLl~%6H7A5!U@!2bvyfXB? z|9r;*QF2}Vp{2()OrRKu;Rl??QHZF%(W`=BJ*C? zW#eOTqwP7;n^`&WoHEStJu}YDDtj+O^=}2N_x(P+G#7yJnAU#jr`luX7aRW?wEp;hi%S* zhC}GWnt2eZa@p1lB*DjI;XZMds8^=8O4Qh*bRx>(f#lU^1gRapytK%>po7z$sZ%RL zv`KFs4dE9f$QHGYnUUwO5WPmDbOA|JAWqP1tchYhP`QS%vJ zF`eS$huwHuivn;ae{5{*=^52u7a#Hnsv$PSghe@Oe1%fsY=6eVf&Rv=fqo$w^XP4H z%E#j?TI}n&Pwv5-iWNw+1W#!eRo6)Rz__KB{u29naT2o`VgjrUeDtPl;C6OHgEbki zm?Ope`=47{N`P+p!0Q`~?8&pvt?GVNz+?k}ZPJlh{IEfpWfU#Nfh0y)Q3Z~S>CZO!koWe)SPlvNEscsny%)MIdm!zhzb z)70xnw0Yc--plC0bIMv;77*4vIjsS#H|>b8#YZ)QU6-P>Aeb{YXU|x9^NBlCS_x+O zp`0lYi#YQ=%J77U{=KN^Xzd<5p_8zH0C^*rBD*qr|D=wan_Jztf`S5Dz(cx$3z@!t zqwBuYOQfn_fi=p&{_*85xR4~J;wsLO|7?#mZO-(icAvD*D%?ir@a|?sq7^jMX zT#{eNHq%ikcTtN8suZbWOWP9VC#*mdU&dUjcgM5_k`O7{*}G~TzSF#OFh9^-fAl?*p*w?Hqu*XQECNx-tJz22NH9rsD0uq` zmL(6GW)bY%>yo9ImJkI2I+N`|tbFPi?n z|9${*nuu38DAjT=!e0EIb>w388HJ9S%)_At-Cx?LF3380#7}y9i~+HB7W6jm{z!cO zTtkK6Cm`S@N4ZODO1N(h#-rqs>284qr(ZdByw8SkAaB4&gh#(q1rpm&iqPkn_wDa` zPjx?lHOX`S2T3tWbEtb810#?ZSQ^t#%!5ji>T0OaDa1)#Hv&#{YP=5K3Wj*+BQ~JD zqr+?Zbh@67y1Ke?Qj3E-y`GMa&g&ac_KLSk!~anHcj}c4Nq%>sxt&;hsTWvJ(?b;k z^Oltk1c9WxZ-xHo)4{oK!7ZJnI|gIt4~JNcSJ=R(lQeI(OYYfK1g(m6xQ_*0#Z3k} zj~K*{<4UT82kBe>ZqNVihid0E8lSBnN%L~0BXPS^jy#od^xQwM`1FMMri0qpi7x{v z#A?jSh_9>kvRs7;f7C!YFJY5eB65`)g%)!h2b-py&at#{*|TsiBsU1S3_6=h`mZG8 zSBB=jd%RZ)5`{z*{uDu{;Ruvti~yKB#%uv|yVUBvpf3XZ+rqpZaxSdr@M0$O;&sIK z!BSR_s=NGEn)iUwWOLhcB#gU9PPC@sGmaZEa6cEicM0Go_-vr3!UuEu;{LSu@SAtp znVa;)wKt}2mukkd$?Y9D*ex^AmT~$q0%Jsingpshzw>zMQ?!-v5K$?4LhoiV)C~ei z&2Hb;24qv8M(m|DXVQ4_bWR2L%tB?QD4oIe;E#?(oob^XIZ*_{R+qD=w)E}n?8H2N z-h~f5T8)A`ng_)4L1g?Fhjz30Ur*{QR^&Ej#ok-)oEI*HShRsr{po>s(!q9^m|;br z$Bj5)=OQC(m_`={*u%>Qetr(et&Xi}=#&!_>1q9Uw*`*CX@AI+xVir$umNl8NpBlx z#XXI3zI@pzuI*3%J85y!u)m@?jHRR}x*0N0XmA4p?N64X>90O9WOQ?--%gCg@H(y% zv;VS$v@A6!GBP&o4iKDvPRl3ERhT$Gv4FxmKM*SOPRQT55kJIg0cU!TU^Zd_tlFdF zOEm{i=4Ia4{BwqYz>s)C3_4nd%mFQT?yX$@GY(_bNcIppr@F)JGw%#jxnc_*p~l|lgB(frtZ z_)EhTsu0ZHE+oklgblbkA})1*7ksRd!#B|JZgpyCe&cm}#E$Fg_8=W@`iyh#)j>R# z(>&IRl{g|ILXh}V1FcJ(7@SVdFFeOnz#<0#Y>c-*9G2x=AgoGg*rW7;nIK2Eq&Wd5 zjj;6>78VB8wLt^WK(p}lg(si=c()jo_4I5Yw7V=efggz2weUk3DZRgWsVSA5DY+_Q4%+y!rF{9 zvnAfPe2H3*qwjU&gz&(9W#-I^f!2I1^k97(qz>r3n~15PyKQDx8@#`A7X763^p9op zR2k{g45c$OHq(%0wBKSquopgHlFq?iS(A-z?C%uvlTUel*I7!$SB7;wCX}o>OtvNx z=6gqTxTa`C8fTqT7eUk)ru1wLeb8`SE zOGnBJ)XQIRrV?E4RGX#$yCx%h7|)HL(uV{`HpGX6-P$~=Y4)f1-!fXSrM5s~KNSej zG*R*v5M5T>47M+7)fOp3`W!V66-CcLB5*TUJaQC^{oX!B>3`^hYLQD-V(LFr-$>S) zEIKsbapDSi&hL;qe1W5j$|5;KwQDWF(ndncP&77Xw7-7Djs&D3-k@aee2FD}PKmj= zp1tozaoRBpYy06#=>{*ukkoJ_ezV^?7puNy4P>?O(=XAh5R0}W(s?2$&&?e7g&J%> zypQ-Jkr!$gK3vIEh=75wdC;ltALmp{%!afxS#=z5VDiC;p((lbCe&4O2InAE04r%B z=Kez+K2MSrlDYH&QF%5s*3JnZ)G@`AG?k{qkS?`~*MZx@#m1JleZTGC{;gKNK`=A| zHY4lzh1nmk;`O10P5V=V5Y7H#WfNerjRoeW|6Oc43rQRdIrZ%$Y%r6#tV-sgGD)CY zQB?PwihRKL{@?8D?U|B%v2Ft-)2-!>Ri1Koxm1a{irtjUP&zM$R4tlgG+iP&hJ$6; zbMedDH%4!UPqA}xIaA)sBYN-Alam@y@aE0Uqo@4_+VBTxq5%Cl|kN7D&0auMK z@C|06C$x#N=#zz=UC!jzk^cb#VX#z#a-BMeyNFzGGKh2)dPy$Nok#l(aafphWf;oXD@b zgo48(v5gbg`=RudyOL!V+m+b1eLvsQ3#(cmM) z25x1@8SeZ$BMRz61yC-1u&EDi#@V1>AiI0f8)v_CQ0q+puzVidF&HW&`aa|L zF!RPhP+z`n17z)Rsy0>%X(__Lp zh9ZCAIa(qzUVL7x#hmZ-XG2Bi@&F6jhnw~K!jHvB`l5b+&$J1vC z?h#LHX{G4v*_BV86Mg4n>HxRiur-3?C_JoN?^xM z|2sk12p?Qno5wTB{;}eqRKGi*bNtQgRxW zzzHFh{v;3Mw$vs_Qkd&c=e~X0vEu@09 z`|mQqzzA3v&5J=(F-Pc3&CO*-&dcm93Rx*PIfSbZsUALsi{h(J3RH)(*}eicQ(^hF zv%E$a{LN=>I~$Uc2RHt_r{gWbE4CYW`H%88%E^*Ooa@X_L@$|K(mm#%%89lj?*;1M zZBx@uSDM2q2{nn^OKc*mgLmGaTLD7K06?B<_O+jh2%?UVQ&RSWxXk$uJ0^2lxY)(FB3nW=#3$hBFCRw;~{R=z=QR$G-k&>hrnQ0}%n; z&}t4bn7*yjch`OMS_3A>7Fx_wB{;D~P-hbgoCPNM^<(?%mL-MThbwG>D*UAA%_PRB z$9zHLvmfwX1vw!rc^l10Io8hBO-5eFF{xOn7xtPi$BZ(ji5ndJ+)j(?|1t*(*T;|k z2)n_Z4<5K-jwp;Bet#DVz_~m~>iVFvD>>F#h2=5@nBhg{w^b_#9Tt3ja%AkVjHPCK z&Cjf$ATI+H=5LWVgCc|>n8+_7qJ{xizRwd95^7{m@2vQMZ$IQI1|EFk3BLe|j2&KN z7rNFsYbCGcI_i7a^~God)q@*9^tzZjK7YQ+))@bM9R=ucF@#j-O_TBDFao)|Gf|XJ zszw?G){Y;@R(S#3l?xITFgZe>{QOIZonr~1NA;Fkn&K5MBlQkD6_|NYa4S^k!xv)@ zVZ^fu1xqs*Wo2EMhM+-xaR7!zW>|SRba**(Jpj=FOLZ>?l6`-~K!COH*$8h6rW0|V zG6g#H0pfp$EQB2LT-YT>8k)rQKD<_QA&ztWa0WqW z9-yy)%<2XJNrM#ZZ46JxcJhnGW)U8n=P-&VXKS2IT<%vNpBO|ruWLYK!0L(E%8P=e z6=2vDfhK(Y8;|uM24!VsBdCprSe*K@Wy|_;+RM#IMZ!Tw-sa@sodfjyD+|yt+RcED z{9HhwnXZ1mOP7+x;vucy%f^(5A^FJoB%KF`?NfsG6E`|6lXJ2kZ?R_{YQCVJg$-0M z#?QY9ldS4Qb&aZ@0k4y@s5+7JWElpD7DCNe*pZ`=C9h}`aL1Vd=1>Q(P4tTx6iAG` z0k@$haoYjngfnu=8E%ct&GO>+VU#QV?QhPGEqs_SLHK8?N-pkjFUKE~>3B}_0^ zbT+_F9pCH&d2&kX*DJTpaYS{}qx1LvRxHmA4S-3Yi`t&N42Z5uWQsxA6}!RSL&r`l z|2o4PrjLDSxKySRdC zC6whmrqvO2P4TuYnZ@Sfn~%-S#ZV7_aMKkSuq)uv)(-nd|MM5iaLPlk zmkRSG2(B|?U=>6UCmz-T^}8$(#$65x>Da>nYFbbnRxg`o_uM8JoJer4O5Za- z4I*xb<>*AJ*LN%5BXSh>0M)-3pEymovrOM9LUk3j?39$cj0a@tInQHbr_YyTE^$T< z-16uH(Of|2hbMO}nw(|>>MX`jM1KeLq)Jxq#5+VOm53v~Vm~bU{pVyCF<#gTL4p@HmL_ij zB{&^tr9+a9c42KYH#38to1seiYlFK#$UwqIP^F~&^2ltvWV?IZ)5-lK5@mxU`pJC; zL_iOqhRI%txY%jkrnVdNm_AF!1y6falVIyD2N%~B>@^j?3J&_!nZAxt@oiV7usB@5 zWh#%34LZSVMVrl1OJSh;5S{QKWVPMEpXog&!9!Gs@sU@&h*{F2azB0cye0Is$l<_g zy4&zS*v-b^K6-+5?h1fN14udy7Dr*W(cKjXoJ0OuRh_cQf+U=5yUAKiOxSqQ#O0V< z)>Far`>^&DQcrG#p){j6L1ajy8%heD(KLM5_Ff)(iV;deVhe%*rGYmy^951E7x)fz z2_(qo--Y&~EPRLs)P{&go4zJqk^@t!+?PIQ?C`Xi4m4)g=Jgo-6f@eQ5PH8~m;5svM~L>U+;Z^ACG0a${rUFWs+EaJ(LHfjM#hK{+y^ z@(+ACW_WZ8KLY;q{*l`6=&;tQfu+8?Fr<}YDBX}tOG!y7*S;ri2ZKlA+EaoKqdo{s zY;*YT!#-d$P7haAd}2CBvv(IT4Ee}$cgOCeNF&6+jchw|o$_cij>wXf;|CS?XM`Bq%V7~OuN$s&VE6ruB6fDzT^iggE;qQ5_) zwgUk75i1+!dbSFJr99`>Kl`f`dX{uFG&CN2sXO}^(90+Ecx;ZQw&X%jevamd^NFBS zdxn-F2ZdN-sO~)sc?Q_^db@|@{x4$~HHT1P%X2we1j!Z;5MXUJm!Yr%g^_L$H%Cj= zknBFSP6dGA%gf4^FF-z)QGoYHwVf-i2FVbLlQd@q>}-&`9nlbS=9UbN;{)9^CB5_P zNhwia0kn`r5dt2Tvb51FInxm^+13&`lte=M;(wR=Lh4DJvEO$}Uj*nWwj|o5ISBG~ zfs0ocx+J0_l6#C+xX}BcBW{oo3f$&^E)Y}8^f{R<>1du6jL#a~swdEx$v?z1ZLr0kSdL&R2yJq+Hk6FuSUks$O-YD>edC+0;Gj-Me znGU4UHV6m`eZuR<>-vaETbVjwcFFa@KQ~q@oJT6SZ6UZ%ZHeo;!j&^OTqQEUF^&2x zw0okZT00q_m{|~6=^7L1{*7SKgM)q$&c}dk2#;@jyXsG~d*4&1!hEGJ-3#Q^-PyTZ zh#Kc2Ik9)*`ae`bNS-P`ZMAQ$n(rNEE8)!Wf;de>Pmd6YKM)UpSQz`r$<{6`lP>{1xORtn(ENP&|0R_6%sXF6XN zVo)drG*9ySJg|QeY*a2Nz?c-n@C>zHdC|D`L6CG{WJ5R8AYhmy8SQe5JCgQXJUl!m zHQ*olvD&#e)E@ptvM4z@xuP_4b90djfyn~y{p^46d=e7})J?vv7K!kjRM`Xcd=4W| zy+)cz3Km}T2_;XKxk;kA*!cPLUHpyqT_@p?3Av$N)up1~8x+}*3z?=%n2O2NSft3( z{Pz%B$@JglVQG;T_IF~Xej8xjX7d~9GJCzRiiuSvhcyqmjLfRHykdMxL{P;I3PL9G zo{$vMM8?L(2JoJK{~Cp7IlH;YP4WY91IygE>-Zb5&RsyO>KZ}0ZUtgU5z{c8nZIMf zJgF;n(X=QcLAfUU$D9_bXE9_Ek-a%XG#10BTJ2sx%gMgVdEzv0P2cxSZiV?(?7OPG zyuAL7E1{Iq?3SVXwc9z;)_EtaNl(rNklX+EHs6E$__ICm!>0k+ie5ryJ!C6_cT%@E zZ{9p@#a3O%+5q?t7M7?K3o&MiLG;8o)!WXj#hSy-%P@AP5NdHkv{*&Eo)KwzheVj= zT?KsNW+8lNPm0{BpVff4TLXUe_$qs-R8j&;-YG*bQdghD?Yi7$c_+}%FoI{x?=V`! zdw{ih=uV5+_CwfcVQpsU)<&rhyx4pvuL|D55%D%&O$_MhX7NAjkU4 zdLGcn4RT>$qGuzR)xxhDybDe~C}~L=&XL)ZcHYsT>nk|_%$e(n1W;bKhr(Xgol9O` zCgaE|kr050Liru}*7gbSlf5u_WO(tH#6L$l1u3!zZL1*RPQZghL6LyZwu*8vf+TgE zdhbEmL4|lITk~9b>C#g}Y!*n%&c*RUKN|wN7O{;ued1by?hD}tc3&faS5rAYTFGP7 zifpc6@ApLgiwW*tb0kMClebPgA(fDLG=~6dq4IJ;Ld|)H^^h}sHb6Wz=5t&8A~2gA z%q{PG<`N;gk}WCT5V-jF9-?zhyP<^OVSh;~HtbjDTrswl?Pt|Jgtr;W{ zgI191UG#^`G>ssPQoP+QYr8P|jv|qITKJ$B9oBCUybXRBS3hOVmc~?`^~)mV`9Z&3X_?!=czJF)YlK6tDsxpp6>wM>| ze(*r?L$OR;PRB!DwxD!on*4gSGCEFzp@f^?Mm#f6(xM%bDxPWOZum4dmRjGR2GFa$ zT^L33?4w9Ti(!~U$=mesNK?p~`-^R-H}65+UtypQZ+TQZ{*~!NKp+|mPd$zquD%Sp2yT62~#86QQtI74}^to_Onc?V7J8TU1k5|9u(k_Z6hN1|iF)-%InI*Of?2quQU_ z^5gT}Ep~`G>2rne>{nHhzxO>08DZ|TkEae#yz{<({kpW%HL%^Xera?VXbEF9<(8*Z zX3EEpacSk%qyh*1*A}J=Cl+y9+`BTIL`jl?6xDwXlRMIs4KAu1#Kol^)SRXx5d>(} z7RV2b&!$%UK;e2U%=9|}nZ!;=yK^{ZK$?#60wxqT^a==dSBwR5j?o=G$RdNxS8M*+ z?8#whT_!(;MLOk5xp`JPxhYzW(rO? zp}gmL^qza!xgQW6z%mafd{V^v`H~%9@~KW8Ul|RWjrox4z0ApWUY)Ddsshh#aJNmG zJNEq76ueKECd?i`%`aA!3Z+~N{AUG83@SQ0IyJt)FV@?@Yx7sbfxTaVp+N&8I14b% zF3q-`O8ZDy(gn8Bhr(tk}jiJ7J!1&|EqzX{?V^i$&-DM{1KDw*@n7nMo^c50~KUzJ6~#P zJOg46wlGz}@pL3N=~}MO)%R1&ni?9EwaG2S>y=3@$M+GF^a_}uargq%nP9?_jx8I$ zdpJXl?Nf7e&W6!{D5uJdqo2lclq0`*cFoM*%B;vBc{|5A?^(^=IE&PEMxZWC5q?bF zR?`sQ-~9Z|aM`v&s5-?>L;^4P-G~msQkaYg4!m4B`z&3Pl)R@M$N@HqQ%xHUKz)8>lS}@ zx^w52$my#6cN5@)>o5BjDiT*63j=k&kB>7vzy#EQ`W_cEGjk4ye2p%o#aC>4TLB5E z;Z}0&O1-mVveYS&nbYB&Z-I_&1?cT8L==UHGT5cVcmDBZ!k8d%Q0+ZK{@+`+N1ak$ z`qjl><^`2&gqx>vj3m8(7{~!>Rvyrsm`oqXOq%}6hb#r^+qKQzk_B)BbYSG)R4-rJ zYrGG>pc;sBj2#^<;=ZT5-Fz31bb?|L- z^M)(ltluIdBc+Qzg;TcUYqKct?i+$pU0(qI1Vw&Br&5wm7*xFk>)D`0`tsj`NCNJ| z!*RsCzOl0j6X?Q+y3qez>PAOPC9|`oELvb1(Dxf0OZ(52h=bErED|Xi#m~Ylh2nVU zZf(bqh#b;2jZv6=SqwuE0(9vz&yq)C++ItODLXeKMQqPZsK^@M^QQxXp#~Bx6r%9&Ba9F3yTr#g zL_!AS2ILMsRVSD&d;^Rct6R!niMQrHH#NyyWgYtmwWgHAx-z^UM(-quWCW}e6TWi* z9p0ocUV2S2zrN6-VOvxw>rUC8^!%rTAaY$X*@)M=5^b%NuHdu*{g6BxFdEbFVicxp z1!$E**a1jmC;Q#Vw5EvIiOrw{V0=myE6vI~&3N{>Zxaeno>|v7%I~@6-~nwc@1XR@ za>Nr_30I&d;V-?=d+Q0(t`dIwj3iV-3sFde^l>^-!T$F`CkSMaSr5oKPTt2bRX_{q zEMYn7fA|h}nTLDJ5$(MH8del`>x8B&kQx<>a5(k5jrB~&cI_OAtR+%7SpR)V2)+P? z1H2+1KpJ^I5$vh42lnpL;5mn-HW`tl`AfX+U}F_;7eRN02yyded*aS>Wm_=UG$*}3 z$DiEyFa=N#6Sfxo#h1G40=vUe{X-Ve!cNged!G${O z-{ra1=olGGiO0KpTnZmU=s@wwOht%{tJSI~X|Wy>LHI4n~y?aaYV-vR4Y7AYCY}0eZV7U?#_7>m$yqrK4wmS>ITLDwhN; z#O4Jj#W(Xzk`W@0K12i=Vvc51YQE5T*$;bIyMA*exeL$HKE;=Z3u^yqw3mf=Q?`Z% z^?#RAAfDAPznfoJcv(E0*Jbb2F$`ak9f*q~Kz88o5vlU%+`4=y;QeUKf-Dtk24n-bdc;ViBR{L$#3w398`|Hl^X|;uDup|z2a4< zFh}4sB%@PjO`@$VeANLHyhw2$p(hgM+3=;+k*5 ze25{dp+G@I!OI$gwF6`J2C{<+rt5w?k})B zzGx!#(KI+Xcoz8N#lR{S!4AMApTthCZ)!i~dBbDSOFjzNm&G=HCV0xT7I>1^Q=ym9 zc(T)wdy2vM1>=!!?gJo9NpJ!<#q4=T?@+P4#uCVmfIs5?wkFH*3HkMbL~ zhfdCNrm`)Okw2jsLHL+q{}8BO%UwcB|6(w0qj@B=b{Hw)L(RAtMt2A~^S%gVLoclZ zU?#vCmp8lUIq(h;nj%I&$=A_$iWCz*%}&10=nfoQk<4 zr`krmRx3uNp=hhev4F4$Bu|QwzX4i=X%X*3eRh5KHoddYaVUrBDtl;g5g#g{7j!V{ zjI`00SJ2wM22$j$TUUn6JGS_X;4S=IP0+n3e&@`dL4d`-g{(bZ6SZT`YteTL^bFN4 zl}-yC+;L@{lHkhRN6Ti^SqTsGqED~@HI<_76E9s0X$VxvI60!`1#p8!=2O>*s@es+w%5kPXPN+zIu1U5cE2 z;1Y-Qt_V>Ka0<+JBh|+ee=B2RPZ zMc);q!v;=mlI4DCTAD6+-r2+AYrc?FeG!t9s|QGfpEYC$3xnbgfn$m(%dGq_s1cS5 z-8GS{p+e~huEK6yw#iu+sagg8y-x+<_U2FVfdTt!Td;Dh1WiLxK@(&Q$e5o2Xcy;G z-NTH@-^lrhNbWf5PJIk^plGzz$r?0WjsuKU#&h$3(T4*Pw$D{^OZ_k52JbEhtZT7G zDuxg5IrFPvBUG@)FfT4?@?}+V+H2$_?WnXMG+dq^5x;Pg_3LAL@!{F8r|41Vc>r!d zM9pV*vsZN41saEx{`}#)hE~0X0g3yv_(wj8grG&Fk>8=6cb{YA$N0DwP-(V4zaQMW zKYACEfGS?5Y1bdfA|f(S|LoL0w8}7QkAUr7ThU_3#X`0l`9mEkn^{#|R)3rZ7`+PX zYj%}FxJWhy2|7FkX7@2oM?S|1bs*VA-k&coF1`m5_GfPv%}j_~r70U2D~k^n?}xCXH(=b6J7lMO3wo_W8Q!n_~r9K;bv6NzL4j$W;Pq zspp3|LwQ=uE)c}OW&447N|cgZ1LS2>G54iBsIG}pq&38evLwa7N9Y^c+S<)thXwfS z)8b{Vtkx@s;BK4uT;AL0K$6y4POdljjLFp(S7V`m3$_OE45^njk_%2}70gtv4j(=Gvb3}p!4f{Vo`xvmvkgGvxW3y_54H8& zCtu^*q^XP_z%3O}WG91Yr>j9AE zu!Rn^rm5L?j?*L0!vcGhhr^;)PcbfCGYJHliL-r z0|yl%Md-bjRM_%gJi;WSBc4LFT)1OC0JHO)fm_>m`*Zdzq_c{Ve`;$bjpoAqw@CC-g__)~juedrlxpq zzxxXW561U4ztO`;6Var)6-<2s5>!g#Hp1EA-y*IMC?S}#fGm^B1xVJ#Wp z<2c|ZU@{PP>(EylbTT=jR5d$T#y2woIe<3YgjX}HZvK#O2~qqk`lPR*kXTU^AT_T& z6jy54A-Z-IIa7=iAri`th(XbZ=&01H%VDTG4^HpcuH8495{j7XJ6zGk@cpA_2(WS- zz{KF_n7Hvbn|cg_mfxRgh<36}hGoQAS6OFCjUjn5NNs$(sd%!xqrE-u@72ka@brWj z_o%@lK92L}^MMQWu)YTd?oE$WS6hEO$Gb|5&{#-0CB(s*`iSZ5wFrglwSBF`+#< z9H3~`2kEwi8T6++fO`npUGb@27`UnsC)g$z6x11EnpubQwm&x)!`ohh0)|AWmX}6_ z5a1vkYB%u`iI8#Q@ze^Rnwp$A$_`V;%G^28u;T^RZXki_4pUeEq;*Ucz61pQ^HSgM z-h>?s<>QaM-`092byyw)7F~Ed&TbeQSS@p7SND@M240w2qju#5Bq0cL9N%OD(RA+Q zyyftz7ci9z@gKySdGAl~i7gP>V3E*e0IE^bRdS^HY=jXD`AF)WKg}3t5PKP&Od&X1 z*f9f@`y)c4%*^lQBHCMo!JL#zV&>_KtYsWJsz+ehTpuj~86oOCN74fv7rJAX>5XR7PcLUjX^~0QZqpJOj+cEvTquD+tg4@xzg_6zbo$&=|z{ zDh?8KBxtL5GcA{?sYXGn<4o3bf5e{9dctJ_k~r7D-$$YXIL(mGLIeZTy5R1$0;ZGV zVmCh#D-#E!N?>553s+#LCa}t(Bk@h~dk4`S8xTZ1vFac6d4e-$gg(X_LiV_LOfQ9K zy}_}a%fGWPYxf|qa67+qkyxaSKvck3fbH%nU4eqVwGtCq{|iYFX20t$WcSznq+p? zA}9lia|A$UtqV{_7UY{Mv@O^6!xJD-Aw=cap2z7()YEb_ODmr#t2U{aNt&)zW1kBk z_WL8Vn7F{XQ7YeY*6VB1FWi`(+Q4>&dl8!OZ7)rB*a9e_XbuDh#>V%W`p%IE_c8xW zfB|rid^qgQfw}zZu;TKo8W{X#wJxMlmH}XV3HUd_M}Yo`!}lI4fxN8w+|3uG2@HW~ zUvknl=-{7$p(>#-E@YhtOWT3O>-Z1_NocbHQ+9`}hEu@n>IC!=P)lTK9@F_)0h1BZ zB)q<}c;kzEf}e*Y%TYQy;UZy__QWE*AIQtbNZJm$x10MMdY{e$?N0Gv{@aA0IEZ+Q z5W>5Xx{1*ZXF#6%7*Z- z2x7Rh^Li$Td9`A70IqT`BGxju%fS5-k%YO2&*bql~7o9AnRog&;3 zh@;YE6}5UPyi-=N)67Bf7gtF)A{>z_VGbtmz zs~BP`=xsVCQVhfvAXZeQua7e9#x!GyEP<%=w~tEQhhBnV~2c8zYF~p&ZMP(e#F{B@tZLXEKo0u(Nv9^69hNI zK@189tqGpLY5f)ZN%y0cxp($sbW@Zqa{dw0Hb zCt*LsZ_+74?@T_Y<__9R=OWqtG(TKG1i{j2Ra&)@kxL8(!Uq|iAh)=c91pRZofTdk z-Ce$1FDUrjA&x*(>R6>oi6z?_sXXJ9SAuC8o%tYeoRVQTDz`Ej6sst?8@h;W)O-zU z#ejLQv8BkZj`huFG=KJwh|(RcFdg5=1by&X9-kt8IWO7?0$~EX^~mecb9I~-r0H*@ zUZ|b|apNVVFxH1`fp+UyJElBOMxJ?z-b0XMtNx{TT_%}j$@0s(VnQere7~!ThpzXn zqM8hVBe52ls!Nf7N+f2dD#=tMwC}(e_jbW!7F`YJ)y>Nc3*Nndzs}@mH}4fUcF0Z8 z2c&E}MRUDBd2y{I2aT*b$2J_Qx3{!k)Bk@XYw!D$&bEwsv*#{sG0<3ia?#Ac+Y0}W z^?ecXO$^B&YG=(;(f>TOv*IHhGI%E~4wdr~)oEVSq$`Co%Bj!$7&5+bxBCUmCs+_N z?`5)Zi=UV*;qpg=!GHeD&s!!(q~FjJTmU?@tjprah0j09VTr{|+&Xhfj*(s{+j#hGVr*M5U$N9Wv`8X2NS=eK*w=~$t;+5l^Bh}rKsM0ti$8Rdqdi3L9eGM zS>CIAwCp+!*@2d$fihtJfz&%SuKT)AT&|>m-Lyh1r5p7!f}oLSO0_JF(i467de2aaSJqIh7T=MV`jA77Qc4EtzQaHQ{fdG?(L-eIwEZ0ptng&R$9dQ6@=P?d$ie&imArop zhVPgM4U8A0@eM2$l{Gx;VOVtR>am?)Py8YPp^Vs!tzB}oF>nF)g(fFMT6dhnL8}%* zXWEUTOXuPa`MLC9n?ZEGG16n8X1;>%dfJ#V^^v(I=f#nnqeSL@5kz zPo`4Vl~sw$4?mE&!5D|$#EEma#1u**^c#+ULQ>+nd#QS)D@7~c zu(2F@5-%8AM`M!OA4Tf7Guc;P*@e-=a|C+MDZI)g+LuF1;uvP4pvxJ5_mjm$wiCoK8w=lcacIOarHn7S#y+Z~7UwzHLgA%3X&JvR^2k6NE;T@t?e*o(SEat* zuiL(V9(@oE65LA4#n{h|-Dr4h2c*Nr&3I!bOp#cXkcuQ>nfJa(5=1)Z(jmdiW>R@5 zWuj8je{$F~!|{(QLN6R6R`TR-=nv-388~Xwf5?Qz3vMdcKb;lf49udM@bX_inn+mt zAEZ{ef86ek#?(W-*O|MH-$_0_vxofS=s-!ty@^CzLN&%f%&1b#-S6JDqV#&06dD;> zQNy^#!e-!oCVHfS8hv|Ds9u0TEa5@b2_^E_TlwqsL<*-(3bHnNJeQlx@cW}IBS@K+ z#TIcwV?Js|Rp>i%r_{B9?{=Hx<(c12%_jF{xR2XgFu7k~%Fnyt<0eeX`2jI0Yg5(< z%%$yN#?b*DKX36m9(f-W$kC2xXq)F(1fE-2BIkk++6KD0n)q{=c+YOTYxqM=irwUEYMpeJ*@HQHVd93%-xAUMwE!2Gf!2^wM(^^H2P^T)mLu3@p z?xqL(x)$Bj{Ji9R&m8g+(k4_8UQGZ0FEpqM8g6fIxS}%5Mn=H@lbtpHp?GZl+hhq%k* z$Q!*7UgF-eOAlg%F1Q1$d>B?FTntSUx)~J$z7B6|ZhQ)Ihc$X@hVGbc(8yIjm2&sa zQ0bPn{}gQ;fodq&B|{V$@x6hk{T&qzjXv$%VUlZXa=Eh!MhD5xQIFoX)k(}O52y(p zF&W1Z{3>60^``}Q8r$ibG*b>he6kij8;{xBj7vH6bERa<^hZ-F4`7K!9lm#&aNOHk z6Sv{@dBv{4Oa?*EZcfrL>6(FUN*JxY2iE+69E79k^i+D1W8mn*E0;LY4@ohF_ugd9 zk0f}m(JA$yUS})Y z?6B^1xs(D8k;f~Mi)m3Xz0#elO^6e*Hnt(fxJ4(Bu3wL?;0BAtu;LTH-F~!maL2JNA|z zH7?u~@BT~Rn|TQmlmVHjYr^_VX!{zHT6GmVc$&&#Fg*a@uiM+2qe;!ma}-XG13)%> zTbRd{We0Bx`66W;Coj;*FCh&$>TfDOSj5FNg0_O zIQf{zq&hxKS(hqG#|d;@jt%xcdVV8@>m{KuEoUEO{=Uq?DBFv83dM zS)s3-8gjhVx6%5P0Oj4q@ewrH3r~p%x_7=yCpY zA^6xdV{YbGwrh?$D=8@vQ%&Qm%ZKUc)leV;?O=ial4IYl!EQi{8y9? zCzU`lyKC~pCqnNS{@lyKkim*0{}@^wj+GNdgN0Qi$`?q4e6g9z8$9Z%YmNFpcQD{X zd9L_dMn(>oizKo^*+ac1WkVj~o@v)6gxa;o{?BD2X$a$Dw|i zmY<*BWY9Mm5!>*gXGxLSi>M3SGZCI#^|pl6JBOo>LK1}dDT3j-3tHql)IW#mPqFK}%1m~& z0vzGsm*M>+I;d=#O$FJpJHW|Po)ZHH{q7Lng9KhhmjAI0Fv*pWd2pv@T~$ue-zeRt zq=z66YC%`jL5phAaPJ}xN8H$CF{&w{_mtdQds1Wazr`#b)~23DX|kJ0bJwvQ4XZ0f zeH=VyRL_1GIr$D8Ia#z+J@vHzj75=%MG{7FS-;LI`PlS+zr?5Ky$pA_UgG|&!;Q1; z$_imyrnlXjpFKUszdg(L1;rNiHiEj5D%?(=3I=YE+hHi!gS(`9STyIn7&7;}Vnll1U4u9u5o(#%(2v|U=4 zq$_ZfveU(=+}*?(L6ThAA&zvtJvjG2l3x1(aSfD#%gRSlVX5y?d;&pbp`NK>HTvh<%#5Ln>Pr{av#!T46* z3`K72%7u-m?QvKRrxZXb(Y*blW%C|1Glch>N54+g=C6AC)SqbS18);^z&k4>qLSja zYB@G9T|{sF{QM}`%|E3PkN(}5C9Y{%6Vniu4`5GcLISeaX1#@ht#_xeHV)1JY)%qg zciYOb-PkM~UwI4^C*4P^JBTk8YGg^THyn&9{8v!c>qg3peT)Yks10{M^S7BpJao1U z%_FH>4ZnbTboN z>ix5;dy!(YvIxPHXEytyE79@up~F;>jUUq`s*5mS>j$E_}i|Ad`d3DSDc76OWpp)*r~R*He-G&D$Aq{DmYFd7-k!F zdd25^i_Yq6Fo-#rq(>*GC)b&2=qBkNZ&hH4w&z;kakob^E9p{F7P}q;h(eOH zv&>Pifczu4O04@imuP(S%Y)7A4JtCEIgQI=&Q)5<5NhFkTU!3i%x@>H0Y2Yb@U%dFH;yX7{f9O$}c!2YBxyEf}YrD~!MZmlob}rfp_mbDw zXHGJGc{}aMNA(#E{B4RsK57><)ZXn5G3SYu=Q>0T-OGUinCk=KV|4Jq{s@8BP8&ZR z;ji2DkQ!?0BIo6=x#oFck*j@j*)Ji6Oh)mSVE8w%E}z*a7P4e$JSaQ?@RK_6C^9DI zzy;OuWMF-5ji0#}QJlHAqtY;XrjWmnb`&>b8j?3>wr2j%$%ff{2_J^9rO5m(C2`xa z2<~Og0Ui`(G^V4WIxg(rD>A0$^ZCoJQ05cN4tuGS7Rl{ku{yQaW0v#eM0@Ax44goZ zU4{trH($KlBaatNb!6!k&vc&Mf19Y+n!JBDkGRC}(R~sww_i_iHz{IYy}qpR;Zc*N ztT_-Lwt{A}Bu=Q8mo}dTuFWrkgM%M<5y!+wS}#{F40rYskMEGSLR&j?$8D*dpc42d z-FKs3DaE3huob&$Ta>a;!x8hwvx)PVw$V~kFpT13IKt(u2OrhL+|&tE7A`S{v* zzjW+Sbu`eu!v4dym}KBM=T=H>7_I-d)9pPTe9K>GRxmIpoG1gm9&yfY*WrrF%C2EQ zEsI_Bx^U(y&=zl`1S1=4iwxx;ok9xg>aR2fDO_9Wbe;TBZZ{nQ@JZp z-biFwHda$WlQS>lJIe7I5>bg;lYsNj`~Ec&2!tIp?cQRKM(-ACL%%0T+A9Tv1}9|V zrJ_^n7POD7as}Eid?sLG|D$$J;EYlqOL6I$8X9taS%aP-F?Hz>RQ)WhFTo)88jfen zy40vglE-vXdXIHq)M&cpr>6#4JbL&ww&r4a4aL#`MEJ6Y?iEJ%?zI=Hw`?S2#?Hlb zRbJ#xRW|iIy>?R*--X8_R~zv%Er77tLtHoEkBj4H3GtkX)K%1vbS(f{b}aq+3jHPw zGrbmnH00rG6ElJvEIQ#U6nCo=jMiVNH;YFnIB1}?wKYp1I+i2wP8rN0_oI1b3Jj7I zM^JMp6|vWI1fDE=aFR^~U;r55xpEGoG=?3mZ8AEqs{0e*q*YU+GF(j;l!}^m z;;VOW8QqNHQV>}q)~y$-(u$4CEij*sXfNlg+p9U?V(>Dl;}eMFea3Fh{K~JIOhevs z24+x)(qCvfnz?$%&s`w@2slm3TxwCyzMd*7JQ*VI#0PonelBqy`Ay&z>Qu!}=sSi3EYKLmGR~6@u@}z`Uz2_HRvfnYt{3@XG=P8{ql+RsEPxFwg#Q4 z^cLx(o#lFoYQ>VX_*h1j5f}}`p(blpjp9RZZunaVFpkt2&Rgu{rO&dEQqQUbZWP)L zNtqA#K8vyg#Y-)x!v&zQ=niU;kA?4O<1T{<*kWX%&5}1*zZe>XBO78?aR#0)L&wto z!iFit0;hzeZW*ysl;lc+4;x5jj0S(nh8EQ1m)U67V>G?I3NLl12M=m_HLvGK4JB$y z#KE^}tUS#=R2sN_dexERWOw8Mv_dttvrG0q=V#l_!a4*IDg<0!a%M?%EKVm&c32y27orgrp2ciZr;+XD+UHrTS zx-WU9zw0X4|Ll{B5}2Y;+Ua5&r1-Yv3Xoc7AYT;Pc3j#VCGd-_`d#{_b}w z(S{Mc@^_xLT*-@L@YQ^PG)IuD?%rGNQ;Qwn1jSl@@GY4t zN}pcaniyrqH}hWTFQ*=!HG(C)8g!19sJ;!lnKcj7%iN>dPv{D%&H(9(c+bsKC-p&W zGA@{g`$HP?sOz&P1c@GxgXZml$v=_LBVn)qF``g|32~9?V zRfn7Qf}_qm;i8DfDc$#k7zJQkWeq&leWc^H63Lz&R*Fw?M<8p%(4ka#j+Gv-mP8d<_Ql zI-t|&QC;@WX2so{f_6%b*>7iR`Yp~uBu8x}GNqUkA#p7+Gjm0^`ubFsV>X8&;8G46 zz>SmA@z)~a$o@^o21Wl@_(Gm|=7p~I8u65GXM_8ec6u?0J&lF|!LCEZQtj)dxQR!j zpSgu7CM=Tmm~nOME7VJ7K_exfd~2PH2G*whJuFXfj1SA=V`7Y-Sz2oqr=`2PA^k#k z;KU@YZ%x;TLQg82)C4(Q?mlm>ETlv?>}1;eglQuYYO3$ z`eL&QGn0H7!rSixr&>ii4QNXydo^}ljDyy~eIU2l%Wcbv0S}_Sz6!ig*1EJZLr=qa5#B2w&+fDY zMo%v}K8BzPeCW0K=ZG*)OVRka8=xbn8L79iY^?Z*^viuqGPejF+M41~++&|g`_hxU zw}~{Ca5#$}fR-12n6cE%0G^|MUGa-|I}o$`-h z$`Q*=Y0IKMtTL+?Ku#FKWhj-m)48CW^l1<31W0mH`xFm$|Kb7&sgrn=B-MQXKuhK> zQhYBx>EFYMIKK-{!kH5j6H>eHL0~ozz_xs-y`6bJgB)w`>x7g!pW1S7FP#8T0mp@K z{+pYsk8nWdPWb3mOi z3VJbY))>Qm6b8~CAt_>K8wBA)+@LNd;%qWUvOy=*bceQ6TA`wGG|y4nRHjWa?@mD{ zXU(}6BRi-W{YH99<=PEM*i@u{rR8U=S;8Uy82(tytWrwR8b6mKVhs9!DwHRU?CFl5 z&ClMBVIX*iR~plFh4bRiCGI1FCH_`7y-H>)lsI1iLc378{@%Pv;I&nQdyy<6+Fg?-*zAl<{;abo)Mh0ENlI@UFYvo%^sNQ z^4>G-OnkuOvo!vL2MP0$X;wc7fdV+^cXir6aV_d)XG|qqARm3~af+I=o}S+I2R1MP z3A|PYot~hffth8T+w-mNuwi}V!c(XwR7&xZBX-aYKdx))#<4&NuouiQ9iLg(AfjOA zth@J2b9(vZc0Jx*Rx%eEm-?1A9vb(#8WUqF+lJG>9~37O!5ivhoqIgQDE)U<&82N; zap>_!_T89&`xSng?wK$2hD=lbFxADjn5*S-wcxklMwMQ|Z~MIo{&)PNHa^a6`~qBy z_`d0V`3i%s0odD)#Wa&tM{9uCNJJKK$->^zng)aKza?&2R+z75G~6mACs+I3Q@>!J zaz8rZiO-EAwL_Ukif)3Gos@8~Gbv_8DVVLI8c&9BNX=-N%uspvzz+=Rm{pu2ylX>5)vYWME>zriSbi$e6D~no{{O5J5^k#Pu^S{aBq6b`#Y|c67fdaqw6;h#115l zKC1w6Xa30nw^PHf*Vu?VG4~2g68*`#n()l$8G0J=Z(3k0|7J6{WT+XfK_Y;LkS)xtA7j)tUkwSJ!NVJs&SztF7^!Ra;jn?<>$=*@Yeqa9FkedkLOuJZ@sh0Wy2p#WHYxpU ztx{z%J2f|BUOhcE#{|fpO(@4|`CCW9fy4M?Wl`Sjo3tYcexU|M<3;@FLjz^`i-~ax0$#n0>?h1B> zzu8oV%4S_xVCP$cwlz3-Ns5Y2hKH~FyKih*VZZ2 zNXEY{pj#PoXfovS=Jg9`nb)Pyvwj)ry)Kvk)3>HvC$k&LlNK?d6wjC|0yGDaXWPAQ5SMY$b?e$11w}9T^D^eV%zBk<<=Q(P2L^MdTHvG3zaWrI zD-!rHOt9l`$;vU`oqD}h$6syRvB__C-|KfU7F;bjt`K@`&lrcFCDZh?8_oNG;Z0r5 ze55n(mEi6o=hQoF5+~vnt-5XgKX)9nkj)Z|RvI{*7D)KXE{Xo7D+&P=7!6*$cro&rX|}ht3>vMz$x<=uQIIfbz00Z-B@Nzftt~Ed}QC< zth+5o4yh@E9TrBC@~}$iN$p5n)V#Qe!zIn1j{<9>4(Vyst`*Trhb^4cy1w!emXCpE zaz_11WKat!kY}!BJ+IB~T$%fL^pGQumk5L@9=`03d4rW_zkFPs>D0Wu-cmhyo~$`c zb-W|B9d+8&ZynuOd~-#qd{$xKBHt2y>sj^o#$I>s9W&OLw7i>o=u7w3R*Z!#ORgOD zVQJ~op)+cJ-S-S+gLFQUq5pq<69(VU+SZKHN;&y43Uw(dRp05WmdK)5f^#9^xi0sI zS3|v-fp^ThBWJIFMa-y6i<&+{&dy)VDsY=pWwV4p%CZ2&0!rpmBWR~G8Do!ju^4Gs zPWlcP^u)56GN;maT&D{S6vj%TXWfy_mhw=pn5m&5X>%cW246|PM(w>?lM$k$y9H1< za>4h)AQ364578%^ye<{Ky7JEHsMV}to>K4NS4YMkbY1w+c-wn2@0jj}oAadS4rFF9 z^?EHHF_?HQHeCeId@g=|Gy897jjnZ`BdO}fuUv8{DfOCys;Gp-k8@jMa%UB(j+ETT zM7N;8z@e8DI{zS7Sd=EN`1}s@=Hm|Z1LVW(U=|3GTU6ePI&C+2PK$YRoQMwcwdUp8$QWW{L1$=z=`y2Z`@6;UjKQ>56VXQBS z|2>)z1R}s(0>D?guj57!#v)bU3KQUt#~VwT6}4<0oM6d@GAJV&bLhkX;(Hj!itawh zAge}3Hg(tfP2DNs7WRTDEq?RuafN$)clnmQ>vJ41lz+~i?XRlf%Uj~anR6b{=fd*0 zc5^3vwa(<8nI~K43``}mr?2K@Tdy$3CTk7Q3WqDB&4<4p84j8%@kqZn3Trtz_&XQ^ zc=1ZU)iW$M{aS8YdSPj4vuRV^s1ZWe>1e1C>|$?z?sW>eyuj;W0AD7*oPBeE*U!b7 zIe7UR{$1{47EbbnTCiU_Ud}k&XV&&h_3VOe6~_sw0>zpTW3+L5`ev!vPHc2)hb9fLr)>bX8;J*2?y&KG$y{r{PdeyyR`EEO{;`BW_mBuvSwtL>wM0>+O z(yaXwxTOYudNdC5)ajihnS@xzOTp)9_hV{VvPoQ`$l8o`xes_H9z50;UR7v!7-&pT zbwgrFw}1fvXK5+Np1FzC4GmWak?~tb84>o}IX;ZWog8?SBAAU}bC`xvk(D?%CE0aq zGR{_6-%lRV{AQlB77~Q|4(|24A#zncSm>%*nLzX3&6M+(sWqFV(ud{@IecjM{jWsd zvomzWP}yFLu92(VwCciz3mf(toqAq);m0ODYvl&Z{K|#nQ{knxCaw-oJO@;)n~)iv zj#lw}zT{fe`@l12xMeftoWkxFx!T%ZueU5oebZ-ZUF>i9xo>eHnKJX?7H;M`jwX)m{fr*CDw!grO;17bxv{a3g9j*qMq>}h+@`ucG- zov1xzO@jci0$Jg~uKek#AMap_=?_!iMM6XEhifa)NAJJ9)y*vjQ{JC4v|bE|VH!CY z1a85&jeCWd#CP2>!hSZznYV5%a^#ui8I)F4F;xi##P$!=Jd0W!z$(2{6Grv>L{DT#z6O~ru0Iw zgRJ*i8T{BtY$0;SsIQQrUIfVS-CODXroU($%++xltO@j!aT&H8b{J_V9C%8MbBK?$ zR8(LAZx#3A0s3Y)$5-0=LM%D`>5q;d>IX#?a94?AT*Bv&-3nfl0SME~NIsmhBSF5G~W8d&WXBVub58WS_XTRe5(Mh1(^aQga;Wd<``v0o_)z-Mv1>JGQu3R37~7Eqy6 z!R385yUzIzNfkZaPtbJw+ zXZ8z)w%ob)>C+Xwnf+I5+g27L`qd0Bvv00(D%}EV@VNkY-y9GdzPw@#^uNpqo|`x> zfv>DV%TJpYs?`L)1CSDqY9}hx3*y&q81El4&E7*#s%$)IaPUUXbobp`QBYeYcXoo$ zkqwDQ!$t!GgU9`hzw9=C7xs9dN{nva`TYZj0QoHbTRXw*4Gj&o9ry9^DTb@p{FO5o z)P#8a;+ot#6$uHA^Gh}?H`hsL3Pi`o?UoY{56}D_uq+oW8NH@_q4&lfg|DG6k4LP% z#rJ~mQ%(Bx*EK*gjf|^brR`J*I(KgLDib#uqVznN`k^UJ8rQA|H&emvjZ_a7GVv&S z-H}SCHIoZa9f%_(V^-slnaK}GlF+HnV68CV7>l&<-I$Jqm5b}Yuu8JN8}V_Jdu>Bm z$v>aXAj__!r?)mSWpN@H&mU(~T2QHmphE=(x)xW_qtoggJ_GvG5qzm?vqcE>!z^vo|D9crq#MHV2`s8y|_kxo7s%P zEX7~joLpA@a$Sf#-)k=|Op8z{=%-Z3n> zquMI=+mRnGvi8k!-sbH!c-Pac&~mIX9s8fbvU~19()Ucd)gC}fM5>dXU zyNc{!Y?mQL)z)p>6quKah$Nz5czgqpl(W6?Zn=JLDbl+q9xbb!KC8 z>cRNu=LgyfO1kT=9*y(*u#9Eiyo`~FXkfWtITbN~{&U-Grh%^o_UdFJ%pbQVBGgiz zykQyo`Oi!w-7t0QD{@LXHx3vZhshpZ>Oep2PAqfgub__foO5?og#)^AhE<28^CuMe ziL)A&R4iN0@MmjiXqb8F>ESd@vmhD^OxN-+@w&7XP*HyCBfskE5kCsTYXoefo4PS! zn00}oi;&*W=hve8#YJME<{mq{?<&^H3Mkrl5~2L9?@GTX3H%YE$oezqVCiXm_QwR6 zjrXiF6G+$;$ea(!<{WVCc2}C_nK{ElPMb%QK4wEGgaT6B?cT2)L^8sg*PLwdu;szd zCFYB|zUO6Jh|O?n?g2PDTYk^`Eq~FZm>n2e!0ppn<#2ja@V%73s&1(=jTAKD#5Xh} zV_bf3YW()0O}ylSgBwiF=;N&&yvg6*V%Fg$sBRRccVx3fmSJqdxd%r&M(dgbgMuzX zn5GHp%_cq(w*S1%X6`j=Ak%(*dF?~qfpH=-^y^Dsi3aN^R1Bd29KCe)@7U|s2XOo> zqD*+}y4+>m*JC{O{#V62M)p=Cqqf6Fe|!(uQKt;y-7TEH7qN(ig@sE%pg(m_g?Kk< zYleM(`{Zg@UEE3#-sgJyFygmQ@e@Tj(JigcI<}z~3FkEbo-NHRy){eZiiZMt_&z8b zy|0Hm>Wv#kYfstyd-wdanN0am8dv_BELce&wi2y)=z*IK+EKuD7GmlGd5I~aoy(lJ zX=`7?QCY||0J3i=8hNJstn?7koLGsmdvC%{ALHAmy0CRqVPRvtV_&Ckx042JfRre@ zpUFs`iv&}->&Xe9tFYxmfFY}JrRe_M+cUCv?krjgb1@3=Y|J1vyh-j547oqqT$K_~ zUGUHI{`p@VtC3M0-||e2{>3Ri&28HvaHa6--ewvY?Qf2NBXSVmQeZM<>m>(c>zUNQ zwP5@x26s*Aii(P)__tkM2_RH`)jH)MD>sCGKC-b%WwPJ`t;5V4_%cfYO%ei)QH;Fe}5Nyl`aB_E;S~n*Z|X(|>WFW_~?+hW%2g z3w3|`qBBpJk-Q17*@-7tLtVWrfPTg?Y(&y|OhAlV7-_)IT2=QD(g#R#LTUaRm@uqJ z4m)DCt`b6FS@PDXSrdkCAZDzONQuFmSMvK$mJHsuer zt!~XfwEI>Aajtbme}vK2^F6}PX=b2lTTuSktvRy$ME431CRs>jSVu=Eqw@jV_bznB`LL(J0F(Sluqqd9dQGWX#{IhzJ&OJ&qLG0Jv z@{J=tKjtPAWssw#)VHX&ElM0*C{ix)`Pu>HpTpl{UBCi^ zKP_gsyw~-=wqkNJ&MGhO+uu`($aZx(i7%$-SBv(!k`N0X_3>NzBJ0+f6EjHH#m~p` z%7D?Iz5XzCHVLNRp9;iDhCdDB-s4 z<0vV}+j4GU=bwex&&3JH+H`P5(1iY3KrFT+*?t4T9P<#36>-CYCi`UdA>0^=V7yIP zhb#b0Zut_bm;LgD@Jwa^Hm((&xhD$!`3NO?BM#`>;rMUgj*_$d;}QLg0EQ?Ij^Rzc#cv(|v{W;E}_I7-7jXG_+$S#zIF(7)%;KlJwzNJ95X5dDj$+`nEdkLmDx ztN2ZYzqkO;5>Zf?vPB%7S>5GW-EujOH)M5DzEwPZ8bX4Fj?SEW%H#Fnx70}qh|{xK z;kB0zxKYCN&YYe6%!X2o@aMbXNGn?FHh+bUzX~i1xAfTk%o_fDIQoh0B==s7`{oML z+y&o%uXbZ7BPS>4b98$6t3uY1a74AkJ(6*DVGli)hVfj1jgStYQ^r+}FC-(CJ(kd`h$n*>a0J4)$f}k^D54tdy(xU`pgpjq_UbA<#Xv*#Wen% zC{&_F=Us4X=Eua(p^*j?8i0Mw18wMaczndM*-Rnn1Gj{pCK~7UZy_csnX^Q-eKTvq zf9JWsK0LJ*XKi>6J&?JCQL%SFw&hky-$ZQEMuR#58UOjp%X{dnNs-1Q*!V^gUare= zV*5tw>y?RKkkeIR({xa&=W%3oI_3PnpNUrWZL8{rtRMnDO^gx|Y)EIf;>=m5Q^$Y( z@?R11=e-2M6QXD2%)3xz81TOm7bgdQu*=9JHTUmNJ#q4+((-Lw^oY%zS_b?lF+QGp zY`jk*5>~LE55FV*SA6wv_g(h%o7m+nf`JpwyW(0LG5%k4Ng@bu@H^uml=$^mznr-M zBG`7&_Kiwe6e}-M(7cn!n6&yBRWf#5M zr+?R1n=^O*g$K515s=t&c>w7z$cV(32g9&(Rr#vJ?{yZy+|aH|6q7fYW6QvUlg76D zVm>r6TpNLN$Rx*Xntiqm734XmICvKDHmo0O7r|u1w3+X5x!^x|D&^d6H;EU>h6*GO z(K{G3XYbc$uR_dmF3?t^{<)eqB(SErtqCL^{h6n!@FN!$7YB{uWich)0q^!IXmNLu1H2$*Ss{3$r`V=X) zQQ-imcszHld0p(qiv}a>NuvzKC->9DNV;w4@54ubMoA+A3JU%Cc>dG{Slk6dyk8(UT|2%AVQ( zh(UfWr#2gwv#)BC%b(B7;fUqjY+3O%NfK+`eUiD-V$DIQ6&M2q! zi?ymhs`t==NQ|)WcN7TKfQKrYjcW%WMA`JWC&)>341^~7@-$VoWHS+{sIx>~!UZsSZD-q~+bASSVnjC3 zqy}>sJzRudE&fs2(i;BxYaGMKILRb+37soKK<|&J{V1O-o#`}DVUL(n{AGmPuV!+&5um5^F{UlrtDjVsGYa!zDv1O%_Yj+^# zf@(t^L(-7+iWqfzypfW_s=pgh7wt3&ym*}c zi~f1hxN>T7N`5Q|>!W`$Rl)`C|Ml#v(RSHZrd7m!`GP0yERZhk)i*T2GIg8Ewz&aKBm% zLyDQqKSKwL~%Sa^O_7P;#6_t8*XSE8p^ zT+@8juhroC^8|tg{l{XP@Wkhr1p7zR8R|B^w8hHqPhps*OM{)Y)`;$&pIJjGqjSlq zDFRL?3`*-2yhhJ;AWl}`$TQ%qUIq9m4Pfx`r$E@Iha>&Gx>x<1DQ7;g&v)pNtUP&V zf2(`}Vpb}b_#p)SKt?hu{QF?hr()9!fJT7KNUL*Z?T=@~))jvHh5pZjMRAEGTraMR$-2lXjhyuK zr4jxK7QkN)al_M!esdVB+u(kFUgUAGVHpgh63ILg-pJtH^z(<3`qIJD?~kRGODaBK zXvfV>tK9dR7aou2yX(!md35$EI53zKOF%si(uS?VIw%rWL3!)-&20N1;CuI0;-{U& z9~;Oe7Tdd~C}|HppY7a4W}E;W+&!)Zu0H`Gugug8He4<~hm<|KKc|v=eL@QSp?Ob< zZ*9~tqSz(qAI6W!ievq~>AeUTBEI4E0cJoHF|jP1xiG-rL{293jbFy21{WpA`~XCu zzp3moWrB0x+cReNy-1X^L33$XnU$3l8WPg^BBz25^!|!!^rx1QK@>YF$9|3eSl_l$ zi|qQorih&;S;kNH87-7@Ue38ElpamK=~53Stp`#mrl8R5R0HIc z)(Ku?I9wg9lNeQ}zU}@YzPWodF*goDZ|v$ZzN75<-J#lhVCND@eq}gM3(O{wNqLsz zXRYaLy>nCSt(fE=!FOhHUG9=~EiK(M)4%j1*C86Aq9DGBUwZUNJ?QM&M>C^U8RTea zL}`Itcj)j7;!-q`dIe*E=0I+_Z05%nGYY~WlAyx6Qf(z>ez7aa@8I2@?{dutI%)Aa zlhJ$}@*kx$;rfmGJynFNJO>bY-wQEg}O^%u&PR_L@yIq(bP|&T=U8o%{a}oWMu>De* zz+XMzoa9#*kp8xi^ukqOrf3L&@v6OM3+a;3;9(7y-kZxBah~_#ZWdsE%1IvM-+M!p z?2YBKug#=krqrUl{e1PM7|F0c0o5;Uu74{%e(qmJZbCVMjbw*xAg3)>uT$Ho5!1L%}#)a8%kUQUv$DgRu1!)L%^!{7T0`%hg`_e z;c1JjImu`A)Uy*O7@HMCB>ywQF>l|5M90bE@9Xp@XAUJ&EiqZyXF29LcZuk;Yzz*t zqkpWAw@Y$)-s(&va{TBydb-Y*P?x3GN zp>A?@Wuw()vE0zqSg8@==nxn2g4^@v!AWsgJ^^#7%MK!n*=k_zFfQv~ zWjpX(b$`o>1?T|j$}iQy%kI1f=gChIFJ2gPYk-)czGcgU|E|KB8Fi6<#~a+Cj|28M zVZ>mAWw;NLTu5mO@nN>sl}8A@G#*JFPWO}Z5;AYRPs;Bwh`6-JLNfm30K%ShrG@f5 z$BRW%gZzSmgKC_HUn59a=GNb&OX`3qSIoJVcj=`1$(BQk+{r;B(c=pWt*hCd?=G7q z;5K5fc;33NSNAXqWxfIDk4_H5Cot$-6L46}+>P$|CQTahlBZZs-2!+T8iJ$S`!ss% z&xr8H#!e-Bbxj7F0X^O^>XY0k+xLfi11n({1{>u(*|*VS>s%wPPnS_@JMq_naJtO|M`|ifg!g3R_d9fhtsic0r~)3Wy{m;YvQP-w?0T#+w?2tsV_+NO<>>*OwDd%Qg* zKH2M}uAxzdCT#+!YBk!iXK|uUD8RlS33w{^kWFn zyLF7CB2DLb`3+)%W{ui`O6C$X#`u^}41U0-2-;P$-6CPtVHOk_K z)FZb7iQzAE(0>-{FVc3Jse+%o4|bTEUAqj>L&z^f13iVHddRYGK>dXX%_V zcM}-IvHJe;g;S6}3k)c9euaXD9*DT5fDr`>>o233S^JtmLvFurjMVQwxSk%@veENK z|4AlX*kXs@SFdzFI=TkXst{bnF2V=shlKWQfV_S*HBOe>UJIc?Q$5)A!cq!UMw3yd zEA+`^|GH;5Bu`_DyrXu_49k2?Ip$TOvZoj~{FW?R?1W{reUHnpTeogcRu+9IDz%q< z-pMsW6vh-OqIkxP#F3~iY!^sZyz!RO>v9V4<#00PhY*h5@^r4CQFPlwPPF5syq;Mc>_iH29=mhMOKFBI{;$iCISS9a@rJ!HeX~om zI!J6A=-uH;wgH*!R~`~XZ)*x^;@JMp5@pB198!i7*$$0>q}Kk%+Y&fJbL&!c`rXJd z^a?T!TI&ux`1Y{NOu(mOPbrSEHM`?(hA#yEOt4; z@JS(fBRS@OB+Vz(5W4k~?}(GI;cv&7)4Nr<{#%=EA<7ZM+orNrkF;hmg8RIHTJv9} zp7OuPq!*_u3!3OEU4bP_5+uKI=a=NUxS~knP2M+nI}1tZ zMaL(19K25FI=5Kkj`(4{N!}%|3{c(XgSIlN;OmH>I&@Q*(`u&G34fT;*0elq&1_f< zB0W5m`2L+JGTsO(!iUU`Y;_p67YojsJtySM@y=KH*OlV?v`tL_ooLbxa!5)6btj zUyi=q&@SWBaiqBdri;3a#L@r)?^Vu8gtC$BUxt>q9U3`Ft40nJ<4`91l<{jkd1n%m zk}9DUb#Tkt`_EfM9Vsv?K(^*jV4{Uk=#(vGZD(xIX7(d39w49KYDYe`vQNJ{WevqM z!CdiP#*-5@eBS_ECc^w9NfhQ3Hf{$Fb`<8`VR(vcY(m`S!;57F5UJ}9_w|f;)Y`D; z@#lT&C^92zL4x>0{i#7ljN5#<^QXl2&n5ef*!}B(_yD@8X`nFtU`m`R43y{Ce!p>3YZkUw~ALZU0PkT|y(0a|>ym$PWbvl6*_2=PwQEt|kiBe^%^||I*hZXN9GF*Pnmgxg1~YI8sv4w1e#K)$6kO zmcYN|63FN4qz$rJ^2_j|6G50xIszhSH>&DTxIQte%;v+J?_uul>8XNWp@Wv@28BIO zL*m6hGABh|8ZvhXW{&Klx-Ge`ZF;Zx`*vHrC_&(F+hy8?CU8Hx^4gq1*Y`G=49DA zcFugD>)n%MuNCYL%ihrv3KXWAof6+5*D{-S%Cj~CXB{bSDy1L+fnou-~2+DGar8Eo0TWR7h!zR zY2xcIjII_5=6)JkQY&`FACp>&GZzjo(#f^<7s@n4_G+5F2;uy-TSgW~`Bx&vT2F+fU`dd`^vJMkoO$XPKg z!ZDxrypZj~CztV}MYCvMn2SF@7Lecbl%wGqhIm|r`p*C+Ii|7u6iLFDnM&P!<|V1| z$-Vex2PV0+yEW*BKT9j75j!+Yw)HK*52*5H1q0wON;+3v^AiQ2 z-k%L-P?EjOH*EJQv!KyFX7N2ERWji)YP5F@+Ak zQ478>nqbpq-H2hoiEh9P`j$}4D?^Sa3JYn)Ow{#;MeYZ7Ysi!+1^$nef)N$QS89d4 z9Qio@156OH*}+mENoDEMr3q*U+^xNUi{cWv44LA)>? z7ZWDtf7IVzD^3yf+eUczL`am>%gx1gHhqB9lUwaikefGbxeKPcRf0ijw`d4MgsX@r z^N0IC^;S8({doRr^48l$;)|lZg4;$#epYUO?q=pwSi$@H_A@@RFIkb#pK*7VQ61Ur zBYQsh?Ae?HR*ZCf)WsR+vG%|tPUh_f)H8DM;T4-vp?wA?b~|{9Y4ew_+@V7~=sXE8 zWeEb{Jk1$0VxxkO$EG( z-7(cPEvke|*qnS=8Y?;|R=ec&sAZwVq!HdQJK&3!B=%NB(uqX{gD1ZrAVdW`4;TZ! zyhD2XbM!yFlxEV-co5y2~0QX&_^_H332)^Px@dnrctim-ON|(0P%Ny zxutc(uHTROpU>YyWJ^CRqzSn5dmH_$E|d`(nx1++eF++gmpm14+11!l>Qlh9RFs$- z29pGd$a_z=pzPUVPV#&&uc;erb$)RHHcWlHK?W&>qKo&T&3tGIIC*6tr${%F<+bNw zzkhM!otz(wS8<|jKH_@hdhffnS1%DmWS=zDTjB5-`_EYYd)HKgp%=54`OiSZs6(h@ zUmgn_4CISWNKD)c)+YuU-|uC;bpb=!S<@!*dn>^=tvXVJ^|wk~DvTSxym}+q)FO;z zs&^1y){lkOKA%ro0E{{R^pYsLks}lWXrMy(WO@!tbmRuVW10aC>}0qr_vCtS@H@Ah z{t8BsCjN`0W?yb@n5+nN0_gjtdR6WG>0^L(y5WGqvb9)@f0A5QfU!a!JWz}KOi&>V zI1qw1GaQ}g|M$bzfIaY|;G81eJn`4dk`m5D>JtgSwp#Y!b(RQBcHrFsBN%n9otpab zsR}I0sv{~WHf_6v={KK-2U(DR-}xifs#s*w$YN32o)(U+7F_kJ(ZTND6=RH5v5eLm%?L( zmU5?Uv=>^G@;k5lF2wUaKF9HU{&3_e-PikizpmHy8s~Ywpd(5kDb`S=+Pin}d?pc~ z$*+=-2vNyLP>sd1Lb>Lbgv)56bNmsbe3$p-<6;_)JKGFxrE_Q=ZAb94-!+CF;mT_^ zp?T2vHb8#uS`*BtwR4r)M@)T;9ni1i?HdFmUaFjdTjD=WDBCvOG1KyPY-3JUdvQ3wPcm+rLTw9~tFBg}R_ z+*I_C0?qD=2_nW0v4buu1_bih}JaMZityEczh!PeY4haqpMW*$3)iwT2ck)!)8)u`6 zF_?23MQ6+gB7{el-Fo6g)KK1B#iQYM#QFiZPw%gfQwUn8o)!50ywe;TqbaG_UP$Ao z-O;*?=~jJcggbxz^v{ww(y&2#d-XiuLGrVgxW3}_?S)jyrmR6&zdkSz%`VAA5%>Ps za3>4rZ4~>B0Et@)z;P%(RDaErz^hxFyw%d>xdO^)Y)aDJI#fyk3FS}ED{ek2scMiJ zPGt8!l9~~(g7d!|HL$;pd19-G{rjOK1whNruMDG(h}cVous`Kz z^9lf%QWG|9$ZyovfSajo`ew#Z4o_$mZS>>1#5=s|Bm8VA4zbZndji$;W^F6k9Z1-B9-5BDkQ|?K#vfS2)(%30{`cpYx@pD z1ItIc8W;72Tu3On3$0yS_w~L}loMtREvRo=A}A9&agz4d)elwNVG27}3g-Dou?2o0g2`=pRBZp^k|glq``|wA%PD8^P6P zi$uVqJ8qd1**n0=CyLU#ZLGt9-aUyZr&-7y3Iz2pg7u_FX6BM+goY)p%>tO<6KWP3 z4at#G$vG_xNi)r<1h_bUh&$Z^S*4_{?!I%g25BGiDj(XJUgU#f`;*{>oC^$1oQ_!q z0Cj6JpZw!Pcz9)(qWR>OxDUvo*;0YiDQ*=#~)N8emg- z#fMRPoD%S!LdLEi0=;@uKnW&9Xgn^bcuE|lURx9fWKqeC1g1_jr%8(JgzcX(f- z`vGciDVZj0wf|+{%yBm7&do9DJafpAb8>QeGvneGae-8bYY;%ep(poH`rlEw?^F{h zQ6G?sF@2&`c%7?JDHc_iC$qx6Ugs-|u1p`vYj{}&q)$6QHm)dT3EndPQZ1|*`i!uz zY!1{Um`c>YdERiIJ17RHo^zs_e%ZN-`e0zdk!ClOccE!Jl7Z2L=X9JX^10d9Kp>&)~TeYW2m4 zO19fh-wuqOg?9id6UBMG_iaC3EA;R()6H&+4Z4BjVD{}GOZ~ugcekNKYYk6$bay1H z^$eHs6m+ew+yg+0Wl!w2b&c>JCf6GKy7#Iik+_Z%Y~ExLyTes&%VU`ot#*DsJa=4w z@0UHuLMfuYh5PI$TJcp?EEQZX^=;c^n9v$P8h?tjCzGq@z)n(B{}fULpsbprgc)LT z8YyF0RSE=i)kylieEIWrK|#-8D^f&DdqpFWyK_xVdRZp;6zEs=aiYlMO-PGGJ7mqT zC@27|N|A~=c6j(lGFL7&#k^5u+Ft%9a9f{~c{JP4LeP9YDwoqq;fzh2Vbtdf3P{p# zM9k_M$h}QvFIMbtHGX~~#RW-aAWMBlUS8ExyaFM}yo$?gb*tcEq#Hikz|p&MJI$V# z(+kR$jz|8H`O}-SIp!m12rm3rh=#CX+d?qq*PC?Kh4PN$<{6z2f>(qqe|e1Q>kRK) z_tW2zdT5;aOzPq2pj3${Qw3f9X8EM)v%YrA2j98^yRWfro0E53wLGc5q$c^h4;5m@ zn{?cD&l9prG*NQD5(uy(y;k z5Dqu%|Kz3xuK5jo>HJ(c?Bf37v%F}|EI0_Ib4xV0Zw>&GBr-f|k%)&h?{Rua zqr%TdG4~m`M09XAEqjjEOW^(TcH5Z?R&MnD{&_QLI_u2rO#%MK{29>}-#P^Dd64}% z(<^X;mX&1c64T=Jy%q!E6P^Ec4Dgl8SyZ{^u&;hW4={`^P&GY&>5`?! zN=ZpAWM&^|8bDy*3dA_Lf&spn^mNe)bbcj6y?h#lv5!RgBhVQ%=q2ctj4CY3_~eLY zpL0_YL;3q?L}cIA?k~Q$94AK*2kRVk#u6$b7cIA6*DCyu=*AYwQpo>vT6HO91*)}I zprU8zEP(N3=uMNNi0hvHpWhE+fP^OShA$%PP!zuLbpz{cpIO^Cdq}ubBen<4>HY}E z0E&jlQ0{{@+Ad^@rq0F$xe_zCD*XpW;Y8Dgfl*^_H2|r+N?w)yRk(mkv#$mIM+xXF z!6^8tube|OiNuM9QJ-}g2E`;8XC){4Y~e#$X4xmgj0xlvBjo=tXuw={zgrf338OY{ z>-djB7)}G^fRa-e!^1_1wqP8P&!n_U@S0m&f!Wry&we)z4dxYV6m1^tww(UB`_iQk zYsr3iQM_JXYWM`6JM}%BK|pxI>3e56qUytOj zvfYnx>H-@M6}q%)MZdOsckR}7@6S^)P~Ms&$Ix=L_=)M8gD6g&#g#u_?lB#1uPPPO zcp>AR%JcGZahkTNLX^Kf#A)IoaxRi!1}@1a0E48qfi!K;g0M*yFkP{F1^LQ@cgd(# z?F9@H@#XeiP>(nVQSj$`LX?(*)qWOm(B~LaEs;_%7|y}PMF~Bs19XOTkrksv>4-4p?}ZA*3N0S0onQB zHvhjaSAx(R6@Ct^2bPe`4La6^k01Abc-4M>Ly#C|eD`=QnS!@$O0#-0Ttb9xNCt;D zGxlNBd-ES1i76kUR4%PNKtffhMVt3qc0U_KiIC@5SKJxg3@>mMi{wgVu6yzars_k; z@+-8o5Up9vgOFP@26g6egM5evpNpHYjLLIaTz%3x%q1Q}G$w20n6%`{xOkw%1= z6lsMLHf2TFi6+{?>sopirvP9axnrc?k*j12d6KSB_RsV(8BtUD-uq)LCCMnGxGkP< z(IN?CTbvRH79(6J&3PeePo0vN!6&zwJnPYsA+wQ_2KE8W^@WB48=?{k7zW6bArfnry`Le)d2LMK1l2a0dxHesB( zg<8?;JzUoK0y09*bLPz99&KBInqC->efIivo|JV@an3(NMdU0naipF!svtv;AQ^Y6 z_=P4JXO*ODKnvmqQe6hK$o9W4nr*mf^4e`Kh!L-%qRr^q*^BVtwGploS(dtSb0yS1 zGis1k{W4MyUD6J?+Xo#WK!ya)-rdg7U9601M6|hgdtBJZ2Jc=q(pq88C7qJyYbW?t zzL7AiQ-&f*dt;$r(TDQnJg*N4TshH@sj*e+t~4VAT%LZnw!(~}QD_B!(lmkILX=gj zSLxSI^Bi=ZKWS^-T+Lk+v4kcpSm09O5ef-qVjK3i2?z6$<+j)IySOQe4+xu zyA+_KN0K7#v~M3ZQ)v`=L-FVqH*p5Gg|9kwAXB5>+lI?6=N@5h&! z680&EDN*S_BMN;^jhA6`-5f`_vIOkJV12D+`r<I%zZjvTZojoA+>NzLP++NTi45b6&G^8a4E$Z-%!H332?mqyAt@U6=dODdj0Ow5Y0zeT6CXIB(+zf5oO_e0Fv zrX~H&Dsm@uzS)MS=F=?pz_OS~Dp>m;`_32#-Z|i*Fk?P;oe;WSL{GWlV9hWZX-hyJ z^E0MMDJ$Ras(yR#O$9Ym^nvyMCZcKC$^ldon*={C1iQxm6#*iRa1<(KRyS6?Cxp{S znd2^Ick2T0D*!;1gi(Vb_Yi3$Y&z$y_7q5SaYA$HcBVoScEO6>8+GRTsI@lJ*pEmg zdF35df_W8o8>ItGVwUI2C?{(0H{IeFV~&_(C`~`0tNQMv{cFjACY6b$1{7NPL4*bi12Uwvm@6V#l`fr-oc7w90qcP?Hzk%if7s@Vh<6+?Zk-<*8K- z){wim`MOvd%qul}0>w8JxFe{>IK!rS;7RJ^*ZgZ4zw;L@*78-^8^}f){(_#NYB9V- z2_rUgpJp&FF({ZwJe|q=elX&(%VL>&NR@#9B4v2t1Ni7OZ0XrJ zVAQXGNi|9!xM8uhQnOtqEWALi2P_M<=tQ%E+|O%{ySq@YshwWvqUKQNhs(VgW3SJH z2KpSG81Zvb>uFBnqIpbu;RA>yh~@5CKH*1xd(2M+GBu{XcQ*amHRe7mEe#{L=q%fA z*PEsr0Vn)KZ;1vJ;T~7ZQw92fD$)a-^u=#|tuN3bwPRBf5Nw*wkUK5+!hBiW= zR#l`_dQpAa)Z<($Z34Ve{S{k1N-%UQR@_x>b);dp{ACzXyxmwB62=Q?M+NFpwv6f= zbiYY^aQYt>-f$9jelyf*-leF6Qq$gr_S&X@^4!<#q5a5C?V_hGG}(u}mX-?^iDg&- zJr%wZYUczX$TW{%h_P#Ye8_WDQ`LeN((j}a zZc=I?7u*)TA1xKpGlt8KOX9LEna)obufMxUTt-A%VEsS)=KlVjpLEI2O%s7*&!t@V z3*ErN^C*}^_91LL^IpSz4}`>>aU^nTPJBd&wuVANNHPnRc?&CJ#?<85qxF5LwP$I? zJQf5@>Kqb+Am9F(-Az3?=aLX=#>%m0I5e8!fbVOxA z6#LbxsWk;(;T}R10Uc&E|pN*g2$A z5iOO6hX{laV5jeyeDg?2Nq=tH;X%}w8!yKqlY<$a>9sUiG=_`FiW{^Q?g>h z0my-i*i(CRT%EEy^o1Z?@W)=#|60UH64VcC<_eErzO2>d~qvW;8Y0)Dk3IW;Y1DbI2D8hXa(ojbGJ9qk#t=LsAicwwiv2I*2;J6DmY-k%78-Io@N&4nh?r-K5b7DKn!r+=u^mvg6B5O~wmfai@u!<;(ANqJcHFLyMM#tQEvW2D8WAFog`#^2!W& z9dQB^ODCgDTbeIa@6f4*rTs{wtokF;G+r@TpWmf00R4Q2^Ctx$2@ zvVT>W@|-OoLnaYX#ew7*a|N_bRDvj|((YC*CkVaBcZX;?h$vQVJB8cK1T7BRcC=;s z=03xu$pgzB5$cjz7ihroEUIH=VcF>LhR{SLqD#S>YQ8_xa{*;|uEz_Z>*?x1y;ffX zYN;r~+Vdz?7%MNPAa?%m)u$3#(3`xa8|ipoc7}T2@1T!3qazx7+P3PpFn+IOO-ZdV z#|_dk-?;;qm!=ulVbz!|DnXq@HJ;rXIwwG+@;5sMpcpBRbDl>@VS6fNcH| z)0R05j9ubopiY-Z?;+sXA@@b(Ai~`nuen1aAvBaWuJhXTIT&MkAziN)1tlRfYHI%_ zA>!lzYwblfI9|ph!)%L)sX(yZJTo;8JfQw_x4Px5Wgooj6vMkm$r3jVE z)AbG-vkP=mp@QCX%xQg#5wjO+=f$v%J;j4)X`M$&Jw5(NDyuxE{xTjADN8hzQthaa%6jT1s6l&{ z=`2>a(x9~T?PU_m5A2+r%|%J-v|1Yh_7CP5Z0ykbDVy@#16}8bj~>;ZdVf9%sgP57 zPnYm!&JNXHk=O+w>fIAt!;6r(!Pfz>%zK5Y5UF)h7I&ic5#@0 zemDpc%buq*yE}*!7s^a0{Kvi*<9f!3?AY{1lf(%uKnP-T_C<@jXHU8Jm*GI18qtWh z8P9ez5y5|CgQLsHN#tQ}8~i{j(RFnuDOR08Z31C%2|bq@epXfTJFbGzp68MxaYbPR zMwL!=hU}s4%9?KmL0$7pICf&BLmkw?l`lkq5VaPK?2@fllaOiaPykq+SMbjC#I0;o z559w>-5S=4jBYQg>6<>s?&pv?kb+v@)@Wr@Qbc?4SWAVr_W|?1;^N6m7n5^KrLO4e-(T9ooHS1ecx^92LmA8UY_eEMMHJqwcIEuDCpF!KhiBAAn+xx zaa7B<|N7$g+xCI9@Y=C}v}3&MzTPm<+rDEVXzQKa`zPTPX&WhBFy)>5YxCU;X+~0( z=U?NNo||h_d&hKiH$A0_nZxj~dpLWxUVy&@O%d?Uo$k-=O-&Xk6|!3`<;+Gi<>Q^K zhI?)HfW>`*jDjg3K6Vu))*vOlTpC09(9wB$;lRK^O>{?#_(1PfvnOIH`GTZU7k{h7 zEx6}_JEsMi!+sUzCa>jJ*3jN?oygfMSC-G3HA@N07t(KxptX1Zc>9}~n6nf`pM9er zRe6yZcNN`2ei|x)xlPmGG4Foz^eX-`V}I#m9tBJF*!qDAxm(kZu2D1m#1~1nTp)2a zuo5bA?ET<`@&)$D*YDL~Y;10uEe3way4&^gcBs45H)av(@xk=dNdMYn%>rp#=U7PK z1(lVR{X6AFM7C5?A!RwqX^o0~~y17-z5p`N?JG<_3 z9RQdHSMwgvVN@RN*Co&#%(mINI+L*NIudTZtdg#Wk8Ec$18hJ6+3%ZMH3J6S!BJ6B zlHdb<^6Vvn2X5^jZMUy`q$(*W>>~JqQ$ay}o_9ECKCMY1;QRMO3Gwl5I{wko(St(l z{~zm31q&j`e)pa|1p2tqv?7qj2fUeY_Z%9PSx+zi-Zb54itaHhQta|S$4CZOC;L&? zJnBY<;*747SJIixOxYY%#P)*lZz|J2J99f)IS>vNeDL4_U*d&hw2+`*AjaL!!N%si zzyFl(M~#ih*P$JaYqeBT2gUQYu=Cg1CwHpL zwXkb5946b*h6nC$*ULdQcrZ(iFGp4U@ARH- z44z@IfZp5&S6ZFULYslJNp$)0b3oc2aaVaumi`&ef~PlJ=k5?odS<4LfJcULOpVOh ze`W_jIbs_TjLo<*ozGK+&%0}d%W4g7Sd|+^REVTSHa>E)vKrprd4nI%A;x{(&4q&& zJ67OB)I6aBR5N`4{{7g8-H{(qbUKTyYVfOK7I*Ps`qC!fb!LJ^v!l(NuUXFvP{zUP zqo?UADy@``uos}hR@Bvr1IW$al-$>;b`X6-J~)P!oKRO(t)9%&R_rrJHIH<2gWgM_ zq5TbI<@AUJG*g(%gosEy+HWj}wx3Eqdol6O-tJa@zRB396YH#gyty6mFXSr|3x>*+ zs(o=q6eAC=GvW@SHHs&%b9`H~$hO`ebEOfMV)g_C2hUb;>$sS?CvUj7WCc{ofIcpB zYQ9J!h|3$`3>1==m}0kAFeT@9h<=O44CbKsRToYxL#q;?dFg$7^a%dpsEjC!xR$3x&QmXVRME#0}8WYaGN;1zhO=Okg-o-_V5x{^7YqIfk1V!V)+IL)iD<7t&Hfj(Ot2mmP6I&T*jx*o_Uh2-UTvg(t*)D!#D z9c1;9EP959FXs4t-2f6*h}yA6Ag9!r8mkH)(?A++6o7TkLT1Fu&h>aLuJClfRwSGz zZyJF0*^8E#X(8?z-gTUeW)6dPnH+_ZD9MRXHlErY!1szV3;A0PPbe45era zHhPxhIT0E;x+ssS^20;@vZpndApoc8_qn_N3(dB_YZ8>iJSBag$(x zVo&x4U$kb7UnaY+G6*PTmC7$u6I&&L=Wa3!K;>4uR>|~CiDMp1IFXb`!`yVoOGry* z_-QIeQ*J%%7p-nk075Op!W+03%{TjZOf2p1XnmTfO14kT4qh5V-rxTOV@*ws(5h9s z;SmuMqS_&|qhZVO<{I={8bMihy-e~;;u2lCNsdgkzD0{2{6>rcXjQNvUeB7ba^B&} zLT?-FYgJD>=`CnJYz|rb<)m!ZLZV-Sf|E|~GS^^W@}2<#BD8vSl9QRCndQ~O0n8=}%(UXz$luQ;!)Ba0#n`7g^b?S+6LaInMvR=ac6*FM z;sWJE**uB=5D|hRZxVc#X57^Mz>M;hx}BX}$l(pDs_DyWq)#uSNva`jx6#QS<{Kig zA0T%Zq%0RDAcJ8xGF|H<+FsP)Ha`1Cs3+)p7}?q+i7%W=Kg846Q@K9wXihZO zh5%i_=94^aMmt0)%=0(HS34zhUh)d@_liB^b#L3yTrRGgKI{IK4yAQlP}j~h>PP91 zV9KQpHt3Oyb*4%ax)T>cd$--}J}0a2TT6u2H=~;^1l{=&eQa*dwR#(l)l_*;kNmKI z-N+R(wR~!P=mz=d6C%k5DT0AP=oFE)?rSI6Dp%-5fAh-5lG}ThZ-kE5#rQAbdRR3TJ)4; zE63-05~MOj&Z!;UeD;38ELx&dKYQSs{n!qHZ-~|GqA=I4yD)D$sTU0=4=ge|eSsDr ze2YfP{r&1O!8xsu%il^L9O~c4WMgZqHu}D(=H$tfXA!+B`04B;p?>~O z>@v6cAtUM?k|(Iu_fvhq!PW$Q$KLj4Y7`A{@%`)5b)mO!i?W7;Rrn1+1JX23C0FuI z4()e+Cl>qe?7ZWhZCYRHQlijWUGK7M*A=b1vy)Tmz$P|D*owxDkuPq#b%^6V4_uD2OzS4Gb3}42RT{cl^pw0-}Gp z3{QKAdNKI46p;_xVr*<2vT673-H^a|{`J+t_0u^yIZ2E085)O4?jzK~F@4tiG#{15 zLgu)CLGR7THpM%8^veFIb1;*}*?S0*3sM*LJ!UM_%I4EuoIX`)J) zJRvL`&_L;U&fnoZ(z8KHpJ2l*{v%qMJ%i2O<75c^y|I0|>YwrSzPrJN@bF@-u&BJ% zNx0FM&V^K9<-;`80EtA8I_P$oPkV;vqpg;4t3d%AJH8fj!~*MJ32}?{+R#q z9w-Th=t3$bRw<)6;Ee9of*bRS$(!w(_Z2kLx(sixA;%F1-#(u1mgon;0EF2+9lUvS zX}2Dym7!wm?R8b!+vT7GB(U9!M_in)=G4EOq@^7R0`(_`YgYLTyMFxh0OM?&AZ}esxVXo$%mbQ7!A!TwOQ-vGt4+i3jfL@U8_{3qY5@A;S}1le??y> zy(nj4{iAL|7Du;me~~^Z5fkRbGyD}wu^Tb7(W~xbRA}hUI}l!5)uf<+q9K+M5WvF0 z&HVykUGdq`5KkPGIrVeFzrx~bF`NT4g%WzHSY;WldJi=u<2##_yw(Z}t1Y{V^%|S1+DUKM2x0129dVh?+jO z27kXi%J=DS&K0&wGp{aAY-I{>EB)WZEFloM zC}IwC$0sD5!+6?_MD#wR8h5c_OG#wnk4^Dp-yF{up^5zwIM&L2oqYB`5GyYSI?5+H zG5!Olzh6`8j&=F^_3IX#v_nIAjaBZ&N*Gp@ZZRy!~AuU@^nKVB5#pnBQ$2)qAt-P%8*;13_$Tmy{rJQ^%per(ewDEp?3 zw1Oe0p~`Uer#IyddxX&~!9S6y zxVZR6YHHc;1p^yzo;}NEC{_BMeq;SI5q^u^SoG5S+3B=yL6a%v)vH%1DlYE`tG9tm zeF2_OK5KwIxnGvCxQ<2SLcLe#on{743*zQZO`{F3xpUh0@~#^$57~=u zw$fP1#slfJpe|+=!+?;^z{c{1B}z)BFeEnviRRxP0H==ljC1fmJnc3*G%Uvy$|y4` zFhJl(onEA90G=SdG3j`isL}5QEE+XX2{4CUAD-Syw#)Mb(bs53tEtJunv=rsNw}j zx;q+;jpgPA&^0qKO$YCuFdcVy0ARmm=g!MwKc{~D=14!W<3-T&Y;ph)ts$}U_4RFd zEgeZ#Aj!pF*R$K=CR)q7WEQj`L5D9F6H9B85)fEVCK?mz=jGnFXt7>s5pcU=g(LO7 zdrPAVkfQG$kmhubUTGOv=hb=V3uXXsgk&^HAI}1-?YgK@vDz1vq8Fwf^-OEYe!@d> z#wR6J${MvR5m9dlR@mP;Ho>=_IHOpn2|}S)Zc6QhwEFWDUloVrc^wChk4hb$3lY7#|;jvvPm3<0W||^EX)_ zYx+`So8ng0`GH$xY(+xNiG_EX6>2tbHg=(|AR{vo2PL5HIGoq>V9?)x$}VWmn|OC; zOm+Wi(Ys(*zw=G^{OFXBt41F0{7aiv=nKqcMP{doIXO%O@8)@1M2hpbmD8WWaSMF@ z20Badr>X7ZhC><@+v>MzUMgqI7J!JKJ==0UV^6VH3efmyPkST{-c-FjN2&kp@{yag z*AVW{GHQxRHyExH>$67M_vXO<3F6O1+s1`VQU%$fl+rq9|7{P$VE}|E9IEs zxVBhXSy43vE+n7-)GM*5tayLnq4f)A7gF60sHz_3vNv3U*-WUF5z%+vGL!l_f_2JP z;DizbNfpr6)m;KXDX!>k7=$CR;ds-ejwIa`RZGBB?AMSX55(**Q@XpmF$qqjBdiNU zi`#~qvsdI@vmxIaAVIgoOBUvtn_}+W+X0A&xYmMozWJF!5|3Oc5KPJ>@7{n_9!hb| z(35Cx(I_?LGe80}hxvQg{&g4DVd8mB@rD$i&EFq>n5M5*`}XyY&u`Xt^KzayRLmx% zqdXlEVPQ*c7dO7G+4YjLT68pnAQ1*vfP(hp{ZE1yiJ=%VE~rO$Jv9FV{R>t$`>crI zd9+BJO*%?NQ!^-jb1W5M&f~;Iu9aGA=vPK99^;@Je~eT>U?9u$($Xvujrw$Mq%tYH z3*y74PM`e@l)pX8B_%W4jJjpNgR=4*pvwF$M-9*_u4OU!Q8{ZTdaVBc5s&_{`cVI2 z%OfnAS(%xGB5MITuKjj~cB@#JlKRR_#(rT7u{so)le=wRI2QWnI_+SpU5EH4F$f84 z-b#-ilOgUWfy6JLV62?Aj@#7roSweEdRzZDcJ~s&6QT*VY3n%RyF9Jt5fkP=tU!dHxg-I_T?u?${$IvEg&_~c$l3`ZZ07lzDoTO|N}_LSwrFTL zTeZsVQP(CF4{7ND5Ui}X=Zc7lT_8hHR8;(vOmcR>*~q5OkOv~cL{QtzOcD%cE|=|B z<#kk5RZZ?Ky)Y<2q>G9%UdLu2hEOSpbS^V_w<+v9^W5)16H)K`o(dtG64v)07I$g? zSaj#ij)6kWxQw;Nq|lXvG@?5y#4)elm9COmrWteX+Il335+*9C8CP>DK<~tGcIVkxVVG_k{%J@QtWf*{&QAKgh;eFhM;~iB%j7YIf6JzdFKi$ zU&_Nya+s^s^uF#mCQa^T|Ew8gs1z}o8Bw3+oyu-1yjtPg&24+*bK7*H!u0~viS`X$ zJzCp+^TS5s1p~||9iuH36+2kD2X4%by8ZYCQ5OE`*J)qz&c#i1lCPE4TI08n4tVlp zlSETPLqoDY9|wmJYWg+NG*b_VBBrj!AG004XE;X^qPaK2!g(I-V<9Y0zDz+qneojX;&4F*d(ZWV_4ziZbLu)^GK{a&f^ zmL2P;wIls954*K;clcmjeQVz<^>CnOo*OxlCFF)b zpwqIUNCEp6`JwHZIN_U-dG9S8#28#?apR2!>6Pza!*Q`MT*$)v_ZC{9YCgEW%!+IOK3nHZ1oaC9wOF56;M{oe(iHU|h(<(+uD)S2Wa-PtW9$ow@2y zV}swf$F}|X<}dHU1$`w&vS7ik7<3CTOGMo0GHQ)Sj~<<$BU4XJc3%<&8XVW{bXjnc zB?yP7XC#J107X@_ku?w(Q2$qLNYkb(d1LI5lRRY~sTa;%8gsZ?w24oCn0JBmx7S(;_lK{0-}v?~pG0*srDt&VuPjN$ zfx-CQAWFIm*0_q0`tSHFeury}J7$_*=5vA_0GuM&cxo(Vb*Zfh3A=cgeIg18)6m9-R03`}$lQ zbdpHmG+(6&m8y*I82eTwdM0Wl_v_|mZ}r`5Ed%uI3w9}bK+*CGM2_FeY;RRRTD$1| zhrQ%51=v#{`E?1E^IezO>{~5qIn|_X4n}p-L+@y3dC=_MBo9Tm$o}L z*qWvc zpd_TTeN*48Gv_XMHm2E@e|cr7?(LHUqQxeh-LCNKBV@@-_tJPS0T?anC3TQoc$}Qa z{sSOL+||!$VG4r_%f+y;+V975Qc_YN_aDr5K|xB%6k97rVqPJ(vRnRM54S>uQq8Hu z`y%lBFpQ$xP{J}gIMSVU$3Pjl({Gr_A}k>Az&}!FCEjF{GQ)stP_Iv~_Yb2os(GxW zxdg-Yn{(p*L*I|?7$|o>H)zoP75wcT7$=p_5LruIKY95qS!wH8q$WWwX(!Q<6qBwW zzB-;7&S28e(D(?pn1NznU*EipRW@6;oSdO}i-6CYevp%ALrz{*RTUw;>zII84#m`t zG^-=}ZbYbt&_6ReVq*9us+Ga~KjNmA11t33&q!v)Lg==`Xsu^mGyB?iET2Qv=Pmvb z!>8t!E~{>PFmpBEXyWR9K9vJGAQe0V+B32OdwNTHd>Prg!dUM0RPi zc{jxu@jvQbB>4VATlo01OrcC;lLwp%@&-?A;ushhR{rylamLJ-aGW|3qw^N z5Q+p%InA}pVs;0g{m|#R-^wfhIig@{Um#>AdAW#MyZ)LJ!6{qpAifaAcp%b`s^{I5 z`0FloJb@K?h@_1JG^TO3wY3os+&wq#%_dk58NGyx;mjHVOL7}!l6HLuF`x+#z!7%- zydW|FoY*P)1t5ifLBBg%R?G*0Lraw7r?nkrCvL!p6(`D8&N?B*vZJ(wCsU72+b2Hy zZdEiu#*)@IytC`0n4$^~=9}~t%pJU1tUxo6rSsqyF6QU24N9)0-ox;z3vQZo2xrcmAtSVd-lKi?yvN_& z>>j|rFR-(=eO*L4f(R)p?r&X9+cYIq*Qu|oVz}@(v{^e&MRz=pF4zp1W&F@-5*bf6 zXMg_!a?Q}0ez+F$w~*8sH;kz0)_r#Ik)9P570lV*<+g_n=6;%n^*1aLRptaBE#6u1*%Kv0c3$4o|Dn3~hb!x4x3ab_r}Ur*XTTEz+&q+U zfm#17IiFyXUc*z%b;rf6z|8F|BwZ_ng#Nwx6nKtiv`~4*CpV5ioc}R$iqz`GYrUcJ zvcotFSOhSS>Yc|q8BRgdjEK#?>b2n-p37#t*2iwy%GYD6m0{@JR z@|4$b@SPQyeS!x0oIgHWekJD8jSktqa^hduX*v2tm=i%k4tx>S<)Bhb9Wy=T<8$sm zaME1}%6^4DO$8LuCSMGNu(q{L3uK!&Z;2?!WAY16lPcCT!;l&z-l3#y5+5sP(){{lNI-_T09&vZLPsmnV!fWVX%rV!90g$zna`Kzjn0jn6#Idp3T|dQdK5~t zZ)xTLq&GV2_P8$ol|4*s)VObPoZM0iW37DihUoQfI|kiiojiK#vxF5_@dhp_v!rg< zd=OceWT|#z1&_&FAWA|J6ujVy%1R;8(+?;A{^5CqA`%!F$af+kS`4O8)0l7wJY8A> z^xGe8x+p71u}v&$OAN4vn3@rH{rdH%YrE=t*u<6ri5`p#v9oQrHge}`VMic}2nP9; z%aOx}Z`{8hWszr^dzA)trk`$q50?0$qlvd~d#zqPf4&IVH4QUVsehdTjH^Q4c73lP z{loJO$7@TuQJtM=~kF>7PpFh(O{<>32 zT>K)!oQS^T$B%<&f9C7AZwfwkOX+njSQB~NJ{Dx8w(B%q7X#Nucq4tX+xGvxBrYt; z{wHJOrPO$V0&iOkWbGD*%d=r4w%85tS8+FWrp^FxK~Jx!V1!7)5*ledD>W<}<6)7C z%W@+bVRO46_`scN&T8=6>nS=wfxtM`SF$tz-OhT~q$rk4QBn4p2JM6w|J%=D>2>5F zylN63M|oVKb&rqTpml_OnZHWfj;7$J_i(WkN8Cv}5GX=0-Nlr}Lv1aQKzQ^wj? zU;J2xC;!$zJ_Mdx2xonpvw-!a-tSM;i2o7_VD~%p^{e&-qQ{Qx!*Q?C>#N@22wwp{ z^OY}>o{u2xFxGB!d2IcEBbmlu1v7kUX~vCt^oO0fB!*AFv$b{qWv}HNxB-k2r+JwB zoB?k>#Fukw9# zG;gfGrECyVotEgR%1V`kvZdDT+52jf*TK;pf6FEPvA&56nZ9Rrf+QYbs_pFT^iJZ& zG%)NBr@6U#R^T$d|G@F`iBw-#iL$XSL!;WNi-u%C5zs~d@5l7SHBhE(JmS~gdC}w*s zMi8_TIK|I>eNzc{pzIRdkE!Wwg5MUS`~YgM`7oN2B_GX6oqZNRQl5TT_$1@9>c$mVju#@9lN?-qHpO-bzAs*RYGn*`zPgctNCm z`zi|1nx%v;u3x(P$nWvfFdKRVWlzCqt|e!$t~FY+g&)Z{RJeaIzQouvRGHk$UvJa1c`pG zj~$_*Gfopr#l+2Bz&0VRe*rwjbni7!$#2r)^lZC!f(YcLDYPc-O8eNEQs~|hzIAd> z!Wz0>zHWclo5JD4?hm{Q)gJ7E! zdFf}WII8Fs*YWG^9WDI4wLLmB-WxI>$2*T5rf2XIPX{|z@xvz#cx;QeVxz1rKg70^ zml(i&J#v206rE|LghauA0de8)L@TCJo^W3V!kh>>$nxY6eK}~xt@6F@I)(e#C= z!ITngRMNV{B^H`0$Ch_=cE%MHn2uQ4+LH0LQ0iI5X@o|~RUnC+L9C4MG4&a!qUrVx zY+LoafyI~yAQMVRPVUjMaCA)F8opY+P)&CMT*9Qqqpb)d{6~`W7=6KLcz4{*?D(7+ zxddZwAe&J@Yj&$}W8>VM7Kl(7SP8p9XS-*+vZ|`;-uM5Wx>>$MZuk}OdT6g77<464 z%`T-%`@^Fq-#PtKG4`t=5!2(8cDE+S2jJXcsVJ7eU(pcxB)?N4bYKTV@6Rmi2_&tA z0N6(mTQKKXFs}SP_)(=zr4O0=myai{O2MCphQiQ530JiTblw@ji@~=FsxDs{lGXhrM$V3?8fTg$NaBuHdxp?W) zbBOSyN5&W?n=FT1&};ojjwAkAEaR0NwGm8UJpR4Gf(!*mv8y)!Dj^zKg8qtX?}s~K zSMUF2n}58pB32S|K2W=**r?Pp@A=&$hmj9I`~Izu{I`hV%kJ)2?p3=W|1r!%JsWJA~{PYw3gxl)C zfl6AUEE_>ku0ldW^9y&afw|QqvZKC=i(z9-BE*Sefc(Uj>>=e`XSYT|NG;|cf>yp z??6%WJWa10uc4@!G|VydT1-YpMwZGlW5zjTZZnvf9SKo(UlJe8BKGBXk4V=^)_5E!HsOixrMaRNj;&EnU; z_-mO>EF@>H@ z69%k=#KpHlgg2(P1&p@kfI;2c6@B{$WMs}^M1X3RlJ+DPre}(OM)ae~kyJ?7Hw3A+ z{=FhStVpYQ@5*tX;}}M(Dne*gHmq-8fCeMa%c8aR2r#<#`V$45auucWIM5=V#&#^t z0>C^w>nuakn~DlS!tWv22-y&Wf7k}T;WpYoWtH<}2h-#m0KJyL;cqubq#w>puakOA z8sNW2N^m$S@MGT1@}SMqT;W*CS3~hY>}1qGu{=y9Rg%OB4q{NRE%lT|PPSX_JhJx}8I4 zSQqJ0EM@0ki}Lr^B}R4Zocg$XF485p07}kF0Njw(Yzh;L%3YHbjdwNoeLi6!~&5p<-L z=Su{u6|JJ6yHYbWrC>9?RPJ>%-ae7YCx7|+A!KORQxv+%=qtXIOO#2U7%;|YV`C$P zX%+9K8~nPr2Twpkf4#mU3vAMyO+lFCNL#8(7Nz4{HZI8>W@Zi7pFm}ujIVSvmOBRd zJYN#~4Ap2aphQwYy&{}g*0Y!%Ms#x4PIH4s9vRfpyxnhDH(I97ySLyAy0>0QT3n=k z_G@L+mLRUZSunlU8)Bho9kyBAe82Oz?~ngv(M@tY622Q*u7xNA=Tb3IQFcyuBJ>Lq zw(h`Y#7gLCpz@lwPnfZbQ+vAutl2?a%TO*efv0Zm3Ia|gn1yDL-!gK(BeS&x)!O;d zEIH5Ejc+CuF&MkpMICT`!BN(Kcqt0}1Ce{Qc5vuj@d`;UnV4FhFx_ViLx6-x{}y1R>a{~q9J`-n znrDDyM7Hgl0%?~1`pi!^NV5L;!m6r~l-IYm5AEHR^!Hqmr6d==$Eq=@G~L9Dy(w|p z%f)CS0fwpd+@;W)BDIt}uXet^#QGY@GCx+Pnm{X^Ky=?@-us)HoiitWy5n(L!gxk4 zH-t`uJ-_Pa{&B68-xjH&f(4YYPOLoNh!mVyFRN|ZI z6BE5Tc&&~19eDvRLJ6$ZW{C^-i(XO z*{#qr`8|?FNs;b#9CuXagjJ`TnuYKx2%=ZHa`(T?3&5K~ty6_0d{%f<2L*t)4FH7r z1;Rb?z(`1ZzbH)h!>FS#iRPoUAZ7P9sF;IMtB`}4o2MBxE=^w7tN^s$t$X9#7vmgW zz>%<+bnDQ6SbiIv-)oU86G`4_p|YBq+f222y{n;9w-g~zth+bu=wnH<$dd57UjSn+ z9;koq3*1qd%w6Y z3*a(ka`gB5r-xq$dE|>g55MkLU-H*lnhxUJL={fco7glyHqrzFRGS=RBPGN|=$)+9 zo~0@1@6Sh^;^*7i^C(gCs?)76a2-gAk5Aq8FY$sB)g?poqVlu|@!{8}B+u0b4cxI; zi6Apjp-SF$ao6N^;`kSd;rDtsTi&uB_XXM{xZZCE=Hh!Bh0g!PViMhkB6s0gV zp^f7!0e?f>>QFR4p-7X16f?O;ag*a&Nl9pUcsO4H)3j+cbnQqSfpt!D(co_2yq3OA zBW+`{3vDW-c|`O$5iGIu@g*M#6v1Kd7erk{%JA?S{DUG=D2TH&r)Y6|B0=1XNl66T@6rQipf+n}=~ac-?VYP8Yr4m96Xqkq$f&SW1P8kH+!9RqDvt`}wK55U39?>$2 zhGp$ap3#+$xQ{pgX%W&1cq13gcGgU^hFV$T{S$|ov|6uw=s%MIJO+pIDu%gZb9xvd zbRr=7??O5rywcQ%13iS2d7dx|BH(u(C-Lo7J*5ZDZ}&%Eg0}h^hky1>{9gLHKr_|X z7sd({T}XMI7L{$d={R8E}yntgCv=+A!GX+kWXPdz0%zJEnWNJ|OWTdTCg z)zv#mbLA^ozNs3a2uchIU+I!~pJ0;-17|u4erEySw?+!K6!W&rqtYv=UlC#9mHBPo zmyOC5i5^yB^lK|u$$?+znQTJ|Q>FLy4yB5QJ*Zl(NxAyv&jY1WbP_ks8PBTtiIY$# zs%>H-4vnx5mu(pvbO5moK+U)HV2!diBv6^A2bg zB2mYn2+QafApn{X1ScUJT-90XGTF%==g^j$>(Q_^De7WXLxW^TtMGV-{r8n)coss0 zi8&5{DZ~+=43Y7`f6=2*`XF41t=1~K%$|ubK!<`a{dTJZ&<{^YO6tRW<(phQ?hkF4Qr%2|?JD&6RDh~9j(ddQzOZf-eFVG1|udnIs=r~|N zI(RyHxoO6EL6Tgr|0?56HZeFjS-6wFil6J6ww#n+L9(v7?qN48L$?dnf6Q@pKbz(v z4`)a&@`hyQ0e%ZpmF}8kcZXgjGQJ62T+AJnco8NQMikw*Kg@AywRteu-|rg#$7!A> zUM3)@JXJY->L1@AW@Ai361$%-)14XhTN(s1T7X$RBhsK$zUwnmOORK z=Hg2vkbB*~WeM|Tc!nQCP?`-zlsoXY1NU}v_Zwf3DKAGJ9sBFN{Iw)goC)ec^R)?u zCF#TdH3dpiQrkhx9ufB-n~yQ(XxeVF3R*b#lNSuz><9alq9zJaA0_evL~A;2-r~iJ z?QRW%Jli+$wuu_?!m*mxs0R#mTBtJ|^CoAeVgtB2t2+ICtXMyMz&i>Xh#hkLqv z-$hJxUrz)w78!1{X7-FOT2;Ds38Xbc(K=L)Fbo(Zif@2p=Fd5WLiO(ksmMsk=mY!j zV1~_I>l2HjuKtZcoQjM{S$f&8IY32IxdDA`Tx1NSUPB1sjjcPF_?iGeL$UJPdhWDcOVE!J~xo^6zyq z??hptK6gUq&L=i+KPuD=W4ze?`X1%WRE{QDRIcOYG&3j>|h zA;os0*hHo_V%|@bDbq;R`ze#&V9YH@W=+3=GTT%0+e0!{BN6{aES$_YhuEo90Ipxy z()sM{Y+pM)X0z_Y|6#b-1x(v>1w|2k)}n`Kz%9t|QKm(dBOwuQ^~n zOT0O|<-UCyn>U|u-v=EF)Q3+-M>q2CfA0u<^>JLI`$bkxrwq>E;N-Mc%t$fK%WRxc zf_wl;<1rJj_Bhf63HnfVK^L-B^}TC(Co-JzMOv5=hBL}>p3&#ICl>(A!SK{BGFSb{M`vwc;GT-#6TbhShbr5mkKN)Mc+kvV#h#1}&qC4N!vcx}YV zh=2tauWRV>qLXEQKWmdLi}sCQq^WUtP~^{4{Ne?4?~6JNDDd;I4`{p8p?m>A%8^*C^@Z%ALRRY z|3qenWK;#rI}q@Ui|EyGL4dxS7|2hl>{n0W&{j-OjI5~&?jD`Rxuftyu;NElskjDQ zFEo5W<<@z)-#Vy}Xo>*m-!G>WO)%X5<2w9w7O#5Fga60ZcgJ(xfA8lVGBO&75>k@U zFtb-8qmsRqy(N2VP-K)9G7HJfmRas1BdfgaQTEQ>e&?xu-=FXApC0cdUa#jo=Q`K9 zuH0W8D@>x=EpmJU&E=bGrbPoU~ zaq)7mtKsV05Tu!U^G&t2G9T*da#!4--h=M?JuExTqkk>y|BMnos`ga+U;OZMVR_(C zykG}1QB)KS!+qne33=bOgFhPPWkE>+#S6qOncsVuk{fTQ65;G7vH&3$#DH7{G1m2r zttj)%=G#+%&`mA3!$GkMITd^0*GtTsEjR!3`~UNF{R(J0hKz6i9NKtm@9}XnY7PVG z3b~Ao41^1V;8XC67cV@5M&LLb)%CJ*-M)Cl8)%f^GlLw(r&0+v1K`9rO;`f8_Jj%v zSGO(X9#>FMaMY8EhK2>!-km7lJ3sg9|7RMz5gWn1E&Ug@t4J>X#S3W}S=s#6s<&@J z=vP6>D+utHB{*ve`vN%|PNInMvPoJ|ky=}(HY-y02BWruKI(`wxbv-7JCsD(1EQJ21^oN2lJ(BX;Q+t1yp;>z`ywR%2e?gR=wTbzmzLVF72XrFCPcIZu>gb?0uIj&=d?f-lunr-?d8TZz>$5CeIs=_gq6bp9 z0V}9s1eW<-9NNAWnJ#;CbtXO$>W)LdCbTtDGv?1Tg@024(J0#(F?OV3{f8Z0} zm$se?PX43!sD|3<4@NP-aLg@`*Cn8D@+eIOmGDIXCu#;>qxs%MR&Tf2LjKn~pm9VL(-Pq`P^+|&QSv*b@d+KM@p6Xi{f+!razUj258RxZ3!FE< zT!29RoO~SDe?!hSsMluBOi0-OT$e!61}y#>2${j*@EFcdj}c&og+R@0stSuO?EA{M z3nv$)G3yk`BCdEE8XAL0vYVkfGt`%(c}S3C>90-t{ZpkSWOzLn8^nJ-o-yh#%=aqkysnDZ zyM7ooen6=mlB|9CY0$4|jp_>-s&SdRlu32;wUlW9=k?k3;uhxpf_*=Zq&@` z@?@~EmA1Ffm(*l=njlW|?~~=x(vm|5P&@G60ls#eo15YXU-!=^{2vd82k`B45X1ti z4!+WTq9WHDzCAb;)nWuiVlcUfgVo=j#aNduh6_Rsbq+M}$X*Pi%H4g6 zC9ZlU7eQeKX;|2PR#ttmrjh7-^GAQWC0}X9<|ooL0?4uaP#|qwLJuT5a*z}zh%k5&0hkny zWF?SL{MhvS7cf;j#YL-8;2tA&DUuf=q`!Xf&WzQcMwT@|SrF=6`1b7)7;B9U4;$v{ z?q2%^PyU=)Z%=?8N5X!cg-*qy`uh6V%hP`1Q*D_Jme{($5*-g`lfFAJUPAX9TaNB~ zk(CvJ{FroHr?{bW^T<^aRHX(fpqiE>SpbCeL`R&y(C6PO>3mam>qVA5bi@F_J^H{_ z4YgK_Rx*Mx-;_;IdVS*e0Xih62e!V6R;1Iyp8}`MMo=R9uiZo6|94*taPO)yEQ6U2 zwyG6*G{SC96=6r=6eO;!e)n#Szp34t@raif36ARBE?tjRL$Go*#`;BQJ49{()o+A` zzF)x`S_#;jG9Ap%Ff$*z$`0cCIW`00C^^B!!`l>Dn%>R-(#-PfO0*~u!(CkQOC|{t zqo0WgZqxh4(@QHTm8vLNyr4f8Z_BPltR~7vPv8=kNKYWMZ(nMQ>&%I~yRmNzd#7UD zE-@LJaST;pYcY=%m$qW4nMR(Dly)WC6WK!1f%F5&c%L|S?5!JAxhV`B+j;+b?S2Ie zdMfvIhcw}HCC{X2nfU+Wg~AYd^`RvbEzuzQ>&(UyqLUoN?*~D@oT(rA3V{yZiNR_9 z8wG zFe|(bS62H=egvkl3NNq!9h~OrE~(00i=B8RKX0U8n~%H(wWY77HkAKdX*hKI&fD~R znI!e4XV?za-lcUPJjA(opQ>+{aYNJzWP*~Xv0882x`OHg!2UdHi#sPTN_Tk;B+%qu zYy!iJXR7d8l1vLgNXSX{IW&OrWK{h+D}Mx+y$sp*6Dpit%I_(mI0f$W`!_@WN0>AS zl((ggPeyRpeqZ}uWCSLkO-U|7Emu7t8Jqe?I>#(ToC z7V=pN990!7UC=8>9QP(J)0TgfDm*~&uEkgsd9XeQyZUnR>hpqfdLN(iaR99&lJ8b> zgOE8mr|&Q$pss*o>4u3{^na~C&xj@HZO*i828*RQW)_buJ^ipJBTw(^Af4aW@ZYP0aV|%QXIbBxfB^$mW4NCi3$&uZm)*C8i55E2b;=*_Xk}f=&S^ zoW-X-$MmAT(%w#i<4zc;^wj}E+c2>O@+LtCPiwUc(sS7Ki_ULC&31nCn518O8(+9M zJ(V}esA(WU1LPgwa9Ja16BVLC^t!8*l=xR%`F#$ZD!hardcqYWxBHaRi(oE`_NMhc z)lf|Sd2{{v^rQ58{aNeJx%V0&Fi{g?XKzTpIt~4iVAuZ6PA9F@yhezhzw;Kp#1-yne@B9DP=6z{eL_zf&fc5u3%p)u)$&VyCQIAQna0D>RcjeBJO zd5~an+umH}fB*^|gz{ZY+rHdQ9`Geu*qxRdzW4t1glU$a1EG@&!z3TAgrP7f>`mfHa3*xgC$!k?5mL zLR!bJfw=X;Rae;kZgT$=42(V`9BGV;fa?@71R+(pC=<$jy{mS|g!}j7uH3JL^aUiH zgjAlTs=Z1qR+0M8eTjohBo6tw*o)jNzqTkDUQYCv^Q?DN?zJ2?1~XL;=6`~Plq(}` z)}hXdkW3?r2rI{*TmTb|Zx&$77wMBq(ZaP68yad*z6}nuvLJmf6n5Lg`F>4Xw)&>CD8C$(l`v%cxk`3U zLeW?Zn1^zZ$xPg-pgN-?r&|slAOJ{3jjSQ&;$Pnje=R~{%>qgtOuzm`l*tEIf*OB(atlicp~Jz#rv}^-jkc^8mvzg?c)$@Uix1kh{tLO<5EW$=p@qC24nKXY z33t0r;swHHzt^CXmT#_2c@b2d0)4t1p-2t94z8Z2Jv>O?5%Pyu<82VH8#cv@4X=X+ zM>r7BF1@<(PV2LK!Pg-S{{+gTkgjtaJB#Jwh73U!{S+} z)|L9WEKghBp4#f}r-flMkZ#0GlPlgawYJtgtCh4FOr5NFJpx ziL4*$Q<7IF5^nq*od0JA;O#`2;Giv~|Mf1obK3Om?DEKg282n2!LheJ-;=}&0NN7UU(53B3CwxY<;Epl(cK0*{%w-l9$dEVHNO^{C1NyFNG7 zlWnjEvqpaxzY~N$b6d%FnjYR7$6XI|{C^!Rhj{OdZ|`D-O3qVo)1PxwK9hbVFz#f;H1(`!k} z_Li0!rV-@X85(THK}fUj1RU_lxvt8WjF%Iy9`sK^OEhA_$j<0C+_+I4ghwnv;UF|6 z)}^-jvw9;jE?3PKWWhC{p<{5nZ7C0;&^oZGU_q`mU@z2>`%;%}{o_*w4$}@^qjbJ| zUBooU#;!fiJJg|(sZ%BcyO#|A_wN0@hW`E(1U3WH3chzf{yw`+nr0wEL_+xUDO&=C z$;w^xM2DaGLE9Nv&B&!EP;~b#JiUKA!-SY0tk7IjxO?BpnluW;_yW1%tAu*-Vr%72J>UPN} zD~_?kTJxAd;8bYq$d$UJP}yt8nU!iUgg)v#m;c-{rodJ)BYgj%VCVONMpaoMtfy3M zkC-*&a1WMLr>JeZZGYIDYwhgFF`F^#aI}p(uFY>O?CN)qGNd-?%U~2s!%!xZ_H(6I z*Z8blYw{B2zILh)kA#bE)(WK!w%+?{Q2mP5cIigq!>RRG7Q&^H!cRo_u~px68WmcS zm*jhGYesjxp8wZo{q?o}Yp`oi4;kqHKA$oVHW5wJ*kZH%sm>Ucj6u911DAGY$>*1| zG;+xddO=>#29}TpXx?~90dfrmfXR5?id)bV2-LY7NQUxuJ=Y9nlju6crUq~V&w-Rc zm(UX!bs11sPXgTpVcjJ6sy6|1lb@&toxXe%j2RD2W1LxZtH$kRZ|Jpg?flHOYO{4H za&`op$a#9O?d|Oe5JpH<_0 zcFwPNL)YD4NF|&n7mOvI|Bv)M7P{hk4g?Xo|4yT`_n-INDkUtAN{X+>8)O z)Qs?}YPXqz=%bI#S$KIp&+ON_FdpiEg>F-dSoqOR|Mw}|C6~1HiwnlNudR7fbdtsK z9h>LfWGcBb$y0|Ud5qmf!ji+H)d zx}ngzIV0@8Yp)C>`RvAnEzajD^u{eGsFz!O-&I6%H}4UNDf0erzbw5m(i)4A{Y7isL^TN@=|F1?>?;UG)9p<^}QF>Bd9nZHMot-Y-9SJxhJ5!78iHa?!ehYg+j0nxBd{cBu`FvV2{p zGPEwoh@6;`>S0p7miZ)3=+m5-bI#NOmAa(lq*~cNvT*0a+s@Jn9`{`47AwkgG^Rx= zO3xe!_pmJQOLj0<&o)e0D9=n0>|IkJBqJ%*@E8je8TytL$JH0)pLv`!E^0WxIxz6h zN-d;opigyylur0*YAb{{VSr&mOUPp8n$bTj2OAb4% z}aI%6otS8spxA920=636c z4QA*{qa=NLMnUo!2m9Kajpn&`k3Gd_G%o4vo}O89Vy!+0WTDZiw=zH944ni07;mtX zsDVf>z2H;4*zQwWMcKqll}vxG%O9gN0tvUkNOkA$|950h+3wo6PF)<|n=M*ZP3yCk3(FMEy2o zoK|Vj)CZoiXM79a`F$h?BTfyEjc-z`APJ0Wb)?qWaAYFoL|H)N2SKRY&PkxW=*D{+ zC%acB&J`ofsjB6fAWyeFaF~9uU`|ENt6c8p4E;wBLo|);|Fbtlf7nvgsQmHjN{BR-$gl`0Wb$%0 zU@F&MDy3?VHRu85}PnA4bTOW}jt{gqCmN*9q2G zX?}(tk?9jDALBSANC*gm@hQe-)1ugiI$vU?GoD24KSXYF;EvG1Qr#(4gE!%LbL#~s zayCavn?0UZ*os}drfA!ZZ7-*b7B;k?u9{*u>t@zpa|<@t1+hRoX7#_~UM;rZ@Ng!V zj7boG0??Lu&Dzp_qAd)-4yu`ehW~MO1|sHaeL(*2u_~1lP0?-(F7X)Ss)POZ(H_^A zj4m9~D>e3KIQk^T=IufNde$8r&1A$BK&N)c=?SNBQHaiQbii+N}v^ zDB5+~*0Hw$n{!_I*+r5@niqSPjjCV8Kp?!^(E6=#nvRdJk8EoZQ{tO%1>bmO4b;9J zk-A}C$nVYn^OKi8+(xvw^#9O}qN74Qd#%@Yr?3k6`1ny?B}p$`b-bPFPR@4> z?6X>KkVxbGHqsD%(!~u5AXn4@q|+*OYEF1FK1mvWwq#2^_1X#Ff-0F~a7EOl+l$m) zF*p9uxjAusYFtDam$RV%?VFZot37iUqN|@v+w4n=>)LPC7m}^&5>%%8QMX*Ljf|Ky zWV)dwa+mwq{T38()>WriuX}&nJU-BUX?~{k?Nm>ceHcRw{*cRgLQp&Vl@|Y=t$%&W zf!4u~tbbHEyxA}`W>}k>=p2CLNgW2yDGjUg92K=J3Pr_oC!5lPB!qQ& zc(7r1mpfmkw9+w4(dS5 zaD)Bc*k^X=@1W|99qTpcHYO=Cw|CqWxbB#8iP&KG-7ez0JtqWufHw?lzFNsx7t(5A zfz+f#cEWT7PoFQ4R&7Im~ z(0N&BV98(gw2c3wj1zp^9qG$Ph1j8jwZh?cs*Jfli+}7NKaRQ)&d_azy{>=#_Y?jf zpDItoHSKV7$9DC{EnPtXz`Zn}SgDigo@PbO9Y(3+IPqn(+e?ynn_^`==)qiXDVf~KTFNtw6@tsRl1Yas ztom+Rq}Z*$kXqyS*Iko8R&}hQA|zy+uyhX|UedPP`~Z8)e5>%-HdD7wc6D6YpE1Z^ z5%{i>hO;MOj&x5Xj0 z^Ie5c0`Ty0Yx}BHj5=*#N&@!qUYfbNoRpR8GHQED>qYkJGK7xu*+Tk~TM3*#bq~2Y zTO(k7vHs-5|9;kgfBGNmi;kkmX5cpA>j^AWbf%6PhA_!b>iAO3>FTY_4%mMCB8eJ3 zQ0@%!`i9^Si;T86X7;+uQK^BXdMaf34jCVZhx&YmuWZ&%2pP$aK$dUub`n}6Lcn-A za(r^Fw_YuyD|{;Zp*e0~tPoRSMW6a(#gL?{dJN72s zT!}A(#F8VY>u@BctHIl^bJ)zGVb^7?R&AZ~Dao{{Jol74Po?>$w)zEP<| zsTe?H7g!=*vPs_dtAUifo})3}6X>xCSCWUOND8xhDlV@DdNx@|R140m^6jV9Y2l8y z0LJ_uE31Y+o@{!em@AiHF6Y0X}Z?%#LoM7wDQOlcq zU69CdeQru$@wxbexk!ht>F(vh36YbLGh^E^g`a0k!ued5UI=z95uQ@WyX&^K9x*qN zrQd=z*PdW1<}1&?>+4gO(CTZrm8>hddvtBa`e-DxVz}o?#jPl_@H5mp;;~lCp?7@` zhDDp@a}3x)BJzOhK+?L;dAR54ZbQpI$5XW56SLO8 z0tjJ)#5(firJ#7XctVHvKMS|N8I`ryW}Ena|95N3rlv2@F(GH7TEVrVlWQce_&})8 z0YD98X#DvYKz57|qsh+PhwkdyKF@7-piCtas!ovf17+J!WxX5`D-lZs@Q@MbBl8Jq zI%WRc=544vJ_Kc=#{fjsLVJW3|IxDRS=X14y^)fUbyK`|B#HNMBxddCy3;@klU;07 zc$D!;*6?&@Ye%|M`TAz+>?M$N+HDu5Xk9A4v6#!(xOM#1qgO_BS3Kt*vUQYmRlA1; zGPBPtyQv}=C7RUoaqri)sBL170>dn}N7?;nORA<`2Qaky)CQRwt50nQ`V`jPFYy^N zt^9jSd$D8S$OTb>`Vn$i33K~T?HB4P%0e8xhsB;sMv+q zqA>vDdztRB`h-V#n5)W%@{skR$#=PrpFV~iDIrg>9CeO6$v#7+g=fp?los>I_7&9` zZGDzpYrY)i!EpppJf<;B`*2uWH{y%rv3i1q?Rsj@ZRXszhH%2XA1Bwk z`nnWKSFh2^+dIi>=Gnh;E7eP%6e?Er!=-rSGBi=^D%2MiFD^!Uuj@>T)}!W%z(>W0 zhd-pwr^rc{Ybm97_oPSLnY%r(Oa~oDi8WVhWRrGaD^goPlwMUFBNP3&U3H9 z#ZU%RY+9!PlDg2qt_$U%$AI{!c$!jpSi(PsgG_k)tCM}YO2((upa4jitBIM?!0Dr9 z2a5vKAW;mwlO#Amz}-duNe^w41@Jj0_p9YQ=3nrYlGU<1QPTETP@~13?YeAri=ELt zO*xG+H@cW6`hO59ut<`QwCV7$Mgq82O`Gsfh~*kJTu94>dC^3` zM_@=rnNH93I_Pz%%*W7JdD^z@dJvSsp097dIn&sAjgS9hzQ7IhKOg*9Jl;VFgN=#>f0H6sX6}XUZ&%<(h9_J1Q~%Q7vSd9 z`vwPFOz$m7kCgkhch8m|I@VVE1#D|G&atZJJkK-7etg&i6b=S3fRtYF#7Qh+NmBmxMB%&C#vw*i~&yTDZk?237Q;6RQmi8RJ@IO?EDj9Hu zvaq*S(lekaaxGJf&$r;iU!cs7kd_kzL3RjK5u@d~Oq!69SFXkGY0&6bFw*|x$Pttl zWqn}&&e1Usve8t{!b|}kZN08fUIqA_`OqFHpyjNcQqK>dEttYx0$8CMb2x}mKo|s2 z2(!!=?KfLy*FdPezQH=yr>6X4jql>)|xAGnW z%DGYFi>uyebIe2CU0FNsb>#-0=VD&iPJ3PbDV*tMzzH6X_l4IF(f-=YqUA)R65|~p zSDmWp>+3kbD4qRZ!TlO$J=w|_aQXQ2Gc|n6d<)<+ud}65}5Pa!kE!!VXq59W*F9Ou%u>INI-@t5$S5kUiClePAj58pAz_7MSWJW} zvSF)zWj*QhKWy@8rN-$SR;jzPJTqa9~t`=YDTjqlc2Orc_E4%_TQ=76~jvZRowUj&MOEwI6;)MVJ zs_xx>&1=^WJ*+>M6MY4)EfI`YV-{nj#~=SNdliR7Rr75dO=-d1EPEnz+19fuKK!@L zfyERG(4CRS1y;w2fY$CP{8C=)-pTzjlj1Wp1#Q`G?~}u70Xnz9wA0i$NJazYl5kl{ z`4mI5y-Z|$2~AX1s8U*LrS_}FjoypWCigE;28BZH;*>(p-3t*9d6Z}Jb39EApB3!=}C;Ik7NFu{>dWPH>2h@Jz*B$D^-NpMu?tSg%4;1&lC)Zx4@XjasrE6Tn4O&!Ogm!!&X(kTN!n+i3Mdx2LnSWxMo9r^3u)#B zWtwb2`I&E>LkV#H z)B!)mmBf{uN||_VQDX4}*ObC-x%^zF^PAEoq1YQ+2gfzezpdf_`J243grk#g9o#Y6 zLDbmNX`7b+U@{vQ<6(&-e4bP1?Ucu@b`UN6`M-hb#;O-d%aV0CWtG-S1U!ntTwFZy z*|Q|*4LU8s2W-a;=mgk*=peJbuGwhLR1U-U`|RnyCOy~W;1bTm`hVPTL6l92yEWYC z&2y7hyrjq;e*8VMKe3cXVkCs0;{d6%)3+}o14}^JEXlu?*yzt8nsx9HY-W(pInz>L zsY!iS&r3DX`!Zwy7zWXE0q(vptjz7UVsmBY^ri$*%b*C!s{j7sBRKu%PmS;-cr38;8v;TP=}t)o zR5JA1p1_8qHP3;eZD+9o9eQVwylMEd=A0a74wCcPl;@phS}#h z(2#=www?nhl;uikDkL}H6uBdsrBjAlmUP?~l}&-+co<4N`$XeCx3_W}XLOoH1nfq4 zK{sKMn5al~UXB&QCmm;ct=e}-U#RrNJLGDRAM%~sl=zBdp35Fbz*tZ?&L&+nh-UMO8S%L z$?oFZI`Mr_c&Bu?Isa1ZQmT#A2@w&Ey*te_^dh)Kc$AM3v%qwSsf8=^0ar%1k{|9p zqt1Nc_HEF*k^vlP2*`3ZK~}HGa5pZC(#1}~KA~QQFn7~xWA7pFjUBg8C^#lWJ#>E0I4DD5HiWqa+B8 zzxoJeUjijvYE3|LjNU3}jH1IRlWG*3700HY^N-*KWSmm$vBzQ`jtFJbp4^4l++k{N zth7WW9d6$JesHQ{1FADqJ0dl`o!YYLr`BJBwA|T{zTX1?&}m*HG9WsSaC-p;53pbv z^0$X#$tgHC>@678+oC`xsrcL?GIos@yQ7sO&vV-=i`Z>*5sO5Y4n#H0;*#L#lA}ar zVg1YX!o5j0de>8FHDzg(URd9rZ1@r-?PTJVxqhsBI$Yw-#eFr$!HR_n7c&iD__T-q zQvW6fF_$*imo-T)(BU^9u5t!9DrdrPw{XA9X9rr~d3QtEaDGj+auc4s$GZOL1`-+( z2r7$HdS-tz;c!8WcD6S0p=-rGB<&V00`SeQ)i)C(zN;Dq(UmQe!khNqd^(ymLMR9& z>SX@M_+8xn(-s0iqXp~`YcUMkVPU||5-7RUCRKR`(SqMyUn&uM&Cz{SiCNmLx-ERA zy)&7^HMds&I0swHX~iGd@pm)ifH3lGS$HIEEw;&&9RYmcglYzq1DXnr*5N5c151Jr z)OO)~*IHmaEJm*iPgE*OZc~8(^~1S)wo$W5MRhNoRIFmQHaqp|HyH8Mx&ebF%87NtS2QEPm8wl;JKMS|k`qnIj-m zmIfv=@@#jkI@*35L%^n0bQP?6Svm7(fxAu$hfF&|e4PBVivb+wP&$+XcG#ra`ZiS$ z@NU5&ufZYI0P4S9qu6|inz6vErgjgVTYrmXF0!nU(i{00gBJY!G8my&Li3XqIU?CY1JFkc z^`Cou`-~0r@gciKic7_|L(d^K<55Tg2REP4ys_2D*py~?$wkZ+!Ebk;3OHWI-+Ksg z=xsMi+rb;|iMa0`(j&ph5CmfVfSr@HzsIpJ3^-uYa2gMSUyt3+cxcN(Pr%XFyy_*KXo6g%WtGl1mXk!;U#+72-DX6l1^rZ2Q5 zUc&`2OXdx@F{)@dS3dL+z3AQjc1rTLxI84WU-a|&T_sM@DU%}cZ~&fm{&>1yt-_EuvdA#Vawb4Epqs&SBi;QU>y<~_ehosJ61sKWPM;r=dmTg~CS(mYQ= z^GC4sW7PXEVQ6fu0anQ*8#-XM{G9Qk?w?~HUy0l6zO3y$aF2>(N(8tbc`WNd*_1C5 z(kCV+4grF|2j~q{*K;?jCZG?lz)WDXs4{wE^FL?l>cS?QE99K~yBnoOOq8xZ=>C0a zPdz&3-%tDVQ)M(di(8u$vwp4$G=BXmNJHiW5^4l+0y^WzES8g$dqDY^1? zXf_f;BIuoNRkG2ABPjH=cIT#mF&X^AM;K_d4hN2s(YPikD4P_4k4`P)x?IX1Km6B5 z`1@tjB!igvA98hn&gK8{K;H*pmKO$m%i*6*r&6dSh9ac_ zuv26Nv>*a5C4uzjRK=5EV5b>70d#PMUXX?mjL^ry-B728E{oDDsJjmwKjsE}>11HW zHzM!8Vhr9nwuc~f3ITNS1N@j1VCzEzbxIH}$l@|@tG6nKfJGZDFrSRLKp)&3u=t0I zj}X%b$6)|gn}hqKE>Y5d5Y`#6hM7@t3lUn~9Wr5Nz};`EJA&@U!^b46**ipT=wE(n zJcZ1uwO=1MtPOnxWD;or(@`gsLs0De>5>m>INnF_&d+>#=k4W=St}W?J5#|1Q6vv5 zP~p0tdh)fLpRv6VU=Ja6Q{TCha!=?%$UF?V8PZ_fy6T<_Yrdt>S~peU8NLO_{}aYrT?`e3lZY z%z6WqW@@1t|3i1zM0g!}5spOm9&TL@5|W?E=x`CS1UYQf3g*hwm_x9VUkUmLr*z#H z!_GYc8*bDFl_hjY5Ca5daBs0HTU2SLzMWMv%|Gv&Ak^@zv2K!@pzfF+@}4=IpjPjS zxA1%f)c8ZlgjXuH=$nQuKuwTs6wkL5P^!|qE5#MWP*>{`v`ZAzmSyaop2;G59~V;z zYezo&286&Jm@$$b)E9Qtd2nCJF1RF_!PT(l7A=H{`(KF)6OT&x)968lC|BUx7M%~6 z4TsnsRW2mzY;d@oEuQxtQquv_f^0z*fVMA?N5HUnj8MS*Y1ce8O7Ev=PCuhLg&Jq5 z*d6>2fB?6u+A(#1bdGS}VgoDy18_A5Rubm7lkK4`}8t=qWhR)8KyUSAaRSTv~&bUBBKG9zHYRpvnJ^gTTqlixSrf zTFGoT1Y1w{+GDkcIpv9+o5*L4aoq1uAQ2u4R+YgTa%yT*qW;k;hJpf6XqJI9(n8~@ zO^Li5+g-1HO?~ok!&rHUe7*=VH9n?;*d$gWOUUfjad>pO5aB4mm?Uy&n54D0)RjU!%E!9WMmp`8nPUFqEN3p7U~X!aeEFIq6OEi8Q;O1qrjz zbbj_bi*zaj)5h*Czz^$stsX8>nSr4?t#vl;FtlJq0K=~ix}u*$7wz!v4oEjo0~www zBd-IhQAqluVf}pvgq!MOZOisJbtA}brub4CCo|~eJrKU1$ZLRw)&uBs-~bPAbpJLS zdFt39_wF{qAakWN)frM;3#uk{sa}@}cFqHrfYtCE(wbqnOVOMI4j)S_MDW=jz~rt8 zBe%O{6&Wnrq^gE0lYXoMW^&7wD`(+Fx;=OP_p>z$w~G0pV^!YR?kdO!i;8(2K;>orC~|}?X37ft%x#hu2Y!WhieWU{Xt zQRBLaAp$&8QRcmNGic!3jlcJ-x0bu8tT8c`I#4xB$I|B|=eCJxu#cArF*4*E)=2b- z6^zxng8a8AN$<^l6{q+tfd%p`Y zk0nx=XhA}EC({E@mz1|tF3o~Knb^3-15IqjKtbG;3mZ7rU+Sgv0wEcxO!Kv@S<(W@BjzD$f%vkX##`3A!S@`g}E!p??BH^Y}AHPCc3u zr|Hx*ca6u_0NyC^L+WWF=4Usd8;dh-Jl)Y{yFNTQm(e`cWfIOr8Q{G{GDHh1jK`~S`{*x^_wD}QQ=)v0s^yd?&jm-hq=-H6k1Yocd>AaC+O zdyb)h>i&!{gf?3x>*dK&OMwlhZ1|EpPR5ahIAe`BhJb_^F+EO~XZ>PE!D&ge^jXHJ zfU8Wc9C{CroFVPZAqf|wufSu=>H--!`s%T4?z_*GyBEKB#SRK|!7Q@Ytd+B!MOhX3 zE8$&&0GL_$z9c&|QLF}H8>?)&h8OXyg=bn0xA0$d4-WAW6(h3gRSsU8>^h9cMV_D> zpWm6GGSk|3QhT4(NNL?+U6O?kMclkfIXJBmP-Qo6mC+fi-TIb#t$5_+Ezv8~BAcT0 z0ysi_O=or5jQF;jYMa)2k?v3upusA2$e9mrkNRZ@L0EtTQ$VO;T-$oKlyYCw4Gb4< z_sMt)-I%xs&F-7GEb7)gy7J8vmKgR%S@M{sa$DVrJ#1g49s zx~tnQ{amSk4{WD%h$Z+ zOoGChz6y~t%qWCCa@;3j^S7Uj|J=BMTW$L$#-_yGgKbI|6HeR-86{UMkujE|cam1n zDSKh63(NEzvaed`%4;~-t1$q7@@4?j<0L!6BFIZ#2+ zs=7#1n(g+{BrFGz^r1^%0!Fld*mXu8wq84{5yqlCcjP275*YYc(w$mY;I2SFVShpO zUKiiY+&fib{n{%yWy1+%!uWgk7$3H1DL0Y6N|y+caTzGB@QajGmy_2xdc%zn9r-G! z0P@7h;JZE#K$Pzkgg5oCXe^b5pTxK^~`$`~8zAhvvy^K%VsoY2huM;pnV=7sHVCkq)iL38=#$jciF) zU6a<7mv;QLWj2`uq9o&H6yuQXUJ5!YBR?q+n^*B#ylEc#}%D*$jjhIQzt@&J1_fhXpua$1cb7y@*t_!k>b>j z#Xcvwo-9C?`@yoXC;Vg(Z;Yd<&4sEHYXX+lfWDcY zq+MTyI&P|NMS1a_>*i{`;qEzmG36}roUh00GhKSV0?Nl-;lJN%`SY`eq9Z%ZLX$_# z?$RA|XTv=__%w=R<~gK-a3`F1RB(lC7rGdb&IKYE7lY+&!lsMn9!K!cD!CAt8@xo~uB_l!N5@KChoKoQ z=pJn*?!ao@k`JsZgN)$>1A`b6N>m&Y${Lm*(cVLLli^QW)y z?O&+U#MRn4A2kDcHW!R=>YNjWl~y34dE&chO0eSZh2Lc#F5n*A-nM6b4++h2AYGL~ z3a)I_7;C9WuOpNn{~mhEY|G9hGq`4q_k!GqCm-&^1312Tfpj8PM2(|y8hICY7r69X zpgY*yAJTg#nZc`41hb~o+$a#ku0YH+Hu6N+M)|q)K1G{n&}_}4XgUx8m+EnBBWKSO z{BAgG&E_4{$#FanAe)y{H=gCC;+qDV2vH|fbqGEY4|UoN?<1ixGd#3u(aLg8 zWOE?|X{v#2E#1W%1lYh-B_p03t5+}rH|?k0%|8pbpr z)wrOBjlcsS_ymv#(x?+vrds`^__*t;G=hYdo(Rs@b2{fZwK_+5s93dUzcG_TeYBqs zEMB3(#L`zfN1Qx@w+4c4aJ1j*9g>%NTJG|!647alb6Vp=baFjGtE2Shp#^Ghw*%RN zdlN^PktWMpzL+L|{AYZC{7fm!z#2o+I67S=BPz8!Gk2m4LJuP!eUc*c1n=&TWR@Lt zb@V8>A?SXkFST}dQNtaTej?a&&#t^C`zk^ItP+B&hKKm!l#q(_vO>TH%AMy+vH?nE zg5np?#ONkh%!vdb)()=$Z>DLsM7Tc55}NSGIREL)KLBmuWVi_6ZJuCK_s<39{+&CG z5yE=Wdn#MeF6ny9MP-lO;QMaukkiGR6tmCtUHs6W+5Wa%WK!I7A5E| zPm8I5L^)B6#S)#~4P1f%VAiO61>1EfaQ(y8-y+D`0*Nir%wwWVl899&fH&BoOkD}>tmIjX884O^_9Mzel zyBXGAw=IpO#G&--={OIVjjyP6_~O~&;|ZN?NhXv0oUYDU-E2mnQ#H$fZxgoG(-gnL z7{{@P`;f;SO@xXSmS`Hbq!`+g=ZO~HME}^5(ShgP7kO|<=*I4>t&x9VFYLZ?wCUvD zQA?>uTf-?{_#g8z86Q~^B{|qQ4|a9#(blCq-b|h#T>3QMbn$XVd+d`ZCPd-^(7@d$ zpL+!3aVnU*TPM#%fs-*7-zm35WhO#;FOBy$p#e$ZMByS1t2^D;%$+s8unhUe`Gwcd z%15Tl*R9eL4{F@gxO0E4B)QkOX-`p}=s~y(w{$D#Dxa5=0fqb&WI$sgkW#YZd3)k6 z%wHfT9(O<2z%t&)-Vh0QgJJ304WyM_L3>k#E{pZ;Q~~*T0BZ*MOA6M7yW>!a&NbwQ zYJoK#f%?i+f^k0&K~b7*2}uc$zgluZOD#qC+0u-OoFkY_%6Qw7G|7&mn2&@-xwa+j zLi5k(Gog@D2ia-HYuY16EM6A2lF#BoFd;a=+_cAfzl~&3Pun-!Uc#I=8t6#qfgj1toA(SVf z?i{0|G#$`(BKPF17;xiFFt^u=la={Q;fz-oHNGMUmd4ImqazK#DSQrsuEU#OYa5@6 zY;SOGGGqf$Rotrd+eK1548g_~QM%L9O$m3L;}wkeW0&>bLxLVbgxMx=Lw+O8Qgnvv z{aKKNYP#{A$(4LySSkqvSa{@=$fPmkIJ7kOK)sf{!jWUXN@0a{Umk6i*xFjRR^$dV ziF2d@_rl0$FW{8je10WOpv8`9cb$>|HTI;zzORiPB~R=( z);KeC2F7cpQ9uDwuEXl5x-rMe=;yUBl zteH=hsom2D=~&mZkp%2>2$PNOLWfnoy^L#yaB^6KE~Ip;*ov(o4vH)MGc7hHKHa$m z(2ixWE|6VE-cF9;fsoyh@t{A$tcdrDFAv(wkS7u8S&T4aQ_2-OB={onRsFSHYAB0x zt(mqsCF#wa#}NeQ*PW9Uam~Z-Loa777%<&BVqa+0V*t#t#F=Igul;PuPh)|Nzo$}W zv+#y8!rq5uwX72E;(7~A=K}tfHh&z-_=jT0H|zZ#KD4V1v?)<^OP{R5&@i|7N-g*V z`5a%kq3s~gYNm0N134n(S@-oCvc%f;CJnfky$a7Cg5m znkc*mMCVvl>aPW=dVm9RIL{f($Ik2LdH{^q3nF7+;mw=3CHtUeokEoVl?NUsjoH8+JkyLZd2+2X zl&b^LR^I9>+`9)GYz!=?ccSscJ0FY$K|Q8K>IgpnBVEiYwN(Y&bnoW4!tsSrkd}*r zG+Gp-ofJY?=IFgVxC@L+^g!-&N7?B`Q*=rAY!<7Q)Wbszx}KZ)po3cjsFn7sO9kFu zRTz}ofNF#P<B^=^>WyBL>mzDgPT1(=B?2dG`1-WSA!wgrg$#AzI5^X78wf2B42yj zhtbH;_OIDNy3U$LiZNHLzu6+MvBoKzRxPr*UgD4jnQ}co^!IR$=< zV>EALy>KdQ9gh$q3YPOZ)NNvwBe)B%%XAL&-TZPFkzB5UY>`Fvi#qkA;>~?z>}38c zM+kO{)05%EMA`#yV|e~ditDb|gbjK~9K>)Lhpne&og9En&h7eBPin+2RMO$Gk%hK% zIyeft-Dre9BJT~#nw9KCp>>C$I{~MK&XlkmlM6R)OfXQVf`rHM9CP%%1&XBYqhbJo zi}WYsyVth(F79RXYd6HNac#BvFG(*G!`g19%`=6au=E5b?sN|3pgXfn_TQbDvxx{_s3dTO% zQxJI1rX=GU+ei>5JXis8Qq)t|v0v?D6_;GX%t_6t!dORI5V!*zQ;+)}DC8+H(qQmT zRXVGRjptfhAB0N=Fd}QgxrL4ccnf6-HlL~pXa;FkN(?P^p zfOH2*)kNl>ELj2)VjTzqUogHJ%WbX_%SEGsU5?W!X$`izoV#m`$G)pG@0cJb$MB^( z%>S$G$pfM6zGfO_iAaQsX+xG&%1(nw2$dyERQ8>S#+GR#gcf-#+nbOy$Ql~UPo!ka znqeqwMBb1Hedi(OQT_AzYs@^)J?EZ#?z!ilHDKEw&q2NMxN1_YtViYSbBKQKCz~SK z7>8~k(K&;%jZoh*YS?X3j;z%5c%A#zpr8lVlS=pd*Lpa{L{C?z1-sio_2=5*vJ6C* zxd_$JdXXy05I!tPdKf2W?d)>~G2ZuI)+pZuj*LlB+tr~^WciBNXD&;^#q~%$RI2vB zX9^(c`+5MIwUb7`ZLJVTw6NS5buRJQrKH%Km^eGNF?|vlf_sqar!)9{_-DYlrelHDTmU6pO(;)6b7x=Q!Py7P(hmM6bxpd0ak` z`(&f>E6{CDizl>7O$6NMZjObd`kF&A(TE9M2?+%WViQz-EtXKSXQ!Z`%}oDc0e>r% zi#}OrQw<%B@$s8;v`7Adb{t@hls@>5t`e-#_lvjq-ha*nS&4g@Mcc{`gHZ_1EW5rG?oCo2GQM z1Ra}DI3n=9`N?ixSDxu1LbPE&QtYi+8KScuy{xDpw3a31n~TF$&PYH>&VmkOa!OmE zB`XK^MAAX_rzN&FYjK|jVgg2u`36ogxRtggbumticA6rcM8P~F)l3<8kh5fi7%Pr? zM*;9_8kRQ zGOA~XEq?Bc`fx!1vE-23HgvALP;=B);!{^i3GZDh<&Dg+ZsnRtaCJCl@%vaD&Cdpnp}|;WQc`c#NWA|y z<2VCP#hUPWoL)URA6RA>GcUTbSBZASQ3iMhtf_8SJ|!X@(u$7Xb|%~jjPvU~|6#Xf z(1APY8>@2dg{jB;PNcODZ3yS3z%gB;76ksgUKtzm*ce2sv12D58!^QGw}BWiH*@a^ zC)lMk6C}5SgUy?s^)qrof4^_=hA%FhT@eC3-lRZ7!v>aipa0~FlBKUr%$>dWrsh2vg31jeC;d<11!kL>HTi7n((SF4 z$wwZXXST3V{PHfyIj8V!W#FU2!J~W0#@rh=^bSifRSs-LjB8cIgiYq#69$xKa7p4v z>k>Wt)wOzFRC6O&r2u-ei#t?mpyWPO>aHuF_PY5jGl;p@)BInq*vZ1fUK!(I4EvmT z?_QfjY!=0jsg3X65DT6CC9IuHZqB8q#O+i57IR;z{>N*fcnz>jJHJwIOnL3Ti?PcQkhlN}NaUzzgc>~#{KijC+yNZgZ*P~#9UX$!MT3;mFgAK2ETgduap00cF59U< zmb`MouNHV$e)}jU*0=Tyf~+j&9yJI0F%~VQ2}#}sSH(PeS$7OoD3T66ZWJ53YzhuQ z8(+B-*L9*D?!Djf^YB}Kjw)k(+D*6_n?ofa38;}Eb>N-WM+Ni8N$nU56QKL>=Rg0ZV10y}*auyb|o4xx* zHAAq||1z*0T!_yh!(4rBO9f`e*BZ=NpW8(~cojWA*>;&>;sYD&H*06P2bN&Z$r>pz z?`hls56e_Ychf2obJ&$D@98*=tf}7Gt&8DnYIdB3 zusP}0{gd-qwQ}nP1SEXKEo{~6gHD1ji|e2Hh#0k%d~{^Wvdvf=JV+O3~1~OO(bqR!pTT_3s;tMv02{C7T zOKdC=*z>`wK$t3eBD}-vtR|NiwMd&S^@#HvW3EV5``2JX zc*+g|O*^EdT1wn`6w#1QE(BJ99oTAe4)jq_6PeGV5Luj2V4ww3p*XbsEe>6mt`up3 z5&q^GKZX(NVH}fkr8+VEYd{%pPCGp5WxfqPOyq92$sq${2@^-J&0@xNlg^c&&L65?NFb5CeQP2|x9gQ+ekFsLOg@CVqDZAs z%;=V)6{RtBIhK+OpU6Y(Su{A^37XQM)}RUSYt4|VvMxe4YtTq{*B}cyJ=oxlWj5~y z(_|KOc}fe1U{@7z$eWFAd9>njy>1Ky7G=5jsDqY~H>5=}$$ezk@Q{IeSZ)QAFM{ZW zh7I3lZ`mAN0Wk`J_%*Y^9;={jp8U6?qLNT?G7x%xYsMpM@W z2hai=ae9FmlU#og?hr(FwmB3j@UX@Tl)2w$6?hOf(^N`g&B+y9;sP+dZa-VuIRtsP zP1p@OKFflotNES2b3R98#mX=@z!YwiV505VYK=#O>(+!J)0?bJ(O)iLbDE?6$p|6} zppm-h9neLOfIGD8Z)~OmY}U2q-0Bq-WWE8L=N}HWM&rN0n5BmFq_*@ZN_HON^f4zF zk{+BvrJ66%v@``lx9Nk`9yDg%4hXv3*1qU37tl>;ZqIcnGIXtLhrYT=8aKD$P-I^s zZ@?}PToUW#FRxftQ&3hYA{FQU81r-*(h9W~8VnkS9#&V^gzPTo&b8Hl8CVJF88g7P zYt;(+7(s71?<7Hr3V6b>>p3}hDkzv?R;^NA@sPkqjUz{Hg4nl~*L;%q<9nIyg+CC9 zL`rin#G)^e2S_=K^u9PK;9nUY_=5rX2??1y2Z}kU%{QT)=G2!vifF#V6PX9gNkv{G zw-DJr7aS6D3rv0+?7G@y|J=kh%?<^SeasH1&+mU>a5KhS6p4nF1=o+=^UilU4!+=F zcmye#=JLDcRs=cbG1*OigZPlw5aQmbI*J(cAt0S1ReJo7Sq271AdO`kR#j)BxffM@ z3YQ&dXs-ZSMO<1CYoPx`pK13B{5a`Z3m|__AIcNTZXCO9S-a;C_QQF@9A2oP0nic6 zuuuOtVx+c%ZXXO+D!X*3WOXt&^TlTWR!CtE8LH!MkOEqA@j-bsjr= z3dzJpiZ$*s&3iiix61KoHiN;xBkuK!N;6?w(4nbc!SE0##KH30!?b^AEquLOHmK!Y zrS~-A8n5>X#N60+y0NP1=g*)$S56KBT9rp!<=6l41Kykg3IWL(`*SQmg?u2s;%IAc4}o?z zcCM}$V^~K}uPlyLl?h{A3rg`s2LAQ#eFHozah%cBoZ{7@z#?+B@m9vm79fri4uQCG5G2-0TxYgX|tYe*M^7E{WBcu|J%@bI%99+F@Y;)2mg zVii=>gB{8^S(2h`uA(e?ZeSP+4Mc#6c9JcvAnG?vaC(~o#gA`IK!(tJz`Ffh43G_Y(TzTyD)p4->K7?cBNb!^6Y>K|3h{sn5g1p^%Yx zP=~{7>k?Zm&D=^4YQS7pJ+W_rSr)&I5W;oLUuf~#hVL%H9C_^T>Y5P_QMdEKZ~FCU(fw)YQ=Qgfxmy ze;Io|1J11I%jj811Gc`3uw$c2zkWRjDY{M02W4b*xrBb^U%Lz*TJ>YQryb;=Cx5+<;!zWiewSo|&D^SyWVX-a02g z{}psT)fb5}jJCT-lR#Iw9ydEY%gNdBIwQ2kbf&g}@@zkr$I1TgUrQqW+KQ&@R5=_rPm zLqo?|SI1RX$NlFtgsg{wmKx^yP@6XK_gqjKPIWUsf6IYLKc^W;3sEmHt99`Z5&B)M z=A49{1{JF^6_-(@$9w`|r90)Pe>fo+1M6}<-?ht}G6UC_#EguLU@;%TdCg($qB6A=f0|!N|zyZB30@ zs=mWm_}%Tar@NC&9yN7!2{bk~MxvlSx?W2JgtI=Wqg)Cbg!m|jHETFm$5GFpwIiT<01`-JM^;)3;DoY zA9}99k1LrM#6WM8272S&;L-^2g|>LD;`d`(;$qrIy)RgjN$NBayZ~r}5iI`m>{eM6 zoO}RN!f?wJ4v~AMaO7M1`pQE?%++AK>KTVqP=`ecvahrlbQ-i2flo znMGii*Oxic2u??&z@gn$`}#Mg$3-kCB`;oV&NU&Wlflzm0ef`3EiVoQb#al!VQ;wd zl5d~{e$^$|8{El{)M;A)*}CNHv8U6b9Q)PCgS@N<}FnFZYlir?L`K@E_; zLPvbcvg1q)nM~%{vZcmHbcnXq$LuiBdo&o1xWYMTer*{Lpd=FYCb9YK_LbxUefK7! z@9uXdqgK+*7Dyw1n*iGV1}4AxS=pA>)}GIw#VRW+&)V4ut2OVsy2Q1CcsT|axm8L0g}gDN7-fbH621{CP~pe#}qOhq|y^$JATu5DCmvD~w{i$(=z#d2q| z5)%^%n@sP~faqXv1^$400jLcZ<@tDcf+2V!#`7^NYRCnq0c@^N8f7;cpe_xO>tQx` z)~fJg89R=2Lw$>zG41o?&5HuY+oZaNCh|kX#z4t_1xY%fOrG)=GfCACdHb*TA5a>R zb4SN%73zm9F*tYnKBba5Fwq>x9A2ulT+k;%s}Uh8w5J@2>*?wF56Rjly|ST!%Mx>Q zcjpii5^A7O9`s2y>HI;uD?mEI%10U~KqfnZbRvWw>v3ax#L3A?V9myL)e{pFFME5f zJkOt3^d!`wc!efbmj_SyfJkGZTpUUU5Y~gb(YSw7CE+A;XSy35-7_(<|4rYyu<-Co zPS9|ATYdnqqZN{mL?B?+<%#I^2g+#O}wD}Q4VK!6y;Y-Vm=IW#oXY$2;T z-+nCVIAQQs9BoT2A$cJIG|g4?im1iH7Xv?xD_V4}m=oTe0os3_b#?v1oIoZkA~!sL zfBy=G2DI#5KpDpXgxbY(Y5fw~@T~@@`o2E4iThAX4?nwE5bNR(zJieHA$|c~-s_M8 zDjcObb*kOt&&jU?xqgu@?l4+vmcXd#Qkv6r?`tapu{Ea08Ay7_o@mUCYMU5zCfd7XK~QvEKi@t z2|`nt%+Q@QbRKEprssY@oi@kv5f2ZKhR)8|^h*Xy7xU%wou+NkFc<|{8{jRe3x^{s z5o&lLHV6~aH`lTw&lQ;pifDxFJ=Oj3<2I#$Ssu9hb{RrtQ$&P)Ar1dJfuAQK*MAp6 z24(pjK14XlXo;d$Gg1{~$YwSJEiB_pDwS%GIX94Iw)@rFw_#A!X!|l+S2?~zt%me~ tO;eMT6=3*1Gt(lB+GGpQ;YgUD^yU7u+uqvk$)tn7BWgN_(p64h`ah{YOauS` literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/reeds_shepp_path/L_R_L.png b/docs/modules/path_planning/reeds_shepp_path/L_R_L.png new file mode 100644 index 0000000000000000000000000000000000000000..0d3082aeaf30772b53243558556fa4940b390d8b GIT binary patch literal 271666 zcmeEvc{J5)`*-aq!>N?1sAw`vg9vT*X+%QCkfDT-q0Do;(m+BHnJa8VDDzC6P?<6( zV}!Ob^Az6eHstF(r|10EyVkqb`^WED>sgN{dw;+8ecjjixjxtJzP#+|^)xIrt5&UA zFC}?GVbv#5elztG>OR)POnZJ}`b*sA!lZDjaA)aH_E7OPf0@IwDxy|dwa z=&DuhtE5i+sbs6w+hlh&Sj|bIHDUb7LwbX2o5iL>N-iHfB=aod`6o*1KUGtiqP~Z1 z2s=ir$K}qWer}eVU7hj7>gXtjoojh?VwgnZ!YF-JBILK|C(0bG=a}y2E4$flJ5A1> z5-GjZ;$WgZZCdUfZ^|LwW1%%|uP;7e*K-Q~b8IK!#;Vmg3MxAG|M3rd8KUS-1)k+T zqsD$o=O&Ik+nY(9dM@~19~eck`s6QhF41PMkv7qH=X$w`l zT)v$0zwS9~isE)dteITgz2*H74>E6ApV}f?>X-d(FRouN*DUh%uh;(W2bqK$=F=ln z-7DmhM%~DAb#5|rZt{w;u{&po?XK9}t^Jq&{Wy%&2JH&W_IjhZ`6{_y0{OcD@wun z=iiJazkmIU1Q9+DWd8D13Am%Ih@BA%0QMhey+kAlK`QJmWK zd;{fgWWTVWDn9l`@zVTEPK+t#pND0|(_)_bo3-Tkp$}4FKj=e%_fveogE`Ru6x;m2 zd{l=|zDz6nhIx3D3h0ATlUff}#jwIzHaHGmSh$)?Kk- zdk2|^%WozcF@he{2B+-99t1X2{#t-eB5d)oZx!a-t8t2;aG|)6$Yt3s%W1_^2+A~6 zX{sHm>I@i_>Hr(k>KD80{I6fnm!YLfD^E@z#6F&G)7!p%YyNfNH~v@EmJfV2?*C6! zGg3vt-pFQBMXMbbKgW`{if_TQF`NZczv3f`wQ9mwP(@dbXsKVy`MV#g?|`kE^d>29 zUbYB%efYLs>dwgHzx&oN&GoqeFaM^YgVnL>=kQ4W{>;Pl%a6o3K&+@UARuV6VU?SU z2w$fDwEo{$?vnzaR5SDZfb}wQu=1MBq}r4Jx^fv6Lb_Ap^)Hxj6Le_c>x%hRKG-#4 zSNCf}QPSWHV;WW5F;Wj}MDD}sZpjMA^^afoH-xW0WfIuucv0rOtCxq!!La>V0S2g>(@CiZ(d_lEL>nS&80m>-xIvHrl z{hOyOiPHlH4#Vkl#r{^?#3w=<)K(xWkMPUxSlY#8(uxo~M<6 z!z7eT+fd5AL675g*%*ge1|xErUnA8wV|LLY0K1rVxP0edcadKLUoU@|R)KYyUer`+ zS#;Qc`OS%>fxpe#h5evB4i0s580(||qCNQ(=p;;Unkb>1fcOC(BG)W?25UYtAOxpM zOBRel{$>fvJh0UWR%12HR(;aID(nV4>#=&hEHdoU4uPb^hdWPUvk3xhiVC}_-@N+& zZubjs=Q0L4B{uJPj7iMH)WLRQtqkJau`9&v>zBu&^M48H!R3x*%(rjkGk_x@-5_Dr z`5(W`F7FE}s+xOw2?@jCu_o94sb>_~0Q26B?BNHGdGQlT%`VNR--W;P0_M&c6oB6LNM*IM}E~g?Z zhWR#?%%7lXG`0c%15M)wP4jIq!q)FTup5Vr0k6sbfu`|;rd72SVvme)0#xmfe_i-$ z-2bW?Mv49(sv41oZp;09nKb?+?nQ;D+6l+DJ!Wc!gV?e9tF<51zZwdm)fzsiN`d{L zG&^V!&hj`sK5P}yxGugR;*4Kn!0z3Of+;lmv-r$?&fiave%WMaj%@4}W? z)r7M8eQ}3Uj7?3;aDz119sW(7iPH2?JS1;Fq>VAVm}6kHJgF5BJN)&DU%!6k3v+HS z^k`^SjZ9ABnBEo9fv+- z6>4YOUVC}|^{%e$vJgCL(ZlV<-Qka$74L~tHkmo)4VPD?%5VQ~Ihg-#@T7Y_31TAn zjeI3=#3Y_5{AygyF0Y$CbqU&eTXpgdmpB_7ak4DcNWFT$KFOeKk8S5ugG6UD{=UAx z*Voz$gZlPqWp63Rk2fX{ivP%8qxQow`;n}c9A{dKT4rYE^Q|F-SJUPz;(u^ztK)LSg-g=0jQouD*pO6$&rx}20>3p-^vdYFD{Ocgy04yONK|u zJ^!SGOUgI|8AKQTkk!JG>vYZs{LZ_FcY&hlE5I%|Qan!HfO;+b#@L6)oMw0Gi^Pad ziNorkfR@(QomWF}-P}>m#!{Raj%?21|kB6flm^&7p-9R6ZH``T2z2&#!gA z=-1cOFg7(ciA+m4PMBZFbrh+j{&x24*?L~eWW|OHdLurQaH5h4N~h+IHamdKD{2D@ zF*4A3t3nQhh1quh|uO7B(&5xJRX1T+k5Y<$V||o?28>a z4&(Y4C+QLRL*KL2T|qiDD(EXqt4q#L=UU8m)NOW<|Q$snMQ#UhN5|ni%ER zS1O(dQE-0_!S&lbLAEaTr#99+vAF}1jh7rD9UtnIfHiX+gjbSQEBjGUF=)1eE?@i6 z`X*~CSo)KQ)e~HITwI)*tyAqwHQ^RTFHNeyc@Bb8HJE; z?MOzfokI4ajvQgi_B5@fkAe(8B1g!V`eqMRbvR*a(qeL`Lz2_Z#>S>gaLbl0_qK~! zH!72ok`AfFUwE2iBKl@}gj}U&J5$E)Ky#GWcemHEe#7#i;DEVmMLE5?nz)D;FLu|) zY4};Z=9bKJ81HZB4u7ri$w{y`MBu!(NPzx-!L7W`Kt(nB&lQ!C5lPm$A4Eq!bq}K}s%9X*L(dFdi2*-v${@l>eFdWjTbw@B#@D`42u}{;T zJSANx6Muc;$JZk+vp;Ve)YaB9S#*_^#utq!tbF$h4dX%WgQ4+HG?>psAy}QJQBaXX zJ`%^B9U`kIm%wnWoKZi|f|^(5<-G!T=B^8BG}}pD*G2ioT<^28vKA}7P3BS7sf*XF zXlap%Ad@&Zg&PaHHdV!@q*zJM7|JXs&xAPI2PaNw#_c{Yf!RBSG}`=T>suJLlJ5bJ zmf}o#UV<1+{UD?yrVc&<9FM-Yhocrd0eve8?C6W_6hC` zi64ZJ${eS?{l6ry|Jdo#g*-ZIKZNdk1e#Z#A!Q-Q^8fnlFM309{ie>&PQH;W@Gjir z5o>S-bV!LU+fQW{Ryo*T%2zrgTHy58o%M=+ryMXwfD!C`n!gpfja0s_=a4O4f<#NVHaa1}GsB|m)alcwnXZ^! zz4~$kdo25YYLwMB{gFwkY7!F@)9v`^E8-x%dNNqdrdiqG>s!~?_M_cWCCBJ75?^^H ztBBEn%*dUT)4+a22Bi&;%mX$>=@4gUXC+CmNb(LeFG-cv)eI2-inC%+f}>zA>}$y~ zdc_}4*}#aS=x5rpW5>g1&z|)<@Tr0;m)R!a{4<`1n<4b=e@j~b8!A#Al22T-ZddSU zXM_4=L&cJ(hd4PUX$m%O*q~2JN=r?x-4Vh_@6SQhFx!@4b#MD z1t$hTRhv-R#|BY@M>9}w*&3tPf|oJ+eA1YG{{bQ`^S*ar$Nfe=vUg=kCwM8SN?sB~ z>z&{vyk+h3Qj*isiV8hghh;f}CqlX-17#Vo(!-h(grYVOFmus40qmmuy&x05ovy?o z&xqre%yOC@+p<+EEqqSf@XD2YC=7RZH%4kPvYKpS-0PLgRz=SU>8^hcX`qUcSLIz> zfxAWgi@ZDu>%K3(HBy|f{HhI>xB%G#7t;4L@vAfN^Yb&NI6vO|8$bn8us~E#_uZSs ztXG~MeB9yJrA%sTaKfgI_rPTr`0}b=8tyE$Q+0%}o^DC5EVVB!Emh;P22(w!tsR<{ z14=KGK$w~hI%FU#C?wRm?fbV6kFRxCM`v}1r;;7)-`u3kC6R1mM`V}%?y?mklU0g_ zwfLI8#2g5_d^4=2BS%92G`k-`lq^E2;{YZ))KM%PYx*Ubo3@~nhiv)%ue%$;Bu+Ek z0G;1=6-U7%uLGxaVE_L8{UufOTRY1`LxVe;Yim`Ayn=eaJtcx6a!u`~N|;X=A*i`f zU{!H~B(XyAOF0xr`ca2n&qLYdYheOT*!%4u_e2b&Vo!0Z30fYIelZ=LtgWr(`xc@V z@=1Pwpd0qcmz)8THo*hDdfoRz4IzxbiU2Pl5SLehJmFhc+IsFj)%Xh^>iH;Z(@YvT zvPCytu%cE9BiLX6%X|0fOXlY0$CBjUjE%gz0|Bt;rCJh4waS0lU>s;+-A7psPRtwi z_Cku`(}5lY)aaB91PYsD)L zLOJxkyW5RHU73n5YCF;LPzi+0q_FAHo;uFtACZxffusx)#Ga*RMbJqK^JIQ~#V}Ne z1q?v3bP=YyqUHJvD$PHFBfslFkt~HYP=l{y~)qcJN}qI%og&7$F}C@eA!G#rvy>2Pi5_1)29do4rAT?g;Gp72zfXq4Hp8BHuho@2U3O7K zH^c&%;7`6m!zB4=*^4BBmjoxu#8-R}2k5 zhzu)9%=|PmGxO~4?}rp6&dWD|1GAeI0w#p*hl6_?RE=rz+#sBT)wq9*K7^xZI$}3; zIY`v1TR#hSWf$+06#5URs>E=6u@kGxmboE|gVPVjkKmPdR-NWr-yC{zhkYWTBV*LTowrP=X}KxRJpucXHh0QU(Q z4Sw5Q>?cqzR@U08(@f{sEUN^M%Kw8pJkaJLn}l;6$k61q-EimD0N0BvwPpFRR^zG= zn;<9GegzG}AJli>A2>y3Nz#^q`lK%XD5vD2si`TH%2CvjWM8g>3Q=;gW^k!{P+7&( zSr)8u>d;|ugTHxK{x>)sPBYS8?3r>P@YzswJ#{08`C`P>`DHdt-)$_iWI|-ufh6DCd-uPSO6p_6C=>7Q2ikmzKyw3A?y7-rr;sS4xIfLld+b z2q*s7u%YnjA%iw}_G|spfbZYGzwfyYA=zKT#kmBKFf&a??9)~{?jE`UUV7mf+xE zyM`##s8HWzJ63Pd{w2jYjbC`?rAz|Yp!&sEvcEeuuu?Ga%P(ZG@9ReFoA{aJfHs;7 zdCqvyb|yao?T5;-DvXvmhi89Iw3R8Dff{g`ft6X#&Cck`9t@rW)C9Z^_rOX2?SI?T zFL}x&p7S}0)YX{`lDgDW8wXjHwyfe|X4rw! z?fm|xtQQFh0$mrX6a}8}YcSC=@kQM`{B+N6-`E6itjWn!!7yJ4Pr;Y^kqiA*q$uv( zz1t3%^tGuGvZPCH5}$T%$gI!EB^sU?lQEeDU1{TqeHzMbms+}9~48XABu%+ zek;(o$YVOLIg4RF5kG>XPAG9Y)YC>AB;g`17U!g+qtjT%%EHo?JKgU-5|8qr{C5=b z+Ic&QJlQ-Uxwy%a3VC&ma_sYnh={N$p5OWt3OCdqk~!;y{Y2Oz`z}_U$g3KEnUiLG zbd)g}vUK57G#BPU{QV**;n0_`sTyE+_1Syo$q7|eKUQ~|HwwSyrf~&8URuFrg^l(^ zv|ZXXg``Z1O6orD3w96#ZZf5se|>vC^{N^G_>4;0dy%Z(^P5A8+*C zb7I&xK%~p;YHMl=pul<&8_UbW!t&AnEC<*T&;TXnJ|D3kxq@)uE(JfZLvZPF)*E`T zJw~kXC@|fpU#1VR-(mSU+|10(HGsyl-@H$r1yu8Vijgu%Rf+em6=-zWE=pAFHHBFM zgp}1O0VoHGvAddr!m;A|_00Jn+#u*^T|GCm!Xj3IF5$eCqK^iG zaC*o#s_W|H^ten=RMELZv3A|MB*jKZVnUmIk|9KGWvSo4!WJ+ZL*PfbU|YP#A^9K$AXS?#Q#^0AKbP zVeqV|tgnCS#3U#vSiSZJmO_P*6)53ypJiEN{DS~;_|}-r6PFL^qi%DyT}5T(Bb!|S zFyDM&=Zg|8f)#Z*$vT{5)2LR--LH{m>H(QWxB9D^<)^@>uu6Us9f4@{227&B?gbbw zKF^z_V>i@0bayvwcLRTX0#4^@b9RO!hXDtYuRIg(gy(JOxw%Jdf9Q;ikGIsCSy)&g1X0#RASShJ;YAq5T2KJODCnH(K(qQ*%&+u- zVXIXbsB0ul34mdu&UA1DlpnM_k@?S|@PH4RG9J0sb|OgJX{uA(9tSsI|(=^P9jk_&2{9 zoiFkj`MpdZ8C|*ZKI_i0o{m1r-}=|EHk1K4)AD29O_W9%z&p*@CJ{D~>w7?22X8<@ zUj!$!o3e2sr{1rO`q7_r9BdG@H|+=@XQ+|i7ff?W{u*xgrgN&-l7uc|b`W_Q@Jag% zqu3S;F$l!A&r5o<gh!F4@$(wciA!rH)Kpe(h6KwUP@03GDdgXZ ztqPD4am~ajEP6)RfS3rUMW~>*JP8T}M(FdGWyySAYa|o4(BU<&i&=^d2i6y3zrI2T z9sx0@2P-T$`iZX_UAAaXRr<9RNz7h@M(_zh0Ql4r_h|jN$^4GBWuowNvSHQjTA!QB z%}v!YD+#Oa1*$ZCw~iYQ^%>iXJWo3~IK0%(b9T!yT&UMMI3Q|n z$+GTq1BCVfYh*d;uyO4PMa8OjqAGza)`l^Ms4L*C+?vH7FIQ6X8aUuj48mfMh|f)y zduIKx#Epi|)Q1+B&D5GPK6s4F&6{w~J1_6_b?m0U5|1uA;UlQAn{7MT$p?_uR!H6T zjv6Z>4@fkkPq*$EO1$?#OIT>k(Pw1-gNDK`wo{WdAv0;k^;f$5$R3aE~beb)7U z+Yz1Jt0&-odWYQ};4!e08Adom9S_d73C!+7TmbIYSr0SE7p+xMp>~~5Z990ipN>w) znK|(q+%ST~3jEh{M?VMm$`lmgCVuI6p3_7_jU z!qz+&*k`)9$KzEdI0BZNI7Bka0mU`&SeraSglyfmWxAP}JkvDbY?IweDX=AJTs6Cm zvHn9f_qPz)>jL49!+|XiY_i+8S2Q<=1h0~yKM70(9}jPUf}n@lIFj=?mQOQNFf%JF z*sUiK)xE?=RN*ZiArAc+-vpT77L8)C3Qh)9MQ6zZ(I8xs`v z-@@e$@#bxw9_w=#&YLV%+mh=wRFmL*So{ZZBT8P|#abq1cb<*Ba5~-T<84tc0=uTc zx{W&?unL<#&=A8%vj^W613VIEue9KBWkT}-N7{zB7c7H(#lj0EG_NnYvL;5F@s41+ zi7O0Ange3RLHjjW(Oo4DI1M-qMhfR}_l%))PbX!yi1fG2_O%qAmYAyeoM~m8JvTGp zDd6~(b`Uzv^OU9hfmD-*wltUNwD!FMc2X6Qe2rRy(%U_Dn?ufx;?08x;ax{PHNSlM za;YiP3VM$3yyutVMCI{*+u!bsaHG(RfZppJGNb=3)DQ_n0OD51@fd;1=S+DhKDz`08Bb5h8-@zJNmQ~DUu=Saf;$(p>Xad$d?1;LwV@8oMES2y%Cz? z;4Ip4hlPX+0g-r-le2x-yf5G~CXP%i*wcLYJ|NS67WGalnwt9V#3eSL#qv@yF#+1I z04FndhBINDi5`c!K|21d8PuGEkNmRt%zpQr3d&aX^8Ye2zbMX0NS+jHf{TD7oYeM4X`xk9J0U!>|Kdo zRftn|SK{YI$Em8&vSZy41qNLO9Cs?@N1yL-Xqnc^CZ9F?m^t0pCC)5hU*S&EZx6BT z+Rur>hVJq4@uKPG@!Z}4sJtVUu5BZt##F_N(-u?V^d?!EnOhcD${;DnDFRvE&u^R( zTWw~^opI|~g%IKEWPC;VZ#@VV0H3QdLRQ}WsjiMWZ!$1%E6Tf>!M_a_2sppKVtj@e z6Q_};KQluPoi)rJ^e_ujXyNuB&0n+evJrDNm^I z0#XxgkvO6pi6a>{KzouDw(?L`h;o9)8bW&}-BWNFabZF*yZj4?7>6?lpPc=r8$e#p zovKMFTnFwfDmK=AZl-0<1EMCQN%VNLgBifJmpS9X?U{urwvPtq=HPl2ysgb2Uyqco%^?UUs$&b4(g!x~y- ztTi0KJ<8iCzBf0(EGR_5>t-MMKCa!@Qnv`KC|FA)IaY7auEN<2#pIoq^I!}mEoAaV zZ*HyI?Zgq;LJM(v3-qP9({p~`bhASkSXZw9lCMDWw4wS5W@C{(-84`(JH|Hql??%K zx-59eCk9c1HLWh1kpoZ%NslIOu76J$bXnKfkigUK~qF zaGB{r=rnhqxB0Zsgi-EbN3owSfQ9X%mNqu0AtNmiooQVsac?9i$W%oH{C4E*gO&`DW@PmFYJ8O)`z!TiB-qI}G+?A7N4$-ckc?mG!vtm!vj8!8KuGuk^M?cU=*U#=G7JLMEHs(ZP4=oJGtBwPJS9)8yKrP}~|Gc+ix8bab>n zMFL`_+wCm-QKO?n?{^RSCOGcx`dKCFGBEBeAU=3s4yCdu<7<9vfs3}+YKmGA*kKOF z-9NlN9ruWjXO!y=pCt+BjmDXk-puCykqcTjF;OJ3qx|Tw%-E=>^T>JLre{?H7?e*UQf$&dDKuuMi4_XyF^B$-XOw<}lHW z5Dn4n%wDq#7+=7F;I1tLcIAM4S6KL_Wq0rof-4+P<>4+FQIr@}tZ#{6pKfTG9c##) z{UDbp6#8O`3*dZkb}C^`^wcQ@>9PLGPoL=6ezvY_w@Pqmy4{6WS%ZMaT1QT@{aHC4 zNnx#UR(z$EdUQwdfTKb9z+Xy0gWKBjvr||Xe3T7;7jn_zB>wOLvJy)Ci~iauaUr@` zXnt1Le?BpMz-4Y)I5c^G?OGD&5u~j3ehRCcfyZ;$ zW&0`wZV(44D+h?v;{$nW&wvQz@I^{jcefDcJXUzZuo5`1;;YAHFvSY-3(Qy~csPZ8 zR@kD`KhT3IVpm|!Ul5qr+5eJ(S6MyS1jOHOt?XyL~uoG0n4A|xQS2}NG&OY1IeihMt z#z;f;<<3IQ;EDV$@4&{m6+2tp5U~;k`P!E6m`w$I0XHr@kC|0VBUT!0@PId8v`M57d&^o}Xj> zH<&jpRZ2XFj!|h{;<)VE=%P?}Gv;%lp~eXp7nf?_SXfvLCwrWe-Hz%D&(my9f`JO6 z(X*g*^-~tU?#u#(0R9#mZta}Uyp-9!LY_Y|J$NRx02p0p^dVsKX#CB-B#Pe%8w~~W zd_HjoE9@a8Y_swb+bIe(xq(=-mI|gkp>sdG+P~gq+hLOr=qSKTiq@GkNUJA`p;+>V z3V7tKd^y@D@WRLzdN3z~63D@G=E=10toCh<>7$|ZmZ_ub>rdZ2rvOC zzOJ)v_~n%5fW4|?8-3_|qm-1C0=RHRq7XUBEcFQb2JPX1x_36Y!@<4A64OZ%tSHYd zU9cD#wN^-HD;gRcR3%WldhxG2{&2EBMW3*V{E8#;0;*{fBQ~8~9AnLScYJJQ1SRdy z7uerwZS_7aKOph(44uvhb%$7gT9|X(O*MO$)>xun0o*aOYqGB~SeOF3sv+L%1Ji}qUS-ug3GAT+d;9m$yGE?7l9=`D*Q@2@n{Grb zsSU;pEu2~vC%A2=RC{a#CLh7VDOT5lfamsb2j1SI0uf#y!K`CCwmSCgvr&Y4CVijp$P&W*ab${d1lQ7JdMX2%gYfs-pYaeIc=HW*0miY`nW zJ;*|pKk_)S%=rtc1%Z+J0o1TiTD<@xHE>|;i=Ee0)U1cxntbS5wraP@%Y=x$gxJ_( zEr^XaGa@sZXU?1%`%h2+6|eCt`UZ=4iX7Vi4Kd|`=&1Y9XV$=(Ce_B$vLs*Tk40RU z;S9U$Xr;kVL~fjUASb7HZCL&FyV3civT7&NWMGoHL)Zh>`+F^NIk`nq@%>R%yP*%9 zBwcB>Q1GJNS-nl%@d!YF5}j`qUO52*f*2{?8tIJlH5id))BABXfmW^E%s2Jm%V9DU02^;2 z`yT57tPSCx7W&-m&Ta4RXLSRoj~{3r*HfKfgh=mWE0@^%2?l^T_Jj%O}S_ldoKTYVT8tp4Q1YHCcfO2GkusrZ3}>+w#2`W%6B-d|D1 zQwm6~z$W(@-dr-DK?2k51|c`_3q>R6jc6YDy3qx8*M#Y*sl+NYI~bBfQk}{gNjX*w z@e<{wK|xJr7`yTx*YAb?s@`zG!$&v!xLZSFw~1PE?E}i22BI3I&&^I-q@J;m zwGcQZb#Ywm)&M#A=ZMX(b}m7W22G3T$u_-&5HCLpn^4XxV8Ucu1QC>gw8zUh%A&&K zF{j+a`u&s*ijrY*aVBlsjThD1CxwuEV;cPLZp!tGy)YhgkUDfjzLe5A&?GVU2##0| z*^3hKs;G6{+mJR8&x7i97#$5Vu^DI%rtBxZ;DaH7C;K!5l6uyx+i=3nY{0~-@_sjT zZcFR;JsoJuvJs689(`(hB~Zd;HhDBbcjYO_$HMwkGKXuIp`{xHDRB8`K5F~Cfuab_ zc(Nu5aHcZ5p68r*EpTN`<-lt4IPtagl%@{M0#tnZv_Hq#{N3lpE6PqXpf2l$Ov~td z_*rdL@^B}*@2lQsYJd*nMTQz@uw#f8YLoy@(s8w+s)`=+KOhn_lMnTm)tz^dn6e>L zOaY0dchA&_b5Cd$bOi2&7~>3oR#f#W1`7HC5g73$%Ir7?zKLsgG&>ANo6>p*o z<*TG`sw^G&Ap7^cDxVCwu{$_6n}Q67tH`it5pqs~s*sCeaCRpeQ<&+_vPp>D>{ zAVd?miLEj38cWpd<{72fX zNU(FLbY`>@WceaRFd}sw`e}3VqKk!L$JIdR1j#xXd!7sShXn;0^h~gqilD6D7g2+# zvo1fx#?xSkr+TJ_G^yH|mWCxCU^-9KAvt|9p{$O~2hOVXb;Li0@9*_;b_UMLUI%`y z>?5?kT|DhG4quU%wD~G0K6zP%GdMe>a4X&^CnaT6-yd(r$>Vc@J@`k6seQT4@diZ5 zd3T@QrgR(*`hId3eMXtW48X{I-$R;b%FYcH=VR6dS)>jN2$-}dA-OI~Zz z)GzsS-G_BceI^~fG8I}kPh!!}NkL=Ww10A~cnl0&aF;lP6Otquk;W}W$F6XHJJC0Y zD@H@umfiO8j|!!U-+>Y`bn0N%^ZA)}C{(RfwOt#jUV~agB;I1PgDlE|ufgYZWpTgY zqODxv-@$e71nt;*Q|J$@+c!lGgWjI6FbsSRQp&5F7P#oj^|S|9Os*+K=L035=@J`0 z7(X*TVY?Ua!HWkSmYPA{F_j1MYD9JQ7dF%KVm3WF+{PlPIH((Z-0#_4gO-={NYM+@?w1?u}H*X8? zVu_`Hg5C8C>Mzg3skfDoo6)fcav&MJ1WYkE(DIW7d!cX8`7&e{|KroM<1pJnuKDtX z1+oLz4bOHEv**EDAbIUG%elZe^>qTs07{Du$K{rm=uE0jSN#$ZU;RXhPFFVr!c!JaaQf|!u4~17iY0$ zV_^ySAxX}&L7tu7l=Qcv(q9VR`LtRH+nJ-7%>z4|)S?0Gu$&{!v`KX5_)rtap#_04 z?)H*pat5BVu8vM?yhs|0gG&o#=$Ok$u@iiFz&oz%};VWZ~9JM3J; z6_u;VG0`OeXgO@lnR}`c;-IH8FW9h0$WB5i8_n<+tzh&JnGiIUVjo06rsFD;a*$B^ z2rdqyK{bJ*9G;Pk2TrMORbE4r{lP3ws}9BCQE6zqJ!1u{r);Wnv0;gQc_HJVsF;|= zz5}iu<9!W&PA%ars+GkqtkLgc-v(i@5q9|uSe|c|jXq{81WGiO+0qHFg~uUzCJxBJ zdyxu*v2+MuJhV6+!6V%YXs?<)pKCc#2!O2_`@GXE5$U%nks&I_cJNa850l(SvZgSs z>8Y$>>jZ>1Z`ml>0q_!&nZs5%Wlk?yEjD}w-YMaM_@DYHm4Q)Ri=4%(t4W0uKd1w~ z!>&PPdpPByp8K=qWg=c|FfJ`Z53FxakL zacd<|5oOMvEdcLvohb*3U;yAgX&iuw=S0%Q@a|r+Tnta#CiYj?h#o()8YjNnW6&-X ze_goXE>LOgKN2>g`Kv94JB_z>@_ELlNU*QhHvoq*Aq*rj?gp09iw5THwOBf;F{@r#AxgXxn`=9e?=*r?< zVF?%CE6oT{Hdd`mT!?WgcapYY5vkRB%NhCNc^E@wG`qstvhPgo5fSLFeMd zorOh3NfOa+(?dho!&zlPzj7qy(i}9hEV^VLczB$IA{?5_yQdYkweyJeM|_c6_~k1X zZ*OYO#8@C#3^=WGlP#jQF$bT-`1CbprCD+s>MwkWaFVt$&qV@g(2ZAAE3&R$qu^21 zadsA`O^-CUH#Y9kU=}@aU=y6CeTP589X#ayFi5Ae?~(5&t~EpkOS!pIRRdDB*N5ls zvN`*2pT2%Z?yrUn3sRu+N1eR03!INd2rL3!1tv*v1w>ry#h%jbo=2nhHf zRP?<;^qjKq;QEC+$J{lj6q6wWVE*p=_bX#~K4k}4VlCvlIabo-bd=s#Rw^(#pY;u? zYKc|8x35#w(qE~qs`L=x{s!$;Q{kbwb!D$Huc3=tz?Ltc*+XdU!xe8jw`Pgi z`sxFieBd8Dyq(?$@Z8^i)OJ7gOod!lZ>_+ zzGK2?UqU$rSfN(69c$1k;#=DA8`BdLwxH1k)z#IR>tqtF6yBqoSI#N6D`r`(5nVA% z#E5uS7g>$KNEX!zO(Ox@xpSZjnhLttuOD>yHVP#kFoG?HIWI0je)$>{P)IOC>*>Pa zy@hTEx-FJ?mRWM(1q|9JwRYPF23pkecG}`P1on%G1-dp?h5Cj_52rE;2@1XgW^SSc zz+WAn7b!8Xrepsh3(^>P*SQB{d{kGV=j5d8+=F+3n-k#fbS)7RsIXtV%*~Ekcg&MR zP-J;S@x;#$yc28vdOO|}P@2p?6Lh8kscO|Dj?8f3&+Te5KZM8U>v|ca zRr4sQUP86gpZFi%Qg|a?nYnjhK>J!g%r+Oo=?R$~Jhe2P_;S~)^z<#j=e(~pY8g>m zSI7CSgJ%~ZOb0hSJggQrqsg<6#M8(9sh?YovSG(|dM*v3(i^;!wv=#bNlD2|#;hS72wDwye6+)i`3{R55sizBEJmH} zIPMW&Tt9El9Vtd{IcT9lsPFk+@eJNzo0VT(t;A#$>hFJE)v99zZwN-H_CqkIs1kJM zRRCei`H-k6OZ1jEMm3F!l;aR_CYwr)qE@6>L>fTX5?-xO*@ijSkH;bI|CsiP3DJU^ ziy%Nq9!sLkwmi<<8IpX|yOa=wjK<6*-1*BnhpExv!+x$;h4c|DMna_ZM7n9xHo1TdM| znGMZUJ%0R{SApTX{1O*ngC$%Q^cgPt`pS9n*P_-^fFh!%M8S@QOS2r-9pb2zgttgIT|VQ_^~<#ZI_cqajeJbXw^Y&DLO$v-r-JeN5_f^6sj%hj-Y$KWPc zupay23I=8xDGVd!w(%gBw{SHvkJ{yK~`Q6-}07>F*m@0dM8W^L$S-e?egF%jO3Palp!jQ9$g68-K=7xWsi8@fZ!n z@^>&;W!>IVSy}1+tg`BArJ@OPAj^y3(w?t{#SSg=^$GL*i{UgoP}FPa#;c17bsAvO zXovwWS({y3O~07)gx$jdDXQK$6jJjbwQ%VO?p7_RoZoF_34n=uT7Y!9E2qQj0y)(g z9Sk1G-5~6w(AtoJ+K50aR^6@-IysG3SU$7mg$bc%@NlWe5={R227$(u=8Ea6Ptg?8 zr$9au8s0n>5#15Il)?&8Jur$^@%giV=$nzH)R=42{CSiH3abWr7)9(&l#2WlmdmSb zCMTS??T9%$(4$q}J>80UR<87tJI6<+p8;T~ye`A4M@2?P<}zb5)S=7}4`M^wSFI4) z=c6F9(j+15mA({Oph{g`mw<-uIXF1TC?@9o(-sYn8L;Op30qnQH4{-BFNsM_71{v& z6=1aP6;iB1{a(1I>M0L>LT!kuncTB66g^?0SVgR$4yCG$I7LN8)JRv=I*vRbU|#KH zVdZO-=dm-r9SDNl@HYq&&2SZ_Szf)$2c(;%OQ#pwFgb&Njw~4|*F_>jiS+6?sHxro zK^Ffy^7i=0Y6vo|a7x!8%<$PhHT|X;7vc8K-QE3IU+kZgqQpzowgiLM-`e5cD(_rU zZgZu_ak73GgJm5?w*c>17)%nzBEINK;M~_9p&=n<;twvUtA8YOxn=>bA|!MpY032U z*!N3Fu#xZNF}#Cl8zn=`$jC^CyoXorWj9oRa8MsFyix}L7%a@+9ULuD*(Fu2C%cg-Qs-{3FeboOYU~h9r%yrJ<11;T6O!xM6kA7VeeQu$t0;< zcNYerp}Q$^=-P2JZ{eaJ;Dh4wp;6NY*`T-SHubm^n5qKb2jp$1l;eLJ)*S+`9AY5f zgarh2_#vDapR*r6P+VNB_DT2hFR2wd23GAJ7TK^*xI9C^AIMs1T?xO4iZdxvYF{^Lhitwlf2T5=hS4i%b}xguq! zu&s`KURcOv20QdfF6rp7$EMdTT&*}sK0kl`&?_k%d2K|%S(f63Nz1TgN)8T=HrVR{ zF|n-f6AfR!JWorrscGLfuTH$Q*?rVod4s*32a=)VBq_JPdPyMyd0JJY0zaDU#|`Xj zW$Vdm=m_C%43S$olC9%`Q$w4o$duXl53raj`pk zR+_Y}4Vbh|n#GEnHk#oN-^>J)gO+>{`>PG}J_Y^;jV|Qj^^Z-#l}evxZ?ZiIbW0d+ zHV&vpLl=l;QeB-K*}i?Ac5KY-|McmHkPvSzvA9~OaoT{k;~nz+8CD%`5M}`w9X5+O zjrBAyk)`l>FXtgb>|V!`qBoDgv{sUqLP{5C;3*niL%2jyTgTDyC@M{&Fa0n&d+++; zo!a2g39}THih`BnT_agpHR=Wi28dIvtJ`jL_iuCEFCis$+J1h+QZj&C79kgGW_WKj z+tQMVb(9>OoCtGbVq(&o1ix*;WS$Tg=X&Y}!JA?pXyFcbA;qQuq4jf~iwnA{bIBNn z_`FQ%WPBS{v#7aq;_YW|Z%cSRluezvbhz-sMQpf-KWI6nfooYHJymS^43U9Llh~o8 znPEvX0Ib31ett=b47&OAiC>kCuWAGA9kJE*5;s@vkr%;{TiOB5zGQ2A~m^?$;)J#{*IicMMB2B#?IFeexLOHv9NXx zvY^zQ9ox5i7?g+Tt$qnPa7yquu3sYBvUTfyU>Iz>4?S0)zwJD6BcFpNd|WVE-63=E za!M`C;^xdrDK{KO-{4vg1==*+=X>Dr;gq)9m5M?Nqt<^zmf(dUY^Q(45VSNMO|X$z zi_)?(ea6#@zAqViC0BbgjC@)$Gzt}FN#*D0CP=cCfl>7HEB5#l$e(KDtYKKzjy@d< z_3%JzRbzOCJla(%=-32*}q+dAz z%C#tJ!Nui@)<908b^CP)TMoD&G{6Vb+X>CY-QdCZ5j*ZhMaS>eK-Wd8&`T3}_v7ocQ5!E0R@CA*E%66j|v0w6tma3zP`Y;G(IH+l$I( zUgK_(f$Jk#A>Hm7c)xWyXMp|xI0ZZ(<`pO+8rh$<9)XdA7r(3^!ruu#H#QIW&R0DLXJEsD?<}Lo-PDU0CI& zUL|mdwL(ULatO(b<50iCpB}SV!D|Y;OaYOnc0^nc;4d)M=Md;Gcbe`(>yx)dR~4R| zQX9M;3s)KLKK<|n%z%95)LAM<=Vk2k3?W&j0o<5?FF%W-NXuVJUyUwZ+7)Xa^~={X zoMLx1#qT8TPqmMeA(F{tl&~?VOTgWOFr2H@c`R=J_TgqVorQ$yv4u033F`cS=Wfn0 z<6J@(k+Fq60;kPuXA_69S>hwuyg+^2fdh*^fuKwsF8w^stmPpvVv$=^j%&I^ogJGG z{t1Oq0a-a;8vt)-$?t1xk z5-;I;SSQU3fa%QJBitmCl;75NiK*-?<4MIcj3*Gb0o@S09a1(FJg3?5Ut0k%@;0Th z%h?W-*3cQy5^+!2jGp-39nCGmZ6P_|W1+ZmDDAi}V)wNM+m&TRgFMgv_D3C3;TQ}t zf7F3Tjh)hB8ZIz*cAoXsOHD~R3DEYeOi&0abFKb#NmI2h_L1NAGNy zmuVt}zJWnfofZ&A$SErJr4hf*4sA9+5JaxI9kX*fE=c4YHevo8ix)MZMeooYjh&sy z>2J_HeGOQ*0tHp}p9l{}I!zw%(};QJ0L}-lhtdNC4|yd9N#WBeX=w>koOnIXrXwp} z48{+JcC9WBd&Spt=sL}PWdhqZaDf^v>g~mf1nDI;jFDQ*_OCzrKa{<7T$EeX2C5uT z1d|j|0R@y$6qS$~n+E9;Pz00?rE9PQQIwKY=@z7G3{=_!A|k1jNK5x!dthc>&i8%4 zd++(fA4i#a_q+GnE1&hOl-X;?F3^0NO#@mMMtdmvvc@}Kzg`B}v6neHlNSoFEzekS z;W`8fC7?xVQc_PULJY3UZX3L80_e3#i{@EX}t#VlbF5!JeX!7uKFNVwtT#R%#)xeoZ>QRuxIXuoeUIDGmyH#&Pr zA}vG;7N1op6;-f?OWPFn{P_+;>}DtIfQ2MASxq1 zga{Ni72W}ASfFF=0awA?=mhx@)USFbt@$Nwk&>~!{o%qHr|g_>om%~$P^1GVT#4xP z9wa6vYOCg0H3ewe19j<5jQp>`C!ubM`_?(wA#L(X(Lde~CZ4>KbTW|tc1hdjUB_d5 z-4icl^sK07jTA&5j?A06XP?>o`goOO2EEr3winasW2ShghTBoxHt@qpfe^9We)&0` z0A6(`ke~=Sg?b%~Z4bQ;)aQ<}o>+m5MsQb!{|tbWXHA&2b5Gj(oc~ry8zePQ-Z8Lb z;oGvDf!$}r-@0`x4;38wzozG|WJ=}D(s)lomKEG8BqOrJ^=gp5)`#Y?6xH{A%VPsl z_CGd!8tc2&)>6W0;4Wy8vp`~d2CE1(VDyN4nN8{~%qmqYs2X>!{rliSkY$ zHhi`b`J`XsS2n(O?dVWjaadLw9G`4@EinHH*i^He?#L&6_;5OA-*&+R2a0_Id~bl0 zO|^U)B1)XCRxaR95Af}=wd~s<0qo*lcXF;um~diNBmx*}&#W>((#s>6#@|iZ(*c~N zQMw*|3P$(AFeKT@;h$*SvVc;Nc`=_@02Mb>IF&6l(x7BDz9fp;m8i#bFEd?HQtF?Dm9x!D@bxey{8diq6x z_+l;(2zuUHv5i;GJ=!@caZH<(QbDSS8If$BZ@zjMbMqkQb?kPtxtSTFGZk1Dhq4DC z1N(yqkEpC{6z&XNQQz4QU{4VDCglXr*@PkD z>I!|%)@x#7VtJQd+zr+aGE9yQ+qTfcKfEAEN~o zzG?+f3e*k+-yPgeo+<>D2gteStyGf;%bkp@hp0>i9;Xe%ft7v#{$0QEu}uLg079}c zXi!gy==Jj}bO4a4$xj#DPg?_>+5GF{zt5{QC#Iz4?x4t&CL|9Hv-L@nqKJBiNj>_< zyTQccm%P2bH@hY+hWZYIds)`9*@UE!0R)bRO1H9u3e`?g(45*ddxFSeA%sdiU7Es}ISse%f_9(%O`gJJ=inF}$Tm-1e?wz4stw)$ z1`A?vnHncq&+4tiEUB9ZEeUGUA5orCBmsD6AbHw(Bj<0ywd$Z{eVqV(`|C;o z>V989YB^1>jrZlz@+F``sbQD(TEeyZvjsmzq%`H1eb{c!Lm&rIT=rn-{pzi)tR6yA z)K%}2xK)BU*;}$o!xgA}O~;Eg&hI+QXyd*9XgtNbfp`Cks)51A$iUzs@F<_2ottoi z@C?GoPiOfe$elB)Yw%1VJ2*IM`@}V=q@Wdc?b)w9`1uVnhvuNW>=!tiwgUh;76FP+ z2FQ=huN-X_)YcBN<@L=vARkKv`F~{dG!*g{z&jg-U_CrSr9oP~L51w) zMIWVsX!jRTehFw54fXYHqdiz{eI)s=?8Q=$qqA;QZ^QK5WCD_!fRg<1@+JY3D|AW$ zZq?S{J?iR!4qwyavlx;T+{*Od+Efgm8lGWm!fm^`W~%dvKg^S66Un;iSsH>40=}k8 zF#}k5;1C&)9gA$&FDTTGI1&b#HE4z|{v4(U{&EcaQMK-ss8Yk1(A9N0CVnV}y~xl8 z^i-uy52|L7ueYiV_!QkaCOy~^(HUBeQ+ZNSJ7$1jO?A$Rnf7($@91XOy1LHzS+*BC+d3@-se{vXetw{K(aK|{(&*9n zZh_)pNxKf*e4@-m{I7FfUFUvf8rA27BV&Pbt{#1E2w1-&d zV`oCO8?VjEN=l|uvGLEqL$9kgV83=9n`taVtrw39&y%u>APor)c=;{4@e^oZiFvU4 z^;+-)&OvT9&}eNCNznFh!M}d}IuCqCmWR+^av$m%v~q!;zG*fH1_uRYvL9BJkY|1QCX9Yrga4c~SPVdOwzA-o@mSziNZlU< zu~BgX)5PC*YMe=hg@rG_S&-}nUY-?_rCx|n4RxP+CVtcYNM&2_R^&o1-*hV=8?=%Y z8l3ChKbDu5TeTtXhks;7{u%wW_?_dyxW+BilRnC^_}=?2;1i}1xx!Lc)cjLGMAkei z24F0U1u>@=eVnGQ_8ufa{umT#l9ep@d)q*Um|y#`VCi=9H)uHId0x8o>r5FTc#6j} z!3lI6M_OQWnMDc3%2k~102zbs^N~wAh)XOoGBVR+%irSmx#CgF(n-rEy*ft5#m1#s zqb5B=8-$>+oy)PUv=LO+?2nI+&k~A{zXH|u!1AIHzB3ze@t2uph#4Bv&0vy8Ejr1@hBYdFNCWjmQS~P-{1sYq z@Mxd%Y`=fGbjrPy)%%yq{5|kVyhg7BVcUfZhzknF7{){aM@-9I@T(9Tpl%zjmU!Vs z9?DzO7NIf3&q>ch*Abvc{NgQ3#VAT}Q+i1Rrq| zfUhTNOGPfzqXhua0phIPm_9?FRy$I%~S(fXjIVxXvE z=#dZUXH(`Dm<~e!hN}Q`Za#z`;AuD7bYq=<+AgJNy?2AI|I}~8SUJsQG}gNTNXA|Q zR1EX*i1yMSBfq8js3pgon$m^bC8zmj?>XD{f*x>rCJ7kmhECog2F@K@}J@#*Xy?W-@ z(bs>Ok=i=x(kG>10i-WLnGy8&!j~Opi>!<9jP43~&r~)&S?b`JzcCGLA$_@#$BrCf z1UE+L(KZ{Se=<*@Xet)*t_r>NO-NH2F=MC`+Mz2IyXQzQNo1Sk-Um$1T?CkJYH+T0}Fm-27qviRsZO9=4?Na}i>J$kJaAtPSHTm{P zD{4glWV_g7Yo@SR4ujaI&n^AtNG({)_i(yJF3(f*;CgsubP|nWseM&{UQ)?U!N_H| z0tvMo>PP6x3BisJ4n*z6eU$cM;DQNx{=9fbA3?2%xw#Dcq0WsRG#H zymFq@F4U0%{zeCF*O?ATLmxhV{CT}LXjK?yQFJMaX(Um_lfPu-meA$?#U~syPo_ho zWwAI!_a$%vrD`?^A2{7$w9vqM2Rz;WQl@@Lj^KV$@0Rh}38}88+Dl}I4Fy%V5Ub&vj75wyz?tET z^E>0~iw(G_Nb;CWxD+06_GZmZ&25H?sY5lsWXeR*J z9)fWn=m$O4N?#0qW%P4mb{opMLN+huMMGhcL`dhl%|OLS zPP5;8WWDzxXfhAG^}Td)BK=dZ%+d^$%KEIC~bh?*CEgII&eHf=DLkq9r zDoN8*_cUsGfwi7Pj-!1l-p4^mwPLOUcR6Am@*iGW9QKDpXQ0b1l>3;CKtA$YWo6<& zefrd%_YCqyfFqLNznJ)q>{5eF-b39X-&c2sG;pa7{hWNG!1sL-a3n5Jhk5Y0Fln&C zenF3ie9iEFw1PrHpP&!q7dQdBqJ6wg5L=y5@{3G7NRbhu5O>NM*S*KcSD_Y z9*xeP+Vdk@mh56G@)Kcv;bqMhb%l!`z+bhx{2+YUwa;vyYK41NR;@1ZBqmA@vN|tU z<=BcqSN8_0n`6}AR-G_(U82&DdVT@W9G@&I-ej*8!_4c$Cow^X8Pl_{@Nf^)1r%WT z{-7G_FBOE!$t&nvD!Z3hVRP=>r&$Sy<+#*E38`dvx6Xc>{t^5P%LY>B5FJJ1v ze2*jZgbyDc{df>)z|h#os8fG1Gkx*=pefRSRp(yAIOX?|S&($!OBNX>Lr%?J<%U=4 zpC{q`fW1y_`h=fq9TneqFUWL41mARj3?X~l+6)^jmKuRaNtzJ}`c`xe8D&NpM}e7O z!M3HHWBx72LqyNn)F?BNs8W``_$NJRJlog-?Ew_`p@uU$J=!U%+@@sFou5u>eM4rJ z3FRK`wW~;wT9mC=89R}KTUk6#lTPs9!H?kXL22y}gss9i;A&r9>zwLFQ+NFd#EG6? zC!O7z@6TUwM(IF#cf`rtlozgXN{KnpV;h| z8+7*Sb^cX5A1d>H8JNv>syAlTxh#?5q(Zh=u?ahxcN@%nwoYyV6~+zsN7x@NyFB}M4bmi zX=^aIQa;waYVt2;gg||Uv@jet7!<(G0Uq1tO zA~faQ(J>xyS02-#l%3XqaO=q9q$l(_>4K3qEHjbAGm&ujKI-Sj#KrMSFZ8K=DxD8r zs#D^gDR5ctSGQ%B6*Yop++n{@w0VU-7=`=&F5p(qj;~zf<$u6CGwsi{bAN7o;X=fh za*3hbdeR4AKHUf~zjqXQK|{kcfy2_R7GCp_?JK zkXo#Z0Q+9RfhArtT_*GqA@MaUlycxUqj8iUqZaGEk1zJL&xb*eJl{j&b{VVFKr8ew z2>fk#I<8=pl_H+LB`pJfDPbc7UKQWZCBq()TteVNsyNURnREcc_%i_8j7bUuzsZ!> zrht41VLXpdD)SADyD0=V*IUY^{-t4IWzD)j2u`)YK@m+0X!X{}zpxS$RcPY~#U4{N zRTOjjEE5UY@FQ}n8G>< z6P?ti1+orOIDft6B40$IJk{e7Ouy(=6&O^KdzrA);=a?K1~BDif&i zgo*Q*kn>rvk~mn2X@Pwlsd$Ahs4G2M$uelpAwxYjR>NM76#jP6xmq0zgG4(^lds5wChXti^zc zb6OF~6hsp(rS}LMdEz3eE4W%Bsrca@`J*Nzt%#)TC<$lfLp&;tzBVKo599~9Y9vjh zku8yBN)G~mPvyB{HA~2dBIvfa<+2>$y6F+VFnw*5%mxRT;nHMTI?gRi_UO>%u!O{w z(SraJ(pRGoJ~qcY(B}F>e*+{t9kftmgcvY3M4q{J&bXK=i7H*YYLxhZ={RXL(J|hdDr#}-~q6PkR~77Mg+~FHpaS`KPi0Q+ge&4u5=hAoWw)TPxj|(08Bqr(~Z(YI>`cuc49qV zZA&g-$d3Yc;Yn8AI9>xv%e$$sk%d@w6S}6O|DNM0`}OOWK&4WHM7#U2l%}LW$DS30 zj+I4+JV-4&sP|ERMn^;Z_{LX2Yi8m=fUNeg{UH6>#rtuN)-XBA1wR3D+XcqF7)RH zWJ#>_S(g=>^(}7`tZ|s%4qTp)@bD_}1!zI{{W5%C&$su$!GmX^%(9`T>e=!R;?gUQUE5Fk_ceGr5VG_y ze%XQ;8JE|O)_6Z?OSj9qy+jIf1!_MM%*eYAeqJAM#mvl1xOgP!fxw!8HgPf~ZywjpSc^8@g#(RFZU!0oVrKz60&#P%As6xRTAD2N=!`3|O^*Rx51EhWvF* zuLaSCL~4{4aWF%oP&?ept@;U_HMWCBBOMIn#87b{)-0UHt8L7!t*$PE=4=Oz6}dX| zRTwp(5>FGyLmQJc*f(L8^liq$67v2q2{7r4u5VZo57qqerUq0d*a z(yGc-fSW=}o_V`xb*#`7Zp+H1agCcOD! zLjf@o^hl|V!1wApvrsvDVw3b0VKZ+cUfANwF)bL}L(>8qs$l-oY^Ct~ES69y`ftOx zZ)a6hQ~<0U+^wgGo%K48VxUHKTg)MC)p?3byw$93*Zs<0`u_Nfy2?~=;lNI_f@ZbU z3%)_o765O6HZs&$!^hnUatT@2hXAq037o(O+MJfHSNxfUSodK`8)|-#?uY|}tV)1l zx;VfW&^XTSqt_kDN)mnRyJ3MQKrGW$ctZ$s? zS&+{D0Cf{bGsI5>aE|^RT3uT)=f^L{Db>JNtRg#nAu<;QrQiv~l&(ssleNzO5v|99 zf7Y-a29rKM(g~iWnEPZ(F-6bfqUC7-EcOeWp(ekK#5$mYLcvSoZBvX8lV2r+4XM=^ zR;z~F74f1s0jC``XvBppXy%2i1kZ zhh#nRiKNf48&13RE_mmD{f+78+-AF0Du+50A={c@2RfUs-MEtE7s1X#eNz5#%VOqN zIBPU=f;Uq4e>-ATH!9aOoq1@DMIbnh`~_DDs839uX2bX*Bx>$#Va)l;>qLKjKggqK zj_ordpQuJ2$pscqPDxGmL$E)XV`#S)vqaTmIFg3KDJ^Uh|MEy1+bbj$bBw+#|G8Po z{$OZtg!IQ@@UAp_Bw=uQNx`>TeKeFTD;?stU=nm9I))knG$Doc`puhXN7BbXlq0AM zTvBDiZs3;!r_3cjv8aGD%J>+p0cgU@&nl2)GH{(pW<8CD0Fa{vxz8`|DQT?X_*X2 zpqwMh5L5zah1p}?Vi&??LK|6tX1RA;j!o-x%__iPr)sgF^e55>@~WItSIr=HE(?ui z9|xR>fp3-wmP|_o*!W7eN%c}x1Qb1XfuGmDtp>2BLtSivF;6gDxGO2S8mYvZ*+?%x2f&&{V0*GmY5XO{ z#o3@XYGi*4Y!Zsm@fmb&-U`bKB9MsID2~)MR2Fq9`2h$!2B4g=`I>ywFJ~R;p#BdO zGpuLn#~ahT$pGwE1)ilHIAfvKR;!c6dlU=2(%B$x|NV`PIZl3zyV-N0A8P`-f#+YS5@~T7*iQ^ zp=b}3WM?0PvdJE)GICt}EDV`=)OrVr62~}*uyz7G>*4Coto<;#b@FfXkt5hD0|a)= zHr^3KQ1R6LQVe-fs8I0ZzA<1{DofRusD!A3Al}>g7@nN+@+wT^B{|NxCYYXP-Iix> zQZ^HRa(80%9n$WgXnqEz!P_H44`U1*4Fd`ifysXUBr#tL8XzUfb#`kPsNT`wrN2gx zWTtu-4cg8g41^>wOUz!9h$2OImQ(6AA2Gw`(DRHxJ4(!c4=^Ffo0agAG`ov7qB(|; zPj_^DC85%uZP|;J18&%fJ#X1p&`;=u@O2E+wo8MhW&R7_{Y@J-wSOh16;VaDNU}yN zulUVmyA^p;D^EY!8N8-E;kAXPe}H&R2voCWIb;zvMP z`ysvu$a~+=3|YpSE(=C2=->m!?tOxCdYWqs~i1?bS)y@gs_}#$Awx z_1;ywG*=oW?g`~~KNZhE>g*zOuk7X=5UTPK*xgN2iT_YGEN~BEDS-}NKR~*={Oyv{ zvOjVwGrNJ<&;_oP!0tTMw*eCOCqm2@nG$qQ&Y~WwCUwiYVP_*-)G`9IK7{rB5-}19 zj?RwdHz2M(`VY~YB^HED&{7voO_s4Rf+ob@wm>{R!bL|I^bF#tk#co@i z6zNFiPp^30ixpM?et882A}Av&Tn>sOX9pmMtA}#9FT1u=Hiw#DuY+T$(>q*KWPZ|i zX>uCRF^y+#oP8=Y^K?`Jh9SVHYv$6q!qUQvTYgS%V*Eo%VxFX_vmDd#oSz8dw~4C= z`%yuKS|*;xgSQssh=VPI#@P){`7X;MgTK#$YBeC}R(=38L_-}R?UMTYm_CJ{i!=x= zn^^H$+1kGcM^u*jWc-%KqZZW>dU3JRdq#+T$SBYA{mtX#{ZCLOsRu``M&R3QwMt4Q z&I5o%w}97^h~(SLCkxj3nH>IGRvPy~-3@$LW0`RYrSa>WPTzerdBsKMnT zG@u767Bgke{L8WM@AP=QOz}@Hks~c75CDRlH{Cf-F~4{t2pA28}_3{w!@`MUckg{-J?-qmNLHB4RsMHq|RTeK`EKp z@vCO0Sr4!ix>l|a4j6R{Ey=Qien{WoG3D&-+=8laOJOGmy+?%>%LY{F?xyE1O#3gn zz+3_&m(HuVHs{8pagL=eb;s2{!w5vaKPO?v(IK!hMr<;gc9JmAqoDB@rZ*>y>+!oL zpmMHYO9GN?AfPT_Q{Ufw7O8YQe%{X@m!HGL5@e~EDQa!$Z1QKfaBEZCs>q2ULSTp)&xBNo6;N^FoVu%!NW zFk|Pow9ssKaS~D`LmHMj;VO>J_s}uQzL+FdjI}0AWF}2UMHfG|>)79daV-y3K*E|D zy(Z1QMM}mbN*zxzgl)6oU}t{-X`QaBF=#zSQ;arMx0h3Hn#d_)mkr=T!e1bWE|`L_ z!?yz1O`xJt$d?OFKv$31$(7&7t1-)#`YWmA8zjb_ zrfCK5J|Q&i4Z(@gxT(XS!-9^4p?PXVyySU(eRgEC*rB}tflN)WhWQ7B#a z^(!kzLQD@le%C>q<75OgKle(#bb_KDuq>j<&7?m4{%A zMG1qOT;)nr(aR6qijl8$|GohT@v&lc^(Z0Z_(5iJvc zO9@0bF!NT_q31i0;cD)vBgqkLZZZL|cqSnJVP2rGv|bm3M*_(+y)*@3;!qmmb!OOx zvVD^=(c^Osy{XVig1V+5(ZeIGP)~LXI8}F{+~w<9Ei6Fu-Ue8}B1u{;G}-uH(-W?d z7x3-CAt;|o-P_-q*Hl-RIW!hQ@-iTE%tK5Z0I(j~R=Yf00cQcV*u!=hnYDTe@63CN z9fP!5OI1rl$81x&aw*pr0LBxNIhXz+KNAvb_IL<0fDb#K?gdYYO595QN+XB>)tX z@X#``)2P=J@%lp@QCvV?bk}Y%yXccz78w2jdFWIuelzuH0Q2S$O`W{iTz^Lh zam4WFswgQH)0V|-xuD^Z@`b)UllYrBIazd z9PEm-D-8}AzdTeTCE5CVPGMi=9eBO0-?WD@N556)eDv0zla1@2BjETDa?C$|JS%|- zW^woEs(=bYvpG1pzIso3&Ptv`;aX1|3DK7ziH8cpC-9wXU>JoIO$%0W(V<$Tj!`jb zjp&_>&)}VyiDsHznQDq%A|x7Fo0Uuc8-5S1#fuF?$t2Y{3t$^&zB#qP5Cg=|As&s0Zm%Fc5y@xfuDxT?9i+-{c2eMci8)7YSJM#h4{&=u7sozB9+hk|G5hIDgk=%(}~cr zu`;H0FyO%9Dr(n(hNJMlxIbfwbj9Q&RrSC_B^{bY-`yAG24Z8x-#5DN>N?8y@}t>n z??k>jVArt)?9bot`?APY!Tm~jGzn{9U_jvMO2#O-=cZ9uLs(L6tT zt%=8-eD}io-Ik3rH^%n9rDnL)d1`0PNltSmdMlli^qV_wa%4OfyNt)tl_`}4Sm(M>V`hsCF4gN7D@8h07_$AU{sMa$`f!_m74x1?#_c;oii z8dT{KW{zWBr%tU|OT86G{Dbog^^fM}SQrCD{o^|QmMv3ZJdp8`2VmlRj|nLcUER>% z=XRiPT7&-ZvEA?{JG&e@aCY)C@7Q6{_I{>*?tFWIsR-#e;Mc_Hw%YWA9h-efpUVKqM_G=AxSs`p|J%C9Jm{o!<8l0_XXPz*ByO+JXE$6FhV*hK^nSO8 zaAz$G1;HABc-sd1Le}Frf;P?g?Xvs#>DbuWpJrqnDzB*tf=Xf}p)+~kLszb4v4Dq8 z$FBM5R4Qq$xC6UG^A}(#PWpEi7rp*H*ZC*t$rCO>LoU{QnBTViByd%1g7fwnxB)pugo~HdyDH} z#D~)6c0M5QC9JZ9PgP%E01~*HpVr48=u;2Ag87=&2gpGW@*7BgGvYtGoB(^l`h|@F z^L9eCkSHz(zKLCDH*eY$n3*Y@RS9OG`VLtYl-8cG=Xlx`6qgJ*yW;eol!XnAYIh z&5oE$z6S5Z%-OO#BR=RB<;1F95};wb3o=;3$B$cx{$Vo@Kl~soWKk9Bi!e!+69T6= z3wK%B&*NLnR95XT@!}Bw;H0Id&0YUi&g>p`H#^*^ZZ>-khacKY`PdTU7vn;$(;V$^ z#5}ybAI({hN=ga>o)^uI)F>yW zre6P@8WVF`O-)VmC|xUgOK3R{d9Gb(vi0;VW@2WRyLN4Se9PrkuXG3&?8=4t0Ib7s zE8K3HYqw96Uzb)4EbZFFloTioJ2~Zab#+msAGgmi9h8>kPo25};G{6QKh;5Q z^*pOIMmQsUXE>|--c|3pd)vtAyamX2GB7flw7z`#Qc_s-_zCi3afB#p$OrKN4A4oP zSGG&V{Bb_{^cRKfpg|k@U7U1ep*?J7=D?~4#t8vFc2;ZP9(k|OlU)=Et#)&uWT9&J z$wnH2j)36ceQa!OyTkVFqDTm5M?V$xcfK4>x7NRQ?Tw&e(f7vqnt6%>qB`9H3^jG% zzV&202WK@@!r8_rCBPK3kB1~+XU#u_o~L{W{Uov0`TZb($uc1vTHo;Q-AOqWm2>Qr zQ^rSc3)wHr#K5oz=18$Fh&3zOp5C-&OVr>+wk_n}B0Qi1oTJ+L^M`+KRF)V#de6^q z;@7}-tO8nMfc-Y=eb7YSFOXB54{aX1jjgqHU_rt0^?m@EllSoO@Y(-*BSl=P<5&O& zm4>;_!Rz}ynTBeObfsHJ{4_8lasp_6BASQXZ%=I%nM!x1w}>fF6m@*pSR>49^UYq(PRAVIZwC8>wbU-bLO9+ zqnJ0_Y6n)b(9v+fZ?#OE2AL?l?R@luN%Nc8T3{`a5|&vdg+|oSiW!rcS$DAj@D~A3 zpB_oB+%F^)3{=f`4znK6cA&pOV!j2j;HSB75 z1Ta#*W~~f^ooGwi&t02Fzl&_DymI9>MlawpHh^!h4*Ne4l&aaB?KWqXJ*wG!p!2V^ zXHLzUPK?Z9?iP-dcB{>nn^~WCkaq`mf-p?ovLV;3rT-I#>T?;#bfI=a8BL~7NG z_ica)g^`Tz7)1g{vYXj%UrXAHU7Lm<+CnOr+Fa5t=r_d_5{#&!?i-tyR&%l70n34a zygV^)-F0IW<%@m9T54ZIFalpnsn@LfYg^hpMjIK2uDjr*iYvO8-DhTCVEE3XC3=G`N2r<iM^JZ7VO5p^oz z^XI$2pWcSvep5R;RUnSN+*cRN0K@=qcm;P-6b2sZ6}e-xt6rPBh_gdEulVK5ck>J% za=^M)KqqT)1_Q=);Rth7P;AY#Y&`g{e-0p3mG0laUnFzF3{Gb4zG!Xs$Osm@_&^$T zX1iIT_Rs3c5U*vKYYm}ZKxk;+=;-gQm_^{gHtwc1e{ziS2An=V?HgeGVft45sVnC= zO!Rehemieg+)nw}T9pk~x}8!xY?|R%F2D7qiQM7qh1p*_`RLM8qokyyosaI_y?dyk z`6@+YfJE=d@x6}ZX+E8(*1Agt{}&AW=1 zFULF!46Oc44gA17l9C>0XXDh#hlD3=gTj6wI1+bg0-rsTm6wwH}}4A!b6n^Lq-Ra<)>;0!i1>b$;m>*mdy zF4ryrGE(ir1?zXRy1KgHDs=w4*hjfQoOaX&g@vXNif*Q_n|cga44Uz2v23XCy-3vb-AU0_7eH-is?PWZK(F&kH-ZQWY845z0diRA{=zZ!2 zJj^%giDDNsvpDX3``oYX#Mn35jd&n9y5GhrUNY*~N)Rhep(0BSAq(!DRKJ`pRu+5+ zZ_rW!L39#s$j*;CnV0XKK66IN(#nZwkw*^T?<~4#h%7B;Jbd`5Nl8%jn7o79OKx$I zle6p2De_F+e)^Bo+|66JKdT(%3mQ(VnMyr#7#%A_i#ejc!1?`r>QjNKx%q>|CUt8U z7oCdAN>i(<#e!WdEWFT26A10{Dx1#8P}a0|PqgUSKbrzN_0`k@s=`Eta9ZWUnB5(D z2;P6KSRMUp`F-Y-{Bsf-Q{){Tv)=2Nhuhy)@60+v6dYSxE057=$=P@n8@>B}bWgK; zdn-h1%L4+cw%?KamOEMLIK1oWr^S~2OFOr}_F5XM?5X%6)HU<*WeB<>9X$9aPqwk` z*zwmTaB{Trs)a=Ww4aHm2nz@(I5;{Mzj3=wJXE408M(f;_=H+}`Xk#TqcL1YxyD|U z7o%0=g?rbye)YPE_YU%6&j5m1$ae1Z=@7an%NAjY;rrx?td{9yi~bna?vLfRHV2;; zeNBw|aK5olC|E{^EBn*Z)kprc^iKw547nbR{aT>M6Wuc}-spxOQv*$Vcf{mcb8&I? zNV$ULiAufOM{(Y&f_zvG{QHZiQy)kam{?e9z8&4Zo-8VB)<&U-d@TO%2Fgdk-{Yjq z+hLQQmc}CWEeHC+%3+!_)suV2kgi)R5Uts$-7;DdJ}{GaN#9HF&HT(hb6JOh@l#Ly z_O0(4bN1#QEPfy7FBJ8Jt5i>aM~0aox^p8mco;38n4IhwB5z@l#Kg)v_l_y_AMz$a zsshld_qA+$&&qK~olvB>d<1CG&Yi1DG~R>RW6rILRB5-Hv*o)+Mm}+!RZx(VdlC>3 zVEoG@6@JU7ogTzsUDNch6aB{xb-fG1kI9txU6-0_vv0c4cz`uBlDGGu;*-xKTjS?C zh-n6VAH9aArkuBT>HD>y2|!sKS$OoFk-Sr!`)Qy=)eW)VX3JWL=)=RqqmN$v7qg;= zu#+{Glxs*-0KOotPN^ulaalwm?1=fJuI_Hvi_9B|(M3lRfhNqkBC^27aax={pu1Z? zIR6LpC!!Zn6@Y_&4xsTTTs#^Xb5voU&qdPRz^~c*CL7>2Eb8OqTZE9Ltyj)x@ zZ+5SV59Og~-#k8uYn5=DF@_q}WU$TdSc{EB(Bhucxo{`%J$!i0bjQvcL=T7tpH^~F zcf@;%|JBl*`#_XYJ}zxhF^ARc-Ez*Uh8C#o`qlJ0UI?9of zeHoVa_OGGwS2>=3663CNM$?eLIP#S)3{=X*&(I^sD2By|5l~lwK<9bqYT2hxXkxRcbwL$I z*73S;d5)dM#}c}2zF8_b8!U>?r!z0f%wvK!)xiErL$0R4)`)ubvKviPj|KOPRxK1O_Y z7D0XZX!&gK=Iy?}@2VzxyJ#MA%y2^bwUY`6Q(ra%60m7}EGCBg-u?RyS5u&v37i=I zzt1(ZKvpp+=gzHL`CoeDwN^Y;(tFNnHa z!)A)=_$j0er1y;UJ3sHrS=y9)?&dAo&R0>RPeKoGLQ7hrfvRN}0q<|inQ0Bg+kp_u z2D2nEH)lJ{O{0_*Bq9$^l%JrS^Vl+>GDmuI_WVn%^jrRx17?c06 ziw5FL|C@MKrtcCIhD9r#qY`pzdcFjCKbgLgv^e{@@8S+Pn_j9}>B559rH*{EqD)5-?yN8DdgxqGo6~bSP_C zQXJeqf*Xd8AeH zl`fbLL#{6xO!4wmWvx5h3 zsTr$D!h8k?jJ9bvo88^rdAPYxgCov;^ypWsS#hFvAS_WIEOE~DP;I`-YZ$Wa!0^(z z;)YH3*1Nout~_;Q;Z`tUTH?*){d^u)dW8zA>Q8?DyjW-&8y6=JT0~s|LNDe)1(_cr zo*X4sO~PYd;g}fLM}i6xlxq6={a?;3+qZ)HW1ldltRoi%b(3EY+f()qY?1j|?RSHW zx30a>i_!9nAzqs4V1l~0IB$Pct8K*ig7$&O$y%lo#dp1T{(hD|?~%*>>2~GPj7OTs z(#w+@9FOq~kN@6@F79-kkCt9zhwJInH*em#6LvsYxUR39R1dI+1d*C5fl)MkT{k6} zjo(1S&(D7u!qTEUO3KPCn{xJXb4TBzC?(t%w8=lzYu~Nf#Mo^(*w~%`tAm7~$i98&GP5Gm$NQr!s!)cBRuJFloLx~WrDu9U zL*5{7ezs7dYhXrB{otE|*V<`bF=~JGW~)p1?6>{xjSA;-O+2r@yK*yerRwygys^{6 zd-tAz)Fw(8Z=tN`KR*S7zfkz$BS!texA?eI)!c3d79(OlMm6yi z-k`gWgJF+Dd4=MPOjK=PciBCL9hXYePE~vU{VJjK_k+HYu$ZJp3EQr1{I#tHyvZy) zbNi^W(7p6fjV>uMgevb&Gc8qBPB?aHF_XBPlp|gB6ZLJ#!4t&%F+Mwd$Gjq;$<7@} z8sJpKQZn=MzDuSB5oNujl*)fT@q|~w;Ny+{kD3nb5f?F_J96o?K*5&H{^d`Cq_0|V zWHj$P!l&kS-7_)#n4iV)qQHkL5FUIJD~zpu3Xazuyo$`iwGH(2VGA1$??IM!Wl4DM zXc;Ot=TqLC2mG_ie@mOU5A+={gRIgz)CLT8A}!Lw!h0ZiLpgAfg)A>1^a=v3bZ`%0 zdBaQgsy2Mt>s)+I7R5ZNa%XPe`P|)mx!k`*OArpX{`l<(q8bZl1eACXU{JEaw94t} zJ%>!Qc;kluWO^wJr4>UenD3y|>Lp3;?Xb#gJ@RTfPVh;mACQ<-aW&CSE;4H7oAX~# zhv-pm=}W?g)3@c#F2#fgvF?k~eYS@+T{igP2U#Pd&0{G0Ms*e!6%)hUod5c$u`(Y$ z#%sZ9T@I)T487WS`zpoEg0pN4)sHO$W0il%+W9~7xaxlit`HK}gxOPL&H&6t4g@>7 z8~U(M!+wnR3LffGS8Z*B#T|QOFLSHd(f@v0{fqL%6qIKr$hO8$bAPv z3Nj1w!(oW-A>i3FCZ=_Qlu8Z3n??}tv?;rPPRAOE*8>6ryGtKj>cO7H|ErN)S&C1w z&uu)Ah4d1j#;}KvkIxRXcO6-%Q$G{>W1v=+6=t%MGB@w7{y=%Nts^n8H!2o&ME{U{ zkq#-rKGxs7B#POlaHcO)(7M*J`5ZG;EkLB67Qe<8`mzMfOj}TNq|n308FAhn7QOw%T2-ct)6y@2bchb3x3( z6@in}nmoVp5&3vwr{40z&Gv-!OkHcM^(SbO+zWx(Tlvogl-J!FqKXqRu!yZ3Js=^W z@8ICTD;ZZ*WB^sbfs%O9ph&OTzWo>*1$9EV_hv3G(<%OyKA4x9_5}$u5~HtLi*d22 zeU*_yR#NfotH^#&^#p5Nh%kH^q(`y~fmS9DL z&j#cYZL+gVX_P-D39FUeaWI1TC{h5~_vb7^YKDV11Q}y@R7L9&<6PE!! zdo$fa-r}jAO&icx5FDv?*fc&aw66U8`LVAr)twV7rEOT$Q?-*PeS3M&s9-i|wO&yN z@r??&y9>L-HEV0>!TdMgCqO0EiBV2b@n|4^S(3B%jsSJ=bK}C;TRfK)bS&=OTpH#z zF%fRjvTQv&r~LfFG1-}S^g^FQ%_GGn7)_aoo6uD3o(t^H-{oRrW981De{w_F-MtW! z)N&AgPPjwRn+ZKq+!#q9dB)3IXr>E=Bf%R-c9OL$;RBVPiV*cqYF}BjZKkHNfMEH) zfrp2uyvTLTSJp2Uxs7d%c_Z)WQyYGqGO6btQg4(We@DMBLUs6@%4Zp8DU;UTw8EhP zKXy?!+ied~34;0w0h*vLySRL}DFbpBH3I_=d74e{flcx5?N-ojJV5So_k#{Uc^O0j zC+wq|?+MUeNq)33fmKoR{D`${_-JOZw1$R;2O*kpG6cN|>XYHkZDL|On`>!spxIXPNA07o3`Y(hy!9O2m7HkrbnkKkn^ zY5X65_~e4}ai80GNE-W()UluyoV58>*6|2FK+BU9L<+QDU6?^;iSgcZ_Y#G@*GfJ8 z$2q272^y6cI1RP*sd4Ni`aOp{@dyL4bLSfgPI2*2_J?sQpCkY0gNcjr(MD?bR>TSH zd2)V7`fyIbXJW69PbsZ|Lpjgix%MT)m#i1KHza>6JT{oq?s4j@yMEWonG`gzt|wl0 z#e*pCO-p_gT=WKD>QsPy3XI~uzv$r#Tr&8a)8DWvc^f2e=vQ6;ts}ljCxSBzm*j4% zVtrj*OhUqE`Ydx)rr;E#7P0_f#j$w z#i6{;&Hm$Z`-o3|M8$Zk89L8Rfx3H@QP!pcJOdPYIuG@xqzIN*S5G8oAJSdESHvqH z2enAghW@(?y@byhV<;}YY;30{GU<#- zAC3wr>N#=mGymAJ}{a+CZ%{0FXuQl=ZD7dzw7=a&ett5!5j*5fKyH4_zc* zu-*+T)%EMwVRZSQLybHNL9$TiGD^YAtwg6j`)KlBRX=?`-u=H|KOkD7LT1`7Ko@-V z>1+ZtrJJ@DxteXds%`c3%lD)HDdsU_3E>_;`Rg0Sd&5mm4!ONjgLrv^0njL^W@cqc z3A03?w|*;lNHgz3sSNn+phUnr3qle0ZB^M1%2o3)h<^3z)VMiwr@oh0$z?N;-hogG zhHMR04U{LHYaSF+K7z!+pBD6e`)iXs@ADvO^f@sa1&GEc@z64-iWvXGhGV_W3vb?Z zjVl=bt{U}baaJMDXwz%|^c_2)ByjKEy&l$jC_sJdn1k9|cZ*|fw-s^o6xE{(3iQUM za;@vv6tgYWp|>D-E2t+KGfDxKAiAU*EAH`&l}chVdz_`Sz|aUhJxtUPx2+CN@%yZdBD z&M|7J$jd)}qoVNnf(&rr{h;pHM^~bM+;wg+*VNdUkfxG4p4R_Get0(DI(rH*3H~Yf zl+n%^F@@}JNo#D)ckHczrle}WSKu%7@a+iNcYXTT@eoFmI)TTt;33ocQMa9z1vo{lI!t^_|zUZnjQ1F3?Qr+ZK0!(T1A` zkO^h6+gkkJz7$G-Gno5A=!LRNOiD_X2XR^Ry3v3n`FWdTQ*OVXG>ln!48$CaR#AV> z?)4Ti9-=G~zfTpE_ed7C=Z=3fO)Ghexui$9b+(b;8pnwO)~>9|AFIU7oCb;6^>QeJ z6;42W(o|ph0qh)(`VGUZYj1?P7Gv?q9=Yi%w_L4ni+?u>x2Wv}G;&b;!jN;E8?a$N z9%wH$8V|0A8rM;OR$C~a1qHEy{Xg1yb zNq^~KfJkKY%ScKZfRj`8eaGV{fOl>v0XXs3`A~E}rVDUq&fJxpwH1<=P6Ht``ERG=mX;c$j(owqAT2d0RJ!kQPc<2vR~OjM{Jc3nE(C$N+%J}Fu{ z)qlpDu z@42umVqOJG0_FXiv;Y>w`#WukrBCSJZ254l({bodlyIsV8rs-EZr!c^QOOp6e}B=R zPL+N#jYi(Z6UCF)8!zlLkMhhB62yyR9Jvn8FO7|&KbMxWGBdeFMOhD%uPLNAP6GG? z7k-vy6~=gx7b(G)cFItXOZ=!nl>HFhwW)1snl0I}hLb5bdAh}qbr9bEKYV?6IMsjn zehHzJk_MR>AtN(eY1x(RolQpe9x2+C>^K_8ILPK0r!^o*=-!P5Pq?6vX7+Fo8>&O@XQ{+> z1%w7Lq<5hhPpA3hFX{rr!u$SO#~B!;1~qzpO{a((GZ-{M`|;%98qu@Em&SA$DVVQb zWd(+td*1hN5m4DPB_6~7$|>w74D(Oq#2qQSMSvRS1@yIWA%>iU{b9XqI-uk=CV z0lTzc(4F%i6OPj!sIrKtp`_thBG%E=ij30NS=gz zvsqLsha9G-ro`0qAgHJF{2E?vKgIIxKqREfR@kr};=6Z_D6(REp|W3FJ7&H~{Jex{ z1fbn;e!5MFrl1M3%P!a2TpyN;Z?(3VkC>bklAa2Ao%6=`>AS1PMs4%;7hqEiM`w;{ zFpRZV^Dn|!CvDju+7p;DM}Rc|ZQwKjJ;f!q>34O~KO!6-T6JkwUhS+G^Wm!TVqd|= zd}0yCpUylv87E+d_flTr{k5PgMuVqp!)KSQMmfCK0c5$j`JPyS)j^XO=)Oja2g z{BXb~p?yY$=}%v7(gsI#F`~H~#`XD?JnCVrO@)_!UnAG#z zXw^2R+ZbFmw+BUy^F+rNx+y+1Om#pdCp3D?v2vp@?VjuRQ_HV6IK%CYq)QmLR8;mH4d%!YTa= znH?e3$~NL#TbdTXWJ_kEeC1lkQ@Qn-s-bZ`KGmY|a2i@$0X{xAQ}!(>Xqj~o;6#sc zWue_z+|&boGrQ72J3})=>#J~swD91EiuFMOsR@_GPOBP5kM7f>?;7N`%0}GNqhe#Z zfzD%@M~xk?+YJ;73g4ig>UY3x=5)JLxftLDu@9oW@onx?k&NuYHyS-{>A)cvK zoJtZ$jr(-}w1-X*Hfc@PXjl=KlqxVe_fukX{})q`24*mRE@d7WAA9PVG^eP}4n(NO zIf&Av1=-s}iNSdt9b^+%?b0B_1#_&^hgSE@BNO)f_fKn%gBFX6V{BsLc}7<0H&c|d zK>78olA$=oFh4@j?(-Q%QV7E<^Q8xx-;okKJUFQ6?3|m2exG%{qW0 z7&(;8&_A`XKQBC%qdFt)r5!;m2i|68KCcm|GyrB)-2?lK!hpH>UXl0qU0+B*b8(nD z&FjG~4{1OPO#W)7vJoQ>%#5wO3myj4##;9F42 zI|U%7bcEmwyoF&XxUK=Rq-yD_RZa8c9OXUM)t68`@EPP9c(;cszmoRydHDdfm+IFT zdV$tq4!zG6q8mkMN5*=q^QXOtLMY9QHl+AX@1YoR0A?NrYEcIaCwSC4!&3|o3{=BY z9Y3{KBP;La%d?1%bg}utWYi^8wr<`<{)**(?l6?~ZokY`&;loCX5MW2kzL$R1qY0u zTIB0lz4sfVsi?$!96%b}{QObN%bx1{)dQdmPXRNyN??xY`iuhm0A{N$yB=E-M}fZee*DXQ_Dla}DEI{RH=f27z6oUJ8f-keUGMiOW>MvfCD8EV8hFf)Rg?_LSAp%M) zTm;i%i-!7Fu!}gp=+%Fpi~Yojs!rBU08ph*e#hgH7*(_gZgpJVeANvN;-<_zMLsm~ zS$_-0GR~xFAJD|wIuKNpl%CzWLz-Q8H;AYO{y)bOR#k|{c~ft%V|tVA_oiG6OUrs& zPp7yVGh|kQbtDsW=sroW*Ov0qy}ZZv;gcs(R*7C0srKyIaJLse{j)A!Tp4=MQ9Xsp z)sDGO50BKqRkOTtCVKTI%x&O=jayQd+p%n3pN!IXcsf@v<=FIds$`gH1zz`5P6Kat z83cc*sKdvzFlw{2vlC+IlW1cwrFF4MK%hAk#fV#4VPTs$UoYI=l9X{#Y0xYK7vwPU zT_Os7*ia;0&wMqtB@X;F#Ynmqy_Xsm%h($Q9yli~cP&|b_y!n26d9C-1GzQ)5j{Od z!nyXX?i;J3Y?9ZcrpxA@uZ_I^FEan~knq|CGri zBy{aVRaMS!R`&xOZOz>PbWbz(ijrPn>$H*3Z5?gmz zk>=w1;=Rvc>_spQ1PCFp?Ho#z{Y}*wDirzMlRkLev6$u z-@L!}_sIVHr~gaI0jNz8TGmE6$GVZNF^S<9Nke8EQJyU7b(l0aH~+Z0qV7LStMT~7 z;(a8(b%Wm!7*BJv0>|(o??y~`IEzQGUs2kl<0F&m0jm*d-C6Nk_h3)tQ!sO@Q5DCF zj5eXXhK_mt{B%U7J_1HU=cbqN9;h#CDGH?PssvEnf?mob1>e)d5B!c-?P#yLq1aTW zQ4Ja@DyqyHw(coMtC$s{%7f^A{eRn6&m1_}rZPbFkA|hbC_^q&bM55Xm^L6O%RswQG8~d+h)_>9_Z%%KZ zcWs}UFrS3IJtYPG<*CD2t#47jvtJc4t$~hE)l+`ZPoMPhW||KL938x*2f&`$z4`k% z9Knh4aba=72sLZe#bP|p>d{Z42ts`1g4B^yXiNORexE|ajQ3Nxq6X6xXlNi6_TQ!3 zW^2=&A%VgsdVRIMQfyDt%xmC6e){}5F3AZ{z)MFm=;{lcbNpL=iX5^(=JF~C)?ukq zc$KdCxaOvgO#J-9T-4(VGg1yyQ&Ygmfs6rGV`EH96YIHtSv2 zytkcA?`m7o0Fv4+wWqgFA%wUmPYM@-6b!^#VDCB~RnA`0Gwir_%+Lddry@btGW86T zAQhXfG2U$2iw^QZ2WHv>3Cp>LugKF($zLiZ#GZkHLG`YUG6BE%S}Vpq1#MKW2USdp z;(o6mkHrVTW#6r1_=(h1I3yyUCNsziJir~RSGn(ZU}g{GXa8GqG5?HH|J3~ypsVj& zWRYk*^_NNt2hvv=uyTxJU1BHllR+n(S~a!5Vx}wX4x8&2l;`AJG4lO+A&lSkl?lco z@IJ{DEg6n)%}1E9i3~tCHq2fO@BSi={)~!@6dipB7C{k6mphjTOR!g$5FC8i$q$a{pp`#gMn~(uE5Nx#}Ba`C8`f zgwl{uw*cIO$shY$l&1B5`ib!t!%F$DyY@@7tWL*>q2;q*`fXUOfcT$7Osvh!(p97+ zP}UxM(6`8UeZopk%3@&w4y-Dy^O%rqpIe3jql#pbR&3=&ZcXjDOD=Q~Hs@yPT^qiB zJ>BPlOw7+DQ!Hn~GoWNdRsMZaJ=XHtyC(F4%77vyQk=2V!+to?CkwphDrZKJ4r}4=7sI zsbw#>wLYgh6Fam<;+-gR)Dd?W?ZLa}v(oJoPF+zs1hwh6zzkV1Te+(vK6h_{iaf?H~>wyTTNZxVE3dT7Ipd z-AGub02J{s8%LJbO6RWK=SmFk@4vDC(X8T;po0zpBQHa1>vnYIQCJ{7IBUb$y?p*Y;A>@w+4+jFF3#mTXAU?6y>c*0AC|z? z|Ab#zSWs)L?bA?biQgd!z%8fVUhVsb5P+d{jv;0z`&=p>!C= zP5vhlEeVpb_EJ;FcG}U|p}WBeo>CWtCBD->y>rXyB&^*az~)ewS$O`g@d^f_FP~AF z4s`azw}d6<`GVxu`}PCU5?0&s23&Y-6Lkc2p-zZLRF0*(i4KBh5wCuLEqynWNNU{O zKZy>=^>WQ%Z0)4e3;5_nBKeV=9oy{rU*VD^36jL_mQnN5M32Kl5I~xtL6y@W(4{yZ z^o2RV031$Dqf&NyC|8#Q9#FA{pRTWdX2sLp1A!Wbd%{9iI5kl83_@g!1olRp08Y!k zawyJj;Dt+l>`w{7Ko7F{=~`%o>QY*J_?YI2^&6OT1m_Q2Gp8uqyyk9w<~qO7V)J&>Fy_UB{; z?LgXtK(0s*q7E-Ga2inRr45&ldk@I72$F5W*1zfqby=Ik;$mW)K&WlI+v8M44S=!G zi9M(^Cm)!fjtJyfl_Hf@kMEqS@FUrJX-Ua0->klV7})D&6gSLEkMtIi&VPOYMYPS$ zo30e)Qgfv(49eShNx#Tj>Bc%PySB`yP&hj@nV|wUy|_=F3iC+_?!KT#6Wm=0mz6y%<8ekKMhdt9#6Jz zSr{DZDZ)dwP0Q#Y0auWLgdVo-_V^@26yIxA@?>n-D#0xZnSTq5Q3vcRYHw|gO`lwS z=xncNp`XEOhk=)30ZXoghc15E%?OBtDJs;{FeIlK~~7l!})hf>{AjJ9ON>efy^JJ$(D52$o=> zKR*R@m5@%w?AOpg4Y^QDZ_b3uHpQ9jEjwgRbY2;$}G0&J4S+nQ9Ug^+mX81%E~G}taNaA zIDUt(xA*GvFL}X^6eB)EV9OO3&wVpqYs$FPH4PjlRz9DP{Z~LoREc8mAY*1z7C~yn z{2}(U|HR)>bs*N23?3K-0q}a#@m}EOSTl+Kg4oX#U;+MN&n{n#LwcYDn7W}Ot6{@- z_BR;i3cvQIVM}1X8IIr&2DXQl?RRc9Ab|BX_DYzlI8^R_PJAAs9tx=|796KqVq5rxw2Dxe1ASP zevWvRIGKS&*NZAdY-6sgzz)xB@_=dmbazi%8z(FveG9bm*wzameNx52M2QQjma1g|{1eBxLI5S$)=<@Iu<{a;L&4~9;Duu=sT;}7=K}YBhCR}%eDrqn>WsO|Ae;oQIVLRQfNge z6I7}1-O>5#L=gF}7ZOA`aFq6GI6;@67b!1@Q`FxF+GHmv75llmUI)j6!5kH8MH_6w z_MIY}M2rqJG)s^|Zdm^9&GxlF?M%7c{RPN#m(!GIk{G}ZRPW%nBYncVc z)P;6fLtLb`5qE|bdUiR+^&VD*!ustBv@|JW7>B3^KIR2)f|}3F``yVoIZjRdfM%TO z^C{Lg^7@qUQeyEC3Akhq#bv9He7CD81cIV&t~sUU-;eu0{^SoMV*Gx!gBrvm;vg)o z6GwLz)o(R`RCr6vb%5RWNwaGKfI;CYFV8Dh`SUYF3K#V|z1vTqK$@Mc5m5H^E!%xD zwsa2wFd(c)$|cD*`7HZ_J{Ux5$Qa^O?!eY<+y!3M@!~EvHn!RnRbFPh0v~#kAeQgV z%_o3{Y{|gv-Tt7r*+!sj=JrAwd1}`dAZmp@CT5+NP)CtX7mA_qMTCy@UMjzTwWzby zNYx6znIER*&~8_06iUS0{2z~5fndi=4F`n(dCVP$K#NrY$`D{(=Fv7LHG^nr*OmL* zd2ou-7rx?L{|#@LX9zPshJY!BAPg3O^-oa~J~sZSn)Eh%7NS+K0nEO4TIbpWm;toq z;O72HALF;Ru{4;OSD*VtECTLqplyyHtm?CrMz>{w0{|++3Oo^Ld9Aboik0UL7%!+g z=-=KTx}&$V)5b8o$91;DEKIdje)3Y)@uS) zAHTFgzl|W6q>#WE78&|CzM)qWh%WBbLHR=7`09V0jPQO^Yl_<>haOXs$=h*2bFXokMw5WC;QtG zvJf5x$}Rv3{hqYT{^6UE23BZ3UW`8QBSHpdz@^7MyHQy1p8%YX?{U(6`ce*TR%uZ%;Yj@@v$EJW(>kM9K<4aHbOcb$ z>LLV02C~%0V_>d-#Om93qRUZR7Pz_hykjn7uSiGMP7mU$ViO4s%=HId{<$-Ov~Xv7 zT3QBZo?LtJ%WT0DEAb9N&9QWd=|>4XBbxOK^lKo)IBhr@!Jk#JYO4((>e2FxsVOOX zRsHnVl~4z%py<63?LA0QagT3-fq_P6Nm*HUZ6yYS^X(Pu&N3b!9ld4e;5`EiLQe`* zEWavXM$g_{@c&0hB~8XYFQ4<1TkC=bFG!WZMnJ~lFvv*xX(6{R~@C*C^|xgvCu=w;_|B&ok+ z0P-XQ|1W0m8GQ|t<9|wK=)V!4mcz`y2#ABOY15MLlf=U!4xY-%Mjd zQn@kdI2f=w98jA+f2%vnc*HjRy24;j@v+OnQ9whU^@14%sQqJCY?^nh0KGwV?x7_* z3W-mRZq|c~P-y5)mCdOE|6F`cOk7-_nPcj{(;Aq>4Qf}eMlNWYFx+ex=mA_M*Shi5 z4xh-Jgcg{{2{l6`eh-e{Gq&(_p| zf6c*KQKjs6dXJl&6I#bJdf4B@!_cBDZBp5I^;y~G>Uhr!Su>(4TJSXqLWKdVC(P-2 zD^@+0yF{Hwpd2)(OQCrmj}zT3c@_eqgtrszhk|8y7?6b2bT@Gm1AaJ4YHCkby1^<&>luPFq803NdJgVw6+rrzTyS;Ejy)|1JUtWrQT%KP zdH#Y6^-WB3KF|7vBZeY2M;fH(9^q*jPf2aH2W&)xloKOdrvJqsDY)dIDM|?=+jF@3 z0Ua+pC#U5%S#UwFe9%*CW)l^_kRlyUG}@(^5e@=$Xl^Uy=i}6X)z16orT<++c^ZTe z)F08%MEo^jeGq}Q=$o`w-!DaFWzrg|5y)3dioph~e+kgZj?jCD2av6*uXm;1qwL#j z&8GZw82iEHfb}2D$VBOW2!9x}oI^$G`vqjx_^Un*YI|G#66a*!`Nm67-CNb8Cw?x zXQvH}Tx*>yfobRiRwCZ&o5UIL>GGn>k;J=uM z^oxUf_8wQblv@|avn!35d?rq(KC!YQx?1aJ3D?!PTH+NJzFs08pZXfY_%s{EIur_D z10s^Aw0>V3F0V&phX9=hM<6cAN=ov86S?!zGcax<4Mk7~dBHtp3vK$jaKsgo+Lfst z^}8Sxop&Uib#G1|fu!|HvlDN>>Uci{XP73N+1KndRr1Aw3ZxWmasglnyR9OaQhWO2 z0AjV^Z5GC{?6CF|iVz_|K@-dQnX3KD{{EY9@|qcLiySh;%}cHV>Y(Cn0J?y6XrEj= zE@cNm-3dM)_D8%?Q$9M|H9!F$IIeWh|4?ckAA%WK?MtNiGk^vn%e9IaTv*Nw>>cuzvE9NTcGuF<|*M`PGdD!?!}>q5K{K;0wlU|MRJ z-mwYQrZV7&k>_@8(Z47Xq3-I1QB;M>r|#`B$WGG%(R=ud<$>lkb)SE97ZLi0I`Dnz`zk3rE=5jX zr|@QML+#W1MBjuH544eGVnmH4ym5hT>med zD7ymwvo}8%Qr|_nwduZMtub)~M))jX(U$?njXW3d5>C6#hVc7ElYqz^e^P0#8PE;r z%x?fqIOB^X9x%`2GTztgrRP+*`S=ztSJHRD0I;1yPR@92d|al9Yn$TzJB$-}Nme&O zt=DNP2{izUl9>EBV}W$^zV0y$L^TElX=b2Q-y#^j>M6V^l-K(T!Ypo+I-R5NGlEaC zVgBrgs41^em=#Lydg*ZuCB2zPyT0t^;Q*2h3z) zlKYLHz>Cn`SJ2cSzt{-umauu%Ujl_+&*iBv4`(DE|D_0Q=N|O@L(#<|6oR$cPE%s?4hu~V$<($Q z9W>;h-(Sp7gIzJ?naB1Z?e*t9>rlc+Ak?yaZ;Ti&XP~HJfo}y$TjmyP$MS_J=-nB# zf`PU}YYW|Sp8q6Vpva8u3dy$#IzUvY&B6kDMcHXx;ELw7p{%qUG3-5|-je^J)aXYx z42CiBF5L+$FoS0U;4Rm-l}8cOu|Q1*#|R;Pa6nve@k23!5z&;>@oh6kf)$Aw+rfS- z7fU1?2VO`@O}&JuC3k?5=oAQw5=6<0hT=M6PzDwexmFEKyXhgM z&TPBD0Re`*V+&Bzm_b`IBXmUuAK)Ai>N#0i-ygdG;>Ck#XJ0_c$Cb}AOJu!w*N;%< zFFC&ni>yR-jQBHQTm@vX-V=6!BSCNI<};cctuh01?5$F8IP$#7ffSRfmB>()3*E&8 zHnB(C5d>LUY`5fJa)`VMC+R$;12k>>41t3avsCy`LPhvU0w~5IqLK|Um;q}p!>eHC zY_I)Nr!wmKb9M-Kdvt^kBR|$bCB4{T=G-8&6eD2s*05?asu23QlI8w~!TU0yr@GSx z+qf+ZF(I9zEm?i;%D{V|rMBePFFZB!NC(=ffC%;W?9>@bQs)H~|7_dyqeNbtK{kk! z+hJNMqThiCok#~ZeMVqJm9EkSCYXrrW0n<{5@OHP;Pt_1z$~{3`@0-DT@|;7+ZRlLfjSG@L=2(? zjQOETFTIrF2gr{XG#08mHiS_twfSphz+*PAixZ8Q+Jf5bE1a=9Sv|VuYm9TNAT8gA<8_P*H15yFi>xZt~;k|c~O)KtRAO#g$k`o=>`Kxc1j1JnKV;OjMho)k|p}ki8 zD|@V>kV4A(l3w1yXD;q534+{n6HDfH_!obT7zxHCu!r&ao+JDne0tOO%-1}2ZCx`h z_)(ccCkl~+xI{lEV-3Xe9gGn)y}b@IKxYDW=lDHAK*D)2j6M zv*|8=XZ`j&4l$UV=qblt-z5vnavuzml9I+KO{N*YaA?bn&9`m+M!&k`zH0~~>?Us# zL%i(j$O%d+s%N0owA^z8c$i|q6 zUup=(r;*^qX5~2rN{sW&qoUdkqeA+_$G8A-SIs*!QbaL{8C+KoGd$#HzkX z(?{zS)Z$@($=^%knGTqadbv>TUuP@$9bfR~#i$z_9fqdD;h+x29bFqIS~Ktev;P8c zlk=av*|~V`E|nr!q_L1UBq}!Y!W9hPMFNaJanreH9Lh>Chs+ZRhOyr_U=!Y~m+@WBxt?Vp zp}g_NOZyuyT~rO8(<_(ZRSjOE_bj5W)bG(2KuZ$g)H4D*@$3O0 zLc&}aPY9ne;| zEiA7?x*%G5W$;sPTbdTB5P+*54wVM(QR>+xD3p~GrM+G-ZGn11G|1gvj}^YNDK*si zM9^xP-%#zbx$mkvQAG+Ndk>&{60b5yIKN3dIX#vVUpc>41#5&1@uC|@H0P(iSK)1F zyLXGPYV)>pFDKa?nbJ$&plcVV_MF-r6T68> z$29Dfkj7dWBd$lr@)L>?;NO#8(*EswT;xkD%Ok(p$FkOs4S` z*exu=SUTRsM=iUGIvT}~^!ORrJCwBM>&rje0_-{rr?sA5m2w>kU*A~jeI*xc=L7S3 za~LQxrFLa#3pCalOj&a%J*U|)io1#{b;~d)alXK#m3fkm=epAukr9O0a#*V9j z)y_l9wu|}X34DB1xIu~hw(>QHVq|Cw)^2tNS?3u3Ypg4+35P$`=-3dE`3)FP@j;kK z6%cp`+3m<4FkHR_Y?x0XK8&!>1kOmkuUbYa%qWt!AFdD0xf;s?;V&Lt(OK<3qlKEX)0YLV+`q z7qMSRVaXsHkpBzF-DZdCcmXaRy87nwfyUu)kSBDR3xj?h6ShRS-NR4WAP}dm7+HE* zC#z}~aH__=Su1Z53UOcqN;-V7;3?p6h}y#^z- zCuEVpVplEWMrHu6qWX<8uUkpU$YR4WvLb@9ZTgeS!E=RvU7NVsO^6p9U}m&h?7fh# za9KIY(AZNA4>Ypmv%%y;S5ws(L;Y?cI0)e(Nm@p+RsKc572YrMXr_CT-6hAJU}HlT z+;Wpl)BDN=Y?iI`M8vlJiYa{Mm^Y_%a^xXe#7w2Z>;@>sC-incN2)t>O%}J}4O}Dj zKo-xa+|v0^M$rXQuLfRkB}Q!=xYcH=e3Y@`u~Gl63V*`Qxi3FWx>rq`tur zDtoP$vOe{2&5gf}nlG?AFbxLVtd74isE3{K#K{N7MQPVFBYE+<_8svrVj)g?R$@WW zGXSK(9Q}J0N2Or0MLVUIZPRLm?%y0n1;m+{j9F5a+FkIdIl=YGRdw}tUh*{`J(tFB zvr$*T`2Dh)TJ$^QeudFcK;EM3(hx^qT!9`oUJxTI={iCIQ` zNep>cvmO1ue9|uENS?v@I0?iX7fdv%JyVxlvi-MWBwSLmY2TE{Zd9ZNdEmalw!sSl z>eX*YPt!juvWGd)bC@5WteOJ=Sioztpj}A%Vr8$5vE**QjP^QcP%uxCb~h+91jpxW zd{dIQp+U~%?(x=_Wsk zIuxF+nc*#WkQZKQ<&kB;+7Oa5%$az_!p>%N)@|Vlez=n}^s66x(rlV#s6|K~Uu)$8(aNjU1kmo7Q!TGy}QOKjx zw`2t+B{tZ=z@pF9%VEk|Qm%4)^be)z&-3-UR}h=n$YaMz^ZTbjdu;&~QA%!72sy|( z`9ai|IzNfih6j&I6Sc9Z0)m~C+mjG(pZSr#mUqV(2hyF^Kwko+JF!n!^ysegt|JJ~ zPRAqnz?lo?F<$|TzIMt2wktLj+UrN35;%SODomy=nCLyjfP=1B89REuGAxo?3^KF`&sB;1qTD6;!m5)>kf33g0u#^c3lUS)2Iz5g( zWhK&cwZg~TrF<4|Vy0U=V?zfG@c9|6O8}|W(BT`wc-6BQd6QoR3?ewQ*SW=?ZFQDO z<{49uw!JA1&3-ZZH;Ddz`SP}K9(+~*9tCL3v?(+73X~8cCO}}9U3$PdNyw&&-3!p` z1fzDi!GoJ?(;j1<>U)aDy9-Eeje+z@=4(Ryn7Nwa^?lF-haKqv#@8vm{L72ey#lIn zBBy(IcenBzma@ajC(#DBKt5Un zQ73We8Svrz=gGAKgj~MpEi7dN2!>}gjK}2HCP;}_Rk#UvXIF08ib?A;-K24;8BEe3 z?dBmoaKfnNOb*!3F1_Qm%nHLB8dxr5_qBO7BZiiL&iwYDioqKkGp;(iZ50ABbvu4` zv*&;@(`Z*g1}ySbNWY%OcH-iraGYZ$etiuJ$LEldE(0Zu(hU%~CC)P=Dmai)yNbXe&=wjDAwgDyU%{|W_7vq7SRTGOy$+!`71 z&u)qZj~W)tqX+vQJYDeFWN<8dYN}mI=>Q*{`$=P+nRoP&nrW}Bm_2^*W_`#EU=6%| z=hfJi4Q}DivE*|D?LQxPOWpD&>IHv)4bcE{dq{9I65ppl3@JG^J^K~_ipkIk%rHfzYr1IjX7NYBDXewMDc zuzhpNATvVBE0CRoL~SY6Bk#9lZ|m>4^+uj{+z6qh{Y?r`(0=hY$BL zG_t)cv6#+J86kcsB$p#$1u*^GJ)d3wPUMI5?yvJ6VtcJ1CLqKRv^4U?X| zH-RfsM??%>z?4krZ{nGzzXNN4Rf}d{YcN{$vuNMN37=*UCHhAQ!X%~K1rQBvvQqU5 zY+o@L+az))dB{n4&Ay?m9M>;jiwfxhe0Y+xyU5WP+}xEz_QcBim9Eb>tGj>k1u5XQ zw^v^7ZD{S~bGxbBjPbN-T>^fmzQXis#cO|QjW}Iaf+1*9iv)1aM&y2_4X0!Yg$B+; zRZ%@;?{6ZHB)-Sm^k}(Mf<@lj_|VrrLqvZ7`%yNnSN2y=i70bLn z%*-r+FLiVIrZi1{<<)sgTHm6wg6qDpYrIm!&k42}n4cm*OpcCk_!?faR%hZx;_`J= z_YQ8Q3%O)4KH-Elq@pjOpEBR|>aLNi#>s8M#_#j3jxZDNYu}Y1j*0S7r1Sgd;1Gvd zb6_C?8IkX2nz$|p-B*-&udl{fOWFy9AVYcfCa$oKbac<5lPr)IBaF(uV=D|>!F*Ba z8Ieo<`c--HRJAw}?z&{y4QD)WCWC;D(|4%;>UJ{>SBTGS6UKL+L zwx>A5XFrqxOg1He0P(^sop4RFf3JMzP6uadOSPUR2NI{gCPssG?*0 z2Y?ueB?qGHCp&3yWlgFMQ6A6@st#qIl z5euqDx;gtI{Ls8Xz{=ne321*|Wx!>hTe-4Hn*o>^!400U_*1h5M5sg z1%@(Y`Go$NcyWzW@cQabc-Ak0IcHi33e)M*ke%ctqCi%&3G#Gd-Qt39z6KgwhG=~ zXok1V<0rYf6<6m+Pe|^^{nyFmipp}GAUr0?qA1$Roqi@Q=9lWWQWMf1aagqDRR3e+ z{k0JE4R~o_zU1Gdh|hP%ysq=iN}wz!y61!!Q2!6V*uF^+8-JY>>Fe^ryhx@8sfSH_ zR)R``WGi1l_!d0Tz*jDm2$joF?NdNitds`=w$@N0)-w(0ca%j|51&QAgt~_8_hD9X zp)1u*1L(@A;#|tFQHSkLJdIng-%>Je64GI^WnEkrQ`F}AWn@SFD>}7>sT~N&gwS}U zp1;*X$Bl3fKk5Sb%>tHLyN8a1jKgmM6bBV6i1{ymixv>@KC;X25cjo@ePw5M>{LHo z?NBVUl2To@wW7Z%d)O{Y_nl78P5%wG6254z?6?x-$%`(^2RMBHAV_Zxn_P+(?1Mml1tyxETo&F(G3%IIKencp2z;E;o&St+64L zkiZpsZquBSEOmB6SL)1}4woa?+A=-);3;UIA>(^x?BD1puxrm8F9pcFd2beu-$2|J zA&I*metq%rGZ1^2TZ?$jns=6Y<>605M;V16eX&9oASnl(JY%&rg=eX}d)1_)ub)bf zp-WR~ZS02aX(^cM6(7z)~N*y%vF+MEt@>8C_|0UDml@rv#f!Ld&Tl zSmd>zf+D=#$VWB5Gy$Uzyu=F%Kj>ctz@#@%^hHM1q_{(OI1oVZKYS?s(w+K;9j|_2 z<{@6KQ~EB0=5W}sh9sc(MdVBOwFm|F^xv9nQ(>{z6n&ik_Ps6BNxJ&_A`mCqM6|=X z)R~|RpXqNs?dEtGcI)Pg&i4R>xi=aD2`UETne32fStryt|ELS3UWiSrp={%8< z*za1v0ZEb<4NAB1tp9Gx5`}evJ2i>5rZd`g_-%RuujQ?kSqlWB9<^PiH$qzxntOlb12?Lz{G?uCUl zM^V@9+h0!z1Zp?#ZV#|H zb4;ryTx&`w%oSO{z^?cXL#`$6f(Cj68@r|ZB~yO7|0GnQ*2&{gxui&qLu{x4f2Q)AnkwxmGNb~9*>j#OB->}Kp_}#XgL8y<~swwVfqi6|^&-vOvf)Q_az`1HUT#&|O{GrB?0{eFer+jX4#$|Hg@a4^5-q^1|C z&cPui3-mvyR=3b_!iG$}dRymS%55FE%;?Zi`%O7?_t&}o(b2MeN=jl|1`)BQ5`WS8 z|L%G>RK9rC9M^xgKV}^nY0ZdU2T{H=gzVU{$tQZC*6_H?+cDe+2-ttmSr32GOB_sJ-eC5Y+dbXftFC};C!1fY6t=353HKQ*@(#_-ECej* zvJy~(`$i!IAd9JRjITW;UbBX4?gZ|4$u4Kb&9b0tFRhKzv}LdBwNpp0*@iy+$2k7? z(XK#jjK#A~Wc+ujk+3vOmd~>Sl9=!`HxS;claP?qN_b~1!C8)760OcE(krru!auS0 zg@lGfPg(5H(XNK#TR#lk*F4~|7rgS*JBxy)_8J$$h{oE1;(I{rA<>=R`9_g;1#)Sb zS8Od~(9Jzy&u|t*>o!cl9d4WP(eqf%WmFOOgqkGU8E0Q)aVFFOU)rhpxP5F=*s`{I zMjE}i2^4;12<_LTi<@-{1thjPJN_q<0!l1+ANCqJ9418LasT14>LpzbyzJ&_`)cMf>_=&JILj#s}J?&b`=Y|mzcrLdxxB?w__c{;P z^Fgie(%C%lB6?um>4M+ia#nT6Ru8qs(q(1N7c)MZahw z36yW`l9z!=^4S6H9a;b-MDH>BQ~HG}V4Cabp<-f^bV$IcTN*A9N3wEsVMs50vI)8@ zm4Auizw?kAJe{GH;=fL{fz2dSR7H03eGod_=icfUWm(h7B1bG-g9H}BJ_AHD@uBk= zi6FA>m#~W@n4J0<0QQ1ak**`(&uV2EjPA;?prq*b-dS#@*O_Y}d|W3Z8&;WjPR00d ztSZ8p7LwMUj#>ne!`#*s5V^oT^(=&oTGI|{M&ZQ@M3YwXNJ3a2=+*YJKrk=wV`PA_5`n7FYhB#%{7+8b19EW{$ zOc-(b;*Ls=cVO}wI577+ToW#vfHBRh_d1vC0q>jzJWxvVQNxKq`F#|R=tY&lf0qlw zJ3n(dOg5V!5bj+wgqk1Wzg|nf&dsfx`(^=MVO->37~ODx->-x-!yW`$yBe6jXsCet z@G|t;KNOqI`Ts^pilYct`9D^#O0W>>fna>O@cN}fLp}Jc9Iz~Bw-&N1n$SSPAnt&` zb#D{}z2~iM06>+S+ukj+V<*?P zoB#_OC76*uMNDr!r?^nQY`y+#X#8no-=B8}0Etc#xJH!teM`~aKOo`cms~@whHVMoQ$(naQ7uBY5@-QHIlDVh9npX z!`m)&0hG!@mbFJw;wC}ce{I%*x4L;LU_jVwYK4?ZDlg77_T56rk%`<+eILjqpkRa* z9p~RrU{fm;VkfEQx5{5TCCbWyZ7A=j4{p1b0Y(!3h%7Kg;1{H4g*Tx7Q!4}edk6Fk z`OXc0kfc~F`CZxb>K|^M2)vI(_X{!miP9Lw^4&nGs!4iIJg9{d%)tHVdZtdJfG^^@ z?iqrG;@li)HSQ55lZCheP>LPEyZ+uWj(r*!(k0qGr4kQJh_cnOjQZo>fRRhEAkk~Z z1DTbSz~@-N;{!AVVS}p>0S4jw<$jWOE%`y&#v<-m;!?A^98xMY%W$4Lr2<)!8)mnH z?>%Y|(t;6Z?Js1{S6BYwOY5tLa47+(68Jqoug=WBun<-mvE~`QYu5GmrNKwQlT7U` z%6O!uSOF9sDt7ecOB_too290U6rK@*TBJTOU>tz&(Y<-94IMB2^CN9f{_&yhWE37u z0w_WS0F@upjzLGcJ@sgLcO2rz=82?uEZn@CMFc=~Yhb_{&H53kFaaBOry2*r^sD{U zjpNgVyHs=ssY{~y^tIBpv-zR=3HO;U*LIyN5fH;a$_MK{msDy$>w7>i>bmy&B6Z_q zQe-3y;M`h&lP==2v~fgEhlDNmRfo8b-7k`nHiZEohZkAtAHRdubP6{%WoXkFYSl=Li3gWZ}>U z#hgx-1P>);A7_=F^H={Rvw~J7LRenmuhAi zS0?togAxBT=y^c}s^#1M6GVBoAEu$`bUyQhizx?&Psc=UpM%HR{(Y(KFs+|k3(O{8 zXC!e#Dx7cy63DvFixaw-MzB=Ua{7nMrU(x#Giob%THnx=FYWH*?4ET zBH5Fm76iP5ZxBbCj^Frr?*Kxc>Bh& zw?dW^>kJuV`Cj;}#9;@Y zUjAFka!3Vg2+?5Y&Yev#zz&^r6^X*gRs!Yf>IvN8D{o(rhG<6xu7Bd-UVZDuzBT=7 zfo7Xg9{g*2Z;<{8lTJdUw@7(27a4^^ov6v7zfU?0CtS+$(^KLD9vE0d+RffAE2U!Hpo6sEt;!liuSjEsK;g&V+d(u3 zJo@XSgjAIilv%C1BoAAk<8D_?47vPJdc&UB!G0^CE-GH}=g=Ieih)+S2#EdB3nl>w3al~g3?MoPHQLCUV3fzGG7F107oJEE8@7mVn_Tc162YtR zvY(JTTqu?)KXM8gjsZ~UDsn*%6{N8I!60^1u=Npw9YgL#kmCtFMjNg_KQbtS>>Z<2yz1|5x&#)A8joe% z@~BHepRNexOx0z4A;K`~J1FXzJ#2HY0+d(RfXt;ax&a-!pk^;rrK34v`TLGay1qr! ze?uAF9jtm1G26WgK{g1YV+|An6Xbw+$hvs{MLeoYf%BP( zyG6Vh7$S^Ckp2O=N94h*~x0FELz zNrlpyuD`mv`p_`!%zCKhIt@b=L*sz;pP}8LlZd4c4n~S0Z3>u@>w!>r0N_SM&0E^S zvV!2uNJ|-p*jAXq=64lQcj^SG)nmG0sxUx2{RxYe=Z1Ruf$ek@&s5YdQ3KTKN^>Et zj1lj`*pLT$HOq7bGG_en6~B?*eNDFD_wcTV^~9T>JHECjX-BQ}Z!TZiEOL1#V%MgE z(5(jj&-_}T@J`;lZ&A{1?995+K(WVf$vL)?)ZxM9ZrgSmO!tsenLZmY&bW$r(2)YTI(z2>kS2 zQ|TEQ`M?E^rhHcuAVue=vF^b9X|$b;!m!#Ly}E0zP&FW1;QHHe!^%RsUblVpkJJr+ z;*S*t2JUD~pDm5O48Eh#b=bCLazogU0wC@yyaf*R70YWmbqw{c(VM5m9jlWa$rYPE z1q(S3T+U;S`gMkwf}mxqhGj34lI^Gjz&geg&yEsVtpuF{=|}_HapGJAm#OnWF^njo z-HAVvSHPwZ3uu4`h`ny%a{U;;l-&;lh(78;NV|x5o?|}QRa@1@oZh_u;nyO%Tn@oo z{pYtSPOAuobfwcBL5)$(>DBZfw#j!zdP&f}Id81GH9i%nZ`F5*cwf1B8tYso9Tgou$N zH3=SNPm$?_k^hPXrXfMbN9(~6fyB<2XAnc$>Zm~SdN9jVYYw$9E{6)EDciX6=0d`% zIdu%PlzZ*U&~PNIf)Llvn(*wTjxPdcpsN*w!!*EFuA@z#G^@@`T-s_&YVBF@ zat2D(tJYr8`K+@`aCvltr}s(aN?_r=!gxKsX&BvTbWZ; zLBCbk6)+H;XaoJDMeLbduVB`+{FrRdb_3*;5cvNnd+&Ix`~PkHBFc!ARVqnIWRx_F z(2$I#l1-(MY&oNZhDw9%O=YAaWjiw(D6*BZDG?c2+5L{!siE(Ee;<$g_s6Hl^|`LA zF7NmI^?HuuIG)Gzyz3%`a~TF#bm^SH0g>wzywNhGp?$+aXMjMNR)Vzs9-EirvdX{U%hc{-EfBi+X{O`a&vj?dDB?*j8pjDEd;>?44tS zgJ15~eawjsA6vec@^fToQ0uR5Swr&mU`NHvk5!v#(OH0#{_EvBghdhb?ZrFxF8PZl zxw(y_YN9p;&8LN^KflP4hIBt6LYd62w&S(!wHMJXnZ*2E-{s>^XVXId5{~k<9jN`j z?KH%El|xUx4#JdBu)LF9h@$D7Idj_4WCP=w&>_PNQVt#awi{!a;JTxi5QyJ?GDj9L zL9_GJ_2+rbcUXCxOhkh)c@TM!-PI(O!hQ1RtI^;8S4=i2@LDDbOxa#1 z*MSC3^!=pIx}&;jQ;ZctWYk(Zqt$<}B|q7r@=1c3^Pg+!ieTO|?{M%2!RB##zW0P7 zY}f{+vAJmHZ^*?n52=!Xy*@!fL9K&C0Dux$spgB;_cYK5*#&&+%Ly zMHgtDGrE(s_6FA22Gd4-r4uHUiGBd;)ir;5x1MSRm$BDqMoJ1(Pg1q4_cjQwSP^6L z#z$vSfIVvbD-46C)zB=)Xy1nQH#UpL`j=rFjb#=dt}A?1#Ffwv9Kc^5sDxh1;gG~sXaAz9v&%;QWB+8%LkhQ77J~`pgnn@P-d|C;Yp`kSE zK87IEy2{e-KAtT$#4Z?LS8-2ecj^iBIwR?BvrF*)t$POdrJg*bd0M|o(eCrrgTSiV zHmjM>#}N=>OVea3-al!tQFC%cJ0VuQu|*P!24CfRT^cTL2r$KK|0IVd3x z)#8N+cLI5TbF1+U4`0nP{xP{2R+?T0K7ijhE_wL;8R{+uBS-1ljfh$$Lx-u zPYp2?3rNx|W7Pbm{8wRG!BQd2@bnJ^4%;6bkt1rx^O;Nxnu%9|Q!^5N=hdX$o$k#?lV)P?QLLdHvC6meR;UH9mqN7#OWxh^(ZJz_Ou%M zflqb*fFjJ$K4Qq(HrW!`--&zY zl(ZR{T~8UN#oDbHzOh5H=g8OyW^F%zG>t6La-ANZ@y_{GT-wyk&9V9Qn81KnQ@$Al z2HQ|629hWK_GWlz3WDC8EyLhMhypL%7=XNx>(qpTV6oKScl1n0X^j{H&I>DMSea#J z%3X~ShwK_Uf@73=eA+hHFbtodCuZOuIj&+c2?`E^JC>ZVnp~QJK7tTGZy*uTC1R(I0?dtMm_6Yf?kbyXik0lf*E~B z-yCF@DI0&C6@Lyts;M(!N_#H-fhn-=;WRk7q0K91Aki2{;*~V?LtS%ys{Ul1n&0Z> zDqj5l&CSMLS8!%Tp{YuqH3lox-BmX?;gl#sqbSp3P3!m^-p?iSr`-Dwu(x#l}y+%=E; zl$>(EU-tSc^&8`7BPOi76#bi^Z~N#FX})z2DHWxJZF=fu2t3)KdZ})G`|FCoX(=7r z_3;GT6Ejc?5{@sECr@>*Cxh`2=Zbvsk)v3}AAZb#cqSpUgnQ&$av8y29PQ5_M;r%W zD58+){!WG8=~d4M;?ui*-WI=mUB))36lL6@>omY%wAHFUxRGc_3X`yc7=gsLa3B-1 zHFePY2C@}#5zcCZJ@ad!Cz)bT47Ed~>8P~Te-~V8jdGzM#FnSlK&qwgoreCTN%%Cm z5#1nhz#?q5jFDcBbA!<5QaZs*`XzgM$3|TiP>=Z3XH4uJYF>7JWUFqvRd=5}JFSL( z9gzp#S4dFsMIz@UHEGIax<#EXrQL){Oo)E?T>tNRNBFm9uoJ9L%ph$~!c_np*T=xM z4lQ;ij94%)O?M5w&494o?CG<#hlQY&<{nDz(6jJ5*Q_Pdf3uoo%b<5}j>y0S^xTf$ zU08AmFxw(@H2~Jjv$7zOdOhBoYdw|FOH>#V2BUo~FNrl%Y#DrqG4#8U?z{4J9#zO# z^<}jjW!2Txr2M}PIaMzhP9F?3yuSs|K1K~z@ijlzO?_~B1pa1kz><~Z&bofk*IRB( z&G?C~ot{ll1DCb_HNQ)ra(C4)Tc)dc7`*=?Imbt&T9#99MN@=#CCq@DaRvB8M-|wR zDdzuB7tU(sp#7uiU+S?Buc7!vR(Q^o;U^S{gcj68S1K@Ss{0|OQ?t@QNjT6zt! z-FVYwTt-z?p$0M=#`^vv`PfYaQ^s-dPt8yQJOyTvV+S4oC)_0>Y4+JC* zt=f*PD;D<+9_Dp<2(hJgjnqmjJ$^pT!n=)=R?dQM7E5GCS$M=>5yVsY+-|Y33j1eL zi^)V?K=@_%$B@ksFS|7{o9)^+>q>m6R!um%mnNsAY4_M4OoJ$FK?PaVj2<>}Io`wP z18?Prm=maVIfqTMcU|D42_&WQ%qKQ-xOE0eZ?1^v4f$`G%iwK!xL1C$=le2_3uiDp zCUhI{)s-+#i6tdyjbq_bigx>#r_aMWcFp>UKz$n%+GmHOo==!jhv?ty!xHBRi^02PhP;C|;WF@2Yu(4~WV8YtSG5f@bbghdudD$D6 z79SALKqE~Y=$P5r9f!OJX}&iCf@70}S{D%;l+oUFcBTbt-~YmdL1mbm@fQ1~AM<{I zK8=i3fTZz1Dvp_m+q_2SD!OV4>Cb7pO@`z+8R+<1vtlk+zNGUTIzjdQEj3y#s7&Bm zVl`(y`e-LqYc7j#yu%bVi#ussfQ*?a#FnvUZC#JqkguX28%6FS?Ma~y3%qt~;ks?` zm_9aEWkdC-Pj!Jd&0N7W^OW)Yk07?=gU)|`eVeP{q?`W3q^?!}u?^^biJtSdAxOHs zF~{ZX;XOhxbIwl=9fnr)M(We-*=xkzo!LIvQ|{|IiY!F7ozPI)Bm;-eIPKK)uJ?^{ zb0SrfreiYg;#-prlI`#{nVGP$TNz1Rnd(IsIQq=pF}I-$$$`lJ{ri0&aU;+GNcNX; zHE*YPds~I)AyTw~PD)#BL!t;4ze)?=RookQsKNz>=_+Yj4LjegAuBb0Bw=?ieFZZ2 zT;9i&OWN7asWLma_wjk`wMf>`V%V@+5h2#T6YbURDE&~YEOUq(w6Yw|+)_AvGHHu| zfI$9}fPK{2yyCmPz{iC#OAU9vQzveiS0<^S+*Ey6U9(b4k}j@4T}m1qT*juQFDuE0 zQfy;^M|MDQpk&amy0R-!?MidkrY^|J*}c?}i0qwm62L7>o0aDsw|}FiGFIP2rC3*pzNkI* zFdfQz1LEoR$bq!@2o;N%I)1$U@ZkfO3d5W^>S*(AW@eR7B&*a59ohE#&5&H&JdY5M zEuzUg8O~`cJxm8p_F)rm;RD*cvdVO`3Uh`V>9>M+HxKI4$=r+eUzIBL)UxV9w{AA^ z`J7rF#a)3)z2TI&)~qIYp>ZVe^?1HdG1uhWT(f&KU+eqW=UcPK_dAA8i64Pn{3-Ny z*Sx&;Rv3U#-LWiwd$+PD*KHzhQgL4F@l@{dqp-(iKXI{QhYr@cje|`V2k%~@mL5i1 z_v(Esk0|+ay*_Nr=3GGe@=1L*4bvyTNPfA_#&vt3s9K0eV?7(Lo+BPGO( zJ}x^ftH@?!8uPWcvo=o4!wXvQUcCqJELIyWbG{TkIl4={v*V zbrz1J*;PZ?IN2(jMAiz^st?GiILjjyQ;YgAWu~bih{cFRX^8KoMzQ1Ttp4P1G1jsw zX#zluz14oQhZ;lgWMCZgMrvjW!j{st0^Xs{iCQ5w-c+FvR->0@b72+nasvM&N1izOC~Wfx zYE&t+a)AK~vn8Juv6DspsE$k228;LC*UZ-ucBt8xek^qxtz+w^cb48@UMTVS;9U4I2e&!h%J9doye!0=w(dL*K|_bOnt34UOI3a(_-fPSrgNUD*=F z^YsTWl)*f$aM|(K-pgYbv!&@>xRiSGoe#32?7K;V|3tX}DRM0A(*FeG6QIT-3UU4& zLo$c9x5S5fG!MzMd3Ak>f-?cvkGk|(I4nvzC43{Krt$B zsdp;Qb0{6<&+FZ{h0d->HCH+Z9nt~F!yF2=F|#2fxqSKZ{B;2~&gk$qj3l&Burrck zSaoyDye)(KvL-vf48cLED>KWnp(Ak~+oQO54q{sh)A({C;wW#E9=#FL7VL-1%hluZ zY%T3?dKe_FH7bcRy5c{UIME2S9q-)CyN zWWP&Q;dOU=1^U6yU?>Z@2Pb`VGBkAeb%i8_}{bc111Cb*9Om78A>xS$5w(^4XDFtY% z>=U&tq0r<@EVZg4$;Kk9LajYOEfaO-hOIr-mf&&7#8(Ad2j4fV>if54UM)DecZ=|3 zy26~!-tK^7RiVklygWPsUwVHa3)!_5aZ}q{qoM>v(6cay#aU(Xvtg5;p(bCFx7C* z_4^|-im4=^!eHn+dD;nsy4?lu5ki)^e69|2SpOc!@4ym>bAEW9H@b%ru3i=rn+HqT z_};$93}2)w>d)kqX3&JY$b^E6dD|dB`oUiGnZHnlOW zT*==)+S6^b+y7DO(^8%!gS<%n`Jv83GB(X_;nc?S`qmZ1S-pv;yxk3z$s5SQ4~V58 zzusL=Nw`FFY(l2=r|0u{1ZgTsAc=M88dbsehVv!jcl3koi`hJ!Gv4F7%ypt7et;NY zKGST50h0HVV}&7aESU6OItK_iXlX@<$|9AV+GB}i7axVJkAOZ3@%Zk;5W2n>7$E}f zh@XR_dwy;-u1h&URX|o~OQiNl^;%TjZ09qpY0su-WZAr7%a+40`^L)O-`PG#2aZHe zxkkC?rLg&OAZIrJhI*@yVo{6rPtPs>pu3bD?l0Pt*+<|VazdQ%b*^J~h^D>ma1P`a%*EUjifCr_c2#jShdG`^8T(6SI`dI$IK#_Uqt2K9d^H!nAHO z#fC~*wqed3QhWC-C~wcgph}6uV{W@4iq)i^o0edWXJ=Z;f|KbCMML(^6i@V5LBvUC z{WvxA)}0ntbtQe*FF2^wMOupIfzfrfA3b(Vc~f@hi0;>hr#i+zrzQ_1pV-}XFjde6 zK-t?|WDLwD6~w%&g9DimE00*xt+;`Gl9sX*m&X6Wb(82mz23s&Ez92?8|Pvcqr7y*TUl3$&1$u?7=xj$%-Cj(TrG9v1q0Rdb}a>e4S}>o;zAFF>D0Pwc^^!% ziqKYnJLvH85ZJQt_s-aSx1;QdWtND#YuZqaqvnpO_yG;rIfwC-dv*{UC0^|Dq0$ZV ziMwCcI>$*{nqRIR`UJZLE|*&X7Ayh+@3>enIwrirKkpb@;)K970D_f<9hx-OkQ%gM z!PWFjy{QMNLQzd13!o@AdNfe6Atq5ivh7W67+S~!qY$i@s5tQRb>`ZB@*t2pX1|00 zML6cKC1v~nI3oOFXq+!fvTM#LopGVK`%-Mi(Yz$2FG@dD!(t84d!T{!c@amSy*tFM zuYr_wb4jn2LXW6eb7VT_{$$G7C^3l(6)gHHo=hl}l-&zp$u8|6j-z**iVtjJGuIX6 zmaCdqNTZ@THp2{Q?!vW7gHC1gp^eYX6YLV*?b$5rv`*F>OA&QWw`zz6XCe{oqoq)z z_AS76Y^X~Z8F#&l;^=2zDN2t%uFUsT7E*68ztYpi&q#WfFOk?5c8x$*h-INFK!!aB z6RonCn+fZ%m_Fs}W{}$Jw~j&lR|K!=j?U#@|Id*uc@2oIuNZK|((3T(phU|5X7d)u zLp8jO;*$JzhL@p$BBS?{pI#)XF-+{Dv8kwpqz}VhS+W?iwKf$#F`62qS&Ny7lpCG9 z#HlSLkOO-;6&rh}sgP8Alv0#KF(}o8JFicxahTyHvpr=j!|FrD$qq=G(j5~JM0IcL zKTOx#)}HlTWlgFgQLuz~oDNG$THECj`4hH^l@AWB8IWPij+CS9LBD!zD#0}_>7ZH- zF%4)U^!h+15PAE(t<|ALq+X8ln|_!&^G9_Q6O`n!Y6HWAP|@{O#9hxI%i)P!8xE8|iYU|A zHMai0f-KAOSiDC&v3lUIP1$x9 zWz9-p+Y{q3`tZd!|M2XweR9G|MHCa9D{F{V&M0vmg_vo zblNOlg-a&PfZ+>CqR5jwFl!@O1mh=qsOXyEX5vEuxz=0SDgwfEQhmvR#{}pbeN(}H z5I(PQf-NbHD2k$?KM3ye;-vis7GfCzoYMGw8W>}TkT{(AVuW^OuXnLqyMZ35V``D+ zKXtMrcxm0oPeT-^ghngoD|L-qw_hB>jY{rPyVwJVDQ{qLA!P{$R4p=bKQKkm3uWhG z=df^<6J9ulk>s{Q3{Vm;>#9DIgX*roV6nAHn)*y%zv-@uP7?c;dW3jA&Huq;teMZ8 zM46rbHK9OrlS@lB)Vw*T=WDakpBIhtUuguD0tOG0IL{!IMx&oPFZ%K+Eo9e=M{RXr zi;lCxm(NCRxvJ`=g?GxSk53)jvtjsLe|cq9NEoiE&itTt$2=Yx#NTerd{UUMhVuafbx?+7;^El)JT#d?T+ zAtJLhrJjk2X>B{^h2P1adRT61dVW#(IOYgrKlnYgUwt6@>bfv_r>6%WYLysluYybR z-}^xOtItu;@hy2}YW7d|HKN-KOLXNF1FGXkgM}`1Iz|&|*~*ze4Yz3Ba-*=CF`3|- zI9|UGvO*(tV+obF@Eh$V$ZHwneD?!vtSfm8)W090-qgI2?@`J@!L;t?rk_*knVifd zTic}P{hH-n#I6~oL}y-`5`U^Gr(t3bgs)QOEt42$tV-%G2QMj1sT_w4`R%wYC85?TKDMV+#-d4gso|z3-4{bxijXq9*5cg* zA=HcZKe#%G2SXn-U4wCqq8y4BJ^ER*O7wavzj6i!DF1mi3Sv2B}vUBvq3<;kXd zbyCc38`S9fQ-ICu@E=&i5|=ZuZ+y7B4Uw(HE;5V=&rNnV=kpr*k-@6)ySa*#&T5*i z1gC&LpfDoo{<4|v3d;WAAK1MtfxhPLTkl{6t?f6+E{o2tvHFLKKP|ed;=JC%Nxe1> zKGH9qX*txS!L}vdfSTrH)H@aJDp~G5o^Z00EHbY!K1-&Ofs($zxf@^FAC+{&gZQ;% z=(0JLe$1ul>646%_&@_5~vnX4G+=5h6XwmEz1)T1TxXUg~N zHd0D^7S-(@t$~@+B}_0cGf462COW`d&#eP; zi2r#T=woPSCIb8V_Ku~iQx0TBv?s=Le`4hpHM!7IyC+gXJj>l+dncq4eh9*PYeqmc z8G>-Myk!B;B_j5EZ*Bl*yVlm$`VA!x*T)=Z&~3HhhfNRdBET?) z(B8i1lXi>Ws!6dDg&D?*+qbMR-vyQS zsj1U~kDK?ec}>PTW9Kx;M;+=A4`q_BPh38|@x(1#3Gie?_^rX!Amr>7euG2uyP9LC zUVPd*a72{pe+}I8(k+kW+uJ)VjGwmXgI~nv zS9{%1Po_bjx!{*ET{V-4{B3Ran9KNK#9_mYtENZz-EO+YU8y_$AZ~BuMoFtUtFgPb zn3KxDBwDi&eeOj6b+VYjywnkw8e6*6C3TpqrlnFl-2tn-0WQ=Xn@E?B;_bv)RiX{T zY*=;Tvcm^2mkodJKvD5b%^26SpD?;5nSdnvfk09n#AQn%xG^8AKKXU5Jofnj-K^O` zC$oCYYIA4Ti*uK4(D(^`UGSYjC(X!EMOf1g^g?x`j?tvI;}DlESh_U)6D7Y~rlWVG z>@rJK0}D7fj8o6z)z?4Y8A(1$4Qt0htb$mR{h-U_`KYpcGb=#({pb>e4Y|M2RFA*A z1O>@vww7Ti6Fwr3Hl&t&TH!zWW7Ogm{ro;gx&#Iplh+){Izp$$QgeB99Qa4fZ5EmzmIzJx_hK`@@*5L;SRU?R-ana{QD?SF|wBC5r54`AbEJN~il~OV6B$TbU?w;;PVOycQ-(bzdI4c;wdylOI{EuT>8*EgO7uwU4ZL18g#}UWHZ&%1@x0} z$NuoGce$YlUX#m1~RYo|?pnwUGvZu3c1_o}4rzIfM} z5{22Xj8{7@20>_%+NFMRh%A{@FNoqKpebF#=0x{)usXXyKCRckp+FhxZE8BWu^0Z! z#Lczsj$<7&82~>&(lTe@4p7x-Chsl-k)E7!tH4ilU``5L)uCo1Scg%RM4C5}j~DY0 zmyOXNtrR%7&+gk2L)wEWcvD=RvQ!R*1!PyngCD3chWz5C=KWLVZl}w>(xRAa3$8}s zAz-Lv(L$%+?}vs%C~ahTCR87BQ^-yf5!5X&c6X==jwR6@cb$?pyZ_E^L(=a-O#^y9 zF;}qB-C0C)ehz;nv3Mh#dN8T2{PJO10??U$-1N*-ONb+WFK4;ZFxV31i{-kfpFuea z_p>FbM5_P>g4ATU*h_}nH>{n4o-RoAb8U)GmV#I}*_?|(vg2o$)Uiu5CAJL1h%9K{ zPsEwZM>^}fmP5?!4eh4R&xEqaFuhLMc=Q$1D9VG96zLCE@r{Nkw8=%<5Y}rxa6;jq zMmS1fWgFevKF#kmSz8F zT!Sx`vUvL%E?^_IF~<(aA5aEa<#V?Tg+@@`DrB;Wz0G8ble@xo;=4)(+uDFw%8IJ; zWUH&+qp_!U9SIFYO{|t4o-Rk<8BWdm!M-<3c}_>uA*5a7hI$jd zY=f6$V{#n7GvuFQ9S|v=g<`nr#6SKmhU8g_B?YQf@>m(kHjW2c?3hAjH7)a_H89Uq zjZxPT3bA%Kl=5HRi&7Kyy@nrB);zI9`^mv}17hzySB5=do0mgOysm7{ChN}K&E26M zcc3F}wq30_Ip`~f?H{s|3DS?B+o@xKJhB@8+s6mqN9Ag5F1s(A&3E#hdA`#K~$he%feZ=;J<#E(841&89MVo zvpM}OM^cm^NyUzeE#_L5ksB-m=E4=Et*aNJpdoglfYJ>~PTjQ|0=<;4;A1<{lZA>v z4U5pScH7v&q+@=A8?3`y`#$KofFmgztVe-s@pk>rXMc? zKkxBb9_(m3Wt#A4b>@$-Y*$mCV3Xm7AEi%;7s6z4i1eV~I~2QeVq%JliuW=Mdf5@6-u2JdNG<*K7XHS%&3bOF zj;5^Z7617s#@q3C`FZ{x|HjqcS~bI@u-H|Gjfp*pirQ@ z;t`$S4EvUV`|s?%%~oz6{meL~l*dNjc%VMf+S!QeSdtMgGh^V)9YFSL+*1t>C@Swf z1MIhlE(Ed?QoBf}^IUBN^0r6ER~2SmTj+KBvavnm-u+2rI7h}i25)eg#he4@bbsmo zy5b)F4`6_cm)0!$DH+B14gN}51M}XhR?fGasVwB;7;abc_Ae92vW*38#B<1T7U(xwXVF+jQmh ziY;==p^erxsDm2!l!N77!&4o*iXn0`B%=gXe!3I2nf9hC68ZW#-K*R&>;fI-P25Ip zFy5wzxpbe^V1Vvk(nn3X)Hr`8#vVsYThEJGlwJwc{2Qir_b#}*wEpx#6eGm;!%yx? zy^CKM0i-junlS`w2j_sQyXYO7!XteXZ(e=(H`s6_?ZuHA{~z9I95(me4qdPF^{h<| zQo3I2yAw11F)&eK-*6PR8A(RX$kPS+s}S&?{#&6tEqr`#R&$6caW19&h2T2T^1=h z1+BY37=q7;Ocpru_bXX2@2j^;m=x6g`?rwO7tlTANw+xi9CWA#HOiXL;)kP^X_wHv zeU(XJZag_8nUl3@*s#FK8>($Jhj}46-#K|`E>;jRzQ}Em6nqACv*_u=0-_uD?~+W@ z*kb6^#ytvQd{~+UC&YvU3@IGF02uv9Z48LPfb}x$`7o0njnqlR<^UUjAc@OftLu!C!q4Zx9%LQ$` zC>$1EuRfiFsLalD_3Bmc`73tT2OpwplEF<3^hhGm+V-8)m_F2QmhQ;tZvw>iG>n#P zvI>Ki_wCnHV_|W;M^`PwF(4XESrv$SXv?g*57{6L3?FVDslOhL`*yRF5-t zA!7xQwE7=Adstu+Wyiw3%Rh%kb=Xbk+2|a)cWSTBb>cPMzbu^ z3iUPfUGPixO?%=9F??R(UiK&dbOkjm+L;*!n+Rz`rfR==H5R3v`QCarzk4nq%!E9^ z-vo1!7Jty>MYO4Ayz0OH&{7_=%IIt0bW2m-!kLpGMWu#~K}OeQ(feBHuGzRTKrT4L zWR5liT_FpG1ByY;hTh%oRLOz^?GIvM7wD;_)caS;c(9-irA8)a8(yoBgoK2$N+Zav z>xQ2@yFL-4SK|X{q^$q)yS19Ow*F&utj?mHok85o>>zXXtQ8;aSYc+pfb2n=fRhmHBR+DO4}JTn ziSfNJyW@RmYvA0ju$XPlB8aE|(oeph#;9O_TaC3x-9S+eVK2At_NV>RZB zckJQQeVeGJW9nTD=-#EI^u4>|`nbI5+918~ z(l^xfE=HYN=13Bi&rtJ#v9uxS#!5p<&rQ+lcQoq%%M#io;^|6;pyQLohpn!1{i6-#*No2Wr8vVmkcQ|C~z{+EPk^;PF?p=3u{)GL_mBcs;dv|SHRyCyk ze0UlgM(*Vi#Vut7Zeb#wq31f3cRJg8ogdC$XIU#<;T3&*;>SH=Wf7JR1-rMTc=wYPDUd^(Ua>Kq0>hvRX^%!18>kdOj^Cbc)`sNZ zEq(2AeaTluul^bBVF6vOdp78mMRxhGUJ)ILlzeFodxpz++WzJofKGDpUAgAGKM;vx zn#hWsMgR2lNi*y&!6Mvv+N~!ee)G4rQq`uNzR#5tcbl@O1ev<6G8E1 zg3($uBBO%nwi&iFS_=@9)Tqjj{)Q>MfeqvhlxX=d{jQRllj(^g^{M)d3csH?jgr_) zrfAS}_i`u^k3O*i8E_o`lkmFCIA5tbmmc-!T8Rs)4Tt2R8zAN_Z$dXo9@OC=Ga~yx zM?8x%pk`RyCMH&%!Krx$iey>EW$rEG)o9o}L&6kXYMBm7-hw4(V9UMyZq;y40&o{t8G}98mx1Z$}k2*8$18A-6evv#p@=u=7@To-E;INKNZl>QgP? zKdqd-vkP@#!DS8I*TLt^;vBO(zCs~GnbKjEgDC4A|2D{vfDb6M69I-nBmZTgx?1((Cs%PoDkeHdn-o@}HpQ-&38j zTj}}=#P?IWKhaeBx?C(u6*Iz zY!E2l_8s4^B8id&h8qlBin4pA(v35zR>x;yI;dvjK*frj8hAWTY;fsT}6T+-E+wJEmh8e-7-p^#(U>tn>B2}_!<<##U1 z50-Dgd-?U;LZ*)17TxA4JV7xk$zF{R!`oEH?+N?wdF<~ngkg9gLu<4SXpIA0DP2E> zm%Tw@`jcw7>kfsxqCFA)kDQ2XETOUGRRpl`#X)7>&BOySYIi9~{{)?{WJ87PC zSUVKku=1~K5DXp8*xM2w2=_vFaQ6@~eFJ-+d_VsylRy-`?v4FaN6WR-uf>L{1XZ*N za$@XeGNTP7F{`c>d#uv;hXp&|SSqLGF>hHTqA6I}SLuOFV=>&Ra_x1AaCvc}am5G}cQDp#(ttC{uiVEoaECD|yAZb-C8Ncm9A zYHoGMtH7K1hD3LKFa5qJN0kYNL@YP#u=%^0haFZu=9KE*3cGN;=#QzyguEs?u70jqzQMI z>GoM!!2Z8FL)(CwNt~464AJA0hjAkTT%UCcr4d^!&b`0hZh15Mg5%`J$a7|Ib*md8 z$OwG(R*;0RIA-GSpF*eFkFJ&d)1IX>BiJKS9CJHfTlnYgkk{A6@a##3L6dYYq}k?= zQ<$)};;CW!m6ey^0}k*~g!m8!VE0cHaazQkYA@o@{o5f249Dyij0; zRobnVmQ`dS+=}a+v1KE@QeF|gZcvWNn*~_5z&q)(ag>RT%^&S}74!Rxo3wjRJpnNI z5q4|!S*O=1N2@l}4>f5TE%BSk17@}`ylm*lS#ig*&`rJJ^Ar_xsYMDB5~ZuNs=ZJW zeA?zTS-x$!+Us#Or$ynB$z2UG242Mw7s8SM)#_92g5%WM1;o=)61wak@sfrxE{*J1 zD!!0*lc#^t-inyM=G%gG(-re{?+!PBtWBvOw!kP*xdPLi_NYJQE`L*H?2dO$SDm+wwLNwH*#rBj3ERf7f$a?@3{20N z&81zFK*q|k#R)lDHF9>pt~D*SC0!uZ%*H22;zM7P*BxT$LwP&0I8Foeh#-EvgWG|k07O!woWq| zy^WH_l~k*a2Ce_6Z*E~bj!upYuYL(_M1kzEZy-xWidja_82HuB+ujN5uv#D!gQMX~ z=?A7+c4H=(7Vh_8UwX2#oZY*YPMey3_C*k|+re)itGJ3#^tN5*HSD{@agC17i)S<3 zC`f5YMjI+xPn`8|EP;{O!+L-_!%Irn@vn+ndfqoHv#Wj3gC|3nJG-mBdf9MnEaSH~ ziYabe;<2fSb>-kK8(LA02%AEYq28)0%vQKUmM7okwO>b~^+T30ILZ)HdX`*N%XcZY zGc$rQBb{emLX!F`k|X~lazo+fg#7NT{pQ*3cda8jLRaI!B<*cRYTeoXkxZ=ZA)`vz zFjSLs?U(U9@&^P2`^eCGpv|?txLIA$c#AtMT(Ul0VQ1$E>Y=5+VCv=M6gDSni(=IGSvWP&WHx&~Gyy}Nn zwQyOy3XJ-qK``vm2?S#JADt;{N7Hf5pO4Hxw_9Ug+{Pcc|$ z=5C7^7=uGsz_@a56Zd9pndvZyg^afix##P7cDUDL{Kk_fQTS)rSd%A@cxM1>3o4T} zV@E9D%ce6ZC_%!J@dhGSS)>>Ve7DP@1?qeqaqiZ?-lbSV;#uc%Wu1cw~)!M$&kn<QiCX5W%9`uVlQu9bhv(c%2DXWRnRoWvr3YNnn z`X1B9p>o!Ql)eT|mB)tJCJ<}HmZw}jO#N>?N8cg3?ibluI;8XL%#(`L+K4;hhVUd8 z0s-ocGhJuTQYc`&$Q_!YA`&_=61FzK9&FJfX*2KRcFXr6QwyZJP2H#xq)fi{74|Z7 zmz#kf(>-KDnd2WWxaV(qgL@!KXDw+}Q<7!Z=4sp2U;VPF$%q!PgK_vzxMOSrcgk~j z2n_uK>vj!9(drwUV44CUCeZL{W+RZ37)(=1TyL}Dscf$x<@+Aui4+aekg}e;P!O`r zLa$}%RP9ZhHxoDaH7I@8v9vB^I`c3OkZ(jQ{n76CWGu6y)o~_}GkqH~RFHmuWF&*O z`xA?pMl#$axzf9MdU3Tgl$|>FCmC;rRQQIMBFnC2bjeCsBRheO);dz}z(4Hl@J;Q5HA7V)^yp%X(6rt)P{9DT>#Q+hc3 zOyJ45{GK}1kO`c9bMe8?J=#KDRk%R_3p3IYfull`*fzZsj?CZl1qQECpqYSfWH#S^aGR=J{ ztzwLDopK_~+ShN;;(pAqy=O-EDDD=>sk(2{4bZ0rgDZ;j*saf$u|vsKaWUKh%@ZKF zRm1Ubt58|iCZQ+sk(uZFN_UuyyavMb8M|+)RtG-W6HuFt^aM84cdTLU_1z50Ni6n%skk%qunuxRZo7`nb8P~VcnD73#4 z16nBP7DW&P>EArcjK9j*hU0R0b@IOl$y+Ti(39-aH386RH$H4x^(hK+&;vL&{L7dG z1O&-gB$0}(x{j&i*H`DSSUU|D=N+f7%^W4LQ35XXdNM>&-1@p`Tdlh@`s!E_V2R06 z;_ZUXx9P`!^ls`=Bd#CB;%j7dG-h!-<~)`wPV`-L=&n5k$Gxw&W#)6uJjcJD0Gfq; z^*z+Hd%w(h5`pHObVj09hrj%CZq#T6I*RQ?r>)NR78DAqpY?F#VS&T^M=lLy@-}!4 z-^NKgyEAGBEp0Uq(GwDCF2DQ-KT~`bWw|Vi7AkiE-t%X;d2GD=KzW=XE8GVJb}~qD z5p)~u{+>bm$}_P06&r8~IdXycEYJLjX#W>efL!V0pVNG$Xa2Jcy}TNn=cNdUojh0*RVt`Mpxxe&PPIqZWNa|OCxnAdzjal}Mk|CD> z=RcL;fH@-Br5Jg2(eG~kZ!>RztLWtR@2Rok=u2&N6uN~~V6a}Ot$v?a4G8n}%RNae z>3evCaM8$s3fF5QCP%XHN6V3+xJ!^$7Q=Z75}?V^!BT90UOD_6R$Eabx2*Xi<-~__o5wnG)Rt=X1G7mx z1cQ4lr z!MRrwD==rQxtz-LOnBwW%??XfZHGF>**)5Db+B{C(uKs)fpR%Ni|LF%nHn}h6d(k| zipON980r5G$@t7gg>58&Rt6StJu7|0^)}wq*@jD#`RUS7df?nYpC^)#6T<1?(f`Dm z2KpS`dVXGBVd4q;y=$>VZMMPn`bA75K6yC7Cg5gc{eaW&C(e-Pu3gZl{pNbHa!jg_ zODf`tf}t26q<)FPmw+19*I-9os@?#<_5+P-Vs)T&Ti!*66z}d}(}>&9AFUA0rfx%s zBt;4d@mp^%V4;7{iIGVUq5;S#4wzySHaEL--_cr}locjXEbe_{wEFVM#G{-XTcpyZ*AzBX+tov&7ltc5R{>BG(^0;@xH2&2* zd=PFf&hN&moSdp`QnBu&Y@JP?BO0~TE_Jb0e~&Ie06(D2qoT}Cw4Iif zVvRLqHBHLL(fa)5C!8~p=G39;P^Rh$FC*j2kmJcz4cH0NmvU@AJN$^&J4CHCCz725 zcXwQK2&`%nAArl(4euaM*m0K2xu6%Th<%9wAC1XG1#1R;4cN9Lzlb{*Ui-Ygx0OWL zGA8fUf6gbCxu_#>^e(vZa^?yBk4}YY#LkvFmS0eyhIKH6ZkQkT*4-_Jaj>Ki${N1( zXT%lIY?IF9)UWocnT4)N1nzL*3&t+hT{L%lP-4^u9&8>{(8SDw3g5=kns%0C6x6@|{2Ziz1 z0=5kD>SPT_L6hF6*47>d9zH%%A~k-bbnWjz|9^CHVD8g7JzvgvOvE%5mJw%L>I(5- zRyynXWEoS3Wpo#@`4_o8hlC!tE380%l=-uotTq*Wmq|ZR&kH}tq zff8ZAe)tnpJM*{3Y&{+^Z2`!sOhc}B+RFTW)QP z{H_zWItZ;I^TeyG?&?8_Qrw<#ZqyFWx;I6Ma^Gq=wJA7B60dQ^Vsj8GcUMx>2797r147F154P=eXz*YasBy z(mmD3%E}YF$=S#2A$vW($y`2$%Xtmi)34EX`H&gLFG$kAwr2f?KQH6go5~T!57XN% zv*@3sF$aA?4_&Ad)9<$l>IUnm)CjeLzHOB|V8SAtsBE<_C?NguCWMst5cw)6=chwX zJ~!H#SFT+78k5r|i0(x3L8XT*EG}hQQY`>RD5Yx&*_+#r9i3Q&GeIn?iS5Sd)})!V z0_{JqAc!B)>lE_ljM~G^6mo@#sq<#0FKJ*?Yv={`GUsm#ey2liqbLwqQWo#UGzBrJ z?oG}pV*iQBmA=QL@~;A8+SHcfG;o55E)KV;NkuHTfn6{nWgrn-fR_KpBD!|%K75xI z80_ZG9=U)LDnfWIY7MH@t!YG>%U4l4gQ`bOgVyPTmF7LwYtq~cyVZE_@=c`H82XYeOM+)Qb+0ZjFW#&Y)gcX1(7TQsb*?kZnuf3hjJ@&U;SynrD7y@^1=uNU#&7VxZ7HJW1l>7G; zBaIiilltN~Ob_#Q{++qxSeG?|s;D?=1d&)sOzdsDfrL?x7~<`dukc7?gelUn(~AEd ziGatc=DKW;1MCL~ck!}cIJv$^Ip$RE{kLi8K9+NUncUC9wYs^;Mn5gUaPvpfC4d$2 z+>m-K&G1qIk)vW{*c-K7L83V_oA6ln2XGwU2kuF|laOZLmiLk&B?G06rq{2|Ltaex z#S99H_AH>=amK96t`flwE!vP@o++W%sS7>RoJW@lOZufy+rVbuR@7GIwa6zuHVQW>%upkwimiT%RUv?n# z?X70oH23Db!;C~IE59s;AL#O9a_aiq%X){TYxh%el@@Sw`wJcxKVt-KM@{?Q3p$(` z7~tP87SMS0)~x^-w~m!AMhAWA5#7#8vRM?x8^}D<4s+%9RzWCPS*b3!S6)(3{}r z*lQo<0-U`de;%3Qb)ERMY|)p^L~C)OhUjcSqe#g|%tAJ-r3Zt~ojvPn!kwR3UVPd@ zc-J7F=n1hHDrk_@oabUmHb;8h49)v{@;H(X;P;`li30h-{>ns@K}?X? zbQh6Z1L&*u=FaQi79AmZN{jac#yI7NKODQ8FBxA5LpT%6$!hKWp4hrf#x5FLrV1QN z0SODD;eKsUlK;GMjSZ{-MiIw8<4?>P$oAcG)-f2?i3Ge%yc$t1kR=^sEVhTj%Ka zcNtk3=WkgPmo}oo%@+nnRP|ep%F5LAIDQ~nJmTj}!SU9*OahUWK4P|M7%x(0uE_o! z6H7KO=0sscWf&~AhfDA+qMG1(0jaVu8Pzy!_6W(vP|T*Id^tAq?zw#@GBUCnE_}$y zU-E-}$ppo8Zg+c3DvvdCyCZ)89g=gJ_Y*?8+K~ed(x5Y-=V~3mT{dr=eeDrq|i$&3NNj3*+DpoO4v?S6sq^%hMt$#bzU2&H|udF8wb!__-mCee#<?6Eyu*m4|(H0|t=Y85Yq%pG5^G)!2Ve49xn?A|E zI-0ysE!LHdVtY)3a|CO0w~cu!z2S>l-XV z_VB8>)^s%G{tQ1xHpbu6PKAL{6uA@|88K@mL_q2Y^65Ruh)J`wI|{fW{8<_Uhaq=( zS+jW$tLL>DeU(iTxoxwL%g*@eaiRI~RNecZy1WIS+J>~VfS1>l>%<}W`H-b9qs&<9 zGKZPe8Xc8|zrH{?J?IU8I3a~>E3etD`yr9BCr2JWs@BP&J=n}-g5Q{<@#$S=SFe$? z%0(1{yI`S2hTRu^8OOy`!veS%{0Rq8$IkU?|NCXR>A}UN<9@HmKkzHz9u_O(n{k9Q zb|8)fu1)?UVxk>)?*neF!*90;mPRUCJDl39kaCvlxa#hD-7gw4#p~!XLUDz-jgsLj zhfY=&7Q45v-cFmn=NT}eo>oC=b!6ZM%&E77RtTpCm7JZIaOhzG!AzAekb!#OSI*Xz z3L!d}oZVlZc)5E_E{I)Ro4AH5U(fqPZ@T$23`$6+^^_m{1)BRGSPl){pQ@q~ZG8Bg ze}8s3Gob_K-vSGA93j(zS8$gpUpL;PD)Z8vp7;uoeWC?75Sx90%kdd(T{QhVGSr%} zv8)pHPKDgHXnxdFw~>YRy&YE!!piO9jMd^p<@6nxR?a+GtX+7G9$vS!3J_v%v-#Sc z-_eB;`E%GpI?X>V%Prmvo0bb0g|C#xUfwn`RrQ@!YNm;_6_J+h?)$gK%|R`A_RFwQ z)3b_Awx`${U%d$vF+FZz3|_b&y1g1>R$GyO;&MKSfn(d@#%H+hvj{lFY?~dns{lhMY1`Q&mA(f1*vPVkFEDA+-!zO!V)21{C znIUP&$jDx8dzP%IWMr0A3eRzoEYpYMIY$MwFh>pgVvg+8C>K&?#S z{3(Jo9}%VP*8%7GU!jD?ScFDX>r?2wj6pmkJ5TDVb#AM}%U&|jutN~-u9B$Ygrd@MN!u~ZiTl5F^pSC2+@Hh_MK0af#+ujKL03vqaPD?r*dzJ(i z1?qerm9{K`2Yby-x#TgfM;0T~Ip7(ccFLqOI`j{0`3r zVyCa4Dcpx=4PBy_e@2bC0GA~Izf#Y(Jt0sUDE#-r(Emt5%-Xf;pI^bVi6OT|i;QM` zsHoMRr;;~QMF#k6B(+H}(1+$--w9}s#<_VX-KE)72e&G|y0@P`G;Br5OK?53tk&JkcsBJ`}OPsy*S5wVCT~Cw+*pLUC5ast_1<%KA+JXNLPi9CsQ25_I zoe~bxufb!LftWQ``eo3aI)424yEP{kQP(llTuXUsy|@iXENqPz%pG8H{SHF^BVJ8i zlBoIOZTZh_%m#!dC*{q#i3qazHk>>YT?|mn2uD_4?H79B0oomGY{l8>dm)S@_SMc& z&xx?y=Potz_{G}X8~94M6FhqFgEvm1+XISrL9gFuG`6Em zA=WuIinToUHI2WB$_(?Ym2ob%X{KheS_mrlu+b+jrJ4k6)L8QaLB35)OzdQ$bN=GR zTpr_kWM(B{FSVTLsv=2|g>8 zrR2^vm$X$^SMR*Cla6YJ;@eNu3nq4NaRCJoAD+)O^!I78Sn~h@)*{*xu`;3q zzlM+F5~(Ta~+^ai~UexiQGf z-^IZsswuL5m71E`$Wfe9jq7b6Cd5q?&mN{Kd=}oQ^KzEFzL!^ga>+5R4#YY#Fwvlb zHS{eEn;Uce7$oNFU6c#Gc#5j$|4#35w9X;ST$3YantD)&b;W~cABx3sule6t?dD1K z{N+qGMppjD{?^mEos<1r&rwFVjZ29?6>;!y)*B|aBxv!TIhC9#QTCi1y_r%tS$3-w zSuJ3&ec1#pyfpPNAh~5iPYAJy=fuy4K-&c+X_EN);1audlLuMN5eV17%LZ#J@yeGqqvH6|LRWhzx4zU4x9B${jDZ{e+k5)eDWx5vIDt4AxymDr7BI}x_rCG zZCBR<2|5mX@T*gNV`gASF$?7j?ZTI2_ZuVJd^884rK2cSy4z96aM)5jrSwd84g^d zOSBurZDruE)mbAEMs@@2lc8(LES4Ty0vlAc`0X-m2SVxe+S3*69d?G4w`tE!VW_7K z5lUE>|C^zGeAbh>+^$?_>&6v>PvtQfh$jrI3xmt31$k1@-BV`wqo|+WK%+n`L&KuN zM`rKmo5Mu13MXi>h}Y&5U(qouAq@#dUiwd+mbe0CkC2gwx<@SVO|n2fJCZ9EG%?qn z*h_+XCqPH}j#6*^>s|w={`X|TTi8d}zZ2Xu=Lk?oa9t~_{wPO8dZIBNzBu}(}eOtT0K&D;M17kTW=d!PDd0CEM8%q0@D^gxsu_qw~5ueg4h3}q-5KCaD--3di zG1Xrn9LntN1m6S(zel?`zC0GDA+<-CluNSR-V(A(6(N|#!V_$HQguDVt-JWzo>WDY z>bfIjG?@iPG2L)J3PypBUgaFY5vb>qt-G+TvOt2e* z$keOoe8LJ;JHXxuBxWHd2854ExabC$C+!zLe;yrHfJ`!>j6OR0nd|Y#>W@7 zK16MX+L%*rQS-LnXk(eH${b`59Xxnzjlr3{Wb9A-6`YS?vY^D_tcpMTUD43!H9Hvq zA*@-_kJZjU@@VEF9RMlo7LHJ6fsmfnJXWf@Ry~KghZ{7m=>_J@r!Ze$G7H$YTlMb- zOA>+vNr&6j+AqyR*uScEvJ(ya=qT#ap(7hE`P42Kb9xey1{W{&$%&!sl)az}s8ku( zVl6?>g(FYp!N?_bu&QoLBgZ?cKFD^8Z#iSTbB4v+vPSX9z?2U(3PTrz+>qJicTbIK z+<#mePZIP|>QR>}=z$Mli+Yd4s@do8eN3y@lJ>HvhV}Gk>szJW{E|kOnflwL63gv& z|2eRSk-j#Tl^V?-LCQJw@kE8+(tRuVF6iK-rsGa{14=S675hCkl`bgKJ$a)TvC;?z z90^x35#j|@69TOB*NsIFDHTn&`f>QQ)QJS>J|ppt7;1cWTK;?|6*j-!1QR=qV?F3% z2g8L+cV5|XWpuDj7tq-)**KU2y}Ceyeq{;ytYPWny(t`b5A26d)j^PKZ{gDZilkXe z>BF!|>g%fjd*fbpKZAni|IX3EOz zik)A)@C4k4mt6aum*+J;Cib|sac8laMnje4CL~FBm1K5G7u=yup%eNyllGaG7v%tH z6m$KgPLvaP4DHK-oeqG*2$@LrSY=*9L*oIr&F1o-VZnEUBsuYe0?Z!7>J8IBmZ(>a zq-scEBDkGeL-b^h!jRccNZg3Ek5-q8I^{#TwmLi4t3Xe?uyye4c>LSU2l`i9<{Ddk z@|>iK^2?L`hcya-V~jkW^_5I__gL8r2t)6kuA~KOEkQbxgMEZbPAiCXf))*2DQ|AF zQ{L0ALmfcdzrR0qohV1G7ENHrR(fOezFh*g0+)M;DiCUs_qY5CSr6#Y`DvYf|FZz%*$kb^AO^vl1s(^2S=jEve=gc z+G0kFs3ZAe+V3~Z*#J!@>~yK}0^n@wn0%NDRR5;DzTMkvu(z7<(JK34slW#0XIzb? z`#xbfVnx9{^H=~*rLZ!J+~jjXQyh!fP+J>{QU>0B@|}b^Puc}pZF<7}>+o9WIrtM) zQL9C9Z7qH9pP6R!BagxlOCdH1`%c@Rxx771RJGulRXjQx#&340EV)?YkkXUbebQ3e zar26-J7iGYy@_hU-zbj{Q;KBmOOlpbZb(oND!|Vq9MmPKtattPa*dD}gXwH2zTsOe zHI%>AjUhOxHrL7Wa~zMixA%r9E_!BW4q#o1Ph{~zz5r5J)q5+cp|F4d+9wJ*y>!AtpV)hqvh?RU4BW*rb1DmEFml?w7E~d{%$%Sjk>6En!nJsVe zo+!T)h{x=H;^Q+$Jw4ecaQ9du6jkr&qAycQ=v@ZKfq4>r4=qK#${MF$Q z%tJhGUWjBE)}G%$tlpV&VbHB)+nT%|ubw}vr5RAN*bIRLlCsBtH+koZ`Qq=mN4j2g zO7lNC<;Q=_g@IA`fDZ7_&hpUe5vr|Q=7P(x+rk2$M;HmkUEqCq$=L!e`xCP8&0wfw z=~4@=?`ZYIWy$IQ>?L-Wz04nQ0+_eFTHc4!SJD5A5u=)2Lwt!nrp6i*7)P)1kxdk6 zPFnV`C_vSCk7j!MmrV|MLEM*sblR=qJTPQ6St6B)5900bBpoHcou^)0m-2P}cK33_ z?58nIaN`2YJ*EHhFEC6X&ti4t)2feZc&M&*!Vv5$kpOlD6Nr47t=s&8$(37oCPT8mK zTYR4*dg#gP_|ErF0t4s{M}4j6oJ(09$4Cn6E1hH3&Rr-UeUidnc8;FQIMWNLmJ%H- zk3KlOm#i)*B#LlKs#`#{eHg;qG6Y0ZMxf&eV~cNHp&?W!!s|<#B)+!9H20I4UREoj zficj&G`J3fYvr#`M_?uZwpUk9*-+pLnJ$`9>sUpmN@bmSkK%>Lw7OC5}iht|Ac2D)2vHIL8vW-S`t4cTipI$|VO$CqH zHq%kl@(ZKX!x=)x-){nEA!<#qQ*!6ofFz$VuifpDO<*dMYgnyzD7~jGQEeAn4smlL zc5KA_B#!&&qg$wY4DGwC1{SJG@}DPj{4^s!vN3x)`eZfN;TWF`oAwV}84bxqoQ|*i zdI>p=B;nN?xiL(mU*rVT>QEs|5MtPmj2>2p&}MuIFd!FMpJxLOd7sPtRavo-5w8mUzGfp2+kg4q)S-*1Kf=J}0?`WLu|( zb#8Vg;LaSZ_e9M|W-|(WpWnG+$EYzPOd8B0>uK(o(`aJ*1H2_DgS1aWLqqR=Xm7wz zFf6~YAXRy&HLfi}<2ovsQsAxmJ5Spqw5_MY(U!lN$D9dogtc1**3>+6=CgHac%yOm z;;rxu9Rs1?|_dKV)|p^icB{%^49gP-w(cq3d2?Ar<_AL0HlZQ>r#u z7FWXuI-_l*&OZrX#-04TQoq+cD@E;5iaFp(mvyAEGvE}ldJn%DaZ1(B=0H_6J(*a0 zukBsUGnaxT*C+$~4o|A?-P6bTt0Kd`ys*D;L8;e|aa)XIFK_ir>bYx3P$Fcn&|Q81 z18E&12(m;AeAQVbz>Q-#j9wJt7$2Vn)k|+EM)L1KxdSuu>~vN9ER;zHWR~|+DrXDS zLe7{AeTXxvLUw$Q1~GveDmioPRWrASAstz6p6~{F+N$^2Gf3rKyTVM_MMXvTjS+ea zCdps$2damU&93{ijr95O(HP$%Vd(*EY9y|MnAp6gpfTk2y{JYa7cQcS)3o z1gk^ios%tPoUmMC-rZmqX=bY5FOHi%kaHKp zCxc`F9q;u{0hK2cwEM}`voWi1TPiUb!=eVWj~Pj^7p$<{dxDQ?WtB5_j+5=o8s~Er zap4?MDTr7ys1?N0TIQzn|LfPfR3#`4FMv zxVB*UbQ(2bL^qB6epSXA>w6gRguHp9SicThby3Oixv`(^EkeQVB-AW0#akl3Lm3{7 zg)x#A5?yva#ppcmfm)X!O*AU~ZFyS611Z(tJpsr0BBE&2OLb?lf|k`A0OvBd}ztA+I)U_oPcncJs)GUm!-7lsb^)dkzVb6At-7Q9}D3$71yT4 z63v}z)g(wPq`9++uMCRET^v0G;J|#FTqrXBA!riQ_9I+vKR{u!((7qNwl4)j{kl_@ zjq<8z1XAG|?An)<#SWR;i#V4KQ1IzstAvk%nenoeTLYIxQO5DTAzLTPZ|*CDn?3cr z#LzD}x94sd!tek8*(|NcK;^nBb_?*&zW)WnNtFKe+H72&Pok2Oao zBQJl4F`9%0cb6TMowD#IxImPh!g+&<2H71|3@C$$Da^x~LX;-NaKq)|t69&86|0DR zo*=fOru9;Ox3E27FV9X80JC*uX5>BKs=LvzdidHx_jV@)!Ve`e-HJ5#L$_uNyZWY}Y&C*Lsu zeM~8fMJx*5tI;h-=>PbRebf$Un4rconC;&Lnl$k*a%&4AIwo8 zViZ6pnyR(kCx_aLiUC%J1JSt$2!a3lC7O)_^dlqH@@noNbFioy z7!@zz9(_ia@OjnePe$H}n)V~!8>h#7K5dm(G;2&|sVe;=lky2Bl<)6@3{vwD6p6&g zG!divtlEg#D8`7Q|GiUHhD`zto%-1K$InIUjw8NgmmXnmIV|Ust$#)w_9R6Xak%6c zqiiR-vS1MP?%&qSvp}uz{2QJB<>@Li90BI(@Eh0%h&vfe?; zimMLRg$2XY$f5Q_1rxcP3kd)F(o(1tU?T=l(mXsJT^6wgyOi{DfAX5kdtB?dEUr%u zVin>_iv~si6|B4xLphw4rvwBHc<(C&2o@Ujzty@YQytAxRsQ$c-;!saT(RnZ>;sR1 zk>PB4x&^6(9UGENYJlUBR__1+mZacY*X7oOWs-kF(Nt}VZg85nE4XfhH-6r!y_bnJ2CRV_Rr~D>1 zF_pmz>}tCLC`3aQjo63Li(WLO+w>nJ#A^EYfT!(3qZ>YheQ^`oS9kdv`|Y%-W|}e& z#DPp`wtmg?glMh|2h+Q$Z8QA*$^}ke{C|wR&rX#7czo_wr#?kkd-q{a++S`SZaY{) z81@hmCDy*`g$wN_>s`KjXU$Z6O#`>$XpMCDCP_y{ps%O-le6en(9tmtbXE=XE-cuw zx5y=kU-f}OL2j-77#Kq1^OB02&vjw8gkpPMG|uTk%)X4Y0@!>}{G5U&5Apf{tJQbo(YCfd-N(IV8n^!o2o32h0S1rb++WW9*p3P;?(9ZON4Jzh zKPr)4?-0G17RJ|#xNa&bG=#W}ZLAqQC;3baf!Wj!w0($O^LhH*$+hk|6bh%fS9tn#7>zy=dB#U!TR=GIer8HLgDCoXEd-?-cSSyMW=6ECrg z!q$2KfE~nm|A@egy>L1PvOfLYNJ;u@bzg|KOYtY~fr%9tC2~3ds1sp3Y!enfLKuL& z2QYHMc~G_Od&l>AyaX0?Nqc?sbhEmvK22VnUT>4XnUpCs4cIg0ip8?KwjQ4C)l%b& zAywHw)ExM(CeE49+VspFALmbo*aynJbKn_S_Ykqv(sUdgmi1B1aO^(0#-CY?G{rr? z4atJ!s*h}x+uY7nBeeoN0o~DSf|5j4{}7v7ZBE`0pw?~dg!6$W{{+}X%UPfkrvO$4`<5OB7 zX1zPHR`;$rH_V&Tz~$hLP@}wrLowGw(V8itWUoAy@m?kGETj=_15YL`7C=T;@U6@1 zYpl&$%w6ust=T-sntpTDhxy(uF10O{8kuV)lCE$FrL%UQ2`L8mCmznG2{A+#4_j%K zZ$oZsoe*MLIa=%?UI%_)6etq214u98Qgr7+MEtfGZ$n~jL9~fK@-*wtfVYl*)-YStiKak`IT1YNEdSUJ&@eK<0iE4tQT9c5+2MO zA}05(OdA`LEOMUoK$g7fx*IEUZ&%!GUwGY7?U`vPP;fZ;>^E-ga= zi%ZrQUFd{S6p;Ny%J#tF>j*+W_7kc23mF3;q~z@weU=AKh8}V6giv^nQM7=nkT2%t z0BNu>Q@hPZ7TFV(n9YATrKwoiG3kKYoUk0maJvcYw^&Y@tCVIHq-LH?!60^-#U*j10=t)&eHkfi9 zuB9^J+ut|?N5$4ceB6!J@jG z+}(W5Z+fD@G&5D?D|}ZySps5=r=Hp3i3ayb;VaJiv~+YJ*9{&^_sH-v1fo+VeBJ91 zyi_F1M}!uVAJfN%)@)}wv&elBR`&^{z6ca17vVP$;&C^(G0exg2s$&ddRA41Rbs-=6d-YTC4UJKcZ@0 zKyl1zUrBL1V2S3mJw0NAllV13g=LXe&(H3AZ;E|cSpSvukCVRZ4x_^CM@`9MM12VB z57H|8L{B;pwtv4@vc7|rQ_ds3oHVt_G?yWRyOzHYxL#Hd&CqSjknw;|LGRb!zuIR) zkg4Kb54yp*qqYDO(%vd>@Y6M1Ecnz9rQCg>`areWRe0+^4H&G5^{%d? zyAKZ3oqMhl02elFjZrz8k)!rjQ4RFvFh=1X{MoV$1j!`?Km|((>Lw;DpbO>>Q`h~`kltH zGZp*7et8O1PuO);NHlu3{ZnZCI4F~N(o|KiNYJmX_JwecexjMAKh(u6 zdh3;cYB-9qU*(&Mga4%A=fF>c!7KDgp5$1U*to0r8XnUKjOP^LEy=jw$>#E>~mn~#G{&36d0LF`GPm=A<9v)UQUg9^SqpepR5iHEO!!xsI#M|<_13b|y&Ooay=GPHkoHAwf`{7Jdse1T>K`sDy zMvs~eSwIvH*<`{BzTEgw`yGuByeTA-8wcAvy@?P@dEM1<<(h_uhRRv@uH}m*L&0gN zRgOAuO1*-07Z)*BhRsv?dLGz!a8FJUt^-bpoZj>>r4L}EExNfjasK^?>vw}Dox`}SfwMo z+u*cYu9C%}%U6Qv!c?6rcct(8QXUaM{!AtO$CiH zx+dN-N&WQEhdMl$Ew|YnI?r*a@qya&6OBX?O005o?C&WZucIEpTuO^*>vZH^x5Wmx zij>NIz9LYV`Zq)@Z4Q6MVI>%yf=x*P!zMZGw6RNm?Ldh6^Gi{>=1DL0`Z(8u(r z>t1+F&B(0KuLt)dMcKCTd>_h;#oyC@dkqq$(N1gh*+0c%Vpksx#nMJ(v+-X)h4xaO zer8n<0_X3EqM1s2b;u;{9*gSuY{+v`RDz+VopDse;Pb11l&|t)FD%BKJqJQ1fT?aH zo@A&Fx{b_|DQ}(i;&J&%Wtg%B= zd7$eO{q_dcKG1v!oi9s8pHWwYTN;jk?8>3s8n4oZKz)A$D7zx^(lVAUC^|FqIr5gb zMzuz_x%PCOBUTJ$LzDN8z7}EmQC3v0+71`xP_S*K@{hc(^`8pcm-rTNgrwB-$+set z;&rrxZYlUX{9s!TC;p^qF#;`eW%^#Zp!Z|(=XtiCdajU~6gEb=U1wBff&#}JqaMdW z3-ley$<3N-v|o%WykQyuZYjnK@n*Gg-vRtIRh*vVHb)c{)wwbE@QOLl`yB<9<|e*KYX zcue%o;%EuiwkW?!gvK}}ct@oltuiq|YCZEg06JCU zWOv99jA6FYRTP1B>u87Re1e7KD3{oqz6Z0$=gKX_+W7X5!IhTBR}3=zfV#-|+4-fS zQN6F)2sO`SUmJK{#$cI<4xowVMZ9;Yj_;ZEu=3qN+vB$dAX*?0na)&BegHr`3q6b6 zVP-%)&lAHfUOJnqvSfa}GnB_+>s8Gf)DSK1UHIjK8lSFm>E3hfE)Ug1PMgmbog_AP zuq+I0k^ZclGWSZ!?@;IaaPY!JuQ~r`vbV)EH!NZ!EXoy)3BlQ!TPA{Imp&3}wLSN| zj|gBP8qR*SD$k%hpoSe)M}nf?s%^xN=0M?9s$rdyyP{F+~#ef&sAvwhlgw zkS!u1=<*UU7nK1l_3>)8VBoG%8nI-#@93ywFDSW0C}&baHa0wL@G>Ure~F_9=H8j+ zGq~&FLkzPI`a_w}K?T>35_}tit;Ahe<5?I^`*{n!J@IO0;QJmslzs_QX>g@nSJsqY zKl=j1M@H19G*X;=`Vzr!ER%1(#~b|`?Vi7D-^D+}7Wy~5GWJscl$zG$%W}vPmpM)#pO~e zOW$^mgv^ITnueHMxij5U*5A6CpYvon<9J}MoblR)j$K(I=D<<$@V3{JGcot6J> zp)aGFGAHAp1oFLYI|w&yt9H+$=p6qjTeeq1lZOsyzM z@vh%j9gz=BY&mV(+>OoVV_wobiK2dmz%H-f*%EbPQfe_WzU6*{I&E#b_x}?QPfXV3 z@#Ns-j4(lwgX%80pI3k@*=}3T6mgd)US5Q*hPs|TN1BUuAuk!E3@7_c|2_=~#AAa3 z$#P$`LzZ4u^d(zk*6WTLZ8sHNJ>FBhkCZ!5-`)gCMe=d6*Ko()oPnn;2aT&LzF}zH zbi{ontJ+-2ok9iZBAQn}x52~>*d?J%*2*%Y=4PX}qB4h@Mf~_F)yVwdnTzX5CXVx7 z_4jU0Zi)zt&d-X>h#ucNi-ExS`v@gP^E%3){Y*5g(O zzKr*`zeU%e3^CNWRQ9K`tNwT)`i$)b8+&_u(=bFG8TwvU<7$33Zx4IBd&`U9&T(A1 z@JeCK0i=Ul3Ow(wB|Z~NsC)@JgzzTkJ#MrbB$<%usb7mrEVR$k_Vgu_U6Pf{#M&H# zcFp`A3E81jyGKw^eK7m;it?w;GQT`PHaty=bbXV`@GnO;3D3g%#C%KH03g7AIvS&E z_^nbvA#HQ(H@!B;9BpPqztOp8#!>uE>KjGBjXPxGuzFgctCIb1?o4K8%ZXATuW&xH z?d6XNZV<84Ok8epv_DclO48}~Q!01W#;(dfCF|-!XC0kz2`8DN(FWgstA4Y_)u^&oU`yuN8JG?3PmI5|cIVl$frW0>VWK2} z()r@}mtr%x0Q^4ErSh%6{)WR-XY3``?=MH!)>l%2$`uG`rxaY+l&`MfZKxi#aWR%8 z@?pP`@xUce3vXM#PT2OIRP!u?cjMH;sh>iSROL<{``jT77^m1-^FMC`KPJC#L&Fh`Fnz{mktg~* z54(j01HCfC9WngvnPHS*WXq8@_0lp(x^AapTO`;dop;^c(+bNN8a;#3dz6CGK7amv zTF2a}1|`^~PWe@MA3_}~HcA>rM^HAT6BfM4>Nb&#Rr(kc=Q|%_p^&AEXJ~|LwG+*3 zFdG^)A_W@h?GSP&XHMQe5kloATZK?$9Z2DkW<_b9+5{i%menX~%nhy^!4}W$4Iq!U z-K-mD-^}rC!`PJl26gS}@S{*j%U@^Z0}(Lu>)9dF4tw$3$Ug4NUJ<^ndt$&r{B`R+ zWu^XNU-kH-JVp9+jDJJ)4{wxTBZ~h-9kw^r8R{KCwjT&~&AF;=PQ+_)#RIZr5dQ<3q2PDYui?q)tH*o8Xog9UUwIf3r0Y4T}n;F5MNF4Wqm?qXo}UwU(i! zwQ6=AY}ID<`f;Lsw;8z#KO%~Y){802>P3<=>q~?Go?)Md?^vV7QvRpe{9%CFs=fU` zllkj|v*e>o19&ya*!bDwMRi8wkoD-Pnl!#}ewL1R=l)L2VMwP*|BzsffQobVb^?0n zB)wJZDX8Cn59Q@;Z?VD41je5zDwBok#X+}d@ODJjF9hnAPgluyh4a^nF*Py9ZW3+& zY@BgH%&gFoIQPU**D4docMRKtP|v;bW8{p~3A5(d0MQyrjH;O~_ik#Qzq8}S*~)Dw zeT6yyqn|zcXLLIvYzl9Jb=f$W3Mp8e)}geK@n)8l3vHIbt*a%!XmBtf=)-OIm;k%p zR*9en);+FiUm8Xl9~lQW)3w@P`QLYP9UbGegTU>j|Adtgs_;}$In0}^G42itegvH$ zC!pWL-^NYc%Uic2IO|I2e?6G!YQmn|cL!4CA`ef*9(K5DpYSH*CN!1x@-xyFnJ!ah z=5cu(ZHD=0c6MH;;>>BgcS$IKGT4k{s)=`2v98{}4x7!0t5{O2Ds_lYVe&ND@BHo4 z%fMT=IvYAgdLN)7uS3S!P;{}}q8OVxZ+{&a7u7^%lw#j;ikCudaAXEmf8Ha#w9FmGTQLXx#4}i+DWcESv=kT9x2C7y?<4Hq&dOBu&O@g z&aE?}YTc3vf3XN3!=;EZT3P2x|A{fjd16Y}!AK#HEXYw&aeCxm2l#8N&eF-Unw9qj z1Do!~#YHLyc6*&s#c``{%58Q~R`yqNZmitesOJ#yak_e%xG4h#H5+D6lDumA)#G(>0IZe+18x}h6Uf(U466{yZP_y4z#SACa z^Yp;Mo~6=mMPwB@VIOn_Zpf^CG)z?eDw_z_h2X-e;OVe)_7iSmc#jf;ES(#?2SITl z8gG>8gjO}fQ^`!4 zi!Yx8r>XHlo8%2I#e17HjX|{Y4_ld-zxvY3O(77tmIm{LW?dX@7RPN22=~R;_l;Qt ztHe$5Aep2gQS&x7LnIN_|3Yni@AcI(bfhFAGVu@rL+kX9I}(k-G}1vI!LAeA9+7f~ zbj&%QuSxY+jbMHlq-#?k;?o&M@g|l@T|)E=NY2LTk&s-M!=rid?S$Cbm$#hGKb3jq z{%xEoQevB6##p58R4KOWz5pB9Yslczn$Bwh!K9m0YjSYN&92UIG=Vw0@~xKv@r=y5RyM#tVn+r7^h^}G5;2iGAvXj^zc(n( zHZt`szaVF}dYU9@45)a`&CON$a!?&o5I(3&`61g^)&D#wPaN1@ynNZ@nCQL7ecZ}r zrGoct=s8B)W9|s>D=lwfDx@Dov@#okXE+Hhvo>h6kOCY{2-D^87nzRMcS(WtYdG(R z@MrelI~K|hgn-}w_c5K?`7=Tfo2kH-|332XRQU7Gd~d8KnjV$lA|$9|y=c+zl%MK-AD&_C z6n^eY=kEvPg5?%s9+a~yPs`Br=;#Bd<$*2wU7rbMfvtlk+H+i+Ma)_+q^|}Hkb_|- zx4Sa>ZYEn`ej*k{Mq8mbj0cIzzML;h+%w?*x@7Hi`E{aJW@4KS6RWY@?uEv_dV$&N zrA^y2^nrxswxN|Qg8Rv`+)>O@2?IV z3^vPByWW*Ew}zuju42+YCryP3w(BQ`T7b!S{7ot9n@)n4&%OP zqS?vc*EUM^U( zZm{WmTx005Stp=f&CJ+Y#iUVrph@EA%OJgZR7G?jVGaQy?JAA!o!y)2%S)4R=ng+( zbx!5Pn5RGK;{d2#WTjdn&V2)LF73%4_n&TMH#Dsp%LdN(QJHF`gfKdE`%jyHqw{$& z-p9GkZNk};KKW0;p&xd~VVas|-nsYhVLHC5rn3Q{t0EvKct5;MYyOTWFhUJ`QHE!& z<*FpF;&^ZM9O=|eEI4E1Q+f8|#9|+}UrMihiR$z`7vON0f1j4Y5t`Aw4C(6(f(v z6T9)qNGl;bPd+DX4-bzYhazzD%d-r(U-~X>#tz#TL)J(%p(t#Lp0hQX+x&YYI$|YuM5y-h3=g&?I>Hk-FrvElcZk#4n8TqL-_y!gO zu8BvU{M(cI7Bit3-Z8X3{V!>73EM)?eY%XzV|`_JmB`vG9pAR?WMSDV10}PpK-$Mc zL9MLECV1|rzxD6S&3U;Uz5|wltz$e6&+>PNqV~|u*nV2`CT6VZb{qgfEx3xNyfkt3 zrctbDX+A!-S!a1)u$BSEF+=|~;PLIieuUd0Yz%|pMWsz+`3uUU+Vc~kb(aa&fitEU1See=p{7n9M)pbg(x*?0NO;sT~eSQVjG* z#}0wUso#6;>1^!EmXq;*9SuMBwnDOy`nHA|#S^!l3gIdEGsHPR+wwN9Sk17J@5$7! z1GVr}AHCHx=MIJQRQwu2=+}=$J18!Xl#WzpnAYfs`5x>pPGNa`=N`z#;Iyn&h7MAf{eEKQ3;ve%&$WbgevC8nzDzYz8)B;szW3XDx(rKqeN2q8k<5reEp zxyeUch$~1v1m{Wd#C&4?#s9XUuh>o`c#s#pHYw8)aREc#H;t*wkNoiTMpQNhV-S3EK>b^Z&G_{SC1B-2SJvpNCYs$>RkyEUD+Th`6!NG4T0rG1 zAY<>|(Y{afZ#mteK&7L7EJ$_iSUXQ*hN;L)cy*D5Q&VO%2Vd%viuyqF#Ah?vNvNSJ zdzXh72fsB5eQfeb=_|->1R@)iFhR|*VvQEIalm_QT-xV~(3|Z!(tLcCN2K(LtI&5h zT)4FUuukVSwdRC^N&UcwBh&P#`H|50hynmToTx-;YgR8B%E&C6CNe;%2~2M0+6|O) z-pSA#M)ZqE-dw2r#pCynZ_Z*mJ>2?5Q{xdw5;ZI9eC8f6TlY8+P?MnGLerZPqfSRK zZEuxkpW5sr^MEe?J_av$ZHoAMA3j_m@?A5L)Em1Cs_mpF;M`!k6-e+wniW~V%D z-r2N3KFs^n!fF!m(}w$x{yL)9wQqB3%yC>EaBd%_U>(`llasfc`tK@7?)~`qY)4m6 z0+j3<&yT?k)GvC)695>s@k5VgTd+?~HDi@W%zj)g$r-pK$`Q*GlC+OBm>lqWujs8F#9zug&5Nb!zBSC^zglbpceo@+YUk9g+LCZ+lV5L3 zW7rmMK0!rQ`V%sly)5=t`=p&gKo^V=DnojfeZ+!eGa* zbz98)XEE@}{8**I$z7kg_DZMU;&@6NQm`SUG7HUL?+!IE@O~%QCvm)9EGw>T-T1Sw zcWthh!d`oKwpQ~lviQd6&~Y$GIG%W-XwY^Z26ryv#W(`HsSSPd_XovbiBWjorwDO( z^aG7M(LUK@kp$`j!Ys?(d2aSWid(31S!Rfi7c*pi5l2iG<572-eBK3p&z4CWFe9k^ zt(L@da3GFtRexd$GFzvgMq$JBLl?6$NK$C55mns-VtV!=%qIris0A-c%< zl3CFC25{T1OlPIX+PGQDCU9hSLuk`fZnh?#R6xA}m9NqOMjNea9drExy*~d~%z7gX zuE}cVo1kzTyC!kG(8A7SV5a@*GlgbW!L5T8k&4zX@_xh>R;FXA*|SL~`s551j8~`R zfA_z-cITF1<~6cHst6}U-p{^BpCy-J2u;Q+>9*~+_Zj{&x6dn}p2-_3)Wy!&U&jr0 zTT%dq;Zwe3=+B8yjVgbyqFSRZsY9O#zF(Kv?uC?V-FU%D?ss#3%`)_~lr7 zH1Vm_`tXD6Hf~f2b~Y`Mjo*kXW`9>-uM41D<;Yb{&c+vE-p8Y%@E#kbpZc92n!oZ&M{nBG(eB|SEhZeDQALQX*d>6BJFm2dV zpm4Cmt zsP|k9Km}KBQaahJ%G15*nV(dwW6?3PDjnMINrUr+_m!|K^DULz*Ba0uPk(TzuVllw z3Ia2DUx*Uh$Dl)6N*nQ<}1$Li%fWbkr)cLUsz+uc^m4{ zhA;x$z-r?ZN6g!i%;vHT`J)J z(UFByk!%iTC)P_Jy;)5)eTd^{^&WKB_3hp^t^x;kjo((X;{4}f|L=iIB>j7`KIW6L zrdqrr19nJ1Q4(~DvkX7~faD&x&km_pDmsnqE>mm+keYDp#K-p4*}Y+C24sG+TM_^4 zRPeWyb?>U79n58U-Drok>V8+Q1Of8=@zTR%pyUTmH&Py9Toc0as)UVl0O^e3UD4IO z;iKomfAmndryJEUeX_L)Kk=oaZFm zH)jh5nc<~9zp{xJW7~x$o?Q$cR8>h_1Ec0jx23eMsYF@0?k#Dt4kGu%Fks#PjPvNj zaXl_|d78eR|5{L6(3*)n1OLy!DVU=cTbv`}os(*0**g63E|Se^$CZ6EGK6bSJsWf7 zgj8VjHIC<&&%!kA8fk~1#Ld%7(!cXOId4$16lNXOzJRm@uzDy2l-ly3L%YqRbtwc5 z-x{VLWYsX}jD)IoX#p4sLC{}c;0U~~RRI4ca5;h->+9jI`d1a8TFKsQdyzAQ(tX(0j6yR4dQX{TJ}YH!x^A80@;-)9dX| zbK}Vt>pYck(bHeYclOTu0L@U3j*XKME`aeBocDttgDWIL^!YPhAr_(Zz0JeT4HeFM)h2i}4px@W4vzDo|vsNOa^ynb=)={*V^lGL|2 zVMwuS|EAa_N()si_8=uhN;;LXKLq*YL)}O8Q}9dOtaI~%4BLJDh3+Fa`l1+WRz|>z zi6?x=gQbI$+4W?vQ7hnvD#wrCMA1rS=qAC1CXJ)yX1w_IcB)0>dwB2<17ay9<~oEA z|2&7RI1)6kV<(!n>h2B7jK{#S>EY%X4|GejuUYPxyR>AJXdTV7g0E1S5jQ$fjni;I ze5{kXoj#;^cC)GMei_3QzGJDy`F9?rv@fAPt1Z)hs0G-Ft0A8Qv9ST$lcl0OOHcRH z@1ORgP_owLIIL*tdU!x#+Ck=LQ)Ij0KhzA?)@M%t5a!lWEy&@ZD2Ne z^w>7}%Ad+OJYfIiX=FM2YXIpA#7dYDH5+b%e*Yps#gxL+nGueQ>f5@}x z?-#cz7aPAi&$zfogLlI4cg~1+qI3H2^;MM{sx)m@a`Q6xsgaRL*@5mYUC+g)==mMY zei$5Z$2_BsCQ5QI5iSJ0CZPtOdTOM{lrwbWpe4>Aw7Q|Z(6gPkziLf zM@1Iy<~j1Q@ISx+>@#o%sy_b}*RjP@ z6A!3st1{Ps&l2b6t|-0EBkx#Xi)Y`a?RW1dB$Q#GbTBS&IxG5cY_*eS?CF)j3?B86 zq0!dr0AhJa(8Pmsj9;PeRU!QAx57UuK1wn^v=xx`lHp(KmNWbJpC`7aV4(HYR%$L( z?in}d=c9Ws04ntHsQj3n1j9A-Uw zD5-{B*fhGEFxhu!yrUh$AfDqyWz<{QG1p^3>ki%7ecIuG@ZMxpWw9QK$B3ejK7&eU zV1!hq04gQ)PJveQg$Ru?M_iP2p@_F1N1QlF{Dk;M4wWz?;`ZvK2i_R7`$zl8Wgn8^ z>2m3*DM@$^eni;Ufk~VB24)Qv*6xG?SZ-O?1}9%~ne|-SoC>W2 zN;?WC^>h=J>rB4GZ)96*dM`Y`q>|}8mFE9|nUBoq1M?is6B9iCf+7nR9>8ni^ZU1Q zwW87~@C2PFFglt)yn&T zj?P1;TVEY~G$}*y7x)ThLLw@0cd!|~`gQUL;bt-cUC5S-Eif8>p2)u|Ok1!tZzMei zP3pqbN5#=`9O-+=0&cK%8ByyAmRf?1#WZE}Oo)p323AB%w9d)+^=@*S9+E(w<_a>r4)es6WCmWWiv4#U7h|?U{G51Eu^P z=rH_G&Mi_}d*{i&sJ~3H2#$^ZNSw%QrbfE<*+k3E$$5n%vG39hS$uCJ$hhQ39!j@q zuS>EHUS!-xJix4-wkI7tiVGYRpR8mZb||mrk!EhC=-RN>qN>Tmwe&^@V<@kp~)54yZvKPITWq8VWZX(X%P(YBMCS^N3A4N z;F;gO{Jrwm$(CmmWjHO~AU4J-&2#jNLVD<OJZej)W-wqVZ*9rx+E^Dl!VnjRlG4kqG~S{!F=)O%vk3Y zM9lCP+oy&qR=bjL(lZSk@mMs2oa zD@s$YQ)0k*&9W#VQ`O6KPdsLi4sJpL)#UECm;mq>89Esc>GZ@R0uOGisdke}w+P+< zU4}%KdC>E)3*FTMJ3S{A9j~)`J*7$@P1tPA1!)K!amz+y>G_f$>yF~@-7AGMp;9e- zeEYJCbqukaZS&4K`{54`BrWf`0F}BDxM7u{9C!QftRs9veAA}Ke7J1i;X_u2One%R zsekwb>)`n0DfmJS*@KZ-?%C|Vd!^Yy4g%(#e^3lYi!q?W?^re?#gzReM7QEq0&vDl z4{mjbB<-n2!RJoa_?Uglo%ZVFa;$GcSxhNtfYm7C;_VWXaC6q_0HzX%kE;1J5M!fW zXw2(9Yv{saBLsO8#sJH7vXN?ejKthL>DK zzK2_~Cm8PGh6OYI2hWhd`;0qM@D_gcMV&C1KOhUJw1^HJ!;f&`Q>%6Kvr)CHBT7(G z*d0>n3b`$E-Ydh{vT~y&`{ag5iHz{0$Xu0%eTzN8R&k8&p0Uiuh6G|a{PPMPR}<36 zXsfa3a+GgT$awk66``Z=g+zIcMS{@XhQ*J=sO6`1+Fr@D>Bp>ClBJSaig`9sVxDt+ zTT;Y3wJ{rW)41UMLS${ymvVukWnR>pf7W!LIV^KXx;f4G3isd*2|yVZszS@2DmE3i z9kKjBeEoG;)#>&>4#O5C3|d7}=~k2y2?a!2X^>J{kd&4(Knzm43_?1UE=8mp0ZApK zyYshhj5(k0b6wB*W3Dp}!|eTzb+5HvC01nQH`e~lX_^@oROj*s|7Rcu|2sHooRXQ{ z|0Apy>e4eYNddagqAl`;9Xvu4B>hO00pDxGal&AG0+(zce*U<91Ly02ZkU_vBQKb8 zds?hav@HS4Nd~yU37}^by4t~>r_H1nLaULfQ&&eN)INF#-sws=3`$}|Yzy!l;KG|7 zEGsEps^@si!buWGa!SzV_2vMZJ%#k(^|a9&-L1eAzSh z5@}yW1$p7Bdc((y{|$NKm1O8uxEd<@-+61t85kC3!v28{gdXi39bDTS;Qb2ZAVhBg zG-KltI%I54Mm$QxYEy$#0#=tIaD9EoiBA5~XZ*CNy9V#)}7d2dAb zg5|R%b5`_Gz+}%93^?90;C`WXpmf4{=@mDZBr{8y{A_~2dVjOUQ<6g;9fg$$wuIfw zTTc^7=xQEL8TI5u{=ncZK(h@ zt?iLOW|LX4J%gPH3ry~ga`E?ni>o}mQSc~uY48A$morle{#i&^6cHkX-*RLkX&Alo zR;L^A6*#A1$J#IZMXF^8i^%_VbU78jB`erY6i_C@R&5E~LtJd`7ylvP=6EsZdjgpf ze2#EiNx|tiJm~PUXS-7CZ#XW z&>JE?fp50R#sAE=dDkTI;H}+b1Z-Sv;Mn-TneTC-m-;niqz=XGmMk)GR3(Jj0u7Ax z!vUzOjOgB0Y$gQAwV&~3SBi?XRq5h2Qy%*sP|rG`1jpqcKcGwRZ)b@;IIN%*54p>i z0@%uASnO1b4|v)=Wxhxvbg~EJ-hkrqC^GrFgDM-qG4i&AHTW%cTm}8X%LJ{D^be9k zih)M##Epz$;SJmPayjy#V-TMpm`IWqX=AYm5qdDv`JW)@|6gbZUl1+GR8n-)+O(v=^Wqh! zmNLLCQv1>3^f#cm5OoTFEmfn3M||bgOE~`IpjjVy_%=EkU;(#|aF4)KN9oQM^8T{^yA!7v&R07{THn4+QnI9TrJa2v#Kj;GXz{&?S$pFDdUfPui$jDZ`lki-P zL2$!IOX)|IWT${3DIamJYOcCsbDXN}*wcS)moxZBkHN{2Pgx8OG|2KxU*7LL2|n0U zmN+%|3E7X1zLg3)`~@6p(CQE-y8owA3ZR}miQn+QO4);Nc6A&22qr$hE@kPoe0}>S zzPDGI-Zdo1DUq$K-qK*2ZrSpz{#Qev;2$l->DfWJi{ zmp7>g&dwER7CZ}&G@cR0fN4P(ENvoCk_-D5^{l@j@QqOJQBoSLHRXUD)8EGBe(>lU zNf-ceI%&%lM80EP@K1t)Vl4~i8lVfJx4;%@x(kIS*Psd`1TKSN$G{A1^rMPOA)PlH zn&`}d2ry7bgaR@YV@^dJG5mJ$%3||mgSFTuVAc1&k&uxcM4SPu>(X#{ErxhO!+Z3D z1rzKvHrG9qMUDAdvY+C!EpCjEE^mzN6_bxY0j6-mb9|Qe&AKLo-zh(5fWqkZbkI5M zAMmvCT-?qs*RtuAkI!nb;;8P6(@a2@G`j6L=l2OFqo%lYXb? zo}x1oXdChx+LK&BcAyz(|DCXU1XH|uA5Jx9p*5g>9?wFi7m&pu4-534pYSg>al)XA zyS!`->XC8NG_{Kmx)|p&PMK!%K&$psb->oljuaPw!`Gq=a*yx0b zx^HdVk$vG;X^cH^BMK6LUz5tn$p$|zvLEYlo7c)rgAFpW zc?wR=8!M*g{2CN(aoyiR3Q8@c2UzDd1M??J1*<-ci)!UC=idc02sIfI*-SX+SDc%o zRoSZge)Po)gap_Fs;N{w`GNi=gnS#P=T?@+>^4F*82Qe({ZO_0S|i&?rgRi%?ieiT&H5lBhWxzjIgpYdn?C?oc_rKgTAnheT zb;0CC>B6TY%D_o5hmywcR*`;$a?>IOsA%8xQMDDNtD#b+aSx zmkM7gnA)lCUXrliCL;N(Gdhd}&SK8`t|j z8k`Qibapr0w;6ALo5c)v8X5D?{Nbr#^85Sd$15jCP_M7(txIoO(w@9 z$V7NfSXc6s-Nnl%QBQM*4F$;|r$r-RTH8TzqVM72MKd_omjFxgNeC4_kx>K2hX?S8 z!nKbA*Wm3#siAM92?g8gX`Ie%Y&pXY)CeR#jwjb(Qw&}MhaOqC{iYSbjs^G>O+MG% zvd+7KSWs_>7~fe11t`C**w>+i4c&MG)xh=B*MkJD)Ck*;)&|dW=f@ z|6&Gvtf)B{q!|Air9V}%Bf1irmC+$r%W zt5%BRth4C8M9X_w=Z@<-zu)gy`p?Mi4f-xO`XQ0=znNF~8!2Apx6{>}TVjPxP2N+u zufDtkOX58sc|eASH+MGp4k3#Jt!pXDi74x#SGyhhgfVCi?>lFxx7S~{3wZIO@tdFy zy10*v#jjp{Sh~B`hr(c=SzZ0`47j*zhlyx8qxv&tu0OWGKxZf*GmCQ75|XFSGkm+5 zrp^`8>GAoPfTlnaE~MPFz9d5h5rDey5q}7VK7YvDq9o1`U@;1B+6T&80t=JlGO&Kc zpYY28o0}X;cGv*eL4zU(8)t!}pxN`>Oe}Jr`in@#jGr0PX(x(&^z^KA8*uo4I)@4* zm-h0n~<^cn&Cp zOWTq}4PQ3ido$-(thCE124qqZpfnU%;AC`kw-S4E;MRcOAW!MSL)}-9N-5ef|K|5- z>BWMZue}DukJ;mkohnLxaiRc>9`goZCuBJ8<_qbso!x^_0hekPdTB>i0>tWnN2ozHYgVCNu@COxbErIqSU!(*F_*;v={bfZl+YC5slZm`} zEKbjYDK64cYTJbF%d)ubYt$ZE7~AvWbpPhm26B1BR8`Ls|KN`OJ&*_?Ypa;GNG>(* zdVjBSy-TnZXKPe}xR8eR%-jn;C7DGw6M-=iLMo)cn(}6H&3uoeb5>GP`quxgBHl1! zxX}-AjsFFi@NvAnm~D{6c}^bLM#1L(n3vi)DV)oQLdXBILyD0zy4xJ!gtC%B1D`Q3?e}!g3_K6g#h!o z8RxNOj$Al`Z!reZBV$GJqIVAPELFI~>`|-?aw&qc z8}50n*jBTc@U}N>m!rRim5zxQ`A zt&Beioz!OIWk6FYtXvs$2I8$x+bva{zvjQ8-Sxc;qD*flVxxWl2P z$aRzK*~(@fa3@Jm)XbevZjG@_h%Q7{j>u$!a5wgPEL0+;C(10x%*Tr>L3_gnTdfan zx1rHBjw9<5)1?dL_oe1bQ@mb;}%rAcHuy>F;PzN$F^P6uq zc>HJtTmKJNju_tvU5m}R^G^S+g%U1|p{zi&34={cB!ejOm&$z+Kgf|ZCJaC9ZrV~i zN1|C^6HcB+Ii7i(DnlwSjmBYah{;*}j3S5k?Z@z0HhA|Q-h`gDZH*_CkRcdO|IYmM(o z$xn^^LENjZ=eg@pO$-y;%JQ$VYE*V@-zEat!#cbNP!#>9sIYqynb^thKK)##Re#zw z;vHy1@b*Pap8W0Kyp(X@;AaByC4?1Ege+2$V|ya>WN4mvIgb=IZ8CZ-)ZMyHvEb*v zx1>K0i>93d4})1*L>OXhv3OgOh7urLMuViQZ(_>Q+}mm4eOVB|&Nzxz!9XAx(43M- z2Mek%+EtMWj;7Un`q2O^q+CCO!eN}Oi1m9UsT*=C;zc2?G z0L~#Acna{zzTE1#P5t}kzVM1$Nr_Is&+uT}8N@72(<&J68)SlL749*~RCJ1N-e!{I z%QG3juXN!*bxV9slT81Qy~S;~`4SuBdH4T4DQegXHCD#Jjh2ugKuCf&ga1kCHOKb8`Njy>OoeMLx649DOFv3iv85p;IK^KTU)cu^^x~z)z}NNl0Z@Jr$AP~j^r1mQfGP8i3I^Del+u&DdZzn+{!U*t`?bPYhx?F*v+vb;&!TqTsMmXd^xPh;TEz)((v!GkWmiOwA zsTH8H6D`awIKAp|wyPC-5SPvkg$KEwv)z3Acwb?`^TMT7*n^#W-fgC#c*(jel@$09 ze= z-?#?-$xz{iyUn<$KS^~r@rNLy2I#|>q@I!2ZPIJ45T88B0v;=crM>lC-q7>kA?-(z z?3eTrJpdo);BbcBu6#8AY^o%^w0-v|Jrbp@0R)ZviFeo4AK0?Nu;l1#%mD{J=!C2* z;)Fwv+`}G-I1kdI5`07@Y~lE`-5Dg;EOY(vf=ZzIXfF_TT^6eFqy&zU;*UxW1ExYs zN9S4e96aC=Wdr>N}GtA?9A&cq&2^I!qop~CycKLZ_A_g!Cc;d zm*p!)Tfr3g-Q$8S;7vfddJOfkxgf4_Tk9{ZFF0`VN84;imPI%_u0yMTS+ok4K4|V3 z114<4nkH!KdDWa@c;oA zSAxL;d%)mz^gAG4DHsmSqbcw(YOsUhao%FYTmqYw#*rcHEyxOtn#xm;U`_|=H4 zitO_X1q^?i#cWU?OA-5=FRKF#*CszkbOVQpFmV2Un2@0W^Se-Rsz^?PNK%H7&cP2B z8p+=~uFD&L1z-fpf>Aq?3wbBVrVqt>K@~T1Id+VA0nZx*pE5{hzO%arA`#vI z^M7O%{EMh--2{UqDW&)(>a9x^P@6?X+||?a=}up`#!V~qGmu|H^;PxC9M=~*SJqZ5 z?B)L|r+B3ye0R4OVg7&d0g%C5my-*DqwtwJ%YAZWBnDJTIZaJX1MXK^48w-#oPBWU z)SxkT26eh$SfqsKaWlSkaN8*CH&x_`fO*aA(=L$I>^ei$m)jrT$Qaej(kr80{qhAB zR7V_y&I-NRg$1Eq@pIJig5wCvs8-Y`n>w~?>a({~Yx9kLM*GYVyO!>JkXrPO0^{91 zjs;}W1Dqmjr-ul)gon(YH+p|i)Z{Nv=7@9gjXPW;J4o=0p7-(fjXryLOMB>K5NyN0 zitV(jS{6Jz3u!j;`+KBXNiWn?%KuyXc!^&J^ov%xAo|O{Lh6s?nurk#Ybj2uYm$;r zJvMZ~FGi3=oE{G@+ApjCxiW4vqlQRk2J|(yW$FsMfGb9+Xz~ke2Z?WBawM7NU(5ht zx*4g|e9PQM_(HSWiVr-O-=EO+9jQsbV*I*;`E9hYGIv~Xv z;GmFTe>Np0r50sL4vM>Xz(u_1rUVuk(ggO$Nr-c=r&dA(!;CD1nj&Bb4*@tFL1m?v z=-eKO!05v3IHOt6BoWf*1}y{N&$hSX@1t?o2>$^r{F&c~z`kf@l+pAZO#S07ldv!u z=PL>^gJvxmX-~mjJ$Q@)z*1iOad{+t4Jm6s3eRY(3N6Ygaaxk_IT{3nu?y!;)};S= zhJl`iq&{d`EExwDO(dCV84VklHMA8B2Ir+|+&WG(P*#GdUblmS;8Z2nMDPE%-8+AT zQS`$@@CV!LySE+x76kCxxESdU=8?gHfx|YO`ekf0wpfS7E2Ys7;>X?AJ@MDj$1#fv zz&@};Y#b96aj1f+lN*}jP#};R2}zbe*c=7UrlQgt(9|M(@Mr3)UG@5?Rs`x|@AhWN zB%& zjA5ik%m3DJ*e%9!h?J{T5P*f{6$2#PidcX78;gTy*AxC=E`I%q*1w5gkL0?70)f5JXa_IilgzOs=VH1un|Fn z7a~3x^*&M`FB^}tXdLG@Mb^Z~=@e~J@A7WKcG3kP_c0$TE1Naa?`Md!F@UcH0x%U7(#Pw& zH<-2Wv*Pd@#P{;zIS3G2E_Q+4Jc{F_1QH`pQdNWpJ6ca88pl9K7UcVk!GB?W%3K~6 zMfGn^>IEKg926)CKBw{Ks`AgAuZ+dgL}H=F+H+`&s2jZUZx!$qD1`6+Q55iRVrOWl zQ7Goy-BP~^MJ1$%7LLQWvYb@d5M=`)H@93J<12v^W(@mReww>KJAi%sK>1ihZ`Vr* zf7NrHWb$pYE}7+TBNF>?sf^6TJYCl={y-Kpbi)hxZg3N=(i2-p0WP7;8<(x#m zE;2SeH{VL0;|%3H*uUdEtpppe#_4fb-Rkp=K&_Vr(}qJv6!IM*7+BK=0|DgL$_LMJ zlr{@=hUanLe!aX78~G7{d|AdDbEvsfrH=T`b}OB22+afZrxK6ZE*<!&O=_QJ@DjHnG<*96&S1u3 zAv4f;aD#*Dlh$7$D8)E&`fAZ4bn1;VG$1TXMBxQ&gc)8#K<$B9@449*M;KHnB0xro z)a7$at3|Bb+}x_>ngRz4NFtm;&wcmhC}7DhhC-cE0R++g9EZ;e3$}4i>0z|G#kcLK(s>D)1WrJx~i#;;yd6;K6nS z8kexK2pGJA0ik-TJ_bwLN_!|%Zp~qF0}QX#TJ}NkAKjdPx5$GBwtjPzwV%t7oB_16 z*1>c%Utsl=2wRr7bnpAp)UEjxGPc~n@Y0VtSr5D~4=8!~IFVjffhf4Ju^VoFj9#p| zi6;zg3d-9}0z)$^4sQk*U}2t=o2>q|K%=NF4&G)L6jEujEG{oE|DG(@1Ls902qBEX z6vvTo1qKNM-`}^sk_rQ@{t~R@>R`!i=~Du`-9~UxvB`{?DXn8VBa^Z0mI0=GjXd!8=u-=-zz1avuM z8CE~vzkNg7m*O|8?Z+Q@2PPq2U_EZa0#<&hJTnIj0Z~$t%FP0R6M#|dEv~KX)x-z8 ze2istc|16Ep_@Q&;fVatphz|x^iH5}G6tu!OE!(?cG2nJiT?{mdso1V&j?t)OZML z-$*;mqmdaS#Fhcng7Qf6cUwA@ZEX44y%j*zAw4nPyPib$t10C3iFr0QRc|WmR}n06 zftZ59DSH9W7;#tas2H96>xw+LnAyOgT3b0-lAMPdG}J+FAyNCswU?5gJ|V$UogcVy z$UUVIydk?X6*^|uJm1T}0;&c;B*%URF$6nqb9$wy&ft=bvOOxW(J?@6or> zhI1x4#q1wx2q&`=Dw8o>po8A+B;q%>jR=4K{P~c{o0OE4r1lu~zOK|2Ehzwa$3Vpv z281@e#_thk3$V|o-B}lG)p%bQwdH`QZ*nLEJ>?yK22fm?-4gGXWXDNPr))Uw zx(W%p=IiuS4E-S1expm4O~Z8C?XJIfdls|%J~+K37}<(B&>*geMU8(b!^qcYM(3Bx zpM7K&@o2NPOkD4#Qd0^bksfi;{kk&}MnD{!dnv$}^(f?oisSlvSIl27z}%}{3196& z3!3-C_X=cs3CI{VethB|2?iN%!1eLJq)u;ov=HuRI?$#5rife-7kdw)%iKN{sH=%! zO<;BEONp+TT0im^yTZq&FBVt<)@qVNJwTr+NSShmfp2*i)D;bI#30OQFqZM%nZPGd z882VNTp5Pt{@c0%pb+LE;zoXMk-EZ>(H=;e2S)wMQVWrrMH^A;2j!GFOfX5Yj3vB( z%s)Kg9OEW2+Ii8==%iqFEa9aQH`l8ge4La@0I%fjlFR2hUvftc&&e989-oKaB;Ty< z>dIrhvu>EXLl6w>t9B62%un2J`;~?^YdE4z%?7LxAPfAScGZ9$;>NyB-ZC>*{WHBO z9f1wF1~Z^e$dm?|NygFo@9k=eA6c~=DDIlG@PyUDSxnsbYF9QPE&sCpy|Jku{t<6M zGZ9hl&ZLwm>ybX$mtropGB8lQtAEE$GeVN@9y{%ZCVgGxd#nj;vbHD&^_~cwD~(5Ch5nh&ey+_=Sy{Fm%l3{M!h4A0B1^DWj1QVu|NZ=PE z<~cZi)m=mx#9a^y;$;zgsdsCINUV16j0EQ`3%&)?GB>$4$63xkAJ<3KEutZxvr6xr z`t<2@;!L!)?2nSU;%8&+75nw&Eb*^K!NTzA&o4}TXR01lth~Re40uoGT{ksP5)$RL z)$V&+9Y-$a?8bxh{o9gj<xb1GQnHH^) zqAUdz+UZ|;A7k~PD{(pG22<>KG#rxUh*my#DgS!_GwBrHX>E7SG(l4Q4OGGPhp=m; z#YX`v7G9zl|{Qz#Tf0eR&=He$3c~ro-co|GbM9&`}r7&u%5FOQG&&9jQ44 z2xhfY+(CWY8+8NditxU2k8eup+mkgPnV4n}v8}sFed+#n01n-X{9LE~6u~jr#)DoP z@^5vq6|6uL>h^}>{;wULNj%ZNYq3fd%ogp-@_Em3@S7JMwkX{b^YUZ}x_y5;ul4R$jIK=pA?*5UtZ4Jm?ML86yQJeT<_^VKYaky zHukoE)`#AEaq0L;;4BoXB&!bW-1~n0$IW;5t$eZ8?YXq^G1Vb*KErDXj6!|sk(Y~I zRMZG&y5x+TyESO_iq4+YE(l|hkx7+JnJ*`szrQ|A>>RMi1n^e5dIsZbX`-^(CofMk z-JI^;x8{V@;vcs^w|5%bl-#r?P=AYs%PNjdc*6^Gjo@7204uXw>f_g3CQ3QU3^nD- zUKsM%Sh%^`SOQPrY-M6)y`KFbStJZZZiznkg&y^j}@%OB#c!1z9uB!JPso7|9e zJK*q4-tH0jZF>P{q=!#o@b5@rO+lx#avU)rc&+*c9~~MjcXyM0y&bDc^y7uv)tVop z;!ZdvebY|)IU~j*ggwEP;C-Tu`Cf3Z&qTR9`zpHOYU2x_H0CX_WhSQ+ab-m2ivVEB z07{G)o8S6fVH!ePXQas7*xt7IW{OLAqtY2${uJ7sIaqmFSjg`fzWMiszmZnD?*OZF z%Ca1MDU`t!==uC5yQb4c;1(S<>#CN?={;WtB8!4?A4Q!Xi)C(h<6RmmIDr%cd3U7B z&N_v2heoR;C6vaA7VcJoVVDr(sAtx%+B0Jxtxpy_*gQ(8?=dgpVl(WO`iOJEtfSM; zsg9J70Q2QnVt7KehJK>?v#QyodOKls@zG^w4ZP`9HTyv0@8800>50X9s09gT@3&rZ z&eYa4U&VGKGq5QsqdC9U9fS)uHLo%K0d!)SP7wnoP8yMeIXfTTfV%Sy=3-D2@_=B@ zp#TSosc#u+yv1PIB#Ak6Na3z8)lDzV7B2BQFqO5_0w~SE?pfy8+=m^AIvxWa^uZ9b zTV7mLWPa~cw+aCyZq)**!5GFSQcB7cy~VY)FaSoc^bZV}OJNflg;c^c$bsY~20sHb zp$~PYynRjl2LG|=C5eA7cBMZ~VBsD6Ay+Spv;~LbzDH4eTKMU(=OrboJq1cScB8GrjnY4U*nPAedDY#4S1_cP zf89zX)-p0pM~E%YGLl)Vy3~dAys3ZcFReEZU+ERA+EckxoCOP|X~VCn;bp0+L9eBr zx2wW~Uzgt>`1_K>H8vtPun`_2Kez+vO{lzr0~4Iu+Er6l$jrTg?ZXO;*AS^mEBZ^1 zu)mt^V~$!C>>JjS2!>Tc5Njf=`0ub}{DV#;J#2yf6+;Vw}2!btYYk7cq1MWao2XX*2=1(qZoTx!#kl}2{* z7maOou+zn#ADsh+0Lr0b(=RU_Jx5F)OX-*3OT_du+IrNVq=jOsbS(;JZH}vmlUg%A za__tSfLoe+-OJ>(Gp?`LnW`+lnH~RS382@+xPlswyNz4V`&| z`bsLyLmnTeNu3&7SPLU8ahmQQ|1s7;y4q*GG_*JpY%}(Zv8MXEvQEt4T2P(X#P)ng zY4fmS)8{I}|E{+g_Td65g)h(k`x8faI8Q=0J@kd)u-)smlIH5n18Us+qXDca6axrF z9ap*XC<%>Xu^#p1HAlJea@v3yeP|?tv=c~!I)}~|i=#XozzdX;(uoBtAc9*95({Vg zi!P}2C1vT9xjMK2!AkYDaBfK+ym3Cr5)(|THy7Tz$l&;u2ds}juYx6uyqkdNe*FQaB zg5q7*UHoALV_H=^x3lr?vFGBG?;#qAvZN~`0a0#cJwW(Fa3r$#pEHQ2QBb}@6P{4TZf zB$Y;KqiPX0O2-nxgNGMVr9sd7o=w4yiiOOXoHi2^@y=#M*sS~BNl+DX<3We?7Bv0r4>)z(=aB{?Zj@Tz#dz%uAo zo@turg+kqsIEp`KGx=*TEvP#J&jYCbd;?Z-?-`0h$WQMtapI9+39Q4RB%=9{(44vr zO2yilWC1c7hf?ZrLqa%)&j+NHy}S#PFf#VOIAGPAn^>C zv_&0rRZC~Z1_`q$Per;`IK>OH!ez+K-Mc@gi}MnXOFN|@;SMchyA}XUPRw1)zEL@d z-X&}4#>FivsAiz$&tWvZEGKf6bNU{uT=Izd1Z^82=&Jl~65hEH^sN9d<;mDk6Tf<% zK8K`6KoE`YPl}F?u6KUHxr5vwz|-^kjT?b=v$hh1JyDfV-MZ!pnV-;0lw{V$MNZlS zM5{V}dxv{uo^zZ497@D;ftyohlmaI&mF3Yi4KVgm$+!%14i=Pu-qgY^ zpcL~cZT^_!O0AwxfRCSDU*605`zl~zA{xrAC!)w#;q~%7l zDpI?b_^mjH0*Dh*7FyXZ^>GDuE%Z_Nc)kJmO9>(9WKfA zVJP2KKO2|1Ry*vd;QIgnCTU=4S%7|@9-mM~7ckcMVa5)f2wvKpn6wLN5m}Fk5w!hu z)3@GMC>stCnvLP_b*)gr&Z0BiXK-tKy8*ll*lMfm&LUQ7D9JALKdwSR7+`dcu&T=i zeH;BuuQvSwaG0WweXXuu5SCW)qhJl(#h|GQ zRzA|E(!dtyh;XjH`ulOrPC77J2F!}m(VLM6I19rx)id9jG{kmp+#daXhEqLudGO0W#=Mn2 zQ4wyKu-G2!4<(KLdbN+~ue8c_$WG5cdFryPTDHeFJMPBQHZImicGmOZFi_6Omd;VHEc=$^a zHnh*4KY#w%$LI9Xag;k&|L{4;F5)#WW3@e#Fzz_c3BL$Ww9t|FqLGLmbgw!kj$8@> zB!!Q?l)~~cwGaK%6SfF>iCWyYUN^Qo;-C1ueu}qbkixdB$z>2w!H zNhV0YFezv_%xXY@ogU`Z!itm65U~sV854o&sVR1#52=L+XTQAym|de)$g!u|y_gUi zxW|djbx@lUfUQiO0<{8bpF4N9#tu9`0+@%6?t{Ep7;twy2f9 ze7uL4H=BXX&F+fH{eWPmRsWU2XB2jZpB^7H!~0GUI^^_ zB*@j}3te)Od{}!IGjHjBWTu~FkC1#!z{B~c5w##l2Sf?dgWu=57&(4rkLUcz;Z?Z? zRr$!=J;sxaSylDgVEOjTRy5gxbJY9`OVJ;SPiN= z9CBM%7b})keoz`?-K$JHP#n5sw>9ioYLh8-M8-KP{SX;B;mUM!0iA8KV%-;2GW~i` zNftePq%!6EdvZ_n{B^Hi^O-_aLPLOdFwsMJ0M>fEHkKAYL?WF<#7ToC;^!XN=~%q?zF#b(2*h=V zhCu7;Q{PYcHbbQ@d4#FbHs`|DKB}^5X1}IC!hv}--IbQSXY|Ia2m>;ODJLB7nc7+p z5X|w(bdV+j8Z%Y)J^QxAs)v*p&U0g2n?0m8MY{`iE1!N@Em zKm0vt(XvSxE*7jlSkt=VICojz{xOrf2`d*pD++Y3hD%ZEww|7;9=$*EJep%4jVs>4!PCY;J0VVQgwpotdMS)w zYMAcfiYBYU5j3wpc~>cVqw?Ybhy_B+OsA3bqc%zdexRg6`N`afLQE(qr}v{e|E5Vl zJFuCNDGHeOe=|b<=6#oC^N;*;N4ueeLxa|bb}WyD zl3(&6B3!r4EU920^pG<&a=yYnD{xzy%{BNGK*cU zbBIo_m~mY_lN`qfYU)mrJ?V0{erjgsu;Y&BMBo`a&*kw~v}X$kU{_Pk<>_(doNK?> z{`Jn9m%%GTo~eq>SD&bcITYL{V-2Rg9GKS>mAKN>)vd7u!WA8$Qr(e%LBA~gaI(#0 z5BMk;7A+o}>S6Yo*HwI99Y2*Zw{`em~Fl z7-xeQRK@t;OzK#@X7cGCEOT(xJbIiB z;XEy^N{oU?>wrQv$G;Az)0Dcdrowc{V!UBxWu=^{BXq^f&7?j9M6PS4E>Y1Nr8~Je zYg0^dEh5R#`lquHJ1r&XYz{wqMQ^9;w&eDUhE32cP-lBVqG@;ymZGGh?#2Dvo2FGm z$0+8fx)OU5WPXm%XXR%!h2}9EUhmr4>qYk`gJHiZG0?vXL_l8b z5#Q$qsbGCw4>V~ePEL8)Dt+nh)&R^tAy>+A`kR8WmFXKVE;M3<`5)fCirs-jyrKmT zv&_uMZBQnfyA$q1fzEs#jmC!?T4LT+fWpXu{Ba!Xn8%1qb1 zKd4=*z1Bp!0feMZH!3lR?;^$#tf6wow`^_>EXxA?tQ|Qafxl;6LuYgco@qZnL}lY1 z0U?E`*bBCeSZl~BtWOGP!8!q3utnVLOQ)HsCppl$06btpQ5@;(2Q^8H+iUwSFrFyV zPlT2mkb-OFq1;lX{x^#l&0X9y*E88P-47xJtu0+_7GCSP?7O=J2O8Lr6?kEV;`V1r z;2B1nh;SUCx8IKa@|R8Pj<@LD@J7wtV8))_XkH7W zenXh6+uFjCv7b(f`a=2jLR*R8J9ij;3knK1H&fP@`0p|n9b-(sZnbfSSr;GE3i!C7djiPfD0@JeUz=c-3|4Pakl^tsHm8_3sO zqN1YL@IEq}+p2-sfZe8OzQv`o%_Ou66gtMp*lPKhB3EJfPO{=d`FYkarj3D@SEo&H z=@%OQy&`D)0E=k1wO;#{Kiv}H4e?~Guu)0kn_G9LmST)xu(VV`Rmnw%`hy0(GDK_@ zzdO#;_mu*AUOhcM*KPQ)$0)@8=k0FsfP7Px;|)E-Iv941L0_!(ZLG3VoZ$Fzb*(<) z9e??Gq*Vo)8=;gEo2jqvIfj+}hqI7pr^3vcQQuH=PzupPN_-p#Vlh;21eHI;qCf0p z-2CbTn?V{nxVsoeoOeGtH5A&8;PmE#5h6q4hIlPI9$ebi8t~yv)e; zw7B?erXT;|wb$F=PN%w0k`U06mChY;%FF&Wg#4UZO%{=7%uYJcWi|!N2oWG8!t>bzqcy85$BxE2-L@Bo_Bs0|oYbzhl~8y1LYeuYLUV zmkWTPh1`oH-yfs)OFS2=SpZIijFXJ)?9bBj7iQt|LKAc1WTDG)68J7(4Lrx}j(m1N zL-qORw$URkmW73S3IZBl$)7E8UH#_b*Pr45znnWWGs;2hj0Nsnk8OpwPBVdzTW>6; z>Sz%X(Pi$(*nU2YaD%eB@n0-sAMcUb+SYwPZg2hXIrPHtpMgRhEqHVW=WppIC%$bU zJcLVb!wt)3;qJxe<~D8!OaU8!!m%^?{Mre z<$zL*;G5iHU@>d&Mut)jz7)D&US7^_bGmm6@pR6y4)*o+MKI^3D?+;GFbk*`cO&=a z>-MiXuEJcB*eT(T!@^K_h>R>Zj~w6_+#D9Xyb&cav5J`)()Elp*??t7@>zrpYH#eB zL3IWrQEdzcGa&;PPdpjOlZQqD_3liwU!T*hix(4H{j;1pLD2&p_5;v#Uh0bhIh-nl zUA)~kH1xr>X_^`tG2~aN78t_!$d{din4)Y`C5nqpccL*jAvCI|qj4LGqp~Gr3@lHj zQC_0*9DkuRH*kye-P=wJZ}6fr$kO{L#JcwEcT;`Pj7_2E@zQyx-&w9~L`@WRSuvEiYI9Rl(gvORxhWX%&o?n8l(Eo1oQ zywU2lkB$}oG%oU%y7X)^-0Kr(i2SK#CR1R099&|eV7t5?p0K|cvJYN66SI9|GI!pl zhNM|)5o}Ge)ZM1{dz?WOz5DLpGLrn964cZ2O{xch#AGy3Z_wl*g*kPIv2V^Gg?)w0*HP{Ig zFq>ziQRSRER+_It;_D&LecgFxB>V^I6jdMNG{BAMak+?lt_~!IZKPQY^jn~)3IeXL z#m6ebaRP%UC**CExFaTBPD{(P3M4V!;mai;8{MmU8P(-}EB^*%*}!x1w)6(Vk7okm z2*3T=SFUl$)4~zodmc83r1A!T?-cqNHhSn4pU?SK`?tPkV`FDjt^tr_TW3Wjs5pbc zO-BX7;(cyYCkFg`flrk*r!iQy_ z*af~W_-6~jQ}VWc0cJ2h4mukCEV;^-7A0dH9&lMA=h9Y1IBKM6+)eD+jUPsG+ipV! zcaVRaF-Q&260#~mOM(e9dywuMD1F5Sq_0X!N_LM$iJ&v{D%P(nNO}rOqsiG8*r#+p zqx*Lv5pe34>&#D`K|IxAJ>lmLIOkkw(()2`A{bv<$VseAXE(uV&UC+)xT$%J@OYRP ztq7y_yK7KPtN3y6tj~vU!?3p>D|ja0)8{dn2ce2$R1g+#Ouk51QB zO#@d}1$!EVDXQ4Cn%uNnt1p_~CznZotL65FP5~ct4REzI<^aZUXoea95z0%u)z5>= zI{X;3;a?*e3H-|`nq6SYqJc#5{pT|Wn28r3j?IAJ?N2x$i*xoFhtZc4)O#OltYXU* zBNEeDG9#I(Y~LVQf0ySw|WjnNFu4+iOQiC%`@5dr!@kR<>sl>A%($;!uF z?tR5v^wJMggHt#UM6nCcBmGL8Hk!_PAF7&*X!UNK-w>uvAHkD*JCb+8ftZ|*ifZ}> zEiivcL9bDD_h_w;FP)Kw^fw2bECx9N58_IH&kIKiBxpR!9$i^m4GbhM0`+**rNSD- z^(N=m=@FtAl!fM=8Ry)OB*3ZBVy$eq$^wD+3M=8UXoDh-y?qjq=m>3;^t0dMmxsWb z!F2yo{u`2EZL02(V#3TTHX>1Co*uDT(v8t9uvj+pXLicaCT-12cGgHsf}!l+vvTn3 zzLEfCVT4-F|MB0`M3|(N&{BF_-aS%&#^~t`GhCp@=mLq~p$IwP=tn}@K=VCt{Nw>8 z5O0dEl~J*my4N;1 zd(nH{CGzUFN+TCwqIeSYOK-z%#c5 z<|D?=1eC9~*XNZkq9Uus?uE4u4-zuHS(#gh$tn!oON`7b3NIYgU>hB8sD#P#>7Q_h zf%+Z7(WCXl#?a11Q!}DD>=@I+=6p3lQF}=NqlmLXwnk=oIVmye*}YidTW{7aga2NQ zgWr_x09C7Ri{#G!--~C%>J2jJ`j=D!D}xKh1|yrXhjCB!Hw!%F!y&#dY*b4u z1lfu{gz<>Wt`x4*(yB zm*o%L_%E0?H~MGV#{a3OzKFZ?nMV2e)4$i|7C9sb1h%%`DAP4GDB+^zTl2$wqkx}s zaF5Mdg&R^2E|k1RQ%`VtKQd$oF>T}KWBREsn$bgF*|g`Miw7THfdCvnr4;l&;Y7eW zW^NMy;@Pucn5|^M+h7dBAIO}XoT5(?2}?kwPR7FYgGZkV1i!`Tc>y<>^5_X$MIryF zgAYWlTdDW3FH5(C83eiCTm*@G^Z*pQ7-CEJ#5e8rT44waAJH4naBk9`k^(q6+TlP( z-z*n39KB2}y9abJuM222rVP0B^)F~D9!3ZUMmRhlJG;Ai`AYqiKy})MZn9<1aM(-) z2`fOI&ht4NTx63TKGn389$p;z8Vqi#Wi+nq15U;eN&T_o_8OFrT7GX(^`;!1sl6Pj zgG_B<_G$SjYWo#^jz$u3FJVj%fB@+QkpQL1gCG07W~)N3-_KlSCXO;*K{(ea(-mA^ zy5WKBJ06oec4yLFPz?FcWX+{O& zmX_(Vmja9X%iJ{1ZQ?zN?91E6x7|Ouzr)wzD>)^+tIPR&P8ir@3g38hKHrkfx$}kb z+_~2At)}D941GHZcX;(>tT~ae<4kK&e+odnVElFkTyN*)sU6R&XJD;^37(DeLtSba z$6(Ai67h4w55JT2$CW#~y4J%sZ8W>L2e>Mxu=XMv1+w(riBlHPaHSt=QfCwQwj|R8 zMJ-Td)#vw+S^x}3WIwJ32>*Hej1tAChS%P3$<+ zODO1IBb;@NYpdpqQzIIB0CT1MZtST4T=`bwc_V=ijX>P@@Z78S@=!sguvEh8B}N`U z6rCQMOU93AjzV(}GW_p@^oZMaa8$hw%3LLx6de~9NHK_OV!fhCt z`9%pG0}ejljM^|L1e8HW5Is?zakv2RqxY4Lx-9}&zW@fTs;c@qJIkd+D~7mavOq() z8#NAa3}(np>GH#e7pHSE=o!0(?rR3!nYF*aliuP{->jP7?%%TKg)zaWuiS-o0|0;F z?Xt*l6d(_i{CWkb#%?EVriLBe#GLuR?W46JG&dJkfHb3wLKUv~=%47LsC;yXh={0+ zrXRqt(yb|QM8{ft0iE})VQ8-&QV0fq5xji4|NYv|&JIrez7KQlsjk46s@mlbih%#H zZTG90rimPfwS*17$9D4US6IxdXB*}K zDoX^(aoF8&qmGv63u#&|5cl{`Q|RKR;lc%1A8>j$m?M#SjQYKh2OyJ7^o)|Q=I;Je z9cIvKdd)7ON9p%DCxFhmJ`zLEf8Dv9cPI87)OqD}&GRMHc)|+Ugqn)*FNNjZ9}h#U zEO4FsCesRur{>@-aACQpsYgOW0{O$ZZo2`KD%!cnO5pVjEAEUWRxc6wIJ{?OmAZEA z^uRQbD`cU)OoXp@&Dt=H0$MB<+_V{(dm6(p7_Mf`DyX}OH<$k~9uP__US|2SVsYP5>UsizW8+#=UWo=$wkG72) zO#eEi&NsoK!y&h@q$I7V}G{C|ACcRZKv z`#+9sk&1?QnWe}`A~G_{DqHrR5g{WaSxIHR?7bUgMA_qIWMq$IMf5#RC6p5rE}so$l3-b31YOQ2qGV%Ui-g}rT*?5#^SB5MPRO~*NJ zf59}=wL&HvgVHHuhJ-3=ac>Er9}x!J(Q~;5H0$v>aYrFfd|SGv6HYJ!NCyuO5Lirr zy<$(sq=Iyzq5%+f1KQA`_phA$4a*CO8?vyoe|c{?m(mVtUe^niCE60GfT>yh+GOB8 zeLQM(n!`ZU2W(9If^e2-pQtl}MeF^tgnZWBw`s$POq7T{!E~uTL~IYH7?*vb_&7E! zs02=RWi5FQ2_-OS=@fPA9R2)gwwX_8urgC!4aHSV_I_OLO@-ud{@44wyRb2L5l;&>LvGK%KM3vBQNCTVp850 zzimUyt`WRa`Bzw=L|+Etu>yobi{#k3D<=4!0QErHi>)`7mNtOPhI$k&f{o>HqLP!q z4wWP57}*&IMT5{8TK==upt26~%Uo!Td22v3vmKh06QFLb`gN?p46ws3zF56nMZoYIqdC~Rrz<|!#XQye}Xazp;@V1Ve zw{v!b!`a(u_$xQjEUI*Jxp240th^u(b2M&g-8+=+NJXyMh~>K=0FaGgr^;nQ7V+e` zi+e!>AID^`tzG0@!SZgrU?d03XvwrG8!vf8UKPl zrUC_+^m=-FQiwdF2*L~Fvibe<#y-qaE%#;A1p*S$-8PGMp-Q8uMT#bKDPmZgJplZL zg1}W+U>}Z}o@Ni1z;h0xqNGfYq?+bL)PKmSn<3W^mpC=9w;LvEF$9#@FsAjDG??_Y z=jhj1(8u!-lrZOR!xN{)=-Tl8{{BkznDb`gTeYDc{a94@(y+aGsGSFa+29}E8V%O! z-_QL@O(f9!BT)$qJ8l5ag9X5vGf&Q@B5i7dBmNP8*w3E5g3gKev3J3gg9|2>kHVaA zoJ*h;V2G)4lNH$GsItty|ye z>gG2$VUCq0@)}D-U~y*z#^5uw6dL1Q>PuRpFbywSK7Dsrw*l{={Z?9mqr!ak+B)7SsI$l@Tu5eY_>{KWM~ z47bL^avh%wFS2H)}-GVEHS7e*JK0|eFFcCNH9Ou5!0JHviCut z{mO0wCvut7VxsF3DirDG&Qt&(q4zah-SXG_-kV8FI|z4f(VKfY{If*a;nR}hGHW_p zwA5}dwUeRu#&10&p1`h|pge4T`wblR!09{#2J&6;9wH7mZF#=KMob4DGYs24Iub@? zut5-Q{P;onR_#3kn=lz^X^a5|ZwX^X4-9%OA*miHfH{M%@sD#;%Grtg4x=uL9LvVEmU6q_EaoHCR49Ab} z_T6&~(+!N|@BbecApqYBTY5&=dPpf9B_R-In7*Ue`T&w?-KZzjA(X`AW`e!c( zX44$hm?O@3kcG|s{ssHTm5AopvDf*fZmzDE7;)tGpd%VbOC4rof=@ex{Cie=HAg5s zC1GPXivl+bauVJLaq2@$rz)K~*-3iK)eFRgJ>17tBF-+ay^&Xi3D(!m-CC&jJK!G| z9>_f(+q+Snqc&3`Yb|G)#g3UgOoir$=+{W2ILoK22dRLKJFbzrT=&`vD-)A+?kkSn zr7Z(zQdt~f6tx^&A0|(xC zDwN7rg4A59wdn*)T4+R8HF*lu)}v7Zr)>GDP7Nx|@J7lw|IFLzugkW8>Dvf6+}l;C z5qr!6pODbZ%G8`1E@Cd{zn$W3N8%2=ZQnLE4+43@CDF%ing?ZX70DY4tJD1;)N5f< zC7%n)Kjq!FjX!_V?t%V)*sH%&%)g{;uSD?`8eHy+5G(O_a}5p*3@j}#&#+wb(1lI* zb>2a}cE-Q7ArC=xB2MSgvx6Zy=Y=yGyp@k8f}LGl(r0raU?~FjTB)B#7>&RTrAlEy`_2z75_+f*&uff8VxtQ1{vwNV4C?5liLVG1-{^)ux)N0_OAktc zkev+J+eSh}Pyn?P@{0kp0aAdzc`0md)zd=)1;f0=$85N4GYO(=1E$|1_cEr*T-3UF zZmlAw2(5q-U(sDq~6$33&c7IraCSROKD=#sWbr6rt zFOCYP7WGQgVy!MHT)c|=j*70H)Z5$pJOKoq zZ(XvVGDt}1*UW?vn|J8Lf=aDCoWucL%ZH;u8u}%7yy*cP`t1Zk+2TE=Z^Fe$Y8xHrNSEYW@wcP z4P1K+a|2f6d>bgLjDd#I4uJC_p8S@vI5LfvD|Z`U>wOv?)~^Z}>nMDvwz>`@_*FX0 zS4~(Oq?!sinRj1_IVq!a3aA8XwkDgT3w@)%52FzqKeW{q9sK6^`+0*mW7T6jl~M^?jZNhVzP z+jlZZVz!Cx+>hr<`M`0R+32x}5`QDu>Sz+SMbF^2*PH4)>m8&<+$%eBk(56WfROz& z9(j&7ZcuLl{5ZqbpYamQW8lN*_~ZMHDcIXaY^~17=lV#mqWl#8Qx{7wC~;aG()~Sz ze~cQX!&Z`C>7-!1K%E+K7X+TT;4`ZJyNdU5TzYf7CkbpakR;#cBx+Q`kfM0gc9a4h z?&Q&0i9h4x@1aM10!vkQl~I>~>pD!Da$lw!OZ(yI?Y??+0KG7?IS#& zK&8@B{@Z#UtLmT~_b%hZh$C0^Y_H%!BDR~wF+pUEuRV!t^rTL;86xei<_m_Z7x7+b zz0w(h*z+9hvZt=r9(oQ$w)7Tb*eu@0h*`))TzXwUTnP?6$(X@7^5U4jku~TvH3O3; zQ+64&BAf5%dl+l4HE|wb0ao6JNBjX!e#Q=TsNOiKKKo9de-@@P;dqc^^P9AsL|w`bA+D=;T)Ns;)C>uF^EfYh96y@i+q}tl+-j7W-;E)-A!R7H=IY; z)pfz}jei(P#dL#Xg|jV3`@3fww=otry$`5-CfMOM+yVMF^eBvN24Jkw2n6!%nOfSq z^~A(PjseItv;u&nwv!;abn2flw9R2P1iMy2d5HKC=8R{Hq30kHR}1;oL_wRRBCXK5 z?iuY10&os_Xng+sIlUYi#}7pdCxnE5+xH9MgCs%XlPAp` zm}hiC3Z~&ada{HMjYRBhis~nx3%`9t%!4?Ul&1(?8kwNNXtI{-I zm5pybM%e%ep1xlTU^#=Nq)Sclx2^jN<-6|LxScq~vJil$%xUnzINs=3Ry9~o*|SlP z=I)*!(u%0(+FoLzeL=;ZM(GG8e`pgWZq}Ntth8SvhG;&GzV1zE|{5 zQr~$W#d{&`f7lE3ZEh(lnMb26;l`ya0d;UsgVxmcd+43?-4osaIhF;a} zvk@?o*ag(DYK$1L8${v3yN(7+0cO@85g6tBzEcS1dj4DMIid#T-9$(_hIpi69D1oe zWqeA@?m$e;>ONvlP%>QVu7z2dWpnxPL2%2n;{G*`twy#;W+v$Zs~J)lBSyiB&HQ&| z=^YG^H^uU4==t4%*Q4qyn|DPQL<&3R)ycYfDT=$x0XSyE_lX!8qgjnAn4FOsKbzddfO1a6j+$Q6d(1UAYd8 zgfzSXKR-Y9aIxL&UJBnHE99hA^dhaymg32g*WUY5@;-cY7|tP-f7&hL-w4 zM^(qt_qmYozC8Kch^_dlOzfn5oGj+YJ&>Q91#Zp8(Ujg56RUzdJ@u&REv zi?%#R>FG0P&WcpSDfRGW52=+D_Vj5K%b<9!JqaAm%}8`r7vouU?p?A)uA)&e6BlvMh!X z{O%8W4-zxkF~_uDUE(0MQUb`f0&+PMHZ+ifEj|E5jta}uNplOQ7>O}j1+oBrie1+A zm;8bI11vidcy(+XPan}4`UfELiPawcJ8{14u>h&gT)zb=p`{D)96dq45)M`1MeCs~ zPd+$GqwdupzS59Vs8+W;{m`x3x1Te~(4NChWpYcySgfP;15|X?fg{HP<9am*$UQ$2 z#ptGb`;i#nsR5YEXy@-ASGk|Fvs_;&<6VXHi3~?<_TIx)AJF`Sl`GxZ-%NBAvCBPQF z?w9`QxI#ccrKk9uJ*B|XNTK&-R3(_8)+pa8E5qceN=@lJIbXarrX`@>AnOtZBOeRTfL%8d~UQuiT2$s%y^V1yf+PkvuA{LPd7uFt{4J&eLt!49r;k+I{P=uOXnNZbL*M;TK-~(ntYZ%3tzty@ zs0FC0j$X!uLuvidahQ=x{sD$_m&}zDq;F_8fNrTSE2vAL=$50I=X=EEPqFPKTqC}# z_sQG?B;7Z@z5m5LpaDTSG-Ea-+9ul{ClWOQPI&^FwGq&7A=oTa!QbN1%> zy)mex>gNV05;D?Dm&Uo<$;3`hqe!fI1g3HT)qTf6E&ihJP!{yl$#_55_yiO2Z6Go* zr2Meu8$h+71Qh#cTHJ%>ZGqxps**BRLoRZK)F=pgh6Vn8DUOf+?RXFligX?=`fISH zLUY8)AsTE2(FCXKqcKp#%WL5TLM9H%#%jsb&6e*OidQ?UQUP{a>o9ytzmq+O}VvAqKT8c-bGN_q%T*&3opY*RI+R-jUQivXin#R-gzSUB<( zRaGNzedGpSVxf7DG8~eh8&Asy17lq}5=O7)5%(DapL+3W2`>y&Al=a)10npsu32V^{^x4!jo?p>{=Fs_f zTiBTYeImzmFQDmSFYY}j_@KKF{2cup43k7t(cH!|n>=Y8#Ez`p~{?7#~kg zPJSNLh`2Z4fx?rPm@?vs9e4m~Ovcm0zaC_Ql4;CIyn(%ab+9ZfuEMQee8kjCe(;t2 zJ2;BYP|n>kWwTK$M3N2zmlqPC)gb~8Pz-x!!kgVd01vX=RD(Es-83*ON873~L9FEK zO6;i=?{pxA=RxgMv>AB;3Z!dh-B}!{Mq)DDOY2BQl4=1hg`o|Zf_jC&bbWrH=a09@ z{oUVxo!Q%B6rBFL)7$rkx|d^~fKLxe;yvsOajjsWe3i95x$^kazdm)@+DMJ!rw#;^P`!yk>Gl7cqhlyI-h#9uHfrA8Li3i;v#Y zIZH#XD{o52-(Y6!1NLrBXg;?<;8O*1a#Z-6`6{)H1VG$A4fGu!(uMQIXgJ?qY^j4z z`MmgC#@&NZd%KB22Y{y0DKroxC(YY7asdZD>?Cn^F)TwIVh-;qMXHsOHsf8V(IK%G#1u@tbF1a!2&zyD#Lv3hf0u5`A??PizzsN;V9_%DL1Aa+g?QzpxC`+Yc= zY~Dp^wJrL?ZWeZ^8lyDI1g>jVYc-E<`E7~ACMn)kBnJ1*Kq!C}#*?N!N3q|aO0L5{ zlJ)684B#8vdB7HOh8c1v&u-|1`M(Xz?5 zb6z&$DE6o@DTt7i9PQ7Deh!*sTL8Pv48m!Q>x!xo261X0n7j#zoH%J1T~-6~G&WMq zoSdAj91#GJ9&e7l2|4du-|?e|^zP>O_p6n`{wUb_lhT;p+~PU(Zw0q3Mv> z@&ND~f=q5M344Pov*nV|c_J4}$H9yN2)hN{e@37S9vOPE_|Ju*5p{)Av-?wvT}?zx)s~ zyZ$&u=JV%({MfdaLW)os+#Zf7I~C*)j>Q?iLjr1GF*5d?gaEk!Kv*?3vFqON6YZbb za|qbz=!w(kaquKy8lf5s{rc`QTL8Er8Jf33EokUKdJ;AMnNt`_`=J;^hN8ZUZ&uQv z{zLfz5u-$4Of;Up`>)4`!8CG`H$sBE?>iQY&CgfF((DgND8GT4Gsz94nVH_Eg67Il zf4uxsx1ZmhSI41s0h|{H%m4}FYnv1y7+-V{#)j=4rgOJ(8Xo~rGWEBlGSq%R0p~=R z_fbe3qf%rTVv%<3`F8Jc3UpiZmQXepDC@V6X!g z@3tZ2I5*3Ny&G{iO7fubU9XS_;n3hZ&U&29=^c2XkAAk$7QJ>dFfe#4nZ)rQYH$rU zmxLR(?9Rah%fH10sQJOl>k0}@-^i@3tGNk+dbcmSu!dTh;IWyCGzBz>z)tAP zGn5NZfTm0(sVmSdSqWf1U<5+{m*VF@)VY-!pS#QpNY*?)00M6;cbLWRv&*X#_mwR~ zbj>aoH>gtzGnO6pe!2H8JQ&g6!d=)1yKoy>`NRQ0`F6(b#`lhhi4H5BL1qL2Y+w+< zYkdC23%AXchnGhxG&r>K-yoH0U-|NM5I(zU^bb^_7J$uTc4ZWcWdT9Cw7+tvA9jDm zkfI(DfN9d^u8 z41G*3HkdwU75q#*$bEqKfMu_5amSB-%ZI^W%-(vMUTt~R|aKs zTcD9*Uwjcf+L2J$`PM6n7`@*hH^$gTeu{j>+cG+OXD>kZkk@O4Mt-z7_r2d z48OoRe*F0JiR~X0`-7-bCx4uEsN3j1eF1MqgllwNU%0Ugr#^0T4A)(5q~ITj|8V+k zL8Zt7O4`ONqLs@}Gp$K%f0M^}JYI)Fs4p+vBvVb<} z3zN}XfJMTeT->NrxB}@Y<}rO75u9*A^}W#kd6El<*zf~=v+yI!>v74?#SflA78RLmtg%}hr*dv zT>S2&=lN-0+T3hc;@(mUA8^6ymu0Wx zUpm2gn|)xj=@cw*IE}kWM%+>$!aV|1!SjTlm_dE)({9S1%Fq1vEF3%4;-pf%N7g)e zf-d~4V3a$tP7T8C7*<6=F~;e6p7z&|pHH`6E5KymJ}K^;JEH&{5`5e=c4(W0!5i0zuL{XRmv&L4v0Mh0ruQ{c4r* z&&xM_R^Du~Qf0D(=hya%#(eiPqp5EL-umKj5AF3QXZ~z$DFz*5opZLIy9EDWjh=J~ zvq{+w#Ls8Yjc+Eud zsGbrqQEHkggNz_!5r9m`l!yh2ArH{xKr`k@0`Sw|MPX-?ZGo$5WAv%-h@&AI-%UWN z%Au}iYAwu#(Y2dSO+OzV&vnV80wS?`9w+{jwM z;v&>ZhC`0o;HL_+5~aoIA6ApLNXrMD8gRpjq)ZXC=iU(#5-Nbc4*&cydU`GxrKk*4 zfm0nwY56L_=7(?V$QpPBUo?KGM9+vrF-IksDRBZt<6`eNs6}a=j|-=| zGyjXdU>C)Bm<*qYD0A{K#)VXIXHD_O&tS1C<@^5@tu>RdJhGXg_7;#~v zCykZ^9|Dk((1FdG^jz!Pdh;90DMhtm~0&e zB3>B6FUg5U);}|Z(v=?)`@{51nPX7jq=nS0cGfQj32`LzAO%2_A>S>x=a4ZrY8rxZ zBdG%9r5t#g7eH`T{SorJ1uE)<-x0}g7KF5v(1IUNi`6?I2_O>2G3gUdMkaD6oLE%P z-_FG&@%;hjW#PJm6P~+AN3AcOrmZ!gdNMv&hOz~@rM4Xpcn(qEKzB{(sS$~` z{E5P~8sI{SI?Oz0qWX(KR4}vAj$hh8;GuPbvInl@eEEZP!$OA%qBa_L1EL`sdVm9t zrhOpR3LrD69diRUCTq{b4=bN zZCR*Cc)Gd-=U*5GdZzvhPyieCOF<>F7aAz~1`C6QhG*aQ|5&G56oN~6Q~ou{zCYu3 zD(R_q97FaWJ>dol;crWQX76hm*1FldJ#*f*Dp*bL#G3`$5xtT*$+=-sXBtwZu-Qi9 zJ~`$jyy_ClD`q$}yP?#uHAwfFK}@Y}fLn;dZZ71{-IAYfgD1swlc?%nl^CzO>Gu5U zG&Y@aiBB8iTl=dg+(nV((%AP9)K>Z0#D6OhDtq*>$2=1LS+($>$LVciNt`(}kgtGo zQ^AP4#H!Pgb6RI+4QK4AJbLQUzYeUA&xhu9I9OV=!X-DYG7>~5En}uCE;w#VvW1B1 zZ7^JswXBqKh(xaK2rip5Cr9%frKT_lHW~6}qik?dtYk!_iHH zWMH{l$9md>FV4_(MkrX`+Ts*F`s=U!+ru}C1STuLs(J`_wZ0lN4yulaue-#vZiZfL z$rD(0*2-9X+fQrfVfxjS?qp56<6FH{%_b~^m|^RHy>6;z#$sGiJd{nhsPO0kDGSZG ze6wyjwc%NKLR!D8tlHWHv$pjn1;__$`s&@4Er#E^9bf^b@&$fYwVKkEfBg!-sG>zR z34ZAJjO$w5P9^zb`gq>>LlI?hg=&ikURlgE>$AmI)LCoa3mjOQURwRJ=m#v{PUlEKzBpw)Al8A$TF<~|E?HABX{V<)-%=)<_l3{rRMPL4 zySJFuBH-26oKr0eKhj7pgFJ2{C+%IIvx2Z4BWG__4aU-9MO+Y64pK|Fic za`Vg?m=(>ru;^fy^zgh1&zM}Kgj7dv&w4rf-@93{Sm+uXb7s)85oli?h2CNdW$Dv7 zC2hs5u}|m>F-bZ;WrlM)5i$*--iub6uS9Im$|Qhxg&8k>kZ~nwYh|}P+07w-fyrfh zPH1jE>++2b&8yhg^1MM~`)CC^p7e9VymzBw1qui&(;We9(j$Ja8W5TOj~{EL4sf!| zHd6>c4A)}vxO{?^JKN|zsLksEqi}NhUz~N+bTuy^ujb%#1?<@^H?Ee;aGp zM!WKfyZ|yE?avIMFUabNH{US6U zN`gh{gt{n>h=AImd9J?5V%?u-MWn4RwhNg#Bfh66y`~kRjzh2`!U_lQoi1}*$EcTE zh3Ud1MUd_35Ak8`D3y@Bj}8zWCu1% zRxdrK3uFS$X9pF+)S#drU&3(CUYCCCTu^s=c6W8PKvyfU!WCk;A1+mSQ{Thr*I4DP zE6xP8TFJk&||ouZDPCYBqQUoQi%}Tvq1CRtCt_Wwv3$}F6Iz5>Tp5fl>AY~hi=wBa z^rGNx8xQ|QRdZ?{G1!!)&wLC`-cObDS*P1VK;M$nu5&LvZIJCPZa4>l43V6FwkBl$ zPINO6vWk=XrMaijOIi=|}HmG_iTQ$Ig)OD=K z#y0#ujE&ztPkdZU>-lfnB;3n3VyeGOKU*NM3fBztNp~y_s4Ey9_uWcwOj7?dz(?I9 z9?-@SI`7qTnu>Mj?}^n)p6%aP-0L5(<|+OQIkok9HM-l0W8tIbY~|6U+4MUL3a7A= z#!bfoF89v%=2?%+;z8XR`cIDJYN(!9!-PgP7|eLM7!Gr3uPPPE%ss=r;Ywc*6gjE8 z9$L6*G&lQJ4K6-TDtXRI!c-6R%T;ZzT&d!rb^Ny+ir{_@p`v#wpU zpPTWXH&b8BOD3MdJ5GK4HvaTAN)Ehs)|Iom3R9}bnxuTBmobwY0r5u4{HEHEOnz4M zynGz#vDUX$5ZD+OH{3U%Rq|>FOC`ot#-(r4omE+*$hA0Wwa~=z{xhk@9QJEgT69Hz zuh6?LY*E2-S*4U|xBH)+)+V>H!nrJW-kT<0|30*ysLG2=h;Ex`%!-S5TOR5iY@0}^ zo=UsrW8=nu^27XsWN5o&Yb*_EHHDN-ih*Q~|G-yW;*$6Zo0O5A$9O*+7yl_gT9>iE zSzWtc&kp~wg)&rsR;Tsd+Hpt)!&~Q1`!MoU5WP!`P&B9tOd}x~g$$Ridb02LD z^Ok>T2B^crS=Pq`t1|q$pL;EYX+F#k)li^k^78L?0w(byXb*P;16Ze6e681z_r_tk zG_RLlneH9m&dD#p+T>aMo2rkUuBkz4J{A1pKOBEglKogK)OW;gQw|RDE$O=AD!t=} zA7eo8h1mW{QvKD-E{Tn{*2h4lklo4Xu!_6^MN(YZWv2u zgA$^#)Np?s`S;~Y2glwy1rxd_X#GBTQ|QyWs;SQ;#H#ivH7nCde4Es9eQdKee93dP+p^5;VRr&>2A2VYzriaVjh^ndSIMSC0%!&@nw+?PAuwH{O zM%G2}D`J-$Y$^gk_$|pgOEz=6M0KS|`A{6-x^t(tPMe}FKnd?INfa()31ymT7UTTW z(MF6(E85;2i5E;AAI_U;WZdTXE~=RG!oz1VdonEAauz9CZ88ct*a|1lXIJaw3AkCm zI&RhD2?fT<#Y6R=Bmq`H$|dHgmIHg=`cjJDg{9`E6J&ou7W6t`m)_|LN=TOJYO{Uo zx#$t9sJn7Wz2xl8oDKfJu%_=O9y|pvk`lITEMug^v*XhRz2-TA|4PgQu)WJ^M+u(+ zj^sP0CSYLIVURm3H7VuX{9$-Y<~LI+$d6hH3$wxwIClNV8Um;?KNCN@>9z)x#I=4Y z-tCx%cHD*8kmHU;nsQYgXQ)ia!Frun1rwM@dM*Yx+0Q0TC7+ z@MLq(?*9k3|6HjXe9FDuE?pyjJqO-W4{U;k(QF$xd;7wv6Qbpz?>r;o3-d`}PdNSG zLWr+GYvv4=7s=X;9azZ~06)#@pz`Mh2+0O%+c}M?(#*weU2Px;dI_Qt*rQ+E8zlcX6hNQf77Zx|4|` z;HvC2wR9)JGfEVhD1Q$x3TUz#s*JO`vq}~V9V$g|qGko8W=!BjkS@&K7&Hi!JVp-@ zQ9KFAa=(>TDXgLBQT>h=)OF;YSY;s=w4H?ep-1;qe(62olMXHu$K9amDg&>)y_Ktk zZ82|1I{8dB6lFuxYFBDn5bX^)zdjr+%tpp4^O;A`<`X`q-W&S1Mt71-|#9|A4^G_9^&DI}Lad z_a@*|=q}xZbd>Smkdhe_h|gy74jy}*nLIOCJWaj*?TXmT$|;(S)&=%1a@bmFQ243Vx5H%UubV7y4cJ^@m;_a++TubKX|H zSoK<1Rb=Z*@1U*o{de1rCz!rf9Px1IdBf(|TAi$VQ(v-Yu&Bc;skNA}ldm8uXKi}H zjyZb_>w%e_eZ529mNi+<=D4}V{*dfb;bzWHGx&Y8ljU7q#|LTSD;!m2?J1oaxXQ?I)>Q*sjrnr8hWf0!( zR?tJj)nhs2jCm)l>@<(9vicoUCMAVFP){XDB+~h#zR)j%n=_H!ZpW?5bX+h*{aa#A zIRkfvhM}nyLMPPp<9wB#7l4l^z)C@>ps{d>zQS$rr`d2vhV|#xxvD%ixc*E3p5_2(#>Z-3h3?}=!S;lnm2yi4eIB(IGlrrTd~FX`Gb^{qB^Yfwegoda}vR6 zVOsCUF}kiv&290*ZJLd`UL}{fV6qhnUE`-iSLe-a*UPLX%D-ZUhs)p=Gc2`NJ+|*o zijmv>k@ob8?cO4Q2UEFvw`BQJM7LAY!Vd3mjp6LxxGG^~kFS~k7^CVVb0%yWZ{m!M}gD6DoQv_5L()-5-C8-CpPzoV{qhI;bmlGoKwEbX>v^dxkLg?0vHG_HyCi z1p{YjWg6xk@d#Zj)XeL!d*N|se!<YbG@PA zUpu_=wdlfCn61sSg|98z*I(zTejRFmbLu}gu-DSsTo<(Zd>cT3J?xmiIiEGJlUwP@~aJnK}J$LoQ%Fkm{^~y0o>*H+t(9jrH!X`$!tMyh)h# zJb|F|J1#XX9vGnVYkq(u>x+@cU>pzm(X3gTWWJg_t5tCCEz8XnTv|{ zg$MA7YOU~G?b^YgmJQ1Di{&u|k8~Ob++Q>dhDepjz4oFrC@g?Zp>46@(+0LTxL`)f zgsb~ekj1-xtWO07ZkBT~Zz{GVR=&w33Z1(@N4W!3kCXFC376D2SEk2o;|0O0ZrA!6 zLq=)kG#Ik)CM{hXfakhiX|-;lVZZ7)_#w&{zO7f@+omGHa4p)`JAnYrdx5ZZVIF`v)erph*?l<9gD5ysHteW_?CJ*c-$Nakj`G|4 zF2FwjNTz}#f%R9ovQ-SnVm;<2k9MIqCESiQ6BYi72}{)lc_(4Ts;BBhCVs4@&P2~# zsjG~_KPC0?g1BE4Flzczi$zYN+c&`_PhN-l0@FA8$ACtfKH2~jxDa|(XfYdbuS67H zkB|#}bbjxiiA%ZRP&ekMIB+8tBmE1Q=hv4%bf&@BL2tmfHEitdO=6~z8a)4jZ2%5V z|AF=sA`s<6@6Ba8EjEOYn}c}64?NhJLq?*t;y`5>xb+>U11_J|1^JVC2O-YE*OCt3 zd5po38sTk5Hv6yL$=Gv948JQae7l>zNfM-ZK-b=_Tx4@=9ROxXeyM@DM`d@B@XH#& z=pQlMIu;oUiL@S3hkvL#Q92m+Z$R{h)m7z-VLb`|z*%_8QHNpI7?nx3R99v}8|rCR z07BV4H3lhmFzkBB0GxrO-1tbHU@Pm~pRn?cc<9f=-5hxyW=#_Fay zKpdB!dHwyUX!?$JcQXp$>SnLQBq4ltwnvPBG;`q2BdKpa534$GxU`cGXyFGDVnHBw{u{VkY=Jg| zR}Q~iUXAzAUs2OmhG}qooobbxjz)S-fbZr4PW*DO;WOHXad0c%@p}`vckdhNwNRl< zRILw15s~}jMWRsHOs7tPLCus&S6?r!b3i3hA)R5>6 zsCSBFHnknyw|pkUgSvtr`XdN0Z44+TWu4AwcA@cBvl`{}_b3v*;i5c!ns2f4cNhTT zhNgMx`o9T)O?IW6Bt#r&3;(nlaG|R?+o#wQ`|Yn+AZJvpf9c5}sS+J4iyftfyJDt) zpU~I4+&>G~sy_Pda~ncp0_0psIXTIC`u>CRmu@q!YYqv1+G#lLbyCdF+y&^R#(;6D zo@U5KKZJILBJ6eD(bxR@D`U^mbL12({vq2p@Vuan7x32e&jd{%RW!F&dvAtr$=|fz zo6>i>dt54DjSRMeba4l9>jYSNc%FJIx4+^Iu=v|Q)!e@y@POB> z`MZ!I9P+;od3=Wb;4>b9yIgxg)>LKhBOc-~n8s9n6Y5yw%}D zP5{Afb?iHVRgcig5^%!_#D!4S0l0@}wWmawWp<65nQ-udE5eP|G0ek0wLgGj+r%HM zQ)FhGE*TA>$H(Br1~7X=r8l9t|M@)S{^wwRgIb)iqsNZj*VZ4{geG{$pi3%1{1NVH ztf&fPe3aW133gX*8-e|gKp1qVZEa@VTMuM(y)L;q#ccT4iFE(<^~%A*_W0?W_@6T? z+^aMt38mGMSB;=r>|kuZ4ab{wGAV#x>NO);v$*e;ssKvlHwfm;LdEu zysOL=7)x$DTG%t7qX|Cw(G9?yT^+X8)Kb^HvGQ_m_}@;+)vH(W$&QX)g}dh_gO1!F zaS^nMTce_g2PgGmn(InR$H~jQzzPgOffXkgVar#7vPJvrYh;S6>F8*|&##5O zY6Pa*F~cP@=2IYEha@*3CiS9?C>$|)gq(lWBclu|A#dy~! z;7R9JKoG8I3;(?{2%7I`+z#`WN*z&{%ffio$U^AGWu|ZVP%4|_zY#QuF0Wh%TNHQ| z!ruZc27Xxpp=ISQp6LXttrO^Z5YZcu^{Vy`oCk|!Bgvb0Eg9E|yd3x=&FwfVgjfKX zJ{iKwB42sm8zWF}3u~B_xC#_wMl*$pXSdEB{OJC&lKx3bY1MYut95rLLnPrPWe|5( zK^vC=5r4{H{j+d$w|v%kkG{jG8t2DaOVXj6ZpkT;fa8k4_#1$rv;#NQD2WAe$>o4U zQ+H3(wIju9UJpd$r0Mgs>r=TV+ra(FUd*_vtiCB!5aBAo4DoupYMO=6iA#R_yA^0O z4Gr{XoIJpBx<{26hLj>fehR z`*8q1{~9H<-k!N6(;S3`%Oh|sBA32E#B5@geo*&}6OKhb6fs^Nx#O04CbCc?-4j4= zX)qSTT$J~~|9eF`r@`KQ4LD#ODK$u6QkVAGs4jBpX#^!rMEpVkri##5kPn02%;I3w zce?$3yAfIoMNz2t7O>JL04El+Ir#48Y36Y&W1^Fa<`zyGE7qu;V)g|0hqtyu^%v*W=tWQt450$@-H6wx!Ni6i zM2(f^>DlCJd+^H5eF9#$Aa}zw7&}!jTu~|X8mlKabRyo?1wCq^jtjGkwM2~0Ozh$( zS@!Sv1sRk8mjOU(i01VSki{HR1MXYMY#GsM_iw5moM+&*I8uL$_YwMr;VJ@8tPWLS z@ZQn;9$!F2!N3lPvm*P$D5Cy%+weDj4R0H_dRM!P`&-OLjfs;}VWqjelNBV7kw69s zIk`iDF$F|xujAjslL-5SR$_09lawS~a!>#{dhT1WM?W1GjP~4`7mkx~D}KiG^`j@!qEqinXomhugFO3ShV+Km^&-_3%LNZp88j^Y{7r>1#Es{Xe= z00}~=eqP0OKtoz~@Llrt<|Ba3hzLPcgSu=E-{ZZ9+<)KDPn2XDkOWQhsit)kVe&UZ zBLFvP?9DU0<|TaVzc)oKVms>ZzBOO649}<;ay0G~q+wt$v<_@??Tnjf*D@90+pk|E zF9M669<&P;2SEf8Gxb#*QIY_AuXQOv;s18;?%(3L;M}&`78ToHV49TQ3@QSo)ndh6 zmal^j33s71q%*`UKF~aW>KT!CZw>I0v|bAk0#j|az^N{juk^~5E8`$j@Fko&kfemD zyGcy~l&DxhBsTjr_wB)JD8}wS3stfytMf?H`d2O;4%Cq8Xv=AS1uOQsWOVQq zA1wtsGIGY_2aIZSg&HVr^lJK#KnGn?Q&@EbjV zHk*H36r_kp2n5e}frNx8OlCi7t<}kdhFT0)6EUnGxL9-Y*leMR`tI{ zvUiccYH+N3wbEC~?mjdoc6@a1Bg`<&u*E{w6WtafVAByjKIC^5$LBd7a&!VM@|6XB zS7t2o%|hU;(4J^0#EpqXf2~gkfGoTR3SRpbT*XV65d8?JbD%!oX_%{N9W=+$WefjlpGKft*1}!2CN~< zUSQ))O*(*+XDomfHO(O9DXwp&arRYAW%<47tayhsBrg#VCD)*Tk!hUzxv zncGxK;2ZrKPb90*+@Nyw;PLG*iXn6~Nl2}rOb2qxWNIV~1+wpPVKuO?-GfdPwjCx6 z^G-!~oaDY7r1VPU)*~=#Ln>iWT89?kpjv7Ygj0#sFhKAT0L}sb5N!MV5IkK50{d%K z$aC7=z4GIcVYfwzKZ{=f=sPVoH-ACmT7H~y7W@hkIu32;{#brfiEKm;Go>UvEbV&omFRqXVAtW)0B+ks(owWh$ zW*7z;*pK@VF@}3>&*~$9^mlbTI6YbEJmIXU_yty7UV|H>Ez!tI9(l_K%N#p)3=!q) zho@tm0N-YtCO>16TniMwGl+*iHPh+pCj%QsU}^3ZDegZ?l00G9e8|5MLPds$GO{6cjxcRA=xyr9%fgPMG9VTP2!VZS8ak9<}4BA$j^#u!Dcap;M@srO(q&XJ^S<=q!h5SIIK@6Y&F+z zdwVa49fW^M_&^`#cZ5w>P$v(zg7+@R0H__JA!;QOKgsgFlROEZcsHYGpd&hsz{t>z zk?jIG1X<9RG@Ce|+6qdvsPziuZ9NPj2ALD`6I%4)?33!L-iPrSL(Ec)_a za}~{!3qqH`VM1kQznI%UpNKc|pv;j<6ffVaA*7i|rySpy=)auiY!Wi-w9&jFN=bf_ z3Xiz-T==aYj^wF;+8mt1(py)aK}o*(sT=BB|8^GtA+4nP;bT_oPufk15K9RHfJr~< zcyL20xYAel@FcDmH8Ls%_C{~YR(bvq3@rXSXg*xi@zaO;-pSfi!P*;9fJvy%T}Le> z-7DbYaMXtJF!BB#z*CeSE>Q+OmzAoBp{02Rm+=U>|3}z$fOEaJ;rvr+NjoZ|LPZ0G z$SB#Xl#!4kBhtST85z}~p-4tD6G>(%Gf_%HW+K~3R!H{t-7o5>)A_o->pCAYe!q7- z<9_bve#qhPtiPo!hXvN&;gL+o%D_s2n8C9YIZ{59zgOfR)qVcf%nHoE`!#!_l6*XR zz~ITm>XvDe79Y}Zjm{+ck@pOHkp!7m*$X+tRj(y)zuMpIX>`m!QbOF>S9ykc{%vZC zw5_OEKiF=aFdp&{;mt_Gec(WR)N92eNJAN2AGGVFb|@TzFMZV*4!Az>#!*3TXHncI zGT(E(^8yxrJAMp7{$zP6E?C%Vn^8gf!R-^^46$NmO1kKV&wQ6=y;ctj;GaiT!&P3> zC5a6--BU@kJD>ArA8h;Z{#qQU%#Cf<`*U#wwV5upS3VR__;O*<0+DVv`8O(zlWREX z*;!+e%Fp^>%gZ$3^@cTT;e?4Dcjh6=mUMIfx^$_(r@v_@g|1(U_1?=irqfD;Yeo?& zE}t)GqXHZtxN!)6Yc*HeNUv|k6{sAtk?NEFyE`R){2j(mwL0>_ zp#n_pEK-){2;McnDpkUArJN4tHxZe=j*3%-rzRc)KK7wQyA~hNIv*%V4i7X2sx9Da zX*LsOI$bIa!3ZrOuWUHGla6qvS#bK2Cod&ofRwy{NvRXgnihgePVkA%n>990pxr;5 z0quPxzv+JJQWKGxL(RC(E>6wbLBkdmC<<=a8{|-P{R;hB2k}h0b4+HX1%m`nh3ZkT zqr!>&NN#jPj*fh_Uny3!r3E5@B227x7Owra*0E;3BJc&pXPO=sM>03;w_{o`%@Iz1 zg}`)FY-^5eW17bTEykJ~Dlw`+8MYw8w^)$@RaSB}?S%P-zGv@riEDy{du)43)H7Rh zk<(ay-g~bdK=gW7k>1F%a|q%G^)Us~{B`{zj|Xq9@FL&c8V>LuFOvx}?N(Ipt>b-n(0@ND#0SKwF{ zNUf_L;ylaXem6wUCI@-V_^?;Fs#Vu#hLS6Sia0@-SWKu@2ZD`Glqc_Tpuf4`UyJN>tHn9 zAfJ|lMn2L9%bR!C(PI8KYrW5AfGo}_g|@%O>_h@W(EB6lawhm+%=Dz*C1L80+y$78 zt`~Ogz2r$&M)VZd&}+wN5A}TUUXvJ_GS7I0{K-qflWE2@%8QLu46Y^l;J1Rlf_4ui z3)%R4$0M5}Q+6PLXYHD??G=XPoFq%AVc}*=hv}2+ z@!cN|D;G{&9^TuQ=)E09e z*!Q%kk|Nu;8Yca*MzJxUV1LpB10I~h$tQ(Z0Tl8ceMR@_n&8PLz_s^wo2?|M8v-hA zNU^jPPyxH|JAv9&v>6p?7u=XpS8G zSJNo8rPTUvx6fPbCnrC{B3b~%m&uN18O3%bW9LE0?s z)sey16q+`+k#rWqhx!VQJLXP=ijxl4L0p^;m*%puK5CrAme4wh!^opUDU&YgOG{Sr z@zW3qr|3~#C`j(t)aFoAET~W%lG4~G;k|sb)>cXz3GyIeAPdo<5QNq`jL!VKLCo>c zF=;~JIqGCE7{75(_AgRHn+< zNe`!EHO+a~d%G;Es;H!YX1M=U!ZWB0>9;;BK>y$;!W3}WCtYdOA;U}MXJ_55mz=(0%d?IP%ky?G{=W3nC~s$&_ZX&r+oyi18frp^1d(I7 zlS#gCJJ+S*oGXtzUt|y$uZQbG<|DSau+NM{e7>Q;ec=m}1!*Imq`b>={O320e>8U3 zfhw##|P1)ehcxsZ-A8gOgO2BNFd*+R|RQ*{|l^5Gb~!m*pS9~5EW%? zSXF11uRzSs;f@RhuQ&pv#V4hNeij>p0wsC6=gjh+y8?Gmfz4>E6YHjf4{KU5y$t)bF7qp*oN`9^kD@Mv$&vGFf_U>I>IA#bFybIdiFF<<%;f? zR31K13v~g~UMAQrdMMtMaGH!ELXt1N4CR_(;nHa(P`LLCh(Ul}6m>`-tY^GbHt{EF zlgJ5kF?kx|oU#d9s}2y(NXrIfNd<_8FQnO$bvPc6=aWiKsL@kN>!FxN66cuRG{l;E^BlG`Gmj2l+&qO7$By?xtL)ug+>peoWwU;X zpjmZQVKP-Wv=FHDpQEO;1nHHe!h$OZCZ)qey0o?I zA6F4cwSHQf5SxbCZkVu~ui?{yb@k#{3%FED%=|SOAU72hK&5f9%$($WIDc~iR^_WY zUyRGNE$0(OxrG+_@GG2(r@0Aqg~pDBM-LOdb2J>nM{p$Dc&4zEoFUDVGvM4yjnGus z$9DeLr~Y~JiH{Q5K~vboPrrN0L8GDFxfpNd6DV-wLx~^iA*SW;p`K$*%Yw|VR>Tn? zg(h?!+6#i5-Xbt>^IYsNdcNF9K0_JZ0gv7rU^LajvL;ZImT+qn6!9GR=XYlb5_l7R z^UlZ*G;qn;tv`i?u>*u7K`xn<@Mz6h=$(k1aR0P0Yb#BvkLAc$w~r&#Hzzh;bdk)Gg*pc3FUiMEz9a)30S1mNW1K#*VRq}>+}v0p z7~ru+^6F(fU8V5~47Sy#A@7;p!r>VE5qWcF6>o$a*=O=aypvYfx6;uDi9;xogzM(| zOxarxeXQDeF}fxEZZAp*@<)U1gqxljxoMB3CLopFRy+PHC#+{|nuA?DD&0y1#n4Ax zLuYpKmj^x8v5@U0KI?4h*nL*r_fgg;P8tG-vos^Dq8m463yQ1DkfuHiVY{uW8@X6zF%2zc4|zMKdZ?ul z;VOFn0?)VA)?YS#;^2nyKX*6?NiNCEg|=0q1VUPLb2uxXns@_SknUEF2t_;!o3(uH zlO;?{$9uL;Is9dNAr~|qcFj7j9w&}KBRb8;0(M%}-*sl@jb`lG2T&#EiTqkRjfD_P zZ~^Hf^BmFkhleu!yjA`z!d$afwV=BeBjXI9sbXT zwS0aOI`HL*H$GQCZ$4~@%mx_1u7HJrSGVteg2QUw^a?~IQ`;Bv*xnktrj5Sfn%qJw zmY|<5JY*46O>#IttUS;ywKO7>p#HBGE6c!>MKSLd`DdlY78T^Lf@F;4T82pB!Pc@z z65H0bUJvF-tROhY>b%s5!U_0 z-d_T*?*&JOk;xLa1Fd^Zd4R3P;OD*Y(bJ7W<`GXz-HdCQbaRUd(L*-K4>)0K<#*r? zX0V|%tmm__@k$!nJ^H|sh$`}|YheM_a(4Z7vvQJ%$1?N<~GkId9e;3cQwAdoMv+@gzwf;nK6oRYY~wk zB(TAak}qHl%(RctLpneqf3 zapo)MM}JXV%%oeo)dmFge4%gY(-*ABzelQmbaCnr_P#J|3_kMXPvAw!+we+Y4-Foi zQJVPlf|huiVA0a!-SX>3YE#7>DZ4hm?0{!mflE5;QzV}OF5x0U^Cq`P)+x~eKFLjT zt;xO@qMuhoc`M9_)Lf9590cuQJqb_|R11kX&6(ndLY9sDFY{98_Vpp9ki;p0nkC2)Bu`a6`q)QFUl@fA)!0EHmnNk^zgk2IFTu@Gj{=75~tvrc|x64 z*yRCcKuL9wG7%vcy+tp6^1bK4A`tv>I_R(XCxUiZO^aP)M|E%e%XY9Y_|!h#aCPmo zD(x0Z+;e3SnORY|v}Supv?~BlS!A=b(}$=tp*H&&5~#sv>=B&fp5#|0mHMvcJv!QB zpnYEKJ+fir>Sswi!LbY$KJZUfZ*s@zI1rD&*jC}PbaLm$x6gDfYzP1TUD8MZZqdS- z8C>Ew_w0QysUH1aTp9U!J#h4_5a!dGlfQ;6)F>wdq!Ebb8(5@Fb&Ws;-r`3UVhqo> z-KXgfDX?iS3YBCT9D6(FyR>#J;4d7m6^=b2Z}8BPETp=`JlKbOod(@zP&?C0*0lw@SgmHPs?dJ8MQO1vcAQzdJu+a4MjDjn43z&mWv6|UkbvkHXx|L{ zrOp8RvH?%tX1A_RxdZy~4(&?NIXkU)whw7)Hc~>;T#%N^w zbGY;YXh*vgq>Q@!ZBH5ec;Ta5>!7HVx^dXlU|>Ajb{Ik^SC#Nd=BJaCegfy;toWel z-s#f;G0N;atgd8I^E?$1;>***2SAg`r&WvAGLGyhLk>{v)cdt&3y9o#&F5fvMalXP5wXx;CB0dGYoWk<*z!+qE> zJWQqyAyXTSzW2oCpWMVjaRy3Od&GnVAxreFpo0uXzCLXjC&5LmXY6EU;*sKoWod_i zqk4e3!03wpai+jyU+%%+5n~mu@hF&(#*i`|AA3+vWMsq;!D~L{iFWXFb$;gp z6fGl_{Dr5LN5*{;Wf;Bb7o3!91lIjk(vy$Ke}!vEfwc-%JL3zxoQE5Dq%y#Vuh04y zkVxA~45{duUCI;Ii*5ytwyI1*aVlc^t30T-=a)VA9JdjynJp&dT&)L1i4&ZuIovu+ z3bsZ%nFyRH_XsXQr1f^O^3J-~e1%IWbPpV&SA`3B5_U31G#Xx2i8npSC}wASM_2LA zwwn+>5*oGzgQ^oNNOS$4?F1A@hi;xjMEeH^BJ5RWCMmss^Vy^6di(Z@PlGyNI7GUc z4v!rgQ?LdpCArWyZ9(DQBvAr){+%C^RxJ9(EQm=+c`yYWjTJ9?LdJj!$1caI%2Cj>83Rt3~JSXl;;2ads ziJxhuct{6r*y@V222IN+lRxfQ%da{~7;ck62TN!WnMqFW*rI~7iI*2!+vjN{RSn%Y ze)`~WB>GsCNfJg|iNq2h2!eZkgq)Afs)TZ`t77n40H$n&Yd(Dl+9gH*+_^-fitrqu zlp)Z`@XD9`Ct~~A?fvkA9m=p;qdQJ^GfjL$#hg9x9f&qo4|;=%9gfj6Cx#T?;Ltg` zEMu(1XlxfZLs?%qnX5bF(DS0qq{F#Bs4@-*WvJz>AIH*SFVnNq?O%TCx7=s0-Hvzn~u}@)W{dJ()6E#70Xw>~OZUP3R4{ z1VVh>b7^RE$pGT(dxrpcbu+w1M#8aalZK+yiOK3R?vq%-)bQ$N#gK-k*Koa zn6Kqj@{2XsFfw`o53rk5=+HFq*j%ASPFbYKBlk8>MxBOs$$5;lFnjtIf!=t=@Z0~O ziW1weU7LT3>f%PVq2}`4Bb-|VR1&o00s@adEvSx2J4EBrQO2TKO2iEGUqg-6-e<$$ z74Z&2lq4M3V}yqYSrGYY)_i)t{3i(ei%egWe-ol=3`{`kP`EtkQu@He-9d73EpODF zV%DZcO+SuLYz+R)P~Lozi3Bn|h8D2;Cg@!*)2`#QDl8Eu*$bp(zeRj2IEY`CzKLeJ z*(J`(cCXmxU4Xhg;6h|kYfLR&zln|E6(w0{5LqktY{-7dVoJ4(G|CCwtMx)vAef~O z^o3p(tGXUlkYG=a2j7{X|G9Q{>tQn&a9-a$5!>lXI}#N!1c|GYEuhaOgDA4C?ARco z^6Edti+t^PlbM-~Q0Ft4Yef(zCp;fZru$22FKFnZBRMlIqFWBB&~^KhBzr(%!b;nO zm`BpgakmOEU=|KWs+}m)#0LFXrk{f}vXV9kFcaSFESNj7!oxZQx(tp;2-}=|9JlJ@ zu$}EZ^5Y%xYUh;eC9q`47Hu1G!8I8%Xp1ZOfJ|Gl*Ot#g#+?G7(3(qU_r|dhN_w z7#Gp}A<7r+qzb!t@2)g?|N0(jAS6wm8T-Cliq{{;dBgwbHcX?80%opaF}NZ+j*8MI zhzDQRSFp=E(FkQFVcNM*AK|RagKSe}<~<$8#8I4BmVs8g?m}r|H=Ugzw88~-^S)u) zCl2D%X2U_r0agRawIFfe9#qzwZzz2MkETlnGn<~d*4OHT z8pG9X(_53v&p>}@r!bB5TCfYOqvDYg0BpQT%0MerVdv5DP~J>;)-r%HV~$`{W6qr9 z=@|%oo2XaEM*Gq*#ro?&=ldr=`Rw1_lS#;a2m8b;IIas~3rFTBG!N886_sb_zKJt! z)FV;VGZHhM&x3cj`gC2O9<^lp>m(KAMH^q=%0?Mlib5@>uirxZv7pOwST&U>&FvMg z7MPtygrS}7(8DfE#;3Be@z?yF)%%igQ-5nyzF!s_a3vB-Z3|XTUJ)f-fbxr2SOSA< zn0QGOH7Wdm&6IE^d+b7(MbEoY*xLjQ)7*$vJz8sg0xr4=Do^^YT}Zc;M*Hb`)Hmqw zJp`c?1eupxq$*J4AX6hG4uc@eWd*|JWIg)-J(%OX#Q=B3bk<&_+Bk{q7hE{Gbes&U zS8syjIlDrG2;AbHOqMO_&g}zQZ*$vve+iK54S<)H1>(0i zv30Y&iM@qQ?HGr_Wk}D6jj}7a;PUY&Yuc$)z_Q2Sn%cK#@1vtlOeaw=K{^)kj3zx8j6ao`^@kpAoG_Pd-46KszYNYMHo|6EX^n zFKMA9ib^g-1e_Ohg2L_pv~2EV?JR>HR%xV29ILV#y|2;ed7B)_~n)? zhjmV&lR7*3<^DsH*WzpXzBmKLw_cl8DvU3;5`mCc z9#E1ylSRiG-}!O^Cz0XFh4#MBPOHa&>jn2Z+goZaT)6Ntf@kMbqrki{Med>li`euj zUM=08c9G<(G>dDUEQhSWQ{BIB^S@{xd&so;)6GTfNq}*QL`CCzP+!o3_=2OMUm@X5v&@n5m9e+2`-gya(kavZr74orlX$cE!*=jZ=$_cYS&5c{#wyp?xn zQtVi%fG9{GG$P>-M^rnXB;#3?j4|rjs4N8#nB7*nujb!i3VB8n#){;(yoIn+yZ^0% zfAGtxnda2}x`X{vxYzh<%GX#Ka)HM9=Z_-DaEU$HLZ(t#HTqj#IO=)4QSN<*p(B~H ziV_m~tv9*fzHMZ@e#V?7ZgA#VdafcI=y>qDF*`&qIr%)S89_L& zwqY$U8a!lNKlSL7es-I|xVtpH0BZyfp!3d$%xkc?BR6=#ft^O%=R8W!QV+D%O%pWH z)WD4}B5|8(*?B?!_{^nSe+l$HZA4qFT4wzeJN-E$nx#}f$H?^|$JVMO5)z>h z*2#QWkCZMuL}&1g@nP#`b~2)4m5?xqd4>L@Iz18Y{p-9;{zGjb{@%!$>Za`zd&Rh! zT$>%1?S6=BRG~c2O3*OSzEf4=bq+s848p)AER=Fw@JPInO-i*Ow7y)J>fNGM(nw`r!`4dddD zNL(H|;884l6lr-i$cW<1>-Kq9qoGTdXj14q1D#zjdShd^8aj7&9iUjRepve8tvspM zVsI+~{GR=DXny}u`U1GYp}LU5V-x3#SF;v0>2biaxFtI{*?sdkXp?>xdmin3ik4!r zL=f#sgiOAYgi%jO zLN?b=|Jj=$h3r-M+*m)cZvD>UsB)pz?Zw?VFc&>gSs8l6+C&0vT|x`w_hm@F=x~j~ zbUYCE0TpQ}Afzt$&MqbD&L3WTJ!p^qUhJ>yK*=x%DN?;z+?0*^kMre&tXE|5w;hw` zYIIEpXsR-%rlwchot&KH5NC`Wqw7XJo*~vBJ6oYRd-d-0$7C32D45ptJ!cwnH-NwI ziS5Zbv9FNN5qa&3hz4Y)U-kkX*lFT-?+-UkoHYZxV<@gtVHL7wLK@(kx&*D(Qc z<^pCv9{*bIKVC4>7o~GAgbiFV{c*8@dKzASTCF9CD48{7w}E4G`kTyzM8!Hpa$|>% zg5^c%r-adoy4_!#bQHU_q<@2Pn~|G@JrWD<8r!bxmo9bCuUX5{1^v85%*>mwTp5gR zvnK`t@bn#*CQ9RfL~j3B!Yyc`?OVg4NX+>Q?)3T7UhEv2=(|WK{rC0}*O8vkC3X~ ze6?knf5`qE4wJ{oF}_zkbt!AV!Y)bTP1pe!$n$uj`sq%HeE9$2^H-bGSmvO>^A@4^ z8XzLKfE2D2E(sxgV0Jj#CEDy-C-c^0kQU30@-YJL>XWQ$^-NxL&w(-JGPb~N;U5em z!ye+qj2<&?{BD8BK`)bLEz4*lus)lF(`BKM&F~R?7hW!*<&`5hAM)uG5`TRrrpB1G zi6VkkN+Bs3+&xv(bVnSB6jTVkPzw-x@)(Wrg>J$>LCn81dBdoKr`YE%PMs2jPjj5Mn68&Pgzl5^Vg-5~ zmhcUct^iO1DW>s^H>xI(?uOi(gaz1Ekx<+UUSmcGthU7$(Gi}7w=qCx-iod1b)3-r zdfv42*FL;|JxaP50-K>XI}7FiInKCXTOD;5Bz!T4PP#PoPE8`?Z9$;!47RhWUYHZoqE_NQCLgP}XxvXcgAAVG9eIU!$k@yVcpR0ukUO+l+dDAX-|5t$V zlTTAdRTPWa+*ryYI?Cy5dZ9D**^lJn( zT->LN0%4{cmgZ!_&S9J$d7unr0GOBS-J=b2z_k(wzP#T&7>#e82vj@E-IMlbeEfq2 zj3t6Qyh|sEE_BS}Of%F{t7satJ>^Nc51YSiJ>1*&n;J#TuQd_=>m_9T`IkS?ASxswoyH3OfjU8V_;?HZfpj5rwdG8+}kT%tlyL z4~ObSC6EF5KR2NoiHSmz+^Z$nZRS=&MhaQCXYeifD?};1m-BvYl>hg+YTbk_tL~DR zB-dn7$v_w~X1wWP*jstz@fd2dGh--YHn!eT9Oi)e0bfocuO=%$zna%(?Tv(L3*NDY z(0LNaJbJ@?3!$kTvan5frZI*l4C@3gyMW$b8-l8YRVy}g*OosVBf6t_^Iba!=1unG z@i|7Q$7I6?thPGqTmp*Au_nQ*wX`@#8@65t10{y^ znV`h5JZpb$*|T+k>y~cNhz%Has2XY8_~ucYR>H4$bkjvbMV+jXQKf zmbDf*~pe>}=i|6{Y#qU0uhD{q}v|N6G7{jd`mFKzpM8-Sgge@2-P*H!;tpl4 zCk`Zslpy>zuUoeVzmA>A#FWg>BXuI$zr=%_E5OL)hWN$l+c^ks$?Ui#8&uYI~U+(n}t8)B+o^B=G>--4}>jRx2j1i>HuP0%S1m>1~{kA>Xy-l8Uv|G z-?<9l=1FsE*lU?a9w;cO*YX4fU<3?IE>h_R|HH3Nk zpHKJu(Vg)h3rJf@F!N>*c#V=nD!L^&VH z5R{9gdE+y#ORm0^(n&*_)VJ+WCGbQgafkUC7!L%*W{vH|0xM^8Vte*3^L%F`ZrE;r0G^rpknKVLj4Y~EO@xN=S{fzEpus)C!U9Cv{<$hVZH$ zmxMl=lnA|btTz-t+wlmBU~3lrz5DzY_3PKKdqR2R>S%Z6N>fy0~x(@@^8qlw2X_ z{cxO`=-&u%X`RzZknamptOYOIzJq3Yf#@UQf`w471uw$`SXmA#hVArrfKXK)?7eHw zV=mwWP<0l|inYBD(?Q$~K@dQH!UBr7=*6xrIa9b|Y7X(c`+APlKrB}oPX^#=%LE~g z*L3w^xO~ajo9fi`KCQkn7W+0MUmv|ZgRMxwc><8T&indeyQdA zuCBrN57=mEXq3+L^Si=E2|jd)_^U$tIukqc(73`?FQ+zcoaP= zWg>25JxoiF21`x0?Z=8^mEmHaw>nD_yK2cm4W$l&PqIg>h@XrgMD1_SNw46f=i-ng zB2-!;{|QkbOOe=^m>4qp?|^~ji1#H4KPqZ%&7!J*Bc1m~f+F;a`6KNgo{DZ*8E|*Z zOdM&Pg-R{)i$-9@#i^`U3AubATI=Jxvx1`d6>c_^Xy^_zbfKE@8L6q71_+{_5VERg zUc)DRi44ZB2gXCD3uYl$G%YX2ao;q!OM*3F2FX(wi1r7S@IrZZp)y0(3EKwZ$o_Sw z{`nf~O2iUzj+qP--=rlwjx>QH8?jauB8r%J(JUwZnZOYa60;NK63?Uah-7tK6$nGs zi8{`=zCO$Kmi&5RG$X=$(2x>&IIX&6_EyV7p}3tz_Z3%?y12*seJ|~Nk8sfPGIV_V zMka}cwD3@C#WC!c&Fug0CV)F#Jmc!t3$d#w98o+8aGJMT9bYT|>`nU33&s zxoFhs638SlgWTIU+s{I*^EN@HqoTu8R`nvH?nK^|Z9m$@0+c49xeUhC3s56mW|?(M-Fc#2gmYYh*=xJ5hmo z4Cx5&ce@%ZmlklQqQa$u3g%{6Sy}!~YRTrtpmtmf{}5dgXG~Y`oDNFIG4Sft0To9t(F3!xQ24zd!Kz5>Ce zY4G(#@b6nkN37MV)eE!cI}#FFfOX4;h;YotU5|Jw`#QT10qnjnbyxR zj_M5Xxh1E6eg6D;wDq1m!mky)5@e#T$Y3Q~_Zq*kwDviBe2fN3;uNKm|@)KU9~ zr6*>|ceWs4sx9hhBZj2Fds-=g9b3SZ&g)dQg+bRJ?*C@s=Tx>m_c;Vq2*-Z_tn(7m zMRhR1o2GXmraEpR08=;z7g(A`dm&OZi-=lw;8TH{WC`LJn&>O&9nw(^q7 zEOCkSkF-eg49&7+DhP=HTy1Lnr`W^4y;J|(I4$VQrR3;n(*NXJZ*bSj)%CUt*&}!6 z;Esv{yY?}dojC^})pDPxMK<&iYBcbFeM`p7PzJgM3%u>ehH8j^AaUQb?jm`gLHGlm z3l}b+Cc)v;8#O24iH%_fCn=y6S6McZM@YJ;+ zg1f^t21?M|xm%v;S}i5|dmxpvq9tb`#*|~Cp!t2(%&Jy)kI+vX&JeX4H>3uU2?+_d zxcQ(#)p5U*G^F)Y4MM-jX(W;dDq=vYBt7DoAz2ss=4j1N`}nWjrc3m|qj)F#t(sJ_ ztC(?APw#b2O-(ON_c)>%8{v@RT;a+rvJokqz%G*!EA!D|s|dHVq}?8!{)rfLa1h#w zCreFgm2SPmb%G3?{@HpEM+gO=>dJ+<+97VJ5k!3$H@Ci<*CR( zuA`$PbdmxuBWM!dN|h2=ejD|2BE~Pb>*O#JgTH*gP;LLP>#GPPtfw{0VnW4MJYWvI zQx=l_s1NUJb&}=$u(D3SMAN-qpMKv^&>ssxe4Uv zqcB`jiQA@vJ_2;2Z>=fb*bXH5aSn6kDR*Q$*$B3xZj6E~o`Vdq^~O5CkMC%IL{#C( z)ix9H6~6g5CIG#EAA`wFaL~i;x6J+WGJ0~=RUL6--{OKtet3XVuh9(kaeYkj_PK%* ziRWRhJ2O|FT;YP@>vA|E^@s@G@#FzcI#v+0%OHTT9FZ-z3pGObK_BJ&h9RO~f@>xE z=1WRBElMJbFd|(cB8CO{qLeH1i5+&3UkrigMU(SV^|f_7=_*yl$0FCUvxg4ap~`&> zS?+_0bmcb*&G)yMPR@?Qwe)3^Z(%~TsNdrJMtRMLv|63ul$X%vVhlT9Bu!|y$Y(iP z1FG(eoy2+?I;Hh|IMkVsm@9gJbAF_o8^dC$o{kPT042UP#e0H-gHaFOPKb+WPIN`5 zG28xSQPnzVv^z6j-edhuV|yXi+T#@5@p$VCyFddb+62)S2gYHK-yiz%eR0@N_8>ba z^Zq1&;**X>AJ94YOV*8!juOVLpJFbN=ATC6J7bkdCF(eVIp|O+7IB>!f@*=CZ~mRf zpHP)thj{R*Z8(r3jDl;*#x#q1F+NS*y0BtsM*uWFjxD$jm z|5!vP;=1&nJu;4z8IMJr9vC`j!x$aqS4q+C|8k$T*RPmfO0cJ8SqO2}44 zyUOFyFV&2#4`_9ioH!2u9jw*1BU-mQ`~4Wr&T4j!iP^$5ZbGfr)n?UMuoukv0&2?X z{*EKpWI)YUEa^sIV<3;PR-UBuSFT;l`Osg#3;IU~lk48EQfx`Ti2k4>yW5EV8;)_+ z*)R}ZJW-Uqf*$4Rflg6uZfO)u8}#0&`cUJG1?R7jXKYf zGYmHU9d(^~!e4JcBK;*u)C_D`@_4Bb7v*?Aih!*A*|F4tAXH!Y`@+^z+SdmuJ0yaJ z_VAtn)O|o{Xt=S;?-yOEf1L|w0&DH{zW8qH;de-(gC!9e&@>ADgc#PBYGdI$^Yius zJBXt4y@rq#czZgJtdbEG$syq89@*ZZjh=DeH^Teh05iX{mrQRrEss|_ZVwtZ=`TP@ z;_ir%~K?7SR$bjXcOq8@@+`9v1LPmo}wG;6DiDI?X)YKoH z$SA-n>NSDbz6N&A9Ze&e`%ny%#$-yipa1H=kE)|BR3rji`?-HY$J)7S&FXsLau{eG-|(eiFW)?~T7F!&{<6P2{4;k~yT0 z(TWb#FJ=TMYAO7bJgH*s{gb&B7bWW^ZRjCq> z{Q__aFKC(Ja!SYV0XugCphJGWFQ5hj!8M6*c$>cqX<0al47<1M$``k^qWpFXzV?dR zi7++?@jTk@26qRCX%VuIhYnovYjZ06kJI+U2fL{dY-QFzD~FGe#;n><`5dinrm89l ze<|i4ME_S3I`W%GiG)A8AWkseF$*M>S)?}HH5FiHZbM2|(e?QaX+_FL^u?>44E`0z z`)Jkn)Mw9l+m!JqVztEsDW^~~J1`wb?!;i6@zBPJFz<&U`LTgN9>_70?C--BBNGcu zJxaXk6}5-meSHEY8*kaOZ*6?F+%sye14cs&$|Y)ZT_!_*4(uX=lad+!Pb!xR0vvN$ zDbOB$4TbjGCS<;@sd{35)#9zfl)Nn+kirA=|B%XRf)b*$Z~JKFjYNd=WY2fkj@Mw9ZdG|4nzgbB7KC-577^s)1Lqy%p`qTbw zHK-UHmqz<@Ys9AW1o@dRCxfEM<`!#1avP%SK1TYthJcu}cU3*(e2O2hg zm_ETCof?qsx@xel zVhFuqxi>v(qK9cl_|QRqC_>gS_x6$MG1N)_JCY*{=_UrJ-1Wv^b>jGCopD5eeKw@! zB0oey#@WbIXCj)bo>Om`sD0Ax>Xj=z&PsL<;a;7gEwdL9jluKil53+VwSR0Wb&FEr-@o;11}cAcK}L9w2a2%FKWf*7FcHymGvBDwj9UB zixMP0|jGR5f}XMa@G3(5I{lMkvx9+Uu`Fh@Sq!{)_%uiv+O+pB=b1O5FWg9Ird6Cj3L zWx7sVHTW2=1#_D#vTj;FoDY`7cn|G+WPhD$*!H|Q<*%! zUC1GVmZAb9a|4`p&IZEITKMRn^pMaE58yN||x5kh-XU4(^ak=g%_tnz$6K zF*7!6C9*P^DpZg{zUCwE??>H=(X6z%*?MfSG>tUZoF+h7EmAiFrdk59U=EEotgPOy z(|J6ME)Abt=fo=(z`1HS0rz1%d!Oth!|Ph>?y+ewrks(s_gNrh3i+Dt|L zs&MP!?1r|sO$dbFb*09#l7CA-OgT6|!G0v?*uc<*i;SIC=PvgToRed-KRJ7I9p}^R zS#lLZuR}kNyne+enRgx!O_~@8lj5DX1ed=nBOgbG!w}lWLO@UD&-d|O-LruMoF#s? z4-hx?_4=^a1{FOb56)4m1T?#JF_9+E4HTi3spwhD={8!jO<}Jw5L}ujWP6Rv(rQEaup&%L~;G^#dyn1yI6& za+7dfFG7nuxaOJ!PVBPGGD5*e+v+S90u&S_H?)hIgNcxS)sb!CsZQnQ>FmyNC{_aCNeb0yn%oqkYxn61F2 z*f#)l9pf`gyF9Li&QCO%R#{wJY#t6Jf!Vi)`upo|wI0qPNZ(^jz$5$}(`soMnajva zRY_qb$I6shK^pOzoFiycG6=MydZX|5Ay@indq2{t0;9JSV@D8A7|g%W#=pP#mstQ) z6F5A0`s*2$9F@<3o_5`CMg!?>2I;+f-Ez_MOhzg%PkXg$yp1HiYQ__xuOLrEu6VNX z1Y)d8f9EdJbTh!=b_+wG!kqmAYq&E~rK{xJW~^MR-%w7Kl^N!$AElP8=`3kVZa9HA0@3rIOlEjr9OP)J2jZI_B*A*n1FttXgko>`q)e0%{teZ1AY)etY}p`}nL3T&4=PQXk;@P3W&0uz%& z?Tc-LHTRT&Ff?$Knep-9JAc`|pFXYJlm0oQZSZy@fYmEArJoqP#Q+}&9{cndVMp+h znUiCWqPc^XTDh`_nVo$Fz>}1ExLEw-h?Ah-z(wjCm@)bGW(|M)E z=P|KC6Fu|UiaJ)Ok7>}-yjfn5wwzP!${MQ#z}xQNg5f^OCu&dc<}=8Rjg*Y7GSCtF zRdRD8mi-=?C*E|(ajw8<3e(xKHa0fC(#2tYiN*rS4XeiGuhQSqZa)0nG<=>=Yv4dC=|T*s%7)4XVibf% z8%~2n#~0>QvAsSz3OVCrV2wFn&m6MC`=RmhrMdU)Idj}eOB`9p)Cgm{JC~>qm5&C8L^T?9QTNj(+FCSZCmWJU6h^*uR?Hb%)Q)YH;{rUgz z87o!C53Ja7s9qaJf0bAuvJTZz%TkkfNfR%3fbiC#66Mp<&CJY9v=#-H))8j2gC1SI zWTFT!hYoXKyte3!euMXmLda?zG}nW!TBddy7-q3sL8t4cp2Bcx6PP zUcFc--%QwUIMF8sIHHfzBhuRs%pA$9JW}`15Z!xgK5sSbV(N^U$PZcU`j2d+J^xYy z{DXH}E$1eDQ50Y@6@vz%&o$kYcOidBB&hp=N10jI?HKQSb{L{F>d_p5#1YWf+!!V^ zQpg)(rK%7+Of%y&hOv9BTeQ-f)iAo+eT><~!)oQ4dae2sX9nN2Ec2F>IDRD|%z0o0 zSrYirS^z;?gU^75O4^K@V#=RAdj_$QH@4A7@(786P`kLJLhoA4cOl`w%OP~1g0#+& zu>&M;$v3zeTjWg&0q9n$*OsUs_9Wx4Xqsy7PNz^zFUW4GjJE$8fHv1vqQj-de01>@ zdt^EBm_HeupFb5?PW?ztaq8tYA(PCYksuUjW=j|v|NKyFin!9twu2uPIz;R`cl*xi z%)NK)^VsP&LQX}`2(cNF3ZBL_SoK|GSOTog{TQ{ADCU)uiM|lPH@JVs$eB?6kfwYl zS!YQa*rCKE`8EU*l~CP?AAY~8r+FFT%*V!ep49cCG?#;{a4m9ylw;3E1s(u?EZ@fB zKjrEEdCngnbxN_y?%`El)%Z?F<1-mUcd23^?k8(B!0NWVu2)=ai}6`|9%G%j+vaw) z%!M_a0#WO2(NkC`*Vt>y)G&;ZI41Ys>!!@Cd};-g6=aCEPd@E-Krp=E8Oau@bZ@wm z*Mq90jIOTk{WArGKpLy63)TgZ@r-DnEbo_ZQ_QB?;H6&W=PN@~DdB(~>QHQ`S9t^S z@@)v26iWS%UuVp^_115F4WO3W)hikY@EOKbd3`}I=kbbjcqzjcoh<3<7H!D@BdY7MN}Nu`^bsfl zSQI1q@c@Ve$Ecp`$8@}O!3iLl?&!w<_yn!CaolVJ9@7VV+qlpr@WhxN*fhp((KYSo z)Wn3WlCwAr!OAYNp`r5X2LK2Kj4ys@a#lW zlpfZ!jA^x&#sm(ueK#^;Uvdskb*JgOW*~s;>+E*x>he8i{rHQ0^-Zgqz?(^5l;w}Q zUv~PtX3S>3Rp$$L15?zZE;&12bE<6nh}Y2D7|EG{j+V>Ln>Vi^rX9%K&f?EVgx2C@ zK5Z!l5M~7halX|AofS`4LtaTQgO`g+o+PH26>l?!->$z(;7UEu%~fd34x zsj?2rIypnZigOFbL(Ttp1wor?=U9G6Z>j@z(3?$c<-n^h0jVq#uF;zs*0K2 z*U;Fj?k}D51;+dqu!|ImaSs_z<+B4|^0+C{K^evh^orv7?)R(G$s_}O>;0FfBGjVB z1&lCLG^PF4TihX1LzYFKeIzTy+}47WlQ4Vzu|yH@)+#UUe|lUsrwp5%MMjLv%G!%4 zO4Jl%Hn?7KrTHI9BI*9YM8}%WWbsXVgmD#|DEz5tRgL; zFr}nu8Rz{(dZTC8jiK7W%aUn9&?i6oFoq1MB#cg?T#DW}75C}BtM7mH)V8nOHgozR zuUi5E$@#Vfh24QkeoZ@j&Bnftjfm~H8Ub8j;9tLN$&z)XY=J8Ei)#7%cfNwd+=_m4a`O{R_C7}4 zESRPfh~c-+PF`ty({kpIXLz%1M_b_$qC{158-;XmCn7{D02~oL1v0cC=g9`HwUE5b zhJQ2t7${QuA&J0B7|`MV;6YlRpAK?j-`RH_E=5jWc_;|*V6gHvnU5F*Wm+AE_j0OO zj9x0V)RWpSUlfQK5bBfy55qKvx0`S%wWL{PzjmJT|3qCh)ouN72gF(Y0t`|qz)0QE zTD$m8;R3L9k%6+mYNV=PozLcgM7WHr((GDQTmPQ$LD#@_{F@8SS$@PR5k81hip)GK zhyV^zDK;uGKLK74&)uPVuT@k~8WYJB8i?T;=PZ2uzL5-qA|^sb#Xa05@`(LNs#6&- zo^dffGLK-#Q|px8zV7baA|`WSOr?vA&@nR%7E?IAYO3|w9Z=>~ob_~jW%RAr;Huy@ z*F$T=pdF%*Z$TbB9uWU0jvH&ujLszS*>%0P_A_E99s6lz@rz`K2_+NEw=tJP{(a}LIJpOWru_g^Bi6|gk_dCu+ zvMrG$cIS#71Fk5wVWelD^$$io!mubrI%^=KAy6}fmkEW|MfjjU6gZg?n}I*|WMB}% zfTE`*@|(mMaokKIvK~H-C`}F89g)vLy{fU8xZdqe(I_XVaMUud=r6V58%J)^eP}xe z#ySNTFSYrB^8XSOn1a}6Hhq!y#FwdRj&Qd*;C!f@IGk|_;IzeuwcsPbv>&7GTvKVs zzEP)oXw>D|*a)L+QSSB2Pa;(nycUer&= zKsg%1={NX__N*5bt>$n83UIcFwB*1BY!X2 zpLYn5i|%lU&PbOdiAlfH5n*8nxB+IT?C6Oh6MRe}IcDZHz&m)WJ{e1iG+11?bU2A! zI)7}#>?>n)qiWQJ#MQ1xa)n;&zw-!n>C@;^D@@f7eGQp6IDdTvKx$%!MZVG(yO^kb zU0sXk$1mS_Aj^C%(kU#e9Qc@zAKN;e$BeL(;ZL5O`Xq%S6PDnqN@{P3ZdyF>99i@e zwZ<>tfDdV0bQ_xW;eG+}+Nsthl`gjq<|tv?34SdZXnV7g%#9`bwDnok-l_$@f{dD8H@sq@APa=r?yu1{F zjqLla)x3^6ih9)@j4HQ7F`no(A{oqRY0RnWtp~XvV1-Jo?ymi-wSDb2CCP!YoVFPW zUUuHi$V^O+I1J>&OX8?mOS9flZC+4xR6>Fh z4s6=Lmr0GDSGD@L`hmS%UqN6)kvlyR3iZ@Ga^xFd8 zA;V-ER7_BuCRz?cmhGlb?a%L)1dWPUL>=dJ(0uNB*DA=p9P>w3FFzi8lS<`Jk^HZp zCKAP)v6SFJF`hu1_8mk%DSZ6{wsZ`x*qD$~&K1x_e%_25{XV*O@mA-~5#~~*#)W$X z7Q4abRzgilwTNQN&dQP@-I)VPZu^R_z9y1;t*G&u`)yJj6Da}td@*n7%7-fasXiJJ z;U>j_l7oD*f$JXw7@o%!S@Af!*Xn`ptCL}Z1Ak(HD^>&*<6h!Bx9I4vvtcRh!CPs{K9TphkI){NZ={2d_ILPB8%jVk(OJaZ9)x zj2Z+UAD5z~8=Wgil$0VHA-rY+SZrF*rX3oY`OkvEYvG!Cirw)d){x< z**=JhJDco(>=ykuwm<%fmy|x8aVov5XsR=8_69p+>x>&v5JOSywSQ0N|GP$#ukI)B z^DP(N5Sck+QV&bgS-3%hBmNZ>6!c8soH=tbuAnP8^k%Z|;8+Rry5l@+4Bo5ARD3C# z9eJ&vG^B$fZ12{d$PS@hTDXY03=Iuew2~4E@Lx>i74J^NfxJTS2y1{{-lVQV7VY== zNr&t$VYm|sPr>xjXE%VmYsP1%ld_Kw`!al6KYldKMN|0rgskPq@bm z3;9571ha-AI#9d%@k@CvG+cv@rA5vl1UuIOe!JWhLh1oDmklAMck97NxrP~>IKn$w z-*GOk$TwGyb&Td4V7zo`cFt9P62zRuH7>H7RRgi0y1#sihBS zIwskmBl@eSpL*W4uI``dtND;KD0{lFt8q+qW$M6&3?rTOB6VCG zYDw4wXvj1g{vvYXfsavgYgO*&t3|kgXU-ILbHON|+uud^KcbE{$X@Pd@kN^Lu{^WQgppTf=uoqA%4$~IEefONgAZkyorK4cP1kc@3j%}6Pa z-zJuEkymc{CcC#Q>l3c^KY8+mmqxvh6PCpU@Dg~R?}u@t!H?XhYc+C=1Ny~&kiV)5 zLfb)t`@Bu2Z??}135HLrqJwDKAbKkL60QSWxYAoYPSy2yzUPOi&su*q!kgGhBm82Z zKLHl5P!PC@k}NGdi=%`TRdH?IL|B^guR-spK5>IiRlVyY$kit$oGS5M_vwXxG$?1J zj&a2RIC)o~OR`UvNONk$XcSj$Dg;m~mHB7|+8u}Jg@e+KRArY&)RP`PH?_$Bn+|P2 zIyCp(il*)?r}0UQMdcqw@k;u~8$ckESt)XyrW1(W|3-V!D)eb{1$85GM`l8xblNRn zKs;Mev$3SZBJVB;nV=v=X&64PcrfR%JD9x4$%;jSb$T0V%OI6b!Wxb6adCKVfuh6x zUG@h^7wcul1^Z;n!1R?s4PS1A+WPe;NI}M`Eh|9c*Q2~b5AHizGK&{PA%*-EX|T+^ z_p(e3v;QYcQI6PbP@?**O{QJe(HC^pQKWUyB4DwEL^<;W1pTGAix;HP=cgq%@8ts; z7ze%x1Z$G+w}`gsym3Vx7wNhfES*c*8G)uoa_6`DETdPaFLEt8xIa7_3aX^B4zWS3 zSKn&6bdE~I7e|{1TxeMTu>py0WLCsQ{|bcgF*spy|aI1WTSafy^T%ub3GU57S?y90(=?kM%ZO zFeOAx1ZmT!7R|LgCe*Rb6cvDIbn)jw7vxk;<8p?h4(N30zugkLD>l_~!;wM9$0W%? z1o1*AhsqvWOA^G-E3+5x+ESfOVwO4=(#Mq)TAbhY7=X_{*=k}vADm!~yjbf2H{gXq zFj>|CCSqaV_1l#^NAFU?D(hI_1?xX1nD>MHD3W0wC!%! zj{O9k`NACwxfSX2ki{9W(%feNel@98JbX}bGAk>4eEmln?Lhk0T-tXoKunr?J{$ob0+JA~^xu+>=lf?m9pH&su)=g}O0_8;BBt9%bCiZjRu|lYr#)5o z;$h_o0gI>{L)*2)X?jWdRl}o3N6S5?%8hDg{OK4^+6Ot{L5cNH*>|JSfnrMDeU|bt zB}rTecWX^>7jNC~Gm^HHVL~OkH?Z$>LqSPS6Z|>Uh8Nks{cz~g!xI{f9bdlOsXwCu z;8z=b#F$T(`};vt@dNK?JCSK}QyX65+t8oo9uG#^b*iB%v*cNmtbwI9LKjH%Vnum#tVUa^BD=GvbFPbSQhi$%RRy!E8dVVb}q`}X|A+)0H0&R zeBV{Oyo%#*G^z|lG?rcI%GQbXdK{)?2uTC;oXBf5_-%n7J{4;|eir%w1yd&;`s%{T zUmrWovAt&d%5OB`ZDJ8Z6NjWqZ#TIp+zs9K*!yKGCcNoEIYnwCw z`J7aA2`Ob&EB9ycYDOHnpQAY&D@5;(>58aF?mzkHBi&tE&V2@rEm6d%V_zAQO}8x6 zdhT~1OTnKj5O2{JUq4x)FX_mY=%Duxw(Bu!3k-A8+wxr=m5MkeOkEs4++Pn%j+ zh1ILK%H9P`LGMqAj3DXl5ttBMJ&)*OXs3R>ZRd>K#`FW|)RnwHxvyP1z9?bg5CYKv z5!3PzbJjaTkJHiY#r#E5#D2pAkOe;8t3UvZb(ApIYcuPTXD-pH%-Z##-_-N~?iC!B z+}#=PFWe+7e5=|2FJ>P{6({#L+pMN;@hs1g^43@0bP)?c2vN1c6Xv6H#3%25lbtwK zNBLRzpK(ReZR8GTm}2pTR=Pdk;7M$O(cJ2o`$0|l+NO;!?cnt3P4E0+d zxJUe?%(<)y%zDCEhu=}7H(ozBvh8%jAtZ`}tCP&vIljMne;9$H zP}%9E8tD(hMiD$>>vZ;TQhE$(^4$V}nM4@H2c*Hfr?i~Hqz~wLJvUwoi*Ydz`tfD` z8PaZ|1;|@mjv)8wBZ#B$>pUgRi2!3ZiC>6X@qh09N&AQZmjrf2?+tpsrgpedQvVIym$D zfcKl8z1-A|SK5MtV!NzPBJfBGGT#8eeqSE(7KM9pBoejl=9Me~GyK(OCg&SbitMBl zO>5+p_7viZOmQR8B-Bn`Ts`$$6U$$35buq7w0~(toX4-fLOR|yn(76b6J0*IYY_FK z+M;YxJ3-Sy8$q&}Bh)fiU2x0fuY4iIq(2R6?SJkX4q5zld3iM#96Nl?iN z+SLMs`qo_Vg}ce}8ROq_%|_2B|H5DrOgv%M;p z!%x*Dzh5awkF%z^r42&E`4WU2_Vp&M-?&i)?s(E_ukj)`Dij@{fS zf>hPKq<`=s4W*hXF(H=92C>Oe+*WE0Hr5mCjg5@fA8$w2SMc8Ls`ttENM&fOr9151 zTquM+CbB1-erw{2<5jz@w4zfm2nxML_$s^A3;v(~aP;V;CWi;K0Xe$mwAoJlKA!WC z^+`Av8emMkUOCPqNYq7;yum`pcmYKeREnc!e^H{=glFYSG6w8W5|5|K@T|HA*%UDM()&hQ5*Cl zLBYw!7`bFy7htQjjA_1P8WI+TtC>|CHL}&sI&z0}{U)lvPVm?c$hVRrPvkC}b-%zC zSjTKLUf#y#@kJ&*r*$#=^y%qQ>(6Rb)vcK8lKROqV0G`h{{6x$fD)Z}=_@w3ts2al zflCc~$T-ayEV6#)u?1LgP`1ECnk9IqaE8l2UM3eKbH&Uj!KOo9w>>t)^xs4p&S5)g zmF0?H!c@Y|_ViFz`2P*!%9&T=pwb*r&-YC9M2LZLTgEOtG6?v@Hwr*XS8(Gct&p)IW!HZhoAs5l~<*x7@ zN_lk@JU}aY5p;144p-hwW>VFN%fJt{P<6D;8~YlfW!Ap$e~sJuCQ4lN#{Izs`pH2m zx^}egR9)3JsQV&+vUZP__>Jq=qiaHEF72cH$Svs<=Oza?i_N&_zPd_^lOCC}Hz+s? zfY7D((jFX$@;vzYUx!r=Eg#;#Dfhd$uzK!caC1@*`j`G$!+GT9{cyaK^83K zaMWlnvUd>{(Xd7vZlj(u9|)eHzn;w*o@F7eH4vjRV|Qf z5r#o1em-Xoxf|-Yk*WgJ;2J>y+g?+!Es$}uv9o2Sva!WQBzb*MLL1x6fj>K4MZflzMBvxm(-0 z@n{P;dpTgSTt^)Xo!`vdE|Lh|HYtO>jMO>|sM(cUU7zYe|66GX8@8p>{7-@Q&-S$_ z@aU!;J2;xUL*^_WZPRs{>q&Ss5-mGv+tytGOmAN_m?VM?pZAm*0n9>Fra>J8*GhRL ztqh?AK~qDAHbfk0tdhP^9QQ1&U+GG~ypEdyHkR9&mNRwmSWTZYJ7mUN zdq|BU0BXUB7v()SuF2INd{B1RR>3M-pdmwohi}2k z{pwz=&+hXGRC~7fU0ZU)CUZhva#E(&k!sUVHvN{jvjtHtx_suV!GVEN9+Uw4ptiB~ zTgX-d2;Ag)5_}lj)@1FwzBUxl1@QB^`Q&3YiQI6jIVZR%B~M+a{2!Qg95ojyy$+R; zQ<%4bW#!Q$z~MBaI=+7O0hE~j?kss7)UHw6L4TOYv(^xNxfffT3M0=QJb5}P`%atX zCgp)%H(N9x))kF3b4ePW8{O0m*437P0hH%no>}Kxea|t?4U!I^j9%4f>PF3U37o3H zXU5Ct;}9ltJn1oYyZAg(W|5zyp<cB0s8=!?s@xW6D$>96)PkrbdD3i-F$@0s3sY)5mT{R?@W_D`__eQzC0 zYantLa5PgvN9zF%Dn}%fsq3GNu_L2#eW7!9Zw!D~)2qZ4!JE(yX|$3D#xWB;Y`Atn z4EYiEm-%}umKgy6HI37n}~dUsQ2ab)O)=FcP9QT&=>V0GFNNPd}xA~8Lw!2C*0Hx z;?Y^2x%_nIg;bd1r-qjr8g!R2eQ~(VGgNGChB0~rP1qGx)dvocZaGBf_prx@TT%N! zuS=O0F*aiyTd;;Sy_z79!AA$EUY%zGT*y9kTI2z!E7}yiPBbIe-7X^3+kz|a*7GAM zx+j`F_<_+(194Q6vhFjhB)ufi1mfOdR*MxICTmy(H3gh#YvQ=;a;aW1{Y58$x4_b? ztEv;s9537S1JgGFn9^#+W2M#&W!`(>E#xPdnJy=filCIt_3mt&t~8KH>Op2RuJ}Cvi|FnhS;tC(EIzWz zJXTp->9qNLj_{$k-6|C{;b*&IgHln~@JuSH_Wt$>#scA-F;NUkzZnBduvck|Oa*hNB6cE13gAyB@+9JjvC zOQ>KG-_k~it$%PR7=C6&dU6MIW;1>&?<9+@SbgYL{}fM`jhCmd{(KY!A;IdHE33dE zS=WvWUy6%oQPo`1ro=av5( zeCJj8ivq+UQ3P z|8pX;xEI5UK_7gC)l0<{^SUz{3eUbSdP?Y-s!^A1M5{>u=+?M3esy_ zsQ?;=OMsmi_qFlDb#Lu}sDug@%PRD=7oK%gfdyh_i(n3wrA&z688T+wdZ*GEx5t0x zERTh`^F`Kt37ctNBLh6jPimeX#y$vT{0Dg^q%Pe6Drk@)lquj@S^YUuI$kHsrRSqY zH{ry<0Yw0rs5_DruI$u6%d~7DTetW~DJW@i++MRR zQ^Oi4R1jc*AgPu6J~cHhoGGf|4d7374dq;@AJjucIdXYs3RKM1poVqO-4MM* zNo{XwwbZv>B*IIeW?|%hd*PE7&o;v7K@CfA!V7G+^;Z9AL38Lre*?8d>b*U?z$t(4MD@UWbS%f1bU2}Uiu*XEN?m!m<_#fpb^>HfgA#9F*~o_;?6u6E$;DdhA}8u zt2%^tK43j=lp6K@wEnjj%lRm^`EwFDTj*5-|-ABtMe>E=u4R_>EH|g?|qeZ;j zGoM({h_-XpdqOEhP0*pIJMF}=RC!;>@lH_DS*9Q?tnBLMwqnCMFE4+%+&dA2`rWYU z2UCg2p-Q#A@6$=w*G01X%~_$)qQeV_q64$-mOaQOR-hIv_B~jnqCjrS<4pp&|KHVB zL3ZZi(W+=RHl!OQwW6NI&~z4#mg*`od7&8bnI(&(l9JNX$sZaT8r~m6qiD}lb;-^y zM~)ovdO(AZ5*oNJ_|ymAYDoEI5vfKGiAk{pGFU_uuk3DYt3^LiK~!lyAnI#lZp^Qw z3Hbaqcc+ZZZ0|zSW0`Z~))!D}TL|!__s+cM^bIhBeG>|kviNj1>npANoUqNq{oPKA zkB^V|OE`YjcYvH&^F&vJEV2Z;`LpS|8hnN<{*s0gq)TZPD4$Iekv}lW`FJ7!|J+(O zLgZpSoGd3s26eQKbpYKtd?3yYF^1N4>(0R;XobwD;c$obxZ9 zIrD9}{Uz&V&8k49_Eb-!ji&4K#*b&&m&ki&9naK)g%VP#`+1ELtGw3L&6`=-`e}9W zY-0{7qu}UelM5E|EKOOr=#=adAqq1W^FNEC`NE6%)GJfV2YG^;{naU&FYP|Lb>r-` zgx>AxSL}~F<~Q&$Col=&4EN*J9b0u&1`6a;1nWaPdmgY!?rT+5wNg{HRx7v_70NS_ z*M{=JWf$LgrjtuPBb+WUkGkq#wePFx)30B@KCm`$WS%sGk8*U}c&0!6VTS;shwEkP zlNo+{Qql(MO9g1h=Fgh?I7Dv6GaGDDV?f@w4!T=DpryWa&;8M}I-=KGpY*BBlekjykTjfE9DGrlxA;@`JjePwiO2{sJmS}pP`Ow^uH3)k^4kB# zNoiu^GERg0_WlsE%lo8ddIc`QU*6}A+{vJEk@v!rx$or#D12Q^x!>|7ji64eZ7;Dq zk+0)D&xA1^HJ+)9pRe9Psa$Iz!=z9)hR^<&hBT!YT_W5A&0ep^#ff)xKmmk(=7* zcMQJUEYQ%D)h=NG|1HIDk734RHY6772>kaUJ_V+HF6%I;n6*}RC*Q!ewjCgeiHXS} za1{%@R(%Wzy|A5iJd-`2`W*Jf_Dc`a)a3T$9X$d7H+Ji4n^$>ATsHT{5x_InH%f~@dVnd%#EA2}-P?Ok{vGkqX+YnAjR>dwa^ce2(D1^V5__4O7Z(qof z=Cfa3esWLU*p_|KOvT`&xHz)c=9d;Z?)l?72;NN=- zQpxcnSF&aWh%(L4GgIAp%i`C)xI>KWpWNQJS7b%-hxUTJAn-qqamGf!184ZHwoJ+5|4tyop%_^uZ(hg~rBZn>L7K_eGRKDIo>9+y>~~1s|W`;TuQL-@O^a zQ=4eVgDznibwzBzSSv&anLw#W;KSU&Cw1jA>sY_P`JX1GhIf2ZciB_hCFF$-^4`|H zea*iV*!gbIO#CVUq|ZjA^SIEV5&$1Hi(B~t4VTNgl9Cep+%QywhxXpRcM++N`~}$6 zTLX(57Z(?|7t6j4v0J{T8&h#mU#<8o&C-y-iXk}O<_Fc>a1q_go9_Pk_>q=Nn_><( zf@czd#;4eGH=!rVtJ7v;!4*DaiU>aUol z$w_{mS{~L7jENietxPlx<^65PPWL{$pn~=A9%ec@+Zt+qZjcq@yDJwF5uvFnuL#ul z_0fN(6%Ai_Hhw%4i`Wxn6274sQf#MV<@QbaSZlTvvkT-Mi5>cV2$N7z?>`YzDntB_?5w#B4rS5`j2pDYofL5&Bu-d*#a~CO1 z@N~}|k5#j#BCsw5pEFRi1)}xbXng9Nacp5YSfeBYWi2c_}aSD1qqoSbsi`A^J8bXvJsFg z2bv9LFTY`5<}W*@M$7kd12w zM6la&7sq~_^x~d<0#W6SV4MWY#XcgY$c2iizF>=Fwnl_EOmP9Y=mGuB8h@WLn2t#- zC+g1GJWIx}kTR_pbQ+C$Od9#4Df%d8fxwEvyh_$z*Va_AOozayU9Od&HwR*Zr7OL&p1!+& zPC`Y01(cTJIr^}}+B}*I9dkOaD))VH-25R$bqzMHI_XM(2Rum8T?<^=?|g|;8oYIC zMcUW~s21n`_O@+yBL?X5WP$M|SQit`YCuWvAf&4jt2GNNJ9#G`>v5&8Mf}^fwdWMy zdRM$3-0AZRloX|=N*d;@25Wa76myLZ`Gvf8TP-ZK$kveF^$Llr zTiuNhkkxjthtNRqs;g~d-ucli*z!7*l`Qm~RWy-Gq(nGx>Ujw4Ex`_GUDs=Y0D^LV z(oKbW#Y4>xztuGk&D#9Vj<&xhaj$@(WuZt^2*;qJKZx48Q+@%8M)F?U8@P)#$(du!Wd{OCb+4hxUVh2XVdF9F@dr z-_t+N$fk7z9* zE($hvtD6VUpPxQ59`B394@-QSSLjsN+J>IxXVDq> zW{g(;SbmuBEUbyq3v)NT%TdZxHdKQODGqi%6F&{KU_WZ^p7xI;zj0%|DN;WKwyD`# z8qxyRe%-z@N{jDzCmYutNWB1#<9bw^emGYw4?7%fM}^BQ)_^@B+Gd4R@)y)MRrS`+ z8f#K0;m+fm9Mncabzu%FDp(%kc3%EckeW}z{2WJ=NczmUK@UE<_`Ol0g}Q*(DD*mW zJ9o%g|8=nlt(cY8miu1BiL(+9oCiI`gav%D#N`NOPI+M({0#>?CeGo>nu#V2oyKF$ z3ZM5}OiO*5t{;61Rc7X4V}LTV2zBCmpDcB~$&ZKB_^P3kak-mx(*qy!xM-cviCW*= z$v1Fp55dPQ2w!s?-9&KMRQG@=d*_+zDw8gI+-~{sm9=dKEl7a%w|k3{gV^uwBh_2< z*l)z=q8^)31Z66u9hSKdd@HR+4;YR7WpWV;tjR)ADYxgr<~i~nddRM7DS1Xnm6Lgr zhR{+pNH2}rVI}Lc$A!a&1XX`J78D+4QU2=!Q%^=yF{Cbdlm-`T{22`(#qCrb61|xc zl|yJjq;+5ILHp)t1voJCkc%$~dG4M!eqxO<-iGU5o_)1GH|E4d>mmuCnhl5E7*5V` zEF05*Bo}m$%&aXV3mmcl`-$!Y;h7e10?O}^siXOi=L0fep9TJLp(Gde3I z{S;m*@me1IhuNqF-9M{zm!aEC+;$T;{>cD*pK*#8^NBh;=7ZV{E8w{^JmCS2_+7-o zN57Beu;Br-Ss!Ii)}l5sST24L7Rlj|^_c|L8Nw=5T(kw?%*1x)0Fx=i$vIcC?is@i z{5IDWi{PsJUsa#@eGr)J4GYzEo4N&xLQgF9{Zw2HMM~}X#@d~=zBc`R{BnULPwWL^ z?@A;(47s|4U?B5!s0au1N$7Z#*P&+bm(mrFDU56N+pgj}4TB^1Fm)xvbMu7~BbvHF zmz5>0rg~K#v;#F5+?bUdbx#ITIVvhDF?!V~vYx$k52ZC0Zg_s`czHoe_&XK=*0WH! zQEHp^>KI#dN}aWs^MY|>y|%3gUVDq1CEX7k8G`y@rbehiHJzGk1f(|bHgY2m(UmXO z)ey74G2Vyb!eOeGBfUC8q4yI`7(kp{kKyYps+Z!QKj%II$m(^AuUh$92pG9E$K5SI zwqeY*o(8|c?#w}R`dWK$p$e=_?-sjt18r$_q`ELu&c+9+45mWL)H;}$8 zE$fLXSmrS_AZm%toDXXs>gz170^ie!v&IK;h>@g-h&H#WVSi)Q3n_#~4lhiu*b5~K z-FKvW+e2!vqHlP4Muj@ZOy2y}r3=oXS4(65*brwrC)7KyX8X~vXNoE_LQ_r%ftWw9 zMS&Fo7v9_yJck<~Jb*cdEfrCK;xth2r>x^JYW!?ztO!c_dFz)M8=xdn?Iv}g_FjN; z7a4IG2Y~?q1m7r8C=Nb`jgg|=krwdV{$p4hYArYX6Sti!$bB=8s=qKCov&sb|%<5Lj54fmj5(;e(f z)0anz7hid(=F#`8EbPg=u};XO${5(cc-x>6->&5}h2sOzjct)NE%zD)*1v#vv>z78 zePy@`M%r?R!ePBY%0ffnptLj4)a6%E%PR@p$4mBW9E9$?{W3x9Dw$e=+~YtTD&u&D zf&4w3?(ywkjp_th27CA04dxo1MgRM&}`r!PZ0Y!zI`;_%qUg1r3;B+U0uM04Y zYche#KKJZC%{=L*+AAdG-CL(_XuAkEfEbBqyW%{58#%-5a$Un*vRh~PGd#8^8$bKl zLt()M6-GhcwHeiTaTVVXd(S(V^=0Fiz3;}_wv@>*AUo4UREU|S9-geRas6ibEjwqD zebYi7H{UwQhjm7gB^BMkNE4YPX9%Y%6DZi}WpFdYKz_S^xjgaDueIM)WO$__G3?8% zT8VrPKJ{@-1d8W{|F3lL>5rYu|%mW8A_q6C2H@`yW=)B?3*DKnKq4cO&^5{{=t(nR6V>x1@e>*P1yD_X|FLi(fsb67Q zbkhEor8Rxk)Oqo|{5y{`>ecgdZz^!6a{>cXFaj*8Ihmj?;yU+)9XDu?SU`qxGCqMS zitm^|iD4H^YN23jOnisE6~3Q^080A-TxkuHAY}EIhnySQt{-Cj_^)4V4x^`5=M{Z= z#PCuG0+Itjd^ajpF2nTV<_bP8Do(=w<{2mj+!6VdTtlovA>O^c$OB%y;Uym`{8n(v9dqj5?HUpw9^(NL&%;C$<`H!2`(p_IypJ5gm-UXd1p3W z!E*!7+inM)Fr2r|;UJeTLk3%P@qxQ#(qB+bvI#Z5&op9m7h+{+!#6e8=yxd zr+MCrnd$A>xd;9rCi{B5!!}Mn?{!o(a$D-&`^eB#^D_{{f@`Pe2mM_xd|sU$TGI=#aSTD%$1b7UU990{msYo4?VLvCb#6 z1-Whh5x6q);I*^J!OQ|3Tzd&R1e5DmuPDCl0+vT^Cfpa1+eTs%~E7v&gwh9Ojdoq zQiPo6^*FVYF_r2)OiI1QYR%QTL-xVc?zpgQ%pDAvPXTd!;#j!s)>&iL0)u-&8 zyfs*Q3FO;$M5I?#R0vB-UIdrnftAiK%v;eNY*R0pysu=(=FN9$zvRUKw(kZwcXz;^ zB;ofcVExwvp@@gQeP(@YG*G>im*v!9gnDxAyFDMO#Ly_fU{h?6Kc*&s2`0O~|F#Pg z^9O@HK)>L*U5q>FCD$5&Lm~7bXPnqiNA1_yOniY!4Bpl{VPu0IVJf~wD}GO#>jjS3 zCIo4dZ||Ll2#=42?4}y##hAY*OeiDR6XH;7uB`x_jxv(@optzA(BID-R}O`oSoh!! zHP;yKaEd(>^t3LL<#M`(;2JwmZ4a3e^@(_z{ZR|z6~zgCe!XB=mab_^^dy!|Tm6}$ z^|y(mzuwQjhc_D)xq?CxftkF=8j+>Kis@b6w+&yrC1#g5B-d z440L7r%w?ra%n^}(`V;z`$HPoT+i0gX`Vv`U1cRaao>oi$WAD)rO9c&3%(8WCBxX4rS_?b|1=f9C>xU*zB3 z4Kg=W1wz>&B~G*fvfg`M}aw{U} z_&(--jgy3Sr_<<_`)CB1`N{S_ zzS)nrAr{F~W|R5%mBLOlfW+Xvk_sdXVf*K!Ofg-!I0(NN7AF2+t!f!i?zL28YHrlZ zSOE+Tz5~QEBGG8^Scnf_q86wdcSoPA!5#op1s5r`By4e0HwtVwKtRcyd_kVpWZ2Wi z;Uu4&$WBEw2GfSi=}k3AhQE$aZ7>?!VJIPvd(N7Y5u4Ms#5<%mG^8Pv`336k=K#8b zM466ka(0f)10?0R;_&kKt>X*mXZ%Ngy#-jkC)nFkEHgz3KK9o&LKX*i$EYVy6{mu= zya`v$9P%%s|G{L*Q=}H--w*A26@Gl0CvY-r*NtUeo4~&}MjZPT0AwduEXUtRjKRdvmv9{PGTZ^w)h$_2^HH3wx(zVfRk9Ct%U)t3w(YKg$y8dwKk zN0{^v6$P(~L!D7dCYpU{`&EGE4;|tEEFLTPz?uCxXLRe+cQ8c(`=XjZC4!FLApNo) z84P0-a%eg?>^(ith+J`CI9S229ZNeF{SPwT{b@w(vFBt4(HR6rkfpSqPJke~>)8ak{RkGtZAJ*V=^Szg> z0ie%%7;3NtUlDa9unxiQfZvG7PoK(w#(h8hKc=^67dETwOF8?I)UET3-H?_feqkV` zzr;_hIzA0p_6Ckw%gIXY>A-f8X)GlOM@>K;LFKW#OEOxpvR+_fbIkuSwZDYUjGK<{ z3U+gPWvVp&!^-Itj{RYX$+Z0HtnO}W&uB{!xozNtCn!f@AIbM@&_v{YJ1?KxkXH#M zad&y39b5N$pyTo5#sUr1Ki!3+gZMdz$Sl2S&xguecTn#mnu?xm>rt|QBQDO$E|Shn znY8|dO=cnawq&uy!uc-5+{SFJMP4EROfP{j*?o+!@Y_?-vy9R4lwIabh84l3EaL7gdhpt&r_h%dYAXmuk!Q6m|8__q#IL`JtWLk zKLE=r1Y>)e>GX>NA+^tLceEj6AC-bt~L5uw6;#1SgB0>|GASu+6sO-H}M=fxyy^X0YQ`ee>I+<$COs%)wLguirN;`D)u>W?Z$l;^)*w{Zx)8G??4$Jd)$YWR}=?EPD$ARLjQ#NAmEj#Ofn)@YW>#UVc zg^lA|1SdEp4T>?r8P-rcO0j0i zfv!cN*zGJI&4=)(uY;(RzNGvE!*cvS6IO6o`e!{$CrmVaaJN_@bTH6YgM9}1Yt0nQ zPFbEU3GAM8l1=d1rLo_@zxYt$JZ_Tw5F7Ju{JI+#*+m((_akGy!i0>$1q2`_IoQP^ z-hq$G5@D~LNPgo=UF3dnJo#*3B?}?t-yf$k-}&7&**BMW?ohwRF^1FSsTIC_k&0(Z zzmBUQ%nHi@F3uRuM# z*!eeBw(e*h+p!@LoE#-}1W7A$q&hY@3AMF!Bk-z$1>^6vCQF_tLr@Qd3LEerT8K*6 zH9-!UdBBMD(9+!eY7m!Cr{JT@v@5n_tnMVMv)G{i z(di>FBv*PKOynZDY`1@(B2*{cXD+qv55rjJVnjVB@V0v%{pYop5z8WQdk%RK^<7MU z?Av$j@(sT7msit(b?Kpuo)KMvr69|HL*d8Wk2Hwdfo8YwTT*>wqe{O zK%Lx7etv#WArTNKqe1S2WlmpP2uyF#d5!S&#&{)o5e6%Sc8%T`jeJXy6AeJQ!1Guz zO7y{cIyo2bG|BZioaRj=^%*?tN8UH%b5=+BIrM6=d&ZeI7K0w#VUQ3X$I^C)lP@DV zK0?ifyznJgLl0yDHV}vJ=1l>&4Y7ocAuRr^_(Aaq@;onoiCJ z?e0SxsjC^|wSo~jPw=A{NHo0t5ADSv@YASy*IaCt<@hT>eYM!93j_HYLxuQHkD)Fjr)$|EG%iD#uk7tAL1KCPnEBnO!#!jThGLQ%OLi#^(+Kw z&%o+L-qDjHTU3Y%E!mX^UQJXg(&+~`>>O#iA|$2#H~KJFw4e z8b$07`j4oui3%2S6acD3CK#}g=Wt`l>FTL~$9n~BYWAMa2P|<#vm4n(y#wzQ8vAxi zj=5icGHE)TqacWkWe$o1H-K+rd0-wVc??5<;5KPBQelVQT{~^MqzVU5xnZj|(gO=j zc8|@*;4MpI`ANt-(fN6d9nfbCa!SCRsfrTt<@JLX=@t z%BYZ{w=dsbUo_Kq7$rfc+^WkSE66%ZnNMhTUs^@zOzcTFx9=Xu|SQF_o!N>ADB*vV~U=(uY z$mt}E)<8&$e0OJ{6d??qaqnIZi$;N9Huy4&;1({bwTkE91Fmfra%f{cn5o)5Q|HOA zbRX&nJJ{`NJ>nDn@o->4a*3_9%+(n2j=!$m11*QAsN=|r*1Uv&6MYa5=$n;_&{vKQ z!ItUvl4=TE2n2KWn~QAz+}qjRI_*i1B!XqG#WLaqzj@9@ghG;4x15F1$A65S*PG>H zAw&t6U~&KI8}{(F$6#CB;&N1td_yKp_jp7q-*&^}+WHJdbTBx-ywT6~I-|dzfmAFL zKDm$06@=cW;NI+pYMUQ7ba8mWhQEMVdpg}Z|MfioxzG)Ma%i?Xs=nT{|6omvzB|FG zdWK|mP$1?LYNR>#aIX?zWlsEA#tHLAZsX%Ea`9lzvnt+b$w;+3jGsjrFVFyp;>_&ceK#y0r5Zt+>KqnC7UVkU@(TGeCn$<+8XHec zUsLpUo(3a=#5l>qld*c&YfQJ{_70!HJdpeOWa7Ea)1hkNh19+P($JYWePWkWI?2i7 z!NI8xC^-omPo==ML0cXnQsEe9y$R+{=<4Ae?85s;gB^TdILm-q9ZPohZ%LJ(%Z(;! z@Fz-FD&mUW4O)p{eFLQTNNxnY0F1597HAN#RZ?OBE1MN3MlVCj`g}}gowGCjiurxx z(0{@eh}-4TfiwsDa!@3gA@g}-Hwv-^D{~wO_yBq;cQKtAlaJC;gRPnIyWprSPDF%K zNaU04UyRmuHB{0J#!6;W!t-$C*sRtiucN!06~aH#3IrzWEL{|*PB>C9K(J@Jjd`1Vnd^m|=_WHIKMB4Gj zy?cj!?b66-PQvpt5MFg_Ivh)_JxJSqL5kjVTgS7op_LNpEk5yA8wMG-#Ba8RfkZ;K zvEpQeI|3~^LxlB17_%9U=*>_|R%*Jh4ayPdwOg zr{s)qaq3h}+-SN2Hn0nYVSsSsTqHBwlZdOCx?fdh)SLVByZ%B;apGT!EHj+NY;~80 z_5cJ}(QJ57hPspxZc_m|%K-p(lFCPvJ!c`U0PiW&)nZfppTB+7YF1vyj$C3C^iyeO zFsVej>|Kon@?k2-$`28PcvrPbRqJsQqUyEO+e*LM#h*6(56}9?PZ`i><*O9i<^4p> z`-26Ri;(CYaBWpq#qo{#r61G~g$>2UGiL6n2;gSG6DnmQH9iAS4}ZLfKrGGAbq_8v z<;iBa0DikA_+~)IVg5gi&#b%wrkGj*AX{VTzy^k$Mm7kUzW72>apa1qecVToE^SWy zciJPJG?X_J#`Zh3uo&bvVJuMoY3tAr-;Twwgt{}C3>8du|b!|UVUx4l7>694? z6&C{cw+WUP$5HM7D{WtdT2k2s`Uv3cM|8$;tyo0f{2WoJmS$BFlWOFRh!I=9C+S@|f1 zWF`**ur}Fz`O1|-kXq-1bb6EVX#D;}%m+672qA&O7sW*6jYzGXsF?3Xw|Mys$4~RI z1Io?aW)b3yK5-oU;+%lvoXdkhX@q*N`0fkm;rKZYfTymy<<^Ja>@uT&!?zfZ6L~So zg#JUS(X1b_-J<;!H#g&=jtVgE1cX1Htk~yPiwonZ=kvgyS^!MT%)j9N#09*-3al>s z`};61*zen(G81_Ibmoya_O>H=M8ZZlLY1y|a{DMg6;d5Nj)}QqaUz%^-%zp54bR7j zkjyx}>yiH=r~2HAa#{W$=>r+sEFMs;UA8ChD9=l~GO6l^=pw3j!!kB=KjfoG*jNBi zsu^U+GQH(TKEF~{T_%my1w4p?F^hKeL#;~j9r&pDIqx5~2u(M}Nuiqq#+{&k4zrYe z#$0q{gY0?4g1o~O)@W;4^w*jVaWMO&xBkyEd@1)?1@3h7g}<{>wD$jxd4|!K0pBn{bye<0GM!dqXm>|y+DDKwxb~)~m z!z^$R5}syN>0b`1m#ELlceRFK#dKz*Dmfd`D&nr_0X$bgDB}~HLZ>GuIT)SX-|T%6 ziR>jR<453{Ng8555EM&NuNcx`pry6ZYaDeEcN!|9U*iV3Ai&p)3{)Y$U3Y_klW!^V zt}FKTG!C@N9Qu5JVzqKRj`+C+gYPy4E*(HuhDE*EJ9n*1%TCx=w&f^Ahk2S@i}$xS z!{H#!asnh&>pSY}lxQ$kGcZi_=q?dK#z3tpQg{SdEIa2g zig}TZ%!erQARO6dZ^`nd4%Ma4OQDH`Q&;9KhNfyN{u zOl0EJfW_{ zv{`)+E@GK@H(Dz3gCx0|_JEve^xqKZs6}}+FEWEQ`>30D523oy94gf^64{*sfO?8D#`P8y(KAxOJFlZ}2DwW;UPo-s8;prfsI?kImNFlR zdrbY6I6LSSmTdKH-gaFNcKOSbb<<4}>R>WfTY<1|A+~TvtJ;z!? zQT)|8SCZTM_N|+305)UuJcizS6hPr3RI`Cpk{-cJ^7qPwAgKKP>iqE&>NZ@92UUs) z3z~33Fv4|q$+gkO3Tc6-X!8|PX|kP(*;dHrm)-q(E?Y11)5aLyqbx;OU)guz z$ECG9VXBRw(?b#*vP~yAmtX7dDkK-o<(;a<%rAYrhQD0&SPu%AwA`m!HpDF%-ynvf z_ofdu2D_8?ZEk&hqRw*b`?W}?(J8m3pI){+bCl*qzU~N-a1n{q**w;s0^EeO-G$8S zf+JgxkKa3_J~ZT2PLnVy%8?3Pk3!AOAhEA!vUjp|**4n{J5?4%k1MW_TKq4P!(Sz( z(rI&VYeP*E?ueNIH|p3`P{)p(FQ{mDYSp4Tb7X>Sy1?d#U#^ z*azZ}#5NSmPXPB92uE;Wo2OX984xiJ#J0{HEwuOM05ALq9|VPcG`GQxe2pB{`Gan4 zx+1qU#9AlS6-a~z%-**DDvCU^uo>wD+#ppZUs7Z_ zYY(Jm4n5a4Gcj<1Sts<>882GeyiVllrou_s4iLj(+)`e@xTxb^p?pn8lw!#zgXyAqN1gi z8KFgAa`l@`#UjO|XckVkApa9!*#L^?5yFo0hI`w>kFfYqdf{Vmf-7T7%s|!J5Ss_A z%TNI=3%m3h2VZMSqs@;=|(_=ID z;PeJ689?MUBiR~9Q}#pjjgq#*VC{`EYChkf<2(92i-&(-h5RC0Ciqqe*W5|@QDyxN_0TefVGgJpQg1gZM-{9dw)OcDC9rVtB3YQDvM)Q%{tvgaW1GDaCL z@tQW-+J5dcMq_|LOW#W&dG09Fh;!+E9~I`sCXvS1(Fm9K!a0cyVS2NyFH2cJ*K_z)9k0U<_CfVzgp_}JFX5hZ^# zFyGBPUn2}n$AQAi{}>zLMG%F0?$LQ;fr(<-wG48PrwtGFlLBQ;gCVl@ueN{-`53!T z^fr3A(m;!FTn`T|xkDP@9cSz6_cwi0EGEKR@q7&Msbx1QZd(R*uF|<@rFls(*!oOr z%2>0EZ2|Iczkf+OLqeV!!s?2Edq(YFzW{&5|4ayxEpef=ZKd9Q^$c4qq+~F(9;Zh0=%k4{Z$eF#q(tQY0o6V z%NMl8&8}_Cl@qW2bF%CEw6+j5GxWgjJAT0-f!aH)wzd7pv;$}b`snN;wF!TM=vzXZ zTK4X`&!{q7ad7EqPWo@VEl~;bbY8=2E{Itw{3@?zkNsZU8Rad zNedi)UF7C=0?$^Q9OB;h{tN2r6k|K#Earo8!vR)cabXIPTl)JG;VFSlo3gNE6kJ5D zBQ%}^cdqx{S?Bu{3F&wB=^d?VEz|H~mE=BA;L|+@(X5$AP{h&IcBSN_M?b;onP_V1I!ImKzoC@qx|!l^`( zXexz<5kjSsz4z+do`{gGg>1>5DTJi#y(K$4`*+k z;}((22E9hzs(fyRmp4&UJ%Dh?@R%LJsD~dTl?NaRht}$mlxu6=PA8d8xYc?zmoyQX zd^*h4IvdwUlvRpYp>t0jOr@n-r&s}Y!RQ#`3dAs8MxXehDBOtWRV>#Qvxa-8^4bpN z#C}Pmi#&oMc?_gPV%02EQ#UK68>b2_$}r>nwVrZCA`8o94htLBg^hjJ2&Q z1ge|A39k54)iEUXw^9+!FcZQAiP7mA-8DmRk(1Bx>jO_V@SmvLZ_7++g*6aHK=o9q z7Uh^bkk9)&=p8Xf&=qEe{Z!Z8jpXjv9(8UbVMKWAc)s`{#eXY>lRjE0AhTp669wR@ zH(<9bY9|oYFrw;^zUL9Dsk8i117M`Re>XZjg%TmZdNdIWot`kbgWbV|f+UlB0kDuH z#+H3PE!*5uF6 z$K!TB^K(wP>foZlq4WHfbH$VAW6xgdy{eqQelUAJ4a46|^5>5YoOhXMOSWdaS9a!; zr(m;nl5+F5*YAvLN(M)gbv}AG8-{*s8<90}nTBCwh2GLp9zT9et^|RT!vCnv8B8oS zmY{ztiOp!QWR_VBP+FIDm!&?+9nM*L#9<#|_j=H^Z+P~0)dFHlek-H@wqv3fh(hfu zbR}=G)q3CM*Dl{@K=qt7{EndVthT2LgbHc4FT^3*z+F2FHW7r&a-G;Y|KS0?9nXi{ zQ(e<@;-u5wjetrw+6s~^M7+$6GbbL_kuW<}=_VJ?JNGD+v|G1BvVf4*8ZkXi$K~kN6i8@+ez^sa(<|s}eNyeP0llxaP ztrPX7qF_qS*H*a{7BK1ZFGPZxwu(?PSLmhA`Rj*E@RJjAR1JsN_<;7BDgU{I3LKQp zpy;1O?06xEu+!(qGBYrod&~!f)fCFKyL^MgH7bAs&zwT7>AWmIdJ;>)nP-v>`H$C= z$LqP8%1xyoqMYF-9p!wr$_fhcZU=FWA48e_DLF=JRH*VvmWWpy8N$8!)!45T;zu-c zTy5J)0wn^kL(0=2o8$Z*f|f+>WX{2F3r38}zgHEP#}FrO2YbxahC9q7Wb#b3HgitJ z10M7d>C%zONWJIeX;gwqHCOsHIMyEl?B7}ZVF#9*;|q#RnGk2AM~+plRR*0I!SR8Z z6apn_d%>pp)B87bBUuR(gmubjp*sioAixUg7sjCRoWYaOPLJ?4dpX@btg$&B^<5W* zc5Y)(D#)!Ygrn}(0adgDeaP!HP1f_^7^$+FT^SpHDTGEjMaUOTRYg-+f-f|aml4o< zEgZzHZV(#Sv8}9k&m~bWVq!Q5Jmjkg1vt=jG-H+g#CnKA|BLBjdZWuFQ}f1Ro7U_9 zT4L5_7;HnEJKLt5rIqq&xTJ36x6ZfnQD`a!vz~(0nL;X-t)-5>EgIVRh?w<Y8kG zAW6kgL~D@kHdylW4V*r@h0CamfKmd9DX1x!lFgb-s ze1T6Oh15ggeJNs?$I=dKLU`rwRh1x4ED9h^QpQI|)`^}Dn!5tkK9X#1>DmTWAygnr zW#uy^X8l0caMBA=eB7+?Z6$oGX|+nj*Z3WAqfbvy_vrtCO!sq5iY)^JLt(`@19~C@ z=!vLJta|Ps8ame#5x;)JJpq@p_v>9x(G$65ga2$RI5sfyU z;O%56h>0irKH!U21gAHq=zAmbCXza#(P6x^K1M5%l@PAvTR+wERg@xoN{}Gn;uKvF z;NH0Lrp?&!e*EQ_>dT$`E{RrSiJQmP{f65zmu=#nAxLF!5Wk)HWI;g0p86TfjE~>h zKiiwbsL9}B2a3B*k?IzGM$T7{kzfs~zbg8HtwD_$Y z<%Fc*dP2Y5QX$guvY;NOC{K>Xde)Y;Lpsipe4?QE^j(o8nD15UOu@E`IK|K4INWt@!O=@0~# zgounm$5o*BV44ca(;FEk!)`^mt>kByLvcgbQUK54CR&GE{P}dNcX~tmw^TP}jP-{g zYx)n)+(!hsgwqjepvW*4#GVsJ6f7*5J{CzpVw2^c@bJG+te1C%w!{+fS-KK?C1Lb7 zcjBVHOdtwFB%e_A(zt;&W-*V(IXQ20obY@4D4a(ro|ImC9%&21p3k9xT>S<$uzY8Bh=khgxk^G4cUsa< zBs~rSOmvG`y7}zBQ)qo{OG-k?`G?n?aUs)R9AzgiJ56ixlzrGWkAzqAV`2b;-Q^sD z!dNTGwS_DGZlZr{K;gA+Ioypw+^+KHds-G@sE(+MsqfBN@5c;H|J&-f9`)s0OWUd^ ze0cF&WfHknEq7iVpi3pT%KY3Y#zb;Qwu34pM3^rdH-71=8IBHXox%zJ^i8I;AKHG* z7g-zdQp;+nXcoPlMD3m`pNLGAvjv|@rWUh zKCk-G5C!;QMYg>2A6iLPSbkj<)Y-f>j zp08$uZe5+ptguxS#wB2mlRF+-OdaC8v}|i$kisFo_?Q+3)E^*FEJ$1~3(2iV*?|`; zI~=7FxZXj6>QJ~fsQKqzP+AIKDq>^B?;JEcE@Q4Vg1@9}=?zm0IK<;XUEvQu3PI}9 zyN}UAB3$)@mpe&n$w?oJqHewlyRGY8lwZee-rQWQUw4i9GHjXXvq?q@sYRZDf7oU) zn=5P|1jRX%?C1Ts<1Tct$<3i8ispJ(?(q_)f zPro=yF6Q|?Hs1s?5pa2mVxIM69R#&d2@wd$pJ@l88r>a30wD|_(a!O;O8_R^Tl>jF z*A8g+gd-k}Pl;~Y6S0LR|9oNAFlzC2k6FWZ6n{hHPc4A~B%g!_CncZAVx-D45mQCn zC&1SE1;Foh6)l6#!P9welq<<3Ne{yP|J-~aPt zrw!Aztqxd+zp&$S^b~^0L6Hhk*&QNvyFjRYQC3z5+2KHvzQ}O&qP<3q8^nmFE+;c7 z?~rE4tLd;4&uebJWMUc%@V}pgw-J>@oY(w@U*iX=0%e$B231VNy{KR8^+iZ~-%8_% zyec_EkfymH_9$>_Wq!IzWQ9lpiuR_?kNrJLAmU^>nQWNO9mcH;&;aFFau%a8x=|1n z{o#3k`iy7qa9Q+p z@wn9%7d?NYNRb*2t|QX!s4#18sEbK=KER|wG1#Ux|KZ-*NjhPmxNX|KD-g!%eb4go zp^p%80*1~W6ZU6I!l(JCo1`H%`xxdB;5H9{oa{%h*+c{!b9{K3Du->o<~L$=r?P`DT^988ZmyZ#FZS$# zap8@YCsIY^I&Pr8edkUC;(sM^sNId;PqPW!>n|Z;=ZJi zoDmkL^ZUAPOUjb+82|l=EsI%kob}N7)9<+!~!X! zXh7xpBo%W|Zc~%t9Hg#Y4>gi!lP^_Cy#1JP@fy4ot`vjHNO?)NmjU`pZy@LLpD*=|N*g*w zO~y;XEFYHA;{__gaEPt8I!KO}Jyz|kVelbeBI?<;2r3mXj?|(Ya1RJD|H?oefFie} z_7WMaF*|re)VGs_LGR1Or{Cygf{8YZ9xo3M&xzObI#0>g9wc@C~^9C>Gt zkw7jg#(AVNjRZlq^8tVXnHWVk@4rsLBs|vsH$VZ&nZ$xQ(^Lu>eO^R#8TY9dLp#p} z>!i7?v}4{mw^V>e7>J-koXi-gQ8!6xLtZv&R{kntiDj@2@216&p)rP!@T%=xv&O*# zXCf{xEPm}#m&xKf$WdI(YJeK+qa`c0d-t5#X^nFi-MneBLWfr(JLcB(CRlKj;noj# zSzADk;XxT`sE`^+f4o@w64o#Ki5H=!j4m=m`%o1h!W&bDz>%L>J21dom>b{sa?ekcf_mq*k6?$8myh{%ci+0dr_`oD4+JIS*j2Xe;r+})p zmEUM##2Ekd6Z-);Ncy4WP`QLCIUuE2JIGQ1i4zsXJ|H^3T}dgB5=ly{9Y!Cv0WtPF zuj|IM(udGCLQ5@d{mGaglRwe@WTO^R^{bFrV^R_gQFo5^Crov?32o=Fae<(J;OhVV z;Dv+>y^^#$zirmh`U0E#*dIRyX3V)bbQblbdhn#@aiTqDfs1a0_ zG9X}mGRHYqc-GyfHh?6Cu<5{YcCrZ$SE!yXKIU-6T3tPd20o3%Vi9OY61Y03!5TTb ztqZUnq}SwSpm-NPmrT6*3oN&4i?$GhE)UO7CzOV~4{cc}jnd4ycQe%vWg{C;!5L||r;ml4d# zeJiThBs0>$811E)tNgAf+ga>VDiW0CFoZ_I7;JguE|Qx4ThxGTyEc2naSqisoVu_% z?uVxz(v6<5;?PPBd)EZk3=4QLhyBDOK~j_f=rwHZ19iA20+`T$w>k5HVi5s=+6xby zBx*MDvT^@mb&uK-_mrpne44Vl2m)N2F)s9Ev{o52AC%}y&n4M#hDYuc7485xkQA$NkLCcMQ;)eglr<>Xkw!)U%3m;fg3iVm|rWC7$UP8roLi z2N2OizS3$GkB>N?Q9}L&&!{Z%cfq`KM{7wtjDTaCWcA)G7JEa4*>(TUsa+*MtIdKv z$Fqh^ciCAT)TmIPK6ditLp3E$SJ5%1hda#;%2VNT>mgYykpf(i7O=5TZ3O%*s07*m zHtnq3-WD8Le_w1BM@-NODdBCMNPSndDscU53BQ|#w~4rNpCdmhA zgA9p?Z*@-_>&DpB`t&=h5SdhWMG`~c#!Y6K-iR2>H~HwmZ9COeQmx9 zW*LzK(zNild=USdQZJ9K~xz zYY78am>$V9>yT*^=F>5evSA#JF~&qdH+MOijAr*(=Ev;#-xq+gg7Gah*VXqiG;WND zo?dOY#b_)l9r4<+4Url@7fH^E3;kC1aU((d-2|C=R?4*~(cUI#dBXN{p^F4mB(uwA zFo8(Z)lJ#SpT8<%18%x=hhmdl5{w|oIr+h&t7tK|mJO3?l+H9Gdb_(|<&MTjb}sYI zp=vGMYw3G=l*tT*IwE&}8}qcB={BRRMaDsrX){Cjo=yLupL$eyf&0Wm?N*#_j-kIu z5GQ~xEW(v&;;F%zA*H#=9H^0yfRrKUyLFS^>-hq2XqZnOJ;O*Klo)u%|JqsMfAj9? z!!dPEhe&dwG7_RV6_hNbDGpOvO+tl6P4h{8)7J}x_MtJgidNlC^a8eWYlDsq6+t~! zLMotX4-vKqjr-)j9V770{MTBpMCYSqb8OSh24d6{B--_)Bn^0V$#}8(u>z>wFIlhP zBw9U}P`$g!@IACP8u0%|Mpj{ZOC=nlxvK9mDz`-sp`7DsTrA%W<=3dnronQ}FfxX- z0m>!s_T55A{qvw@Y8z+TFyHp!EjtAby}uzdD19ae7*cyM`50WeQ`38|iZ!ohIEB2HHs;frvt7v^}i)QdlP~h%yiDdjb~i^xOXIi*wG{ zKUwV?XQzKDikGnS4oZe`g`Oih1+Qi8eqQ+28+oDpTk7oCSs z8&U{VQYW_Vx`Dc*ZRUFaC?AwBzD_^;&t4GcjFk?@Ci3)>2h-2>_NpilqEIGY=jdx` zzD_XCdZZ)99z#MdJl>~C|Mn0f7|%*siSur$gkVGziqIW+TA6J^gwjfP0r$HpNO?NA z{kO50{LWhy{FTuvORwp+7GZ*adhfLyX#8W>NKpr%3yXd9CK$C+x&^<>-D|jwl1=Ss zo56#ziR5U-oq#4N3&zYF4*$XPAH{F#7bM)X9N4pdY7r=R=WW7#CRmA;r^f!C?C*!Ql5t=67Plk&97UUogpDjbbx-nz~5Mx zGil|eRDUWQ2YcxGvLc*4!E*>DlP4%gzr|Zpk+)1W~EdFeV;0 zCCJ&qP!{F}u^WR5tm)<`N!CtKlQt}AhLLLC9w)+DB4r1tt_TRtwyOA)w+2|PO+N^E zZdo6WHts_~!wbPm3H%6QCo^|xj^gzWC$J=fQC{v@4yn+mW+X`Ovp^9v$&yVcP0)PT z+1(qOCwq}d*|a-xPP^V^O9*ZofX4NNTN1&t=?JSUSxI$){^KQ7K2|-4PU*d(A(cbf z*gojcOv=U*jE=F=d0rK#Rl$$t;j5B7=yR?DlP?BEYv(Xi0ZNA6driBl7(QbT*|X zs%D=!g^*y3^wLu-{SBthkf`ij(%S(M?<`7f9z_M;4x_bf;q$pvWvG>Va|=DP(_)V8 zFIHS97-0?Ue3MH#fC>cXbjl!WeOa~L@PF)?FD(w4jOdohabx6neXS@Eud5-7m|NJ% zToK3GN4qbjl4L}9J~by35qCHR@HT9d*;Ffl3MeBh=w`nM3O9tZ|P^gJbX??PdQ$-|FIHlu9smDQuH z`vKe2KXG>^I@$FygUK6ryNDzJS zUf=gL)!-BnZOnQo%!L_s5U4m>L}!7Nbbh~WRyk=rrNLpi|CoUj0#lDk31*(|{Z#It zqotix>L5f({JG-6C!$o_7!Ow0lEv-o0nub1`g58VTqTR&DiCBHU!iv*hKDPi@yhb> zAi5;mfzx>ry&5p=?;F9IK;tNNXw%zHdYOM^@zc<%DRX?(pNbe>8~~a43+S2^oTyYp z=G1a($=pIBOFE1hhoN?<1i5g%oKR@Qc}IXoTnUMNb3&KTkJ~VnFZ^s5$d5!jVZ@s| zt6QgsUZSr}0udtY4t5!5NQ6>?$t1EInyH*#npBiwA~Qqgeitn!S3LhHu5XQU%lS!_ z2271j?hn!3-;=eH^mnHZ)z7|Yj6no#)0NUW<2f0pRT_YWl0LH%9P68y;KEPFM18d2 zmOQPAN7a>(7|dp(kV1t%;n@RR#I=cINZJl{N@1eOM}SJv55fpTVzyU*8;(!EJ~O*vP{p`Fkf?y3ZdFAVLHgu<0{6~-k44aK%LEE@GArRUM!K^ zzJ?6*B=We=3?+Wp=bzaW$|xz9gpC#d;9g1Nn@Grl)hDB%ir(B~SSHDl5b5lzS_G5@ zaJ`}o4b!HR4%f?VA!sjSaR`Wvf}&DX`i<>O z7E0K(nwtQ1BhDTA-Xvj>FSCD)rY)}MP(a>fQ-$QD1dG$x)t;S!iI5Nfs6Y$kXqj}% zbbaX;&p_Ep-k>431mM}p4PjNJ0n%g9YMZZT5N0Rl(=P`j0TyP-!(j5hWQlRH?n!mN zhq8Jm3g#!v_)^#%^eJHR^Mhz$t@0^IdsfVz~+K3$V0^N(Ibn9Vx}gvlq$C zG-NykuKOJT1jyVZ+ASc2fupr{1(iI<7uS^0^^OJQL^6@HNWkjr7ozl~ihwdS-^yv` zO@Hx4DuH@?(@ftEip3gIW+p}k?cn`AW6feX)@NOnOm1DKQrlE?C-+_NTFrHp<6t3Y z0;ZO9C>jFI-H|?HoARDTr97j;hz%ox|Hil|Dd`s3teV$Z>K*LfW@nv0dCV>@f&(#5 z2vb{ULhPeq)HoXs-u20djUJWOVE$UQWE^;eRd;CoILF)y%yr)Fcjugk;ZzC$U1P%74y(c6eAEU@34Mv^w-g zP%dL3;sfQ`C?_q-@^KQdWz%guC|RQel-7pwmluTT34^{84pW~LAyAd&3`vB6*U#qg ze}kzg1p?Cl0b_trr6w{2UG77JGwvI{52HphK($YKp3L@F3c?hkGxCJw32m|`b?68! z7nO1cenHH4BG|R4oa3_MSRhS!Zq~awB zMfWyQ(SWFE8R_?U8s#4%P%zn+C0jWYd}^kP1;04;zfmS&hh`?jfUA*66l(IFf+sB5 z=9u~~XdWF<)4rmJgAO^-jIZ4d1*@DEkrA1@p4CEDK+@L5O8gbN#col5(B|AtC6Fmm z%N}FPDTUVZGE`!yCS?pKNT5s1+^w!S^pCikv44x$*Fjz z6vWW_y}1JZlBDRC!;_%pR7T)o1d>-EvT()rziqx;S>2fE|3?nlp}1`@CUhvC1}uBaPv!O~!Dtm+u;14m1`H zH1?TX5%r^v=Bu1!mPOCXP)@f;{5$7Uh{ol;{2;|27G8 zZU}2rT+<6(L6G|nfF?rP2hQ&WD5A#H(QK8;dUa{BU+eD_G)E$5(nl$H9|p80hmVpe z55S8aw1r6wCyh+w?5#1Y=q9B}q2HTMq~Q>;gdS%n;`}7rCOCXK^<<*l5U`b!e{*9% zWYMNs%#6bsJoI0>mzt&nFzOd4PQ&XEg<-y(o_B$8@mn(pipT}ESAl`1REpowkUPOa zQO_fD4I9ABs|cPTL&k}>?rSE+InB_x41dPL1plWNG-T`{Y3C4hb&%DWp3zZ&aPD@2 zd?=Hgv2WT3{VGm8st8vVwZ1KRW>NbUSOufTz%wlmzJYr0(=~%Avlg|DGx(TO+^<(a zSZy_#8%XLr+QdVXfzaB;M}e*+`crmIIj;UGLa6wjMT^Ky_Y{qy46FI?@8Q&D(i&RM2{FQA@G%V%klhQaDjQzPZ z;z>bxTh#(Ju~*yX$3X9(SKUEy8Og^%kbF^jeHA8A5E<6t5k#HbL=d6Xu%sCy}e@{XF5t^0({pQ^v^mNzshER4elduHxJK^GO@PmGH1{?VXAqFhd z!s67UIL*n}udlC9*uUvZx9gog;<-IS{BOh!@@zhv9PR>!z(el0L6{=Akf)43?r&MX zjh2?S9#S#4QJ|MmU+IL?23;nPJsl833^{(Eg!@F%i8yc~{^1;&<#H&+tnv2OUXe^S z<5=sg?DgIKnj-UG(#5FdI6av?!fy>id~ZEHV1?{pq5GuS*0VI&Vt^CjT%wL}*TUTr zg;uiHL+s(0i$vy=L5zt1Q3v9A=UuvFC><%XCw+p|I=uJ&fw3iKK#$hLQCXw>B}Fcz|2TVV0)4PSzVGI6qZq58{0Nb!AgndCR)X3K;aK~O+R?|_XK?n#?%G~* zM^j++8vxe|*?h4l;|_%0cA;c&vcWPoT!#iIo{zYXLiNDAhxVkAe&3_LH!^_oTZLA4 zP>*pLzkXA^bGP&6KcD*S{1B;XZ}!!*yG-`1LSB^p1n2md9_yAtl#%21-<~cbe}BLq zQXk({q>A_?_c-VD-4Xpn?RcWnsh|>2X}PAg7?zF*p}^M?W;n>o>sB21(E_~@G94KB zTtbD}FG}c=s;GXIJ+_REHK8GGjx0k*>hcMY4P?wCh*lM`c$qONV;u*p&pEY3n5Ea7 zHR4VxW2pXtSPte*dhIwTKQ|^quQ7(jcV3iZ`U_#&)0V4ePGdCW4k)V#zN~_ zQ_YtUm2}G3pSt|bK9S>$Qpvs2N4!TQ-;J07dy%q(g^B;JNp3}kotNp|S7XUcVx9VC zeA?3EHCZ>5ZO?7`YPQ>=OHFJS<4T2>_9>%=R--LZf1Z8+A}&IwA>M54MafwomCn`6 zZ}UG;RIA|;N*@zh;o71d{%tP8_caSor+PoH=IkDU@83dpz70j5Ajj4CVbkG+ z%=flzt87&FR1Q~ms66DVROW~TCithvX38uDkVfjg(o-|O%b|;k1mRK!D$omx+6dT- z*Y!L1Mj7!CNr1GX7arGQF7)Z4YW>Z1b^%-JQ50x^EKV8U1jf#p6OkpEVg-ONeY(yl(c>9+1I)xHC+Ww`wmn4G1E%k_?I2@ zfQCezYjQN}zfw}adSYDd!2_44y>_dOv_>1>9%~t-+aLFIQ6A2XWgijt--gv4uCQVk)+k^XYnchwd`$erIOY z;}l`l-(w_s!=*!YRDPjWd}i|*yNRk8)$+@O`KzlevUMARMLd@;zawy6t`6h5y6wf8PZI%%>HW zGdaF`=3C1am&WR=Zc&_$pz(EZ|_>2#xPNdv<^~&Cv9X71=K+&k#3Fm=!=#S zxiVN#e^(Mf5d|ZeW&^{R$0XFQ2W9;xVeyk{oko>8W`Z8t+fg%8J@{B9#il4eI&_1N zMf0ElO|H~%kLlSrkC-3C8PV&BbS2ZN=3d`M2CbR3CyG7RtO)h^WV4H{=9_Jj5{au# z$uunRwm0k=F}n8$&HQ=+_9_OI&d9C{y}Oiq^*yad2G0)Um$h^y4?0iWGF&(=HFqMC zF4?;6PXO`*v7Y348!sck{y))l(LzBEqLQ-GqawjetN90wu#5hzK{OiuGv!&61p@z!I z+3W{WucN{Ek|Uu}Fn=vkjKfj1v``}AQlzhu!eYGc3khF=$Z78DCwaEzM=z6d4oOIV zk?#Ey&5{Y~)FA68J7P~0Q==&mEFou6pO$i0#aX;4Z(h;-7+y&Kk#_FEYSH_5iBbb#1gAPaIY}*xt-VaQ)_j-K zr0qvjB*=O-v$PcJycZMXVyBGvhqctu6)hvm8)W*29jg5n#`)vEK3&V(?(jbi+29|- z?jKrmPI_CVvX^B_%$Kq4oiR1yyz2P@hY|-0T=^45d(ZUSaSOdUv2GP_@0)=<9tNGT z_X{3=7ybEmi5g=>du$svz15|v`XT!~N}zzx_Wh6n2Dp)skmZ7e@}cnUg646^2^gz4 z3HDo~*>ddY(M3c<7h&wY_>#LKnqh%DvDN_A5!{~t7=a>e2CcqtC?M-AX0I+KN);9@ z1m;F6yb?MM?&8!$Q<(3=IMkjp5wj?2hY_s-hc$cag=&T*ovRm}=%CRUy6mJg;bUgm z*=XcEQKFg``zdzw$LBKs8es~{>jngKK4my8PlzVePjFo;=aN49{6IN=(qq2E%v-IcK$v6%S)3gv%YhPE0U^q5od!_7Y2o77$ZmhD{ zXuaP5rJN~2`4YiQBYUTU^0re{JJAYmiJC(jm;M2vD&DIab_2+5(k`4M%v{1?Z{T>>(5cHXqO(yyHUjZHN#v# z+lF1{WSE|%b9BLf6q5dj(+ndJU`@)b2PLf}C9Nh#!Rxq726$%p8<*HL$p+Yo8l#aC z7ZzvC`!}pZpY#|8ooyI%PrUVP2T_mGhd^WoX>H=Z-v!ZJwz((Rd!!J7WYfZlwXz|K zQSx41il%nf77K5O^^a*-o%bIr_+lyl1dG}|VX-mPdQ>jr!fSVpIB6!GiJ|bE`T*e@ z(q>ZF%KIKa(I7(49jvhnKF4p*z(iSNklh$s+8WPvDURAx%LboZ43tq#a6K8I0VqJ* zF?R8ggRG{Ql`u46MhHdx*UFqkEe~b+`#Z_0{l&t!(QbSFO(L{L@C-$9FO_p8B#+zH zuC~2}ZCE>=bWYYS%JgE{E*rB{x6M|yn?1&o1M3D-lE=(O8}nSX;%zFTD>AyT*xmDr z=~$gLw%nR$XUdm`Yx=`od6j%IFZ4#HjWli5wTiYP)#oRt6PfAYbGo@bd2wG5t+gD1 zgXS}adT1RHc17Ry)rI+kq#?V+n~R0OO*Sb;Z$bsqDVeB}is>!TK> ze#QX*wJmw3Gxc_&cC?MnmNyNJwnlx&)t=^}`&vV%xU3KyK9v4Fu!E82riIgBd{zfj z(%q5T+nVFbYmc_p0aEQnqdBCoj!e%$8BfQ(1TqHD1yy1((nYQOS&7F{QzYWXYDxvp zj$-)`Za9&2-}Lqz&e;Q&pR#ZiZ^dKgbyklMl-r?A&Qx&~>dsn2h(B z#nQaxfm>-WUs&}0mrB`4JqV@Iy{IL|?{P+ig7*p_{RZ0+8oWp6!UnLo92 zDVSrDi2B1ZH#P4=Der+T&bYRLGC;b9z@RRJo=!lwbx&Pdl1!rvmU@!Cp?IC zId{~IUj(u9H1zF=tQcn*Bpvn{xEs+MNbTu`*lbw7@dj;SymE+I+%r>mh->=&ZApJo z1@l7h=?Vf;MI=G%(TKBy-7osOE6$)!j7#M90&bywS1$j-7~S`#k-g#ZpEi!~m%V(Q z8armIgJuWbBSAS)!@wpsf5VNe#a#ZDS{?u@05pqQh2Xb7&hH1m|c4~ zj$kCXCdV>-+cQcc<3Xx;u#^LiO+d>)d~c`EwJNVx<#ibvN^F(N+@T>m;($6*2EJjE za*x@!iithhT-%audp6wPyFid_{!8{SL^sbf2D6{h=~{OVd~FCC%zROlQ}5o8@kYQz z_-Wce#zfnr*wH$br-lp4ntWpiz6J^8+7k1B#qz!QMCCJyX0x8OO#XzD*Sbe;`UsoJ z5BCy>9=Xnk(=@4Oyu;;S>&U3tkYkEiZ-$DMQ{HsE=Vj6#A(!ze!TL$sD#`dU+xm_; zrvgD&+g`Qq+zC@@9_{DKvmQ-W^lNcbvb8sVKLCmaejd(arig`n)r1 zFryef#hPKirmD?D&2><9xI@P4jiZyF0nKGbQ~?9^=a32!q17+gUVCXf*qo}Mc?EYT z8T6;I*O+r2s216w9kw@Tpu0`CW>JE6jHX)$k5bg8WYcE#&6-*M?9V6K0}j_ej?FU<9}b8MwM`HrbS8$)W~3##>TEwvKmq+4?!L zF!0?Jw*2cRC28RH0C%}qWJc~;WUbxfX@d=J9JY6g+T{FuhfP|RPt+_k6?>9)z(dFT z-AH+nN==`im-0%>j1tpbe>;X-Adqf|-Tk^CPOZB4iJ5tZzyBBZHD4S4T)BKAEYtgb zVNcik$hCr1*3~`cA5%0_Vn<#IH3-Fcttep5J=olpJf=e;iT!sraI4l-Tl$Lx>BNr3 zv+LZnR2hElKgNG?kyyKpnO2QW!pW~$Y1>D9S3k4jE0d}e~}z%%RpO<0d$RXvJw=MujyoE zwUd+%+Wv9wrW-AX5m%ED!{RDghdK`QgPN_#=z2GWZ-b;|s5oJ23tlq~;XZU41DCQPa%b|l@h zVVGTaG_A6+ZvfkTPFkSSoBFdoFa&4!e!QMrY&&{+UW9gqc2MJK`q_`t|L9Z9ZKO;} zsQ{y;{=qu^Hls{uENRYlL^J-m74w_Dyy<zoRz@4cWQ*c>7`&hiFM+XQePUH4Mt zsH9au=EM=$_rbKHj89Zyi9O<@81-~`KAErfP#|pdZ$slzg(!_Ej(6VF<%BcedP)a? zdfoTtT;5jA&mWG~32inlyV1hYk@dWd+x_KDQWjB)saT&J(Y7W+E|1q)GdB6+-n-VH zKAD~EIT4}N|KehGthte9jP?p4J+r@R+CEE^toKixsB0Rjk5kXf^gM4^U>vPp#9`82 z$$tH>rSw-uY_|$>Yh!fA~u%CTx7n{WpmQg@(Z$ETu`adp_1T| z20t|&yXSO%`yaR*sQA=z)}P0^{LbbC9wHWewurpWo9QRrxqW) z?1kFX5tTz9tkG&}igvkbx28yRq z;m<_`FOPjVIE@9EF){#wGEoR*fn*0@od{=hABq)LG&xKLXir_CEo=^+@!nS}MJ%z{ z?Bq@ipq|^OxxWGJfO~*qSf3F`FGLl!qnx8+WszD23YPTJ6I!J4M(VwI^}{I}bpHTX zNS+8eTj#oMWhdQhNhwKPAJmx!_)gq$CbRX3W)lRdB@oaKR1kqxts=%Hy^U_8`L4+i zu9pM5{-v+r50DtQaOvf|QG7BHJysxRP@X)~7XM*GW&&AJ9a^?m$OBV^bB|O)TC3@g zO89HT3F9B^K?W6A>xVuF&r31|$2V<+%|F$ZagXHX3Q)-czm%W5NBSXix`6KV4@*l+ zV=3{{W?p4nc#LQnJUtJ&noVR#6;b32f5%pfZeLg?nA5T9%IfOs(NVGu7LH#mdM?~# zOZ2w#0$K|=WYrVCDH#Gh4QbH4%pkJkxFwz+l*{}VY324;-T93YNWfe*5{cY9qFa{= znM&;G96Q^rJ(8(Y(ZRA(VVK$>ki-4^8~nRi#X3UccsCWr_c1~YyEexZkzmbX#_xgD z53Oi<>u+QL&RrCNd3wAGFF(_j@MAF5{LAcNY<=TpgJgz-!j%`amKZlyzr5z_f#IOZ zDbA3(&?piCM8pguaz$ej-3`LcC-G0lo z=fY*wWzRXL0r(-kyEam9#8yh;a>t>!!t)bMJ62l`lx{8O*FAAf$bD7-uZ)G0_50osGad1G2QHM4gvF5RLd!lyA=M?RU(x?ia z2)Quc{W%-B+vFkxe`J5ooZ9IxSaX@AjV>pkUN9vMO)ez{&K}(JK1&l|Adln?>=)(u zNoC`pNC`j7 zy*f~#gc~WGbwL_vTVyPJ3zwieQoW%`$i|y7TmZQ?Z^bQwn=8?8Cy2oah&N|KE_x9_ z5mks-m zH#^H_&=SCyyr;Q+`*uCh8i7&9PEG|0;G@@#k?tj`%q{9QXizIYa{+aN&2C3)K%a7! zdc9D4_-m#b0l_HYdCmm*LnirXe;jkPaavOB6g~_M!-7-``m+<8UXIJ_37bFJvw_sr z)|y{=gEe%$UPdPO9&u6CrlQt3=Id8CFv0U&yO+P^d1r!Fg5h87QF1IMx+hD+nYc_f zzn{79)^f&dM(^`Yyp%x3En{iEdj*zxZ0t!uf~p32Rw~QRnPTC{oUFiHB8d8lRP(V5 zuEgQ}MBv=CVTUgd9r~Jpd5-UoCYK_>Ih1QGb|3Zb^{( z34dO-f?dzAiE7hoh2Tn-l={iH@wM;r9a*Ig)0jAWoORAsRDRANU*$M}Uw&(F_Gez1 zXh8xw<@iU0(}_Z-2?<9liE+Txwt=C8WjoRtlc zV{KH>ic!IDD++S;*}%}1a5kM5lEmIJoWbXE|8QQJxUli+oYhZ{?_SR=D>WK;{A7Bd zT#ydtAo1F8u-2Y1*iKF6gxcGTZg1EYdhFzD_hR+4AuKPAQlf)=Y<>KfiPcljWxezp z)vy19IY2>qnp<9>rl0_i^X^)OW#8vB3O3%C|M9P`?uK;7Tly3RBdO6c%_=^+gbUKV zK^u>RHMneYrzC}khrb)++Z%sDS4x)eL_F0n9B(Ati$#czTSbUUN;PU@pQ6jguNKQ% z2eD9AxLzSorO&icLFJrn$Y{a%@c4wy*jF`A!HYsvb7(JW$qX#rlsmka-^ar=a z8#HC>95_ZxHMGfhk>BM<@h-*^ClHy?r)= zlF`>BgycW%1Z%oC#{onZKJ*hn2DIykU+EBuu@u9n|cVo=M%|;I_1-!M_yD`RH?5^rmLaI(db+w(D3?^Yx}s?c@YFC>(P8TXx;^ ze|Db%R4IFFNJp5UOI{A*IYSnIe!$ncXgQXHXQ~5n=u1@~Ja(&Z=f3we6^yC#sF%e6 zPc=C!2fw`0mMVVPQ?~-m!i}~jy=Zk$bevPvinz870K9kNpVMpMtv0mq<3zpiu^lf% z)F!1_ofwyr@t`zedu6iiiJ+7dS5obAD3kj;&VDpfL!vD|IMO=)i|WW|RG#*m+5*J) zXTGpHlu!Xr?tc%^cA^N9NP9$C;AVEFLM?11ce2wiuRpG#i z`i*3^W!bKg_6GNHs3@Gg@<*kdU4!wWXZ(ZhWd+IO!*#$60;KJBb zM-D!uizuaaUuj zT$O8c&oF3iOlI8R73~BUF^;(d4vf24>IP_?BKF?IyWfa4JS)8|_pdM&g|iZLXIkXy z^DLacA_{#0M_X<&*tzoN?Tm8wIU(XjoW;#AtV51J6YsPd7VZwh)s>ACKOb~FF8hG3 z%29_l+iO&7YFW+K`pQeA4yuVR@tJL5J6j^drF;9I*{U2`_c^{ORJNjArz(S{EP<~} zOK4lm!#;+q6<1uE&EgnP6FY4Ee&x&G>IQuG3o3`=;hN+B+-~cDrMObqcruO&ztOg; zc62xGBAtcDom8*w#-=T`pzNStkJ|LcLv~C4n3L9V=JU1D(7i8CTb?ZxY;`WXN^rfD@M`raUvSSP z+)l#8h%ykGn-t==J2q+0JFOK4_{23`tbuZC@C9T2*@m5q@G^gT?PC*lO@ zxP?1zaa!OtJKb*2@7;&D^EP5A>SH4mt|iNxZsBQnwgfoHZj}jFD&pRl&v%7^+6s#? zIPY!eqb01BtKxYc?b$^=H)bSNwdBJ*tdf%J(MQLrptKnA`-1JMV=zYAXq@RJ-v!-5 z8vvpx%y_E8WRMjJ2qvso+Iua2`xKvYr1ijH>29F+k7DUWjBzn`vd z;P&kZ>xbmz#F+*t?#CB$(sw&v^WgE@h4+ndu0^S8t%BBa6S5awYg*+NlUM$DwgRBs zO7De9`&K5AN9Ig786vN|+JeK=coSD?D9aL^g=#5HN+AsKalqP~N|F+6VhBP&Ssg{8 zU3c_286Pu%+bj>vW-vq_YKbMH{XGQ(Sd0B6mRErK*c;C+y^26R-teV{9D8!z3&^5N ztc%1ckiRWQmFH9ycK1AH-AN{R$1e+qZ$}TwEeSZnWIJb*^`(pF*i)f@9Ekw80%7ra ze0YB>vq!oTYZde>S^BkZ90&=Kc(PK<-*2VT!z6_>+iE;vaKd?0M)NV$jX?c9x*GI< zqc-3O*Q?v37=D_fjb0>1miV5My=J(sR#8;79=4}qr5LZZY@l@3;AX+!sNxuwf;>6~ zX>=1vd zvGekuNt=+(K_f7>2#Luu>K+AA-tI7ksBGb`Vnf|Y@9OMcW6{Qq(vBCwXbn{|wAx*= z#wZ1T%K9AB9T+rwHvW@KX0dC660!t1DY z2CI`S6@eVdKCoEFUedOJ{>M0Mu3IXKKNryF4WJ7S+E}R!!V`Fz-rFvINQI)t8PrRz zgq(`YXV3x~$c@Y&)gD3fyMhE8FPM(4#NT2)IpyHQ<{e-CQ`6?AmMJ#>@H zAcb%atQ6NOgBs!r81cU=0#a2641mlTHtmU4vI%ra^(J`0f={0o|yRQSLETz-` z1SwEC=1nYIzUAD_qA(Sa5}C%)&5U!0%L|hnAare+?rpT^9FZ)8rR1P@6Pkr7OZ)JBKd z*r$e(nxu$2yR4ce&9ITnO0w!jS_r)A_p13w*GSVg?%-rI9Y6jqc8GLDW)eSw%xPAAl zL{%yw9##54pdZduopkjpbBkDM>jqdE1P^?mvWR{5+Xx(_W8Vkb`*0k&Nqu!ue;*it z|Bqw(aM&CD6k;6WYOmm*oEoHUb`{+aDsj!6p@$<3gNUSV`lu<0)+`K*`^4gb0SwtE zI0F29VxYoOP*nGIE(6`U)^akTx=MI4?=`&y=JnB8Pg65j+iJ0U>Rsk=a0x_%BE$Ls zLU#ctnYz-sT5P_|4|suwdXVQA)eYm<=q=TD%_i*H=9h9D(R4wVHblk(V0Nk>@lBL# zy*#gQ7a;DWEA4^L z9V$sQiGZWWeQ5*{s&U*B0#X?Av2>7CB9b5N{w0+6SC<)DxOeRqEvZHSvMux#_;d;K z75xjNee@F2Uj6>(0wXnBV01%(72(i4{^Y=XfgA=J$|+i+5JNJ=_+`cj%sWCA8Nr=y zXMAssgA(`U@}72gjuE(IlQr3}1ZAM(Xk+Hefz$KbeV>(9ifOoZfkXfs+h-S)$1dk1IL%Hvpjaz;}qRz z%SSpdk_XB)b)p`kXjrU_nb>&v&ZY0WI_1yRmluu+=HB${x_ zneGlp2ZwP~B5+jLCH4f&3+dC6EV;0w&II{?qDfCw(OveQsOHB?T}O6hu6we$LzBHA zWL>4Vdfmg-6Bs)h0r*k|KO|Q?Af{5|a-&FsI=3`5d<42tpKK8Exric@lGyr^^Id3} zUSGl4l0;i?jiOhUc|QFIwQ!wt@Km`#|D9d__vuRsSwVYZg}INL z(29yK%)kWCx(k2p!r`kreDK-fvsRC8EFqko=Ezm%jrVz;`ZXo>r{23PdWeGLhC$?= z_(1(t<;&=kjJ4xGQJ_$if(7(>xr1JU?w$pU!c#G9p@r&C+N_W-Lut@vPLpj_AjPO4?h zAD(Wo*gy_4XRFW~ZTO%>yE@;99w5e`}NEb2qE8 z>lNEnA1LPsAp7Wkx3ElOVe@X^$5g}ZMfa3*rC$(VSH?n;uKOKVm_D@5@%Od}^f=Uv zn80AGzYEWBaIsqS?KD?~l^KUW?xo{)4L z5b&t#Z!s=zmCnCf5%kUylm&BK8*n<)plblT-tkt*`?g`ytlfJYlSf*H-fqrZu{T!u zsWoGahWcf$D%TIR?=3nXs};9gtys1{nH05)W9@{;$0&52Skg_BnAK zLpg=$k`6_g#X%GuLNa8?km*q744D%tlzF(4$Qa5jGS88uGS87IA~PxBCiT|0`+Cl~ zxBGs*|6hNdzV_K?fA?N{@3lVbv({P&ir)^VByyyRd4`RtpdYX&>jg4m`&t%w09wME z#ne&krrQIxt*wv@a9wX>uKJu2k=wy`y#K5el)1Xz4{;l|;Qq6pWTr-OQWQt6X571` z|4unp{|=|)f|Xl5Tnihr2Zt6z{z%-uXC0zVf-M(S8QHqI>6NSdvd%t7;EAj~p|_A5 zJe)%5`iXNQYVX9yoUx&okBxPyq|Ol1ZZBZj~ZbGO|4 z4i(_irElj$z0xRj<)4*sgdc-A2Nk*l)lvH{4|NvL!@+NA2PC6(y>VB18Tsa(i(>bX z0IV6?WkPtn*q^+~>b`6iP*&hct5|xP-fhNB!zX)dOdPva#gWn)Q#qY*BQ6&>*P*Dh z4_Qd|=9gBx=sk9637)Vq&;Po)ffz80gurwx#==MN@p`>#TxzO~#E}rsyK^eTdpsZ=YMbkQX9n1GjxdNS+Y~_x(6ulVg)E= zLaSQUvkxo}#5q_2OGM0ZTrMWDBU^r^4OvgZD>dn|=w&(SHA3;+U+bCbwP02WtVCr*r9xsgoS^4sSIV2%vOFJ%S$p49*S77Q1VtAH%= zaRVlbmKcbi%t&;L+qjcGop!W!BH4WAlX*^c>ifdzAuaAX5q-K~*WTydQJ8k>R-7S(XxmdUm0x(_z56-eU)NCCCQ{&J9Gz*@-H3Z*H0 z9#JFdlvV-k7=VJNHelnZO88URY-Z`YP;}LZecJtvQErc+R%K?{_9@~JQp(FF^e z>!UQx3;NVaM4x&@b+{+b!4p`hP~nZuSx^M9GXueAMbbfxxRnbvTn{vt>Fq6P_qER* z-fz(A&avN;=*`Ad_F6a`Gr`JWNtjS<0z7ZT#8zFJ}&TfL>|}vDP674gu%W zg#8Kt|2ac%3uSQRfcJ}(;c|j4o^@06K}Qs!5Nq@d;u}?rxBb|0V29=-Rp0pO^Brxn zH9wd~K=q)zg!RMuLJ9(4GX!X01GhOc56UNgFvbSjI71-+A|WBT@u`QSR`XMyhCIgb zuaMqr5K_R*UwaHRnsUk(;M5KdvUAnByKg z0JUYXB6hH(z6%_;LrN^v<#XoUg^z0+l@t5k=_gODN%y7!6MgabK4&~3s@Zj^VdD#s zXQ7}Ww?c>e7^GZqsnx9Mzo!y<#HBj_{#Dye2<{k`x+L|jLwR3Nf$-Ss)%jMdUOl}a z$lull(GI2`r`iPxssn0>s!^PG>u{O>vK;uFY6qjUkn{7yMkV^>0##W+3e$yilzyBH zJlz53Afchr-CPcF%mqb-+eKK|b6()uT;$S&surrxyPuXsnuD6P*c|tDe+QG8RD}AA zNMAf8F+h6Byiq?3Kw$~g^X`|bQ`Kgu)4~*iLL~+`veTGL3ncL_UtmbS)Sccsx{4Ho zLrSkKF0})U+%4=M<&L(Bz9`k9*%`7E{D4XW4pJC(W`c6VAFL8xOqek@YVuv!o#%@(HOY}v({)t#UMtiM zu&31m2)Op8q1UJ0^q9L^5CkmK{htn~Lu`gD!CNwIXU%dD+29KDZ?;QjufwmUlv zGK(sD{Baa`V<)GwDJ3pdqJpS=SE@flJT8wk?bxb|{D2^u%$yUq9FZ!-4BBiKu@qfAZg?pH_C4kCqVhYWf&dut)^g$udB7qRZ$^W? zLqopHeyz(tQhA59Sn=X;mFGa19p*(j+#aFy&L}!mY+S|g)2v~xpfsA2Sp^Q-C0FCp zW@9qApGP0xfA@sS%;}w*V2N4iynK*dAvZ?O`)K^9NyFt`FZxQdDCzVQPp&QDWc(H< zH8AKK5MXo5V6TSYzzoHXhoR^CLORc9ins;_;KlM=8=S^G@>0Fybc|D@4yc=1P#iWt z`354aoPA0VR2p#~6J)!lin$7tk@Egw3p2>)nUx_Si z0#L{dG#B&(koWE9C$MDHX1sV-lRFYxD&&P%?ARctXB8L}mD)^~z_V}{-Q6NYGyV7( z0F##>KV7-@L;YTe1UJ>!3-ZP1Q51UFeTBG9q&7*L=muO1ML=bJ7w7%)K!lbF@Rb%N zlAFK)du!1Qy2Wo~HLMv^2SJzm4!CWyX`QFt7j^LYX6USn2&MSog zj-jMHzKuT_5wh{{tm9_^@ym;bQ1`x5A)v(t4yEEzHnVTG)Iv!w(#57e@I-vq>Z(^| zzmy&rVyl&28yW{9nCL>s!;#Di@K%UR>Rvc4>vwQPgd&I={onv*r6e}osDG%zXy65FYu+ z2-1CXd(nXj>ItHxI#mTJ@wU%VQVf2YJYAHOwt+fra%T*$N8b?=Lp?pKT!9jmcnJ^R3apG|deZ;$EZt9RZQ?xJJbozdNOGiW)dkpt+BJ93e=x<7#@ zLz{`vFue+da8X3kMc zyucL^VsloIje9=%0|4*_Q2xv`{fzU+(|G!`kXO3?H#)X?oxx;SBOgdg(**j;?_j6u)&7#cW64C4shbpe4tUGB(NTBzip(*N z-9$&RM*!;wZsc6J2lBYG9#?m2peJMj(iZ5Eu(T%g5;zkp{H%r?2RFh4Jc1qr^d4`4 z?WA!I60*R=LFPWc_|u^Jmlh&bumVpyg&yAp7)m>x{t zcvg9R4fKV6@Qq&tYK44PpG{SRvQy>$1o!iY(L9YEGKZaLPoRQgf_a>13Ha>5J%i~7 z)IX%92G8%Gpiu-6m!thBAg&<~SS*Gt08GR`@i=)-BzeU3l@XYC8KL)X(_f=H z3Mnz1mOBJ&+{Pj^Ub#;I=fU}Unz~b((w)dYdoV&uAPrSdYv28Ni>P(Z1{r7el@*%G$Xso-s#v_-_U#)5 zprCfZF)4v^o6WdpLSgDRHDL9MZ@^8k-Pr5aV>~w2yYUeiSydaIklX1^(f}uK<+q%T zIv#?qr5SCjXpA6=TJ9Re@pI?oEV%=K?RY{h_eG|sPh}%F+Dr-mb`UbCWwtz>lPDob zXKSVfgUQltm*a`86xYx>Pn(!Ucv~Ke0bHI+JA6hL`yKjOU)Z;LXsAszLc<5t)OL!i zqE9bIT++5E?qWS&in{i6!53o5kPHo$=_U!$Hy`R1y;Df~ESuiZ0SwIxkfbKDHSt(X z09`@Nc>OEzkBrUTKH6sm{7(B)li{m~y@z;qSdLiD$PQcee(*s|KE(NwbeHY=7sq37 zLqJ=Ak2>6DpT86ffTR8{R`aFU1YcW{>^W0|b+w%}YCt*wnOk<|M(7dHf^lZx^C zPm!-7KcrV#><@$wW_>7_+2e@b+nz3w)aa`f({Q<$0MzTAO=fDQreez=j95wRHoJR+ z0`Ztv>5cuLS;6I;U3D3$1z0LYL@_~5d#Lcxc^}z1PS#7Z}brPVX&i9 z4HEOfysHHBE=dptVYP1U=WtIVbc6wX+Cw%Ov|_6uIIfl`+3Q>a`bYYOrx-;4kU6C8 z_W%{^f#@GJZTX;o)cVdFr`JJgn#t&p-j*G4H8s_m;F%}3f6FvgALn!cqq@RI<_Td_Pvj_q zGxJ;K)-5p^Umf!`()UYSp|PD&+-0wJD$GlmJGsD{Fuo4103(NaNNMc)mJr5NY&!>3 zE;~>YZMu5-aq++%PnylnXzz&RbvvTaW|r?bk0oDO`Ua+uxMUAx#$0S<@NkqU_^fsEx?)0lsOrt{P0`+?HX^+>G`%NwxpmwV6+3}|;@K2&QL;I& zte=Ge?Xt4n_91ms^QnPZ*S53zZ{YNBzP&lkR+MyadL!9Fr?-C`Y=|QigQCj!9$SL6 zwXD=c9KpTP5F>Y4I%j&0v8DmcG6a!Y+rahpx@LKL^2EuPuY9!GOhnaE>s}m`gM%Y% zUQXggg?J)l8V zNDFf%Uyp)gWr=#9u{aGnQadm-tec_Z#%rkl>@i~SWCg70@&!f@#TLyhJ?|2n)5}y& zTE>W;mi(8&dCQP)tOde~(d|=~C&`7`lbIxOyg@OkF`_sdaJJY|9mY$TH$^?j=)NJe zX*jmhH3@c(lZfQOcvm@7dVcww4vXwm8!xCo#pitQVffC0D-7>{2e6o?=nyZ2q`T0S zz-_cov6ZTfvi^k(YEOqsghzp*@|8op9@yOWsfMmcL3T)?>2b#b-@3$Omn}kB9Y!6> zTd1Zt2v>YwMq0jFJ6+SDCIcSnYk9377LAZvQv%cXmld;919tyz?3^#qE!DbwmMZG% z@<2!=A+HK}CpETBV(9hVptwi7F3H|5g!Fjz6a#1PfP1?iTwo7DYk&OuNgH~d5lKM= zS@k`}4rq7I4}i1TO)yLod@SBNj2+E*>h1?T`ixqm3k)8Ddc{tS5VUdE<()}m$H1&i z+wIeENh6TSHS#8!vKZHIu}6ycUs-J}-S#%fHpE#vA9bzJ-aIVjrIq^vS*bD?aQNmp zOi^)0B@n#LC@BqmJI8_oIv*APL2cmGc{I14%eq5@JMf5&+-A?d))gW5_a^oepQn$x z?KlHkmP0fvw+PB3BB#9zP`Kx01g>TcXBKm48Ru3jBSHGyoY_-_kJ;&VD9%yFR#UyWHRE<$ji;Y()% zF|Q`D1Z?kfmrsP9`V}^b&p~9D@{w>&d|1(to|Q~810f=j{N-o=^-%{p3Z3hkx&(3C zz-$;r<|^O9FL7FcZ;dX?;C+6Lgk9oI2Qn=EzMt`DKl_ho9Na+8iyT(EPdsAmJiOl1 zk&``i|7cI#?8kc+@Ih|1`?C7pU+M$x1ASmz zP};=9^;w5L{xH7Rec_k-IBWpmtuC5`h7_?K zEabTcBd}3>lhTZSsgH;}coUb&eo{Gk&knp-O17&1#LxTwyZD1J{ig~ItQm;k<)#rx zNWW*`XVRtmmqFo6p$|)ggpZ`HEfmTVn}3KjvGDxlS^qg?KFNv4fc>}m9H9W2uiJQM z`%_989)r-H!P@^ZSbQLb`_8@NZ7CNEfFaB_x0tc~<4?ph|Bq)8z#~2uL-9*P`p1{Q zOZfjUG4Wpdzbx^8noqoJ@{1PgH(MJxFamZ0+LcR{lwwLEbv_;Fh(an=UG-gm4XbN6 zsF8bEj*&|3S2)-&54PIO@Cp*8Hdc#pZy(7B#iL zBpvKGIFF{3e)^4n?jJFb>^4Rp5_z7$!yew*A;C!^!6Zj7(KO%Ght`=@0ZqiSf!Ct= za&s^QZkTMLVwzvNEiUlFZBc5Z_H-8>`#VZ*FtziKVifXCY&Z%Ke#e#6R-#}1`=Pis zI*b<_kDW`V`hmnR#SV;4w)!(EO25=c#98D(o}8K>ZjI4}hmH$ZUWXBPOx$8?5b!Ar z#KGB)bes~1{juHU7b&eN$f+~CnBqkI8yIaEg~o#3YrlUT1^!knW8KzRBK$$ra2@>! z8G1`9-otbc=VLbxY&HD%Pxu~0rF(eFnvPf`Cj6k|>S->XpB|_G7@i&yZz6AdhIHTu zk!j*5ohIVdI{u{6B5%vIi0YZ6~Y`wQEq9FAQpPbx!1QM1F8|nV* zqFn;B1%4aqzoS5Oi6{BrMu7=LVm=hzc*6u_F76$1uWFlDrJQR*C zo7$Fm_CKfv7*8J#5#GQW)HaB~B0xW53oIA?iN#(}va2@{D#Pl_iqj*_t1GCCF*_9n%vegRTpJ7uoMVAH3D@ zfBAF^IS60cr)d!X2IfcT5Q$3pqXj-4(VMW|x5-@-wq@6|6K|buWcOf9UZ}!j#IFS) zI;@>bPd_Ee+WmbyV8v0@DtA~ew;@As09J$Nm(K}%h*uVmh6M~rrq4u?bWd_9{1_(m eaZ~BdH!@-Iy>!yjJ9D?ezti$()` + +Hence, we have: + +- :math:`u, t = polar(x - sin(φ), y + cos(φ) - 1)` +- :math:`v = φ - t` + + +2. **Left-Straight-Right** + +.. image:: LSR.png + +With followng notations: + +- :math:`∠MBD = t1` +- :math:`∠BDF = θ` +- :math:`BC = u1` + +We can deduce the following facts using geometry. + +- D is mid-point of BC and FG. +- :math:`t - v = φ` +- :math:`C(x + sin(φ), y - cos(φ))` +- :math:`A(0, 1)` +- :math:`u1, t1 = polar(vector)` +- :math:`\frac{u1^2}{4} = 1 + \frac{u^2}{4}` +- :math:`BF = 1` [Radius Of Curvature] +- :math:`FD = \frac{u}{2}` +- :math:`θ = arctan(\frac{BF}{FD})` +- :math:`t1 + θ = t` + +Hence, we have: + +- :math:`u1, t1 = polar(x + sin(φ), y - cos(φ) - 1)` +- :math:`u = \sqrt{u1^2 - 4}` +- :math:`θ = arctan(\frac{2}{u})` +- :math:`t = t1 + θ` +- :math:`v = t - φ` + +3. **LeftxRightxLeft** + +.. image:: L_R_L.png + +With followng notations: + +- :math:`∠CBD = ∠CDB = A` [BCD is an isoceles triangle] +- :math:`∠DBK = θ` +- :math:`BD = u1` + +We can deduce the following facts using geometry. + +- :math:`t + u + v = φ` +- :math:`D(x - sin(φ), y + cos(φ))` +- :math:`B(0, 1)` +- :math:`u1, θ = polar(vector)` +- :math:`A = arccos(\frac{BD/2}{CD})` +- :math:`u = (π - 2*A)` +- :math:`∠ABK = \frac{π}{2}` +- :math:`∠KBD = θ` +- :math:`t = ∠ABK + ∠KBD + ∠DBC` + +Hence, we have: + +- :math:`u1, θ = polar(x - sin(φ), y + cos(φ) - 1)` +- :math:`A = arccos(\frac{u1/2}{2})` +- :math:`t = \frac{π}{2} + θ + A` +- :math:`u = (π - 2*A)` +- :math:`v = (φ - t - u)` + +4. **LeftxRight-Left** + +.. image:: L_RL.png + +With followng notations: + +- :math:`∠CBD = ∠CDB = A` [BCD is an isoceles triangle] +- :math:`∠DBK = θ` +- :math:`BD = u1` + +We can deduce the following facts using geometry. + +- :math:`t + u - v = φ` +- :math:`D(x - sin(φ), y + cos(φ))` +- :math:`B(0, 1)` +- :math:`u1, θ = polar(vector)` +- :math:`A = arccos(\frac{BD/2}{CD})` +- :math:`u = (π - 2*A)` +- :math:`∠ABK = \frac{π}{2}` +- :math:`∠KBD = θ` +- :math:`t = ∠ABK + ∠KBD + ∠DBC` + +Hence, we have: + +- :math:`u1, θ = polar(x - sin(φ), y + cos(φ) - 1)` +- :math:`A = arccos(\frac{u1/2}{2})` +- :math:`t = \frac{π}{2} + θ + A` +- :math:`u = (π - 2*A)` +- :math:`v = (-φ + t + u)` + +5. **Left-RightxLeft** + +.. image:: LR_L.png + +With followng notations: + +- :math:`∠CBD = ∠CDB = A` [BCD is an isoceles triangle] +- :math:`∠DBK = θ` +- :math:`BD = u1` + +We can deduce the following facts using geometry. + +- :math:`t - u - v = φ` +- :math:`D(x - sin(φ), y + cos(φ))` +- :math:`B(0, 1)` +- :math:`u1, θ = polar(vector)` +- :math:`BC = CD = 2` [2 * radius of curvature] +- :math:`cos(2π - u) = \frac{BC^2 + CD^2 - BD^2}{2 * BC * CD}` [Cosine Rule] +- :math:`\frac{sin(A)}{BC} = \frac{sin(u)}{u1}` [Sine Rule] +- :math:`∠ABK = \frac{π}{2}` +- :math:`∠KBD = θ` +- :math:`t = ∠ABK + ∠KBD - ∠DBC` + +Hence, we have: + +- :math:`u1, θ = polar(x - sin(φ), y + cos(φ) - 1)` +- :math:`u = arccos(1 - \frac{u1^2}{8})` +- :math:`A = arcsin(\frac{sin(u)}{u1}*2)` +- :math:`t = \frac{π}{2} + θ - A` +- :math:`v = (t - u - φ)` + +6. **Left-RightxLeft-Right** + +.. image:: LR_LR.png + +With followng notations: + +- :math:`∠CLG = ∠BCL = ∠CBG = ∠LGB = A = u` [BGCL is an isoceles trapezium] +- :math:`∠KBG = θ` +- :math:`BG = u1` + +We can deduce the following facts using geometry. + +- :math:`t - 2u + v = φ` +- :math:`G(x + sin(φ), y - cos(φ))` +- :math:`B(0, 1)` +- :math:`u1, θ = polar(vector)` +- :math:`BC = CL = LG = 2` [2 * radius of curvature] +- :math:`CG^2 = CL^2 + LG^2 - 2*CL*LG*cos(A)` [Cosine rule in LGC] +- :math:`CG^2 = CL^2 + LG^2 - 2*CL*LG*cos(A)` [Cosine rule in LGC] +- From the previous two equations: :math:`A = arccos(\frac{u1 + 2}{4})` +- :math:`∠ABK = \frac{π}{2}` +- :math:`t = ∠ABK + ∠KBG + ∠GBC` + +Hence, we have: + +- :math:`u1, θ = polar(x + sin(φ), y - cos(φ) - 1)` +- :math:`u = arccos(\frac{u1 + 2}{4})` +- :math:`t = \frac{π}{2} + θ + u` +- :math:`v = (φ - t + 2u)` + +7. **LeftxRight-LeftxRight** + +.. image:: L_RL_R.png + +With followng notations: + +- :math:`∠GBC = A` [BGCL is an isoceles trapezium] +- :math:`∠KBG = θ` +- :math:`BG = u1` + +We can deduce the following facts using geometry. + +- :math:`t - v = φ` +- :math:`G(x + sin(φ), y - cos(φ))` +- :math:`B(0, 1)` +- :math:`u1, θ = polar(vector)` +- :math:`BC = CL = LG = 2` [2 * radius of curvature] +- :math:`CD = 1` [radius of curvature] +- D is midpoint of BG +- :math:`BD = \frac{u1}{2}` +- :math:`cos(u) = \frac{BC^2 + CD^2 - BD^2}{2*BC*CD}` [Cosine rule in BCD] +- :math:`sin(A) = CD*\frac{sin(u)}{BD}` [Sine rule in BCD] +- :math:`∠ABK = \frac{π}{2}` +- :math:`t = ∠ABK + ∠KBG + ∠GBC` + +Hence, we have: + +- :math:`u1, θ = polar(x + sin(φ), y - cos(φ) - 1)` +- :math:`u = arccos(\frac{20 - u1^2}{16})` +- :math:`A = arcsin(2*\frac{sin(u)}{u1})` +- :math:`t = \frac{π}{2} + θ + A` +- :math:`v = (t - φ)` + + +8. **LeftxRight90-Straight-Left** + +.. image:: L_R90SL.png + +With followng notations: + +- :math:`∠FBM = A` [BGCL is an isoceles trapezium] +- :math:`∠KBF = θ` +- :math:`BF = u1` + +We can deduce the following facts using geometry. + +- :math:`t + \frac{π}{2} - v = φ` +- :math:`F(x - sin(φ), y + cos(φ))` +- :math:`B(0, 1)` +- :math:`u1, θ = polar(vector)` +- :math:`BM = CB = 2` [2 * radius of curvature] +- :math:`MD = CD = 1` [CGDM is a rectangle] +- :math:`MC = GD = u` [CGDM is a rectangle] +- :math:`MF = MD + DF = 2` +- :math:`BM = \sqrt{BF^2 - MF^2}` [Pythagoras theorem on BFM] +- :math:`tan(A) = \frac{MF}{BM}` +- :math:`u = MC = BM - CB` +- :math:`t = ∠ABK + ∠KBF + ∠FBC` + +Hence, we have: + +- :math:`u1, θ = polar(x - sin(φ), y + cos(φ) - 1)` +- :math:`u = arccos(\sqrt{u1^2 - 4} - 2)` +- :math:`A = arctan(\frac{2}{\sqrt{u1^2 - 4}})` +- :math:`t = \frac{π}{2} + θ + A` +- :math:`v = (t - φ + \frac{π}{2})` + + +9. **Left-Straight-Right90xLeft** + +.. image:: LSR90_L.png + +With followng notations: + +- :math:`∠MBH = A` [BGCL is an isoceles trapezium] +- :math:`∠KBH = θ` +- :math:`BH = u1` + +We can deduce the following facts using geometry. + +- :math:`t - \frac{π}{2} - v = φ` +- :math:`H(x - sin(φ), y + cos(φ))` +- :math:`B(0, 1)` +- :math:`u1, θ = polar(vector)` +- :math:`GH = 2` [2 * radius of curvature] +- :math:`CM = DG = 1` [CGDM is a rectangle] +- :math:`CD = MG = u` [CGDM is a rectangle] +- :math:`BM = BC + CM = 2` +- :math:`MH = \sqrt{BH^2 - BM^2}` [Pythagoras theorem on BHM] +- :math:`tan(A) = \frac{HM}{BM}` +- :math:`u = MC = BM - CB` +- :math:`t = ∠ABK + ∠KBH - ∠HBC` + +Hence, we have: + +- :math:`u1, θ = polar(x - sin(φ), y + cos(φ) - 1)` +- :math:`u = arccos(\sqrt{u1^2 - 4} - 2)` +- :math:`A = arctan(\frac{2}{\sqrt{u1^2 - 4}})` +- :math:`t = \frac{π}{2} + θ - A` +- :math:`v = (t - φ - \frac{π}{2})` + + +10. **LeftxRight90-Straight-Right** + +.. image:: L_R90SR.png + +With followng notations: + +- :math:`∠KBG = θ` +- :math:`BG = u1` + +We can deduce the following facts using geometry. + +- :math:`t - \frac{π}{2} - v = φ` +- :math:`G(x + sin(φ), y - cos(φ))` +- :math:`B(0, 1)` +- :math:`u1, θ = polar(vector)` +- :math:`BD = 2` [2 * radius of curvature] +- :math:`DG = EF = u` [DGFE is a rectangle] +- :math:`DG = BG - BD = 2` +- :math:`∠ABK = \frac{π}{2}` +- :math:`t = ∠ABK + ∠KBG` + +Hence, we have: + +- :math:`u1, θ = polar(x + sin(φ), y - cos(φ) - 1)` +- :math:`u = u1 - 2` +- :math:`t = \frac{π}{2} + θ` +- :math:`v = (t - φ - \frac{π}{2})` + + +11. **Left-Straight-Left90xRight** + +.. image:: LSL90xR.png + +With followng notations: + +- :math:`∠KBH = θ` +- :math:`BH = u1` + +We can deduce the following facts using geometry. + +- :math:`t + \frac{π}{2} + v = φ` +- :math:`H(x + sin(φ), y - cos(φ))` +- :math:`B(0, 1)` +- :math:`u1, θ = polar(vector)` +- :math:`GH = 2` [2 * radius of curvature] +- :math:`DC = BG = u` [DGBC is a rectangle] +- :math:`BG = BH - GH` +- :math:`∠ABC= ∠KBH` + +Hence, we have: + +- :math:`u1, θ = polar(x + sin(φ), y - cos(φ) - 1)` +- :math:`u = u1 - 2` +- :math:`t = θ` +- :math:`v = (φ - t - \frac{π}{2})` + + +12. **LeftxRight90-Straight-Left90xRight** + +.. image:: L_R90SL90_R.png + +With followng notations: + +- :math:`∠KBH = θ` +- :math:`∠HBM = A` +- :math:`BH = u1` + +We can deduce the following facts using geometry. + +- :math:`t - v = φ` +- :math:`H(x + sin(φ), y - cos(φ))` +- :math:`B(0, 1)` +- :math:`u1, θ = polar(vector)` +- :math:`GF = ED = 1` [radius of curvature] +- :math:`BD = GH = 2` [2 * radius of curvature] +- :math:`FN = GH = 2` [ENMD is a rectangle] +- :math:`NH = GF = 1` [FNHG is a rectangle] +- :math:`MN = ED = 1` [ENMD is a rectangle] +- :math:`DO = EF = u` [DOFE is a rectangle] +- :math:`MH = MN + NH = 2` +- :math:`BM = \sqrt{BH^2 - MH^2}` [Pythagoras theorem on BHM] +- :math:`DO = BM - BD - OM` +- :math:`tan(A) = \frac{MH}{BM}` +- :math:`∠ABC = ∠ABK + ∠KBH + ∠HBM` + +Hence, we have: + +- :math:`u1, θ = polar(x + sin(φ), y - cos(φ) - 1)` +- :math:`u = /sqrt{u1^2 - 4} - 4` +- :math:`A = arctan(\frac{2}{u1^2 - 4})` +- :math:`t = \frac{π}{2} + θ + A` +- :math:`v = (t - φ)` + + Ref: - `15.3.2 Reeds-Shepp diff --git a/tests/test_rrt_star_reeds_shepp.py b/tests/test_rrt_star_reeds_shepp.py index 20d4916f96..11157aa57a 100644 --- a/tests/test_rrt_star_reeds_shepp.py +++ b/tests/test_rrt_star_reeds_shepp.py @@ -32,16 +32,14 @@ def test2(): # + 0.00000000000001 for acceptable errors arising from the planning process assert m.math.dist(path[i][0:2], path[i+1][0:2]) < step_size + 0.00000000000001 -def test3(): +def test_too_big_step_size(): step_size = 20 rrt_star_reeds_shepp = m.RRTStarReedsShepp(start, goal, obstacleList, [-2.0, 15.0], max_iter=100, step_size=step_size) rrt_star_reeds_shepp.set_random_seed(seed=8) path = rrt_star_reeds_shepp.planning(animation=False) - for i in range(len(path)-1): - # + 0.00000000000001 for acceptable errors arising from the planning process - assert m.math.dist(path[i][0:2], path[i+1][0:2]) < step_size + 0.00000000000001 + assert path is None if __name__ == '__main__': From 9efd4c07a78b52a03c37c221055db1ddf4401667 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 9 Jan 2024 07:29:57 +0900 Subject: [PATCH 698/940] Bump numpy from 1.26.2 to 1.26.3 in /requirements (#964) Bumps [numpy](https://github.com/numpy/numpy) from 1.26.2 to 1.26.3. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.26.2...v1.26.3) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 8b3c4c1739..417ab84425 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.26.2 +numpy == 1.26.3 scipy == 1.11.4 matplotlib == 3.8.2 cvxpy == 1.4.1 From 1de7ac951041787d2a02053931ef9a618d1bf037 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 9 Jan 2024 21:23:11 +0900 Subject: [PATCH 699/940] Bump ruff from 0.1.9 to 0.1.11 in /requirements (#965) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.9 to 0.1.11. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.9...v0.1.11) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 417ab84425..172a88423e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.4 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test -ruff == 0.1.9 # For unit test +ruff == 0.1.11 # For unit test From f8515d109e38d4f9cfbc665fe57f4a13b715e86d Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 18 Jan 2024 23:14:51 +0900 Subject: [PATCH 700/940] Update doc_requirements.txt versions (#968) * Update doc_requirements.txt * Update doc_requirements.txt * Update doc_requirements.txt --- docs/doc_requirements.txt | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/doc_requirements.txt b/docs/doc_requirements.txt index a8cd2bde40..b29f4ba289 100644 --- a/docs/doc_requirements.txt +++ b/docs/doc_requirements.txt @@ -1,6 +1,6 @@ -sphinx == 4.3.2 # For sphinx documentation -sphinx_rtd_theme == 1.0.0 -IPython == 8.10.0 # For sphinx documentation +sphinx == 7.2.6 # For sphinx documentation +sphinx_rtd_theme == 2.0.0 +IPython == 8.20.0 # For sphinx documentation sphinxcontrib-napoleon == 0.7 # For auto doc sphinx-copybutton -sphinx-rtd-dark-mode \ No newline at end of file +sphinx-rtd-dark-mode From 4fcab6aa578c60d4bc594e47671a140e450c7cda Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 18 Jan 2024 23:15:25 +0900 Subject: [PATCH 701/940] Bump ruff from 0.1.11 to 0.1.13 in /requirements (#967) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.11 to 0.1.13. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.11...v0.1.13) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 172a88423e..127b89682d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.4 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test -ruff == 0.1.11 # For unit test +ruff == 0.1.13 # For unit test From cfe1e3035746454adfc02f66c6190fe58bb7101e Mon Sep 17 00:00:00 2001 From: Ryohei Sasaki Date: Mon, 22 Jan 2024 22:02:22 +0900 Subject: [PATCH 702/940] Addition of velocity scale factor estimation to EKF (#937) * Addition of velocity scale factor estimation to EKF * Format * Add a scale factor motion model in the Jacobian function description * Fix Jacobian function description * New script: 'ekf_with_velocity_correction.py' * Add doc * Fix doc * Correct the parts where the first letter of the sentence is lowercase * Fix doc title * Fix script title * Do grouping * Fix wrong motion function in ekf doc * Update docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst --------- Co-authored-by: Atsushi Sakai --- .../ekf_with_velocity_correction.py | 198 ++++++++++++++++++ .../ekf_with_velocity_correction_1_0.png | Bin 0 -> 40148 bytes ...tended_kalman_filter_localization_main.rst | 105 ++++++++++ 3 files changed, 303 insertions(+) create mode 100644 Localization/extended_kalman_filter/ekf_with_velocity_correction.py create mode 100644 docs/modules/localization/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png diff --git a/Localization/extended_kalman_filter/ekf_with_velocity_correction.py b/Localization/extended_kalman_filter/ekf_with_velocity_correction.py new file mode 100644 index 0000000000..5dd97830fc --- /dev/null +++ b/Localization/extended_kalman_filter/ekf_with_velocity_correction.py @@ -0,0 +1,198 @@ +""" + +Extended kalman filter (EKF) localization with velocity correction sample + +author: Atsushi Sakai (@Atsushi_twi) +modified by: Ryohei Sasaki (@rsasaki0109) + +""" +import sys +import pathlib + +sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) + +import math +import matplotlib.pyplot as plt +import numpy as np + +from utils.plot import plot_covariance_ellipse + +# Covariance for EKF simulation +Q = np.diag([ + 0.1, # variance of location on x-axis + 0.1, # variance of location on y-axis + np.deg2rad(1.0), # variance of yaw angle + 0.4, # variance of velocity + 0.1 # variance of scale factor +]) ** 2 # predict state covariance +R = np.diag([0.1, 0.1]) ** 2 # Observation x,y position covariance + +# Simulation parameter +INPUT_NOISE = np.diag([0.1, np.deg2rad(5.0)]) ** 2 +GPS_NOISE = np.diag([0.05, 0.05]) ** 2 + +DT = 0.1 # time tick [s] +SIM_TIME = 50.0 # simulation time [s] + +show_animation = True + + +def calc_input(): + v = 1.0 # [m/s] + yawrate = 0.1 # [rad/s] + u = np.array([[v], [yawrate]]) + return u + + +def observation(xTrue, xd, u): + xTrue = motion_model(xTrue, u) + + # add noise to gps x-y + z = observation_model(xTrue) + GPS_NOISE @ np.random.randn(2, 1) + + # add noise to input + ud = u + INPUT_NOISE @ np.random.randn(2, 1) + + xd = motion_model(xd, ud) + + return xTrue, z, xd, ud + + +def motion_model(x, u): + F = np.array([[1.0, 0, 0, 0, 0], + [0, 1.0, 0, 0, 0], + [0, 0, 1.0, 0, 0], + [0, 0, 0, 0, 0], + [0, 0, 0, 0, 1.0]]) + + B = np.array([[DT * math.cos(x[2, 0]) * x[4, 0], 0], + [DT * math.sin(x[2, 0]) * x[4, 0], 0], + [0.0, DT], + [1.0, 0.0], + [0.0, 0.0]]) + + x = F @ x + B @ u + + return x + + +def observation_model(x): + H = np.array([ + [1, 0, 0, 0, 0], + [0, 1, 0, 0, 0] + ]) + z = H @ x + + return z + + +def jacob_f(x, u): + """ + Jacobian of Motion Model + + motion model + x_{t+1} = x_t+v*s*dt*cos(yaw) + y_{t+1} = y_t+v*s*dt*sin(yaw) + yaw_{t+1} = yaw_t+omega*dt + v_{t+1} = v{t} + s_{t+1} = s{t} + so + dx/dyaw = -v*s*dt*sin(yaw) + dx/dv = dt*s*cos(yaw) + dx/ds = dt*v*cos(yaw) + dy/dyaw = v*s*dt*cos(yaw) + dy/dv = dt*s*sin(yaw) + dy/ds = dt*v*sin(yaw) + """ + yaw = x[2, 0] + v = u[0, 0] + s = x[4, 0] + jF = np.array([ + [1.0, 0.0, -DT * v * s * math.sin(yaw), DT * s * math.cos(yaw), DT * v * math.cos(yaw)], + [0.0, 1.0, DT * v * s * math.cos(yaw), DT * s * math.sin(yaw), DT * v * math.sin(yaw)], + [0.0, 0.0, 1.0, 0.0, 0.0], + [0.0, 0.0, 0.0, 1.0, 0.0], + [0.0, 0.0, 0.0, 0.0, 1.0]]) + return jF + + +def jacob_h(): + jH = np.array([[1, 0, 0, 0, 0], + [0, 1, 0, 0, 0]]) + return jH + + +def ekf_estimation(xEst, PEst, z, u): + # Predict + xPred = motion_model(xEst, u) + jF = jacob_f(xEst, u) + PPred = jF @ PEst @ jF.T + Q + + # Update + jH = jacob_h() + zPred = observation_model(xPred) + y = z - zPred + S = jH @ PPred @ jH.T + R + K = PPred @ jH.T @ np.linalg.inv(S) + xEst = xPred + K @ y + PEst = (np.eye(len(xEst)) - K @ jH) @ PPred + return xEst, PEst + + +def main(): + print(__file__ + " start!!") + + time = 0.0 + + # State Vector [x y yaw v s]' + xEst = np.zeros((5, 1)) + xEst[4, 0] = 1.0 # Initial scale factor + xTrue = np.zeros((5, 1)) + true_scale_factor = 0.9 # True scale factor + xTrue[4, 0] = true_scale_factor + PEst = np.eye(5) + + xDR = np.zeros((5, 1)) # Dead reckoning + + # history + hxEst = xEst + hxTrue = xTrue + hxDR = xTrue + hz = np.zeros((2, 1)) + + while SIM_TIME >= time: + time += DT + u = calc_input() + + xTrue, z, xDR, ud = observation(xTrue, xDR, u) + + xEst, PEst = ekf_estimation(xEst, PEst, z, ud) + + # store data history + hxEst = np.hstack((hxEst, xEst)) + hxDR = np.hstack((hxDR, xDR)) + hxTrue = np.hstack((hxTrue, xTrue)) + hz = np.hstack((hz, z)) + estimated_scale_factor = hxEst[4, -1] + if show_animation: + plt.cla() + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect('key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + plt.plot(hz[0, :], hz[1, :], ".g") + plt.plot(hxTrue[0, :].flatten(), + hxTrue[1, :].flatten(), "-b") + plt.plot(hxDR[0, :].flatten(), + hxDR[1, :].flatten(), "-k") + plt.plot(hxEst[0, :].flatten(), + hxEst[1, :].flatten(), "-r") + plt.text(0.45, 0.85, f"True Velocity Scale Factor: {true_scale_factor:.2f}", ha='left', va='top', transform=plt.gca().transAxes) + plt.text(0.45, 0.95, f"Estimated Velocity Scale Factor: {estimated_scale_factor:.2f}", ha='left', va='top', transform=plt.gca().transAxes) + plot_covariance_ellipse(xEst[0, 0], xEst[1, 0], PEst) + plt.axis("equal") + plt.grid(True) + plt.pause(0.001) + + +if __name__ == '__main__': + main() diff --git a/docs/modules/localization/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png b/docs/modules/localization/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png new file mode 100644 index 0000000000000000000000000000000000000000..595b651bd2354f67fd57de47e35b9848433d7c93 GIT binary patch literal 40148 zcmeFZWmr{R^gW8GbSWqeBGL%bf`lR=-5@O;(%qmaDk%ceC0!!jA>BwzcXu2byz{)j z|L;D}{eC~(5BGyF?{heN@3q&OYtAvp7>h58@{+h%WLPLDD7aFu#FSA`Q2kI)Zp>kz z!6!TeQ%mrJ-%0$nlZvgWldFM)35uM7lbw~Vla+_~$FF`l2-TIR&pZesBz2%)=vyDh)ESe7lq8J8zN9BEf@IN#k zI&|-%{P*EsQcRSO$d9&yZ}}mAL*OET`uxAIKcl^o^52&e!%-BGziH}wg~IsXjm#dQ z5Fx+(i|hZt&Hu;ehQd1W-DQszujBQlyP%NJz`9d;Unp`}sopCGZjKc$E-w1(*(N(1 z+(j|{eRjCIe|T8p%!^#*aLj>$fz$Kz2?26mnj3HKyLot^PT(#rFPkh*E$Mc4cIN9h zB*`ZV7(5}dN~ElLU}8hAyi=vnC3tf011Dds?CIH=W<&dS_$@!pHx|c;gM)7OZ1^m)FSW1ArcSEQexc)}hY^1AU$C3M(`gyO5KIvK ztPt4V-09!(_tjeh*HxqLO_nB&Cy$*bge<)6HvB!0*PT7kM##l#4z>r=!}Y4ad-rzn zMx-cVgwrDT%HNOAZr0ZL|4bQr;Z?rPMTCX&NtMyUp@roqLDE>=-sh7>uHU%*hb71%5IuF}?LH^oHxoa_%KRih zhAMcw)o41~qb)v{cxwN8?Bl{dnvcBs=hPjiK`3A z;^VZP6?8IXq~4b69m;THZ40?QMy7-~ch03x$|5OhT))VSe}9v{_VZYkz3y(8GrHLV zB}LWFnpmy>yG=C71xiXOyI}*DSK?VR;^=FU%aX1aRd~^=TzXQbSab|3jC7cVkz!aG zGwEN?(DYWw-R|J~p<@bu_lRp(ey9DM^^I(Np?MugWFv2y~Y!+p2~c3v8#B~gy$Dsyp=xw4@U??|-=hcYIz zx8s_8c0eq}u3E1=SyWar4LUphutr260^D=&)p@!3wl@aXFo#5s0q8~&W>Y5L$mK2 zkJip9hkEZ2RZyVj`mZ zSv9bxXwtV`?I-=`d|RAA?$!Y7ZGoGceqsqvH|F~9RD7dg+3G1$?xZ-Wllb7v&4(@C z++%Kz%3ZhkzVo@HB2^K7ln8pFKW}Ao1Eq;z*Dw1`iHS0+_Nr4ylt^|RVQa$D*6Ybw z3T#u!&n#pzIs>mCGMjl7i2n0X5-KL*3I3Sv{yUtkh%eio3vJlsh>@zH%)k9H$FA_J zw(#d!4o9y9*N(0f1)hNw-vdMt>_fcSdHeBa&T}EF{@(uwFVJ$ z8Ma^;8X1)&9Ct;roGk>gKXut6F)fKLHt8PBkRi@gNKRTVE$Lop4RT-4h~60&@xAua z^G1xYW(XNH-BK^qlY9O8_4h${qAy>*1XJ*TOZGYc63=HlSnut5ebVr6elvbwDC*m{ zrVp5eudAJyh}m>foYn_xPZxrMsYR&j^x`vi;NHQcTmgv9F+y^3nLPD^(~Z2sY@IV< zU&e)0WNzqi+`&0t*^Za&WYKe)(EUO!Ka$bfz!9ksaszMg;T$e2s?9(Cr|ee*W0*q-cw^p|7R^rlU^e-z_@!=$kP^@X9ia4zi-WO4iBmAM3g)RGS(0|C&ES zTiJ~dBQ4=ctb9l>8We+35Y0QgLlZhRVZKsEhMR5w`%BzEdPOd#zy+NQ?Lj6Flrh>q zJ37?kXX

    VivrrRlmPaNRCsNQcs9hX)fpUe5e}G*;-oqP*LGpo<&YX)H0+X(wmj+ zBi)~btRxit4j*vId5tg1io3eIgBII|X5zp5J!O9-FW>g&iQsS%twiu#n8@|qYO-(U z>mtM2i=7&$-I>HX&y$6@xvx9?Dw(ndJ5yC&|E^Akvz7dXJdgJVW!ROn6=?$SsY8_m z8Is&k{eL&^Hv9{Xjwa?Z?MZq02@jrn%hmN{%d6&Ca``5#s`_+|t44-Qw7Q>GnWb9X zSe4M;&Q3CW{prJIZsNyUkvsf+wliL9UahUIOwZvzCdUQiAJfwxm3bg6qaq`XH}n67 zT&k}O*bi7Pu7_Ag+eed~^}jM9`D8g#mm8;39y{?i`v+0_nUr`|6Cz60G3#4yt(lVA zNvCwzzBhX7t(_~2kS6SpH@oVxYc~EV`<5;2VX4)%`5_*pnkxD+-~D1O zEll{zb-NoA&^6PJtS6pvz7la69k5|xYNW|FH?NEX%|$=6h= zs;Xkr*Vji(ye-Uua?O$vIZ)@B{8tlPGaQp+6sdv9{*gA&l2IVlu71-y%vEtY$y-)PJF9?fK~rV@x%iA)D7L*K znvjqvq9)ztJD85u?WexoSz@3I6D z(v>n%CE@Eg%^d^VFTN$%+z|W?T0_LYP|8n_7%PqTV+S~>}a)fLW(gdU->EM@W$RRNK6Bk!3L4PgThB@!%va&^IlCgRPrec|W#DSo##ueIPJUY! z5So)v;1F4&7W$qv<_1q*^`Hv%^NS%5flJQ->YmkgTv?%tkM^r`SRNi#8mo4=X76RF zOjg!ndjz>7XcX{LhnJNtx{P;c>W+42lQ9YD_l8vz?%ciG^vj@`Q9YjonLSY0Yxhu7 zQ&YXpmZNXox7vBNYQ+(paF`~3?cL$T+H4H>T$Mk7qvc!RG6+HLdApK>%yOsm^3VaFV;4}G#AfTQ4tCAsFX53dP zEk|<2MMY7meNJg0vC^}$;?(IWczFrJhRl?W<;>SCL4yGuZ%=+2w_3@`N?O>PZ_d}Q z2u(?O@H|gVwc_p2)b#XttveSJ6B7O7_7syDZbU5)UYqU)QOn6=AvLkV76ASD&y6sAQgLkdw9NR&@} z=E~N44O5y|WYo@_5$UlKYo;2_raM@B4Pm4?6c`$$9{-RpN4HJaQe}xA;q&K0TI5Bc zdFT&F}-#R@F7;S)VX6n6I4XI&z9{5KX9b<~cTQ@ik(Q%SNZ|Fw1T4YMt> zjntcYjucyWbDxp$SVrdR)m1BRG)%-dHa0p*U(aZj1`9{PtmW!?Zu4v&-l3I9&zY~e z&LIbvhZj#G0BKM3!of@;a3#1nBK-D8Eb@k#T&sNe4$qsv3Z^PTXYV zW)epW^$RH|C{$HdBc1i#+$vFrf9lrcuae@RIj;|9aIe;%%y?Qh`rQ~^b&Wm)1P8Ta zNa$?sZ_%RAvI9fOc>av%u29C%dSqH!+Tgm=2H*@i$3%zat{k7M^PIP1KXY1I#1P|V z$xP3kH-?#-ou~u6d{-mL8YS)b7sRj6H`(j|U0ial9S7T&J?+K;HCM9 z9hg2`ReBOg?#qa;QR^gHXHlhTF5G#Oh4?!i%5yrM#qEo(W8m9J6S?@E+hYCCzDhuUBtzzFWpL8!$#zFJYJW2CbC5 zv9xQba>YADLFAgK_RaPo!)x-JJ)iF5c~JDuWfKW}laj6z)g|0Yz@O!hG$r83zcj+s zr#>fhdG|9e)PiP+WZdczN^d-$*=W9IdS>R``}YI<{a?mu4fK$3n-j1%Tyg^5YW)5C z9U!Y2*C(H9YM%LCA&9f&6AfWhTYroEU1zX{eH0yMaFCIH#+hWEE+%4t9*LncrdZC(_qd4^r{!?=i`TD7 z0GKwmw|{zf6W#C$2_!hW!rB8YD9EkwzIc=Ze_-gc%aZA8bEru0Nu{8maDKGzIJ*d$ zx(ynG9JRdru#WKZL$&UXcoa{+&aeG|2z?vH?bm6HS{hmm^vL)LJr;?~_$$)oq*}!l ziHPt*SKr>?M6M@~$kyts*nBCnC09Q@p%_OqA1boqyY;Ks%U+#_Urx2v?t!43fPho2 z)~edXc}0d)EdA(QrhKQs%IuL;_$HQk;j$LiH(B;C$tmo z{rzG5jw_1QP8L0;TmWvC+d{};5*D|%f|Z$@i{<3x>Q)i3kDUajg;p6e@=e0y;$Rm{ z-W1{6VLOBniGU&xJBLv@{WGF6h?sq_(tZ(Vh@8igC`}@y*kvqNy?`uBA$bKd-7@60 z+bJ&F6I(NN@s*WNzkU10sPy9&?9D7lHk#*N5xZ%qBq(e;m0wqrJa^uCpFw33ji8sy z?}zS3zRm-IY)wxOy4i<>R!jPYjTTzIoNVbg_z2n9*l2cFQexoXlsezvlDCOIi%Mr{ zdDLb%cYedC?vzEX`R#sd`7utdo!_^uVycR6#YB^9I?b5_BI3)Y9VyAMq)_o^%H1XR zN2c2)8`Hj#m@R-Vz=lcn0h(Zbx$@%^2Ef&Zvc#W2;Z|9%EX02vJ9V&UaLTh)85?d zzqe<1mymEM{SGm)q@^YE+tK_~i4d~&`e@OQSo_dTDi_Z9zI+FlCDQkkLQg>jNU3#f zEE;>2{ZFyFjPx{XtH$F7!=05h7;)(g=` zU`BKr*UbR(dFp$8Ddf(smP@2vZj}nNcarW3Yvy$5bmDDlz!{4qJ8q)k%t0?9CL!Ul z)N$u|o&`4vPE4=qF{IFg&(ol9R{NZ^N89Lel~j&~x)5G&Gc+jV%;PW)Vb` z(=OtoDAFC^A$%^IC=hl3u@;Km_5@E;bMyL8mO{Wf^uzW`9pT)C$%5|R0Ey%D^ZQ;4 zdY_3{Sw5J_fy-#$T8D*;4nWa69+U)FLIn3*)USSqMd@(UGW4E5aMMmzc ziLUwma`c2gK0Zzx!03}A5L4wxrI2#0*UK_<8X71)u~le&c#qnW>>Era0Obts z-voYXX|%u-twKlffQKgvlHS6~N?R!9GdpKz2>eP)xRBq5)JcMa zR_(lr)|e#Z31v1LQMFuMR8(Yf+#AE;52*lkuZ2)y53nv0?E_YqfAtCjHW^w9fL$Us zotTH>flnM)WOa0OvUO{CVSiOtRTWuJ@~-qJ_eV0RWUFN1K~$PRg+!ua071&o%>pga z8cr*@HeSN;;>8OJ0VhVeB(A|sIr97LdOc7@B>{&G_PjI`v>g69`39?*np%D>NAY^< zlz}E%v{JpjW1?K*lnOP8sk!k_;E{;ud*KaK>z_MscC=0xcSUR4omI74OG}3Sq%IcW zg>jrrR(bJn%2Z_WTWJFAcD534t0=ucs%@(TgbH*A>r+)+0PItI|6Ql2r|3 zH9)bO=y;_o^N{K?#J=1GiNpSM&j8viQDDSK`D~`VccDg?&W-cLBZPY%?QmfjL!HWn zG#)EGX2qL_hD(+mt>>|x+8-{Tj?Ykt_lmK@A+HBX6CE^nk2ta*5Uhis0Qv+d6nL^RFxkK8Lnw+h%$Q!Hz-GycrxjPXIN7hv!3vdavArNO#mQ$5Q z2L}hrKrZFNR53F$c6j)hn`h_h)|5NAxTt>*YYxtQS9MVhFDYG82&HYKmv6T8`vs7l zs<5}B^78UFpc6Wu|3tkLD_{%+RW9r$i_CXY($dP%WTql}Bu)~XuE|Ml#Ll!frJ&m% zj~Qq${$qZeoz(yiD?i|l+?Hzo-hpK! zlL9w1*X!efB_KcPoTDsdsX{?kc!~w(8;7i#T|@{uUoJzkm-5-!8508ogIcaC(+H5p zW$>=ts|7k$$|E@{lKlMqIZ&qaguTyS>q8ojMZOktg5=_P)u7%e`AszV`Ubeqmc5PM z_*;~QtAB^QNLbIMM&j12p^j{_9YCtHa zfNXIn1&)%q_1xxfcSSN8ZTAS+FNh&A2BZs)SXm_hae2BJW(8HO*Ejmah%=T^HJiZR z-d_2p8})b7PypsqxNq1x*E#v(f_r8-;@2lLhpdfMBzC`KsV(@*m1G_Hux7sw*nJk@ zSij`FdHoFCeoE+z!wbbfyUuBy9i49(Fa__O&N^}V9Xhk0qmP)mx#1vGLN&wiU4Ax4 zBXnL5*%0TTl^kE#p0hQ_!U4FhhnG%64?cO3@C-XL?BZyv{U;oO;tIrvnA4h=t%HVx*4O<=}Um0_29B1 zX4cp&R{QORXx8GL&DInV^1b66+EZq0Rdb4@9t7?im$8VJ$f~a^I-o2>;;B$=1l2$I z)$TcM&Uu%NvMXSSJpV1v%}9QYz_C#^lUGLufoXEX-XTq1y1ahuo>X&|`>&Jo5EMdr zN9mg5rli+KDMRawdbLkW%=*hiaq1$3zE>51t{c6(>!o~?@x!l>oXIRsdUKo%HX?(A zINn+pAL@?-qpCuMES>pXQ88oQBJ_pUqmE8%ZVk&9PT7A_8+rBvJFm18%{k`<&r!w7&e``nh3F#sWA39dH$VB%VRdvASaFB zq1hU>*JpyJ84z&;uK6Q#M7+Ct+~xSW_>ziN`IKUwh6I@GnDHn>LR^as2-sKzvZ zH``%K`^Do~pwu?~K&BTt=Ji%E9ZABZ5u4epaCb*0t(23Dslo2{u-iWz1zzhWy>`n= zNB;_=atDv=2CoZeN3RgNnEL`D#a!K-kB#FBW&;RZURZ+irVbsQ0RtUMQWv+TP)Khd>yFMz%;c=?v=dExsp;s2D?<^zr!Bcw zS#V?5Rv}f+ki`F|m06=}-(`Q+?c`(rmh48QmYF~kW$La`gO-(vTm$3R3&-%l4te6dq%+nrV~VwdUKl zcT}B8F|G0qiy6a@5O0}eESspoaUx?F$ z;QuM7ahe$X+F!1lrPswF{AH?Zb4X^db9SD4cjSXHL&;?cjTqina7;Wi;UQ zk{6**tZV2wXRe8XdKo{fT(hV#7wN5sA1LFhy_pMUEv4JdPD-q|4agX%X{cP=G|Z(k zl&*G`A4%YVajEn1$Bq-w)0^ZW2-QCn&YflS6J9hWfAIBQG>qWS5&;s7eDn)zOqHt6_;cdxw?mva+Z8w*af`aQ3-YSG4-rhe3YjB zcKSDqtHLhRsObgXwc8hq!}ubrLwruH*PpE($Tf-**?qr3H6)rf;G}^vdmZt-SJm30 z^?9^M?ew9*{78jXShP}I)BT+->Zi0$XqX?3&dm2jSVOaWg4O8U79=osld$JwN$K3{ z#Caq*0wXjOI5Wpdw9Rxsdr5)80_)fR0pm$ySckoXZ`p|KqNrQa^S7<-J2vb?ds8u3r+h`%{HIlYC));?Gnj zRmuMuUL!+yiG1)DtJsaQrOUfBlY3NkW93V0(egMo)tEwow_D>6{%Uu!ZeHu}F9?y-zeuX9Pw79T^ ztw}RdEnmhjHhgDq{-BWwYJQmx9bpRovWsVBwn*%p?KGjFPIzbG4oJLWH#nUyR4+{< z>2`+fnpQIp#4g#sJ=wEATe%e+YU-Gl_I$!*GJRBG$r<>$o^|1N0mY>^1xDPYj=>dq zr8GDACT6e}=kTLRt7>VgRa;?KBUcq2Ho#}p#$uP$K(`fHdwVc@o z3hKJbL@_h2{xOfFd)^ulsYEKz*{%G( zcv{pS2BMDwsz|u)v?h7>%XU&<+C<6i<*1Fs&+UojeE5!glSJn~ZT&>^a48z>YYR#q zizOjlVP}6&Ll#N@tzLKuWnuc-%t%_W*|(&k%AKnkH_2#Axk#5CA4c3G5_`d!d&c-< zCe(18u-jZW{~q>5Vb%_p@RmdVi#rRabjJAD4ORi3wL!8E9*YUUrg}(S%zegow(nUk zSJ?9_C^cq)qqpWULV|2u`{EXg{|3%CADmX7}c3o_Pepy>f%E#<-O`=oc5aS1=ZzFci=C`yd6q=XPbW$0owfIbj|HwV6rcZs@ z-Z*&kEOU}?aEfKC>6zT@JcNgP**J^W-Uj`I%g}a_a3@xo}-7p zk#+xAgx<>R*DzJ{EA-8?G{^Z{~G+h9`9cB0*H$rX0~#ooLTvpw`d zoi^-_E-%_2G>?u1pQahj(fijGOFSOIQ?1!pl&{458{ejW=wp;@RWZqsdi_@jc0(y1c{J)T^!=q9uoJ9euBU`;scl=$yZW(`nMkXDsQ zxj7zs4^!rw#j99j*(dUlj$f-m4^zLFM9MhHXXLJ!kqX6oizdgxmqs zt1goQd7?{X$gvr*%GK*%am0(54V(O3E{GY}x5+5Sp{V~zo`mUl|57T#_P0{KmphO& zQD#Hka{S@0aPz!g{gpC4-hKI~Q3$G|uKU+>M(c!(TLEBMTB5-|ew;Fu z?{Hb?!86&wEFK;2Db*Mv{CI2OE7HOqM{6%Yq#N{p%*{=d zDBoW1ec?dI?mAKD$p?K;x$xM!Q@&oEK=*o*uy-6FPc+czfj5AbH3KLD5Xc^OTbN}X z?R?3q5h~!pte|S|G2=TF+pKO`l+V)k#5mJ8=t^e0XcT^D)|c=iYv|7X``iDxPbvY8YGXLZA82@h>_!{Ip7B-Sd60!(8c;fz53qU?pYbsivmZQ= z)HZvLk;)MljB{>8;EbofP^e}fsh;&T>oBvOQ2a0TFZ4g>7a_JhdU0OwVq!=(7eUQE zgkI1A#OqCA4UIAGcIc^$o{$s^Q6oun@AISit??3Ij?&$&p|Jt-{*wn{!{ox5IvqOX z@g!4a<-3&6T+*RAy*!?@jbzg$OB?8zD0}-QD5(2*(*)^{SR2d;LR3XW5T@{85<9T9 zkhJ|7oD36DcT=493j9MIIE47JA!}NUs7yHebz*F8&Zr=SAWHT+zyy`VbR<^|so_Fj zGXNZ`Q~w!o67D-yt4LB5$pTA;Q7w;X=(moHMDfkI-Sh+T8W^Cqlo$T5i;XcSD{Rf6 z*9YC;J@ky6+Ov5b{*fJ}K*Qe7hW}`r(J9D4+3_dtQ%=z z!pguWTJ$CIJ7$7FrxWLmP0XeW@1X);$%Pf&h_|ip+?xOq0rW~`ORyBTpE~?Jz))=-0&>pSFc%;x0OYtP%B}N&TZvRAo!vwlct(WWYaEsXJ<>HLxPWqC8F9m-L=(lP} z!-+{(q!Mtl%nu$sN7_L~H%*-sgoCfIF7nuPtJBBFkn{s+a%OIQT>XM+=f~Uern4Y$ zM}dI_;ra}m3&2%?V*-biQ;f%AaH;-`2_u>P;Hn^!`v!J6dhqO1szXUnO+tzQbj(}T z!)eR$#2n{|(e$&dBwVIAwsna65O^8DOXEBDU7j5RIYbe`ps=zwkmd!ih7`Dvwx@Nf z-L@G-S!?p7@19$TaU)Y)G%eZ zEqr09blD~YB9H#bldr%|?jx1wu(Qp=hP9zAd~jVog~c*!4#4Gx$(}xP*&RjWW7R7C z44c|zcSa64-1R@HH$lIVcHDw3=(gWV43@5wbQM?^Fmg0ppR?rT%;J{?et=wPOkB(> zvN*A@A|Xbg$x(nHMSZ}?h#b7n#Wo*`X@62LI4Y3LJUTvAI?VFX)_BC{&!4%+8ZMG> z@bDzEhU`~*VsQ>B$jGEYvmD$4d7q1hhK4jLA|~c@P>@WV_s^d{NkSz0V2{i?ootQ2 zbZ|KEmR2Id;Kh4>$a99jFi-U1-+f1EC!JEVgLVR*OiS8~=S+&&L8YppMwIsm6|a2P z3x6#Bpyt>0WH}7BL@|Skvr_pf=f)A3yI^n1IQBqF`2qf@xOqevl~689na`ES+o}r7 z5ow{r9xm7?XgDM(X!ukKD+w?y%wQj~nW@c*l-Axvesg(lE(N%X{Ps_uKCwLCo+y)H z%1{MnZN#x(DB2)t=chPrB3TjS=R9CBvw^M$X&wt3TLlaX;t~?3F+0Fg7EDb|<@4AB z9a;oFo=5}&Oi@fAXF7v{3umZO8-5h(q1w+8^*%Rn^pJ z`wr&aQI*aK3}Io8`;pKtkWF2O8p)OIo`R;ao_oq@ja$1sgJjF%xPg)#Uh0e(+Isu< zS1LGTUdJ8o)HApO`2~7cZm@(=z%rDMVQ>HpZE1rH3{J7Gy#(Z#`1ttl5fP;;tEi0Z zFSe^e9w15qfgCJuYCm<(k_2sM>veBzAU9H`E`hNA(uFoO;lD_`DSYWZQLh{>Y85mw zWYp{(kZViX%fARqT2IWB@oix3$d+KGjb_)U7Z8X857ljaeEiM+bg77^&Ks%$t7>`b zA%GK#-1ZGofV6IfIClrK>&D+2S9Z|ssQm;Ul@`aAu9@`yn#fI^zDLH0|^E;WgmFRko5-WMes}cAmyxE zXlPo8YCt>zF+yp@Z#b*czC@)X>qM2HwipjS>v;yT5s-lFYI_0g95fcloz%8ZRFtA zq=Y03TwoIjmAHQX{>|P)a<&bOZpH+k33#9QEV|L#CiSF$v?ejbL3?9$7V0HzM>%yp zbyeHEdiT;Kyr#x8ZWZh#a$JwUX6AGc%7VId=_xQadzKNK1Pju7{_z5mGqUWw^)uy- zC*?H8fZRDMv>NqT`#8y))Vpf7>fg=_w%B=a4f)-;`MT8n4qy(0@nREvo~yvDECz6m zrknLAflBbDFYy_d#o!|Wm#x!AuMjexK*%zmKwwnLQKkbI-|JP;P*kpJymUCmlP-+3w^aG?Atnxw=DC*^dI z-7j_k{q(8jO}f>xxdNI=Bt4KbHfVbu@Ckbm;+;C6qJoc@P3Kj~E=2mM>3Z-1%rBAf z)sYHR;OAfN(gEVQ>BrO9&!{UYDG3|yxZ{lIENB=yx9-f3vPK6howA8zePow)Dpk12 z4J78c*KK7K?ZCBIMR%g+0gLF^GX1aiF|>x{gaah+li}-lXmbj zJk~D%W!!le6bHJ^XkVcGG4Syl7<%E0nv$6_IS|F5#NMH#w4Qbam2qKV!ELLk9R;MV zas>930SQik)5Uh(`9>ai4E7uTU4<_{ZY?eREaVJYYe4TMyNnb1S*Rc~c$f zUh_EFk%NibJ3g+r{Z|1`u%B?~=X{+3el6YkjczyI1^|eIaZ7E7k=5VJgk34> z_n%Y<&V!7j*DB3hKV@rXXlY(t*6F3iI;R)fyqAaWnWuZKsDiUU8-H&4sx*{>{|6wV za}bS2z`!zsOss)KOy4r`=O7~?C6hRwx8DVPE-MAx_ENMe?NZ}FSGak&4{l~ANI4l} znXLpTg7*UuTZMchpe*JDqv_}*Ng(~-_rOE4!|LjFO* zs?j@H(oAI*L-fcyf##Ww91$LsU^Ylk-)uajEw1X24zPQKglV9KeW#y=*-!!SgY*}l zc>5w@8*CF*0CPcD`1l%k?%dg^*{w%9kT*c&RF`G~B_SKI<`0ljazLTZglw4MbA`}& z+fV`~Y*D0QvOU|N|MBC;9H{e*P(gUSPWN!S0Xf`9A}lCh$fA?GJz0?lHpd+BP>38b z&VeC~5xhEO-WM*;5MT&^{wWwnYgGsyE) z@Z|9 zA+!RJqN}%8uI}o1a-$=h*7EoJ+g)#-WP@3gr@591duRmarfNp zr)()<%1G3xKzUp&b4%RofJ=@?DmR4(jciS>f89t?mhO$^l0<4z0K^eZ*zDO5L9<-A zJ&+pI5(S(ikv3{@i2&@6ItM+JDkcneE#q_Nt-t$8V<0zWz#C^nO^5_D9;kROad@Y( zv1q2y=#6@TwxNSqA7W@e0&JFsG?5{9ntKEGeb!f8jgOF(PaV?f_gu}AOr(O9l#~R8 zSj!ST$%a$ zp~S?+8+cYM-J zh;H_VY^1d5|2qYKWUBwviCsa237<3e?joSFA_dN_>1kc?$mc*ml!Zz1_`Scs8VFtg zdDB7Ai{mou^FB;f{e9{czH18$C-%P!*L?9}akyrgs$%pKH+Nc4#qm-IhsklWqi|Um zDu`N%shqYMt%^f+&!>FSA2EI#)3xE!Z7-M<^}m~^ojx(Ub~*IF^hlnSs&6nM`bEIs zXU@sF6qc$(;qk%3>>uhI*)oZq-4aT_RK%w)3g0IBg~i2jAO`fk5o*;pRc{5`3Q!TaSTKVKpuaxDixuDOVwx?(_`TYi{U7 z-mROOT8q?Tkob7e=HuBWM9xW&KcAcS_ehE)O_GQ zARFzh{5uvPz;HISdr>&yv3h$k6y7#ZYo2}95Ps4yCgI*dd_*M?G4OqyXd!$#2;~V4 z%{xColzMPi;)H=Rj1A{=Mw0>5&+y50PXr# zyGi=Yg%t(B5K`9fiQ@@^vp!5RXZM<5MFi})y*3Zoi7=>pAkK@vB{r2Y5AxT#^rLB3vEwWw(lY4pEs-rlKcJu9dpOD&4Lg zCTH*Nz5bIh(6-(4jHHRDuv*rX6WTGasg*^Y&Y%LK4;O+Wt3owvk=1XtE(PVYhKj&J zpX9cHxmgbl!Q%Y<3$Ve$K3?+27k)rT_Yr#hg{`dw8v!T^ta`OEX35^8)wTelYL5nG zEZ)~XlZ$!s4yw^ii7$KzrWTX!kT0l4oo94gvko!VBKpnoGFFZS607s=Rr5dAbV|9d zYA=+g)(04V-4k8H)%f;vZzEjeH;!YyMf0D$-%~9gkA=GLXzf0|DTANxnln@0msuG` z&S$f?RnmW#nD|q4baX+95#jA0XnVjQ6bt{n*$(8p9egw8ySrJH1UCAJS7MxLkhemApFUWtQc|fpw~+Tjvo4 zHb&`aw#0c3O-*g3&o!iS5^X;zd)a5ze@JXt1Xm9_dC|nmv@YBr-DVMc!JRYx2nic; z`)^e@c*MR+WC!gm|Gba5T?}2~cBtWH+deD{!Fm_*jW=*!0BPVApQNRw1+OhFGjkyL z1|&i$q=0P${*mVC(-aYK?dZC~KM2yB_HF|Y_X%cu zY;mOH8MWR&4=08UWCuz<__w2hu0!4Hd$y|xy^`?d-b-+rKXqCo066;tkSx*#3YCul zY{+1~<_XEpW;8T31aBnI+crR%JpfUVUM=Y7Oo8;^2HV8gY;wnJn=M7yBDw)i%`ZYO zfh23?WPfM88(Mn|L!uZ;zd|g90}~5(mc*jC1gA5xOr3D5ixbCut?@c6X&%~k5qqOd zmRdAlp|Sis>=(h8rG5JJG|Aih;y44^RL#z~UycwGcLcWiMyUny8a=NmPt$@%%btIC zBW&{FW*zzplK*c;366=s0TvAYz=->&nOGJTjnm9vdxV);3eoDm5K9VYhX%JJ2&Anc z-^&D(O}0h9*j?;0(~UzIq)aWQfv*HFc_+v?G1pd4M2KwO(dJwh3&&xF3m0pB?r=n^ zDTHwG?)4d-$YZvbOwJ!~;;E4enB!0B$;qI3V;CgUm&LbKjxK@^82=eA52G||UUc<> zNAs5|&sAxaUmaXCsSJG{B_gq&u)&fjr$`M&b5~qo_w&1dR81? zXV~><1HKJQ^S4H0lcVhE{qY2KlzdeY0| zkFO|3FW3O86jxCDo%fo9Lp2IN>`m#1WH7y6A_W<1ALIJzF}g|Ld9m@K6w0+mF@JZ> zN7T6#$Nw%x@v8GW`>{xDWmyy*)?I$%P2Y|ka}sm+RGp)VC5eF}@&;d#YPNPmLubDX zwo1a=EiTph#AsL4l$Y(bJBR7B$plT7#wFo6IeZ@!(5y^L98r>5N|wynDQx*Who3a9 zAZLI^7CW|WEoDIVI+de00`JZzhO49+`5!V^0!~|A&J0k&T1Ur;M3*=gwZkMyiEg5` z5Cjp+eZxPTKiNiE$7i&X0SSbv@qen(bh(C6DaS3p==k9Ur!$hHwb)rBVcc$_9`V_a z1e!(`SfR&tEnn|1qqvEf3Oz2D@_lZgeP;O3oW_dj5%UMbv8mT2PNaV0tpW#=+nq_S zwbd`*i_o-qhgk7``>S09H9|LxXQ`E?Mzi?$t41U7m>O5M)~UeGIgaqnbTq}!=&v0w zU01yILzFj|KOL!&9Dd_nGkR4=bN3RHhN>&wC4xlR7Q?pQ?Q4XGNLP+y&)GG{lWt}E zCSK%32t#MuY|w>y-m*=HdGn@6<+rsv_~zc89|#rWuqCIc7U(nZzC}%8B1@Xs&8tg!4p9$QddwzNp=E zqQI;i*cdfHyB@*#n)xQ&6Zx8K5UrgJUOibg{WqV~>!8bzJjF1Vsp}MI5dEA_HtQj% zbgyqusWlTtcG~lsp$3*gTMzh`tP`FY;Qx1d1h0bOLh*T|;uyx5#zK77zZ<2Q`kEVZ z7~zxDg(B^~Z~1>f@<@txo7S8+vWJIECqn)Bs&c8terpi9bHs8dOIKsBooi zMcjWN2T$G_nQ0JW>SMxL-@s|?9xET>EXC8`K9@d64WwXz3oGOxN|)voVy~jPLeqff{`b1eimAy6-?A*-K`NVtrkbmM zl))pG4;`c+Xv?lYx$Sq7B+@~r%aI$ez~LaS5_?}_=_zb!6w}?95E&hV%-yk-%XsA? zUbAkU+v)2txsI$uO)dB9`<~%4-`xAXo_H!56=`807WxfE@vjhAy^j8@2VYl_E=Pu! zoDX^p*y5vr`62>2(9mL5!iv&OJl>~c%~9H3he3Rd$j4E@KK1c z8K!wUtCx?)z4KJxwpdKSq}lpt5?e_)61FGzWfVnr{A(banmWcE{+FoF4aOkS7Z?6L zbUSEMSGJogn9+EFF5twCcx$=21s8UJqlgqXO7bx-Egt(uy4c>9{zTmGK_b@T_*;HW zHc*vkEv?U5CtXTIQjQ_W<);0 z!{S8bm2wk;Ux@!%iG~cTfKE+#PK{b>p&!6UY6I~>vlZ_A@hgL?gSsdFGF-npc#(4ieg&k)YLFMVkY)IJ@a##JE5-vB9}F6+{$kON1*%kv0gZH$f1IW! ze!&>`$3f9GaDDhwV(!jn*Ix|l*a}SNuJEr!1+0uJjGU(`JINcy z(2d1@bxh@j9LXwX|HwaEB#XWr7_FF09@?$eqT5%OTZS73~s%NAc&+V>h|lkJ$Fiiwu> z1M)3UIzGP%M<$&bj>pDivme=3rWdnNV)W8*;C-G;T*IG;$UMH@=6Ke)>MVouWaY?b z>Sy==Uh;kEJXA<;x^ulVP)rv-;;x5h{+)wL~plOz>srn)M+%&D(K-L4=_u`rV&yLYkuf~264QTO2 zXh7b;$u6Y!i#!wxYK!m_UEqKKqYYkGR#q;xXcO>qd$wC`>=eHE)FPBV*Vtn-@hKzt z5(0x50t35ddztKGj&bOZ_E7<32*xg&Z{i3B1JN}I-Kdj33z$*gy|b{r25B@9c=bE? z?ukPa!zHVcH8j7yomk+0&pl|s*w|yu$!8*+C;Cz~{f?4}=nc{{$aMM>7Zqm3tHvwQ zHtjJnAvn_ot0(1qXXX9w1@mtY-07*Lpb@85)6t<2NDPG@aP|agsD*JwwAE$X*4t)N~EbFj;kazA$DY*Nzr3izmrI zEbY$i;}g?v&I&VRZ<5qiTdU!YLPJMs6aKJD)L8tXN4eW=qZ`GWEA zGT~%P8IGla+_MjdCikJAT3B9=nzsk}*a+5eI9CljqO%1gd5f7^esnyF6cBdTlMdlb z1c&{?|3%q*$8*`Y|Kq1ETOlh#!w5y$JB6%5gshOgclL@TGO||@N%r2eY(n%N@t^E_YcJdWczjwaW=T%B4vUfxo3S7NOG@q5MP)1%yz zTzB&riJI~Tib(^^jJ3x~L85J(V)b(eP9$C3zMEo-*%g5a0{zF2 z4Sx`dw1b@Oi$}G<_r#z@4ef2a*vT@R#sT#_{zRom!vdE=CH|9_zH!x-1<5cd5l{tZ zT3WYBWYZE1J)l0^^YtlP&B=DVeW*+>_D{(2K(is#Tf8a{QY>$8Z~N6DQs4UbW`l_} z`U3RdXcYe#J=ju>Uhe3(x2uLAkf!bQyw<<$|k-R^tO7BJL^uPtXWomA{1 zmzm#8E@3K-U3|9J#C4>)5kEV~iE9W+I*Qv0+z7|xQ!QOn1Zr^0leMA%*PD-(ZH0M$ zd{vzUnv#p8q+!!{0F>tw6r3!a)V)17D(W*989#3TXJ)Ah?Rd%ECe5`u#_#H*uXqt~ z-MI|BxAJge%?Q^%p0qK$WZ@5omqLZ>?Xo=>Uus@>lqLHI&$PQOiDrnlIMxU~skPW` zZjq}y_pnRh@CDhX?=zp;z(8CdA0LpQ4>4tYjAXoZD;Vm8i(*6%EZ>$Xv2>lxhF>vJqX*Z49{?;uWG%to}4bMN|Wy5BN9uyG8iCzZ_7Hagk`1lxC zL6@JGcN=p!cwAf?08{{lpaVcM@Rte>Y8o?l5nzI!9WK%)tAA_Y9C$K%P$oMaKC?V$mk!yO5Pr zgUAdv*hk2|2a=)QZ$=G8#-^sGXUWY!esDQ&>e9Kc-T_dv2{dOz1%~*5_q6TqtEHr+ zc`4xZe--cl`nc@&kzS*9W$LP3W6&nK&}9{xo8iN=D*la6i?2@^%os69ivP@U6YM(D zo~GwrbG7+-Llogjn9yxEf8%yd=MS1WXw&v-vbJx}K7+zypHMQt-3_QHc9;${jYC;; zZ71y-ZOw7W-dhSiM|(dtozAUWkoTlpB-fv{m?F2nuA{XybxQ>Lq{8eh{k)T#!=zQ( zD7#3!BOZ>iv)^e1p-XQs10A!@FC@r~@ivLak&Np}>rLxZ0rO#>a(CB1nVEb<)R>oU zN)QnX5x>D>xcZI9p+ic#=}q#;6>Qzd)#BS9nf;haP=O@`7$?IoIT!6GBIj7EeKBt9 zzuXHMF6l~Y!GXAR_&$sCzSi2-=Jah3A!lc?_NcTRt@bxJlYeQ)-$wiKuD$2mH~#$B z(T-%;Q~M3Yhl8>!_#-tE$F$WsBocG!)AFzNd1BP3lrMRy5v3uwh3zW{ut|xpp{2CY zHHS8SygxOEN$(!HcP}v{6$AUdX{^pxVYhB;IBn~XqW31>h6)oFIj&&pJ`rBScoGnj z?jdhC7YBxP_)+y&MT>s{9nF|xP?Cz0nkJ=Yi$PJ+P^!wcp z0GIRWu6espKm?BE7Kc5ziLZ$2-5R82%o8TRor}`IFm(qJ@(?D-<#XzY;dfa}duMlZ zo9hDdU|_uLBbFWVf$l{dxuW91G>)~kmyU<`e0$+_8gLlSOc1eQFZA)e=CE$Z$8}f6dtmORPu<$($*NQ^&K*`xz zsN+PL&EpKB=auPL-s&V5$$gYB+K2X=o~jP?4E%^JKldZS(wcwqp=agKH_I>gFq}d} z{dVMyOt2~TufyV~czd~cZB3ztxU=;_&AGN2o_6u0cxizMo}^*v_Uiu4Yu-D~g;^ey zSMAO(FyM*kaO!}MSbGii%{K!de)wXJY9S2(7QNxEPA(^NNY_J5`An~hb%2iy5BCR8K8r3rcaFh#kP``kP zYhFonw&8n42G%4}BEr{LG5tTy`pY7isy(V_l+Ug5P%CNG=QGv8KJ^>KzV_9{4%9>Z z9hHk0i?ZW27rHo~Q{GSP4Z zSW1)Z*+nGiTOp>GjEuUXS?@KAN_!T+0MX6O_g_f9CVuhD4VtFtGSANH^kUtC8D4$j zdcG&AD%2^X?xB9Dy$i|na9`@fiR{Jp6RP{cO|$GQ7Vl{t zZ+6eJ+_bZY3z5Xt3uV2W6|9|W6tBjQ#7P-vamy1Ya-1R$sQ>*1lBwBH@eJP&Yqm=<*{3(ZB#`V;@2Hmj;&_cx@?MD6vkl+jwQqX7|q zqAPzO}3?**X$9J|XI;oy}^Y>Ac zbIy21n`;}FMOObV{+F=ImG_zXk{YP@Vbf3dXM@lWlQ7WcD5VNM$Pha#hU zRPP#35nQ{k(x2>DulCh~g{LNnIUW%+tdk?g9umjFQQlW)6#fp%8-!%4dcSBbh}@cM zjaHRZjp;TU_q$KUEJTjv{Q?5*e>h==jbe$dD@$>ZPEO;9-F7h&o13T=Lf+%U315l{ zdkpjxP2St_dcS|&<#gdQp*MebR*hHJWjk^dy;1C}c!ZkXIESm!*DVm~_LU5=Rxy&W zDAc~ab+R*n!<~Wgu=9sA&W(vjts_UZm0zXM9yeDi>@AAJIK;x~onQG9 z6Vwoq6^{({^)!uS<{**(yTo{{Ohtz?4P}idp3~@=tFsbWoYlrjWzDp)zu3Cgu<>Y5 zTMd5V4h-crm$;$%XZT(e(}oBYF5?-bpDid`R(741SdF@T{o=I*ev->ZiRZaJCY*?4 z`BSlF!!uE^GYwSijq`LO=eQtdky=8QK!8a~fx3C$a*E`IwXN@Ohm$=@El0+@wzl$& z!yFLlS^SYI-^w6zbc4T_=MiA?t3Fzx*IJ7!QLX&<>eXpi!A-7(I-Iu(I9Ao4h0nHS zg=n9n8B=Cp#aFhOw%7jMUmx?~+TR()Z7P)x7v96fiNcLnpFCXAX(+ejk2u@uHghLr zVv>1YeX-f#%2VYcZ+g8CFA%;IrR8ns+sM4zL0PD-aN6#0yz9V03ztUdC5cflE z0%2PL1e217fR>iI{1{h@*bGA~gtE=s7k%!&JTAjJSuz>10N=tlcM(yFr?l|E5~x9@ zDr+r66dmxsnv{g7RDQXK25Soq^>!~VAa*ZETCQ+Z z9}ysETN(iiOb?2Q@2aCK;4<_Uz<8t=Bg$(!77Lg#iDK|fTDMX`_br}DTPbIqskyq1 zhErrFNl}Ycm-5Qj0FRQvuS^y-3Ja;lAu5$N!#~PNT~OKE|AkS3MGeB?-*>@AE#|f! zI%LLW6%{BUHpt=WW7Z+7%LK+Y#QP}eIFQ5Ue+uSd%(t739yphU`)1iLIdqsDO!nDb zhn+K`W}IyIcLdvN18W^vV^}kvEGZYC_8Mu-{V(v;UgsPL<1rw;MDYkJoi=^|*9esA zw!qFN=p!H`oCgH#1(@T|@>v7H3Hv87>41(9t8A63YiDzqOLg!I-ZFeuwGETQ+)Ijghkj>JFzU(*lTzAT~D` zUtC?41LrUxx3z9o{rvg!?jizY(Zia>K%6{GuMEY-q3htT%4}B?x$CljX-Yr*pEolA zbDACnjZU3dwh=N7E}I(bA_wdO6dweMWPQrod8YLFkqro6kCUP&_@n;x0;%&q$@f*L zazOSi)#WOl%Be$#Q%6fG{`<ssdsKZDELk_y6NZ0iUuG-p2GKeMKTSJVn zgS|}L;-gI0J;U9EZjs~Qe-KodSU^yPB`opNxo%t{^zz(a)f*it-mjvgq>Pz2J0aP{ zILjZga2+egB(#*|Hl}y0b|tn9+ZHU-bc`%_w*SXQ*PS=Q65YB>8RuLgc4fqA%t>#u zhcELEtUEr|>l_1_7?H$J`T6!M1DzG3Flu#mVn8+ttk-R^KY}uN zofUd4#j+@;8#rqNp%t*) zIbgn&tZV+m<7(fe1s}kK#0@RE(SLGo^QXnENJR`KfsD*lQi+bXYWs5VGQms3bUB{^ z0(vd!?iZevb#}f(!RB!& z?6VFWFS5JgzjOhw9%$-#Kt#|7@iY+S?!0IUeD2|dCEfGs@rk2d!<$RPNma025W|bJ zXnbnSu~-gPwPlX%V;Se^BoaeeU@6>1-V^83p7y+OJ=*)~9{Ydg#nd%U6D|P&fNp~Z z1N}Cz(jNv>)&qUa_-6_lki+z0tvOFIylOv%_F_teZLf_+gq*0+bS}hybN5PQi>lkYXnj2eFD<7aRx^hkqQBx=7R*qgz5c{9B~`?XtbV4Y`;)Fi+(Yy7Ax8=kWXcdQYnb%*XMh zLSK502#ASOIgonUeJ@TA=B^%nd{TGeSrP8T5I-D(Gg62+W^|h9mBX@-r6*;R_SYta zAKds^YIpbv`|%tT|1*pwogw;tOf|fZSROxSG?eq!Gc)S@pW+KRt+nl~;4w&gP$ZLe z%ZGZ()T1G}L!Z3lQmi&mnQr?Ej7tY4(xhAKG)zqV^44&Zginl~bZc2h6eK)T~ z<+Mgnv6w<`6j?q=N^khj#aXW$ENDp4WMqcpieSzjzkQxLW}R*~#jv809&GBBIq7pCeS5FaF*>OO9&u&o6Al1fke$8L2ZGnXr`{nD z|2cp6r`RKqkoJoOuO(*c9nD-+nDEpsoJV)P!uJxAR9b{Q#`YfKg(z#6K0ols16 z>yMk?XJfwI(@LALS=111YKsm~%@$)hSk5r7E`dQ)i<0@1D`<+AGRVG$q4GahwB2P}tw3Eps3*kKsRrRU=}DGm)FG8`>Nt;h;tT*+}F#Nj1Kec_GyKT2NM-0Gn- zG9pRGXdb=i#Zp0FInMY1qSUpm-p|8M7GQIqam!ci*V=i!Ln(&DzqjOP!in=f#XmkD z#B^&;bnOlpg4k-*u)XfqTWv`D;tfdx5BKIWqxK@mr`gOSnZho^wAel*!t{b%nJ;Z( z6lXIj%sf<-$RAJK{;v6Gl*Qm>iNKRDw)t&KKgX3ZP%_+y5gjqQxu}O^!a=VS#PJ>* z#&qkJ=DB=%X;jViman)U3A%rQJyy{G5_iXLTVqdQh;y45CZY?ziSWXj+~#w&VSM3u zV!yAT=~gfe-%9oNJjA+qsc`-X)*bzW=kJgMPNeEoEVoZN)A;(R!K0xBh_#JWGSPE# z-oHxyz2`a*Br~)Nc|D3QA)Xqd(BInKE`E~Z zmkoJ~EjYkANEnZwoeqbmLA+tfZyKtlr2Or;?@DX>V5734NoX`@chm|#Y(4`R&dkHY zyVy=&e%7n1Uv%+;`!C)#M!YOHCd_3xL|BsIOEJXMc0AE^U$;}Kqt}U^dC~9|TqlMX zn0#i65SAW4zA0$R&QfqO&^-cqJeTmA(0dgh5l#>)b8$UW;)ijkcXgPd|8*>>i$Cf~RkE-xEth6yxA;6o+FMQTd1+i-eyLEfUTeku z`Z{v5qnLdInjWkM8(t@ATob$fJ;mW;*axvy0QeXe`2-}YUm;{6fi1SSuxf1^cPZYN zU~krRQttj1_s6r|xpA_q7PWH~_S-vHPN|2Egej>M$jhNujH^DVX&Sf0=191rT)#Ax z9?ugq+eKY>oSYibQzwC239Ea?zLHI$K>Qd-7^-6d8p{r;USmben;cNZJI!> zsVMExuR8R|c#f9(Bi8Ln>6};T?_V94u%G2pAR;Q<4<~Cz_L4mf?!xruG~N8JygJFq zm$Hjir8I=ua+Smt!0i^BuQvL~A3;Y0c80`(->&Lv1jt5~Ki%1w7h<8b6wh0H6*X0U za9&@x^3>M;$jnl@sQlsI_n%dXxPdGcP$EZ{2Nnt{rk+uH^{N$zSrGRJf9w-a78#j+ znpF@<42OjxqdpT0Ie0@o2w)sIh3Bt9J%7Sy?8ipL|iw}`3&T!Pd!GRO{XD*SDsLoES%z7=Fi&uy|zpRS1; z8>jc>{X&wq>@ic^s(7ONjYdTpjk!el&~R{;`ej{DMy+DI0^o$c3FV*1y=m^2+V;mA zW;*|_pqw(*?6|$F_-MMQTHVK4xhED3JGQ*VEP5SnKwlu{?7~FXXt52=-{vQfPo(PAbhXGM3qr$I?eW7u_2z8g~m3gx)^EX1MoQ_S-!vpB# zfuRA70o;iS0eDyVlr`{A+&ZG~jA=ig`xwuakdWf)w3Z)?O(8*MU#fm|6?)EbrIYY^PwJ+i4!U#G;kR3T^(T8Y%paDk za2X`E7a{Hlb-ww??t&Mts0AB_m>+D)LBNd+j`!p;NDr;9Q7Z9e4L&4~=8Zz9vk?Ko zVBIhkBU53OP$ImLA#5TQ0ZnW#S+bi7s%WI8T4}hOI zZ`-x@*0e{$HP29X;Zl!Dy!2%YuD+nlMf}-34=vpe?v9NY*LbCLUVz3bSSml4ud>n< zM}^~N^bT}CR>zVg3q-8J2ndCGctZ4ywltVK>E12qapD}egR*v|87|iRDs#z#HR=m9 zpDT~D$=w|@?7BOO77BG=)rvHop=wRcOCJ0nlx{>7Xh@Q1;Ja~XK5C>=^F<#0%JkXf zwV&YTf+vYQ1Jz$ub#*ov=^x%CXH!iBC}v+c*Pu1rq|46Qy5%$NCdx&&d^j_Cl-)B+sn0kFrZL_LIneO|q>1?K(NZrsp-)I~!l z2&5-K`z%a4L~m2#0c9-g`)0jC4kcczA1A+*V;|)@^-ol(y~6jqUmPF(?Ksh1f%x2Y zbMMEUtH`)FM%p)Z-&fQAa`V@7D+)UvtcL+osI)+3H(-|Kp%OA!lcnHnrfmGqQXoz# z=QEeq%l}F8yzvnbYs;IP-vUSI7q6Q^z8nWOWl<3IL(16#GD~U5moE?zr9-)ZDrx`! z3A3)Ycz9D#QU;c0vAy%ASsBQ;SsRi2T(~xAL7PQMC_ZH+60pOL@rI-I+elGR`vbZf zo?MOouPVaUUb6TUd6mvvs3$J84TK`5Ty31X!8E-kEykH>kU{03=BUr`APM{q{8480f@?6<2TaM8p64EqCUash@_#dwwTN%^ zz6yr{LVF9^RvaxBg>(4{#gr0QQ;n`*V*|ET?^g2v0 z0KP#ta|g=8v{(96&7l|+b$NYhP858FQN1g`D-+E0g5m##S=t82?>WbkwTREjhBp>5 zz5$&}z}_#a$8s`#u;}x2dVri~QKs(IHT&CGS-jAsDFo<8HRJp2gdAoVqI*%jHJ2Th zjDHXQic-JiBI$hr@%8Zu3<{b75n|0^F=UJ=g=u$0csM1$?KPlNq=WLve6-{p=zrge z#2SZ?#p-6F5#alll}U+=L)pB37rQXE?I}Wi?cr1mI^F~0KTI6lgC8-<%8Yj|wtc-S z5s2Qvg(cUBxmIbVh_zO@H~w;C2G0BTZ*PP?!K;JfMS=y@>tNl*0%ji*2S+m*G!Ai~ zjkeuckOxx756~)r1E40y!a&yt7K{&UzQYO2FQ**IM{GXzvgAC$RI?-{d2++f#l{Y! z-7Rcoz>tFwzTWz%GLp+j%rjPMZUM(ZK0>kc-=`J{++k{DG4RRaj`}>rBhqlu(rJ@( zmH4%RW0?w8O6!ws&vx&(ICR4KIaG6qm#>Nzk-EZaJ-$P+8Mu=E z79FBZJsNcagdIa%Le{u(KYn8UXn(k*o35HZyF6ke=lpIVlpv zYeh(GIDx`uQDl;8K}_q#rbc&Y55ek{vyoR(@-r`x+iW|j>=$q}?22kduU)TCmk&+2 zjQWjR7-G~q17{z{m$L}1Bhda<^6^HQ)i0X%_tH)Fi0r2)CGqGWj=iL zygyygnzu|;RANpaLKNdyDR=-r`s83vf9OX4&&4Gc#TGX(#E5SaBaURf zH#RM8+b;bSIpO+n`Q}YNJ8Xr778MUzhXX)9PPRA>CXy-K66)ryS?l#Nrew=2xJm;AVtukB0h;O9K4q2XyyC^E7uaTLKk>ZsqR2(b7YgOk zza9Saw@@nyD%5&{{`mK+UyaPl5!B@6;3}<V~HQ*hAF!6 zxjbeTS8Qy;MSRe^FmA(;EuY`)1rwejRf;1t4QwCUY-hUE95TzXwD}}zu^ZSvb)Kh) zukZAacT%E|Et%hfT&Bd84fxlo6>SMw&ICV?393u0oU6XpyR#`f@dAA>tuDtdGXXg6w1&sNUWn&|&%T#l7HRlbFH7xg2><`=rU zNUmh>V!261y_|CRpo}cps>iSEzH0d+wSn`c&%_J^0~1@sRvU&j>Kld_hZb`6i*5Ms zJt~B8{RT`ZJ1;LgF6Oh^voOVd_%d5p*P9#L2dn(~B`xf)W6wes^mFN_RCnlggrKcS z`US-KA7N!2Bym3K|HZ7-b7|~0?R&JVjPAfp8(kSwAAQM)U>d7^ypsPwZq>T?=)8DB zhkwV#WKw%{eUcbl2t=;H3N=KnklGA9q>|v?ZSp~pMgt^JIuuxpdjbxP;P$Fj}T7r$nIE4Stw!pRJ~Q#ftAiE zjCu~JNZ?mlj(NR*|IfK|D7;XZyM@MRN>^8(G7As#@=R14U}lLqZh*6_PxQ7W&9#yOHanBIMV?#%tK<+A~jSn4*8TwKdG?dKk4Hp=; zv0yO^tbTbwIuqFQ!NB#j(d+JcP%uRQ+plk7d!_Vamat6TSfO`h*Yv4JjJg{#mDOcs zaT#puQLGXNG0olC!I}O$f~MzH|K6JsK;+8xQKRGf%j@euzs2r7i}MDuUP6z-T>BK2 zkc~XeZsn((3kdXEf;$nQ?gUL5aB+XqE&8XdbiLGt0d9moWlL450{&%P{8hsfO9&Vs z5r!}5gfT#&U_vjJXd&6tJf8R<_o40VLuvV93s@dABB-rYRX-9&CW!6-3~AsiUgS&N(Kl+WMhG%R zCF4B5yQ5x-=w`3N`;9;5d4&4Jd-Aczd>4G4O*jOHrA3fV4PD>l&;fzA8cV7NIg^a%8 z>eT0@Y$KQz{S4_vB|hP|PH)hm;L#0}U${Z!zGZy47xFE%Z=E9g`l$ObD#9ytTsV0R zdV%GF8uK&^gJs?=V>mlqLVX)OeZ|d%sSmn5yyAKOPMI$kDDYTHB}{ z<)QED8mS`#MgoIhr{wc@DI=Lm_93E@tgmV;J&E3zpGz*F)&_?xQf5K(y!^#z)m^JI z9n?vP?W2IRH6VJ1oU9K7bN4r(=rIN%s3B!lBSJ?na&Wc~rXK1gwmx{OATGrvD^r_a5qkhu*lzO}Q8^g$&u9*|jzINjskZmvK_GEgPK-95$8%a-(#j zIlEYZn?Ap5(tZv5^yy_@%Yw;#R?YZzG$_Wkk9jgGLpp`~7(D4wDkM>Gh-%v$`p0wV zA((=o+Qfk3TLfhg14PG;@3e0NdJ8j3P8aFRz!|l9A&v1t%0t4n{9ovJ47NQW@l-F` zb)5(l!meBOk{GbsV7Zbm4F_B#`Xxj_KwxHV&Ek~h$tTIz&0u~Ijl%RGh(s~tpdH#% zl<_jiX`|lqQxJdF7T($ggLGd)SLwW)276#nGk17Ll z1IYLd_`I%FQ;UIo9-i7KI$CY7HVmEdKPX*{-r8^X>({5Br4v+?@hS0GNT{b9v|2ox zURn%T@4XII-s1O6Uc|cz`Q3^xZy`fH>-+XGV=kq|zBtJ)>rc%2LOP}QWL+(=uWpu$ zX+)b@M7aIaxD(Yc0j#eoPtQ0=?s+-cIXPv3W*m&((~c|t+t>n3G14{lji;d}LSf;K z@G;@PDOxPYOug6-K*z8q~rixC5-0Xps3ADhkeeCy-*?3yDS^u#jj@}uujGo9a& z;isVYll~p^quWw{$PY8)2hN{CRXf|@UVQB&z?_HoCWkZY2++%wU%X%hOQp^{mQt|v z*jLd4CUX)PYPZOTsqL<1S*YdwTEHs$@Z(+aT32F8yDyOV;^D}8%gZ^NJxWg1hw(_4 zCk>rzTg@O8RGna;5Du2hm%!#7HV(=e1R8pPxe@wpuwFqqA+KyfvzvL~$D(Q!&~qdb z_^}1L_2>^nB70O^R5KK&rqLcUtxi}}y1@bE*P;h|$?9YvrXZp53+ML&juE2}ps){r z7Q^&LHDZ?8eZ-kYIF4;uo&LmbfWV_dy)<2A??SGLa1&VX?p1#OqW#;p-tgBrji zrWL5=CRwFd>6*S{RX7dOjoQ}ycufdlSBrF+eXApse94|c?89uId2J(k0>2Jt_oQt8 z+s}{sZdqGAU5U(4*P*XVhJsE_E~j=C2o%Aj;U!S<`2o~mN^-mCaYp5FN}ev)gPuR8 z`h^54;!>fe#a_a%<~-=28l?f%s2`^n#hwhm&kcL8+mBxMuoVX9BnG%N}+I(TG{WLT(F+fppS1u7!^-o`qFJ4goI- z|6ByV%!b=j!n7=j4UlTA%Fnydq4mO2=VG$pVs3VyJJ= zV)~V|m29nRdQ)p6=kjVdnBZAZ#YoQaO5cb}z(Woo9=$?#5#F$fZQ3Mf z&omcl$I`lRV|P$Q6Lb$PEU5QbT+S$7>lPi&p(@iBwqOI{72{hFl6F_<4D9Hom2_>m z?zY>F%W7ury$#Wk?#pc&yQ8Ga9qJ~NhR);unIgP*(i z_WttcWwkjWh|tddba0P29@>ruH)TJ$PZNCcG7eBH&UWFdi8S_z&6=g}!KYHl!55`V zjI7jXAiCj4aS=rwmOo{;*{su=PbM7?@=~TaTKof<(4js&v86_I=b9Sc4KYKr&l0H= zEwFT-x7&a|%oc?;dD=R@h5~rA=&3=xkhCbg)Qx9x9>-Yy^B4L&!foc}*F(~%m8ifh z81!}p4ix@ZAmy6VfdmKmt&x#qwKX6O43rBjqZaRB^FI){hUcZ|K5G4?OMH3%rY$O} zI5!<6dK3vMGo149=a6Gps$u&;=i-sC`dKl%`h<_ZX3;u+X_{LsMK(R!_dkQI7eymH zY40ID+U=v`)QUSE%zcVaOFQ-ZX*TC45(%L?crE_jWs#)NQ3cjl+Ux7m1+o{BE3Ec; zHtT-EKs}zb>K4s~qr}h8Z>+lHEk0PH2$%F1*aJ}t%I#bxhbjveeJ_b(mPh@@9YO&I zUCvY~3TH38iRz!t=xNrA$@;X{rxqHzogdvZGabDjV0%6S7tcq?M?A~RW36c-nVxD6 z=w2(R;rZN122@d$MP^v-vi)scue}5CSv)_2C9H|sCi{25eRfPLF~zEZ2W)3gE)k8{ z_haX_7I8LEpjL45XDU8s=KbRth^PFV5m@YByFI7g;#%Z22Wk)wJzXL2k~?NJN3pri zpMF8uHBFgpqS@QW%{0;LQl%`o$={JMcE?w3+eMv_2QX#cV*eG)Uwt1f5jCqfbh@0=>ziE}J$*pO$LqfD-aAjEfi2l~_MY!=dvUbm7%2 zU`b{XO5a^=2I8)3FnlrOOoyjZypL>RZ#TD92_1Otj;f}+{RIp^O~Dy)S?3oW=d<^J zZ+KHt!qjwK3nY&jAP{~yyzC)#xX$uBEn$lB`!fHg0Pol(H1>lC7M;IH5c4x_5B1R; zO`M*da=T93`64vtH*c)>%-5eQqkaI)dY^cw#vJG?AI0pw54@yk&vw6P5=(61_>v2x z)Sq-SpHpd+Vi!_TaCRk{3Gf-W_n;;4g$V-vY>o!aRtwP}7sZ&| zJ5a@T4-}F@7kjcPba;)771OAz?#H`wJ9$`;d9t&-Avf)pHB@s2-(G6{wrT!jNR0;# zW!}*h%-6`atDSGd;a?Vwx}%MQ|6)=fo#(#R`t!m^E*U!%K+z=}+$@ zi7rNFXgnf&68Uk(i)<#y?A*LfvYSy9&Lpzuxz*_wiyf_p^;f?Kc~@5M@v*WR_X{973AcCcQXn; zbJsFcvZ}pSNEBm<5#%+>eVUU{@_`zh#Dh^Lzb-ol=^a+>0S_%~7fJi$x9^804(J>F z3}^{O^`T$Q1BmBtH}vF{1ng%RO!mMitYV`a3jJx;(+&JFf_iqjwL~j}jXqenZ5Tlt z*x`_N;aMQMA=nAKQ47U#E*8&p%4&2@YTk?6dRj{&ra7~=LzLW}LLA0P9!OnR3Ehm) z9)sTv&R;+YtTN;Qof$4NQC2XLA8MEly+2%Fy~}z_C&_LwAJdC}{MRkN78}$CIuF+C zN{Fg*F~J9~2fPE$0~+uMM|B85d9EcWGjL^y{X!;WSiVEZejiLTzd&Qp*UcaPztEtr zyn)+y?u0?lvK4?iFj2`7Kvu)Y5AjH3hldJ+|M=p}f)K}aK~5>j%+B?4+?c|xFETpE;ySr7XTMoPsBrPrM)k{$Et~kz z!qbYw2jXSjC|2TI1(wg|iEmc_9IfQ;fK3^yH<6n=eYPT`8_?{^9vX4p7$1a$x9*?h z2U_Am^27B(Crpsw#-&7Uck<@6YbDS;N6mDw>+Ee>dT*hQsQpXs6$*C7eCe>&+SeqE zQrQ({LD!9<^AF;G2+?P}+q?2Jk5p8Y4o_?{+}&kj(S>GF$)Fz?XU==WMgZ?Lg0JMj zaQ+)~a-;@Y3xO$e95`G}ZET#kEJBabSeSn6KTAFKI*R|%{|)_bmltT-6hD9ed_a@0 zBk^synVOR4xv*5u^wP>($aKP;)_epUZ0D$nnQ|k`t5Nymu=)Z$wr9(#XN}%+!pNVR z{6sL3FOhNgSo=hHK&fIxGHKuL&+>V@%*PtViwwHVX*r0d>urp#`e+M!9~FR?4(PqO z$xqNw?F>PHXLL{jEu?@LyuZpzNpQFqdX;y$Dq+I?@0^&v zrBvF>i1?Zlwn(afyt$TI?6IaShD}-CRAl&%)mj~VAcb>DjV7)JPe^9RqKk4smEHDmw1RYO8V4hhWU4LXe+8$lV ztHmH$GVE^2n|e;wdHhx&&)f;O>)KY9l=29n==J*KJQ^rWANOU1mPn2jo82~2*h|;? z^1h^Vy-o=?jGbatQ|#@q#o6RUb@S7w3$C>1tDS~ywp%{l%*^xb8)({Je%f9Pjk*_- z(bH$v5*vQW#qD$Whjeb$W=)xSzKH^x^lx_GOjv1*Zhf}DO)k3??(5hjiHlWLN_vT8 z;84Gv4ma+a4d?L6@!oectEB3I5m7pdgL#($f3?f!e&sIo75eLhw^tC zv^beh-V7=uWGh=+-m%}N4gNny9Us46d4l$MuA*>fNFhl}AfBCbvc=Cze0)bw|J zrjluBcnMgmoWtF7#5Z@orx6eBAE{e%o}=FszxJJQMl^jjZ@<7Cv%!h{P@n5*;dqa6o0E(WUs^r7;Sx=fZo|kkBKFFrXGS-oH}wYIT_A8_ zj8E-1I{e*5$GE$FuM!Dc@#$QspquhS1Et>PQtEBv$Bm`R(*l(w^vOT66(y0uFOw0= zinfhg))U9c;=vr_Xmys8>q54n^*J8N718o<GnnDwtVOz%afM37_CV6iHMlyt@S?M2p}S)6o(~lqGB@I=e(C#-r-y+ zdW^SY{E+H1=H`m!om(}YG#_fPdCcWPlNDYJN(z*&e|sVt#s-7Ctwk)1>3M)*@UkII zX7lVgM;|lS4?U&jDVsG#p0KB&XX_c#eBx%icSx!rfY28&wWo@T*7t;HqDj|WkM%ah zaM|p_0V`teLi4a250vW|Ck;y*gUF{Aap>I;HZ|?TiU8tDIwq!Ec?(AEZ*}T*muQl& z{+?%!65b^UJ%4dIYtQ0(Ld4uqYT16*L~u+=XzCSwv_TsWS*csse~JE@YkLq!hb0yU zPOq~S+_-g-EbkND4OiC2S6;1-?rW%ApDFGw$spaeCEKVzG&(zZ;dxebcD3}mKoh@2 z%!tKp;S75H@%N{?eKsD9@5E7$ck>>($QdP%xmUiv-lBr>#L01V?pGhq8f)Q=!EUDO zL3bVCOjt1J(ChrMufEx(CCAZKSO0`HzmU-$w{YVeC!?{XEPC*>mLzom4AXx8==AQO zR;tVJaE@%#H}##~S!LuY^8+xA5Z&Z_keeZ&dSo!6ht#*7%Q@g`0%&~bS z{Ah5!O368lBHDLSWRj!fjajFwll#LDRvamr+N6q4fKI2>+Dbw;hvzz4QZLV2Zb|R7 zKrlB~7DDAVOE`GPi;?2#&Owb!au?G}9W_;}5Tn)d?yW`#u4azf^^^U&s{@4NZ=TF* zkO|b^Z?Yo;Y37SDK1x0kk3-p^0xXf^j{b>nRJXJV8ehk1Bn8HP4c#bwN;y`_62h)t zT~=*gd%VjYBGM7MKbu;wUd$np{zR0t8$M(vUzUtpTD)>=Uw6i9O0%tyOJ?HzJb60%5hb$)?J{{k~)2~^i7NyeEgb& zg8gvl?^fcGhJH<&A^bx;r#S4%XtDBkY|n+D_T*N~{9@aM3OBb&nUOrk0^W8h+O*p* z;$7Vn``K*WVb_y}u_+0E*ECciRky|<_UKJasFD^?Gc1oj4A^*g>vvDmIaN)>TlTYc z%R%*O#=*;2Vx**p+V?V?Cr9_xepo0>MdQdGw0;*J;ztv^;C;eUbUC*md}2)WV;_OqY1Wmt5sw;qlwrwZEAEcRPo+@i|;KswkA-c zICqqRFf+c;>t}KsntD6K8B^;ZqUXhG2Qi$No381oi(oCX)b)w z#wpuk`9LHr{XW`b$tH;!!G`@83vVf3ix1xC-R|pV8a~?XY>GC*IH&Cq)UAC}yvFoQ zaLUYaS13qNbit!DByldrz{7S{(cUdt`Vwp(#+i9j?F5&zfkPFlr$y|R?LW1&p4nXU z{%Ewb^xOgSU@_k{)}vaT#s$M{HpFge!B_XV?KCdk`9YirYIryw+Zk-Q9lD^OVzdg! zx2LDZJ3H)WVJ4b)PF3@6D=DDgSGV=t{FQe?)Q@A20CqjMam!}q5$h|Jv|0+Og4Z{9)Q=lZERCfQGwffcw!=oouw#p zc#VaHh3?xk$+Vm}G|qi=h>0) zJu|C3U+jA$pDmb|X~!S0Pi!ObhXe|q$7VrlO~)?sh}-d6DN0KOFyU;;sO9VjHElgG zA4ll|zkK;3(7w2^z-2op4KzrXolf525(^sWbCCvIN$B1A!!K7%GOhwPx@NcK=RaaB zS`wAN;)1fNW@>V?YkGtbDHB91v?QZ>kbU{dYUAkQQSa=DNreh+b7*1Ra7FRZNdCW3%&Iw--QzfrTauGp4l!xlhM=e=~JINp@9*uLp0^*%h02o7>t$pB_*@E&9UB^s`L*{gX#*UG@9H6a9;~7-%;`XT;tUNz9`!~?pqX$TF0xKQKqR9YSmM9zpns@;hw=5{P zj=Hz6ual$R_Sa%keyxG%nj((1mB|7z=kvzvZhSJ#-}iXP4zZM1jTLO{bb>U8n2Elo zlo?We|7gS<#5`rNVpX@-C~nn3sJ}$>>vF(&{TtiC?2(GnB?V)3=9~K!T}P)g+oD#V z+{bs~Y?F1$tm{`V$}N(k<;8Wr%-Sv2qjVVYFg`pQ$wKu`h6d{UiwYSLfONx{10nV- z-_W%>C8<cl$B!5TcM46!4h8fKRZ8v09-TR*r%uT8<Ntxc`xmI$Pc)V!-@P){0qN}6qI~iCk2!KQ5HKb~-x}1r2)`<- z6c!dvJYKKNop1nOXZ2D`t?UvgcYv>L#+Cb$)T`4m0aPP4%M}xZ4gNfkxyyKX)ErlMaKG%B0(=mvB-CDjSV!Gb zhe9(eRF4c^zC;x!K(MR75Y50S|14mNXl&xQ>I4!+n~Y$FuyMFF)J{Gp^J*M zaP9>!1P&JiXiL6Zvo~Uv+iyYxtr;qv2CH|&;4cDs3*)uCQ2zs!rlJ1%of-AP3Vas) z|Lb4X#xFGW5i}xo%l2{4TX(ZRee!``NK^I#X5;ivbFS=`^Z(jN$`IKXvRc~teO{V% zPG8E1RhRWxNeNxdz#y&l1Kd*j{)fm&l8YB#I8vqOQK^R1s%3ut8Z_G+dWnq8uk$5$ zWx`5S-|{uEKFX~F#V}n!3U`j%?rv(n3H|CW~9ASy8|W zQk)=F!~!~syj=q0U0$a`MQCM+Y&sY$R;S}lDpUh(t6Hm0UJF(vfKWh~C}J&!Kw(9p zl1b}Efc>u@_I2OaFHM`?+~%Hpo^$Rw&-42^IDA5<8_U&|z8z`rzuxq8mcJwGk2pS( zX<@kkX(?$aRPwO@%1MLgLi4oSf>-0rgIMroV?ffkGRNEmZ?|YByPBu$DXSq~>Kf-& zME{WV>%WIc9=4t48k4`iMHBwVh3a*46U;@Ww=EFH#>S~2nYAe=r>9-N8fHY^Nkt_H z9vYuS72?O(ula;j%`2SB?tg=A%((tPbtJ35`73TT)B4}PPgqf<7UEq*p)jD#Y# z8eZhH!Cg;nlZ6vRra>(TiHz(eZ7DCMjmPmZ2M+O_Q4&Kgyju)M$EoWGz)3(o!N2n@*uX!E#Topx7%8kB^?EH-6{6@1;SNqtBt6$L;&$!WNGvwsNofV{ z{`=UTH=|PDNxDi(jyDDW6|}~R`gUUdN-8$#hSPu)Ym0AG394>Z*mn0!=yB04H+@L2wA7thh8sJT1d=+N~$OM5)BXKYGKOSAP8pnc7Dj0}R*9s#Qz^Z|8EO=yiN9$Jo^ z%^*VdIU@%}r&^db^pk%vEE;31X z&Kf&!tn-l+1za0cvxY%H@@!IeKlg+n|FPGJBSPBNQ$P(4$^{v7Eiavy^^J;EudygC zin>^zs>o>BX3VfalK%z_W`-^0+F{8fY!X2Qk1G1>gbK0@2}b5W%j<^uZZE#yecE&t z52AHpSybKN-~qS?X3prVwjcFgyt%p_bbI*YL2x_BcPKlM*OeU4mo&`seTH(V=e_qrv{xOTy5H!~DWpuwG9<*r~nvN>ZP3Uxi zsQA!owWN?o4QawaoDLpyfEDFfk{alVe>J$3{F10KS0I%VL{#xRWJ|*UHbf3AyQh- zqY{J1yV=~CTa1|t|JBp>D!~{|^?`?AE)jVl&ta$sJ?~<4b+}(Zz(xm$Vr1!%0}zaW z@JrOz)>cGUj=*{HVGTz}M?E+KI5TCy{u1{y1VeZEHrY`~yeR9vUM+jNyO#qA|2u&8 z$p5dvoD=Z;8lVFJTPuK$$;#65-g{KfxP-@uR#=YMd^BSU-eEE!^z1F|KN6(Hn;}8 zvQVK=SXo;iOiWCyK<8iQ!M~1ajt41MLPTet)c+>7LkuEA8uIa?bUGbe66*@bTWtD} zk|RWdSI0Py2G1f37LSbdq0G+1h4HlHf`__ +Kalman Filter with Speed Scale Factor Correction +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + +.. image:: ekf_with_velocity_correction_1_0.png + :width: 600px + +This is a Extended kalman filter (EKF) localization with velocity correction. + +This is for correcting the vehicle speed measured with scale factor errors due to factors such as wheel wear. + +Code: `PythonRobotics/extended_kalman_ekf_with_velocity_correctionfilter.py +AtsushiSakai/PythonRobotics `__ + Filter design ~~~~~~~~~~~~~ +Position Estimation Kalman Filter +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + In this simulation, the robot has a state vector includes 4 states at time :math:`t`. @@ -61,9 +82,28 @@ In the code, “observation” function generates the input and observation vector with noise `code `__ +Kalman Filter with Speed Scale Factor Correction +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +In this simulation, the robot has a state vector includes 5 states at +time :math:`t`. + +.. math:: \textbf{x}_t=[x_t, y_t, \phi_t, v_t, s_t] + +x, y are a 2D x-y position, :math:`\phi` is orientation, v is +velocity, and s is a scale factor of velocity. + +In the code, “xEst” means the state vector. +`code `__ + +The rest is the same as the Position Estimation Kalman Filter. + Motion Model ~~~~~~~~~~~~ +Position Estimation Kalman Filter +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + The robot model is .. math:: \dot{x} = v \cos(\phi) @@ -97,9 +137,50 @@ Its Jacobian matrix is :math:`\begin{equation*}  = \begin{bmatrix} 1& 0 & -v \sin(\phi) \Delta t & \cos(\phi) \Delta t\\ 0 & 1 & v \cos(\phi) \Delta t & \sin(\phi) \Delta t\\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix} \end{equation*}` + +Kalman Filter with Speed Scale Factor Correction +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +The robot model is + +.. math:: \dot{x} = v s \cos(\phi) + +.. math:: \dot{y} = v s \sin(\phi) + +.. math:: \dot{\phi} = \omega + +So, the motion model is + +.. math:: \textbf{x}_{t+1} = f(\textbf{x}_t, \textbf{u}_t) = F\textbf{x}_t+B\textbf{u}_t + +where + +:math:`\begin{equation*} F= \begin{bmatrix} 1 & 0 & 0 & 0 & 0\\ 0 & 1 & 0 & 0 & 0\\ 0 & 0 & 1 & 0 & 0\\ 0 & 0 & 0 & 0 & 0\\ 0 & 0 & 0 & 0 & 1\\ \end{bmatrix} \end{equation*}` + +:math:`\begin{equation*} B= \begin{bmatrix} cos(\phi) \Delta t s & 0\\ sin(\phi) \Delta t s & 0\\ 0 & \Delta t\\ 1 & 0\\ 0 & 0\\ \end{bmatrix} \end{equation*}` + +:math:`\Delta t` is a time interval. + +This is implemented at +`code `__ + +The motion function is that + +:math:`\begin{equation*} \begin{bmatrix} x' \\ y' \\ w' \\ v' \end{bmatrix} = f(\textbf{x}, \textbf{u}) = \begin{bmatrix} x + v s \cos(\phi)\Delta t \\ y + v s \sin(\phi)\Delta t \\ \phi + \omega \Delta t \\ v \end{bmatrix} \end{equation*}` + +Its Jacobian matrix is + +:math:`\begin{equation*} J_f = \begin{bmatrix} \frac{\partial x'}{\partial x}& \frac{\partial x'}{\partial y} & \frac{\partial x'}{\partial \phi} & \frac{\partial x'}{\partial v} & \frac{\partial x'}{\partial s}\\ \frac{\partial y'}{\partial x}& \frac{\partial y'}{\partial y} & \frac{\partial y'}{\partial \phi} & \frac{\partial y'}{\partial v} & \frac{\partial y'}{\partial s}\\ \frac{\partial \phi'}{\partial x}& \frac{\partial \phi'}{\partial y} & \frac{\partial \phi'}{\partial \phi} & \frac{\partial \phi'}{\partial v} & \frac{\partial \phi'}{\partial s}\\ \frac{\partial v'}{\partial x}& \frac{\partial v'}{\partial y} & \frac{\partial v'}{\partial \phi} & \frac{\partial v'}{\partial v} & \frac{\partial v'}{\partial s} \\ \frac{\partial s'}{\partial x}& \frac{\partial s'}{\partial y} & \frac{\partial s'}{\partial \phi} & \frac{\partial s'}{\partial v} & \frac{\partial s'}{\partial s} \end{bmatrix} \end{equation*}` + +:math:`\begin{equation*}  = \begin{bmatrix} 1& 0 & -v s \sin(\phi) \Delta t & s \cos(\phi) \Delta t & \cos(\phi) v \Delta t\\ 0 & 1 & v s \cos(\phi) \Delta t & s \sin(\phi) \Delta t & v \sin(\phi) \Delta t\\ 0 & 0 & 1 & 0 & 0 \\ 0 & 0 & 0 & 1 & 0 \end{bmatrix} \end{equation*}` + + Observation Model ~~~~~~~~~~~~~~~~~ +Position Estimation Kalman Filter +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + The robot can get x-y position infomation from GPS. So GPS Observation model is @@ -120,6 +201,30 @@ Its Jacobian matrix is :math:`\begin{equation*}  = \begin{bmatrix} 1& 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ \end{bmatrix} \end{equation*}` +Kalman Filter with Speed Scale Factor Correction +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +The robot can get x-y position infomation from GPS. + +So GPS Observation model is + +.. math:: \textbf{z}_{t} = g(\textbf{x}_t) = H \textbf{x}_t + +where + +:math:`\begin{equation*} H = \begin{bmatrix} 1 & 0 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 & 0 \\ \end{bmatrix} \end{equation*}` + +The observation function states that + +:math:`\begin{equation*} \begin{bmatrix} x' \\ y' \end{bmatrix} = g(\textbf{x}) = \begin{bmatrix} x \\ y \end{bmatrix} \end{equation*}` + +Its Jacobian matrix is + +:math:`\begin{equation*} J_g = \begin{bmatrix} \frac{\partial x'}{\partial x} & \frac{\partial x'}{\partial y} & \frac{\partial x'}{\partial \phi} & \frac{\partial x'}{\partial v} & \frac{\partial x'}{\partial s}\\ \frac{\partial y'}{\partial x}& \frac{\partial y'}{\partial y} & \frac{\partial y'}{\partial \phi} & \frac{\partial y'}{ \partial v} & \frac{\partial y'}{ \partial s}\\ \end{bmatrix} \end{equation*}` + +:math:`\begin{equation*}  = \begin{bmatrix} 1& 0 & 0 & 0 & 0\\ 0 & 1 & 0 & 0 & 0\\ \end{bmatrix} \end{equation*}` + + Extended Kalman Filter ~~~~~~~~~~~~~~~~~~~~~~ From 13137952eeee39438bf6f0eb030527ab804a9481 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 23 Jan 2024 08:07:58 +0900 Subject: [PATCH 703/940] Bump scipy from 1.11.4 to 1.12.0 in /requirements (#969) Bumps [scipy](https://github.com/scipy/scipy) from 1.11.4 to 1.12.0. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.11.4...v1.12.0) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 127b89682d..5af5be1794 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.26.3 -scipy == 1.11.4 +scipy == 1.12.0 matplotlib == 3.8.2 cvxpy == 1.4.1 pytest == 7.4.4 # For unit test From ae0676bfc0b5548ab643c8db73959edc5e68a324 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 23 Jan 2024 20:18:49 +0900 Subject: [PATCH 704/940] Bump ruff from 0.1.13 to 0.1.14 in /requirements (#971) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.13 to 0.1.14. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.13...v0.1.14) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 5af5be1794..5848b32aad 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.1 pytest == 7.4.4 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test -ruff == 0.1.13 # For unit test +ruff == 0.1.14 # For unit test From 73d1189e824c38af70f724d3ba5b0322e55f142d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 23 Jan 2024 20:40:15 +0900 Subject: [PATCH 705/940] Bump cvxpy from 1.4.1 to 1.4.2 in /requirements (#970) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.4.1 to 1.4.2. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.4.1...v1.4.2) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 5848b32aad..ceee1d03c0 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.26.3 scipy == 1.12.0 matplotlib == 3.8.2 -cvxpy == 1.4.1 +cvxpy == 1.4.2 pytest == 7.4.4 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test From 0874d5023cc79cd2d9ad535f6d008c749ce4d257 Mon Sep 17 00:00:00 2001 From: Yi-Chen Zhang Date: Sat, 27 Jan 2024 23:59:02 -0500 Subject: [PATCH 706/940] Fix predict covariance (#973) * Fix predict covariance * Remove trailing whitespace and unused return parameters --- SLAM/EKFSLAM/ekf_slam.py | 9 +- docs/modules/slam/ekf_slam/ekf_slam_main.rst | 181 +++++++++---------- 2 files changed, 91 insertions(+), 99 deletions(-) diff --git a/SLAM/EKFSLAM/ekf_slam.py b/SLAM/EKFSLAM/ekf_slam.py index a624e8765b..5c4417d7c3 100644 --- a/SLAM/EKFSLAM/ekf_slam.py +++ b/SLAM/EKFSLAM/ekf_slam.py @@ -29,10 +29,9 @@ def ekf_slam(xEst, PEst, u, z): # Predict - S = STATE_SIZE - G, Fx = jacob_motion(xEst[0:S], u) - xEst[0:S] = motion_model(xEst[0:S], u) - PEst[0:S, 0:S] = G.T @ PEst[0:S, 0:S] @ G + Fx.T @ Cx @ Fx + G, Fx = jacob_motion(xEst, u) + xEst[0:STATE_SIZE] = motion_model(xEst[0:STATE_SIZE], u) + PEst = G.T @ PEst @ G + Fx.T @ Cx @ Fx initP = np.eye(2) # Update @@ -120,7 +119,7 @@ def jacob_motion(x, u): [0.0, 0.0, DT * u[0, 0] * math.cos(x[2, 0])], [0.0, 0.0, 0.0]], dtype=float) - G = np.eye(STATE_SIZE) + Fx.T @ jF @ Fx + G = np.eye(len(x)) + Fx.T @ jF @ Fx return G, Fx, diff --git a/docs/modules/slam/ekf_slam/ekf_slam_main.rst b/docs/modules/slam/ekf_slam/ekf_slam_main.rst index 70a7d131ae..b27971225e 100644 --- a/docs/modules/slam/ekf_slam/ekf_slam_main.rst +++ b/docs/modules/slam/ekf_slam/ekf_slam_main.rst @@ -63,27 +63,27 @@ Take care to note the difference between :math:`X` (state) and :math:`x` original author: Atsushi Sakai (@Atsushi_twi) notebook author: Andrew Tu (drewtu2) """ - + import math import numpy as np %matplotlib notebook import matplotlib.pyplot as plt - - + + # EKF state covariance Cx = np.diag([0.5, 0.5, np.deg2rad(30.0)])**2 # Change in covariance - + # Simulation parameter Qsim = np.diag([0.2, np.deg2rad(1.0)])**2 # Sensor Noise Rsim = np.diag([1.0, np.deg2rad(10.0)])**2 # Process Noise - + DT = 0.1 # time tick [s] SIM_TIME = 50.0 # simulation time [s] MAX_RANGE = 20.0 # maximum observation range M_DIST_TH = 2.0 # Threshold of Mahalanobis distance for data association. STATE_SIZE = 3 # State size [x,y,yaw] LM_SIZE = 2 # LM state size [x,y] - + show_animation = True Algorithm Walk through @@ -97,23 +97,22 @@ the estimated state and measurements def ekf_slam(xEst, PEst, u, z): """ - Performs an iteration of EKF SLAM from the available information. - + Performs an iteration of EKF SLAM from the available information. + :param xEst: the belief in last position :param PEst: the uncertainty in last position - :param u: the control function applied to the last position + :param u: the control function applied to the last position :param z: measurements at this step :returns: the next estimated position and associated covariance """ - S = STATE_SIZE - + # Predict - xEst, PEst, G, Fx = predict(xEst, PEst, u) + xEst, PEst = predict(xEst, PEst, u) initP = np.eye(2) - + # Update - xEst, PEst = update(xEst, PEst, u, z, initP) - + xEst, PEst = update(xEst, PEst, z, initP) + return xEst, PEst @@ -170,26 +169,25 @@ the landmarks. def predict(xEst, PEst, u): """ Performs the prediction step of EKF SLAM - + :param xEst: nx1 state vector :param PEst: nxn covariance matrix :param u: 2x1 control vector :returns: predicted state vector, predicted covariance, jacobian of control vector, transition fx """ - S = STATE_SIZE - G, Fx = jacob_motion(xEst[0:S], u) - xEst[0:S] = motion_model(xEst[0:S], u) + G, Fx = jacob_motion(xEst, u) + xEst[0:STATE_SIZE] = motion_model(xEst[0:STATE_SIZE], u) # Fx is an an identity matrix of size (STATE_SIZE) # sigma = G*sigma*G.T + Noise - PEst[0:S, 0:S] = G.T @ PEst[0:S, 0:S] @ G + Fx.T @ Cx @ Fx - return xEst, PEst, G, Fx + PEst = G.T @ PEst @ G + Fx.T @ Cx @ Fx + return xEst, PEst .. code:: ipython3 def motion_model(x, u): """ Computes the motion model based on current state and input function. - + :param x: 3x1 pose estimation :param u: 2x1 control input [v; w] :returns: the resulting state after the control function is applied @@ -197,11 +195,11 @@ the landmarks. F = np.array([[1.0, 0, 0], [0, 1.0, 0], [0, 0, 1.0]]) - + B = np.array([[DT * math.cos(x[2, 0]), 0], [DT * math.sin(x[2, 0]), 0], [0.0, DT]]) - + x = (F @ x) + (B @ u) return x @@ -261,22 +259,21 @@ the changing uncertainty. .. code:: ipython3 - def update(xEst, PEst, u, z, initP): + def update(xEst, PEst, z, initP): """ Performs the update step of EKF SLAM - + :param xEst: nx1 the predicted pose of the system and the pose of the landmarks :param PEst: nxn the predicted covariance - :param u: 2x1 the control function :param z: the measurements read at new position :param initP: 2x2 an identity matrix acting as the initial covariance :returns: the updated state and covariance for the system """ for iz in range(len(z[:, 0])): # for each observation minid = search_correspond_LM_ID(xEst, PEst, z[iz, 0:2]) # associate to a known landmark - + nLM = calc_n_LM(xEst) # number of landmarks we currently know about - + if minid == nLM: # Landmark is a NEW landmark print("New LM") # Extend state and covariance matrix @@ -285,14 +282,14 @@ the changing uncertainty. np.hstack((np.zeros((LM_SIZE, len(xEst))), initP)))) xEst = xAug PEst = PAug - + lm = get_LM_Pos_from_state(xEst, minid) y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], minid) - + K = (PEst @ H.T) @ np.linalg.inv(S) # Calculate Kalman Gain xEst = xEst + (K @ y) PEst = (np.eye(len(xEst)) - (K @ H)) @ PEst - + xEst[2] = pi_2_pi(xEst[2]) return xEst, PEst @@ -302,7 +299,7 @@ the changing uncertainty. def calc_innovation(lm, xEst, PEst, z, LMid): """ Calculates the innovation based on expected position and landmark position - + :param lm: landmark position :param xEst: estimated position/state :param PEst: estimated covariance @@ -315,19 +312,19 @@ the changing uncertainty. zangle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0] zp = np.array([[math.sqrt(q), pi_2_pi(zangle)]]) # zp is the expected measurement based on xEst and the expected landmark position - + y = (z - zp).T # y = innovation y[1] = pi_2_pi(y[1]) - + H = jacobH(q, delta, xEst, LMid + 1) S = H @ PEst @ H.T + Cx[0:2, 0:2] - + return y, S, H - + def jacobH(q, delta, x, i): """ Calculates the jacobian of the measurement function - + :param q: the range from the system pose to the landmark :param delta: the difference between a landmark position and the estimated system position :param x: the state, including the estimated system position @@ -337,17 +334,17 @@ the changing uncertainty. sq = math.sqrt(q) G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]], [delta[1, 0], - delta[0, 0], - q, - delta[1, 0], delta[0, 0]]]) - + G = G / q nLM = calc_n_LM(x) F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM)))) F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))), np.eye(2), np.zeros((2, 2 * nLM - 2 * i)))) - + F = np.vstack((F1, F2)) - + H = G @ F - + return H Observation Step @@ -370,17 +367,17 @@ reckoning and control functions are passed along here as well. :param xd: the current noisy estimate of the system :param u: the current control input :param RFID: the true position of the landmarks - - :returns: Computes the true position, observations, dead reckoning (noisy) position, + + :returns: Computes the true position, observations, dead reckoning (noisy) position, and noisy control function """ xTrue = motion_model(xTrue, u) - + # add noise to gps x-y z = np.zeros((0, 3)) - + for i in range(len(RFID[:, 0])): # Test all beacons, only add the ones we can see (within MAX_RANGE) - + dx = RFID[i, 0] - xTrue[0, 0] dy = RFID[i, 1] - xTrue[1, 0] d = math.sqrt(dx**2 + dy**2) @@ -390,12 +387,12 @@ reckoning and control functions are passed along here as well. anglen = angle + np.random.randn() * Qsim[1, 1] # add noise zi = np.array([dn, anglen, i]) z = np.vstack((z, zi)) - + # add noise to input ud = np.array([[ u[0, 0] + np.random.randn() * Rsim[0, 0], u[1, 0] + np.random.randn() * Rsim[1, 1]]]).T - + xd = motion_model(xd, ud) return xTrue, z, xd, ud @@ -409,32 +406,30 @@ reckoning and control functions are passed along here as well. """ n = int((len(x) - STATE_SIZE) / LM_SIZE) return n - - + + def jacob_motion(x, u): """ - Calculates the jacobian of motion model. - + Calculates the jacobian of motion model. + :param x: The state, including the estimated position of the system :param u: The control function :returns: G: Jacobian Fx: STATE_SIZE x (STATE_SIZE + 2 * num_landmarks) matrix where the left side is an identity matrix """ - + # [eye(3) [0 x y; 0 x y; 0 x y]] Fx = np.hstack((np.eye(STATE_SIZE), np.zeros( (STATE_SIZE, LM_SIZE * calc_n_LM(x))))) - + jF = np.array([[0.0, 0.0, -DT * u[0] * math.sin(x[2, 0])], [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])], [0.0, 0.0, 0.0]],dtype=object) - + G = np.eye(STATE_SIZE) + Fx.T @ jF @ Fx if calc_n_LM(x) > 0: print(Fx.shape) return G, Fx, - - .. code:: ipython3 @@ -442,68 +437,68 @@ reckoning and control functions are passed along here as well. def calc_LM_Pos(x, z): """ Calculates the pose in the world coordinate frame of a landmark at the given measurement. - + :param x: [x; y; theta] :param z: [range; bearing] :returns: [x; y] for given measurement """ zp = np.zeros((2, 1)) - + zp[0, 0] = x[0, 0] + z[0] * math.cos(x[2, 0] + z[1]) zp[1, 0] = x[1, 0] + z[0] * math.sin(x[2, 0] + z[1]) #zp[0, 0] = x[0, 0] + z[0, 0] * math.cos(x[2, 0] + z[0, 1]) #zp[1, 0] = x[1, 0] + z[0, 0] * math.sin(x[2, 0] + z[0, 1]) - + return zp - - + + def get_LM_Pos_from_state(x, ind): """ Returns the position of a given landmark - + :param x: The state containing all landmark positions :param ind: landmark id :returns: The position of the landmark """ lm = x[STATE_SIZE + LM_SIZE * ind: STATE_SIZE + LM_SIZE * (ind + 1), :] - + return lm - - + + def search_correspond_LM_ID(xAug, PAug, zi): """ Landmark association with Mahalanobis distance. - - If this landmark is at least M_DIST_TH units away from all known landmarks, + + If this landmark is at least M_DIST_TH units away from all known landmarks, it is a NEW landmark. - + :param xAug: The estimated state :param PAug: The estimated covariance :param zi: the read measurements of specific landmark :returns: landmark id """ - + nLM = calc_n_LM(xAug) - + mdist = [] - + for i in range(nLM): lm = get_LM_Pos_from_state(xAug, i) y, S, H = calc_innovation(lm, xAug, PAug, zi, i) mdist.append(y.T @ np.linalg.inv(S) @ y) - + mdist.append(M_DIST_TH) # new landmark - + minid = mdist.index(min(mdist)) - + return minid - + def calc_input(): v = 1.0 # [m/s] yawrate = 0.1 # [rad/s] u = np.array([[v, yawrate]]).T return u - + def pi_2_pi(angle): return (angle + math.pi) % (2 * math.pi) - math.pi @@ -511,53 +506,53 @@ reckoning and control functions are passed along here as well. def main(): print(" start!!") - + time = 0.0 - + # RFID positions [x, y] RFID = np.array([[10.0, -2.0], [15.0, 10.0], [3.0, 15.0], [-5.0, 20.0]]) - + # State Vector [x y yaw v]' xEst = np.zeros((STATE_SIZE, 1)) xTrue = np.zeros((STATE_SIZE, 1)) PEst = np.eye(STATE_SIZE) - + xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning - + # history hxEst = xEst hxTrue = xTrue hxDR = xTrue - + while SIM_TIME >= time: time += DT u = calc_input() - + xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID) - + xEst, PEst = ekf_slam(xEst, PEst, ud, z) - + x_state = xEst[0:STATE_SIZE] - + # store data history hxEst = np.hstack((hxEst, x_state)) hxDR = np.hstack((hxDR, xDR)) hxTrue = np.hstack((hxTrue, xTrue)) - + if show_animation: # pragma: no cover plt.cla() - + plt.plot(RFID[:, 0], RFID[:, 1], "*k") plt.plot(xEst[0], xEst[1], ".r") - + # plot landmark for i in range(calc_n_LM(xEst)): plt.plot(xEst[STATE_SIZE + i * 2], xEst[STATE_SIZE + i * 2 + 1], "xg") - + plt.plot(hxTrue[0, :], hxTrue[1, :], "-b") plt.plot(hxDR[0, :], @@ -587,5 +582,3 @@ References: ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - `PROBABILISTIC ROBOTICS `_ - - From 6326e8c21205ca9c2d8e809c2dc2eaab60940bf0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 30 Jan 2024 20:19:54 +0900 Subject: [PATCH 707/940] Bump pytest from 7.4.4 to 8.0.0 in /requirements (#974) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.4.4 to 8.0.0. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.4.4...8.0.0) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index ceee1d03c0..f0729fb76e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.26.3 scipy == 1.12.0 matplotlib == 3.8.2 cvxpy == 1.4.2 -pytest == 7.4.4 # For unit test +pytest == 8.0.0 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test ruff == 0.1.14 # For unit test From bd253e81060c6a11a944016706bd1d87ef72bded Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 6 Feb 2024 19:07:36 +0900 Subject: [PATCH 708/940] Bump ruff from 0.1.14 to 0.2.0 in /requirements (#975) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.1.14 to 0.2.0. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.1.14...v0.2.0) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f0729fb76e..1d2072b01e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.2 pytest == 8.0.0 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test -ruff == 0.1.14 # For unit test +ruff == 0.2.0 # For unit test From e4ddf10ad651dffa7c04f344cd13e878637fb8ca Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 13 Feb 2024 20:21:31 +0900 Subject: [PATCH 709/940] Bump larsoner/circleci-artifacts-redirector-action from 0.3.1 to 1.0.0 (#976) Bumps [larsoner/circleci-artifacts-redirector-action](https://github.com/larsoner/circleci-artifacts-redirector-action) from 0.3.1 to 1.0.0. - [Release notes](https://github.com/larsoner/circleci-artifacts-redirector-action/releases) - [Commits](https://github.com/larsoner/circleci-artifacts-redirector-action/compare/0.3.1...v1.0.0) --- updated-dependencies: - dependency-name: larsoner/circleci-artifacts-redirector-action dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/circleci-artifacts-redirector.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/circleci-artifacts-redirector.yml b/.github/workflows/circleci-artifacts-redirector.yml index 149a087a5d..504a3a1004 100644 --- a/.github/workflows/circleci-artifacts-redirector.yml +++ b/.github/workflows/circleci-artifacts-redirector.yml @@ -6,7 +6,7 @@ jobs: name: Run CircleCI artifacts redirector!! steps: - name: run-circleci-artifacts-redirector - uses: larsoner/circleci-artifacts-redirector-action@0.3.1 + uses: larsoner/circleci-artifacts-redirector-action@v1.0.0 with: repo-token: ${{ secrets.GITHUB_TOKEN }} artifact-path: 0/html/index.html From 0dcb68a8020a5dd8f5cad53f69dffbcca3f03273 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 13 Feb 2024 21:49:03 +0900 Subject: [PATCH 710/940] Bump numpy from 1.26.3 to 1.26.4 in /requirements (#977) Bumps [numpy](https://github.com/numpy/numpy) from 1.26.3 to 1.26.4. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.26.3...v1.26.4) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 1d2072b01e..dd5adf0409 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.26.3 +numpy == 1.26.4 scipy == 1.12.0 matplotlib == 3.8.2 cvxpy == 1.4.2 From b1bdff203c483533c32a7357a124945b74d88aa1 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 13 Feb 2024 22:57:15 +0900 Subject: [PATCH 711/940] Bump ruff from 0.2.0 to 0.2.1 in /requirements (#978) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.2.0 to 0.2.1. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.2.0...v0.2.1) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index dd5adf0409..6b65ae5b8c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.2 pytest == 8.0.0 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test -ruff == 0.2.0 # For unit test +ruff == 0.2.1 # For unit test From e6215ace2e62c350dcc174641fb6804d3bfd4d55 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 20 Feb 2024 20:43:17 +0900 Subject: [PATCH 712/940] Bump matplotlib from 3.8.2 to 3.8.3 in /requirements (#979) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.8.2 to 3.8.3. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.8.2...v3.8.3) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 6b65ae5b8c..be43a14788 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.26.4 scipy == 1.12.0 -matplotlib == 3.8.2 +matplotlib == 3.8.3 cvxpy == 1.4.2 pytest == 8.0.0 # For unit test pytest-xdist == 3.5.0 # For unit test From 47eb01f88f0083929f1948620b313019e44b96f1 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 20 Feb 2024 20:44:06 +0900 Subject: [PATCH 713/940] Bump ruff from 0.2.1 to 0.2.2 in /requirements (#980) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.2.1 to 0.2.2. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.2.1...v0.2.2) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index be43a14788..e18459efdb 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.2 pytest == 8.0.0 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test -ruff == 0.2.1 # For unit test +ruff == 0.2.2 # For unit test From bf6acf3e31934dab4a496190ca74191cee672ea4 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 20 Feb 2024 21:34:06 +0900 Subject: [PATCH 714/940] Bump pytest from 8.0.0 to 8.0.1 in /requirements (#981) Bumps [pytest](https://github.com/pytest-dev/pytest) from 8.0.0 to 8.0.1. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/8.0.0...8.0.1) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e18459efdb..e40542015f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.26.4 scipy == 1.12.0 matplotlib == 3.8.3 cvxpy == 1.4.2 -pytest == 8.0.0 # For unit test +pytest == 8.0.1 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test ruff == 0.2.2 # For unit test From e2412a6667d12a8b640f2dc5c6e15e22b1e36753 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 24 Feb 2024 18:26:59 +0900 Subject: [PATCH 715/940] Update circleci-artifacts-redirector.yml (#983) * Update circleci-artifacts-redirector.yml * Update circleci-artifacts-redirector.yml * Update circleci-artifacts-redirector.yml --- .github/workflows/circleci-artifacts-redirector.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/circleci-artifacts-redirector.yml b/.github/workflows/circleci-artifacts-redirector.yml index 504a3a1004..78eb479aa1 100644 --- a/.github/workflows/circleci-artifacts-redirector.yml +++ b/.github/workflows/circleci-artifacts-redirector.yml @@ -9,5 +9,6 @@ jobs: uses: larsoner/circleci-artifacts-redirector-action@v1.0.0 with: repo-token: ${{ secrets.GITHUB_TOKEN }} + api-token: ${{ secrets.CIRCLECI_TOKEN }} artifact-path: 0/html/index.html circleci-jobs: build_doc From 6e743ef31e8f99a5e78bbb11343228d433693034 Mon Sep 17 00:00:00 2001 From: William L Thomson Jr Date: Sat, 24 Feb 2024 04:35:13 -0500 Subject: [PATCH 716/940] PathPlanning/InformedRRTStar/informed_rrt_star.py: Fix hard coded graph axis (#982) - Use self.min_rand, self.max_rand variable values in place of -2, 15 --- PathPlanning/InformedRRTStar/informed_rrt_star.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index b6f9d234dd..c37326e490 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -293,7 +293,7 @@ def draw_graph(self, x_center=None, c_best=None, c_min=None, e_theta=None, plt.plot(self.start.x, self.start.y, "xr") plt.plot(self.goal.x, self.goal.y, "xr") - plt.axis([-2, 15, -2, 15]) + plt.axis([self.min_rand, self.max_rand, self.min_rand, self.max_rand]) plt.grid(True) plt.pause(0.01) From ffd28c2d635975ba9294c6fa6603a211d074ef1b Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 27 Feb 2024 20:27:30 +0900 Subject: [PATCH 717/940] Bump pytest from 8.0.1 to 8.0.2 in /requirements (#984) Bumps [pytest](https://github.com/pytest-dev/pytest) from 8.0.1 to 8.0.2. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/8.0.1...8.0.2) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e40542015f..b464481003 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.26.4 scipy == 1.12.0 matplotlib == 3.8.3 cvxpy == 1.4.2 -pytest == 8.0.1 # For unit test +pytest == 8.0.2 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test ruff == 0.2.2 # For unit test From 9a22fb34ba4a205b254b8d469d62c73188771bf8 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 6 Mar 2024 08:05:05 +0900 Subject: [PATCH 718/940] Bump ruff from 0.2.2 to 0.3.0 in /requirements (#985) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.2.2 to 0.3.0. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.2.2...v0.3.0) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b464481003..9d8ed2ac33 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.2 pytest == 8.0.2 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test -ruff == 0.2.2 # For unit test +ruff == 0.3.0 # For unit test From 707f12fb363316ab687566a0b9819c2545eb89b8 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 12 Mar 2024 07:47:43 +0900 Subject: [PATCH 719/940] Bump pytest from 8.0.2 to 8.1.1 in /requirements (#986) Bumps [pytest](https://github.com/pytest-dev/pytest) from 8.0.2 to 8.1.1. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/8.0.2...8.1.1) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 9d8ed2ac33..e3eee34e5e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.26.4 scipy == 1.12.0 matplotlib == 3.8.3 cvxpy == 1.4.2 -pytest == 8.0.2 # For unit test +pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test ruff == 0.3.0 # For unit test From 1477c34cc717428ad6ae9b234451e679d8d0bc11 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 12 Mar 2024 12:19:59 +0900 Subject: [PATCH 720/940] Bump ruff from 0.3.0 to 0.3.2 in /requirements (#987) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.3.0 to 0.3.2. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.3.0...v0.3.2) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e3eee34e5e..2cdfeaf126 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.2 pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.8.0 # For unit test -ruff == 0.3.0 # For unit test +ruff == 0.3.2 # For unit test From 655fbc71d9adc324276985693c3cac773791f1f1 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 12 Mar 2024 12:57:17 +0900 Subject: [PATCH 721/940] Bump mypy from 1.8.0 to 1.9.0 in /requirements (#988) Bumps [mypy](https://github.com/python/mypy) from 1.8.0 to 1.9.0. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.8.0...1.9.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 2cdfeaf126..1021562d1c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.8.3 cvxpy == 1.4.2 pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test -mypy == 1.8.0 # For unit test +mypy == 1.9.0 # For unit test ruff == 0.3.2 # For unit test From a79cc374f3eb3f39ae1a82e7738b988c43791595 Mon Sep 17 00:00:00 2001 From: guangwu Date: Wed, 13 Mar 2024 20:20:01 +0800 Subject: [PATCH 722/940] fix: typo (#989) --- Control/move_to_pose/move_to_pose_robot.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Control/move_to_pose/move_to_pose_robot.py b/Control/move_to_pose/move_to_pose_robot.py index d5c51caa12..fe9f0d06b3 100644 --- a/Control/move_to_pose/move_to_pose_robot.py +++ b/Control/move_to_pose/move_to_pose_robot.py @@ -79,9 +79,9 @@ def set_start_target_poses(self, pose_start, pose_target): Parameters ---------- pose_start : (Pose) - Start postion of the robot (see the Pose class) + Start position of the robot (see the Pose class) pose_target : (Pose) - Target postion of the robot (see the Pose class) + Target position of the robot (see the Pose class) """ self.pose_start = copy.copy(pose_start) self.pose_target = pose_target From 1656cab0d229d294ec151ec9d4cbe086b271e1cf Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 14 Mar 2024 22:01:51 +0900 Subject: [PATCH 723/940] Support python 3.12 (#954) * Update Linux_CI.yml * Update MacOS_CI.yml * Update Windows_CI.yml * Delete .lgtm.yml * Update lqr_planner.py * Update lqr_planner.py * Update config.yml * Update environment.yml * Update ruff.toml * Update README.md * Update getting_started_main.rst * Update doc_requirements.txt --- .circleci/config.yml | 2 +- .github/workflows/Linux_CI.yml | 2 +- .github/workflows/MacOS_CI.yml | 4 ++-- .github/workflows/Windows_CI.yml | 4 ++-- .lgtm.yml | 4 ---- README.md | 2 +- docs/getting_started_main.rst | 2 +- requirements/environment.yml | 2 +- ruff.toml | 4 ++-- 9 files changed, 11 insertions(+), 15 deletions(-) delete mode 100644 .lgtm.yml diff --git a/.circleci/config.yml b/.circleci/config.yml index d8f1e89dc4..9f803ece4a 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -6,7 +6,7 @@ orbs: jobs: build_doc: docker: - - image: cimg/python:3.11 + - image: cimg/python:3.12 steps: - checkout - run: diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index b83954f17e..7b3dc14751 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -12,7 +12,7 @@ jobs: runs-on: ubuntu-latest strategy: matrix: - python-version: [ '3.11' ] + python-version: [ '3.12' ] name: Python ${{ matrix.python-version }} CI diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index 19c6612b2f..5ea15ac72e 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -16,7 +16,7 @@ jobs: runs-on: macos-latest strategy: matrix: - python-version: [ '3.11' ] + python-version: [ '3.12' ] name: Python ${{ matrix.python-version }} CI steps: - uses: actions/checkout@v4 @@ -36,4 +36,4 @@ jobs: python -m pip install --upgrade pip pip install -r requirements/requirements.txt - name: do all unit tests - run: bash runtests.sh \ No newline at end of file + run: bash runtests.sh diff --git a/.github/workflows/Windows_CI.yml b/.github/workflows/Windows_CI.yml index 906edcfcdb..b9c8dea649 100644 --- a/.github/workflows/Windows_CI.yml +++ b/.github/workflows/Windows_CI.yml @@ -16,7 +16,7 @@ jobs: runs-on: windows-latest strategy: matrix: - python-version: [ '3.11' ] + python-version: [ '3.12' ] name: Python ${{ matrix.python-version }} CI steps: - uses: actions/checkout@v4 @@ -33,4 +33,4 @@ jobs: python -m pip install --upgrade pip pip install -r requirements/requirements.txt - name: do all unit tests - run: bash runtests.sh \ No newline at end of file + run: bash runtests.sh diff --git a/.lgtm.yml b/.lgtm.yml deleted file mode 100644 index b06edf3510..0000000000 --- a/.lgtm.yml +++ /dev/null @@ -1,4 +0,0 @@ -extraction: - python: - python_setup: - version: 3 diff --git a/README.md b/README.md index bc0198f78e..7a01ae361a 100644 --- a/README.md +++ b/README.md @@ -95,7 +95,7 @@ See this paper for more details: For running each sample code: -- [Python 3.11.x](https://www.python.org/) +- [Python 3.12.x](https://www.python.org/) - [NumPy](https://numpy.org/) diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index 497b85a23a..88f218545e 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -26,7 +26,7 @@ See this paper for more details: Requirements ------------- -- `Python 3.11.x`_ +- `Python 3.12.x`_ - `NumPy`_ - `SciPy`_ - `Matplotlib`_ diff --git a/requirements/environment.yml b/requirements/environment.yml index 13dfa29f66..afbb3fb8ce 100644 --- a/requirements/environment.yml +++ b/requirements/environment.yml @@ -2,7 +2,7 @@ name: python_robotics channels: - conda-forge dependencies: - - python=3.11 + - python=3.12 - pip - scipy - numpy diff --git a/ruff.toml b/ruff.toml index 578864b33e..5823ca3db7 100644 --- a/ruff.toml +++ b/ruff.toml @@ -6,7 +6,7 @@ exclude = [ ] # Assume Python 3.11 -target-version = "py311" +target-version = "py312" [per-file-ignores] @@ -15,4 +15,4 @@ target-version = "py311" max-complexity = 10 [pydocstyle] -convention = "numpy" \ No newline at end of file +convention = "numpy" From 4bdf9036b60eb40899079b777b208870d2c20bfe Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 19 Mar 2024 20:15:00 +0900 Subject: [PATCH 724/940] Bump ruff from 0.3.2 to 0.3.3 in /requirements (#993) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.3.2 to 0.3.3. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.3.2...v0.3.3) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 1021562d1c..f6e64cc5ab 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.2 pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.9.0 # For unit test -ruff == 0.3.2 # For unit test +ruff == 0.3.3 # For unit test From f8b340be53ebb6ed4b6b0d2579394b58fe8074af Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 26 Mar 2024 07:30:04 +0900 Subject: [PATCH 725/940] Bump ruff from 0.3.3 to 0.3.4 in /requirements (#996) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.3.3 to 0.3.4. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.3.3...v0.3.4) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f6e64cc5ab..6e7c77d836 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.2 pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.9.0 # For unit test -ruff == 0.3.3 # For unit test +ruff == 0.3.4 # For unit test From 61d5da8576c43c59f69655cf6324fa959031623f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 2 Apr 2024 07:31:43 +0900 Subject: [PATCH 726/940] Bump ruff from 0.3.4 to 0.3.5 in /requirements (#999) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.3.4 to 0.3.5. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.3.4...v0.3.5) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 6e7c77d836..c1edf2951c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.2 pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.9.0 # For unit test -ruff == 0.3.4 # For unit test +ruff == 0.3.5 # For unit test From c6562d787f797f56561e362ea2633ad7e3b4ee3c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 9 Apr 2024 08:00:57 +0900 Subject: [PATCH 727/940] Bump matplotlib from 3.8.3 to 3.8.4 in /requirements (#1001) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.8.3 to 3.8.4. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.8.3...v3.8.4) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index c1edf2951c..fe97f01e24 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.26.4 scipy == 1.12.0 -matplotlib == 3.8.3 +matplotlib == 3.8.4 cvxpy == 1.4.2 pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test From 84237d6007254c2a644adcabe61673da11f39eb4 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 9 Apr 2024 20:25:11 +0900 Subject: [PATCH 728/940] Bump scipy from 1.12.0 to 1.13.0 in /requirements (#1002) Bumps [scipy](https://github.com/scipy/scipy) from 1.12.0 to 1.13.0. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.12.0...v1.13.0) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index fe97f01e24..7a94111985 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.26.4 -scipy == 1.12.0 +scipy == 1.13.0 matplotlib == 3.8.4 cvxpy == 1.4.2 pytest == 8.1.1 # For unit test From 808e98133d57426b1e6fbbc2bdc897a196278d7d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 16 Apr 2024 20:56:21 +0900 Subject: [PATCH 729/940] Bump ruff from 0.3.5 to 0.3.7 in /requirements (#1003) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.3.5 to 0.3.7. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.3.5...v0.3.7) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 7a94111985..6ba7ea1c6d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.2 pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.9.0 # For unit test -ruff == 0.3.5 # For unit test +ruff == 0.3.7 # For unit test From d27f7dca1d2645915d03d087bc12c2ad281bb114 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 23 Apr 2024 21:28:01 +0900 Subject: [PATCH 730/940] Bump ruff from 0.3.7 to 0.4.1 in /requirements (#1005) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.3.7 to 0.4.1. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.3.7...v0.4.1) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 6ba7ea1c6d..7dfadddb48 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.2 pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.9.0 # For unit test -ruff == 0.3.7 # For unit test +ruff == 0.4.1 # For unit test From c12faa6a2ee2ac92102467487c4b168119c6cf07 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sat, 27 Apr 2024 16:20:45 +0900 Subject: [PATCH 731/940] Bump cvxpy from 1.4.2 to 1.4.3 in /requirements (#1006) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.4.2 to 1.4.3. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.4.2...v1.4.3) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 7dfadddb48..8e4d166c4e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.26.4 scipy == 1.13.0 matplotlib == 3.8.4 -cvxpy == 1.4.2 +cvxpy == 1.4.3 pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.9.0 # For unit test From 8f84f0f5518797c1c11f4cee204c0a5c6bffbe82 Mon Sep 17 00:00:00 2001 From: noob3-3 Date: Sat, 27 Apr 2024 20:51:19 +0800 Subject: [PATCH 732/940] fix::Control PathFinderController bug (#1000) --- Control/move_to_pose/move_to_pose.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Control/move_to_pose/move_to_pose.py b/Control/move_to_pose/move_to_pose.py index cc29666297..279ba0625b 100644 --- a/Control/move_to_pose/move_to_pose.py +++ b/Control/move_to_pose/move_to_pose.py @@ -74,7 +74,7 @@ def calc_control_command(self, x_diff, y_diff, theta, theta_goal): alpha = angle_mod(np.arctan2(y_diff, x_diff) - theta) beta = angle_mod(theta_goal - theta - alpha) v = self.Kp_rho * rho - w = self.Kp_alpha * alpha - controller.Kp_beta * beta + w = self.Kp_alpha * alpha - self.Kp_beta * beta if alpha > np.pi / 2 or alpha < -np.pi / 2: v = -v From c76f74703f6b9f7b2ec3bf993eb9c9c5d2ccb4ac Mon Sep 17 00:00:00 2001 From: Yi-Chen Zhang Date: Sun, 28 Apr 2024 07:55:25 -0400 Subject: [PATCH 733/940] Fix covariance dimension (#998) --- Localization/particle_filter/particle_filter.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Localization/particle_filter/particle_filter.py b/Localization/particle_filter/particle_filter.py index 17051623ca..ba54a3d12b 100644 --- a/Localization/particle_filter/particle_filter.py +++ b/Localization/particle_filter/particle_filter.py @@ -96,10 +96,10 @@ def calc_covariance(x_est, px, pw): calculate covariance matrix see ipynb doc """ - cov = np.zeros((3, 3)) + cov = np.zeros((4, 4)) n_particle = px.shape[1] for i in range(n_particle): - dx = (px[:, i:i + 1] - x_est)[0:3] + dx = (px[:, i:i + 1] - x_est) cov += pw[0, i] * dx @ dx.T cov *= 1.0 / (1.0 - pw @ pw.T) From de2434361cd017851e10e4866bf6e6dca3b9cc95 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 28 Apr 2024 21:17:33 +0900 Subject: [PATCH 734/940] fix plot issue in random_inverse_kinematics.py (#1007) --- ArmNavigation/n_joint_arm_3d/NLinkArm3d.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArmNavigation/n_joint_arm_3d/NLinkArm3d.py b/ArmNavigation/n_joint_arm_3d/NLinkArm3d.py index 0cea963168..0459e234b2 100644 --- a/ArmNavigation/n_joint_arm_3d/NLinkArm3d.py +++ b/ArmNavigation/n_joint_arm_3d/NLinkArm3d.py @@ -127,7 +127,8 @@ def inverse_kinematics(self, ref_ee_pose, plot=False): if plot: self.fig = plt.figure() - self.ax = Axes3D(self.fig) + self.ax = Axes3D(self.fig, auto_add_to_figure=False) + self.fig.add_axes(self.ax) x_list = [] y_list = [] From b93f170d32a4132762ad879ffca19befa8eb218f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 30 Apr 2024 08:56:40 +0900 Subject: [PATCH 735/940] Bump ruff from 0.4.1 to 0.4.2 in /requirements (#1008) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.4.1 to 0.4.2. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.4.1...v0.4.2) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 8e4d166c4e..ced1457da6 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.3 pytest == 8.1.1 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.9.0 # For unit test -ruff == 0.4.1 # For unit test +ruff == 0.4.2 # For unit test From bbf7d1ed857dc79e306f9c7fa09323cf74d0c71d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 30 Apr 2024 12:49:55 +0900 Subject: [PATCH 736/940] Bump pytest from 8.1.1 to 8.2.0 in /requirements (#1010) Bumps [pytest](https://github.com/pytest-dev/pytest) from 8.1.1 to 8.2.0. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/8.1.1...8.2.0) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index ced1457da6..ad5ab50f47 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.26.4 scipy == 1.13.0 matplotlib == 3.8.4 cvxpy == 1.4.3 -pytest == 8.1.1 # For unit test +pytest == 8.2.0 # For unit test pytest-xdist == 3.5.0 # For unit test mypy == 1.9.0 # For unit test ruff == 0.4.2 # For unit test From 1262b0bfd1823f4a0476eb5060bd8384dea34128 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 30 Apr 2024 16:00:24 +0900 Subject: [PATCH 737/940] Bump pytest-xdist from 3.5.0 to 3.6.1 in /requirements (#1009) Bumps [pytest-xdist](https://github.com/pytest-dev/pytest-xdist) from 3.5.0 to 3.6.1. - [Release notes](https://github.com/pytest-dev/pytest-xdist/releases) - [Changelog](https://github.com/pytest-dev/pytest-xdist/blob/master/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest-xdist/compare/v3.5.0...v3.6.1) --- updated-dependencies: - dependency-name: pytest-xdist dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index ad5ab50f47..b56c6e734f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,6 +3,6 @@ scipy == 1.13.0 matplotlib == 3.8.4 cvxpy == 1.4.3 pytest == 8.2.0 # For unit test -pytest-xdist == 3.5.0 # For unit test +pytest-xdist == 3.6.1 # For unit test mypy == 1.9.0 # For unit test ruff == 0.4.2 # For unit test From e14134d1e705076e83ee4228fd463bbfa5fccd61 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 1 May 2024 07:54:14 +0900 Subject: [PATCH 738/940] Bump mypy from 1.9.0 to 1.10.0 in /requirements (#1011) Bumps [mypy](https://github.com/python/mypy) from 1.9.0 to 1.10.0. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/1.9.0...v1.10.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b56c6e734f..0575353a11 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.8.4 cvxpy == 1.4.3 pytest == 8.2.0 # For unit test pytest-xdist == 3.6.1 # For unit test -mypy == 1.9.0 # For unit test +mypy == 1.10.0 # For unit test ruff == 0.4.2 # For unit test From 16c16b6ff56dbebf4fd0ae0f170c9acc6df080dd Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 4 May 2024 23:08:14 +0900 Subject: [PATCH 739/940] clean up fast slam codes (#1012) * clean up fast slam codes * clean up fast slam codes * clean up fast slam codes --- SLAM/FastSLAM1/fast_slam1.py | 100 ++++++++++++++++--------------- SLAM/FastSLAM2/fast_slam2.py | 110 +++++++++++++++++------------------ 2 files changed, 104 insertions(+), 106 deletions(-) diff --git a/SLAM/FastSLAM1/fast_slam1.py b/SLAM/FastSLAM1/fast_slam1.py index 17f6d5e572..98f8a66417 100644 --- a/SLAM/FastSLAM1/fast_slam1.py +++ b/SLAM/FastSLAM1/fast_slam1.py @@ -17,8 +17,8 @@ R = np.diag([1.0, np.deg2rad(20.0)]) ** 2 # Simulation parameter -Q_sim = np.diag([0.3, np.deg2rad(2.0)]) ** 2 -R_sim = np.diag([0.5, np.deg2rad(10.0)]) ** 2 +Q_SIM = np.diag([0.3, np.deg2rad(2.0)]) ** 2 +R_SIM = np.diag([0.5, np.deg2rad(10.0)]) ** 2 OFFSET_YAW_RATE_NOISE = 0.01 DT = 0.1 # time tick [s] @@ -72,19 +72,18 @@ def normalize_weight(particles): def calc_final_state(particles): - xEst = np.zeros((STATE_SIZE, 1)) + x_est = np.zeros((STATE_SIZE, 1)) particles = normalize_weight(particles) for i in range(N_PARTICLE): - xEst[0, 0] += particles[i].w * particles[i].x - xEst[1, 0] += particles[i].w * particles[i].y - xEst[2, 0] += particles[i].w * particles[i].yaw + x_est[0, 0] += particles[i].w * particles[i].x + x_est[1, 0] += particles[i].w * particles[i].y + x_est[2, 0] += particles[i].w * particles[i].yaw - xEst[2, 0] = pi_2_pi(xEst[2, 0]) - # print(xEst) + x_est[2, 0] = pi_2_pi(x_est[2, 0]) - return xEst + return x_est def predict_particles(particles, u): @@ -235,28 +234,27 @@ def resampling(particles): pw = np.array(pw) n_eff = 1.0 / (pw @ pw.T) # Effective particle number - # print(n_eff) if n_eff < NTH: # resampling w_cum = np.cumsum(pw) base = np.cumsum(pw * 0.0 + 1 / N_PARTICLE) - 1 / N_PARTICLE resample_id = base + np.random.rand(base.shape[0]) / N_PARTICLE - inds = [] - ind = 0 + indexes = [] + index = 0 for ip in range(N_PARTICLE): - while (ind < w_cum.shape[0] - 1) \ - and (resample_id[ip] > w_cum[ind]): - ind += 1 - inds.append(ind) + while (index < w_cum.shape[0] - 1) \ + and (resample_id[ip] > w_cum[index]): + index += 1 + indexes.append(index) tmp_particles = particles[:] - for i in range(len(inds)): - particles[i].x = tmp_particles[inds[i]].x - particles[i].y = tmp_particles[inds[i]].y - particles[i].yaw = tmp_particles[inds[i]].yaw - particles[i].lm = tmp_particles[inds[i]].lm[:, :] - particles[i].lmP = tmp_particles[inds[i]].lmP[:, :] + for i in range(len(indexes)): + particles[i].x = tmp_particles[indexes[i]].x + particles[i].y = tmp_particles[indexes[i]].y + particles[i].yaw = tmp_particles[indexes[i]].yaw + particles[i].lm = tmp_particles[indexes[i]].lm[:, :] + particles[i].lmP = tmp_particles[indexes[i]].lmP[:, :] particles[i].w = 1.0 / N_PARTICLE return particles @@ -275,34 +273,34 @@ def calc_input(time): return u -def observation(xTrue, xd, u, rfid): +def observation(x_true, xd, u, rfid): # calc true state - xTrue = motion_model(xTrue, u) + x_true = motion_model(x_true, u) # add noise to range observation z = np.zeros((3, 0)) for i in range(len(rfid[:, 0])): - dx = rfid[i, 0] - xTrue[0, 0] - dy = rfid[i, 1] - xTrue[1, 0] + dx = rfid[i, 0] - x_true[0, 0] + dy = rfid[i, 1] - x_true[1, 0] d = math.hypot(dx, dy) - angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) + angle = pi_2_pi(math.atan2(dy, dx) - x_true[2, 0]) if d <= MAX_RANGE: - dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise - angle_with_noize = angle + np.random.randn() * Q_sim[ + dn = d + np.random.randn() * Q_SIM[0, 0] ** 0.5 # add noise + angle_with_noize = angle + np.random.randn() * Q_SIM[ 1, 1] ** 0.5 # add noise zi = np.array([dn, pi_2_pi(angle_with_noize), i]).reshape(3, 1) z = np.hstack((z, zi)) # add noise to input - ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5 - ud2 = u[1, 0] + np.random.randn() * R_sim[ + ud1 = u[0, 0] + np.random.randn() * R_SIM[0, 0] ** 0.5 + ud2 = u[1, 0] + np.random.randn() * R_SIM[ 1, 1] ** 0.5 + OFFSET_YAW_RATE_NOISE ud = np.array([ud1, ud2]).reshape(2, 1) xd = motion_model(xd, ud) - return xTrue, z, xd, ud + return x_true, z, xd, ud def motion_model(x, u): @@ -331,7 +329,7 @@ def main(): time = 0.0 # RFID positions [x, y] - RFID = np.array([[10.0, -2.0], + rfid = np.array([[10.0, -2.0], [15.0, 10.0], [15.0, 15.0], [10.0, 20.0], @@ -340,17 +338,17 @@ def main(): [-5.0, 5.0], [-10.0, 15.0] ]) - n_landmark = RFID.shape[0] + n_landmark = rfid.shape[0] # State Vector [x y yaw v]' - xEst = np.zeros((STATE_SIZE, 1)) # SLAM estimation - xTrue = np.zeros((STATE_SIZE, 1)) # True state - xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning + x_est = np.zeros((STATE_SIZE, 1)) # SLAM estimation + x_true = np.zeros((STATE_SIZE, 1)) # True state + x_dr = np.zeros((STATE_SIZE, 1)) # Dead reckoning # history - hxEst = xEst - hxTrue = xTrue - hxDR = xTrue + hist_x_est = x_est + hist_x_true = x_true + hist_x_dr = x_dr particles = [Particle(n_landmark) for _ in range(N_PARTICLE)] @@ -358,18 +356,18 @@ def main(): time += DT u = calc_input(time) - xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID) + x_true, z, x_dr, ud = observation(x_true, x_dr, u, rfid) particles = fast_slam1(particles, ud, z) - xEst = calc_final_state(particles) + x_est = calc_final_state(particles) - x_state = xEst[0: STATE_SIZE] + x_state = x_est[0: STATE_SIZE] # store data history - hxEst = np.hstack((hxEst, x_state)) - hxDR = np.hstack((hxDR, xDR)) - hxTrue = np.hstack((hxTrue, xTrue)) + hist_x_est = np.hstack((hist_x_est, x_state)) + hist_x_dr = np.hstack((hist_x_dr, x_dr)) + hist_x_true = np.hstack((hist_x_true, x_true)) if show_animation: # pragma: no cover plt.cla() @@ -377,16 +375,16 @@ def main(): plt.gcf().canvas.mpl_connect( 'key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) - plt.plot(RFID[:, 0], RFID[:, 1], "*k") + plt.plot(rfid[:, 0], rfid[:, 1], "*k") for i in range(N_PARTICLE): plt.plot(particles[i].x, particles[i].y, ".r") plt.plot(particles[i].lm[:, 0], particles[i].lm[:, 1], "xb") - plt.plot(hxTrue[0, :], hxTrue[1, :], "-b") - plt.plot(hxDR[0, :], hxDR[1, :], "-k") - plt.plot(hxEst[0, :], hxEst[1, :], "-r") - plt.plot(xEst[0], xEst[1], "xk") + plt.plot(hist_x_true[0, :], hist_x_true[1, :], "-b") + plt.plot(hist_x_dr[0, :], hist_x_dr[1, :], "-k") + plt.plot(hist_x_est[0, :], hist_x_est[1, :], "-r") + plt.plot(x_est[0], x_est[1], "xk") plt.axis("equal") plt.grid(True) plt.pause(0.001) diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py index 2b57e3bcc3..d4cf0d84dd 100644 --- a/SLAM/FastSLAM2/fast_slam2.py +++ b/SLAM/FastSLAM2/fast_slam2.py @@ -17,8 +17,8 @@ R = np.diag([1.0, np.deg2rad(20.0)]) ** 2 # Simulation parameter -Q_sim = np.diag([0.3, np.deg2rad(2.0)]) ** 2 -R_sim = np.diag([0.5, np.deg2rad(10.0)]) ** 2 +Q_SIM = np.diag([0.3, np.deg2rad(2.0)]) ** 2 +R_SIM = np.diag([0.5, np.deg2rad(10.0)]) ** 2 OFFSET_YAW_RATE_NOISE = 0.01 DT = 0.1 # time tick [s] @@ -35,16 +35,16 @@ class Particle: - def __init__(self, N_LM): + def __init__(self, n_landmark): self.w = 1.0 / N_PARTICLE self.x = 0.0 self.y = 0.0 self.yaw = 0.0 self.P = np.eye(3) # landmark x-y positions - self.lm = np.zeros((N_LM, LM_SIZE)) + self.lm = np.zeros((n_landmark, LM_SIZE)) # landmark position covariance - self.lmP = np.zeros((N_LM * LM_SIZE, LM_SIZE)) + self.lmP = np.zeros((n_landmark * LM_SIZE, LM_SIZE)) def fast_slam2(particles, u, z): @@ -73,18 +73,18 @@ def normalize_weight(particles): def calc_final_state(particles): - xEst = np.zeros((STATE_SIZE, 1)) + x_est = np.zeros((STATE_SIZE, 1)) particles = normalize_weight(particles) for i in range(N_PARTICLE): - xEst[0, 0] += particles[i].w * particles[i].x - xEst[1, 0] += particles[i].w * particles[i].y - xEst[2, 0] += particles[i].w * particles[i].yaw + x_est[0, 0] += particles[i].w * particles[i].x + x_est[1, 0] += particles[i].w * particles[i].y + x_est[2, 0] += particles[i].w * particles[i].yaw - xEst[2, 0] = pi_2_pi(xEst[2, 0]) + x_est[2, 0] = pi_2_pi(x_est[2, 0]) - return xEst + return x_est def predict_particles(particles, u): @@ -266,21 +266,21 @@ def resampling(particles): base = np.cumsum(pw * 0.0 + 1 / N_PARTICLE) - 1 / N_PARTICLE resample_id = base + np.random.rand(base.shape[0]) / N_PARTICLE - inds = [] - ind = 0 + indexes = [] + index = 0 for ip in range(N_PARTICLE): - while (ind < w_cum.shape[0] - 1) \ - and (resample_id[ip] > w_cum[ind]): - ind += 1 - inds.append(ind) + while (index < w_cum.shape[0] - 1) \ + and (resample_id[ip] > w_cum[index]): + index += 1 + indexes.append(index) tmp_particles = particles[:] - for i in range(len(inds)): - particles[i].x = tmp_particles[inds[i]].x - particles[i].y = tmp_particles[inds[i]].y - particles[i].yaw = tmp_particles[inds[i]].yaw - particles[i].lm = tmp_particles[inds[i]].lm[:, :] - particles[i].lmP = tmp_particles[inds[i]].lmP[:, :] + for i in range(len(indexes)): + particles[i].x = tmp_particles[indexes[i]].x + particles[i].y = tmp_particles[indexes[i]].y + particles[i].yaw = tmp_particles[indexes[i]].yaw + particles[i].lm = tmp_particles[indexes[i]].lm[:, :] + particles[i].lmP = tmp_particles[indexes[i]].lmP[:, :] particles[i].w = 1.0 / N_PARTICLE return particles @@ -299,35 +299,35 @@ def calc_input(time): return u -def observation(xTrue, xd, u, RFID): +def observation(x_true, xd, u, rfid): # calc true state - xTrue = motion_model(xTrue, u) + x_true = motion_model(x_true, u) # add noise to range observation z = np.zeros((3, 0)) - for i in range(len(RFID[:, 0])): + for i in range(len(rfid[:, 0])): - dx = RFID[i, 0] - xTrue[0, 0] - dy = RFID[i, 1] - xTrue[1, 0] + dx = rfid[i, 0] - x_true[0, 0] + dy = rfid[i, 1] - x_true[1, 0] d = math.hypot(dx, dy) - angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0]) + angle = pi_2_pi(math.atan2(dy, dx) - x_true[2, 0]) if d <= MAX_RANGE: - dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5 # add noise - angle_noise = np.random.randn() * Q_sim[1, 1] ** 0.5 + dn = d + np.random.randn() * Q_SIM[0, 0] ** 0.5 # add noise + angle_noise = np.random.randn() * Q_SIM[1, 1] ** 0.5 angle_with_noise = angle + angle_noise # add noise zi = np.array([dn, pi_2_pi(angle_with_noise), i]).reshape(3, 1) z = np.hstack((z, zi)) # add noise to input - ud1 = u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5 - ud2 = u[1, 0] + np.random.randn() * R_sim[ + ud1 = u[0, 0] + np.random.randn() * R_SIM[0, 0] ** 0.5 + ud2 = u[1, 0] + np.random.randn() * R_SIM[ 1, 1] ** 0.5 + OFFSET_YAW_RATE_NOISE ud = np.array([ud1, ud2]).reshape(2, 1) xd = motion_model(xd, ud) - return xTrue, z, xd, ud + return x_true, z, xd, ud def motion_model(x, u): @@ -356,7 +356,7 @@ def main(): time = 0.0 # RFID positions [x, y] - RFID = np.array([[10.0, -2.0], + rfid = np.array([[10.0, -2.0], [15.0, 10.0], [15.0, 15.0], [10.0, 20.0], @@ -365,17 +365,17 @@ def main(): [-5.0, 5.0], [-10.0, 15.0] ]) - n_landmark = RFID.shape[0] + n_landmark = rfid.shape[0] # State Vector [x y yaw v]' - xEst = np.zeros((STATE_SIZE, 1)) # SLAM estimation - xTrue = np.zeros((STATE_SIZE, 1)) # True state - xDR = np.zeros((STATE_SIZE, 1)) # Dead reckoning + x_est = np.zeros((STATE_SIZE, 1)) # SLAM estimation + x_true = np.zeros((STATE_SIZE, 1)) # True state + x_dr = np.zeros((STATE_SIZE, 1)) # Dead reckoning # history - hxEst = xEst - hxTrue = xTrue - hxDR = xTrue + hist_x_est = x_est + hist_x_true = x_true + hist_x_dr = x_dr particles = [Particle(n_landmark) for _ in range(N_PARTICLE)] @@ -383,18 +383,18 @@ def main(): time += DT u = calc_input(time) - xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID) + x_true, z, x_dr, ud = observation(x_true, x_dr, u, rfid) particles = fast_slam2(particles, ud, z) - xEst = calc_final_state(particles) + x_est = calc_final_state(particles) - x_state = xEst[0: STATE_SIZE] + x_state = x_est[0: STATE_SIZE] # store data history - hxEst = np.hstack((hxEst, x_state)) - hxDR = np.hstack((hxDR, xDR)) - hxTrue = np.hstack((hxTrue, xTrue)) + hist_x_est = np.hstack((hist_x_est, x_state)) + hist_x_dr = np.hstack((hist_x_dr, x_dr)) + hist_x_true = np.hstack((hist_x_true, x_true)) if show_animation: # pragma: no cover plt.cla() @@ -402,21 +402,21 @@ def main(): plt.gcf().canvas.mpl_connect( 'key_release_event', lambda event: [exit(0) if event.key == 'escape' else None]) - plt.plot(RFID[:, 0], RFID[:, 1], "*k") + plt.plot(rfid[:, 0], rfid[:, 1], "*k") for iz in range(len(z[:, 0])): landmark_id = int(z[2, iz]) - plt.plot([xEst[0][0], RFID[landmark_id, 0]], [ - xEst[1][0], RFID[landmark_id, 1]], "-k") + plt.plot([x_est[0][0], rfid[landmark_id, 0]], [ + x_est[1][0], rfid[landmark_id, 1]], "-k") for i in range(N_PARTICLE): plt.plot(particles[i].x, particles[i].y, ".r") plt.plot(particles[i].lm[:, 0], particles[i].lm[:, 1], "xb") - plt.plot(hxTrue[0, :], hxTrue[1, :], "-b") - plt.plot(hxDR[0, :], hxDR[1, :], "-k") - plt.plot(hxEst[0, :], hxEst[1, :], "-r") - plt.plot(xEst[0], xEst[1], "xk") + plt.plot(hist_x_true[0, :], hist_x_true[1, :], "-b") + plt.plot(hist_x_dr[0, :], hist_x_dr[1, :], "-k") + plt.plot(hist_x_est[0, :], hist_x_est[1, :], "-r") + plt.plot(x_est[0], x_est[1], "xk") plt.axis("equal") plt.grid(True) plt.pause(0.001) From 20818bfe3c7185e065435ea4d204510db6dd37f5 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 May 2024 21:37:44 +0900 Subject: [PATCH 740/940] Bump ruff from 0.4.2 to 0.4.3 in /requirements (#1014) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.4.2 to 0.4.3. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.4.2...v0.4.3) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 0575353a11..4db551eb8c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.3 pytest == 8.2.0 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test -ruff == 0.4.2 # For unit test +ruff == 0.4.3 # For unit test From dfcc08e36723e7a371048147d2879f7b373e1902 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 08:44:53 +0900 Subject: [PATCH 741/940] Bump ruff from 0.4.3 to 0.4.4 in /requirements (#1017) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.4.3 to 0.4.4. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.4.3...v0.4.4) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 4db551eb8c..909b39faa7 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.4.3 pytest == 8.2.0 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test -ruff == 0.4.3 # For unit test +ruff == 0.4.4 # For unit test From ed5004b0f84081b93a2aceebe96defe013d99e06 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?YSF=E3=83=84?= <50619491+yousefbilal@users.noreply.github.com> Date: Sat, 18 May 2024 13:56:04 +0400 Subject: [PATCH 742/940] fixed hard-coded plot limits (#1018) --- PathPlanning/RRT/rrt.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index 55092e6e00..e6dd9b648b 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -199,7 +199,7 @@ def draw_graph(self, rnd=None): plt.plot(self.start.x, self.start.y, "xr") plt.plot(self.end.x, self.end.y, "xr") plt.axis("equal") - plt.axis([-2, 15, -2, 15]) + plt.axis([self.min_rand, self.max_rand, self.min_rand, self.max_rand]) plt.grid(True) plt.pause(0.01) From 36b630040224c79bfa05974b8107b7a384e8271a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sun, 19 May 2024 20:54:57 +0900 Subject: [PATCH 743/940] Bump cvxpy from 1.4.3 to 1.5.1 in /requirements (#1016) * Bump cvxpy from 1.4.3 to 1.5.1 in /requirements Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.4.3 to 1.5.1. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.4.3...v1.5.1) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] * fix cvxpy update issue --------- Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> Co-authored-by: Atsushi Sakai --- .../model_predictive_speed_and_steer_control.py | 14 ++++++++++++-- requirements/requirements.txt | 2 +- runtests.sh | 2 +- 3 files changed, 14 insertions(+), 4 deletions(-) diff --git a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py index c55018cf26..eb2d7b6a73 100644 --- a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py +++ b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py @@ -6,14 +6,16 @@ """ import matplotlib.pyplot as plt +import time import cvxpy import math import numpy as np import sys import pathlib -from utils.angle import angle_mod sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) +from utils.angle import angle_mod + from PathPlanning.CubicSpline import cubic_spline_planner NX = 4 # x = x, y, v, yaw @@ -281,7 +283,7 @@ def linear_mpc_control(xref, xbar, x0, dref): constraints += [cvxpy.abs(u[1, :]) <= MAX_STEER] prob = cvxpy.Problem(cvxpy.Minimize(cost), constraints) - prob.solve(solver=cvxpy.ECOS, verbose=False) + prob.solve(solver=cvxpy.CLARABEL, verbose=False) if prob.status == cvxpy.OPTIMAL or prob.status == cvxpy.OPTIMAL_INACCURATE: ox = get_nparray_from_matrix(x.value[0, :]) @@ -545,6 +547,7 @@ def get_switch_back_course(dl): def main(): print(__file__ + " start!!") + start = time.time() dl = 1.0 # course tick # cx, cy, cyaw, ck = get_straight_course(dl) @@ -560,6 +563,9 @@ def main(): t, x, y, yaw, v, d, a = do_simulation( cx, cy, cyaw, ck, sp, dl, initial_state) + elapsed_time = time.time() - start + print(f"calc time:{elapsed_time:.6f} [sec]") + if show_animation: # pragma: no cover plt.close("all") plt.subplots() @@ -582,6 +588,7 @@ def main(): def main2(): print(__file__ + " start!!") + start = time.time() dl = 1.0 # course tick cx, cy, cyaw, ck = get_straight_course3(dl) @@ -593,6 +600,9 @@ def main2(): t, x, y, yaw, v, d, a = do_simulation( cx, cy, cyaw, ck, sp, dl, initial_state) + elapsed_time = time.time() - start + print(f"calc time:{elapsed_time:.6f} [sec]") + if show_animation: # pragma: no cover plt.close("all") plt.subplots() diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 909b39faa7..76f203f423 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.26.4 scipy == 1.13.0 matplotlib == 3.8.4 -cvxpy == 1.4.3 +cvxpy == 1.5.1 pytest == 8.2.0 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test diff --git a/runtests.sh b/runtests.sh index a2a683e571..12d1b80453 100755 --- a/runtests.sh +++ b/runtests.sh @@ -5,4 +5,4 @@ echo "Run test suites! " # -Werror: warning as error # --durations=0: show ranking of test durations # -l (--showlocals); show local variables when test failed -pytest -n auto tests -l -Werror --durations=0 +pytest tests -l -Werror --durations=0 From e752e50421e66f3982cfd84188499137c55d2925 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 May 2024 21:16:11 +0900 Subject: [PATCH 744/940] --- (#1020) updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 76f203f423..65885f423b 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.26.4 scipy == 1.13.0 matplotlib == 3.8.4 cvxpy == 1.5.1 -pytest == 8.2.0 # For unit test +pytest == 8.2.1 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test ruff == 0.4.4 # For unit test From cfb736316aed6a6160e45e1c236beda0a5f01622 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 23 May 2024 21:48:35 +0900 Subject: [PATCH 745/940] --- (#1019) updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 65885f423b..cbf18ad938 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.26.4 scipy == 1.13.0 -matplotlib == 3.8.4 +matplotlib == 3.9.0 cvxpy == 1.5.1 pytest == 8.2.1 # For unit test pytest-xdist == 3.6.1 # For unit test From 5751829bab294019bb78917d91f280552bb549d2 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 25 May 2024 23:31:54 +0900 Subject: [PATCH 746/940] Enhance lqr steering control docs (#1015) * enhance lqr steering control docs * enhance lqr steering control docs * enhance lqr steering control docs * enhance lqr steering control docs * improve lqr steering control docs --- .../lqr_steer_control/lqr_steer_control.py | 14 +-- docs/README.md | 2 +- .../lqr_steering_control_main.rst | 102 ++++++++++++++++++ .../lqr_steering_control_model.png | Bin 0 -> 17366 bytes 4 files changed, 111 insertions(+), 7 deletions(-) create mode 100644 docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.png diff --git a/PathTracking/lqr_steer_control/lqr_steer_control.py b/PathTracking/lqr_steer_control/lqr_steer_control.py index 4078ea56db..461d6e3722 100644 --- a/PathTracking/lqr_steer_control/lqr_steer_control.py +++ b/PathTracking/lqr_steer_control/lqr_steer_control.py @@ -55,7 +55,7 @@ def update(state, a, delta): return state -def PIDControl(target, current): +def pid_control(target, current): a = Kp * (target - current) return a @@ -70,10 +70,11 @@ def solve_DARE(A, B, Q, R): solve a discrete time_Algebraic Riccati equation (DARE) """ X = Q - maxiter = 150 + Xn = Q + max_iter = 150 eps = 0.01 - for i in range(maxiter): + for i in range(max_iter): Xn = A.T @ X @ A - A.T @ X @ B @ \ la.inv(R + B.T @ X @ B) @ B.T @ X @ A + Q if (abs(Xn - X)).max() < eps: @@ -178,7 +179,7 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): dl, target_ind, e, e_th = lqr_steering_control( state, cx, cy, cyaw, ck, e, e_th) - ai = PIDControl(speed_profile[target_ind], state.v) + ai = pid_control(speed_profile[target_ind], state.v) state = update(state, ai, dl) if abs(state.v) <= stop_speed: @@ -202,8 +203,9 @@ def closed_loop_prediction(cx, cy, cyaw, ck, speed_profile, goal): if target_ind % 1 == 0 and show_animation: plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, "-r", label="course") plt.plot(x, y, "ob", label="trajectory") plt.plot(cx[target_ind], cy[target_ind], "xg", label="target") diff --git a/docs/README.md b/docs/README.md index 5c4145e8e3..fb7d4cc3bc 100644 --- a/docs/README.md +++ b/docs/README.md @@ -8,7 +8,7 @@ This folder contains documentation for the Python Robotics project. #### Install Sphinx and Theme ``` -pip install sphinx sphinx-autobuild sphinx-rtd-theme +pip install sphinx sphinx-autobuild sphinx-rtd-theme sphinx_rtd_dark_mode sphinx_copybutton sphinx_rtd_dark_mode ``` #### Building the Docs diff --git a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst index bf6d6b5854..b18e4728cd 100644 --- a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst +++ b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst @@ -8,7 +8,109 @@ control. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_steer_control/animation.gif +Overview +~~~~~~~~ + +The LQR (Linear Quadratic Regulator) steering control model implemented in lqr_steer_control.py provides a simulation +for an autonomous vehicle to track a desired trajectory by adjusting steering angle based on feedback from the current state and the desired trajectory. +This model utilizes a combination of PID speed control and LQR steering control to achieve smooth and accurate trajectory tracking. + +Vehicle motion Model +~~~~~~~~~~~~~~~~~~~~~ + +The below figure shows the geometric model of the vehicle used in this simulation: + +.. image:: lqr_steering_control_model.png + :width: 600px + +The `e` and `theta` represent the lateral error and orientation error, respectively, with respect to the desired trajectory. +And :math:`\dot{e}` and :math:`\dot{\theta}` represent the rates of change of these errors. + +The :math:`e_t` and :math:`theta_t` are the updated values of `e` and `theta` at time `t`, respectively, and can be calculated using the following kinematic equations: + +.. math:: e_t = e_{t-1} + \dot{e}_{t-1} dt + +.. math:: \theta_t = \theta_{t-1} + \dot{\theta}_{t-1} dt + +Where `dt` is the time difference. + +The change rate of the `e` can be calculated as: + +.. math:: \dot{e}_t = V \sin(\theta_{t-1}) + +Where `V` is the vehicle speed. + +If the :math:`theta` is small, + +.. math:: \theta \approx 0 + +the :math:`\sin(\theta)` can be approximated as :math:`\theta`: + +.. math:: \sin(\theta) = \theta + +So, the change rate of the `e` can be approximated as: + +.. math:: \dot{e}_t = V \theta_{t-1} + +The change rate of the :math:`\theta` can be calculated as: + +.. math:: \dot{\theta}_t = \frac{V}{L} \tan(\delta) + +where `L` is the wheelbase of the vehicle and :math:`\delta` is the steering angle. + +If the :math:`\delta` is small, + +.. math:: \delta \approx 0 + +the :math:`\tan(\delta)` can be approximated as :math:`\delta`: + +.. math:: \tan(\delta) = \delta + +So, the change rate of the :math:`\theta` can be approximated as: + +.. math:: \dot{\theta}_t = \frac{V}{L} \delta + +The above equations can be used to update the state of the vehicle at each time step. + +To formulate the state-space representation of the vehicle dynamics as a linear model, +the state vector `x` and control input vector `u` are defined as follows: + +.. math:: x_t = [e_t, \dot{e}_t, \theta_t, \dot{\theta}_t]^T + +.. math:: u_t = \delta_t + +The state transition equation can be represented as: + +.. math:: x_{t+1} = A x_t + B u_t + +where: + +:math:`\begin{equation*} A = \begin{bmatrix} 1 & dt & 0 & 0\\ 0 & 0 & v & 0\\ 0 & 0 & 1 & dt\\ 0 & 0 & 0 & 0 \\ \end{bmatrix} \end{equation*}` + +:math:`\begin{equation*} B = \begin{bmatrix} 0\\ 0\\ 0\\ \frac{v}{L} \\ \end{bmatrix} \end{equation*}` + +LQR controller +~~~~~~~~~~~~~~~ + +The Linear Quadratic Regulator (LQR) controller is used to calculate the optimal control input `u` that minimizes the quadratic cost function: + +:math:`J = \sum_{t=0}^{N} (x_t^T Q x_t + u_t^T R u_t)` + +where `Q` and `R` are the weighting matrices for the state and control input, respectively. + +for the linear model: + +:math:`x_{t+1} = A x_t + B u_t` + +The optimal control input `u` can be calculated as: + +:math:`u_t = -K x_t` + +where `K` is the feedback gain matrix obtained by solving the Riccati equation. + References: ~~~~~~~~~~~ - `ApolloAuto/apollo: An open autonomous driving platform `_ +- `Linear Quadratic Regulator (LQR) `_ + diff --git a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.png b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.png new file mode 100644 index 0000000000000000000000000000000000000000..961dfcdc05cd4938c1ea7ebc79e1c8e0314e9dd4 GIT binary patch literal 17366 zcmeHv2|Sc-+xM8Lkz_KmW)7{2#}0Uh^w%?`}ih)tgqs zU@%^ik={NS4337uIJgljK?xByr2~F(`0O(z!irl(2VpP~ak{=G-95m`g-U@*5pua(sUKQuZ|_X;U=L_Y3v!`S?WOPr$_iL8l#Hppql*Wf=5thvKm?yj z9&`#7{07C~=N@zL!xH?%VQq2BwyLt=QODDhN;ybzFm?f}F;FI`DiBmav5c{ig{g@Y zUKc!5UEC<(mm$T`jRtkmJ?c$!2PFnLypjSI`U48h?VaqsU49q>+L<54+sB3G!QPmX z0{FAE1q$8Xd8w4L>!67*!E?WwKh4$I=g@AaK>xi<7f{a z7tzEml{nD6$rSIUBCry?6hU7Ks{@)se+jy5yuk+#d$8)oo>KY*DK&zWx(@q+sJr-p zmm;dM2X$dvW3Q8`r|13yzE(IFM?c>^WP4?t+8^gwp2WoT1W#E@V2O7Q|&Wyy_DEP`MGs#rf#+ z%s3VGr5bnp<;Lut_#Cw-)BKnE|Bb1ZU|a^%n??iU{b0!-tCt(O2k26$5WkmkWX}U= z_#f~48yeof9k2h&aDc3fN5G!yyUe;J0@DMR3GD1m^Yvsmqj=LPY{IY?!ZxS9!*X-> zYCP?KU*KZXKS$|ztPCmO*wVcN0bcBx@HqCEY-TDgfA;^~&dQJ;Ks!15gN^Yj%1edz zY;HOKHa67s--ADB!#3ZauOAZ9KUkUY*U(Zt$T|@90oNR<_C7u?jzAEP(%q?`00$lc z@*dqRd8Rm;Dj99yyd{^T_OOez1PE_8~yr@bR& zK!4yDe&*lLj3X>Ek`C;>=q%+45Gg?%LDi*EX^?C4pm~6CfJcWc0=()UwcI{r_M^Shhb1j24Z{ zRtVg(PgpkWKR_YyY!|aEO6R$FpE8h21tA-Bj{ia&?0r0!;y5Rl0LVuz zN`W~$Zt$T|p=gIlcJT&{mIMQs1d6o&Ir^aXvp(Rkivckn`-4ERkK>Q>@c%MiVAJVO zZS(iy1s^~>`hOsd0CA&tpd~xPSo~o1;|D$Hgh9%_SfvM%9s0C%+WuNt@Ytnu0J?!L zi+uZYH})?aef*|1>{xgC;Q!;J5&W{BVo!CA7351qC)#3k=kr^V zq2lEWB~ptO@;-~XC6pWEah|{ifP2gJ;K>{=kRH1x_@w_qxuI=_jf{_Ww!h% zWgt3RbdbyL>7N?uuv6>5V|pJ?dk;|AStD#~=Uxm#EpGERwG1|=vPi#%nNhmpxU@LDxqi0fPF zw$pnHs}5I1?$>|$;LwcpuKgd0n1ay#rN%3cUj5p!+DI8KSg=jz+BcY_0&i!uU13zT zLE6ykkQc1xTVt)Y{sXVSsS!S?f)`kUBTS#kZ^I!u-?V0jd>%A#aUir|aAY`)QyOI_ zkoYhKdPKoMsdg;#_)-lD7C}Owh|+gjbC+vT#Ms|EqQenP&K)O+?AGB3^h(gBi{Eo9 z#yF@jzlJqbN6iYa(K^s>mFA&bp_SP~#tFfBq{9(br9R9}oQz%dJvr#XiTmGMRVzMc z4tyG!I!(78?UG{+=^In--a=sw;jt;|LA+V$6m<^&y7c@#>xFEnPKsS9;yKJ<%YEl$ zv_M+m8|>UWu*@_c?v*+)xI3b1R*@7`oX^MXQWw!{QZx>ltWKbb3U-xN=2*6g1mecc-wPqJxKYVQ@#Jc4VRs69-_v1NN!K7=N1Pp;QsGULyZ+ zd|)h1V=F@)M-ys`7i&#~FRtirI{=%@sK)f$(}F*x`mxmKV4p&LS+5ycP=c zuf(r-WaHtaby{H6!0L!QlQCeq=2`J5F<=NyF!@YA z$#$84*8q83PR2(se;y~n_}jOd&HxM-$(yUpp=ab~p%l6Nc@JQarc3+ArD_)z;m9mAyU#lDYWx5O4$~Va*gTOf>5snxHYXB#sLUM0x;>1gTxr3*EEesWdzw5+o zO?-kh0>Db5o$XcwGHnKwG}(6~k&6E)WR)@)e7~s~oCvEVMJ6{V$`cjAAinb^@Z7lz zj+&?ujNcoj?GXdxWEj@>^h*VtG{#r%Lp5jN2*>M{IH&QZ_p;5vemS`uzi*hS7TTpMtTE%dm5(jG} zqe|((Ao-@bO`&?jhJo4FhASu4tx~S_#Q74W0Optau_AC}XL5aXK{`@+>t>Au{AfhV z++LrJoPO)HBZu_#Rsd4Va=O;o5b0+nG#^znBqAvp1pzsM`Cv0?c?V0m;mD6?>Mz_( zc0VB~@lMA1`1q&Q+fUS!fWsSaQAeZ4Lsp-Iw&u&kA}^Wfq)SH@Yv)LR@Dl) zIpDI1PBsqg?G9q7VjQ1=qXWKD!RpZ3s8VfsDtFT`mm9COM^{IAeW%l|W?&sFh8ELw zfYY@ZX?4rvTtPbP#JRz?Ot9bQBliLj!AbSes`Uz!XU1ar^2Fg|Tfs)__?S8aoPM|H z?x|hKPnvkXpbK?EU^(}z(&FA3*dQ-G=w6Qi(i5xQYFl!A?-woq0r}Gi&^w$+; zf49o+Kjirg&sEVDjndp8{J>;2oEVAZL}u_u@cN45PMG^0pT6uxajoc)ZAVpYIMu~8 z`)I$7b0uJcFsEELG1nHpgJH9&H>|ys;(LIP_DOT*Bs%DXc052yHi#<=wHMiG7;N#j z!?x4Osc~OSbGz{;vAddxaYI0CapR!l+9jMfF}2i90lT}94TdFeb)AtJTtLP!uOd^` z`9JCgv*bnYwj1x}Z#|6uRUICS%;SK^A=T)El%%edXp@#9|F4qkc4u%zSOL6QcTI(= z$#C7cH3m@h-nMo+DWnPP{$8(R@j+dX@S7hXyCSMbq zOnHE-I9`7nta>)BUlSp!oog?gH{@RWKK4?A#idy_lwH+&I1jL$RiPvEKqlt{%b>v& zUSX48pD~X2A--9z-jtQgD% zgyIO8r3Nvo&bd|+>(pZ?V&14$pIDHtaxNEW_@bA=A|ouy#Z8}ze5%FACPy5P^FWvG z1xAh9&Tug`L{Ub~tQdp7%?iefPw$It(Y0#@Bl=8=Rc?`RmKo-H@&NLmfk{NdBD4+RK8J(4Qh6_JxTGRx_k8c?w8JNj z4OQDA&k_!#gk!7ST@3`rG}z)2t-IW~r%}T}Kn{&P2o_Www6?}@OX=x?^tD|nM}rd2 zKR4vTtvs$>2^Q3K^IY5)iIfx5g%sW5%eQ(9zQ<188d@!=2?S;mNMx7DW>p1deOkJW z%D0mR=~9MDJ}0y@K}VMvt}D_KDb|x)u&P5T>Zx3~3QGp$flyckAQj4TknX{W-yq&7 zXN)Zy|Js_jA)k(}u^ZUH>g0(KhLpa^Dx+JAqoFZ#kmM_Vox*$|Uo&^?IHc90Kw7=W zxBJ)#I=eCtg}@FDKL86DKD@XIO?H017r@e?)3hT%hvm%5Ty@_SqC8)C>RGAQM< z7qIq-HG2RbG#m|#B4K@wH>L}3y5>whlI(M3fw;tp2!fO?q3YY4?Tr;* zp0%`QbR7%a8mD~+fzU5juyE~x?C|gV5i2}4wQk^xY4pbO*^S?%VQ-fL2LqsD@V((IPC2UU)PE z&hbg}xlP7Z=@arbvcWv19B{UC*|_tRXoa}ri;!!)sMm5&8G^&VpO|m?oJeuE?kAmq%@?3SzeBSGqeM=+AI{3lydN>FGH@s<3-;FjOcy^^RcWD}tWfWv0K4Xq&IVz=Wk8*A0t_2J#abox_8!_c#t{X4#g)tMujYe@{{~Gtkvvg6<>)WU4cK_BbZaC(_VDFlJ5-N zjM}AKL1W+i_(axP_t-fVkiMpcKM@DQhgNogpk1{T% z4}9!Z(S&62@i~}8{!Y0=m69p_?aj!(^9{ozwlXfYA_na*uC{W1tH_j-;PKY~PF=&F zc0SBHTC)WV&kl2g2@!|Ick?#$*WP~ryl2m;aaFEwJS~`3ZgsEf*{4!-2Gm~Vidnw( z=c{M@WzLO*xWWjyncR(V=JSxVlIKEq#DkI- zRj2QbZ>x$f&DI1GK?nP3pJ>5gnnz3e(LkNldwTjKpM4+&MKPm37CI4$r!}nF>y#?Q zKNCE?$7wm=Kk|Sm1$bm)A!D)E|feix*mo#*9Z)VxHp6 z*NK~!y&K_6G`DCO8qjr=e^GG#$g6m@Fz0K83K`aWAjCmHz6XVmD)h*IE1<|?Y7_Yl zW0QwZyIIvW^KWs~lX84#0K%`V#$%aZ*4Z2y82LP{n2y`T$YcbU%UOF^2X9otn92Kn zE8|+1shtb?5gV_84l8#nCzZMk-QdH=hOg5!r(XFeu1yY^z9&9^!lzYz>)I8^g5Tb` zKLYz@BEcQU-p6IMe>)!zoP!ro`P6<1HE87stX zyf^qruH@O1^M<|yOlJkF;L`Vg_imKN_Ph5!=}$Y}dw~a6-qh=9;<^T`1Sg{ykXXI` zlEH>|#Wf={L&DByy>7gu)rAZ*pYG8*a-+vDOI+Riokz?FmekVW_$=gFK&+~L*W})k z8;S%A_ffyW8uuLc?iOO?4JN`Jh1~#-m1X|M?X9oM(bjrR*@j7?>h7!g%NuoX4eP3i zz0T_Pcp21Pxlo`tQS4q-6Oh7fwM!D4`~;BD!0`4h4maPG4>$TePj@V?>Wi-nx+`$* z*V`4X+dofjy7hFTyGYV!jZPGh9}X;sGMCAu^L5PTzAlV)nCpnv&H9rcv$_HM2m z`5QHe&69!ra%9c5_nLZ;ogj24dX5{|t<}HG%QtK_auhZD#JbaCs1PG0J%-b8GiXW& zQHgCYAAamv1={rUEJ$OKLM!O;(?YOqM?jW#3U~~Y=uqa0i)VSe%IUZSs*&lN{VR@c zm{cV6G1r5{2Z|%m<5f3OwJ%%yiIk(tnkD^COCAv+_N=m10-o^_*rxHsP{Y_R_hygx zI%4|K1=F!%=`X!cHA|O{ z^$>k0XltMxlAE6>xMnx%`qU#6d1B$Lkj6V9aQ%_N4aPAMRrV*iHRH>S-x`S8DUHM9QwzPnHrOew34# z2Ek!dHs~>h5b~P8MAm(PL_Z5j6tY|c!e$l&7`n1J>*8BkvTn2>nyfV-oNmbr@_bzo zBk@jMHO!u=#p}j`T;Vyo;iH0ySSJ7swSk z-pwAiU~-(*G!_ejS0p&BQEJ{EPczDmCie2*ZEt>+$9oL)umC;wO_;3oGu@wmvjm|N zOh%qI;RhlIHb}O3wdQ~ncE1W)9Q5ER18zb)Hw=t4&un*G1-~9MD^pVRMS{2~a-VvQ z8Fe^3?E;j=JAp(8zaw3~?M>N@p-O%goeOb|K0Xc^kEBsxqbB5(3ZtOHkB^;M8meRaCV%lQDauP6aoE*>cbY!=}Hf`bch zTMI$?qi74g#`kGS#@i1OKDd(7v#h>n0g(plSP8OAVFaefZ!7kI3b{Ec9Xlh`cfRHe z$W+15nqcVJz5VCzAlB4U(r+f;Ic(Sn_1Z3=9Z5HMz^f}D4qj%by>qGO8L3eI7U^RaHePblVxLN*9${^*4r>j$=G*fixBCQ@| zvys|HY4zx?lq0_4?z>G)*R3`H7h6b6AwaUbqBrvg=`GRMie^DHCc7&GBpX;~fU^2A z+S|$-pklqalmckCB4!YDs(|k3PG0${M1OIN;wN9LWTqSWPS}{W36L@wP;6(8o!Lok zcPr`L_*!angyX?4+tlGy2oc(7NvdSO>B?+G4bn32=puHo+V!g_@HR< zQioL$hg9;rZ;l%B|rKjt~B=Y5O-N1H8p=iJq zq2lrFu!vnM`9729UDryGVILkZ8fqu#I~o2!{wY6#!|S892S57hx8zg^Pl$N2F+-rf z+(%s?8r+zHRFm`!m!T{QK=Gsw3Ii)?Zv;3fTsvBW0KfICQb_=99UVA(7%G~P$;=@}$ikK@OEBm&9AOHiYs9H}%4*yh)! zBmmrwbb>ud0?fcjdYeyJ-2<|?rjc=O(e?oIL1IE>0yK4`2ot&sfq`~hYN@hx=)gZn zcn;wk4KXerGbe2fz`W{)T?3ANA{d$wLpW0Taoq~2%|0kwxG&I&+r)uKpZ~=P1u@7P zfPqN)CxAgoP{2V~!l?CN`4$=xo6qy31n`?&S1y9FnBqQ6((aXL=;=Q;UXZ46dOR@g zwcOxJ!r0IoJb(uV-wa^gUY|FJM~ur7U(LNvvymTkQQi(>`ZVT|x;3sWaD^JKy#VYm zM<{4);2xI(t&~V%5`!8f@$~UsB>!DO@%bfb1g;GsT7#?S-K1PY z{;#!Zp$7ZNJH_0cauNfpXLm~0nzi2_t!9Swo*tu6p=DeGl9B&OcxY3icCy5~xip0o zdK|O1(zUcE>{R}Z4P7Y}Eknh3r1cihv=c~F@#c;8lk=Q2Nc2dkD#>5)z%5d{sd7SV z+W1hP^OSPMo*^2}AG-Lqlm`66&pom0T5oRr$E0v%$GKCkYm`brz zo>as+J)>tKuWZJ@nULygqJEX9zL1)S4%1mEF}5I+>ia$UDo*tE_Gn2A8cWtbV<{9J zr%(ADTnJ<4Teo0VTUIY!aT>hIwY~c|vi>mlxFnHC7EK?2qE^UadGLyjgtm1ofQ&*w zs`dfvoa({dor`og0@gzhw)>ZJ2CYLo8_neAuUb!hH=$ql=>{oCuZ%FDLEuS+t|4F8MeeAscBFoGgYJ zOifF=S~(CJX}+&wjhr-?mo5pYjz}D6Mm@fWuv*FQ1mbXQyI`=EQ6|9w4ouFi#vuTX z-VmU3IbVbZ2k=JYJ1W58ZU-lW)GTgESO>s0$`xJ-N$>`6w{>@mG3bx!Y0U@Dr~z_g4ICrm8w3|XT^#7pAbMQAAG$if$25a51dCsZ+6#^% zS`zwbvM1c6X#@Mnj_U3`~uP!$45bcbtL*4lECPB|umUFi<-y%mrbf0x;D+F5Z0^{sji% zCI}oXViUOUKrdQ22yp1a6vqY=ZD1A-dNgzuzl3!;V8p}rVH3#tKthL$v1?sQFPsD+ z?!5#U#3ug*1~4Yl0R~qFKoBAAs2}HSiZuDM0+Ru*)5!3TYq)_~mary+cLQk!FPR{m zO98Ia$YJfBvtD3|2X9$2kcd=57>NG`1^~MT80R7xfQ~~Mc?vi4^(sp&2QUlgV__)p zSi<_RNJoYErukPGES|qbGH^qXJQV1&Lv1fYgokkuSnMk@hzCFQ{SUV zsAzul@VUOx+!!Vo`)~-nI5Hy{Ug?c0LsiYzO6|PRAF$BD^7tIU*WwKF8T=M!`%m+n zM6%I#g~6}WT!-UR`qID3N!Gf=+p=ccVt1fR#lf48ZIMRbj&zo!kN8*5;z)HbM_b2O zLo-QJiQTVy>WtdIrFq~g_!75I!&mA?V(Q~ee%Ty>6uZs<%8pKJtvmyFdBIbJ!qVVT zzph2^vvIT69KZT%4o=dt5&1wR*_waHa6WQ&&C%**X>Pyf9y9)Bq>VA&oc6kO9eR&e zeu?Op_Zw+RHf{9QGgPDOdYQUN!u{530+M?lMq3n#%pH3(vT;|u*2=!1aOPYIri)mt=jjdiK0G>@G47y{H{#xaa@R63^wvocngLTZVt(RBU z%FTP;t3C?#4&CVy)M|GPAm7S8s3+;7TuHjQdN5n6&#kP0n9<<1=+k z(0E@NW@15d?i_QDlBKO5dF>aytoul?m&ExOy$*KxR4ai_aQ(hNacCWSWWMbn-*scD zxuQ)&e54?!_rGl7dlOI}jSQ&B4?A*gVJ%_S*MH&encOO3yMWwW!-~24SKfE#FzDx* zJFkA-n=H|N&^YLj`zsNtotLhfdrf6Y?ks#h5al#^+4Roak*V}?xwLb8-2^6sFEVSd zI~XF)zEEOmF^X@$WX)eiuD|nPL2#-EJo^_U6Atzj3aVaQf7fke3DR7v0~_;#6fad? z>Kjsh43XS>S`c0mH0Mleb6t0!!vI{#FKoIq9fGi^K$CSQ(M>yzQKef%@bN-j(jZ8% zJ|G;vU?KFie43{&;PK8Y(^G~mLkS71?7!`mA5MxPW5&K4ecx|`I9*7J%dwS}#mg=j zwa>+i?1n5|RHcgNOWhp!e%IAk)tj{Na;YcdG{u~qUfi6WTJIpC$rJHa{6J1^4{JVG z*5K8g$9n6$FSfBC0_=@rnIC8Q%P{Xp_N0w7@^X;!Xbp)Sqerf6I<1&0NF0I_YI=I6 z)}u{t^*O%~6puuHJAWpd@AUW{9vdwOr_bGD{(L($_gxFwb4O)1APNqHA*`V90^n86 zwhD|@E0n7_9VnSlkGOaSA$!AD{%t~|C~9y1?iCFkX|K8Y5o8mTU*h%JptemTNVKBu zobLj-X~R`CSzaya-Z@36uzpp$jo5c=j!u{*KbcRH7(?<+mncw6_9d3 zziFyitWwK7Ha;MnG1riGPvl^;&c?fJS9@RO+O-M-GtG><<(rGRG#2E7RtxQ6-9C@^z_i?|v1G&z8M1bA z_T1Rmx20UnUr?*0yQfU9_M;K;|3UP)Po zG4XLj@y(j;@hR<$gUl`-w~&~Oxc528?Pc=StP8&Hj9~o=N#T@>(w-y(sRjx~!o#Hx)G!80{g!2-y9a96?mp4HuL242eUIApCu$4?u0z5Yf6~iGREJPbTP9l%a!ku zrFUH7y+e`Un)q|wK>tv#48F*8g&Vd1EYZiKB)+r1;wpbx>zagw7Q{5#~QG)!X zgijTULz~j-Etx4Lr^aasSM|8Ji)EUL@GA>>b?7&dxGvmZQS++B+kOs<^XD@YsBwN2 z^KFIX_3jRSWj?3LGGLe{$EjKFEft57)O`%4 zB|oV<_!}RdxckgJU_FZ%+px~E7OScmTFE@}cEn7n#*10t;L|Vk{)4-I(@bG6rp^O$ z^x^g1+#0vN6PE}h@$eaxp!PEybCtgGnDeOtzmZAD-0UmHZ8-eH-Sp%lM$ z&*3vMfwIKBk^afNI|To;zi!%^Z;*W~Ju@Z4{F!${E2A^S{Q7&FG>3z`5k(h^8F`^D z9V2?9?nT3ODdUb@ry7Tm=+u)kJf>glopOpWw(jc@BlF*`tZ8yQc)zySQtn-dr`Kc0 zE?R8$9@=zf!{i6wBc@L~c12>QW*b>hH298W*Zelb7gd{(yg?%WrlhALVYcqfu~vD% zBMr&ju_-s!Tl<97vmADKOx#&0k<@?Ud|f*KFh1}S^Zw);*IA(*u97t63K_fMLm4wW z<(SH|L=Iy!cJ z+(el5&$>;CP0T#1rQJt|XZol4($eg%WHyvp8YQ}>w+wE@uexywvFPb_$ zy_%5VUW+E@A*QAhj)A?bO1m$NLa(%`?C#s7U--Ehe6t~(^5j$8P*RPdyYaKC;5z19 zR-QW=_k_d_nj0Osk>OvW+KiKk9p0xGJuw2F>W}oa?pR{BAPw(MU$;Igyx} zsJR8t{WJmVL=i$cHZC6Surmk)~Y?<<->jGzPhG#Jx?g3}L-XB<9zV?H-17=o$CoX#4F@`ftb_WCS}0{-WNlUSj6&JhvWWTjCveso7n=iHUX?2R>w zeZL&unW}_eRhG#A!J^}6ixo!CSj zYSzgu4_`Rj3f`4iZE@ad3q#}bL5-ufc21)QL%USOCPzz8QVkB*>^3hxnSthiB0nG=(lkSB_elJ=SnxYfnfe9Z!Cr9uQ;vETCa+dSOd|$(%(y=8Ytlq-O-* zUC#-j0`9)F%dW0d7VPcCg8Q2i)e0?9Cwfp1_##Ak0up-D1k`efyK1&8&4I^V^pFbSSiolbXMV-4 ShTuQyfRXff>lG92j{hIC6RZ#b literal 0 HcmV?d00001 From b1fb7fe24e353852b3ab8cc97511463746eac0e9 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 25 May 2024 23:46:08 +0900 Subject: [PATCH 747/940] improve lqr steering control docs --- .../lqr_steering_control_main.rst | 2 +- .../lqr_steering_control_model.jpg | Bin 0 -> 11721 bytes .../lqr_steering_control_model.png | Bin 17366 -> 0 bytes 3 files changed, 1 insertion(+), 1 deletion(-) create mode 100644 docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.jpg delete mode 100644 docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.png diff --git a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst index b18e4728cd..fcc9b5278a 100644 --- a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst +++ b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst @@ -20,7 +20,7 @@ Vehicle motion Model The below figure shows the geometric model of the vehicle used in this simulation: -.. image:: lqr_steering_control_model.png +.. image:: lqr_steering_control_model.jpg :width: 600px The `e` and `theta` represent the lateral error and orientation error, respectively, with respect to the desired trajectory. diff --git a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.jpg b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.jpg new file mode 100644 index 0000000000000000000000000000000000000000..83754d5bb01c9a1a4339248be09b476578291922 GIT binary patch literal 11721 zcmdUUc|26_`}c?xr9voMWl2Ve3?WpEHOnw(CdTr~7GocxkhV`^L?49g8Ov;DWHMwK z`eYeP5@u|JvS&ouCG_a`eO}+s?|FTHzvuOQzRy3;^FFV0pX*%rbzj$YU)Oz~bD#VC z9QgSObi~rs!W6{A0|N2v9-yD&JOdWS#%^}@wx$+Wq5r681?__G90(K;7>2PoyK?fH zqtnTKpZ?L}SKW1w(BNO!{|38y*ZO{G2Z4H3{~MYA9b3TDE7W6G;M?x0fY~*^>+I28 z`sj^+&}V+p?*E`K{-Ptog2Q%Y?0(T0xV`Z%?YT>zx$&Q9_y0tD1Y>^5KiQSJ7~p^N zm#ts;zl$Io2y|f;1mgYUFP?iQ2vqe51UfeK z7f;~@2z2;&5U8^2FWz4<3BHcG{vYc2cFR59-XPEt9t09{1c5|9fIxz%|ESw7{u|#; z?p8_f`W3W$+yME5yg(;G7N9_o2S{y~(gd9YX@InUazMr)-aWtYtK{7UA3xtO?C0m- z%P+8BP*7mMfPmn^!v_Tq96BH%AS5hw=kp)WqHq@{d@NA+kb#(SB7T~FW+ANefxz)PKjy=96c^~`C3u0=5;Y~d02#mw$2rM zdgU>sdq{G6Nsoe-u>-;bb3ZkW)xE3i=&u3)zv35H_+Pn0po6?TyI%4NgN#7zbN_3b z|MHIaT^q*#uFy;5lrAuu&i1Li!o{`^5rzNgZThIg=opmD7c)5D-oBWv?Uyim?h7`V zjv&wPg;v(=yKQBw6_{jNwmCF)$%yjcC&;tCH0-#V&duWLA!uiZv9(O5{ZpZgVJwpQ_9^XmT=d-+E4-q9oAI!b$)HlICQ zG}zbtD{62=B%hi)3e1sLG}SY0UDp#gZP^HjIOI|DdP+>a>4>rQ!7$dM<{2DXQ(J?O z=m)!CVq&XcV)PpbyfeQZLefXP2)Es_zInR@%=ihi=BO`t!hKnNKS8}HZjw_VFbo-H zU>VA+Bv+9m9G#*WAOcnzJ`a8y{u6|zHyZ&r+oufHEK4}5fz7^0Q^U7h}T-k{7VC@AZi0)-g&k11@VK^*QJsAtR4q>@R?&9&r2&;BV6TNizEK@4BhIM zYJT}|CY5K;0y4^JAH4>^vkvC>W0d6`l@~i~t)VR@V`9`Oz2uh~w{1?SWF?J7My81g z7HcatoG>>jBX+2ew9cDQlMt2NjhSK9A4uPb@)!JRg`BS2(H8*eBtHckt|))QrsWFL zwyd*fUWmp*PZzOwv!B=P6*^)iWEKXG{^D1MggDfN$k*j0g+*gbpI0)g#A>BR_zQ#9 zVQA%fc&c7hOunP+K*4=#P>_guPU)kV1HI#x(`$}S#6JVVc+q+im3}BfMWFz`fJ%6D zva}9fR_g30)ebI7t!=QZrntt2y?O>UEl|7P;ywf^zJRJhu>n1>5 zf~K4%>FO&b+Dw`tEpwf;;BFS;LuGoLB6!w)yv13k_!6-Lcgihna%^Fu05y+aKM%HL z+U7V-+Hhi-%mJ6GF8y8^QGLMl^NJdisP!HnyVOV7yYoO+{`D5)*BlXLO_FUw#J~gZAcG+VIX?%F~s2LgmL!koUr4?CTBmKV65yGF`rYHk#&plb;B>D_v zW_F4FEm?AMhVq#-WfEa^^bp#`ZA5%7@Nh-IM+rg?<9sHmZS?^7MW|ZF{xWUS;#1&DAynWy_Baw#j3%?#7#*U2~h+j!MZ~K zF!?>*>@2R_Nm-KIum3$IVoN?&Yig;rfnP)H?%I^4Qpia9+Yw4LIIH_(!XZLT zgL+(}UEaFjAB^0q@qiIg(n>wG2B$Z2Vg)_CboQ;x_0j2KIJzF$%a+MQX-G-OTQLS(dQ>aOBuOrCTVPIWpUtothiF@wH6$NkY6o&54^zH zmWe!%6C>t$2NGBm6JjXZPxEXd(JmSOy?UkFC|?MOT4i{qKKrr){X~DU8(O{~N_Je2 z5aXIh1DAT;*3S}uD@;qHoGr%gDN8+xPZT#Jl?kw!R)7Ps(`M=pp=6|Qi73A)bCXk& z&I(b9*3CZccn6OOht9&SqQou^)&B&kjL5S0&^>F)Jy$S6QR?*B9w%Ckl>O|W0}#&% z{6;J342J_)Wnf{pWZGBEfg&uDS1cynAsOmJiSp<-Xm&AjT*v2XW=kQpEe+I~R6HNB zSSDXGB-2S2h_6a2PCI!OQ`FCH2Uj3L-BSg})i__XH1MyXw2p{qWf#ACJ?%EvAEoAG zX||XxG{q!2GE+%~X;L<8T4pPIx6luhG4J1Fxy5Vm86Ekk1Y+S{*Q_6TBa45j^>nh) zSKTD@yatITs$0w6;-;5hZ1=qE86U9G@qan^IlI@^II!63qA-54MNUa&(G9YZ_vYUk zoS;*b#=yBNl}zuHG2&pfb@f?aMM&&uY2GX%VQTD8R_>VwPV%+)AL9g`5o@2XB>0|w zjCi&04Kbg%8IRQL`7>$Y^rF2$T{2yyrGKS1Z&XycCv>_Gj}c0luP-x?NVx1(m~nXp zK{c^ZIc-r`>*|x=0Z`zx(XG?!;rK^;3e&`vLf#H-SNJzvsVomb%uegfA!jG9ahFtZ zno-X>UG<))$iw6k0Rmatr>|^3l?$H~EcY8SovrFXS>y-V>QVkI=kJ_AX{|9OjTJ)H z#(Gv&Qgqa%SFOg|bE=Izb0F&8{|B$g8^8UE9S%xOX1<2#1l$wj{qmsfoka#64mcs4z#NNc=-3j&}wTZqrTndWDY z5^~D^yx9KIHTJ_h5x=0i8!tHsLv zP>uZ`TC_bP*asM7`zms_k-a8ZN4q3d6hAF(-z5hoY3mt|R!l;7S0AB$d2?BlCWg+n zitJqP;g-vl^Cwt?T8+Xz?_xeW+@Zc2n#GqAsikPclyt4kB+qj+KC`GeEMuq+hc^%3 z6nmw5q5EA*nf=lMO26Ie>6x#HsX>(<9FYo4*=Htn_-20m-E?U(sFp>@5eHFgudq8! zI=B#dGkWZzRb;1DzTCDjaJ!^9K-0y?+r7;UzVSS+buv`=^K|(In`av&qWit$-HZc@ zUvFgN8ml_+YyGbzTD_l2v-F(IIZdU>tz`ME-0$fZx?8_0WMx4x%W`s`tJ~4kY>&u4 z@yBJKd$D#@@d{NPmtk+^Y7C3ky>1xVdL);jx1?Ei26d4?LEar_#oytjUpKq?)^#@q zzaT%l?FGG9YQ~hms|4wUZ#`QPJn(s%HJoZm`_g#bi5Z-+n$25EBsP=Kw>{Jlc}1?z z_4?Cnq*Gg1Q_;$9gCdIK+yBM{(!FEO7Bc8L=oH=WfcfFA>xIXda%;XPCx&6ML@Cil z3%NpPLW^AWEmz@NdJhhd8V;3mNs2f zz=Z1u?4fv}hKBpTXi5$r{w?daseZ47v%N2dCAkOvC~aag%P!r;*iSl+Z{q(WlHp zDc4i1+=JE%4MXFvrfaN~xZBgi?LM=qZ~Z3yMT)MPn3f$3!-P+H#xJKkde&SQ|;6?Puhnr6gO-MzFDzq8@4JVau%kUmr}r;X3A$2NcQPE$L;gE zk~LSGEB67tc@^;$8Qd0{fUos$3?TupUD3mosfL#~ZgscT6&4{@<@E97V!MPT)Y?*n z*dLyH$k@}mxb&+|pE!oFRQnN`$m&jeZe(N;meUkm$HV^MeILYvI<6wQq?g_Gq&(avxp6PTwnOs#rp@<9xotouF@gdd9C?) zClC9{Z(6-lrDll!#_7ZwXZa0GB7jvy)aL(y1gX8Mi70t3o-+RIxnZ_@5ANPokFTN!)Gt?>Mk*qK42Tn4JoidL?sF;d&8afF+^{0Nv~Gbz}R;- z(;9gq@nE;6S>XWoNoX330+`rLKj=)IfG^bxEJ=A{TBbY(HeYvlV$=n(SVr2>3A!w& z>dV^T-qWQ$ze#NFSD4PtSnFmnr4v35FIJmYN5;tX-&5IF_)w^6e(2$A|7ELe`)z%O zXWtJ)9VEngHK5e1UYVoS-E}_adtoS7--y^+7o5O(u$ZGrwhKEiLTmP=-8iP0)g2UX z4@O(%${0W{`nH!@NlyAnO*4{3-{EUxS16y-^>Mz`fq)gq9T(@B9%eX+6rh+D>#A?m zlv)fHz5oDbObMAS=)yf0m;dwGa3&pKP&xw}Pf^~i3E)$DJ)ZSM7KguZolQA2p87lT zRt)%TNN_&{M)gkxgTbcnnNq*|9LnHU8k~J6d2HpWF4K0=8<2a$((9 z`$%9pQuBdpqYi1&xg8COf$H8H0kMz8n^wP?`L9KJs^SX^a2=|D{K@A#*{4Cn$=%)F zqsdV(?BMB^re!WG zI}&B_0Qq*C>C3IrQ2`w9;-diAtuK=p9DX|CZN33wL;JBAFUf1zRdD)zlD$d=rnY8r zuoS?2-#Q}jM(ihOt3f+pSpa)?+2SWidAf5}dhnu1y~Nynu8UL}sT4=~hq^~Fhh^y4 zCEBG@pgv{$DQesT-;Y&-yq`6B(1pny{zl&Lzyl`pGt7O>^JWA2-U(P$3uaYoK+I`yEg?( zdoW=uw8;wRAHe**DPFv_0FHY_dBz*fv$`1 z-bX1UxAvJgZ|Ekv-M`9^+)T~zr7Wut)YIWs{3!gYNS{ZC9Tm|xLYtGT}S0KTMa z&7>vW9J>%dymu1>I=|f0Sp9X9#(d~2t0V$=A+s53W_AN!Dc~$8Nyi57WGj(MAB8;6 zuz++4$mdo(8hleOiyyh&=!?kFB=zPt9H86&F?qa2$t>hGtG8&m^D5_&mai>qC-T&+ z&7w{$n4CkPhNc-mY!1(?ywh@hVC|KAM(3p$RbJw)e$U$vwp5e8%e1%B4~GtaM+mM;(@`$`fo_&bN7n;lyb9|+^WPR#Z-)K^z2e)?u-O`}(`e|! z@JKa&9vqYw))ebwx}m6dF0DAvZ5oitE|Ld|UIR*JJY+D#QI{uM8WOVi!@t~P(HAhidQZ-)ZFH3KQl1`vv*gEQ>{?g%-m$l2n#eHkl(Q zCpxf48aG(qOIa%Y5YS*fJfl-=A03$Dz1XfkmW+*K)NM@uXlT>-JE5uv>`Zg&+rana zTf^t7hHho@Ns8gio26h+JT$Nheopak<>a7)!iT8|S5_dmeGGyfu+XXwi74A@9Vp5f&C^ zBp+D=oe&aB>hMpyQ91aTsJOda_~t;yQTbMrex-}no ziZOEH@smaiu3XC315!+?ljJI@3cR%UuY-0p`GDq}`hroP#$s)fet>$e%eB?{|Kq%8wWrg$)UP#8|Ay|crkDr8Zrqe(8FEXn%J6OgGB zu*(*5>KEy$D!F?26g{__!lEVGWtfrcuWjV<&qu^hJ@iQbA(sA85^4=K=5@zvnM~w~ zb|O2S>quoc0S6B6;z13Erq+}3$^S7UB;)$%qQ9G%ESVUu{hfEtzsQOqd*rJGR%@Xn znb$+CYzZ|1a+BBCUUG79#`UqKUdXMPkEZei@ozWEp&yfqT&p~#o+X4u@_2X672yLd zOlF*DXHKCZ<^4_Z9o-FV|0kh}CQCN-pjCMORSw%aYoS+g_`QeW`z4>3Pxc`RV}w>} z2)vP3)u9r)m@VaynW?0nVxB7qfq`ZFs&m1U2Xw0q)_l|k$M3w7t8X~f;W~*u=-%|1 ztI}ttR6C($ug$;Aj3~3m{h&myDaV#fpoT`9U&%1$DCe~@%+;y^9P6D^epBp}ql}9u zOgo}wjnrB?$2GJ4z`{V@J&NwQS=nG#|9e2sr+3X~NavmB-#Zq!(fItAX%YIw9*35? z%6%%;t`*#j+GI~S08P;m+Zt&yiaS=dUJ8n-IN(17seIxU!cb~bo?pnMSkC3NrVOhI zVo3=GSMUzqV$Ov3?}F@C=ygQpd;b#Yzt6x{{biny1Vv$Y0>@7@9Yp=;11Z}5eRcoR zVh?y2xg2q1=cN0`(U&4bu|VUs3$D7s%d6Ix8t-(?->TY_yleDWRtGuL%M84IDb02Y z0IZ?bs$O0u!47YjR%dCtlC1-*srQ&NPZJXWaM;Yzu60M&t()B3$KO(9>ary5G>3kH zVI0dVH&94sc4U0RJES(e*)P14>@T3&GxNb`lmPd2hLBCRFJar+mBA@RR`$uI@p`@T zKhDOzzYVp?qc)dTIiCsa+w`N*NP1a%1CB7;i#A-(as$FNgS-gc#n!v~%`_LelA%?# z>>E-~`=50dya-o!E9{#+m4vgbFOK)YJ+RzIcEFuHVIkDkW!lEx_;{GLge~-Z<7Kqx^tGIjQ zob4h|nr2SMeC%cyZrp!x7fbog@&(8cpmW3-YUIG;RaVdy_=f5ttf96n>DE@Y;fud# z>A#Q`MocvnlFb%*`F?`LoZ8^nD%EWnr`=(#v_b0QBmEaG{x%DWO5aJM><&)REx=FF z9z0yNa?@w$=G=N=RPbhbX|;EuJLmZ}k8i`U4AR1XaW0j8je-sf zW){XAn9Pabh4Q4uv@v?OM(;qG3x_>NXLo`OaTDtx_9ZVjT2RD}ex z5Two;M9st_FG>FCKSOjFJNNnSu-Dp|-|7QXuoGezI|+}{Vj9kSq!9>%l1Y)@CZVok z`gkyZLcmZqa5p6i@)bq3f@M!0+*S`S_P02w&3qSE{-IeUhA&ntNhbnRW7@ikA%9nR z1>XK=^kn~;8y?cV_J)5N-}hH;?xA03mi;q7fBuylNy0($U-^mpXKwgOy#F6rFwTBi z!rstAe@*{vXbcPJEH~ZBD!}_&=Sk(jx89Q=t95gVHJTVpR0{nTWqa^Ef^` z^1RMr{6OMIo%V{`W_S~qD0+lIUi_Q zKX82;$}lQ1>eW(BDe2PhAD{lwYrjN_i>p@=7IvPMjD2uTQ;OfwyQp>1Z>oOTw=D5= zQCSs>hRZ9+A4)O>(`N^xaHJEU-2cKGvv=r2_(l3NgG=&~# ze_%nOp=pt*Y3f8Z1+{18PN2~hwLfNb*Q$oUk}#$@7lCAU+5Q|v4Wi95$;2kl z-7{%6qFM{hpCqjI+Sjm@3jnw~TEo_JSI1u@c>~Qsuk8C3L-QyI-431b6?x})X1@LM zq}8Q^a~!XS;ga*lM9BJ`Z zqX2u$A-&@e$%d6X*2V#>@6sFF(TK>bq6p*XL(Pxmw#@4ofV{0Cb^i@?wdXO}hYRZv z5;J96=&AiO>i6_2aG@Vc?5xc-X9AYcFBeRH`wdHen^qN4-DmcPzs-Y*@Zp%}LtkzS zsnSrVQ^zVL!#4!xG%R0Q*nQ83N%rCldV*QDB8HDJg|F>;gszX;j8>dDLwHNq(M}n> z6FVr>r?-E8RkXw5Ag$&MN6@r+QMSy3!CHvJ&IFInbQ1N4I7z9KVFO8C*>KvTDqnhcwnu) z#n37vmew*kC5F(I9W8QGs$I`R4ASMVYCUycH-=Iia~~gT=Y|pk>s6PiU^CW$jELUj z#xPQXiX;;pMn@)9uGth#o{dqjvF3ZH)qAQ>U%Zer`F0UKJKt}`>h9Qk(cx_}IhiaE z^MWpVn5qc3u13KamUXg+o_%!)(qpFge0rUZLfJ-FJJeA7EpEMHb6i626WiM?xp6~- zsrZawHg^{4dI1XWjBI~S6T*7l4$On3f031Gvx+En>)tUikV))je$qpG&03uDm@J-F z920{P2VM@Y?wx`3CGu5GM|Cy7;xrpxw}@f}Y=j@Sp{pEqw$LxhlbpGw^)#OJ6jPWC z)18gDg5&F|RQ>GWN3G$8KWAwcS0J1QkP>bm#GaMil)65B*D0DZu6xl&&uPUYC+Azj zv~6TnsZ&V7Eico%Bu6cAE7gln?kgr!Q!GmE8XRes5_VHa8UrL*z}W7m3MuU)I)iL* zdLhCp5g743STtJt@+ixThBt$#0CIb+vV#?G-baA>yQIL9`Bvi z%(VTp&Wtnl+*+FYNmuo$P`(|cgR#iG(j0c;BSjg??FoxXTz!gMjCRdGoG(#ji$pS$ z^z&4iAvG50G8QKw+*lv1^#GebkpVe#!_EEyE^}2_my|dj=KaV9pSF`8t8XN!uyL5AM{)INfv;(-i!A02A@ zhsU-SdMe9p?|bY8uiZZx2RgcC8Ll&j1%84wKDP9~^sk(GJi0tY^ezV!g{JEtbUHc) zRl=8h$KZgmXrV{)C>O8NLm(`OiHStfM^rO9ycD?|!6ju?{cqZ{oJhVXh4XLM3Nz(p z+3-+j_U>|f40bh#W9{weGq_{r-WK8ez;~O-p2i;>=uN_(wZpdb)+1f((2|Ax~1l)&r*3 zKjMe1x_Hw1-rrj_g7|#PA{8&cJ`1S{O7W6F*_?N@YYRH(~-Mca3tSJGG z=_WB%IB(_39SA9Jq!G`2DxZB0)E>6A2)06;4_HSaV9h_A9z!meb)8T1%KeNF8>&?FS-`<|9vzN-%R*xI>|29fK{d&0YMOCxS&`>o@#BtgbB4QyMmunlL79r41 zWIAfMRb36K@*b#A=Pd|W6HpGcIAmnWBHiCo8M|9O3V}lrF|sg;2UkI%7e=4Y)}KIG zVVciLM|Pp0eo1Y%0MtMB_;{7Zh<}lPB3k#9SybBzgENecNlIjM5ei#_rccPboai?2 zY2oGzj?ZP-U$zQq5tAfsj3|*Bn2(!Wi^jM=LF$UCANCyK@Q-rCLd{fO-Z3WAJtOL9 zv%#&J#n_B2LF~{>=tWq|%6frm;k8`zTyr*n4(-W}&G+Gt^M$@ISuM%3#(L-owvbPg z=tBkg%y+<)V_zSxPbZU#mqtC)bAqpvLvTj~_B z_kR>d_4MHd>#a?ejC$05IE_kv3&{)3Y>N?BTCjbvv z>EkzujTk8y#Uw~tPA)h%>4uH=kAh8O7l*K3p)<{kS=`E74giW$4%MHS$$OM6O2+3& z;PdpA0-NrEl4z>cKH@IV&)aDxN;U>o%PV*`6obEfu(Df!mGqdg5TqU&>F_85oTDTi YY#zr#%kTQLyIC52cxCrT=Fh?Z0n~N9RsaA1 literal 0 HcmV?d00001 diff --git a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.png b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.png deleted file mode 100644 index 961dfcdc05cd4938c1ea7ebc79e1c8e0314e9dd4..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 17366 zcmeHv2|Sc-+xM8Lkz_KmW)7{2#}0Uh^w%?`}ih)tgqs zU@%^ik={NS4337uIJgljK?xByr2~F(`0O(z!irl(2VpP~ak{=G-95m`g-U@*5pua(sUKQuZ|_X;U=L_Y3v!`S?WOPr$_iL8l#Hppql*Wf=5thvKm?yj z9&`#7{07C~=N@zL!xH?%VQq2BwyLt=QODDhN;ybzFm?f}F;FI`DiBmav5c{ig{g@Y zUKc!5UEC<(mm$T`jRtkmJ?c$!2PFnLypjSI`U48h?VaqsU49q>+L<54+sB3G!QPmX z0{FAE1q$8Xd8w4L>!67*!E?WwKh4$I=g@AaK>xi<7f{a z7tzEml{nD6$rSIUBCry?6hU7Ks{@)se+jy5yuk+#d$8)oo>KY*DK&zWx(@q+sJr-p zmm;dM2X$dvW3Q8`r|13yzE(IFM?c>^WP4?t+8^gwp2WoT1W#E@V2O7Q|&Wyy_DEP`MGs#rf#+ z%s3VGr5bnp<;Lut_#Cw-)BKnE|Bb1ZU|a^%n??iU{b0!-tCt(O2k26$5WkmkWX}U= z_#f~48yeof9k2h&aDc3fN5G!yyUe;J0@DMR3GD1m^Yvsmqj=LPY{IY?!ZxS9!*X-> zYCP?KU*KZXKS$|ztPCmO*wVcN0bcBx@HqCEY-TDgfA;^~&dQJ;Ks!15gN^Yj%1edz zY;HOKHa67s--ADB!#3ZauOAZ9KUkUY*U(Zt$T|@90oNR<_C7u?jzAEP(%q?`00$lc z@*dqRd8Rm;Dj99yyd{^T_OOez1PE_8~yr@bR& zK!4yDe&*lLj3X>Ek`C;>=q%+45Gg?%LDi*EX^?C4pm~6CfJcWc0=()UwcI{r_M^Shhb1j24Z{ zRtVg(PgpkWKR_YyY!|aEO6R$FpE8h21tA-Bj{ia&?0r0!;y5Rl0LVuz zN`W~$Zt$T|p=gIlcJT&{mIMQs1d6o&Ir^aXvp(Rkivckn`-4ERkK>Q>@c%MiVAJVO zZS(iy1s^~>`hOsd0CA&tpd~xPSo~o1;|D$Hgh9%_SfvM%9s0C%+WuNt@Ytnu0J?!L zi+uZYH})?aef*|1>{xgC;Q!;J5&W{BVo!CA7351qC)#3k=kr^V zq2lEWB~ptO@;-~XC6pWEah|{ifP2gJ;K>{=kRH1x_@w_qxuI=_jf{_Ww!h% zWgt3RbdbyL>7N?uuv6>5V|pJ?dk;|AStD#~=Uxm#EpGERwG1|=vPi#%nNhmpxU@LDxqi0fPF zw$pnHs}5I1?$>|$;LwcpuKgd0n1ay#rN%3cUj5p!+DI8KSg=jz+BcY_0&i!uU13zT zLE6ykkQc1xTVt)Y{sXVSsS!S?f)`kUBTS#kZ^I!u-?V0jd>%A#aUir|aAY`)QyOI_ zkoYhKdPKoMsdg;#_)-lD7C}Owh|+gjbC+vT#Ms|EqQenP&K)O+?AGB3^h(gBi{Eo9 z#yF@jzlJqbN6iYa(K^s>mFA&bp_SP~#tFfBq{9(br9R9}oQz%dJvr#XiTmGMRVzMc z4tyG!I!(78?UG{+=^In--a=sw;jt;|LA+V$6m<^&y7c@#>xFEnPKsS9;yKJ<%YEl$ zv_M+m8|>UWu*@_c?v*+)xI3b1R*@7`oX^MXQWw!{QZx>ltWKbb3U-xN=2*6g1mecc-wPqJxKYVQ@#Jc4VRs69-_v1NN!K7=N1Pp;QsGULyZ+ zd|)h1V=F@)M-ys`7i&#~FRtirI{=%@sK)f$(}F*x`mxmKV4p&LS+5ycP=c zuf(r-WaHtaby{H6!0L!QlQCeq=2`J5F<=NyF!@YA z$#$84*8q83PR2(se;y~n_}jOd&HxM-$(yUpp=ab~p%l6Nc@JQarc3+ArD_)z;m9mAyU#lDYWx5O4$~Va*gTOf>5snxHYXB#sLUM0x;>1gTxr3*EEesWdzw5+o zO?-kh0>Db5o$XcwGHnKwG}(6~k&6E)WR)@)e7~s~oCvEVMJ6{V$`cjAAinb^@Z7lz zj+&?ujNcoj?GXdxWEj@>^h*VtG{#r%Lp5jN2*>M{IH&QZ_p;5vemS`uzi*hS7TTpMtTE%dm5(jG} zqe|((Ao-@bO`&?jhJo4FhASu4tx~S_#Q74W0Optau_AC}XL5aXK{`@+>t>Au{AfhV z++LrJoPO)HBZu_#Rsd4Va=O;o5b0+nG#^znBqAvp1pzsM`Cv0?c?V0m;mD6?>Mz_( zc0VB~@lMA1`1q&Q+fUS!fWsSaQAeZ4Lsp-Iw&u&kA}^Wfq)SH@Yv)LR@Dl) zIpDI1PBsqg?G9q7VjQ1=qXWKD!RpZ3s8VfsDtFT`mm9COM^{IAeW%l|W?&sFh8ELw zfYY@ZX?4rvTtPbP#JRz?Ot9bQBliLj!AbSes`Uz!XU1ar^2Fg|Tfs)__?S8aoPM|H z?x|hKPnvkXpbK?EU^(}z(&FA3*dQ-G=w6Qi(i5xQYFl!A?-woq0r}Gi&^w$+; zf49o+Kjirg&sEVDjndp8{J>;2oEVAZL}u_u@cN45PMG^0pT6uxajoc)ZAVpYIMu~8 z`)I$7b0uJcFsEELG1nHpgJH9&H>|ys;(LIP_DOT*Bs%DXc052yHi#<=wHMiG7;N#j z!?x4Osc~OSbGz{;vAddxaYI0CapR!l+9jMfF}2i90lT}94TdFeb)AtJTtLP!uOd^` z`9JCgv*bnYwj1x}Z#|6uRUICS%;SK^A=T)El%%edXp@#9|F4qkc4u%zSOL6QcTI(= z$#C7cH3m@h-nMo+DWnPP{$8(R@j+dX@S7hXyCSMbq zOnHE-I9`7nta>)BUlSp!oog?gH{@RWKK4?A#idy_lwH+&I1jL$RiPvEKqlt{%b>v& zUSX48pD~X2A--9z-jtQgD% zgyIO8r3Nvo&bd|+>(pZ?V&14$pIDHtaxNEW_@bA=A|ouy#Z8}ze5%FACPy5P^FWvG z1xAh9&Tug`L{Ub~tQdp7%?iefPw$It(Y0#@Bl=8=Rc?`RmKo-H@&NLmfk{NdBD4+RK8J(4Qh6_JxTGRx_k8c?w8JNj z4OQDA&k_!#gk!7ST@3`rG}z)2t-IW~r%}T}Kn{&P2o_Www6?}@OX=x?^tD|nM}rd2 zKR4vTtvs$>2^Q3K^IY5)iIfx5g%sW5%eQ(9zQ<188d@!=2?S;mNMx7DW>p1deOkJW z%D0mR=~9MDJ}0y@K}VMvt}D_KDb|x)u&P5T>Zx3~3QGp$flyckAQj4TknX{W-yq&7 zXN)Zy|Js_jA)k(}u^ZUH>g0(KhLpa^Dx+JAqoFZ#kmM_Vox*$|Uo&^?IHc90Kw7=W zxBJ)#I=eCtg}@FDKL86DKD@XIO?H017r@e?)3hT%hvm%5Ty@_SqC8)C>RGAQM< z7qIq-HG2RbG#m|#B4K@wH>L}3y5>whlI(M3fw;tp2!fO?q3YY4?Tr;* zp0%`QbR7%a8mD~+fzU5juyE~x?C|gV5i2}4wQk^xY4pbO*^S?%VQ-fL2LqsD@V((IPC2UU)PE z&hbg}xlP7Z=@arbvcWv19B{UC*|_tRXoa}ri;!!)sMm5&8G^&VpO|m?oJeuE?kAmq%@?3SzeBSGqeM=+AI{3lydN>FGH@s<3-;FjOcy^^RcWD}tWfWv0K4Xq&IVz=Wk8*A0t_2J#abox_8!_c#t{X4#g)tMujYe@{{~Gtkvvg6<>)WU4cK_BbZaC(_VDFlJ5-N zjM}AKL1W+i_(axP_t-fVkiMpcKM@DQhgNogpk1{T% z4}9!Z(S&62@i~}8{!Y0=m69p_?aj!(^9{ozwlXfYA_na*uC{W1tH_j-;PKY~PF=&F zc0SBHTC)WV&kl2g2@!|Ick?#$*WP~ryl2m;aaFEwJS~`3ZgsEf*{4!-2Gm~Vidnw( z=c{M@WzLO*xWWjyncR(V=JSxVlIKEq#DkI- zRj2QbZ>x$f&DI1GK?nP3pJ>5gnnz3e(LkNldwTjKpM4+&MKPm37CI4$r!}nF>y#?Q zKNCE?$7wm=Kk|Sm1$bm)A!D)E|feix*mo#*9Z)VxHp6 z*NK~!y&K_6G`DCO8qjr=e^GG#$g6m@Fz0K83K`aWAjCmHz6XVmD)h*IE1<|?Y7_Yl zW0QwZyIIvW^KWs~lX84#0K%`V#$%aZ*4Z2y82LP{n2y`T$YcbU%UOF^2X9otn92Kn zE8|+1shtb?5gV_84l8#nCzZMk-QdH=hOg5!r(XFeu1yY^z9&9^!lzYz>)I8^g5Tb` zKLYz@BEcQU-p6IMe>)!zoP!ro`P6<1HE87stX zyf^qruH@O1^M<|yOlJkF;L`Vg_imKN_Ph5!=}$Y}dw~a6-qh=9;<^T`1Sg{ykXXI` zlEH>|#Wf={L&DByy>7gu)rAZ*pYG8*a-+vDOI+Riokz?FmekVW_$=gFK&+~L*W})k z8;S%A_ffyW8uuLc?iOO?4JN`Jh1~#-m1X|M?X9oM(bjrR*@j7?>h7!g%NuoX4eP3i zz0T_Pcp21Pxlo`tQS4q-6Oh7fwM!D4`~;BD!0`4h4maPG4>$TePj@V?>Wi-nx+`$* z*V`4X+dofjy7hFTyGYV!jZPGh9}X;sGMCAu^L5PTzAlV)nCpnv&H9rcv$_HM2m z`5QHe&69!ra%9c5_nLZ;ogj24dX5{|t<}HG%QtK_auhZD#JbaCs1PG0J%-b8GiXW& zQHgCYAAamv1={rUEJ$OKLM!O;(?YOqM?jW#3U~~Y=uqa0i)VSe%IUZSs*&lN{VR@c zm{cV6G1r5{2Z|%m<5f3OwJ%%yiIk(tnkD^COCAv+_N=m10-o^_*rxHsP{Y_R_hygx zI%4|K1=F!%=`X!cHA|O{ z^$>k0XltMxlAE6>xMnx%`qU#6d1B$Lkj6V9aQ%_N4aPAMRrV*iHRH>S-x`S8DUHM9QwzPnHrOew34# z2Ek!dHs~>h5b~P8MAm(PL_Z5j6tY|c!e$l&7`n1J>*8BkvTn2>nyfV-oNmbr@_bzo zBk@jMHO!u=#p}j`T;Vyo;iH0ySSJ7swSk z-pwAiU~-(*G!_ejS0p&BQEJ{EPczDmCie2*ZEt>+$9oL)umC;wO_;3oGu@wmvjm|N zOh%qI;RhlIHb}O3wdQ~ncE1W)9Q5ER18zb)Hw=t4&un*G1-~9MD^pVRMS{2~a-VvQ z8Fe^3?E;j=JAp(8zaw3~?M>N@p-O%goeOb|K0Xc^kEBsxqbB5(3ZtOHkB^;M8meRaCV%lQDauP6aoE*>cbY!=}Hf`bch zTMI$?qi74g#`kGS#@i1OKDd(7v#h>n0g(plSP8OAVFaefZ!7kI3b{Ec9Xlh`cfRHe z$W+15nqcVJz5VCzAlB4U(r+f;Ic(Sn_1Z3=9Z5HMz^f}D4qj%by>qGO8L3eI7U^RaHePblVxLN*9${^*4r>j$=G*fixBCQ@| zvys|HY4zx?lq0_4?z>G)*R3`H7h6b6AwaUbqBrvg=`GRMie^DHCc7&GBpX;~fU^2A z+S|$-pklqalmckCB4!YDs(|k3PG0${M1OIN;wN9LWTqSWPS}{W36L@wP;6(8o!Lok zcPr`L_*!angyX?4+tlGy2oc(7NvdSO>B?+G4bn32=puHo+V!g_@HR< zQioL$hg9;rZ;l%B|rKjt~B=Y5O-N1H8p=iJq zq2lrFu!vnM`9729UDryGVILkZ8fqu#I~o2!{wY6#!|S892S57hx8zg^Pl$N2F+-rf z+(%s?8r+zHRFm`!m!T{QK=Gsw3Ii)?Zv;3fTsvBW0KfICQb_=99UVA(7%G~P$;=@}$ikK@OEBm&9AOHiYs9H}%4*yh)! zBmmrwbb>ud0?fcjdYeyJ-2<|?rjc=O(e?oIL1IE>0yK4`2ot&sfq`~hYN@hx=)gZn zcn;wk4KXerGbe2fz`W{)T?3ANA{d$wLpW0Taoq~2%|0kwxG&I&+r)uKpZ~=P1u@7P zfPqN)CxAgoP{2V~!l?CN`4$=xo6qy31n`?&S1y9FnBqQ6((aXL=;=Q;UXZ46dOR@g zwcOxJ!r0IoJb(uV-wa^gUY|FJM~ur7U(LNvvymTkQQi(>`ZVT|x;3sWaD^JKy#VYm zM<{4);2xI(t&~V%5`!8f@$~UsB>!DO@%bfb1g;GsT7#?S-K1PY z{;#!Zp$7ZNJH_0cauNfpXLm~0nzi2_t!9Swo*tu6p=DeGl9B&OcxY3icCy5~xip0o zdK|O1(zUcE>{R}Z4P7Y}Eknh3r1cihv=c~F@#c;8lk=Q2Nc2dkD#>5)z%5d{sd7SV z+W1hP^OSPMo*^2}AG-Lqlm`66&pom0T5oRr$E0v%$GKCkYm`brz zo>as+J)>tKuWZJ@nULygqJEX9zL1)S4%1mEF}5I+>ia$UDo*tE_Gn2A8cWtbV<{9J zr%(ADTnJ<4Teo0VTUIY!aT>hIwY~c|vi>mlxFnHC7EK?2qE^UadGLyjgtm1ofQ&*w zs`dfvoa({dor`og0@gzhw)>ZJ2CYLo8_neAuUb!hH=$ql=>{oCuZ%FDLEuS+t|4F8MeeAscBFoGgYJ zOifF=S~(CJX}+&wjhr-?mo5pYjz}D6Mm@fWuv*FQ1mbXQyI`=EQ6|9w4ouFi#vuTX z-VmU3IbVbZ2k=JYJ1W58ZU-lW)GTgESO>s0$`xJ-N$>`6w{>@mG3bx!Y0U@Dr~z_g4ICrm8w3|XT^#7pAbMQAAG$if$25a51dCsZ+6#^% zS`zwbvM1c6X#@Mnj_U3`~uP!$45bcbtL*4lECPB|umUFi<-y%mrbf0x;D+F5Z0^{sji% zCI}oXViUOUKrdQ22yp1a6vqY=ZD1A-dNgzuzl3!;V8p}rVH3#tKthL$v1?sQFPsD+ z?!5#U#3ug*1~4Yl0R~qFKoBAAs2}HSiZuDM0+Ru*)5!3TYq)_~mary+cLQk!FPR{m zO98Ia$YJfBvtD3|2X9$2kcd=57>NG`1^~MT80R7xfQ~~Mc?vi4^(sp&2QUlgV__)p zSi<_RNJoYErukPGES|qbGH^qXJQV1&Lv1fYgokkuSnMk@hzCFQ{SUV zsAzul@VUOx+!!Vo`)~-nI5Hy{Ug?c0LsiYzO6|PRAF$BD^7tIU*WwKF8T=M!`%m+n zM6%I#g~6}WT!-UR`qID3N!Gf=+p=ccVt1fR#lf48ZIMRbj&zo!kN8*5;z)HbM_b2O zLo-QJiQTVy>WtdIrFq~g_!75I!&mA?V(Q~ee%Ty>6uZs<%8pKJtvmyFdBIbJ!qVVT zzph2^vvIT69KZT%4o=dt5&1wR*_waHa6WQ&&C%**X>Pyf9y9)Bq>VA&oc6kO9eR&e zeu?Op_Zw+RHf{9QGgPDOdYQUN!u{530+M?lMq3n#%pH3(vT;|u*2=!1aOPYIri)mt=jjdiK0G>@G47y{H{#xaa@R63^wvocngLTZVt(RBU z%FTP;t3C?#4&CVy)M|GPAm7S8s3+;7TuHjQdN5n6&#kP0n9<<1=+k z(0E@NW@15d?i_QDlBKO5dF>aytoul?m&ExOy$*KxR4ai_aQ(hNacCWSWWMbn-*scD zxuQ)&e54?!_rGl7dlOI}jSQ&B4?A*gVJ%_S*MH&encOO3yMWwW!-~24SKfE#FzDx* zJFkA-n=H|N&^YLj`zsNtotLhfdrf6Y?ks#h5al#^+4Roak*V}?xwLb8-2^6sFEVSd zI~XF)zEEOmF^X@$WX)eiuD|nPL2#-EJo^_U6Atzj3aVaQf7fke3DR7v0~_;#6fad? z>Kjsh43XS>S`c0mH0Mleb6t0!!vI{#FKoIq9fGi^K$CSQ(M>yzQKef%@bN-j(jZ8% zJ|G;vU?KFie43{&;PK8Y(^G~mLkS71?7!`mA5MxPW5&K4ecx|`I9*7J%dwS}#mg=j zwa>+i?1n5|RHcgNOWhp!e%IAk)tj{Na;YcdG{u~qUfi6WTJIpC$rJHa{6J1^4{JVG z*5K8g$9n6$FSfBC0_=@rnIC8Q%P{Xp_N0w7@^X;!Xbp)Sqerf6I<1&0NF0I_YI=I6 z)}u{t^*O%~6puuHJAWpd@AUW{9vdwOr_bGD{(L($_gxFwb4O)1APNqHA*`V90^n86 zwhD|@E0n7_9VnSlkGOaSA$!AD{%t~|C~9y1?iCFkX|K8Y5o8mTU*h%JptemTNVKBu zobLj-X~R`CSzaya-Z@36uzpp$jo5c=j!u{*KbcRH7(?<+mncw6_9d3 zziFyitWwK7Ha;MnG1riGPvl^;&c?fJS9@RO+O-M-GtG><<(rGRG#2E7RtxQ6-9C@^z_i?|v1G&z8M1bA z_T1Rmx20UnUr?*0yQfU9_M;K;|3UP)Po zG4XLj@y(j;@hR<$gUl`-w~&~Oxc528?Pc=StP8&Hj9~o=N#T@>(w-y(sRjx~!o#Hx)G!80{g!2-y9a96?mp4HuL242eUIApCu$4?u0z5Yf6~iGREJPbTP9l%a!ku zrFUH7y+e`Un)q|wK>tv#48F*8g&Vd1EYZiKB)+r1;wpbx>zagw7Q{5#~QG)!X zgijTULz~j-Etx4Lr^aasSM|8Ji)EUL@GA>>b?7&dxGvmZQS++B+kOs<^XD@YsBwN2 z^KFIX_3jRSWj?3LGGLe{$EjKFEft57)O`%4 zB|oV<_!}RdxckgJU_FZ%+px~E7OScmTFE@}cEn7n#*10t;L|Vk{)4-I(@bG6rp^O$ z^x^g1+#0vN6PE}h@$eaxp!PEybCtgGnDeOtzmZAD-0UmHZ8-eH-Sp%lM$ z&*3vMfwIKBk^afNI|To;zi!%^Z;*W~Ju@Z4{F!${E2A^S{Q7&FG>3z`5k(h^8F`^D z9V2?9?nT3ODdUb@ry7Tm=+u)kJf>glopOpWw(jc@BlF*`tZ8yQc)zySQtn-dr`Kc0 zE?R8$9@=zf!{i6wBc@L~c12>QW*b>hH298W*Zelb7gd{(yg?%WrlhALVYcqfu~vD% zBMr&ju_-s!Tl<97vmADKOx#&0k<@?Ud|f*KFh1}S^Zw);*IA(*u97t63K_fMLm4wW z<(SH|L=Iy!cJ z+(el5&$>;CP0T#1rQJt|XZol4($eg%WHyvp8YQ}>w+wE@uexywvFPb_$ zy_%5VUW+E@A*QAhj)A?bO1m$NLa(%`?C#s7U--Ehe6t~(^5j$8P*RPdyYaKC;5z19 zR-QW=_k_d_nj0Osk>OvW+KiKk9p0xGJuw2F>W}oa?pR{BAPw(MU$;Igyx} zsJR8t{WJmVL=i$cHZC6Surmk)~Y?<<->jGzPhG#Jx?g3}L-XB<9zV?H-17=o$CoX#4F@`ftb_WCS}0{-WNlUSj6&JhvWWTjCveso7n=iHUX?2R>w zeZL&unW}_eRhG#A!J^}6ixo!CSj zYSzgu4_`Rj3f`4iZE@ad3q#}bL5-ufc21)QL%USOCPzz8QVkB*>^3hxnSthiB0nG=(lkSB_elJ=SnxYfnfe9Z!Cr9uQ;vETCa+dSOd|$(%(y=8Ytlq-O-* zUC#-j0`9)F%dW0d7VPcCg8Q2i)e0?9Cwfp1_##Ak0up-D1k`efyK1&8&4I^V^pFbSSiolbXMV-4 ShTuQyfRXff>lG92j{hIC6RZ#b From 3504db00a666d84de0e4738fad1db78142f34c17 Mon Sep 17 00:00:00 2001 From: RyuYamamoto Date: Sun, 26 May 2024 15:42:25 +0900 Subject: [PATCH 748/940] fix: typo (#1023) --- PathPlanning/DStarLite/d_star_lite.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/DStarLite/d_star_lite.py b/PathPlanning/DStarLite/d_star_lite.py index 86e777d7b7..f099530173 100644 --- a/PathPlanning/DStarLite/d_star_lite.py +++ b/PathPlanning/DStarLite/d_star_lite.py @@ -2,7 +2,7 @@ D* Lite grid planning author: vss2sn (28676655+vss2sn@users.noreply.github.com) Link to papers: -D* Lite (Link: http://idm-lab.org/bib/abstracts/papers/aaai02b.pd) +D* Lite (Link: http://idm-lab.org/bib/abstracts/papers/aaai02b.pdf) Improved Fast Replanning for Robot Navigation in Unknown Terrain (Link: http://www.cs.cmu.edu/~maxim/files/dlite_icra02.pdf) Implemented maintaining similarity with the pseudocode for understanding. From 9fed26e503fb28fbb6169e8fc3f8b4c29975e16f Mon Sep 17 00:00:00 2001 From: Tim Huff <89954856+timmarkhuff@users.noreply.github.com> Date: Sat, 25 May 2024 23:43:05 -0700 Subject: [PATCH 749/940] Fixing ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py (#1022) * fixing script * removing unnecessary code * fixing CI issue --------- Co-authored-by: Tim Huff --- .../rrt_star_seven_joint_arm_control.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py b/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py index 0f449bbe51..3bc2a5ec1d 100755 --- a/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py +++ b/ArmNavigation/rrt_star_seven_joint_arm_control/rrt_star_seven_joint_arm_control.py @@ -265,7 +265,7 @@ def steer(self, from_node, to_node, extend_length=float("inf")): def draw_graph(self, rnd=None): plt.cla() - self.ax.axis([-1, 1, -1, 1]) + self.ax.axis([-1, 1, -1, 1, -1, 1]) self.ax.set_zlim(0, 1) self.ax.grid(True) for (ox, oy, oz, size) in self.obstacle_list: @@ -375,9 +375,9 @@ def main(): search_until_max_iter=False) if path is None: - print("Cannot find path") + print("Cannot find path.") else: - print("found path!!") + print("Found path!") # Draw final path if show_animation: @@ -396,7 +396,7 @@ def main(): [y for y in y_points], [z for z in z_points], "o-", color="grey", ms=4, mew=0.5) - plt.pause(0.01) + plt.pause(0.1) plt.show() From 1aa9a12873c49393dfa1b17a01f72e38b71ece6d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 28 May 2024 20:50:36 +0900 Subject: [PATCH 750/940] Bump ruff from 0.4.4 to 0.4.5 in /requirements (#1024) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.4.4 to 0.4.5. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.4.4...v0.4.5) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index cbf18ad938..6a07880f45 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.1 pytest == 8.2.1 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test -ruff == 0.4.4 # For unit test +ruff == 0.4.5 # For unit test From 01949a6edcf79100527a24ccf7d07fad235df03e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sat, 1 Jun 2024 17:46:27 +0900 Subject: [PATCH 751/940] Bump scipy from 1.13.0 to 1.13.1 in /requirements (#1025) Bumps [scipy](https://github.com/scipy/scipy) from 1.13.0 to 1.13.1. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.13.0...v1.13.1) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 6a07880f45..337f56781d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.26.4 -scipy == 1.13.0 +scipy == 1.13.1 matplotlib == 3.9.0 cvxpy == 1.5.1 pytest == 8.2.1 # For unit test From a9be11d131e404df00d9b91c91289aec7bc895ea Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 5 Jun 2024 07:21:06 +0900 Subject: [PATCH 752/940] Bump ruff from 0.4.5 to 0.4.7 in /requirements (#1026) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.4.5 to 0.4.7. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.4.5...v0.4.7) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 337f56781d..a7cdea961e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.1 pytest == 8.2.1 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test -ruff == 0.4.5 # For unit test +ruff == 0.4.7 # For unit test From 9d06b1e3c3179f9da85f9646bf2e25aea0e4b068 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 13 Jun 2024 12:50:05 +0900 Subject: [PATCH 753/940] Bump ruff from 0.4.7 to 0.4.8 in /requirements (#1027) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.4.7 to 0.4.8. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.4.7...v0.4.8) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a7cdea961e..7a1b36454c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.1 pytest == 8.2.1 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test -ruff == 0.4.7 # For unit test +ruff == 0.4.8 # For unit test From f289bd22b9390ab7fafe20c88fe8dda6919a4b67 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 13 Jun 2024 19:45:30 +0900 Subject: [PATCH 754/940] Bump pytest from 8.2.1 to 8.2.2 in /requirements (#1028) Bumps [pytest](https://github.com/pytest-dev/pytest) from 8.2.1 to 8.2.2. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/8.2.1...8.2.2) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 7a1b36454c..3263de2c56 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.26.4 scipy == 1.13.1 matplotlib == 3.9.0 cvxpy == 1.5.1 -pytest == 8.2.1 # For unit test +pytest == 8.2.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test ruff == 0.4.8 # For unit test From 83cfed15b6430b01130240da53a6c4d745ef9378 Mon Sep 17 00:00:00 2001 From: Yukihiro Saito Date: Sat, 15 Jun 2024 07:46:15 +0900 Subject: [PATCH 755/940] fix(README.md): typo in reeds-shepp path (#1031) Signed-off-by: Yukihito Saito --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 7a01ae361a..ee40dfc7eb 100644 --- a/README.md +++ b/README.md @@ -407,7 +407,7 @@ Ref: ### RRT\* with reeds-shepp path -![Robotics/animation.gif at master · AtsushiSakai/PythonRobotics](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarReedsShepp/animation.gif)) +![Robotics/animation.gif at master · AtsushiSakai/PythonRobotics](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/RRTStarReedsShepp/animation.gif) Path planning for a car robot with RRT\* and reeds shepp path planner. From 15e1ed5de1b2f3d53eedf896b0c9efb9650d25bc Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Jun 2024 07:57:18 +0900 Subject: [PATCH 756/940] Bump ruff from 0.4.8 to 0.4.9 in /requirements (#1033) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.4.8 to 0.4.9. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.4.8...v0.4.9) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 3263de2c56..3b51f38858 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.1 pytest == 8.2.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test -ruff == 0.4.8 # For unit test +ruff == 0.4.9 # For unit test From 75f3e4d56cb68ae0d6c1b2fc61e7f265cb2005d4 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 25 Jun 2024 20:27:21 +0900 Subject: [PATCH 757/940] Bump cvxpy from 1.5.1 to 1.5.2 in /requirements (#1035) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.5.1 to 1.5.2. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.5.1...v1.5.2) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 3b51f38858..7cf9cfb7c3 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.26.4 scipy == 1.13.1 matplotlib == 3.9.0 -cvxpy == 1.5.1 +cvxpy == 1.5.2 pytest == 8.2.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test From d6075ca7d039b0ce98fd51518b9f48ca13763b3e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 25 Jun 2024 21:32:49 +0900 Subject: [PATCH 758/940] Bump ruff from 0.4.9 to 0.4.10 in /requirements (#1036) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.4.9 to 0.4.10. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.4.9...v0.4.10) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 7cf9cfb7c3..576bfcb86d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.2 pytest == 8.2.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.0 # For unit test -ruff == 0.4.9 # For unit test +ruff == 0.4.10 # For unit test From df5d99248dae9967a9e90517900e3858b0ae8b5d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 25 Jun 2024 22:12:57 +0900 Subject: [PATCH 759/940] Bump numpy from 1.26.4 to 2.0.0 in /requirements (#1032) Bumps [numpy](https://github.com/numpy/numpy) from 1.26.4 to 2.0.0. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.26.4...v2.0.0) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 576bfcb86d..12830626aa 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.26.4 +numpy == 2.0.0 scipy == 1.13.1 matplotlib == 3.9.0 cvxpy == 1.5.2 From 71766f0a3eba78fcf6ba3820ed74464f32f751ee Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 2 Jul 2024 07:38:06 +0900 Subject: [PATCH 760/940] Bump scipy from 1.13.1 to 1.14.0 in /requirements (#1040) Bumps [scipy](https://github.com/scipy/scipy) from 1.13.1 to 1.14.0. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.13.1...v1.14.0) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 12830626aa..7285355871 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 2.0.0 -scipy == 1.13.1 +scipy == 1.14.0 matplotlib == 3.9.0 cvxpy == 1.5.2 pytest == 8.2.2 # For unit test From cca764edf600f3a29456981691af8f414c4030ea Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 2 Jul 2024 21:19:23 +0900 Subject: [PATCH 761/940] Bump mypy from 1.10.0 to 1.10.1 in /requirements (#1039) Bumps [mypy](https://github.com/python/mypy) from 1.10.0 to 1.10.1. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.10.0...v1.10.1) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 7285355871..1c4806ab75 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.9.0 cvxpy == 1.5.2 pytest == 8.2.2 # For unit test pytest-xdist == 3.6.1 # For unit test -mypy == 1.10.0 # For unit test +mypy == 1.10.1 # For unit test ruff == 0.4.10 # For unit test From 0f8ce35bf236ac7c97baa99e4189f6bc283be834 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 2 Jul 2024 21:57:57 +0900 Subject: [PATCH 762/940] Bump ruff from 0.4.10 to 0.5.0 in /requirements (#1041) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.4.10 to 0.5.0. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.4.10...0.5.0) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 1c4806ab75..5eb478dfca 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.2 pytest == 8.2.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.1 # For unit test -ruff == 0.4.10 # For unit test +ruff == 0.5.0 # For unit test From af7a75fa837f98ab2980e4f637e4273ba4a78e50 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 9 Jul 2024 07:16:58 +0900 Subject: [PATCH 763/940] Bump matplotlib from 3.9.0 to 3.9.1 in /requirements (#1045) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.9.0 to 3.9.1. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.9.0...v3.9.1) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 5eb478dfca..406786edbc 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 2.0.0 scipy == 1.14.0 -matplotlib == 3.9.0 +matplotlib == 3.9.1 cvxpy == 1.5.2 pytest == 8.2.2 # For unit test pytest-xdist == 3.6.1 # For unit test From 4b69c7a859e7658483c16cd5b17820f1056ae21c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 9 Jul 2024 21:21:56 +0900 Subject: [PATCH 764/940] Bump ruff from 0.5.0 to 0.5.1 in /requirements (#1044) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.5.0 to 0.5.1. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.5.0...0.5.1) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 406786edbc..e334ab227a 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.2 pytest == 8.2.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.1 # For unit test -ruff == 0.5.0 # For unit test +ruff == 0.5.1 # For unit test From 26deca19b63382e2fffecc804fceb6694c21d5aa Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 16 Jul 2024 08:20:28 +0900 Subject: [PATCH 765/940] Bump ruff from 0.5.1 to 0.5.2 in /requirements (#1048) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.5.1 to 0.5.2. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.5.1...0.5.2) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e334ab227a..aa91cb258f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.2 pytest == 8.2.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.1 # For unit test -ruff == 0.5.1 # For unit test +ruff == 0.5.2 # For unit test From 1e101d1f8adbbb6cdb9334807067b872ac62004a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 16 Jul 2024 23:02:31 +0900 Subject: [PATCH 766/940] improve LQT steering and speed control document (#1047) * improve LQT steering and speed control * improve LQT steering and speed control * improve LQT steering and speed control doc * improve LQT steering and speed control doc * improve LQT steering and speed control doc * improve LQT steering and speed control doc --- .../lqr_speed_steer_control.py | 13 +- .../lqr_speed_and_steering_control_main.rst | 127 ++++++++++++++++++ .../lqr_steering_control_model.jpg | Bin 0 -> 11721 bytes .../lqr_speed_and_steering_control/speed.png | Bin 0 -> 22550 bytes .../lqr_speed_and_steering_control/x-y.png | Bin 0 -> 31256 bytes .../lqr_speed_and_steering_control/yaw.png | Bin 0 -> 23991 bytes .../lqr_steering_control_main.rst | 15 ++- tests/test_codestyle.py | 2 +- 8 files changed, 149 insertions(+), 8 deletions(-) create mode 100644 docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_steering_control_model.jpg create mode 100644 docs/modules/path_tracking/lqr_speed_and_steering_control/speed.png create mode 100644 docs/modules/path_tracking/lqr_speed_and_steering_control/x-y.png create mode 100644 docs/modules/path_tracking/lqr_speed_and_steering_control/yaw.png diff --git a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py index a70e30d378..d85fa98a84 100644 --- a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py +++ b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py @@ -55,6 +55,7 @@ def update(state, a, delta): def pi_2_pi(angle): return angle_mod(angle) + def solve_dare(A, B, Q, R): """ solve a discrete time_Algebraic Riccati equation (DARE) @@ -221,8 +222,9 @@ def do_simulation(cx, cy, cyaw, ck, speed_profile, goal): if target_ind % 1 == 0 and show_animation: plt.cla() # for stopping simulation with the esc key. - plt.gcf().canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.plot(cx, cy, "-r", label="course") plt.plot(x, y, "ob", label="trajectory") plt.plot(cx[target_ind], cy[target_ind], "xg", label="target") @@ -290,6 +292,13 @@ def main(): plt.xlabel("x[m]") plt.ylabel("y[m]") plt.legend() + plt.subplots(1) + + plt.plot(t, np.array(v)*3.6, label="speed") + plt.grid(True) + plt.xlabel("Time [sec]") + plt.ylabel("Speed [m/s]") + plt.legend() plt.subplots(1) plt.plot(s, [np.rad2deg(iyaw) for iyaw in cyaw], "-r", label="yaw") diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst b/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst index 68ea9c88b2..a0b145456c 100644 --- a/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst +++ b/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst @@ -7,6 +7,133 @@ Path tracking simulation with LQR speed and steering control. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_speed_steer_control/animation.gif +`[Code Link] `_ + +Overview +~~~~~~~~ + +The LQR (Linear Quadratic Regulator) speed and steering control model implemented in `lqr_speed_steer_control.py` provides a simulation +for an autonomous vehicle to track: + +1. A desired speed by adjusting acceleration based on feedback from the current state and the desired speed. + +2. A desired trajectory by adjusting steering angle based on feedback from the current state and the desired trajectory. + +by only using one LQT controller. + +Vehicle motion Model +~~~~~~~~~~~~~~~~~~~~~ + +The below figure shows the geometric model of the vehicle used in this simulation: + +.. image:: lqr_steering_control_model.jpg + :width: 600px + +The `e`, :math:`{\theta}`, and :math:`\upsilon` represent the lateral error, orientation error, and velocity error, respectively, with respect to the desired trajectory and speed. +And :math:`\dot{e}` and :math:`\dot{\theta}` represent the rates of change of these errors. + +The :math:`e_t` and :math:`\theta_t`, and :math:`\upsilon` are the updated values of `e`, :math:`\theta`, :math:`\upsilon` and at time `t`, respectively, and can be calculated using the following kinematic equations: + +.. math:: e_t = e_{t-1} + \dot{e}_{t-1} dt + +.. math:: \theta_t = \theta_{t-1} + \dot{\theta}_{t-1} dt + +.. math:: \upsilon_t = \upsilon_{t-1} + a_{t-1} dt + +Where `dt` is the time difference and :math:`a_t` is the acceleration at the time `t`. + +The change rate of the `e` can be calculated as: + +.. math:: \dot{e}_t = V \sin(\theta_{t-1}) + +Where `V` is the current vehicle speed. + +If the :math:`\theta` is small, + +.. math:: \theta \approx 0 + +the :math:`\sin(\theta)` can be approximated as :math:`\theta`: + +.. math:: \sin(\theta) = \theta + +So, the change rate of the `e` can be approximated as: + +.. math:: \dot{e}_t = V \theta_{t-1} + +The change rate of the :math:`\theta` can be calculated as: + +.. math:: \dot{\theta}_t = \frac{V}{L} \tan(\delta) + +where `L` is the wheelbase of the vehicle and :math:`\delta` is the steering angle. + +If the :math:`\delta` is small, + +.. math:: \delta \approx 0 + +the :math:`\tan(\delta)` can be approximated as :math:`\delta`: + +.. math:: \tan(\delta) = \delta + +So, the change rate of the :math:`\theta` can be approximated as: + +.. math:: \dot{\theta}_t = \frac{V}{L} \delta + +The above equations can be used to update the state of the vehicle at each time step. + +Control Model +~~~~~~~~~~~~~~ + +To formulate the state-space representation of the vehicle dynamics as a linear model, +the state vector `x` and control input vector `u` are defined as follows: + +.. math:: x_t = [e_t, \dot{e}_t, \theta_t, \dot{\theta}_t, \upsilon_t]^T + +.. math:: u_t = [\delta_t, a_t]^T + +The linear state transition equation can be represented as: + +.. math:: x_{t+1} = A x_t + B u_t + +where: + +:math:`\begin{equation*} A = \begin{bmatrix} 1 & dt & 0 & 0 & 0\\ 0 & 0 & v & 0 & 0\\ 0 & 0 & 1 & dt & 0\\ 0 & 0 & 0 & 0 & 0\\ 0 & 0 & 0 & 0 & 1\\\end{bmatrix} \end{equation*}` + +:math:`\begin{equation*} B = \begin{bmatrix} 0 & 0\\ 0 & 0\\ 0 & 0\\ \frac{v}{L} & 0\\ 0 & dt \\ \end{bmatrix} \end{equation*}` + +LQR controller +~~~~~~~~~~~~~~~ + +The Linear Quadratic Regulator (LQR) controller is used to calculate the optimal control input `u` that minimizes the quadratic cost function: + +:math:`J = \sum_{t=0}^{N} (x_t^T Q x_t + u_t^T R u_t)` + +where `Q` and `R` are the weighting matrices for the state and control input, respectively. + +for the linear model: + +:math:`x_{t+1} = A x_t + B u_t` + +The optimal control input `u` can be calculated as: + +:math:`u_t = -K x_t` + +where `K` is the feedback gain matrix obtained by solving the Riccati equation. + +Simulation results +~~~~~~~~~~~~~~~~~~~ + + +.. image:: x-y.png + :width: 600px + +.. image:: yaw.png + :width: 600px + +.. image:: speed.png + :width: 600px + + + References: ~~~~~~~~~~~ diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_steering_control_model.jpg b/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_steering_control_model.jpg new file mode 100644 index 0000000000000000000000000000000000000000..83754d5bb01c9a1a4339248be09b476578291922 GIT binary patch literal 11721 zcmdUUc|26_`}c?xr9voMWl2Ve3?WpEHOnw(CdTr~7GocxkhV`^L?49g8Ov;DWHMwK z`eYeP5@u|JvS&ouCG_a`eO}+s?|FTHzvuOQzRy3;^FFV0pX*%rbzj$YU)Oz~bD#VC z9QgSObi~rs!W6{A0|N2v9-yD&JOdWS#%^}@wx$+Wq5r681?__G90(K;7>2PoyK?fH zqtnTKpZ?L}SKW1w(BNO!{|38y*ZO{G2Z4H3{~MYA9b3TDE7W6G;M?x0fY~*^>+I28 z`sj^+&}V+p?*E`K{-Ptog2Q%Y?0(T0xV`Z%?YT>zx$&Q9_y0tD1Y>^5KiQSJ7~p^N zm#ts;zl$Io2y|f;1mgYUFP?iQ2vqe51UfeK z7f;~@2z2;&5U8^2FWz4<3BHcG{vYc2cFR59-XPEt9t09{1c5|9fIxz%|ESw7{u|#; z?p8_f`W3W$+yME5yg(;G7N9_o2S{y~(gd9YX@InUazMr)-aWtYtK{7UA3xtO?C0m- z%P+8BP*7mMfPmn^!v_Tq96BH%AS5hw=kp)WqHq@{d@NA+kb#(SB7T~FW+ANefxz)PKjy=96c^~`C3u0=5;Y~d02#mw$2rM zdgU>sdq{G6Nsoe-u>-;bb3ZkW)xE3i=&u3)zv35H_+Pn0po6?TyI%4NgN#7zbN_3b z|MHIaT^q*#uFy;5lrAuu&i1Li!o{`^5rzNgZThIg=opmD7c)5D-oBWv?Uyim?h7`V zjv&wPg;v(=yKQBw6_{jNwmCF)$%yjcC&;tCH0-#V&duWLA!uiZv9(O5{ZpZgVJwpQ_9^XmT=d-+E4-q9oAI!b$)HlICQ zG}zbtD{62=B%hi)3e1sLG}SY0UDp#gZP^HjIOI|DdP+>a>4>rQ!7$dM<{2DXQ(J?O z=m)!CVq&XcV)PpbyfeQZLefXP2)Es_zInR@%=ihi=BO`t!hKnNKS8}HZjw_VFbo-H zU>VA+Bv+9m9G#*WAOcnzJ`a8y{u6|zHyZ&r+oufHEK4}5fz7^0Q^U7h}T-k{7VC@AZi0)-g&k11@VK^*QJsAtR4q>@R?&9&r2&;BV6TNizEK@4BhIM zYJT}|CY5K;0y4^JAH4>^vkvC>W0d6`l@~i~t)VR@V`9`Oz2uh~w{1?SWF?J7My81g z7HcatoG>>jBX+2ew9cDQlMt2NjhSK9A4uPb@)!JRg`BS2(H8*eBtHckt|))QrsWFL zwyd*fUWmp*PZzOwv!B=P6*^)iWEKXG{^D1MggDfN$k*j0g+*gbpI0)g#A>BR_zQ#9 zVQA%fc&c7hOunP+K*4=#P>_guPU)kV1HI#x(`$}S#6JVVc+q+im3}BfMWFz`fJ%6D zva}9fR_g30)ebI7t!=QZrntt2y?O>UEl|7P;ywf^zJRJhu>n1>5 zf~K4%>FO&b+Dw`tEpwf;;BFS;LuGoLB6!w)yv13k_!6-Lcgihna%^Fu05y+aKM%HL z+U7V-+Hhi-%mJ6GF8y8^QGLMl^NJdisP!HnyVOV7yYoO+{`D5)*BlXLO_FUw#J~gZAcG+VIX?%F~s2LgmL!koUr4?CTBmKV65yGF`rYHk#&plb;B>D_v zW_F4FEm?AMhVq#-WfEa^^bp#`ZA5%7@Nh-IM+rg?<9sHmZS?^7MW|ZF{xWUS;#1&DAynWy_Baw#j3%?#7#*U2~h+j!MZ~K zF!?>*>@2R_Nm-KIum3$IVoN?&Yig;rfnP)H?%I^4Qpia9+Yw4LIIH_(!XZLT zgL+(}UEaFjAB^0q@qiIg(n>wG2B$Z2Vg)_CboQ;x_0j2KIJzF$%a+MQX-G-OTQLS(dQ>aOBuOrCTVPIWpUtothiF@wH6$NkY6o&54^zH zmWe!%6C>t$2NGBm6JjXZPxEXd(JmSOy?UkFC|?MOT4i{qKKrr){X~DU8(O{~N_Je2 z5aXIh1DAT;*3S}uD@;qHoGr%gDN8+xPZT#Jl?kw!R)7Ps(`M=pp=6|Qi73A)bCXk& z&I(b9*3CZccn6OOht9&SqQou^)&B&kjL5S0&^>F)Jy$S6QR?*B9w%Ckl>O|W0}#&% z{6;J342J_)Wnf{pWZGBEfg&uDS1cynAsOmJiSp<-Xm&AjT*v2XW=kQpEe+I~R6HNB zSSDXGB-2S2h_6a2PCI!OQ`FCH2Uj3L-BSg})i__XH1MyXw2p{qWf#ACJ?%EvAEoAG zX||XxG{q!2GE+%~X;L<8T4pPIx6luhG4J1Fxy5Vm86Ekk1Y+S{*Q_6TBa45j^>nh) zSKTD@yatITs$0w6;-;5hZ1=qE86U9G@qan^IlI@^II!63qA-54MNUa&(G9YZ_vYUk zoS;*b#=yBNl}zuHG2&pfb@f?aMM&&uY2GX%VQTD8R_>VwPV%+)AL9g`5o@2XB>0|w zjCi&04Kbg%8IRQL`7>$Y^rF2$T{2yyrGKS1Z&XycCv>_Gj}c0luP-x?NVx1(m~nXp zK{c^ZIc-r`>*|x=0Z`zx(XG?!;rK^;3e&`vLf#H-SNJzvsVomb%uegfA!jG9ahFtZ zno-X>UG<))$iw6k0Rmatr>|^3l?$H~EcY8SovrFXS>y-V>QVkI=kJ_AX{|9OjTJ)H z#(Gv&Qgqa%SFOg|bE=Izb0F&8{|B$g8^8UE9S%xOX1<2#1l$wj{qmsfoka#64mcs4z#NNc=-3j&}wTZqrTndWDY z5^~D^yx9KIHTJ_h5x=0i8!tHsLv zP>uZ`TC_bP*asM7`zms_k-a8ZN4q3d6hAF(-z5hoY3mt|R!l;7S0AB$d2?BlCWg+n zitJqP;g-vl^Cwt?T8+Xz?_xeW+@Zc2n#GqAsikPclyt4kB+qj+KC`GeEMuq+hc^%3 z6nmw5q5EA*nf=lMO26Ie>6x#HsX>(<9FYo4*=Htn_-20m-E?U(sFp>@5eHFgudq8! zI=B#dGkWZzRb;1DzTCDjaJ!^9K-0y?+r7;UzVSS+buv`=^K|(In`av&qWit$-HZc@ zUvFgN8ml_+YyGbzTD_l2v-F(IIZdU>tz`ME-0$fZx?8_0WMx4x%W`s`tJ~4kY>&u4 z@yBJKd$D#@@d{NPmtk+^Y7C3ky>1xVdL);jx1?Ei26d4?LEar_#oytjUpKq?)^#@q zzaT%l?FGG9YQ~hms|4wUZ#`QPJn(s%HJoZm`_g#bi5Z-+n$25EBsP=Kw>{Jlc}1?z z_4?Cnq*Gg1Q_;$9gCdIK+yBM{(!FEO7Bc8L=oH=WfcfFA>xIXda%;XPCx&6ML@Cil z3%NpPLW^AWEmz@NdJhhd8V;3mNs2f zz=Z1u?4fv}hKBpTXi5$r{w?daseZ47v%N2dCAkOvC~aag%P!r;*iSl+Z{q(WlHp zDc4i1+=JE%4MXFvrfaN~xZBgi?LM=qZ~Z3yMT)MPn3f$3!-P+H#xJKkde&SQ|;6?Puhnr6gO-MzFDzq8@4JVau%kUmr}r;X3A$2NcQPE$L;gE zk~LSGEB67tc@^;$8Qd0{fUos$3?TupUD3mosfL#~ZgscT6&4{@<@E97V!MPT)Y?*n z*dLyH$k@}mxb&+|pE!oFRQnN`$m&jeZe(N;meUkm$HV^MeILYvI<6wQq?g_Gq&(avxp6PTwnOs#rp@<9xotouF@gdd9C?) zClC9{Z(6-lrDll!#_7ZwXZa0GB7jvy)aL(y1gX8Mi70t3o-+RIxnZ_@5ANPokFTN!)Gt?>Mk*qK42Tn4JoidL?sF;d&8afF+^{0Nv~Gbz}R;- z(;9gq@nE;6S>XWoNoX330+`rLKj=)IfG^bxEJ=A{TBbY(HeYvlV$=n(SVr2>3A!w& z>dV^T-qWQ$ze#NFSD4PtSnFmnr4v35FIJmYN5;tX-&5IF_)w^6e(2$A|7ELe`)z%O zXWtJ)9VEngHK5e1UYVoS-E}_adtoS7--y^+7o5O(u$ZGrwhKEiLTmP=-8iP0)g2UX z4@O(%${0W{`nH!@NlyAnO*4{3-{EUxS16y-^>Mz`fq)gq9T(@B9%eX+6rh+D>#A?m zlv)fHz5oDbObMAS=)yf0m;dwGa3&pKP&xw}Pf^~i3E)$DJ)ZSM7KguZolQA2p87lT zRt)%TNN_&{M)gkxgTbcnnNq*|9LnHU8k~J6d2HpWF4K0=8<2a$((9 z`$%9pQuBdpqYi1&xg8COf$H8H0kMz8n^wP?`L9KJs^SX^a2=|D{K@A#*{4Cn$=%)F zqsdV(?BMB^re!WG zI}&B_0Qq*C>C3IrQ2`w9;-diAtuK=p9DX|CZN33wL;JBAFUf1zRdD)zlD$d=rnY8r zuoS?2-#Q}jM(ihOt3f+pSpa)?+2SWidAf5}dhnu1y~Nynu8UL}sT4=~hq^~Fhh^y4 zCEBG@pgv{$DQesT-;Y&-yq`6B(1pny{zl&Lzyl`pGt7O>^JWA2-U(P$3uaYoK+I`yEg?( zdoW=uw8;wRAHe**DPFv_0FHY_dBz*fv$`1 z-bX1UxAvJgZ|Ekv-M`9^+)T~zr7Wut)YIWs{3!gYNS{ZC9Tm|xLYtGT}S0KTMa z&7>vW9J>%dymu1>I=|f0Sp9X9#(d~2t0V$=A+s53W_AN!Dc~$8Nyi57WGj(MAB8;6 zuz++4$mdo(8hleOiyyh&=!?kFB=zPt9H86&F?qa2$t>hGtG8&m^D5_&mai>qC-T&+ z&7w{$n4CkPhNc-mY!1(?ywh@hVC|KAM(3p$RbJw)e$U$vwp5e8%e1%B4~GtaM+mM;(@`$`fo_&bN7n;lyb9|+^WPR#Z-)K^z2e)?u-O`}(`e|! z@JKa&9vqYw))ebwx}m6dF0DAvZ5oitE|Ld|UIR*JJY+D#QI{uM8WOVi!@t~P(HAhidQZ-)ZFH3KQl1`vv*gEQ>{?g%-m$l2n#eHkl(Q zCpxf48aG(qOIa%Y5YS*fJfl-=A03$Dz1XfkmW+*K)NM@uXlT>-JE5uv>`Zg&+rana zTf^t7hHho@Ns8gio26h+JT$Nheopak<>a7)!iT8|S5_dmeGGyfu+XXwi74A@9Vp5f&C^ zBp+D=oe&aB>hMpyQ91aTsJOda_~t;yQTbMrex-}no ziZOEH@smaiu3XC315!+?ljJI@3cR%UuY-0p`GDq}`hroP#$s)fet>$e%eB?{|Kq%8wWrg$)UP#8|Ay|crkDr8Zrqe(8FEXn%J6OgGB zu*(*5>KEy$D!F?26g{__!lEVGWtfrcuWjV<&qu^hJ@iQbA(sA85^4=K=5@zvnM~w~ zb|O2S>quoc0S6B6;z13Erq+}3$^S7UB;)$%qQ9G%ESVUu{hfEtzsQOqd*rJGR%@Xn znb$+CYzZ|1a+BBCUUG79#`UqKUdXMPkEZei@ozWEp&yfqT&p~#o+X4u@_2X672yLd zOlF*DXHKCZ<^4_Z9o-FV|0kh}CQCN-pjCMORSw%aYoS+g_`QeW`z4>3Pxc`RV}w>} z2)vP3)u9r)m@VaynW?0nVxB7qfq`ZFs&m1U2Xw0q)_l|k$M3w7t8X~f;W~*u=-%|1 ztI}ttR6C($ug$;Aj3~3m{h&myDaV#fpoT`9U&%1$DCe~@%+;y^9P6D^epBp}ql}9u zOgo}wjnrB?$2GJ4z`{V@J&NwQS=nG#|9e2sr+3X~NavmB-#Zq!(fItAX%YIw9*35? z%6%%;t`*#j+GI~S08P;m+Zt&yiaS=dUJ8n-IN(17seIxU!cb~bo?pnMSkC3NrVOhI zVo3=GSMUzqV$Ov3?}F@C=ygQpd;b#Yzt6x{{biny1Vv$Y0>@7@9Yp=;11Z}5eRcoR zVh?y2xg2q1=cN0`(U&4bu|VUs3$D7s%d6Ix8t-(?->TY_yleDWRtGuL%M84IDb02Y z0IZ?bs$O0u!47YjR%dCtlC1-*srQ&NPZJXWaM;Yzu60M&t()B3$KO(9>ary5G>3kH zVI0dVH&94sc4U0RJES(e*)P14>@T3&GxNb`lmPd2hLBCRFJar+mBA@RR`$uI@p`@T zKhDOzzYVp?qc)dTIiCsa+w`N*NP1a%1CB7;i#A-(as$FNgS-gc#n!v~%`_LelA%?# z>>E-~`=50dya-o!E9{#+m4vgbFOK)YJ+RzIcEFuHVIkDkW!lEx_;{GLge~-Z<7Kqx^tGIjQ zob4h|nr2SMeC%cyZrp!x7fbog@&(8cpmW3-YUIG;RaVdy_=f5ttf96n>DE@Y;fud# z>A#Q`MocvnlFb%*`F?`LoZ8^nD%EWnr`=(#v_b0QBmEaG{x%DWO5aJM><&)REx=FF z9z0yNa?@w$=G=N=RPbhbX|;EuJLmZ}k8i`U4AR1XaW0j8je-sf zW){XAn9Pabh4Q4uv@v?OM(;qG3x_>NXLo`OaTDtx_9ZVjT2RD}ex z5Two;M9st_FG>FCKSOjFJNNnSu-Dp|-|7QXuoGezI|+}{Vj9kSq!9>%l1Y)@CZVok z`gkyZLcmZqa5p6i@)bq3f@M!0+*S`S_P02w&3qSE{-IeUhA&ntNhbnRW7@ikA%9nR z1>XK=^kn~;8y?cV_J)5N-}hH;?xA03mi;q7fBuylNy0($U-^mpXKwgOy#F6rFwTBi z!rstAe@*{vXbcPJEH~ZBD!}_&=Sk(jx89Q=t95gVHJTVpR0{nTWqa^Ef^` z^1RMr{6OMIo%V{`W_S~qD0+lIUi_Q zKX82;$}lQ1>eW(BDe2PhAD{lwYrjN_i>p@=7IvPMjD2uTQ;OfwyQp>1Z>oOTw=D5= zQCSs>hRZ9+A4)O>(`N^xaHJEU-2cKGvv=r2_(l3NgG=&~# ze_%nOp=pt*Y3f8Z1+{18PN2~hwLfNb*Q$oUk}#$@7lCAU+5Q|v4Wi95$;2kl z-7{%6qFM{hpCqjI+Sjm@3jnw~TEo_JSI1u@c>~Qsuk8C3L-QyI-431b6?x})X1@LM zq}8Q^a~!XS;ga*lM9BJ`Z zqX2u$A-&@e$%d6X*2V#>@6sFF(TK>bq6p*XL(Pxmw#@4ofV{0Cb^i@?wdXO}hYRZv z5;J96=&AiO>i6_2aG@Vc?5xc-X9AYcFBeRH`wdHen^qN4-DmcPzs-Y*@Zp%}LtkzS zsnSrVQ^zVL!#4!xG%R0Q*nQ83N%rCldV*QDB8HDJg|F>;gszX;j8>dDLwHNq(M}n> z6FVr>r?-E8RkXw5Ag$&MN6@r+QMSy3!CHvJ&IFInbQ1N4I7z9KVFO8C*>KvTDqnhcwnu) z#n37vmew*kC5F(I9W8QGs$I`R4ASMVYCUycH-=Iia~~gT=Y|pk>s6PiU^CW$jELUj z#xPQXiX;;pMn@)9uGth#o{dqjvF3ZH)qAQ>U%Zer`F0UKJKt}`>h9Qk(cx_}IhiaE z^MWpVn5qc3u13KamUXg+o_%!)(qpFge0rUZLfJ-FJJeA7EpEMHb6i626WiM?xp6~- zsrZawHg^{4dI1XWjBI~S6T*7l4$On3f031Gvx+En>)tUikV))je$qpG&03uDm@J-F z920{P2VM@Y?wx`3CGu5GM|Cy7;xrpxw}@f}Y=j@Sp{pEqw$LxhlbpGw^)#OJ6jPWC z)18gDg5&F|RQ>GWN3G$8KWAwcS0J1QkP>bm#GaMil)65B*D0DZu6xl&&uPUYC+Azj zv~6TnsZ&V7Eico%Bu6cAE7gln?kgr!Q!GmE8XRes5_VHa8UrL*z}W7m3MuU)I)iL* zdLhCp5g743STtJt@+ixThBt$#0CIb+vV#?G-baA>yQIL9`Bvi z%(VTp&Wtnl+*+FYNmuo$P`(|cgR#iG(j0c;BSjg??FoxXTz!gMjCRdGoG(#ji$pS$ z^z&4iAvG50G8QKw+*lv1^#GebkpVe#!_EEyE^}2_my|dj=KaV9pSF`8t8XN!uyL5AM{)INfv;(-i!A02A@ zhsU-SdMe9p?|bY8uiZZx2RgcC8Ll&j1%84wKDP9~^sk(GJi0tY^ezV!g{JEtbUHc) zRl=8h$KZgmXrV{)C>O8NLm(`OiHStfM^rO9ycD?|!6ju?{cqZ{oJhVXh4XLM3Nz(p z+3-+j_U>|f40bh#W9{weGq_{r-WK8ez;~O-p2i;>=uN_(wZpdb)+1f((2|Ax~1l)&r*3 zKjMe1x_Hw1-rrj_g7|#PA{8&cJ`1S{O7W6F*_?N@YYRH(~-Mca3tSJGG z=_WB%IB(_39SA9Jq!G`2DxZB0)E>6A2)06;4_HSaV9h_A9z!meb)8T1%KeNF8>&?FS-`<|9vzN-%R*xI>|29fK{d&0YMOCxS&`>o@#BtgbB4QyMmunlL79r41 zWIAfMRb36K@*b#A=Pd|W6HpGcIAmnWBHiCo8M|9O3V}lrF|sg;2UkI%7e=4Y)}KIG zVVciLM|Pp0eo1Y%0MtMB_;{7Zh<}lPB3k#9SybBzgENecNlIjM5ei#_rccPboai?2 zY2oGzj?ZP-U$zQq5tAfsj3|*Bn2(!Wi^jM=LF$UCANCyK@Q-rCLd{fO-Z3WAJtOL9 zv%#&J#n_B2LF~{>=tWq|%6frm;k8`zTyr*n4(-W}&G+Gt^M$@ISuM%3#(L-owvbPg z=tBkg%y+<)V_zSxPbZU#mqtC)bAqpvLvTj~_B z_kR>d_4MHd>#a?ejC$05IE_kv3&{)3Y>N?BTCjbvv z>EkzujTk8y#Uw~tPA)h%>4uH=kAh8O7l*K3p)<{kS=`E74giW$4%MHS$$OM6O2+3& z;PdpA0-NrEl4z>cKH@IV&)aDxN;U>o%PV*`6obEfu(Df!mGqdg5TqU&>F_85oTDTi YY#zr#%kTQLyIC52cxCrT=Fh?Z0n~N9RsaA1 literal 0 HcmV?d00001 diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/speed.png b/docs/modules/path_tracking/lqr_speed_and_steering_control/speed.png new file mode 100644 index 0000000000000000000000000000000000000000..ae99eb7ea3ddcb73d6d3e657ac0bee507b1ad6ed GIT binary patch literal 22550 zcmeFZbyQVfyEeQwExnOO8U;jJkQQ`Ip;a&d*3m>@4xqt*D(~?d(F9K-1DyMx@Xum%}W%d%%li{P^hWmv=Ic) zA3-oM_yJJ^d0NehXd z;jnUbb###t7PkA(2ZS7)ErowDEptLA#~f7+T@ZxoCi)kXc|OA$LG%OFa7sF!NlU|C zp2yt|iC4FIu5`V-;&5N-MvE^AVHr;6TIz}Lv33@nFShzh%5ojL(k7jo272_J4RqJ& zE2$l@1k*9sTTZH$ot~akYA?F-GQD~KQ1y7G-Rnm@;?KRRQ$mPeXr6lIz-u?^laIw| z(JJBK&->T0

    x2Sr;Z!M1MZLiSWP=ZKnVG>;FNkaV)OfUvb7&#_7**>qL!HBo8^< zq+$2E3DWq|Dl1Q@si}2Xb@wxTMLdsbzEX&sn!26U%E85z7U4MYiG)>b``Sm{{tMUzPXmv-r#G{67q4Ont(%*uRP!B;u>^Rkvs1 zxU%={u6W#&C-T*eJ)xLYn$i&8`ucib8YEJMyRN>TZkr6#5+(P>*TDrdRThNWt z=QtLN&0@sofFH3fA_xuoEBP$?b2pYRJTogRpnlw{Yt6laRY^%HGcV76-32d9cp#(4 z21`quJ}>=%p$<{S;ih;cUs9Bnl@%DAx$+>2FI-hswI=L1FD;XmPmjWz&d@JkaC4jY z^OLWuF(P51q5CzzT)AXrS&VY&(e+u_yh19cnQ@$sj*f(k?E2KZh7tQ$eBlNC_oQ5A z$Ul7i*!kJlTlvAT5FI+uSoXeql2XZ2p1AD?MN?v5)yhzcgd3+h!Z{DgREDPZF{3E5N)_iM*h#O+%nm!(is4HM^0< zXE9J@t*W7cgIl*bPbs1qWO772JgN+H!e|p5?>0eaal%DvxVIvE0o2NqpgnvK~UF zp5ug%+2om#)mmb94h01^GoLlW<{>xT_|v}f*YW>6T%sMP z#bCK`*kV6isQ<#+fZs)eq~armZN|c_vgKQA8M6nw2HVoiT#~EDGJXU+;g#qsa(-or z=XJ5M=UHF6OL^pbW1K^+~}$XR7*9X{`#vbc2%Q>wDb<~4=QF)pJy_2k%9h21H_>Qf+8 zX?%6|B^R@Me(oBl9{6k#>Jrt!P9TatK0e8flarJ3uWXx=q+LW@X1?8z&NrGhTN&UDS1iUa=q^3f`AJgHjpz}ZyWvT~KO_Y*Cei(J(XV`Sz8>oi zbvvT(?4~dX^vAF8?UMBBKnTmU8OFJpQ$@_?xqO$3C0r=5^{2KV&J5} z=|GGz?*>MSX7%Zwn%;X(LHg7BMG@6aQ&YCDkt`w4#Vsd-S?m?Pyre(f>woy+gIM2^ zd(Mp#N;q_8zMFK;&dws%T|7aL9*s9Jm=PeAhkq7!e*d_-_GcmgjosjdwXoVJHOZvD(L1kwKbm`U8RRj_0%JO48tBDXvBWM_Bw)mrt@0aamP zVWPaZq?ovPXPJxTRm*R$`tM2V=<43A52gT}lC@DbbMH&8&UvHTb zzu$!;&CSh?KR!Ng>MK|=93^4<(|oSub;mDPQ~8qa_#w%$iGf+yaK6I67&Ciir7}9g zySB-G33~lnHid7BT7o~kXO>Ee+}!XC;Xv-^63OHe{o%mCf0T?Uitw(P+zH@6^KG+` zsKbW9im-OGWG|XS@eP(b9h-`^IdVTQRN5v?@^HbS^zbJMGWLMHgT(TPVteD-o?Mbk z)PSF@%~9ll%Y9Sge9a-lJbbzyUBr!L^fU7tc;hTv6$$0zzL z)Y`LPVL@|J)6>uNC$w2)E4Ayt-ECiW5D%`)tac=qa-Jfwv9WOkMZ+Z_L5Fly`}raM zni+wn`HjTvJ_zXA2M2#%XJ(RI&(Lguogsx~^gG;m1@@$PR(iO?qp>Ynw$SyL_G3m- zJcp`H`f`tzs9sa=?;8({D?LTEuV0T%NC-(!=Q(3iPRs7IicyJVCPWO%UHP@OwNrZ+ zSPl+un3zPy#84Z%e3#hV!rVJ^_I=oCeDezz@DPsk=h?%;!crPHHa0rnT#8nCWhugF zF2Xo3pZDXJ5B+T)ufL{D@nEY*DyfP8)0k%=p|mpn3E>Z8o?0iP7;ZSG_2JoG*$8%j z=*El-p2J#qb8_K`uRBsd{=>nzX~ejxL?V%NAdAaT&KzHyC0Ame8}=*m`y;Cw$Pw9L zE>bYKw6k2XBH}!SD4WW{%vW+kM4cVI8;aZQOC~GA&pfVtmpd^))cq-cpF_oT_^a^J zo^&>1w%Dw!rhDayS^K!7A~k{4S>|?HeE#kCvL#U)zxqG&5>c@|{{7pPoJEqHiHWIn z`q>R?Iyyon>X?+2sDgrz^<(%%Z07J_0RQz%JG z!$Ve=N=DP}v_5lFm|eb>m6=(yI$n?Jj$T_c3k$BO6VhGjGFe`etJ{RY6-zgWQ6G6vCf(xZ>jCMDBiL{1yJrpC_D)a$4Wq+a2pZ z9dDtpdF(^PLx0xin^6=$tvh5+(eihyq<>|Mr8yqnJ>bWy5~RqUUfH~hQ>VS-N?0?Y z&VtjboO|u6L@gvmzThgOb$!rVSU37L2MMEyIYLCv=x_bw9VZ+f0sTAzWU>Dvv97Kz z$+2S?ztpKH8bK;*?|;tb6WkTXjo2?P5pn9UhsJi5;S~ zL7KW>Ha5 z^wk^f=i6^onQ%3HzC}#IJY^^|O07gKV*B&Vw-*wv(Yjh3vhMHjvbSc(Lq^vNW^WrN zw-YX$ol9npY`y-bLy(`GuzID&?oIxT+;Of)V)Mlvwh{%>Nql)l{4z*zNXRWP9jMa; z=Kyrn+E*3_^Dm*;ot?>OQO{NLB8O47USpR?OO`|?@w=WW=e@V?6OdEkJ=i$W@~N;?PJ$+wqt}NS)j3jk z9;tQ`C@Jb>QtsXrP#1JB3Xd!28vQj?Ca#xjOEl3^$1}*Nvkc?4qJ2KnH9SrDL>;6`3N4FsBq($GyhvAa&W9&W ze0&+Sr5g2R$u~}P{R0liD4l*8C$#M4e=?zzCJ}u;{XYE-if4AMwRMq=F%Is6God7% zzvWyO8X3&-8x@Ix%dxw8j1c^IsCv6n;+-#+>R<5@$s+*CUjjfOV zoXJSn$Hc(UIiED!ZM-vDPE;I(LPUz%Pp`k#_1qmCU0eEWj3}mSh46~YOtdL9lXN*> z<>#`IX{UA+pG8s}BE;6&9wfI%V`6laXq9~`CkgKQxgbv^iO=FW_R?h~iWT8=MQ(be z@N$(?w{yju+Cs{=35yNRq*UCESur@1*Wfc0U3?Q(z*Ct{Pj2%U+kU(o5z-+bK`Ind~eWB)Z1lia2XGtUZN@Es42kOG6&I%te)~ELamR59Ey9SFRXP z`p9Zf%{yx4PM7@Qh^pCwq}}(v&`V1Gxt>NuH5?Qqy~82CuBvJoSX^`u>9p~{Ud6EF$Zp$$$;!1w9@x3;JQdVt#6Wa z)fi3UoZdzrHK+U6c?j^UIK8DfPQOxFc47qAaBJWm&j2-V>zcjqKoA-WI{jETWB@+xNaIPzct)A{C6 zv;Q=eNx&z;y1&n*m3d=mnjfvZ$Mf_Q{FGYleJfjdRK!$x^ZpsXnDOY){njd)()f!t zwC0QmKZkTOSIVKQ@B?Y>plen15xl>ZE2M(YL(XP9mq(g729E-tgD~A|A!;mJJ_DPM zU2Pk#ax`ou$-2zNMHenvK8r{m*mK~VYYsN>{zl_P#J_sfl_}4D^uk1VsA_K7 z1+<^z&`&%!;k4((jTcmc3ydG5cf=r3e5hQ1kPS;>< zzr`2EOnxuWR>rZD7~32O!QHBPuRI;8fE2k#Kp-aOw!HmN0J)M8x_~yg97~c!d4F0dMnugWr}d>sc)Na_ zRbp2`41B8yt@Rcuc@GOu zlOd}$x^^96VmR2q&^F;y@h-?;m6wAmq$oN)E*YI@STAlgQ^YW}jG0pKr&WdalBaVe z689!=A~m;qiv#%$c%78t0s89|B~m-IcDO4ua!>kI$i&H?Uk&QC#JBJl`&YLvZvNj@Dp^OsSNC zgOK#_-N|NOm5|Sj_{~SCvhEC@UtMRy#aPo+tHzT z+K(+MIlK{mk<}7GHJk4NK2x+esI9xlXG|9lxYKHA>y$;ck`Y@AEYJ-V@;zEt*qOY@lmlM2eApWBg9*z#17w3PQ8&$ zlGVz|RnD`_IR=MFS26^Sg9#+ac9VbbTet))lWlJ}dgM5xI8KOL~* zeO_-7D0E*kIw9jqf)rS`v)vmgItGcim{PH6tTJ}==ovA>*e|GscHmP_ovw@v75JT; zmHDicIc?**9n}~(`D7paA44dol-*M|?l`vMcO(n>l-@a)97wqR{OBSJE+|rCUs7*h z;$5t;y<6#P%D*UW7z`c?Sh7+vL2WHN+t9dw%hon!_=2*H*X@tJVWDKBQ=s3*pYUln zoObE@eD4Qo08YI1R_#6h___>`V@N3OyzCGV$ zGy8Op>9NY2{L7REW^BFY!`2k{ze+hd5HBBH!nJI!95A1dv~|4dO%b$4Wy@O>FMtuP~0vV zEWG=j8O@W)n2fb?!{YT;m0@`=XN#^xxstCi=O=!WP-$Me?mURxDY@Eghd=e>Gp|B_ zgu~YKc-c6s(-dJ(z2ti|Hc>nXe4<$3PxR({fT?hbRz3 z6!>~%QYN|0(!t0qWsrR<`AmItmrc-I5o6a$tjusfAxFT-Co(PPJxBp5_Wyn7uR#WO zEFQx5soS%PGHYguGZG@4YnkAFWm`o(v9nAgoZ z{KFrA+qK5jD8bS{38A#YQQP?Mkk`=4VMMNSXClILD)!Q~YuEfC1+qUa>{nZ4{UcrI ziq_9VQv_k`k~W=C2g!+sMvBnLO6<9a$FlLaWLf=rZQ2D_YdXrQ7n~$D#mN(>@oAbh zDgfIZWV4Oo8NK1r(X;2_rB0i6(QCtuOIrc#H7&XSl=w0tRVwa%6spQ<6jX+1Uf4iX z5jbcX>m!Q9UDfG7u`{j8iI_X`wjFVExrK_&zwRNSR!%MLIt3~>(gNXmg+7oYp;`2p zTq$Hn1XW+_WRWV0_Y!SeE(biXui-I+w;Z>nD%U^yszgl?mJJWQl6ta0??^aZ$u82& zfY0HT%=b64K+Me>=~4YSWwu;}kd;yg-F}RTsa*DqCFH&QKJ^D_Y1);?-P6?AU0t7` zY+{l8$MXJvyLV%;W$-gjp&@)@T72UQO{{uDFC}L7B@?3dnGtDTknEv6G96aXLlz(W%GKpZm_0pqgyakF>7T43<2V)po!FfLu;STUxcw2R0#@**5?X0-d_EO$(k zZW5f0({$F|O6*gAHe0@@s^!6`Y~L?YF1GQ5Qn6|U5M!Q)1aG3=giHy17Uu?N`cWW* zRx;%H+Bgwp8&I{YDz<#nJdfa18LWDK|Fb2dgF#`z;1WM>aKeNM#_x9U=)+1&fQOGk ze1D{&Dp}QN8EG1$TF~ujK1~}~#%W}-fiJIS zLWzw{m)pjlIiVQGPo%gWp4-?)dE|V^j?FTuY%V4(^#_M49H#$p;|Safb*T*EYqZL+ zt?wc15i*1zEVOUj-bcz9IGU;PIZWc>)LA}|31ATUC){rZ zgF{tSXl(WIW?>U=hr)oH^N#0@k4g$&fNbAobih75D!~Y%nV_d;d`!!i+}~AAEII)X z5t`jU&y^+<2Rh82-y2bTz=-^cEA>WDsmaVsAK)DOac2?3vkUG`#0&(=CKX7Kygv@- zRurGq)0P447y03 zR~>^48!0>DTXCfkmCj;PCN5CN0rpyM1>1!|%1grIKT&gWJx4zl_~+y27$l(>Yz++; zmzR2YjtNN}tPR?P&pqUL^=vtwxd&jkX+$Sgx|a!?p4RY)!|b#urxWV+CWH8;NU}s# z(Bm8T_Sq2m3v`QxS{#Zuj)X3U`*S#ANU&NL?=z5T26^ zDgrWaEQClI{J}plxPTKOz@Ryl_eCI6vBdZs5-jL95|NtON=eO#{|2IF%7|q3mm)!- znZJev0$j>y5^sZB@gkB;F*Ni=-rHGw4r7uF>$QmL_fJPf-iKzTU!GE9n_pR;6bbQH zQ$ZV3&OF0M%6UWqGc*YWK{*$AN*cD{E*OmJ*|PhH>`4?>G*P922Eow4P%}aI4IF8i zT>rlj7aXfCBjqx@v1W@1=sX!t-uHFyrTuF7HkE2(FeG&DLfjkUij%au1K`nuNXL@- z1z!JnB8T;GDXD4P48lWj0L)2Y_ma+x%PGbY6Dis}8{IG_Q-u5(DyMvorQVpU&m0*O zrvhMd)8L*x9U(zHhMb5eCMI6EF20FYm@n>? zcblhur!_OZGuxwF+HcpPF{XCHt0~j>9hY$yq!Z#j7Hzo>m&;0 z_Vhx3`RGK3?l0s*y76LrihQBt_=Wt>Ft0Wb!kVo$2qU=486l4aBJ0eNotKng_JE0u z{tSZL>;FIqaAD*5qur}M8{f})PK5EU0$Am}R2;=B8%#(>Z{8BmzcV;`7|bf`K33Ss zhT%asR!Ko)2&`ViF`!t>*2-wKQXtXzx98%f-hx%8(IZvfw>D-x^_+=`R1PrHQgU zz1CK1W}bJfE)>gjW#roVf31)=!PW1#=@39}!-?5E5qa;eFRw3#0G^|Y)Epk{b(Xu? z=70X_kHL?5`c!we5Fp-Uk3j3dS|srGp(8^7n$A@Of0jL^d_R{> zy6AgC{E))Q5{hf?e_hCtCEMXT0wv_M9c7{&mqq>W@Ap3^4bD*f%ZEIft;_-9a_Q*s zzzLG+IR=GzkmE-DlVv?7+GJOL&)dqceL3D&?j~URVE4`mX=j4gXM**BvazFHb$0$6 zf=f2rM-hO*a0QK?1v%#i>#7}O%h|M+rVdKF_=z&r*xpKYG>bze7O>Kt?dl_wl?{sT z6%{(Ze}31tJQY|Qa%sN_IIHUA%k@KLE~55BQu)<-sj?HMm=let0ufTSd5q0a&tARs zny^ayrH6nHmqQ$M+x7Nx=X+fNW3TC_o|`@TPOD=|)s@Q>=Z5@!_qJY_morx%9m=x# ztiq@EsZJ}HKB1@^HDE2myA!V=U_O5}b0K+v5(Ak7RYV0Yvzot`1{szHOB$bCRS2VC zkvzL+&pBlhvSH$3HqHk2HQ}AxW822i^WmjTXVos#W2h0(5{|tl9^=qJ>E=z&neQ({ z-oHQnnB^QLq#{daQ@mIEEnmI<5O-v|er{XdUz$Jz;&D)$&YUk1PazQd@%oTSfR|7p zw7{n4bdmiq^GC~eG#KJ{^Lnps=i%v|>oCZrgGO<9H;i%?X8Ayu+I%n|aOMQ4O=V@I zN)&*H<&h;zzwSd}2`*g7T*r)^Aq1puZ*djD{;ls9`HK6ft*6>`4^LY5TN-0T1SN}_Up}M3YSmx(ZNw8q%-wDrc|QEi92iEL z*dFTDspcmrGR_U0766a{=3Cv@TF5m@chBjdLk7P%gOP4x(Y9rH=*Y&Qrlu$F&;DSC zQ{iaerJYq#^?v^&OVr-XbrnY)YxuNiv9HzS<PN32D!tK-AkY?UDIfMU#k$N$1Yy92>N+plD4HzGQ5C z0-|XXhuTYb@4mx5&AR@)Au3Is1wol)4$`v3F&As#eS|d-YTlY{ODJ> zp9CVB&`REK)IohB_@n|kQl?f)C3;xx1l(z!Y-#`I=H{VgWtFyNOp`Zq9P4%c<$$aJ zYxY63WNdZwY2-5?Jf1VpEms@a{Zvgz1H8e9*i|2-&pR?;7ldq!b(0OrPF}_G!v+f_ zfZ=YQWnK`(;};TomMP{oflB4)@y{iHI>n8TX>`TtB1y6ydEF&)m8#fE3Q+r5Mqr}uvFFdUjf2^=hT`GyIhhU%{!%dOU>@0o_f;Aarki?bxwnn|j1gwpsHj z{Q1#IDs%=51gKpAd%V2Mdo_jA9Nq6%W9sH{aZ@gcT8b2$yr~;0Pa!|bb4&!$mZ$s4 zOsm(2ApFJz7jRR@!RM$W6=*q=G^%+Be%WTJ_fgtonIK}9&nICtLCgKgTKdy#;xnoTTZ7C2zC78^6^H%ia&{78mX$F65uSE zREC#xt%p#q@#2>RJV9yw#g$(pPNDF!Er}uE=hXUO+D=rd+3I zj9LU6>sOS&g!v|ztzt;0kN4zAbp${0#f$mf?c9=)@RE`HWI#CjE%&p^+XL7rlR%C6 zk|=tMC-a&KAT7M=e^-oZyjF%snPAe@P=azc;f=?F6{Pc@##9oo8bhw?qLGnNRpXDY zE%O>>~KPUqY!-_g=e_@>uZ(B2BLGfF~R21BMLPa$?Ds-!~EguLVX? z2Yhr);Cgh@03ke-m#v2SdO>)dd>Kl|=Y^cCLP89h1-2_&Y%L+q;$ z+#j>b(!YNFnnpi^lJ_zi3N*cvIh8a_`i@`Lg4!!E2af{*4iJi5$CZ=!$QT+CB34Yz zY#>Q~RtyY8N{IRycMzJ6y4x}3JlYt;?-&AqfG(-^P2A`J)OXz9aYAbTdR_pcLn4nd zL){ny3I~RU&H0fA#v?vr4-;42bQ%#dC_t{i1Ns7%`C>bxvu#g5Nj;Tn zKwnvH%RW0m{lbHQ(=Qf|^*IMNdLiS`*;jsSN=lZOG63_A1Usi@@LUEC?Rv|53?kT% zuZo*GH`|8KvrY_a0P+Itv5zB@kaq$SAB|4B(C&;)x0Eu0H35Jef8%@!8Qx%g4f;g^-`!-D99?zo58t47EPBwC|s@r%#{e$!lK0R3EA}4Ch$o~T_7(Lm z)-*=5Hv-`!_Q@0c?4EG&(dvLu(4%h#zH)=?N+q{jSh)N9ElJ0}XZ!s2g_whkR?o{) zFuqMh;c#biZn)x{y1Ketl^^2x8Ac)ygFOH9LEMhq&l`d8ptD|XAe0Aq2; z#KoTYPUtly`(Yjfu3^exb@BojYLVxqTrCMhM}v>WnaoMLVAHU%GEST%yAiO_Dk>_; z-iM?Q{ej1$@k)UeltFx+2;D0A-~3DL?Q&;$Ff1q7f7El50wn~Ql)EayK7Wm3jQ|P( zWI5@<-X@gGDNmm2z~Q28E^e83`MwbVkZi0zBll$^e7!aP)Gcvfv#g7k{yVV0T0R*qJ zjY#p(;Yp~f`mg3##9yBG^2yx5_$wd}?Q$FBDc;M{!1c&(oBWY+wNboXE)X0x!?c$8 z?|PHCn~&&_7&Q3g$@;Aqix|uMLmYI2oc~$QeZyW4voEcyj|`@E}Wdr$RE z12{+$<-9&zHMBY8nn-ITAZt@N*&lNQ;F8*Id% zWm9R()U|I%WV3i+o1|5*M&a&i@^2-bY1m9?00Ye*1MUTPv>YDdxwllZ2BzuUj&zM% zNKCLjlZWUj&7{zU{A#v~!Q@(Yi0d|jCi!CJl4Pl3nixP6Bx`1vnXN!*f8p-kQ|>?# zOP~BN)~{POTg5PC#qe^^z|ic*mKTfj`*a$F+M#Q2dUL;DlAo^(<%s`_@V!3JDpXtdPl~uPMe5K~J6#u9A9;K4bFPb-?uTni$Mu77bX}LTKT;~qp@5yX)EA;;3 zWdg-j_{Jx4l{cLU(|@|t&QQ2B*gCq{66dMuOb-Txs_NmeJA?T~1~vp5zw`pTMY066 z>Hj_49M?|ZK4wTz1Kj0QU?-j%atxd;q*B;HKvpi@xpNZOq=8-=GqvU-o=XzdI}>C> zu0O7H*c7KUo}eTqQ1VxK6VPLmyCI!A{=We!lH0Op4?o^G`bbf6HU8#d@~@^jnw1~D zc>9C@V=2T2w>!Et_TzO!vzV4*bRJyOvXf1q?QQ!{jDr4R&Bwdn>tGG!Fpi_2eM^rH z_nbg=r-3Cx@tGLV#wg2ZNdk`4V=y;8Uia#Pj?Hyv9f#bDk?=mozt-GJBxv4M=2exo zua|v^&qsmoPvMjs3sek#MOW0-|Bb_+nzOZeC8FV~;iEp^uE*&lcZzd4|04{IKuUo! z_bo+!aAOTs7{Khj3EXDHA5a=lPQ%%l4$!(ET7|MV46Lm9EG#U5Xn9+Ll9#l_1QX+d zflOlbNbVa1c`p5y@pX#X%(QmLY7t`DW2rZWT|3mcSI`(vIz|J6@S zjkL739(0-P0SoM0IfBa?@zS{md*6HaA&ytifCNqi2;?#uKp2#~-dkM^pM>VeFS zrKb;ubdh5IdGD(OphMY#0Y{^kX`E8wkLtE&&HMo*@jEy^Vjy+EvAhR#f1tPlaV@(9 zZyO>#Wdp`@O6!j*Kb!`~6o+%3qV)ID#Y5>@p=0y9>y(D%mvI>d!w#QAEhS*1HJL%1uP4 zOm3rJ7n~iQ^9O^acw^6QH2|SOy$;E=fC7=!Eg_Dz@ge+}P}QhEZ_8#dY~KVfslB~2 zVWY~=i0J0zv{1gRKZaP{gbW>5+#86bXfEK8nxD6n0i;o{g-({ekxNW&A_P5VJ{NJg z^$vwPI-~@^<^&Psy@67h?V(vx7zz_i<@lBgAodC^i0a7Sc5F3LsAnEm>^{y#fRWO^ z7VvPO!5f$G5Ob{oVsRWT;{`XxS%TvTgeD$nXBgBr;RSokCSD0418gJSAD#r~U=7Vr z@_6ePM-U=8=Us_FuNzYk$`C2i$qwQ-ahh{+l`TAB4x>({C!E&XPq`uFCQUmAlRGo| zmpB0{Z`onpS#3v-=nHdnzBNa5vdTR$H>o(VS{#hsg@lOt!E3xQf!B(SNT&A8du9V$ zG!95p6e|c6Ko0+0I@Xd6`0&Mm$CztxhsYGUF1V8XToVExCxAoZ6s>jP>rAKcA=(#0 z$M93t>Ee5Zkee&)SS>}TZM?&z1}}ftH5kk3YIk0*Wem*Pfaqr%zOjc0yC!c*;OmHb zc;_-(jpqm)pN`z489-xpl}uD2+!3-}vtDzt4G#_xNGhTfP4>hy+GO((>^XKw?r z7Cbt5BbsLBbG+jkMvUYr#0Wc`q|Jmj^W>-)(H7(_(Gn-?)xL;iO_Vc6E?nJjzKz zL;@c_l{A^cA9YGdZ^Pj*?h&F#RyR|O!?Irk^Ct7cqiOUz?eLHFH5nY?mFGkxD9|QZ z$@op+6wvO7m4Cg+o?hE2{-D2lKpTU!ewwY( zn~X1IjuR(Rd@5bP3-MUE1Q3gi63L~m+c!|{ZGh_n5bL!&rFbylvfoO~kC$HJAv@-+ z>|OL1KcIt3kw>ol)evD{w=OHisMJKAS1&knecnACqaljCCr6KEydbc>>xC~P$eBOW zRMruk{T7H06DrW@KHDZwiI5%VZT_iePL~-0BfNG8m6CLygbdtkGo!N*o31#tJS#sD z$B7P-1p&HQsA}_}Or{`W-v8-Dyx}4oFK0LjVvpzmzpo@Cfy@ZSdJ} z^XM#sG1rsv&PhU1rZcdrtF47NOX?p@6XH_p>B2IbJi=9`QP zV(lz0YFQNC!p`D#Ny9Qu!7^4-oWRDe6Ix3o$`#=wW9M0-orE~Npa)egK!zA8k7%%2 zUnz!ZIz>l<*5{ee40&q6CY*xS>7`w)NEy1Af@hgA*Tsyh{8x_RBJo^`ztF{=_}haW z@|f}tNR{@J$3ko1u?02E)GTCwMCSl1O*ve^#07a1iP{7kE)u+V!ySak>aVsZJ4>`H z*c^9q|I-t{FjHtIVg9#zWL@MhHELz^t#ia2;c49`V}o>9k=bw00~LJ#0LPkBNQm;* z*T+hF&zvj1%DW(Fsxw{v`X$$goT`C#{S7hJ2?5#5O4Le$ibP%Kxqz z8uGhYD`-tT$8SQ7h)p-pt)j_oh>^t2O^iL+8;kcN6rMfrb=?$9fn^R*5Sp+>D>GpNo)tmfjD!8_um}e^M;iBra1OyejVBb%9t=+@{yS+Veptbw zM9?Uso~2~7CYh{c;zx3ZNcv^GV7Du)1G_IIS~fv;wholpyIEbZfaA+&>EmKMMFa-A`0f9FJEx& zucFT%8q9Z9=4ICP;4?N1)?l%n(!ino#y)sFR)uvdfVjI4pxg zfww~67yjn$Y&5d@xMxO2@E;;)MpFVCs&9iB?k2*cFX9dUd15Fv$|+H%@;GAt^Bi%( zviWB?vcjO^g1kwjUZ83@6YE#@j>3K=nLL9;uKXUuRubRSa-MZ8=q)t02LLpLjPf&L zxUz}}l=uxot1?+hGacJL~~EbQ^YMY@to)ipL;;r-^4GY>d>Lz^R#K$TNBq4#0} zbM43uDIJ^lA{VLYug(QVt(~Hczu~l3alyg#%fXTUhnpd7 zs_-NRo-Ca`QVyPjv@=S)!3FS~)`>on@1xTHS<;Wx@nF!KFGyf_KVvkP=wTn?tgmQ#V-Fn)7*4 zy*8~S4yv=JUmiiTX}AP?^AP%-<-+VvVL@j4m-y{IpBT0UM*@HXr=6g31s&+JZcQg@ z@wtT6!pUnt5a-v3*UMhW?-|R;5pVKzksmSii+91tN6?ir7|Ql9BMAby;1akLO{wlX z%WK&kvJ#}g+c(`kx8H?owx zmHXUq)V^FbBwVD6SB>c=jB$X1IKKQm%vd?y38+^--w?zk;-yNwKmFp<&Y2CK z!;(!Yw90F+s%*#IK?s=bu9Q6-^9I;IB@uy|t)Kb*K)_48-hUik#G;0aCziU3-oq?5 zyyDMW^CN3xG9MO#3OeUu!F! z?6a&v%4 zz>B)7NE6WnG;Zqel&3dN;GKd8&%tvWL&S*@Kz<3$1POp1z*WRz58yyQ3`_HDJ8g~% z-QV6H>h`l1^hjY=^&FuiS9tni+3eA;BD@QmMkvJ&!XDTYk?sBJP-=MsrI=D?_$ZEy zNRiNG8(Bv+FU}PzTL>pfAwuG^A%XTzgrLK)5yUHpBe)cSjk$g=0QgES4l4n$xo@GoA~Y2EN+LB&E&R1X4YJp43c00a z2qKo3BHW#BY9~M(jRUqHW6dW^hFf)MOW-!fjGV?>iChV!KNSd7AF!t1L=mFQ@0ZA& zjwZ~s?s%m7y=1IB_xaofipnHt?Rry#9AgEwfNTa6q<;9aMKu*3+ZPHn1>6kbTQpk0 z|5hs}zHCy24+;r_(FVWeUxXK_>p=*y609o(G>QNRIIZl-UemkNIL#kR4!$_fRSVkT z-WC&W3-<>APBYN(=w@e?@6GOy_z5s2h`2-$DX8$+@jSQnN|O7OPBdC~La?%O85%Q$ z!MA4&{AjbOrqI|0UKlxL^``qIyip6eg~XTTHioZ#oj-%rEOwf73P`A<ca%$MP4KcKKN^ zjW?aHIQt*8XIkZ~h?u%xKQcO@=X)cSOb2`0+j57%{4qcHv)T8_?nc$@w?t8V zNWSK5?|it^YJT>zV3_=WSC`jkJEUgk6;D3ZHJl4SLEg$pnyhK)eb^7h@rECXE{2@W|KD7-F~sd@ z1AKi(78Wun{o3E(mx-R8o#p1_d|f;H*Xs+u9}VTE`Jb(Cxyn@f{I~<9$S3k&-O&6m z((*q&$FS_2FOQ>0^=BJNi87f2-X(1dP*F&x@7c$Y+I6aAX?lCUY`8@-!<=bvjN2y zcC&_Oa0+kcfiQ+*0_kc`(uD${_a+A&fd1h>s=0r!iF@-T!srA zkeYjv-UmYvJplFW?nfpdbT7;%#Qo=WCI3oA|3i@KDr!IQ9z5_ij$}lHmEe*BghN`| z5akDlW|l!N5zY{&8&e!LPNH%2^3=awuQJx-^3P2HlV8G)lTcA@&zHS@_rJd7*+p@8Wx+n|sTfpr$PYwrI+VE<=d{-Frf94%e9ZGZJr z<`(!`*x2yDMg^`$!B5p-A}2zTA)-K~dF@I~Ain>5yMM9Mr%SHpL0QV*wfskur;DL> z8HYO!-+twb-QAddUifsgo(P4Gp%j*y00Z}qC?~f^q=llg0|kR{!vv$)Z4yd$ z1)tgt$!+gmhPGZwsB8tMTH1{gdlCu?Ww@Zn>MTp zK0Ac%0^7F4skJLgO4O?Zw)qnGHOq`E-tF(_!}SKRZ`k9<1A%!q1Z2FX_V)8DUcy`6 zPun0hfyeH*FZxd7`9n|(DE9R0*DprNdyJ%{q|9;;fC*Q+(I)G3bg+#A{EXsv$x+x~ z^ugZu_NQijph!iXCU9sKx9!iIfMNSfDk?;$1q9mnDj`&ynwhzOc;ftnp{sP~%%Jr` zcR5T~C7L4Lw&Yf0l+2P5MBT{P&l?VQzonf&+y8&O;KlxT()WXr&8Hj1-z^F`V8m!G zJ6wFR2J}L10O8J!cuo?w4<>DY5;mC|z@Sy~@MfRg^^Fv9>O59|8M~J6-y47oMx{jU z2-L(^+m+6x?pJnqkG>qgItJj-S17R#-(2XO{Qc|4PBmn|H&V7OKI>;4!>v~Uo*xb| z-fy2pN2xDRu;2s=fP&3$(5@s5cmTf1jj$xVhfu|^W}Q3&MGYKy)R1NvofD0q7o_3l z;@a2mKAEWCTb`JbGBP!ZzdIlg(5waUX_Pa5^pDNr|0>5&>*pE&+U@)08V>A|3ETXt z8Lyn8BAv60|n*irlMkatk#3KK$Y{kycI@5QuF`D60G}~~_ z2ElwWi~Ri}&tbP-xNM-zwBr2HzObMmotsSZ4oLd_s9iv)q4_hx8_aTz4G;3W9u*RI zK-~xnibZl>4EALEVRaUjO1R9VYs>}y)t>c4KsF5CG`6Zin2K=7$o#2n)CJ5N%DEx< zXOzEx76_Fq(d$AjKqx~objS~w50yGKH8)%T?o+IC2P=0uL8t)=Lx`2AndOCI@&?P` zq5`-9Lw|MvPHC!H^@B*$ml3-oPb1(06_SVkO-)T3Y`w6X-470TEx$B0yaw6v+!+ti z($VRjD-5{5w7#*i2HdrYL)g=?Lgz|%zr)>XNXqmrZOQb$h7%1}23Y@=G5)rF8cl(| zqNAsWG9$SD=X2ZS+S(diTw}W`?d9bK++iWO(B{lh`L)mg9oNtuhi1YOHeA6hgT_yMyCE^8ADbx%U z+y1Tb0=vv8Y5|u9UHaSO4XF3hIQ4@tM0MJ8iTTg&tAqsNDpRwS^IQyn4rUeJWwpP4 z2lrzk+If)Kng9z`F=iYOJkB?MM~5lV`IYPH=tTu9pZA2|rk|w+v6pwCra#3Ga7b2o z(?uJb({LHjlT!!6^4Io(BiR7F5CGr0|DR6I{H^IL3*%owp)TwwJ`zPOMJQ0E;}oGR zA~9M;6tKtu2@s_NMq)8T#Xwmqln7R3`pmQnO%y1KLLviHwh)ytR2@YNm<%FIuml9r zfDi&m=Dj-qz|60CvVHGz&bjw|-gn3?^Dj?3?!waJmnU2(ox||7C$N#VQ>%}6_v?-$ zUOoiBL%<&_vp>MT!zCuRXA(1V5VLO+8TmmgN6{hD+pnIYX8v^Kh)Z>Ng7ovfI-L%_ zRdKI8u+lO5ro?Lq1(cERo7Yz1HHSOP)#&IE=b;^EXqup;9xJ#Cn6CER9L`zGYQRz- zAOMA-nb*T|^`hUBc{m33`>{?ef3tBmT0YEvclEVOW(}%?Aklj``R~AGv`^79k3d@4vAaa zL3k8#6yl2Zf@5L~s={Lp1!A;)NE2+i-GU@~aHN&or=HOA{c)CNnqx@dBsROq?8Db$ z;0-kF$4B9Y!(DZ*;nnXEG7}C!1(S_i>$&mq@fe9Kyo7hIBaeq_>VAC5EURtq#e&cb zob_Gr;86N+buD?4K%v(uU<`PY5{`NbWRZ=OKe>(1=U0iGJ8K#qw&__?zTf5c&N@@1 zs<&J3-Qv%e=k41+jOMnbiP6d0WDQ$`uAa)@%-bFiMlKd@kz=k3Y0uRMeL~?ty6$%y zH%G^vsn7+7iJrIvk<{RZ z(ERKg?+?ei>p~hq(a8Jyq7%XQ25;_f6sC@UrU62UiNm{fO8~eZN4ho8E>k7l%5=>S&{eQ3LuU;@2MVERu&VVrW7CUT|^)|!;5tA zxf@DLN(6iQiEc#IGN4s3abpj%;T`1?#p2;rp@NXAQLOI; z9qV>JHxLNA7y4~^slJR;AK|~wJvU;&9EBTV!b35E>ZfK1E>vJH%fNUp94sy z|0BPkU___Iayd;3I%ns56JcRtD{tSvUE*kx;e64--hTSUWcQ2C!!>Csd)5aVn=Y`* zKVolhpFEG8mu&FE>|VTIx~|U;QiMl4>{>9p7R#4sV?JCWYt2y@{kSQ{0DgtY3OP`k zG(F(F!Q7I>fZxE0<7~srCfn@n?E7LJG9d$D$AU&XjgNO9yXPuw^Y|%{z;KuZxbFDz z`JQBhd$#q;(tWwL{YI$En}IbTbNv$@QUy$7iy$64`aw5Iw!ytSmj72?GegBB>n4s= z+#nf{4n79$k}ttvH?u1#YS-@Fi6}KL0T`H`R76z*B7de=_Zc>#$i!~(6(*||6W}ULmgY_Mb(DpWx53WpI)dtGcbye} z%?@Tkm^o8K)fke!hHp0Nfr$d1YfVr)09#)_^wJD)%vkUk}Ac{bX zA~VzVv%Nzwmm(5^Hjkck{nvyyg^dsl&-}k|6AMWkI$dGa3NRdonk;i zgG@d!2j3XDNBL5O4p&ykTlIXcWiF#_F(IZk%If!CV6DcS$k;QSDsB zwNAutBOqN9UMuYE%qUzTP;X6;kmW*7PAo={?0RPY3Dg`VrKLsq_LV-VTfQ~3J5#`| zU(6`BK<>*#3kLsj#H;m-suSBt;7WwjAmujDCE44Fn&o9!F1+;M;8aYr;fLx3eb5=25-cMjbS+3TIXL6~f?`|mEduvGKUpFahJDdx^!KcF&T zvvljoC&)BoHzl(9T(E%yAmq!dCP5o+gmz4@e}j|LV%gmIQli&F$O@|n#fY<~U-dtX zyD+a;;W1L-xCQvw=<2m=!~xSKs)>dGyodr3WQ&}A6R7Z)qe?eAgP|I~x3RT%e#)KN z8W6AyBa=gnnGB6hvqG`pckV z@kzgrp|rNKfpWh(E>j?QPb71&D1(&*IYHkgJ>mcPYT>{45QF*!uA0o8Y-8pwc=S@A MZ4ac2w?%*RA94a*245^ZYCiOlkPR9 z@A|&I*FN^2^=JKB90w0R%zNJRy02@*InHqof}SYL;9sM-hCm?j}F>`b=vNuI289CZo+BjNT7~gg_wRf@9y1yfW;ni~TTle8rBEfI} z_s#z&HcX`m%f!UFGP%gS_XZhRV6!o|Xc!#B1Xd$gx%Zifk&%(BYxz#>=(@5P$_XETcbADgMZ3^vp+-pD1ZsK~&|+P=mzVksad zE*=yTqCo1#lYN=oJbN%WGc!}CwsmtFZE3QMA3OTJr zUz4VA|82K_aKOyRchkmZlTS8wJL}&YOv}cFy-$UnXMf7i=c=l%R^rryjf;yT!^Fg# z*r#jAwXH>3lHpvvdR4c|H3HchuJ%)t`z%TI3)+&GpFezv372ne*`A)Ab%$XwkVd_G zcgfSs>ls`BZ@qnhhr)DU*)^)Eb_Ty)6p5@WZ%LesH(n1Kp7)8`AR8q>Fj7J z^(p~@vu>R$EEDc}yuZF0m#GlTQFS;MqFdt`FJLwHQP4&owt`h7mx|Y{%eG6TzG!WLX-A~-=seThJ;iiMa;Vs9&b)nlk>g2K3;0|?cw`te6Ril;*xTt4R&59 zA|j>aLiiIXX<^!Ys{QgPidF?TT;iBzIM2ZRWPcs;Q>(~7N!X##eeYGP*z2L6U#us8 zH8nRsO_#q#!l~btBJSaOv=HmIoE}Rh$_NkhSXK1~+}e@NW3~Ysu29TWPNo_NqY`dd z8!gf*eo0h&iozW)vsv03HgFL;Z)Z;Ba$eJH2_H{)S zXEvYnBj%Kpl&~es$zS|7HAhUQ9nrHB6%I+FE@4ACI=n6$x)SGyFPM~*+GZOAwDJux z7CJt8%y8dg=H(%)i<9)JLDo!K3qE}KFtqQRjA({lrE~Yz_BOX!SDanzo_e1CY9tW}iCHL>Fe;@;>hWW8U!q&L_NMil#ARh=xxnTO85kIZye3hk|M7Qv-msnS zM8OYUC;Q}rHdCIT_wcA+kr|RrO|=^Y5L90{F)}ieYvk$kM@B|&h#0`4sC^O>1Z}LV zF3wN<%gV~^&W@dsyUPPOhE!lHgQkfBR0%c_m=CFHV^1h1jjj=nQ%N+uja%W7V&HJQH=m8ACs zB6NMcjMCqTEcM{T-DN8H&*Om%M~TZ2MF)4b1)!z{Fl%+jSlP=KS}88p3dGs6ZxjC6Dj1-W1qsBxQGyTvZ@+ecfk0|=;9 zJ@3k&pB}X*3g#ibyA${e#@DIDTt7m*?nx2vY$TLSqC>)eyUx!}HjhO*VmUVtB_L4F zP$ zm+8LG53u$(COf}A4xtL4?$|vLE33IU898&Hx~Q3uT&i%IepNEHFBTLOG_t<0o(kq# zwKiRwy3iS0T0T$;A_9Yg?udwtZQEJ-^tvg)k$hLnBv>CS`R2a2VmVPB0eddwm9)ul z=gyl%K^xS`X6n%7+U=kt3@y{RhPXQxLy zVSDKr2DRS18h$Ub@U8>=dKeAH4PhFwS64+sBz;396m_J3j$9;8rf zbF>6I0fYfW^kQT@P0APN6263u{%^v=lOOnrQ^}xh$oPq7VgoBeI zbm>F|z)CcyL5i@$;ua)`8#ixCL1OqjQa~?|_yHW52!4^JnjR<7R~G z$$A;Nm@8MhLTm;cu3|jT`^icdUaw=vw{PEGxpD<@TOo$+5;nH5vn8xgB;_9bFXGar zOV?o)K{pryLd-xU0?-y-S9c#m^aIEy{ICAhL846cKE5g`DJdVzah7`id}>u_T25D& z%G=xfPp;lcsTFfc!-_SJCkC7P_v?4=-1(_l(D3vSENZmaf*1m-_K!|i4-YlSTF-xK zKG<38elvezm!nzmc4M+~dbA}^fn8>5=ER=@?W$P(D{?Z>-0a%LvfFXZ#$R6c zeJ!>ejbu*sjJ&6jyEPxBf@&r;5L)y=eh>@{3tL<-n_g^qj~mUQmjD?;^{dp?nY`Yf zYW|^%s?;&D9PJY0`nTABvNghA59e~bp-c+Rdwae={pPxwQzk1f|5dlbo=v+r5PqbO z3T3u5He!V|N3PTcbfGqp4@?3v$%u&?Bj{zQ4#H_Ad%~zi+fu|uk9L+a&3jYuXeE;1 zY@dFAat8;G?7pUE+_wn~^e368xV1dpazEHm0^pFPUGn2a>?wE@*xI*jgA_oE5tVv> zM{hB|4W$$evqQF|$L;rqYj>uIpI8l-RY&of_iQ!ba;E*_#hfV_)~`hN5W*J@K1CCx zDOIm3!}_;j2a_0oa&!cny<{bRo*h_7NJyL>BE!paRyTco7`-~KV{i3JUd$J?(l|`i zI+2w^az>k=%amIHrJ(f|z%YmPF@74ic_MEBEjKGY!)e4j;E<>ebjqx|n?p#+0aHdq zM1-QF>ppjU%nLNhAay^2bdMBcR!%Cn z(mvRj+;nf#kdk5$|E`{O10wl?AEAUTRpBkS>*Qb2C}3Q z-@5l44XPnW6dKlJvXS75Id*D3E4Xw=CqOJd-d%p= z>M8_hbdy~>+NSnwX!{Tr@Et-t{O+Bc!3|Tps(^k{p~G>4)<%~Lg~*?2aD zvt}kMGldQU1RB@q!ZDEQyS@Q~6>c#fE4BzTg>>2M&?_!uYs)oSWWEH!?R;28HbQhj zramZ8w#A6-I_2vghm#Y(W>j907pk2Za8@8BEfI-t5*oR>kX}&>ovnav+al;MuMX!e z0d{8Milvknfc0Fuq7xv67Z^3-NSy7e-Btfy2Ox_2F{&$`m(QaA9Raln z7Zei&R6_TMbM?0O_Re}~9}Bu}8A3#EF1JH&?e3b?`C_b%mxY6QMnV>WcQir5elsur z?gIt?SF`SfpL&%fDk>`egtR@xDq{5jl(zQw&sBQa(X2&eL{rPd`@X`x)Wld?g{P~Q zfZLkK$0>b$d;khl4dgt(_sAd5Zh{lSC8dC+A;2!yYleU?4i^(`sL~gqU}-Wg*aDD_ zTwPUI?oWsOfd`n$iERfeC$%h9M(I$p**F1+;;J-R5NyC`=Tf5Tibzr=vrA z4pc|jw|&k}VehfHUJtRYIg3tv?%>BH^h|; zuy{Vpk&l@v?!jPRnC*F+U{dJ(tI5Q{5%x_cd}_y`!vM`OF(9`NRHlf{ha4n*<9W?d zLpnCxQ2x9c`YC5j@?gYkrb0|LNxD)v5*M zfWn21|12V3b7Pt7=O{1)a`N)>+*Sag{``0r0-$@6dtHBD{}ap8x3u1eZ@`NoGa^O` zO%;OO?rP+ALE*)!nSVPaCF{aMg?&Ks(>)D>%E=yZYpMX>i(K_A)vjbw(nc;S4~*d) z9T|8gs5h`8aYup1pz4IfbbxZz$1Axk#%j7o914>qC|omCQYFxfRnOIp2Q!Tjb+HDt zuwkKR?;?V$39+mF8VOrlhEk%C-P|Scw+8DnG;eW!x})NKwx@yi49Kq5_w2JQ#!K0O z!H6~Rjz2p&*nujD$E=GCA#-(gD2Eb!{)fcIvM?)tSm#G`GiZJ3r+i6h(m@o zg}`5IGfk5{c$}B#FjM#Dbaz07O4$BgwZ}oB>$Y+0msNE1f?$J!7mA$MwPkWIPHHdE z1>nIJafFZRKNBu2n{vm^9+U@vYyWhQ6!K3Ms^ebq%f7cz>Z*N{#^*4oNiw#XNd^d2 z@UoB2d2QqYgv@`nGGs1aq}Lk=**|s4!qU|7e&O$E5p#WgeVB2KcE%si?PgN3 zleMC%^W)WMHmyhq8urK*d<1H-yA!Nuq{@vKIE9%(4TE%trJmi*>FEN`TJJM71Xhta zVu0;S2TtWCtLnUgL1tN*;MwusH_sy!KrqVe!Ikn;G_DL@en0nLX&#`TRgFeVYWtIi*bQ1)DG&jl3=H1f7y%agsUmssxgH zWJd2D^6-5$ju6sV< zAoJjlXWIt{na^{yq1fhXc89d1yfIO66%Q{BV$JUQcr0YhjAq-QtHo%hlLxPnE3l+F z0X1>1f3C?Er6Mu=`^%$fcAc0nj{-3BT{iU*z`AwDalc@JQ-Vy3gaboo$Af7f zSQKrBa0y5sncex>sVhz>WdU$2AkyLE6- zi}b*n_Sh6}38PlX)va*d8`N0-lSK?c0Lu`d0~${#LPiRp^^Sue%mV=!?zd|Ypw!Qb z#$fGS##RNFLh-m3Dqb8ne{2@*6z@*tfBhW7C2WBUmAAO<3<3eLFa3cZPM90;(#r3z z-J&`Oz^7~hw69fedk2c1C3sedA&J0vqWMY0HBt`GaR=ZS`q7NZt$Qut`rG^aHLqLX zaZ@4TAllQ5Ee0}xT$^28?KDsIk_Mw)hC&U2b(vruj)$I!X)#5=Hq9q~@wzRbd+N&3 z3vYNRogX{XW4A6267%x%LexS611kZ1zY0F#=H{;28`42L;mnL7)Q%&yK9XQph_#Ud zEO1wr*Dn3Q9H0*$SibX;Qw&IuQ`=rIU$P)bIdl;-kTQWF6K_7fsNy8o$r!~dH|-<= zK8xz$U~Tjfl&LQVe+*K`UcGiremf<=W3q&kj&5=50L7ep!o zR2}Hd^r9scUDyED++Hi{jr{l#;hUN|EuK>b&kczq7V!F0I53~&>CVp1?X#R(ALq(5 zeFJ|J+xQH`B9!#aXHUOLKTVU3s5}pEH!k?w#X=N;2S8dO-aNi4GUs z)j@F_49P1`r9V~C;mYAAc-|r8slR`+2J{YAnjxotzK;R02kltYHotEX5xG49*4YF? zQj(C}TkwZTyG?DVhvNioXaFc1!a){WjSDna!BuJSkd7;Vg5aNM6Nb<41~6o!GYo#< zI{Ti~70PewP2nn9arfOBV7?YAH*1hvvyJGo3p`+1R*NapVjpon`4$_u+09QFu zj8Q(?5XdBSrT_gq3(%>LpadMLbm4^jtKbw5iF^);q(1oe?Hfk^s3o)>GHd*GRvq@; z85#eZ&n)UTYvjUPbN2WpEM`IGk6fMP+1r>*gz8WAm!pOCRMm31Wv8S8+F}3pr{k8q z8l*GtNvhiE5rxE_sd;g@jYMZ6*R#Fh3eO`Rbh&6VUBf!$w0Z(WW@KDk8vy1WI7RBs z%T;@al1sIFXVaM_76bn1d<;;Ch?G(%&S9nL zRJ@Shh;1(CZ-|!#9s>}sS>M;k2UVfnX5RpPfCE7v!9QK37hPcSn6z0909zVXTk9}I z2?5+^dv_OT+;>}BTOJ|>5Bhs}d&M3>6pI(K`#Sn`Lk=1s00QWEcp?Ef-3)JrU zd}X@W75`JeI>Er_Y|!-m@`F}k4h{lfLS7B$dX1MltX@eG?R3PpMa{R*_arAmAUw}p z04E)(_7GG`;HyB2LA7;wcsL<2+1Yuo+j}%);nxD^fAN(ROMnyrlhe@9xVol6B|R-d z<#tcQ%%ntH>z5-dy>#epfUq|h<+*@phxPm|#3K~xfvX{=t6zwl#Q4w>(y86L4e%^k z-V@77F>qmK`NeiC?GAib-u?t!lI(G$@N^Y)dgJApstn(!aa-}a#AZSIlx;B)Tw9Z< zP5h84c;gmrv(mVdHPh65#yZos-1a=G_p$4cEed;q-r$KugI`1YVr=)?$Q)+b)K6MU zN{?RJASTTAalF6p!bQ>bwi;Efd(w2+c}puADt5ND zyEWhN0XM0_+kc=hQ<&N-A*6s*_?B0&T3=>dndDJIDhZo9ezv?{1OCe=X&C%FgH5eF z`<()EEe@-^<2Ik}7m@qd11q(?v%^~*YGwu}jYf`EGS->UAmo7dIqyNwe9nT6-K;c< z7A3PIDSy_mm!|Xow@w!NUxig-JrgFh>=So879MD^kvx3#s2xa&Ux!yX0UQDi zp$s9}$(0*lyiLf%&CQ~Bx)xfB5qvI-$K*J)lwANYF<9b@7>HAoWY;lEqRh+PZ^fKq zQVP_CQQPjaBne?$y_%KFiTIw(f3M`x!_S5fSbhicKHkX}v!Ut~YC#qG*q*nz#Zc)t zL^dk8I&Ei*C0sn!j(+tZM3udbH2QeSOX1k8M0=o_)(N1wu`yjuP0d|j3t41RDO6Jo zO3lnI1NO=a&id0q;e!F^B_})1Ic3`gIx_*ZhGTr1HB{%@TFC@7G&7ro&Y}#A&^<)$ ze*Zo{UhjvP#~!=bG`Sd* z=~IF%bk=eJUi<$f)>gNdwpm@$#?l&gqh7F&_2;a8_w?J$?sBae+fz&$Z?Yd60mjXr zpWJCn7Oj95=9y$rknK8!ZVjG!55p#_m>uT+x?i&B?BAzs5lgJKGhz#*_a$dc2vipN z+gc~)f`0A@b^jpFMw@dUr(1HSf|yc3F!jqPQeehvSaE>(Ny1S!S?t8bSRMxrrB++5wE1TE z*gZ*KhP#M&F_kYh?*5SQH0Vym(lsBN(&`!$4Z+mH{he-4D)M|ycItCg4;dy=grmYz zUWjZ$`J&ysQM>lkoHOU{G7HbPx*}(*!yT2}h)?NCk^#t8qnSDnPM-t1+lW_xe24WF zB&s}DZc>TjsAb%*biTRU(OlVy92G=~_$a@lNxVI>*xvp<3Qv>Y_Y{fR+3m{I^0utt zV7NyYAA^n)34v^rwEOx2QQ@jaKKwKZJ7Of2$+yIMa?5-^4+nh7y=q**K&#B5er2po z#hZ3EhF#P9JpQiah2p1l(IZ1GItPVDjc0~d7^1j@9452%@1wi*Vp90s`%86oPOBV= zjEUOC&~Q0vW2HNrO(-AXdw#CxYWCcN%~@2Up%k}Q}?lJ)-7XcKd@ z8k4z&|G5C3k9A=jQ`O2I`zF4!d8`A=6U3A^WvTUhzsszHFRrB0aJDap8+PS=yr9qx zu5QYo4v4rwo)#PYPFY_nO-$C7nty{z=?^k4Fv$*od?6`Go zcM*1DxNeGzJ_?BBmY-qA!1!H2|5Hb1&%l{iytR`m^>1h5YP}>zskHUCqo0fF6b50m z2WNqk`H9JzQu79AfrT3NFV8E!E6jNqAI;S_Z<5;6{Og=ckP9}l>X0xgGfdYEgk~LJ zFfYFAb78;K)Y#MMVZonyYeAB=J#>;+w$QwZl!b2NA^Koeet(+B)STUY2CY)_lnSd9 z46I1bo5@BCZ5W$Xk8-`3$&bdulTN?g#TvRlBs4{$mgWh3}OOF}!(CI5vu8`SozJqAS2Rq-{$^ok)xEa%F<$9GX_F1bHa=zW1tYqS0 zn5K{`l7Zc)PMMBF2IXL+zMK#fkcr|~ifu=|;I4}{-*kuMOgksf+68*$^QkYiprc3=NnHIB( z`N%sgD&al6JS&WBYVWYqWE62n-|PvAl+@$6WL2q&Xox#PN}k4Ih?=1LF>D{1A!zpd z-C(?uEE0Z|cEfbKprv>W*B`q^R3LSZmUJ-(JI`Tn@!7vm{r9**D)Jn@5_0!nz6|cH zEwAoRXFWf=VRkUxo>5)$-Gge5T`qL;2>Y>QSLdOmL_c{W-5d{km-)&FFisdS>+3Vj zEKXk7l_X7Gwkfk!1>Kar44Srf?CBDBy8=R{n`2CPMbiUK9{yXKmRBU_vFGIFwZ9Fm2VJcJ zmetcQCWbRdyt5d?Q{HKYGaR1^M+P_UpiaJ+!s;Rv(TcVtrtD3F)MLBJKtXOfoKK>H zrp%{p3D!P5rZ(L6Q@&ohX+5F-j)zqeq&B*IqF(|{Zv6YKnv@z>ok+qn>E(W=gKpLI zYwPCJ^M>#9+)RB)*l;{u+^`v?7fk0+g!z=tMfAb4IB4vk{Aoax%olfCqYFQ>Pm9gO z=L@cZH*x#%h=6+NyX+JJeZApW?M+g%gVA;L`tZ=|siYtGW2z8I`BL#o3{fBn_(GUj zw6GvaURH~Evz^bn% zjcQ#&8X-x7hOv8e{25{oYgsu(IGWh$P&Pb|G0-FkNeE+e&U~%sl{4V=ShNZm02oBy z(+C58yPPFQcJVov2N6Q~5>{(id;()p;k$QRr?IOe2fq)*e44@;2+5r6DF&tImwtar zHftr0z`Lz>^S&=MU2TB~YF!6%u^d?iB|#>TZjKuh@j#XiRJl2Tgal*`9=dUw3=Vfu zwV1BAnQc$YD~xz5blLSyTFlMkeX?lo49|XE;y+HJYD$bsK}t8^7a@aWMPe+jea_5e zhVE#XPEV5XrqCvI7aP#M11K|GVpL|2yXhCPC+n}EBOATFr| z|I+1w)1rm7Y{6K9fFeW9nW8pqb&8a5_ST_rY0G5Bp2V4>fffD z>q-4q0ZkBS1*95lL%}wZZ}dpJ^=A97y=nVnmN$qs;cp6`%H>O2*bi5V)D%Yz-g`c^ z9dZAlJw0gF)Md>u8r2oXOt-9s0TWkjK|~(TBwBXT61x2l^)U4 z(*w(;5^Mntnmar^sN7y+T3Qv)Q-f6N>(tcvzEItoIczLBO=+hV4c}w6NE(n9zId1v zGT9s!;_)3-=0i)dRBXDleW$z|A;2uP)ABVoUX3B_fI!)BIX^Z2w8Q3R+tZP?!1%YN z=EJg`c0;`!Q8(*AGay>SX;32uZR*eW-(aFCA3&s{>u%CvRPCVXvQ9jQ?Va7++$>%? zsxwelVA4mIuZ{7cDBE(M;H%eJ&>wBSP>klVtpJrv&m`_C zl_gPse|pGTgfyiXOVOieZxIH$!t!d@OR&PzOdxhZIno2IT2(JGsBCvG%Eg+Y@`mn5 z#j5+s-l_~Jzy8(zR|yF-p;Q9qSlo51wqVqfO{X*zx~nq_3k!e#wYx3oMNTP-NZ4Pz z4op^2h^~A7{bS20_IZW4py#<8g^yrZm`_coe?Eh>w941+*)z}Mj)t45<7^inylu** zwZnFD=v_D1)JW<;Zx{xBRRzxK=oKU|E+#-xqiIfVE8zJ4{M6dXUESN>u5WE!DqRNB z*J5AcHv2yXrsy#J`&U@`;+Jk5Y}94DqDnCMdvdoA>^S=NsJ(5r*ft5>LyfTMr6~`{_*lr(R6f#v%TJ`2ekRX4i>M#jkozE$oG6rD~nv2<69R?bx*RVtzC?!n`t12iFE2(p#= zj!(G0fq_@RB9`K6fjm`Al}OI3ISvNGaSPZGbTbuA`VJ{vZ&!yhoc}EH;Mhtir)YHm zTSes+!FddIH_1-J?0kq!ZG|~oj`TAo5oOr(IcuKgJ2OCDPVH?&;X5sm0}Zp{SA%yy z+z4uW^msMja9UYlBy8J%(%PBoD7Efb>9D3jj%H&=$Yy@LapE2I8VyCyL~bXG&UgRO zZKhEM)ZoxRaVC9Tw9g=Rjo?T(vn4G-@nqpq z(YK($5P*WR3ExTdiKiI|In3T*t&+r1%bd3xe`!giEn3fN<`Y_f^fR+QB=Pw7`hav3 zbIZjEiZ1dCASu~|t?k_}F^rOk*M#S0_7oLSNluCRj(@pvQdkgm@3L#3ddOnXaZvLM z#|Ne{0?d%(bwY{b)s0b#TuMsOdelgU+9M)ql~gEA%pctmdnU=z{3}^9ky=TrKM-A) z#Q!3!Mbxb%aUY%|=T;+oT;2Okny5;jrN}np(&+A%ZjVfuDQXG*Su>%F#6cHv-G5ll zg}mixk_dfYpJ*gf%WOQTU(#O;*AN^)nUGjM|6A^L-R6T&0)t27Xdg7w|GfuV+)sv8 zulVZ43dAQ#Z#;{!e-Erx@lYKtRC_V6(Tla(^pa;k^kr@=XtS;3_Z(jMG zscb?0PB!$!56PCrz>H~m=O=~8B*BSd5Ue)XVy)O`33;}o&?#rnM>WSiIb<73-W zG4AkJ5zlj7nfq-YC@`^88#%KPxgq{72rN$JlKLgX_HBc1eEI|SpXaweS!tnl0Sr!CVm{;R! zs=y!e20HSO=rgEjeO2RY@b$f#meJDJyzVf1!n#OiLV6~e*`k4k0QE^CrC<-r7bbG$I5@X>IjdFwR4bp5<4D8JwTQ!6_;9`h|?J2z_?#H+AcLu zg9hXZ>bSWWbt+dY>#YTaKZtQ}Xu_?mCvM@)LsW4Yo#}6+ z%Zt5l_RXmv4$>@ZS`(VXBf%}1J_#-{I%}uIKM~7Qb+BaJPwHFnmg*NpquZdL-okEt zOqUTm8lKkn6m}W*;{F9+`j?_>u9#O@qyEMYjyjrr7%h;R=RnsSrYSudw7zb!=Ul=; zLOO>blbR<@mamfcXA;cm_G+_RH!nMm(njpc!?WrxE@#+azK9E zzBNrclpuOvRM`_4XmRu-=!0JexFjY?_Xi(5BII4Y7(%Vx$(z3+bRg_K%HNB=T=L)L zj0)oNS(M%*Kl5GB1I$_@_~y0F?qnS3DumGMH|gLfTpY61uIre9p*?`5EB>ZCp+|Iy zR{WV~h#ac=F=*Iwan>^+BNkLfAts(J{5tIKR&C%YdeIBo5`DP7&7+*e)OI8Dd~kKP zc+(n3Eoz>Ka87KEFY)-&xUvm5Y>E!Lgow@7oV_aFa(H9&>W(=f%mtMDx+J&8pPlNi zB)wZ5lA`c>mWV}qkVvi2WQDeuPN0|c+af##wsxZ=;W>4i^DG=l1mYA2d2QP%Wc+$x z+oH5PdI@L*@NftPm{SA)L+};5nIRCJMKVMcE>Z0kP0!wrIeuPR2xoC3QufeY3W9eD z@AG`rJ;x!qls!2Ak&(kW^!aGCThLI&Q`Vk_1b@WbHEo{hTlH2t~57bzL&!->WR z>YzpV1M_(Iz;Fo+2}dk?2u<6y7Y(M5jN*e5p( zU)s3~2G%|Z(RQD7m_4h+`2weEb6@=3e1NDbKv8>(o`$q9OYumem-B33={RbgDXBZM zse=&-4$onmeJZSc*cKapAfc&zLQOLw{(0fg;@U7j=Hq_#3>IH{nXokIRDn_=5_iyHrYnX~+Y1C)Ge%iuRk> zTc9q0{v`n{(jT%o8j%8L4KnCez1Sj6ws-H|30VUIwR>tzbX2*b;_~hA*}VdNu7lPu zX01fT3&*x%k~De2E_7@{m63MY(h1aZ3~C*4+f-;XAV6k!qPG+h6!Zn4Bs7J0&}so_ zlxj4AMj+qSt*<8!2cdSL4ACyGV<778G>7TL;{5dV=IK=G9?_~I0b}HmYXWuMC^SvP zJ@)6(>Ix7%xFqF)yizfNF9;-0#J6rWLks8ovuqNNgAGQ58qX|_e@NN03hC|W$cF&! zZ(?_aIp==^Wj&;R%h6HBX1`B!)X!_>Z4r$+EKl;khV+}##G85aBz)rVBiTMFmx;rb*jye^K-LIK; zU}07-i}`Fb8sVzRv+(AgT>;SMW1u8bSHB6eSF={`#~F8h(Y@HrRPQ-xvu1+O?ZWK{ zaM0cb?aP!OyUktzM&*0?8v&B+%v_!GuP_YcLA|so=^oT$ zSHwbuY|K6QR-nnop%}ky`fGiZYve$cp5|_8f)FQ}Hd60+h|<#eN0(sFvbuJd18gS9 zrW{u><5&qWDE%LR+7Jd3BtREXlZT3pj&1_+sYQQUJM|JMy8nOhaAiyF2ZwA@nf|j7 zEh@Y~^OF|Ztf!SZxC5~779P1<3t~)S8llSJx@KD~L}J=sC7f`@&79e8JA80(kNGb& zoCeZHP%japktc|1>FDV}%Rdk8t1veZL(71=13K3P)EywuYk@Z1NU0SiXU!oU=-|QPmBww5N=F6-V&zy?eEg1CLVm^dza(-!4#&yOmKB^HWwbtbl{Uqxj%X)2w z)WGur?7!3M5F;PoA3JEA$GiaX=RXKs?z6Y@?3eSpJQSN~$p^@=e;U-LfJG#3-;kR3 z8PizDt5ZBtoG{0OS;Yz#`wZ@l-zd8`^ySgzRx#L1 zvyN!iuoKWaaKoAzBqUPW+GNp#C!l-MrPY^Gb**|v+h8nKKKDA`BsUj>x&73mrh8Yx zX-oOt`-trL;v7U3P;x3+OMeybTT`ba zk3{1kQPbCw3JckgG`YN5Dj{h)HjT~8)pU-fd=?tHUX=Q@HUssgfew|2#+GLVnt#cT zFCn6OIRu15(*&`lz3Z1mcQCn31}>kvnT50mN%7F2*AP2aN*?4ww{|7i^n_M20bl{K zq@+I8HgC?p$H$l4u6FXgAZ9Sjyz!3|Wzg$LslC*zt1{KeYteoJYu;^9Eub?{rC6y;_ZSjbe~$8?0fu2hK~y>AQ}m@wGMnd$!cU2Ow*xW@PJeSQ;@oJz zk6!KMkApSQcdeQgE3dZ(cHh9W?Y1=f`KO+Ct%^oTel0@oE|rtGbWbSKk-tN4h0b#u zT9LzHOvC;uT1930W!0%F&%;x}o7H%k?89!zN&z$G8|~N8ch+0oTC+vOU>n>qKA=Uf zfu+-d6Q$?*LTrtTA4N)HnP?5mb?hA=zqdSDdEld;;d60r(wj0#uEI$duQ_X9;%2ET z@EqG4-28Cxf1C zZhhTLWe43)bljZMgYDRm%k1aOUs+pHtl7T2IeKGj>sQ${|D5#Ow`8am&zLUPq)E3q zSEsqCuJw|uA|Ah_YV+K9@4i5wvw;~KfY`UGpv{@vx z3XQoKl%5zDzLv!W(O8E4Eu84B)M|c1OybD^0eM1p-;c9IBhJTav|?S5zr?(7Va!1DRlqDA;sjClFf4GRq)KFR)y z$}q=hZE6A@C3%jC&R+6|_(TE^w|A3UeHZO9+UmG_Bh!y^=L}CRw{-gN)SPD3jz&oJ zQ)iOa!Ia@Zv4t9XA`O<`9>Y!v5td#^C=T+H@X4}NlM-l=MHXM<)TOnh8T~os z$=b7!z{Jj|N-mYLYlU_0Z`(Vid4V6@XrOnYVG=wFwoeo->{+6E!R$1f%n^k)6Aq!X z>$V_&Ko4UUY22g3yq_uKj^G+xLX?IqDZwe|y;-CtGta(U=NqLqQhi1mMI4kysLbh$ zmax)#ZedJ&9Z*A9HU;f3t2G@R;n!_q@hd?)^Ts5ar;{GwKX{*!`KfLwPp+#ezc)@u z7@G72MI!^3lk^ds`c-Y9=|by*K$7(hg!t+|)Z4e8NzFfS)vkU?s!QrC7hvwkv3=*F zVQ#f^SlpYwRS8$LaLQz4rnM`K!B_;I9;DMxLBcCwIZ_89U&#B^H8>BJ@dH`Zh@pAI zKH1@QY(kPW&)bixgNI*rQ44<3$5y73Wqyjv48|PrexTV4z~8zO42ki!D7fa%LbJ5UNJN%pP)WqGDh) z`xcSh7qw;rgrfY!TRXkYgb~nc_dR0( z323npkc=7SL4iVz4&5in)R(h{1b+C_;as9&Cf6~%wc-aXSZjhvyxU!(2;GN$4_%91 z1eGTZ+HcY6e)$lid#tko=P zKvudxtKGw~ZSs2MWwBT<>;V7sRB#8~j%A1=P0whuwr)N~7F|bTNh)vJz(m1)sKX5$ z&w>*4-&ZVN?&k3784NEW)tU%UyEX&JMP65TLcI3^ZC6-1T5U%w_4SwDZZt+63i18L)0Sarqm=*V=9*Bl*rx`h`Qt~YXh*T|zu zNjWI}1rtvqNQ=i(ZHerXDw@Fs?-~`4&WNRpH?5o*+70i%dv4OQBiV1f$m^-mciVLZ z*E1>Z-9j^IcNkNo83dur_{TOH>ON>aVv2YrdM)pi!}rYESB4Kcgx-D$AehmrN`nyX z=k{ZMK+)TsXPv}(CW-=Qw8kswL0{k2@hWfya>U?Cz=mgnFc$=at>oDxL`NFkG|N&w zrWdWFw<&AA1V1uu_6mqbn%w7n_DV(lA)mPSktELWdtcgL+l$KsT%JO%f0N|eb(3ly z%RGLJ9-l)C@&bwIg*^6u7NtIvV!*b^7UcBjgA|qZ-moY>NtWlw2ERMkX@L=*WJ7d{Ss42jkV~`C=GzkQ?y4FxxUD6JXnG^~YE6)|FBn&T>PUV{)>Q^){zw zK)uRS=tAoiJ{yjIdFE_vOMVWsha|U$RD3^Oq}E$fH2j?4mvX||Ko3ZVL3fPSw_A=C z2fV=}Ikx%-h zTk?pRR}LH~$VL8e)p6nA%PSVu`dMrrh<>v>HphU!DL}%Z+XgbIBN)zNftCPNU};w4 zr9io30K4o78c!+k#w1h{u=6m^{0Wpy!Wkgte**eYh{YdQcwiLcv&&|5YzX=|a7oz8 zkvmPTt;82)g!nM1h!bg0R77BNu#S7uTl~#@gSNoB#4xD)!PJBI!q0R0kb=+BwKe%W z7Vn0{4tBEkE^Sz!P4pkHU)|_=hCH=gx89xN3!QXZvpjbu`!r3Nn$a6O_0q$+hB-u{ zeQt?#=d@~Rl*m2kZeHCmuFpcd#!zA8Jv@&xQLp3UzgC$&pje8b7Ihtdak)2o^!@Nh z>f-z!bA!lF5Bwtkjt_4X+YQwcF(+f6y1-CA4A+3rwh^j~EX{&Bs~xfZkr$UPUlv^# z=KMEPdjl$DIc{;46fqdBy*+3ORf$@%Bs6WpdU@^VW&QEU?Zr97Z4B>t@F|N%JsEyn-NkbpbEwP)xotdkJ$t!v(kj!f zCDK)ln#mpU2uVTb&LY7Qanb3^? zcb>;Q5UxgegK`r%_-h6R)1p1-5fu=xC!hVX$c2sr>pq3_f2#tiJp_|yd)M(<_v%x3 zcPSoxVym?kqqHP^)BR~DpMP8_ckHW{ixu^1ZcgK?0+j3_ebti<>=gDrHjF6@<<40G zO94t?HNJuR*wxJ<@0GUQg3t*`!B*!)X1pF-SV0O-jS8RKz>Vz`g(Yy| zsIl=gztj-zqxs>^Vlv5;V9ATnY8k>cYSD+E&($_Si+i$fG+Gf=o~$!!=P3?TKqhKE zt^x~wQR%8Z68o}5ZxuAmnm@^hYCVn58T!G%q&-@5CO75LyHTuJ7B*AC3%DRw-@Sb_ z`&0vBThpr&dqBQ72YOQ_RlwPPbOJMSnt6or{~EQ79q=9{pu}kmaOHmagdL^s{;9h* z^!9M<=FWLdMLtT*8Q0Qk+V}kj+@h@x9OvZe=7d20pFx_BHchMDYPxnDb0^{{++G_N zXeLFrQw!~wv$!k<+gU$Zl)KhNFrT*RL~^!^VU<`S3tJHmTk+v(W0j_;$t6w#_h^Hv zF*~Ni8@;9eBFxo?p4)OAHG3pOMvb49DF2QS{dk7uawKk9*0_z#_Yhng^(!zJ3{bIr z@uGoS;QiQWG@m&+~ z+_?Ew36G(#!`#ZW48_g+y#MPMDn|bJI?Sq~$51nWDMHgq3;r|�^J9P{5Ky^UU$V z+@DF2PK&=!z{z?d8GkPf6oy_qiMWR4!c(;SM1DO{ri8Wg`+o9!qZ}QFs)Lti%{IvK z^=W&MbkvNV<4;>&`14eB{H}I)8Pj+fo*J8Kktf$Q2vQqIwjDY@LeKiNCidcLTMYXp z0nr!}TUH;*Ve|7|2uIYg_VXJ!Gi>{${|2yqNk|8h+I9 z*H@a)-g=&kyp0)~u0NP6dQqZHF2v{ODw~wK3p9$>qKZd-Igj zUG{yg#civ;mo@Cy!kZUoFJkn+jHX~|%7pq7(cfmcMB{9c0RuFjQpXCWV& zFd8Ke_W%N6>wWqFVG_d^uURZ{-{% z)J0sx>7drHJv_ug6Ax)a%GWW29;|~AekBtV1{l^Z0rs zA#brYJ{HdPXF{B6&Wc788FoqK&X@=T6$7+9FE7CTDVq#;rdfB}xl>XzYZuuP4!uH= zn2{uw%aUPRQi!!3i}HBU>okF$Rl1?=?UwL(A43Ue`lISs*kTU-B0QJ7eLj3{iAZ!k zJ zjye76eV_M<`@XKGh^fr`BiSmC$&kORUXQi@=w4TQZSmMgt^eG zpowkT`&P4f9h&!Agp>_-Ps`VjIwz@W-FX8EIZO^$mwLX7zFF)R>+}49bt8&3ivPKv zk#*mr=W;`>`F7j_uOAQksP^GsNQvcuK^K%G9`M@!Y|;AEU3Z~<5;+2nX;<{)x-#wg zWm^fsj^7bUU35;_FI#a6weMHp8&9mEP0&a(|izyrI>HY9z>XNz%OfRDI zSLS!;p1r!re1^EtY0ODn=_K!fB_bEk*e)hR{uB433m+x36Ej}2|B#o!;ViCrjP0-@ zbIWUMu{nr})9!loA}Xub6Z5Ot5zlC!h3U_=dz#jIm^`~ZdJD;MH@(7H4xA1K${HeE zZJyIbeEO6=QTk%4WjQopEVw>Kyf4Nr8Gf_kU6nJrig^oJSmK3;bI%F1g&Mr~S8LH6k_V_C71bGO@n)r^CK3p(ldZG^Od&2Ui{o7 zN=0F=q4c@@5C_3kCiCua+ok>mC21Q!X5|GMvAWbhW@I1ERi4IjpW~L zVG-i{)lD(kV`zC^7}XamSvKr^dUTiJ;ey3Zrhb?YFWZ+(o*GZss(aTAjw*kf3zrAK zi6OM*{>5nezE7`sRDj&Y$1w3=^umclwc_iE*Ke`kUZSRaAR}?k`^`mFMi(OFn@*d1 zcTz+W=K9_;_-*+JgD2O6#fuCVPfusri6vl)u-aX3C|R>cYv=Ld@G6wes$TjSnLlpI zQR%%FIi9>2TltGeM-?;jWy54Q%6C(=<=z3^11`~lDf6%ELQ!F%}wFODUyVg{4SQ&mi zzoI6#uH)O64$!_mfGkG+!_yAlPOxhnHXL;*A*UUG7_GT zD|FD2NE*{{iO5DB-Y7>UW3IW;gTreu>)z5A4IS68XgcHXTZeRYmb-jTSX;zIWOsZ~ zLQ2!!7ubX<&OH@V;SPToe0XO4UYG`P^ohAGH4)KPHbzx-HR+wcm>+|!r$hvM0zJMv z;*1Gaw|8~Mx>b2l?|UPK%!O(@SGF1U(v|%)-~K4JX1RzK(e-^TCHV-0Y2;}@imvai znxr(U_6dRelfFkY%S+uq{7OZ(f8Q&K9}EDkZbFjI+$RxH5i{K)K8y(B+l?7=P-Z0J zin)-I{xXJva;%c(+E(eJb!hX;yzg*~aUa{emcbmE*&a@(U18G*AMNn9P@f(nnw(4E zsF~t=7SUg?U0ss`M#0Kam^Tli`&c&3hK{`X5NY8j&#|=B3GyD?s~M^^j3G|>3b0nb$_L54!11H8G6kot46TsX)hiG1t>p1 zvqu>7_1W5j-xz)>XR`H$9>yKxyBlby+03nXH=f8HIXN#33K?pA36?-fBzJEKU_?CR z@Oq04bwa<`dr*7qyBv_BSQ${WaX=n&`^4KlbbAm!X!Ygu&0847fo&wkj&+@8l9D|D zZX;ZPtCpQbE5-Sul{zTaHlSI-9SUj>9W_K~P4OIbzdSX?3pAsuFGa?5) zUTMh|(wm+$v{9_huvcL75=Tqa<%Dki4n4nOUgDYA8Xx{l(Fh&AL3&Vfu6YO#K77U& z?5iQhIv7*c=^rnV8QU@t5e-8RezEE?_9>c2iiqt=uAn%_=eC^oI=e(J5$hd^0C%;> z{4)0p9-r0>9rJAhaxC{gD{F&Yb!dbV*$9$J$kIH{N!P+&78?pvsE^Sz`51bGRNJp3 zRz~OGfUL_+IRr(3PKQ@BHNDx|s*u*laMw7^Kz_G2czD04-IVH|^))MTpJ69JA6!B` za*v^P7Zk8w!uV{;m$e)D!(60xVCCz~S)H66Y7AAZQ2j(P3*;FY2DA0>z6+805SZO+ zJYpM9`RH2*YIhvVw{!QM4>zS-=)a=NuJ`r2N8gJfj7!quE+h}F^YRGC^|fnQSfYn| zw`5DkBaGJ4oJSzWP$g~5Q#IW>+0wPymmv`%v-J0EeN%a~sA6)Ls)~KJ?I3o`Br96} zMnCgA)1pT>dcP*9kP&agPA0)6eN&2aGSbO)R9{T^T6{lm-Yx%K$?Isr*Y8ne#y{gz zTNqnn;q&8O;ZL5`GwEO=eznHQALQqE5!4KoDlA^c^~Z52-Q%RkrqoL8E`kQc29zbv zms-VG+gik#e+B8=#5~0-z?DSg>OV#2^iq;%6*_A;T`jqaq1tx~(?XSD<~mFdZrNI7etM~Dj!89ijBZv6BjyAzMc3(@0CI4)DKZUFn4Z^&vjMJ|M|K2aKBL}%Gk9e_$O;y z;)2}U)N4BIzNl|8_E|&9FI3pIdM&egeCF$-x^;su*fc_)?8OG|pP_OdUOEXcEuP?Y zJdGHqr6W;X{P`XRcx<@`T}FG%5LL4+IAC3=J=fAs`}OsRY+zmv=R&8QTL|XfUr4*Q z60f&D7wpPNB?}MT>XT9OH|qu98rz`N5glF;U|=wNh@-?E{Y1)o%jDUQNbW^^@?f#g zzt-3u1$Ivh7*_nulCp0r7%P6K?fs0B=1c=&w>Y<8u%FBiSm}bYwfOcAOr?qP?8fv4 zKXmsT4%{Vra%Isfaq(MgzRIh+n&h+^De${=OIdeBFeclr8Vg3DN5Bvc?ja__qbEcq zycS({E_l1aRlQkq>~r#)(^KvZ7vgh~L2Nn_$Ck_*#mB(xD_2w)f9C z&a|9|!k&EUUGMd+tu&c120UtBKRB6J-%>BPe9A^H7ciQeU-#?%*KiZ~h&R9ZjrT9S zX{Ki$aH_^3Y;ID-^>~k_n0GQek)y44?pY}b?=8vgC-59;qnja~g$5Ku_$z=giGV>G z+_uoDDgyBW!skO^T>y$2_jp_#I!- zQ&OS}mT@1r>Uh!BZ%+mM4j3_GO8Rgtued3FC$c=rJGYJ(W?7l|&UKu1f97O8ka8dZ z4&WheeN|Q5K&TqPIP-Wq1l%YflC`tnxY2>*-))yt8y~HN| z?JqxeJ4}7A_CbBrafPj_RR6e>5&nYra;NWWQ}e^NIbIkb?Sm^AW>;_C3;?h0>9Q*n zNN2%5egzb_KB0O0Eb zud6^kx*(DdXKMVgKuqLyAx-<{&TjtF(=`55_2biX>ja#_HksjJWs8ds#M?W55^5NX zwr4EIbo@&Awj#5~b}iWMe&!!asp;`bgMm@evLV8n0COZK;4YxQ?%aM*cle9-0_hFF zGf`H*`u!f{sbJ+k{^UY{OGwxAN0uxG{{L!nX;}|1!prYl@-*j0s-l=$r^cNNSP!_Z zjdpsvik*_@{b?1a=BJGP;OIhTC-lt=Yu)4Qrmcd$7)+~eSOa<3HXm#~c!6UzB`jOJx?ckQBGJEQT8&ahgp z&TBRCf%@I}Rr)DoT9DoSEab~knnI~|L-q;)JKn=3bEpL~J65O53Bq@Zy7@R(#EF}Z z?)2FBH(2*Q`}>tl>+m|S1f9CIBn~f#FU7C15O`cL^zf!Fv|iu5lYF!xnB(>|ST_Xy zUXjcOt2N#}rAt$$h!S1lk~v}{DVca{oV>xsJ{LXTheB}~wpnk?Nc|-Yk>^qbjLZmd zKrn#tW(;zDq)-hO`U30eyGZ#36x1xbbv2qCQeWQOd<^ZW_0gK(iK~6qDCLoEv0D^{`UCU^w``vb?3R5h9Xo`X`WnvmryZGyg zxmUO;`-_P1i z(E!{SVCdwOKYG(uTsY zxNN2)tKXhghhWai#FpHNY#6_a>NI5v1$X_Iqau(n5 z#Dktj^u;2tT`^EU;x43gcqnJ$^(4v`PVR9xXR(hmYdv#5w-U`*H?hk{KN6s1XKkgk z-&(&qaKd^cFpkdVeslV00+`o8g{^H}}$BStJX-L;v=Ab5TAR_$l(B9wnR_I#17m z&;GDFJ)72L^Gd$!_-h;<(GQLUpO{;@xA#&>scCwT>g)S<_MzJseL52+{p_UvOvUE@ z12QL~PF|3OtPXzM+}k4&s|sc98cB^ zgM!ZgFU<~@@w@VO@mNFid4dsOwKv9=Tl7#TLF;NteYpxC~_GP|fQy{#`$i5&V_l@vE@w3S@WOs@m<-FBp z5Fw5t^E8%@iKCT~oNENlYC3qEj4p3cy~#|Pu8`)K7@t#!#{N$3;gz)@axaPqN295) z(+9ED7V!ZoxumRTCEi#JV}LO_s`op27~Y@PUL?3a?6S7i*dv$NA(-e;j(drcuzF?D z@zp@!BTDM76@`eGL)Kas&%b8V{9xUCCBZ=rHtOG<+_OfqB_&rAE~LnS9bU0lXKmvo zPcHEWZwO{}5fLe_ONGR;u8^vw44nyjBO^dht5755nX(AphozVre(U4xo$J2DM3o-! zOi}rV5{^{YHTG*#2x#uooL%cySXcPIW)oM&s*|>zlIU8$X$boq6XwsZ0i>8I(d^iW zgZ|GCzqYx}xbNMI7f;pc?`y(|RuU^}Z@Sv|qU6bFf(lj<&-~)FGb)~Ez6(d<<9Aw5 zIAt4|BcB-8dUt4{Z)<{(DDgwNUs!wKyKCejj=EX1Lztv%sHhEbG<_j*N{`=|?>R3~ zDkrAFuJ%w0H3RoM;-0_X7(JOpSWkn&)q?4W?Ihc`B%jr{^o^Ws+Z)bLCcG3sq{6|) z-8$J{taLtpKO)QX>6EO&Q*MB?Pnp)!jbbk@4(@mzoPmtEG5MC)cPWGg2aE}4^M^C1 z_%2eo5ifa|k>lK-pH3qDWw(naDmF9`5d_Pk?GkaTEhFlj?f#}d2~37#pj!@;@5+~? z(xET*X+G}d4knMRHkz+0Z~R$7MoO(46odPCVLdh2q`gPL)h(j_I-?TX(dmULGLYVN z#=>Cd7VI0lT5_2;CMoT`M&gb=o#2|B7g^oz_lN#Vd``PbUgl5(SczRieTzr)aVdlR zgIfe%%dg)V?tNXfy?D2na)_L|ErP;}i;a`NTlV=Ui@s~MMMZiKbi>Whn@B65*rMn1 zeWnGlUFQM_G6H4Vz=$zpnWsi)HjI**%`aM`rmWvC$tsTWpv~IGoSyfq$Xt?&gF9R&$F4F!d35);V?^?>*m-*WRx=iG4m4 z@iwTbSRuSujFvqSEdBXils>`4?QPi4HWa7ru7``H-F(w#eRJchW=n%BL}5pW#GL?B z({3Pb5sx4=!1!V3>qqrO@-@uzo%TMy1U0hr6DO{MD`uahE2dp0A12D2XnnXu7d@w& zm3$(YKqAgKtiO~)^}?jDJhO>V1;5Z#G5#|D@39I@VTbD;y0tLV;H23n!xzdgB zNtMl>ya(;KDm4zw6!X;cV=wQWXjh-LTVV7!9kYX4Lje!>fwlGL_4tK(V(tk|5!biAI(W*m8kbjhUNm} zzRfsp=3Ctv|Jd_2HCZHXIvicQ=drkM>E0H$&G`fTKjGRKRGdDvzcqKO``tHt4XEQo zEqMCQ^xVZR)BEzUBt%0)umMO~kR6aXI|Q7d>fXs*bq?4Hwt(pt;h%wqBm+=$w;r&D zJ9!&(GCBk}I&ibxEw3;?8_v^9`OG%-5xJA2XkmAVex?EKJdn7$ zf!*Z<-F{4DUk*BB1F-su0OiJv>TwG@)Fm9#@AA-P_XlzD8&V2ySiF+{IKPOZ^XP!KKV);Gvz#!Z+F{{I=W~%O zpZ+o-2TiPGvCwTU_AI}SH(k6q)*vLpqq!Xfys<$LbV8rhJInMJhZV4|;M@sz+qGCV zP!|ELvd;&fW>o`Yc6Qc3G}K`Xk&!f*6zkh;B}HU2uWddZD=Y!65y#78(#7rP%j z1F>2f0H6my(?V5}Jb)eha^*XhR2&w9iwzasr3BgJot$obI+56`_k7Z;#6TE=>v5IA za>2HVsSLI69UL=U^m$Qax4xEz>6FiLrh=J|AK`rbQI?Kg_iGuNQlFZ7Uj2`J0Y}$bet^byEo?@VlJrOSX43~!XTV?^PAM!$JbSy#P#UqP5J#N#3U?wmiF>x1rVT(S7Bt1-fMt! z_jLpnwk!g=$%ppN0Fi|xlDQUt5)fa_l(j>)2n_KlIN~8XolKOt$H}L)YjF0JEmd-M za>^LtcwM6X7oE|8X0fKx$?2mGy-x11FEpHTLvEQawb5%(7kU{EvF5R3ytp`KbR%J- z)FN{zROy)H16@qg^E(+GPdI2ocKMmZld`Rr_86~#k;xI*<`GP3`6>wyd@9ef!#ldNSQz|mat!@XaFd1 z7(lX*v|hmoa&&ZjC+x8Lh&~_K1Yj>l)D=*4Ib#iHOEBtu&{Q4XA?8YeUZ8@UnABjn zB4CZA^XZJgg&F7lDD;d9qY+rMPm1!^H`e!LZ4kQqDL-xV{*5}y0NsamWYuR5h+Q|< zx6cp~%E)+v8q%eX@uE2gRm*Uc9M3oY!Yo{_ze<70Ab@FeosqoK|D-OZif_ZI!k zdQ>xQm8)NxdT6)|gF1S;%VN;0OLB7hJN7AtRowlaubJQ*ZcS;itnHkd%fdhR`3^}E=K|JQ3X3?pUuUmXciccOUha$(&!BmVKsoBlUGE zq}UM2s&juvz|wwx9kqWb+y9@%LqVz48mPDk_RR{UNtLs<;P9!nI8oPi`{vz=q-XU^ zo4xYH1=S8axZPt6egKpA@0^?3^i{No(SiJ(J8V@aCYQ}KrW&-f_RA>!!p9qif-1+mV@QmP5a!!46 z!Ti?+E?h3_vx&?4x`*8hw_ct6^mLn7f5$Z41N@$uVDI6`>sC&@=9NpmU(;ntFhKEQ zJN#dlOp|~fJ8lyP#zY>Yj(4L7tN5ue0;l8l`%h-Ge-uB(V4D3$@e=@qnSX;JU>-Wj zT6|Jz%LJEl7Pe79(q;VSq%w*{Nk`WUr0>LkiavL>VGq_+jt-xz>cst z0HgjTF0KpHJjSXPhTH#?Z$K>b&wPWwuM2P`G{wtbYGc^VcS!+)bJfYcnG@OFK)tUz zpMC`(kQnFi@sInukq9&+MyeAb&+(?B6<|IhgzA450AJ6^wX*^07@+X* z4?dta%|?ot0O{;tZw>%cqL^;j0l^-@!8H$hz35}@n7;~lvjG~&m|1$5DTvL6{M+9D z3n-ZgfY=rr#x@yL*d4n`K!fHVk!m)-ssIfNh>%5Cdysq%`+o!-Ax{j@ zA^~^;SV9C*Nlp%xdY3wyhb|cOp1!`g2w`+^5w=NRI4CI~1m|C4)Tm7z#$FILI%7ZKb_yzjNTQDV!D0B1u1tIrB0|u*HLoxXbA6V=$Y}Val6Aqv*em;flS?uF9gC zi3fUpyD{*^5EfrEzQAuemI6s#u%?N9YZpgD4iMxBAYC-bC6k2t3K59g*x1~97+-ii zDu5-j(L%yfwn4>XQo*UeP+;54`7}O21>QyDl^1c0b9HcE`@@8R3)?x zJ3c6-dW~>#i~jd1Tl#mKdZtmc=9E4Ib#5-R5Yup*NzvpLq=R8`Lap79^8V)T^8CCp ze4}=*K0xl{H$d0njV2dQjYmkaKIQ!+A^RZy3CHFdrMP#y7@61p7SF@*7XBCUyq-Z( z&mt7;-+Fs1S6J)oI8H>^ z;Oaj?1EVFtU#DP(k3tO-46ad2QN#O5mDWQTwV@1-x z;T0vs%C`t6dz?76??GMy!gPnF=`EmTRDqF95@D|zTm`Hc?PB<^KgNyV& zSmVG`#0ISFrst(!z*bY7X6y*(MV1q3cc4Eb0Dp+y=tPN&gXr66e|?&iRV@gfd!(fd zHxWVxE1gn#QmTXP;I9GD_#DhK2*DUCA)5fFS1Ng?3|K59cz(0MP>6WEAt%WneBSLx zhXC0RfXv2!cZ|4BD7yWwbBQO!gJu!ljvGRnAmZdMMD-y<2j+?QkYIuk!RNNAVn?#B zcK;STTH(0{p&UqjopPrYq&klyChekStmP=SIvjCVx zSQWpA;6gQXhI8QX!0);Swhtee_myF2&B6s<@agqjz1>?_Sa=@}M8R;Hqk{DfxpYCm zpr;1(uSt8awF-@418hi&43lAor_QfGsS0C%a=UqQa?)`j&NK)PN^ulIScl~{Aiv@S zHnIg`1BOs1F5sI#uQ}cwy$^u{m5n?C5CiMOdNB*OF@CXfYrw_$ze;*7=liqJT!iW! zY*j@2t02g6MnfGQm85V*Nyd)|O5+LZU$grxSoqvic1kSAEo`^rOD`ikH0UAAc1zIm7&$;b3VN9vo=^u@6nLF6;L(gR(1O4(P*(I3vN43WL9LT< zP}q6<1{44Rp=>wP;_sr>hH&F+TMa5_d8@})Yf=~(ZoR+Pz!07dd7|qxfgA{XA3VQz zfIs~m_}GAvyDc0Kay?|1!CksH;Svf<0J72|;YAxWtq>a!0Yn{1`M>VLN5F8yT`q({ z4HyxOeb`fEE2W;%b=~j=42onAk_a5922&-ncw~}6tP#B3m4mb?6+_B4i*B@?7W_Y} zgzF69%0J=4Rg?mof&^j<-kv9+dnO8^l51D4c)~VWh$RlxMTL}y9C>~f*>Kjip6?>N za`1itp5@v#`=^kZ2lFb{C0bf}sPH7gd5ZB5vjqt!zI=xK|9nIrctl*kP}YLuDi0~m O7_w3iB|qKO^ZFmzkv<^+ literal 0 HcmV?d00001 diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/yaw.png b/docs/modules/path_tracking/lqr_speed_and_steering_control/yaw.png new file mode 100644 index 0000000000000000000000000000000000000000..7f3d9c1d10b7994d883e720d51950fc6bed47916 GIT binary patch literal 23991 zcmeFZWmJ@5*FQRxgh)suAwx^4h;%3*C=!Bn8z9}?28^H}BGO@^(j8I?NP|dscXu;q z-#pLzuKzh}o$u$vaV=0`=Dx4{ioN$Q_Po?kQ#wb&NP}z{d-Vb?@{i9? zcu}Dk45sfDZYunRY32F<|NH-)*|__rn_w@myj*H$Wmx6WBM!2VngwTM)hH6xxRoMU zzTA94f{)*qFLW1Y?fla4&zO=DvGisNO3KKv9GhOjOF9`(+!)?#pvv(hBO?R%38`sl zrh6V*T3QOb%-o%roFpbAb6?D@^XpQpysd)UDoJQGZ??J^**>rTAG>LeQI3+5 zl6A~gqOq}&O;ogZL9?N)jf;l|L&dG;sVI%5rKeZc(0G%Xy)Ma0fV@^HCOW#V((kaL zp&_S?y83xXY%IO|^1yT<8=sU^Vqc%$&6_tf1nc-tZ{(Q^b5mqDc+1S}BF&}y7dbd; zH~vP)#3*@tOTe{Eir?gQ&U5hbg*_uA&$Ao6ZrzhH?^_<#FvJOMwtvS$AI)T6#~h9bLX@*!hu=3>tHdHHNY?d9D3q#r-ED)r}y zO-%3<1;|cK1(J`JnAFDj?(|!dGKsyZ@Yy}j$QY0H?aeZN`Rdi9z8rH74vrkp^#|e1 zl7DD)jecP$+2{U#z(cK;Z<0;cM_3M*xuNbRNkkhuR75*X{^`gzl|@Oo&dKFlw0h2e zi3vS9yX6F9oT%7Y4e{DEYdo)4POp<4{IFhd@A3^fsWIOpr*FFCjH1_BdyNUT)60HZ zQ?@%x{Q5!gp{C};8ykuduh}H2^;)XC3D;jsu9i~;;t`UqO-9IGg>Ce&vvYo^R9L9$ z=<0_LACPBoo&WbjHR1Zb@0y$gMRv_p>QcXcJtO2bEaJa?`}R9tt>99Z*?%y^y!?Fq zf+v*iQk$>1s~%K+fyo@1-W@exxW6|}s8_bN)r*IldWYtl&bg+Tkbhr3Ji1MEPNXW9 ziA>B1S5vb^$@ywq)d_kvyNal#>FIQHYluo~yyNk<XVcVjQJ$)ZkH1F)YozuYOX>4j5uuH+emIO)UbFi5T-s;HvHx+*6{iUW@9l*bHRBhhrIXBS zg4bd4^BhKHoSmJ;{Ex&WJy!6m#~uHERlP9NmZTCw#=HkF@Z9Q9VvzQ}c0tshgO~Ru zmukFc>qKAWEgTJnjHpD??20p!f0CH~k&s=Nb`~8a6&)eU&0P`Kl?$8~$0D;2Lteer&}|7wW5Z2e9g8*qXrU|2SLgkCw%V(&eXA+byFO>oubYk4^@?$B+}DzP|o`%4n9cq|DwJ-b{On`m;0V zFrlGM+WSS-?K^ju-kaR?u_%q1tRg?DOc74b5JE*SMz1g3qsHJqD+I87l zX2h!=|JO^Z@p{(r!_`)$=J#BmuiNNc6M2~!QFCw3T+d-`>>2sSp9>B-mhCLac`!0! zLY<`({H&X8GUUCOiTa$DmhX4CgPSr~WM_DWl)k#xG(h#I`!b4(#IiNM?)Qtc4A-7$ z-1F!4SET!iQSNAL3l<%@T$Aol@%Xpt=FD2B`piI85MG$z(XpW({g6`#anOb9)z8S| zKg_&1tNMEQXH7VBPZ!rjO_|4P+sg3I{k0nM`Qe`)Cz~QRJ&&5+@n)D*#KS-TR`_^q zY;2JD+E;jQ^XTVsL~*HJqClmoCEc;G;1cMT59pvqDSm#EVQBfZt2*dSJjuBWHy?Z? z))O7ln2UR%_|e^NZ%sbGs|AldcA#?aw-okZ@lAq_+Y7YJCxw^ihx`whA#40CwCO#X zt$)QJ-}si(s^cSpahdA}tu(c3wtYF(vl2{X2F3QTYsOQx({%!gUqH~mW* zV0R6lADuky8gEi%nH-eCFZ|G>i)U{50xn)=*2>VO`+@2*LG`SnzeIS6lf6m4-VMSY z%DSk2z$Er2OZ&`qd{PS9My22X{yS0Jg`_+?0DF?=x6<`p>#P(R5z$yfBsiu(!)!9|?Hni;Qt)vsd=gbGLrSnm(TL)l| zMMwR1nO$bvq#u@0Eh4px<}h`~axf*Mt5pe$2Rlnwf*hKtv2luqrFje_ z{s&gV1=7A^N85D1TO9=1>O2#xC(`M<g^850tp3BC(p`e%S zAtfd}6TgV#P&z&J_BtAEq6SBAXm)q>gFNBhp~I5_YFhrlJJA_gO)dvJBF%rEht#yo zCQx`Dm2_*r#3aT*R4J)1vg0~pma(<(-)R=o`0=h=+iPUIH^GfGj4mWjxK;W^etu@w zoufBez40a#epPL%a0@}>JE5g^gF$#RBNbIgxSV(NjI}$g25Bu?#QLfB)@tJE(e_kK zOr&zbi|#Kqd9qex77w`ztj=RFM)8SE`CZMy=OF4>C>K1sot}QlJJYacs?mbp^EbZm zmb7gwjE$9ul$1k4A|BEJih_kDyk_D>=jO&nLsQd4?Mo_rd{14|w~%<**`L8HD43a5 zQ-uV?wV%Ttp87|6!D40ZUb)!a6#JX0#>1{uuP#`6qe93AP>@U zkw{{a^-p|I7pl*4tDQ?iLIQipm8ONFjtmpEp)KDC?Z@st%s0y$mfoT`S|=>u=Nbx- z%`o~d8Qj3>BF0qv=Z|KVk$7Ik7-Q$slI=`uf>OeDyK-lYh?tn3binKf$TxJe)i@=) zCN7zS^5nmUJq(Q_cj=`W-wOzPkd_|1=To=w7FVAy)e8y=GNH7^#lu6Y7=Hd1KD^Y# z6pwR5bpOh|Hs}6*ISa)H#NR~s6uGp{#y4#8nAfkr=;c0eo%D!(I8|GK(9J#CbXJD-TGT-d$NlSMGi6rg@2>9*e?R z>&t!Em2H~h0ek&bb_9!beDR2P*!pCB{-eh8p>#rO5GTZ(n$Vfj-dkpn$T+yTHfqRa zFFTA#v3SpY_;_$$!FP~cHkOz?C}?dyO(P?=o5m}pS@7BVWa~*oUEhaX+NB|21f>L=#650)-%;Z9 z5H;d|XeZ&Z(t>tc?`Ddmr(kaCqGDQ4z&&P=J}6n>$(~{0pZA7Z+DA@6qkZ zUj7L!6JJXA)$3Fj3R)WXD~_+f6LNUp$ROFXV6C8lVqJzyPE9>RHN^;-j_q$uH_ukR zhs&2bPm`3hP*W>FI^P&|;fjlkdt_lTBdeyOg4bfpEc{w zu_H=6yDD5*tdD!e+uTZ0QE{AJ{B0^BOZEOgm8l_@h>Dmdaq_|AyZbz*4&0`hgGon% zDDQtznbFJm?pd|BCyGa{tvN;{3SYU>!Cp_Zo2Mcv!X){=q~$J|i5pE-P$@w?d2UA1 z$4^$q>9k+2+o4N!g>=Z6o~Sa*)C$UKRkrC4-uBR5uR+ZjY&l_1j$u2`$W{el{j(|$ z7LIn0e6F-6CNhOHi95F`vJ;ZC+=asUWU`>(+Qh^JCL)6S(xs-?rZ4svIj&rZgu2l> zw1O^QTQbw=wxi~GR0pfSvL$QTPCMTK?{!+s&6!$GPRhfLX0hzjKk*XfiMj>Ri80y5 zQ8xJPZSY(W9iyQRw`fmJV%_`q?;orMam10!xcBBvDbvu+ zYPD{4E4Ap4MJa>Vk zJ$8Kj>c1a!bSHlXlLn<;j1{M%<gnm7T#>;ZxmfpRsUGeuBh_%GLE*$Ra+#c| zMap$=cBS}bW)Hd6_@17L<{$TiMk-n>pB7;B8n{CO2McXNI_ISp7s*1N(V2J#!Pj`k zDzEkrYA69V6ui(Uj~8|F=Y*?;+w}~?WIcEEV=v>(v;=u=rm9{@=Q~e%VWW{nj*|Cg zb`_bI7gWD%>e)Yyp5BR8+rh0oDJv|*VC(=YHS{w}lce}r>|i%pZEV)LvmTp$RSyv` z%*a$!u)Pf_qs{&whnPF5b@x-7?7}ie?7eha*A-H=v{Ee$Mwt?cxxy|Iz2&`7h<5tLYt-I51#pGVTy`U;7Yr6Dmw&<0thG3O ziBUy>#}LjJ6+?IyXR)#M`qqPzm$;1)#IEl#Hxf3br?4 zB1qz8n6F+o9t7tV|s6XWY{*~q<^bA z6yq5SxjNBxDK-v;%XlJiXM0gT`jW-YwosLx@oP*Uf)5h67PH^PS^aL%*3~zD?I*?r zIK?8MiQ2}7lG0EEMjmApMIqtQv*vKmg`k?%|F5kX<+>Ok)hmf@kOP7*WMtNb$BTx< z(krWqNav!_ET3V<{sf=Pc^FbETvym@VEpua=VKgBONTLeR6*!gj!e*VpYX@{{f?Kigi+gef>eo+I|~q%Fl^$L%=9?f36g zJHz~x*e7=I_`R?I`2L6I^730ZghXuMeie1~3Ck^UJw0q_f28m*8Y*JouG@l~ZAK|ygF_We0%ngFp6@3t`g=i1lj3K z$S?XAx-HHtf7f)Jj@Hp-Pt!zEQ%|J4piObs!LTs4F_ zbYh2Zl6P(g$zrb^W(Bg1d^eZRH_rWyJbgAY)W~$v?{{c;wEq0loRTua@v9?I#iyh! zMlSYA#HOXE`zOc9;*a!;mnq1YpAP>#-6hXQ&s1O1{xRk#rgk_tS|y8G9w?MtF7!V> z&^IbnrrbaF$gfzqWV85YlTU|qq3g;a;~82?QR2KZl)8SAEkkK(>3&3SrlC@OICJS{ zo8)H7;$X3mQ281pu(h={bmqOHd{6jb{#ED@9xH6Sl0$odPTPV zxDiU>Ot-fex~%}ZowxuuRa;w2?Pi7UX=;YO+*;|4@{_L#zHI&!DbMYWuA`DK0S|;d zUJU>)1qQy6f<4-7--np4boVYPAffU7*%VnzAu|A6P#x??bpHE?LbxhP$-zvKpW(AB zlc7HQk0g(`>3%UVh{?-0e!oxb`+X;DDr(u4MCtedAEzyvuW`L2`$LXzMds4)-oZxQ zMR#sP{Oa#oX>Z@Yy_s!Nv5~SkQXv`5r~4I>Rfh4;_h~8q@lf$xdEE3apT)8kLrKai zb5t;E*_Jq;J3d)ks}RAYJJcLAz-uwD8ISv&=F*#ME?>K+sd-JU)3gXIESw+8p~9yg z%^a-;B=TrCExeV2vZ2Y|w=n7I)vFnTznp>b#rD$7b$zE|V`ICUB6FOv8YgT?wmevD z+5BGMezwW+t5tC=ax*~2P=cYMXvh=+elRLFRv8xOfA~S)+$7vv;T(<)6dPq8+#VAO z>CL?7EBn;2wD+@F!e3u#jFVxuOjFZ|nY?oHSI2#9arxc*_qXD%K2}y$bvs;jFdg5O z4g@aEtS3W%cBvol$v^>bwK$&HlP5gD8Kp_HGBGXXvZB;k42SB|2IeDVQAFQ#BT%N_ z`&E5^B%Lh(NH?3j_4K;^^91|6GRBC_`Jy~ZQ#)?cjQ-&xcLw?xVk#~TDD~~j*Z;Uw zI>4?#LA6ACLmN%|kJM~*%37!wpM^3~Wvo{^(96pU2%sRqrRS+#H&lQ*mmA0 z+|{dujtaHUjwDcj>g!#;iVMQ~I5;`=H6k%}YRo6nk8g9V<8-IXD-%6>RK2sTkr|Hw z0`kt3H)!{XGXEBlM4n1^9-^$0-%E=Ua+IYCNL1LEO|dXce_!aB!wHhW z7*l&YW@o2sRC@mjD}sq?1ahXc3pn>7^Qb^3c|h0L=m_~s`Uf$7Wn(v9i8avjNu?jOcYN9ia~x+YdTBBcE27&!=B zf<`zw7OD^fRJ48;^_LB3DNLb}cvCmiYLU(&H#%c23l}cMKYc%&88#KNnLT`aKv-Iu z^Ej+u7qw-V#pe6JugQ5x_{dWJ2~TYuWDX+|U6hm~N>h_xKvBUL0m{sY5;z=kvO6*Y zSI<9q*jl+*rbZcg_VXw{+I@_KBpzpp)s;CFV}wSc;otL@PZSZH9ErTKWQFnGr{F?2 zj1LU2ffI@R&+G#A>2iU*+%;AL<}P3oo_P3dx935Z8~4ov$W} znOk6Wemrs$nIP-_5w~+!U38fb?Hq*sI>}~FRFLfHv&>AzA$E?bM-Ew#5l*LKPtq7W zn{qlVTo_hB8fq@ZNVv>cxLi>|5Gfg|v`|~>aJ^;I0DZ#{%pS-8yb7*6bsk2$C#fr^ zf!Y#+IdmpQZl>>keQDtF4h`x!EL|FVGUyAC9)-NC$cAoe`UcEiEfgdrTI&-UmF4{& z=QhJI)NkQVvXa{eRjA{VL*{dMVGWA^9PlXvz7k(NIb{=0UjRdKKyDL>+y>HHz$p$# zCZ@f}L3Hqvc1Ffcsnbb4eYuMOj@I|LFsYU$xMShWZ=xO|^QDEnSzC>4Y1jrCqt*)& zit`T!ym#%>(?KPG3UDHOXGO#Yb%s#B)ERPdG6jX>#(^3#CIX_3+8b%A3GTmAI&&W? z0Y5(zWUXLpJ*$@gI;@j1@Fc@Pq_3b6zj`q%AK90bpja6HbgxL=m1H8j?l5v!q<5Pi z?L2SPi><4J+4OwR^%T>fxTaSu=j?nHqQZ*?pw?SPY35&Vq7UoRU7 z)|638{rR&5=VnKIRx3aQ@%l(jd8kRADqZq^&q-jP9j!?OccbFEd-3YkyuYigqV`M> z(4B0~)dZib8F!@K`vxO9S>#qrOa<->i8B}sk$u&%`_AgS*{)%402B<4Y@OBhhIray~rz=h5urbNBKuZt=1+qtTX= z>nOdC3dCQ5n{;)(2D~n=*>qF%=g*%hSXtYr8lxCQtf})Y+rI)gU@yH3tjl+e54a$z zTyq#nq-4LP0jhvbhTaW#_v_3Ot_=YWP&$0S|NT5L=@K@mmX;O{VPRpclYs#vs=vSg zk)`F&LigVFAwMH0p=`UfSENrPm~bviUZ*Y3tVGWgE>CgYh~}HrD-KT-Fm%+(ws#Yc zsU00`GTrl*+_xTHnOaBDQ&Gw9t_*{M;X$-#DS)VH$-W!6(d_K|8_h!Vz1ghlvd6AL zYy&FY1y)*IYKh7K-uj9iSZhMa)7%z&G7O8ufl&Z-jR_AIToVTxgj-yEKck-M$^(3O zjqLJ1WK?fkE|&)nJ}QOttxVf3Q|DTeF9$6>sN1s|znR{=&N$Mew&JYnDVAG(!0K=2 zW1rPMUGk!;D7tFB+r0@qquoMCIO0i3dSb1b_68LZI~G`*ExzR?1^Ni zVKEmcXWc_Lm~M?y=f{75%gudI=Q$QcNU}A9W8~5*V&t=2_=-_v;Z?oZ|E6{4L;e|H zz|K=q&G+T9|N8aIUb?6xqPQsPVGsXP36DQs)6r8ICU$P(?>Bqgonr!@u(P8AjKW*Ee_X5a=x1hA$xpODTr26=9H)TEkMhrp@$jhty$cTycJ(NWy zOTmD83p*?QP-2&~H?qq3XWW*j1hM>Qm`iNvg8VnO_w5Y#8UCB|rDV?TRUWQM9X%WLw@+OJ;~?~h$zt14b2}&J@`&HAG4d6WXj-ee zfKw1N_k`yjuBKM2K_H}aH%0Wsv=j@3$1yz)}X38jJ57#g01M;&=~Y#sQu&DqUChbqeR=QYRn0c9ZKje3entv`?l(@i(@ zVhanEI}oUU`s(uX@}un&wL+g=dpOe4e%_Ra9oqprpTC$XOyPP;A+^;eC_q!P?qWGIFR+ZM-FuXDuNuR>f~V2b)oAeUv~Lhkf#w*21y)H#_oYI zD0O;idAytZa zDwsB95Y4fX8l(~{j0pRkGh=#LOxLqnfxere%fTOJ($k)DyItWX}SggaJX)k$(Z zlHgF;PsNGpi}6M+r{AH0EY3?EfnS|v{FBym$x+NvA}LLpFwrSE2V?Yk$jDJ3`!kE& z;dcWXovg0AW|ZPW5iPiF&CSi&SaBCFT~j|1VT+cFoSZM-y`#2hiM;`-X&(@ev=dC& zKymx?>eP#vm$_w(yw>qVX!MJzbsH2R2x5EdlduJ~Ph65D+|VGvBiz@y3)el%@F@=+ zjj^^y~k<05eb)g4BSuAp@s9f%CQ2*Gxq)`4FjoeFv#SwR+ zFWvie>zsAhw;OP%`tmKwSp$x8Pu~Gswzw&}^*U!A)H;bT>a%e&?tMCA)0@Q!yyxo+ zqPUKAG`c_`haANLDZ+)k97DuoNK3|Yts+p@)DGF5>npXszOLvbahl!l ze@7^(+385OF@$f29YK9?3~KudGTRYg764UG*S;iRBi^XTl!uo z#_!Ri*ko1>^3L*?nhHw~>&fynjTo-|YN|xkvKM1CP{a<6b)k56 zv@_%TPqyjAk`5lqDYP|AE~0QDN33-yv0m|9GlPSMTiq1R*FRZiRe>>*&_#8@Mo!nP zdtUjle(W8=o}z-<^!j77o-AWTJl=3P?kRRKh1=GFT;Esf!VUa?9CF49w^1Z=Prk+B z7r1cS4wGEDqNB@!HfflY4g{ifYoR*~)D9|I+V@!B*|wxOQHNw?jaai3Q)y6NyxsDL z%eoQX!3LIA(6H!L2&?~I!K~2FrK@kFqE3%4Ojij~g?qut4Gs=|`~JQAz-GY7J~vbo z+gtOBOKjYPK>h=Xa=JF->nP97R?*GhXNBG*C7p{M{JlI>8ijyr2q43qX>_?E6+UdD zbWfkLT?c`n)*7i`Sy;#ep_Y=EpPzrnryCB-&{WX$AQCRpCDbZZOgnaH7k1&1EI8`^WbGT^dE z=DAU8LXDap{h_N1ch28XMlngc+kP0CbrgeRHgp3=<0RADO)pQO7bmoV!HWZB->KT5 z82TPJ^(X+FrDC#OB-GV#JNyFckgB}x*JP9&oV&KYaxf9_^FxVX4b*9|#*h2F z>M`hv6f)M}SETu@be47k6VgZ}$^>CwH`AaFwoPMe>lcs!0!z;-L(T$>JX5hd^6+o! z4Sv0xK!}$AI;SyvDOD#|2mAEIru_#WxQJNCF1IDUi6j2-p{Iu(ZBjQWUyTS!Q1Y1p zWQIKOl!i|y2ZFYQ`;v08{V;N-?FI_Wq1H_nRIHVSGm~DggrDl`m49MtlI)G6ICTwK zx5|S{LX~@H(9!nWqj~N<1uw)E@2w}lYiby-J|g1N$yjscMV~ZoHyh(x!osCmU5$EvN`S*1MRfK-C|_~}z)QmLbNLO zKs^WQb}^=KTvkxkTx^)pEC84@bXo@_Y7dcJs!!cW;Ruhjzw&dnufj+4r^o8d&(%t# zE;&^qz$D@fnfB*)Ifx`%tD`AkLqV7osC^;Mz?x=MA0F&1H-l2KA$u!=Ww}Q}K}tNLBkXKU+7q`-&0Aomt>E$wTMu8fwWG}r6N`%qa zI;gL_x>-yx52-*a?YD=7giujYP4>8iQS%z(@mNkC)EGzyqBn$CR&icoFk>JSPOXjC zWEd2Ng6i+Iw`Pu*GC)%#tM1k{ZS7{M)V^nJeW}{2xz+b%e-<(Cl({Wlg^+U9sM!j$ z_q641U&Y{(4Uyi7s(dxtnHH|=`VxalHL37cbSuLJQv)K^2pAT9hT3Sq-D7nm2{x40 zhnoZtYnnUNWm~_hCd6KS+{6$O6&H8g!ouR@VXw%m|0(?~{#*Jt4_a+nJWWzdq@{3!a8HqjX|-`J(8M?A&@3!!bzMRwBu?W+hy8hjyf8TAA^UhUbs-Ff-knvghAXO4j0EGVPVCTt*mgWn@6 zKHk7A`n=@2CpkD#WRx{E&+iUs&NaIM>ah$Q z$F;Fv1S_@>{cZs-2V2D+OZX1lMh_mKnI+vhpk&Uhr`^phOTs-VU3GtSeBcV!q=xoY zz6^VAK7yWXa+jIEAMY|G%B(rmw%JXqz>FBNd%Dl8qr@KmA@x66S28HFouAjD0bici z(Rw|ye`6&*1YrwEug-$X#u(Vw*C$-b!pL}MjzOoBoQ!Ozk35h&LSW^gzT|Qrj-1?U zM*O+aMz8*j+3)UlvBDv#nTEeYD%}l>qRBV9-8bsuhg&Ccavn9leLpl?450TeOyO!3 zHo2ie8Dc$7K9L*XmcIWt^6g=NVJMpJu1a;o{u4B$^`Lr7oGK{7NExnvZm{ePzaSdk z)pZ|=E+t!A+mm`goj63q#O6?q)z;T*{dBiGbB?igxp=f~3+lWAwMdnZimB7S1=O#Q zOZlKo1CHH_?1%4wJ`8$rlhtq*pKjJxgIBv~F{hwlIDqVkM8nU@Vo3&g8g1>sg*`qy zHFMJ}wQw7Q(OvUIxehPOD-7|AGla8-1fss(Z-mrhsQm-q+}v>j-*z-hmR13u=P3$M zn}&MI&Dvz(9N@QXY>?qc_%2gqmEZ#7zr9EUathB=8{ntqje1>6_hkkqLVzqEbX&~G zlvgMZhLO6sxG+e%^PBo@(}2edoQ&z!i$Hv@yAq>Mtbms6o~U$|$&$Q?NPMzVBY0xI zdyW7KYrw>&3g;G*@{s$W9X>w(W!t{XND&>ti@IZ8>W%8nE-oUYTxW!s3K&xy_8=R$ zVbEaAgmb!%lnsv>C}@RDkV1J+h(L~)UzZ#}-hX)<8i=J)QBkD}Khja)`n)J2LKB!^ zU-lBJvJS|)>*{fF+%bXoQ13Q@BoCzv$>7gtdWGpr2G9diaX)}-RCl_rK428ifLzEr3pHyR@DoGe{n=U> z9z4Ap$UzcJFu9dCkc7w!@X&LrA#(o^3=^V2w$Bug`hSA=fG@G`^z~&Y>Vof(l8hIg z1DmOzZ*k40C*zws--Ico-J9PDH5Al7yhv5_1%A+o2Oc~nApW)j`hg9U50!uB@1x$G z)%}30pd@d<(ik9%et;-kl@_Ze%Ic!Kp51=NUvikpzUj6vW$PoX*8_1V-AyOU2pzW< zfbN3)YRGu)@?bPyCag05EF4OhYX9SHUA089@p-M6ea{xr{^zhwFRc6i+QJ^O1uW+X zmI%aFIXCwNOj@mA!Keqq8LWRLY3c$KDMmFOS>sZXznuxHyVF~5PQZ|0-d?_Z2{qtl zpB-Don*oTnbh&5{NQ|#=&XZ*-Fjyyo>Vs_0_%pRz4RZX@}xhH z6AG^{_rGf*aL;Yw{&j1v_=XpajpC(mvSDt%rC#iGDR=$Oa3)K?b0Jir77g+L2twT) z$Q&`o?hFD31!J=*0mvQsO)C?@hU1)BDz1$a1r*NEWh35MIydv=3XL_w+IRZf^= zTIK&v!0TS z0TL5puQB!CKOL}Q80}FNcJ~zeFfcG64;!HWv&UBCh>vcuiv>(N0|pA!ca;r_$wqw0 z54M6p-updmZqBt=u^HY?bHE8K0HoGvz*@L(;^Ui+_BZzd_m|FpO&}s7`nz!%O?Q(@ zZc4K|(}tE()|JS8H5iQ7eCH*dCCt|!fXiiX=0acb>e8yT^XIvRyhwB$zBA-jP=Syz zi-2+{DBkhwzXh;FS2wSC6atg^Bj@rrt@cMRCEsw5W4tO=>#XaOF>NDmK z!f66Tw>qzd>3bF&P-h%3DmwVMxnH+`xmEafK>QimA~2j|E`z(|OLx22Rp z$MZJj07wsEFx?`GijIy>P%p$VEox58UM0M}r|?xsL){PK3m-qRan_L%{Ioa|R?-}V z=Q!$j+2yO3@8s*Xm7f}=d4+DbWg-Zx`|~Yb0263s8i-uCA5sQ^r@zuqQY|ei_&{Ch z^V)mvTW}) zQM>SCN(!C`F_m@(_*&S-A{bs zyr)dV&$f=Hr{s$5L8pCBvq8z?@Ws0O$Mh6#X5#84Sb(M&h*(?Y6M%JlpiA{cA7ESW=JnU zKg`G2C$m4x;BgN=HE+hl`X>?(@WX3DKHOu6lX~v(fF3puR1}CuxHVn`_)y)x$+DR5 z80zp-j>xH)gl24`x%Kgx19@YT=6Q}BK*zSD;rYH^!iS>h-!Kcfa2SDcjE2H|t${sa z%Jk5q=A7tStLP{o(`95)WO~<(60Sp0e==XT*y7&C1amNY#a{|%)K}g_gQ7HwTfQz7 z@HE{o;Op)yxxIOVsy;Yet)Guq=8#EK#!W>4hVtFJh!d>3S`JADP>Quh>zXuzvoI`= znsRjP;LFfAN(DuI!>~P=I!Kd-BB zC>SH^c&@oLcwS*B(@6ZAVeb+*C*0Yyn9lT?bl`MTn?~T zkpya9Gpec1w=@LNC%Ze{eCtWRtiKf42Cc-M=aIb|&fGjw;o}9BdFjDIdi!27WLan` znVHvA1AIV_AT&I3scK}tfDR)jC!dW{m*L$oP*BTvOD{chS&ZJG2pmuAmh0;lhhPaO zCy&&EU7aFh;d8j`xCkkg!+vaCu@0(i8TFKjkB=TdhT@mx3^_|8)<{kcg@ED?ef#j_ z{{kSy#8*w~^3&&5{-S3*@A9xzzgl>$!qdQVi`Is7WY>55-i3WkN!xrf9G{wV8DQj_ z3X9iY&W5LFmaA7wu2PgZbGFSrasCtjLd$=4-}+Ptc{Hf~n4DQc!QNhQ8r%KaxYE}P zqNC@Zc832`#W>HxvJxo)h*8=Z^cM93txvb3z7ZYif51)fKWJR8FJ?cMN;1yp%l>@S z6n!M_&TnY{vvt9_OUDGwArigQE~|bq=c}Qpdxnwzn42lcHLpn1RdN#T@W$%sr93Ya zWA6qKcH+^~(JA@*`UcrB4zo#0CVRvs^PtckHGKdNQu;hMr+^s8Dp&>$7qI@diOUnaaI5Td)Dy zzypctPiyf8*7YIC44`-o{cchSwCZfx`E!Bhv)mb-(WNbsmTG+>6;{P+`|81_|XTvp0`-Ez-wL zd98zjEIyb5_f}Lyn;YCooHgCX;zxZ+r=W;sogQjrhdjFr{3f<5x!*5jhS98)ciN_@ zbx%yXUvpsLH+bX?x{fL2R>YdM&K1QKx9ryY>v0UkjXtf#9t--t)hZEETP5~ev39E? zj_)};YGolTdY(>pBlROV^K?<|BIB8&m}tK77}J)jAnZ{+ptl-eyvpl- zXy-VwKYx*QM8N;x#m|+i5aV7@af3%Pv~8}#!e@8b!dQ770RbbwyAM4!TmO@zD+;af zqA%UB{!vP+aWuLz3^CurwD+X{Dd_5=4Q;_fm6s29M{EEI;NbktPwP(+>-eYn83VTW z72M7&=B{i9HxW&IWB|W*N9CQbzT+cIk^qlGLnA6SmdIxZe4m~@FR9jk5n5o^>k+L4 z>D3hV+%?W$9@O?)+ds9@fp*;2$gfkFfc?irWJN_Rk-t61a9q;Br`-Dc*Thdavr)3% zTVRCDg;i6&ci}2Nu)|!csfMC(YhGw>FdLK0mv#OeM~$wun!W>t_3z&;8$u6MU@{b~ zmItEfOd=RQoz1Q*hH$8$_=`0lmf`b60vtclQQHA6+uK!s3ZZxGvr2m%Ojw}1s=)d& zNE&os6<$VF1j+}?sf8DAH@s+Wl@@=VJ#K0UR5tG=hYA9fn0V8V4wY7JB4|2pHk>=r zSLHF-!<6psh8OX&tl$TI%Q=34SVH;1;-N`>a&R`;uV<<1;L`nXW_HqOI=)LJ$zFe! z$S<6Uivz)tZZ5&0Wv9om^*Ere2)446faD-)A(O1V&S0-VOl|M>DtT@$)Yj#@$=%(` z=F`(jV zdXmxXYNXQG&R}MyQf(40p1PWaH`Z_O*u!Qq(nZp3Z?{bnPE|Q_Ub&fMY*$j^-{Jz^ z62U4QsSXy+803{pdG47DkS({q7kD=OlkMtx33nvl+f)I436|SfDS6D>G($k~88onPLJU}DRGa$1-WjW+v3nwiVF<1!u1z3RT% zz;5w7$deF&xT+}Pp8-KKQYF`!(+(`7|1q80K>S0wu?r|wkqJdubiuCi8jGOW5SHIg6Znm<86$-QWWeU@_88rhu1_`M zKe!}|E!PiF%MkV}>mPBAvX|#2fb&fKzLPkLJHaLiP;cr*XQfwWjgaLyO%-bAx|@gW z(A7W04_ln1_xGObBL&_cTS88l0CtJ7U&}nPUs1mpZiYqU4OClT@^!Y-) zNaGoS7^`g^X3e=}ho@jeS~?0}EyI=}vYD2slpY;NRNsLx64tr>jUrwn0``7Y0TwUgh zN@)pzaO|;=>++AqBS5J(*}vjN-n@IX5}W^scn)ja9xpq3_xE>$Zhjp04WXj_%=hu} zcYw83^EsJGaQF&hO@VcHs1;*!PK102bdm@QgAvqoj*aRB7f*F8LA3p7+jr28Bmf7}%m#{O8C)%qii7!ldP$zH@3_TB*i_dO>9ILPfbWdmAV-;vT z+S?g)m>($QgL#>TTgps2f$5>q_1sxpD=RA$IFzCQ;Pu2C*SqXG*)29uGBv*+-`m#3 z^*^T3$^PTibZ#-J&^od=oz6?zJ8>zlp;3I*y!*7_o&fUe!u_WP#eZ^r#l42hA|<`@ z_CGCBTl4J_-ML$fGgV+0)`>T&^4|s{Cbe1KDuRk3;dZH-Z}&d6?I(j0uW|UUyKQ%= zUmj>5tKKYTR==$daoJsHh_Qs9w4}&lUuBbDxc+LqCM0F&==1F;aJdQ9>RwEyeV43O zTj@tV`ZEUOcZlh$NO+qds^yD4=^RM_alfsQHs7#gk)(^Lun~ot95jnrdo!^5+F9r*wF%F073m6x`a6Dc8eoj)V7(Fu8QCdl`GCmc2{O@Sm zLW@{SK&!~)E}#oe4vyy_k)SR=ZladipNiTfqoRBH?~9X8c3bW%Qjq_`YsN3jb66gr z+N)?O%(6O(iFo#$zRrdoR8UfClwEtr`%tDSMzsAU#=~ch4L;f640&)`^3}6SyDN5X z+Li6|&ubO(vq29h^JhQ-oCG7&S;HdR575dYrbBY4poB z_VXJ^K?=17fMU#d4p(X-6I3R9P3zZ(J#=)ZeKt1C+L*v5&U4yVitah&#-DLpRg<$9 z43hQ^ygBwlzhb~hi-CbyH69$eo`@zuxlR@oH06JE<>x?AU1SuV$M6>lPd1~Ps^x(j zZ%o_PsYLFb1$> z@_CwfQLe`+Mi);X$)1dml+{0PclAq*+24yVs1ad6+1Xs@lHsdUO-gpc&l*{ zc$XJSELXx<2Zx7BXAU*eX`!fwM9+Tu8V{)*df%hmc^Y4=A7p8Mx`&pGC(&W2k5c)? z!(s2pMObSOdqTcaN|=`i9n=ypUm_s06a}dpJ>gU4_ROI&=nci*j$z3pSwl-f*^iIK zb{CHJ(}-(&jV<9m^8Xo&+cHV#*Bg5D(2mT)Dr@hit+)udut@PN&%NIR2DNFY)3UnI zMeKh>`MYL(Hsyl~9b(x0@o{sr-NNU18wfoa=;Bd;9$NsUuNXAS#afcjLB;1?2EE!Q z0Ia>iupx*vRso-V-Og<0E++KpXAUaNzke|9eE-8%{9)(mF~kaT%lGtSc=keoBz@I4 z_e8IRLc;x87{?)B@0vrJ+DwrbnobV;KtZ84031^cv;x{B&^g6+S)_a6hm?FTwviJG zOiD`ZzZ|xs1HN~HcJ`6(ldn%aRL9zqax7lY?=SXsAZrcvAqIo}uA4pPxF%4%*L(iT zXn;derooN=JU9t5NJF5)k=C;_7O~f^o`-J3L5JOxx{qmUB7<4RnHe{I|MM`}UsYQr zg6cx!zC1uy0s7Dv{xOL^u#k8*-%njibh;3u2F2GsNQuvhNLvEo?d7GT>$dK{hXVxi zWsgE@0FyF+5#eU0A!IYjK+3F5#{hk)me#Fp%ybSLdf{~XrH4G(eRtye12$FZh5rnA z3*Nf*r|}Sb3DxwU=RGW$W$|1V$;WnSt<}->^tgQZsw&KuW34@WEHC&HnfN}Ho4BO( zW;;GR*My(@)dA+T+g%xR1ZaKQ-awg47lLOJz`Rn{+(J~jt)o}mw(z5Eb!|M#13TAI z1N&h1bjqN=t~xE{X2SJ1@6W&|W`vOG8+Vub9g9p&#crR=K0QbEr!SO#@#5DzUJKr6 zyTP$G$qJv>a=mNW-q_l6r<<3k9Z=7WREi%FWsjkVDL+Byr)6p|*|DKmO zHW|@+!XAM<83O((DFY#VM%~EEYuOGAz=GZF&pTf5K>&ni+{|`22yTI|c?Fy=%Ru7VcMLFJ79s<$nQ%gRsd^9K>MP!L$xd z-QbM?yB?^!7N97X1H(lMMGm=<)-r_XN+z=Wtvl0ATo~yMC6nncv&J@{@lQ zeeBnL{QX3%!0UD8$`woB<;`|kZs-hCm)U>*<_!fjxYt0#F#`~aU`QpBD&YF94JlZb$jhxy4)ylbtL!Iw&+*D3V){(VhE8-xs}S&MPX1Xx0aY(s%fc+$WV$_NXSS;Mnxub-e0@tY(3BU z<2>g%e|g3;&&==lo$v4S{ajw}_jU~mThPf9sQL8NM>p8SargzEDy!3irDjk3bx(-2b9hSTZC!B!!u-QqGjOVNJ^uw z4y}q^p!n352{0w<@b`$OO^hCf9J}+HEBSRkPeIFK^4B6{u6`Q-?KRb9VGY;xiral> zzs4X@SF5Hrgcp!J);!ht=o;h<5mm+*FgeKgl&9B)TXn@%ViF=im-n|VA zO2kvYNdNkqTw}-ovbPFgZ!rw{cqBc~iBdiGW@UDrIfMPqHtL#mr~58L>ae zQoHL0n98UGFoM3FGb(u)0cex#`4sn+Yip^zJeGOv#JY#rorl%)5~LGs{e?L zx&!x#bJvsgf68Pm3tA!4Ju-Ab=9_8S_NLjkLt}!TCNB-O?nDZBt0>4%MtOs|oAT9! zf_mzqqd4lk&=A#Snbn@@alW{WCDrCk5(bPr1_}zi+!)7ZLZ=Vdv9^S#q%sR^%9| zn5}d3L2yjKg7s6dIC2FllZS#_G64Gj^UHJdbESuNFfwO{VSZJjz7nGy%zscFL3Ocz z{B7l`FI?vCzYBWyE~xc{f&}$841y>zv9a7z;2v_i~n?X<1VP@G-qVL`& zc1XN8zD5LN1s|xOZGQ~Y{HuXN_uWT}vLT#m0632oAb2O>gB>_ZB-`1Y6*E457_`PG z0=h(p(~AYC5JfxBtzGwyXMn*RiPE@?ux6GwHOeBEYADz-r zYn5tzE+S$YT01o$GqbmrnE>_g1ki4u=)N0OR0dStyzw_TS-}UPZQ#9Y+Hy>tmWsN{ zh8N&%C@OC=_u?*(RV}mLN`{u*)Mt}gU2_G_yiG7~! zDcS5$w94*^Lp*YVLQF%?P`C2^nw_eambBi%h?i1yQXi0_3h7j#Y}Ov)wbVo#R^}3k z6CdL|0gYc*=VzZ~bK7uxg_Lw|!bS?844TE>&d#a2nws~<`f~GoXo(34owH<}L&t&cNc^_- z$MxGC($|~95k{xFZ%X$??8o@zWIEVIY2&Sbj&XNxu=6p2HIW3%Q@?q)?X@qd+c1wz zBsL(OrFokM+>SpF6>}g*B3lRha}-1A(%~9yIII-4+>Z?gu6)JudIG2~&ika0%fZRW zo<})YaPHnVBak94ev5q+i*`NPjvobGo?-9}4P2Hr$fhegbVdP8CyBTYO0yZ#(%c(! zy>(?MLGi$QzgAWbXqlA*`4`#&uH<_2iZ|R0jQ$q@iyz@M(R9+(A=iTo9BKrS03HcMYZ8OesFM=bhVM3Hk=N65O_`=B`K^%Za9kI578zJ#b zBtCR>>Me7CDC80Wb{oT9DjkxRra60bv4X5e7uN+NwE>gYv-L0&f-|he&)8$VjhV9e zN|G=lFsg-$yp#037%+iclGpAG+~5JsolLRU3=WJe0_?sW)UXITL)?bEipsfAncwK> zFE54{!h{gZ=l)L5&9DtK(19z=>;&W-6@j=31F$)se(Q=q;Au7rZ!|gZzWlj7>XdTD$aAr#2Ue6cqea*{6@AK)X7$p_js@qr1~z^$HRr|QflwgES8tI9Zgz@VCeX+>#BRb3%{cMDSfL_=M)J$J46|P(YE6D$;7Oxa`$_#GMmvg7S)r z_llaGYaxSy3YbW~;I}zkK2;VZV-juJO5lQ``Z_dfvEtZ5w%Brj{tpYAT5~s1p(v<< zqQeZ~1uCwdNG0d_T3XR!k$^^a753TkZFeH1KRU<65P`ab=jhOjR)lThWdUtqW5ya; zqBSzLw4B-ODE z?>syUT`=1u+a1G*C`g3PveFK&5VN;j+j(2ni?^D|RKV_Xg+AK&-Q$g8Q1X0yO^gar z4-sM%%tYK(kH*WwCKDEaE)h$E1ye>jhqyTjETL9fvbit=wZHVdV}I&2?Y zeAeRIIk+yji7v7garz~TmG_yz$N_#Jjg6czHmWZiBCmpRo^Sx>OP;unkf+tr3dx>I zy&-Bs7M{al^%88}F)XA)K)v|WbFrbTtE;qA6*{j2kQ46>cO{hoqkIg@koK0B8BzyH zpw~nfq{%Eem8IbDhW8yq00=21jE$m7(j=c%pE~(?fCv|+<=W+*;ez-Zi(~uvq(D{T zPYyVNNG&Etl$=LVkfURCL=7zi9*BI$8%Lf5*!a6xD@!~l9%&_hukCfpM8iV0P(+y} zj-^*kh>MVG$2%8E#8a0#jJZw8kq0XzbICvZmRcFth6}hI-kswG(85r7Z z#I}S-YO>e>+Sf;y=t_MKC?iPrN|&5IU5Tg^t7~hg63_q;71PW)t z@z}f!)K8+3Mr+Abbe1=VSAoCj?&)zJF*G+nnxGjT6Vu#>Vg#`Kd8{}n^J9Fv9=u=QZ-G_X#5_t}#aq4vU zC^pQ6ah~)*ROsgB<~Y=>tzpZYykNU5oA5|!r34($=uK>L@|!ai43Ux1jq)OI0a5IR zz}VKEpRx|YcW2WT70lf(fuD=a%K-Hl3}_W)QzU#|f7shvD%xC*$}sHQj8-`1zJa4v z&6%aOV4SHUX+^ok8Ys&#^_7y7+bYCO>4t~`Fi`PZS4CJ?JPA9nY4%>9GxzMx1VZLP z^I0<2+FTSz_Qv7}?6x=0P^W6?kd^&@DN@lq1`Z$Z~~Ucs~HSN z_zWEl4e@2vK(^8$7E`527Z5&_9FdIfYF r$D_jjjL0WV5yk$8K>b-%?-5V+bm{K!U@*sEqAsz{f?=L#=5pwteF^G4 literal 0 HcmV?d00001 diff --git a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst index fcc9b5278a..baca7a33fc 100644 --- a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst +++ b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst @@ -8,6 +8,8 @@ control. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_steer_control/animation.gif +`[Code Link] `_ + Overview ~~~~~~~~ @@ -23,10 +25,10 @@ The below figure shows the geometric model of the vehicle used in this simulatio .. image:: lqr_steering_control_model.jpg :width: 600px -The `e` and `theta` represent the lateral error and orientation error, respectively, with respect to the desired trajectory. +The `e` and :math:`\theta` represent the lateral error and orientation error, respectively, with respect to the desired trajectory. And :math:`\dot{e}` and :math:`\dot{\theta}` represent the rates of change of these errors. -The :math:`e_t` and :math:`theta_t` are the updated values of `e` and `theta` at time `t`, respectively, and can be calculated using the following kinematic equations: +The :math:`e_t` and :math:`\theta_t` are the updated values of `e` and :math:`\theta` at time `t`, respectively, and can be calculated using the following kinematic equations: .. math:: e_t = e_{t-1} + \dot{e}_{t-1} dt @@ -38,9 +40,9 @@ The change rate of the `e` can be calculated as: .. math:: \dot{e}_t = V \sin(\theta_{t-1}) -Where `V` is the vehicle speed. +Where `V` is the current vehicle speed. -If the :math:`theta` is small, +If the :math:`\theta` is small, .. math:: \theta \approx 0 @@ -72,6 +74,9 @@ So, the change rate of the :math:`\theta` can be approximated as: The above equations can be used to update the state of the vehicle at each time step. +Control Model +~~~~~~~~~~~~~~ + To formulate the state-space representation of the vehicle dynamics as a linear model, the state vector `x` and control input vector `u` are defined as follows: @@ -79,7 +84,7 @@ the state vector `x` and control input vector `u` are defined as follows: .. math:: u_t = \delta_t -The state transition equation can be represented as: +The linear state transition equation can be represented as: .. math:: x_{t+1} = A x_t + B u_t diff --git a/tests/test_codestyle.py b/tests/test_codestyle.py index a7d11d270f..55e558c184 100644 --- a/tests/test_codestyle.py +++ b/tests/test_codestyle.py @@ -54,7 +54,7 @@ def run_ruff(files, fix): return 0, "" args = ['--fix'] if fix else [] res = subprocess.run( - ['ruff', f'--config={CONFIG}'] + args + files, + ['ruff', 'check', f'--config={CONFIG}'] + args + files, stdout=subprocess.PIPE, encoding='utf-8' ) From c862d496f415399f28ba131abe503353c7b6dfcb Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 23 Jul 2024 10:15:23 +0900 Subject: [PATCH 767/940] Bump numpy from 2.0.0 to 2.0.1 in /requirements (#1051) Bumps [numpy](https://github.com/numpy/numpy) from 2.0.0 to 2.0.1. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v2.0.0...v2.0.1) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index aa91cb258f..a0af999bba 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 2.0.0 +numpy == 2.0.1 scipy == 1.14.0 matplotlib == 3.9.1 cvxpy == 1.5.2 From f3ca769076b11f03f02508ed112c85901e4b79c5 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 23 Jul 2024 20:14:40 +0900 Subject: [PATCH 768/940] Bump pytest from 8.2.2 to 8.3.1 in /requirements (#1049) Bumps [pytest](https://github.com/pytest-dev/pytest) from 8.2.2 to 8.3.1. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/8.2.2...8.3.1) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a0af999bba..9cbe4747a0 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 2.0.1 scipy == 1.14.0 matplotlib == 3.9.1 cvxpy == 1.5.2 -pytest == 8.2.2 # For unit test +pytest == 8.3.1 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.10.1 # For unit test ruff == 0.5.2 # For unit test From 76ba4ba1913fc7153e51fef434b3e955a58b3c2c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 23 Jul 2024 21:44:01 +0900 Subject: [PATCH 769/940] Bump mypy from 1.10.1 to 1.11.0 in /requirements (#1052) Bumps [mypy](https://github.com/python/mypy) from 1.10.1 to 1.11.0. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.10.1...v1.11) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 9cbe4747a0..1055194460 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.9.1 cvxpy == 1.5.2 pytest == 8.3.1 # For unit test pytest-xdist == 3.6.1 # For unit test -mypy == 1.10.1 # For unit test +mypy == 1.11.0 # For unit test ruff == 0.5.2 # For unit test From 65cb7f5b41b75ef0d198949e5274546b9f015cc6 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Fri, 26 Jul 2024 17:53:37 +0900 Subject: [PATCH 770/940] Bump ruff from 0.5.2 to 0.5.4 in /requirements (#1050) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.5.2 to 0.5.4. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.5.2...0.5.4) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 1055194460..2c2e156d62 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.2 pytest == 8.3.1 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.0 # For unit test -ruff == 0.5.2 # For unit test +ruff == 0.5.4 # For unit test From b1856d5ef3384d7ce1e8ecdd4937d1f76b28d99f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 30 Jul 2024 22:09:58 +0900 Subject: [PATCH 771/940] Bump ruff from 0.5.4 to 0.5.5 in /requirements (#1053) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.5.4 to 0.5.5. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.5.4...0.5.5) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 2c2e156d62..7a89f692fb 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.2 pytest == 8.3.1 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.0 # For unit test -ruff == 0.5.4 # For unit test +ruff == 0.5.5 # For unit test From f9ae5e5f887e527b7333b83d0332d5d25f1e0564 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 30 Jul 2024 22:10:12 +0900 Subject: [PATCH 772/940] Bump pytest from 8.3.1 to 8.3.2 in /requirements (#1054) Bumps [pytest](https://github.com/pytest-dev/pytest) from 8.3.1 to 8.3.2. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/8.3.1...8.3.2) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 7a89f692fb..528c8f713c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 2.0.1 scipy == 1.14.0 matplotlib == 3.9.1 cvxpy == 1.5.2 -pytest == 8.3.1 # For unit test +pytest == 8.3.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.0 # For unit test ruff == 0.5.5 # For unit test From 171e3a8f60c984afd493c333fb97a8b8f5fb19df Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 13 Aug 2024 09:06:26 +0900 Subject: [PATCH 773/940] Bump matplotlib from 3.9.1 to 3.9.1.post1 in /requirements (#1059) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.9.1 to 3.9.1.post1. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.9.1...v3.9.1.post1) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 528c8f713c..d9e5930498 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 2.0.1 scipy == 1.14.0 -matplotlib == 3.9.1 +matplotlib == 3.9.1.post1 cvxpy == 1.5.2 pytest == 8.3.2 # For unit test pytest-xdist == 3.6.1 # For unit test From e1e3d8f5d7266229d46cd5b09d0c034d9c389eda Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 13 Aug 2024 09:54:41 +0900 Subject: [PATCH 774/940] Bump ruff from 0.5.5 to 0.5.7 in /requirements (#1058) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.5.5 to 0.5.7. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.5.5...0.5.7) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index d9e5930498..1bcbf1ac34 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.2 pytest == 8.3.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.0 # For unit test -ruff == 0.5.5 # For unit test +ruff == 0.5.7 # For unit test From e6c6814f7bd8865940f31354a84b18ebd659db87 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 20 Aug 2024 22:24:41 +0900 Subject: [PATCH 775/940] Bump cvxpy from 1.5.2 to 1.5.3 in /requirements (#1062) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.5.2 to 1.5.3. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.5.2...v1.5.3) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 1bcbf1ac34..bc09cdb54e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 2.0.1 scipy == 1.14.0 matplotlib == 3.9.1.post1 -cvxpy == 1.5.2 +cvxpy == 1.5.3 pytest == 8.3.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.0 # For unit test From 12d6e694dc62d4ab4441cfafb429623e07803270 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 20 Aug 2024 22:33:02 +0900 Subject: [PATCH 776/940] Bump ruff from 0.5.7 to 0.6.1 in /requirements (#1063) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.5.7 to 0.6.1. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.5.7...0.6.1) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index bc09cdb54e..54a3c3eaf5 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.0 # For unit test -ruff == 0.5.7 # For unit test +ruff == 0.6.1 # For unit test From 791d4e7f003e6e5e75df2b4223fce40e05f87eef Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 21 Aug 2024 21:21:17 +0900 Subject: [PATCH 777/940] Bump matplotlib from 3.9.1.post1 to 3.9.2 in /requirements (#1061) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.9.1.post1 to 3.9.2. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.9.1.post1...v3.9.2) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 54a3c3eaf5..dcba39a756 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 2.0.1 scipy == 1.14.0 -matplotlib == 3.9.1.post1 +matplotlib == 3.9.2 cvxpy == 1.5.3 pytest == 8.3.2 # For unit test pytest-xdist == 3.6.1 # For unit test From 6eed25537f3c683047ff154bcd09d7dea2dd898f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 27 Aug 2024 07:07:58 +0900 Subject: [PATCH 778/940] Bump ruff from 0.6.1 to 0.6.2 in /requirements (#1064) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.6.1 to 0.6.2. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.6.1...0.6.2) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index dcba39a756..f219e1d279 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.0 # For unit test -ruff == 0.6.1 # For unit test +ruff == 0.6.2 # For unit test From 2b6c9b0888734b4caa4bf1a8f3c810def3dfa0ba Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 27 Aug 2024 20:14:07 +0900 Subject: [PATCH 779/940] Bump scipy from 1.14.0 to 1.14.1 in /requirements (#1066) Bumps [scipy](https://github.com/scipy/scipy) from 1.14.0 to 1.14.1. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.14.0...v1.14.1) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f219e1d279..500002ff0e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 2.0.1 -scipy == 1.14.0 +scipy == 1.14.1 matplotlib == 3.9.2 cvxpy == 1.5.3 pytest == 8.3.2 # For unit test From b139717b297f90daa063e107154fc1ce96c5066e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 27 Aug 2024 20:23:07 +0900 Subject: [PATCH 780/940] Bump mypy from 1.11.0 to 1.11.2 in /requirements (#1065) Bumps [mypy](https://github.com/python/mypy) from 1.11.0 to 1.11.2. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.11...v1.11.2) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 500002ff0e..0b8a51fcac 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.9.2 cvxpy == 1.5.3 pytest == 8.3.2 # For unit test pytest-xdist == 3.6.1 # For unit test -mypy == 1.11.0 # For unit test +mypy == 1.11.2 # For unit test ruff == 0.6.2 # For unit test From dab1a9b2dca0b27bc4eef30d98c516ec655ac2aa Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 3 Sep 2024 21:34:35 +0900 Subject: [PATCH 781/940] Bump ruff from 0.6.2 to 0.6.3 in /requirements (#1069) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.6.2 to 0.6.3. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.6.2...0.6.3) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 0b8a51fcac..8a27c1e301 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.2 # For unit test -ruff == 0.6.2 # For unit test +ruff == 0.6.3 # For unit test From 4ae9555a699b2823ea2e065e0ffe11b3622aa2b6 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 10 Sep 2024 21:39:10 +0900 Subject: [PATCH 782/940] Bump numpy from 2.0.1 to 2.1.1 in /requirements (#1071) Bumps [numpy](https://github.com/numpy/numpy) from 2.0.1 to 2.1.1. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v2.0.1...v2.1.1) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 8a27c1e301..87107816bb 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 2.0.1 +numpy == 2.1.1 scipy == 1.14.1 matplotlib == 3.9.2 cvxpy == 1.5.3 From ad600cd9023e67cd8064b678213d6586d076dd15 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 10 Sep 2024 21:39:27 +0900 Subject: [PATCH 783/940] Bump ruff from 0.6.3 to 0.6.4 in /requirements (#1072) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.6.3 to 0.6.4. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.6.3...0.6.4) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 87107816bb..c614c4e96a 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.2 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.2 # For unit test -ruff == 0.6.3 # For unit test +ruff == 0.6.4 # For unit test From bf69f444afcfffd8ebb44ec8f0988598a0b37ab6 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 16 Sep 2024 22:03:54 +0900 Subject: [PATCH 784/940] add turning radius calculation doc (#1068) * add turning radius calculation doc * add turning radius calculation doc * add turning radius calculation doc * add turning radius calculation doc * add turning radius calculation doc * add turning radius calculation doc * add turning radius calculation doc --- docs/modules/appendix/appendix_main.rst | 1 + .../steering_motion_model/steering_model.png | Bin 0 -> 72443 bytes .../turning_radius_calc1.png | Bin 0 -> 14926 bytes .../turning_radius_calc2.png | Bin 0 -> 21792 bytes .../appendix/steering_motion_model_main.rst | 97 ++++++++++++++++++ 5 files changed, 98 insertions(+) create mode 100644 docs/modules/appendix/steering_motion_model/steering_model.png create mode 100644 docs/modules/appendix/steering_motion_model/turning_radius_calc1.png create mode 100644 docs/modules/appendix/steering_motion_model/turning_radius_calc2.png create mode 100644 docs/modules/appendix/steering_motion_model_main.rst diff --git a/docs/modules/appendix/appendix_main.rst b/docs/modules/appendix/appendix_main.rst index 8a29d84676..cb1ac04066 100644 --- a/docs/modules/appendix/appendix_main.rst +++ b/docs/modules/appendix/appendix_main.rst @@ -7,6 +7,7 @@ Appendix :maxdepth: 2 :caption: Contents + steering_motion_model Kalmanfilter_basics Kalmanfilter_basics_2 diff --git a/docs/modules/appendix/steering_motion_model/steering_model.png b/docs/modules/appendix/steering_motion_model/steering_model.png new file mode 100644 index 0000000000000000000000000000000000000000..c66dded87afebc082d11743b5bab8b7531da1d20 GIT binary patch literal 72443 zcmeHQ2_RHkAFp|oB_c^FTcu6J42Gmcs6?fVEisIp8H};7FH2GJdTB?ik|C5Ogh;#= zEuymKNy@J5>vyi1%U~+6*X!kbyk40*_nvd_`Tx%Ezn*gs?b1+XW8r0)F=GbXwyj$< zXUst8&X_SXmuVI_!qYT&2>dgXsHv(rBd&1ChZ!?!lpU3I9Bp09ENx6@2&0rJzX>D7 zEeJ$MVbm63Bob?9Cx)}cnmb@^iDGzDM{o#yk2N>NQ%_JQxLMlRV1WV zVU)74_-4>5^arIx9T)Jy5=S}7X_ti)N|j_m#8}&@pwxAYNvhQD@K|ua!y~$dWNe8i z8roqUEetjHXpV0dZrs*I)d6c~p-#XJ51+XM+z0jEp!*+lv(OoPEZyLP!}p66Hz!%* z;OC@X=|~{hI9l3KAD(*9gn-AJnowm*J%)8~AUKab&5U3}eN>v;*fU|^pqtaS#5n>C zKp>JqqA3Fk9p7qdX>I{`Bq1$J`NkFu2jyhyjT0@fID#|HA=;dk47}K zU&ANax+t02KtP1Yk=hTy%U{2Cor>Ou+*IIf8E$oh>XKP50PgO`ubq0dT-E3rAZU@JRyviY3}ngllH$ zVhRMPh{F;spkIc+B|16~tViU90$&3{uu&q|5FqU133#XnO6OoYIhwkFqu?W*K^Q*t zWl4<6L)8?_VMhm7AQQMnG<6hRDLo)1Bq`lG(_o2uiUkdfWT?lmRIr+lvB(%h#Ykj5i;K zinthB93?G*LQ05BN=pFFlmTa$;&CJ24_`0|5Kxc;BSRR8Qc)2HKj89dctA*_0}mAm z8%JdchrNnU+huVW7oBa2rZ$s-2P7Vde}Q~WY_LQiSun~pQ`&(*!sCXgFf{xVr|?)& z;Y`i2BpbkzRA5kBCIEJUkEwt;4?2VBf+9>)+&B$mhaIK6Z=LBhGg*qxOoop+nA%_+ zEuA2Ak1`Ft>HX#DN+Fw3%GpH#rpXuhMw-eua8E=6$-%^wde!8(%)XHK9zx|l{$Dd0b(ucTnOju$2k%3jE8ikgSl|&(>#lU07Ij}s5azZP+z7lmX11r{l&$kAlZXYy3i-;?^_^)apVIu`$m=E z80!QDe!w-8RcJ_Y3gd$Y!6lzJ%fHN+qxxoqjFI9rlmN2^EhWImevIOiM2*!#DDi(> z@kz;!?Q+DnpYn>2I&_nq3g2YR!LwnQ2dQ%b{{3@v0kZ$UkC``iR?yWS!^(fE&kCt= z?k5V35|gF*p@wo`zU})(((9U~>3-@SFLtLjyMi%wHnZ7UeLd!_j7uAZ`JjPNRdyx=2(V zMJM!ur8?jyAlL(i11EUqww5>?(bfizS*7Dg1&gTOEaTGNOaj!4j0A&}h!W(KgSDf0t%Tx6(3 zGvyFL4Ik4W0v7%-7yJ!g!NCoUN70vQ3tUAdF!0+jL4i=oG#mkgLw}$E*+e)>z}7Dn zj==Auz;nvMQGzpyBQ zgEZNg;g*Cy)2JgUs73)232hJuDNTL6f5l>^Kj4(R95er++oo}hXySB#IXD5uT`4_$ zFA@P1Cu?BxgYA8(;bP) zWdHs~MjMn~{a1MghKdYzh+!WIR!T4i{sG=WQgs|mb<`>@xW_3=JCiU%zP+>x3Lx&G z)@Tt4Hc+{lBF@qQ)L&6(2*?R4b)&-hD+N__=i1+99XKZqLrI((SEHdF>JZVA&QE9C zP~rF`?LpVJq0~lAzPJX2eH~nNK;(>)h6W#WX+Ml6V4(B1K!XY?n!jfjA;l@PixRJ+ z3xla`K8?^C)kB3jX1s0l{b>zEKgXC;BhjZR&ubII&lJw)us)6 z2^lIlV5>}mN;t4u`u>^_RL+gngs_z1E~l)8FY$%A_unNsVI^f@MWAX&gVz5=ZbObs zA;az|4Yf@TbqL4O$1od3w#2^+70iDgB|njsG+grjnYChY@%-qLJKCV$@VD@4zp-Dy zM@QF{*~zFYZE>}i-RofGtnK1LFtjI9iTyKc0C#9YBuv{ZO|E?OhQM0B={10#S>%UO z`ixvDBRM*rjlG2uvt`cY$6Ga>vse@Ef(VWye zq5t?ySq{eDl!GHRN;d|MP+bCTk<9;@nT3S4 zAXRuHp&%OJ!SemN&8*2}0sr5G2hTKk=1BpxLV%re!lRdq7&r5N=(=Mmq_hlLToNUL zmXel6gLN|F)*Yjv)u>}5*Pq!hWvprbqqoW!pW{SMS%grL{UvVxp$PfPPAXz3Bw7|N zD}fS6q0uO5SrmF|07e21)WMVjyDU?VQs^bY|4m8(TkfD_q|q|6QYaZ2v;<(5@uVUH z*1G`2pvBQ>UCLlOw^8Ld! z6S{=`Yq-m)5TII@$4rMQ>r!)PN(s z+{jM`M{tYNaHP^C{bk$Z;fR7uLVf~v{6WcnLvv+yqAFU{%t6#vXPfg*rM+%crX5Z8 z@3FJ71Y4+1=lCHn>_5HFFNP@YWJ^+VA{e7wwN1=qTxAShM3Iw-fzdc1)NN|UY~cG@ zSA-H3{NmEg;WCDa#V7P_b{Y$bW{$%p`?MAieC)^UXC@^f3-*Z{4uQg!8XUZaZTau- zK1e}h1Yw%mCH%;6k5j>Wpo>Vl6>-pm(&R%-NDfXT8%R%t=VuWKPNi-%OWCoHW|y)t z8%=*5v*31ycW0%nkfHw|!k1$RH)sd#%uA%NBqwqa?Gbvh1bFgOXXeQ5f4$I)wq^KUC&VgHu#pXu4Q%*)r}oEh z&j@$-*P0(TfhglVxhVjer`et7%hyl~Ccka}U>V09u1?bU&8C~xWRaVlBneJPQ_+c~ zB@}k0A)UXsD3fMmP*W*TqBFc29IT6?Ic_%mGZL|<`9=}U!r?0@H}#ceo8PKbsf*%J zQe%~wgfulnO`~+-8A+>j;bZWm`k`S5xw zIR*vYGNgoI;eLPCAKxV$9SvG%*TIkyW)JZ$KH91f{;|!Yr@b-|f z_JXw~6=*bM11lg}vVrjlqvMB?4P7wce6Fk(2)l(;>k!f#IkTj2Ji= zKjoMX!WN{iz8IGM<^_7RuWJH}tbX#uo+P{h9962Ykuvp!Ix))mpPi~w@JkJ-LWTEn zn|eZ>jHNlciT89R8l6+=5xkCU-ar}6kjJWeQ`lcC1P|2cjf-=*ZZ9>3Z5`nStkkTR37tf%q#MLbHP zsA!-XZ%7$xVCJ90g8! zJ!c1jU`Kt+f|aSGqbv2Lxmc1T0n}&G)R)tHH}>dT<40f40A8Ct@@|HaH#$&HgkIdB zOMP#{@OPt^jd`cT#6tJ6_3V`SIGI=*#SHvH?K+a`VNuZV)f2y5QU}L(Xv%w$;*(yQ z0bTvI2-5d2+Jo!MCTabRzPjwMzTRW9Li>gxrf~sbD~L8M4Ii7dBqnnUqp}`v3c^80 z*iWSfX8t**8*hBVh9TVJlw~^9#8lnH@W-g;oyO*<4hHa~=QhL8_+i)_ZxzBfF!iws zf~{YTw@zadkRQE2bg=m~qd~IZ+;Ca-yfUfSH1rK z@Fu+lXf%6L!0#@i9-8Ea!PXSySU}8$ z3jdK!Y^dm$f`ijE7S+i6O~x4Uu<7-$Sn+hl_pJdpnk3fPEZA5nL9a%o`tha?mS7xB z9roB^O#uA>;f(B}L?sC6;mu2Ec2yz(-vT~H-FXRmjrnI~JT7_l4HBl2AgoJh1qdJe zK}ious&rtS!SAVr;q(0?B;)NiDVVY0E~i5HjxNx@HF`G0&NUpGIMQ| zQ^#fZP;ej)20Bcra8KVK=#sDr^SLgkEYRtN0>}BKG^GHe>AlYa{l7xDD7d_k3JGaA zZt~Be5GhHeB^ZTp{WaX>lttlRE61Kj;fQgGl93gIw@mwSK>R8LPgx++iy4li!yoz% z9vKwa@Kr)m8YwFwC4-if0ro6J$9VH$-&9;oRz?afAt@z^l#!K010ekES2j5i9I=j; z1U%K?{w$mSXa@&nUMXr#nv)bp5kNBuSGn`%be_?P8KNl~rh zsYhYdi25WcjJizxv!OA1D`@B#GXH0JiGLwbhJt4@94M2d2AHNkMbS%4&=i=^@h<^| z*^>yv9wh8Z!mh$39gokFngdLaP-W8?QX4h%{!)?MRHHi7xY(PNG*v!RkLvzfB4C>8 z=&kKRp{Sz>^NtkNqJVkl`&(lu@E&E_-IJuiYq*C$!(C2YYwWKj1*Q>67m-jH6bfLE zAd(spfZ_2EAQCk$OErEH{6vWSL3MVP>RW7fTk5IpCFo#Owe7apVJ!40Vi~Qo+v8{o zYFt6=Irk@=e)yix5*A;Rg9>Hj+rQ0V~>WDq3C2nFJtSloGmOJ zO`%#VsCL5{RB?is3XLB_0qcaE4^n)B`|`P=9zUY06YJ#0G8G(x9b-vRPoYf$ja2c% zjP^s5KqivgZLPPeY}ul;dpk~Zr;^^*%{wMj7 zh$DHjoZ3J+F;q#R;K7CKJ1JM4cb_Q~)3;{^wUy~F!B9>Q!t@}Fn=4_g{T+rw9j%pJ znOzaOew)r_@_V*Ft8T7HPbqY4TzM-zQ%p<@KiJXwM8q8B0j5^@GC`cI5R>F8akeem z+S<9@E!B|;)$coQcn`!P^*f7<4(&KJ!(#m@NkIwTcN-~ zg+qp8VQz7|%KLc613bPah`=XWx6agV5K=Ij53Xiq@LFZJFfK~G^R~m8b6g9%s^%3u z+1As-&L{*I{5sk@u4 zej+(_8(-xrfmy3;xV2aOvNUvyLc#W&Yg_>J_gI&(>g8ZEB2O?_fjhB^K5j2IuXRJ3 zvQ6bJ-|TMNdnSgdt+pj>EN?g%q&YYer4^hGdNM?Xq_rjWdRo1?R>#X;j=pUfq_`9NSJy1#SSN_f)3?-3&5nM&B^Ny_7RSARL+&yK zAB6+pK@KQ4*>BIs+_1@iT65Z{5a`BLstN^bt}akX++~#Zr1+KpjeG0vwI{D($XUmI z^5jXa!^MKk?P~>b9s33X-fg_|hx|T|#;A&2_Ug6#zV^i>>*i_9LDT|B)xIoXTE<{g z%;9@^TL&UgAh>U9M(?pR3N@h98b)b(1Vib(coPr(4#~6002s*))=mt700b?hboTDC z(gc`IB-^S#P|vh2F0y&fe7I|=hWo82nDvJ8oH`w;3AU!_+WY zkUbE8#V0iBO0r2fx1Cap?ou|$L^wYWDEniI9pXFCZJoPJiOa!|Z31_{DM`#LswlK} zR^^`$O?|jo{6hYeXSXm2D zOI(oP$_2ix=VIC{;$b7RahLofqkfmlytGWW0L~cw*CejQ2XP_KIDuJnJG&a~s`Qj) z=;pDobL-s$6){eKYR%?I#I(77TH@P!K;Gl#hmRi}3d?Q@D+nIQPLTiLN1pTabo%^6 zlbqutBYCykf<(<#^)(n@69ILd z#}3aqRw)^k%RS6XJM8v|&p+)kcUkhC(4<&rXH~BFG?ClP+H2kz-%+o=PjHPYjoDF= z99{PO5|gf4ZAJ^($A@%c>o15rrc|9e(Y)@*g?7j72v*%)9Jfj`U)aVPRd%uJx_YKJ z4kX_=!3X$*OOcvfs1T`t|im6&YbT)!%?O3&ev zyLK)5^>#)L19HB6(uPlVUf8RKYh^O#lKNlSHKEu0lY2<7Kk_M-oG9hvv+l1xR-bv` z==&XE*vU6J-il5$`o@?=1A;(;cNqD`23}IjmDnc&$7;w(sXKgJm1ZV zYLie^BmByf$kM~=XuMDn^SVP~Jvh^5sa?IXs6|DgcbTVlg1uct#k<-SP6h>a1nBFav>0U{YtVK-7tq{8}>i zK`3&cI%|6Sif$sQ?Co3o(BBb?Cw@2iExWXjX#wAhvrHTXD>#S=5wl|XTb}S{*`7Ah zKXXNY{k<2WW!o;*+yo2=rU5%6yZ6(mSGz)xGZB3(_x6)>tA<+ZJ9;juX`eH`o_X5>EGut);Lop0zQ65V_mMbDh2NL$y5LUCH0z@#a(cfYF-pWGvTv z#q2z{{ik2rq}w%bCH7)ch-dl+orSCohpdh^pH+s`B=g#Nb_o&r$!2B#MAb7zDQV$F zn>!i-(nSV!dSb;Y9-+f z!+MUbqy+X&BEUWgh|g1MxN)US>|W}<&hYDa36tk$nLeRXRpc^fmp8tdNX1fO132nr_M=zE_>mJyY=EUaLNyoguJf9F{Txbc&U9z;j3 zzI%BZa@Rd*Z%@F+T{SFsI^cOdP0IV%7Rk**)+=2CA&_iCtX@|l-yH3X&$CpIB{ayH zR+Jom<{knFxo{4E8OK6RL$Z6uCXqVz)~mf5254{Y=RkQ_%EvU@{*k*aCL;bWmtgBf zh5F!*>H%GO51WPQO*zMknqQ!}_Pn(H<5fo8EnspqrgEMdRA_%{zLL>*kilUeIe&2u zu_9)#ahStkqFdvvz9l4)XGtXz%s?xNwWVHF>r=!S@2lXvrjVVt-r%=F+w}PMtu-fE zqGEonPu@#B+r_L~Cd1=-JeTl`fuSLf{Qd*W6a?=8_^dB_p}+nxIx~=yKaSxp{BDtVNRHW%1oYyTdAuftX=d|c~xWZmJKJ;&_W_f7N!IKTt*%}r{WX; zTqNe}2V~DI;q4M>-7PHbaVzC5cVC7MN&jMcg}WcQi5x6&-lsMujKXB?Q>`&*HDAack%{wfd2*)J~eckLY(q3RcR zwnY=zt8y&x6y1=v1eUhs zQE;z53dIPbSc#fqPPLWBb@Rpivyv@2b0WM~V}dp3JIy&$!?N$XL2KO$(Yy`q5<7wA zQ+GuQXsR>w58lxUskUgo$uze`eS42hZtnSxHwWgjW4T2bPJfV=a>w5~*HCsMfn@#h za;%Z2B8E{Jxdq_!?E)F+1dW8HjxJpNrN!hAL3*u=v=7~vABw6L@wnVwmNig@z8iDp zqBR@hPui!s4X@i;E<89TCA4X_4C& zy2qIbi@jENR>ZIuJ9@I{epnmayt;peRTDb(;$60*3Z{rao`&PqR@)Q6Brdz}*xmZp zq{}KP6>x0W0FQdXn)Hp^RL}iNlf zzz$7K_>dqS=sxJ*_P`c>;w4We z^P=K76Ji;W_+01GDJMnD;pbjJyA3p=WfQf?>Zkbp6gnWSR>#kL)9m@xUjAGyrp=wl z)~{QO3rCmU^bbwC>h;b?c-Fwy1Z@4w>W$jbm^k+Q*A5((uK4IDDe}Es ziJiNu-kicD02`MHG+yqMP?&H=>Q1ygd4DaFJtmQN{brHypinK#YW!lS?rQFcEdrPu zIS)_r@~%x>&AD~0oqoak3eeUtz8g*Ea_C? zVu;g^Dm=<_18hJ<&y)9vt1b;x-6_I_O3@Q}4H}RAqx!bFaE$-I@-Ig5HEwH)}^bT@j!k~#8h`xKZe5+$=SM?oTwU(GOsFbk7XS43q-nKn@ zy4pt(Gi$HGJfK>nePwwXB>MeATBGK=YqV|1wye64^#NRh)`~!-oM^z5mFq3M5n8Os z{n!`8zC;+`G5q#{rRa?N6%965w*v$1I%;Uq@Cl8-h)q9NiQ_%W$FE+k3~oslAptbl zow%Ged*VX5F|qeEbM5a(+7h)N;?o0dj_!=MHL1tczj9xAGPGDBOkVM-@6s~}-*85J zx=v*2R!4|fi{wb>TI-0p#V#9!L{#>l-3O>r>@`~-oAMGvHNu<4< zV_zL3^BFeUcUsled9?^@nTk$q z(@kcA(!4}zIsYZ^4}y?Go27(79!pW{Zfstjq$5I(^>9|azk6iPN%ME*zevrBIu*HD zb`$Rgl~uSV4`Y&-i%`s;T-mDr+&oX7GS6QcY9$vyMBgRw#i{HUiV5Y4Ey6PCa`RNO zwG5xoxYo`_F5pzywXy&{uN8b{&#`}~hDN*ik@p_!)mKrcNRK%VRQUMV+!V`oD3*{c3`!E*&@4#-}UWp)q5g)U$oY1XSt=Iu0`2pEPj4;_JTyGd(IX> zr(B+|^GP(b6xd({?W)e-s-wfm>%7{6bFB^gN~^1e2C4#Q3wYRde>|DBVMBjwF1nV< zw|=G9pDP1mVq(rNZpi9Py20k%#^WvF(SAvQFT(ZR>9g|8Lk(Gj)-DbDRqHc8hTT{) zSbt-1jp-uu4lVr(Gxa#%`-+%flqDGv48040LO6D0i|TD~0|^3)B3N{*`YO8uPTpxW z%@r7G6PQcz?kfx2>GkpV+{l5~k!*%N53~cIyAr7Ee}|rnO=^g~8o@i*R5jT2E>d8q zJ3r8Su+H174c8Z2)f-zaFjy@Ru+H;?T6(xoQn4-iS~&Y!ToXe}JQ!ph5phq+$EAd} zVyA?o0|l+g?unJ{QRoVf7d#uK=fr68@bKgkpU9&#+OMqR+xYRfkU1gpov&K6f0;Wc zvisgjykd!a<)?`10|NbT9&g9!RJegVNB2WrwjOoPFtJ_Dla-a6CK_RJg)l#Hjp#Wn zm*CSI3XSMlbxg%B2}gTCkD(pabG==<8_hSl-<(IP^6X-JvazqR^$5Yk#N}mrrBwgJ ztp0~~LjzrNBL~~B5-@3s1-(bAx{sXYj%#J?l~1p-@zPrF-l7iywH`%tXva$mSHg9OPYBQoSsCRnvhK!J^IS3_y_y4hTOZOBYUH(*A0DK7l_VmJCX}@wD+7%pHQ2K?KL@BLw#8S zUOgwhUAvzQ^*^b;>fL+QS=P{+Tqd?lj&E;4DYMrf*sEQF<+q7-c>-(IdOz|5_nfm} zQJfXKt^{|6DDF;c4r^}6PN*jjmFmts$0s`qq3;(Hp@ccrr(gN; zL^Uz8ue`OrXy@FW8`|!%sX}J0L+jbBp0j9ldWeunIgw%!cfjUzWjtmteb>v(M8q(@!!J+k^~n{#<(9B9WzmPAY%RXwMRIw6ArQYR|7`ux+ns|rm$I@-r%&eIt+Tybm-XTNMFn&EhUbVf^Ma0N zRuv1d^Sf6F#bjSxviP|quIF0(v5SjV_?||nq34CWp1Sl{|Bg;1tM2N?&c;i{X-$@A zKE49s#m9#|^E`rA)KrtyeH6@mr4}EGTBsMpV=W|-_xeJ}a8T|xTNS!u?usSSjnDoB zJii!m#lu>s;QA*It0X)LQ=_UXiqqP)O@JG-Yq`>L@jZgIDi=|6J#V>!Rz!4H7qWY< z1>wXK4{WbJMn_3|2 z^0-2Dwbc@jCZ2{5>n;`PuOZ`;7dHZnk#smy?GM* z<;(Xd6qN3%N&qof%=r^`!nk5jmXb__ZpvWKGgjTYBew)W)3>tu7avlY+k7G*$&h@t zDklQ}%0_tffn{4Dr+$mklOtR9%vUVfej(LUAnB#8dxCAqDx7UYlLZtsi|T1`7NbMDOqpp;ux-t3&8@Dlw@OV-b!lrTSiGb}2y!cSm4P`vKhZx_>Q0Ymd8%%~ z8R7zqvw9$~DS9S8>%#zJg!U;8j5dQA%dI7GDnSbrF{jk7Y3bzg8Y-4N`rY8ua0IpR zRyZ?oJUdj3;uPjqUr!1p>6i#vH|yT;+&)uCr3!ES6n0i`FSy=! zW3z}zC`r4z{k=a~QAF;JZ;{dkR?%Zvsg=7Lz!0!JtIsQ?eg4x`D{-c?O5}YHDKr5z zt%?c_Q?&2fs25w-dCc|bDqO9-K}AD!V0c`!&TJ?P@iYgtvb}UdD|Jy_kFwKR_Mg83 ziD3^#46!A)?tg4houBwIHLjlIR^rc<{$~gT(q>)Pt(!=V>?mfz3IqhjmwReJ#%aYZJtL~SU=78 z|4_&!{}}Z6&eal3+nEUIdFqA?LLzrQERaveq=-IB-ViVxTICds-wqm$>Bf5!t-(aP z^amMND@SPeNC!sKt3}94!;kMTg;XAH{P;03o|Bi|w~5iiL_EtiSV-g=2oT+b$ZH

    B=42M# z$CYSYn^dL;&$q5J~b@#E>(b^g)= z+vjfeM*t1wXoX)@Xv|wLE@a6xV+M~7R11)7K+ZWcm~-0+1T`Fr4GV%|e|5SIhHYPB zukh2;K6YBpcTJ#M*Ey0jAm9E}39?t5+k5;JF*e+{9tsQMYL6AK^VI+kS*mh@a%Nc4 zz!Af13q#PJ?_xr^^%_2whD2iUz`sFxMOwiS+BJ+1FxQL zr@a~ApsksAkWCH%;c8}bR(#5vmVwF^wkMm0`X38b{LU?MqhbLF`z?5YI?B26*F}c6 z(NE4wtW^g(VxORN*ODhfSDtQSp)>^Ke>$0<-uR1L`4i zl?%P??IryB5*;!%pDatxdgUZr7uQk*Tsy3JV5pYP<~djOeY5(~vlc_fzWci&$VAQh zD3XQr=*|`3-`^IbEosW-o^aHbC;0cYtXDNr_>*q@2?Ke_YVw8yc|iX58fTM$k9NsP z5Rt-iSf~NA{aX`H-mzf{G3|k@yJ|LqOK$66SC)5oMb$t>6obj|T(;Nj;&Cs3(L}wi z=(?CJ88BLfmPMHAnEV=%u6bQiTtsmMH#2AyGRy-`X7$&uJK9gW;a<_&nmc#yPWg_# z$~R>+P^vY#XufEnw0+H)4`^7$p-a3_3Jbg3WA8wgJ$>^GTaaCfYRP8 zC>A8@$p%zLlPzKK#=h52*h4lAy6jn+z|#Q6UM9LPSRP;R6kW$zW@rN%D>gjm6Utq8 z8H5PJnU?^Yk|U$H_y&K3XXoqc%)Vyp?aMoj`O3r=tR#6SpZa?&lcHyDmp zpGWzAkk`cuH}q8v4YvBP^T4{)$yLb$k1KMKSBJKD((2!apF-!{7au{R;`a{LtX9@s zlMs37b8h?h$L;|4{8X$%#3TBAr#9KJaf1njQ}=yToOY=AC@e!l3>Mg0R^J=aO z2=QvabmUR{>>|5_{n~|ha;~Pu#^^UYv+CaV?*J*{Foa1#FXSbi63+_JW~G;h64Aj(TFJxMG7gX~Ma3ca2_$wH+9tJsV0lt3(k5fKYQw=+}y zLze9fyOoqCDnknP3J%qBbe(e)7<6S!w;U7L-Pr=d$iSh{b#AGwm}MV$>DJy9zV1W; z&4LFS8-`|7yXw~jT*jU*3%LA=?GDJ2yCOsl$hl9R%7Ma!8GhcqsdkmO&y&^z#DtqB zM!5CP{B4f9DgzT47><~>rp|XK>XR26-~WYGcai-`r-~xYF3n}Y-V=;fP~&Nc@Y-z~ zjkkRA9_a?sd)IR1FL5NYtPK+4wAgq4N-!x^z&fLLX?aNTM^PTp;@G?_V?~UwR(Jqe zJmW;xqCJ9HLY(h4p%d3tt(~*dN{wXQwk{%6%RZRlp*dwX7MR_OJ! zuEcTc6-S&%XBG9ua=zaVUD+-9roO&D%1hMyCg8XpZ)IR~SuY3YEzDi|^qPX2P|UM= zeBme3!VGMMVxIQ4w>OQx#%g$RkkmBJ z+)@H0ceM}%@^)QSVC88L4{Wt25DWOSh6;*Y4J{P zJHJp8Z~>ZTS04n;tlQO>r&nM#I6v0mS4B*oETb|C1jVJf-?w>@)qVMFegiCe(6$WiA4YD| z4Nxpe?mP-+P7eYfvnosF&e2^3*Ux|4h$Nri8nD$T8;`hC8IrU(^%qr;{CT#wPilT* z=S^oEg5d$rserXH1GO(>u5z;IhV3o$)D4^eK%AN5m3lS?o&HR&l^IHW@5zOa12-jm zE~E%G{M&$k{W$00L$xY#@@0I$HXkrm20%b%-dBX0UB_}bB*d>S0*V{*~J&Q`{I1Sw)JF|w!M4Ls?2 zlUFp}63~~03+F0YF~L_ z)C!!Gj$Mo{+k)cbOpeQqxMMCEqc>^+WmFH9ZiTtz zFC_|Ydq-D(T1G~r(fz1b*TG|3nFeCx&lKC)s~>@$K8S}SF=*Yhk25v2Z`#zwmp_vm zMt3$S39&w;r`*E)u$f_yVd376B2Q);z-mnyH@`FMu)VK$i9ZG@we1#KpmruHG3AkU8drt@o-blX z)D9za-&`#+D1Hl9ecQ_L5kSOsUvP6r>+EvibOy#R%isasCv(IHCHW_s92W$WYL`FX z{WrG*Vv*#6 zmk~8yI?}Ql53b*20T0I#oZJyQppur9TElrwJ9|ZbM@eBp5#Y}c>Syci`+Y5k$Wafh zkPL}TF8j0>V8St=5K3!bM!C|a{v++Zz3aP#AmbztQT;12GiN}j`Xp){LLOW$uRZjr ze6F`hhf>iWiayz^XJ#FjMKkqZ1G#i^s#f;LEH1wpzC=Xe%!h0(b@%$a_5;Z5UvtMe z!pkQv`x6Fngtc3l+=e(?xdz~m+i(-1^T-7+E88fBcPy_Gv2mw5?|`wtvv>X74TeL# zFRM0eb@RB*xpC%oF(%2SMlmN1;E)B zI!0;!!F8vk_gU;w6BEPTTp+) zEkhGjqnbi?eN3g<+5I4pL@2cl2|OECss^e6@7`O?!4c29>f-7~&|K60Uz2AES|n-h zy!l}dxZ-BBSvchi&yZg+T~}xLJYdZ6$9mkJ9rMwccQ6jjrMUhk{(VoaQj*O|GP6^U z2^%FDTB9C;Dze&+rnIiy^R+Qm29fM53{NXC>4Bj50aXhvj7+ZRcEEqvmo%}N&C$dE zO1P11wgnoS6sVRWv=M=|o}I;JZtgT=m@9XHbIF1Mz_NspcuPnSm$X~;CWJBYnFUN) z7LkM1V88`a6jHU39)2xt+PANCRDsw>ao-}NK?WwrWgN{RbE&Z2<_(BStj zK$@5QrDOjDBK&jv^OrvTP8HgB9y_`Fn#_E7y{(gEcW)zr!p4UE<>a}}fn72oe{RPq zaI?5PCHgC)-bR7Tq8{jW;rj0zI1e1o+~E6RdqT*c4`V_&lRzP1l3~qtv-jwh>kmxh zxtaXV1Gn8YJ%Gi^^k5SZW>fL4-bLyMPPnUHUw0J(%XxjkZe`C;%D34I2t3)aHeCa< z;btP>D8leG6+8f-GgIp%_)s7!-dx$-CIg0MrxBRTN#%udtQ<@{yaKBi>|#=Swf9Xc z>(XX}^5a!^nYIj@HM}QQi0`-Xkh*j0!NQ$lzPaXekLI^I3!Y5%VkU!8FX?gZI*O=% z8=kq(!f9=Qk~xn|a!7gi?hD1`js5HjM#C1>$vp` zLtO<-=uU-IF;&ez6wM!^iQ7%IN`A-A2qNQ$)lVVmBzWcOINYpJrG zt3V;94vCn_$+XftHMPg$8FRvw>}WRSrqWDP?j^z5(x4yd!lRm}va3@#W0%jzoSzj) zT(i$Vdi@aZ+SJvY-PP+pVapn=tL`~$Y+r8V9UF1|&d|OP+ZDVjrcYu9tW6jg99VSz zcn}@a@+YHT?4N2c?#-C{1XX?gP~sT|Uuu<@8;8t-WO8%ouAZiM3%y>kXqUOl&GVfH zkOU2B9@Am$LwRK0@yn-uyQQs%t&e9w2TFzo+<_2eZ*PCI{*Ce*X6h- zELaWb<3+KvGoq+iR7AJ-q<2P2eK~rYNm*gOfDkXJYhQbn!IzJby`{sx#-rExaG9uI#M~_Ig@cdK zzZ9Kq_-%%-03i56280~*x!!<39c6?Zb!+wZpC{h0$@jw~o>=U@5}s6`8I20bO?=19 zSH+1ut+uLm`P7>lloaO-B{IOEE)m?7k?rD*S@^y?0sH9jr=qT;w0fyKC)acz9^&Ux z$QLZTuHLpXdFH(LI@#MX`FZG$L`LJRXHHgGaq-3|uO%3hY?+j~y4ND|Umy2mU(DxQ z3D~6a$&61o_6x2!{79FR)wi*ggbzND+Zl*H6&Sc`r=i4!mSlsH{7gS`{Z2!WBLpR6 z#g4A(akG8fYU0~WZkbe_4`$Yl&e6MWC)s2^$F(}rgz4Pkem5DON8rg50ge*uv63L_ zw4k}d%LzMf@yWgqV1EA%yXyJ9z7ogz^qChAtzEH19o@U6 z&TZjwX7kJG<7hP@dcucFW zyZdqH?QNnK1LL&q{rgv;guPnnDOe{Hz6|NhB2_?Qg4g{_jTl(q-_zbrsI z!QRasC5PG{_rww=v+6&2B|XN0W>P(LEVifl`FN~19e+bi2d+8{s;c3lx?`McEBeg69^+w<4W#--LOvBSN}iioa9K>{63k!+x`4- zwWh+^vFrPMq0qFKY|uKMCF%_VKOPmIMGLMwo>a9}tvL2#+QkbtG+WPrZ7<3O>h}e{ zFE_iddk);3t*vBvpS9SZt+t%`y*=fKUQf!bl@@0ocfLNJq*_|`_V>WgfVVfjqJMqX z(>r*)J3r6%+$VNlFmi8!M?~>ZI~)_-aD8X&k$19GXBF*SB#^SkfHSv0{e8~KX|u9v z-8qcXw>g8?>ethLhQsQ*_xV5hXp%hNQ`7u#C{c76qT_JZF2kwb{u&M*P;1)S>;4=x(e`yV7kh zwuA@eBy7qjZ#0>?u&1(mzEY~iI0OFZrT3{syzm`I^o;yh;hiYn)rW(e^LaxTwXWdX ze=FYjr_DRRu9U)H*3F@%iIXtBXxlHZI$O6s(hUbe*pD$5d!Zzm1~{ zn?MHaLn58vr0RwkGWbXxN(+-O(=kZ7DsezRIXjzA<|{K+OvA{*irFRaJtbKyY63Ur zPw8%Dj{kdOf235jGPd{OsWcBIFnULasUBvzEf0;Qa`$er(un0K36;ux(byMw@~ef7 z!??6iyl)vc0oc0w`|b;0m3ReW@2Ks^f?#6;=-@bh8g&%SJFjiQW z6%pTy7(zT@EfBnvftDRh8oYKvZ(2rN_!E%(}FNf|+7D*1Nki>b%UG|(Kp$BE`dHu99>jOzM z$mh}H5Dy0-UYP+L?`2`@Vf@ASq0rCY_hICV2uQMuCOAreAMVDX?O$WYzz}FJQA^D7 zRt8&q*Hl>_)LQHPDc;oL;d?dxN@e<_)|}gR}^Hqj6;#fj~)1TJgN)Ae+L=ZGha}b%d=>b!Lq4%^vF@vabCW zW!Kc>VJ~IPU7E2%&!MVirl{rd?RlV~(Bryp!f>Kt!ENM7%EaIaTf&tQ{MPYKUKdS9#T zC6<@cv|gkghlMI5wR`Ptv&HvQ&i-K>8yPwOF!4Aro!>X5@%$ar7M!j&muF|rLkM1s ze5}ZwFna`-Ppm8-fL?r5DEYE%9&@cK3a~#YbzVU!!O$N2mc8UFOQOIaLE-RFiKnHB zbX0`>u!oDof|y6kVE;I^9MGDbf%OMq%EsI4ojvUFk9e_Z(l!=|JH7JHf9n0-xMXRc z^<)0xZQ#!cS-c`JJK=-K(96k}H``1K1XL}Iw{WpK?os3uQ|nKj7J|m%!F~zC z*ZD|ud};bP*f)`QY+saJP?51cCW25fFN^S3(h#w=LGaM4oVQic3eTB>Qn(#73|7ic zhpv~~^{_-?{@1tXtBI#fVhZzodlTguc0@naz=Kdyd&f+Pi0f6C3I24$`_@kfe+DQ{ z+%|mNn`%9>33#>=5?SK{J)fU8-rO8Y+YZ~RJN7||sM?J1b)`uCRbI`4xXPwk!4SM@ z7D$m`08$@<4cpb8gU#XeUw*})Lnc?q5<-jvC#D&<&xXv3?!4z4qxIbRbvNy-qmX;j zXSh`s*)Vip)_H{he+0%>0vh%G_N(zLDofzfgv8rw0Hd19L3QUNOZB8ojcK|m7EhQm zUeUfqiqU=uJE(R>U1IHD!-BE>l0{18E*~1nNU*xpx3Yg(`zNO9)ElFU@Ez)UF%{&0 zfA!w<1lx|z#ZIPjz9~(%)MYdsmsOdr{V)=R@0pk>uB^{*!~>}u!b@tQKE+>hN!%`e zJ?jBbUXPnokcH0=S&LAcg4X=rUMSv#pDS1WoXoERQW+7#8png5abwro+$V&Q>uJD- zvZ=7uKpLZmx$jDU2s^DW17p^${Gll;N_n*$&cgD|F7Ah5`bM%+$XEs_(wT!Z!DX7QdE%65z z{+O(MHv*s%BYnuSzjccQ5=w839D#SD1s?}>zC<@{_&y24?Q+{e%QthnnIErb)V%@B zzs&r1am7xmyE;jQoz3${P#i7aZmRumGz*my7}%$WiT$QtpU%(iJ0C0oslJs7s5vAZ zh#n=}m=vD7xPmunR)&Hh9q#cz+nIkcO>(3V$`G6!Mu}cmYnZMc{}3-Mh!095W8Qh=ri7CpAd}+% z737%udNbkYHc^UxXy$x<#zE~;vp@Ga0TppTD1vks$C#@4M6B@GJ#nYDLp4tzQZh-J z@44-$DC0ROTvuiY2|`C2;!Ejl2TI66HI>uq!Q?*TQxDee1nM=q^gobZ{Us<66tB!; z_RBS}6QDVYKMC>+ztIy->ur(NO9jM+dSHt|{qOAhsKNUxb!h@_6&ci4yErx=@rGNC zhn#A*9j^z}NypWywpM{hwyIcXJ0PY>MZb)9&)tO;YDe)tL?x|*j76rN7? zvFJDQ3!D6KW%yQ-kXqe0d=|dL9Ex$=%8%i#(b7xbZw$Qmb|i0h!Av7_|2mrNSOMqT z&b#|RRryJOhfq2;D%kQfYu4H9)W-j6rV$d2GMNaZO`*LDWJ1R+?_!Cc)qM>?Z(1JyUQ`>3 ze0eg<{0(bN*YEn#_r*~32f{zuL}gT8O+1HFiPwu5B8%U%_x+Wf7f5se(b62Mzd z#7B8AYmD2;UK=-+44b|EU1$}x4Jz=G=?hMXagg(w6@*dxY@2I0v`0zV%uoQbJB$n; z_x&x|m)2FSXHQWsyi-TkLL!OhdQQp+5@|{QIySFH&a_o=){VF}9jQGhN477wvWkT4^1R64;B^NCnB=UVvAo-W`20Azl8b6 z!FpH$SJNt-4-gq=Jz!J*L#!?K#Xcn9yO%`X`ADL1j7@|LF}%|deM)oXZznl9Yw-p%H;cNiCIgzzxbI#x8ZCP-lH%*Bwhie%$ zTi$1yt$l?x?Mk%aI-~obub)nN^U3@u9)f);Th*SFJgzn9MpglIrl>6vE%Hq3J z5okUC_=(wo+Q=)=ipKP}lSV#|vgLgpPcOFUDc3nK0xs2`--3~vePprBc#2P`UUz5Y zgXcRF92<&M3TDuG0|!E}^yw?aBvPcC4PVk{E;CuKa&PyJw?d>tURZn(nD+7nm>Gyh zCmK!Df(olFX{IaWk|jzCGxi7{Wa1w(aPINZlNa!XY#x_aV+9XsOb0GM2>alxJbeq}XDd zwuE^Ej_egHZC_Tm0LtAc=4|7g3T2LV_#ERUKer`hh8m6cGDNqo(E>b8$EB5T9;7_HjQ zww~D4C@;Q*1wIJZh=!%6x_KL|njXi8Nq&u9)A4XJ@60EO9zzecuPPm%aQ`ae8t9e( zaxu{MH_2=xetvej(ErDCQ`gH_0m^otY&ek_L!;X&cwon|{}kq~#i;ysC^!M=TVz7% z7{HNT_G7=gW%Duv4blB;!A3fD9nNo)@{BM*$t5UMVeLCDsy=c#^%0eIG};l?c4}TK2f!A zNIp>a{FD3(NSkW#|c_H%2bx z6hi}eY7pmekiqISarRVPe&}mko6imChQ#SrNtO@fwwY zP${!Lm3Qe$4J7oHKMx^Yp?)VqzheKCPy z%wr5(3`)?dRZp1!D?f3sx!&E$0;h(OLgHzS3;&jX=0kvUD?$T1S}^yzxr%33`o0!K zG-wc=@T9ubg^>&I`e|IgU1_)P2Pg9ultr%A&5SXEg5;S0u;~Mu)xk`1ZC2glM!2yi zP1##l1lVX7g##*l&`eLD%qbW*67X5^eb(zI?S&MBMY#@! z{hx3&BTFT%LK=ETBg}8MhaIx4UwGn&5Q?BUgWXH~R5e-^@=^TY=s8>(n*$KIlq0(S3$e`|PinVv41^e{mU{fER0xRz-W8=Ah!HE#8F)GS}%YnmXKv(8F zs-pA)bru02l-?l#*~3$$OJVB~d0dl;rQPg{5R3m=e~0I$`-bz#CIvmVnVG3Azv~In z=um>=qK6}EC)M-rGddC;;ot*#F5Wv8y3>E1PiJzdm1YCs&VJA0R+&!nQt3vCJIgJ# zE|R6B>&O9qam#HVOWX5On8dcZbAlNB>%-tPkKP?yV8Ls8-o`1k(k7m}gww$Pu>Hzw zzDwch>FH7ghAbz-(O@UZu{Qi5`zW?=^!7n+{Yk0e^Q9M^nG!W#P4 zp#;!edMah1@NNw51C3LIIg5_%9K?xWeQQncZcx(1)OW}h?ftWJ-B{pC;Zg2CXxg8v z@gCTOM*8vU+0Z^+{L>(T&%4+(?_bbD%bPOw)qIR|mEP%F(2Yz^xo()dd{(_0qHY{2 zDg1{?k5}e-v5Z18AvZ1dsInuZI&eXeT{ybcIQ()%_q(SAwKCWlIA<>WgC6Q{QC~iV zd1AmZGm{~$iPs%jNH|+;1R1$=2N<#p^(`~A@k{=p`%;LvuWK`;Vx20ON>O1cgRdM- zp>iLfkzeL59!q%jcYIB+Qn8d0Hc&<4?)E0#vI_FQ4@w8yyQSJdGIwYcW?cyq85RINSuf)9K zd|Bpr&t^{$;u;rn4B=n>pW=X}6+Sk)>LI2jGPr!5knZ*zaj;6K7}Yc2&t%8l`iYAb z@aq+v|IY+=m*)6{-YDugwEj}5Y)Y^3+0vdE0QoL5wnlLsy~jSssWi#lDh`Qx?4^GI z+ozIA)B!6$xgPMm&AmZYm$_h$@8eNV0D$7X*z5gHi<`>q`7Xm$^i=|n)lWv-DdsE; zPM!vXOL8sGUyiV+Gv1oM7>wOX?q6;pf@H1|&-Tup@9S_PbAX7t2WFJO->bgCBcG>N zI*;E;vXvLP4T^F%py+wY5IkH&Bv6VUP?W4EbW*d&22RXIA6OaddB94pG@@^7n!Rd} zNJ9<2C-Zy0_>8Ra4HEWK5|}ikSuYP1rOVW@ebUzi&|(>oHKiH=gC&cGMneJ>5-|1$ zTf`)!!x#fm{zVERk|+uQz=JW;Z)OZ;jTRy?Q%rMVtnc}(HEi+FGpdNA6YUC;$JG29 z&r$c`hQh2b^WY$mp;>=3d=Pb2Xr1WF^}st{ zPNDVqzDSOt(XiSGANcGc0-sUf%A%hJ>?rWn7XG|@CH>n@@RYVUgQTHz-Zn+r+ zLe4RQxO{!NHTv5JsP^WjInyoJG2Re+ zp2{=}E=8i{tnr~fP@V>*My(3UAML>1nG2K&#pf|>QHu{9X)1M2Xi~2vgGny^2&SN( z?B!LhWeR9)?xfh4Kdl1_)(xtD@`R|rL)eO+#y?rmADLs`D4Gc+J@zY{*&RyAf@=qJ zL@U#Y#hV;i**z#a`<1L9G^MSk+EP1a4h8TiQv#Y9>oos{U?=1%CWLh`ha5hjk%|iE z_^|l2BnBK^L*Tw-0N#affx<5c8=OwOT*gw&mdFr+-m z0{L0wDqWP4AbjMM$;xdnJOHOmxcaT&cuSIvcswnzm|3* zSN#hgn2ln=Hqmy!9WS*$b&Aw<{9nq8@gALXm7vsy!Nc7C5$hexC-xD%o)meg2C1$+ zwQ(}Cc_!be^Z5PJYlaz?w&6VigjGbE$|HDZTa<~&S@q8oQ~N*r_6zxiVm(gxC)@It z?>_<`{w=pWFy@>lAI}so&OE#*u@{p``_yDf|NL-c`l~8-37A*F)waR7ay$PjFG?xb znpxwWnIBduZge`p%5psG&wcB;h?KttXCeM4)reg!N3fB`WSxv9Y$6OmN&V;2d8EaZ zCq&@w)}Z**Lhwni%b9%EUVf}nKYg2KWr{5rx*tLxh@XeD{{bZ3{83Big9M6i9c_qc z@I$eN74JXRjpz7A%!D~u7PCs(<|+L|t!p4agh9dz$zsvw^l`Siap4wV2nZE-~aZ>o`?@j|g->DJhQhQ;~R2u98zp zlol-M!lx_&Xg+`qkfmBzZg{H0lXv%rt@3dGVY(_gu4R_WZvr7?Hie1i_lHD`f2eIY zWDTHox0UZ%!#vI(NH=2q8?(H8J)^N0o46u6mIy@_T`0(UP)0vN&VTb_(F z*PrA|(miu@bcy2n`OH1S+0`z%036a&#=&8yxdX)V@bTB@@o5%+$a;3=HdPY(&s?_B zSDF!BcS9A_yf&#-#7#~ed~pK9W%dgQc+|^S;Xmn4D?1;LKV^MTj>30KH2E2O&jRplU^sQtJ z;uB9L!IBp)sBd^@j8`N8u&~M}$VL7=DO!%9kOJaswSY2$Nlm$K zTMCLD=R-_r%JN@;dvFiUo$(?b;C}^{-Pugw11dXimp?QQf&!anK8OqTZulMer6zX8W!K@z_4%TzN{NTc zH}$7Z&$yZzwkrk18ON8>c8KYkPFuAkYmyt=FSGA{6O-BlSxevPO^e%3;l8^r*>($B zr^6HYX_VyKhMcelKLnt*9k0S+6J=kK|0BCx-O7h(Q+qCGLke3wxHKq&zWWC!oCi>E z)GYELi}tw~?<)bX(KGe#tBG&iLp!VhLFD2gcPDpG@Nq-u=+IOyO~WEcCj?3z5!2*8 zQ)BCAR8sob&iO@Zp%=>~3+XV#Md$rMr&)GM1eF>&)|RqDX1pslYSXfn%?{20yqb_` zL@<B7fU;2UuFz%k>6U9y5kRY zgfViry&zVU|1&{gd~mY)6-}le{ad~!l|MwkVLXdlH$g6Mf-z-Zrcnr2`IZ%cqFvjp zNnU4DASnM>hEWIg9Zlu#+)Rk|)XJ|20HPAt94GDR+*u@UVT_id<`rc+cV1GwM!)B# ziNofSeA_jpri-4Q2q@!fYsRp>J#f+E;T(E8R+Mt4JibT77TfHPp*(*P3r>$F+Jmd9 zvJMm4PEeF>8$=TvIr{g7^0cId*PX&!OMifHcSDMfMmKR&1P(mS{p4uhjj%NFg8{Kmc-<{}5 z_N*cm-Srl;W!MUcR=e?z4_{{I>Bm$ADd`nnxBPb#DYR2$!GrDq#H{q0r^9!`tUy{S z)gd1F?|OFT=QY2Bx1D=zC;1y}5-VJFbtmGWp~}9>YVicE^3d4m56R7%kHWEDu*yzo zJlgEVn83;?47;gb(t+29&+Cgurw$)HmAi+Mnp)Q9(TQ7+5ovBwGKm$+pH;P;l|ctv z!q7uvY(OoZiAC(C??7)46MpS)p+urUT(D@GtTlOF;?lGw`^{HM9`kUtwJ;G!zhC0F zpYC8Kf~5={3|TueKI_=?uM!r+iK@x{mwv(6o?%VpbM9zzO@o8A9a z zJdR%fo*SCG^!a$atX2I`<0vAfL8fGv{t>kY=?shhed-s2(rF-91ogqkg-@qW*2MKb z4AG{rL-sEP#l!0sdLI}RS0|8+uNwl5h<9oK=cMs9QY}MZEW@mx^aJ|#m&Eo>L+DQG z*IyTT?yYtGO4i1y3k=}xcC@MJ?+``+r=T`|Pu<+ii7H`Xpa^gslPOGT#Ak^6MbU5F zX@I=LO{qyQbJ7VH5*A)4oVnAAF!jq0!iX*5)H+QNs{!&^9KuHk4H_?QpbPdmyeQsE zEcW|s80_~;j1C{_Ly%tBW|1QhgJ|w)uF?AJX2j?lL*>pVk>ElWVC5TmI2(6^<1d3wva5Rk?=oY*U`RSjVv9TrcWc zu{vc;u3~vs$`@bZU!~fvs-qg0`TmVm1?|&)KSPCgA=jnX;BW2oPEt8Aw`7d13S99_eF{94uR743+LG$q{E?Z*k^e)?1 zrj+PS#c#iqqoLHpxVoRTP~tw*rTVRjJPvWIb^2~g7UCeh@1>}4yRTcBPVot;sPX;WT-}N1aq{>t)6xB!kqgWfGhGJ1|M;eILtHOi0!8Dft@aH8p>xwEj( zn|d@Fr=EjM2?2SumC+2l(rM0G|8wj2u7P`rid!x6@DO71$wq z?d6SADtnUoArsd}Gixxc^LWF#{Q{EFGW(a|MTnyHKYH>B#H3A67X39jEK2$8H@-BA zhVLi?4xj`P-KHQ~;F5t*lXbN8<#uJFm>OqD+Iq?qscWL`ymRF~rPDNlLG5zE2Nr$Y zRK{`5bUXEbqhFe3>L62eEy>D=(q|_7lge-pZyWLH4K~uLs56=Cq*O$S1#9pd>}~6s z7^AKRs1-Bk5pOL}D*&ZaH~r-uFGR7dk?ge~qiA<|Gi(gD8=XGl?MgE*r{1kXvDP{2 zpG5msa4U1?f#3ZnVj&@}$wJr6@#1PUpf#9Qe1U*%&bI-D+3Ois z$}_~^1f53jaVaN7M0VE;Y^2$bK{sNUOv3;UNxkTDnM%Sal6fb}8%qAs< zXW{d%x6T-IIpGPex~!*OrZqCf3Me%^JKJF2Lu#66ynW+432#+($&tz6&WC+cO2UGY zy29GfZH35vARaQHq&`?zR`V-a9-*l(abX5x1R+S)8%Gi+XX;GgOkg;k&pZo8FCPS+_A8iF;zR4%X@R&&DSJ)gocyq@Kz}{ngI&?eD2H^nH=K>9g{&aRfd{+XhH)r5eFTUUAte0%eUbFTtg12`$#z345}J^( zM&{L69ESluIBWXzcp?efVC)v&*~x$&nchxSrrGU@^fw@$l1&k?`O_a8IH62W&CeFz zz7&i;cKN~B^n{Xf{u>AtC7OFe{>-7wveEBL0^r>8e3I*Iv(r0_+}GxeU?HU3-s@&t zpz6K$*(=k4Vgw$j9X>$0y9n@WrsR?=S33wy2DySItxFdI;Tkzpa1a=fTzhK>-Kbgj z_hg5ndu$0HmAhvNOj}nlZqS2~W>K7Ki}-IZJPvY?Vv$MGq}UHL+5Yeka^&m#`joJ2 zvu~8yC}%yT3~$uIYq;%fACS`Cw!4@58NRaeEh18?!8aQghnC~EBJyI?eLJ2ljjKhj z5z+^0J{ViC)z!(SdOLIHBO0Em8t_$u4S!)wh((L5hhJQo5l4il`JWF5e zhW`fOv<9(ROw*L44@jv^=4wj^^|Z?%<{Q|6AY0!o^*~tkei^7ayI%@qCt{ze_;S!W zn!CgHd$3z!FqJY(hDn}Kwhd`C)kw%AZ5nH1Q#{#8)SCdSAwd`JRIal8Ic_D;R4jzwSuV1YibDSrSDL8OpAfBc)jK1a|+Vktii zrU?hDkg49@$^t3*ax_*xn}!gQ2}{V&4ZsgGg<=qIV~JmDgbBz5nyF-|+K?!P@`n^} zi6dA+A7IS=op?NOOJV3R_-6zK|NsPxtG-G!5@4!s8bg3@E63{ z4h{5%L82rR(OT&#iG(QvwRAte;8BCQ+8~)&>(=sf6Y#coC|G2Nf55QAygi#$q6Fqo zQGAbs%tPssD^NaGOr^oO6YkH-I$lwwzpYou-IzEO4uLg%zosCel>fn=H5L1crb*tvGabU{7fYZ}1I- z4ZDw44^aB8rWl(z6X$+vJx^#X8zQE-!>d_2GLwwPsWh55_WsvgY`!zl4PT!I)9Wn8 zmE6Nz@MiDxjs-!HRoGEX)?kiA+pG@94-?oFlZv`k(8f2OwVw2I8IaaCkSQYlMu{*p z-9=EK>1d9&%|MiuWd2y_NGPO-L)haje^2Ip`Uk{#3R8UC1s=!BV3mHiEOfnzzyUGu zWvR6xkWsaz@t{M4{!@eG)C<{6(^0-aHe?2(X=B7{5qSSl=kH6>fI*s^!{d75WK?DU zk+?0I1@gjP9W$G;AIT61cF~B#!Cuu3s5#fhZRzR45urc|mV>URGf@SP?1_4t8QVzg zx%x%7x%&48DmO0v$;wnrX7*d(ik?DX7Bm6nxEc#)GzdvXqQsIUlO~U^P{R_u#WZeU z4_aJZ{{IwUWiTfJ`k-N`m@?XnB|54nt|vJ1{Rd3+1xKa`%M`VxIUc8Se{IK~;)r(Y z7See6uQv}Ler{ajlhCJ^iY7u50L(71Dc^fYOT_GbpS{JjDX%8SqWf_F9;EVb72G(z zyblwBEO)*(dhJMl`=9I6g-@kp(Wf{Bu$H=ELrH!XiVerGs@298+JuWas)MEMk}UGv zKJNHCQGF&;l#QqE-pnf?wpNWqjs8!Db__FHu=MO`a0E-Z7{8w>_5F<5pH!$fLx zV=#%&oR1G|4gr16FgntVGg@s_NMntRYfEcwVF7lDA{zh?Ul)Ok3{14ieKcS`hKTPy zvDg=d80SdEosL~Ya&5Z|qr}$^rwV94XJ+*YnUE=R0PtXGAm<`N*yh}BmI@l``0~xN zKVVQO_Wf4fFiZLU8B)b5Eb;A{YAXNVjBcE%xFKO@NI375$BG^j`@*K*~ z#(e#B+3T|kg8co}p7cBib3srl+5PNe8M1Qyc4-KNsN0NC%vdG<>bKZR2Bi7#5{v&7 zcabr}j`4odGbt}gq#|p!u?}aEnn!UFQL#08&mFV=#Ejyr$urq!#&i^YOWjM)ajAA~ zm0E1mDUKnDLSWA5(W)w zbhNZwuRJ^qSK;FB{vs#8C%t=k@Z5iR@J&J)#7Oy^MS!xlXC^t18GQp-`;Dcpyp@s? z3LEep69qNI1_d4Xh6;Qrfe#7_S{B;>+k>i}_2mD)t3Lj?OqqI)f+CJ050lXRg1VQE zH3v7p=q~pdD_V$AkPiz7>xYs;h;rWlNMv^3)BinPeQ%j>{~?hdVUbiNZ4=8J%b*|) z;gFlDz42{I+V3_`Nw&7isIN_S70ujAw%T87@VOA#5S`NV$%iwVX@XFt#R*l>d1SKO zx;(d|!u=SsFu`b~s9FdQMlc$%sVa%C8JkETK5qyd2726&|Nn8nKM%G)LyQAD--iWz z7Nr!6``Z&0*AWSfz6U$UO-Z{j6e8 zqzU0Q@4_9gG?#VV`!SV*N5%Jj(f46K&7}{rKBma^S}}=paK3kE;Ft(F=j6D`Q)p`p zshFA};+axu-kkzmH+iAaQy=H7pR4&*?VL-5&1g<=?URvQb~I5&RRx<y(c>lgXC-iOJ^CB9p>btMPdT^)Bu~0m`pw2}Y3Kq6TYz>wjx(G+d`Gladdb zZie6-`jc~CRw9EH+y+x#f2z-9qu&4Relk$rd`~&@_OvEk+y$^UOSfz@2P)dmR5?Fb z++uI$$9f2@4_J7n&Ut0v3BIt&VLl6S)X~|LajK~I^>-{{7N%LvW({;SDRB}TlaY<{ zu*z2<&nJ%91OtbU!c`ey%^{*K#ZiQY3ix68wS>-8HMya&Hel<5gzXO%{V>>pRU zBG(r@4_=FSoN{M+9fwUd$kgcSwW`;o!qoekQi{-F9*LJNATA2qG)1<;CYYXR8)J)I8;M!Qj~~Drq`< z%mN0yS(0A=BLahlhx?mShTW<1%xULtY6rFnU{rPs-WP_vKDS@So4h@%0fVLN&;OdW ze4zEcHTBNxPvWZeRjcW_zd86&TdG@`^9~{4^kH=y^y&_xQ*Q5f(iZpoxQ~4hFwBST z$x=Jns`*c|)0RGqP2LUx_dT(UcsA;na(e649oBj(OXtEMQWyqdNu?@M6U$BF0CZOWBn*DNqO|7(sv4wxvFMcOS> zcs%{nOs`Mvpv37DX}X}tC;TVf8$z#Dq}l6rGRQwkghVR>-V>`oMOx1m*&rH~l74+> z>0Lhg4?5@pGQgCL=+LPQM@NICuTO@>$QYI;*Q()M8tVu8)m~S}c{=4rd`?<*l}&2s zl0kmje8HP$tFx*-gwk^gtWah3%y2d}GGg`Y!^Y+3s%q$MU;Ws|Dhvs!qk(k{dyeY; zTXsKg%Z~*0|BOF+1T0_iRRUFM%6i4TC)(&B{|fr7@K^RauBm04MXQ|2&)+N( z(p97KaU>kl9e%Dd`qG79R09rX!fXjRJD>ePb!-Q*$f}cI)tb2zZDwUA%X zml)q{7v$O-mnd@9cbxZltVHrdUz;9z?vPH)h!Y=IM;6dHmFbv-4w+Nx=I!f|Yd7Rl+D`U!k0&R+7~Bz!GX4JkH#^%J5Nk zN^GNi8VD~2B~v5wU$AORRN*n_J5EDp582o%Z$NjPn-||`u_ZS#BCzq(%%cRlep=i7 zDN4ASYQEPxwevneMWeJoMw##uVG`Tzjb}|Y4nFf~JS|(S_)@9Y{5}@q_uZluZ9K=v zyE^c;;L7orfa^fBPDus!DU!j@`J0M#Zx=R)LPeb!3AF-&<)BX(dM1N^@|T;O-NF@F z)ehaJ7x502E?1n>mBi`e(Zdwh!ZOe|xVq~nwMLB|MRMMC{x9OZ*(2>sLw)I*E96SI;Mq#_psAVGC(^O?*BW`>$By;`vZ|_oVDk42q{w2})`8pATGH&A zz#{K6xD=1&rzL-k850sxa#E&J<@Z``5f^}it~;ymdLH@Udpau1$4ZQZouh~#Hs6K& z5;6;ZIW%cMY6sK$T$=u?qFLlV5eD4vz^E*(LlMq8+dZ)SCd5h@UGol_9~Ry|94qpk zR1Xil(6dS+wVc+38w;svDh1s&)qv|1%=YRd;nZrM^gH6_p!dCzKkQN?&88EGCvSd? zT{;R??)LTHoF5y06xcr)^I6qVGXlR4P&%{Nl2;@OQqJ{CEK|X^R5UJl8zeliQ}%0! zNa3VKx6Ua$+ZQys7ssp^$L0io)$eQY{9CI^Yr6AB`sW!84AC|Avbr|6&5>5k(szG` zO*iX*GGv8oeh8LC=Zi4YWo{avA451IPh&nXFQ!4b61RfgU2;(PBbrAG^~UXIEXk@X zO{FwsQvN!`>G6DCP2*tXx%Zk%P7;gmG2rfTH+lZGz32?{edbdUIfG{tW-0750&c&%{3Uky+D3s| z?!axO`5;YP_{6)!$?jgFnmAakVwj{jUxaj>L}I0W3P1l-qLRPB%6BoN4nKKWn8{7! zMclz5ZtPhyTs{Eu%wG9=R-d4q){NiT7< zh?S_Enuen}MwGypi@H2jVaxr2Oa8M=}Oij3ayiX zj*;@ne)g}|D~gzmFvja2ud%aM=q(OFT)|-#16{pW6>LW&qAb|I>)gq-=n(rc?0wDz zC3RqkTGxP7yucn{yz@@$F!YGK;aq+`SePe8RgHYDQ#N0` z?DOwwQj0umx8 zF&NR^*XgIc=Dm@(StmUTOia{dv2d7gu=0+k$$Q%!mB%ppN&f3_o{2mj<*OdiSC^yw zWc(7pjZO?u5EP`HPT zx-Ek$enEl-+#F)6^ZohR zJpa~Jw?0Td6Yj_w<+J)%v|0!X110zdLOvc^__RJ2(P9#-&KYW=Mj+fHvyC%qk~rL+ z;WY-mTzcY~2=!Hoch&r9&0`f`0V!p)EVNe9c;`aa@2<%ZdJ|wm)VB|0YW#y8L_>)t zk?Z|qqNKe0B-)(Ni(hVAail7>00jXKa`WfA84CVm!e|hWcEPq`9|2wnB z(Ff{m855;y6Oh3Y8eLHDb;*A*!l66IRLE-=JX#(nO zv@qW?*13f;!p;SE74D|u&&Fhii>2J)HM6Z1df%M?n0tD~{ZKKiMq-0iMlfN= zeMrDmw-O~ZV3}lSg~iqNjl$ekA=e~f3l^sw~$Rw?AC?uA5YLTqm$w7xg^E4if#D zr+d2*Rfp3@{W)zTL3EXuD3X=ek2zQP1rLm+dcMcW#3ow0h=>-|K%V<;Z27mv6ws>x zKTOhM1*b~#3oX{u`_OWA6pQbHJazgM)wGf?*!%`t*>Xfr0toyV)u&RIY zT=xSF(hQH4vm{IJhIz1b7#;2w8?4g&X+M2zOXJmHJAUfuu&{X)k@04Am1$!s)dx^q zL}c4^efp}uc946oxxewve0~wn?AA5Ugq;yNBq! z@K<;Pde1b76gX)Soj->}BJULCm+!I6f)|*=2S^>lnd_8omugRUtl1O<6$_y{44uy- zEqNp7$%Q5tmH6i^+{M~eY6I}SJL?Jne|5n(@y2 zMX#6}jr%I0EYY2!OI^tUyQsOW?XdSCsOOqV@{>3gjo{eijLb!6`F1E(AK@BhmD+lj zlboNnJSyr~YDdT>W^p{@**awRXo@8@5$b&Zdymgr>TFv(Okvj4T50y@&Ig)!-NZox+PN}y2h8r7VBDuRO#|I-1A?tmKZUraWe!{ zD1osRGasl@qhOzU}!l&s-Ubk%9#^70g zaV~~~sUMnbu24+K8vtzM?H!a*ARk3XCY9g^>jkhV?OsJE?f^OyIT?S2b3(uOw*feu z75EdMR~JALnj|))rhp02-!k-Y3uVKzqJ-Z5OdS!k)c?P>4!W z_(TYV8uZ~pjeN>5w^Y8icgi9Cf0+dgvTJTG#pF4z411XF*}IF_%LiTB9apXP78f<+ zPFc!>4I~Wk5qzU!G^A|hB%gn7bbL|E)8sD%qp3+{xlKIVo%*t+s00_Tj54PKf6X7O-LW{Y>{Ou zLTei-$25tlA9u!1B%X!j8q<8EK>yEt5$XDSC1pq^x%5VNhV*p04Ipn(9-s z79oQCYMamDUkREb-!r-li(KfA%>mE{6X(g8t&Ok>c|cZE#;4)q++IUGEsp7$N!Ik${Xm=9|iz=$X3QAm^&ew%gz%aps9+$rLGL zp1~Zsuez}Zt9e?G02C5&qODIsJ%3}3knQ`7&%#WX9k#lw^YQiG#Uhk1wH zCf(EIl=rvc5RDi0tqx6=JooZ?83IJAP6*yLz7_lvjIp=FggU{D5>4Fryw=?;#i+9C zYcG!9N=yG;^mCJOVv0$wb{(4Rm|);IR{h5zD(eMP{fE_hB-X?n-Ylb=iX8+goQq?& zVvO7f^3E@*5J-sEW;E(05+J)*(Y@5Kd2d>(+MvQh^e&*rX1uGaK-Q)ZSLDT2q>C$S zN{Y`uJ=&6Qy_?AwRlz?*#B`!gcV|9MvX`Gp;7pi@r#gh_bo8=&ZQB zDV*w%ZU44rH&`&TMGwUGb#qGjWBgoMr;<|h1uAM^M6U`7S|!p>0T8&z$^U&6%^jpT`{FbJHplX9ju_bVo(a7K<@ufyOHE4n7Qq zMrJ7L(=nl-r`>VbyhgW@ta6^SFLT6>LXO`tf;>`xs;@ZkCKLIH`zi9Ezo3UZA(&q8 zkG7~^3r{bpu@r)rI7my8%KE_L%(({rld52CRLto#C69{ACP&YT(9GFv7C#+&{)hn1+=lA)Tl7 z9bZ0;+lDI<23vV2wSBPNx~d3|V3{NnA=CY|H}j|AMOP%1&S^1x0SEFU+Zfb)TdZBG zV3SG5XJ&(c70%+1;qT+IVewQJ>tnf5qdl{xhv&x9WT&v3!s!om`81%o>Mvvs>Z*ym zyxPc2Z@gHTCF~@5<6jO2rPgppwx-20%Fei#CG;RJB_66^!RVhGWB!$K#XZwv;QqM} zRcQ0iPJ`zGy@oeT!{#sZ7{(eWtVp2-b=(Pq)a#cGi1+d>y;}f~&&coFx1q3wuD1}% zi5~ZBM_jIy$PxX$IYTA7J>CY;yQyv7bBg{uJNhr=L{sJ)xv49!JjZf3R9ki~oL&Wk z(A6oiPcqv2LqL=F&CG|X!OVl(X=H>}j{fSpF1vzT;B7@U1T4-bt4hi}nO`J6|FWVH zc0xTz*omd3q+{S5?0VeGD)gcG?vrzB$g-!4@s--pNu2@|6d!p>_XVto^FdZy@%(d; zr-HUHVW!r4`-MU5G7fT!)USVRnkCUXjyU-WR6Fl_zB?V|hVmn^a)LxCbu~|S`p3?q zf@Vply?%~vd=+k$XiHqpI9++dvrl2Sg_otOV_;Q!Ug!7!2uWJsS34*%FAF^cLWp7p}u>!FDQwr{w4Zffsa&5%N2zIovu_TzM=;_wZu35 zkA6Y{?wB5{KXOnH_fyuZN)LB4bBZpUCK9x`Whw*0x@TrjWHlw^Gd*PcZW-c(jNST5 zKy`eQ8EU8I-n3@uaue3UYit_Y8CUOv#be9pR;L~ynlvAX%R@{g=I+A zyIgZ}sAv+ydXz!>LahHPNukLqSjVU`-*~<<7s3pYLo&bojgV{!YLaJ~m?|@zmE)JC zvS5_`fk0~~wo!6)ESMYM+kmgyq&*N9!me-gkO4#c zT$Kb=+yk2?gbRh=lFZ36Gu8%z5}!*m7`}0!rN0#ERH&|xU+%Bo6Yj{gb_F-Sh=y+A zskz9-*l8DA`NRfY6cKf@Oy3XlIlT3E3QHsjHdd!!jJHRrtlPUP;O?`^eF=Y=pu)fK zB{%l|l<(kdL<*lo^8P+AWq`d;avk=a7boXisgC*Q1c(Kzb*A@E`Y^GBj()8t{w#?n zstuJ0WQO72h!>TDX%~yWi?LSDLp18OoZ2}X?nrc=_wwwkt;(~LrRnU5PeyfrON~#5 z*9X)8@LDI5V<)~cBbhnxR&9G}Tpnb}{rXZ}eCh3J-Tq>+K!*^gBi24u!X|x-NOJjd zvNW6D%ulk_Z|divB%LmBFQsEeW*)l}7IzQRY^!mzh>KTDz6n43bUS}^n*ElX!*AbIx(uTps;UQhIxS{@RMy+ z%FmO>xRX~JJBz?Ct1dizwll_3Ows4wBi%2O>s;GLwL7jdp<-$gA~rF@Q}E+v*IWUM zUaFJmR6FMbF*R)KmBN_ty;jE$Z$Iy@_3?)L#c$)e} zu#;^xr=@N&8>W_Lgf&UI`&zf<%<}DL#SIlW7%`BFQ1Q;g+pegyly~r!B;d*|U|#+m zNra5bP|iI~y^yR}SIe2$_Pi56HoL9tb}LRb6PtQqM>Caa;gwG5Lzw=P3B$%mTFR(c zX1dkJ!WmCCbE8v~iQZDaD^3*9d|pximZJJ9C*tjza{8D^+I+_G8wEkEEcu3zSakPs z05PfSmh^A?Im~B-$&rIKfpt-k%xxM#mVbEm-QqKWxJEA?de2O@JY%a4n8;O2*l>mn zgEA40p0*n|i$e=hzzx>%4xt`Us+wEyy>emHQncDD%ulHr6IM=XCgbn$^@{Gi$gZK6 zI65H^muM$Vc>6_Fb!8v9h%a`c*OnR{@h>az`Aip^GG9}LcZfcW#O80Ag4IgwQv6-% z((=khz)oQB#e8&*7TN>z}F_&<7`auEQVgneu0Jm z>nTZ!Er-{%dE$zzb|Pc z_L!M^@1wwIvgDl(g?YNO%1XUD32+)&@&j-GYu|^POb*(!>RrB6;+x}suD#1n=D5N3 z?MeVXF?fB>&(t^W;wUGGh_@5S7qE_9j%TXi)d=9y=}!-ac)H!EZYf?G^m}-GR;qu6yxqLKLD&aJurVo`PBi zTXTBQ3f>MGLd-OFUGkZv?#pvegIh<0P>BQckVtP)l*_t7T$%;~J+L7EfI+8lc#{2x zOb@bOv58r6cR2`o^qMF%u8%!+4E9oj%{@EQ_r6}qIftvxscZ%<2xyd#HlTxNPZbLZ z&sb_fxH+5AW>}$1ENZ>f=-k|nK+vMni5aTb;wn4S|T7*A6oi4bD-5+u&5iop;sQnHDtoG26`s z@H92VSW`Q0>_n!cOTvtOqdHZvX;IunE-Mi|N#&Mgo3Bm$I>cD16FXdl#>N0aqt*!% zU?VMM*DXRwBA2zDE_%C+6EDY9hgl?X)V>X_^mjQoiawjh0FT3NQ4uo#KE?ig&1V_q zGWOG9)x0@?TE>D*qY3I|&Rk4dnOiiEC=c4U;bgRl)bJ&v>8ateQOy4&fq+ zh-5}ofRh1Mh!p}hZ%zxec|Z9=^?g=#3v{&zYE-e-5<41ZZ;p~cP_{D6Cc>bIfV%Kk zYS^Gj5k=p*H@Z1vWCJdh*!{YoynOQkHT0i9g zR!N{qYjsFM*>pp5Wuy7Hejf%Ht}m+~w;A-?T;MIwn}pz`(A!IcLcf5u@Wf#Wxx4GL z$WsZPIAhy)wT|g7C>)`cF3M145MZEJQv(}e`l#F9&=b;o zhn%va(SfVzf=}9$`lMjkPrNRs@_0XkAm2&4mHdonhTn#|t!K^VMWJv~?)L(HzTq*| zW$gBk#IM8B7&_Y+X$MQY%jiRm*~?RoX99v56iQ0K-00H%JVq&6R_Flxr&WuVW(;tD#U5aS>L0FIP@}eAQEQyM{OxzNO!i1S)a;e*KR9j zH9&qR!E%|PCW^g

    6Z`_+{8?1B@H%YdP%(7_CGmCl6K+id9EI=PO@jD>J48ybd&T zqu(J_QGVgve^T3#I(NJP0v)J)si*}!13y&JtEd8Oi5DLeGZ-zOx)i)sw5c0MPXLit zh?)kd4GwGVon*%LQKVg-IhW{kswGb_p4U9LOZ;jrrwo}x!2KnEJ(J*-AWdi{M4=)t z2Pffa2ofs5*=o2qe%(jrG-;qSSj0;5Ny4I;7XkhR*%Sp{Iwf`@ExjZtCY%NY$&9@Y zOrT^z5}qo_Ej=F!0GMx2Mc{2Gzrr;+#w6uVm3jz6zezW|A7$7%KsfMX6B@rSxm65J z3p?-pDW8|g_lLM9Fu3*<;P_PkXtX^dw;LR%35LD5IVZ!hp?i>xjeC{=hKR*TY{@^7 zK*_}zqjhO-Hz0kHEIbB~vIZx^RxmnilR|yt=rn(`u|U;9(6G5%aZ@QtXH~wG1NXeK zt%+k#v!fMGEJ3k&i(7or%NA|KnycOix)gR8>)L09x2wC=!$0dg(*-|bb7ad~K-J5* zs0HX3=-l}=BzoJZ6eu7nLYS&FzPHZBay%kd6Bq5*LThjh`~7u*+V|qpZ7w9cj2x{Q zE5lo7t773764Sm zb+NINdp3Gu|3Ml@*x!@(ME$L(ss84XB-68KpcVTp>$k8@m3gjQ?{CbVXqM@}XTNqC z#C41UdNB8Csy?-WV~=7zuxP{#yejr)Yis*4p&GaO!dT9X6{mw3rt*g6Mk4LES2!#Z zn0n}snMbFwqE}!Y+CKr-3#LQ}9{$##Ov#hy&qVQo-0T%9W4lXLZN*5;96rt>&@GkANS+tkO-f~{`QNT%>i@Yr~n^3b1g5IFeU7$oh4fffgVtxo1=(W zwBcsDA`WWUt?Dna45Ce7Wk^&P#cX|}uB5w+L9a`_&4`C~<&;6pkAJmv%efU!)wO5} zxoUl58ienQ*+F?*ut^$rz=QcOCmUw$vBm6(+G~oueKqxzQs`I_QhSzq`}E-z=}T=J z0MKxuwoNz2#;g!b7I4j@XB9Sj?v5RD=oUZn4zc=*NGXJb)+H`0Xw}J!M^p9(fEnKJ zEjIfO?dzW5g7F(zn~YVH{4GDyioZR4fxej`JIaJ9afX~<-d?;WlzMON-MN* zAu?FSvPWE{QT#_B>R$8&{3m2aY6_(7U>MQSN^6@61yy6tA^Um?x0s6}(7*4jNxRjJ z4}&V)4!LxyCwU*9XSo$*!S*7X?oM?m||(pYKr+N z*&cl`nr!T`x*B>ogWsd5rq-GnCat_Z13+F@^E?E{ZF=HMp(Zc-Y5+=dFu$nctM|B%BsU(1?gkH$2d((CvqN$&CU~Du zcXQ5$HC0=P0kka#TXIq;HhG+p4+?>5ov-!4cT>Hly8RKP>GU$TU){4Q%wP((aB(Oa zIqfRL$%x}*N%Gzn>90uR2Yl&kVli^tDXg}N+s+S(Ds8vDVJlsm0M8v<_f)-=Rt9?8 zxEkrgOGX0KzRgFgC&5SX#4jmv#gFzfK8<&Y*8!6 zOO_6sIs7o`!Q7qHn`Hj$4T^Lzt|}?d9qV(nIWA!f8!`}r$nw2EySmF$XHs({3MPw( zD7NBt6t&PyoWil{LEXyp*|g{urSDH4Hh@vt!$eb8+ zbWjOb$Zwj4c0bZ}NTB;&fu<9|d; zNw7u`lYT;TViOpgIG{Amyks2Z|7P(`l2u_})KvMVf_Xy(%;woAipyk_n&$seN@p zTvDnn15K7u2|E3GS^APz*`n}QItRPELw3D!%s)N2LvNT>rLh$Wux2I(j;Atxl8qpyM0-vvD*Wn?*kSZ?-aij3Da}}`C!KR*&!(wYIfxOBO943cm7$B( z&*3#eJ zm3-TMT-NW_JlrF+HfHS@$j+}9n7C9UUU~Pp;gg}lag|UDIVCI2kdKsTD*#a6XYs%7 z%vZ!a1>C3VG94lQQ;-e$6MKKZVpgS46s#+BRtP#)&b|?eO`9TdB$u2)h%jY}s8=5U zqE~fk9ClnfZPJssI-2$gFigI}=o%)>_2DMC&aYEA=$y`{>$zs^dQYQFq!9F!du%ve zXzJ$`odX*t{l^Gq(G}DBghB!fbG>p>n>^q&pSsv3U-7)R$!66ea|(iDs;bi47=5A{ zftIgJ#W#~-3}S;R;}9!<)?yau35Tze%jbE3qYlM&80 zRoyl~A<|I#&Rlp4^QyopgXbQ6^dpZ~cAn1@)5-VfurqWi!+&{{3oA$lKa*@NOP39b z+AH)84L{$Qth4weOU`tIb^hC`dpMne3qko%*hiGqKaae-_Zo3gG4UQi-&|kkX)+eD zsB{T2J8%&sTtP1|eekq$?&oMm7StU3q;Q{)0$mx$aZaXL#_Y`;--mlXQ^ENOXn>Ni zTLLQEtd4Yak^?%L8Uh|1_Xa1Eu9RQ%R>}|MIf>lFZo7<1xyP|eqeW7H6zW0`5Ffcp z;h?EIfcD&cBQ*@CK=TKyLy0#>53TDUILUa%7kwbq#EVtWxEvTW<|L%wryRsK;m4$i zPsImaqd&<)+Upjcs(*dUkBjLq4uTNA4xn+0ZmTFG!bMx19wo-&0gWLGW?9>!4+Li+ zvIaYVU|=zWF`Zdd8-glNB271dd08fR7}D}%-0~l(zE^ft$n-EP&2%3ITGmZ=XVeeUqZbys!?{Bu0j?XH8x<3k4aetplmU~ zQx`r?8UFlC$`SAW0Eh}KUFsapO_QUv!hO8}qU)>|?ZFceWUb66@urh1#D^3QoqOW_ zfl}Z6-%9i9rYeP?fP*cSTe?frLx!`wcRy^yy7DqHLQzN=VS~fMC*Mjz*^=8mjL`$w zzd&1#m*)R8IrgvH>09_NonBA9X`y0Z$nR1Wx;q_r;Kv%fsT;n{+BltO=;Z2-qY3a| z_JI-Be-aRQOXD(foW0B0eCzV-Me}x1vAygQ$H_QMM|3ELS5+sL{G_AZ#`4cU2PCLy z@ZXpzab{a&?$HO~np_`i2%NUA9|N$)A4k$pkN^#4NNamlN3fq|9}hH{z*IXVU$*0sOO^Yp+~5Awt8ozyqZIS$l#hQ=)6Wh$AX zKV58kV(765i{AYxk{Gpexedbj!{tJWI>pdQX;^6%%;l;jy^S+a|CuOdo)9zOA6A3t zrED{hXw>8&V5?XRl^qX2tA8aRNGv^V#eU;Qmq@bDcVbLc`v67kBmxQspV0DfP%&Eb zQx&Y4-69wjYT`U=np41_m}Q|4AWoS<3Qo8eVy7X2YK&hOc@&^q2U0~8uBYdD7|nBj zCZvljw;D|O`sb}O=iZgX9Dq0fd_`FH*05}?Yw(*Svlt)}p#33|Td>%zpoE-*@A^5; zH%xo_v-ng>QoIyZ*FseGY(5avi_a2ze2s0u=nkY+?~0DE+i1aNmQS>NVZ~n>tmT4% z>ZK8gf&X)A3b`u;h?10mS}9IB4yg-(H-i96-o8?1)RrHr?%~h;r-Pyuj!gRqDP0QLs9 ztc-X#Mj25ONHXVxWT;6M&m z>of~h=T~(`=q}1bhemMFy>t+cH8f&h6@2K#nKg1{A_v;>#q3ESjSafjzPCr+vxwJc zo1^XL@gCcS`Or7IMZ#`(Y-jz^>^ao~d}vK<>Lu9xaf+|BnI8zUhVFs9jPFscp_Ce6 zTJ-)o1f3Xq1Rx|1`l5YRM!o4L2cls!-@Nx2!ZYpG`VxLxr7HWL?My{e8VN2y>HHGv zfvS!&?%KwQ->d_Z_w&BNc!?fws+Wo|az+#aWJJtIf zoWgL17;H4Kx`7NP?2Qk1NFjsLTHhw0KV3_-KTBAR@X<;)K@ZazLQfVY6D;vI$g?Nf z$QYQxjOQbpN4a$Li{7>t)bb)G%Jf-UP68hVL^5&1CpaK17|C?CQ_IECpyhDaVUejc z=PrtM!0BIjIC^*i`qmyPbX5drEr-NgF{rvR2}Db&B0HLbx9b_f@ge0798kx#m_Ht& z^Q3-TAYU#F(TW{ZM|?)EA@UoL(XCRTNqZx75k3gC*$5g@}S8!y>S#1hY&WcIXT*INxsG&IrCWc=2I z_Z&>fb6WzFfH5<4c6=(vC3=bU6fp&Q6u|BH&~&pNRUF<|uQhazMxzE-sAjrQ{pVk8=0+ zQM&72@Tm9L)=~ZMSAWJV<-Qg!|L2eD->R^dGyzw8+6v0ow%>`B-?Sc1*#UUg>$d-_ zcSwRdc7K^` zGgnvnfq0S_0^EO}0a)i!CxB`r1*w=sN@?#iz(*iGlO^#)h@WLg@ax_8k_;)pye?Fz zUO7G*oBr?V!r@^6OTP0wY_v$Lc&@2RQ0Q@h?&xTyzB%P0SXWE~*P|-T8|695s=$e8 z(sTsUl$+nqR{zswTTq}bj%QX0`-r3g#ss4Qa~S^WP%-Pt-3L_ zo(tfP<}+!?nS4&K1lj8!N8VLZY z9zWqG2^17!?#KTHKn^GyDWvj+*dA5+hh%8}7^$a{|E>ENEVLN-h!9$G^fTZ3-)>epi7?X#*o$FQY)Xy-qe-(FmVx5#GZqS&z`&a z?mV@$HJZBQ-uQ7as081ElNz>@Q=r%sRvUqq#N1LF$v| zd$Xx*T1DTV;*dUy-@&prOSPeZAH&2)D^c%`qPCkXGqke>G~H2emP1u>If0X4DSQsL zVTy-=zt3mvfW+*7y14Fms{8kiP7f)2W_PkPGE!Dq$2l^xvmPrH8QCP`WF9GGl@(cK zg|aC#J9}h=5{U;LD&hy8}_F8tdfEJDN#!- zr?=sp<25mKwq~#j{_?>_>taQZ*z1P-H{QocxJKNE>)H3orQT(e7OqYdgyFi$3ym;j}&)Iei_1RGG=ujkwE?| zImN*9jLEyXfV=Zy_qfvY79wN9(0Pw-)~0KBE_i*@eGM&+$Nd(uNLb2Nw*~_Nut&(0 zNDQ|nsLXK~6T;AnTLY?njs+PG5^c-HqdGQ?8D19ANh>bTKnvt^Ar0&BlN#^63<`CY4S}AajiR%IgZv+~tq2 z3xo{#8$=i38){2O#<-xg*r9(1Ptsv1SL000v>XbyWrGY)$t3*bf%w}Auhogc_v%oq zd}(*A@aY{$j(VSV=07Zt$011Hv|_mwon23J-O^|6<0Y+!o^|pm&V?NN`Reb{;?L5` zV%RR(%8~quing>-BSV)RR`;#`{HTHl*_p1zKb&FcxLFD%brq&z(Bq1*xQ`5gY`*eb z{ud*Z2Q8k!Ado8dZ{5T_z3Neq#QdiW(TU6@QlKVHyXf|aen-w27NbQ49Ub~2tnZX< z8q%UDwy2f#s8O>79T{c&7`QFmjG*D>sy&$n>VG099)iQ{PGNz^ax#pe0yOqp;2|_X z8FdK5SH1U-pFG8)_AwjnOY=QslNEpM%Hc@zeKOK?Hj#DBlt-Cn(VwDjxXKYV#Oqfj zRl^y)%%N9j&6_bQF+2pfR5q4GbAQUUzE8xmVPX}OSBuXdh)K$?mZ|bCar$GrJ?5Z; zDD_7%n-yCL?%cjX>YJlgC@|z zy`3r9b{$X7RkkXjw^f}RwCAOX;hCh^s1FajmGZ9-VN0z=b0dYn7(4|eXX<^cHIIvo zK+s{oY=AtQ4Rn*6^!KZbUY_sK_L2%ScPw&n?v{TM*c>^TY##2AM5`YOE(kjtA3NEh zgF8Y1*}Q5Bdca@jBvt5hQmwP=wq3va70oH|*&6L@M z+NbP6Vv}sw+%K50E_~+qj<4kgZ#w~58 zdxZXq{(Gpp^eCcEeBJiXgA#x?8fC+QkO`FN$|x2x(4#A*e-65eu5)jz!1-8y2eJ|G z=&bFrsRoSZf=7xE9=|idu!Wv+o$Uwd!;sOpLAH;i{}?2b!?ETp&y zrYkZm7I*M_aPv3k_g6TW@G-Q0APVn;Smvsm758FzvOqPG`ZVV`79V|#*@Cc#s;+)F zeRvfg$c==FC2x(8bk8bb8z%cDMyeNT0WE;PqA3`NgG9FUhL_I5Yr;87GzuF^q4sc7 z4W}x?-T~5zZ8VLZvU+zNMI^;94;M@+IJ1ua-hLHqs+nlqz4wV*o5?Z0o;y|i`#KB} z-@bfw;At+hfqRkxoGhMRs6kt^sp<9_PdY4>`a>I2G zw%;4&ZzKmH{WZzFBN@u%bwft{J@t@TlD1w^vo~dH;@^H4dK5pnB_sX~QkK@y??Z%r z5HT20Cg)7-Yh5WvaAhRzKzBYbO9J0zAw4jlxc#_f>l_?mr!VLo7JqSOZC*!x=Gg$! z?lk>cmtEJcl0JuD)gEs6SruOGiY|)Cj{n+|l7`TTaYHDo%&UJrVsdKC2XffQ+|W;e zI4$MbINY5z=R^3dV<+|vt|=y+GuZUvD#S^Jq(uGx*LTKVM{(N_QO7<7=yWDD=bKox zQVs1B1^6=c(vV_|?X6O}aIbrhg7s z_W(_+K*pG@0E7<$v#SbY83oJ)J+EE7Jtp##RNWeticM|CJg1E24Kx#qE9)ozhF4Yb zXbzBw-_c%yKgZoE?~z zjrdYA=eKoDRY}fmBBn++GyU`XWV$Bt+e+bxi%(d~)WyVU<*0hUAGU7SaoYDVe1DW`8E=u&!N1d;tde1KP9m zXH!t5`kS5ZYa=fc{Gp{^LY)3Tf06>PI6hLD=C_4729g9A=<)NB7YW*ECYSl~RGMLb z=7k{HNA)?F=9R3T@kv{rsjqffz}-Lm(ZTJO8MtHm>$LxX@JEbNsP@NpskOlky}{IZ zP-;{&@ggPXOsW6oVpWo8l3pAZBGN}CYj{0XZ#<#;sxqRc;)L$FU1LWDsq6h4w^V}2 ztSj~;mU*|T@uum~FZMQ<%#Aq{S30-s)-*$F1+y5cSvev7{omA~&Y`n^R4IsHR zV28}P>&KVIzX)Knw1}^^r(oJ$+X-r!MVQ37fI#&Q5Gc!nN6@MGprixk5Dq)yBaPf( zfI=>`gpcDT=Huzm9%LiXbd_W=JL1IDR?kDuW$}cRl?v8HQ)b-vtQzlnx9U@ePeO#s ziJveT@mN2~?QLd4%$cUT+-aI@W9j*nO!H$VRcva$gFDt8Ci)oC;0gKlh8q#5PTL}` zWq`kSTeunYj-cieYR=quFXcH8mSHQCrWJMs+4(SrUNE1^D&9WRPy-+Dr)L`(c4ZZm z#OIN@On=A#A^|kPT^dGRfvB>pgn=B~NlHrRG`qaIljGjkF>IwP@m|v44pz-9>~-r+ z_g8Ely$dQ|JI$d??j@mM>i$(}I$d(juu^u}(8L6OhVT0?mtFz$AqxoHMc=35zis&= zx{zw-6sn>afbFNb;t)JmK0bC7|NXQ925Rm?9LBC5rV7R^!12NXAXWqndx)Pnx^R1J zWX>>TJg#mRuH;h~AV|Az>EAA+y^tN5C~oy>zv)2$?w?Ed6ul*o=l4(6i$Fyvv8Mte zn-~ug8rWo^Mo^?+>v(XiM=!f81Az;8Y~T-_b6rjOXqOAyXnu2Wg0faVDk^k`3k zbUS`=Vib$l$yE5*a6s&lA>XcFfBV}0g;oN$*s>wq3AaamatFgUdpgO-yS5&(UzCBF zgY%s7K5x`yM%s#iwl~Thd>f>Jr4i?2rlkvdF-m=Djs&4P&5j(0IJbM=(DGBoJcEeC;CQ?Pk zMI3A7R{UUIR2`I{d&LRG>o{vqWy`Bv|}lFaq9&U*oL zvut~sPclvbeZ*4L!>dduI2lcuJ5qz9h+e3p{TD02FWiU{;5zS&k>7wyBee%L!l+0~fem`! z)cc|6YLamLTo*5iS}H3I_3zIHnex7+j(`eU1m(nN68YBXt5jcBBnmWY@deXC<2U$K z;Ly`AQW(Nx9gL=xup7P5gZb9TH0T+oBD3#6!b{&5GI0{*y2`FsW<$sLtqFgOs%;WN zNo6#n{Z%2cAsDHf+P+|!$~q=|mF392VZBun%NhBO0wR+5r+8WOa7w1)XN*>klFH?C z=fGz#FK{rno5_REk#rg+18SlZ0||Bp1kC0Y%XAjLzS(A(W-kR>TJ7r$Dot$mQ ze3GumA7~>PYxQ6eGb;hgC-LYVh`mBH>dSsS;(+vkboPAt{Jm0m}n-ya>C96eh? za>6EiR_-vi+zY%*MqXLXiaqF}=DCBh5+1@oHgy$LC7O|+Vzt&Z?J5x2e=fNKot=l8 z7BR6N16j(+-=6HkA(sbf`d+SKm-AiYxE}v`s_j{qj5Ozhjq)HFvvhZwH9O_M7&;si z+>)2*yeU34627(`rsNMIN$yl-7CMPi1T^L+7Y27EoQM`@oj>uD_pF1v=yeg}D!#+0 zcMWC23@2s{)O$2jmI%5-{lm&ifw{|Bc~krtlJ=ELiRXWtS{yft z0v{nS3ueEacF~aIF>cJ^CNS?*FS>rhuiQ|))Tz^GaXChQbZ^;bFBEFhgW54U2nuu? z6r`fWZ3+{`VjwCO5Fd}tC9@SRfWl2@;f35q6>}LwjY1@c&)D-U@yJ0AF4Ce%K%V#mWr#VyEpBJLgr)t$LWK2WLq=N>^!u9!7|!6*$`6LHw1SEf z(@SjAcN>I=2}UeSu8f=AEQF=G5C^TZ*4t%B@p6UY;K~x8_C-@^r+0{-rUphwtyIPO G{{H|kNPn*Y literal 0 HcmV?d00001 diff --git a/docs/modules/appendix/steering_motion_model_main.rst b/docs/modules/appendix/steering_motion_model_main.rst new file mode 100644 index 0000000000..6e444b7909 --- /dev/null +++ b/docs/modules/appendix/steering_motion_model_main.rst @@ -0,0 +1,97 @@ + +Steering Motion Model +----------------------- + +Turning radius calculation by steering motion model +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The turning Radius represents the radius of the circle when the robot turns, as shown in the diagram below. + +.. image:: steering_motion_model/steering_model.png + +When the steering angle is tilted by :math:`\delta`, +the turning radius :math:`R` can be calculated using the following equation, +based on the geometric relationship between the wheelbase (WB), +which is the distance between the rear wheel center and the front wheel center, +and the assumption that the turning radius circle passes through the center of +the rear wheels in the diagram above. + +:math:`R = \frac{WB}{tan\delta}` + +The curvature :math:`\kappa` is the reciprocal of the turning radius: + +:math:`\kappa = \frac{tan\delta}{WB}` + +In the diagram above, the angular difference :math:`\Delta \theta` in the vehicle’s heading between two points on the turning radius :math:`R` +is the same as the angle of the vector connecting the two points from the center of the turn. + +From the formula for the length of an arc and the radius, + +:math:`\Delta \theta = \frac{s}{R}` + +Here, :math:`s` is the distance between two points on the turning radius. + +So, yaw rate :math:`\omega` can be calculated as follows. + +:math:`\omega = \frac{v}{R}` + +and + +:math:`\omega = v\kappa` + +here, :math:`v` is the velocity of the vehicle. + + +Turning radius calculation by 2 consecutive positions of the robot trajectory +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +In this section, we will derive the formula for the turning radius from 2 consecutive positions of the robot trajectory. + +.. image:: steering_motion_model/turning_radius_calc1.png + +As shown in the upper diagram above, the robot moves from a point at time :math:`t` to a point at time :math:`t+1`. +Each point is represented by a 2D position :math:`(x_t, y_t)` and an orientation :math:`\theta_t`. + +The distance between the two points is :math:`d = \sqrt{(x_{t+1} - x_t)^2 + (y_{t+1} - y_t)^2}`. + +The angle between the two vectors from the turning center to the two points is :math:`\theta = \theta_{t+1} - \theta_t`. +Here, by drawing a perpendicular line from the center of the turning radius +to a straight line of length :math:`d` connecting two points, +the following equation can be derived from the resulting right triangle. + +:math:`sin\frac{\theta}{2} = \frac{d}{2R}` + +So, the turning radius :math:`R` can be calculated as follows. + +:math:`R = \frac{d}{2sin\frac{\theta}{2}}` + +The curvature :math:`\kappa` is the reciprocal of the turning radius. +So, the curvature can be calculated as follows. + +:math:`\kappa = \frac{2sin\frac{\theta}{2}}{d}` + +Target speed by maximum steering speed +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +If the maximum steering speed is given as :math:`\dot{\delta}_{max}`, +the maximum curvature change rate :math:`\dot{\kappa}_{max}` can be calculated as follows: + +:math:`\dot{\kappa}_{max} = \frac{tan\dot{\delta}_{max}}{WB}` + +From the curvature calculation by 2 consecutive positions of the robot trajectory, + +the maximum curvature change rate :math:`\dot{\kappa}_{max}` can be calculated as follows: + +:math:`\dot{\kappa}_{max} = \frac{\kappa_{t+1}-\kappa_{t}}{\Delta t}` + +If we can assume that the vehicle will not exceed the maximum curvature change rate, + +the target minimum velocity :math:`v_{min}` can be calculated as follows: + +:math:`v_{min} = \frac{d_{t+1}+d_{t}}{\Delta t} = \frac{d_{t+1}+d_{t}}{(\kappa_{t+1}-\kappa_{t})}\frac{tan\dot{\delta}_{max}}{WB}` + + +References: +~~~~~~~~~~~ + +- `Vehicle Dynamics and Control `_ From e26d5cb99aed3d282508cc18457feb7a7b8ca18f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 17 Sep 2024 21:13:36 +0900 Subject: [PATCH 785/940] Bump pytest from 8.3.2 to 8.3.3 in /requirements (#1077) Bumps [pytest](https://github.com/pytest-dev/pytest) from 8.3.2 to 8.3.3. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/8.3.2...8.3.3) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index c614c4e96a..6bbe33e378 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 2.1.1 scipy == 1.14.1 matplotlib == 3.9.2 cvxpy == 1.5.3 -pytest == 8.3.2 # For unit test +pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.2 # For unit test ruff == 0.6.4 # For unit test From 3e178598d467b65154fb1b409ac9fab8339957b3 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 18 Sep 2024 21:55:03 +0900 Subject: [PATCH 786/940] Bump ruff from 0.6.4 to 0.6.5 in /requirements (#1078) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.6.4 to 0.6.5. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.6.4...0.6.5) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 6bbe33e378..f149183e96 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.2 # For unit test -ruff == 0.6.4 # For unit test +ruff == 0.6.5 # For unit test From 660646a361162b9c286d5182558775eda5207ebe Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 24 Sep 2024 06:19:38 -0700 Subject: [PATCH 787/940] Bump ruff from 0.6.5 to 0.6.7 in /requirements (#1080) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.6.5 to 0.6.7. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.6.5...0.6.7) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f149183e96..453922eb8c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.2 # For unit test -ruff == 0.6.5 # For unit test +ruff == 0.6.7 # For unit test From fafae87236eaf95785f5566e35fe9d6ba2fa3701 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 1 Oct 2024 20:51:46 +0900 Subject: [PATCH 788/940] Bump ruff from 0.6.7 to 0.6.8 in /requirements (#1081) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.6.7 to 0.6.8. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.6.7...0.6.8) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 453922eb8c..83f9bc438f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.2 # For unit test -ruff == 0.6.7 # For unit test +ruff == 0.6.8 # For unit test From 857a80febf8aef959d7df441f8948fe073e790d5 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 8 Oct 2024 21:05:58 +0900 Subject: [PATCH 789/940] Bump numpy from 2.1.1 to 2.1.2 in /requirements (#1083) Bumps [numpy](https://github.com/numpy/numpy) from 2.1.1 to 2.1.2. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v2.1.1...v2.1.2) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 83f9bc438f..e006f944ff 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 2.1.1 +numpy == 2.1.2 scipy == 1.14.1 matplotlib == 3.9.2 cvxpy == 1.5.3 From a791c79da200435cb89d707320e106c10ca5b6db Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 8 Oct 2024 21:37:36 +0900 Subject: [PATCH 790/940] Bump ruff from 0.6.8 to 0.6.9 in /requirements (#1082) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.6.8 to 0.6.9. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.6.8...0.6.9) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e006f944ff..62f9bc183a 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.11.2 # For unit test -ruff == 0.6.8 # For unit test +ruff == 0.6.9 # For unit test From 4d009a7916bffa53d2747cc6100180a3521e376c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Oct 2024 12:48:45 +0900 Subject: [PATCH 791/940] Bump mypy from 1.11.2 to 1.12.0 in /requirements (#1084) Bumps [mypy](https://github.com/python/mypy) from 1.11.2 to 1.12.0. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.11.2...v1.12.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 62f9bc183a..cbab816c8a 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.9.2 cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test -mypy == 1.11.2 # For unit test +mypy == 1.12.0 # For unit test ruff == 0.6.9 # For unit test From 74e9dcc0921f8128488b449901812b1b51e54bad Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 22 Oct 2024 22:01:11 +0900 Subject: [PATCH 792/940] Bump ruff from 0.6.9 to 0.7.0 in /requirements (#1088) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.6.9 to 0.7.0. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.6.9...0.7.0) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index cbab816c8a..f275d9d82e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.12.0 # For unit test -ruff == 0.6.9 # For unit test +ruff == 0.7.0 # For unit test From 899f749f33637159be3515264705ca7fe2d8609e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 22 Oct 2024 22:24:33 +0900 Subject: [PATCH 793/940] Bump mypy from 1.12.0 to 1.12.1 in /requirements (#1089) Bumps [mypy](https://github.com/python/mypy) from 1.12.0 to 1.12.1. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.12.0...v1.12.1) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f275d9d82e..0b44092a15 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.9.2 cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test -mypy == 1.12.0 # For unit test +mypy == 1.12.1 # For unit test ruff == 0.7.0 # For unit test From 9ecc98d3e6af70865d902a88b5d96dffd4764b7c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 30 Oct 2024 23:27:05 +0900 Subject: [PATCH 794/940] Bump mypy from 1.12.1 to 1.13.0 in /requirements (#1093) Bumps [mypy](https://github.com/python/mypy) from 1.12.1 to 1.13.0. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.12.1...v1.13.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 0b44092a15..92ffcf3a74 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.9.2 cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test -mypy == 1.12.1 # For unit test +mypy == 1.13.0 # For unit test ruff == 0.7.0 # For unit test From 41fea75c0ee0cfb6a1c24307f0e0c1f1bb0af133 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 31 Oct 2024 21:32:30 +0900 Subject: [PATCH 795/940] Bump ruff from 0.7.0 to 0.7.1 in /requirements (#1092) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.7.0 to 0.7.1. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.7.0...0.7.1) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 92ffcf3a74..9fd97ba106 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.13.0 # For unit test -ruff == 0.7.0 # For unit test +ruff == 0.7.1 # For unit test From 7c5959c5f2d0dbde7889870fc0056491577a5653 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 5 Nov 2024 21:01:38 +0900 Subject: [PATCH 796/940] Bump numpy from 2.1.2 to 2.1.3 in /requirements (#1095) Bumps [numpy](https://github.com/numpy/numpy) from 2.1.2 to 2.1.3. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v2.1.2...v2.1.3) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 9fd97ba106..38a0aed0f8 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 2.1.2 +numpy == 2.1.3 scipy == 1.14.1 matplotlib == 3.9.2 cvxpy == 1.5.3 From 5d8326957bcb40d62076e2920f5d61290f658fe6 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 13 Nov 2024 21:44:25 +0900 Subject: [PATCH 797/940] Bump ruff from 0.7.1 to 0.7.3 in /requirements (#1097) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.7.1 to 0.7.3. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.7.1...0.7.3) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 38a0aed0f8..21c9c64364 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.13.0 # For unit test -ruff == 0.7.1 # For unit test +ruff == 0.7.3 # For unit test From 3f87bd4cfc9b8cc5a6e3c97dcfd113f020023801 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 19 Nov 2024 07:40:59 +0900 Subject: [PATCH 798/940] Bump ruff from 0.7.3 to 0.7.4 in /requirements (#1099) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.7.3 to 0.7.4. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.7.3...0.7.4) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 21c9c64364..d3d3627d5c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.3 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.13.0 # For unit test -ruff == 0.7.3 # For unit test +ruff == 0.7.4 # For unit test From 0f91e58ca3d3e67bdbc592105140791efa6b2dbc Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 4 Dec 2024 08:25:12 +0900 Subject: [PATCH 799/940] Bump pytest from 8.3.3 to 8.3.4 in /requirements (#1102) Bumps [pytest](https://github.com/pytest-dev/pytest) from 8.3.3 to 8.3.4. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/8.3.3...8.3.4) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index d3d3627d5c..44875f28d6 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 2.1.3 scipy == 1.14.1 matplotlib == 3.9.2 cvxpy == 1.5.3 -pytest == 8.3.3 # For unit test +pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.13.0 # For unit test ruff == 0.7.4 # For unit test From 455542d7178565517ac751a025e103d5ff11ced0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 4 Dec 2024 15:36:51 +0900 Subject: [PATCH 800/940] Bump ruff from 0.7.4 to 0.8.1 in /requirements (#1103) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.7.4 to 0.8.1. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.7.4...0.8.1) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 44875f28d6..a224af5d40 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.13.0 # For unit test -ruff == 0.7.4 # For unit test +ruff == 0.8.1 # For unit test From 115b32d2feb03bd96b52efeb2403dfb272c5e703 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Fri, 6 Dec 2024 08:31:54 +0900 Subject: [PATCH 801/940] Bump matplotlib from 3.9.2 to 3.9.3 in /requirements (#1101) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.9.2 to 3.9.3. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.9.2...v3.9.3) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a224af5d40..91566508d6 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 2.1.3 scipy == 1.14.1 -matplotlib == 3.9.2 +matplotlib == 3.9.3 cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test From f86eecec7fa851fcc52aeb09a7c58b4c3c0110d0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 10 Dec 2024 06:46:52 +0900 Subject: [PATCH 802/940] Bump numpy from 2.1.3 to 2.2.0 in /requirements (#1106) Bumps [numpy](https://github.com/numpy/numpy) from 2.1.3 to 2.2.0. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v2.1.3...v2.2.0) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 91566508d6..a99ed51781 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 2.1.3 +numpy == 2.2.0 scipy == 1.14.1 matplotlib == 3.9.3 cvxpy == 1.5.3 From 4ebe7543ffac5f4eb40bceedec14f11703cc6a1f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 10 Dec 2024 13:17:18 +0900 Subject: [PATCH 803/940] Bump ruff from 0.8.1 to 0.8.2 in /requirements (#1105) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.8.1 to 0.8.2. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.8.1...0.8.2) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a99ed51781..dbc555e0c9 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.13.0 # For unit test -ruff == 0.8.1 # For unit test +ruff == 0.8.2 # For unit test From 0d8cd9bb6cca5697a3cd3f1b279e4cd8a27d3cb7 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 17 Dec 2024 09:32:02 +0900 Subject: [PATCH 804/940] Bump matplotlib from 3.9.3 to 3.10.0 in /requirements (#1107) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.9.3 to 3.10.0. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.9.3...v3.10.0) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index dbc555e0c9..650e7a4048 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 2.2.0 scipy == 1.14.1 -matplotlib == 3.9.3 +matplotlib == 3.10.0 cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test From e5eea35ee4a03082cd5acf5efea208d677df0a0a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 17 Dec 2024 09:37:51 +0900 Subject: [PATCH 805/940] Bump ruff from 0.8.2 to 0.8.3 in /requirements (#1108) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.8.2 to 0.8.3. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.8.2...0.8.3) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 650e7a4048..cd4a01f88f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.13.0 # For unit test -ruff == 0.8.2 # For unit test +ruff == 0.8.3 # For unit test From 4bc70480448295205fceb28053d0ed9c5efca99d Mon Sep 17 00:00:00 2001 From: Weipu Shan Date: Fri, 20 Dec 2024 20:32:57 +0800 Subject: [PATCH 806/940] fix: arm_obstacle_navigation calc_heuristic_map node through 4 corners error (#1034) * fix: arm_obstacle_navigation calc_heuristic_map node through 4 corners error * style: remove trailing whitespace --- .../arm_obstacle_navigation/arm_obstacle_navigation.py | 8 ++++---- .../arm_obstacle_navigation_2.py | 10 +++++----- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py index 75b1f9d2c4..e377897e54 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py @@ -203,10 +203,10 @@ def calc_heuristic_map(M, goal_node): for i in range(heuristic_map.shape[0]): for j in range(heuristic_map.shape[1]): heuristic_map[i, j] = min(heuristic_map[i, j], - i + 1 + heuristic_map[M - 1, j], - M - i + heuristic_map[0, j], - j + 1 + heuristic_map[i, M - 1], - M - j + heuristic_map[i, 0] + M - i - 1 + heuristic_map[M - 1, j], + i + heuristic_map[0, j], + M - j - 1 + heuristic_map[i, M - 1], + j + heuristic_map[i, 0] ) return heuristic_map diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py index 591cd401eb..10f4615c34 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py @@ -105,7 +105,7 @@ def get_occupancy_grid(arm, obstacles): Args: arm: An instance of NLinkArm obstacles: A list of obstacles, with each obstacle defined as a list - of xy coordinates and a radius. + of xy coordinates and a radius. Returns: Occupancy grid in joint space @@ -234,10 +234,10 @@ def calc_heuristic_map(M, goal_node): for i in range(heuristic_map.shape[0]): for j in range(heuristic_map.shape[1]): heuristic_map[i, j] = min(heuristic_map[i, j], - i + 1 + heuristic_map[M - 1, j], - M - i + heuristic_map[0, j], - j + 1 + heuristic_map[i, M - 1], - M - j + heuristic_map[i, 0] + M - i - 1 + heuristic_map[M - 1, j], + i + heuristic_map[0, j], + M - j - 1 + heuristic_map[i, M - 1], + j + heuristic_map[i, 0] ) return heuristic_map From 1f4214012a612f2163b01930444d83712d99b5f9 Mon Sep 17 00:00:00 2001 From: Aryaz Eghbali <64126826+AryazE@users.noreply.github.com> Date: Fri, 20 Dec 2024 14:00:49 +0100 Subject: [PATCH 807/940] Performance improvement (#1075) --- PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py b/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py index 8968c54dcc..7e93caa8fb 100644 --- a/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py +++ b/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py @@ -64,7 +64,7 @@ def transform( is_visited = np.zeros_like(transform_matrix, dtype=bool) is_visited[src[0], src[1]] = True traversal_queue = [src] - calculated = [(src[0] - 1) * n_cols + src[1]] + calculated = set([(src[0] - 1) * n_cols + src[1]]) def is_valid_neighbor(g_i, g_j): return 0 <= g_i < n_rows and 0 <= g_j < n_cols \ @@ -86,7 +86,7 @@ def is_valid_neighbor(g_i, g_j): if not is_visited[ni][nj] \ and ((ni - 1) * n_cols + nj) not in calculated: traversal_queue.append((ni, nj)) - calculated.append((ni - 1) * n_cols + nj) + calculated.add((ni - 1) * n_cols + nj) return transform_matrix From af456c70b0ec336442b0b32c5aab1a220aefaf74 Mon Sep 17 00:00:00 2001 From: Surabhi Gupta <103124390+SurabhiGupta17@users.noreply.github.com> Date: Fri, 20 Dec 2024 18:42:31 +0530 Subject: [PATCH 808/940] Implement Catmull-Rom Spline with test and documentation (#1085) --- .../blending_functions.py | 34 ++++++ .../catmull_rom_spline_path.py | 86 +++++++++++++++ .../catmull_rom_spline/blending_functions.png | Bin 0 -> 41129 bytes .../catmull_rom_path_planning.png | Bin 0 -> 33505 bytes .../catmull_rom_spline_main.rst | 103 ++++++++++++++++++ tests/test_catmull_rom_spline.py | 16 +++ 6 files changed, 239 insertions(+) create mode 100644 PathPlanning/Catmull_RomSplinePath/blending_functions.py create mode 100644 PathPlanning/Catmull_RomSplinePath/catmull_rom_spline_path.py create mode 100644 docs/modules/path_planning/catmull_rom_spline/blending_functions.png create mode 100644 docs/modules/path_planning/catmull_rom_spline/catmull_rom_path_planning.png create mode 100644 docs/modules/path_planning/catmull_rom_spline/catmull_rom_spline_main.rst create mode 100644 tests/test_catmull_rom_spline.py diff --git a/PathPlanning/Catmull_RomSplinePath/blending_functions.py b/PathPlanning/Catmull_RomSplinePath/blending_functions.py new file mode 100644 index 0000000000..f3ef5dd323 --- /dev/null +++ b/PathPlanning/Catmull_RomSplinePath/blending_functions.py @@ -0,0 +1,34 @@ +import numpy as np +import matplotlib.pyplot as plt + +def blending_function_1(t): + return -t + 2*t**2 - t**3 + +def blending_function_2(t): + return 2 - 5*t**2 + 3*t**3 + +def blending_function_3(t): + return t + 4*t**2 - 3*t**3 + +def blending_function_4(t): + return -t**2 + t**3 + +def plot_blending_functions(): + t = np.linspace(0, 1, 100) + + plt.plot(t, blending_function_1(t), label='b1') + plt.plot(t, blending_function_2(t), label='b2') + plt.plot(t, blending_function_3(t), label='b3') + plt.plot(t, blending_function_4(t), label='b4') + + plt.title("Catmull-Rom Blending Functions") + plt.xlabel("t") + plt.ylabel("Value") + plt.legend() + plt.grid(True) + plt.axhline(y=0, color='k', linestyle='--') + plt.axvline(x=0, color='k', linestyle='--') + plt.show() + +if __name__ == "__main__": + plot_blending_functions() \ No newline at end of file diff --git a/PathPlanning/Catmull_RomSplinePath/catmull_rom_spline_path.py b/PathPlanning/Catmull_RomSplinePath/catmull_rom_spline_path.py new file mode 100644 index 0000000000..79916330c9 --- /dev/null +++ b/PathPlanning/Catmull_RomSplinePath/catmull_rom_spline_path.py @@ -0,0 +1,86 @@ +""" +Path Planner with Catmull-Rom Spline +Author: Surabhi Gupta (@this_is_surabhi) +Source: http://graphics.cs.cmu.edu/nsp/course/15-462/Fall04/assts/catmullRom.pdf +""" + +import sys +import pathlib +sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) + +import numpy as np +import matplotlib.pyplot as plt + +def catmull_rom_point(t, p0, p1, p2, p3): + """ + Parameters + ---------- + t : float + Parameter value (0 <= t <= 1) (0 <= t <= 1) + p0, p1, p2, p3 : np.ndarray + Control points for the spline segment + + Returns + ------- + np.ndarray + Calculated point on the spline + """ + return 0.5 * ((2 * p1) + + (-p0 + p2) * t + + (2 * p0 - 5 * p1 + 4 * p2 - p3) * t**2 + + (-p0 + 3 * p1 - 3 * p2 + p3) * t**3) + + +def catmull_rom_spline(control_points, num_points): + """ + Parameters + ---------- + control_points : list + List of control points + num_points : int + Number of points to generate on the spline + + Returns + ------- + tuple + x and y coordinates of the spline points + """ + t_vals = np.linspace(0, 1, num_points) + spline_points = [] + + control_points = np.array(control_points) + + for i in range(len(control_points) - 1): + if i == 0: + p1, p2, p3 = control_points[i:i+3] + p0 = p1 + elif i == len(control_points) - 2: + p0, p1, p2 = control_points[i-1:i+2] + p3 = p2 + else: + p0, p1, p2, p3 = control_points[i-1:i+3] + + for t in t_vals: + point = catmull_rom_point(t, p0, p1, p2, p3) + spline_points.append(point) + + return np.array(spline_points).T + + +def main(): + print(__file__ + " start!!") + + way_points = [[-1.0, -2.0], [1.0, -1.0], [3.0, -2.0], [4.0, -1.0], [3.0, 1.0], [1.0, 2.0], [0.0, 2.0]] + n_course_point = 100 + spline_x, spline_y = catmull_rom_spline(way_points, n_course_point) + + plt.plot(spline_x,spline_y, '-r', label="Catmull-Rom Spline Path") + plt.plot(np.array(way_points).T[0], np.array(way_points).T[1], '-og', label="Way points") + plt.title("Catmull-Rom Spline Path") + plt.grid(True) + plt.legend() + plt.axis("equal") + plt.show() + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/docs/modules/path_planning/catmull_rom_spline/blending_functions.png b/docs/modules/path_planning/catmull_rom_spline/blending_functions.png new file mode 100644 index 0000000000000000000000000000000000000000..928946df46c7f14524247d675697d81e049c9a86 GIT binary patch literal 41129 zcmdqJN!ydR9~j(xAa){HU79CN=@QIf~Oq`*W%Lc)3aL`Dq>=~e&|67oFy9eCyO;LI}o zBj_TlhsPR>^Lc03${9NcX8EL~h2oP{1edi{SN z;IMbHctod!G6@&KaCoBYjD&<|g7|}+Bc5%Agp^MDR7O(6BYE?WyT1DPP5YiUX%L-) z1QqjkZN*q^g{$&RmaA6Y)l{y5TV8(tSY)}@ix>ITi(}S*s<+w0i6-wqI60AL70-Pp z`G)di|G{2|w6kE9=Ne&CsPnd{d=_)~TYM>Wx*!K~y)qQ|7hfuDlL0mTzt;j|ZmA$% zYHECf%na|KFBpGCBL45woN7pzhz|>pvmgZ{K1}tVH~{euKCT?51mYcZwEO?Rzl<=y z=e`*)#q%GpB_$;fcjk;zB>3j7+8&XulD_gPrp{i$~6F=@K3 zlp@rcEa=Srs~=W?Yh*M>H8*{HeX*ln>0m-gNO-zYSg-TTlAzjsXLY$VmON6fZ0TE$ zMlRt}do#K!9*xyrWv@sH9l zt$rd_#{CM@m|czbM zCcs|*Slo#*Z4Ku#?@5Tez#`-L>bTT)dU3G?JD14)D&et>){pkvsHl$XBP?*oG2CB| zbC{L}2iCX$RNoc#;`Q_M^YHZKf>ZwZ@uSD-E?r||qldTm($-dQ%R3@fVun|9%EHmu z^Ie}FTJnBjqjf9LE~GK0=JuZ%%YTsz|F^TVg9{91NTVsGiKYDL%{r*)OA(e&6Z73Y zJZ$Ojk9ME+M3Ysm^t%$G7IJ9-BMJyWs=M6pChMZW$4B~5@OB}T)-T<9^haf7<^0l; zG;Aq+*y{%$4kh1L{VJ!+tCKli>k)KqZSDQF{(g%z-{Y2RyO~PK_9$vcXXoa*xwLUZ z@5q*x7N)7I3#tbBxpu@x3OcW<{IXO{PD#l%tQA7TrSe$ZtH0dGdes%z2=-W@FQ`?Z zpJ=s4BIZ?SSmnepdYoO0#^YoQ76it~&G0O)!IJkQzrCT5>v~IT1X-2S3MOn866`9& z%9_Rga%aPEKeD2d(rO@{*b_l5aITuO)g)!A9q^;6^4Hz4!MUngcjU5S=w-u;JoXkf zwiFqO)W0ic!2iK2o!0t#6&}^fSX%ydrg=(d8*z!jaJ$I7mjc{PDn-b3Xw+})r*0hk zi_hSpS>qeJrRF$=b?2<45y1ra<&ZeRgykYBf~%{A?Q4%nkv#X8pO&SmX2}uY<2S^y zs3Y7UfyV;Z(9m#mvNZH9D%Sp9J8dcKtk}(^GaRS9gM-6r-R|094*Bl!vC?F@=YhFi znYAn|7qJ0*dwV_yz5FBjFXEd+@x)c%yX?%S41H5L=wwPOvil<>cDXC<UzC4U&sK8T7>gu%sI}WhX|Gb} z;|a?|mGJQqdH#iWVXDmLJ&ouWpR@g9vrfWtyFXu|?%S5R{8P)!%DT&EOHL6P(l2)L z9)gDBzoBn&hRv=UV}rHc?p^VZ`bTor--U%452Q;j_os>f>3_+Wq#iYWUoMNl-TlO6 zXDQ~8in4T4ak~8VWXUTmQLjVeo&+u#d3hoVimuLBCabAmET!hXi=VU&7gpkpzQaP1 zG;&lH68nWcc8#T^r2YE7>CpZl`J|M+10m4})_|c*Su6-{Uu_Ews>?G6 zE#nrNL$hral$5kEiJ3oGi^I*SBfWyZbC12x_Fti@kaFlJlx)?W%&K2sWf|tE(0wzi z_q#b0qFtG(@ho*Z*)~{#Q|t;Sc}OfSF5Wshsapj`^=$gtCsvm0>+7zoixc&7YGF6U zLF=+-4i39So*}r@=PfoPmb_g|X+9rIMCs|J9335>YL7_;W3n_5RX|o@J=y-FFnT=K zz6_Qbu9U4VcK$a@V@oMnAmi`RxyCdluVp$?*J5jgdN~6lBP%j8^0T$R6!r4wX<`P* zacTb7g0EiK+Wu7gsZ-2U=MI~yj!D8A=X5i8!sWg_(**%mt^5W|6*K*(ZYkrd7iaq` zpKhUIG7k<8vP_rT&lMo$9-pyA8}`@RM@OAyoiwa;$E%BOTkSL+(j=i`kunGDk7^r< z#;gtYH-o8?NOnho-=8OCQ*qI424W*)g_4nwph^_zR}Ec}laa;8-N?(yIf2W-0XBS7 zh!1=JUh%~54h}_}HFKVM?-%CqrgX_bweo*1LSQXz@QIrzBOU$bd3!et@2#XDi4qo+eG zvz;zy*YpOD(OByd6cmII6saLNUTCB|TjL2Xr_jX*p&M-AOTqZ9F~gyDZ(UlPT5+$` zBz}9R#TJaWfr08rV~;Hd0`^zBvoAc~zJ03}HJvpL>1X)rwEf%K#O3)$;pzD~xAjO4 z6U~jtaJ7h+e3DGtF8+z)Kc#4TnT(ArOr(_y)1d zYYPj=5-u(-ziAKF(){;ly?2V;cMKuBtNF5Xa}z2n_q%Lm8#lhq-4^%KH#VLpn!Zm@ zKa}$5evdhi`_An1vflP~G$y9(xQjWz3wFp2_qe$~f>{(fuPMRds@M4)t!pAZ`^{xshc$?RY9u?tWceow9Ac|Bc^o!-&GdN6(Y^o>$F%e@+SCc?zK* zf!}^s9Sb)AR-MJ%#q)^p>_nCV(1=H-%HHwu>gnDR%SoYO?XzOj)>O-rUoQ{YZp7rG z!yDyyg5}$5b&5@uMatoCDls1cgZ`z})z9mdwPA-;Nr2$gO3XSHt3NEQkLFpHO)*7D zOGqHW9g3-*1`6C*I%M2mwv!+0d@sHWVzbLA(W9n2c+k+$ zEO*C8$1*8@&%1(TXf^Z|y@!0ySKI%;IOL;@De+*tn>#dWe7HJzITps5( zK4W_xmt__jv5e1=CaRp*c(5cQTHnfLnKXysDEIE}j3=p4M!}E$WP!{Qh#2 zm{kKkqP6MlV2#D#w@cUYbcOxF?m~0iQk<%om>4!WX8p@D{FT3Jcln*sn!ar`){cSIU+zdWn0%$evH6(z$ zsfr@(5QwwDr1T^1Nzih{akRQX+uL{sDKx5}|>ExwUVHO0^nQHfF*krN2GWqto z(NPkQl3kxK@;in9hO@J$t|2xfkEtVbug}dnySuwXZaN;Z@(JpA_Z3YA{b&91XAXle z+>bk#9=<_fAtS#thF6cHS9_C|mX~F!-L}X9Cvb6b^`r=s`TP6Z{rUaLx?VF+>lNTH zpVNg<;)hz;@Hz#*-DQ&}0P=rRWe?|k4sZZkz!4+jHhG5@q>Ph6mz{Oo1$dE=H2L$i0 z#C(Y>OVQ%rp}s+&HiT&q5H!N)ShNfDztpDw(*$$@IJ@=h(^!w)d1Nplwio4W-z<(i zZ=<1=dhD6DMN+myNrZs)#l^+8vo(p@M!uhLsfFej7p0(@(5dqgL;&OV_E5kvs<1?+ zW9?#7S-=DBP>~_Z2OJ7sTozNmz^e!eNj;W=_1p^!-IKis!aVFu*8~QWVmUH-dEenlAFY%x#0%OGQHNhIir7*rP)pk zO~Kjbrxiy2SDK#xzQq&s^Ygd%_C9CP{1L}(+Je3Uc6gJxHm6<%KcHXhrD-)+SG%~r z{sZzH>&v$Hs(f}c3ENi2fYlF}QbV&9BTH;2xxZ=Ts)d)9mLjT`S4Zok2n_T|?c1|& zjx9reqS4hJdznLk1rV4F;A!+e0BTl9=E^B|7;D=ZIXIL&H}Wgunu4(&-U*b%Ku1^k z?eZ^Ezs7^>TW_kUcN{0;e8bH+6?rsHeXH^IZ-+T@S<)5jkseNgG7M3iP#XRZ3R}5^8t!l0s z13(nB6->Go^-c&;=rMtbir<++URK!8^%cKtS2O5j55kX*r2$^1qY+{J5PiV8@gP7f zferVhic%^oD=VdnJOyVPjbaWel5`>n!U_?SD!qSsJ+sAzAG&63Cl5T{8{F|4WPBZylZlX15VatHm(i&EhGJ2y924;=^R)oM>77?*H258^(ha#}es z8~h{QzrPJpZY}Zk@%EqYO2;L&*EWNhs6gjYh&Zc%2Wa7WSvWYMt?4u0Tt?*Kh3C;$p1qC0vvf`T+)N;HUiWJC zL|No1oZW||WYJ{-aoW;WMKiSrc!V^&_ZE=xh-e9I!WsAkKkKNoIer%)?0uI&!eid5 zsOCh-Z)%@j|1;ZjVKwoKY@NHC4w4=lXt}eTgF{1MLsB)Sfu@l5@Hpk6 z<#Aot_^z0^-*ODedSQM2{4(R_+j9QVPs_U|wa&+DF5*g((wSmpdrDRB-1iy!=A~=Y z?Mzb+@Rz70l1pjB+qUag65%K`w$O1U|8LRR=2|^6I`owmRqZGTC^W2i?|#Yb5A1&k z{T$lD;>c{~ytaSf4l+y!U5rOlt`NHY{u|RY6GO?b;@F%(uoAJ|-<=ao*OU4qTJmva89?ZCn-0~-|63tSD zlTqG8F{(*;d!Oh+^Ox5yuGAh&$f6M`L-bLIyUD;r>%a87=G=*J*59D^A;-Q`wlu;1 zzkcIzxMW+NP(|Pzc!1aM%&|zdMw_~3eW+95dgJgU5p5QpVV_|o<&5KS z^@6oS>*##As)bDUV8-~mf{<#;AX-z_Kr3>Gu~OAY{xbLgLn)2dgyy)L(%YyvE!ULG70q6VOfP4SBu#E{DBYLu~W^EEX! z*B6p{)Rh;y_MQ(#&Rio9)lPYZ}Zo!>4j_VrhM_H}2B zPW_JN1!<7>O;Dcq{FK-e4|Iz$J$ocE*`LA2?>^&e z;9<*+8bSjl>`;N1spMwN&uwO+F*V7%lEznbbll*OL*uwmu}ow%=VLY|EUYyrzTd<9 zB^hdZ=H-c|EYuwSrY~SQfO>66A9O8XbExD*9o;eJYs`P?U`44vV@}QL=g{dT%!!9> zH)h!SF+W2FYa@;ql8J3wU=Z47O>ykjctz>jYO2QC?!U)gtmoQamFk2>x?V&KRVln2 z=n`}~?gP7uX?3~7tkUb1Cyq>*Ip1YhiH~W)uh-A+Ga{Tbs23XE?GiM!mB01?dO96$ zCrdk}D^sL=29qssrqPO+KgSiGRi6(RNk|)Z-4KqV{8-vvE-+QgxWj@Z+jdtpUBhN0 zzgK%~wy~6Qe$xwG95>!w&wj(Gf;4dDw?rcD{Ngt^$R0&Ds!vse3^86cuiz*X`+oC% zHq2Z^fOCsdWh$GO0`1E`Ns*_R5__h+6dl@~UN*cKH2T+Ti!qvG2k7eIjTmDK3*n;a zIy?iyxm5b-!0>e1nrcsQj2Y^6A8$-^>0bMPiYTe-9umnB?8SPVEm80*Tb?LN786qS z@IOna6o4#}%Y%gvP?&Kl4L!P;roSc%_5uT!N`L2`oo~*^2waP1pr|3NWs&thiOeJ z_Ea^86hUbLOWg}Cm|+;9zNJ4aE;TcpjF{(If0rZhnnn2I){^UeFRfIg&UfBSYULMI zr-Q#8Y^F$GD?Hu#$X)aBI+i$qe#44)tTXpOE5LlGIhftStoW#=u}FGs`g=uwbMxpO z$y9D@CQ>Q%Bqy;&k?wvDi{949EetQli$`q^d9iIfx?7FD+tvO4XJ{gg{^6F28Gk)9r@hR}LOrGvf9sYO4(*8(sHD(R2&x$2v7`OQE-$l_X3!xngzqaV!mNNwZ7` zioE@+U&FH%UVgtq!H$F|JXsMol$eq-qP||-yfkrlclVGTHJ+&ILi*33ibdR!R1Avq zLeIHBWBN6b$i8$Wol2Q_rAJ)2`u!P1VrXPo5$uiIzi=rO>gDF>$aYpwdHEH7WAs-aN%-J$kEGD7BqwolPPY z#^(5VomJu5uxULaPo2^FnCpC?Oh)^6++V4H7Xe)u!J^Qt*c0q>n2P=GdqFXCCqC_K9`BIA$oAQWTRI zxYMBc=ezq}r3z1D9VgzsVb*@(^1J^k`6V?bf05E-^{+8yXsYORPWZB_6W%tDu$0)0 zjZW+0wvP74vy3MFxO*O!B*P`jt$0l&U}ban1lCwk6qalh}@ ze5QMbd@jx5!(rv`js!nqZVlYAD$`pZFYE^fbnuz|SSc960p3rt;L9WS%_Nix<%W{f zv5W;dd&$8zHFQk6l9Wv5&DyGX`zW7S?vV|1hb-+}!$bCAGW#sW*9;@jbH;IUbTk1h z3KS|085tQs39*Wqfn|dnQNm*%oQt{&T%4N$49u}N-*+S%^{lgrr3Aw6yGLf=27b!aB-xrWb2iGormhygsk-*esD5rgb7@ZqyJL zn8=O5d&GUU>r!qshZ_((_Rfx>nk(n>o{xc#W-nt){ZnM-&FE_JU&+>61T%XWRAp*zkk>0v7{M|~AF_vkuGwm5zG?_Zst_nRN$#&;$K_kM(JYHe#H zBqo+oQzO(aG%TC@Hed3^!q4&sXM_gz#rKB9G6%DFt`vzvS?Sy4144NzYUnZ2t%-{| zK2BV8*-}q-!iRGU^mBQq%k}H@^40=$WKdqudu1odMW3xw(5$D)YoV*Nypn` z0mvKqqHmIB--LDl9gqB$!G-@^SDATMXDdhwow8zQOib+04a?e6KZ**cwq%hbl0CQLT5%s@Ju(rIhe$?qEtS5?N#OX|o$%Oec%x|N zU%p{>;`@h8e5;`z`|t&d{|#=^Y)Hq(uCo#I7`C4O9Wf`_H2kPVy^+Uavo~D+Ay*g@ zh7~o6Ibv_Vqb5P;hci(T9BZ-lDY9kYFFkf3xEQ#()jq%NR-(X(+d^+mYA$%R(0|u~ zj<_x#^--;P?cMhX^D~Qq+c{9~vABMB_CWU|rzOteqvtu20nf47C0B)^?AU?;5c$lN(G<& zm{07z{(G*07%{SNR*Skm5z=#-4%Q5pdyFELw-tn>g0}}2UpmBoO9|@ux7|Ls77=Jv zbUdVobZKyzsPmE@@@Tx3L6AZ0o-Ex^=AcBC5~r#72sx(Z{HardE)MRamwYk5LB zJj*LVjlak?Z4FyQMP6TBbt?a0S3QvlqgwVFab?^|>ABv$LW(=&==3g|%c?Q*{1l53 z&Cn*8OnJQn+FFu$*KT7bKmh(TI9^)CqDit|NJP%>u5 z@Ve3_-dwb*g_+Oj9-B?IVz~H%1MCQWmdl+Dv%$jcGmGs8kBLLl9vjRG<=hk{^gUw8 z{(~02v~>cfs2Hoat#6OaR~*+5*6aHp>fOaAijoJ7OKQ9_!N$y+t-3oFc$J>yb@oWY z;%KEkM2tb~oVtoW{+r&v3%B|@FPJ)Cb+pC_sV9v4(7d5}W8F?9^%x-m0aZuNRKHiu zlg=??uEsGu6GNhZIK)z~5I^m0U~f*7^0b5@G2{)7?x-V4O1S&S2$7)X*jp-LJ@YYS zUTnefYXO5;cGR)65_B5-9))xN(6aX&_KmG;bAA5&wYfC78jWHKdJf4ytOpLSb(_ujPXI{ok(nYklh^^uTKn!jPEP9Hp<6wJX_|YQAmp8WY&-dv4J*D;_ z(EuxUTQcu?K6`eM66blfzMR*5;X2C{{elLL-lQ7%=CGg3iL~bhL3~DU8%YW_-|D(9 zoc3EY5z)6p>U>N#KH%wUaU8nSF1yn-{dmsYZFo}c5@V0{zi)mYlsIZs`AYDU>JC3{ zgT3_p4DDFcK&t}8xn+TvcQHPPeBkf=GNz6F{E7i$8S;YoegPadzl#>S?zm7;-)D_9 zR_&IBHN+qfp;!hI%Pt)L8)ms7bCbyq4Y8LPY#TFd2SdBzs3)j^ZtS0F6K>r;~04aK(6d!-N1_iD`0b; z+a7Z)i^a$YA3jkY_I>RR$U4a>qy2LA;M*w?eJny^mOrrmlPnB-0*MB7zEL(|{PuA_ zY8Ckt0d!ea9WO7I+VPWB>k-XcGq-dmoai9O%4d(}QY)iZ12DoFvgAdyTA**Pi`hp& z@)Nb$T@pM?>FrTr^S&59ZH5~+U5N%@(8AaLk+~PyrX>lMq}sFi-etU z0fV@@u7G%`ggE)W^U)g`1(P}3iNh#YjH=zG0oRx#A4$5+o=$HjPv7>9pw=Lh0Sa=X z*CMsgjy{UN4ep>HLV=qYvP>U)$SFWv6F9%{IAQMAac>Nri3vZPe*3Wakh`=|lW7z4 zykP)Ce*8eSi#^MAP=^!*1e1+@%@7me3>V>|1mou0r{BaM$mFIdhLI7b5ci%^FP)j) zFg^+XG`y$wQqf;;382FgZ?1-getD3o=; z#h1`u>{&kXn5Uh;YiaP<%urq6JQj?m?YrG+i=ImW@{4uvzLk1I1lD(}EFmt_jX z1~$kn4@uMCNJsp%!I0P26i&ofCLtw~gV?0&XopI{`#y*Ft$mVDM0RO5oRq^8*sd6L ztFi%O`ol94eV_R;)r4Ur4qH|DV(uo!wDd{YAHl16USO7b?D&!vNJ6tlI|}d7jnIqx zN-evze$fdHI?yauBE6Efm^k{TNOE7pLY1vYR4jfWDU>LY{Atz9%4yYB|465{{FbGZ zfC$`L5t`wfF^1(IhbY7o`*p5I_=&7?IS&|FLdMH$+s5VVj z(#F_ntFuP?LNwV$$y%OB>QWl2t>x9#w%#OuU1%jh&)d44K=ApfAE)tskLAz{GGjX; zfl|XQjV4Lk+VW3^8{Uo#>zK%P$ZU3H34IJgdDIH%dyf#d6^*G8oFSY(pzwhhr`xNk zJonzgvv4+3RW={@L*X`CO6i|0pVyH`b!XiKSA1S&I?>t2z}ZYZbQecAM136kVrS>{ z_UDt&2e)LuM<|7x_mp$>2=QSBh<&@*^)21m<2uhtRz%-p1Gm8mkB-g;q0CIZztQKn zM33Yw0<_YkX2Xlj*^&+L4!%f4r!`b0Kz^pKB=ig(oR)JI+~-!(W17u7pxKHj*B1Va zzbO6$FCC{uhi!AFDi)MKooWvB&Km2eDEtxyJ`OunJvP{6e0eF)mK~~_-G*%p9&yMU zw#|*EwdRv5>@msULO8&WqW9M%|4ofK5)ky{wD{p>BFh14I5wn-59)O9C%E5Qs`Gxj zWG$}Qa_Tz&tSS5jpFRa3K~v0f7s}PR)QVWTj`8q|qID8od7ZB>G6iEQ-0EA&(CQm9 zb^dD95FNbeX&-OZ2HOb3{@{!h?7-_~VJS|u9~UY<8}w4VvG!o#Wp0@S@#5X>wm+{n z%ZsV%-KkRK+Jn}K{%ZapqllFI@2e$AGz}@j?nBTt2Z2T?wBiv2R5@sxgef9d-@SmA z*zs*rspk|pBNVv4{wP^wLDavLD0~lczz-wOFRtef^~YnEPNJ3;mK!(COaB@Cu7J+W zvWlBJQd?V_8uSnAu8ya%MYo|RHuKx{;mYdHPMR!6aFL`eMbn4;57h!P!HsV}@1E>f zXA|<74}W@oI6V+O?O4IGshf~Cbt#iyQ#KOC5afaE#&dh-hvq|&hkaUTKLZiu%F3s+ zH-;aeWnx~cyG7nau*`uO$lo0P#=#Nmk_sDVF6a(XzG!fh3Ba|@rP8zQzwSsQz1s2p z6h0xLv25xrGD;Twq5=JR&}2ijSwVuc2Lh5G)M!N% z>G}5JUp^%nXD8IpVGk3k+3uW>2|t!Xbb@{^`8>L&S#pb7TE2??``GJR`^w*ibqu5R zr!jZ;iOOvMXI)Gh7 z)1XfY&&%65kRfSeJd?Y5e$;KWWEOS5??Y03c+~wV29+%xddi@rW?jP4peGE3WRX~+ z2Ht8dDl%I-Qf46Q6o9ZVYi9OqtsBf zpOem8&*0uY2A66c+LFayC(GzNQK34Mn8^j+CEjO_Lw)MZ=P7Ox{Zph*RaF&wtU@lx ze~Y9Wl${U%s_w7$Ui1_S3k!p0_Oit-u<=8#ec#uw53Wy_@Q{A#<@+?41@>IiOa%uF zaZY%thOKsS9EzWWd`^?<&FHUHfKI}aXVgJ-w*PV|N}7o(+X#A2qc%=`)9@ru1mP6g zf4?ixx9?k;b&HdcF$AH}ovHUZjsFoVd=EUzW{WNFbd#T<3ug>U)H=?qlWXCI9{4xB z)f%u7^jOsvPVvB9C|-C!!~L<8z`}7%@L*4Yc332*YN|L0f3js^4H-&MiOKkk8zF~- zz-cC9Lv?iV3^&#oNei0fjFaE9(9ej79t=fgCw;QV6!hOXKnxe^4_$5CJ$8&i{`~It zl)0bqd8KN*&CIzFznORS(!f%%y)KQz^dmt8jt+CkK6KoD!svIdkR^}qvD^W^DiCW_ ziQ&4r-@@N~WK6Y%p?NCe@t4hT!O z>&_cY{Px>T8>ZX8<8q06sN9#xQeyN`@Lh#_eQ(G^N+gf6p*-wDPW^&IlBPx=e1bf< zC~$avP-+5zeumA@%hD*{5tuP+?w6#zC8)X*hBw`IZ3!9uH4 z7wQ8#HAK|~in#i#V@l}ZHrn##QOk!NKAb|oV;7`}h&x zPrZpxIQpXV{l5meW0bwbptD8HZG`o#CDPup3uro`W4ZHZKlS$P+&4GY>WcFr>(4D5 z#YzVsD;Vk6rO_R*R3JS!-9hY92ZfyS->ZjlJK=2~6+hWH4_*u64C$1piqOicCOG@x z#@>8+kBXK5R*x&Mlg&x6Q?FMlEE~#K^cdGerQLn1o-%pl^yzDYpOk2%f)$TTfvgg{ z+>ovl+{ZyWO5WI$+`{Ahi_OYJBsIaEct;LBrtFsH7BQb5ZU2%TsygP51<4%)(Lly6vOwUP{LAv_2#wb$d5w;KTQmN!GM>r;f*goE+jT zqI3Sz3!Pl`|85xi19U;Zll3z$@PIC7Ce`7gaP#9Jl6#ple|GV5j_1`5F|Y-*iVZA{UyJ_3G^5!OAE8T|+zy$mD8% z=vl1MAF-N2K>{a47xa3-GQG2Ueie^$F2J`mU)H!?cZ@`qDy-9XF<*Sn6nafamxXON ze*qYE%|Y@pe1xq4tu*s&tp!(n#EPT7CtlmaX?E>#Y$g!hbgt z;MkvJ4bHEvg=S}G>%&PJJ+&c7s3w;&tRQ{EADxrJI-LC5KirS<-0|TtsU(dgn^jp5 zy`d~3JQq15!n19fc6u3l&kKyj?Z!+u2hZ%OT*Ha$7Z-Oc9q$pmBZ%uX2>GBzx9r;g z-%?Sau(<`F%yav(Rt`PH5PKRWfD4aN ztV_~cZ~43zLzuS!I`nx|oSe8zE&9ztdkRGZel(Al#14td5B3D2g|#||W%)AoR})_GJSfIgAM+V)TNs8NDT)Oy7a!KLIlP31OmZk6|Gbm#m7P55p(!$*P{N zcJTLza*+l2y*lTroARg{P(VirkAm?9W3{k)#cz{6+L&q-7Kc5}7ptf`3Iwx^KJo3@ zFYQJqH}K>Q?8f`NsEnRL@!wbCvz|2 zx1y%tti_T!Bn%IjI8EAbm(NXbY@EYk zg};uBMW<^y_%T4@#fDl-(Dyokwpzy&#DV%74oQx?#!cHbf={xy zuwSi6P(BJ+pFF;VHX9AlEBH;<%X!!+d<~1Z4ky1{ujc3H8ikn^(vIa0aYAe)H?Btvku_nsDuLIE z5Rh~xC>6=E%N-wQ;R}WvJteOk)VnRG{|1#kV~2J3(I*CF_q_$#5Ic&llvCl`tC(hX z2UW}N{b>yS3@xS1;ZhzR0(i7y8p2&zP$t486$sF-_0<_YJw0LW=iV^8Xdt*+hZ*-C zNMgTT8lmqc*900j$m#5tlrcG&Jp6l+R2IrflmfoCkkRa!aQXoR6bZw&xPAqGiRV;O zU)!@5`{(9pwYA5o3@(9SfhjWwclZ8*e=6ab_+(`5PzfS+fKE?w7y6H%6=gG)2Ow3#p-8q2go({#_H8u?erAsdCPv zUJKS`BZZyeq=>vLMtePo8VCLFMo>_O1g1$9aN}W-L>~OJ`-)@|3rE&IG^@SrpTa%Dlr1N4C6jW zF}4iOQ2Z%IkS`}D72JUfI-Q!sAqAiFf7#aZ#gyDQ?{S8#%Mdk4o_1lEnuC-XL*$(= zH7H7UMXxY7FR?$Grnk0_6`HVLiwW=E6;HlK4k*@aV|6T(c#y!~6?A%_@R_aA zn3L1z)S)e!7Eb~g1LR7lmGE$ktq8>NsM=ErR5gcS?2fyS(HCvG^fX-f*Y?}5`J>GD zez6}a)lhaV#f(7)yR+|_;I>X|ZB6eU_*4m6U~CHBFzDzy@6JoYTuFFZ8ZFc|T}^RO z3IJu|pqN3U^=SZw<0}>cx)O!njIq2R?dZ475nK$d`=5>M`1B{kw6b13OJQ+g8&ic2 zpxKj}PQ^s`86r3(k9ijGTKs6?f*^{L-<4!!? zZN}5B^QlraW|49GF@q-5&-66U;xdIA=y`%#xps>q@z_P>Fg7jF3~Gpmlv$51!t_!? z@A{$flrS{$q{7-;;;maJFmWb{JaL&KnzV)dDVFoHAJ!Utm)3q~!`!Uq=s^P9*Z7h<5M6O-CXkebN1886_nn-S{bWsj<%Z#RQ0lpiHfI!0OsRvB(G=>q}Cx^jPI6pLF z&@gMj6ei#6DI`Q$!m3@+10;~9Vsh!qdp{G<`OsIqwC8!?f*ybWQS5X=QdRGo+D!H7 z4S$FB-SfiGR_gg<44n~*xBh6+KI_4xO?@!aEV^<7LwUCvOpEamvsEBQR}Ytr5&Q~W ziG?Cywg1)^i^JuJ=1C=<n`oz`rKE3WCGj0w^={ABCm1*e zGDF^z6+QKEguoNpb(1tv@v z6+NC2`SQvWe)Hk~W}DOf?nk;X*8246Q=ns;?5Jv;;~M?3S4|eByH+^bFG&wNw>}Cl z2|Jwx`q|twA_?aONyFNBpdAXe_S(_bX+`Rd?d3sbxLLwk1f$0@

    tE>;rj18uQ$r_-%kmJ0~e2j$!iQ~wUR=gX9pvB zCVkC`dG^*vqWSDp2Xo)mEhCWY1R&x_b=ls&T$?>@bf;;iZicy{jR1~Ciu0;?Oe6Xq z|A3*b#^l@LC&97x=GO=4bTW*pwMa0vYYrL?#MlK)bD}sLtUiZ4r=i3c)Y0izzbkCN z=@n?kkXSA|wXb{C4;7y7Nst%Q-xB;TcN7KgOCjf%5|m zG^&M#1&lX9%B#(ZVr&|b1jI>gf-_Yi4Z4#iSLD(K_QFn75ibxnw+=o#Z;M}Fm8j_cs5x^J;o0UI|OS3I~ z(6U54Obd%$9J!X@IvLkr@s>K(NdH7f2!7N9LBYhB`|>amM~Hm~1?HM9E>HJhD2I@O z;>(XM2z!W$ZO}Sq!7LyvL*JwZI}$r7mU$_tbU{Ub59Vle&u2i^@(q@giV(gOy zm92j;&)x{eYcmqiDx;>oOcG!TUr|C~er(|)h7q#?B58XCkf$ekPVl@=uH z4`9Y=#SdOG78R!}WwQ1AC7y^bWYY-)2)drhB(f$`F; zD*SP@EW6|KBDeetk6MUdhiHiNZ6Di*<^0*v2BC7F&w5q(7tS zzOmEEe)=pMXkCP=7Jv%qR@Xor-1Fse1nmFy%?2{iPaaE={E%MIwzs!)>priav6B+Z zHp1}RV4|tbobY4tD8I9n_+OTTZ-IvX@Zp05Oh6*E88AzEc{r?WE$96sS3Mivi(@Lc zpZbNNJ>HX~%?3vd5_iD9h1y5c%lOx#HTO#7%xNtmOif;2>K!xb#+%q|43W-t*Zr)w zwK>=&`R4GZPNTB;_MbXk{c4Y>CDd~%(v&3TowZF9n|9s8aUy(t2}Q-8n@9Jp!O~^Er5uRNE z${+azn8%zfS<8J~w$`CTl!-s+_ZHquiyWZgFsMj1(H(ygT?e%t}Qayl$WXMUt5Bx!J`5 z2;`ICc>pJb;LZrexP=%9;_q6lF)_tFCdW=Zr`tWPzk`85%on|$=7TY%YiEDGe9}m{gOQzB zcHg;?Ol#yyNZ`EnG*nc{+rF(WEx^zR$6df+-YOXI>FKFTk+CG>^DixU^!) zFssPzxF~Z6m#PEY^6YFaO}E1C&p|CYolN-?ZYD0rHJNh#>9>Y?Yo+IDgFjVx%3gjm z3bspk4#fZX+6OHVj<0L7dgCc4Plf zB!%gZn{WD|mkc>2l^1eCao=n(4*nAwBd zuXNoYg@C7U<^^{IOQbHWJ*MC>?@5<Vr~zZWhg{e1GqE~4>6S#}+|NjD62zk?PlJfPyQi;!G2&2!jt zXfM13z!z{-)6o8Ux;zp_@67#mgww5&$q5MdTFPPe`Jn4zA*V@G5cXCcR7lL>`#pu? zuRle@C!Ll%Vz5P{@ujF?7)H*Xy0>oEm)up(oHtc6#m99d>ge)Wd5~fELbjoU9}(Nu z9ntt#e}6os+iXQV-sV~y1ojPHB=!*d;5i*u*M4OE@<(L>H~Da?KKq?a%7?g^bX3}k zYS_*Ecos&dV){n~(3BUpAoGtVevR$xhsxw$SwrOa7aPOL>G%J~)>%h&wRY{AkWT3? zMNqmM0VzRg1?d!|q)Sq|K@>q61O!QGX^>JRlu$sWL%JKzT)yx5zVpW!!?CxU%`etk zPt0e|`@SYI%j!=x7BQ z55|!FHAUxiBsv`E=y*unMAL*e3Q<&rfUq}Vb{?#Q;Ok9+V58S3v}49F{-fGu?0Ex& zU&h(S@uLx!L<_Qj_#=v7)YbO)Op^7M>o~qnkJfeIbCcGk0^@n|4@_E4{=VnDXWj@| z0xC%_UKDV6`xlf6aE5R-l6glm2jI^@lKHvh^OQ+nZd6A?(JO!H;cf7r5D{@-1gK}5 z;DE4$c}>2SGH@lsQ$1;5A3c=#U}i123ZH=fGnf;|c5ijV1KW0Yo{nac#5)t9n?l{l z3{xmA)y2blsg2xLLd$2U^)O!7{8gAkVkO)+$?n_8AdB^za5`?RBKPeLKwu} z0YVY+6$jYHlZ76)nE4+-u8~^8qhx}QF6ysq3=#h8ZG;4ILqWuxx2T|0nRUoByH{$1R}wA@NV6ss(l^OGyWbb%tl z92o6H0n$)o`v8GE*p8JHc~sM>jxw}?973~DjUFgIU%@KFmwFGOC;&iWc4ejLu^_WN z#iY9hWx1pGEBHi2_U3uNHEEWIYoH0@ecvR|1!U^WDD>n*g1AUR^8* zag;mT!hC-n*%|I}+xC3$1AVD0^-Ft#KAbIWBGG0=Tu<~3*%6l2^ugA8>HtKje9_wS)%+L8SS`5*Q#JzF_(ToG%neY|0 z(hx`$efe`Iv4QdR?>$RV`SIWi2$4g1;8{}VCB;S>J5XmuQC`9-VE#HgRv9PGLZ3t zqge$92T#d-=Q(3;_E3%uR>4T>bG7%{5)TLR1Z0+uvps_>R7<-|T_j&_7J2ZSS-^KH zYS78poj=&02!GFfzWW0c6O-RzLJ*=faFNeL9T=iCj(ikD*jNC0!^F)U2Lc6%kfX}W z(bdWKpX*SgNqg^HN7-K;X9I6$AnZ{5kNc^>lr9IpOh7|K(m=uFk>%4_W9c84sJOVl zR6Ul?KW?gSAF@=7FK=<_&|fJYyF!Welk0m}^@szCq_Gqp6s z_HvN9=Xh8$4H>b2Zd=)~9{GXVtr5Agu5xsy`g^>Hr0mACL418KP$%P;Re0X`ct43f zxtw-Lf8DY}v3}X;$GB?7lVJYSCS&k!!|6;B*c|0C%lG{D9@a zwipWjO_31I2a0#MU#AMv*j(h)U{4)WTRpvq@m69I^zJzkni&GHT3DFbX!X-SEo>W< zT>4}g8!Oi^z^)9)tF?&7ui<$hP%b(4lv_HK$%-U zDtGI+eGt;G6x|d}S~KJ~FFrh1M34Q`F|}-j;?~$2a{p=PZCwrAL{fP8u>cZtK3IF? zf3m{%cp$y6!mKkQHg@5w$e(#|<<5c|pHAE@A_yG|%0bEeQSAI`qfbo1eNDw{iX!2$ zHVr9WxAlov@IaD5;_$7-@0kz?&Wr;UD!1BA7%S#CSyAqlh$s4V``jx05RfdMCuW=- zzd!IhwZf53kMnOB2}{QRMiDVoe9r;2^Sw1701_(J1L-*kT!&rrxySm1^W}vf{7V5C zO`~xc7C-x03%a7n=irOJ)yR>9=M)JXfg<|5VAp=Z)z@^o)L7C`4Yvnoiri#&ZAojr z@wyG+%m)+K&pIV>{=f7@>rr0JmQY47+b_-;N3i{GPO0Qh6UaxvvHXad6Ys|-whpj& zKB_Q9ZM`_*&@W8}Jp~_F4K|6vR4ffwZeb@!dldAm${2XBiP^a04R>%zsC~zF8S7rFC@tK=+bZ?7o}} z8lnyTW!A`NL*P3+jYmUiU*f^p^PmNf%5eJig_DmE=PJgp*AP20(`DYmFopc%4~WNM zT?EL3fYY=L5NC=M$siFDA=JfhyULDKQr-#h=WXM|s-EY;saYKBzEW@1JR|oGY9E=m zAB~e!$cYL*z?Fen2J-+wD(eC~n;w?P%AF<>4+iX+d8kl#)GFLi-1)nxE9So`>WC@Q z;;_T@U{~jXM6%agJ<{b<+Or=7ActnjI1hoFP4D~s!v4%W%JBiD%|U7*4`(_+~K?1i_q+-V@L z9w29+MFI>lTIb}c?kOZu=F+kN6~s)|fCtO1gi~iT|FVTFog-?j|8$+g>~L6wWeiCq z!(k3e(Vs}ml#B|YIAj?45gb}5%%yVd8%Bofdb6$bH}TMg1C>zgJqamlL$F@M+7+S^ z^xt}R9K8er?)c0v(y?gh>y>yxdkUr!#dbrCM^i3*p^~^o^r~-PKjovUNA-$Iz= zAfJ+Y4;#L`@V}y(W5A!wG*ntFC$#tq+;D;GCBChDyT&4N=@kbGW=Xj3E9MR9km_K&fT9c) z(RUC;^Lwo6)mVsBI@UGRxTyIa8`E}+FvKERBwGDWK)UJQ| zJ@fmes@+`cgoWe987dKl`jCu-JQyYL9JD1=kdg)QZ0bW3Lqs*q_voG=$4Jam8o%IZ z<7AR53E1T4*w}wD^xxfb<)t$y@VGUDWFwHG0vIzuzqJF9np}33&*PmP9f%tl@>F^K ziD@`G26%edW|RKnyQGYpr&NK23KF~x1D1RG$GsH>|5A8kF=2VPJ3gBwP!R})L5S9b zqM)fUi|o^}(RehmH-4?(k&{EnY^R5tOR$Usbp_#^A*j7B^Bh=%@1^htfk*hUnQaeq z)}nB4Utc7(z+=E1+=M8>QUZh}p5_cDjK?&H@RT>_%L{3!ujdz}W>py{jwqS?H7S!hEs-5S?3_??-B#iIJ32 z==-DXv*~X>^=6d&6WkLv8`6slsYjJj3%&Obxe#a)B%0u`h#5`6^;si6S2=ADitQ-i zO7X4Vyz?;K0JUv()VL5Fg0~7uib2S*Z7_x>FWgKJpcWpYY_rR1V?}V7EN*T+!$83aQCDEU+hB;)gt8ZG=3fp12Vve^vhhVG$7aa!}I zdAS~@**AT-NGbCqs^=RjCY!^cz4ibF)g81(XAfqVd z+zM~8w>lmVaYDg~K3v2y5HHX%@p}g%JP>2;OGq0*A_RpBh7N#Z7UVlJyV!aJ98X0( z!q*kcM|bZwtJ{DJXkD-4q0Tzd0K?X#hUk9Uen*01bg3>OUSj0`{{TKekU@L9btGwk z79SH04UPTLhqo$ET%}=RIGGOL9Y*AAot}giBh;zCZN%Mo$6+d02rY<1c7MTdT8{l} zh}wq>J+BZXvh;xQxdGaEVC7_gU-@ro1Qf=W z@t@8PRNit7p|A|QyqQukn^xT7!qGGv%WSLY1UavqC6dAyjX1A6Kx!P4_k5M1UaU9b za@Bik=N-N3yiVq^SsNylduBK8C`;5gX+yjp;f4rNsPQoo9v6_sED2>2Zwj0I>fid> z8L1kV_gLosVogeT-LL@&Qwv?c5S)+6%$y{USu~3u?a{z;#{5kdhQ|E-JfeE^h8&|6 zm+5wgzr-c&oM%jrCEqZZ8C&d5=wTOw&HUL+I-butTK>dyF&uxwuujzxwS^&0is*@} z_Rs0UtNR3b<$hFRuu<}^4+)|m>3WHp-?D6~-jV%}dF955^&}|bIDFQc&kZuG6)J?q#)37KdC8Y4B zqO6<^;6D_o0qB81p8AFT-N!qbeP{mLo+#bA^y-%`=c5Fybis<~Ukd`?$Jd}t?FxO8 z3iJ>t!N~1(fyjW2Q!fEdW&Mw?g!NB@c{Hp59gJcBzUT*zw>lN#M7 zXq!&THopLk;;7-MvSLB5c)lnXinb-Vqd}0zkRqBA!vODEGad}?jv3G($`g9bZr~u& zJAs265D5I6L?2o#|$VkC_>QiN_K?L0_9Dn})f~yUh$p z1}o?HU1YrvKn*A-nc+!{KlRdQr5-O0i9kC4I~9KWpE`W>+~n4kjx5x7btcHGjbV`% z%M?HUTk$`lCKiVc|FQhJC_yxBPR@10o@B5mV258v!~-rav%ft5u9=do|iwvEt^XL_&MKRKn-Zg^`;=#VFqINh57><_lV#6J-Uqh+O@ zsQX_sNJA!dm0+OUUA+E#;+%rE-2Te+zHRyUa{Jq_v~jl4s`YJ-`Ml;s?>{xbYfo`n z7RB2eKpcV_NSPIo)J293{3x&~bp3oJjZgo`O-sm6lxO&W=X*F4r7koqk6I_v)$9hdca!WcT$&Y|7A zpiZBf`CJxoBc`PYg0QtWuyFl&hj*27xhjVUB$6|$vtOW``!1ur7KTtSjRNf*NU80j zJ4p~((>9KFiY;~J^ykho`V=3epRSZ z`7Nj;uX&BUrW>}#M6;aE2(_q!7bdL9)%tS&hi9-2usrj^dZbH$Q-Xt&Sn>8+y8gfK z7KeN{#E|CZa+TEMUK=cFZ%s)d-xvLQSQT6ymOLP=xu936!Ehxx`^I?Sd(9OCH!$fb0r{JR>EKlAyGIyJ{Vh%MipAIV$EkoPB_NehjTh9E8cBCLv^kkvU%5+O2Nw zk5=M(cE6YpC*xtE3qP|?!Km!}!4gt=^tDR{SZm*ky1U|-VXYOQ7y^23t~+)PxU_SC z)Ma#)!!~e_=^O7$Gbhk5a z-DjgQO@?4d3DU&EaIOG|pLw%L~|i{@LU8zGv9jhmjfZ~0c4R~y8s`A zfZd>u2Y-a*E*~U|fDQT50O*Gw_$r;;Kv3}gncvg6KN4|;Rcx+lgZT;?c<@Ng(muD? zOYsbK(RL7aG~IC8Y=Q#|Fkj4B6W+eP4rIMg0OQlD1xmpiVTaGZo1bMJ*QcaVL5?E? zqD^pv_?~U|fDY#%b)EG8!A=GCS$0_RTXk?$f&t0!qgy0WDe{p{JZA9w!@qm_njw6H z&irg(Tb@-xv#lA$MC9xZQ+&4lV4~58_&{9uM!ai_?a))H6Dz4l2r^H8+6E`V;6}P`Q3K%Llbk#EA&hL)iJl1PAMtw z1HU8deou3xNsu6`J~~CnCytEnUW)nwMG%X1baZqcPzvM~ z75~}R=pKmLqaHoIkrWB6+3!`>>e4{=Dy;R^Co(lPWdg47mk|*S$nOCr4h3=&SUf!C z_a^IMY^DFuUlIo12)ciieSk&iod48=!CGliqvt1CyyO0Ro52#) zwyEj+obD!7nF1-J>g&oqj})MA3e`AZf4VQD4RMDB`uX_{ueeQtIcgNabwcehq0A4M zQ;4($azvRw|CP9`mkOnY1^%SRZ*o)}a%FPAkFNq$%;(=XOIqq_0#U87cx(UaRns(z z5r`PgpQlUF&5F|Ek3BILZpC}nB3n0S;g+bIv+g!zJ=o<+=$!5#^N`N^xaDV`0uyY# z2n-M5X4_ZkaYEvg^+CL;K4jI{)Y6&2cl3x{Tl5{61VGDSwcj{xiNIM%fu z^h);%NA(LMo$EB>tJMIgbDc>f|gMqoDM>x=#Pq7`+lNcr%Vu6fgkGbq1La_ zIMxuqB55j!uhbf*KXa%2!QU{^k$6Qc{1t8{D(q+jfLr!H{N;&5L{tdHR(s&OS=qjZ ze0a|2ML;tx5H1s#?_d)V^-NBtfqLMB^&kUKNAt#1i9Hs#);nW<3WtS967{VnzfQgX zSgWHk1jbf{dRJOU_U-8&N2g0PFw{#W%jN9FqT$Tgz)EukIVxOJiu3(Dj>OV`FW@wm zBJ7|q{FWqc`4F#FzotQ}53m30#npuJ^t|Q5WuEawq@a zuCn;!D{+O?@ajH36a_)ykTX8{AlC5^q`xcS1-l1XPm}EL7JzDn)22ZNl&~LE%TShE z8C2@9TuDl32-6A!yK-SYvX4Skosf@)%-b8Nj7jYmTbQNI-gA!mBb|B7wuH|6_Kdj2 zW($Mchw@bt&WtID+wHJNXrDH>o^l+qQoS%A{mL3bkhsD69~MYnUEJbc@OP?eOe6`` zn7fYXtmnSj=73Dy0PSJ?^Y3p@LKv^QSogfH51ix8i>a>C7E-G7p6{Q{xqEX_8pc z<}<6ECcCXhm)H7U$akU<9Ovv4k@fEHxxWPj$1dS>*|cnV4rR4K6Rh@RqWM|knF=JH z3I@MYQ|-FYVrB|nTbm0yawvmA2)By)+dM?~XV?&IZf>5S`ETGw4*y*wk;6dTyQt%N z<==s@@E_yrblz*}*_z^VU^R@y-3U=8DkXf=Ohj)TJb*J$5_y8I_DSN@zG*a`03z?t?Td%g%S29xf^G&ZNs4%ltWy6O znIN}>vN09pKv*F!Rd717f#|CtaR;(5h1L(}aMJ8B2Dp%?ASk*4ndX7LCu(+$N3>WZ06SAXEFOP*8H%=2kzeOR-b(Awo1S)EsfA0ZMt@a#^f@^v&%zk+t z`CUnwMLxYCk+k1l!_bfp*&yWQ<)Iw()`jKNQ(*B1sfYSBOcUg0=umeCen7YE)x}m? zn8!4tY|j!f{X!;sat-Kp@WrIEz%1-#2G)AI-(X|%dAjx$L0xzpES^68BTz9V0|t60 zHyVN_L5h>IE0m1&?)Zy>GOkY=A$ImMgRvHF1>SB6vG}ga=*W9fZ|yfea6WBJ*Y~z7 z0{^_3YLsAznFP~Q)`)nSx)R#1PTgRZRqW_=(7VngAg7)hcQR!2!U&C1kRbVXE2L?| zdlbfKg@Q4L*)*d@0}oA?T&e-b(D_u4cu@5}A5O>2ncwA81phHWE8+Z2e0Vtj+UA%q zrFF)=hHD|p!R^@ek6%nZ7JnRzx*mFe%MZQYTL+T1mf+>+FoTCxzT}_3dC~$-F(kx@ ze#4Xd##IRMl)Dh;YcYDf^1|wRPb}Gl3#XwR#D_l5j$9@&_*Xy@&4(M#vBP`?>z*Wzx|hywmecq>i%~`w(xrqJzG!X z(H2Yd*uMGKe4(4#P2eR!hvD|`8}L)|z~Uw7O)01^dO+Imfd9|P9&w4BbwJYz*y9+; zJ^{vUG%hKxw4pu>S;_czSp2#D`=3f@wJ%_S7vI1HI}xW^AFx~}rKpD}_0PILhD=p1 zz*&Li{*Hmhk9;VE{+`@rc)H=A1b?+%DDC1|_s`J}Oy6V+=|z*}Y2Px^s7FniHC@m+ z^1FV$3jrk*LRRNT26Ad>sAX%-xFjH;F)lj7tx6lX0rWED%de$2wz_{?#=JxqM5s&3 zM*~k_S=qh<#0Uh_G`q1usQ3E$?#_;uhz4N}J1)FQtolKK+;cHhAU8@E9pVV>jAMn>}3v`kXK3YTY7*zGP8Non%r2Y}4q#rI#} z0svNoofF4GV0x6LQO$R~r}MAo)~cy;gbu_3kgVw-q-%T@Q)c(^!wh&8Y3R!z_{DC% z@n-|N0=9d@sqCgn&Whzf;z)`SQ5ho=J!qjsrGK&K6IeQ;J8@W6(z{1>{A-sKMrqIj z=I00Sy2MK2?YcSGQ^41aZ6A;J?}JdXQ!C0hF8?1%ZI^@7G($UUtAR^L&ZxsKDAF`Igd8( z468D3L%y$f;U#hi!rrzAcc3JZ_y8uTJ3in&9t}%sMPAC(fU7r81zEg%zeHXMy&gl+ z_+2N7fJ2@$U_1bM1M$k+VVV3)fSZ|Mb$;!vFh@y0Mb{4?R3xe)#l>QV1yQ;1J4hKh ziXWEVQf)t#6>^w z$neg@eu;a#9U*cFi5nQ%6=L9WSj^1REgOC5+a+z$tSa!?3l( zxqN|Mf6|emJ;vfRuFG!}(@VmC#XcBTnB0N)hm!bCK>I!PLCPWI?Z`>%RzcvYn zQpiXskB=IO`5%gIV0udXtXwM)O1}Y~`i@F~iatY=7(f_D&M1#tuLSsWH3zYLhrLn9 z6C9}Rw86)Jhjam6^)9WIn?s`Ht>5s0jpd9RbI3IxL8Jcn&vNv%dD-NaCB`1eZ)9pq zWK^KTS~Z%&c?0gj>*DdvbMZ|9aEJobWdwLd#D8}=QJQsSPE(7Xp?j*MyMCBhktc-P zrqQ)>TDa0&CL%yMs64uQ=(7D9Xhqn}428oouUg=jMbyI@VyDOWYQ9I(sc@rR{dtR7 zEC^U%Rm&qR{ZZ7geBF4Mr3@SR+bvSLh-zREN!H>EUl4V~8T5% z2SuUwr>7lbhOX!1i@sxE19LssuPE-kC5C+9x7Fc>pld`jsd3pUrJe0ne>;#cgH$X6 z8C#_fRe=WC5O682?=Vn4e2s+VXm*+sIeDPK0`j|fpW;5Qu%=il046myE{3?SsFjDh z&&{+e=uQ0=Pj%ZRYQO(jo%l)8e=J*I6@LuPAL64`2iCvol7)^^>h5;6^LV8k5fjjS ze7!cXd@HXHnQ+LU*?r}R7rNS>d^pqQD_To7;1EK=DBA@y=?-%yWP%b|2b9v6^86T` zmk*dx0C70|YhqJtxI7oK4`6VllFIq|S|bOmgxbPL!E%%X9C$Xn7)P%kO5{|?!Xk5z z+%C#$Z1~Zc(+L*bP0D6GsDu;(B@yD>nmHWikaOG;!cLDiC^63o)PI~5x4QRrW@sy5 zn)4dZ>?M*#f`JQS6&BEIg70N9B7YiqIPn|-NKUJPGytFva|eq1A^^$N1vnk{43itC z*NPDPIJL0a2X3}H&l~AyU&T2M53HyuC}61+UWEg_t&(zG716*>--SAI^g#(~KuguJ zAlb(q(ME2uDAf0c=9EP1aD?v#MsQS^2kuL@1B*mP4AzoYkUz|v1pj8gqEPk5xW`uo7*Ew0*kSVrR7^&)pmvJ z^1QGYC1)AM^_in(KhWUl)}g-x`Ltq768K7eF_}a5QTvi@T-qf|7z`$ag%9O`%C+hK z=;44GGD^Um_@mLY9G3R3>s?!&D~#A;}LF$3Rt+wJI&j)LNBAM|Lk znb5m;!kF!4IDRj)Wm{iAs*fF(73jd&Zc;U!U#a1TE!t3=p=F776NTOo;@;NG%U2CO zOD?x(q*1^>+oZqpK>tdO%zI61Y<&R2s|eDtk6nope6HQvexP1L85Pok_pCMab+_#3 zg(+`whE5X-Vt9ox806HhYji)ZA;=)(TjmHo6RS>H9V_vvfI{RaQGn z7e2!fa&prz-DgSUr=R&WI3~9>^Weu3=Gq1B-?*S+^tVd9;V=H|AVE5kn%lYTCxaP! z{Br?_cQdjb=qNiM7p$C)+nWr}tnl?y@pZs5YT@Rydi~qN$F^a{5?ul%V}R9EU$hRe zuab8SG>oX-;+Mgd!E(NRA$>dZBGJnF_0XbZlFzZrlr&oXP2D!MgRyI34sY}v?Hz@3}Xc-1c$ytpMz6))snSxlvRo+^hj z^N(-)1F-Z~5wzt%3Hy#AJjU}y3VA#h_V8+-K5 z4$ToYuR$s_j}ewr4Y3>` z>^H)0l!!Stxvo7H`8NI%%`AL+T()AxVf8^Lq@S;qPduT|L{3(D!_Xh%2^eECe_9l> z;{wULVr`AT)_5}N5g$6tL7F0HH3da>^{R88)-yR!(nI?AC67ra2r{g- zzg2_L+y&IENdFH*BkjR*H<1nQUA6wa_0P5V6M_*#?{i?&dvNxC3oJT6rmO_Yb$k$% z9PG}nhrwZ&!Q*POOUD`&!g?=eHXi`KuBFH}L*<6J;rd&`9)R$Gc6$JH)hXaL5waVz zJlR`8j0TY8o!#8Lls}bvb}$6FM5Mw9z0n>4f*V?z%_GfsICRxQb+_zqR7C>)M9Xb44kYmjp&lyf2?oJLEf- zNVudea_Miac@FIQDN3H4(^FF)kNo*VC|ijRZVaRi9nvGx_L-AY1?bmK3#Ad*B)Apz ziyff#Xqi@yT&T4)B($HCP*bP6H2R-^M3dYdgTSBl=FOW6i_m4EzZOQb`V*0*ugp=x zvFFK$2M@XTmx~Pljv6%3(Ur`5dImh6B=PtE{54+sp`+hL1BvvUUB2b-ra^lH-lxW_ zCnGmm55BRoZj5o|+b(>D`?tE9_P1sf92Kb!Mn*>3H4fk|eABbOT?=9{l`80&D6cY! zH1GN;%*n}_zYZhzyZti|WW20}@`-BII@oWtCJ^A(liFV}z*Qz8Sr5M~C@7e}9z!kg z&At)LVlQjK9tXb+8FlRmZljNaU;q8!3G)90CkImauH`$}*x0;rC{)XM^UVX1eb)NH z#MYi*faK}de;@S(`BcG4FhfY@JAg0ZjRTYn(!L3^u&{jn_ht7P)ZVY}`YS@=`zFZK z;EJK8n2rM;`K`VFS`gl5S6jT%FzChx6^H*ayj7RlM$)eh&zNBzaCrj@0&CJZG zJ1{a_tnCuRx&T>b?Qa>YAOS2I;JCM1J_2i5VRiGf6~#9J>+IXx*XhJ|E)TyiOYtcw z?l^7FzC7(a+`L`ou=A_YaC1a#!GCs?W6+V7ylbYVT`y)pFGew!+t}9wvkDYxWBKXJ z&yd9z!EgEgx^Br{v>FkRBJDU4j$qNv#yLs8Hb(kI~1M-wwc3@uapHx(upJ_V)G) zPX4ZUh7qCP{L0jCu;9>lcIi9@<=a|&WK@*OsBkI6mz0zg9R~|!ClLle(1Xe9I0I-B zR9t)b{b&u`H$@YRA%oa~Lqi%&*1n3Izg!}WW@u)UWSxaq& zE1Minv**vkVA?RB_!I3~XHoAy@bSR6qx7BNq_pT}ckt;3N{V`+pKsQZ0842Wj*=PW zoiJIq5c?dgrG8j%+-yO*mJObD!Qe_M zekO72RutISknpAGPMbC1`Q6ZoSd`@-cDNL=HEQFxrk4r|U9#DPf?Y`G9j-)&f)$HQ zn_tC+Kk6rb-wm=PoUWJnH%Pf@2voFKR9-~Zr%-X;y~~b+qentoI!Q_bEp}wgSq6|F zZL@FVT-W1#LXlfGaoHNSe0x${EN8bjbgUCSDNSPjbLhZ#^wOT&BI-PDnGDO4&AqQg zP%`R7pilP;q%kkrZ$Rh4@JME!F6`}Rp6-dS!bi1ka_|Wc1mlqk)Mc!&j~E{bU1@^7 z?Hbq7(dogr(lO`p^ z^qtKgs^^JhA6uiMbfw3b`yV(fkB*slzvG*;ADa35w(H%vncy-nO||H%dp%8tvyk|l z<&gQ1-jMza=P^6JWrkmZH!sB{BrM!KUH7i(yIoH9f0P<{q6#ewW9^CShzu=q7t zt2_frtydV90QgrXlJNTVct9;GyH<0+ zYqCfAYB!&wm_X!Xv}iO^s>cblRu6hY{xLVN_|$D47u!WbYS+w28Y^}KQ`HTBarxcl zrN}KBS2w}yYGPD)O&PNm^h+T6_R{bI<3HHp_BRHaF}UAMT;Wi+akW-t!;VH+rsbGmV{GVpZOi|8!%Ui97O& zwtm3F+p&ah;??3qc0ykDR9n1%x1IPBzP#({v^gLD_4A~B|I%kFz4Y=U?S8%Zij(WN zxxe=3<6YTz-hXX+qED6-S$`)y;&)T%GM9mJ3y>S_XmoX_R!2MY?%Pe#3bvJuBR!^~ zl8X{@HjRAzHv~T1er5%YMUs+8LGurW6E5HmUahzwudw<;0S1oaksj#Hmn#%3`P+5j@fUt6Clps@ zcRIsO`E#ycPw-u(=&N(wUTZ1racTURJD5T1w=uQs>zX&X9{qcqviZ;L%afDb-Tgb8 zOVPsUT|vZhlJ}qY_5WIy-{`)sf9dBIeRtm2jpfjsq~TD#lJfQ5TIOeKzGXqLM)8@s z#gNzUQJ?CvH5q1Xc?eA}*tUJ?!co^nH|EBaG$Qc&2sfX`$^F~U{?F=*DSGCIXLtLP zx#XYz30kPs#;PtWs~53XE?fNSTy8?NZV}M*=KJzZavr2@N+9U;he25d#ZQol{_D{Q zyCXD*LJk@W(9*bna5gUs20G*JD;v2(^y=v~P*JBI2 zFHHHXR?nn_GjOfHq)JFe+@GzxW_IRr9iJ^D`Hh0FjlMY1eU($~HVMCG*+;SvEt0(m z6ZFx&gfszXrE|(P20gqEEFxYd$xmm~sC`5m7XHL$(6H$C;pQ);yDD;#(Vb+J;VUQm zm%fCh;aK7(Cb%|CzCCK`XlO&H$B&*~_*0#o51*bEp2z@$DXjjjrK1w7i^Q#)g9^_g{6rBr5@>a6G~Ci9hV*XM(_3V0ld zhr(}9Uwv>z%RoQzLQ{kCicV2>K6XwqN$$GA$2P`lO#{@w28P)~1wq8gkAsLM-e-tL zN(p3ETL0N_$-KR>|Ksl3Cy%vl{?>Rm_sy8i{`B;ioarbm^eQse$1ojsVV^Qy_vB?YI>!bPailXpM zhqDp~Qen&N9k)fgE{;bgh^dac?O8=(v&EWHs!Y9EnRoZoyC1HjC!7lcKix{+NMQbo51f2ubcnV!NmD;}5wxiOOO%M6) zEP?Z(@N*)G>!@iI#}(dpr7r9$iFQ}Z%A!4m&0}QM^Wpk(hzTt&B{oeTSX|R+ zttlshf997H*_Y@>Z8r_?)8TiJ;8UUUQ3bM6g-}sV=&p(wDQFIjjfH_daQH{sO`Y|9 zLk&TBEsVVzv8L8*yV!+cjy?Qcc+#XiJ={3h^`%>lmPfxHUNPi9bEK~E!238sG;?rS zMI9@oR`1{{Fk*DKsFC((^RvXCjg$>U2eOP8-hI0j$CxY2EAqYl zT{6)19flKk<>dOpmx&(nlmOx$XT5n(^Ta=qpz$D%G{o7=h%h^>ls-H4Vl+=>`Ry1# zz3wrGmf~IGVQ;+Fc|Y3sM@0pp@#$2SUj{sV2BItRSZ8O)$~|-Ms29)`zgWgSry+;eQX zVg=b@Vl|4Pr2ae+v+A+^H$BaF=R5*D_TK*q2h@%K>zKfvsO-t8zy=H{el%_lG={kY z8;c@x1=-2tV7)cZhYyCvNN_A~pHThuV`OSP3|0-Bz?NoA7x{H%DZnAjVonizuKr!5 z4g*G;*nr(@r=A*u`nd_rW%16$OtK3<$tW1>PT9{;ew~Xo?P!V^AHSoe!z!_NvY3-& z6y`4JB;cxXGF<4oUX?LS(2U};`do9+><%N()SYdvWMr6?OlTH6VrTkE9UD`0^9!Qu?CedmWj8$P~Z|-PG_XaB;wFI zB?!1EevFp{S$tO%b)3LojaryKO1=Flf~xqm{MoA+Z^HL!l6t@9+v}bh#n@|hDH%Dh zi7|BkPU1_Cc)WFdOeTFhtE2qTO>SDO#CC5Que9c< zcRo`EXWo;;3I8fX6-2TT>eDWbpFBtu`sqMZj%DypNx4Xesg0g8erU|l58~$<1_rN; zv@93RVwf|za@Z1;)XjOPQ+poc84DUwY1fr}Wnr2ZLNn^MXf$PXG8mq&>9D98dKU1! z`X1)-`Dxn$ z3eM&3SUlUxvV2UD>JgUdf{o9W)1rjW$L-uAISqto#X9fgew)M-q6_;*D~x8YUhW)l z9gSV30gooHhUz=GxYd8BMs1C-vsBJ(9WG zyyNRZ5hP%+YHzdmW@fFH#!uQ)-~32e}y`oprzTyqfhia2|i7I8{?{6~#$9u}3Mx+4l!^kCM^3DCuBM zvq!RVS@+X~6~Ombc7L3y|!_v(aqt3$KS*YFSa+h$swZeb%9TUxE|lalZXZv*Jir#CF`mZ$ zGQNkO0JjHqUyYi%oFLYigGRE}rQU99f_O)(ZcWD`p9HrjjyYh9cqcsO{>nn#K~0D$hHv`IF3st1;s%P$^#^SMYDCjX(7S!!?Y6j& zw&+v;-OI}?8pi7{dMzFV(~b*2t1S2#ZI{-RVq#tRbUi6VpfRB9#OKGua)xcXhqtIH z3sZ82up^{2o^@*Y_`ob2`u=3Oh%Bn;<#uVnC(5~)vPF&FHRG0dtb9}<8oEjr{*P}O zSw~n!FDj6AHd@D){mhhS7NLKn`P)+H3&do#641-4@N<_Hwk@0&jP=o9DI5 zpJww!0bw21;hHv2u^PQ1l{3Se>~F5wm52NN+OIIGqeu=6@WH)*D-Ml`x+-uoYO)+> z=DBoYM<=Q@dJb`>s>9PQbYgb&;p`kf?KoNd0@hs?g$jH@pcIEfl6bK7Id znMIPrr}XHYIzTWc%OUF|&dh0y@4Y>HHNan1x9Vq&eT)*F?R}lolQuGp&ke2`;Fa00 z5q%U!g`M5U!m@L5ngCoiCo0~hd-#~lBO@9d+f)Q$jXQ>(H!aEzk!q#Z4FGY>`i2Em}KO{r&Y&F{#|mH`{TTSek=O5cvod`ZFw z*|v|5uZwp)c^iETI!VRHs~-|cWuoig}i)js}dbP(VXp91{gU26cl2}zNa8K8M+Z@CH zM23;S;Yg;QF26m0mn@!9Y5U0e<;O;z24!?!|A6^?RWqXow6RwlW(Ex;JGlz37l)yS z^tgeRDtB4pAH*siZeFGw-h2}`(84+KEXii`?u@cJZcoRPPgSgL-5-`?thNsaI~SHJ zu<0m{=#coqteLcQpU`!a&OP@b|GsE6Msl~J9u2LMloHRYY(*CKbcyiGrhSTs7|(|+ z_}CLGu9954Y7P217baA)EsxK1`I~ z_#eIe_)+8UU-`=Sc=-d|FU8@(pWyS_uTRZ{Oz8KjCbxa`6)XAjTGqH0-^GrDOW|&J z>~B7SmxD`pR%THfT|*S6zm)o3`u!R@_gi6!3ybCT5=`%ow83P%_QX<^CQgZ8l%daX z$56U3218l`9=gr8*pSvz+nKn;8@u(bA2x>H+~!zuv|I)1O^H`*+&+=(>J?q7DIZLi zdG=%e=P>q&@<__g4H^t>GMn@Bp_5Y{i9`?YN77Xo+IzIm+Lr_zi6%|fi#ae9?wEXx zu=yC#;&#<L|)o+lkwH_6PUf5m%74sL^t@dv80d{yQXUvf^V z)GzEP12Tl+=+Lg-#?CG{FY3lmK?=?Cp2e;^yZ89Ihmts_y{^Z?xPU0x>DHU}q83i` zRCDjs`MoyQ!KE4l-tw`y0vg&kwwQ;)fAPBcrm1V@#V{OctJIGA=BR&P*MX zS2evqePI3cjr9}1;_lagAv9z!OY~y2{#;KdiJII`!cXi{Dj#H}tHEOjf(I zvJ(1j5`E#!doH(lcPS_RcKo-WRYOUAU!;wO2ET~^VQ@hD`BtFg`5s7)$O|m>qOP`Kjr4x-P#ddQ((`-ibT*l|cGJ}>HpDhEw7xH*>Q_BoZJw(&+LdE$R z`F37j%Y*5rSmF!1-XH0vjzpqQ3Faqge*CqYDLKr!F&{j*Dmb3{N^|KY^H3LA6{hxs zciR_cCj4Pz=(-(d{kNS-3Nw9i?L+W*xo^M?wsj24Z=n8mcHBK?zJ^iPh;~UM$E|>x z(67&sh5@^+vqRP4i!7_?TLXmiL-d0)Q-OTCGYvs>0|!gPN&VLnwG(a@i~cM`n|9u7 zJHBcXJQpY)ekDs=vH1&jNDU#iyBZE$z7YKJfIoP)bR?3(cm%~+mN1|{X0sS+B;0zZ zyg>dI7x%?+4wuzN?9gp5L%G`dD;3z&6sV|Fv?#oojrub8nPVr+X?~m22!-M|bqO|g z;rpskxT{cPnq!v9(P$N+M3?1AXUY3r>~M*9ZhJ_0m19xIQ+mf^J?}wpUk{sh4)!FH z@MvJJH<~u$#^$yd{Ia8?V?Amfg~s)YKUx3Y^%#l;2-VNghfd}+PO-AP<}~J<-}(6s zVPZNp+$FX`3BFA($q+$6kno1a?1@cCer3DOsH1Jz$cXZn{6y+Vv}t@;GPd)1{BX9t zd{tgQPy0gmA;L;lBpE~L!XtyDX!$;clW=Cc!KPn~%onXaE0u-zqePt?Nk@+4o6N~K zXKX~JYR8kWc&(F63FAo$U*&#}!Tlb)uEFy&3*CpxI#smv57=qf+qkLgN-0ouu8Ktn^2jEo*`r{-t^&q^-`&9`F~=~!2G`oFT80)KBCjKuiey;G3QVxW`A zO>=rrQvq(fwnmSj?yrR{y6GC#tqHDom8$RDmEYCCKWR>B!gUDuY6#)6Q46nhY`gkM z6P339!Nx&9*O)tB5K0>j^0z_9vGC2M=B&0P8FF84pxZMfv{m1%|MK+_=X8eJHGFY; z;x)p#+RmxT^*d>ugufpLbKk9ClnC=>LK$5_ds_88sdT!OU-bPb_N!b`yN?v9#d17k z?YQ2{p=j_{oLS+SgLeiW$DVwBoMT-z#817vg1_fBA*n_i#Pcd7Q(10sq1z;|ef#Yq z`QO}DhGZEO!we#v^Eo1Y}h zW9Iq79O|l#Nvef1%$RiLAfsSX5aEUV3Gu46q_b9~>ZLaNdj6B-h4)->v;EyWwU*W5 z#$1U@Owp1h6sRwHJ6X087twYkz=VIcM*r0WSn4_gnX z5u%Ej?l$e8c_)B*KfJ+O!=1kPF&&3^aPD9DYgD&}mitRVdIbf6gJS70@@rS7kCsTw zqGy;V9IDzJYT7KS+U!IQI^&x?aEy0rCv6-4darq<5uA~C-z4mDgUAenE0u17WKkOK ziC{po3iVR{cSTda!@!^BR$=|yHfT;4o~?}MSK`pwzD!@oN#_izQ=aCeaC(73%++1V zPNS<8jV3y5-cQelJ$;2?+Dm5oD{&w7(_6dV?J38Y7N#+%;^=M!_r9avNB{25`v6sk z;NFAqTCKhxWL-Zfafeh{W#~_-zEsXiF+?oBh<-kfms3V)Zp0PxM&H830ITwMy@v9Z zk5W^vp(feprz`Bm9h6?rGCtiEjh*yR@4u@c?tJ(+Bbv0 z-|AqFtoZW0^0mCEB`Wv(VgA1f3iXzG3nNd+V;^eYO@EMd)m74jkZP{W?U&6cjeQ@@ zR9KxGL9PFSi|L~A;9~Z|uCjcG(_NDPQ`&h)HI-*^JTN38Am9iBf*^{B=zz2Z7807Y z83czSU|^`B$xs9-N$43yii#it!UO?90a1EQs8W={z=SGDQITaxC?Xxn-nh=rIXnN% zIh%8mmy`V7`@Q!o_ucdE_kMnM&CXoKt_L4q6kX@!dwfxDN*z0CpVNn$^g;Sp#Z-;A zYDox6@CSrwasB)irNcWUPpeG}jEXt8A3OvRj~zcS`8HOk;mQs%$ZV^U0y^H7vz z`vb3~J^lTkFh#$&zOgvi_Q|;vYdVydNf`1irU#=8-TJSg`h45yS%KqT^Wr`$;=TvC zl8waqjYenpVFfh#W5-J5mW_JzdxFZZ8b0R{BFGU=YL}5`kM6|WMS}`rV&!e}y*qTS%LNlU7E-}_Y;b&`k zLpsw;x@7Lfef$$X*kr!IOYSzIH$y2$zDH1a=7WzQ`X?r|aZi;XSa_P?2Q@ypS4j5` z(TU(V%^Q!2qf8NS=1HzY>*&sB;3 zdEo)^sW>sM&_&YOUb^EQ%^SZrC_f^fiTh&{?lWL`>`NnG{-aI)-21Q1_V78cA|?9n z-NSZem)PqWOF@tsM`Nw#vXUV-)8!m2AL6nnPUuF`#fL}YSX*uvJF z4omZ{f+J6MU;O*`9@@Lh9dbgD?Z{+QL*mv%VE0jw6(G6;!vJIcbTbojzucIwYEp1w zKz3;VPLZlQJDXD_T3qkg6ryCBI=U3O0jivygX=f^iE-i79}Xv+H`0z;nxvWua;-C} zXqD^hA?wc$S)5DiYzHBN!%Qj-^R{dO0AaVN%k8`j$W41(P!NY+ZvE=lw=3nq6tby* zSJfM~5Ps3tR^*DWuREkadW62dW{cy|O1e=;PU<`knWje}>Ml+Idayl|8mAJ}wE*Y! z(|4GrkkSfpp{v2yh(VwEzI>?VgWj}!N&+-8ne6cDj=)#3jB*2ryo z?#-}0^u|PoA0*%ME@E3E(L3+eTQm!2b9lS3BO+Ed=?xAF>wtl_usJwKN*JsvDe(mf z2t&PP>p&B0Z|5}PCc8s2T6Rxf`SC|wp=Gh9Va_4wId)(irsV>11O1`rgfB#ntuDW8 za6ikjyfekZV1eX;+;~k`qB3g7{j%Fr`y2<64lae3`$7M}UaP8iV@3NGaN}GdxPAiT z0iPl{0*JcTA>)tc4t1RWecKft(nCD1wl<_BQFGx!H942~!F2OeB$0W=sr0;(CpBSk z)rqxj>pNP`!5%`#1Y04twG6~p1A6th!i3>06SV(C{XwWtG4xPqNJxHJ*#YR0Qj@Gw zlxH(xn;b%!a zH$ZPepOG%N{#fNUz8Ta&f=QhL^b6`SN+=tfl`{Vb-dpH(yOW6yYDPQQ%x?=*Xmc)A zV@1X8RflR2Un?hilEYCjY1*$mrJ_oQ{`tByOXatDRY*9zDdI#th{^SDOj3C`-^kxG zbqm^Jq<(LEA#jPh@n)r4s{3i=TIsyPtDH*0hM)GQkMzw>#Yo_A@lV5=51lYlVjhz5 zK8;C6J&ztC%iD<JZeYW@Z1Yy+37*2soP@OvI7Ui9q8mjN=FgB46$e$VTky17-#f;}75K+0hi@X>+a6 z6(oI#=*>_x){rnNwvLrCwYvO%%2{yT%5hSdHgJJMwpYfY`0T zp3d`y8FmDM76I6+StAR$nSe~Cu2GP|j1}C%T*iDhIYNf(6G60!n>YDugXYZdp*)gd z9hWj279&FR9)0GDovR)QvGh%)O&e&IxP!; zdu_0El5nQ4fy&J25YRcxVnFE8V`D0cg`8u}TSU3Sat(*TpQ* zXA;{ZKNd(;u(^4qLoe=SXO9^Opq~MYP~K_T{vCVFU(cL#x8Hn0A&WEQH#E$#m8e|?^6 zAqi=c!@HP$lC2O(C$>d^1kcOcJB!SDQ2(>{#4RmiDx0?XA)_T36b>`bPvvqU21iB= z1WDcsV$vit{=i0FU2bWW8{KbXWK7G)ncS#2x}$_XcUG_}>aTa`{nGASsWN)>>Ujke z?7g4uL@CF@9h>-Zz*r+tOPq5szlLsm;Xlf!f zCczpdY4JrdY)6XixN$-`lAt9{4gqp^aMJ$t&A_pTGA8Mt5A}Z+*>Z}Z-fYL*UA9EP O%hb^P{1biW*nb0@J+h|& literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/catmull_rom_spline/catmull_rom_path_planning.png b/docs/modules/path_planning/catmull_rom_spline/catmull_rom_path_planning.png new file mode 100644 index 0000000000000000000000000000000000000000..1d0ff001e60bbe01787ab8f134768a6558542ad7 GIT binary patch literal 33505 zcmdSBby!vH*Dbt3NS>`?gj-!q!dv=x}~MNL;-7U=xyzR*FQHJV%kuYRR8c5&Ula;$ z5(f)@!{0MD3qOP%Wi=ch*_t}K7}%Sjlnfl7TiH5VnH$nOo7g*;+uHDQ2y^hT(LZx^ zeC{B^$!YyxZ{V=CH{-mfd|?;&co`Wtmu|3rA!JF%$NwtB$jV6b;Ndm-4g=x4_EvXp zcDTtH2v`;Vu93`fHWLsXUpPAP6kBasJsNSE*jqR(FRAj%T{=36?=UT-Ac8*|dDTTa&AQg3!fq`M#fCMEAFN=ksr@*U0fe%q6$j7-Z z`NFFVw0HmS|FBXhjVNhkYm|YOh6cIU;kKRPZI0PP=cg6U>`albi!294vY50if0y$+ z{q3`Jq+qa7L3_~nnp({DEpxJG1nc8(4>BHHd-3AMvz||wkJ6RrHs{*iysHQ#_I))A zO*LyCh{o|-k}^fM+HY-aeDpln-2T%WNX)D(R9=Y}5g8dL;>3EHO5n!Ln?ch}!H+7O zt&?1*FYd04E-Y?d%2G*|pg3iRi)ZN7NZ8h#2*}IJySZmaGOO@7FKZYY8d^Qd3Yz`V z(t{ZkWbo(Lm+j?YVjmwL_q|o64~a}3hlo|pW7By`eO3LU zU0t&BUS0R2{al-Nnf)t0?}Jw`+*;zVj=*-)|!Iapn{4YEKGDNy%Gki7uz7r=FXw%&0_3pClM>^g^;v zQnpsf=FXtr!l9FLl2~i0-3$&cZt87+EP-!NWC~!LO=B1u868ZVoyvW=|6ZfYo!_KA zy2#VE))$Rh=(+C~g&2{%J1u|5%6OIH`OqdeTIkZ%zN#uF3cYIzCUcnZ+7m7n87gE=U$3V95WbZ@scz(-f!3ocX z+15xF^_;{83*vW`JuLb}%v|QbZd|!?Wq-R@h4*ERWB<3uM(dMx(Jj1YU7wW_1fn=} zC}DbS%H~KVj@KLTx-a758g(a$XK9sm*^lHnEe+KAq(2d~8mi^(7L$JdoC`*{(8`>A zLs&Qt2Gd*NVtYU8=Iz&47|A6(g-i>FH%A1^NmtgV8e$ch5|W*(Pj*MqW}*&?p5*Fw zu9QqDzhjWSsaq-ZyWGiWZM=$NSH6a6BV6)y@?#+FCyjhV3~cPJ&2~;BfdpaaWpa4e zb=XF4-x7{{AFWU?$>*lZ29w5BFRZL|Dhd9M`g5|kGTP#`_gn74146;yj>P`h1oLh0 zZw*(gJXuNd?i^dIIa4+^zJZ2@7R9NTBp=CS;_j`gdIk2)$EQUW`$tE_l$32S*e%aX zf*)dHV&-_A_SX$g4;JW>d`{i|4rD9n>(k%9ecN$$EbfD-i>XjRno6^l`E19<)Q^1jrvm$ObP_67%W>)G=)Cu*u#;ewe*OAI z&ZUn+JxWtF_?dDW0}E?&I+zpvL7HM5UM}ympY(U`+#wgVp{_aJ#N{>ZNO9emK0e;+ zR?E_OH>l_HAtU4FxaXGA-@dQXFn8G=lLwA4S`;jR!SL=(xa6-g2eWT#U+ahRjmkU^ zc-E@+XxX2B*KY}{Gnb<|blNg=tM9i)Fdi(XhCk~~y9_7T zxGPau?Cf}p&w3>4N%qs*Y)rPV3(T?j)SJ~>3qk}kI zhb(EC{anW5Ow!!S%}c3r;q$MVlk#33SV|t13DXj>&=&>?^}WI+>+mhpDzPc^?t=5i zW4$z#pIQcYLs8tHqcciPMD)&lB97NA9?b!!r_?NctC74Rs z&)!S(>YX^tsaS2xJNc8IEO22SW_djCLxIKK_TCBX8}`wNh=`7B*RIWbtW^ybtORpb zb9uPA#rYimNyl3g^*VIq)gLdlGb(P`|8YG$HkgFPP{Lt8Z zK0eN8{_CZ5ApYE;Q+Bpag)@W$IHC8$X~l1JqB4sfmb~SUOq4>!xPG z=Q+2Xzx}CRN4qkzvL^1GEp$F(_L3*$xstm``boVTN*(^&m?z(`>5{J3&SN+%b?SOv zO}=OsGSt3asdC?G+oY`BP8xCa$GVLEqhKHrPNiw7KzDa{xRz}dzw~bibLnsx`m!`5 z;U=EiSdV;1)9;Mu7p_(@G-Rl&tAjy4%6`hP>pF#5-_URXJ0E5AHYg@$!;F!i|9#Eb zX+mwSlto`gT^NmMmb(~(DwhZ*+q6D}6_j?REB9dcaH-vO2uTLLX-eAVjw}s(9NMK) zFkt%~k*l|!bgT=VxPAQiF|IgS)P-YkXHM3_f)zGdYhJc-YXrsJa^(bp(7*ke4pa4* z5=YCt1G#$PH8nMJM{;4*XeoC?DdTi&VEkDc`7at9W!}Id4=45Kld-A=seZX{GI9!= zalw@u(p=^KbTIN4rZ?Z_w@8}uhqg+$t@WLqxpvN)j=Zx@!HL8vJIEj#o0|oR<6Xg* zuCf}(TjtBWzH+=fY8&0+b9%t+vA4=7BqY>6xWANJWAB*^>$TB9Ac<<;c#@+%e5Jll zs8h`8ubRaEhYZcG>VbkiLou0rt&mV|iTQaJA=%MYgT=uZoO7nED=FAS_ zrYfM8`ObuvEX~4#DuMO8*6~zjUqvB)l{+o*xNXj|?Nv!^Pb_+k6j{17tks+zE>#|H zwu>DuriRc-CPgqROwY|Vy}c%#wOQ7&RO25s77JjLxOA&aG>+Q{D?z}TK}<|+)C{r8-K;F-sjD~CjG4XGn|9I#dOfB$8E)KoxwyE9H~M!l*Qep6s;Vju;_kb5 z?<&tuk3y)0fAQcL!JWkIPL$Zv0n}*wd1S^}U0vOmsU9wQc8u&-$o+-~`4FlYu3tYuK!TN|lX(qpZvnxNUF95fO; z^oBr!^n33Z#7_5T5+%GudiMxu#eVdCedKrME|;@%x$OBAI>3pJ?MepOHyYOX<(7}X zsa>?SwS}FSY;Xkd?CruJt6B!(%1BZB^9pB2+b2&;Y&x?`#@nJ;9+le9T>^OY1>jRh zlDKHY#_D)g!uwn5zaVUj4ZbHsHkDjBZRhus82l6&Rh-%Pd4C!sJ(EsjIZAj76NJ%wf}<1ijYCSpL4CXiXn%ELOI23)4P3xEoN z%qK^C3vh@&J1lg)3=G^FG78sB^J96EMQ+p*R%FgD>avRL%@lZf4B$=_n`Q*$WG;_g zD+Fc2RPlTm2nh|HgNXkLU^y}uoHfT0*tD+nqvPE#Twz#og0{5qEoKm&zCY`E(buO2 zxVr^TF+i(Vb9^4&zugu-RBpE2+Flurfel`0Imj{J5hwkg^)b(~I!wtMGR`i5^DIxl z-;{kr@(}=W90w*L(I^y2c2`_}JCW6#>{8iQA23b$oQVUjxdw3q*=;2g-U;3(hiJ`G zfta|Y>%SB@Hy{BKU%68MNJU&0aAUZ{;j@52YH@cy2ulXPKFdSsdlwXhlZhe4<({Rg zsu~MB3obSWr!@KiedQwr61D87?@PwrgW>ACk)eP`g*kK+IK;jpJh5!UnL*^6gb*Mg=r@9N9=*PS38yg!2leK=82lEL6 znLX|8!SLpdF4491gN5X+-!2nGgoIKs9pqxJTz~;M*F7rN>v3-|G4Z&pY9p7S`T%E?_l%oJX3b}3GfC2Z9L_@90QEw&SurVzQh&M1M#%%W$ z3yQS1HIn(_<;zY`)-fr-7N@jXXWYAoE1m%p~1I%R~KAIl{uk6!t>l;o#8U zy!qp+5B-M^BR%eY(E}fyzta|daVmW(>b^OrmE<<9g;e1FEdK{8a8GI--=NusFAC2O z`4UA;#yGTngUPO4tJ`6{Gj(WA2q(b6ATME%4aseKbNkOP3R^$FFo`=vMETc% z3NUm0bA?(21Dn9Kl12j0&W@1Ic65(Z6@yhh;M-%~af|*JKOb<#Ssk4+Fc?09j1=a$ z!%8iLs&F=`q!BUR9x_RPaP6iRXbz)_ znOQp6S|8MFUfDKJUEty-a$Xa#8N8)S{kPx$a3^%sx`d+cr-FJ^P*CZm5*%M*CPn?J z`d7=NCEQ+QK*&{Zi;h zw;LI6z(%3)peLZ_vhg`J$7tSJ3e_q%Yzm<#r^RR2x)V%#SE}>H;}KOEnM;lA=#!B5 zkje!r#yNl*$dPbd{OJcl-~+^b85)%h_w=Pyj_L+#rt$Moo02KpmWr7s@YtD2InRs!g~MFzGl_}8^{IO$Oqg8}7E zyyN#{il-i$T<0SErY>kRsBr&<*OC5$@=UQ2w$-qqwtuPNE4vHVkAHiMez(M48Kn|` zrK@{jsQ~LN5;>gM>&7(bFyBFOKZc_dhW`wJOZ3t9-~M1gK~V4;4m-mt^rYOrkfxHH zl)3jhJUktuq&8sHloa~RJ{w#X78Zb%Jzo^a;F#0sgehp2x?B^V->Fq>rXwc4+dcZ? zi1cTbD)Wq*x%Xq#%*l zmUctkNiO2}EWnyZ)Y%xYbupWg_B~jC{}_TUl2epX0>z={u)kh$EN@r38cyle^<4q? zjkaih<>6>{T*3Dkj}FIc>hdQhV^_kPI4n^7cRqGYuXjrlQsK&l)%K)*W^CcEdXQ+R zIpbuO-5JYmVEAM6nqy{2E-{{Qdh3EG(^?LZ=h7Nl{TG5YjJcl&yRoobTWlNp+GN&{TeG+KNGT(os3Qc~|r^ zx?M9n?aaLSoztqh+K@P-jTQ}uXP1fIGg#?HSN!ZQ-pOFkZg@P>GrUxYU4rX-0Sixm zZ}qp;P+r~NTycYXjOI|P81o~DUl(z3@(zzQwHzJ4rz$*WS?bR2c4JPFpK_1F#VfSt z=2+c-KeJp~dcEajH`Fyg#bR$=eWv;I;nC+?`oSTX}}gIecBL)l{#a5VHl zy%?Mv?x+C~HtHpP=Z+8*O99sDD#=VYW}AOsg@E7od_+h>A_*X=h~wg9-yk7yNrW^s zN=LgZ9}eU3%pT3&BVwY9OPuj0F0aYf&7{r}EeP9n7+ENtI5Igi-gJpvY{_9Y`(yj<0Us;;PmC+Re;rBRJ!beysOCq!!CX*@|MTVR zOSiA`h01fx_C@P!QTkw+0v$clKrS9xY*xL{xB=4PI0@?THHcm z>G`g+^xr>_^+HzY`v&-qoZ9bQlZ2 z*@Bv&5XiOWFq(FNndCyxQ?BFRPJCMuBM9dn^OWjqJjcmKl=35zQ~PV_#e4?Sy%iEh z8e0Y!`&fBJl|&c`m)Ebe&N9q%*1XKo36;-1+I=r*gE$0FA3G^Sg=RD)_3In!sCt$|634nYqpht zhrYSH$@EDTBm4e$hEJ+5>-ErPi`f;(SU!}=txrp=-mH!?ow-HCf9BMovhAN>^Mcn* z|IqQ-Z%WoDFAW;#nV1%KqGV;nqM!f~Dq{239}`#|+CuM)ZzSC5HH(em43wkeAGjf5 zhd%C(ODVt?J>;>%Z=_=cLG%F-<1ued2*t|Yi_SZx4)?^orgY<+FBQ@#{V7DVyhh-$ zSFgZ%yZ_tIO5w^giQ}D^R03I<#wp;}8^4Tk;dE8`o9f*qeB45}b$kHHx+C%8$_T|E z21G)CtlMSw&GZqR)sVYsyo4AS@IL}O&%rWEzc0`G>2xFrI2C#k$}qY>mvO%|rEC2C zv3Jv4Y>l4Aot+SP@1sRT(s8*Qp323N>Afo0d9vad5v9gq= z8QI2Aq}`y^=0u3GzTv0*VKOs!vX5nd-{{%!m0!Q~=kB|%-%gEL-)NaiPj-BxA)}oH zD^gk{hIyN7{)!@jJ2rmpVhP0ZLv>G$ApCJ8x2|*8B__8Q4?)aV@%bg zxUAD>X_+Ys=zPD~*i3mro>g7I9iNQt=S@Q*I~L@94>zx3R8@u~)u>4FD-(6cU9cXd zOn;%C<(nk_(bLU!Re0v`HW3kXI!qlci{5QQdU_PCE6V%0XOY5lL)Pe0T%no4rm@jM z*?i|zVK@D?x>IZ>h6r5b(mk6r7--+r{M7aMb1=0FFjlLnDyu>t%h7t^wMD;z;}N6B z_gqFM@eSM?4kq3U35n+|H0!@zn!jBqW~L-oV!lz!oGj%k)R&F>D82q*%UPU*=v@{v zaoVX;w+Tc37zPjsGR5nbbZOY9O&*A_O4+Spxj7G)xOw}c={@udW>%^HZhn_@a<08uKY~eVazM*qUQvmMoxvHozlczD?AyN6O;dl;4HlFkcaY0W zFPO2(?k%P^<4l_+^SfV$^d<$%e1k0O3WgHXv!43cyYu^YK#>}8)NL&ow2@?J_QvX( z)}h~%&u=k!9Tcbv$D;K@CdO^wNqwWLsSDWjte482`RA#$t43ngx!CY@JuY`8<{xms z4q8BZORd}LrHcx3#RF*i4n6NF zAx4H;YpnYE;=}!ET%(kGsuA2@9ZwDkDJ}++-nRIr6fQ3_mJHJybX9{N=kTCTnxHP4 zJn(J};x~!xM3MIj==am(G#3FTt<5*$GQ#T131#7a$NKQ$eqXjF zoAlmRw}2=uksasxdyRMK$qDtdI4dp5)MGdo)FPQ;J52XaJ&fMOk+O#@Vf6m8a#m!R zK16zM%e8-D+3LsAE+^=@zmA&l=8cZo+TwLbTPwr1DZ`XFCC|~$|9$&)P&+ck`PVbC zZ*wudJ>54F@+7|-`U1e|W7#Cv`dF3qox!OwVJ+&gpwgR2Zx1_9o{&vz0LP;xj3V`= zwDi=rxsgrX&j+rjZbD9N0@ybgIAmdo8~v=VU<8x$50FZ@{)|=0(-ps`__Aa|z#Rko zGS56E2~qf*0NQiN`i?6j@1cuiz!RtO{n^9fqgG`*9@9@tPhrIUt zqHs-YELP+2Wbflsej~2dI)4G6pzUmIh*8AE#9yJs1)N@c@7C_xgbI?Co|HS9Q$2=# z$(w+2JMv<=BRA7~-J&*)hc_58B@QsYsRstq1yp%hJ4i81M~yL|oT2XkY~_28)iP$4 z?pwe@0Gk_~5EC=X_d2MQD*>}kz*>LD0yegWzYzQ7>fvvwWNkz>sv+P&k*XD% z_NZSuRxz!z>UouWv#LXd%Z#`Iy6)COL#10R8CxxI-k+3Ai94aD}X=>r1 z83B_+_36^$7!WSdGot~7CM#x=&KYQp8^v|A!wtWwgQ|ABRxI6goTDIc7lZvUdnaS4;yG~bf9pdY=+7@m)mNHO8~lL0MiSOy`PBtLfM=s?lJIH zQVJ;}!8rnLaxMJ%D z%Q2zKCt0Z4DG5Dh=T*YY%nZxpZ&7mCQsLs5iSJ`$$=gh~f;#~O z`uLnFj(Yts6zF_j&y#A~O-v&I=OIz5>(W9=Y_SvN=yY+9wXR@%v}N1SfYBfAY=?1w zeODniJ)00}?>~%+mV?tLb=a;xyK&s%lNk>me0ph(-{!X+_Z{ENR?aM^Q+Ldi@ZOy} z=-k}gz_+0Ysi+hb74hWGJ}f)-Wjq8xI9hN9ywyH*TZNxbqAFb0Onk zlr|sAy9P}kEP4)(t}9po1R~v5%NCFx6Lg0VN)tH1cYrrVK6?`pS>|aHTJ<(BUOt|} zHfoD?SP1ztXVJ%%_D)`*@U$){sIycFWd+;Wv{1O$dLT;^)e+Ah3=Q(9yL8ab#Kxzd zgx>e@$=(DI!2v&h+-o7>WH2-lNRV6a5)CawmpsC2ixG^D^4K?kiVrfV0QPl;Ckq0I zgn*||o^X3NpxSFHTyk<}@Y+or?~|(|C4tHx^t)+CsY8M^LXjwr#4bD>E-Zg)F&uwv zDocV~4YZx52Hx&k$+Mw(eVNa-Naz#`QhK5PRh7%+O}_gN@jWRE*2+EFF;8B_1T6L3 zky#Cy8)xTldkb&t|CaasBe!9xGEFM>^GPWqx3b5XR`%2k5t2y6rtM(5ou@=K6JJXp z;TypiYKcBt#Osb7PMzQB7j!S_Tr#oapAt?WwnK7!kZvcQQXR(=!6`aOkvrDmKdhlR=4%qiAdM#{H|@`aK3-^!nfRcG3%zw{(lY&cfU zy^}ISYcTc^7k__R%eCo0$jsd6&LYL|@|+wtGZ^Fu3gN?gEq25<=3T*^|2=5vC9)8+ z3H>kh-?KIw_t1G^$OfOfxbMTNF*eP^CCrgae6Br52s2M>#XV9K$c%Do$@E^5vQLIf zE<4aO(B457J*%1ZHWwdBG@D1Ww`De%#73u zSWo_9T%4eT9Nr>6&F7qKh#6vYT+!h)#n~KO7meZte=h^5C6<`M7^V9ll6TJ*{PhQO@{F+g%+b$|FVKimiob{#dU`|Q{KMZjNiZ7f zC)1NdE`EOW2(~Ak4|PNYwL2a|7lOuR5_NNs(Q|nebE^)u<4PRiFXQW~%}?tS1nR6y>c*?^b95Ws&Np^@>tjNziE(lg)oe;?3B1mPhQpmO4xL7p zf3LQ2<7_g|hf;-JmF`LwoF_Q`drK~cefs(Nz%~mmznGYi?+Y=AU0bnHBsr%#u_rEp{Tzl0 zHoX^O)uH9}3HrGd#ZJpZ?|?-V&R~F@{(i{=1NVqzeo~3Nt~<(3uh1?c_F8-3qGMhu zd&wWPj!bBCJVeA1qtGdm1~NK^Q!nlLRDE1hWK@*QFMi&(mX?+aZzCe^+`s?E8kfU& zdnB>!u6oKpGCG51E9a%&MP17iN~LyzxoX?BiYaf?4(edZW+>HzGDr+sF6ks>dNO^e zlJHm`LdDV{H0)TZU0iXlc3Fh4FA7^NO0cJ=Cyb+xJ>x&rcuVEc+!$xsi0yEI$&FR{ z?{@sFEyI$L(AKwiyokS$kH!T(yWTc3F zfnr*6-Ig&e6{?}3;q{w0ZF&EV{P~~r{?ot_?lp!?8CBq0nWt4WatGd38mT z@ro^{Ew%DU7X9v;4hT-zkM`CklHo?U zJ@=m@eI@AZ)k1H{b$8f|=3#YE(9pa8a67e8ZX`IUM_mFB_lZjoP(4~~&1W_A7J6am zT#kzmAeaAG>`6rn3JxxOdD|CAyh6u6s-IF*5yXs$!je5VU#IzkDv$8DrIT5m7w%0u zHHjHP#r0L5#nVHVr`$4Q(W8mzHc0Arn7280)Xd)O0V2rzWJjIq36$<#S-|oDe;LXj zIFM)6z$1`mWxUneY4v9Wr+As`2_B2)6 zO<(ybo==GD*w9BkNsWy6w;QX@W5jW$-Ei}m=85vJ4)e+pwu?Y!|N1p~dSvihL@tKe zkRJ&Z41?sv+*rQC74z#YmeLh4_%ttUeot6q$?rb7bd9MT&^*JoQGr!mIN2IYZ;OfVQ_^E~n=adkFc|}NZ!X?K8#6EGjw@pQ|kYguJC&jpn?s05cW z*`D^r(xw^950zg{az!uDjMQz6JD-kO`gUC@u6e9PL4wMvsbEh1Hj);Sn-Oy7*A*@` z;G~xtErx{Ee6o-nSY)}Pn|x3A9E8l)U-m#lOLCj9Y5jP%Cm9s%AoYr&45|Equo&J& zk5^ou3T#e!+nXLr=(_XG=+f0zOeDv?({3v!%ezOUkylGjUEnQVxgBwVm86yCzg{B@ znVXh4=_{4AV_?&@nn0Jemp`93f`S!HjKyJMECPX5$xR$;5#yG>GWK%+UbBbEiRHU! zQ*jy62fBf3gpMUi>uUsD+@qZv!d+Z2>mYFLRf5zPLTR#aNw(nMK;_E*V&YwX6~`NT zv{recJ$g7->K*mJd65o-rO>IUPr2QEB1g+TaGBH&{d`gm-e$s#xG6+3)u99%z_4IJL70}!wX^lT0hQwSs*?P2={$I73(~O6CPMKbp zNXpR8?;8EbV@~?onQ-ZF+U6^Eu>7xIJAZp{gZDo#I&lIC#%n6|>eBi`GMC}YlQ$$~ zVdvLGgKOr&4qWD)IsI-9n1bdTaqIa|KKt7L#>M$rEsjV1Y|Ll-p^!`0F6JBU^Vw>= zguKRO$Do#r&#ZhbsFD&y1KfL}fHkFofdL7qQy^jHgD`+7X zWfm#6gN}t!yO8W3L)H;@VQXO&^a(y?N+>8EY@tnZ6H(JZ>$4982q3!I1o7PObz!L1 zK-!{d0}beWqb9&PHk*C8Ls=A+>o4qTe0+j}3+FU&}20}+*y*FsP-zGi`GIq z)1V;qjP}mACWY*dl;B!%JSNK;`7o9Q7z=vkF%O>w#@VsaOR2))UD-D%i7<{@N~leS ztGz^_Sx{iLwYiBTKxo?k3Fub1cP|CRH=nB)F_T^D3l7K1rn4JVNi5%=!jFF^7H zHa(;UXrtVsere)Nfl^*ou+t z`9h`8G?tWe{%@jitj7-P^UGn=tjY3bx!ttTOh^*Nz*)=~E`L4UPV{q$szP|3pjR zqD6i2zBOK=;M;5O17=Hoc4);jcKX#nE8iBw+1)L9rs(QgYH|c}OwAG-8ekZ@Hu#}PMwEV_QIec#3GcQ~&T>adOG^uT z?6SdfVnY84^uyPn1p@hKW@%|@(Ox_He|4lSOXhYvutL3~9PR-epT(>Y&?p%u!7*eDtrn2j;^lySOrY+8W6g(Z~5OUneka z9*8F|Y&UaRlJZ#w3|6|iim#&_m!3?DP&WaF=+aK8Ds7@C1mQ8IpiRfO$C+%S(DK&+ zSw;YD-SX$Ov;vT8Aia)rFy=pNF2f}?)68WRYj^fFo$vPdp(rg3DPNG-ZGsMw7jz@L ztH0Y3{e__+1L)&0Q(V@@DX?B6`j0FCIFQNnjau+&-50NgQ480DfOIuOnvjS{Fk*qI z4rSCV6-wD0#nmltHj3Vq3WsaCKaO2?lL`h(2Jj;sYqIn z`TS)mwQq99eA8l|iG==XtIaW7ob?gQ2gPj18`z+yyqrm_a-J6rr4RmMvOU2|Q|4b) ziA5dljpj&g+&d4c0@1m;wY1_X4rce12YBoZo&M{$Qjr(al>F;o8LT`7PBvlSW)eat z$~59{LZmG#;O568@2x*RDGB{Xta5HLFvNy$!5|kwdI>6iCDbZ-2}Sr^@)a-!6*V+! z7rK*OTxlR`QHwg`MYhiVe5xG>XT+*M8pPbpH*UzBNlf=O%Y+!T(ka9iTHUd-)Or{lbNfUuWc7 zN=R_BQ79bl0G13<0HSVcK}SaKQR9=%-?$pZY#}t3cvuv|S60ig??>gCXHQp?psa83 z^Y>plwJHC@6gUtO9evl{o(DpY>T?zpguJ0o>=2glYC()D3w{765sk#B)gEZrmtUwz z_*HqpR$8mJ9KF+I{U$zoDTSGm=advlJ?Tz!Usw805 zoR}t{H?6RsMq+bhujJF6RKC8|IvAwyTWtN&Oy!;euRBK3ouFBNB(()yn5`fqoLngh zy?SRLH*l@GP|0t4fCSaVjyN7F)~ZK0OF2n zZria$h$zsnj^^CE1?GYVV;*3mad2=_0P-Ss1pKdaKtzU6^1p#Fp^Dfw{QX}C1xAcYBZdUU=ntyDUJwT(!u>Q<<3HL5*@L41fu&Q;qpr}_IAom9~u@TfO(R-Al&TPP*|9G$f940Knt@RC3 z_NP(cMnFXNAZ!Qq@eRm?(Q9<#?tQB28`DjHMoTzBB+#WcYL@JE7kKE4czCm*&1M22 zFt`thu3WhTd)STrBxd_En{H(+nXaoJ5-Lea@6I%bQt&+^4A{)=WV;2#qyoB2 z#JXVKoA!I1KUWenalE(KqMtRM&-{**6sj{p&Jt5<$&+E+VCVT^fnLgD$a&!)JxFvC&NJ$58ee^-RT-_Xg9*S#&#*AvgyJ z+G98okpKyc>W$vLT=6eUAcTdJ(hkTY7L;ba)->r*JONhGp7N`o?32DT7LE5(w% zvo8Uwy7u#vEG|;Ut(MN<(|Ye4fb*wQnn1h}a9qaIBGxL8y=JSHch)dC&!d$Ra2()6 zzHBdsbFl&0CJ%(mPqH-XrWyjvKqJd5wl`Vl58E;X5hV1h>utbd*tgKQJU`yI8_3pb zft}~}=SvJ^ovq6gl2E#X$ASYE#`*&ya@<)OTmbB7GW+8l9<7*=w0>tOnV#o6MC=Hx z^wi8uo)gZj4n6m)(;oXlo&F_B&)Hr z#q0YgE>vpFHmz(2&Y<|_)vpFU{ki6K_!z!Ffm5&gc%u0wM&WRfk#p6T=9Yx+529wu zN=lu(t^&5>R#+VnPCFd5I+7(PJbRS{HEFvOg?qI@9EQ6^?48__aaULfRcP39v%r07cAhP^B`1Ju!c;L-$zPFs1NYB zq|yfQWkAHD7^wh+IuF9KvAk%AwsE)AGW2(McK8Kh|B4y^Alw30fv0~ICJ=Abedn*q z>R4If9Jl@{=v@@jXc)dPw>vXnaO~89W zZ%?#-Jn-}(&3|Ehq?y=h()hj3?wUaQ-O5zV0xK{crPqb0v?{| zBLMGcNG6CY{*uhZmVtPKz+%w80-Q?p8er29pl={Qv_C)NOfH|MrjY&8sVj-rB-LwE-NFl5KSQw%tJ}R zC?=K&AfC>5WwfLhwAHLnvhG2$gp`Gv+~1gS`^I0TYw5)ylc)r_9c|pRH};16f&Ko5 z9BlQ~yJ$a?(9sbgLWy?HU3<{^81cjnfeEYlh(^LQ77Rp@u<#pTFDvjma&9kr_9y+M z0IC7YvSbN6+b0N!M$I^G?M(4;-V#T$6HHHgHYlm0*C1BD0V%v4gc4rRy#td#;oUvM z5@l(rk}H{M{ih}J_Yxw;4k71$0itw3&beIP$NSnv=H5$H)!C5DklH9<7o=I|N_D_3 z4L2wEjAV*+NAr)+N@OB%Ql!Q|^ z5#}^9I=Xq(w#NF;T)d#IZh+Ux@$o(IR@^@Te+uaHE)@=2U1W2M8_j`>fUumWi6 z&7^40sxN~G0$9oRi}~o}WWDI_VK5^2oSg_FCZ;c!b7>|cPqk|;lF5kFqu2Ofpy|3_ zH0^r1GHOtVUb-eRdX<#}%ySWS-_3hrv~#de=HMpgAdVXY-&lFHS`pnF4nnuN9z?2`SY1aFR81+#-JNccj%<||NSBFcgS2%|3aAE|4>YdA={v}>6q8&cm zTT{u^t-`^_HwB^nLC#lLT+j77Y(+2%0k2UAtO{Q0o9sVu;GtN=51|#OjBIU$Z08qt= zxq%wW`MU)TBA%RUdylvXM{O!XUB=x4;il)7b^xRzJ_vABEx>nAg$j;OA})|Tm4nSW zWb&@dg?$D=DIT@ZPs%`s>4Hm+?2|t~5>n$~^DNA@`Lxo5@Ddysb|9I? ztKvg}FYTIuKs3;=?_z{tm`zJw9#;S!#WZPq>hL%A4}TWA zXn|J%8__3VBI0slqAKl*i6`62`%;~U3pG2&|0Fxe84yXDtCC>w0!?sZoSS5R=+ANlg-jLV=Y>0sMF8;^!*ZtIL4++ZQ0jvbLY7 zK*80phgh^`esO-QYW^oq{*l+&(h>+&1E6T|uXn9{9O{FLgGT3t)&t;*ibi>ah2sD= z7kZz#=jc{h^bb0l{^QrIg)Fs-H!P${9(ooX-HO+a znw>SSu3$Q^zD)5xL_yPk|BQY2yYtG^kz(ui37<11C=YOt-IGSbiuE&#E5V!v89WUPP55VJg@G`S(4{e- zsIGdHTRwS7`y;!0x0X_$-%an`gSa@I%^_TJ5)A9nE5#O9uS)FKnpXMd{0v*4pb%4; zCq>JHI@i_1!vVUCc%$$f0Hu5P?nQTBym+y-_Y?)zA83@CjjS#$CH(PEijRk()wj22 zN-5}kN&B+d+mjqrK`uA^$)v1mdd1aaZl&+ZAxrVLyNxk&IevFWu^jHz(LEA0*T&Dl1ud2Z~-G!98otPG7Mfzg@J&zU!q+B&3-g2f>*2P z3+z9pNS5|wd6#+f7E6V$vFI6w79uD5H@Ul>O^XAmU%emgj7gR$Q3VCnez&2iew0?* z_f;U1II)5TEgccXOy|ZXC)0u2$`tV&Af-yy)1o&Z(q>C0rln0X@Zl=Yvi)9joo%e* zZQfS{nXa%|zgGl=!lDuIFZkt8rZqAO3VBFw00RrHj-Y12xp>h46wQEHnhLxi3V<*Dw9HDDuVrtM@$r$_WM2Vh@AJW7E7=DwyUF#rmw z_BulU31vH;zYG=uZ3psr2f#l_>W08>0^f-Q;D>>4>*}j;|8VDGx6Fi_4S6%1Vu1M} zPaY@hVJa4+kj}o|!E7x-R`r|?#D-?z0ke$K^W4CMhZ=w{=F`iUFV|}?5NM=La3^#k zUb&K-gx3;GOjwX>fbT2F`T|pr#2UmOH94sdDRyz9#wTEj1!!>B`8cziAa?^i^$ETU z(dbBrLg^2w;{q4-0}!7YBvvH6z@B#e+xNQEC;cutRP5k+oCiSDa?Y4&z#}hOTU+6N z-ojl1TDt>zDK4eQkzpEzNl7$T%+6|^N9EzBI$z~Z!g5*4&XWCQF>UX1z$qv4JPJ!*Wj8f-MsBdbs@rA zmd6#=>jia+=~l>yf;q_l*Y zFa-dCOg+*B0aP`%&d;e+-Uz;CKvAA`fCYrzw{OA=VkqQ4d%st>E0a$>s-Hnor1?02Z##f5hF>B`gLGgtP9>H6n zvV(OIe3U!60~X=^<-%@+EraI^AZ#}hA2w!M91b>3B#zgmp|d0lTs0cv?0g*-Hs7lv zX)=^&pjmBtX!kj}9Bi`mxyPapE&i1+OmOLjq7*0s=b*ck2D?!ktc#G}7Ad8O>|(iz zj5Ib|uFNmTHz;K5wv86~x{O~01y|RH_0lvh+Vh9Ad38K~vz zet=C6-D0*uG~m{vk;ks&8_J@JZ6}l=W_{JjXMpMtTG{AaFNmeU5nVbHCdw9Re+KC9 z1|#DfdG*p@ZnA;a2!Yi+Uq|&HfTUu&Iu+?~#hwXkmw67>~w15X$ zzN{WBKbWpU2Txi-4$t+wA^LD6hF3Wm3>BU%VJ3=P<)a)hDtkVUf+d>-@o;-wwzpYBb%OnKh{|S(2^g#y|wTF5+Rq>M8*!NlER?KL>#rS z(WOE7fx4%t_!%M#QoI08C8VbA=t-6P1KP}hr5##u>>@M|qBAk=N|cB5$J6=Y8Np!q zF;ASLa1w(plo+6SVbdv(f@88(b9NFAtBN?5wW3)W?4=RFGfrdC=X-KA)j(j-hyzuH zvVyp;voTNH&1v-;En0!!Xfg=Z(1e#_-;nwKNg++yR#{BNq~nZ0@Qv5kpAE- zS`UwZdwdJAk-}fLbRVP&f{fTnWm{Q?Jh}vFODsQJ`t=1Dtg-N2lEw&ZRi>Kw(e*(T z9=K63w*i6h4(u8be}Z@QDiBiwHe=5Yyzk$?1oQ}0Q#P%=8@lcAXaS@NH|h@&4@xlP z5j*fKj%g@;I(MH+gNTRq0Vl}rLa5Ehl0~lOXinW13q(&L1|Nv21+!6D+LE;X;S9@% zv{^Ta+OanwA;y5fp&O&&j)Imx!#)%+fHR6QYX4OpEntCd0SEvtb8e)5_f#AoNBC=i zWOh(WFIbd+n4LAI^;qWiK09&w^yw2hphS55LnC-&fxTJpd!&M>TM_py^6ZTo?~_t+ zP=<@|YE*}dLzMubCKNo!&@t3RB&|>d=y~m21sl{1bjT3j4P>ZHMGkg`2t5e7$F&z8 z00VyWDXRVC>1U{<=P*pSVqH8cetc#feE6;s3ihVT*YY92)uswB(piBif$c@@s5qAtoW2 z{rPhfVop!7wH5^CXmgtRC6f|{z*Hdx(eeubK#IIqwPj(?0IGNV^Go&?70KJo;<@6; z(PxKtk17>)mud0@Z3oeHOHm&`LjAy|b4ka(dRL4&=U3S9$;mFs;jQ`E%Bo6pnt}ME zrE!&|ya55x6-xyG&D4_KiO}==1*w6$AsJLJ%5WROSN)ljxK?Wp(sqK0)6-Bl1@?d` zefU+Cu`5}!`?Gu`wN6-2kQU3&B42-O|8RmV9o#{-3#_Xk39-t79F8<5fp>u>Zt@l} zSG2W5T5k;~aK1s|0OLD5Y4(Dmh6K?O5Rs{;=+^qgG|Z0LP7QJ2QfKPAe_k;)UCkf^ zJ$_Kg%RV(D!)F^f(7lR|j-FqyJ>D1zudm0Mh2-*@*76gt2Os@XeJ%i1HQ1iX zm{pQ)2nmr(O4f+w{xDz%v~`1-*giP&I|9&L4|HkBs9bF>{t)qR{2@1rdx~BdT*+s$VIgdQ|VZ8wV{+ zvy}55s_CUZTu}Qr52{FTzep)%{P*@K=wyLq?F!@M;zNzHUw8Xor=AOON9Q7y(Gyb`_WjYP|e*2BY&4Y{zeB_Nv|K9u+-aPQ_OC7z9^7-0;+_DZ1DX%f75_& z@F{e5$w{$@i1Y;-$n=K3OXSnR$B~Z$Cxl287!{)PpvFtOmt1p`3S!N5P_Wx4@R>)@ zd;{gCT_QBJ(~_}H4=t%4Gw#lBqCE#5iA}FMQAOh5B|w&*0uu$~`4ZLe4tO9$+={~m zbabc-^2Y!oWIWgWA9h(x~+Ry-}`%A*XQ&8MA`m& z%eI^qSl7emyATdG64MvG5jg5P*fiY)#0bocZ2DlUs07b63_QHb+A_~MFhZmLZ}4y; zqeSS2^i`U{)A9)CC2kdcq&??>2WnWE%TRE0d}4--4!~3T01Q)XkcFwz_2;53&~tag zR|9||6#6?iLHi1wQaO!S_Il#pu1U&wi7nW{!AxH?0n7@d;0!q_AdnY&#YSniRKY8* z@Xs?lhZMp2rFMIxJKhD|5wFQ_R)5@NwI7x_*F2q4dB53VR__~hFS>w%=E-a1cm+|i zWXO_$Vj(e_MaaIYZJ5kk-7+xF3SeQvre&hg&7Xv>9K3&JaMM~T5@A5>us9lZ8ZcuhRZ^7yTO|6v`Dy>hI3upVqsHG3S#}VdyuPxX$zC9;5Q*NaEA@d(79nXW znK7&)!}lz~_K>;aHBN$uj$8)}`dqd^B0>kFbpqhvILa&m00F!bDE9v{!&pN1okafL zXdMGNcqei}mh^hk;}1{)yz})1MZ8-77wL+QE3RwJkOivF?BEc4`((3qGVr8`nqO}$ z(0^$s=@kidh8?7?{zNJvFP}0xI?BC8&%`v1KvG6(Gr=8A{vlw)30mKxIbw3K+e0St z^9)-nTU(%6QSJ1FMI@j2BHt@X@jn?3I?gzcClg3V#3-=V#(S>A08_ymp#|Jrcq2x@{!GdidkD9sucz0GL188{FtEJBREHlrmoMPEqP#We zH3;u{K-w|ID^ehj^q0=4(HAE``oAb{;WF{H@p;DP(R&sMWCbQU!^^ucYJ#;LHvxNB z7z{cj{6JcKw*$mSL1nf4d&g*-kj33isF@QpE+zv5Y9v#+&J!CSw+?a;obYWY=Udb% zElJlB3Fk7-JHz1(5k2}PWwWe8%6G=h;Hml~9rgI5X0T20fvhC4+@cOl%|(@r?RE!i z;?-gB!Byh$l{S>8ga&Hmixm&nB+}J(`rg;f&%_vLX_s;0zHhYO9S9LGg(|N@r%-L6 z47UC>ejpxYbpfhY?|YE{CX?lMy2?AD_wBTjExJ=oOz%!Ch8CO4wDvZ_2?R zg?ExB;_n0R$Jb&uiSs1HRr;5CedY2ka({k?VOdS+#+>@t=X;CX;6NdN^OSI~mOpW^ z8$hHp8^1}d`YSp~yRL;CG)=F@Bf3kiD&M{;(H5aU$G8c{m^~i~7eO6)!Cdm3jI2R^ zbs#aH^}@IaqwRFb^CcuXj6>(JqeP_+L@lZc8P3%?v^vCSKk>j zgz|ZKFuu`RJ@9&5T0I4-Rmuy=e;=Hif1=&NxgFp{pD5#g(i`WHkwmm+dfhQeJn%N~ zB|3oW7WbU;MZ4<0JX)&d&nvhk8Kk;l*GTYhsoMqqoKfwa8A@eYYLb1tA3C6`KIxh^ zX!mM2`<;=oIq1@%`;ql_8Xi|*+T4H&SlA3L0nM%nDB?f4=I~wohYNy02Y!AsxRQK| zkMgf!di-Se$m-?u_{y?WpIxIFhk=%g%OqOb+OMEkM$keroEiQ9yjT?#O?$RZfXr|lq?LwRhhcw;vx#m4H_IzN3)HzQ8Bi` z#a`T~87x~wx}=vVk$rC97XRP6XTPzYxsZ1~#kuRV+1q0Vg@=ZReU(r2yl8s~lFl`U zp(j460UJe0#FCn+c22%CmwSsp&d-kYMU#(0$&o7WVN?qaR5N3qnKXxx{O}B_vZP)g<>6a7?@QL1qpndjUK@-*C2-So zKjix2$o|Ogt+yJt=ekq)`6bKUnJO|!>oWa*IsDN0`F#5yItSnyeBbcY;kgJrYp1li zNFF?RKwH+azYI^j*43*tFkbvfQ488o&`xA5T(tq67GZDioa@%chEKF5JEHjXn)B7V z5dlNZ$?H+^kvGyuck~5FN$<_QZ+}Vqvw*yOkgU|nn(k2J`jS}jw2l8>eotzt*D<5c zSbYp}n0P8r@JXhej<}U|w55N=G)~#rom<61MdJnl0lMGAn*YK79AQV~6*={?$~_V= z2?qtexWR?qb(`sC_?lD_G9WKmPSom8?U!=reC8Tjlq@dnXp*fbWBvCzAF_X_lKl?lbBC3nXs}S1 z5+#{&UH)={|9KLrLsXJ`TwJ_wwhrSMMJGlp9;|QIGEMX(Oivn$uUXYluN2%Qhc3<| zo}Hp8pE;|pGr3d2yRq$+o&w5y($daUTSL?!O7AhB6XEOjSX@<5Y@NMJixSi_A-d?y zN;egJ&Sr<@0Pr7aeI*X2Jb=!`~3M=P&1vLHBL*hYK= z1uKFv?CHPEJ-+S;ZVUeP_qQoqTK0pBj3smB-UkOx7?z$%(UJ=i{-T1HVRCira|b^P zdv(yg$QY~$#VxDr`NG~sU6~JmQKUa6!Yf(3RoslEv-tOXsV%2#SG4B z?^@t)5km$Nue6e%9+yl^jFtGA`^e+WIux)QPW%KJSGuAaD$Ksy`iq*CNRKo*wlVQd zGts?cTe&;CUE9BUbkJ$ONzj%1u+kCt&hKs$Lj!N@)Ifun!Q4T*JX^PTdc|Zab@Y73XjD zIEpZ>F~(H4TXgP|%Ap~hXVqhEW%5k0U%3Ctne7nIAv@f~twoJCO8_odO_cVWknNs1 z9ymt%`j$wKxanV`$-H2@wBjD%atB-z)+gS)iZj2&=$(W%tx*vpjDVVA4BwkJ9=Bs7 zl1yyT-7D~Rq`r09A2vhdVn>d|G8cbOQ>zKka0lIxZmqKNzA}8L=Z9S%)_(Y)T=S{s z!N>+ULu+c{EHF(mam-Diy4K?IT0Wt?`%bdm?i+hr_|Dc$|z11bf^DRfrupTi==j`HE~iDv5^?}>mqFwiC$ zy|B3q`ef~l4{fB;=uoo=ReTY(F8`8wIBbMODg(OEWkol*UYoM1?0lIat=_gzk#3=p zqd&%8W3g>~@q1tR$OgD!V~&OiWj{P07+dD_lSa%u{Qj`y^Q^g%k-JxznV!!rQ)5vY zVGma)7mRa$B_qcLt}_4Vt@lo51LgJ%KuoI%cJ5|>pb*J`+Zw#z%0no0NIEgI;QDE# z%oST2#>|ZU)dObSt~VU{Q99XW@JZ#LC`VvENl*0Kj$Y&umt<~+ouLOMU?0?8+FZ6Z zn1eg>Ns#{vXTJF{(a`SqYeA3YGT%~S=1c@=(zJkc2d%5Q9`(0|*t%3<{n$>dc=ccY zi7w1?N%`<$H$Fv2r_i(Vbu<``dm!8CR+lX|zhBJ!p<1bA(a~7p5df-O9D7Ksar&E( z5mQJ{$@Rk&=sjP4nnE*2tz@s+#E$MH5w0G6iwc`HTV{`E%8yh-k1LT#^c2P^@Fr(Q z?ZHl8o~xv9CaiKzn}0r-SmE*A^3F@i*S6Eze(N_+o5_#3kGa(^1sKjTgH07c7rRSw zs2F;-*sjZfr2`SJd}>(~*B2u^Ieu1%1galHRWo(9cq zM+19bRY0laYyRwf|N1?64#58m^+k$?!<3e--fY98G1UG!!Pa4PhgdV8jq^4mYT1&+ zrSC^1>th+@W8Mx}uG%on?O95;tQ#3&SIe#>^xh!iE!p@%c?w|b%y3?*8uu;fC8Wv?OanLjp;T-4BR*kZ8 zIcu#QIimNXTz46lbt@d|j&CW}gk2eTw?pk53O~?>_a?9Jaz|YyWtAt80^}{IW`c1J zYDlPXY;-z0uzIdNRG6`befkhevy0d2#ogg4=8}ELz-6`RlDh>Kh!?h3fE~hr1@Uxm zTO}%e2CsPp{v0@qG_>cgW^~?02+fLEcZB%>5Nz~Kd zrw?UPwyNQ45`$~|ZkFJ0TTqtn9tqvP5H;U9(8*H)^@_CTi@|b95g8@GN_c_}Z!SjE z2FKN_@&=K>u4W|IVT7Ey{_7Z1EbW|5)HXO5lEbL2da}`e;d8tR@Kn7l~HBON?8CxfSG1Ztr-Ab;fx#v7|agBBi+A zJT!-2p7@dPU0}pS#rUwqA&!1OSv1UNE_POp?m~TA#nIC=WsbJ%6c{`o9?!lniJm-` zn{TZ7HJYLC6d_ZI+7bokkon?pHerMYlxV4RpVPT%*k5RVz`<;8qn;YeyREd?p6Kc( zI->UBp0ywJHcTo8+#bZR#W`OFkxK5B1=NZ0O_w9Yx|zKy&nA3ZQTM*jHCP(_!B?S7 zL`&|Q?tB?$<{xcS9V^I>9nK8WTlP8&_IaP*>|WHh8^?~GxueBxo*y4T-t@-h81b9E zZ604JagTmI+uVbj^1_qB>)Nk=|9u(%vydS>#EEcZz6&?A7YOhny1$S^xo*>i4-YR7 zdSRbQj*abaQ2EZk9=;$fkshHM3M8tLz{@e5VS<>!`;gJQwNv4ZDatsfTas3v5tL)YWdgG!$7mNqkeB|sJ)o~6|niQ0~T=)Z)>YJvb-FGc^94?i1R|&7CGv1!*x^N;a@`8 z(uVOJo}P)+vP`ISIWF?SpkV7|tGSxOUYPJ)HH3FVM{eBBv=J23@bF7Uo^NlMRO$#{ z_(zj4yvHe3+Y+Zw80SVxmiPZ^(Qt=l<>F8!mOJq`!!zz)Wddn6v2q3OR?bDrx!SVc zB(fJ@O5s9I#@{ZrBKTds9$w};Rz7kyaP3CnG2z6b@&O;CS)KG13dtqj=?@~vuZt>sDRJplvS#?3W z%TJvrg=q|n+}5eIQ>-%FG_!RHk9dJbFdj4y4~20LC!i~G%Ws>3z48knsKmu}4eL zwzh6(LvoK$lFOvV{l#reT&9ctB?SQXDJ?q9GQh{;_liX*R=*}wiHkp2!~ph*GSBbf znm>urh3FlwpbHOC!8UfhHR4JZYQ&BYy<#Y>#gid)H5wZSUwV|)JG*Aro68aWV62 zew9Y`I`4#y)IQwOw5_PW!c+h3xyFV&rYYawtG8yLV=^YQSB7AYwt8pDpn<1nEc?D2 zHS}K_6aE1fP~;_7BLyU{nvBo-iA9G02fO2vPAlSEy@l83M~`yV^b>Qz%S zeD)^DlQ=S|T>ae`ty}rY!`jQqsn9}bGf0$0R% z@$$c`{;$PR62qm*4Q@X9kM+xoT8*G z2GrLz-x3)VqN5>aQmzAa9F1p*E$(bSLnz2s?|>e+Z?Ob4IZoY#rG$GHWTP8^d$~sGoP8^=*wMDCbY# zdUF(Xb!cmn_5XdUu(r^C(r@*e?MJ;(Dh7$*RodY=uBSfPZubB5K%NWWeO~v6fr92P z=Z|OLyn!=O(lb4#70o9wWARE!pC{vUvn21@RGYi!GT|i8hDxJzkopwK{UV^15!V1va%`QUvkX z%Da*rVq_HTjc@p#z^mGdh#sMby0DpLBQUF9RZaL<{N_r|MeL>4HkI_bnCB(*A+zL4 z-ru9-->%p5>Bt4AF_nc_QPgWT&vtTSM>rdCs*P)-O70USo&sP-_ve-n+H}|=<(-W@ zBuPAHUObM1FZ|hxrqiQ{PZpRhAbx?|1B9&s9s!W(@3&9`_8ce6odWxayh ziE-1WtVgU+*7eX+A?HeVp{Wnca;RF#S;QTVa{HEY!VL#NXOK=IBrPz?!y*?3KlBGM zwh+flA7Us2w;U-6449F5-eTpP*c+pwR@;R0h)Hc5)QBIIn?$r{R_)kj=+dMmr&fV$ zt+IF2@O`*bmuFCAcs9BOK%>Rd{4^@5pXb}MC!BW6(!{W|3ZjHPqLT8?YY$W-O;pr} zy}-xn3Jb!c)hQqfhiTbY-)!gR%A;atDKIJTMV~27W#EdnGyp!e@?swg)bkfFdImYU zX>UA6$B61Mcs*Cys>7qYS3Qf;l;!VIscfmv%;-^4M`GyNMi;B%Xjl39tqFbun0)yR zQ-FLtLVLHM3yW@v@Dq|msAG=RSNkhOs&3$;g>XOlXDq`X2;}HAYyKomp0rnGZS6v} zDpqPGz}15ifJxPbpv}M#;a*G1TRy{;h~OEVdq0rETt`?Rz9zL7Wh3|Hi}kR%2cW{ngH}7{@<)XdQDFk= z?8Me%HVqj2@wUscCsO=kRYtaQrgmjmDO~Gv#+G_4$A$yr6byKS4qKpxRF*`vVJM%W z$rHGDlyK>t&~lc=p?$)M;$1~4Nlt#6ETz{c?%FXjpdK*-^8_0;BI_FKzh8ZnQuzt7 zt4ZNkagR>DPNN1GW|nvD4x#)Mi_g(gbn_LnFT~&%Zn+=q9WoJYqu^?*FTO`TqKAkIJnt z%)pg3u2D2%nT`nrfLSxTwx`H_MD*ZHxxe-Fq@1}kp+TnpR!aFdS@DFJgk%A09$m8D z;ct|WA~6rBvT|S{vK}bQRC}*x@>A z-iM#0{nl>0w#=@JGvyezL7P&mJ&M5ahJ*rU7Pgb#j<)e2hI84k9bbiepct~#!tS`) zs>BhnXVc&e2l7kQ%Nxas$IX%BlFkv&^}b?ICP;)$9~qLOQ9MO3uOMqvCci&KiP~p~ z<7()B-~KVrb;Jl!s2tU@;XA}(6DzHBukObj+wLZA-BeWzz7+aC3r-ny5F|EnyB?_6 zX)@5zBMT-Q6hscVFyQbFhaV2aPB>&ofMm$#@<447nw9cG3kKl+7MKG4v(9)dvHDqv z5eDuwvu#?wVil2``i$Bvmqo*>^Q{&4-u$FL-*r`YcrMN=FTRIMYKGv z9~tpo5^;lX%&M4Vhy2E2W^2)N203KKBi~ebNhQ#h>v3^Km_3Y4*?Gzw+ql@ z%oXBxv%rHFLk%OuJ?usokmPzy%Uzux);SCQU~8d=kC$HRoMUkwSMaD;D6qr*I@g<} z->~lR$xSUVfMO|MJa9uQpkz3Z37Q4r*4H27DAcMVF(O8>6??yXQx zK@&PyN6)~6VqkvhV7oUhE#WGA>i`u8Me^65}EEUH%*p-*gyV(945&1cL|a#(lj zdQY$UJhX5Ar&@dAn0w2S*X9E$1LDH8iat_>Z|6sNtJkMZ=`^xWwDhIPV8y2$JEP7r z?nQRJ+}U%$|0~3Ynis}{V4^&2r(5fRwv#T~n5C+P*(EO^zLU#7+J~Gu<@5x(j*6oe>$xC# z{C0hUDrdeDZ%8j1%RWsL?n{e;9xs0ado#u*RkC1hc}zpTc0a^cx-=>YY-9HJ=f0&= zmpU=;F66Jz(REP=u3U?wC`{95C0uH(e9ZbFn#Fp_0=;E1albv;@*=bZ8d>hmvyY-r z++AC~kN+U4SQ+4B>uOiR5wIz3sGBC=fnL;U{0cyTT-)Z+!m8N%)K?Y+}ty=r5u_dShc`#00vHD{zEm)s!(=zsb z+9Hb~#U=hkO3Dk8FJFBQTw><3cpCCbz<_t%eR=I-z0Rfix7S!E0?M;Pq+X?8*Ot|& z9S$n-I3q1c^&$B1r)zl48xczwxx%n_<^wY;@Qcj_0C3p~m%q9}zsbW_0SdOmEb1=1 zg6lCMk-rlxq{6ey;oTr_jC+nf@kz!xmidFDBLJWy8RF{speF$g%~LeD&l8R-QcPe0 zXb!E94^ByviCbBLu{@Y0kvM)U|cuAOmkAQ5wVAhL_`H^U$Zz+-> zadg4)65@CZvBi^Rlp`1bWmY-i|z- z6imih;?JeW&Fu__49wI3cbR>X(5a*Gm+J@*v<`sSE;lUk`EAq#ynJP7I9L{W5vx9k z_z@ohMBQ~3S*pS=*dI(5pdABD!gKIpOF>BpYGo`ahG&Osl(^*FKG|-Rm4Mg)Xo6uJ zUWf)D!E1?-<(H>++tt?e(fAGa&fqr}v!l?FA0+rM#BsrXj)VMkccILyzqVJd*j{o? zm!%l?VQb)D8l82>8h_x*y9#B*?eJ0j#sq+F&jFJkw;m`ZaF#NZ%?)*Oclka{Y`^{Rciv zFrBZ@bdXDg-vPyO?mC=YVc)dZ?5}0IwJD+hD2s2 z!aUqqDnDNl#AIcNgv}utBltbUM-0^{m}Er<5OX1@DM}bZK{gDo0zd))Y7tAVA|TLo zy^C!S9)Hh6D3XSyY>iI3G3{Gb=QQ1gN{#9Z5JHt-T)Qs2;!pH(`Ou#GBi6TTI6JX% zDbNF-`p$oESUHkhXScpxDQFu_j2rm=C;P)P|MZhU@ex1Fixb}%xNO||j(FWUHD&+3 zZe$;GTzP&3drReMt3~#Cv^j|~po9VcVNsTk0>@nhD8Il?*Y*K%eHW-17adk?h8gcGpfD#W#W_gPrqhg;Up6QPWL~k3Y+i*p8a<^?&oNy!uJxA*B(L zd{P!vzAlNto0EeTA-1A;bU$_CY?zRyWE2=sxJoN2V> z^z+PUU{yYPJg5$uaBv0!%6qs##}!QmflI)+6cRWYHhP@ix?w_Lk&CeC@bYH`%VSpl zx;vl!iEo!O%qGvJhETOVRd6KzS|1F0Ul_8dmzEOtOU-xpS3&adhAH4q($zB*w?;1!qP5uM8c;oDmkgsD z2XF(Vtd+73yIa0?kQt(@G<7rj$R&-Hv_3V`?0Scx^=e{u<8PMWbFv`0aXHNJB`m@{=4sSdk zeaYZ)ySNPGBFt>P^y5obr4$939iRUnLErfQTh#T$sz{i;-p+46u#Ykpo(cr1I>b^& zg9hfm0?ZHK?gwEt>zIL_q9aq+AYu%0Xpn&ER1uBH&RgC>W~bgeW63MYV}}Jxgqlal zu4`&ez=L=6?Cqn#qMGq^I}K|jh%VvMXz1$x^`8vXgJiL>GYfZR(<}T|_}~rLfWw_D ziqvPaBK7n4zX=0@E6GosL7A<+M?QPzU!Ug>Ca;0Dze7Ke_`~0R9>mqmD^>?WJ|y0| zog9p&5DUW&I-cX^k2U`Rwjt3wrMYwMCjf$m`ZMyZk;l4k!`vv#~#%OoQ82b0%7cwkTOYhsR{AJQToc`y*_0Zav|LRONARK90;mUsJ>sB)hk#o zL`e*i+m2T^xB!lX1%?l|c^a-C&=tJF>&yU3@`4XSeuI1>2bQ*fwRWrF;Iv?s$_4ca z5>pvk%;JgG zOj$=Go~T+-P=FvAAjj_r56>b{0)K>(k|T~fDMI1V=}AzxU&=L1{3t9ucI0A+-$kku~aW=^D&*_}sI0_^k8VHQ7 z%EfsK!%>i^Zder`!R=6}93`#{XgmwV3QA4qXv2Y`h@53!oVw?WEf4$SkQ(Yn(Z#Y~6NzE0ZS@ZSp5 z+KZbMiV?ISBo!mD4!4>OL(q_3{DU_1frl3Hg@SF(n5P+wg$<@U>}kM6`8T-IJe({aV4p;vhPAHquqp0A!YApDTs*-6b*@Uo9je((haakAn_;60GB z5J4*-e~|EA;3FtiN;9W-Du*I#JdZ|hC@9P?DaRg2m!lpX2#=XpkPzL2|9v2QZfrPE t6i4~79|)siQTy)}Gf-szfBcu%P^(%jdmL7Ct0eHxwaeO<3NKoP{|{|BcqRY< literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/catmull_rom_spline/catmull_rom_spline_main.rst b/docs/modules/path_planning/catmull_rom_spline/catmull_rom_spline_main.rst new file mode 100644 index 0000000000..4d8d3bdefe --- /dev/null +++ b/docs/modules/path_planning/catmull_rom_spline/catmull_rom_spline_main.rst @@ -0,0 +1,103 @@ +Catmull-Rom Spline Planning +----------------- + +.. image:: catmull_rom_path_planning.png + +This is a Catmull-Rom spline path planning routine. + +If you provide waypoints, the Catmull-Rom spline generates a smooth path that always passes through the control points, +exhibits local control, and maintains 𝐶1 continuity. + + +Catmull-Rom Spline Fundamentals +~~~~~~~~~~~~~~ + +Catmull-Rom splines are a type of cubic spline that passes through a given set of points, known as control points. + +They are defined by the following equation for calculating a point on the spline: + +:math:`P(t) = 0.5 \times \left( 2P_1 + (-P_0 + P_2)t + (2P_0 - 5P_1 + 4P_2 - P_3)t^2 + (-P_0 + 3P_1 - 3P_2 + P_3)t^3 \right)` + +Where: + +* :math:`P(t)` is the point on the spline at parameter :math:`t`. +* :math:`P_0, P_1, P_2, P_3` are the control points surrounding the parameter :math:`t`. + +Types of Catmull-Rom Splines +~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +There are different types of Catmull-Rom splines based on the choice of the **tau** parameter, which influences how the curve +behaves in relation to the control points: + +1. **Uniform Catmull-Rom Spline**: + The standard implementation where the parameterization is uniform. Each segment of the spline is treated equally, + regardless of the distances between control points. + + +2. **Chordal Catmull-Rom Spline**: + This spline type takes into account the distance between control points. The parameterization is based on the actual distance + along the spline, ensuring smoother transitions. The equation can be modified to include the chord length :math:`L_i` between + points :math:`P_i` and :math:`P_{i+1}`: + + .. math:: + \tau_i = \sqrt{(x_{i+1} - x_i)^2 + (y_{i+1} - y_i)^2} + +3. **Centripetal Catmull-Rom Spline**: + This variation improves upon the chordal spline by using the square root of the distance to determine the parameterization, + which avoids oscillations and creates a more natural curve. The parameter :math:`t_i` is adjusted using the following relation: + + .. math:: + t_i = \sqrt{(x_{i+1} - x_i)^2 + (y_{i+1} - y_i)^2} + + +Blending Functions +~~~~~~~~~~~~~~~~~~ + +In Catmull-Rom spline interpolation, blending functions are used to calculate the influence of each control point on the spline at a +given parameter :math:`t`. The blending functions ensure that the spline is smooth and passes through the control points while +maintaining continuity. The four blending functions used in Catmull-Rom splines are defined as follows: + +1. **Blending Function 1**: + + .. math:: + b_1(t) = -t + 2t^2 - t^3 + +2. **Blending Function 2**: + + .. math:: + b_2(t) = 2 - 5t^2 + 3t^3 + +3. **Blending Function 3**: + + .. math:: + b_3(t) = t + 4t^2 - 3t^3 + +4. **Blending Function 4**: + + .. math:: + b_4(t) = -t^2 + t^3 + +The blending functions are combined in the spline equation to create a smooth curve that reflects the influence of each control point. + +The following figure illustrates the blending functions over the interval :math:`[0, 1]`: + +.. image:: blending_functions.png + +Catmull-Rom Spline API +~~~~~~~~~~~~~~~~~~~~~~~ + +This section provides an overview of the functions used for Catmull-Rom spline path planning. + +API +++++ + +.. autofunction:: PathPlanning.Catmull_RomSplinePath.catmull_rom_spline_path.catmull_rom_point + +.. autofunction:: PathPlanning.Catmull_RomSplinePath.catmull_rom_spline_path.catmull_rom_spline + + +References +~~~~~~~~~~ + +- `Catmull-Rom Spline - Wikipedia `__ +- `Catmull-Rom Splines `__ \ No newline at end of file diff --git a/tests/test_catmull_rom_spline.py b/tests/test_catmull_rom_spline.py new file mode 100644 index 0000000000..41a73588c3 --- /dev/null +++ b/tests/test_catmull_rom_spline.py @@ -0,0 +1,16 @@ +import conftest +from PathPlanning.Catmull_RomSplinePath.catmull_rom_spline_path import catmull_rom_spline + +def test_catmull_rom_spline(): + way_points = [[0, 0], [1, 2], [2, 0], [3, 3]] + num_points = 100 + + spline_x, spline_y = catmull_rom_spline(way_points, num_points) + + assert spline_x.size > 0, "Spline X coordinates should not be empty" + assert spline_y.size > 0, "Spline Y coordinates should not be empty" + + assert spline_x.shape == spline_y.shape, "Spline X and Y coordinates should have the same shape" + +if __name__ == '__main__': + conftest.run_this_test(__file__) From 7eeb9d215cb5652a800db507f066047bfd5d023f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 21 Dec 2024 15:04:02 +0900 Subject: [PATCH 809/940] Add catmull_rom_spline doc (#1109) --- docs/modules/path_planning/path_planning_main.rst | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/modules/path_planning/path_planning_main.rst b/docs/modules/path_planning/path_planning_main.rst index a3237f16f1..30802fd7a6 100644 --- a/docs/modules/path_planning/path_planning_main.rst +++ b/docs/modules/path_planning/path_planning_main.rst @@ -18,6 +18,7 @@ Path Planning rrt/rrt cubic_spline/cubic_spline bspline_path/bspline_path + catmull_rom_spline/catmull_rom_spline clothoid_path/clothoid_path eta3_spline/eta3_spline bezier_path/bezier_path From b5988dbcbc3c1d8cdbb3f9f3f9dec75cf63defb9 Mon Sep 17 00:00:00 2001 From: parmaski <89462537+parmaski@users.noreply.github.com> Date: Sat, 21 Dec 2024 19:39:16 +0900 Subject: [PATCH 810/940] Fix: Hybrid A* direction is incorrect (#1086) * fix to preseve direction history * add path to Reeds Shepp and its users e.g. hybrid A* --- PathPlanning/HybridAStar/hybrid_a_star.py | 5 +++-- PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py | 4 ++++ 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index 03db0dc167..1962efe295 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -105,12 +105,13 @@ def calc_next_node(current, steer, direction, config, ox, oy, kd_tree): x, y, yaw = current.x_list[-1], current.y_list[-1], current.yaw_list[-1] arc_l = XY_GRID_RESOLUTION * 1.5 - x_list, y_list, yaw_list = [], [], [] + x_list, y_list, yaw_list, direction_list = [], [], [], [] for _ in np.arange(0, arc_l, MOTION_RESOLUTION): x, y, yaw = move(x, y, yaw, MOTION_RESOLUTION * direction, steer) x_list.append(x) y_list.append(y) yaw_list.append(yaw) + direction_list.append(direction == 1) if not check_car_collision(x_list, y_list, yaw_list, ox, oy, kd_tree): return None @@ -134,7 +135,7 @@ def calc_next_node(current, steer, direction, config, ox, oy, kd_tree): cost = current.cost + added_cost + arc_l node = Node(x_ind, y_ind, yaw_ind, d, x_list, - y_list, yaw_list, [d], + y_list, yaw_list, direction_list, parent_index=calc_index(current, config), cost=cost, steer=steer) diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py index 8e134ff38b..618d1d99ba 100644 --- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py +++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py @@ -6,6 +6,10 @@ co-author Videh Patel(@videh25) : Added the missing RS paths """ +import sys +import pathlib +sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) + import math import matplotlib.pyplot as plt From b137ba1817af11ed944a28f8c1c8ad1a95848726 Mon Sep 17 00:00:00 2001 From: parmaski <89462537+parmaski@users.noreply.github.com> Date: Sat, 21 Dec 2024 19:40:30 +0900 Subject: [PATCH 811/940] fix behavior when path is not found (#1104) --- PathPlanning/HybridAStar/car.py | 2 +- PathPlanning/HybridAStar/hybrid_a_star.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/PathPlanning/HybridAStar/car.py b/PathPlanning/HybridAStar/car.py index d7631133c7..959db74078 100644 --- a/PathPlanning/HybridAStar/car.py +++ b/PathPlanning/HybridAStar/car.py @@ -97,7 +97,7 @@ def pi_2_pi(angle): def move(x, y, yaw, distance, steer, L=WB): x += distance * cos(yaw) y += distance * sin(yaw) - yaw += pi_2_pi(distance * tan(steer) / L) # distance/2 + yaw = pi_2_pi(yaw + distance * tan(steer) / L) # distance/2 return x, y, yaw diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index 1962efe295..0fa04189c6 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -282,7 +282,7 @@ def hybrid_a_star_planning(start, goal, ox, oy, xy_resolution, yaw_resolution): while True: if not openList: print("Error: Cannot find path, No open set") - return [], [], [] + return Path([], [], [], [], 0) cost, c_id = heapq.heappop(pq) if c_id in openList: From ca54f1b6880b9731b06fc33db338bc28bd63c864 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 24 Dec 2024 07:50:00 +0900 Subject: [PATCH 812/940] Bump ruff from 0.8.3 to 0.8.4 in /requirements (#1111) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.8.3 to 0.8.4. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.8.3...0.8.4) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index cd4a01f88f..d28cd5f956 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.13.0 # For unit test -ruff == 0.8.3 # For unit test +ruff == 0.8.4 # For unit test From d1f1190106d624e555b0fdd0853b65ad844e3204 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 24 Dec 2024 07:59:16 +0900 Subject: [PATCH 813/940] Bump numpy from 2.2.0 to 2.2.1 in /requirements (#1113) Bumps [numpy](https://github.com/numpy/numpy) from 2.2.0 to 2.2.1. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v2.2.0...v2.2.1) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index d28cd5f956..0992ab6cf0 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 2.2.0 +numpy == 2.2.1 scipy == 1.14.1 matplotlib == 3.10.0 cvxpy == 1.5.3 From aacae0d79a9595356bd7f15ad8e565220a04de61 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 24 Dec 2024 09:13:35 +0900 Subject: [PATCH 814/940] Bump mypy from 1.13.0 to 1.14.0 in /requirements (#1112) Bumps [mypy](https://github.com/python/mypy) from 1.13.0 to 1.14.0. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.13.0...v1.14.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 0992ab6cf0..47db4245fd 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.10.0 cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test -mypy == 1.13.0 # For unit test +mypy == 1.14.0 # For unit test ruff == 0.8.4 # For unit test From 7d33f5f7140513d14bad016f48d132a08bc5c8a3 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 31 Dec 2024 07:04:57 +0900 Subject: [PATCH 815/940] Bump mypy from 1.14.0 to 1.14.1 in /requirements (#1116) Bumps [mypy](https://github.com/python/mypy) from 1.14.0 to 1.14.1. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.14.0...v1.14.1) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 47db4245fd..bcfbbf97ac 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.10.0 cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test -mypy == 1.14.0 # For unit test +mypy == 1.14.1 # For unit test ruff == 0.8.4 # For unit test From c27803f781c00384c9de29fe1fd82ace8279d788 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 Jan 2025 11:49:14 +0900 Subject: [PATCH 816/940] build(deps): bump ruff from 0.8.4 to 0.8.6 in /requirements (#1117) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.8.4 to 0.8.6. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.8.4...0.8.6) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index bcfbbf97ac..5291c45c58 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.14.1 # For unit test -ruff == 0.8.4 # For unit test +ruff == 0.8.6 # For unit test From 01d398f4ab276bcbcac3a7ce8d62b2e2712f0a5a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 7 Jan 2025 13:01:34 +0900 Subject: [PATCH 817/940] build(deps): bump scipy from 1.14.1 to 1.15.0 in /requirements (#1118) Bumps [scipy](https://github.com/scipy/scipy) from 1.14.1 to 1.15.0. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.14.1...v1.15.0) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 5291c45c58..5aeded446f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 2.2.1 -scipy == 1.14.1 +scipy == 1.15.0 matplotlib == 3.10.0 cvxpy == 1.5.3 pytest == 8.3.4 # For unit test From 647ce9ccfa1f581bff558a16803bfd7e2c343c3e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 14 Jan 2025 07:24:59 +0900 Subject: [PATCH 818/940] build(deps): bump scipy from 1.15.0 to 1.15.1 in /requirements (#1119) Bumps [scipy](https://github.com/scipy/scipy) from 1.15.0 to 1.15.1. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.15.0...v1.15.1) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 5aeded446f..f5a7ff315c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 2.2.1 -scipy == 1.15.0 +scipy == 1.15.1 matplotlib == 3.10.0 cvxpy == 1.5.3 pytest == 8.3.4 # For unit test From 4cf7531839a12faa9b7daf6a70aab4f596aa1b0c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 14 Jan 2025 07:25:29 +0900 Subject: [PATCH 819/940] build(deps): bump ruff from 0.8.6 to 0.9.1 in /requirements (#1120) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.8.6 to 0.9.1. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.8.6...0.9.1) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f5a7ff315c..d212202cdb 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.14.1 # For unit test -ruff == 0.8.6 # For unit test +ruff == 0.9.1 # For unit test From 4c2e3e8f9b686baef5774dcfe0afd7dda6150af4 Mon Sep 17 00:00:00 2001 From: Mritunjai <101278178+Mritunjaii@users.noreply.github.com> Date: Mon, 20 Jan 2025 09:59:15 +0530 Subject: [PATCH 820/940] hashmap instead of a linear search (#1110) --- .../AStar/a_star_searching_from_two_side.py | 70 +++++++++---------- 1 file changed, 35 insertions(+), 35 deletions(-) diff --git a/PathPlanning/AStar/a_star_searching_from_two_side.py b/PathPlanning/AStar/a_star_searching_from_two_side.py index 822f5ea500..f43cea71b4 100644 --- a/PathPlanning/AStar/a_star_searching_from_two_side.py +++ b/PathPlanning/AStar/a_star_searching_from_two_side.py @@ -78,43 +78,43 @@ def boundary_and_obstacles(start, goal, top_vertex, bottom_vertex, obs_number): def find_neighbor(node, ob, closed): - # generate neighbors in certain condition - ob_list = ob.tolist() - neighbor: list = [] + # Convert obstacles to a set for faster lookup + ob_set = set(map(tuple, ob.tolist())) + neighbor_set = set() + + # Generate neighbors within the 3x3 grid around the node for x in range(node.coordinate[0] - 1, node.coordinate[0] + 2): for y in range(node.coordinate[1] - 1, node.coordinate[1] + 2): - if [x, y] not in ob_list: - # find all possible neighbor nodes - neighbor.append([x, y]) - # remove node violate the motion rule - # 1. remove node.coordinate itself - neighbor.remove(node.coordinate) - # 2. remove neighbor nodes who cross through two diagonal - # positioned obstacles since there is no enough space for - # robot to go through two diagonal positioned obstacles - - # top bottom left right neighbors of node - top_nei = [node.coordinate[0], node.coordinate[1] + 1] - bottom_nei = [node.coordinate[0], node.coordinate[1] - 1] - left_nei = [node.coordinate[0] - 1, node.coordinate[1]] - right_nei = [node.coordinate[0] + 1, node.coordinate[1]] - # neighbors in four vertex - lt_nei = [node.coordinate[0] - 1, node.coordinate[1] + 1] - rt_nei = [node.coordinate[0] + 1, node.coordinate[1] + 1] - lb_nei = [node.coordinate[0] - 1, node.coordinate[1] - 1] - rb_nei = [node.coordinate[0] + 1, node.coordinate[1] - 1] - - # remove the unnecessary neighbors - if top_nei and left_nei in ob_list and lt_nei in neighbor: - neighbor.remove(lt_nei) - if top_nei and right_nei in ob_list and rt_nei in neighbor: - neighbor.remove(rt_nei) - if bottom_nei and left_nei in ob_list and lb_nei in neighbor: - neighbor.remove(lb_nei) - if bottom_nei and right_nei in ob_list and rb_nei in neighbor: - neighbor.remove(rb_nei) - neighbor = [x for x in neighbor if x not in closed] - return neighbor + coord = (x, y) + if coord not in ob_set and coord != tuple(node.coordinate): + neighbor_set.add(coord) + + # Define neighbors in cardinal and diagonal directions + top_nei = (node.coordinate[0], node.coordinate[1] + 1) + bottom_nei = (node.coordinate[0], node.coordinate[1] - 1) + left_nei = (node.coordinate[0] - 1, node.coordinate[1]) + right_nei = (node.coordinate[0] + 1, node.coordinate[1]) + lt_nei = (node.coordinate[0] - 1, node.coordinate[1] + 1) + rt_nei = (node.coordinate[0] + 1, node.coordinate[1] + 1) + lb_nei = (node.coordinate[0] - 1, node.coordinate[1] - 1) + rb_nei = (node.coordinate[0] + 1, node.coordinate[1] - 1) + + # Remove neighbors that violate diagonal motion rules + if top_nei in ob_set and left_nei in ob_set: + neighbor_set.discard(lt_nei) + if top_nei in ob_set and right_nei in ob_set: + neighbor_set.discard(rt_nei) + if bottom_nei in ob_set and left_nei in ob_set: + neighbor_set.discard(lb_nei) + if bottom_nei in ob_set and right_nei in ob_set: + neighbor_set.discard(rb_nei) + + # Filter out neighbors that are in the closed set + closed_set = set(map(tuple, closed)) + neighbor_set -= closed_set + + return list(neighbor_set) + def find_node_index(coordinate, node_list): From 1cb45a5d3bdcb07b254c20ce7763d527435c355e Mon Sep 17 00:00:00 2001 From: Aryaz Eghbali <64126826+AryazE@users.noreply.github.com> Date: Mon, 20 Jan 2025 09:16:20 +0100 Subject: [PATCH 821/940] Fixed multitype list (#1076) * Fixed multitype list * Cast to float * Reverted to all floats * Moved all remaining to float --- .../BreadthFirstSearch/breadth_first_search.py | 10 +++++----- PathPlanning/Dijkstra/dijkstra.py | 10 +++++----- .../ProbabilisticRoadMap/probabilistic_road_map.py | 10 +++++----- PathPlanning/VoronoiRoadMap/voronoi_road_map.py | 10 +++++----- 4 files changed, 20 insertions(+), 20 deletions(-) diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index ff662170e7..ad994732a5 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -220,20 +220,20 @@ def main(): # set obstacle positions ox, oy = [], [] for i in range(-10, 60): - ox.append(i) + ox.append(float(i)) oy.append(-10.0) for i in range(-10, 60): ox.append(60.0) - oy.append(i) + oy.append(float(i)) for i in range(-10, 61): - ox.append(i) + ox.append(float(i)) oy.append(60.0) for i in range(-10, 61): ox.append(-10.0) - oy.append(i) + oy.append(float(i)) for i in range(-10, 40): ox.append(20.0) - oy.append(i) + oy.append(float(i)) for i in range(0, 40): ox.append(40.0) oy.append(60.0 - i) diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index 004e49f15a..8a585e4b18 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -221,20 +221,20 @@ def main(): # set obstacle positions ox, oy = [], [] for i in range(-10, 60): - ox.append(i) + ox.append(float(i)) oy.append(-10.0) for i in range(-10, 60): ox.append(60.0) - oy.append(i) + oy.append(float(i)) for i in range(-10, 61): - ox.append(i) + ox.append(float(i)) oy.append(60.0) for i in range(-10, 61): ox.append(-10.0) - oy.append(i) + oy.append(float(i)) for i in range(-10, 40): ox.append(20.0) - oy.append(i) + oy.append(float(i)) for i in range(0, 40): ox.append(40.0) oy.append(60.0 - i) diff --git a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py index 294c389023..8bacfd5d19 100644 --- a/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py +++ b/PathPlanning/ProbabilisticRoadMap/probabilistic_road_map.py @@ -273,20 +273,20 @@ def main(rng=None): oy = [] for i in range(60): - ox.append(i) + ox.append(float(i)) oy.append(0.0) for i in range(60): ox.append(60.0) - oy.append(i) + oy.append(float(i)) for i in range(61): - ox.append(i) + ox.append(float(i)) oy.append(60.0) for i in range(61): ox.append(0.0) - oy.append(i) + oy.append(float(i)) for i in range(40): ox.append(20.0) - oy.append(i) + oy.append(float(i)) for i in range(40): ox.append(40.0) oy.append(60.0 - i) diff --git a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py index 0a1f6f5526..a27e1b6928 100644 --- a/PathPlanning/VoronoiRoadMap/voronoi_road_map.py +++ b/PathPlanning/VoronoiRoadMap/voronoi_road_map.py @@ -146,20 +146,20 @@ def main(): oy = [] for i in range(60): - ox.append(i) + ox.append(float(i)) oy.append(0.0) for i in range(60): ox.append(60.0) - oy.append(i) + oy.append(float(i)) for i in range(61): - ox.append(i) + ox.append(float(i)) oy.append(60.0) for i in range(61): ox.append(0.0) - oy.append(i) + oy.append(float(i)) for i in range(40): ox.append(20.0) - oy.append(i) + oy.append(float(i)) for i in range(40): ox.append(40.0) oy.append(60.0 - i) From 9672434483459a00b13ece407079fbb53dd8a6b0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Jan 2025 08:02:30 +0900 Subject: [PATCH 822/940] build(deps): bump numpy from 2.2.1 to 2.2.2 in /requirements (#1122) Bumps [numpy](https://github.com/numpy/numpy) from 2.2.1 to 2.2.2. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v2.2.1...v2.2.2) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index d212202cdb..e1c117cb1e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 2.2.1 +numpy == 2.2.2 scipy == 1.15.1 matplotlib == 3.10.0 cvxpy == 1.5.3 From 2bc59fe61247982eaed5b0b7eab842658a5c07d8 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Jan 2025 08:15:53 +0900 Subject: [PATCH 823/940] build(deps): bump ruff from 0.9.1 to 0.9.2 in /requirements (#1123) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.9.1 to 0.9.2. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.9.1...0.9.2) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e1c117cb1e..11b91abb1f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.14.1 # For unit test -ruff == 0.9.1 # For unit test +ruff == 0.9.2 # For unit test From 5a66105ff5dc9924fc6b8f8986afaf52f0fd870d Mon Sep 17 00:00:00 2001 From: Aglargil <34728006+Aglargil@users.noreply.github.com> Date: Wed, 22 Jan 2025 17:57:12 +0800 Subject: [PATCH 824/940] Extend frenet_optimal_trajectory to support more scenarios (#1114) * feat: Add third derivative and curvature rate calculations to CubicSpline classes * feat: Extend frenet_optimal_trajectory to support more scenarios * fix: frenet optimal trajectory type check * fix: cubic spline planner code style check * fix: frenet optimal trajectory review * feat: frenet_optimal_trajectory update doc * fix: frenet optimal trajectory review * fix: frenet optimal trajectory * fix: frenet optimal trajectory --- .../CubicSpline/cubic_spline_planner.py | 67 +++ .../cartesian_frenet_converter.py | 144 +++++ .../frenet_optimal_trajectory.py | 550 +++++++++++++----- .../frenet_frame_path_main.rst | 30 +- tests/test_frenet_optimal_trajectory.py | 40 +- 5 files changed, 674 insertions(+), 157 deletions(-) create mode 100644 PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py diff --git a/PathPlanning/CubicSpline/cubic_spline_planner.py b/PathPlanning/CubicSpline/cubic_spline_planner.py index 7cc7bedc79..2391f67c39 100644 --- a/PathPlanning/CubicSpline/cubic_spline_planner.py +++ b/PathPlanning/CubicSpline/cubic_spline_planner.py @@ -76,6 +76,11 @@ def calc_position(self, x): if `x` is outside the data point's `x` range, return None. + Parameters + ---------- + x : float + x position to calculate y. + Returns ------- y : float @@ -99,6 +104,11 @@ def calc_first_derivative(self, x): if x is outside the input x, return None + Parameters + ---------- + x : float + x position to calculate first derivative. + Returns ------- dy : float @@ -121,6 +131,11 @@ def calc_second_derivative(self, x): if x is outside the input x, return None + Parameters + ---------- + x : float + x position to calculate second derivative. + Returns ------- ddy : float @@ -137,6 +152,31 @@ def calc_second_derivative(self, x): ddy = 2.0 * self.c[i] + 6.0 * self.d[i] * dx return ddy + def calc_third_derivative(self, x): + """ + Calc third derivative at given x. + + if x is outside the input x, return None + + Parameters + ---------- + x : float + x position to calculate third derivative. + + Returns + ------- + dddy : float + third derivative for given x. + """ + if x < self.x[0]: + return None + elif x > self.x[-1]: + return None + + i = self.__search_index(x) + dddy = 6.0 * self.d[i] + return dddy + def __search_index(self, x): """ search data segment index @@ -287,6 +327,33 @@ def calc_curvature(self, s): k = (ddy * dx - ddx * dy) / ((dx ** 2 + dy ** 2)**(3 / 2)) return k + def calc_curvature_rate(self, s): + """ + calc curvature rate + + Parameters + ---------- + s : float + distance from the start point. if `s` is outside the data point's + range, return None. + + Returns + ------- + k : float + curvature rate for given s. + """ + dx = self.sx.calc_first_derivative(s) + dy = self.sy.calc_first_derivative(s) + ddx = self.sx.calc_second_derivative(s) + ddy = self.sy.calc_second_derivative(s) + dddx = self.sx.calc_third_derivative(s) + dddy = self.sy.calc_third_derivative(s) + a = dx * ddy - dy * ddx + b = dx * dddy - dy * dddx + c = dx * ddx + dy * ddy + d = dx * dx + dy * dy + return (b * d - 3.0 * a * c) / (d * d * d) + def calc_yaw(self, s): """ calc yaw diff --git a/PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py b/PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py new file mode 100644 index 0000000000..4cc8650c89 --- /dev/null +++ b/PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py @@ -0,0 +1,144 @@ +""" + +A converter between Cartesian and Frenet coordinate systems + +author: Wang Zheng (@Aglargil) + +Ref: + +- [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame] +(https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf) + +""" + +import math + + +class CartesianFrenetConverter: + """ + A class for converting states between Cartesian and Frenet coordinate systems + """ + + @ staticmethod + def cartesian_to_frenet(rs, rx, ry, rtheta, rkappa, rdkappa, x, y, v, a, theta, kappa): + """ + Convert state from Cartesian coordinate to Frenet coordinate + + Parameters + ---------- + rs: reference line s-coordinate + rx, ry: reference point coordinates + rtheta: reference point heading + rkappa: reference point curvature + rdkappa: reference point curvature rate + x, y: current position + v: velocity + a: acceleration + theta: heading angle + kappa: curvature + + Returns + ------- + s_condition: [s(t), s'(t), s''(t)] + d_condition: [d(s), d'(s), d''(s)] + """ + dx = x - rx + dy = y - ry + + cos_theta_r = math.cos(rtheta) + sin_theta_r = math.sin(rtheta) + + cross_rd_nd = cos_theta_r * dy - sin_theta_r * dx + d = math.copysign(math.hypot(dx, dy), cross_rd_nd) + + delta_theta = theta - rtheta + tan_delta_theta = math.tan(delta_theta) + cos_delta_theta = math.cos(delta_theta) + + one_minus_kappa_r_d = 1 - rkappa * d + d_dot = one_minus_kappa_r_d * tan_delta_theta + + kappa_r_d_prime = rdkappa * d + rkappa * d_dot + + d_ddot = (-kappa_r_d_prime * tan_delta_theta + + one_minus_kappa_r_d / (cos_delta_theta * cos_delta_theta) * + (kappa * one_minus_kappa_r_d / cos_delta_theta - rkappa)) + + s = rs + s_dot = v * cos_delta_theta / one_minus_kappa_r_d + + delta_theta_prime = one_minus_kappa_r_d / cos_delta_theta * kappa - rkappa + s_ddot = (a * cos_delta_theta - + s_dot * s_dot * + (d_dot * delta_theta_prime - kappa_r_d_prime)) / one_minus_kappa_r_d + + return [s, s_dot, s_ddot], [d, d_dot, d_ddot] + + @ staticmethod + def frenet_to_cartesian(rs, rx, ry, rtheta, rkappa, rdkappa, s_condition, d_condition): + """ + Convert state from Frenet coordinate to Cartesian coordinate + + Parameters + ---------- + rs: reference line s-coordinate + rx, ry: reference point coordinates + rtheta: reference point heading + rkappa: reference point curvature + rdkappa: reference point curvature rate + s_condition: [s(t), s'(t), s''(t)] + d_condition: [d(s), d'(s), d''(s)] + + Returns + ------- + x, y: position + theta: heading angle + kappa: curvature + v: velocity + a: acceleration + """ + if abs(rs - s_condition[0]) >= 1.0e-6: + raise ValueError( + "The reference point s and s_condition[0] don't match") + + cos_theta_r = math.cos(rtheta) + sin_theta_r = math.sin(rtheta) + + x = rx - sin_theta_r * d_condition[0] + y = ry + cos_theta_r * d_condition[0] + + one_minus_kappa_r_d = 1 - rkappa * d_condition[0] + + tan_delta_theta = d_condition[1] / one_minus_kappa_r_d + delta_theta = math.atan2(d_condition[1], one_minus_kappa_r_d) + cos_delta_theta = math.cos(delta_theta) + + theta = CartesianFrenetConverter.normalize_angle(delta_theta + rtheta) + + kappa_r_d_prime = rdkappa * d_condition[0] + rkappa * d_condition[1] + + kappa = (((d_condition[2] + kappa_r_d_prime * tan_delta_theta) * + cos_delta_theta * cos_delta_theta) / one_minus_kappa_r_d + rkappa) * \ + cos_delta_theta / one_minus_kappa_r_d + + d_dot = d_condition[1] * s_condition[1] + v = math.sqrt(one_minus_kappa_r_d * one_minus_kappa_r_d * + s_condition[1] * s_condition[1] + d_dot * d_dot) + + delta_theta_prime = one_minus_kappa_r_d / cos_delta_theta * kappa - rkappa + + a = (s_condition[2] * one_minus_kappa_r_d / cos_delta_theta + + s_condition[1] * s_condition[1] / cos_delta_theta * + (d_condition[1] * delta_theta_prime - kappa_r_d_prime)) + + return x, y, theta, kappa, v, a + + @ staticmethod + def normalize_angle(angle): + """ + Normalize angle to [-pi, pi] + """ + a = math.fmod(angle + math.pi, 2.0 * math.pi) + if a < 0.0: + a += 2.0 * math.pi + return a - math.pi diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index 331df36309..248894c1c6 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -17,43 +17,314 @@ import numpy as np import matplotlib.pyplot as plt import copy -import math import sys import pathlib + sys.path.append(str(pathlib.Path(__file__).parent.parent)) -from QuinticPolynomialsPlanner.quintic_polynomials_planner import \ - QuinticPolynomial +from QuinticPolynomialsPlanner.quintic_polynomials_planner import QuinticPolynomial from CubicSpline import cubic_spline_planner -SIM_LOOP = 500 +from enum import Enum, auto +from FrenetOptimalTrajectory.cartesian_frenet_converter import ( + CartesianFrenetConverter, +) + + +class LateralMovement(Enum): + HIGH_SPEED = auto() + LOW_SPEED = auto() + + +class LongitudinalMovement(Enum): + MERGING_AND_STOPPING = auto() + VELOCITY_KEEPING = auto() + + +# Default Parameters + +LATERAL_MOVEMENT = LateralMovement.HIGH_SPEED +LONGITUDINAL_MOVEMENT = LongitudinalMovement.VELOCITY_KEEPING -# Parameter MAX_SPEED = 50.0 / 3.6 # maximum speed [m/s] -MAX_ACCEL = 2.0 # maximum acceleration [m/ss] +MAX_ACCEL = 5.0 # maximum acceleration [m/ss] MAX_CURVATURE = 1.0 # maximum curvature [1/m] -MAX_ROAD_WIDTH = 7.0 # maximum road width [m] -D_ROAD_W = 1.0 # road width sampling length [m] DT = 0.2 # time tick [s] MAX_T = 5.0 # max prediction time [m] MIN_T = 4.0 # min prediction time [m] -TARGET_SPEED = 30.0 / 3.6 # target speed [m/s] -D_T_S = 5.0 / 3.6 # target speed sampling length [m/s] N_S_SAMPLE = 1 # sampling number of target speed -ROBOT_RADIUS = 2.0 # robot radius [m] # cost weights K_J = 0.1 K_T = 0.1 +K_S_DOT = 1.0 K_D = 1.0 +K_S = 1.0 K_LAT = 1.0 K_LON = 1.0 +SIM_LOOP = 500 show_animation = True -class QuarticPolynomial: +if LATERAL_MOVEMENT == LateralMovement.LOW_SPEED: + MAX_ROAD_WIDTH = 1.0 # maximum road width [m] + D_ROAD_W = 0.2 # road width sampling length [m] + TARGET_SPEED = 3.0 / 3.6 # maximum speed [m/s] + D_T_S = 0.5 / 3.6 # target speed sampling length [m/s] + # Waypoints + WX = [0.0, 2.0, 4.0, 6.0, 8.0, 10.0] + WY = [0.0, 0.0, 1.0, 0.0, -1.0, -2.0] + OBSTACLES = np.array([[3.0, 1.0], [5.0, -0.0], [6.0, 0.5], [8.0, -1.5]]) + ROBOT_RADIUS = 0.5 # robot radius [m] + + # Initial state parameters + INITIAL_SPEED = 1.0 / 3.6 # current speed [m/s] + INITIAL_ACCEL = 0.0 # current acceleration [m/ss] + INITIAL_LAT_POSITION = 0.5 # current lateral position [m] + INITIAL_LAT_SPEED = 0.0 # current lateral speed [m/s] + INITIAL_LAT_ACCELERATION = 0.0 # current lateral acceleration [m/s] + INITIAL_COURSE_POSITION = 0.0 # current course position + + ANIMATION_AREA = 5.0 # Animation area length [m] + + STOP_S = 4.0 # Merge and stop distance [m] + D_S = 0.3 # Stop point sampling length [m] + N_STOP_S_SAMPLE = 3 # Stop point sampling number +else: + MAX_ROAD_WIDTH = 7.0 # maximum road width [m] + D_ROAD_W = 1.0 # road width sampling length [m] + TARGET_SPEED = 30.0 / 3.6 # target speed [m/s] + D_T_S = 5.0 / 3.6 # target speed sampling length [m/s] + # Waypoints + WX = [0.0, 10.0, 20.5, 35.0, 70.5] + WY = [0.0, -6.0, 5.0, 6.5, 0.0] + # Obstacle list + OBSTACLES = np.array( + [[20.0, 10.0], [30.0, 6.0], [30.0, 8.0], [35.0, 8.0], [50.0, 3.0]] + ) + ROBOT_RADIUS = 2.0 # robot radius [m] + + # Initial state parameters + INITIAL_SPEED = 10.0 / 3.6 # current speed [m/s] + INITIAL_ACCEL = 0.0 # current acceleration [m/ss] + INITIAL_LAT_POSITION = 2.0 # current lateral position [m] + INITIAL_LAT_SPEED = 0.0 # current lateral speed [m/s] + INITIAL_LAT_ACCELERATION = 0.0 # current lateral acceleration [m/s] + INITIAL_COURSE_POSITION = 0.0 # current course position + + ANIMATION_AREA = 20.0 # Animation area length [m] + STOP_S = 25.0 # Merge and stop distance [m] + D_S = 2 # Stop point sampling length [m] + N_STOP_S_SAMPLE = 4 # Stop point sampling number + + +class LateralMovementStrategy: + def calc_lateral_trajectory(self, fp, di, c_d, c_d_d, c_d_dd, Ti): + """ + Calculate the lateral trajectory + """ + raise NotImplementedError("calc_lateral_trajectory not implemented") + + def calc_cartesian_parameters(self, fp, csp): + """ + Calculate the cartesian parameters (x, y, yaw, curvature, v, a) + """ + raise NotImplementedError("calc_cartesian_parameters not implemented") + + +class HighSpeedLateralMovementStrategy(LateralMovementStrategy): + def calc_lateral_trajectory(self, fp, di, c_d, c_d_d, c_d_dd, Ti): + tp = copy.deepcopy(fp) + s0_d = fp.s_d[0] + s0_dd = fp.s_dd[0] + # d'(t) = d'(s) * s'(t) + # d''(t) = d''(s) * s'(t)^2 + d'(s) * s''(t) + lat_qp = QuinticPolynomial( + c_d, c_d_d * s0_d, c_d_dd * s0_d**2 + c_d_d * s0_dd, di, 0.0, 0.0, Ti + ) + + tp.d = [] + tp.d_d = [] + tp.d_dd = [] + tp.d_ddd = [] + + # Calculate all derivatives in a single loop to reduce iterations + for i in range(len(fp.t)): + t = fp.t[i] + s_d = fp.s_d[i] + s_dd = fp.s_dd[i] + + s_d_inv = 1.0 / (s_d + 1e-6) + 1e-6 # Avoid division by zero + s_d_inv_sq = s_d_inv * s_d_inv # Square of inverse + + d = lat_qp.calc_point(t) + d_d = lat_qp.calc_first_derivative(t) + d_dd = lat_qp.calc_second_derivative(t) + d_ddd = lat_qp.calc_third_derivative(t) + + tp.d.append(d) + # d'(s) = d'(t) / s'(t) + tp.d_d.append(d_d * s_d_inv) + # d''(s) = (d''(t) - d'(s) * s''(t)) / s'(t)^2 + tp.d_dd.append((d_dd - tp.d_d[i] * s_dd) * s_d_inv_sq) + tp.d_ddd.append(d_ddd) + + return tp + + def calc_cartesian_parameters(self, fp, csp): + # calc global positions + for i in range(len(fp.s)): + ix, iy = csp.calc_position(fp.s[i]) + if ix is None: + break + i_yaw = csp.calc_yaw(fp.s[i]) + i_kappa = csp.calc_curvature(fp.s[i]) + i_dkappa = csp.calc_curvature_rate(fp.s[i]) + s_condition = [fp.s[i], fp.s_d[i], fp.s_dd[i]] + d_condition = [ + fp.d[i], + fp.d_d[i], + fp.d_dd[i], + ] + x, y, theta, kappa, v, a = CartesianFrenetConverter.frenet_to_cartesian( + fp.s[i], ix, iy, i_yaw, i_kappa, i_dkappa, s_condition, d_condition + ) + fp.x.append(x) + fp.y.append(y) + fp.yaw.append(theta) + fp.c.append(kappa) + fp.v.append(v) + fp.a.append(a) + return fp + + +class LowSpeedLateralMovementStrategy(LateralMovementStrategy): + def calc_lateral_trajectory(self, fp, di, c_d, c_d_d, c_d_dd, Ti): + s0 = fp.s[0] + s1 = fp.s[-1] + tp = copy.deepcopy(fp) + # d = d(s), d_d = d'(s), d_dd = d''(s) + # * shift s range from [s0, s1] to [0, s1 - s0] + lat_qp = QuinticPolynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, s1 - s0) + + tp.d = [lat_qp.calc_point(s - s0) for s in fp.s] + tp.d_d = [lat_qp.calc_first_derivative(s - s0) for s in fp.s] + tp.d_dd = [lat_qp.calc_second_derivative(s - s0) for s in fp.s] + tp.d_ddd = [lat_qp.calc_third_derivative(s - s0) for s in fp.s] + return tp + + def calc_cartesian_parameters(self, fp, csp): + # calc global positions + for i in range(len(fp.s)): + ix, iy = csp.calc_position(fp.s[i]) + if ix is None: + break + i_yaw = csp.calc_yaw(fp.s[i]) + i_kappa = csp.calc_curvature(fp.s[i]) + i_dkappa = csp.calc_curvature_rate(fp.s[i]) + s_condition = [fp.s[i], fp.s_d[i], fp.s_dd[i]] + d_condition = [fp.d[i], fp.d_d[i], fp.d_dd[i]] + x, y, theta, kappa, v, a = CartesianFrenetConverter.frenet_to_cartesian( + fp.s[i], ix, iy, i_yaw, i_kappa, i_dkappa, s_condition, d_condition + ) + fp.x.append(x) + fp.y.append(y) + fp.yaw.append(theta) + fp.c.append(kappa) + fp.v.append(v) + fp.a.append(a) + return fp + + +class LongitudinalMovementStrategy: + def calc_longitudinal_trajectory(self, c_speed, c_accel, Ti, s0): + """ + Calculate the longitudinal trajectory + """ + raise NotImplementedError("calc_longitudinal_trajectory not implemented") + + def get_d_arrange(self, s0): + """ + Get the d sample range + """ + raise NotImplementedError("get_d_arrange not implemented") + + def calc_destination_cost(self, fp): + """ + Calculate the destination cost + """ + raise NotImplementedError("calc_destination_cost not implemented") + + +class VelocityKeepingLongitudinalMovementStrategy(LongitudinalMovementStrategy): + def calc_longitudinal_trajectory(self, c_speed, c_accel, Ti, s0): + fplist = [] + for tv in np.arange( + TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S + ): + fp = FrenetPath() + lon_qp = QuarticPolynomial(s0, c_speed, c_accel, tv, 0.0, Ti) + fp.t = [t for t in np.arange(0.0, Ti, DT)] + fp.s = [lon_qp.calc_point(t) for t in fp.t] + fp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] + fp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t] + fp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t] + fplist.append(fp) + return fplist + + def get_d_arrange(self, s0): + return np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W) + + def calc_destination_cost(self, fp): + ds = (TARGET_SPEED - fp.s_d[-1]) ** 2 + return K_S_DOT * ds + + +class MergingAndStoppingLongitudinalMovementStrategy(LongitudinalMovementStrategy): + def calc_longitudinal_trajectory(self, c_speed, c_accel, Ti, s0): + if s0 >= STOP_S: + return [] + fplist = [] + for s in np.arange( + STOP_S - D_S * N_STOP_S_SAMPLE, STOP_S + D_S * N_STOP_S_SAMPLE, D_S + ): + fp = FrenetPath() + lon_qp = QuinticPolynomial(s0, c_speed, c_accel, s, 0.0, 0.0, Ti) + fp.t = [t for t in np.arange(0.0, Ti, DT)] + fp.s = [lon_qp.calc_point(t) for t in fp.t] + fp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] + fp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t] + fp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t] + fplist.append(fp) + return fplist + + def get_d_arrange(self, s0): + # Only if s0 is less than STOP_S / 3, then we sample the road width + if s0 < STOP_S / 3: + return np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W) + else: + return [0.0] + + def calc_destination_cost(self, fp): + ds = (STOP_S - fp.s[-1]) ** 2 + return K_S * ds + +LATERAL_MOVEMENT_STRATEGY: LateralMovementStrategy +LONGITUDINAL_MOVEMENT_STRATEGY: LongitudinalMovementStrategy + +if LATERAL_MOVEMENT == LateralMovement.HIGH_SPEED: + LATERAL_MOVEMENT_STRATEGY = HighSpeedLateralMovementStrategy() +else: + LATERAL_MOVEMENT_STRATEGY = LowSpeedLateralMovementStrategy() + +if LONGITUDINAL_MOVEMENT == LongitudinalMovement.VELOCITY_KEEPING: + LONGITUDINAL_MOVEMENT_STRATEGY = VelocityKeepingLongitudinalMovementStrategy() +else: + LONGITUDINAL_MOVEMENT_STRATEGY = MergingAndStoppingLongitudinalMovementStrategy() + +class QuarticPolynomial: def __init__(self, xs, vxs, axs, vxe, axe, time): # calc coefficient of quartic polynomial @@ -61,29 +332,25 @@ def __init__(self, xs, vxs, axs, vxe, axe, time): self.a1 = vxs self.a2 = axs / 2.0 - A = np.array([[3 * time ** 2, 4 * time ** 3], - [6 * time, 12 * time ** 2]]) - b = np.array([vxe - self.a1 - 2 * self.a2 * time, - axe - 2 * self.a2]) + A = np.array([[3 * time**2, 4 * time**3], [6 * time, 12 * time**2]]) + b = np.array([vxe - self.a1 - 2 * self.a2 * time, axe - 2 * self.a2]) x = np.linalg.solve(A, b) self.a3 = x[0] self.a4 = x[1] def calc_point(self, t): - xt = self.a0 + self.a1 * t + self.a2 * t ** 2 + \ - self.a3 * t ** 3 + self.a4 * t ** 4 + xt = self.a0 + self.a1 * t + self.a2 * t**2 + self.a3 * t**3 + self.a4 * t**4 return xt def calc_first_derivative(self, t): - xt = self.a1 + 2 * self.a2 * t + \ - 3 * self.a3 * t ** 2 + 4 * self.a4 * t ** 3 + xt = self.a1 + 2 * self.a2 * t + 3 * self.a3 * t**2 + 4 * self.a4 * t**3 return xt def calc_second_derivative(self, t): - xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t ** 2 + xt = 2 * self.a2 + 6 * self.a3 * t + 12 * self.a4 * t**2 return xt @@ -94,111 +361,85 @@ def calc_third_derivative(self, t): class FrenetPath: - def __init__(self): self.t = [] self.d = [] - self.d_d = [] - self.d_dd = [] - self.d_ddd = [] + self.d_d = [] # d'(s) + self.d_dd = [] # d''(s) + self.d_ddd = [] # d'''(t) in low speed / d'''(s) in high speed self.s = [] - self.s_d = [] - self.s_dd = [] - self.s_ddd = [] - self.cd = 0.0 - self.cv = 0.0 + self.s_d = [] # s'(t) + self.s_dd = [] # s''(t) + self.s_ddd = [] # s'''(t) self.cf = 0.0 self.x = [] self.y = [] self.yaw = [] + self.v = [] + self.a = [] self.ds = [] self.c = [] - -def calc_frenet_paths(c_speed, c_accel, c_d, c_d_d, c_d_dd, s0): + def pop_front(self): + self.x.pop(0) + self.y.pop(0) + self.yaw.pop(0) + self.v.pop(0) + self.a.pop(0) + self.s.pop(0) + self.s_d.pop(0) + self.s_dd.pop(0) + self.s_ddd.pop(0) + self.d.pop(0) + self.d_d.pop(0) + self.d_dd.pop(0) + self.d_ddd.pop(0) + + +def calc_frenet_paths(c_s_d, c_s_dd, c_d, c_d_d, c_d_dd, s0): frenet_paths = [] - # generate path to each offset goal - for di in np.arange(-MAX_ROAD_WIDTH, MAX_ROAD_WIDTH, D_ROAD_W): - - # Lateral motion planning - for Ti in np.arange(MIN_T, MAX_T, DT): - fp = FrenetPath() - - # lat_qp = quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) - lat_qp = QuinticPolynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti) - - fp.t = [t for t in np.arange(0.0, Ti, DT)] - fp.d = [lat_qp.calc_point(t) for t in fp.t] - fp.d_d = [lat_qp.calc_first_derivative(t) for t in fp.t] - fp.d_dd = [lat_qp.calc_second_derivative(t) for t in fp.t] - fp.d_ddd = [lat_qp.calc_third_derivative(t) for t in fp.t] - - # Longitudinal motion planning (Velocity keeping) - for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, - TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): - tfp = copy.deepcopy(fp) - lon_qp = QuarticPolynomial(s0, c_speed, c_accel, tv, 0.0, Ti) - - tfp.s = [lon_qp.calc_point(t) for t in fp.t] - tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] - tfp.s_dd = [lon_qp.calc_second_derivative(t) for t in fp.t] - tfp.s_ddd = [lon_qp.calc_third_derivative(t) for t in fp.t] - - Jp = sum(np.power(tfp.d_ddd, 2)) # square of jerk - Js = sum(np.power(tfp.s_ddd, 2)) # square of jerk - - # square of diff from target speed - ds = (TARGET_SPEED - tfp.s_d[-1]) ** 2 - - tfp.cd = K_J * Jp + K_T * Ti + K_D * tfp.d[-1] ** 2 - tfp.cv = K_J * Js + K_T * Ti + K_D * ds - tfp.cf = K_LAT * tfp.cd + K_LON * tfp.cv - - frenet_paths.append(tfp) + for Ti in np.arange(MIN_T, MAX_T, DT): + lon_paths = LONGITUDINAL_MOVEMENT_STRATEGY.calc_longitudinal_trajectory( + c_s_d, c_s_dd, Ti, s0 + ) + + for fp in lon_paths: + for di in LONGITUDINAL_MOVEMENT_STRATEGY.get_d_arrange(s0): + tp = LATERAL_MOVEMENT_STRATEGY.calc_lateral_trajectory( + fp, di, c_d, c_d_d, c_d_dd, Ti + ) + + Jp = sum(np.power(tp.d_ddd, 2)) # square of jerk + Js = sum(np.power(tp.s_ddd, 2)) # square of jerk + + lat_cost = K_J * Jp + K_T * Ti + K_D * tp.d[-1] ** 2 + lon_cost = ( + K_J * Js + + K_T * Ti + + LONGITUDINAL_MOVEMENT_STRATEGY.calc_destination_cost(tp) + ) + tp.cf = K_LAT * lat_cost + K_LON * lon_cost + frenet_paths.append(tp) return frenet_paths def calc_global_paths(fplist, csp): - for fp in fplist: - - # calc global positions - for i in range(len(fp.s)): - ix, iy = csp.calc_position(fp.s[i]) - if ix is None: - break - i_yaw = csp.calc_yaw(fp.s[i]) - di = fp.d[i] - fx = ix + di * math.cos(i_yaw + math.pi / 2.0) - fy = iy + di * math.sin(i_yaw + math.pi / 2.0) - fp.x.append(fx) - fp.y.append(fy) - - # calc yaw and ds - for i in range(len(fp.x) - 1): - dx = fp.x[i + 1] - fp.x[i] - dy = fp.y[i + 1] - fp.y[i] - fp.yaw.append(math.atan2(dy, dx)) - fp.ds.append(math.hypot(dx, dy)) - - fp.yaw.append(fp.yaw[-1]) - fp.ds.append(fp.ds[-1]) - - # calc curvature - for i in range(len(fp.yaw) - 1): - fp.c.append((fp.yaw[i + 1] - fp.yaw[i]) / fp.ds[i]) - - return fplist + return [ + LATERAL_MOVEMENT_STRATEGY.calc_cartesian_parameters(fp, csp) for fp in fplist + ] def check_collision(fp, ob): for i in range(len(ob[:, 0])): - d = [((ix - ob[i, 0]) ** 2 + (iy - ob[i, 1]) ** 2) - for (ix, iy) in zip(fp.x, fp.y)] + d = [ + ((ix - ob[i, 0]) ** 2 + (iy - ob[i, 1]) ** 2) + for (ix, iy) in zip(fp.x, fp.y) + ] - collision = any([di <= ROBOT_RADIUS ** 2 for di in d]) + collision = any([di <= ROBOT_RADIUS**2 for di in d]) if collision: return False @@ -207,38 +448,41 @@ def check_collision(fp, ob): def check_paths(fplist, ob): - ok_ind = [] + path_dict = { + "max_speed_error": [], + "max_accel_error": [], + "max_curvature_error": [], + "collision_error": [], + "ok": [], + } for i, _ in enumerate(fplist): - if any([v > MAX_SPEED for v in fplist[i].s_d]): # Max speed check - continue - elif any([abs(a) > MAX_ACCEL for a in - fplist[i].s_dd]): # Max accel check - continue - elif any([abs(c) > MAX_CURVATURE for c in - fplist[i].c]): # Max curvature check - continue + if any([v > MAX_SPEED for v in fplist[i].v]): # Max speed check + path_dict["max_speed_error"].append(fplist[i]) + elif any([abs(a) > MAX_ACCEL for a in fplist[i].a]): # Max accel check + path_dict["max_accel_error"].append(fplist[i]) + elif any([abs(c) > MAX_CURVATURE for c in fplist[i].c]): # Max curvature check + path_dict["max_curvature_error"].append(fplist[i]) elif not check_collision(fplist[i], ob): - continue + path_dict["collision_error"].append(fplist[i]) + else: + path_dict["ok"].append(fplist[i]) + return path_dict - ok_ind.append(i) - return [fplist[i] for i in ok_ind] - - -def frenet_optimal_planning(csp, s0, c_speed, c_accel, c_d, c_d_d, c_d_dd, ob): - fplist = calc_frenet_paths(c_speed, c_accel, c_d, c_d_d, c_d_dd, s0) +def frenet_optimal_planning(csp, s0, c_s_d, c_s_dd, c_d, c_d_d, c_d_dd, ob): + fplist = calc_frenet_paths(c_s_d, c_s_dd, c_d, c_d_d, c_d_dd, s0) fplist = calc_global_paths(fplist, csp) - fplist = check_paths(fplist, ob) + fpdict = check_paths(fplist, ob) # find minimum cost path min_cost = float("inf") best_path = None - for fp in fplist: + for fp in fpdict["ok"]: if min_cost >= fp.cf: min_cost = fp.cf best_path = fp - return best_path + return [best_path, fpdict] def generate_target_course(x, y): @@ -259,40 +503,39 @@ def generate_target_course(x, y): def main(): print(__file__ + " start!!") - # way points - wx = [0.0, 10.0, 20.5, 35.0, 70.5] - wy = [0.0, -6.0, 5.0, 6.5, 0.0] - # obstacle lists - ob = np.array([[20.0, 10.0], - [30.0, 6.0], - [30.0, 8.0], - [35.0, 8.0], - [50.0, 3.0] - ]) - - tx, ty, tyaw, tc, csp = generate_target_course(wx, wy) - - # initial state - c_speed = 10.0 / 3.6 # current speed [m/s] - c_accel = 0.0 # current acceleration [m/ss] - c_d = 2.0 # current lateral position [m] - c_d_d = 0.0 # current lateral speed [m/s] - c_d_dd = 0.0 # current lateral acceleration [m/s] - s0 = 0.0 # current course position - - area = 20.0 # animation area length [m] + tx, ty, tyaw, tc, csp = generate_target_course(WX, WY) + + # Initialize state using global parameters + c_s_d = INITIAL_SPEED + c_s_dd = INITIAL_ACCEL + c_d = INITIAL_LAT_POSITION + c_d_d = INITIAL_LAT_SPEED + c_d_dd = INITIAL_LAT_ACCELERATION + s0 = INITIAL_COURSE_POSITION + + area = ANIMATION_AREA + + last_path = None for i in range(SIM_LOOP): - path = frenet_optimal_planning( - csp, s0, c_speed, c_accel, c_d, c_d_d, c_d_dd, ob) + [path, fpdict] = frenet_optimal_planning( + csp, s0, c_s_d, c_s_dd, c_d, c_d_d, c_d_dd, OBSTACLES + ) + + if path is None: + path = copy.deepcopy(last_path) + path.pop_front() + if len(path.x) <= 1: + print("Finish") + break + last_path = path s0 = path.s[1] c_d = path.d[1] c_d_d = path.d_d[1] c_d_dd = path.d_dd[1] - c_speed = path.s_d[1] - c_accel = path.s_dd[1] - + c_s_d = path.s_d[1] + c_s_dd = path.s_dd[1] if np.hypot(path.x[1] - tx[-1], path.y[1] - ty[-1]) <= 1.0: print("Goal") break @@ -301,15 +544,16 @@ def main(): plt.cla() # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect( - 'key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + "key_release_event", + lambda event: [exit(0) if event.key == "escape" else None], + ) plt.plot(tx, ty) - plt.plot(ob[:, 0], ob[:, 1], "xk") + plt.plot(OBSTACLES[:, 0], OBSTACLES[:, 1], "xk") plt.plot(path.x[1:], path.y[1:], "-or") plt.plot(path.x[1], path.y[1], "vc") plt.xlim(path.x[1] - area, path.x[1] + area) plt.ylim(path.y[1] - area, path.y[1] + area) - plt.title("v[km/h]:" + str(c_speed * 3.6)[0:4]) + plt.title("v[km/h]:" + str(path.v[1] * 3.6)[0:4]) plt.grid(True) plt.pause(0.0001) @@ -320,5 +564,5 @@ def main(): plt.show() -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/docs/modules/path_planning/frenet_frame_path/frenet_frame_path_main.rst b/docs/modules/path_planning/frenet_frame_path/frenet_frame_path_main.rst index e9d9041e0e..38efaf2b53 100644 --- a/docs/modules/path_planning/frenet_frame_path/frenet_frame_path_main.rst +++ b/docs/modules/path_planning/frenet_frame_path/frenet_frame_path_main.rst @@ -1,14 +1,40 @@ Optimal Trajectory in a Frenet Frame ------------------------------------ -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/animation.gif - This is optimal trajectory generation in a Frenet Frame. The cyan line is the target course and black crosses are obstacles. The red line is predicted path. +High Speed and Velocity Keeping Scenario +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/high_speed_and_velocity_keeping_frenet_path.gif + +This scenario shows how the trajectory is maintained at high speeds while keeping a consistent velocity. + +High Speed and Merging and Stopping Scenario +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/high_speed_and_merging_and_stopping_frenet_path.gif + +This scenario demonstrates the trajectory planning at high speeds with merging and stopping behaviors. + +Low Speed and Velocity Keeping Scenario +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/low_speed_and_velocity_keeping_frenet_path.gif + +This scenario demonstrates how the trajectory is managed at low speeds while maintaining a steady velocity. + +Low Speed and Merging and Stopping Scenario +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/low_speed_and_merging_and_stopping_frenet_path.gif + +This scenario illustrates the trajectory planning at low speeds with merging and stopping behaviors. + Ref: - `Optimal Trajectory Generation for Dynamic Street Scenarios in a diff --git a/tests/test_frenet_optimal_trajectory.py b/tests/test_frenet_optimal_trajectory.py index 72bb7a8341..b8761ff4a6 100644 --- a/tests/test_frenet_optimal_trajectory.py +++ b/tests/test_frenet_optimal_trajectory.py @@ -1,12 +1,48 @@ import conftest from PathPlanning.FrenetOptimalTrajectory import frenet_optimal_trajectory as m +from PathPlanning.FrenetOptimalTrajectory.frenet_optimal_trajectory import ( + LateralMovement, + LongitudinalMovement, +) -def test1(): +def default_scenario_test(): m.show_animation = False m.SIM_LOOP = 5 m.main() -if __name__ == '__main__': +def high_speed_and_merging_and_stopping_scenario_test(): + m.show_animation = False + m.LATERAL_MOVEMENT = LateralMovement.HIGH_SPEED + m.LONGITUDINAL_MOVEMENT = LongitudinalMovement.MERGING_AND_STOPPING + m.SIM_LOOP = 5 + m.main() + + +def high_speed_and_velocity_keeping_scenario_test(): + m.show_animation = False + m.LATERAL_MOVEMENT = LateralMovement.HIGH_SPEED + m.LONGITUDINAL_MOVEMENT = LongitudinalMovement.VELOCITY_KEEPING + m.SIM_LOOP = 5 + m.main() + + +def low_speed_and_velocity_keeping_scenario_test(): + m.show_animation = False + m.LATERAL_MOVEMENT = LateralMovement.LOW_SPEED + m.LONGITUDINAL_MOVEMENT = LongitudinalMovement.VELOCITY_KEEPING + m.SIM_LOOP = 5 + m.main() + + +def low_speed_and_merging_and_stopping_scenario_test(): + m.show_animation = False + m.LATERAL_MOVEMENT = LateralMovement.LOW_SPEED + m.LONGITUDINAL_MOVEMENT = LongitudinalMovement.MERGING_AND_STOPPING + m.SIM_LOOP = 5 + m.main() + + +if __name__ == "__main__": conftest.run_this_test(__file__) From 95eedba44713883d805fb92ff74aabbe1fa4f735 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 24 Jan 2025 13:24:26 +0900 Subject: [PATCH 825/940] Fix lint error (#1124) --- .../arm_obstacle_navigation.py | 4 ++-- .../arm_obstacle_navigation_2.py | 4 ++-- .../dynamic_movement_primitives.py | 13 ++++++------- .../Eta3SplineTrajectory/eta3_spline_trajectory.py | 7 +++---- PathPlanning/RRT/sobol/sobol.py | 12 ++++++------ 5 files changed, 19 insertions(+), 21 deletions(-) diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py index e377897e54..593db42b34 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py @@ -158,7 +158,7 @@ def astar_torus(grid, start_node, goal_node): while parent_map[route[0][0]][route[0][1]] != (): route.insert(0, parent_map[route[0][0]][route[0][1]]) - print("The route found covers %d grid cells." % len(route)) + print(f"The route found covers {len(route)} grid cells.") for i in range(1, len(route)): grid[route[i]] = 6 plt.cla() @@ -212,7 +212,7 @@ def calc_heuristic_map(M, goal_node): return heuristic_map -class NLinkArm(object): +class NLinkArm: """ Class for controlling and plotting a planar arm with an arbitrary number of links. """ diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py index 10f4615c34..5295b7ca3a 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py @@ -189,7 +189,7 @@ def astar_torus(grid, start_node, goal_node): while parent_map[route[0][0]][route[0][1]] != (): route.insert(0, parent_map[route[0][0]][route[0][1]]) - print("The route found covers %d grid cells." % len(route)) + print(f"The route found covers {len(route)} grid cells.") for i in range(1, len(route)): grid[route[i]] = 6 plt.cla() @@ -243,7 +243,7 @@ def calc_heuristic_map(M, goal_node): return heuristic_map -class NLinkArm(object): +class NLinkArm: """ Class for controlling and plotting a planar arm with an arbitrary number of links. """ diff --git a/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py b/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py index 468d3b9f97..aa34934c0e 100644 --- a/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py +++ b/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py @@ -18,7 +18,7 @@ import numpy as np -class DMP(object): +class DMP: def __init__(self, training_data, data_period, K=156.25, B=25): """ @@ -215,21 +215,21 @@ def show_DMP_purpose(self): T_vals = np.linspace(T_orig, 2*T_orig, 20) for new_q0_value in q0_vals: - plot_title = "Initial Position = [%s, %s]" % \ - (round(new_q0_value[0], 2), round(new_q0_value[1], 2)) + plot_title = (f"Initial Position = [{round(new_q0_value[0], 2)}," + f" {round(new_q0_value[1], 2)}]") _, path = self.recreate_trajectory(new_q0_value, g_orig, T_orig) self.view_trajectory(path, title=plot_title, demo=True) for new_g_value in g_vals: - plot_title = "Goal Position = [%s, %s]" % \ - (round(new_g_value[0], 2), round(new_g_value[1], 2)) + plot_title = (f"Goal Position = [{round(new_g_value[0], 2)}," + f" {round(new_g_value[1], 2)}]") _, path = self.recreate_trajectory(q0_orig, new_g_value, T_orig) self.view_trajectory(path, title=plot_title, demo=True) for new_T_value in T_vals: - plot_title = "Period = %s [sec]" % round(new_T_value, 2) + plot_title = f"Period = {round(new_T_value, 2)} [sec]" _, path = self.recreate_trajectory(q0_orig, g_orig, new_T_value) self.view_trajectory(path, title=plot_title, demo=True) @@ -257,5 +257,4 @@ def example_DMP(): if __name__ == '__main__': - example_DMP() diff --git a/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py b/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py index d034cb8a32..2dab7a7add 100644 --- a/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py +++ b/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py @@ -26,8 +26,7 @@ class MaxVelocityNotReached(Exception): def __init__(self, actual_vel, max_vel): - self.message = 'Actual velocity {} does not equal desired max velocity {}!'.format( - actual_vel, max_vel) + self.message = f'Actual velocity {actual_vel} does not equal desired max velocity {max_vel}!' class eta3_trajectory(Eta3Path): @@ -42,7 +41,7 @@ def __init__(self, segments, max_vel, v0=0.0, a0=0.0, max_accel=2.0, max_jerk=5. # ensure that all inputs obey the assumptions of the model assert max_vel > 0 and v0 >= 0 and a0 >= 0 and max_accel > 0 and max_jerk > 0 \ and a0 <= max_accel and v0 <= max_vel - super(eta3_trajectory, self).__init__(segments=segments) + super(__class__, self).__init__(segments=segments) self.total_length = sum([s.segment_length for s in self.segments]) self.max_vel = float(max_vel) self.v0 = float(v0) @@ -166,7 +165,7 @@ def velocity_profile(self): try: assert np.isclose(self.vels[index], 0) except AssertionError as e: - print('The final velocity {} is not zero'.format(self.vels[index])) + print(f'The final velocity {self.vels[index]} is not zero') raise e self.seg_lengths[index] = s_sf diff --git a/PathPlanning/RRT/sobol/sobol.py b/PathPlanning/RRT/sobol/sobol.py index 428ba58a98..cddc9d7c72 100644 --- a/PathPlanning/RRT/sobol/sobol.py +++ b/PathPlanning/RRT/sobol/sobol.py @@ -370,8 +370,8 @@ def i4_sobol(dim_num, seed): if (dim_num < 1 or dim_max < dim_num): print('I4_SOBOL - Fatal error!') print(' The spatial dimension DIM_NUM should satisfy:') - print(' 1 <= DIM_NUM <= %d' % dim_max) - print(' But this input value is DIM_NUM = %d' % dim_num) + print(f' 1 <= DIM_NUM <= {dim_max:d}') + print(f' But this input value is DIM_NUM = {dim_num:d}') return None dim_num_save = dim_num @@ -443,7 +443,7 @@ def i4_sobol(dim_num, seed): # l_var = i4_bit_lo0(seed) - elif (seed <= seed_save): + elif seed <= seed_save: seed_save = 0 lastq = np.zeros(dim_num) @@ -471,8 +471,8 @@ def i4_sobol(dim_num, seed): if maxcol < l_var: print('I4_SOBOL - Fatal error!') print(' Too many calls!') - print(' MAXCOL = %d\n' % maxcol) - print(' L = %d\n' % l_var) + print(f' MAXCOL = {maxcol:d}\n') + print(f' L = {l_var:d}\n') return None @@ -819,7 +819,7 @@ def r8mat_write(filename, m, n, a): with open(filename, 'w') as output: for i in range(0, m): for j in range(0, n): - s = ' %g' % (a[i, j]) + s = f' {a[i, j]:g}' output.write(s) output.write('\n') From 2a489b3b82d3d0a3152cf7641fa137deb116972d Mon Sep 17 00:00:00 2001 From: parmaski <89462537+parmaski@users.noreply.github.com> Date: Fri, 24 Jan 2025 13:28:12 +0900 Subject: [PATCH 826/940] Fix: dead link URL in doc (#1087) * fix dead url links * change link to MPC course * remove dead link --- .github/FUNDING.yml | 2 +- .../arm_obstacle_navigation.py | 2 +- .../arm_obstacle_navigation_2.py | 2 +- PathPlanning/BugPlanning/bug.py | 2 +- .../dynamic_movement_primitives.py | 2 +- .../eta3_spline_trajectory.py | 2 +- .../InformedRRTStar/informed_rrt_star.py | 2 +- .../quintic_polynomials_planner.py | 2 +- PathPlanning/RRT/sobol/sobol.py | 2 +- .../state_lattice_planner.py | 4 ++-- .../wavefront_coverage_path_planner.py | 2 +- PathTracking/cgmres_nmpc/cgmres_nmpc.py | 2 +- README.md | 21 +++++++++---------- SLAM/GraphBasedSLAM/data/README.rst | 2 +- appveyor.yml | 2 +- docs/conf.py | 2 +- docs/getting_started_main.rst | 2 +- docs/how_to_contribute_main.rst | 2 +- docs/make.bat | 2 +- .../particle_filter_localization_main.rst | 2 +- .../rectangle_fitting_main.rst | 4 ++-- .../bezier_path/bezier_path_main.rst | 2 +- .../bugplanner/bugplanner_main.rst | 2 +- .../coverage_path/coverage_path_main.rst | 2 +- .../dubins_path/dubins_path_main.rst | 2 +- ...l_predictive_trajectory_generator_main.rst | 2 +- .../quintic_polynomials_planner_main.rst | 2 +- .../reeds_shepp_path_main.rst | 2 +- docs/modules/path_planning/rrt/rrt_main.rst | 8 +++---- docs/modules/path_planning/rrt/rrt_star.rst | 2 +- .../state_lattice_planner_main.rst | 4 ++-- .../cgmres_nmpc/cgmres_nmpc_main.rst | 2 +- .../lqr_speed_and_steering_control_main.rst | 2 +- ...ictive_speed_and_steering_control_main.rst | 4 ++-- users_comments.md | 16 +++++--------- 35 files changed, 55 insertions(+), 62 deletions(-) diff --git a/.github/FUNDING.yml b/.github/FUNDING.yml index 24f0926299..0d943696cc 100644 --- a/.github/FUNDING.yml +++ b/.github/FUNDING.yml @@ -1,4 +1,4 @@ # These are supported funding model platforms github: AtsushiSakai patreon: myenigma -custom: https://www.paypal.me/myenigmapay/ +custom: https://www.paypal.com/paypalme/myenigmapay/ diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py index 593db42b34..9047c13851 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation.py @@ -34,7 +34,7 @@ def detect_collision(line_seg, circle): """ Determines whether a line segment (arm link) is in contact with a circle (obstacle). - Credit to: http://doswa.com/2009/07/13/circle-segment-intersectioncollision.html + Credit to: https://web.archive.org/web/20200130224918/http://doswa.com/2009/07/13/circle-segment-intersectioncollision.html Args: line_seg: List of coordinates of line segment endpoints e.g. [[1, 1], [2, 2]] circle: List of circle coordinates and radius e.g. [0, 0, 0.5] is a circle centered diff --git a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py index 5295b7ca3a..f5d435082a 100644 --- a/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py +++ b/ArmNavigation/arm_obstacle_navigation/arm_obstacle_navigation_2.py @@ -66,7 +66,7 @@ def detect_collision(line_seg, circle): """ Determines whether a line segment (arm link) is in contact with a circle (obstacle). - Credit to: http://doswa.com/2009/07/13/circle-segment-intersectioncollision.html + Credit to: https://web.archive.org/web/20200130224918/http://doswa.com/2009/07/13/circle-segment-intersectioncollision.html Args: line_seg: List of coordinates of line segment endpoints e.g. [[1, 1], [2, 2]] circle: List of circle coordinates and radius e.g. [0, 0, 0.5] is a circle centered diff --git a/PathPlanning/BugPlanning/bug.py b/PathPlanning/BugPlanning/bug.py index 62fec7c109..34890cb55a 100644 --- a/PathPlanning/BugPlanning/bug.py +++ b/PathPlanning/BugPlanning/bug.py @@ -1,7 +1,7 @@ """ Bug Planning author: Sarim Mehdi(muhammadsarim.mehdi@studio.unibo.it) -Source: https://sites.google.com/site/ece452bugalgorithms/ +Source: https://web.archive.org/web/20201103052224/https://sites.google.com/site/ece452bugalgorithms/ """ import numpy as np diff --git a/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py b/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py index aa34934c0e..9ccd18b7c2 100644 --- a/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py +++ b/PathPlanning/DynamicMovementPrimitives/dynamic_movement_primitives.py @@ -9,7 +9,7 @@ More information on Dynamic Movement Primitives available at: https://arxiv.org/abs/2102.03861 -https://www.frontiersin.org/articles/10.3389/fncom.2013.00138/full +https://www.frontiersin.org/journals/computational-neuroscience/articles/10.3389/fncom.2013.00138/full """ diff --git a/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py b/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py index 2dab7a7add..a73797dacb 100644 --- a/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py +++ b/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py @@ -6,7 +6,7 @@ Atsushi Sakai (@Atsushi_twi) Refs: -- https://jwdinius.github.io/blog/2018/eta3traj +- https://jwdinius.github.io/blog/2018/eta3traj/ - [eta^3-Splines for the Smooth Path Generation of Wheeled Mobile Robots] (https://ieeexplore.ieee.org/document/4339545/) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index c37326e490..0483949c99 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -6,7 +6,7 @@ Reference: Informed RRT*: Optimal Sampling-based Path planning Focused via Direct Sampling of an Admissible Ellipsoidal Heuristic -https://arxiv.org/pdf/1404.2334.pdf +https://arxiv.org/pdf/1404.2334 """ import sys diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py index 8ba11a23d2..fdc181afab 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py @@ -6,7 +6,7 @@ Ref: -- [Local Path planning And Motion Control For Agv In Positioning](http://ieeexplore.ieee.org/document/637936/) +- [Local Path planning And Motion Control For Agv In Positioning](https://ieeexplore.ieee.org/document/637936/) """ diff --git a/PathPlanning/RRT/sobol/sobol.py b/PathPlanning/RRT/sobol/sobol.py index cddc9d7c72..520d686a1d 100644 --- a/PathPlanning/RRT/sobol/sobol.py +++ b/PathPlanning/RRT/sobol/sobol.py @@ -13,7 +13,7 @@ PYTHON versions by Corrado Chisari Original code is available at - http://people.sc.fsu.edu/~jburkardt/py_src/sobol/sobol.html + https://people.sc.fsu.edu/~jburkardt/py_src/sobol/sobol.html Note: the i4 prefix means that the function takes a numeric argument or returns a number which is interpreted inside the function as a 4 diff --git a/PathPlanning/StateLatticePlanner/state_lattice_planner.py b/PathPlanning/StateLatticePlanner/state_lattice_planner.py index f4b1461b7a..7f8e725e0a 100644 --- a/PathPlanning/StateLatticePlanner/state_lattice_planner.py +++ b/PathPlanning/StateLatticePlanner/state_lattice_planner.py @@ -12,8 +12,8 @@ - State Space Sampling of Feasible Motions for High-Performance Mobile Robot Navigation in Complex Environments -http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.187.8210&rep=rep1 -&type=pdf +https://citeseerx.ist.psu.edu/document?repid=rep1&type=pdf +&doi=e2256b5b24137f89e473f01df288cb3aa72e56a0 """ import sys diff --git a/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py b/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py index 7e93caa8fb..c5a139454b 100644 --- a/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py +++ b/PathPlanning/WavefrontCPP/wavefront_coverage_path_planner.py @@ -4,7 +4,7 @@ author: Todd Tang paper: Planning paths of complete coverage of an unstructured environment by a mobile robot - Zelinsky et.al. -link: http://pinkwink.kr/attachment/cfile3.uf@1354654A4E8945BD13FE77.pdf +link: https://pinkwink.kr/attachment/cfile3.uf@1354654A4E8945BD13FE77.pdf """ import os diff --git a/PathTracking/cgmres_nmpc/cgmres_nmpc.py b/PathTracking/cgmres_nmpc/cgmres_nmpc.py index bb5699b888..a582c9da81 100644 --- a/PathTracking/cgmres_nmpc/cgmres_nmpc.py +++ b/PathTracking/cgmres_nmpc/cgmres_nmpc.py @@ -6,7 +6,7 @@ Ref: Shunichi09/nonlinear_control: Implementing the nonlinear model predictive -control, sliding mode control https://github.com/Shunichi09/nonlinear_control +control, sliding mode control https://github.com/Shunichi09/PythonLinearNonlinearControl """ diff --git a/README.md b/README.md index ee40dfc7eb..ec65342430 100644 --- a/README.md +++ b/README.md @@ -5,7 +5,6 @@ ![GitHub_Action_MacOS_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/MacOS_CI/badge.svg) ![GitHub_Action_Windows_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/Windows_CI/badge.svg) [![Build status](https://ci.appveyor.com/api/projects/status/sb279kxuv1be391g?svg=true)](https://ci.appveyor.com/project/AtsushiSakai/pythonrobotics) -[![codecov](https://codecov.io/gh/AtsushiSakai/PythonRobotics/branch/master/graph/badge.svg)](https://codecov.io/gh/AtsushiSakai/PythonRobotics) Python codes for robotics algorithm. @@ -111,7 +110,7 @@ For development: - [pytest-xdist](https://pypi.org/project/pytest-xdist/) (for parallel unit tests) -- [mypy](http://mypy-lang.org/) (for type check) +- [mypy](https://mypy-lang.org/) (for type check) - [sphinx](https://www.sphinx-doc.org/) (for document generation) @@ -328,7 +327,7 @@ The animation shows a robot finding its path and rerouting to avoid obstacles as Refs: -- [D* Lite](http://idm-lab.org/bib/abstracts/papers/aaai02b.pd) +- [D* Lite](http://idm-lab.org/bib/abstracts/papers/aaai02b.pdf) - [Improved Fast Replanning for Robot Navigation in Unknown Terrain](http://www.cs.cmu.edu/~maxim/files/dlite_icra02.pdf) ### Potential Field algorithm @@ -357,9 +356,9 @@ This code uses the model predictive trajectory generator to solve boundary probl Ref: -- [Optimal rough terrain trajectory generation for wheeled mobile robots](http://journals.sagepub.com/doi/pdf/10.1177/0278364906075328) +- [Optimal rough terrain trajectory generation for wheeled mobile robots](https://journals.sagepub.com/doi/pdf/10.1177/0278364906075328) -- [State Space Sampling of Feasible Motions for High-Performance Mobile Robot Navigation in Complex Environments](http://www.frc.ri.cmu.edu/~alonzo/pubs/papers/JFR_08_SS_Sampling.pdf) +- [State Space Sampling of Feasible Motions for High-Performance Mobile Robot Navigation in Complex Environments](https://www.frc.ri.cmu.edu/~alonzo/pubs/papers/JFR_08_SS_Sampling.pdf) ### Biased polar sampling @@ -403,7 +402,7 @@ Ref: - [Incremental Sampling-based Algorithms for Optimal Motion Planning](https://arxiv.org/abs/1005.0416) -- [Sampling-based Algorithms for Optimal Motion Planning](http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.419.5503&rep=rep1&type=pdf) +- [Sampling-based Algorithms for Optimal Motion Planning](https://citeseerx.ist.psu.edu/document?repid=rep1&type=pdf&doi=bddbc99f97173430aa49a0ada53ab5bade5902fa) ### RRT\* with reeds-shepp path @@ -421,7 +420,7 @@ A double integrator motion model is used for LQR local planner. Ref: -- [LQR\-RRT\*: Optimal Sampling\-Based Motion Planning with Automatically Derived Extension Heuristics](http://lis.csail.mit.edu/pubs/perez-icra12.pdf) +- [LQR\-RRT\*: Optimal Sampling\-Based Motion Planning with Automatically Derived Extension Heuristics](https://lis.csail.mit.edu/pubs/perez-icra12.pdf) - [MahanFathi/LQR\-RRTstar: LQR\-RRT\* method is used for random motion planning of a simple pendulum in its phase plot](https://github.com/MahanFathi/LQR-RRTstar) @@ -436,7 +435,7 @@ It can calculate a 2D path, velocity, and acceleration profile based on quintic Ref: -- [Local Path Planning And Motion Control For Agv In Positioning](http://ieeexplore.ieee.org/document/637936/) +- [Local Path Planning And Motion Control For Agv In Positioning](https://ieeexplore.ieee.org/document/637936/) ## Reeds Shepp planning @@ -523,7 +522,7 @@ Path tracking simulation with LQR speed and steering control. Ref: -- [Towards fully autonomous driving: Systems and algorithms \- IEEE Conference Publication](http://ieeexplore.ieee.org/document/5940562/) +- [Towards fully autonomous driving: Systems and algorithms \- IEEE Conference Publication](https://ieeexplore.ieee.org/document/5940562/) ## Model predictive speed and steering control @@ -630,7 +629,7 @@ If you or your company would like to support this project, please consider: - [Become a backer or sponsor on Patreon](https://www.patreon.com/myenigma) -- [One-time donation via PayPal](https://www.paypal.me/myenigmapay/) +- [One-time donation via PayPal](https://www.paypal.com/paypalme/myenigmapay/) If you would like to support us in some other way, please contact with creating an issue. @@ -640,7 +639,7 @@ If you would like to support us in some other way, please contact with creating They are providing a free license of their IDEs for this OSS development. -### [1Password](https://github.com/1Password/1password-teams-open-source) +### [1Password](https://github.com/1Password/for-open-source) They are providing a free license of their 1Password team license for this OSS project. diff --git a/SLAM/GraphBasedSLAM/data/README.rst b/SLAM/GraphBasedSLAM/data/README.rst index c875cce73f..15bc5b6c03 100644 --- a/SLAM/GraphBasedSLAM/data/README.rst +++ b/SLAM/GraphBasedSLAM/data/README.rst @@ -3,4 +3,4 @@ Acknowledgments and References Thanks to Luca Larlone for allowing inclusion of the `Intel dataset `_ in this repo. -1. Carlone, L. and Censi, A., 2014. `From angular manifolds to the integer lattice: Guaranteed orientation estimation with application to pose graph optimization `_. IEEE Transactions on Robotics, 30(2), pp.475-492. +1. Carlone, L. and Censi, A., 2014. `From angular manifolds to the integer lattice: Guaranteed orientation estimation with application to pose graph optimization `_. IEEE Transactions on Robotics, 30(2), pp.475-492. diff --git a/appveyor.yml b/appveyor.yml index 4964bab3da..05ad8a2820 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -4,7 +4,7 @@ environment: global: # SDK v7.0 MSVC Express 2008's SetEnv.cmd script will fail if the # /E:ON and /V:ON options are not enabled in the batch script intepreter - # See: http://stackoverflow.com/a/13751649/163740 + # See: https://stackoverflow.com/a/13751649/163740 CMD_IN_ENV: "cmd /E:ON /V:ON /C .\\appveyor\\run_with_env.cmd" matrix: diff --git a/docs/conf.py b/docs/conf.py index 46f69cf17b..4e06f3f988 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -3,7 +3,7 @@ # # This file does only contain a selection of the most common options. For a # full list see the documentation: -# http://www.sphinx-doc.org/en/master/config +# https://www.sphinx-doc.org/en/master/config # -- Path setup -------------------------------------------------------------- diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index 88f218545e..004d68227b 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -49,7 +49,7 @@ For development: .. _`pytest-xdist`: https://github.com/pytest-dev/pytest-xdist .. _`mypy`: https://mypy-lang.org/ .. _`sphinx`: https://www.sphinx-doc.org/en/master/index.html -.. _`ruff`: https://github.com/charliermarsh/ruff +.. _`ruff`: https://github.com/astral-sh/ruff How to use diff --git a/docs/how_to_contribute_main.rst b/docs/how_to_contribute_main.rst index 48895d6fda..915b2155e4 100644 --- a/docs/how_to_contribute_main.rst +++ b/docs/how_to_contribute_main.rst @@ -159,6 +159,6 @@ Sponsors .. _`JetBrains`: https://www.jetbrains.com/ .. _`Sponsor @AtsushiSakai on GitHub Sponsors`: https://github.com/sponsors/AtsushiSakai .. _`Become a backer or sponsor on Patreon`: https://www.patreon.com/myenigma -.. _`One-time donation via PayPal`: https://www.paypal.me/myenigmapay/ +.. _`One-time donation via PayPal`: https://www.paypal.com/paypalme/myenigmapay/ diff --git a/docs/make.bat b/docs/make.bat index 6aab964dcc..07dcebea41 100644 --- a/docs/make.bat +++ b/docs/make.bat @@ -22,7 +22,7 @@ if errorlevel 9009 ( echo.may add the Sphinx directory to PATH. echo. echo.If you don't have Sphinx installed, grab it from - echo.http://sphinx-doc.org/ + echo.https://sphinx-doc.org/ exit /b 1 ) diff --git a/docs/modules/localization/particle_filter_localization/particle_filter_localization_main.rst b/docs/modules/localization/particle_filter_localization/particle_filter_localization_main.rst index c8652ce8a7..20a9eb58fc 100644 --- a/docs/modules/localization/particle_filter_localization/particle_filter_localization_main.rst +++ b/docs/modules/localization/particle_filter_localization/particle_filter_localization_main.rst @@ -34,4 +34,4 @@ References: ~~~~~~~~~~~ - `_PROBABILISTIC ROBOTICS: `_ -- `Improving the particle filter in high dimensions using conjugate artificial process noise `_ +- `Improving the particle filter in high dimensions using conjugate artificial process noise `_ diff --git a/docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst b/docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst index 50a50141b2..b6ced1dc1d 100644 --- a/docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst +++ b/docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst @@ -7,7 +7,7 @@ This is an object shape recognition using rectangle fitting. This example code is based on this paper algorithm: -- `Efficient L\-Shape Fitting for Vehicle Detection Using Laser Scanners \- The Robotics Institute Carnegie Mellon University `_ +- `Efficient L\-Shape Fitting for Vehicle Detection Using Laser Scanners \- The Robotics Institute Carnegie Mellon University `_ The algorithm consists of 2 steps as below. @@ -66,4 +66,4 @@ API References ~~~~~~~~~~ -- `Efficient L\-Shape Fitting for Vehicle Detection Using Laser Scanners \- The Robotics Institute Carnegie Mellon University `_ +- `Efficient L\-Shape Fitting for Vehicle Detection Using Laser Scanners \- The Robotics Institute Carnegie Mellon University `_ diff --git a/docs/modules/path_planning/bezier_path/bezier_path_main.rst b/docs/modules/path_planning/bezier_path/bezier_path_main.rst index fbba6a4496..d306a85352 100644 --- a/docs/modules/path_planning/bezier_path/bezier_path_main.rst +++ b/docs/modules/path_planning/bezier_path/bezier_path_main.rst @@ -17,4 +17,4 @@ Ref: - `Continuous Curvature Path Generation Based on Bezier Curves for Autonomous - Vehicles `__ + Vehicles ` diff --git a/docs/modules/path_planning/bugplanner/bugplanner_main.rst b/docs/modules/path_planning/bugplanner/bugplanner_main.rst index 72cc46709f..81c91c0313 100644 --- a/docs/modules/path_planning/bugplanner/bugplanner_main.rst +++ b/docs/modules/path_planning/bugplanner/bugplanner_main.rst @@ -5,4 +5,4 @@ This is a 2D planning with Bug algorithm. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BugPlanner/animation.gif -- `ECE452 Bug Algorithms `_ +- `ECE452 Bug Algorithms `_ diff --git a/docs/modules/path_planning/coverage_path/coverage_path_main.rst b/docs/modules/path_planning/coverage_path/coverage_path_main.rst index 828342a294..0a688b5ed2 100644 --- a/docs/modules/path_planning/coverage_path/coverage_path_main.rst +++ b/docs/modules/path_planning/coverage_path/coverage_path_main.rst @@ -29,6 +29,6 @@ This is a 2D grid based wavefront coverage path planner simulation: .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation2.gif .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation3.gif -- `Planning paths of complete coverage of an unstructured environment by a mobile robot `_ +- `Planning paths of complete coverage of an unstructured environment by a mobile robot `_ diff --git a/docs/modules/path_planning/dubins_path/dubins_path_main.rst b/docs/modules/path_planning/dubins_path/dubins_path_main.rst index 516638d83d..12172fb51e 100644 --- a/docs/modules/path_planning/dubins_path/dubins_path_main.rst +++ b/docs/modules/path_planning/dubins_path/dubins_path_main.rst @@ -72,5 +72,5 @@ Reference ~~~~~~~~~~~~~~~~~~~~ - `On Curves of Minimal Length with a Constraint on Average Curvature, and with Prescribed Initial and Terminal Positions and Tangents `__ - `Dubins path - Wikipedia `__ -- `15.3.1 Dubins Curves `__ +- `15.3.1 Dubins Curves `__ - `A Comprehensive, Step-by-Step Tutorial to Computing Dubin’s Paths `__ diff --git a/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst b/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst index 0fc997898e..463363ddcf 100644 --- a/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst +++ b/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst @@ -19,4 +19,4 @@ Lookup table generation sample Ref: - `Optimal rough terrain trajectory generation for wheeled mobile - robots `__ + robots `__ diff --git a/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst b/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst index feec345bae..0412b3c9b3 100644 --- a/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst +++ b/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst @@ -101,6 +101,6 @@ References: ~~~~~~~~~~~ - `Local Path Planning And Motion Control For Agv In - Positioning `__ + Positioning `__ diff --git a/docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path_main.rst b/docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path_main.rst index 6d456417fe..ff377eb91b 100644 --- a/docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path_main.rst +++ b/docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path_main.rst @@ -383,7 +383,7 @@ Hence, we have: Ref: - `15.3.2 Reeds-Shepp - Curves `__ + Curves `__ - `optimal paths for a car that goes both forwards and backwards `__ diff --git a/docs/modules/path_planning/rrt/rrt_main.rst b/docs/modules/path_planning/rrt/rrt_main.rst index 5a3a30dcff..e5f351a7ba 100644 --- a/docs/modules/path_planning/rrt/rrt_main.rst +++ b/docs/modules/path_planning/rrt/rrt_main.rst @@ -57,7 +57,7 @@ Ref: - `Informed RRT\*: Optimal Sampling-based Path Planning Focused via Direct Sampling of an Admissible Ellipsoidal - Heuristic `__ + Heuristic `__ .. _batch-informed-rrt*: @@ -90,10 +90,10 @@ PID is used for speed control. Ref: - `Motion Planning in Complex Environments using Closed-loop - Prediction `__ + Prediction `__ - `Real-time Motion Planning with Applications to Autonomous Urban - Driving `__ + Driving `__ - `[1601.06326] Sampling-based Algorithms for Optimal Motion Planning Using Closed-loop Prediction `__ @@ -113,6 +113,6 @@ Ref: - `LQR-RRT\*: Optimal Sampling-Based Motion Planning with Automatically Derived Extension - Heuristics `__ + Heuristics `__ - `MahanFathi/LQR-RRTstar: LQR-RRT\* method is used for random motion planning of a simple pendulum in its phase plot `__ \ No newline at end of file diff --git a/docs/modules/path_planning/rrt/rrt_star.rst b/docs/modules/path_planning/rrt/rrt_star.rst index d36eaac70e..6deb6b9172 100644 --- a/docs/modules/path_planning/rrt/rrt_star.rst +++ b/docs/modules/path_planning/rrt/rrt_star.rst @@ -16,6 +16,6 @@ Simulation Ref ^^^ -- `Sampling-based Algorithms for Optimal Motion Planning `__ +- `Sampling-based Algorithms for Optimal Motion Planning `__ - `Incremental Sampling-based Algorithms for Optimal Motion Planning `__ diff --git a/docs/modules/path_planning/state_lattice_planner/state_lattice_planner_main.rst b/docs/modules/path_planning/state_lattice_planner/state_lattice_planner_main.rst index 3ef0c7eca2..d5e7ed17d1 100644 --- a/docs/modules/path_planning/state_lattice_planner/state_lattice_planner_main.rst +++ b/docs/modules/path_planning/state_lattice_planner/state_lattice_planner_main.rst @@ -25,9 +25,9 @@ Lane sampling Ref: - `Optimal rough terrain trajectory generation for wheeled mobile - robots `__ + robots `__ - `State Space Sampling of Feasible Motions for High-Performance Mobile Robot Navigation in Complex - Environments `__ + Environments `__ diff --git a/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst b/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst index a1980ba17e..23f1218a94 100644 --- a/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst +++ b/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst @@ -60,7 +60,7 @@ Ref - `Shunichi09/nonlinear_control: Implementing the nonlinear model predictive control, sliding mode - control `__ + control `__ - `非線形モデル予測制御におけるCGMRES法をpythonで実装する - Qiita `__ diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst b/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst index a0b145456c..ded187e972 100644 --- a/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst +++ b/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst @@ -137,4 +137,4 @@ Simulation results References: ~~~~~~~~~~~ -- `Towards fully autonomous driving: Systems and algorithms `__ +- `Towards fully autonomous driving: Systems and algorithms `__ diff --git a/docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst b/docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst index 59a7166674..de55b545ba 100644 --- a/docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst +++ b/docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst @@ -133,5 +133,5 @@ Reference - `Vehicle Dynamics and Control \| Rajesh Rajamani \| Springer `__ -- `MPC Course Material - MPC Lab @ - UC-Berkeley `__ +- `MPC Book - MPC Lab @ + UC-Berkeley `__ diff --git a/users_comments.md b/users_comments.md index 66e8b4022e..a2f798eac4 100644 --- a/users_comments.md +++ b/users_comments.md @@ -17,13 +17,7 @@ Ref: # Educational users -This is a list of users who are using PythonRobotics for education. - -If you found other users, please make an issue to let me know. - -- [CSCI/ARTI 4530/6530: Introduction to Robotics (Fall 2018), University of Georgia ](http://cobweb.cs.uga.edu/~ramviyas/csci_x530.html) - -- [CIT Modules & Programmes \- COMP9073 \- Automation with Python](https://courses.cit.ie/index.cfm/page/module/moduleId/14416) +If you found users who are using PythonRobotics for education, please make an issue to let me know. # Stargazers location map @@ -386,14 +380,14 @@ Dear Atsushi Sakai,
    Thank you so much for creating PythonRobotics and docume 1. B. Blaga, M. Deac, R. W. Y. Al-doori, M. Negru and R. Dǎnescu, "Miniature Autonomous Vehicle Development on Raspberry Pi," 2018 IEEE 14th International Conference on Intelligent Computer Communication and Processing (ICCP), Cluj-Napoca, Romania, 2018, pp. 229-236. doi: 10.1109/ICCP.2018.8516589 keywords: {Automobiles;Task analysis;Autonomous vehicles;Path planning;Global Positioning System;Cameras;miniature autonomous vehicle;path planning;navigation;parking assist;lane detection and tracking;traffic sign recognition}, -URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8516589&isnumber=8516425 +URL: https://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8516589&isnumber=8516425 2. Peggy (Yuchun) Wang and Caitlin Hogan, "Path Planning with Dynamic Obstacle Avoidance for a Jumping-Enabled Robot", AA228/CS238 class report, Department of Computer Science, Stanford University, URL: https://web.stanford.edu/class/aa228/reports/2018/final113.pdf -3. Welburn, E, Hakim Khalili, H, Gupta, A, Watson, S & Carrasco, J 2019, A Navigational System for Quadcopter Remote Inspection of Offshore Substations. in The Fifteenth International Conference on Autonomic and Autonomous Systems 2019. URL:https://www.research.manchester.ac.uk/portal/files/107169964/ICAS19_A_Navigational_System_for_Quadcopter_Remote_Inspection_of_Offshore_Substations.pdf +3. Welburn, E, Hakim Khalili, H, Gupta, A, Watson, S & Carrasco, J 2019, A Navigational System for Quadcopter Remote Inspection of Offshore Substations. in The Fifteenth International Conference on Autonomic and Autonomous Systems 2019. URL:https://research.manchester.ac.uk/portal/files/107169964/ICAS19_A_Navigational_System_for_Quadcopter_Remote_Inspection_of_Offshore_Substations.pdf 4. E. Horváth, C. Hajdu, C. Radu and Á. Ballagi, "Range Sensor-based Occupancy Grid Mapping with Signatures," 2019 20th International Carpathian Control Conference (ICCC), Krakow-Wieliczka, Poland, 2019, pp. 1-5. -URL: http://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8765684&isnumber=8765679 +URL: https://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=8765684&isnumber=8765679 5. Josie Hughes, Masaru Shimizu, and Arnoud Visser, "A Review of Robot Rescue Simulation Platforms for Robotics Education" URL: https://2019.robocup.org/downloads/program/HughesEtAl2019.pdf @@ -408,7 +402,7 @@ URL: https://arxiv.org/abs/1910.01557 URL: https://pdfs.semanticscholar.org/5c06/f3cb9542a51e1bf1a32523c1bc7fea6cecc5.pdf 9. Brijen Thananjeyan, et al. "ABC-LMPC: Safe Sample-Based Learning MPC for Stochastic Nonlinear Dynamical Systems with Adjustable Boundary Conditions" -URL: https://arxiv.org/pdf/2003.01410.pdf +URL: https://arxiv.org/pdf/2003.01410 # Others From 732db3d40d1dbdcfe60a3a5a02948d306c6a4c88 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 25 Jan 2025 21:06:23 +0900 Subject: [PATCH 827/940] Fix Doc generation warning (#1125) --- docs/getting_started_main.rst | 2 +- .../catmull_rom_spline/catmull_rom_spline_main.rst | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index 004d68227b..256319ab8f 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -40,7 +40,7 @@ For development: - `sphinx`_ (for document generation) - `ruff`_ (for code style check) -.. _`Python 3.11.x`: https://www.python.org/ +.. _`Python 3.12.x`: https://www.python.org/ .. _`NumPy`: https://numpy.org/ .. _`SciPy`: https://scipy.org/ .. _`Matplotlib`: https://matplotlib.org/ diff --git a/docs/modules/path_planning/catmull_rom_spline/catmull_rom_spline_main.rst b/docs/modules/path_planning/catmull_rom_spline/catmull_rom_spline_main.rst index 4d8d3bdefe..72e558c486 100644 --- a/docs/modules/path_planning/catmull_rom_spline/catmull_rom_spline_main.rst +++ b/docs/modules/path_planning/catmull_rom_spline/catmull_rom_spline_main.rst @@ -1,5 +1,5 @@ Catmull-Rom Spline Planning ------------------ +---------------------------- .. image:: catmull_rom_path_planning.png @@ -10,7 +10,7 @@ exhibits local control, and maintains 𝐶1 continuity. Catmull-Rom Spline Fundamentals -~~~~~~~~~~~~~~ +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Catmull-Rom splines are a type of cubic spline that passes through a given set of points, known as control points. @@ -24,7 +24,7 @@ Where: * :math:`P_0, P_1, P_2, P_3` are the control points surrounding the parameter :math:`t`. Types of Catmull-Rom Splines -~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ There are different types of Catmull-Rom splines based on the choice of the **tau** parameter, which influences how the curve behaves in relation to the control points: @@ -51,7 +51,7 @@ behaves in relation to the control points: Blending Functions -~~~~~~~~~~~~~~~~~~ +~~~~~~~~~~~~~~~~~~~~~ In Catmull-Rom spline interpolation, blending functions are used to calculate the influence of each control point on the spline at a given parameter :math:`t`. The blending functions ensure that the spline is smooth and passes through the control points while @@ -97,7 +97,7 @@ API References -~~~~~~~~~~ +~~~~~~~~~~~~~~ - `Catmull-Rom Spline - Wikipedia `__ - `Catmull-Rom Splines `__ \ No newline at end of file From bf8f1774b753d3b0915960628386bb220de8f0af Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 25 Jan 2025 23:30:14 +0900 Subject: [PATCH 828/940] Update doc organization (#1126) --- docs/conf.py | 2 +- docs/index_main.rst | 24 +++++----- .../{control => 10_control}/control_main.rst | 0 .../inverted-pendulum.png | Bin .../inverted_pendulum_control_main.rst | 0 .../move_to_a_pose_control_main.rst | 0 .../plot/curvature_plot.png | Bin .../{utils => 11_utils}/plot/plot_main.rst | 0 .../{utils => 11_utils}/utils_main.rst | 0 .../Kalmanfilter_basics_2_5_0.png | Bin .../Kalmanfilter_basics_2_main.rst | 0 .../Kalmanfilter_basics_14_1.png | Bin .../Kalmanfilter_basics_16_0.png | Bin .../Kalmanfilter_basics_19_1.png | Bin .../Kalmanfilter_basics_21_1.png | Bin .../Kalmanfilter_basics_22_0.png | Bin .../Kalmanfilter_basics_28_1.png | Bin .../Kalmanfilter_basics_main.rst | 0 .../appendix_main.rst | 0 .../steering_motion_model/steering_model.png | Bin .../turning_radius_calc1.png | Bin .../turning_radius_calc2.png | Bin .../steering_motion_model_main.rst | 0 .../definition_of_robotics_main.rst | 4 ++ .../software_for_robotics_main.rst | 7 +++ .../technology_for_robotics_main.rst | 4 ++ .../1_introduction/introduction_main.rst | 13 ++++++ ...samble_kalman_filter_localization_main.rst | 0 .../ekf_with_velocity_correction_1_0.png | Bin ...xtended_kalman_filter_localization_1_0.png | Bin ...tended_kalman_filter_localization_main.rst | 0 .../histogram_filter_localization/1.png | Bin .../histogram_filter_localization/2.png | Bin .../histogram_filter_localization/3.png | Bin .../histogram_filter_localization/4.png | Bin .../histogram_filter_localization_main.rst | 0 .../localization_main.rst | 0 .../particle_filter_localization_main.rst | 0 ...cented_kalman_filter_localization_main.rst | 0 .../circle_fitting/circle_fitting_main.rst | 0 .../gaussian_grid_map_main.rst | 0 .../k_means_object_clustering_main.rst | 0 .../grid_map_example.png | Bin .../lidar_to_grid_map_tutorial_12_0.png | Bin .../lidar_to_grid_map_tutorial_14_1.png | Bin .../lidar_to_grid_map_tutorial_5_0.png | Bin .../lidar_to_grid_map_tutorial_7_0.png | Bin .../lidar_to_grid_map_tutorial_8_0.png | Bin .../lidar_to_grid_map_tutorial_main.rst | 0 .../{mapping => 3_mapping}/mapping_main.rst | 0 .../ndt_map/grid_clustering.png | Bin .../ndt_map/ndt_map1.png | Bin .../ndt_map/ndt_map2.png | Bin .../ndt_map/ndt_map_main.rst | 0 .../ndt_map/raw_observations.png | Bin .../normal_vector_calc.png | Bin .../normal_vector_estimation_main.rst | 0 .../ransac_normal_vector_estimation.png | Bin .../farthest_point_sampling.png | Bin .../point_cloud_sampling_main.rst | 0 .../poisson_disk_sampling.png | Bin .../voxel_point_sampling.png | Bin .../ray_casting_grid_map_main.rst | 0 .../rectangle_fitting_main.rst | 0 .../FastSLAM1/FastSLAM1_12_0.png | Bin .../FastSLAM1/FastSLAM1_12_1.png | Bin .../FastSLAM1/FastSLAM1_1_0.png | Bin .../FastSLAM1/FastSLAM1_main.rst | 0 .../FastSLAM2/FastSLAM2_main.rst | 0 .../ekf_slam/ekf_slam_1_0.png | Bin .../ekf_slam/ekf_slam_main.rst | 0 .../graph_slam/graphSLAM_SE2_example.rst | 0 .../graphSLAM_SE2_example_13_0.png | Bin .../graphSLAM_SE2_example_15_0.png | Bin .../graphSLAM_SE2_example_16_0.png | Bin .../graphSLAM_SE2_example_4_0.png | Bin .../graphSLAM_SE2_example_8_0.png | Bin .../graphSLAM_SE2_example_9_0.png | Bin .../graph_slam/graphSLAM_doc.rst | 0 .../graphSLAM_doc_11_1.png | Bin .../graphSLAM_doc_11_2.png | Bin .../graphSLAM_doc_files/graphSLAM_doc_2_0.png | Bin .../graphSLAM_doc_files/graphSLAM_doc_2_2.png | Bin .../graphSLAM_doc_files/graphSLAM_doc_4_0.png | Bin .../graphSLAM_doc_files/graphSLAM_doc_9_1.png | Bin .../graph_slam/graphSLAM_formulation.rst | 0 .../graph_slam/graph_slam_main.rst | 0 .../iterative_closest_point_matching_main.rst | 0 docs/modules/{slam => 4_slam}/slam_main.rst | 0 .../bezier_path/Figure_1.png | Bin .../bezier_path/Figure_2.png | Bin .../bezier_path/bezier_path_main.rst | 0 .../bspline_path/approx_and_curvature.png | Bin .../bspline_path/approximation1.png | Bin .../bspline_path/basis_functions.png | Bin .../bspline_path/bspline_path_main.rst | 0 .../bspline_path/bspline_path_planning.png | Bin .../bspline_path/interp_and_curvature.png | Bin .../bspline_path/interpolation1.png | Bin .../bugplanner/bugplanner_main.rst | 0 .../catmull_rom_spline/blending_functions.png | Bin .../catmull_rom_path_planning.png | Bin .../catmull_rom_spline_main.rst | 0 .../closed_loop_rrt_star_car/Figure_1.png | Bin .../closed_loop_rrt_star_car/Figure_3.png | Bin .../closed_loop_rrt_star_car/Figure_4.png | Bin .../closed_loop_rrt_star_car/Figure_5.png | Bin .../clothoid_path/clothoid_path_main.rst | 0 .../coverage_path/coverage_path_main.rst | 0 .../cubic_spline/cubic_spline_1d.png | Bin .../cubic_spline_2d_curvature.png | Bin .../cubic_spline/cubic_spline_2d_path.png | Bin .../cubic_spline/cubic_spline_2d_yaw.png | Bin .../cubic_spline/cubic_spline_main.rst | 0 .../cubic_spline/spline.png | Bin .../cubic_spline/spline_continuity.png | Bin .../dubins_path/RLR.jpg | Bin .../dubins_path/RSR.jpg | Bin .../dubins_path/dubins_path.jpg | Bin .../dubins_path/dubins_path_main.rst | 0 .../dynamic_window_approach_main.rst | 0 .../eta3_spline/eta3_spline_main.rst | 0 .../frenet_frame_path_main.rst | 0 .../grid_base_search_main.rst | 0 .../hybridastar/hybridastar_main.rst | 0 .../lqr_path/lqr_path_main.rst | 0 .../lookup_table.png | Bin ...l_predictive_trajectory_generator_main.rst | 0 .../path_planning_main.rst | 0 .../prm_planner/prm_planner_main.rst | 0 .../quintic_polynomials_planner_main.rst | 0 .../reeds_shepp_path/LR_L.png | Bin .../reeds_shepp_path/LR_LR.png | Bin .../reeds_shepp_path/LSL.png | Bin .../reeds_shepp_path/LSL90xR.png | Bin .../reeds_shepp_path/LSR.png | Bin .../reeds_shepp_path/LSR90_L.png | Bin .../reeds_shepp_path/L_R90SL.png | Bin .../reeds_shepp_path/L_R90SL90_R.png | Bin .../reeds_shepp_path/L_R90SR.png | Bin .../reeds_shepp_path/L_RL.png | Bin .../reeds_shepp_path/L_RL_R.png | Bin .../reeds_shepp_path/L_R_L.png | Bin .../reeds_shepp_path_main.rst | 0 .../rrt/figure_1.png | Bin .../rrt/rrt_main.rst | 0 .../rrt/rrt_star.rst | 0 .../rrt/rrt_star/rrt_star_1_0.png | Bin .../rrt/rrt_star_reeds_shepp/figure_1.png | Bin .../state_lattice_planner/Figure_1.png | Bin .../state_lattice_planner/Figure_2.png | Bin .../state_lattice_planner/Figure_3.png | Bin .../state_lattice_planner/Figure_4.png | Bin .../state_lattice_planner/Figure_5.png | Bin .../state_lattice_planner/Figure_6.png | Bin .../state_lattice_planner_main.rst | 0 .../visibility_road_map_planner/step0.png | Bin .../visibility_road_map_planner/step1.png | Bin .../visibility_road_map_planner/step2.png | Bin .../visibility_road_map_planner/step3.png | Bin .../visibility_road_map_planner_main.rst | 0 .../vrm_planner/vrm_planner_main.rst | 0 .../cgmres_nmpc/cgmres_nmpc_1_0.png | Bin .../cgmres_nmpc/cgmres_nmpc_2_0.png | Bin .../cgmres_nmpc/cgmres_nmpc_3_0.png | Bin .../cgmres_nmpc/cgmres_nmpc_4_0.png | Bin .../cgmres_nmpc/cgmres_nmpc_main.rst | 0 .../lqr_speed_and_steering_control_main.rst | 0 .../lqr_steering_control_model.jpg | Bin .../lqr_speed_and_steering_control/speed.png | Bin .../lqr_speed_and_steering_control/x-y.png | Bin .../lqr_speed_and_steering_control/yaw.png | Bin .../lqr_steering_control_main.rst | 0 .../lqr_steering_control_model.jpg | Bin ...ictive_speed_and_steering_control_main.rst | 0 .../path_tracking_main.rst | 0 .../pure_pursuit_tracking_main.rst | 0 .../rear_wheel_feedback_control_main.rst | 0 .../stanley_control/stanley_control_main.rst | 0 .../Planar_Two_Link_IK_12_0.png | Bin .../Planar_Two_Link_IK_5_0.png | Bin .../Planar_Two_Link_IK_7_0.png | Bin .../Planar_Two_Link_IK_9_0.png | Bin .../arm_navigation_main.rst | 0 .../n_joint_arm_to_point_control_main.rst | 0 ...obstacle_avoidance_arm_navigation_main.rst | 0 .../planar_two_link_ik_main.rst | 0 .../aerial_navigation_main.rst | 0 .../drone_3d_trajectory_following_main.rst | 0 .../rocket_powered_landing_main.rst | 0 .../{bipedal => 9_bipedal}/bipedal_main.rst | 0 .../bipedal_planner/bipedal_planner_main.rst | 0 docs/modules/introduction_main.rst | 42 ------------------ .../Graph_SLAM_optimization.gif | Bin 114966 -> 0 bytes 194 files changed, 41 insertions(+), 55 deletions(-) rename docs/modules/{control => 10_control}/control_main.rst (100%) rename docs/modules/{control => 10_control}/inverted_pendulum_control/inverted-pendulum.png (100%) rename docs/modules/{control => 10_control}/inverted_pendulum_control/inverted_pendulum_control_main.rst (100%) rename docs/modules/{control => 10_control}/move_to_a_pose_control/move_to_a_pose_control_main.rst (100%) rename docs/modules/{utils => 11_utils}/plot/curvature_plot.png (100%) rename docs/modules/{utils => 11_utils}/plot/plot_main.rst (100%) rename docs/modules/{utils => 11_utils}/utils_main.rst (100%) rename docs/modules/{appendix => 12_appendix}/Kalmanfilter_basics_2_files/Kalmanfilter_basics_2_5_0.png (100%) rename docs/modules/{appendix => 12_appendix}/Kalmanfilter_basics_2_main.rst (100%) rename docs/modules/{appendix => 12_appendix}/Kalmanfilter_basics_files/Kalmanfilter_basics_14_1.png (100%) rename docs/modules/{appendix => 12_appendix}/Kalmanfilter_basics_files/Kalmanfilter_basics_16_0.png (100%) rename docs/modules/{appendix => 12_appendix}/Kalmanfilter_basics_files/Kalmanfilter_basics_19_1.png (100%) rename docs/modules/{appendix => 12_appendix}/Kalmanfilter_basics_files/Kalmanfilter_basics_21_1.png (100%) rename docs/modules/{appendix => 12_appendix}/Kalmanfilter_basics_files/Kalmanfilter_basics_22_0.png (100%) rename docs/modules/{appendix => 12_appendix}/Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png (100%) rename docs/modules/{appendix => 12_appendix}/Kalmanfilter_basics_main.rst (100%) rename docs/modules/{appendix => 12_appendix}/appendix_main.rst (100%) rename docs/modules/{appendix => 12_appendix}/steering_motion_model/steering_model.png (100%) rename docs/modules/{appendix => 12_appendix}/steering_motion_model/turning_radius_calc1.png (100%) rename docs/modules/{appendix => 12_appendix}/steering_motion_model/turning_radius_calc2.png (100%) rename docs/modules/{appendix => 12_appendix}/steering_motion_model_main.rst (100%) create mode 100644 docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst create mode 100644 docs/modules/1_introduction/2_software_for_robotics/software_for_robotics_main.rst create mode 100644 docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst create mode 100644 docs/modules/1_introduction/introduction_main.rst rename docs/modules/{localization => 2_localization}/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst (100%) rename docs/modules/{localization => 2_localization}/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png (100%) rename docs/modules/{localization => 2_localization}/extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png (100%) rename docs/modules/{localization => 2_localization}/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst (100%) rename docs/modules/{localization => 2_localization}/histogram_filter_localization/1.png (100%) rename docs/modules/{localization => 2_localization}/histogram_filter_localization/2.png (100%) rename docs/modules/{localization => 2_localization}/histogram_filter_localization/3.png (100%) rename docs/modules/{localization => 2_localization}/histogram_filter_localization/4.png (100%) rename docs/modules/{localization => 2_localization}/histogram_filter_localization/histogram_filter_localization_main.rst (100%) rename docs/modules/{localization => 2_localization}/localization_main.rst (100%) rename docs/modules/{localization => 2_localization}/particle_filter_localization/particle_filter_localization_main.rst (100%) rename docs/modules/{localization => 2_localization}/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst (100%) rename docs/modules/{mapping => 3_mapping}/circle_fitting/circle_fitting_main.rst (100%) rename docs/modules/{mapping => 3_mapping}/gaussian_grid_map/gaussian_grid_map_main.rst (100%) rename docs/modules/{mapping => 3_mapping}/k_means_object_clustering/k_means_object_clustering_main.rst (100%) rename docs/modules/{mapping => 3_mapping}/lidar_to_grid_map_tutorial/grid_map_example.png (100%) rename docs/modules/{mapping => 3_mapping}/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png (100%) rename docs/modules/{mapping => 3_mapping}/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png (100%) rename docs/modules/{mapping => 3_mapping}/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png (100%) rename docs/modules/{mapping => 3_mapping}/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png (100%) rename docs/modules/{mapping => 3_mapping}/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png (100%) rename docs/modules/{mapping => 3_mapping}/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst (100%) rename docs/modules/{mapping => 3_mapping}/mapping_main.rst (100%) rename docs/modules/{mapping => 3_mapping}/ndt_map/grid_clustering.png (100%) rename docs/modules/{mapping => 3_mapping}/ndt_map/ndt_map1.png (100%) rename docs/modules/{mapping => 3_mapping}/ndt_map/ndt_map2.png (100%) rename docs/modules/{mapping => 3_mapping}/ndt_map/ndt_map_main.rst (100%) rename docs/modules/{mapping => 3_mapping}/ndt_map/raw_observations.png (100%) rename docs/modules/{mapping => 3_mapping}/normal_vector_estimation/normal_vector_calc.png (100%) rename docs/modules/{mapping => 3_mapping}/normal_vector_estimation/normal_vector_estimation_main.rst (100%) rename docs/modules/{mapping => 3_mapping}/normal_vector_estimation/ransac_normal_vector_estimation.png (100%) rename docs/modules/{mapping => 3_mapping}/point_cloud_sampling/farthest_point_sampling.png (100%) rename docs/modules/{mapping => 3_mapping}/point_cloud_sampling/point_cloud_sampling_main.rst (100%) rename docs/modules/{mapping => 3_mapping}/point_cloud_sampling/poisson_disk_sampling.png (100%) rename docs/modules/{mapping => 3_mapping}/point_cloud_sampling/voxel_point_sampling.png (100%) rename docs/modules/{mapping => 3_mapping}/ray_casting_grid_map/ray_casting_grid_map_main.rst (100%) rename docs/modules/{mapping => 3_mapping}/rectangle_fitting/rectangle_fitting_main.rst (100%) rename docs/modules/{slam => 4_slam}/FastSLAM1/FastSLAM1_12_0.png (100%) rename docs/modules/{slam => 4_slam}/FastSLAM1/FastSLAM1_12_1.png (100%) rename docs/modules/{slam => 4_slam}/FastSLAM1/FastSLAM1_1_0.png (100%) rename docs/modules/{slam => 4_slam}/FastSLAM1/FastSLAM1_main.rst (100%) rename docs/modules/{slam => 4_slam}/FastSLAM2/FastSLAM2_main.rst (100%) rename docs/modules/{slam => 4_slam}/ekf_slam/ekf_slam_1_0.png (100%) rename docs/modules/{slam => 4_slam}/ekf_slam/ekf_slam_main.rst (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_SE2_example.rst (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_doc.rst (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graphSLAM_formulation.rst (100%) rename docs/modules/{slam => 4_slam}/graph_slam/graph_slam_main.rst (100%) rename docs/modules/{slam => 4_slam}/iterative_closest_point_matching/iterative_closest_point_matching_main.rst (100%) rename docs/modules/{slam => 4_slam}/slam_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/bezier_path/Figure_1.png (100%) rename docs/modules/{path_planning => 5_path_planning}/bezier_path/Figure_2.png (100%) rename docs/modules/{path_planning => 5_path_planning}/bezier_path/bezier_path_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/bspline_path/approx_and_curvature.png (100%) rename docs/modules/{path_planning => 5_path_planning}/bspline_path/approximation1.png (100%) rename docs/modules/{path_planning => 5_path_planning}/bspline_path/basis_functions.png (100%) rename docs/modules/{path_planning => 5_path_planning}/bspline_path/bspline_path_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/bspline_path/bspline_path_planning.png (100%) rename docs/modules/{path_planning => 5_path_planning}/bspline_path/interp_and_curvature.png (100%) rename docs/modules/{path_planning => 5_path_planning}/bspline_path/interpolation1.png (100%) rename docs/modules/{path_planning => 5_path_planning}/bugplanner/bugplanner_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/catmull_rom_spline/blending_functions.png (100%) rename docs/modules/{path_planning => 5_path_planning}/catmull_rom_spline/catmull_rom_path_planning.png (100%) rename docs/modules/{path_planning => 5_path_planning}/catmull_rom_spline/catmull_rom_spline_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/closed_loop_rrt_star_car/Figure_1.png (100%) rename docs/modules/{path_planning => 5_path_planning}/closed_loop_rrt_star_car/Figure_3.png (100%) rename docs/modules/{path_planning => 5_path_planning}/closed_loop_rrt_star_car/Figure_4.png (100%) rename docs/modules/{path_planning => 5_path_planning}/closed_loop_rrt_star_car/Figure_5.png (100%) rename docs/modules/{path_planning => 5_path_planning}/clothoid_path/clothoid_path_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/coverage_path/coverage_path_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/cubic_spline/cubic_spline_1d.png (100%) rename docs/modules/{path_planning => 5_path_planning}/cubic_spline/cubic_spline_2d_curvature.png (100%) rename docs/modules/{path_planning => 5_path_planning}/cubic_spline/cubic_spline_2d_path.png (100%) rename docs/modules/{path_planning => 5_path_planning}/cubic_spline/cubic_spline_2d_yaw.png (100%) rename docs/modules/{path_planning => 5_path_planning}/cubic_spline/cubic_spline_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/cubic_spline/spline.png (100%) rename docs/modules/{path_planning => 5_path_planning}/cubic_spline/spline_continuity.png (100%) rename docs/modules/{path_planning => 5_path_planning}/dubins_path/RLR.jpg (100%) rename docs/modules/{path_planning => 5_path_planning}/dubins_path/RSR.jpg (100%) rename docs/modules/{path_planning => 5_path_planning}/dubins_path/dubins_path.jpg (100%) rename docs/modules/{path_planning => 5_path_planning}/dubins_path/dubins_path_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/dynamic_window_approach/dynamic_window_approach_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/eta3_spline/eta3_spline_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/frenet_frame_path/frenet_frame_path_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/grid_base_search/grid_base_search_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/hybridastar/hybridastar_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/lqr_path/lqr_path_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/model_predictive_trajectory_generator/lookup_table.png (100%) rename docs/modules/{path_planning => 5_path_planning}/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/path_planning_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/prm_planner/prm_planner_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/quintic_polynomials_planner/quintic_polynomials_planner_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/LR_L.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/LR_LR.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/LSL.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/LSL90xR.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/LSR.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/LSR90_L.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/L_R90SL.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/L_R90SL90_R.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/L_R90SR.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/L_RL.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/L_RL_R.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/L_R_L.png (100%) rename docs/modules/{path_planning => 5_path_planning}/reeds_shepp_path/reeds_shepp_path_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/rrt/figure_1.png (100%) rename docs/modules/{path_planning => 5_path_planning}/rrt/rrt_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/rrt/rrt_star.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/rrt/rrt_star/rrt_star_1_0.png (100%) rename docs/modules/{path_planning => 5_path_planning}/rrt/rrt_star_reeds_shepp/figure_1.png (100%) rename docs/modules/{path_planning => 5_path_planning}/state_lattice_planner/Figure_1.png (100%) rename docs/modules/{path_planning => 5_path_planning}/state_lattice_planner/Figure_2.png (100%) rename docs/modules/{path_planning => 5_path_planning}/state_lattice_planner/Figure_3.png (100%) rename docs/modules/{path_planning => 5_path_planning}/state_lattice_planner/Figure_4.png (100%) rename docs/modules/{path_planning => 5_path_planning}/state_lattice_planner/Figure_5.png (100%) rename docs/modules/{path_planning => 5_path_planning}/state_lattice_planner/Figure_6.png (100%) rename docs/modules/{path_planning => 5_path_planning}/state_lattice_planner/state_lattice_planner_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/visibility_road_map_planner/step0.png (100%) rename docs/modules/{path_planning => 5_path_planning}/visibility_road_map_planner/step1.png (100%) rename docs/modules/{path_planning => 5_path_planning}/visibility_road_map_planner/step2.png (100%) rename docs/modules/{path_planning => 5_path_planning}/visibility_road_map_planner/step3.png (100%) rename docs/modules/{path_planning => 5_path_planning}/visibility_road_map_planner/visibility_road_map_planner_main.rst (100%) rename docs/modules/{path_planning => 5_path_planning}/vrm_planner/vrm_planner_main.rst (100%) rename docs/modules/{path_tracking => 6_path_tracking}/cgmres_nmpc/cgmres_nmpc_1_0.png (100%) rename docs/modules/{path_tracking => 6_path_tracking}/cgmres_nmpc/cgmres_nmpc_2_0.png (100%) rename docs/modules/{path_tracking => 6_path_tracking}/cgmres_nmpc/cgmres_nmpc_3_0.png (100%) rename docs/modules/{path_tracking => 6_path_tracking}/cgmres_nmpc/cgmres_nmpc_4_0.png (100%) rename docs/modules/{path_tracking => 6_path_tracking}/cgmres_nmpc/cgmres_nmpc_main.rst (100%) rename docs/modules/{path_tracking => 6_path_tracking}/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst (100%) rename docs/modules/{path_tracking => 6_path_tracking}/lqr_speed_and_steering_control/lqr_steering_control_model.jpg (100%) rename docs/modules/{path_tracking => 6_path_tracking}/lqr_speed_and_steering_control/speed.png (100%) rename docs/modules/{path_tracking => 6_path_tracking}/lqr_speed_and_steering_control/x-y.png (100%) rename docs/modules/{path_tracking => 6_path_tracking}/lqr_speed_and_steering_control/yaw.png (100%) rename docs/modules/{path_tracking => 6_path_tracking}/lqr_steering_control/lqr_steering_control_main.rst (100%) rename docs/modules/{path_tracking => 6_path_tracking}/lqr_steering_control/lqr_steering_control_model.jpg (100%) rename docs/modules/{path_tracking => 6_path_tracking}/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst (100%) rename docs/modules/{path_tracking => 6_path_tracking}/path_tracking_main.rst (100%) rename docs/modules/{path_tracking => 6_path_tracking}/pure_pursuit_tracking/pure_pursuit_tracking_main.rst (100%) rename docs/modules/{path_tracking => 6_path_tracking}/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst (100%) rename docs/modules/{path_tracking => 6_path_tracking}/stanley_control/stanley_control_main.rst (100%) rename docs/modules/{arm_navigation => 7_arm_navigation}/Planar_Two_Link_IK_files/Planar_Two_Link_IK_12_0.png (100%) rename docs/modules/{arm_navigation => 7_arm_navigation}/Planar_Two_Link_IK_files/Planar_Two_Link_IK_5_0.png (100%) rename docs/modules/{arm_navigation => 7_arm_navigation}/Planar_Two_Link_IK_files/Planar_Two_Link_IK_7_0.png (100%) rename docs/modules/{arm_navigation => 7_arm_navigation}/Planar_Two_Link_IK_files/Planar_Two_Link_IK_9_0.png (100%) rename docs/modules/{arm_navigation => 7_arm_navigation}/arm_navigation_main.rst (100%) rename docs/modules/{arm_navigation => 7_arm_navigation}/n_joint_arm_to_point_control_main.rst (100%) rename docs/modules/{arm_navigation => 7_arm_navigation}/obstacle_avoidance_arm_navigation_main.rst (100%) rename docs/modules/{arm_navigation => 7_arm_navigation}/planar_two_link_ik_main.rst (100%) rename docs/modules/{aerial_navigation => 8_aerial_navigation}/aerial_navigation_main.rst (100%) rename docs/modules/{aerial_navigation => 8_aerial_navigation}/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst (100%) rename docs/modules/{aerial_navigation => 8_aerial_navigation}/rocket_powered_landing/rocket_powered_landing_main.rst (100%) rename docs/modules/{bipedal => 9_bipedal}/bipedal_main.rst (100%) rename docs/modules/{bipedal => 9_bipedal}/bipedal_planner/bipedal_planner_main.rst (100%) delete mode 100644 docs/modules/introduction_main.rst delete mode 100644 docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif diff --git a/docs/conf.py b/docs/conf.py index 4e06f3f988..919fa9ac76 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -19,7 +19,7 @@ # -- Project information ----------------------------------------------------- project = 'PythonRobotics' -copyright = '2018-2023, Atsushi Sakai' +copyright = '2018-now, Atsushi Sakai' author = 'Atsushi Sakai' # The short X.Y version diff --git a/docs/index_main.rst b/docs/index_main.rst index 67bd9889f2..08c318ea83 100644 --- a/docs/index_main.rst +++ b/docs/index_main.rst @@ -34,18 +34,18 @@ See this paper for more details: :caption: Contents getting_started - modules/introduction - modules/localization/localization - modules/mapping/mapping - modules/slam/slam - modules/path_planning/path_planning - modules/path_tracking/path_tracking - modules/arm_navigation/arm_navigation - modules/aerial_navigation/aerial_navigation - modules/bipedal/bipedal - modules/control/control - modules/utils/utils - modules/appendix/appendix + modules/1_introduction/introduction + modules/2_localization/localization + modules/3_mapping/mapping + modules/4_slam/slam + modules/5_path_planning/path_planning + modules/6_path_tracking/path_tracking + modules/7_arm_navigation/arm_navigation + modules/8_aerial_navigation/aerial_navigation + modules/9_bipedal/bipedal + modules/10_control/control + modules/11_utils/utils + modules/12_appendix/appendix how_to_contribute diff --git a/docs/modules/control/control_main.rst b/docs/modules/10_control/control_main.rst similarity index 100% rename from docs/modules/control/control_main.rst rename to docs/modules/10_control/control_main.rst diff --git a/docs/modules/control/inverted_pendulum_control/inverted-pendulum.png b/docs/modules/10_control/inverted_pendulum_control/inverted-pendulum.png similarity index 100% rename from docs/modules/control/inverted_pendulum_control/inverted-pendulum.png rename to docs/modules/10_control/inverted_pendulum_control/inverted-pendulum.png diff --git a/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control_main.rst b/docs/modules/10_control/inverted_pendulum_control/inverted_pendulum_control_main.rst similarity index 100% rename from docs/modules/control/inverted_pendulum_control/inverted_pendulum_control_main.rst rename to docs/modules/10_control/inverted_pendulum_control/inverted_pendulum_control_main.rst diff --git a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control_main.rst b/docs/modules/10_control/move_to_a_pose_control/move_to_a_pose_control_main.rst similarity index 100% rename from docs/modules/control/move_to_a_pose_control/move_to_a_pose_control_main.rst rename to docs/modules/10_control/move_to_a_pose_control/move_to_a_pose_control_main.rst diff --git a/docs/modules/utils/plot/curvature_plot.png b/docs/modules/11_utils/plot/curvature_plot.png similarity index 100% rename from docs/modules/utils/plot/curvature_plot.png rename to docs/modules/11_utils/plot/curvature_plot.png diff --git a/docs/modules/utils/plot/plot_main.rst b/docs/modules/11_utils/plot/plot_main.rst similarity index 100% rename from docs/modules/utils/plot/plot_main.rst rename to docs/modules/11_utils/plot/plot_main.rst diff --git a/docs/modules/utils/utils_main.rst b/docs/modules/11_utils/utils_main.rst similarity index 100% rename from docs/modules/utils/utils_main.rst rename to docs/modules/11_utils/utils_main.rst diff --git a/docs/modules/appendix/Kalmanfilter_basics_2_files/Kalmanfilter_basics_2_5_0.png b/docs/modules/12_appendix/Kalmanfilter_basics_2_files/Kalmanfilter_basics_2_5_0.png similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics_2_files/Kalmanfilter_basics_2_5_0.png rename to docs/modules/12_appendix/Kalmanfilter_basics_2_files/Kalmanfilter_basics_2_5_0.png diff --git a/docs/modules/appendix/Kalmanfilter_basics_2_main.rst b/docs/modules/12_appendix/Kalmanfilter_basics_2_main.rst similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics_2_main.rst rename to docs/modules/12_appendix/Kalmanfilter_basics_2_main.rst diff --git a/docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_14_1.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_14_1.png similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_14_1.png rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_14_1.png diff --git a/docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_16_0.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_16_0.png similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_16_0.png rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_16_0.png diff --git a/docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_19_1.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_19_1.png similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_19_1.png rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_19_1.png diff --git a/docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_21_1.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_21_1.png similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_21_1.png rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_21_1.png diff --git a/docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_22_0.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_22_0.png similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_22_0.png rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_22_0.png diff --git a/docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png b/docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png rename to docs/modules/12_appendix/Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png diff --git a/docs/modules/appendix/Kalmanfilter_basics_main.rst b/docs/modules/12_appendix/Kalmanfilter_basics_main.rst similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics_main.rst rename to docs/modules/12_appendix/Kalmanfilter_basics_main.rst diff --git a/docs/modules/appendix/appendix_main.rst b/docs/modules/12_appendix/appendix_main.rst similarity index 100% rename from docs/modules/appendix/appendix_main.rst rename to docs/modules/12_appendix/appendix_main.rst diff --git a/docs/modules/appendix/steering_motion_model/steering_model.png b/docs/modules/12_appendix/steering_motion_model/steering_model.png similarity index 100% rename from docs/modules/appendix/steering_motion_model/steering_model.png rename to docs/modules/12_appendix/steering_motion_model/steering_model.png diff --git a/docs/modules/appendix/steering_motion_model/turning_radius_calc1.png b/docs/modules/12_appendix/steering_motion_model/turning_radius_calc1.png similarity index 100% rename from docs/modules/appendix/steering_motion_model/turning_radius_calc1.png rename to docs/modules/12_appendix/steering_motion_model/turning_radius_calc1.png diff --git a/docs/modules/appendix/steering_motion_model/turning_radius_calc2.png b/docs/modules/12_appendix/steering_motion_model/turning_radius_calc2.png similarity index 100% rename from docs/modules/appendix/steering_motion_model/turning_radius_calc2.png rename to docs/modules/12_appendix/steering_motion_model/turning_radius_calc2.png diff --git a/docs/modules/appendix/steering_motion_model_main.rst b/docs/modules/12_appendix/steering_motion_model_main.rst similarity index 100% rename from docs/modules/appendix/steering_motion_model_main.rst rename to docs/modules/12_appendix/steering_motion_model_main.rst diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst new file mode 100644 index 0000000000..bdc7dc53e9 --- /dev/null +++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst @@ -0,0 +1,4 @@ +Definition of Robotics +---------------------- + +TBD diff --git a/docs/modules/1_introduction/2_software_for_robotics/software_for_robotics_main.rst b/docs/modules/1_introduction/2_software_for_robotics/software_for_robotics_main.rst new file mode 100644 index 0000000000..835441f85d --- /dev/null +++ b/docs/modules/1_introduction/2_software_for_robotics/software_for_robotics_main.rst @@ -0,0 +1,7 @@ +Software for Robotics +---------------------- + +Python for Robotics +~~~~~~~~~~~~~~~~~~~~~ + +TBD diff --git a/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst b/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst new file mode 100644 index 0000000000..4c60ab8851 --- /dev/null +++ b/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst @@ -0,0 +1,4 @@ +Technology for Robotics +------------------------- + +TBD diff --git a/docs/modules/1_introduction/introduction_main.rst b/docs/modules/1_introduction/introduction_main.rst new file mode 100644 index 0000000000..4561efd349 --- /dev/null +++ b/docs/modules/1_introduction/introduction_main.rst @@ -0,0 +1,13 @@ +.. _introduction: + +Introduction +============ + +.. toctree:: + :maxdepth: 2 + :caption: Table of Contents + + 1_definition_of_robotics/definition_of_robotics + 2_software_for_robotics/software_for_robotics + 3_technology_for_robotics/technology_for_robotics + diff --git a/docs/modules/localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst b/docs/modules/2_localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst similarity index 100% rename from docs/modules/localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst rename to docs/modules/2_localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst diff --git a/docs/modules/localization/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png b/docs/modules/2_localization/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png similarity index 100% rename from docs/modules/localization/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png rename to docs/modules/2_localization/extended_kalman_filter_localization_files/ekf_with_velocity_correction_1_0.png diff --git a/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png b/docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png similarity index 100% rename from docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png rename to docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png diff --git a/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst b/docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst similarity index 100% rename from docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst rename to docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst diff --git a/docs/modules/localization/histogram_filter_localization/1.png b/docs/modules/2_localization/histogram_filter_localization/1.png similarity index 100% rename from docs/modules/localization/histogram_filter_localization/1.png rename to docs/modules/2_localization/histogram_filter_localization/1.png diff --git a/docs/modules/localization/histogram_filter_localization/2.png b/docs/modules/2_localization/histogram_filter_localization/2.png similarity index 100% rename from docs/modules/localization/histogram_filter_localization/2.png rename to docs/modules/2_localization/histogram_filter_localization/2.png diff --git a/docs/modules/localization/histogram_filter_localization/3.png b/docs/modules/2_localization/histogram_filter_localization/3.png similarity index 100% rename from docs/modules/localization/histogram_filter_localization/3.png rename to docs/modules/2_localization/histogram_filter_localization/3.png diff --git a/docs/modules/localization/histogram_filter_localization/4.png b/docs/modules/2_localization/histogram_filter_localization/4.png similarity index 100% rename from docs/modules/localization/histogram_filter_localization/4.png rename to docs/modules/2_localization/histogram_filter_localization/4.png diff --git a/docs/modules/localization/histogram_filter_localization/histogram_filter_localization_main.rst b/docs/modules/2_localization/histogram_filter_localization/histogram_filter_localization_main.rst similarity index 100% rename from docs/modules/localization/histogram_filter_localization/histogram_filter_localization_main.rst rename to docs/modules/2_localization/histogram_filter_localization/histogram_filter_localization_main.rst diff --git a/docs/modules/localization/localization_main.rst b/docs/modules/2_localization/localization_main.rst similarity index 100% rename from docs/modules/localization/localization_main.rst rename to docs/modules/2_localization/localization_main.rst diff --git a/docs/modules/localization/particle_filter_localization/particle_filter_localization_main.rst b/docs/modules/2_localization/particle_filter_localization/particle_filter_localization_main.rst similarity index 100% rename from docs/modules/localization/particle_filter_localization/particle_filter_localization_main.rst rename to docs/modules/2_localization/particle_filter_localization/particle_filter_localization_main.rst diff --git a/docs/modules/localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst b/docs/modules/2_localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst similarity index 100% rename from docs/modules/localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst rename to docs/modules/2_localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst diff --git a/docs/modules/mapping/circle_fitting/circle_fitting_main.rst b/docs/modules/3_mapping/circle_fitting/circle_fitting_main.rst similarity index 100% rename from docs/modules/mapping/circle_fitting/circle_fitting_main.rst rename to docs/modules/3_mapping/circle_fitting/circle_fitting_main.rst diff --git a/docs/modules/mapping/gaussian_grid_map/gaussian_grid_map_main.rst b/docs/modules/3_mapping/gaussian_grid_map/gaussian_grid_map_main.rst similarity index 100% rename from docs/modules/mapping/gaussian_grid_map/gaussian_grid_map_main.rst rename to docs/modules/3_mapping/gaussian_grid_map/gaussian_grid_map_main.rst diff --git a/docs/modules/mapping/k_means_object_clustering/k_means_object_clustering_main.rst b/docs/modules/3_mapping/k_means_object_clustering/k_means_object_clustering_main.rst similarity index 100% rename from docs/modules/mapping/k_means_object_clustering/k_means_object_clustering_main.rst rename to docs/modules/3_mapping/k_means_object_clustering/k_means_object_clustering_main.rst diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial/grid_map_example.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/grid_map_example.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial/grid_map_example.png rename to docs/modules/3_mapping/lidar_to_grid_map_tutorial/grid_map_example.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png rename to docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png rename to docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png rename to docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png rename to docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png rename to docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst similarity index 100% rename from docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst rename to docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst diff --git a/docs/modules/mapping/mapping_main.rst b/docs/modules/3_mapping/mapping_main.rst similarity index 100% rename from docs/modules/mapping/mapping_main.rst rename to docs/modules/3_mapping/mapping_main.rst diff --git a/docs/modules/mapping/ndt_map/grid_clustering.png b/docs/modules/3_mapping/ndt_map/grid_clustering.png similarity index 100% rename from docs/modules/mapping/ndt_map/grid_clustering.png rename to docs/modules/3_mapping/ndt_map/grid_clustering.png diff --git a/docs/modules/mapping/ndt_map/ndt_map1.png b/docs/modules/3_mapping/ndt_map/ndt_map1.png similarity index 100% rename from docs/modules/mapping/ndt_map/ndt_map1.png rename to docs/modules/3_mapping/ndt_map/ndt_map1.png diff --git a/docs/modules/mapping/ndt_map/ndt_map2.png b/docs/modules/3_mapping/ndt_map/ndt_map2.png similarity index 100% rename from docs/modules/mapping/ndt_map/ndt_map2.png rename to docs/modules/3_mapping/ndt_map/ndt_map2.png diff --git a/docs/modules/mapping/ndt_map/ndt_map_main.rst b/docs/modules/3_mapping/ndt_map/ndt_map_main.rst similarity index 100% rename from docs/modules/mapping/ndt_map/ndt_map_main.rst rename to docs/modules/3_mapping/ndt_map/ndt_map_main.rst diff --git a/docs/modules/mapping/ndt_map/raw_observations.png b/docs/modules/3_mapping/ndt_map/raw_observations.png similarity index 100% rename from docs/modules/mapping/ndt_map/raw_observations.png rename to docs/modules/3_mapping/ndt_map/raw_observations.png diff --git a/docs/modules/mapping/normal_vector_estimation/normal_vector_calc.png b/docs/modules/3_mapping/normal_vector_estimation/normal_vector_calc.png similarity index 100% rename from docs/modules/mapping/normal_vector_estimation/normal_vector_calc.png rename to docs/modules/3_mapping/normal_vector_estimation/normal_vector_calc.png diff --git a/docs/modules/mapping/normal_vector_estimation/normal_vector_estimation_main.rst b/docs/modules/3_mapping/normal_vector_estimation/normal_vector_estimation_main.rst similarity index 100% rename from docs/modules/mapping/normal_vector_estimation/normal_vector_estimation_main.rst rename to docs/modules/3_mapping/normal_vector_estimation/normal_vector_estimation_main.rst diff --git a/docs/modules/mapping/normal_vector_estimation/ransac_normal_vector_estimation.png b/docs/modules/3_mapping/normal_vector_estimation/ransac_normal_vector_estimation.png similarity index 100% rename from docs/modules/mapping/normal_vector_estimation/ransac_normal_vector_estimation.png rename to docs/modules/3_mapping/normal_vector_estimation/ransac_normal_vector_estimation.png diff --git a/docs/modules/mapping/point_cloud_sampling/farthest_point_sampling.png b/docs/modules/3_mapping/point_cloud_sampling/farthest_point_sampling.png similarity index 100% rename from docs/modules/mapping/point_cloud_sampling/farthest_point_sampling.png rename to docs/modules/3_mapping/point_cloud_sampling/farthest_point_sampling.png diff --git a/docs/modules/mapping/point_cloud_sampling/point_cloud_sampling_main.rst b/docs/modules/3_mapping/point_cloud_sampling/point_cloud_sampling_main.rst similarity index 100% rename from docs/modules/mapping/point_cloud_sampling/point_cloud_sampling_main.rst rename to docs/modules/3_mapping/point_cloud_sampling/point_cloud_sampling_main.rst diff --git a/docs/modules/mapping/point_cloud_sampling/poisson_disk_sampling.png b/docs/modules/3_mapping/point_cloud_sampling/poisson_disk_sampling.png similarity index 100% rename from docs/modules/mapping/point_cloud_sampling/poisson_disk_sampling.png rename to docs/modules/3_mapping/point_cloud_sampling/poisson_disk_sampling.png diff --git a/docs/modules/mapping/point_cloud_sampling/voxel_point_sampling.png b/docs/modules/3_mapping/point_cloud_sampling/voxel_point_sampling.png similarity index 100% rename from docs/modules/mapping/point_cloud_sampling/voxel_point_sampling.png rename to docs/modules/3_mapping/point_cloud_sampling/voxel_point_sampling.png diff --git a/docs/modules/mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst b/docs/modules/3_mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst similarity index 100% rename from docs/modules/mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst rename to docs/modules/3_mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst diff --git a/docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst b/docs/modules/3_mapping/rectangle_fitting/rectangle_fitting_main.rst similarity index 100% rename from docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst rename to docs/modules/3_mapping/rectangle_fitting/rectangle_fitting_main.rst diff --git a/docs/modules/slam/FastSLAM1/FastSLAM1_12_0.png b/docs/modules/4_slam/FastSLAM1/FastSLAM1_12_0.png similarity index 100% rename from docs/modules/slam/FastSLAM1/FastSLAM1_12_0.png rename to docs/modules/4_slam/FastSLAM1/FastSLAM1_12_0.png diff --git a/docs/modules/slam/FastSLAM1/FastSLAM1_12_1.png b/docs/modules/4_slam/FastSLAM1/FastSLAM1_12_1.png similarity index 100% rename from docs/modules/slam/FastSLAM1/FastSLAM1_12_1.png rename to docs/modules/4_slam/FastSLAM1/FastSLAM1_12_1.png diff --git a/docs/modules/slam/FastSLAM1/FastSLAM1_1_0.png b/docs/modules/4_slam/FastSLAM1/FastSLAM1_1_0.png similarity index 100% rename from docs/modules/slam/FastSLAM1/FastSLAM1_1_0.png rename to docs/modules/4_slam/FastSLAM1/FastSLAM1_1_0.png diff --git a/docs/modules/slam/FastSLAM1/FastSLAM1_main.rst b/docs/modules/4_slam/FastSLAM1/FastSLAM1_main.rst similarity index 100% rename from docs/modules/slam/FastSLAM1/FastSLAM1_main.rst rename to docs/modules/4_slam/FastSLAM1/FastSLAM1_main.rst diff --git a/docs/modules/slam/FastSLAM2/FastSLAM2_main.rst b/docs/modules/4_slam/FastSLAM2/FastSLAM2_main.rst similarity index 100% rename from docs/modules/slam/FastSLAM2/FastSLAM2_main.rst rename to docs/modules/4_slam/FastSLAM2/FastSLAM2_main.rst diff --git a/docs/modules/slam/ekf_slam/ekf_slam_1_0.png b/docs/modules/4_slam/ekf_slam/ekf_slam_1_0.png similarity index 100% rename from docs/modules/slam/ekf_slam/ekf_slam_1_0.png rename to docs/modules/4_slam/ekf_slam/ekf_slam_1_0.png diff --git a/docs/modules/slam/ekf_slam/ekf_slam_main.rst b/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst similarity index 100% rename from docs/modules/slam/ekf_slam/ekf_slam_main.rst rename to docs/modules/4_slam/ekf_slam/ekf_slam_main.rst diff --git a/docs/modules/slam/graph_slam/graphSLAM_SE2_example.rst b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example.rst similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_SE2_example.rst rename to docs/modules/4_slam/graph_slam/graphSLAM_SE2_example.rst diff --git a/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png rename to docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png rename to docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png rename to docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png rename to docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png rename to docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png rename to docs/modules/4_slam/graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc.rst b/docs/modules/4_slam/graph_slam/graphSLAM_doc.rst similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_doc.rst rename to docs/modules/4_slam/graph_slam/graphSLAM_doc.rst diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png rename to docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png rename to docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png rename to docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png rename to docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png rename to docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png b/docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png rename to docs/modules/4_slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_formulation.rst b/docs/modules/4_slam/graph_slam/graphSLAM_formulation.rst similarity index 100% rename from docs/modules/slam/graph_slam/graphSLAM_formulation.rst rename to docs/modules/4_slam/graph_slam/graphSLAM_formulation.rst diff --git a/docs/modules/slam/graph_slam/graph_slam_main.rst b/docs/modules/4_slam/graph_slam/graph_slam_main.rst similarity index 100% rename from docs/modules/slam/graph_slam/graph_slam_main.rst rename to docs/modules/4_slam/graph_slam/graph_slam_main.rst diff --git a/docs/modules/slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst b/docs/modules/4_slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst similarity index 100% rename from docs/modules/slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst rename to docs/modules/4_slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst diff --git a/docs/modules/slam/slam_main.rst b/docs/modules/4_slam/slam_main.rst similarity index 100% rename from docs/modules/slam/slam_main.rst rename to docs/modules/4_slam/slam_main.rst diff --git a/docs/modules/path_planning/bezier_path/Figure_1.png b/docs/modules/5_path_planning/bezier_path/Figure_1.png similarity index 100% rename from docs/modules/path_planning/bezier_path/Figure_1.png rename to docs/modules/5_path_planning/bezier_path/Figure_1.png diff --git a/docs/modules/path_planning/bezier_path/Figure_2.png b/docs/modules/5_path_planning/bezier_path/Figure_2.png similarity index 100% rename from docs/modules/path_planning/bezier_path/Figure_2.png rename to docs/modules/5_path_planning/bezier_path/Figure_2.png diff --git a/docs/modules/path_planning/bezier_path/bezier_path_main.rst b/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst similarity index 100% rename from docs/modules/path_planning/bezier_path/bezier_path_main.rst rename to docs/modules/5_path_planning/bezier_path/bezier_path_main.rst diff --git a/docs/modules/path_planning/bspline_path/approx_and_curvature.png b/docs/modules/5_path_planning/bspline_path/approx_and_curvature.png similarity index 100% rename from docs/modules/path_planning/bspline_path/approx_and_curvature.png rename to docs/modules/5_path_planning/bspline_path/approx_and_curvature.png diff --git a/docs/modules/path_planning/bspline_path/approximation1.png b/docs/modules/5_path_planning/bspline_path/approximation1.png similarity index 100% rename from docs/modules/path_planning/bspline_path/approximation1.png rename to docs/modules/5_path_planning/bspline_path/approximation1.png diff --git a/docs/modules/path_planning/bspline_path/basis_functions.png b/docs/modules/5_path_planning/bspline_path/basis_functions.png similarity index 100% rename from docs/modules/path_planning/bspline_path/basis_functions.png rename to docs/modules/5_path_planning/bspline_path/basis_functions.png diff --git a/docs/modules/path_planning/bspline_path/bspline_path_main.rst b/docs/modules/5_path_planning/bspline_path/bspline_path_main.rst similarity index 100% rename from docs/modules/path_planning/bspline_path/bspline_path_main.rst rename to docs/modules/5_path_planning/bspline_path/bspline_path_main.rst diff --git a/docs/modules/path_planning/bspline_path/bspline_path_planning.png b/docs/modules/5_path_planning/bspline_path/bspline_path_planning.png similarity index 100% rename from docs/modules/path_planning/bspline_path/bspline_path_planning.png rename to docs/modules/5_path_planning/bspline_path/bspline_path_planning.png diff --git a/docs/modules/path_planning/bspline_path/interp_and_curvature.png b/docs/modules/5_path_planning/bspline_path/interp_and_curvature.png similarity index 100% rename from docs/modules/path_planning/bspline_path/interp_and_curvature.png rename to docs/modules/5_path_planning/bspline_path/interp_and_curvature.png diff --git a/docs/modules/path_planning/bspline_path/interpolation1.png b/docs/modules/5_path_planning/bspline_path/interpolation1.png similarity index 100% rename from docs/modules/path_planning/bspline_path/interpolation1.png rename to docs/modules/5_path_planning/bspline_path/interpolation1.png diff --git a/docs/modules/path_planning/bugplanner/bugplanner_main.rst b/docs/modules/5_path_planning/bugplanner/bugplanner_main.rst similarity index 100% rename from docs/modules/path_planning/bugplanner/bugplanner_main.rst rename to docs/modules/5_path_planning/bugplanner/bugplanner_main.rst diff --git a/docs/modules/path_planning/catmull_rom_spline/blending_functions.png b/docs/modules/5_path_planning/catmull_rom_spline/blending_functions.png similarity index 100% rename from docs/modules/path_planning/catmull_rom_spline/blending_functions.png rename to docs/modules/5_path_planning/catmull_rom_spline/blending_functions.png diff --git a/docs/modules/path_planning/catmull_rom_spline/catmull_rom_path_planning.png b/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_path_planning.png similarity index 100% rename from docs/modules/path_planning/catmull_rom_spline/catmull_rom_path_planning.png rename to docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_path_planning.png diff --git a/docs/modules/path_planning/catmull_rom_spline/catmull_rom_spline_main.rst b/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_spline_main.rst similarity index 100% rename from docs/modules/path_planning/catmull_rom_spline/catmull_rom_spline_main.rst rename to docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_spline_main.rst diff --git a/docs/modules/path_planning/closed_loop_rrt_star_car/Figure_1.png b/docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_1.png similarity index 100% rename from docs/modules/path_planning/closed_loop_rrt_star_car/Figure_1.png rename to docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_1.png diff --git a/docs/modules/path_planning/closed_loop_rrt_star_car/Figure_3.png b/docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_3.png similarity index 100% rename from docs/modules/path_planning/closed_loop_rrt_star_car/Figure_3.png rename to docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_3.png diff --git a/docs/modules/path_planning/closed_loop_rrt_star_car/Figure_4.png b/docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_4.png similarity index 100% rename from docs/modules/path_planning/closed_loop_rrt_star_car/Figure_4.png rename to docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_4.png diff --git a/docs/modules/path_planning/closed_loop_rrt_star_car/Figure_5.png b/docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_5.png similarity index 100% rename from docs/modules/path_planning/closed_loop_rrt_star_car/Figure_5.png rename to docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_5.png diff --git a/docs/modules/path_planning/clothoid_path/clothoid_path_main.rst b/docs/modules/5_path_planning/clothoid_path/clothoid_path_main.rst similarity index 100% rename from docs/modules/path_planning/clothoid_path/clothoid_path_main.rst rename to docs/modules/5_path_planning/clothoid_path/clothoid_path_main.rst diff --git a/docs/modules/path_planning/coverage_path/coverage_path_main.rst b/docs/modules/5_path_planning/coverage_path/coverage_path_main.rst similarity index 100% rename from docs/modules/path_planning/coverage_path/coverage_path_main.rst rename to docs/modules/5_path_planning/coverage_path/coverage_path_main.rst diff --git a/docs/modules/path_planning/cubic_spline/cubic_spline_1d.png b/docs/modules/5_path_planning/cubic_spline/cubic_spline_1d.png similarity index 100% rename from docs/modules/path_planning/cubic_spline/cubic_spline_1d.png rename to docs/modules/5_path_planning/cubic_spline/cubic_spline_1d.png diff --git a/docs/modules/path_planning/cubic_spline/cubic_spline_2d_curvature.png b/docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_curvature.png similarity index 100% rename from docs/modules/path_planning/cubic_spline/cubic_spline_2d_curvature.png rename to docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_curvature.png diff --git a/docs/modules/path_planning/cubic_spline/cubic_spline_2d_path.png b/docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_path.png similarity index 100% rename from docs/modules/path_planning/cubic_spline/cubic_spline_2d_path.png rename to docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_path.png diff --git a/docs/modules/path_planning/cubic_spline/cubic_spline_2d_yaw.png b/docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_yaw.png similarity index 100% rename from docs/modules/path_planning/cubic_spline/cubic_spline_2d_yaw.png rename to docs/modules/5_path_planning/cubic_spline/cubic_spline_2d_yaw.png diff --git a/docs/modules/path_planning/cubic_spline/cubic_spline_main.rst b/docs/modules/5_path_planning/cubic_spline/cubic_spline_main.rst similarity index 100% rename from docs/modules/path_planning/cubic_spline/cubic_spline_main.rst rename to docs/modules/5_path_planning/cubic_spline/cubic_spline_main.rst diff --git a/docs/modules/path_planning/cubic_spline/spline.png b/docs/modules/5_path_planning/cubic_spline/spline.png similarity index 100% rename from docs/modules/path_planning/cubic_spline/spline.png rename to docs/modules/5_path_planning/cubic_spline/spline.png diff --git a/docs/modules/path_planning/cubic_spline/spline_continuity.png b/docs/modules/5_path_planning/cubic_spline/spline_continuity.png similarity index 100% rename from docs/modules/path_planning/cubic_spline/spline_continuity.png rename to docs/modules/5_path_planning/cubic_spline/spline_continuity.png diff --git a/docs/modules/path_planning/dubins_path/RLR.jpg b/docs/modules/5_path_planning/dubins_path/RLR.jpg similarity index 100% rename from docs/modules/path_planning/dubins_path/RLR.jpg rename to docs/modules/5_path_planning/dubins_path/RLR.jpg diff --git a/docs/modules/path_planning/dubins_path/RSR.jpg b/docs/modules/5_path_planning/dubins_path/RSR.jpg similarity index 100% rename from docs/modules/path_planning/dubins_path/RSR.jpg rename to docs/modules/5_path_planning/dubins_path/RSR.jpg diff --git a/docs/modules/path_planning/dubins_path/dubins_path.jpg b/docs/modules/5_path_planning/dubins_path/dubins_path.jpg similarity index 100% rename from docs/modules/path_planning/dubins_path/dubins_path.jpg rename to docs/modules/5_path_planning/dubins_path/dubins_path.jpg diff --git a/docs/modules/path_planning/dubins_path/dubins_path_main.rst b/docs/modules/5_path_planning/dubins_path/dubins_path_main.rst similarity index 100% rename from docs/modules/path_planning/dubins_path/dubins_path_main.rst rename to docs/modules/5_path_planning/dubins_path/dubins_path_main.rst diff --git a/docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach_main.rst b/docs/modules/5_path_planning/dynamic_window_approach/dynamic_window_approach_main.rst similarity index 100% rename from docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach_main.rst rename to docs/modules/5_path_planning/dynamic_window_approach/dynamic_window_approach_main.rst diff --git a/docs/modules/path_planning/eta3_spline/eta3_spline_main.rst b/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst similarity index 100% rename from docs/modules/path_planning/eta3_spline/eta3_spline_main.rst rename to docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst diff --git a/docs/modules/path_planning/frenet_frame_path/frenet_frame_path_main.rst b/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst similarity index 100% rename from docs/modules/path_planning/frenet_frame_path/frenet_frame_path_main.rst rename to docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst diff --git a/docs/modules/path_planning/grid_base_search/grid_base_search_main.rst b/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst similarity index 100% rename from docs/modules/path_planning/grid_base_search/grid_base_search_main.rst rename to docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst diff --git a/docs/modules/path_planning/hybridastar/hybridastar_main.rst b/docs/modules/5_path_planning/hybridastar/hybridastar_main.rst similarity index 100% rename from docs/modules/path_planning/hybridastar/hybridastar_main.rst rename to docs/modules/5_path_planning/hybridastar/hybridastar_main.rst diff --git a/docs/modules/path_planning/lqr_path/lqr_path_main.rst b/docs/modules/5_path_planning/lqr_path/lqr_path_main.rst similarity index 100% rename from docs/modules/path_planning/lqr_path/lqr_path_main.rst rename to docs/modules/5_path_planning/lqr_path/lqr_path_main.rst diff --git a/docs/modules/path_planning/model_predictive_trajectory_generator/lookup_table.png b/docs/modules/5_path_planning/model_predictive_trajectory_generator/lookup_table.png similarity index 100% rename from docs/modules/path_planning/model_predictive_trajectory_generator/lookup_table.png rename to docs/modules/5_path_planning/model_predictive_trajectory_generator/lookup_table.png diff --git a/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst b/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst similarity index 100% rename from docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst rename to docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst diff --git a/docs/modules/path_planning/path_planning_main.rst b/docs/modules/5_path_planning/path_planning_main.rst similarity index 100% rename from docs/modules/path_planning/path_planning_main.rst rename to docs/modules/5_path_planning/path_planning_main.rst diff --git a/docs/modules/path_planning/prm_planner/prm_planner_main.rst b/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst similarity index 100% rename from docs/modules/path_planning/prm_planner/prm_planner_main.rst rename to docs/modules/5_path_planning/prm_planner/prm_planner_main.rst diff --git a/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst b/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst similarity index 100% rename from docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst rename to docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst diff --git a/docs/modules/path_planning/reeds_shepp_path/LR_L.png b/docs/modules/5_path_planning/reeds_shepp_path/LR_L.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/LR_L.png rename to docs/modules/5_path_planning/reeds_shepp_path/LR_L.png diff --git a/docs/modules/path_planning/reeds_shepp_path/LR_LR.png b/docs/modules/5_path_planning/reeds_shepp_path/LR_LR.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/LR_LR.png rename to docs/modules/5_path_planning/reeds_shepp_path/LR_LR.png diff --git a/docs/modules/path_planning/reeds_shepp_path/LSL.png b/docs/modules/5_path_planning/reeds_shepp_path/LSL.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/LSL.png rename to docs/modules/5_path_planning/reeds_shepp_path/LSL.png diff --git a/docs/modules/path_planning/reeds_shepp_path/LSL90xR.png b/docs/modules/5_path_planning/reeds_shepp_path/LSL90xR.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/LSL90xR.png rename to docs/modules/5_path_planning/reeds_shepp_path/LSL90xR.png diff --git a/docs/modules/path_planning/reeds_shepp_path/LSR.png b/docs/modules/5_path_planning/reeds_shepp_path/LSR.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/LSR.png rename to docs/modules/5_path_planning/reeds_shepp_path/LSR.png diff --git a/docs/modules/path_planning/reeds_shepp_path/LSR90_L.png b/docs/modules/5_path_planning/reeds_shepp_path/LSR90_L.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/LSR90_L.png rename to docs/modules/5_path_planning/reeds_shepp_path/LSR90_L.png diff --git a/docs/modules/path_planning/reeds_shepp_path/L_R90SL.png b/docs/modules/5_path_planning/reeds_shepp_path/L_R90SL.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/L_R90SL.png rename to docs/modules/5_path_planning/reeds_shepp_path/L_R90SL.png diff --git a/docs/modules/path_planning/reeds_shepp_path/L_R90SL90_R.png b/docs/modules/5_path_planning/reeds_shepp_path/L_R90SL90_R.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/L_R90SL90_R.png rename to docs/modules/5_path_planning/reeds_shepp_path/L_R90SL90_R.png diff --git a/docs/modules/path_planning/reeds_shepp_path/L_R90SR.png b/docs/modules/5_path_planning/reeds_shepp_path/L_R90SR.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/L_R90SR.png rename to docs/modules/5_path_planning/reeds_shepp_path/L_R90SR.png diff --git a/docs/modules/path_planning/reeds_shepp_path/L_RL.png b/docs/modules/5_path_planning/reeds_shepp_path/L_RL.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/L_RL.png rename to docs/modules/5_path_planning/reeds_shepp_path/L_RL.png diff --git a/docs/modules/path_planning/reeds_shepp_path/L_RL_R.png b/docs/modules/5_path_planning/reeds_shepp_path/L_RL_R.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/L_RL_R.png rename to docs/modules/5_path_planning/reeds_shepp_path/L_RL_R.png diff --git a/docs/modules/path_planning/reeds_shepp_path/L_R_L.png b/docs/modules/5_path_planning/reeds_shepp_path/L_R_L.png similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/L_R_L.png rename to docs/modules/5_path_planning/reeds_shepp_path/L_R_L.png diff --git a/docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path_main.rst b/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path_main.rst rename to docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst diff --git a/docs/modules/path_planning/rrt/figure_1.png b/docs/modules/5_path_planning/rrt/figure_1.png similarity index 100% rename from docs/modules/path_planning/rrt/figure_1.png rename to docs/modules/5_path_planning/rrt/figure_1.png diff --git a/docs/modules/path_planning/rrt/rrt_main.rst b/docs/modules/5_path_planning/rrt/rrt_main.rst similarity index 100% rename from docs/modules/path_planning/rrt/rrt_main.rst rename to docs/modules/5_path_planning/rrt/rrt_main.rst diff --git a/docs/modules/path_planning/rrt/rrt_star.rst b/docs/modules/5_path_planning/rrt/rrt_star.rst similarity index 100% rename from docs/modules/path_planning/rrt/rrt_star.rst rename to docs/modules/5_path_planning/rrt/rrt_star.rst diff --git a/docs/modules/path_planning/rrt/rrt_star/rrt_star_1_0.png b/docs/modules/5_path_planning/rrt/rrt_star/rrt_star_1_0.png similarity index 100% rename from docs/modules/path_planning/rrt/rrt_star/rrt_star_1_0.png rename to docs/modules/5_path_planning/rrt/rrt_star/rrt_star_1_0.png diff --git a/docs/modules/path_planning/rrt/rrt_star_reeds_shepp/figure_1.png b/docs/modules/5_path_planning/rrt/rrt_star_reeds_shepp/figure_1.png similarity index 100% rename from docs/modules/path_planning/rrt/rrt_star_reeds_shepp/figure_1.png rename to docs/modules/5_path_planning/rrt/rrt_star_reeds_shepp/figure_1.png diff --git a/docs/modules/path_planning/state_lattice_planner/Figure_1.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_1.png similarity index 100% rename from docs/modules/path_planning/state_lattice_planner/Figure_1.png rename to docs/modules/5_path_planning/state_lattice_planner/Figure_1.png diff --git a/docs/modules/path_planning/state_lattice_planner/Figure_2.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_2.png similarity index 100% rename from docs/modules/path_planning/state_lattice_planner/Figure_2.png rename to docs/modules/5_path_planning/state_lattice_planner/Figure_2.png diff --git a/docs/modules/path_planning/state_lattice_planner/Figure_3.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_3.png similarity index 100% rename from docs/modules/path_planning/state_lattice_planner/Figure_3.png rename to docs/modules/5_path_planning/state_lattice_planner/Figure_3.png diff --git a/docs/modules/path_planning/state_lattice_planner/Figure_4.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_4.png similarity index 100% rename from docs/modules/path_planning/state_lattice_planner/Figure_4.png rename to docs/modules/5_path_planning/state_lattice_planner/Figure_4.png diff --git a/docs/modules/path_planning/state_lattice_planner/Figure_5.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_5.png similarity index 100% rename from docs/modules/path_planning/state_lattice_planner/Figure_5.png rename to docs/modules/5_path_planning/state_lattice_planner/Figure_5.png diff --git a/docs/modules/path_planning/state_lattice_planner/Figure_6.png b/docs/modules/5_path_planning/state_lattice_planner/Figure_6.png similarity index 100% rename from docs/modules/path_planning/state_lattice_planner/Figure_6.png rename to docs/modules/5_path_planning/state_lattice_planner/Figure_6.png diff --git a/docs/modules/path_planning/state_lattice_planner/state_lattice_planner_main.rst b/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst similarity index 100% rename from docs/modules/path_planning/state_lattice_planner/state_lattice_planner_main.rst rename to docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst diff --git a/docs/modules/path_planning/visibility_road_map_planner/step0.png b/docs/modules/5_path_planning/visibility_road_map_planner/step0.png similarity index 100% rename from docs/modules/path_planning/visibility_road_map_planner/step0.png rename to docs/modules/5_path_planning/visibility_road_map_planner/step0.png diff --git a/docs/modules/path_planning/visibility_road_map_planner/step1.png b/docs/modules/5_path_planning/visibility_road_map_planner/step1.png similarity index 100% rename from docs/modules/path_planning/visibility_road_map_planner/step1.png rename to docs/modules/5_path_planning/visibility_road_map_planner/step1.png diff --git a/docs/modules/path_planning/visibility_road_map_planner/step2.png b/docs/modules/5_path_planning/visibility_road_map_planner/step2.png similarity index 100% rename from docs/modules/path_planning/visibility_road_map_planner/step2.png rename to docs/modules/5_path_planning/visibility_road_map_planner/step2.png diff --git a/docs/modules/path_planning/visibility_road_map_planner/step3.png b/docs/modules/5_path_planning/visibility_road_map_planner/step3.png similarity index 100% rename from docs/modules/path_planning/visibility_road_map_planner/step3.png rename to docs/modules/5_path_planning/visibility_road_map_planner/step3.png diff --git a/docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst b/docs/modules/5_path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst similarity index 100% rename from docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst rename to docs/modules/5_path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst diff --git a/docs/modules/path_planning/vrm_planner/vrm_planner_main.rst b/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst similarity index 100% rename from docs/modules/path_planning/vrm_planner/vrm_planner_main.rst rename to docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst diff --git a/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_1_0.png b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_1_0.png similarity index 100% rename from docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_1_0.png rename to docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_1_0.png diff --git a/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_2_0.png b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_2_0.png similarity index 100% rename from docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_2_0.png rename to docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_2_0.png diff --git a/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_3_0.png b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_3_0.png similarity index 100% rename from docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_3_0.png rename to docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_3_0.png diff --git a/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_4_0.png b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_4_0.png similarity index 100% rename from docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_4_0.png rename to docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_4_0.png diff --git a/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst similarity index 100% rename from docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst rename to docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst similarity index 100% rename from docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst rename to docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_steering_control_model.jpg b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_steering_control_model.jpg similarity index 100% rename from docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_steering_control_model.jpg rename to docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_steering_control_model.jpg diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/speed.png b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/speed.png similarity index 100% rename from docs/modules/path_tracking/lqr_speed_and_steering_control/speed.png rename to docs/modules/6_path_tracking/lqr_speed_and_steering_control/speed.png diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/x-y.png b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/x-y.png similarity index 100% rename from docs/modules/path_tracking/lqr_speed_and_steering_control/x-y.png rename to docs/modules/6_path_tracking/lqr_speed_and_steering_control/x-y.png diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/yaw.png b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/yaw.png similarity index 100% rename from docs/modules/path_tracking/lqr_speed_and_steering_control/yaw.png rename to docs/modules/6_path_tracking/lqr_speed_and_steering_control/yaw.png diff --git a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst b/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst similarity index 100% rename from docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst rename to docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst diff --git a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.jpg b/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_model.jpg similarity index 100% rename from docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_model.jpg rename to docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_model.jpg diff --git a/docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst b/docs/modules/6_path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst similarity index 100% rename from docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst rename to docs/modules/6_path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst diff --git a/docs/modules/path_tracking/path_tracking_main.rst b/docs/modules/6_path_tracking/path_tracking_main.rst similarity index 100% rename from docs/modules/path_tracking/path_tracking_main.rst rename to docs/modules/6_path_tracking/path_tracking_main.rst diff --git a/docs/modules/path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst b/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst similarity index 100% rename from docs/modules/path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst rename to docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst diff --git a/docs/modules/path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst b/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst similarity index 100% rename from docs/modules/path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst rename to docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst diff --git a/docs/modules/path_tracking/stanley_control/stanley_control_main.rst b/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst similarity index 100% rename from docs/modules/path_tracking/stanley_control/stanley_control_main.rst rename to docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst diff --git a/docs/modules/arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_12_0.png b/docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_12_0.png similarity index 100% rename from docs/modules/arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_12_0.png rename to docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_12_0.png diff --git a/docs/modules/arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_5_0.png b/docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_5_0.png similarity index 100% rename from docs/modules/arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_5_0.png rename to docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_5_0.png diff --git a/docs/modules/arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_7_0.png b/docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_7_0.png similarity index 100% rename from docs/modules/arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_7_0.png rename to docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_7_0.png diff --git a/docs/modules/arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_9_0.png b/docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_9_0.png similarity index 100% rename from docs/modules/arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_9_0.png rename to docs/modules/7_arm_navigation/Planar_Two_Link_IK_files/Planar_Two_Link_IK_9_0.png diff --git a/docs/modules/arm_navigation/arm_navigation_main.rst b/docs/modules/7_arm_navigation/arm_navigation_main.rst similarity index 100% rename from docs/modules/arm_navigation/arm_navigation_main.rst rename to docs/modules/7_arm_navigation/arm_navigation_main.rst diff --git a/docs/modules/arm_navigation/n_joint_arm_to_point_control_main.rst b/docs/modules/7_arm_navigation/n_joint_arm_to_point_control_main.rst similarity index 100% rename from docs/modules/arm_navigation/n_joint_arm_to_point_control_main.rst rename to docs/modules/7_arm_navigation/n_joint_arm_to_point_control_main.rst diff --git a/docs/modules/arm_navigation/obstacle_avoidance_arm_navigation_main.rst b/docs/modules/7_arm_navigation/obstacle_avoidance_arm_navigation_main.rst similarity index 100% rename from docs/modules/arm_navigation/obstacle_avoidance_arm_navigation_main.rst rename to docs/modules/7_arm_navigation/obstacle_avoidance_arm_navigation_main.rst diff --git a/docs/modules/arm_navigation/planar_two_link_ik_main.rst b/docs/modules/7_arm_navigation/planar_two_link_ik_main.rst similarity index 100% rename from docs/modules/arm_navigation/planar_two_link_ik_main.rst rename to docs/modules/7_arm_navigation/planar_two_link_ik_main.rst diff --git a/docs/modules/aerial_navigation/aerial_navigation_main.rst b/docs/modules/8_aerial_navigation/aerial_navigation_main.rst similarity index 100% rename from docs/modules/aerial_navigation/aerial_navigation_main.rst rename to docs/modules/8_aerial_navigation/aerial_navigation_main.rst diff --git a/docs/modules/aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst b/docs/modules/8_aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst similarity index 100% rename from docs/modules/aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst rename to docs/modules/8_aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst diff --git a/docs/modules/aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst b/docs/modules/8_aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst similarity index 100% rename from docs/modules/aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst rename to docs/modules/8_aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst diff --git a/docs/modules/bipedal/bipedal_main.rst b/docs/modules/9_bipedal/bipedal_main.rst similarity index 100% rename from docs/modules/bipedal/bipedal_main.rst rename to docs/modules/9_bipedal/bipedal_main.rst diff --git a/docs/modules/bipedal/bipedal_planner/bipedal_planner_main.rst b/docs/modules/9_bipedal/bipedal_planner/bipedal_planner_main.rst similarity index 100% rename from docs/modules/bipedal/bipedal_planner/bipedal_planner_main.rst rename to docs/modules/9_bipedal/bipedal_planner/bipedal_planner_main.rst diff --git a/docs/modules/introduction_main.rst b/docs/modules/introduction_main.rst deleted file mode 100644 index f9fb487297..0000000000 --- a/docs/modules/introduction_main.rst +++ /dev/null @@ -1,42 +0,0 @@ - -Introduction -============ - -TBD - -Definition Of Robotics ----------------------- - -TBD - -History Of Robotics ----------------------- - -TBD - -Application Of Robotics ------------------------- - -TBD - -Software for Robotics ----------------------- - -TBD - -Software for Robotics ----------------------- - -TBD - -Python for Robotics ----------------------- - -TBD - -Learning Robotics Algorithms ----------------------------- - -TBD - - diff --git a/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif b/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif deleted file mode 100644 index 2fabeaafc9cd4ad4b71bbf451637bf2560f1be5e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 114966 zcmdp-`#;nF|NnP*ZgxOBI83Nv=FCW<)O(xb80HXiYD6ij5v5XXvyC~_oX?t5A!fU?vKay;lXfsbc#*~tAc-m zKoAH-RaI3(Lu1{#btDqW($aFnh7Hcn&aSSmUS3|2k&%IcfxC9?N=QgZPft%xP3;41 z`w3F{1A=@9A^(LTSCPmCi1s(M#tIIonzzYkNL6_g!@K8sD^U#m#*+Jp7M;;78ApY0rc2g7&V)$Nv`_zjFBSr})E1!J=4D zc>=sVS*<(`U+x4R0)to4=v6#^RabYFL|V19T(!4fb#`8LMGv{4hM4%Fz_ml$^@buz zL$MbB=ZPDJQk;iUorlt0hFn}$natIopw)^A#*4zP`1!wWFis`t|FpBGGDj`LCk#51Hk?8ABNvt2sHVMMbMsRjc*&tF5i8 z9UZHGM-Ai*jTa70Rt-IE7@EH@^s;4W@ygJ*>;LBi0|R4YV^5zxefaR<>d@cj>iGET zg9ocmo~*ul^=ff(@#V|a#l_Wc|7WXz4fOx18T!4P;T60zfl|emZ25K%wR_rFshXz%c>1&g$IkPj~Dv$K#;Y=hECKE@=$22 zc~B}bsoXXSyV2#325=+mbOzpYLJ4P-{Zkgr|h(m zSwR-T5UA+jt4GsavxabVf6r0 zvG37jY&pWa3Z!J-IobGmtOrKv*~s<>gYJ%bsma(pDDTGPktqn@tl*!x8(0C?2#RG< zk6Zv`URKCu<9s8i<-B}1R$U-J1>N7I1b@|Z1(6_IL3&~ptLbMsrZoO~8p_py3yyeN z5Nrjt4;V87am%z$IF1HT#b;7}dV-!BJ4!&!sw6$5s|00<5k!vz%7EsJrb>}|DWEK* zIL$i~Vu0D5RcQclc~E;I!D#znfII|bNvBqcHZFm3xdnn~+8QEtr}-%A9^L$Y@O zoaQ5I!#TXaon3)&tANsUYH-j z#EA{gnbQE`=9V(8_s5i=h;0GXHvUoO&fDwH@3p;Q8bZ?D->J#o-XZ?7P@hYLH$q9tDg+wRS;#fI!X{%hvRNi<1{xQwiL%LPH4^Rotfu+Vw)#CAiF#=3c{HI6yl zCUwHe?pa{+J{Oe!@dW58Iwb@RO&K#|CB$W(EC5IB8z?#O!i-YmakabE|NZqH8l?*z zrv#{wT*@#1+Ah-q>f%)uo8MNsj^WK8-aV~Dfgh`X`u$buVe{wP!;pi2zO#^Q`Hz_+ zpZ@%u&9qrro-aMP@@wJzrImjdyFRV_w{+X4Zy6#Bviz}}k$TGOzc-&&1OMngU4DjM-Uyz|`z`eUW1cNEDQo%J*G0tUF ziIl!QJ1rcUxhF?Af~z9y<^hLI!MG|qaivuPScE!i;JxOtQ%Qooh?oKDTTZ6gtic)+ ziqL{d6xPYyFqxjNHTGCTPv<+h4ZA?@Fh8hsFIVH}vS{NX1>!RmJ%s*sw7a94xDYm@x4sLmz*h*0}=`lfmCyr}FYv?TMvVA&q|H(?icN)VI`VjIpCPz7 zXq<1X#zPzk0BKxY;R;Q|ni zeEu4jnHQvF3X-cXkZRJ*8Rm0idcAg~dE>?~h{1!MCA$jo*SJ(RXy%|Z zpy~;Nu4u$~{BKlX+Z{t(w;!fcz(I$XZ8*(9xWazC^Yjd!)oA3-Z{0WtH;YO-=h9^E znkV-$yQpmPs`iX^QJ{8eO%naSL$&u+j9Rh_A@$R@bl-qf*45D3tE#zc)yHnRl47bo zJy#(3ZdPW%G{0Er2{9x^XOU!=yVl=$t#^Oa&Ho`7<1@Rs_J|qmKrl$-a9X`tvzhN! zUkAgfKUuURrbtn@;WcLWZhg@LiaOAaF2N-34D5dP#=I!=L2*os*^UR5hS7~~G7=6F zeUEO+D{YUY8wwUs%=Bnv;vWb(f|s?iW)8L9jjm%k=hf#+mj&n@uoIU(%}nVwDvq%`)-kr6u*or_t$|YFHQ``3@hsY9<Nh7WXuJO^TKbZg6l$9}QiXS3l3j=Rzf@m?zTNij%grCE`z&^1 z;l?B|swxyg=A(s_VTbOhvO$Z2EwctE!N@e_RpWvsR0JJ&9xFSz#h42(S4;o_z!mF8 z>D_RXezZUiRoh1u%w8-)xC|?5wk*$y9v(M3=6Gn`%kYdu4>{(bbiOl_C3Ff?Xf{e* z%_1zrnaUT$&ZX}jSZ7f%@UyH{b)i6NU|i4K=> z0g2!>*L`*-evu$Nvoeg+%sxgs(D2`OfAzqk7^nL}w1$s_i~u=eI*D8_ZX5#xUl(_1@>^0T<**m~RJ81HzZ)!#ir790v10rE zDyG-`@MkY^e&PAb27JB=vKj>2zVRr)i~IT$V-<=5cez+eclu#qx`)vf5<&8j#AxZh z^XHK=(BbvPryz5vl}nr8-ZDUa8EBKh16;wLRQO5=H*q7nYZm6c1nW=Dl%xbcehqDv z|4rb~6CeccP1drDXhRX+z#Uw-33ksU1{R(4AOzbT%djS<9@0RyYM|ci-t$8Rw#Ea^ zAi}+gNuo4#`xGGKpvQh3$DIeH++CU&SpOvOU>bE%3iwdb|Czw6X1R436}u20FDlF- zHE`xONA1YgR!=X-e1y9Q_N~n8f2>GI^x^e`NrVX$NCZrYVA+GowM17JHbZ~u@>kpz|&7k8A|DYgDN!P`m1T0Nyl(Ukhc+VFDkk_)^8itXC27TLfZp9yf=(;!tN-hl5!%2=oY3E z6~)0Agd{fIKI1)$Z0L5`Ms%&ua^ErlzNsDI#eryGApa6JA30j8){n~Ej_fY?au31$ z?&cG06K_8Pd}OCq95I!WL+?|)TuNf`Y}l8SglL(cy#wYzCh#!UCw4^&_<_oRq?mpo z(r*@~Ws=0loJfBgw`BlYz68^Ko1jm0yTWj|T8=+S39~Uhir@(jreVJvi5uB|n87Mn zdUBx#L9SO%;5mprQr>R%-ku^Dm*UaDVKy!Sx-xex3vj`}o`=RfdYpOt5z+@#YR&~a zEcsK;705b0@p88-O5`pjY}(9i4;y*3%Y}onGKCs`Od7}v#L;=j?;H|Pu;t0UPxVUnd+m6og83u-UQ?Z=eOHa6(t8l(Xj3X9%_8TYJ$FKXW;QhcUOs z(S*{7^{_yu9NPJ72}#Gt-w*dd0#Hr_XqU=P+B&|s96$xGATa#x*G1E z|9)-wP6_9o8JH$xl*@qLSXelGg&`(k63XdLL~on!3kQRmEZ3^7FWmmve zh;sv&C0Fdo}?4bXoK z_z^J)rH5g>Vb1>tRqsbpG2)zSE(ck?O>bbk zB*+@B_(6xu5Icebqsx`B zCO6=4&drNKDlbI4V_Fr~Nj*3voOl(eecy3YE2=pJORDO{U*`^W=62|%J1!r8Gc@L! z*3_hu-{qm$#lDMacb6w(lHIa=D2TJukn^1`2{O6UmcSx;7sYPK#z5s^k;-kYP6#$R z*EDH#3%1iVseB1&J`xj4J+57Os+xUD8jdMvpVB^pe1<#{?hXH_hfN5I>{PBGqnD0F za*^-RFi+5h9+JxbM+cZ3WTmdFiF51bcjHz`7oF!-<|8JcU^rsvT$UGh*9b7OvAu$w z6rfui9TL*_7?|8Maq~@rEhE2t>6jPj{@TwsG%1)Xl<{yhyh4VIVYN!KLfvP}F1>+O zu{w}X9+V~Gf5Feq{Pd5Mj6$$UCmav|9>)x&B_@XTUXee1oNzdDiF1*vU{h~gVT)-q zz~z}3To*9;5B6j#`XUwn%^6<7Me=|9?_?i$y8wT-+sBs(AK4yTtg7T4pR#YS#LZsc zFo@FFBt2XbH#Z5p8GK*WfP3S1Y8eRTCEL>>OM=)Y;!1~H7i6@R-`6Z1;N>?Sugkx0 zvGqhL7a1+f?^A(qbwVx;!1s$%{XL<263F{l8A;fMJMpd^I&J{(VBbcIisrqZu#Xf~v9%r}PZ(@!-qCfs3*M zCg>@14Ef|wLNo?0SjY=R!mHS?%icg8wZMs-I9r)}s$<|i5|8|z?o*#=?VEz7+`RfcR1m)heewK!`hLuPtGwH$q8j3`k9>jGjEtfbM`7UC zF3$UL*_s#cVv>3^WILD`Xuvsd8)^AA%%~ry_senYIw;8B5Cc!vLbSgqi;F#|0kinw zzim39%Ja>g1Fg9BfzlBm^fhWO5xv_ZKGNMm%9BK&U`j`rEZD@{!`y^V_sNuc9t+L2qxOtgkrB51~IsVd`Wf z8#ao&BoWn|&u9Op<@HgDJWQ^|sm9;_mF)KA%=t7C`^XB4l(>*%jj5z6{AQQ%wNEd- z0isx3FC{Dn1SeejOrYI7KY;3Bzw)7=8)fOApP+7(#FbONgU5vOw7M;Nd|NS# zJGg@kFOxm$`w5G?i+%FbozFoVbbVLranV&mG1?PzR%8FxV~^Ni)a1shp!H?#TX&Q2 zn;Zg9H_zV+u9Dvs&x&8FtxPPY*ED$CnZC%53r$R9N%slL=c7RA4h~Ws0qb6m#XQe! z-}ZK=6j?=qU&{QqEDDS8Wc2S&4C5C30HX6xU}zGs{cM8oEC-b2Jxk@o)YiF{vF7L^ zgql4mODZ1_p8?i+8q0V_JXOne=?MRM&x}^GrI%M{kP0fpKBE21K&yg-nY;U7y zJ{4%v3toY5P**0KA)8bTr;`p$Ol0{J|~c zVMh(WJ?OBnk4GAW@%G4PP1_+44vxo_2cW zB7^;C#vz3^6$##AYdfABF=Uvv9Uly<5*FI_E?|d@tI}Q|O`1a2O!XLg){Y>;92sMz zPFIMyI4dh3X(C;MsM_8nzDE+jnlIY$LVwMv1d~4(gcZ~km+YxVuEY%9GfLmjKx#(v zr_K7~`Az8Fuq5%d)Z5h2TbMmh_g}EiqQ5)O)jbBo+g*PYr0O@jwyf1!RsEorpY<<= zC1GN}0%`JE6D7uR+NNWyXrg>XoeiLe)DDYBinTDMF~&x93)e?bCq=`1_E?>-lAyj4 z9vk--E_I?sh123%*A3TRxg~84L7_mkqNLG^ySSI{h0dQ3d~dLC-@3ng`gCqda8a+W zdqvnTL*>gV_O7kykJm%_NM=^=MX!jxgN4416S2d!FPhK-9cLL;WSFiw)A7xCx|^YG zc`oORh~igxvie@r1ra;%)Lt`k)>^0wd+t)W5|U8k%}-o8Fo$npHYRi=Xwl=_#U~;c zkb4b=Erw@->ev@-BWw*>fw6cw@;<)(xI&vUhYX%mJxOX(U?g(DqICe0TAuMio~&yT zBs~^sM=RuqYU|mLs0_ZlKR@4v`A@%De1G4%|5%jn78VS3$6&Nv<3$HI`kmwHy@PKC zu4>L_8Svpq-SS6`)ob=iG8(>0Jq2Az+Z0;vbteN7OOU}jDaj)FJ6A*8kV?Dk<^63{Nn(NB`RXM4Di(p^z6@>s)yjn}Rq?FK$@>Ax0w zq!_qQnxX<7EgVn$EJihg8o6^QH~zEV3#QPX?PuGqkS zp`O~Fp>HlyS=pi#Leem>qc;b#Q9yE`%0yt{Yi~>#C+3Py6odITVf4Y;$uOLRcWip9 z03F>{YCTa$yXdLqVMa?uG-%`Pz}le^bvL|i-_R5gQD?m4^%;Ho;3yZ4*^_{nuI3t8 z(!i+2?%O9zQ)2rcuYW=* z;YYS_BG%ombp3JehQ1%AyiPsBaTZr2v7@BX4qQy(Yb&VmvnkogD&oj~5j9HJqlftK zew~=zqO}#Yu-O5-Yc^zkXl$@ zT=A2$7*doy?@Z8xbw(DBr8b<4(`%oxY`0atm_B7aXhG+xusAXJ3OPU?riduqIdmjf zfxlSj!MmrHu=*cF$G%_OdxVakoO8;pP{Js=2Kbt4p;ei(MCYLp`lDp8Nx_y2YE{RD zvf+Us1?PTvDEe9LYIbA2$-{k{d&)qTY|R5s8)`#yEe?^+Vm2u94b%^{S|Ll8&0Af^ z9NqtOsMke?PdA3hYd$;{Fy#VoBGeWHHI2U%-?HtPIKSuG>B)?Ze`<4nqC4pEr7ssC zwx-Q-mthC}A$Daw<<}gEOH@$R*`t-`A&Z~_2H%^AZAemooUp=gPUG*8HXBIzgCK`< zF=rCRP?z@`+#Yl%c+-C+!StI^wiH@tnD#A~wVLTh*RP!ho)lY)K?Tte8v@j4!6=^# zYh?3Nu3uXR+G?yyCF?bsd?kp!=xNNYHw}dtQosaag*w{d!7Smet&94+qnmTqj@hE8 z%aCU}H8yfx(`i9S)(u;Xby%A4`=JUGiFE``?UX@=Z+x#HUO33%TjCK3BRqQzw+xKj z&C=@76RpQNEiYN;t#$a0yVj`dLRg5wT_mwgZr^wf8>Y+)`KO|vn5B&@wTt*}+dllMQ)4+u#ep=%Bb?-_0BNP+iLpLW1-mhT(2XDx>dds!`r7L#f8#@X&P$6|} z$O+ZFjrQtfQ1*2v?Z1Uc^?i+PC{&L(B-Ko?zQQJa31D*bo-RP_*tH@#@MjAlxXk_+ z-;*3OV0_GOD@T1}og(Bv!j}bILiZKb9E(D|>Q& zh-*P_23P2V$dDyN3NCwONQF;Wd~Ys#tC(9y_mVU*ejyY*-_Py+T@pIAxd6)VU!iPhm;zQuCw?p$P{zZ0{`A;h!qugI>WGQvdf6>Qeg4zZpK(m2EC zo*oi%JfRKb|z-fX6@ee(W=lH(4e;mF(8ijC$E^n3`CCG`)I% zCXdYJ+h8)h9s7dQgn1y|*0?WJQ|v{Gq|aH`!~1Bd`HOEJ)g zSQNS*tt?Zr!2K(mC}qM&rgq8^fklEk`E5a2*sb;*6BLTmtLANm27MIFgU8-Oo4ahSg#2nW{;ulw0m&udU|No3bqn~{KQ&&^Fzjk`DI7N8a`PQJdUnUw*VVPUH40EVS}?7 z!LWROJRlCSUtbJqKyS;UBR1wa=e4c<9ArXlD8t+hKcT91O~4IwZf!vlC;j@oqVLYdPyed0Cj5E+MWRTwuJy!D4VJHi5lful$5P|^$%NO(GWI~wUJ zY*9ZJd+*V%DUd&Eo&P$A{|Grdpg)thRe$*#Y;Krzp)WCGa$2nrJUsL718e1ug~~Dm z_V$IfPPTI3-a9ve68!g0rbaw{R*cCj=lzU6>pXZ19;V&ae_5h-=3~=86$^pUZP#MU z^=;)f%xSMv$u1#W)bAWq({8|z3k#WF_bTCL+cgDR%-X=|Zwd9cn+E}o6Hw8u+w^k}0=R(*Jy(1+dC_rz$W z5Qlp?U47RG5$GoS34=dSF2zGa8|@?P+x z>yl0XpgS}{=B&4*mXk8tFt@aHolXu{To-m^PIc8ZQNac z?VYGS_{Vbg+e&_GnabovhAM>(u{0|y^@g99USqqnZm!I z$y$H@bH{5hsXDb*&AzjyOCPS;E@xP`^IQ{5IQ5r&g1zha{m=4;&5-8*jMIcoEvGN! z&>y`bju}6^+T@~&GgXg)tU*?P5B$5wsV{#hAZ?2cSr9OZ83ilo-OXN%!SG;F*~8ma zr3p{*6gYLS`_O&!I^D$rLqbtA%q&lUd`an^4M0(p(QX|uUl4Q>L=eefXQ#J^Ei~F9 zvgw8>W@tOPmKz}5b6hLXsmNT@N9WpgK~Lr5cO1SA2>RxU)4o(lq)!d-ATCjJu;Dle zV#Z66I{zGR*Cm9l~ww{9b&NK|M{@fz`6-OVi{c8Q+L9Jm3VimR|3{C;D`6 zQG66ormp|h>0OrXS1UXfmP=DBG+yRMJl$?fcz2;n_{l9;Gi;=LLEx*CeNUKGdkZ|J z^^z|^WSfGvjO03AgJJt%XJ+TgiRL82r$e`RRvNnI zY*6tT8=G=A5-04apY$%df7<+sja>*iIQjV2`|x|Zmi?Ob|LxfxQM!05`%T_~8XPhh z#CKJ_(YQ+hl_lPpRlV1}=&o9VY06P6%P3jetue`v`}4ahw!Z#iy;uignF?Juz|L22 zO)&zRx85gnC;6yR6)ZeS8IS*z*?R&_OPv-^aAr&V==>UM4Z&uj zFtGv9B|==XGTiPDSRkN|gpiLFkS|iM1bf_jK|qz%lDQMCS!lpg6e%skER^s2eCH3I z0(X>u_KAQR@icf?pzq2keagugUa;6T_|>h`|5ZnW5f@yR1!uq8eDs&`z8-{35RQPT z6HI#I!7F=iSw)=H?c21@L#sOk*S82A2z)Dm;s9Yr@oP@3ojiyapItu?ccnea{MJRA zIjA1JouaDM@nGOng=0=Lk9D%YXv6<-Exi>(7@Vpe`jH>N|haZWm5u zf&SMGYx*TvSD#cAkNgCjApGK6{A>C?t7n>5wqX}PKaBd9)afvPa?k(;>k~c!VNO61 z#(omj_JZah7*f+csT{+DSOjYtGKr>hFC-)vYcIlOtWg0HXUfrgoUv<&WWL=z`f_X> z&X`h2;Xz*CKNo!Ez>R-M@N8zWpCUFn?!DIihORJP{$t>QZ=>gq{9I*5@x#`zuH+9Z zJ(JuiSxnz)tAxY*=*YqYd5oBx?d4i};T_Q%zkVDqP1|!g`tqiQNaJJ0j(h7iiSaf& zd#O(8T_fbi&WN~okSj=n9bE)1 z7W-7&W1n^W)GpF^`v*mhSpS3E2so0?zejEE#2z7L%a6bn@bt87pNWEL#h39ct^#hSU*FLwf2?ip9$8rzi)en1#^|Gg94 zt^cdutL*hZqZXx!Gl%fN#|1ZSUq^VLw~yoJZ$no8zmf>PP2b#1&P&g;t}WJFy*L%d z)Bh1%L(G4s<)ciV*6yP6gd|-KX_Na}@SBN)`X@Aa9;U+iPtP@B)>&E}aA%rUFs8~V zU(a6vXb7ikg*>KYVw4=49(|S1%Hmm)ZLIE8F}<@Uyn;t3?7Z*U8-v|Ux)yo3{h|$- z2KXp$^jo%N+~$4ENcR2FcWtpaQIT&!*snbt&bJllcdu3ah^aoq-i9 zAh)GXagMV=sP}Q_nG1J-R!le7pNRE94(c@#TUR6I)K22X0E;Tv#G*yhFVppKpRAzu*k_dVFF-<6q?GFqGh!3WFp z4@uZ?i?AeA@P=v4KDoHQS5cPxuWs*B5bj%2ASVYsqfsX9J5bP`6Sz$7Z;(J%z{tW| z5$p%lUpjvTG}RaxM#nlyY%AzTk51qSlzwDLH(g^pm_D`mZCH>DD~UQ3Kdm5M-ZuOx zbt40!Gb9y+FW^vK2CQtRshJ6}Q4^OpviGL6_q5gSMoVyp$*2JNnP`qW`ttd+*XO%_ zg3qf(b6&d5&Tjj+|I>=+*O%cx77pj@nHi|*UCSUlBst&xWxcmH_Vj(Wu#}wDkGDu> z<7%iP-!v18&IP1SFQ~Un^%cgxJL}l}jmXon(#+OzlCSB9BZe3FG zr-PcFt_DiR-PEW7K>Y6-Y>D)&P1YPPMy}3uF17Wy%0q_!Pyxji~07m=aH0J~B%xChex%mo3-C+2w0^s|DLD4bNRE z!aN9{u0yVj#ElRJsJD*T?Q!?49V7>tTWVvX5n)V-0Vz7$mkajyW;YNzxXf~Zfn*U} z_1(c}Q%nQOHqz8`b99yi6D(nP_QL}xg>%c^4e&1%!eMQVm&srFezOt9dN1dW8y=)v zBBdsh=3tzE!^P;F;M{T2Xz~owV`nFd}%pqhbaZpR+5t>)T5tpPID!rB=Kb`m3 z!BXeY$9RyIj{C^0$7y6&JFw;+Loc?Ica7x)y39UR$CRBwkC_Duu71h|#&`VN2 zhEl3EAC!M+z@Pt|bKrS7*>?}ZJX7sfMlb}%l(uNf6Vx+$mI_Sf0lZx82xmjWBcElY zZFKkDm{n@qXgHCVcaIEWzrG7KYV>IdLRtJ^Bkf}QIn6~}bk>P{ z-SO{+h3r9u^_R%lGa-*t%rAkh^1Dz>-lh7>xxlUhjdIgy6J~@j3lzv}HQ4ZKCPq#Avji1l-!7zEaa{SZ2=Ts3&xl z4U$2&BRL)1y%$l?FD+LC$SDSAqgmhcngx29_kaymS*Y#qUy>)Q_#}-odi(OpeUv}!^nV&&CTQ6HZ!9Q*F0&EmqZSz#75;y`1_(^3;m3@X0r>A zAyBDfa3W>1IP2k@F&17Vf0__TmV5f5?u2XHISw{gVsJt^RF4&PhThdc)p zawp>?G~gO!yN-7C+d+IcpWLd+Ues(gfIaIE$0vbQgVu&x@w6qh<);u6jVjS1$O8oS z*rA4}j6_C6`;XIA^LW~hYt_Fqq5GLbI@&MqxTN7BoLbxnuD!#b+Ws^-Jz6U`SZW1+ zq&G+&1|)w%MZJ6zfd+mUq|yL7?Z_jL6#7|o3&g0KoO?Q5ojg-fn74hS7!Ibd2}o2l zIrcZl(>tEJiR0<#`sw7f{)JHQB1hiJ7m8NYc%_A$Zo#3G1#ms5yAIKE-JACp^4DFD zUmY0-zL%03CU~tX= z%ynYTZ|XHiHi0x)EK}qY>08L)Q%yj5gio+Q!^GYVKLbHPM3+nva^xU04csEKE91^fAvR8debpDgJAJKZJ?WduodH1nzN?pn>(eq?O@K2N$jo2xDh2NFH>U znC|{fTMzWBVfw}2!8ih6<8+QGanL(A&H|xNF$Q~+g;?9#Ef>|~k&p)wC57o=%W1{< zQn8h#KA~Gd`l!oG@84thvM|O>1+&45oZ!@4O-&Vrw|NPw0XAZ_TOcguA zf&dzW1qu>f=!TeEY{jWn$;TSq)`7qmPd@VVa=&o*e&s9EO4x{T8c9_EHdu>|At8Ex z!E`i&vpMI7?+(13J#R8JKv2?2`uLY16%@uJV`HfK=M|rt5&%U6Ux|chH|cSDLAX%$ zf~%12d9)onUU>@meYLEXb;5EfgAnv`tY)xdohS;!D|t1{&GlG=XaQ!yO8AF`ybB?Y z><{e_Jz{@2bKriI0G2p7w#-;tz%Po(8b0x^Eo2==h?EzC{Igxs;U_9qN;knhdos|fQx~}epAdi#DyEW zmV`zHJ`CFPI_6l!CoKwhj8H z@#8TJ+;Ny?L}U)}PL)-n`9YWkMpZv$;aG3Ad?>e419F<6e@-bnI3O~X^WQfQ9F}U(_D${y>c?@wVKru8>#Z=xz>q=(5m6zh?~86)t~-51c7XK+g5q7FC-0l6)7+t~hO@Xlk6 z%9Y#e#<`U#^+nM_@W0+KHR95QDHcyBwatamIwrc`EMd+AFA*`ph-%B~HLksUuc}Xs z$9KA=;8UUQEN=gJ)=)J>Pg-^cZ6i}jX)>k!g~h+3GhD46xa%g;n26`WDT=<0zAE!C zar(9#!P+P;kCx|6HnL3bP%y=mf1*pxmN#^l4ALJf3ig|MP_dq$lD~aR4tO|cCFd*l z2d<%@4x7PlbmS#ZKkQ}?7NrF#eZ-1X`N_Nw+795y`mZ=F?@jIW zV)OJhcxRSX+rK3^;`5fN6%PrDbMjW@QG5iZjkbR%mKY8Jd<>7EU=d*=)0#mCe|;whfye z_dPuK^Stlp_tVR@;1d?bQQ|-psncU|E_{E0Yc)K?B4U| z@Ph+Nd+s5lH+gLXR!k}nQhmjVeU|8)jzbHr;cb-M?2eh)@U-Q_JIntoEG403FKFx4-jFH!W~)ybmnrl+*F% zG`9toc799%Nj)HcFvNVAgfd1@%L(_PnD)?hU4u3~9uzvvRQ%m;1mZ0mPr`4;NO^iS z5Zv@wCSgF2;}N_2hr@07078K2KJDBpyzmm%7%@?kPxKX*jq8jiiJ;w^E^MRkuI6Y~ z7W1COr0I0$&jdhTLu!w1Mftk7nLXvdH|~D<6r3&{SzH`_v~ueFw+D3EYxJW5=9qR* z;xhmW-?p%b2_Nu%$5T2FWU)_flgminG)*4tl&#S7^k==@?M#faV~S5r#?Ey!}^^4waXr=YQrHmoBRpAn_Wv* z*Txn=O|Mln953PIL^3*OF}YeNyGtDQo3#nC$-x|t@?9Zkw+&?B% zB^W&5pyjTL4j*4e_{dzDdu!3D3+x~Q1!xEiVGR5HQ_|pF5-P2-*c+7n_Tg%a-8Y|< z1;k*izyrY|ROF2Kc$~(&S}~jfWYTSX_fF}?loXlo3cf*FjB* zYD#%#r;Dl*__;=n@J*lr%?$dAp+HMJY z+nxurQ=$QdB^^v~c@624uV~97N5i5(S$HW=uq2qu5oIxFnlByWa(AkYkuEisDI1ID zDtyhJM3bIh6Ac=YSkgkt8q^_mY_P^x086@sXsBPEBK`s|z_( z45zT*uL7fB&Tpc)O-vma$?S-&%QT&6=a-Oc5uc5$DO^`<#go9CMk*Eg7r4n@(Phkx zEPg#!9<$rq5452=n3CSW4&SsDkaENXgXlwzTf|j~+%Pa@`9HkPP;G3Zw_VA&7Sn`( zcJlCoaksOIGKF^rV9g--z0urZh?26bvel{V^PJOnQtr-#kS|90Q0j|A zOgnuNjI8=EZ%5bMEO#t^_qb`W_Y=tWdp83o(u^nqA|{t7dVXM#rnL#<{|RZ*068MS zkbJrMr=z-Jo*Ab_kLRo$HmS;eSHN4G2|L2|=Q;oL4$pr-0X;p~dps7hk5dh=kNzq& zS%mI!9g|HZKvgXk>f+b$g^sM8ExX+9ii)8L_DlD5*hTL$JVseTq;b~>K0=m<-Uc3q zlb~wPW^tzDFWjp_im5%`q;7&+l2$bO&2qzY?GFV^5$<0?vaLgH=g_B8X9ad2hgCTD zgEJn=Gp#Z1`+*iH{qrc!ugo2cG!t+TUr!+M;vz1eur+X?*uz4$5rLRo^+yM*#x{Y4 zN`}-aP<+;z9b^UtP@f-0@5!+g;`og7W|MB9eKg`=qMH_13;OfZuyTi_PAlHu&YMam zW9md`8|fNlhcV1*tyP<3`&Gk|-+~)ehZ3_Ml2^x*4&nH)XCdnSr6WsrQ<@<43+goE|~D1Qsz`!(Lal)j^pJQ z0K|l4;`qG~(pYIegQlJ}&sS)CN5DB6nFOHm(5fcxTH%k&WPxH|++$mOY| zbY-iFZevbg9CGW3Q>~cyFwV(km}WslVPYtFKng4LkwRDcWMY4RxQWjk#OwWpWzM_0wN7W6_FhZ7daPA6{ zi&_;`d|kJ5I8*y*HEVPoMrWk>T40gUChDTWazXoGsQQ8|WmsQ1hzylycC87qT?ZB`cV4ZaWNN0F@R6cyGfzVV$W-{~ zEzU&V!YvJu(jhCqzB{PuPUWMgCvwNX*=p6=1C6byjk`lfZ`dA#HR>ec+%CInH7KdA z%%=htWo*Og!|JZ|&1)(~Xm!aIv~|XlN)D)K!(Fkcw7U*Cldd_{gLT~E_ey!XiJWqb zjtk0Fl9BSFfIw!?qmbyAYq9d1$Ped3*!*oNib4}hh!LuH5P70uI^3DFEBxtul?6+! zQe?Gjh2C9>o&9?cYsb=U2w1jh(bsT|z6o^l;D@Y_b3o_%N9!zQrA{jT?dx?-q~F^8 zc8^9+IUgJ`rw+dU5uaqDwUiKcF6N4|2SmBU<=*)Zmp<*uZjAp{<34CiQ+yiSdD$X5m6QylfR}m5S%jtbL#Amh07c_{zItC!y_eTeV>=3Qg~^ZL{)2UDp&GSJ=LZ zhol(O&lz))7Yv~8TH=9f@noVPnK0$1?LC^e!J&10$0?V52GTJim2u(tMr(hk$ zb|ny`(~ObrEZ&AsltJ)RzG)3d-5lnK9LA6Fh@^Uumtk(^bvwGv3|4HiU2Nu9L`XuR zKV+yZWaxb{rc!vY2?mTV!!jdZ4cC)w(CX+{=IxVS9WCZIsz#V0qu-}7F|HJz(ASx( zM&++8Rnd4ySuGG4+s$cMvouUwG@y4^eagjsCtPf9Hy^y|NM+s}^aTbt=^akI*}kB6 zROZ2wz0|0~>G|C3734C_k1~runLxjMLcyK23K*ns=dY>Z5Mqe<5LZwL5S{9*+u;YR zIH7)t_(M@3mET$>(pHp0x;_qTRJ&gAYfQ6wXP$7&gCg5YxqDNq(+pZ@!W=+@gVREk zmTi%lEqpUEkC@wO&J>u6@0wp60;`AcSs9?d=TyB={jt#3ekSC7^BO_4mrbM9x=4I_ zlWMLB`O7dKVpGGe(@gd&vfHD3&=qJ6Sm+4Qvy7aja#Zd!cuc-cnkdHAWwD8C+$4y@ zyfU}>fHQX`w{Y#pzTyj+;H@OHW|8p;f-%KajZ}uhH$&Fb7TFK90!|hEsM2U7{bi?!Swezv!TEAOdK0GJ6k0= zuk5C=p(?3F6&k~g(;(ou<@NIIq42@3xCbnWP19-8dq=EGp}TN$&Qu*Dj^e&I^AX;;bm$w>Uu&q zm(jC!dr4R8*GVMMp+Ri00KBNiIJ97HXXtQ+)>l7{cZ@^^&8k)rd+ZaE$~bDU$*u8G z8;{-7Xr2zYSo9;7bd}uaHSfFmvty3b>2NBLhm2HD;i@BD+*db)D0lL#4_QNzxtcNy zT;*cdcN(RCFz2|$)=Ge5)3{g{-=INoYNTU(9l3&|7SA{si1DL%XbR4-Xzv&*Yb}V~ zR_Xhl+fV6!BCW@{s&@!bwUSM4YxcPt-zAT#$^yaZV)McY?NPVbL79G$324jjm~XKIO7OtqbB~oqk2j+E%U$S?I%%OZaW+^69~B!cOV&i5%D=nceU# zPP99cRlg9VIdh396-EPT=t( zG%JbPe@k}$9iedwY=@|{G{hUrU_V>6de3h#cct~unTijX#q)hG%W}#P_RSO{<^@xm zN8R=3H+Q*ztXgwG_OCu1WwU*d*#Tre+WlI)@E8V{=ZEI3D|99zN@V@whu=)gHtVy_F1 zy?3zJ>Par%0-BG(y`@ODuDj$*;Kl)3B<@1kTpse434lnXGga zw!)l%=7zu`AjyZ=q9D@FWghl9kewvHzpE}k+a081_L0)h&ryy(SFIiw;$*#+Co37|?^ zcC{0gT`(7KJCf=Su09{u&(Y*&Z>|h|X0^p8+Yw!vd}b&mWc(sQf6$RK!!xlucXRDyjHtSCROD?-U*BcX}h@4sXEn0*pXO;cjSzbul7%b6CJxfys za=Rns@bAFGy^Yvb1Cr8L&UQ1Jk{+<#VHVp^&3i_%s;;L z)=l$9g5j?{3dB6^lRZfNE`tN#@aG#2Ke*{=#y3frbc`UV&2x&&LN6bX_Wl$0dw!b! z0l?e(!pKRth=iD^*=>7|8M(jPbSmjK?+JWj9Z+H|yBa1P3>z96JY`G+y3c5)Taw>P zTr|4PWKk%U@GGYRpUI50mb}egJ{}5t=!ajnBHvqLvh#P>5;gNoY8*Ay;?4bL)Wg*o zrw4act@*09LbPW_7yLcC@Xe14g(7HpOqa!LyEh7WEcKxDfZS8)22&xT6a#| zy}ega>AaG^NqKr3>p@gSk$gx2k~9{D5cqPjggOZg`n<=?pymW^04|+4GxcUX81sV1ZX={xB!*WTxDNU2+3v zRaRcMR-Aov_^q52c1w6?ox*(Z($HIj;XA+m$WV9p^tpwtueP2j+P->^bp7L~m9Eg= zZxkPl>Tdn5XBhImB&hPvGj%iuhS*>{A z^P=)}`iK4#ANDCej9iJhl>YH%MA~)5#|O^w_tHN-R~#Nve0m)*5BG*>y!pJ~{N-Ev z@&#E^e1UG1qdn!|Rk_MbIr`|Af1DR||9sZIy0GHUg5jzK#yjZ2wFmvUD1tg3@R2z#~o5CjB+5N*3V_~V;0rs^pAXUn#`u6wj-5UqK9H1s-} zb{)4}@$1s6pK)6wxib*OwVzi{LIziD>$nU-NYDu`Xz8|}1&49LGZ4gf98!XZ5b^vl zKvmC4M4fR_$5G*ovz*}c3KGN6*1V0viU+L&H^L8mEA*ZhHH zPTNXbryrQ88`VH?-wn{VnN_3`U1M=j71~;-dDP~J2nluZpr3Tsm)&V~3$g%*FB-GV zT|0o|xxQ6|k`SrVZ9Sh|56?X7L*&~fx{C)+^;v>i9C6TRBW1u~?ewn6vrtdb_zMgR z_4OIs0;j&Tg5A*y?IFEH$`0(aR7r;#Ie$XC@E^4O{lbhXPl$Nr6Lii>KEKOb0Z&uW zcFzB4{4P7nbU%WxaAy@Hpp&m}1; zsGyTP7pkfTkwNmu1k2xuCO<4@*mOlfH%w$AA#J)4hJ~;5yWk4A4hupGiul2;+1W9^ z{aC^ka7S&@Eyj-HDKBz%oH+D(e8Eot*ye@dC}JSGsXVte{jzi z|ATvOfQ9vGZ2nK^d0BbRQ%b49q?}TVZN*xDQn33>qbKI|(*k$qgPfE(C?f=6)r=b5Y>sep_kCD+IbMybPo;}pAd1L;y zo`Vgpg&X}h^t}H6f}S^TUY4c*L`D4zJ@4E1=kVcwq3101tbFYMD9;tv|0>U|Hd)g3 zxy!h75372_C+o)MtOwy)LtCq#MQ2UKR8Q^u*LQxkGwW0Gzr^#mw5*x5e~IV3fNSO9 z|KiRKyZ-f^mvQHw|HhqbYHF5o=Z1!cwzjr&=guwT&Wfz8uld#g={vs@{_8sng@5w% z|CE;g>pM3z{6Br?`^Wwzo}Zoimv~;j{*!qA-v3|3^Rn-}tUNCh&qG8163@%p^Rs9F zMLf^V{r`e^URIp{&(AXE9P|Gf=FC{eoFT0b+SoB&n0bi*!?T=9JWJ~?zb;era+Ytb z2-D1khrKu6TAn$w@}UYNTcqcCI+6P8@rP|txw1cQsoYydGHpmqEp?@ae! zYe^%~o_m8SRKN6nzD0(4$H4dRG++NXhlYUu=k1|2RK)dK)qJ5ycG& z=nLYm%(D}cwys-lJFdWptCilMyPI4D8jCcg3?0cGN(DwpOYA@fB48>w^E^X=dIOzz z-Y-{dx(09ikrp{of`E)oxSBUl=bCk-LbU8^PV^ZB$YLRcYpq1l(nL_=h38DM(p`=F zO*D~Hm4T<4zP&+x7sU*9N=4T~br7&7ob33aXG=eK785@Qg%PB*#N%12t(6fIHb|)Q zbNoC7rpsfG)tjld(JrWC7L?gpw|GY+Iv+w#}`(xVs$|;X_U#yi@nrb@V69dVi~b;{c(V zYj-A%DYi|Xxh8||+q1)+dvZ`?cCQ$ z*5i^E8|`XHSx=H-RGhQq*XJ(6>~ zvz^fNuo))kp(!2!15-5Se%#`Y(Wdx%tvHNFVc_0egu@8Y&jn?fw3iU^aTeb>FE+nb zl&`rkjCU~1_G{o`wU)ILf3P|U{(nUg&g38~RjxLCgG$iVN6@l*4 z#YwgT)NcyZP=5wdx_HXiS{J%ZAD32_(R7K$Io4JsgzY!zW*PIj&H*JQiIeX7=94)= z?JzBzmCS;|qPiNIphQ7JbaC5dx@{aH*YP8?^z6rI>XA4m z-|615=Zi50`H6rHD*!QJOR~isWKyk4HBUguMkjc;EIGqCx`Ms~?mVN+%pFiYig=4Y z9f}q>veXr6BWo@tGDz*S#7?>ZJq$r^ds6}nO&zpxSnwt2B@5(%6HZgw)RKsSS8&z3Utjcpv6Cz!-s1ZCdF9_P2|)t#oq)7J?G0y}-tZ#@}>5u|t*r@dtMRZWK7(wFieV6DKmr zKro?<{f=aT$?{H_X}PG?qjThdO0elBPE!Re)I32{U@~MqHlFv$e#j4KNJL1@&j;KnvC%zN45Gm?gBvSF)9iy+Q;3 z7UZ2aBg%r=h8xw_EodE-2x6?)qo1$j%aj=K9YxYi*!pOkH+io+K0MQ#In#9WpE5rs z(FuO+1YyOk+orQRe4nW$!z%Vy1)5?lW|!f>mMW3?p~DYNi|*h`?T50@;RDz@GV^T_ zhAv3-K!EOoMtZv}aLrewReLhX#ElsTKY^R9nZtQco$>Hn7z5=qH-3Pou$4_w&~G~B zUdbcn%MQ4Av#uKdlX*axS}|L#yiwaBQzu{S_a^JZDb?7T3s$v}f#;Gy`V%#(x_y{fQ8n?rm~SE{x4?!0b%uqD9Wc86b3m9UqF)3@;TgALQQSWg108HAB
    9c|O;e7FnVD_n2A9rMrVj z(#!J&W8Is=i|2@u=)N+DK6hoJ%86Nx0N$ErH)2ltO6ZfCt#RXq0XgMe2Z?RH4Y;JZ zfQ=R_ENr}dA$PXq#4DxIgbZXdwXrk6W!U`DB!(*zZNTENjoz`Sw!Ua|jt3yFA*d_+E=)|uhO z*{Z=m;6;d0sspe02)z6SwtJC=a%Q@%%8pTi@rZv^Hxls{_#BL_m^{)S6V^GI6yhZW zBcnOIJ?b72kOCY+h?)tz{ygAy z$rBY$Qz(}5=I?-KWlR8v#q+q6WnG+=n3`=i1MZ*#_Up1DQTz}SFslkvE(Yk3LtjJo z)5|jvor%qFQHMuE8%KRlQv-O9w8{|JA~|!F9O^KQh}Kr|M_>ff@B(VSQYUisQRqu! ztjYnv7saP@z_!UuwO&*!LWDkz>XZW1OyH?KYLyAp@Pby~JZ29Y>L3l;B2?Cu?KCz7 zpOMiAWA}&2a;;pJ*Arm>X?Pn?bkt)P0=MM(-#N%rO;ulEA5oa|roTj@DKOi+2( zbkDTV0l(wrJ!=Mi~v30la-ryIu6kp>P-gK zIuEElI0~Rs%&N2EIhB646_zvLS@&Z24CpnFu9FmpKztH@pw2={f=A&?shCdb0VYJu zpn-cw0nO^@Ci-sGI|bh2xCg-~v<^}`2Jn%UyWS}^xPw@iSb^Zj=HL%wAEQTN>0SrX ztsE{)tm3e2R$-LK< zIFxG339FP)v>2{$SadwOn6i+$uMa4h%r-)+HZ}sq@||0!fSWl-%^##9(WQqgfssc^ zbV%A+9{hri*2NZd41=L9Mpa8-PEx@Z0O2WBt`3bzO@w>#;8o+8v&${FZ-EL)mG0gn zUUE2X6kvivIG6zj$ zZBj2*Dl1cRm_c$NxjYIedxBm!1$>(d-Pr^;I+)QPl)=eNyY&#@wYXPyO$maA#Xwh78FS0tc8*!WmY)({3=tELbElzy!x;>{HatgZ_T=V#_ z{S@ma9i{mwOnnE+x*EC06xEqnzNS@djDv%_PUsr8!6G~6cg7o`8^yUfFBX|W6DTpY z4!IY(N3H-^;`$9})lzCDhuKP4$oAzS_hz?;p?Hmr*^uoh=iCE#n&8hz19!Ei(GDGU zuFC4RV8&zb)~O?%IjBwosF~7bgAUMN(X6w*?SffQGNkM@PidKY&HIVk zV-Jlbux^(jqr|aae`2XwiAP^=Ae0IST&29Y^NH6=eFCVa0>Mao0v&|e(^WlsW}nx}P^0P@FD%M`Mc z+I2;A8VKy#e|!76E>y&!W+3QsP;ny1OMZlr80g0XEHf*jcK}}xU~x6*0$R_x`-qqC zz3`GAof#!RHk^TCrn^JyQ0F%mBO_SneZJQl_?Lu9k&AEpErQbGnt(2juA4 zNjO7((Mxt}nuJuX1o*PkCjM7-tc#0SC&|-7!3S<01X&Boww{I`m=hjr(<<9?K>anG zdkAf$a-n51Gx#*{9PBjAFIQTApq><5(cV&smwZ`~7M$27OwJdb72nh1BLgK}=FcYK)``Vsed#2XHrlb4n2Bu- zDwV0w0y(lZ5fsRjL!^M`Bm+wYu4}=A#L9-b967T^pD;n7u`b^>`Gu`D~* z3C|k*@VLF``_T-lM`O^Wh?6M9^%wxZ6}le+CQPbqU7jVf;Cf5ovD0)d3Fx?lY~g?< za(EbRG~JTxGYK!JPI)O7kZZgL&Wwyj(VJR0(ZQp@UVJO(Vs4l8z{}BnDi2fXtjE|p zyKwL)pZmLJ~xZ<~hi*C;NtM*@n2V9l)zHxLLf1`td9(!GGR;fGGp~WN?@PSjqt_Su@DB-ZWHDA|2|k z94$^vWAdit9~e#qM6u+Vuk0Cfa(Ov`7qh@h>6dHNtmg zJOC7}^7JD&-)4_RquJmabJdRd*vRRNE@{C^^fO>R6!l!6}Cq9vdKKySG29;LSwH-z(nyQBE< z!n|}jIHH2~mRdK_-w&j;SF61SG-IUZ#tQ?lfplDH`9IseB*qC(bc6l#4!l6%tU6Jg6fT%{}rt@(MgEVeZQd_*U9t zoyJ>cq8vPlJxc>=X_8;>P&-wtI;LC9jlr#t0H?~hN^t=v_tO)r&f{>;Bn~k2?UR|m z`yL8(Um}>*j_ja)L8BW#uq#G~J+9%PX4D%@3DD;7m-)!UVj--o4CW{Q@-^Xa%nY(6 z5$sO*0KW=E-2P(z`O(@hi^xrww#0i0dOyP;w^a=;LV%cB3VY7<(HgiDtX95ETw$fmvS#?o+1V5BzYK2<&?=o zJEh3T)o;A1OLYyfFY{iykheAm=LU-2l<}4~s%4LkPJ>sz=+pn=7YzVk`k4|q;^mK( zd%+*)qsF!nAZdmxprc~@F)silUN06DHrz6Ihk&b1u8 z)lL#!M2LK;Qw;)4q)>zhezuR)&x0n=qH#$$7T4K?dH1f6F%%_}qWah5W z{2t%?DJFOp$Zrg?Hdvp&HV2#$GG)!&KIBZr==`SpE{157MAfbL06vX8_V`_$M! z9$ZfIbGEasT^p8>(%#?v8|K_f%1QaDI%BhU@U^!Nvnue;oB8rUt7?+k>hm1#m7h~d zbZc*!+2_tcQi-MEP?e~`x}2=rjL9G*dACrtxX=v-+@ZO~A0<;n<1SJaqzti7DdF0S zoq?u!qbd9GYi07@T-Y-^$3_jKR?3jbiZw7?vYNb}*lE>EY0WV%BfvH+`i*@)^SNe{ zn`d=-YV~q0s-?lq%`J+7aB{Se+X>Ve zY1#UyG9wraoJrv{>~5fP7$S#`an#)4kBI`yktY5vbfa#_B&$3z5JwL7cg!S}Zh76@ zRC4H9bFs!my-Z|Dcs_<>klh4%-u6ginB_Z36cA%7SIS@AWIMt9flrPFe>dH&f4cK* zpf~H&<>4aLi-RJ7BCBDso(;=-qss$VopKSZ5EMk`e6sKnsd~RDkGV%GEQoPGZ)b__ z_h5xHwh3(mTS|m}EZL8Sgok=KoTydZ*<4?E(PnZ8xq==Z|7BPG&W0z)pX4ml zmAyu&8y72$0xzw7pOq3=XG@|9|1kL2@~mZAgK-~B9$Oi>r(|U+cm6+4Qcl zm;cnqnj-{BoYP7$%-858llIC#El&)HixUSu+jma@~M{Iw`3l$~;3VoLx1H%H0=l!+p z85bl&qI;&E-b=Z=dU+h*C6pvy-a->pdJp+0zaMecYnJ7%%y|vxO}0MkAFOmUdSWJ4 zoXVYRa5eE698Tiw$g%z5j-mNSt!TM#X(F23slVJR^Pa6UG2OX2J-SXcSSld0tdLx) z>+h1#Vyeg(|9OQVROdjsAql{xei#cdTR8r#od^c>4q5KDWxgZ{Ab`&BwTjqMvs=yR zd27ZvV3t=h&f#zQNgE+yuwIJ`W|z{q^f;VqNJBkF`L3&AcF}hcg06+kLC``}=IY)e zuw{yFeB(elj!A=qp@N@Qrg@%MW)a1c>Lw_Y2@{M=tBXQ2O?g$tLdcohzT_BZ(IyTvYQ;nN{kO9-9Y zttG?_q*kNL^{R|{b?iCW_$(@Lorojz)VKpF)EZpQKj1}i_qRP7Y*nej!kKejC7Wvp z5S|ooc=F>2w~-1=u{{b~CUF|9l^&zLcGWRkST!n~w%Ev8{Vo0av&sY+&xa$hXe9`V zGDBpz+;?1&2>j@oxYP$dn>zk9wD5V>)t*QW-sc)xvFs-q*DOaJIn_PT9u;m-suz+T zuATmw=oNNtvnUpEPiW;%jCi)8>;z?jL`q#WlUN3gSkWRAH6oW^Bm#6aZ>7r(k!^a_ z0_{t7=*^__MyJBRv>)~VPiFk1Z9h3 z-?UOwVQS&=Vk7#X(OL-&%%|~@V-5`pV_R*-+{5#PNYHOy@Lq60LYA3=tF+WMmr3Ez zzdkgAm7Ecm-;CYsFhCCJll{YdhzL?t=xvCB52}QFKi+y<^q|O^;)>J5(hx45yw3>2 z4OhNH;0>G?Wz3W7pRp)k-X!Cav;!tSZeQ)9dgp|@vBlnZPq;|XM}jP`<(ZP>T?Se> zn%m6onB=r2TPing!d&6$=AJMH>dK{;ZYDtkZin^bL^5Ea{f)y=bzP6$huZ-Jb3e8X zI}AcRykxL zicA;0G1w~&CH#I;;s8@}+;}~1-)0+g{Q5YF}XX&*j&Zi<)rrReX!Lm=~SnXicr%D+!*@{#*hfTB?f0pg-VZI zG9k{F=x}dP>B$Pk6)Fw>IT!9jlNm{EK$){!A7IIYEQ+C4Jc1SW@-sS|EI;>iZ@wnU zag-`pi*O5KwB0xAwn7=`^qtkewAye?pV7ME&pB0})DvZdmiyR2sE4*C4>bMWi`*a zd7v_N<5jt!co*``3?4mLc3x`#oGXPaT)ete+C=vdN+gIe1dD?zS%dvcd zUd7|W+oIFw*q#+j>(wNb;yB>ga>x%-a%>0@p(g3SuKwX?{%R3?MxOE6)pL}6`PrD; z&0P-L_aVMClXrnyBx&KNr=|xTl}xFEb<(O8mxcP#F#Ej-$0R)?w=R!60`FSeLi_&v zVH?b!X^>xOI^8*b=(1NbX&rg0<^{&eN9tAUbcxJXU3luS<;VJsxebu7LZ%#c5o(f~ z4+btTt5b%Bv=Tv?+wkVq$EbEiOP%+l9Ae#V6ReR?@9}R>FDCr1R!`+$nXM&LVKI+A z0me8JaQFwc(kc<#B)QrE;GvxWWS2)1rO&8axIa86P%NCZS9{YrXe<{nCEW@)MkZrk zurIneIc}nfV+tZXS1g!ExM*Uf;tD5z$mQI=@Eo=XXoo7bgrCi-xl)*{=ECByoCYr0 zZY;^qdwz`ka$nw#dl#8BcgilOc7%jTgKa!UO1)9Edb!A1Yv99fyU}n7XamYtFdwL@ z?aDac;Nx4->k?eM{xJl5uQ}g}=3Bo2r%prg8i*FPzy{lebRTq{K5mX>odY1f0U z7p#ZWOU}WP+BU?VEB%y4G@EZ}lR`~WbGgS>`t^E%RT)cbn2+QFhREQX1@os`|9aE1 z(W(IW2Ej?KT!UH>qj!A<4bG4tE*#5yVx#uxsSEU8Vcu7V*QZY84iK;Y9MrZ~wRb9` zvQWnNV6V(^b~*y5-XZ7LW6>7p&)F+k+27aOz1m>1Bs5a#TysWg4fNa?&yd$<peXS+h8Y;rlwkIQ=)p&r&GM@B19Rh^lNrN+&R&4YU5owyX zy^NK=1D!gHeuKeHVDyAyFS4-ncv-#^j_iXhWv zIp>b#Z~vOb1ZBm+=)@acVaj}fDHd=S(n zSIc+&cX8X?s%0~cu%35{pp7;H@3~wOLMccNdn^JV5g>)0K}`;RxkNKVZoO(5N}Y5W zPBb@`2=ZWlWPu>BKZAe{zNj^`uUp(ZHaaqvm(nj@%^GCNAM;0~1CtWcvGA6Uh>$Vu z$FZTtrPn+_C5C;srZ3{<;whxgt7!M4m2#1Z20_0HmKh7vPJcc-Y=(-+S?zocad2C~ zH}w$KCh1U3Su||tall>QKa*eXu_PR)o!czM)omXB)Dz`d_-uj}sT`Qen1;cveQk4u z)&JO|xmv{T$4(o{ysM^sj=jiDjW(99*WIq_u@k9P#XJA4Z54g?#dNFPb}K8!2$h|S z3c>-~!61dz^sMyl^v3|k*dsTkEA(Df_s@u*YxBZ!6Xp>8!S#ZTY$1!VT^ZVUznLuy)Y^^QDydL{sl6&|+`UBn|gBqi$l_H{|VyUTFS%IR0 zBhEPEn3k5BV`Ty2JcRR*6`HeFR;FgQHxQbom6@8h8?sL*W$zd`CRYobve8Fqg{NU8%$gwrbOK1*BhHlsPT%Y1sr#6*d$0(Oz-hUEX_7 z_%0vP$JK699e&A)fAkuDanQCf5YPsB`MU}5wxM|qAY;&@_wa+DOsHXEX zW0T4XQd7@=)-@FIeg;bzX!a3>IOpeZb`=$QI-c*tFer);HndbjnC&I>*&FRYqjA={ zh`bm2*V13NHM333aAr%lAWsBLT26&kf$7laXQkyw6V$3gi(VtbHfe_GxNpi93BS)H zw@NykiPbh?XeV39r_7w%L#G2VnyWMA{&!XP9`4vHg8DAK_+_N8#YLhcQ+WU&u8ygQX0IFUCuvWQ)J@8 z_E;*xHmQEr)I9xcFF9T7K7|F}7F+DhSzgN0()NL)E1=l{D0KL_Qi)Ix*7RD^<#^oR>f_Gd#7Tq-JRq7K4Ux6O+^;|T#u-o|-6F2S2es}dV7~7I*pP3mD%d?+_!)U_a{>FT6O({Xt z>2Q-kO?)e{;IZSw2T;iM=Im`mC6UZsOGg`poGGf;n%6QPHB>lEGRGub5}D5i?luP~yf-J; zWi>g!Z}=&#S^vE2(ie-$EQ8J2zah11KzL52r-wsnZ1fk3_)jarn8pfrR?ToWKxQ82 zIwv@}0QU!FUkRvWO3uuj)NuyEO`Tv^Do2FCX1i9ZFv$xU>;mI$%~*>?&Stj{BzsnM`?{B!#oNdk z$aAr7FTaKNN1mF-`o-^@e6{t^Y40#UQ>4`nH-H&kWegg_gByP5UmEWf+&=i49vM>D z-11VSy8S2jXmmwhd_}A=_P8AZ*ka^!-o?KI=^9B6^Lm)_>eUqo=UhGgDZzp1P$i@A zI{G33pKI^r8pXzyAu5IH%yt1X%6Zfd!DvCmdXgR6(PvpE`IB(?LV;a@!~0i#qb$OJ z`gF2HmqY_Wh$1|A9UwO~6dJ#`mKsD}z8y^MV!s>~Adk{noSo)^87SEoBy_=PTxM*n zk;_P|^if$05W1#;(l5jG=IC2pNY;sV^&yR!z_l+!v$R-vF&)4*J0#!CRrC{pkx&;L`QpSg<^XAfG6#qXCU3{ z08XW@q8+Sf`}QJXmOV*I@9;vDV@(lehe~SkvZB2wj9V@irC_1H`;J?b=@e~l@TOJ- zyI?fFOgB5}1IxeZBR=iN1v3SAuOMH@XV8bbcUq}!pmPG-Ee!* zcCE@G6B}!Ym*x6Oo{-7YS8N&ejs&+5&6zDX?L>`N*crfY_TL!R`4~BQ{X=xzE#t0d zH@-S{K4VN@c*!~5<8ss45q7{_Ut|BTJ{LTBt6$ZL6u>~6ejQto>*_jb?RI+O6g0Mr z_hH!hvqgP#hipIW6GQ{v)VP(=inyegPnJysK4h{=M~|D+6W_9jK0>SttGt`mcCmD- zi+E={Lei{*4ePViLDe(^z%Cx#zw7*ty9N#CpeKJkFBB%8ACXKAXUc5?T4fga7T z;_}J@JV0WvC(zGvZ!b2OLa?#FarY|XSv2OVAZ*4`w5|Ikp*$miNx^j7=0@;Dd@cmH zSi9BL4b{~S->5jW*B`PYl+k4$HS7xLAyK5TrTptKEUb#N-bC!(l#d~D`RbLhFvkqA z95#JT50AiAuG(+xwbEN{0^4v@I|`c;>z(!t(;#=lhVw2Z(s z5bJ=8HCIQtYR4_(^ynfG>~~8Oa#&)Hac*m)srY4})}V^93ZCdXwbcVszTrlw6rJi8 zV}1g1OZk*pf#ceKqSry@>MrcX?H7`W7>jUL=jXx{H~BW}BnM-vZo#(raD;{HYiwwa zbAuu~>fcT(j?e7Z6BMXAR<=t7Ry)iJ5P9SPhJJaaX{7d}5*A$P@sk!;|6n^J6BNv( zdTuu$x}nm%CIq5+q(3^AUQsZfOVd%XumiKk0>^3c<9 z`6@Z=^35rL1Edk~i)ci8>~@q3H!bc)bqPt2~%-nGRYCTiu}lt z?M#ZR11W-%8xKqAsC|PmGq1y3Y%*_g5p1NT3s)M5P=n=HMh)z;jy`2^6)0OB2Hf;= zq^le`h78S#aM69XAGNV$t2^YfbA53O&Lsn~X&nvK)o3)SBNpm20yX}eHb9ioh9?@h z2$c{6Go?=gurjuwN&ho^JupA#&|gzRrse@Q6Yg@a9<6>ve}Pmca<~C#Vog*2f^(rP zT=9O*yIA15lIEQQBpP^+C>`+z_l~SFuzN9~rfT*~*E35C=uX>>H$IN(x)Z~VOibxj z(uN==;)>8YzOx8lz|api9`q#}U7x)ow=y|sE|9Cmv5MYbkD>=m_*ki&uHT>Fy7{7z zDMN_gC;GE+7op}tH`v#0bnBi=@OJS?gFvWtR*_Af=j3JNTz+P`fJ4si9GnT#aSH|K zl4GmL2WGum7P&a*A=fzaaW+}IOUN98NEnaU8i(q8YqF#z6%yPu#lq^0=G*kZ!423$ z21PGSDcG)cQT)K#fMI|y2X$Iy`@5(4wy)~|h<^Co^i0laP@O`mOa>Tj}E zE7S`dJ^KaQjKsHtpv4lX=hW8?zT`(^_(x?f#g2*^{v}*K6*aZcMsj85^t=y1C#P!c z`}^kjmbjyU;b_F!3ihxd%DV30H4}mg-3}M*c{j>}e{^H-JtvrK;Uup4p`z;p6S0%O zp)nek3_5g*;i<1j)>ReZCPP4H_SBiU_RQQ|b4#2n^G(zxoqk>^YIV%f{z=3Kh@FY8 zM(=JJFQASs3&t50u9H4w>{7C;A{YK>E`eDFB;{PiTKG8xn(F2jI^3Wc7HlQcTUhAz zKS4T^WE)j8Dyq}4;om6W3O$10OT3hsU!oqjEeRtAWotN-@;DitkUJx)_nxU|MxV3O za}kpkP7RnKe}d54{*&j-k6v95I_HDu2Y7rboWEd2+;$sTcZk3 zepD{d)J1K*u03A2{X6f%i-dO2>pzoDAT>pD=R-(j4T+ey@0;-UX?B3fRJzBCKXm6& z-@M=SLw`PAh!bmJ$pzBG%ZeaTGdqEBa810eTs8W3#S!$*syw`&>D`CQ`$IxBr!NzdnDYWz15<=r2#SS{-EW?NzZ3@O+UeMn|XASVN9Nq8w>Tay3N*Lv5G7`q+ z&b4EdmcWl&_$o5VkX-NVqMGLbWaIpLFk0G6s*}*6n$~2z{bB3Tg}1c`ctd^75k!h~M0IYI}x3oRVR#>(`~2yLNi9 zo6yHW==_Hj33p8Z^1I_wT*C{_@#1AwA+86ny|d8NqHsnu5=!P*18(PjmSKIK4u=b! zEq$POWKrXcn?82uIQdkv?~U;yV-@&ijhQJ$3r0yUrjo|`2Fk(?n*ea9t)5jr(x=1I z$#&0=BtLGm@i_2ubM1ODjnxBs$0+KZ_2XY$bSim4T|kjJtpZE*dryPo@h)^V#>Ow6 z70cRK%cok36=_cG#9f9{&s{hEbSMLvN~D`VmmjytKe-dU*ZGbi@X~kntV3|+CW@|O zbnJKnCA~w1X(l!NGW}ih)aWVSpqI{S&jn(6gVHp7%varo}Smn0`wTMFWl*UEj8HUS=8Sat@H!ehfeOB#^U5lLdYk1gYg{FFibs{CA{&R=Er?AkOr{N>t*w7rw zU~HT}vpy5gH<8P-#QOyzCw&S(ZVvS|<%fWUYjq!&_(=8*=lU6YLX<5Ox`v^fAr;oR3MHK|-)2BM@U zl5(mh9ly#`wS92T#?5yN1(rL);L*>CF&hWwqS+fhVq75q#@LtTT~|Tlh(N`Nw>$fM zRKXi;C3p@5wJbFmqk{LkOSFUiQ@%$3epjGm14_d4sI@ZCw|Bp%F$_g+p|Eka4@EFJ zV`K2r_(0k1XHqf}jOT#=YTylDDb30+QvU`W?0NHX$Q9{FXi@=2X76O5SzmGH#%)A5 z(QHso=wXn9{Pev7jGWh(%HT5d#tywgn% zlpdASI!L)9o24VLFDr}GT7Kh5#Sg$W;nhrtcVs$3w>qRsM1!sU5sPN zb>a(kYoQ6_F4jk0vX|pIe}+EFb+_goVzj%Czq@up2eSV3Ao%!dspUmTiu|uM;TJpq zwN8d%J5ROQ*pDj{pj#+C?MRiFy<1caDjn%1o}s;knIfIfv&P?VHa_4u#@>;MV&Ms8Tc_HjtlvCnHm@}?4-uHp&?bhB*da0`*Mn^oDU_d%fJ#lFKQ0e z5{hi=p%#Ztt&Qpj1Hbi3Z*#G%RY{vG0=~!#kpvrv=$Tb~m0Ag!!v6wQU9P_f2;1`7 zc^IZlD`4biCIe!m;rl57Wz-b`tmSVyoHuPl{_O6P!tx&Q=OlGTumrMvbNvRTY1!3cZSn zU|B+LTJgu>G6EL(jRx*dJu{L}s2WkyJyn$83mp2oys1UTBT4nC3`i#5Jme`5Uc^tK zKUiLI_TkXQb{g&I?oRpYP%?W32IUDh|E&*JktlDM{HB&*zW>s5HovvcNgvOLPMt$n z0MKzMcMYtg5{UV7PUXJjz_=uOw)JXSm@D~#IG{Us>GR+odC5u4$J!=0tDdQ@^Qmk;&^RT%REb`s_BXbLThzGfIkuU>V>NmU0~# zoZmP+J1Rz#wOQlqlG$$(9Vbkn3Vn%+Qm$uH>x9czu)W8G*Uh9k^>uWK6J6?ZBbL!R zGZsrsby5*!5lrYqEJ#9%JEsl{0y}^4eZTVA&Byz5YfnwYOaCswP$jUlPbIU*GBBUQ z`XbT!<8JWnJ`uhb)&L-*J`XMz+%CB{du6|B=}1@?<77C>_)EjZt@N8fSX)R{kwE>jif64gRj!=Nc zAOBL)@NMIWr3}gip~sWbPRF^Ev4r*!n2J;=LwIS)_aMOs|8jPncvX9-OrF~6B!6>D zmrjcd)_F-`cmJB-aw%(^wh!#Hst;h_2sF%b(}_a#wR6xAhE1 zL$2dd?(@&xxxrT$+BBJVaN})L+16)&w;kVfLFskC<_M?mOqLmiHA-aJx~@xmXsCj} z56U4#ai7>DXkzQJEcoG22$LcHW@UlHHT_>53fmcBkg93Tl+#z&FX|2eI^wO|0e&)@U8e6?DcM zq%{DXsjAVil^Pf45NPzXPbAP@o}is^gU#PCrSlt;)faRpu-%n9`+4x=1-IBWqgMH$ zs1KNL^nVPb+U?^Phk#3C*T-(8Z7Eti8f5DNxDeqU_ePazI_uk_cS=nfAled8Y1YsH z)h44-p64&on_Ug65hA#U6n2>w^+9Q)MDnPaI)uhI$T#uqLY9XxKVNh1YBepbH2XL# z>qgG}d~GBI!Gxd_kE~jTu3z;YDk|I46(+@eq5qRBteJCbKD=_V;pM3W=jP2m2kuK* z#dJ!$iXyd8DLirZ?>+P90N58gCYE>56XtMlyKUt@!)&aYL`~uCoPkxgEa6 zIZKyDprV`0%ERCOm^8LM{ZG_}rGbA-%H$gwf_zYO_kvHJev;$3dKuu+{`SY{v`c1t z(KO3?Vz`|mNNUVvxA#DVIVgHVx&FH`OcAp(wr*hE6H!yZE$x0{lf2j=#GJ6Su#x7Q z1SneSNjr~3wQ9n2_BLOy*za*}U%D1(SLG6;(V@)1Vesx9j4o1->h)uL6}G6#I=3*q zN5BZUSk1xjUSrmBuDCzsXh?JA{=ud3h}22s9cQO<4Gc+ts>!?ki&lZ)O=W2Vj=H$A z3-gG>a@tzrlPWCl=CEwnZKIV8r?%t#0~!>wQ-Y0l>iE?T)?a%#({<{%YPY{CU(|Kh zb9_jY1;FG|%;D|~#@Jjz6U^`10^v1=9Cb>A|Iq$r2OpK`>PqmNls^%ag05UZoz$41$%UZuFVxQBwkJPnkOF2z$AvNntxRU# zJY~hG4|#GBeQRckJ8BZZ4!7IkG86=q>nZwh`+Uk1OXVeux^Uf&2u-y?y$*tK|yt_pxt}Gf+E;p zdbF&MZy>RAD0c@p3J^QGA6e}-l~-7~Y5$yOGHd-wp1Tn z*hVg9)1i7zkE&a?L&$KL)5S=>>ZQG9*%dCthkm-qV&){`Pb%i!SP3QbfUd>;w33KpF{|?+!ZRp$?~`pJRdW|d*A$V?v-!4{d+ff#-FE%; z_LZV|C2$F-x5;QOjartyZ{C_Q`e#8inuIn>-u>jmt$@8x6PH+|e{?O#%O;5ulP7lg z)0t1c!?zxFbWtOyckxpkIY1ZA#9V+QH5LfP#Yc0p6w(!k^hBW+&wKCYG^iLU8SA zqZezJ-AZt}(7UlQQa>~QStuXaHZFImxihY5lE~MNlJ3mXSWsQoxQ&BVP$ml{FWVCV z%4`q$gJ6+qW`2F>;RwtyBOh5F3DdO=XU=5iZ!WL2K?vuwGHM?%LoWm5&2A9SQB?wB zwuL+-!(F1X-doGg#T_E6cP?(&P-fTaxCXXyCmZxGa@vI2_>&35>~&1#M2-e^Q8n?d z(zZMM>r6RvR30E(S39CO$&wy$nb(>lnE|>QQdHY2dpqB%yu{IP=h6K88jxHd*s67R z^h8 z-ht1nHP*`JF`T49EGVKcRG}!`YsR(O^FzvptSNG%;yS*}ZVdv1zPg`_+SOh~U zAPC3242Bkin&g1gs zp*RD&fC;v`hY#L-haq5<#jl=V>AsY+Q(liY{Rk_K#$0frfcSHA$&Ax#!~`ul z`h{1Kd)ja_z56|QV$oBKp}KGW0)r5dt+OZ@srW9t---x1ORXW7?BsfeUVgae=jW$O zYNbXuZZ^#xha7OJq_2kQo{)fNTc16qNCpv{ zztV2}u{M6S)w)zv4&|A@m*tztC-$0ixj#(7B-iS%?zMM9dTO)8 zPg|0|t4#jsB-^pBv**RDh}M0}{uzS%Y{>{&`V#ZxFxdvS$|R}RigPJE{d`G?tuEg0 zZZV975H;IW$`I9D!+P1*&{K%<_v=k<>$Vd!>U>Ppd@Y%$)Wr0xU9>%Fw`@K7n>xRy z)DhlbD0>-WpsmEJK1?xCN@!?5SIQfkc&S=mfFSZ;*-Z#nwjunpBmH2LP!y^a|cmMAkyI%B_&g_*g_!@##re-g)mxt z9%#Se6Z;QZIH3L#AV)(W{5=dcwK$UcEXYs}a`J=VL2Ww)B66<%$9$4{R2=EJcn-F{ z4K>K!P->JedIkN&{;RqNUm+`4bvjjlkJQOCiQm6+bX0Y*)NN+?>6BtlhM{G-1X*Qw zE{cxti^Vm0Kt{O;M^DIeE}>VIaQY+uj3?kBg>EW9{*b_SfsBP>#JBmVU5&VPCK^V9 zus=fmn&1?W?hu4rJ1?LX`wgiYgYUWymyWhWkveKf*6%xO;=4|Ml zkL`)`I$)1$poNoY@Md@2&yoUzKj9ORh(iS*X>LZAbod&P>I&0&kH-A^)baB&nf1UL z%hZjbp(oh|>N40bz7Bt`0Ymfvzu zHVRVu(BQ86dS1EuR<8l?$XiDRdTeOORa?*BS1Ga4R&c32dCDdx8tI=E8rJfa;?3ZaAiUIrIpVaWWoqmW-lEaU!S1C`9tncYKf|+rNNtRXoJbZk96*n8@ zysHemi~p(~w|8M_Po97VwbXetzspwqBR0Y!ce_R;Ws*!&m5DX#ywx}KnkHf&Z4$WljxPY=mcW%fz;Y1;wEufoXj7?iOt{y4}mF#+;~3z>Q- zhEzIkaCXd+G2`$jcj>BBigS1AZK^xKEU26k`Fv?ju~)gPmP}F>tvWAXa?X~y)IdKB z+BpyR-jjTJeIM_!vZVId(s9QZw^w*a(<5k*{M&4j&Iy-vny_t9qT&fpz$`nJFZ(dJ*9wnV-l4fE`yy&UB9wj{MHo>UO-?FHh zw)XXKBDvXr^|h+Ba{gaFCl|!wgVA8GTX?^$RHMd6o;WbrbvzM5n-N(BRHX*gT~pja z4OW3IR)LMFffv38c6|-JHXU#^HRz^Qz>Tj#zgqm~6F^D} zFz^d7_Vd`P?qMgw%In0#OLD_wXbNZpkWGK)fwrs+NPQ-7Ie5Ax->jI+&w zglH-HZZZ2`zXOIcu+L1wg5M#NX1p`sJDQ&Km%2TCeg!GUuSDUQy04?8;O;cEPoEt} zdV|XcIZKa3gHt-3z=zhJb*FjzTG?oe5Baa9Vu)$k_F$&e^Fguyjwm#vJ3VfzS4|q& z>v3Ar4jZ-kX&5-uBnm&%m-z{JZO{a|Qbf?`cjx%uyK8;y;d`(OH}hHQYsFdd^&;@z zZt!UO`fGt6#>{uxhmdRp#CW?sf7!o3S`R$onq}B@+?;XzcK^xr)VMKMbv3$tMR+t? z7i2Bqzmwwukort2X)`Bas>BD^2x7#iE6t9>GK{xoJVQ%gZx)Y#^H*1&&#oc~FQ72) zzUp38&pFvSsQGMPfA3d2jAAo*%DV4&&7P#!`c$NmK;MM?3~RMUUPZ>yo&5sCZ--U6 z{^!0GKn=lx{jZxhrs>$czVa>2D9Z2PSHB>7#&!S0k)_22{?-wyi8pLA_bc)K_?GFi zlJQAMu&FtAx!)ZvKJ;n!SkMUinH`lOhU%it7TOEg+sf$Vq>uX^8H z)_20tE}8JXB<%emRGppiMs*d?5nSyNPybZ&C@^~9$i5vZ8Lk zG^p+%tS%kI=s#q$ z_t;2Z)<|w{Zc$Ou|8h3FySvYyKmWg+&0h*aQC&e#whQ?p2N`oXy8)N1ip0D3Hxp-T&ikejOSa9UYyXp8h|P&9Sln z3)y`4?%n@KkWGcEdHDY|RnvRR|6kP{=}aA?pYP`0+G+|iT2yjG=^Q7Vp5PhxC7P;H zcKaU+C`Q2m%IcDs3J%6yv_O}Yfk7&;nFt#9a2OvB0^l@aBNeKcI)EK8rh~wW9T}RI zSr!ciS)wYdh+ks_T@WgIw*A13;m#>dPxX<6mQ}ymD4s<(h;m!G~^P7O-t?MrMp0e z9KP^UUx|w%??*RP0d~pH1TZ< zNu_c$eqE`Tg$_e~9*H!Ds7y7}fT7oVcJQA}G-&zRXPQz0I`?7w+P}5Vrq_6LPn#|v zdq=@!h6V`KdT+PC-rcmS zhQs4;>p`u+otduRUfzPX)qdT5oLxPTIaRaL$_n;SPH)f0{x?qZ?IO*EWR&5Z{SSX2dRp#-;W(GSg z?GR+Q#S+#oA_~N}^5W4|gfZyyerh85azIdn=1|xR0k7NSAOD(relgvl$86dtPuEG` zp4+A07fspG>h?o6e>GLvOtYjbHY6a>&wpP_GL-b)d#LHGptXgMnQbpYz!mG$)Y3$U z;4oC8`?Wj>P14{!u-WBP$r{%-TL!`d)~s+njofOW6FoBF@0n%NLD z9@2kQrariuV^-X#vY&ZN>&a@a&3L0)`sgj~AFB#gQzb&>$hGnlXIAr*%t_9b`ErAp zoB{)W6RvFuZ&WTX^cg34^-!=|4}2=J`$S^O;UgBGg~i(R^O}!iaaPtn1@u)K8YwGe z_Q;6cqf%u9sbj-HlHN%bE}Bf_!@m%5brL|AMC2n>UScD7%|tkhxp(cd0e_rna3me< zTnIvlH$(LEKzG?*UJ#oBvO&O=I|F=PIZ+HXjpr946+~zHX1Ixa9Lx7^bCo){buf)J z8jNf%9hqv;KDIno3$GwOU??IUiP=%sILgCHrge+F5Wy5fW`<%s`Vg4pABNbXTE%mwFMlagCLJ&oOQY7_Bq!hP}Uv=y9Pv{ z%!yJ&GdBt-WedHrSX59xReea4Pfd}c!oJBixwH6oQFge~OAJF5dY-2wLjCH{u-9_C ze@LHSL+tQ+oJT%u^w?dYy5i_%W4yVtb3GVdTE)|BSQQ#J(3@joA-L)u0BciS*`jh# z?-cr3yL%(TEm45Gi1wv1EO6C{Mhca*;By}Yl}O1k-L(vUtd=Ice68GL?>whmCMUSi zWCpPq7^!y}zSWehd-KP$q1R^#m$!d0v8Ft{NSqH#(|!k?d)Wg z7QDW0V-c|IE`e0`f;Rq~cSCYyxQjffsn0)w=n;S7j-pN4^kT{i=}K`we|IBgeEf?v3GEl_8=v z>XZ`%Ww_Lb$onccWh~s=rUQoV5q~f}vGUGzT%dp9o1pfz2oab8M!2;Lw#4oB((?Fz z7t%OvvO;6o9G9XtTPxMO)B(nfDs(;X6E)`FrPld5LmTm;a_A&NpDcasGApMIB?@=; zG~xYQK3qK`7P^w@h%+>VsRek2e7unWxej1eOmg{ht|a?H|ABRB!mGpOGTdniLt}2zu?9w!mZ5Pyh6<7w!RLi9_raC=!ob)-t^iR3%dSAYEIetr7s2>ws(TQfUep8G zkevacRDo99YMOA#Hqjdn{9AGCuSMm`pJ12Zqyyv>usV!xs5^ZfFjiTBe^2;g8rvu| zgv)W??=hTgA41uCb>G42phxyU6`I23>R#xBRrK`;l>2er-}7!V3>l|{rud(wXSoN* zEgW7gXsc`9?P`ba7E>L_6^!G|HiQjY(T5 z=rA#GwGSG}4%%*}gx0|Hh!DXbXO;w7zZwsOqaKey3-frjAm{G{SYKks7LHSsC<~Lw z-P@SGQ;JNA4kLx5_&xawh$@+@L>h+GeT7smLJD7Tw)a4XTMo6v0HxFWRXlUMI42r- zIS45t*a_`20qyTe&0)v$D44!^L^vpurVcyHErozl5`zR?%2^5#%r$VVmfTNkr;z1b6cgR7oTXjH=03 zRO4awv+L-pzX9*Rk;<{Cu3RJ~QR(yJgsOH#ILuj~UZMODvEdD(hjz4v7}He?g!S{8 zJ?YRHrap%ui?Ju#>YMA&by%fluR#{M%Sr zWHnN_L-892oZ0(%;-IojoID?Q939M%0R9qKb`RpB8LCCB%vlSJdV_3w3}F1z^z(eL zP9W>wa5hRHg$^OGo#8(f{h(Od3_?pe{#9neOddK{F{{|d-9HYOiuO0H0h{JQoVXEF*ZdBy zLBq}9FQLdwW`~=5V3Hl8sJ7F$@!T_xEDQ}03wcm5ikVydxF50j78ybGGCojfhG-5wL03@rHTm%S^;H0&`|g&_9n@$5SGk9`pCXinemjBQRb!YK|Of z!|e%B8fP*U-k_%gQ2T^g|Ad*41F8H1iKewwHbY{>P(HWzQp*`SnyciOf6y%2o()8c zT>8X_#W&Dl7G`M)s@$05DgpYq$SkLji!;nX+6m`*sF4lkq~D2Nkm&3(*Hr`rWfUE2 zOLA#Lr^Df*CwaTVv$1R?eQ~o8fP{`9+r`RzX{>}*<%2!dIY5i}ZF40d1IGp`3Aq>% z1pkD|F@x@3RX!|XZhei&qOoixNMH6P?7R}WBk*M^kS$V9FH}tHMjl&2SG@s_e+RCQ zLVX8e7bg%-v5nh0P7)p-+_ZlkWnT?Q{6ZD9nenkAhVm7rS$(eod{aNJB@Wlf?Rm^( zX062rTRrQC5(N69Bk%BXGz{8HD1z42p zDw^jA-xTDh`w4DW~iejSeRDalsZp|4{(5Ps=9%9#<9;_V9_O2o}jv6)RP z&QnA2_?3=AQ4NWRAoj79*T8{{E#bg^tOPUX z!+bOYQ`m>N^UxqJ?7UEdq2)VshwwCb828j+hmhEvT%u%<*Pam~zN$<|bt#4v)d4j< z(PLFXgR$sv5pb3gb7l$M_Psp;z;>)!Zm_%lxeE8)k*UjuTuX(A_dt)t_Pee^Popau z%{m!0R=Nb?W>)C@cba`Yx{9V$ZX?AKA)09Lb<}MV(a(hKe4yvLHw)YjLaqPCVnuUf zOr0V?g@E4*r(F!&PK@qPEPDNqg7eMff--}}1zqq=jRWX|#%LE&P|y+@N(BLD- z%5a;NgT;Uo=ynk&pLC70-2^(rVQ!^{V7ZNx(JfnpTbi4}($s64GnFq%;@egSVC}&5 zVLrn_JG;H)p z{%{T8uf|+7LmvIAh|3# z01S0su~};C>M;*dAVLatOGE`p4!9@sgJ!rrAk?K*?u7~DSuXU`tdEYa&1aY2PgLM4 zk4p8?%Jys|G8~yOf9Zx(TAv7r?U~bDU*RM^OZE}N>|L0fxIJw)X%~Et?09_J3_Zy7 zd*pKf_*M@MP7I(rF%?~#@ovnYJNv+$53y`uJZA(e0;_8cZOF^Vtttx=m3FKuziAB* zmW2QM=kVFgI2W_4MKS%@y$jJ@@}Yk*r)VI1-wDq3eAqvTJeqQ=S!#Ep66|0t5*%Ou zuh&)3XgV<;&jpgEU*N_Yb;5f&U9j^9A`VDkLJ2}lJbh_*6~T-tltX^sk(Xc?v*yNR zh!iIoQ0GI}rm0YAVTk-Iu>IY^;B_c>^;I|#R+fUORVPLQzIu7nq_`>LENcgbtBYmWF!Ync^=#SNiHVgUf+^JY|LP+7=Vx zD~2X;;rZ;qtBJ_3noe{s>S7|IDLww@u8h;Gr+ug}j#rhwpJ@=!|(TRwz-RM#{ zj5VLCx^QL927+TNbrNcRGxjb!`e*ugF~a;QmY5H51m`_3zUbWeRcr43Oa$Ky-sW>R z>qOR>d1%HTOmB9?^a^KT3(kIh>Do1zIBQh=T#Dn+J zA+Yf>4m;}lA`mPAf_WE^;i%ISwM-E7FH>-32Eu6`mT=bb?>Y=Ngy~PXJh~NK#9$_| zAv#>Z(QF-3IWb5eUg}SAp-GUfW;gN@5hgpFqpBea{xnFj<6cA5_7t9fr(DfGcX1w8 zDFnAMPHqqHCFhBRmdbS?RsxL`HxIZH%k+vR*L<0ZQ5)@CR2Kz$@c@|3hHMhU`a~%h z32eYWi^)T*9p|4lD^=KoKm9))_F37C$$4-Mpx7cAf5$42i+zc;(so#A+AM|*}mgdbKKvCjbB0wXM7yNjq{2G5rP!oF>_FgO>BAU z%G`m57Wx9YXs&|@2sDHF@&NX2C~N`g=d=*z$UL};RE<+M`}A4^^Ja6VOVYXoX6)hY zD(=Pep5}#uAFPiMR!6X_Le7Q2z4H*NnNoe0N8Fo3`YXy2_hJ6qvY))+oPB{M?fBIj z$4%AYR<0)V?$@L;Ti7bnD84ZDNB6>z9 zLhznt9IO9SP3LOUkmnYwUawv2%;TOj>arsX^z8FBifMF86a8Q)yx2?*IBmj^eU{91 zWkM3ns6mdnyDTA=?ac}xB^BxJ;T*pFgwyC_;ub!cDEvq1P4Hmq`-@T077u7TaqM^p z^M!d#;btev7LLJ`$o{H?(LnjcB1&;rg0X+?cdIgr6cg8Xk~ntfj07gNH%~u_IWXNF za^+?ITY{mDlBdc}Y@i*`Mu?D9S-f&mm13eM?iL+2=r&K>&v2cL#$Bks z_}R_24_B`-M|zteE#Ga*@+F9OnEp$yHp$pgdze~*tvRA%J2S6GlT!ZiZD4}rG}2O3 zrE|gzb)k)&l+(u#*7!637R(|XuHL7`+*$9ec^>|MaCe_UO*L-2=u=iIplLv;h88*k z(iGGrw9rGZLO?)3)F53^lMo;jF%*$*fPko|hzKaCNd!btpP;Cys6kP&Jc=C~?)=~L z&faIwoH^h2m%Sz*^C8J()|z#%`}$qefZ4Nh|MWJcVU8K&tifs(o{a|r)-J9+=j(mF zE=%;)O^)r43LSkOt@*iNpunCr`*B6$(%F^;x0RVO8U z_SQb*t7PsCm&Usd0VAf!)oIL?Lwvm`VcVf$=GM=KFb#`!GO$5@4LN!PxC8aL*oAvl zLcVdc(D6B(JSucFVk9e|hSA0`(DA+*enW7x#cjBfY-%NLNKe&At#Og*ZN0x= zPLC|v6?+|r1QKTLqo1v??!Szl{{$*L^!0IWVp@Z$Nwt1Till${jt7uZ|IvO<$Lqrie*2YO@tSiVMp{Xg z8@nR7Y6OHb@vM?y)8M~RPi4$Pt%&KZLaar@Yb8T#({p&)yV;++qW$WGA0!4pprvFB z4Vp^BzX?T$oWfL1cBE+4#mwa7Zgnrm!ghHn8;+XPsIDs`c4XbzUS$5oM4ofGGq^`{ zqHqmsi1Ph$&Hl@JU5_bT_z|4pPm8#kL`5oIzPC$SDFM9y_m; zKI@I#^a5q*63>b2@ZhKZUZEvTqo%#7*K zB6V|4--d@8LVT1d<(Nm1WdRbl_c&q*mZ% ztF5BqXf;tEb@1Uq!bmSFIGqRaOriBGwNw2yZFVnh)hy9xYeqZip-y4$nhRdHGwW)s zsF>SWt|8|A+%v*{q1doF&JS3I*VFFE3*?fPz$hR`D>p)L>{)m5QoMiF)5!0 zkV|Xpbc`rqB1!46#ea}WF*I8rqv?C*q_JYuC1#j!MixUZm7WMW$6pC8y}QfVEFt^9IgDtAW`QzOL|2DCyApha5%QM?uoFRA*y+S;wjLad@VqZPGQ%m}$ zR>lBrkL)OXU!-ILy?zkAA5^Ax&%t9Ok*^|Pn!fnZhghbZRG|#`fkux&9)Q$t49gb;(!h;!o;IAT$PFZ@l{LL0S2ENj zv3Kl0;rVYCrRY$J(Ip)5szrAZvbru;vj5zeu~{KxWhfD37nGm8->@3^Y0W|T3Ai(E zV{OMpOd6>`hAP2=}Eh>ovH_aYiXU_@f>Ww};!M+&7_%FC3reZ z3TYUF*9zm|s#nG=nq@S@W!!^*tcJ4x$-!tU8G8M!5o6dp!B2Rf4n+jvbexXp`CIWv7_-5aO||G5rzQrXG9-cZOfQ1pkb%WciD zu`I@f(XWb+Y^pi8^~1kiY?yAHli=FpguZCGfoZ8V+;mpI*W|SuPI2RHBq~q}?fv?F z_x_VGKYd&c$R?*s$Q$=sp#YJKT=is@!`apJm@P%OpB#tnL5cQ0ZrO~lYmEIxnwUqT z?Sc!-J{Lc2aNp-&4^ywUp40JB5a?U^&DDm9NH64!>JduN~D~ zzcG-(#R)NMbieO$G@hNDu02Khnv_tr<=vVuSNeZldD8CQ`0|R;?cs*SwquM9ANP`c zoV0#3xVA*3W6C;;9I4DdI1Db_?n4rvwQXLf-Zxyi%ci_uv;N#8F-Q~opw#4|tGKDH zup9;RU4#raf-EP1*hb!|Aq>YFdhjBwE)eo2LUd2d`A<1EI)bCL$i^*!XYxiim~eD^ zLEx;W;SDMwvnv->zciI=@#_^~!g{DBvV8gx_fh;|4x4-O0xZeZHJS}^BvQCbS&g}=Bbs>mwJCegeB zTWryR3_LDEHFi#gr8HVAH!IF}NnU7t)Lyl1y2=`P)q+)vOwqY7G0nXw{rz@)ZT=@(b37~6fg1GgQ{AL2k9^I{_y$aS)S{9 z$nDar`zx?rsdyFZB0n}{t@AHR_i{Lc!M!J+o~t&^tPK>k4C}YjXVD3O4@zno=0sRa zhg2+a@foEcLbYE$dQI;^d&*d+$mhU9Q!z_%If80dK@FLZ*gf9*GSCWA2;PRT$?m6p z-*6-IY-gp6J01eTf3&J4NjOetLFU&UcXI`zbv5Y*|1#7pSYBZ)SouQ}GuE1hbb76v zSM_^xHnG%M3nG}}`N?_yOS~{v5qj79{if2wcdsn}#TyX&jQ^#5IgCMo~B=Cg30b00r zNx{H+OP#pe8`x$;5dY&4BT5}~%Vv&{_xE+Bhsg>EM2FSV0SJk`zxp&0tE*-tI!@so z1{J9gkvziT_34KrOF>uD1BvVVEJf=7%0NUStP@h`Kq<2U9VCNQD#fe+NFct%PT27- z{UBH7~T78-FXlmt4$|EF=Gp=SBKBOfqJfgDD{Jmc@Y7Zgfe%J*--b7!6}9WIZ6 z`iDnwjghpmW|)6(H+dN{$+MHmG2M?0FETrzj2SmNub4h#nZ0qQly~1n1=xTs`>i^( zJb5v}kV>BnJb&2nrp}%W!bbb!zD|%6>3m<|p%K)ks61FeH&nBYYbZOa*9*~XE8P+r z0%!4xnQRY}ljpq6;bmSfJ2azL=vT%oDqZE6`d>IB8P{i;yQ*5zWgq;Ztz2va<9b8L zrbYDz-Ik2AN0zFe?m6;K5O9&yBQ*ouh`a3DhG780UEW*>1G{4E#;R2l?INrBG&QNZlWt4T<|? z2s-XMDMv#C7+lMV!Q_uE{>}sbu!mRjEn9Z**HNmCQ%s%r4tM>#s(J^~<5E%RP!O;S{#Cf%$6xT#XzThJf7XRm>3yv>HMi}vdbJA$g2MV)YNDr zRh>A>d3|!))ne<`@Wp`L=8A{693!_<8j*XWf6L~CI&EPi{lVaqKMdz{Xj@gJF4A)A zM~Hb_ks(9>uQG|F6g__GNpaOCJxs^?=dsVeR604~&i*SI3WC&nyDshX49p){54!vP zW_wl@TZ4r|v*H5ZK5=qa*3X03fR2S@IxKswzt+;IHZZ+&MXx!2(EUO(p07%Wm=L)e zx*xB4bmIfbmp=v4B=Q=xE?LQVKJv3ZONBkkm%*=rH!kH4PTcBlf2{w(o@pv&`N6Am zaXA_*M>sAjQF5SHz$f>1o96kiy!4rJtBJ}4aji*I3YpXaMnH9$EB!U4q-hgv^F+PN3(8R18h_WfcmC!irFs9&Lk4nw z&TYR+87TU(ikn=fx=AU`9u=s%@bNiDf$zG>64jCuh^bYM#2^9^IB*UY1!8)s9c`g- z(U%w|bl)r&e00i~*F~6VM4{`-!UYpvnj&4Fr)%f2@V*x|W5F@av-AF4h##V49QZh%DuU4xhM$;!MpNS-sAr7U{{D zC^jeP^r+gmO22(*EfUv-bPX-$8s9I%hS77`?m>MK2WiR>nWS*ZQp~XC9-+ zUUS&LG*F30khQI{dc2XrjdVkK5&2q6p4+6t*%NFhBG&}E{mS~GB$wxiE}i2xvd1R8 z8du%gUSCcpe|-70>K3i>C7bQFq&^oD-=r89ODEHn&dCiS>!(5JjW0Xj z70*ZOBi|e!Z@8hWN^GkLJL_%F;t(h>?n8h~Z;s}7<7%tuEDO2+zi0pWp%%-EimwK* ztRjoKK7lbJCz#Eru!@x(_g8R4;mcYE}|BmGk)UFC7>c+pO_f6;-cAx>n9M(0DI zGFW=1mWOXje_x5!6N8?}1=;ze*<#fFjw!uB z>CER1-&c{cSM}7gZ85hJ-&eY-+#B9<>V+=m!gw7_#1EY&|De<?a#o4W%6^0tepgK7}gnU9?pE*VJ zj+>!GcNZmntMn3sy@vo3Yn=DcfFA~GQ>OeKgIrzDTXo7&Z4V@}#BMDTx;C%;3XEE| zRtoQA5g79|CgSfO0h=i9p)*e}v_#d4zaO?zwL1u+4#T3Bpqt#e_nu^oSeI62K}Z$6 zAWX;FUd6LS(3&BT^eu;Ava72E>pDSIi<>yyy~j{dBLT|4nR&1#*J{M*WZp|>?d2a8 zuNkrT3Imq_|9WVpfXmObTlqoxWw;$>oW?D8M@92bl4rMSS6$wl&oy!?xO@y1dF1?5 zsAEHF(TPB=Pu?HBh0iztor@OS-iO{&y1(>6qAGeBx^@Ec?SGH=r~OsU)MK)=%51c}LA|Q(sj|`<_D`z~6wX{RLv`XRGUJ8taFSQGoARk>{W#M| zTOY&8+QF0zs`Q1(yDGYFw(LKuX7h&JPw!rTHkJvU9;MV`IMUT&rWu60^^ogWRb|tH z_7`PSReFUqG;AeJXdY1;mm8ZBl|i3IMXvask_lAJwM-1%gWjA#&DeFc#<&I149d!* z1tyY2rF%G|GwJ?P8&ne6(8uM$7akBid!x}Y^ZoCdy9aT~bXhN@}Iu$C($;;0LvS#-=qy zoW1F-xzXg(SM;v>MzcYaz@xu5{$BnVd9ac#MP5a}2oCFG)N)NSMcJcir>HOBTYlva zG!@v`@PjeBKpW0HyKS^AT9vdLMNB2;RS|k_7LVc!lZ04=55?Y%)NH61X{;($^)lL- zcnk|$!9PiuQl~qC%e_yLGQ0{E8S}(|f%?E1WyKE5yk&1XZd`3`dlF`qcf1KWsHBIN#GtCH8?Fj{;jT@ObzE)KFJb(|hPCV)!4jI>k zbV^l=o|r=}_?b)Og9wkXJ-Z#8%I z|7khY8cBl_j*1u%L~d+95ARptO(eKtY5nnr83X4`Vz{?rH*G;O7{%(2hnfxc3|Pg z6t2zpC)U2U0JE)aMUzUQ+jRy ze-m(nw0pT0zk#Y0z?3SL7NXIyGX475WL(ED-Q~-w7Y#~%A!?X8z*mU1FVIuw$f^4mhL>EDe)u?Pc*%s;N@-i%XR2S@XD~{Dwa(gAy3_jH4Fy zXkf@X$iWJ+L7z03Lngt(HAMRRj&rqERTb$mz^FgNdYbdkiy(m{^kTUf{ZsXd{+{;Y zDj7YsmbmH4B?v}S1F(ny1H>7h0JseYPNqPjzOI0<3VV^7Oo9<8>5Ky#Xu99-blL63 zne?y=-GM-LH)Rg2uYrrJWn63G(?W;~k8snYjzJS`Xf-WA-Q0fZ+a8d;<`UkWFYdYL zCp_YD7UT(RJKAU}K?hgynsV-6PYp`ZSEW8Mi3skdXF*U6;!-sRh!-y1eQ3VXT`h4d zGB}Y=?eCUi6lq@9o9D7Ura{e(Qb>OwuNtmF4MS%GX9Ago_YVy1cXcBUR!|MMPrL$@ zGn7(LAJn>8FI2W(*EqPdSar|R)pyE4ni`=ggy23d-=Ep7#Sk*4Dz*gMf+XQBmihPy z`tF%dz<5ML@^VX|ZAmUS=hIg(J-vlCMi?HQ2}ZT{R*=(gyIQ@teL(x}jnJ#R-O51R z78Nkf#6b^kIb(rJlJU`ujx{&!7gmP|!avP?FAMVxg}6pYRl8C!`FBf_c|j^6=G->ReD#BXnYvpVb9sYF<}sU~zk1THjOujY4g+N9v}Z z?L@mtkWRPn-WDb*1%MKiJ((OB2~=dvY{#9stq`}VCj%1ONqhgjb5x{iZiZV7EtI(# z$5PR$XEPrNs-aqbgLJy2-he^8M=L?Ro}gvY@Z?;!c<$k%aB;#mwJVZ)bsyV zkjooT=o^?H~$wttXG$c0ro)r!Wz1y)TGq~-P(aB8=meloibj@9I{YCwc0O8!D z8ns6f|2GL-b*W<2@{5z?UO!)HMl~MwyEFUjZqu74)m(#-BR*+MT=mOKh$xK&d<(^m zys?=PjroG1BgZs-f7I2dKv4HhKUn&60_~FRE%y1BVytA)0i=^i{}Sv_wt|diwNF~T zzg|bSMz0}^p+9KW>bYc8ue;7yYZTK0odd%ywNfVcoZlAsY5AI)A& zk5^py3bK5~Oj~mIHjK#&-6|gB6J-wt9s zzPBExf7|+uDG!{)Rcv-{pelylYyy8p;)c9it7kZ`tgK4ty0M#w(J%yPtj2R!?>@Ud z6RC8j-R*XG^^nmV_fd)e^P|JnU!&O|ds^{7VIPI`pc(l&gG7%Hl6!YjnLm46_s;p7H;L}xQ)g)wi?{fY1Kd|j03cwh^|Pm zK@{Fb^EMdLN@(z-mli^ky*sBc+cC{gjC)?;%$f5jYmFB(F54j98D4rRw0{b?IwoaAHt-XF_L52oQ^-94}IOg>6DU`C3B@b@(R8DkG6+-w+^v8 zVl0N&GZL|<2xiFVL0!a_-8Arw)C|M^5gJ~;QTg-_o@R>MpX{+eHcwat8Zl2&a9$^5 zv_gHOo;yK89Kv3j*9xfss}+FB>0EODVtT&^}mH9@L!GzlkK>WIhwv9mrkOX%>l36(fjP&pwHGYWNeQZr2^K&_rk}f zH@N1r97U}VnaAnrk*F7dAK4edEA-sy9DE8`n?y5bhlh28F#@k^Gmo^AIK)J*-U8Un z*#0+;vHwBO= z;N}IdoDLFP-yzMwQU6(qDj1OkYN%MK#845wx=%?2bC-MWE)ol(*GB`;Tb@Wk%QkWqICN2&;bHw9kv_k5IlkB0m&LDWIlh%^jPYvR-2Q+C*RX$USSC*vAQr$DEOU--}0wLIB5A6z& zkwwCqRfou$Jf(?Z0%QD;{xr6>0(*mvk%5l`9V9-VVDchXn6B>C#JEP8{_HY0b48G4Gp_9Q`zZHdmjP45VJgz;tkik`NZCOj~=jbFC|dBxzVr5uI;fZB`F5m zW|<`|_k9qoNC(-&U?I{|ZZuOO1i=&F1TV*m%g5i3-tm97FKHaH(5Yg%MXSO~H(T1S zxZ@g?Rd~$k*-hZN8wmEoOK&$NWb6nXES@9QUmjhaWf~&1*SWH>siTwe#c(%f&`~|0uqe=5w$| zZ*f8N`}Cn03C6-am43pc!sFX(3amg}@ou{-a~Jr@`} z@r9fc+#xRn5DhsV9yC4Dhr#|cxB|(g2Nb^?rN4n7WpsC)(?LWC1vyg^h?xYI!XM@P zHC{&icryOOW66KCojOCQcnDYs5o&xx?Uk4%(FpCC`~#8z#w~NSFdSVW1XuCklIA?i zm#bUw#wU=XEe5|Ox@qvJ#@%(x`)>_;TVvwrZQazghdj%rMKz)XnaN#4$oTYamAmZ{ zAw+WKuGQuC$BNm#M&g4&me;Gv@_ieu-@!A0nv<|u%6uBPGi=oG0b4Z}PNsXT%vDpx zZ2b0d@<&O%5OgU-a_S&wjf`Wsz((Xzus@eXF4h|639?gb0(v^BV!xM{GPdP z)(llEQIcw3WXLTtD<4}iTWf1B6L~n<253t$0`9KYeak%R?}{CP4BPTB{YwqD^(#v@ zO>2jLcrZYbt1IA+=PJtU!-9XW9qRvtVBRGj$V~Vn-&ZW%@Kk30F8-69^^klL^j5q) ze$M6Us~I>9cI2(f$Ct-dK0B(PqdR?}Ohv3d2~?y3$gH3?2F1_fG#AH6BJbYeqClfjf7p$F_E%5ApUNg=HB;U)G_ z$Lwu#Js>g9%_u8h!P@PP+zzJ`=eIol8hOOfyDM?oh)th?EO$ylqn&<8kdv-Mg7H9t z!8ee_z}C$UiJk+Ajta_QASupa%hrM9T>}Zh4%-emB=2=dIh2!F{!Jk^B##)yA9IVj z=IQzBd_LrS`qf!cZ?c7uxBWC1G}IMwCnx=v!^e>Ue~R56O$xYYn?bV(Tzho;uXvWT zqdhIxZLL%#a8M=k`(NhZ-xSA>EXUXbj(H`6d50YHj|}D?{qAe*2%0!gs$7#fd;==l z1|Aula*;0Ie6ch!$m$q{ASvNbxfUc4m;~BY;&b3{Zh^XZw`aduH*Nb7FNC13OSjVMlJsRAspv zNH|*e)``3BLd~_)UhmI)YhG}$Vtac`)^{Wt484T9U6`U=pj$u=ul{Gp6b;;)JC*pu zGV6z>aNtP!=#Fjn&8xG@pE_-MlP~=2chKPCU(EWaOY6bQL;Mfx1?9j|&o6~nyLiJl zgys;RPdAIU4V8cQvm8ybB!a^B{ygAJDLUfx6#2tad4mD(r=z131Y(0`^Y#uKKeZ5h zk;Oj3&jD5|fk4pJ)%~AB!p4moJv=-V zHbQW4@c+Xj?Ay05J3IRdXww{M&36#u4+#7fg!&0X{Y9Z(K{WoT5tpE=AAt<+fK2C* zrvK$6tiQY3=`F$duc6@|Q}Y#j`<0EG{xx<~I0?hh|2PREX!Lnx;2!x5W?4zuDOyW&&M2QRr5_xk)dm2fAjSh}TQZfo&$dc(W_LK2>5 zR49am|H&gXC5(%moBuZ(;cD4`+X(ks#^*Zz10%dVHU745{LAq8@|E$W!ST`2(W$Aa|9>Ij?c2X! zzkdDl<*(uZ{au+C3J#Eji^3l8dBV6Y#^%G5%Md)$$;DcY3xW_0V-iUeE(ZYuW_<)$&ZX|1 zHht*9{;A>IfA3xDHtRJ5A6F(v2^se|q1foBLH49?JMUkD>C+iLVc>p*#`*+Sq#Qg7 ztbrXGJ6{Ki>^gT+)C6L`bQ?@qF~wMeez4tOpgEdoP<;RW(_N24vq|hO#9+`9 zt~f!kqnJWf&I_j;a8*mC94N!6Pwi8W>TUxCorZ(-0k?Z=psOlUj?ugC7EOYndb=Nh zXipNv;l_>2NCk3GOMwEL7TJxkjh{qR(2x-Ws%%Gz@aXo{Y$<~rPhjV2=r2%;j{{xE zL-QJ_1+ao}`n1^6zo+&Xr6Q&HMO~3uP-NA<2lQ}*rpdJUG$MHvv>PxjeY>qLxgT^6 z>Srzk1x&V6db(&o^`iPfOC*D)+mUZCXg=PfWCjpxqbxu?a!Op$?V|4XiYIxg$6=PF zNGj50=uwmM#(@WtXx)V~RHc$~Lj#yeZ4VX6HhwyUjn*)^sJ%HWyacK$;BPcMwGt!$>El0>s|9U_2{r#^GV#M0tOHNyMia$;mpZWdihU16d zpJkqF|9qJV-}UF~?6zGL@Wb2>f4>_ z-oUQX-{tFNm^LxK?k5A1o!;T|%mllsH4$MyCke1(d14ihnj9*QuF>n8sHSr(H)}|A z^2K<v4YCU_|~qlzBk}c-@+{J+;k0 zqRKtt8&A!T?ds!0LZ@rm)&KqCWgLcq9)2>a>}x%0ZOZ1kEccf?K1R`uFoo+_&y1a0 zB!Q{6O5_R&&PVRL#@d=wg`RHTh@z=%6$4~Du<~J6k$*&EP^*B0I=9T#i~yI`1EW=abd2yn{><}1BSoFQfdn#_0`;5NZ-Ysa88yZT{lY5bz+{8FB^g-?aDV` zKe1rzDaTFd!{8aEzA0Q>4yMQwc{`@8!d9>WRftc?P}X#IO5eaqn9s`rO$WXi587#K6Y!xIB_ z5<*)s=?M5OF>4n$~r9PnKNI$of`5tt6fcH&2L9SGj`6_)ubwSOSn zo(Fbw%rISmJ249PAma~`OB@HXJ?Ok#JFu4+Ldo%5!3uWkzl3K{kPULwUNKrEPRq(p zo>W(BHrxxL?j?8P8$JD7$jI?)m@`7SQWv&gfHJ7xA0-dTS=zT&T zh5sKprxt|TPX<$Em>w1)gbB;cJ*Y8{K5Pw33We?FCo0naK}<~6T_}m|wPj#etb#S_ zjY)i&;?)ajdX;j}0sP!Pu`~siB6r0LfkJqqqtl_{98WkZem%2Pzt0=k#(JEB?_|Rx zNf<6Ol}d>`R1_;B?b59(+sashd9bQB86uLthUiYmbqGpKM|qakzF0Y`1B9vq3A&G^ zU(2agm4g{!u-Aitt#yT$kX4LGYyqKZy^$+cI1VR1C1c`^Z+=D5%Y1j z!d?WgUtyv}8rYsCuze!EDSsQWs{Bz-tds~YlA~R(R}ErN`pkVfvY-c{m{)X|zZhke zj|*o4=}e$ao}aLU8#0aKQQ%BQyp{USmv>{CB=~+%t@$93!U9$^T&*y$Bq8d?eZV!x zlOTYR-2KnwV@}CopCj6hBn>COG?)VZPZcP99bo?jJfIfjo{adKh<@h|7Gdy=^&ty~ zId+^T=nIqrjH#CwnF5Gl5G)mw`L!h0M-I`TK#wqx`SQ$NV?bGP;%cE{1Pkmj1?Q5m z17cLXbtVRm06XF>-WSFH&WqN|SjIR3couzg$f?mLfff)OOUim!8T04)LP6iT5 z{-?WY#|A2eVpOA8Wc9t);Dlfy2}ULJAnssKR-unItVPxWiC1du?V5ktHXQ~IkpV@N z6UNwMCfNG>_tUuy=q3VWPyk~ocEM%rl?bGt@c3j``x@|(=ij>Au)Au9Dyzk@SjOSk z+4;C$$n`~6^+uXC1@>yJ^7vxGd>w2DE9ppYOow%oO=-vY8?0h9=w@2KNd!H1Jl)1R zu)8ES##-suaYfgu|Fai}sIxKJ_Q2k-7$@(Y+23;?CFcNb%}d0c3>N$VyCV(+|E{*v z!Z>cb5VdytwEaA4H4|(l1~M3~>tv^1&DPm{1mZv|sI1=ncSzM^FW`)PQKIaq`L+_g ztk5(Bif~5elaTT1I|Jl^1)}(y8a!Eu>R=sC+4E zVZim&&RKxb9xP;|Y&IyiX-sxI^~m_O_OkR3S;R4saug}}k{XDlRP2Fb9xmx!c1)kC5_w4^|CtYX1F zZ`l*{{Cf8f1C#_x)&a@LOGTCR?;0 ze6KY;*$D2#3~6Ft8f3tIL9pvesxA$U_-T0VmzdlTpWaE#v89Y3uPz}9E)=L1hD{z? zYonw&2W+D#ZDGTsL*OBx9>_HMgVq(F`G6}6af|L?!zFl)SG$HD@^d%M{Grrb5~#xj zYt|K5Q0<$2`zW;TU5l$2dM!t(j@h5U*arOw6NDlS_a>%Bk891L zeKUM}HbvecZ8tn-#7NVMEsNAKF-=RLuAeav(QL_bq z)a!=kM|6ZhP$fo8*t&O$+ceQq!Ty(X9iOos`=N_iU!JQCHr$TCOZ1cEGNGbGq(Q z{AlocES|BymYEtyg4&b(>wzPftbL@fDf#GS&8+s_iSO?&| zn-W6~3=}-N?16udL`*I|wVFnQRxpR$9{^Ty`w{U9AwtLZ*@J`lqvl{w5EA14#QE%O zsI?3uLHP*NF1m)N%U$ISG-L5u^%=Q=B+!GRe)ybidC+_LiRU#v(_3D) zLITm7*)3)Jl|-y##Y~h@x%aESm@_O?0vjfKc;e)CSdc8^wqe|zR_v)PGUv(bO`~(& zp*W>?u4`o_kwSnhPO%?a+{;8J$N_^lE3UQ{`bSxVx2(WBtl`_(s1{jtofufHfGv;1 zcY@}~ZC=cC$kxor^%*bpyQEL8aF55tdk5Y<%>@q%%8rJHT`NMhi{JdJSLOBJ`i4Ta z$qM{sySFpphv<`2*NWpQXwR3B6KcqaTXNkh(7Qqq6JKo?uTYja`>%`}9ENHxAgeXZy7#jW__EB&x;jIZj{<5D-QZoe+pTn^qWTZ%J$0nhkiyao&USi%LkP@@oLw$D7RSVdV`CDPm9ib*V61&CWDhKj3!wEb zTrT?MaJ!PO6nV2b`pEp2usx(0448{N=^R$y+yI-ZX$d&xwBw-&Fo6*q^u}KNBxHKs z+(i|yh$Kf|*Ya7Yg?Z}ZD z!L?|s->bd5(#j}@j_5D)45MtZR|oXsZRZ`MW2Z%<_?C46Wj43OqOo#%19U_EbbGkzAPP-PQYI?c}^y5WV|hE3MDhBkjQH)Wvs_5Bg@%M@2+ z;f5@J4XME?;S{Q%S$J2+Qgu~y*M>-?wzcHU@*3OZO9wlwH^lb|@OF#$9`czF7OEqz zzd)jzBKY7E(p+{5qKszkz#NK*EQgRi8{I3pVb+{>Tpwonx_4pWC<&V8WYXRD-Vd#|^?~3*(CD@$dPnqLnQPrOsKEyA$LQ zr8^-)vS7d&r5|AqnVG#P>H6>t7Y5N4K7)4Yq`@DFj?N}^)P#@QdFF9LKy4Z04hvD+x zJMQd>B2`D!z=5Hi*KTj$y{VI1YJHU;5W-I~a#@>6nnRu&t&8&4N~s$0JeTB3Z=0JR zODe>V^$Z0gUUmBI|0o38M-3UOB=Ec0eKg}CJ0j!3|1<(RMYu+?7PG|&mWhPg>lIe}Jt!V@`1(AEcTnmypU zRmfXk%W>Lvl>t3T@%r&`7ulK~Z>tbDB=>zcAD+SVXHtf4nFRHw#-UPMzlbAtZ0F)K z=^V$bp)^pC7~F@_-Brqf)t)`0MvQ}7`V8(H#Up_6_i}95@&6$9!1T143EPKv;7+5s zmN5&en+wK@Ev|s&gYY~^BoJEwC|y*@1!awe`S#7Ktc5l3XCAwyH>!&|g2acD6y}Nz z`GhDJ7X%Fj*0@8-^-YMUZ|?wmkm#&d^e`$x!eUQc**<1I0FRx0{`XCi&dlRP<(i}s zt=e6~@3g%^{jzS7&pKMqTRf)uV;)3f~$|L?@7l|sNN|i zOoc^QDsl$l8?AZnzS#ZHpOk#;47nJ0PJA5I0>N4gprZ9hRjY9@C_pFMTqOr;_a-Ui z^7J}5@2k+Tn(h9O*6FniuEU8|jQ;vHw@G4eiPhpY|M-y=M=gK{()RuA*v|^T zJd(whqv;M-#wB)%xE5{%9rMis6W{*COJSAx{`&sXmU7b=oyM%G`0;}NNyXi|tFxC@ zs6{$^Xs(79R8>zE0HB2m(}j^4+uakcwx^l9z#LlI6>&HC?av_}O{D(XHDG+?n9Qh< zos#CE+DZbPJWzuG&%~=jRu0U&BCrqlkM0b2BBmEp{9RNERL?gjyV8P8*XKb=S78#O zE~*9v5rTC8j1_WQSzAM}qzJxqDBob3j-UD5wT?lSS3xAIe7P$pHXB zJXzk zvB8Up=;?!R=e5<9PVFy6^_x%)(q`Y<9XS5w6LRm0t;>Q?+v-KtR=Gd>ho=-uA3wY! zdcL2e{|_VE+w3mNZ_Q0MK1$yBz+pau>pwQxBS!Ry<+d|YwS+M#{=XIC{N#_X$C3&ztIBw~yYWULl&)E@ZKE zR5lvy++y+VxI1fDetFsNsMFolG|p5--pYcPXuoNpHA~aN9e;bsOr#=Qyr-5w98jJa2 z=U&F@n7CfVHE3q5iMjW+Z3>^_+SEj+lan6M*(4mwPbr zAC%b-P@Uq0^Ck!?4(_TzgfItgTQovUU5#wun#*L(pi+^LQm1tK7U z!eRk9z7j~_EZBRU0eP@@m~y-~{b{i;6{Jxs<4;GUz1oasA#sa&zxp(=|`tQD_ABYU`^IKT^qE?zD~S;A11Ff_EgO9%sL zeY))2wrwc3Ew9a16YMGihx8QJ+uW6spn4Qm>)W<*m1_MMTyjMLMR2?5iO=&Gn6sYe zvy=((ylI}0UWvsLC(0TDM?a8>| zv0TlqW8g|D^PvXGbecFH!<7yXkqeX%R3OhKcVjaE%~PyIaSU&g9KF1q7u8kSJu0KO?W-i4q!4Z1pLvo#>hq?9L!=^(0bN5y3%{qg$PmCL5|D%*NT!PZeS4m_ zG^8Hq>BF@7h3DGLf?OE6+Je?nZ3{}Kk(1(pms7Q^gtd)a5#9_T(v^r5Wh=_26czX+ zadU{jvo1=Z<4x^#6f|HA;tPZPsd3LEc{usI9rf85-h+Iu>lCx0Fu4L?Dh}#i0nN?A zt-XZ)fQRsxmrBR-m7WcAXA9vlP;k;luXPfXy3BD{fsBno+yn*Na9|=IWCqYITyYT2 zY3<7bKdD!uZslRun9+W>sv^~uW(^5=u>Y)LbPp#oleOX3^c{TehBLCknPI~~P{J3S z9+77wswa|BhmS#{$eQdRFBT05W8}gZK(*!ar3zFujYY<>7}!VC6$^)UbYrdgz zhR68z(fp))XGXNxqVO#QoDY%XyzN2?ViatbRz3=S@f7WI+8%U`wI;Uu=jg z5j5E!-3;Tp#sJkN43v-^FajBxiTzHMfrtoc7MS zqno@JV1zZ6y@c)D1FXY=Hh2NONiVMP*zIH`B5zD&AC}!SSXXw(bRHDd46F?e7LYuU zghGC5T;c3}$Ie>CJf-x0TDBOZSfG?hSUx_99M&i$Ho z#62HaG(M~wMztokYM|K0IMdq2QLTWy+fl5Hm-i}x@wq@P_%4D>dJ{4b^dcEV_5#;c z!lTS%e`RnD8C&IDYsy6r+C_1jpM#cdK})}P!G=c}^N?dYu$1_h7o(Xblrl=s&Qc+i zkim-VLAp@d_7`x9u3Tf(BRB8PbCJxu+ATh7sF?qTOYS8EE|0zgvJFvBxiGLHotwSJ zwxP$ewI|B-UzYw;)KQ`T*O$Z+0@#o|%xzxu-OVHNKtU(-%_Q@&->0+8%T1HmCe&?T z&0t?_;eMv<96C307t9z2PI{GRC+^5oYoKINc*HB@&v_=F$I*rj zE=vIN^8hs}a8<}iIK*6F08Cq3+;b=4Fpi&;vmQZ!-gMsRMdU_`jrYePeP$sO285~Z ztqpw-s^wm>*&J6oXmua#V*|%i#|I{fn_@DqmNOhHWApg)xDkR817yx)YD$1EJrF+$ zB!CX33ZT8`awBDmP$F33*zLaRu=L>lpBl~sV(f7?*Bbxo)v?!4_9J%X11td0$(DB! zc&fb5J0&^_&A$$|0IE8tj8ypyba5H6P@1NMLjmR8;>S%@w_%u8Z}P@R=NxbZf1E- z-W$LIqX^uyK(01^gWRL)6DjL++WrUo?IQ#$8mR^*`b5Nr6^P%*@Yfw-Y!TCiDA~F{ zXjZ9eqD#?;Z>aLezy|T&=qYe3zw!PVz!tt?g#nC2V*BwIUt>;(Q(3mOE73%@euepB zOG@0XR3siWsUws1a2+YZp3_V(<^9_~RF~Jgrydk00TDQXf};ee-5gp)wmWzNi1lJU zB6XXg*ggbE<&Jh3wOmqgq6;n;^l(O3RWM^5Z0I=UbGYFvOq#jd(P_QpoTg z13S4F8f`jkez;OU@UD0JQBW^XD+4&53#binYRs%0-<^-~O36Gx00%su6R}v9kne&= zJOS5-*K9@ShV#dX!p^1Ww5-F+^|Ww25lq?!GFo%*R5`>GL2+kCdE!<$Ju#{|kvR5j zN(mmP#R{Qw9V93h68QN9&_~Ky(+YFubMk`&^2Qj8EAPNf<=*!ZhfZlS9AIPsczv_E zU|SC)f^Hqs39;^p{LD~0x*O)75kVaLSA|>6@VZW)qJ1XFi>#r|+?2V?>zYBA_!^3o zAKDaNTTwnmpq8i(_n|TIB9O%xc!=7TTK~X%y-m;*rXyfh=N!b{Lr_mpqY))5_y9AE#G@nFs{hLEk^!x|{I5~@D4S-Rv?T_6%xL9zJd1*qw zSjrz0^Dsui?MbV;qXlTiq?xrOAz1!esA_Xpp4g*sg9D4cEMedFGTjqwbCm^#S8Rwg zZ*kkh;=pT?Fx6uSjA`!n(!DV+gF#SqacWnm%FC7^4HZ#%^Ex2xzP9=Hn7#DgcsL~o zTTaw?M;tG+I&jdd)#Metv_E(v0mDtF)i^x{ z1lmWtJKo*b$1GFL$$DKJ4v!(|D}n0K(=V60H2Z6QGARj%NVDW;m9wlbHam zAGq2W#Ix|AF!yab3FE5GLK{ZRd~~{owd-e@s-f%KiOg_H>MCg<(xI^{e1}EBEq8dJ zOVeD`wpQ-b5HxaLe`8$q>zKN=DS)^-tN}u6&Q(+yA7q$; zby%?E#<0-$qM->X>cWZV9UQ#b9e(`PO8=+GsSOxhs(f%N~$NkIY`a-eIwgb>G$N8a< zf1J+@hL{|m&uVn=6sg{(|Ly#K{nqr?yv**fvXFBO@X(i?9yh;%r#yz$LTDhvR698f z;XI-Kx;D0vF4qq*_57>KBfWeDS`R4Pay|G0IZLL?(KjGkR-A><0ogVM{;2Xbw{|sK zsC5!ZdtOD!m!PNX2SwQjJ2Yey#cWmDXq4H4xVnkcy+AqGe!E z>8deMb&v)RTx5iJ(pfk}hrGuxPd@VV65fF21;<(Ca*&PvZ$*$mSWTu{g+5kE#{wZ5 zfThNfl}XpSRlx-00)b-^u8$i`WW-T7Z6!)UP0YfTX}_b|(#R49()!je}<7_jfH4(*uYOGOuXu$w-^an1<_HB@HQ-&y(FmK%iw2_C+CD<9l#4YzA)fIDM< zMnyAehGuKY`;wWgG-zm>NrH~A?8&R3YlLDHP}zB|Qxxyfp*i2W|7`w!fkng>?#tA~ z9|q4pD!F624vxWg59;K6?Y{o*jCrOtc*os4k52XGUrwDhj%EGK?_d99KsdS7_7s5a zAu#3!GLA`fKEJZN4lSHxY%+^`%)3T7+}V00a4T!ox#yI$bT>jkQm>Vj_^&-HCz zP`#3&hu&{lu*+=M>3ZCt^-asdw3wHL?@70u*H`nIutgo&aLwu7SaE*)qQS982fTM% zmDQ!b9E1bh!f#rYUuj=b*w=e|$GVlE%aK7W?Y)z@@k+&X`);$k%)9&T4pqG{+e5td z_%;Z?T6($fq2u(?`zMyZ;DP_dZA%H0X#8!>S3Di>3J#mJPWxKNZ0B_aM75ofd)uH> zne6Y|JAHoLrrFK>ZBS|7Orx5u9syYpadC3TO3pqWhWAGmQhtgH&q(c{roh08zkNb44ie}p5a+hnL) zyB`U=_6Ntj7Hz`3s)!@qA(;T(sWb@d_lsAJy#>nWKSkfss=ym9+&HTgbo5mJi$6*v zw7he1({0j{e(#7kEBULtK3*{Q@%uG)WPa4sS~a=mINQnFCq7D=9X^6J{;rC@!vo5y zx@$^z+t?L=>pJ4)?$K{IAC;x(8ZthCDI8I*)8|2B@oFCKI8cSQ7INt3m-Bxdm)$o1 znk>EfwQ-x%+mOq@9$dNk?b0cy_q#U#{rHD1{{MoIfx%z}1%>|;A(KUReSCZ(BO_%9 zS!!zP$&)Al6Cr!{FG42w-x0D`K-{`IZdDFF2h^Vim^_A<$PlvIK$~HR^8*Fj_iF!> zBKtSEOR)PNwcUD9beBA(Pd!>jkyV0|F2Mf{?w*DoIjj6{aJLnkbXhyK+i?GwiuVHo z<(-|^ZQJB^PtPA@&oyt#e+GAdghjt|kC<~$n)W;LE;Q+Vc=Er^-K3-+w13OHANTw> zoJ^r2OZ9)^WLWGUZEYFd_P@t>eKG&CWZ@hB#mRP={1;1h%XO{Ygpr zlb-%ZR^DYJvSs)GEbpGt{;%?Gu71T?s|s0mx6vxE-#xp-uR>Pa9SzQx)pnm8uDG+O zVktHIKS8o@$FpCa{I|AS81`>!_e{*_f3jq<&TiN7e_68Z|F^SST3Y&l1<5}A2S~=@ z{Q2*Z-L|$rSFip@WVc{c*4e#N`oDB`U$%~ZxcXl#+5ZNT4G;ghbLY?W^q;3s|12#n z$x^#7U;cUj{?FHcZ~y-U$z%xGq5rQUyA*><{{tbbKWuuIy*+9u&m#&S>?MC%&5oWv z1!(J_*C-Jk9>vF=ZU<3qy;8`JI9C+h704t2Kn|p;AUjK&6oUaUENYqH^7OXfI}9;; zb-yPhOxYqzxbl#B4SN78EvP)h2m>jT3^RPiW_Nmu_J;%TpKD{TU|=}D-6Mtv6tEcV zF0)^B_n*+(a{Db{mlwE5UGn!?+LGKcR3DpV7JSO?i$SDL7#iS z$X|T-n9Pp3h+EDJuE&T-2egX?X{7T!K}C$1mGgBexjhaeJYHVoOLFVpZ>~5KM~OH zB}hE))L9)@xUW1`zo^W(iG1|17s_-?_M3S!KDZkvP%}OVa7C(YM}bBxrQ~Yi^LmZq zQq}YbQ(&{Mgg33Ixm30ucJSd6IUhpQj>}d`e?e{stjxK>RKjr}Ios?vMOA9oQkw5f zgsQiJR7GA9?cyU5mk(Hi7`r6hJ`6Uh_Q<1loqO?@z;H>tBnfN}VD#ZyFyy0G9j8<| zvy+(dD)g)1xqWx#-j@jZX5Z(`5dCAjGT++^>%iYswZ#VxhaHvW5-ff!lk+|=MN|PZ zc29yfPQ_Orx-uEhxQKimTp=djdiwDy)TUNkV%lr)PF!`ErbcJpsDp%E7+3*{0netQ^m^uxDDv>fyAvk7PSeSe(Pbn*L>)N3EU&(Tkr zC*BKxbo#-RwjzbR4$OExb?q5L@7qyNu=ton$~3Z2Sx`sQdRz)jE$jn}kCxlsYYVva zlX4~`y^7n481{PTxqp9FV0FYVQsxFYxQ|qw->BJZ7p}rQ$VXQ)-W1Y5jGS)s70I8qxHWQLz;o)Lg*2{1@ ze!TC3qh+QUYRG`b%-6EAI_s$6rjoGA+3Gh~F{Q6*E8lr9FD3+J-waX_%9b27T{Y4= zP|xJhX9OW;0qe8I(Kqw*F!wxYROh9K**5^Uro^2O#=9A=R5;kPLX6`1Ad_?UaPW@M zy&t~L1wsZ`+PomOD#DP;D{rWEYONY^U<5PPESnnYU@>Lxx>PbJUCF#&=L}49dj=Z; z&{69^d2IC4$#2YB!0ez5Vuh06fOD=GyL4zcvNr639Y>|wZ->fZ7SfagRKG-S(vd{k z3V+o@o|ZD8<>CpLkO2*eZGadO!wAcVK~y12^`>|N4%1aUOLA8-^J0c5)VE>Ly1HqD za6+oCdOghr;2$j69aKI}9y!o~h#8Lpz>Cfd!%T>*i-Yc1igeg?89(Poz$gV0!AbHhSXCdX z+|#OI2V(%j4+ervTw$u5r-9xW1{OZqun#iW+7Fj>T}_rXh&yHTMgKnPNAt#U*t z=qd`vh7AXaIU(sGc=1Tb2}@SKG45>l>Cgif6ZSAd{XlQcjayZ7W}w(rE$P{6 zRxTWADhfrMyfL&swRMn824clXxIS#f+~PTaQF zDQNR$>V~q4XKn+&IiHKwNXobzYxlu1G9^07C=edR1MQvs9kID!K!HuOFg}iqiAiuh zPvNsJw5>o5%7{&g43;5T69cMm0hCQ>2ae_D9BrM%cS#|d!~Eo|Jm6^a#adHg%wXtK z7p1)!t}0^;m^Xoxx$%-Yikt?6?98|`QzeUp<*=|Jm%*P42mQ|6;uvvyuljji0lqk% zZ8I~^qc;z#IBGE;uiK&`#?n>SYfTRLg}P?y(l$rm;=gFlq^J%@6|(m~Ds>|;RT`W3 zDSzLS-&7da@b&7ThMh}LpnDur)hlbOQ=FVI-vt|S7-}S5p~Lxust|*HkVO&@d-Nwf zke8xqsc^)A)E-KBp*0js{&DlXgm@2o4vN}jeETj{(=U6HNSwMEJMCKFYwHq zK#_IUj-}bwA?*+r_&EmN&Nkq zI!J+ZPoP+i13>oDd}Kw+K-7VgVe)4Hr&P%x_CxT5H9YEprz#Qty2;VMJT^)SwGziC z9XVzujW83&qUed^*yD#IsB7OL!6K*)EojH#Ef0?Ddu$lI)dk^0lm8wbZG-o3Ain7QoUhazxG#(eBK}-puXT9S>w(|X8z{prz_#xim@hcz;z>&iq$BuPDg1OY*0=o&em^$^`Hf-mUjj=O;?452FD(Dvact{sWm)E!+f-tqqM$>()BGhYA!_%MnT zG_eari(qxi$4^+pa_H^}1d?|nIz%6GN}MP23ajGbc0b~VY*8Ju@r{164ii~Uck#vt z2H{yoH97hT$ZC4pHM_uQaZHWuytaE!MzeepF^fDJ5lV;KQdnJwBTB|V*S0|LOt31& z8<2ilBh4em?#QxjQdV}3t2pNMu+y>tS&f25NrN6_ppTGGPpU!B3o-VFMRlTec(Qos z4;(ZcAlG*WCIbd80}z=E#54Vqu|f!oaG?HL(9=?2Q(_ra?4(RN8jq(KWuk<_y;`Bz z``^&&w7BS75kCcv_H)f}HE-j*WbS zma}uMwXej87RG_`+K#SQh zYf|>Gz%gY71Xn|t5g}Z9lsg3ZYAwvx$`tksV0Y0CONI!z85MV6nae_#dSOfS$70B+!W8=1g=Hw`QlDrIK z0_F}&`n^y%76mN)iue{uAu`J_G+%*b zXyajMJ^f@o5w=efF#@k1=R)ZKxf4Etyxx@k8BiHi^|U@m_mvR7Tyr%F>lF#i1crajC&RN8$k?X_g+lx=@`$_%1-w z`{Z+otW!(h)2i{vuURNe8P@?1nqXhjt+|vj9>nEBdx+rD2biiAN`$m(d>ULqt2ql* zr_Eee(m{gr{L_}!K{9rsY010TqfWl%sGduQ6rS?J5sJ)xA&UOdum zEwYCW43?xyoHXt3hIJ`KG0AEIdKak zVq}L1;g2eiT-0tXAV7o<+)e3?h(q*nDwx9PP7<(?i{_|B1YSqSnmTQF2dC0#n*p+J zI5L5s>N6466$Yy3An$rZFAG)cg+MC@^b!^r)9UE90@*34Q4T7cmG9Xz6jN z4Bdp^UL%A)F-TC9(Rjq_@gcciS%VMru`T(sbVE?|*}rtqv30hcLRE2L}-k=d`pf$M?Bg~LmZYszm_#&$q0+I8|#aQT$+VYGgSBs0>)B1 z!iXPRrwU8rQ|~~_R+kV}v>mcMZ`(0X_H}d?K@dwLqs5S`zJ≻MieUHv{SR=GG|% zu~~87I5@lOO!;PoA$Tgg$7Xb@L9U{)b;6T+Istx^PxIC(a^ZwkGoXD-d*cmI%?uef zlf_#*eM%jAXl^1{8+!y5&ayu@&IWgx4SwG}^!;Jhj8|fln3}_v+f9_?Wt;;0dOLtS zF(}Bz1en+nNaMrL?Yj~hv#}hsUV$V^p!QMlUOhOx%u$yg)|+{79GV=el1 zZuaZF$eFOoa<~<6>_=}wtO!maHh%gW<4RixZsZ5>!@P9(Tb&g zOW@Q8_FfeUG@9;XyL!T?8l|gpkB+Xyh)>yZWLW_@X~kWl3u2%NVmeo0Q!|OOyj3z` zqgd@YT;=E}3R?@4qrRCK?4zp)WwbDR*tQ{va4EFUx|Dci6DmRofX0h&ZXTHa5EAVx zoeZFXj?l0oX#@&^?mGngMitNV3y$ zq4SX*G5wb47W5lb#D)^b_35x0v6C?!v{~3Tc;fM^4nUC}b4!qy9|M`4bV7{_X99+=Y?0SRQG-#r*D`E%T+E0F^=y!Z0>%pk zS~+~}Fn{QYEfD+@5<-U_KMvO7g9|s9I3f|rsDsV6@(0CEkJ88XY`_fZ&4oJNwih1t zGDpdUgK8=r9K@-d9@@XrlFhXz_A5vf=pD0V`wmK?rB*t=)9ent4vjf=jm|zJ6 zU<7ocxnNN*C122hD=@9PeWaR>Zz-pyV$u20QM8;me}3Gn_Y%^PlQn#~cyR>=1p=|l zI=?sVr9syd7;-su`FhD73grq$I+!kooD?oCd_f~bTiy&VkR~B(jnDx6kz>E`} z*T!PhA|4J=SSu}G^wWh>`JL5^&E687<+iJ(~-5>acfd zA(C_VKSQrQ0M3-Ynz)jz9txlIaXQFI4WjRV8i7(Qd>b_x)E|QErXx<$5obhTZ%N}0 zKDglP)Eys`Hxjx_czGuv^Hb<6SuWyMs`#rmaGxpAK)BR^54&*Au?&T*BExL);LH)e zuUL+T3cHpAdVCaqneteG9zu~{U%VOLdJLtf1qEz?&4fUH?t6UQ0{u_jJ4L4K;rgeu zO6c*ez-E4~pT+(NK+?K;eES`${)dal%v}yBOI&qfp!M+`~thG@U~h_>`dEJRjQnodQ5H=Nh9JP!QKTeLgQR&_#E@>8xwqUr#%fs|{y zI~%-Sp!Tc-)zj+JByyXQpKHhvGRHy@1HQO>|Btf1EWCA(U(Y)A#*4QI;}gKGQmG?S zF6%^=uTn)f1z8vkFDdj5R{r#9Kf2~8Xa|28>(XLD{tH6~#WCRLr7K5o%UgJ4j^s~F3`^vS5C^9re6q6#?n)xX4ZrAjI7brD&;D+_TP(1*zf^&`s z@%%8FoZ!|kdEo7ErENV@coHKum?F115%qEILD-kMPE}|q|I1+p-17TES|Tt&^eyD~ zYDm!%UK^MxMPW<=0ILZygbZrnHIdjBQfV11B=Fn;eahSALbY`<}bM*-PWH98I-lhs;6_yv{;%)r&uRubfmpWwR2x zceFWVXWwVGfzo|=ppy6Ayw72prpkAZ=*UKUF6D&8eXfTR^;L}Hr|7NRN!8%m6r=?+ zc*)Nw+NM}!i+T7qe)RN)I)$OpFoc4$o!!W{JW7>O`t8*9tsVm}<aE0moZc;@W3|(8{>f^eE8Cd|jAo5~IrxF?`o*E}uocQcZ$u3d1TTGfrITY-o z-*)4ayfW5L%jatBlP95uN3qz=G_38W^Ig9M7lYdLNwqmo@Fx^b1TEweuEHn^0rWHj z5F*c4BAiZ|Fe|lcW`Lk<-L-|12zsVZ4$ED**&TgxYP?Q9j@7_t8d4WHEGlKN2OZma zU{rI%A#PK>+~@oeCP7rEbLa=4O?lwyp30K%o9Vp9_CpX!|Ttj?{(-Nz52!np5ELUxGjjO$Q|B$(BO6# zfgcA~JLx_WSa7did1~Zf3>@XwF(VTkm39K|R~k;<4{=qjoem0dJHC{Q|9EvAqvp&w z6vUqCsV8nXP*jeL&L^hyzRy3m)@~!iZQ=eyI0^$bPXrC~C{(#D%ObmLf0pjFKKgaKlC()L3$5nUQ89 zA`U1vefWt52>7c${3Khx{z{AUq^CU#ZD^cPu4~`(Y8DfNfId z6IAy&H9BtHf~+-e?TJ^gx<`Il;%E0}QPmkyvgo5k5iyMr2n}}rXbok-!_*M7v}+V_ z;d!98$?UvpfKr89p{fJB7R>hKf6r#Er8@mn;A-qu6d=29m)b~(yA&+jg|2zMcQji~ z&BM)Pl74_Qfy5;3Y#zj}XK|o4;!&kVpVQ0DSJ^Cqct5lSh;Sy?KkzVB+7P-Ec6U1} ze|}J{gTXZ-4M4PJfr`<~B?{&0*Udx&NZnjlMMS6Et8cQY0BJ~vM)hH-3z5Y0=Z!nlKXVeQr zp+emOzoGN4vRJSUt<~RJ>o$K7>E~n}Wrx>7J3j|dT|)?_Rp z!qgxYCo~N*NUIRFF)5UpJ_8$2^Uqq)w<^zYWk~q>VQE-B-SH=(yN#J2$MmZM?VFF1 zR}EPzGeOBZJmt6cL9VL=5L!T%IS1~?)B_QfGzE;SRPu{BiiQHjCKk0Y5DJeWdN1$& z-h-JrArFC$>v|mC+pzm!JY1Xn)MG0UYE3GzY^RL?Lo1QtDpIwJcz|E-!$53>3H<5f zZt?%f~NKG*Et*beM^=>q2iuH&NbW-($TmSt=F$U=E z-B;d`vM z1@CDk2UX)JH?@%&wOvEj3_xs3AijU>0i_>q%haW3TLAmo}w1#aCjFK zIoROx!N_8aCTHHkGV;za3DpYS^><5K`v+)_A%qFNAh311z7iQBbtO#xTs;SL+**_* zeYmQ6mnG7FpKyQd48{whA`qi_oS;0dTUB+UF){~&nf6^~3 zMl(~-&OQ5TSqV8W%syWA==Qd`(5r8DMfb*! zl?UdUNFgM$BTQu%O@%`XIesa_pzUTXfkni8Q#uU`91$i_vYWvojx;%ZV&hQ z{<(gE(Kybc30J>p{N0lG?gxL!bLZKj-y!a4&8o}mPOC5GNdeN2#o-aj%0`kQ>D`A6YvI#DgJ_ucrl(zOu~5pwI&i32aRm29Ka`D-KOC2VFpYQA5-T2}^Hh2l(Vh|V`nQY>P&_8r!bK1>+ ztoNcdGgPl!;ra7z0!U6gU=NDakT0z&5N~6P`kd_{KKWgL>duqHV50MiGz(p$nUpIKn3c-YwYpl^w>SLUr z#03b<<(7LsNlKfd&m&8!3O<*8g#te`jYOv0ywP7z88w)Hbq9BKBP}f_DLaIWdNU67=YfoqE}nL{+)xSC zcLemrZ$4l>a+>F|tHPyn4LCb#+ZU&0Do`{_E;~Eh9Q(z6TV|twByy7u!l4HoB7r$C zgK9NhW`=UXf{Ur`7h`%ZMhm$yR4%XwI?-u%r&T>PiK!$4C^7&@JX5m{?)s#rFH_k< z#5z`{!=kWWKZcMcK;!imSsa+b!e7|+zSMnI#j{SZF^;8L3^rJ1;T5W1yXMZh!lhSo zA57O*)0pPXxy%yA?ow{WUa(%i60rwlNHb)KwFnu?_EuviaP}DmP25+wk9fq+zWkCD z=Q9rJ&fW! z?*l`FjVQI~{&7QHSfsJJ9MFej)dIuhgTX zAXa!%cT%%Rr8uDspu}f)&mg_=Tt67ZF3GvzAhVvYikM|%ngO{7Z?Ee0CAQ<;B(|Dm z@b#O;E@*dlBHSt`B)d_L_(gHIyHm z3Nqk<&qgcWPSby9Wjz~n+KQn$(hLnCu{$$(COB~KSd~Ai?KUwmMxRHqx;Bk%c?(f{ zDR67YLjz^4TomV1@fNn2u_+lOiyfK7Y46eqcxU5gz|iz&K;bp05-+xY4+K%nvKCed zL>_D$Wf*%mUzS2dfr6LWAq1#14!WwF=ROAU>w&nC$~KEH{P|guBe69g+w`^o>;y6v z4*bMdV1%prrbl`CyO_menBg?6#1QIOffWvJD&g#{hex28_siB11@(wZF~I-veOB%n zbvS>cF3%3dwi1B<8e>z*s7vH377yqY%HKT8x?hF%rGOk5)0@62IlTd>Ewgf)p-LTG zzh)4RPiblUOTga_7X$9b6es>>5y!fn=svABf!+XU-sG)zGoCtyCGFQkzv;s<{2USs zI^6{M8BhZ*$nfx#>pz1Pd>8!{nK}yUQ){wC$U45)S*CcjV6e$}PAZm5ZRVC~RRw#w z>6|Wvqh$CAhk|42CFO=)2b_&m*tTXK^sO+2q3Qf{ntU2$&G%Y09XQLs_v82N_(@D8 z%4#bPY$^Z+<}vKDct>?*?Pk^wJ>GyGPi>vTiZRDomXd??M}8FKQl*e=0ccu>oO+^w zp$Bs!vJLi4Wz|e=cR9WGHMiwXH)R&$-@~z#@e_FP-Ggovzq~{Uc9zE`I zD#$kw75YkQ_U)Sen+QW?u%E#qvRY>Ir9FPb)Y@4VRSNX1_x3b{8AxoIdR;6O-#CLU z`(QV`89sLyF>1-P7~_PUDHnFZI=H!~aWX6uWSFaImI=OZD$o=H&Wiy~Jz$41I~N#) zodh-^`JFfp^F2{?ZtBVC7zb>t)oBo2!GjtTh4oT~5e-aX$lyG%8sPleZ=8d1A(b*4 zJH+*&HVhmtFeLu9ep6d>*r1XsVX*`Ntbm~eC{?2abhTTQ9l9*2didE}(VHAxh)J6)?o|mu5dQTw4Ip#_bqg_F3Edbm8gsPnl1+ zhx6W!z+wc?3&>!??2b_e^JvhyMT5#Q5lM48xC`gmglnyR+xVL)v}|U5@5&1%#5xq* zOlvs1DmEfTvJ7OzCKY4?m=o}2@2Bl0k9Vb(HGq-UuJYPt?a6Q55D*YC zQ~^;#Q@{o&f;}oK)*B0ow~8nC^Souhdp~=hebzer%UNfweB={rW|En?e%Ie#HAoD% zWPxU6#1}&o|8ig%!;lLU#O@Q^ii24?aDBz*35MZOBPSP*Gwg2)tMWJDzA8sIw4(sX z<|x7tshVHLtGrLZlmW^DWx`z1oRp=O&88X&6a^ehG0fo}S6=xfNjblENNGt4O}(t= z`{NN`>D~^!0R1Q5Iv{*fq;ubG_|@M3FEDT( zrC$Wmu$y``z4Z294nA7B=CRblg?(U`%H{o_xkysDNqfsF9PeC*j48C@S_}tNXS0kC&4#uTP;g z5Pr=5z>z>j?bG=Vd;^Er{aLo*4sfgH6(_72t?=YO%MjWUZXxlWLpm~s%UwN=NWZ%_ z&bxGF2H%x+?jo_qp%=CcfZ<63Z7JN1$or5KX##gg0tL+lfZ7OXAy8HaRLm1Nb~7AH z)-pXQtD*Mp>U_R!IPD>;gB4;F|L< z3c8h4`(mO<-0B8aY^%5EXr;QK7==w)@<(s=-$FhjgSFjx!EA#3=5OZIV*JZY9bTsT z)C=hv9QkgjgA)1*a@vsbOodExtV+G*efg$)10*l_^+WwPT3EV*ke*S%{rHM~Nw13i zQ#n$W_RMitBu9_T52xtSkf1(E{x&C8ey_&iY#FBTBX@2e7QH?{$}`VKntO5iLXNKt ztD-z=_U3J)7l<8UryPwm1K#b)+g>i=+w-23jTax4@)zpBxk_Q1lA6ZDv@`oJTgk7x zM_CjNUfvaaeCdkQhlf$DRWRfHZNyiE$b zlfKI25_%>a^c8t*=?ga?!p!btnvD`1rv>TTP}3dT)Q_>07&RS)cN}&vhnB3-x@rIQ z(|;TW>>EIH)@ogRnq4=z+AA^i8Nxy}nyR z?^Y%idAa%H8uBo3|HU;g_;OHSLknvL2YH4$v)7=r6$Z;Y~&ma|xdc|3}oq-UwI*Z*3s zdiTD)?5{{s)KRYE41B#;BnJy~E`zT-%%Mnn4k7u7c&^>-$~W_ZXdmwH_~SeuU}WrU zw8$c}&*BbqK~RA+t3s`x$HWFz{YcC(UA!0VrLuwe5!egH-bN-(DsaZDrbVj;8t59*OIt4-4RPD3CtRR zb46@ZMwXGr)~v(RX1duEk4roX`2s%2n(@;+xnOJ{vn$g)Vkl>?&+VlHllJ4Fe>Qm1 zVnyLP!muZ$Km_l4aK3gX0X>&z)38JSO}3f@4b}T>Ojez)1*kG+4QZ#Pf5eeF=^PVA z>sZUlk{|O2W|Ne>NUT$St3pl=(^BWl(YL2A)yfy`07z0rCT^#liz{S+SJNuA z9Tnihdg4<8i-v=(qAPnz6Pcr-F5Y<5%S@x9#L;4e$!kjHWC)*6bxj#-rMc!B(Zm)# zJ=ozQ=fovN{#i}IebkNx?3uYnk@bfSAm&jrYOaY;aBLbsMp)Fgc z+g^;lO6C_v#{|xsHd;RJGsNlC5^c9>k^HT3B|C2mo^%Jn-Edrtdc7&f&V4Fpsy4bT zJ#cs|_{(5LO^xT1pM_^`mzww>r`q0WrQV<3lW?u&?Cv`*sNxx|T=QxB^yuI|?F>E7 zI!#ijSZun7EI)KFC)x4a8r3RDw3eM<%U#vOmAmbpR8ddZ?nSB93UKtWfnuB1zH9aV zE5H8w8NSXrBk=jR(AoWx$^&hhH9Xz@qx@?cfdw#k%^vNVA=938*um&y?-KbYNlZ@# z3n)HGgdh~yj{18Mh7?uOc;{(;ue}+A8ZlK88e++Zx!GOMOxRtze?twSR`ks%9##Mx z4(HJb*l@$B(_f5qeY(SO?wJW`pAajHonHA^UUP}d)u2%`JW^?)d;xyrNRURs?iXM_ zf!_Ce5Lz!FSp?sun!~0VDGXva?O5c=&nlh`WV&?NgMTF`9YR z-^2;WSLgePhXT$VSo^weLuizF>6;chu`+CC5yJMvDSv( zt&*KiEQ&xx~Xx|o#TiYrO0DK zeV^th6Xd9cyRLe(?&_`^2bv=gu>q+eCJ&q^IJ6I(2HOzB0Fk)5_UGD_`-`4^8q*%# zo8jTV#?(63xRVkcHTmtuvMzd7T9suf<6CHdK0ZCN)R6P6)gUB zDw#mg_aJQiX~9+xn%~*FH793t?{mYojmL&D-ZwJd5{9Z}p_>SiP0xdIHvPBcJK1|g zgU_DbbG3RmyC+a%`k>{Teb<_o!cc1p0sA|6me>X5o^Bqpa?Ml8#peeemdHoh4n{Vc zcMoxznc1sPu8TVRwtgB~6GQA~x+|8gFq#i@f9Cq-o8|H0IpeV$|IZI!ZD==)L70t1|Zh!#V==<3>w-5u4-7khdK9*Yw(qfSYIBivblZ8 zBD2u^Q35imIlN!&zR%b;=k;}F&<;5ZGPW1)xe-EvW&{Ga;DtF3WxPFmQIn z9Txu70W2$7+TIlI?xQ0Lba!ASc>2E%SZ8{>b>3DTN#j$`pzTA53=7Q{4}iR}^P#mR zK>G+}nK@?NhBs`gqDuWV=aC!>Db6Q&C`^qQn&%h~L+s&&FM0q+->4*~-Ed!n!UKb@ zcIR^34M3@W#D$mfO+6y>7}Na55uYyLFsTXt6Wx9Z&%?2y2N5ZOK(pCM(1yZxyb3M5QPaHnI6pF}GN@?&YvIweDOTxuksJ$G7~``k zjgRh%dZ@2{o@qLx{1!N2Q`(AfOtotA_4ZT(0C3(i;yP##v5a7Id`-hK{KLCGS(lv% z!7KnE10I5s+9PL6!TakNf2m0?A@`Gc1{P0I!QBIDm&m!Ro1ZS*(LJcUL>9PNJi`@t z4;e27QhYqMHUYVlP>2e~Jnwt6_m8pM4gfxHS@xNB+d{V^!w@PRfT=O>( zQYHNznj)FWLsN1h^vTrj@6Z(Z@1d#xfe6V%Q)Sq!ntu=>iB9STBW9af)~Jg2lv&Vw zd(Uh3De}tHxBnnQ^r#P1x||5z@ymMd&y*{n&(X{u|0quV?-L{}I3@r54Tbjq_e!Xy zrl!5U{lbL{zjJf{nVXU;p$nWV|5QTq+*D=d@7mhm|5QSKeZPkau3Rhnn+Q!+{hgbd zJ#$4)gxp~1m_O@#ix+M1I4pk4pxd{CQBI^&;-san48F|OA?d=NwK zgN~@JW$m1#{HG5pKmrIPMaHm%#i;bI#TNFn00qNk`w{{9tydv(KBf*+G}T>p?CwS1 z!uDbKVS;_U7(2~AzdXY+z0NlXxLayuo$Zu935<0xUk?~jcE5b$f$|FiDBBHUI@IJ) zD0G_T0ReOIJG+6XXIG9_Zrw$sz=pw-OX^4oah@`c#<8Z{#jFpZu*dr3sEM^MinX^6 zS~ci)|E{i_IGqnuo_m&;{;p?Q)v(tc&)QZsL;OX%J169A}9DR%)S z`l6I-RZ5(p-q$rWFb5?G15n!3YkasPrIG^Jy0U;}h`UnwZ`JR?EU;ByN-1!%XB|ZB zKmCZZ<7`_k1w)v7xOe&N8mxKe+%x211dLS?w#nceLa{=WZih0$o-)rlHbfx@_v7|vSHdOQHr4pZO#xHY6DtoLp_ zAjbW$ql7ghWcR2oa|^HbDigx0j`rFD@uJe0-1(bMIh|W!M@ZvueYP#6eYv@uDBn`= zvr_JZj7&%Gvk$p$U6=~r{O>+U8^w_R4?gIs<+q1Br?-B4l>O@L`K9||O?0~%mfON^ zPdI@lm4SM?i_g4GTPA>Sy0Z??OP1R?dLXFV#$S}~eys8;>yY!-XD5zr+vC+c5hNAF zA9iNFmi$Jn^(fE|8-LgO>I41*{?~=5_)2y60fZX8CTF_Ob2jg(nNL6oN`<TnKU&` z$5MYe!@zIv)~Ngn8Dg33;Ungzi&v(d%R%r^poxu3iDcv6k~tyNwV8d=P;akccr;{S z<62B2?^Oe20l6m5$WOD}NsOM%XA!GaL{+u)g5l}i#ozrYxl7JC*mrRAU@pPh@LU7s zOLn)4uUI5p%Z~fvK^a@PEPgWSvTqnR4K%2356$@dZSK^o$Sa2Zfxyt^cE321g z)gr|SI?MNTIv5WXYnwhtSo9P-ryVJ_^M(_gupScjQalsdj?mrV6a(+oacsSATrEZjVi_X|3xKAMM8Juik4< zVr!svtQt#)I0ZAH1ig8VXUQnS82e?Khy@&D(o;_#iyFwI`}9QkTCt_oIOr&)U=#H) zL9(ZWb_w5-QYc&{?=%E9fLcy$w9ov!YO*CVvb0weB$+I5>H$@ET6@MB51iPPU>0ly zI)92`p(^}bFw&-LC>qcl$O3gtC494Jm{PtGPs^qs*#BKUw+#}(r&h>^%lH*#_9%-iT8Gz61{dT6JKv#wE_Ud$t7-E&4KqQjkpXy|1 zrq3Fz{7ano;*x9o&POkxB2k2oND3M$YRllt zp{^xrQl7CAj*}GNg6Usq5yY9Z&-)w!UzbYdWAuCrNj1t;^jM`y#-IPxhAkf-GG1#f za1?WngZ8`~YuBHy@fi>+G!8Ai z2nXJ7VY?thYKVmhm@(p-?)uI?q`#NZPN|}8vDzhsFiOrNmigK5-=&_h!wOscgr0S#3tH;mYB%5 zVSrfm!@7CDG}Hx@6ZS4 zIk7JOV#H?NYqUiQ=hH5oP}yv%|LH)j(y;H zM6$C)${2lnHRe?4;^xP(Xxno5I++V0l*Q5g;5%E#sr?9MAZBxxT8gJXXXf-9yBSle zqj@`39;p`cwQBZ5)HLkp1X|j_ZC{v{^y{TW554bx*OOOll%DU|9p3gLU4K`FhsFI>aIou^NoEzNfSl@F{0s4fybzijQrZd*~Na$17OqM#OPz3f;%O%z2M85y*jFAs`TvY^~h@@}MfW*O$KuntZnLX{fM zcEFZkGRDi0v0p0m6~(GbkagG{)+W1h2w4x{u#NM(t%%MhtgOy@u;;Ybix6bqd~keg zOlF6(8>`^iEN93Kwc%K7uqU={T;VJoe_n!okp%OZ-xwt2nBcNZcVbS?XH2MUjwa^U z&_WlUA54Y>IikH;q(4*vC`5#^pN}+47g$P!DyGiv0Di5!sY9m(ci|Y+^$8}hJ>!b` z9*HamM2>y#ix3V7LkEeV)UqYK+dMT1OOuEwV5pxO16DhZ+QMS|(x8Q675X}mCjhj3 zkae##v6qM`mqCMzA>v%9)oc9ah`WKSxufF`!z-qXyL!3>{St(DF>yJDTpQmY`B73aPSG*6#3N z8nlU+AH_K6GXt6toh@jJr$iWmI^@3?87G0v?)t{PMtxLF{e!Bq`5rEa>Lk&uRFNvc zkkKZ|P9YI6|Maa2)o2VIwlIuOF+>1KI~;LLVIu4_5hD>RP6jJ7X$l##vLh&nEQL8r zHrFkQ6=0?1=U%{QtG4sEN<#BcU`%B;>bA-fX@b_ zYQ{loIu7Rz^ zdNdI8?aFFQV2b8lr>L!=R8?nJiGr8I=0H(Ch2*?pEmk5{Xi}ufdq+!LN%$rj^dY(Y zqMGwg+KD)Hy}dQs6f6G$pV7udUH*=4l^$+XRjC(yH#w+HBA_rDIw%aylPUCF5u96q zO_f3!SOuXL?WlK}HXqt7MZG0tVS1|Ziw&gKFic@3ua4O(hHCl9KjZMO{JUI+4Li?m7MHb3?QK2_y06$Cpl>8VaspF_UEbRb+4pBRB=Ct_Zba ztT8w=pLh?=lC!KcAJega_cQ#z8}+h!Bm^!hujPmDFdxd5#usk@agqxD0zFfewnp+;yK)D9?lNOXI<;b`AT0W zfqBz9IgA-C=tBB6_B1{j>Okg zqPTS3D6fZHMhDQkD+r2quoZBveJ{6TP+3ofgp8J7y7Bj)Mv zp|D;tdN&2xq%KsWpiZLD_}Wp6IK}OqB1+?B3$xq+i`*T8ZHpS{DiMk)xiu)iBn!zm zy-%m*BSlH!aZ*(6`CQwp0}IVpOwV}P0#Fhl!Q6rG+=pW>RNUiLrOqu~oP^)3&+K}P z;#XCqe68F1E$aH$W_$_{jGd3Lk=`QrD{7C!EPl20%91q6cP#x;jp;p;28zKJ*c2>O zE-louTpu3_+a!Uy=qj()^eb9#h&@C;=Lj>E_&V8^F~?7Y=&01CC;QH~Z=tGeqtUT0 z?WBjRl?|Qmt#Ec0g(8v_468;{Zv@v|36IXdV_JxbZKB6GPi8z#B2w0C8q?U8GlfG} zDuxgbzamT+iuN#!(7gzofe9ibogS_}M^W^XOphIeO1IwAehS1J7?mcgsMBG-08<>P zQi&DgKJFNLXty5`MPv=rAK{c4>rR%a#40HEiag?u<8_uCq$s@|^5^K2J5UaBZk=#X z$3l;7V$9&9#?`pnsxnsyGrfDOZK@G^_LThjH2lgI75iC$KL}Ku+IZd4*$+roR)3`M zKsdpLZ($*Gz9!sj!r0xF9(GpiA)=>-|5!yv_w9QqPbOVYa8PKyyk`t#KI12 z>3Yx(PxC-5YrzB&z%l^cmX7w6CPii;a%hTsl%gILqyIdO+`>}0J?df>YnfV#X_cVj zXfgU`e~4Zq&WB!7lN|Lwv0>%Y6^F#DAMRFJ`l{}1&qx4taVb5LW;0kvee7d*cehZq z?Nr^835Z<%@Iw8GiFSoBnnH>gnN36U)S%^>&Yq(C{*0mI?>IEW0VR3@&zQwLMVNO% z8!1O;FXDQ}Z_AG5kjUBRhT+T>RHC?*PE)9)pi4y4Dzuls18;6ghuS+8!dVJ=^LI@9 z2G-Mau>p@PR_{+frnzM0Pn9TS>Wi;|zu?arR>Msp&TB z=uw`0z~-}(4-n>*Gfv)__Fz6nZDuuCZgh&@XO?B*Z0)~Zm8g)=GXDDRxjl9&l~5AtdsIR&Fu zl)&zx1^c=~-O^#2Qn=|7nuS$3b3S;C+q zYwEmCvRMDhOQ7qViERj>DO@`;_{0LcG4flu2*rKdC%O9rsP>gnIM6a(Y8mYxi7De+ zTbE};Lf_hO;p*1I#{QLAw5sfi*$Nnc0~tvC19$uW&z{XUFCU0vGKbjR=Z z*zDM9YsOdav~FB)PWf7YPt6)9}xhyI+|L z$g?=giZ2Mr+{2fKQ7f4}Rd)xk!}AP@RP&?RWlRKm_bko~ZAeK4)m8Fdh|ZH3AYT|6 zUL)02Y@5GK8qRBMF(@ZaoGpLX?MBcsb_G52s`fP~=82HLokFucZ8vnSt0*0P8l0te zzM7#(N+!J|wqG^<@nf|`FQv%Z78O}G=c)F#f_39qY&rAhF` z#u8b-W|^0A3!Qvca)Z*}WE13aphkcU*Q}f4tY5ho5(W%%cKXx*C|#yT;!$o@(;|WX z`dPIkw?k1@F(F;dl~bKXLp4p*vtg2DHbEl8;V<~*4#fUI#;qyyz7dKJUN6Gl)F5BM zbdgzu9+Ue{>M>h3ddFa&+<@~;0tEKGm`(ep0 zZh3!t)XzV;RPy+v8Y$F4WyW_Ozh}$FBeibg=(H=2=;M1n_^C%>>r36;DZ)A|{;G82 zSkb1?#ED$?R4qzdyKC*AyhM=z?CM?G`-HnKjuV;}DR8}pst|zr8^NPrw-!GFe4g5$ zba265T(gl>>V8aIQ{cZhxxt~^EG435`OyN-vOLyp{J>0^aemfIPys@VL+jI*H#sWC z5}nnco7Scc5-{KTx`V+XIUE{N3IB_U3s@c`b*V=y>v1u8M+NahqjL`2;y|X_wXa_u z+^Gh2W)7Rc?TWxi{th9 z))ap7*(NE@RA0~P#9LJd8RZ3e;h8yvt%1^( zE(pKv)7zvIELTi2z>Vwj&ONktv#XBl3O@>)nlcWx8rp1Rvl_Nqc)vs}7GK+T!kl0c zKjHDn7NPcwQf;yjST#>&7g@Llv;?{l9Q2MF3MjSc2_r)^0E8;>a0sH*5I=Bj1`8v} z-UK3zKY5hccM?m`c~(ySyybH&o0Eb8&FtE1p&icvXSwb|voK*;M#HLN=73cl@0Y{W zS@1gndaTb5nsX&&S&Uj(;g{^sAA(?vB!mHi!wMnt8YC`5fj3N7L`jL@n*FK4@6$nJ zCm7^M;#z&7;CyBW(81)m$&pVXY+E88i~|hO&ya8p2C%9a?&T^8zelWr?8RFX*Mu2i zv^>;mrRF2+pKdJH76VtETMQAdkuhazolSh@p}kPiLom&+cdHrQNP<``Z`SFK^qU8i z3lF#Pde}N?ai@Ne8$71`OWL%vrkO{bgdSjwz!flRJ4h1s`%{xz!bi7+4pyWQmYF@T ztIwx@*9|5_L=LDGcqrzj!%hy#?+5>mEE!UW8q$qNwVW$EuTC{P+(85NLY+M&TvIsDxJNQrUx01+my3C zyRqpM<)9fVf&4PoYQrnZ>xxq09$sG1p@>_1^G{Lbf$pK!@0a-p@OQFK%c$J%6QQRF zIt6Ou1T6dJUdJzL6Gljnz%Tx0KfWwe-D;92!3o`D#@c`zXiPX{YSqV5 zFzRu&+$Cs?URQgMaZeO4e63)Dt%hnezG_{Tfe&BSnB;%jxyd`X<+TqFe%08x`GEd~ zw51&Z*Yj!m_q27YH-GyaUEAP$;`i;x>E|mi5+dM-i~w+d{@ojweaxFr60V}Dx1W6I zQYYLM&-<>_4)J8rFPFP166hTJfddXlGF?Jert6^v6v>rkhf;J)FH~*a%U7T*@Ell9 zvxH~dNY)O4TCJ?^da~n@igdQHR;Fx!lFnr9``lETgW5#CiS7vhn31E>udA`#+C|l{ zboE95^dgpnAFEq*LRXD7O+YJ4O5h?y+?d{@{Fy!}&7 zg3J64ag=rlb!E=AFt^1^Zc5Kzo)Dk`_Ll|C*nT1m_9DU+6_<7Kg4X zKmB>UoijDCccJqFgE*>^JR#Wn>?ue<+$X3uK9W?S_m-x+hzU%Ou zIx^_(8n7elr_`+eA+ZD_iqq@(Q;|Z~B;+};?{}9_DJ69mHqgEChrHEX-y%%QI051d z)3QrpSlA{lLEJmcpm966T95Z+E>w&vk+i^$uWlfxLq_lM0^aLImhGae8!qO~QTIPdV=juxK zh-*C8ep#=NU_CQn&E=mVuHwS;TjH(4NI*{hq0HMbvtp!mH^-h_HF6ss_nZ>#g6V({ zF3ocY#7n|w)izA+ei)%`@eC<#aQ4D+rH+!&jFQlvK~=hZ@R@~^8qlOXMNKGbuE5zA zxqhCdO1ikgNw^Y@UOxw?Q*d7<_{b{xrl|80hE-(Q0GxJi0lhkW=%_BC{y~(WpaPK5 z?A5*UOeLH*P^h=KS~O3}(jK%Nh>Vz|Bp$P#_zOB`e3Ii`W7CIb%=uY`?2QDie=I=rg7 z)o}N^LQyYOn8Mt9aExg&OmC>@}4itt3PAiQb6rOHj z!byu{fAqKbQanl{tr5Vm467|vF}=!x(ZZ_x zWEcgA8E*v1zzZ|-PIk?y8hH6LNTNdh_6!WU~fk@u~x z5*r*of~#g+M=Ay1kvAOf1?Sx3hVDc6HEV99!EMAG*WPuzUZ{S40FPY=(Ws^GeT#uT z3hSOcAzx${Fv4>v6*!RK+P2zr%@_n99A?99NN`&Xgw_n(MR2Q@0cwlj{v!dtvop1o z0xXLwDi7O<3g(FVfra4#85l)Y8T>fvqhyq1ekC$rh2)@Ht^>OJ-Y@lnMDv_Y`^y{n z_{`wTrebhhT#9CK66w`qye*>#j!{7NkpE5S8&n1d&Q`lU;O0K+cAElquCWzj0uTQyT5G2U$wZ9ZwXYZ zh=J?N8q^ymO=-O1&KqG3CT0}K5Xj3_Z?%0b#Vg!bT1~))5*E&POK1qdpi3q9qL+l2)PWlUxCNmF<(g!-V@} z$G0j5D2LKgso7aGK~w{1MxokBIDaLff|-woYNr{_$AFZEo_Nq$#!_Z*%*0Q4axT;j zYW$R8bp>?{hQphq9Pa(k%i6D20{(-3A`XZ@Ac*b;$9<3+N6gN;)TyjT`MieRWXH_J zAb&Mc@r{n`{@ACH0$b6NsagSu{_^yo27icKuIF(qdLCgB{sdJ93qCFwFJWm&I5tGY zTM{InRV+ewtga1@A#zD9NXKfzG#P2ljM2NNZLw4uR0hX2fmCe$R<_(A0zq1bOpB01 zn$>Riz*pWp1ozAknPHaxOu6g%vXT|Z!!qM{g;C_9@{!&KFAfJM@S&M`^spYpln^Av znkj4z;%#{r+f>HUk`UJe{Eb)~{2}Gt!qbj1)~mBx>th{!ybzJ`Pc|t$)_QT@h2FR> zZARFA5217+AIVk3@%Qg}-hKnp@YpD`P9CmAk%>^}OlbrXa(VNtE~dl@hFVu0Ask8A zd$f|UM42jaoEqB0Rt!XJ6hL?8UUniNOaEYJwRkn2T_DWH##XFZc9G7f0;&H>qwXb!uw`vfD5i;giSDK3$dJa z6rL+_Qwu+!;t(M30=AU^>SD2b2D=h!G-hxu7bn!FfEL>@(_+Yuk|z^@f0iRxvO>~J zWYZ&j-vRIX^;|zG;z?b&zo@%V#MLAw8y$eO3w((epw;7e3H zh~#EUgTvnU&*{cs=3$*!pFHBJZ2QYWdL=%65zoh2I;<0JSdN?sMJ!g+NPh-*^M#gd zrJ05^S%>Jzm}%Ar!<;bncOiCwrYUnn4DhPoIBnwrl#yJ?j3jSq0f$ad8QTO=61Sf( z@(|Y`lNQdqACK$;#(XGXoEC^EW^tXb$#s^SjM>eM9gN^C@Y&CEkGs319y%^Ra-%Cn z@_4H6pu~iCT)0XKTCmo3Yar}qc4`raObh*)GbQc@)2MS3`w3O#RP7ZPqkbF1VBs8FPy_Htn(eQdHT;ex?K;%sJ zWkd)Y%x@~;Nex*lBygQZDvH68pO(wJ0o865VfqWrLO>&&u*YNPK@JW#f)f{=LVw5kB6#3LMWCP~)+(5#+RI82Y3VxbRF*L)_~lcDtPuNghPwvDxg0Ru{^cqw$I+VHybZ5!jve1obw%RqA9e9YbV(y zWpGWHY%Ofmk|_Y)w7vTo$g>yBvz@=#OEr^D$=MNipbF3?a>-(WrkJy36Ij~v>iwJe z{as&gx8w)wX=(oW+4t1Q(}A_?;qLx7-(m>C{DIr)M}yXkfB`J9Hf`-&QSr^w?i>;K z!goU4C-gc#=lV0tR(E)?!@YA(Nnd3Cm~fu_8a%nQO+@P-Plr_;FOC{PRP}&X7voz2 zq&LKTZ8p;cScM_bHfc<;-q61#rk=z#meM(B~+p5w{+j~PYTJThC%EApiAHEu|DK>v?=c^%pX4GG2qdYPXaFJ%0}RHt{amjw=E>{*)&ImGno>P>kT{Rj7jz6kOlBvRu%tjua^^3|6z!s~<)q0;zV zLSRXpUS4;dT8I(C_$hs5Ku0w^Nom`VtL7%LBoOjNq`2#`3&IWEG;2u4WtEor{@tb* zGkG4WRpBq)8)k-rlA#xwe8Stpk0`=kdi-tku7|3_nl?V{D;DXl9V2*}VN?F@@?jfD zRk+0JUycrS_Du{y!mQ1RP-bvfi6=jK;q%$=KE*6CzH`x;wah5RU zBHJu`6f{gYyQfggcQ?XuI3}1pWljyIJk9m~SeQ6jTk3&06C6`&i_x_>4!9FGVY?^r z$r&(abLS-btWV1Rh>5d12Ubj2M%I3%?!}I}LaJ3386TDqDjuy#Tff=Yjuf_0S`oC8 z^>1*^ijk~5la!%}BB*R12dQk)Qz*1}nETC&MKX^LG_ov|9aBnaQF@|HE79j+^5}$o zLMSxzyS8Ckqn-u|cIXn%`4L)2993ajG^V-wPzF4^WuUOrRwU0pV{H?rL`Yu)?N9NV5v z#uEC#^}7Kgm?H7#ERJaLntblz`|TYrD&x~zKAQK8;6Fq?G9UXj#yNjnn#eNJEGyql zf^TSIUd2Bi^be49NR?f-uCbWVO$53xDn?QdKxjXFcw23$DRQ+*kBh`%1WWIJkr`8* z|8Coj@~&{q~DT; z2u{;q_WR(l<$7aPG!=zy33oF;d?a5Z^O)vsLDA@(p^-ka27NGlyYQ#I5_vFDmLYH2%ySU7OrieB$S< zAqF)TSQJ!LNgXxyZ5#{f^38AFXJp}6=Hq&$?PyokJ&PmRavwBVnvQ3|IREB@v|0b~ zK{oB>BWcFAr%Z1!*6*me+h=TjMtEbZPjKbKpD%4LHu}MsHhX&LRo`y*xZG-NPkrxK z<9J(hV^-6r!9ZI;xfTlc=jvLJ(l7 zDtY_CG}>(xf!lyq$c&-FAhHKn5B%yt!VxqU=MD%%P$-rkN+(O-aByY|Op~aIJa{-= zUD12Q)&9QxZ>3ABy(EfxuRW_wYpZIr_%+;POrZGiTBFM@Da~^4Nb`|DKAAoa5zhU0TJiZO>gZR<`DNl{e@ zixIUGVKfW56a)r;h8#kYl#&;k^3T2*Xvv;RE4RwO2U0l1-gFiisy4%MsF8RWAT81I z0e#D^)`F1mw1`NNBC@M^r{$Tj&Fk8SLra_O-ZwpztZjezCjM+M(>zhn^`T$pS7I-1 zBoi|!xYN?y;OYP7dO8~uBYOs{yr{n8RAg{d&9VCWtwZ2i6iWUN0j~I8k58^=4H!y0 z+|k9nc#&_^b+kq-1`7ZPnc(Q9j<&qD=^UNbP4F*kYW^oaXuWk_@ZX84?qO9F^8XwZ z()gc2p}WiEQ0N~mp?`-$A4&fYpisLuvsNdo@87M^9n+xqYrOs!R%rIWTA_bY6k7IQ zib4d!e-?%QTP`Fo3ei{m{rS5nWd3hOq5l;Z!sN1%|5gZiOD~ zD!;M0TyBMCQ~y_1=+u_~_o2|E+W#9U^dBvuN00tXOX&ZHLf&n)qs64)rs&bOx@*VC z31d~>?e#Y*9d^8VINE;t)=3H%t>e?tFmcMO*eqtOqw)4>n$iCR3XRA^LjM&CJt`kj1BJZd;je4luQ3c1&>1?}Kd{H(VZDZsJUvrnsBlD)qvju} zZUw7bjalQvC<5i=u(qy~B4v4kinfzy@+Y2xX-7;pMxCEx0}x@!^Q11rMaEXtHgy6* z)!ATO6qKDWO>=*T&=Gr_yF}!C9fUOQB!7J!&w}@MyRzc{%m|4}DMZk;Ht)hokygdm z)sDkD?gUZ(fWxFn7~D4fF$EO7jN02vkP55{k?GPu5Jp%E06x@^m%S%IAQf~JRZ{ee zm^GATPDEMJ1{`VJ46ZbU+yZBL(XxAK4yY3OA``~Z_s)`&l=Ycj*I=9QU!GHxZDlN& zmfkqU#Z{SZoWfLaG%Vitj2?aTt4opg;dS6zTI?E7{P^UAKOR-(@?m$_arjhC14Tsf zq2<9{GBreMmQsV`Zjtw6>%GkGy=t-#VLmZiLTKzfW)Az3B;Fg@B3Dc3eU7hBFybRw zF1BcS!6?O&N2ytRcLxWmc5b08M#S z6tzx0<_jD-H|aI$vF5$4PcsszsfRDD>&>%~nZOFGoL7d{MHVg% zw_4Wu_4wM#=fE}Z6iJJ)I%HGe+Q4621#Lh^XE)l zfK9)dc#6<=-tezek72t(-k<#KZ0kKls%?1DV&DWWuFR|eL2*>Lx8clH;>wW~nx?6hnwpiBHm$3xsH=UI z?+?8{=X<{2pT7S9KX7=R^E@w}x5wS_+*lI`^DAG2X6{(O&dXAxsQzG;u-|HoYf0Au z;HQ0AZ_h~6J=weEuWn&?dhrV!*U!uSmXnbe7hmXOw|=~Dw>{r(5As>wlw)EFF%;Q|k zTaKzV)(N$bW4Isci?uE<#C#F0&6bV%sILAuk|` zKd_c!D0Ff?U$2eMl@GxqQ%P+rr-IQb5$Y8N+76mg#f9~bbaDIvEE}i7vGSj&eYTxe zVD=ugipwW6MkB;?JOM{6`|cQkoeo9&KoK2VEHe~)sb>!VTYh5X%lk9TO90*VJyYN z4qL|4)R0?bslDhwXn3Z>(M`ugiAI9=iC>F;r4jH!EB8$!Ldnq>5G6WRlU`JG?Clv+O6j;6)yax`(NV6Q6s zM6C^`96b`ck~l$XrGwtOl7>V1K)k+yOI-)`B!_c%9SA86qXAKw9KGNnK=APU`5x;x z<4MzxAXBIAit9mfG`|hdM4&gwi1PlMFD2srlir=DDA2S6AA`pZe*(FS^fbscAja{V zMqL$4ixw&I+$<7XU6&)XED9+M>CLhv9ngq62=qv3LaWf?WQQs1A8Rr%W2zFrXm3Oy z^eRxH^cz@T%2n+!pyb|P5m3qE{P_$PI-TTX1zkFzy63y=)v3#&5t{+sf09H!Lc2N(DnqPS&Jn{J7t0;aZNQTmLbXV7-jU8!2p6wu6hE04} z;ihDQIpng1W!q#mmxS{Ux&;TF-DbZ;I@3{*7HNB#tqSh1u1nT$rjShC-@0G{sP;vl66u`W!f>mDS$y z4MJ!?UhIuCkRgy@rh?5KE45&`?QT+%0jUBV0vH^ebBB6{HHjbg#E2j9Flf-SS{F@G zEyDj!gLab`3OSuUO&5kSzDQarCCDuc5$v}h8UHO7yd#kpmTfPU-@sBZFAfaIjFOZ; zPa+f?kCI1)Aq^M4Kw4-|J^+1dFtiicCIJZjVzt-e<_)cwNTjwKA002|nIV*jvF9~^ zGtV^cPN827qx_5g0!FBR#pYWeUZlggO43&!1-P>|yxRZpL-W?*I zgjmZVPi%ZBKC^vu;?{vDpN603|NT4+Y8>+nd)JAq^8Ju>upshtFnMxW)+cvba~-kk z!g$h;&^TO^_f+!DL(6Jm!fEQDmilSqs`l09K>p@p{6 zvbMH^J!y#+TcIRDXtkNN7(3)@LXR-uy?hjl7^;JZCiAGr7|6&NpoTDEKgFh87pWv~r zw*g8DqE1Xly^M{(EI{vnfjw1&MG+-}bECZYi83NKcr9ba80@eRn*)6OHIKnM!>#y$uKru!b-_8{0n{0EZ#04N=w zn3(uKP$+4E25^N^iLmA7q6QH{fJUBJ2>wuope;bWgeiUTgi<{sAAtIAvW5^Fw9taEgj68-HeD$*yxEn2Rzi-eNZ19HF^O$gv$dLqZ%lu z1z(-_9E?;t>NN4WMqmLvOkqq8M%{8KmlZ({Q=B?P$A3;?luaPu6@+72Ou_#uA%Vn7 zs>C5WEOmn>`6I&@0N%w1&)tN9x6`YcFM)%yDPG^uBMXS-uZhf7i7tevN-sn~kaGme zrsK{mKZgRD?luz(yVSJ{4z)N@+EczhI)MG)=mNkGF+-> zpnfEn)(AS4+5jm}IIwWKs2tiXDt~LyL|8oV1(rAX*+yL$e^Pj=hcDr~05x!`*`-pv z>?h%_l3;0>Ucm<%1X6hc*%Pg9M%p!XX=nm28JwQ~s|_*2M>2@WLW)E*4f^%+#J;cjE{h7a!BS#x&N{;Bw5H#GlMozZK^XR+9gm)=o4TLG!eiW zmV*Ut94>p1xV;=Lv3aXTY$}?0AQd4{_E=%1=y(qr^-xOSD zMSOryt2whae=uQG2<<3``-#)m zA%7sxRV`pTBTL)>T5g6rYyQDOguEh8Q8tlLbak2vb`m2Ss3|o`h5>KDqvmyJJ#-Wo z5Ui$+CNY2{5+=kAt2`hPgz%?{GGgeclgBYbLa~p6KK+Mht{@+2;*J#KAR3Gxcs@_Q zvG2{{uP#8g2$3D!CiX#o@wqlc&JA4`#YCtcP}C-SW%tH;tn_}&HlS@K8sdwG;U1xXyV~qu0F!834a1?( z+4!M$u#y1ckcjD{qz2&m62)gXspx)EavbjzMLOgJDn!*0xJtI!C-yTSL0BhH-?-`d+q+6%qlf7!t1$c(mFk*ZQ;Un$d*K(zdj*P&2W+{w+ z`i{<+qz3Vjk5QN%zcAbdNH!pGS_8_$k4UP7E~|l$(-6t6rKuYbec@%e3Mw}j_OrHm z3p@#CA}utL;rxi}5751QSTf!-c_D8k_5I z1fj%YdEp4UDo}*@ts}F2*aWz1(=G$huTO(N4n-aVz#vYrUB{3P&#&w?4DZ~4l42@V zRVJC7IIWDNTQ}od011nVs35#x8A~HeJ6G0959&Z^8^^qbry#|w;{3z{I%-H%)*`~} zTgUve0w%*J)O-*)y0tqcPEK^_m`TJ@V#=g5CF!^eSBS6>*~Fk^VuofFKL(x`K<8wI zTHUBlz61w-f_33+JpwtVc55$FLYY)g3cjuhWV=YxGjU`qg+DUr5c)19-&VQ9c;3~< z3GXS(gO_s>qXmfWed(Q)RQ0ht(POO~C$KLa_5(?_72fRjKwNs@VwL5w_E(OxLxzm7 ze)--u=yg)ZVgYQu!tUKVMwtzwkwT2{ca0YR_@MhmmqziS3JdqTCIUOqQBNHtJgm`) zL})b;d$n$VbRaNt;g1jcD}G$k&ULqv{3Qz@T-%|B2$gxYZ1@<{D$4d0_A^bebH?V_AQjd+s*23xSASnAxsdSS9}^x%^Pw<$x2d^z;?UZekx4#N;4ChVEy3Hck3b zz3_Y=Iw7n z(!UDQ`-kQt9LkwckdMcz@}exDQc!3yN4lL`aD$D=MVm|xl;*%XO*%h1hIq$(sUi3eNEw^hBQf217MCqP8=!^h2g zsc`6J*tMX;FBBW?#~0z1n@o$w)8hZozyB@%sszbez-`$v_x^Gx=Rl-IY%9nds45_K zY#ci?7@5POwKRAf^=_HmSpoXKN(LW{>i&6W2 z+g$%w<2KZs}{AyRFC;Rg64P-K!YWaS<#gb%Cbtke)Eq+4=Pwi_L1 zFq2o&p|uw??!01FU%ol?`s5CW9Qs9rg zCIm0ZEHApDzjdXb)P_w20edH(FGZ|Mf1KWFxL^}%qe3cplmy{wz;5~@M$o82A=q>S zTCPw|TY!oeM8!7fx<1~1H}LE9HX~UC?WneuP?_-OkAdvqPfHC}_2VZHFD z*bMUnmt)&b(jl+v7kq$;oMWG39zMId;@7d|2aFNC1SDTir^2H2(ErJF$!8!gv70izUQ~UC=?l`I+Jz7b5yOsMjX8pPJW(^S!tKAV|@fEaD2achi zQaKu@+_;AH^5=K)rE0F#0#%{&71sA02oWOS`u-JoDg5fGlTMK=PFJ+-N}1|q5TVF5 z#Y>Q3}RlMQE|5`Xev;Oj-6HYH^fz9)g|k?dgC?u1wDL2w}46w z%-%iN?KIz)l3Jl!m6F{&^}ixkFNUAi_~%tQQi@a-cN>b7-c9i9LtU?I@-aahbtqtt<26Uq@tsz{TtO45a`8<(vg!*bth+It))Xv@{7UVdbibe zrNjEd{&Q-3^ro=a@zN)wzE-SBCmLCRrQz=MPOJWPq~(?BWP<%_cMXHRCqfZ~cA7^Q z6zJFRn#52Dk=Pv+@xw#w;vM(9IV^SU7@eLh{C}a4PnS$%EnwtajGdz%vW~>$e}lb~ zZqd|T{veA-87(0&_i7j*>(B65308@)7q98_sgbY#*76MBts$o0Q}QTFq$U}fux$sb zXyG-TH9SASo3QJ3 z?bKUzk~3kuMa$VfdROUbQWEBWpSUO8{M9HiyHQZ2b8QW2Vs2PnrVzR9q%Vd-J~;)1 z1zziPS$OE^bZ86lyL-xBAHTS+D{epcQQs4GR(DmVuHP#dRQtZu_ zw7qcbBX?chrl`7i)+S#RvupV*w}^~)V2uk2&HN{VZvLYloeQXM_qU-=1$9Xmc;`Cz zYc(|6#01Sp=n58^ij0@2YT{ArACR*BXKyUz$fV%AK#ud@oA{b-3HG=2mNsH!Y6&hQ zx0Up^R4Tk>I&yZXov58iXOZzi5-hxa1i;V;$r1r&8aCLP+vr}HiMZzzJj{|Us<77c zVW2+DE{%mSt`i(1@iI8DT#HBnnPzwN#(2(~l>67TuD*j5s?A9G0ziAE_6DU08Ucl` zuQUCp)kcP=^rDWEv}fX_4)C#3la*rx`lb|38!X#S2eSs4*+Iny!iz%P=a9`ypLKKQ9mx$f;*MuLaeowBa4?eMd}NkHc?t5MO5k2pYPN_=iZd3i9U zjaVZ){1_;!)dRYm4okvnh>WFKq$T zQJC-ATV=0M64me5>Xi>IMiX~^E!a&5q&9*k4J&_)#DRFay*?aIvO4OxC#@7W!jZki z(<`%fH|^n)&A-H&dXpQW#*FbE^{E?(?v(nSf0L7lDp1VTr6BOgYo}T9=JrBsHFoCi zUJ0FkO7<&bl`}HZwqOYNa+*4!59_Yi$IXvrOZja;A}a8pvQv)7c-jB}l_~9vW&lb> zT=j52Nb*IW{VI64Qn+QnS@T(^2Kt0VhM>mVLq*DSDO@+?D5LRhlPpxo(S`H;yTU)y zN}@og+AV_^n`{j|0>{9yciW|Ko`no6`yyY~ce>jRI__T3 zRJQ?C8fz-AMr(yPB~mAKR!5EcI}24`w$G;@tM?u4ioPaJic03~^dmaZ+~;bx8cZ)H zhIh|9FXBxP2Q_|8@6f)q4B1Ow+yVUv+F$ywEcwr@CRyktKCNB8`3@Zuiqo<{gYxWg zXRkKfq2MYq+s4`{_|ufYtn^kS>b$OYqfTZ(N z&yDgx*ldg2=XJy2<|GN7q$s3f>4&=Ub-|%mlXrjHaW1fbz4nev2Kf@-!}sid1++?n z9*OKrG-~y5JH6zS!E3Vfqp&H)o{PnblU+t`v4_h?mx3%f¨k!z_aNFW=6G#yxJ? z-Vp=8czN*BHE|}Hs*bwyF0wsae<>w-t2a5zX?GKmEyq=TFejOV%BV%v4z$nL+deQ? zn_$LmyS#NV?|3|vo*C!l5sC7dGaem(OFVCpb?tT8F@Vwv%+p;sclA_y?RrR}S!^e0 zRWcLMUu#L2^r}a^zB_QGi5*mLWuHm1)3}MRwD&$X@~rjq)46mPz+~I{BVmy888&>{Bd>iD`zr zX+rc~ukIWB1Q`b#U2x3$@*I)wxfxtt-tW8QP8!ek9w&H#)m**bcahY? z7~Q=9+U-{FD1uPUp-JNvLB)XWe<}<8#>tCdJ42A>El%wy>ul5hQGib4=(d;)0bU&f zbcgP6AzX2c5(G6eRvs1TxKB`2a)|TBR0i_%(!L&a*H#J#^nLIpV^m4lhrs9P5u5u) z#%zX1W-3LKs- zORCB$;O^srNC0KL0Dz%Nx%Y8Hg?*DgM&jSaQ(Oge2GF4B_8-3+-QOz@KCoy_+t~}a z^w4#RI8nIcUm|1y$`@ybs4kJ}@;Xa$)(bc7-@)x1=cwAP%wdQZ30$blecLtnLg>7c zpMze9w`z-%ub0D9bNwm1ao}-Yq+lw?+Fnq>S((PsY^`bSx7s+}5cZFgr6k^Gq7VufR za4AZmb^^#g6SLeg^JV>95FISjEVe@I3-Dqi8rXY=&F6zm$u&<+y#97XY&~}?=5{gh zEMEY`p9tNLhx#z~IfCn zrC1HJK2EtI?qZN)M$>#p& zxt$oW5o5>}?LM&X?Iwg&C~!3s=9mnoX2NY|yE-ybx`GE>^6-CWDZ?A*8kpAT3B5nw z@ZSt$)jt{uB60T9yUYckf{@$#fE)`v+kr9U!{dZ*<#Z7_*6Q%&^;P=?wilYCDxO%| zDw0IkjG`g$M_2BXpfWjSp=%H~{l#L)D)=+^9}mRuZg}T5X|7NJ)$0Nq&xpGhmp@7u zuodA%Kn`&?yg7U4;WWwpPExiaaL9a6a5cw^3O1&$vP8GjPj&=sf=#wo4(Q9vrI)PY z7ouJkzDIDpHrO8gd(5gF;|;t0MN>l*inYQH3o#cWgYEf1WjtH23a>Q-v|M0|9Q}E% zC>MlymaEc)f4}slSGUUT^4plbRUD&_4$Utn{W+K2!EVz$kdA;=tHIix@^F;Q;R3*= zX0K$rHh;M*T^QxFaX7V`0b_Q&{)nJcjvlw8#4G%vI(mxs9aVT_b z4I=e&*A-dW>SB%#gEb@qi0eg^D%Q4r71-<|JZhjiX}mx?S-Nlr+PPRU`xvE-D{D)~ z-Clt{Rzd`Cv65|oNO1)wi>Y^!oJUfaXVT9p1db)KQJ3_DOO@W@ zGo;9^EIP=%o)I^RLC{@IXCTuBW@wK&_{1~p`)G!RjMS42LQz?$c8T5_%T_9jIl^^g zbOwz8Hj|5G_}Fh;rg1$0&Ij#n2X4FtQ@=x`BS~I6UY?BXk9gr)WbD>e=+l;vcPL_fUE@lF(IT#g)@F+ifhzH1{P)f|f8X&-_K z+m1whYcK5szF@9xvdF-IWVe}emOLQLNyMgVpGk4P^H&wfOe!Y*=JI`>|2~RlK!PL^ z0B&YpwnB4~ZvkYvbNKw12so2oU+Fl*&PtI@o`2BC1acc<0s;cmKCbRj=gdDxg#=6a zo3lEvNKr2LQ7JivOhsbctMpd|ZfihmVohy1xSes?f|Bz&^1|pUSzAAJFCJSI7)92+|?4V`oF&1&@_+6EtvG{&oH?$yJ{J@ z@9ULYAcAk-!KFu>+a<&WkUnozj{q@SU^|fx-!ePr1=ubo2w5InPHhd#bmKzM@Z&uU zwa3Q+ATfj+o|O)rms=ss2;*J|*j%v^O5oYgD~bo%j;gzqPgU&6Y>s~*=h^*FWI=o( z@lKug6}dfJDMk*9TxV=%l~3OpU@BMe>D4|VOOIr-PkTvciDj~O$Z_y&4fUMqe~A#p z4t%eg;}#!kcN5jJ#E}r6r<)uGpG}OSfdu1sMHIH2h+%7$zi!FWCYD?(IXn(SG6c)aB~O9 zG@&+Z3(`*8bw2Zsdb+I=OWl}Jxm1l(EdCX{B536&9 z1CfEq+_fRlS@p67$cKDF!d#%KcAM^JCe2-^`meJC#|da(Q=1Z%lOW6{D0hY7li=9% zEc$M+B7|n3ALJs9GJNBE@qCW~@hJ)~1jxQ5U0V`yfw#=K={~7B+F}`G9;zdVx`yBB zzxA4#nPY20-A*_GhA_>nNaFj5^N1OsF)oM2XX<8t)np_fw&F#W&k?u;X!$`FK(@(H z(HH=&pGJv&(D9aUH~PNOJRamd^sAnfG2a4t@jxBfmV=qR{(4aOB;0bQ*2BWNdq!rQ zlvBny+aE4&X1+hQB0fQ(o)0jbM6+tHe~S#b@YBdPIrz=s1}77X!BO~toSY&!ng{Xu@MN+;>E{Tp zgNA8r6OG?A&U!@IR<3Z|%$?=U&XV=4;4#rRy8Be`30vQ0;Ml ztDq*%JlvSb+4|}4Tu|$9Il=foXL#i1>xByr>R*o9x0YxrHMcdG-Tg;T&HLF!C7RN#5TFrn1Ks4^`~@oL8BK zeHE*cJLURuLh7+=3?BX@0loq>H=9+K9G+Xf*_HP!K-#UWda}M7y<%7s zM^H_hlMQHxIeQQ|0Z=(zrSe4k05UL->|m=|*ivL08{tdkn7Av;*W;&TXpuk&%CM=*2>3_ z5c5hZfk|i(7)rRw(LTAVT7=2CX!Z>}d^(D)NTNHI^BqAEW>kOm*`8$;CxXK;pX}I6 zVLGYq@!{E{Hr`I}nQipcjFumzppHhV?V^I^`8R{@aD2_AzEP*=D^*Ua^NQHoPoplt z^R-T&5waoVO;D%rul6r~vSbo)k8P#z-)Wa$f@YPTuo_`OffeKV`f8yWeaE;r>e0$^ z&tA4){ABsI#i`h8649;|2AO##*|EgNDu*sR%VMI;X;5yN9Y^Lrxjr1K?!C6}X#;z0 zW1x|hF}IvXjpwY$X?)#cT+`2oKkT>^q9Qb$dSZL@_{guLi>Sy!FS)t$2T#_&hB#cS zM97z;`(qU70G5{`FlBMaheJx-An&SETa!I6RNaRTDK(gW!UE4djxeGZOY-M^hMQ*6 z^%k!`{Dq3^OHn**P;zxD?MMcy4E{@Js8SJ!@ok<0~7TYcVjhBhtJW`QDqmJzgpHP&tKySaq0W)0p$dC3T%# z?!#tPIc#&m;%;wMQdJYWRr{Kr?-nP<`nlt3P-zL5pC|uo69VTtmrxfusbkTSx1BLN zEbnk_w(!c$(Kkt$CAwO$JYw=E_k-ET%%V*KefaC%0`O1c%Fio^S@9CtgUJE zCnRL_Pt~80P&2|K-mSl8b+@KzPsi|P_ORRd`3l{QucXVq~>NEUb zYZt%1qtlSm&`=g{eK+6R&k}U}_q+A|z_)jq@B73dq5lho(*JiQ2_Hj*5{t%nZ&VgG zC1FlRLe|X=-7O}P08n$XzW5F~WSJGNVbft?5&{6z%1SOKOaZk!QB3qCULhH>4&OkA z%kZ~lLw1qe3oj!Bg`a`=*h%o(pnsJmpuKUvgGTB^LAsw^2nmIP`m&Z=V;6(#q{St-LQvWYEkC?F>gC|W9QIcr z<918f)ac4;lU}c{RF?s+F<^Lng*G4}gsjZ2hW+@8zul@H2W={3@%0AI;4Y4{-Ta%I zB;|+2w}p04{4z9FJI2rGT#4&K{bhhJ<>AB(2(Ugb1B*p|cL&+)?sY}S4U;alcAu^u n1bp8i9={4d81rZV00i)b-%LrT_UQcoLPCF_P*NiU0I>QW)2;|X From f1b171d88b00d8579e8cd4b0b1ee7cc42e0c8407 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 26 Jan 2025 22:12:28 +0900 Subject: [PATCH 829/940] Update head doc (#1127) * update head doc * update head doc --- LICENSE | 2 +- docs/getting_started_main.rst | 19 +++++++++++++++++-- docs/index_main.rst | 32 ++++++++++++++++---------------- 3 files changed, 34 insertions(+), 19 deletions(-) diff --git a/LICENSE b/LICENSE index c0c52a4321..1c9b928b54 100644 --- a/LICENSE +++ b/LICENSE @@ -1,6 +1,6 @@ The MIT License (MIT) -Copyright (c) 2016 - 2022 Atsushi Sakai and other contributors: +Copyright (c) 2016 - now Atsushi Sakai and other contributors: https://github.com/AtsushiSakai/PythonRobotics/contributors Permission is hereby granted, free of charge, to any person obtaining a copy diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index 256319ab8f..db71960dcf 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -3,11 +3,15 @@ Getting Started =============== -What is this? -------------- +.. _`What is PythonRobotics?`: + +What is PythonRobotics? +------------------------ This is an Open Source Software (OSS) project: PythonRobotics, which is a Python code collection of robotics algorithms. +This is developped under `MIT license`_ and on `GitHub`_. + The focus of the project is on autonomous navigation, and the goal is for beginners in robotics to understand the basic ideas behind each algorithm. In this project, the algorithms which are practical and widely used in both academia and industry are selected. @@ -16,6 +20,17 @@ Each sample code is written in Python3 and only depends on some standard modules It includes intuitive animations to understand the behavior of the simulation. +.. _GitHub: https://github.com/AtsushiSakai/PythonRobotics +.. _`MIT license`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/LICENSE + +Features: + +1. Easy to read for understanding each algorithm's basic idea. + +2. Widely used and practical algorithms are selected. + +3. Minimum dependency. + See this paper for more details: diff --git a/docs/index_main.rst b/docs/index_main.rst index 08c318ea83..8c967ac59e 100644 --- a/docs/index_main.rst +++ b/docs/index_main.rst @@ -6,32 +6,32 @@ Welcome to PythonRobotics's documentation! ========================================== -Python codes for robotics algorithm. The project is on `GitHub`_. +"PythonRobotics" is a Python code collections and html based text book +(This document) for robotics algorithm, which is developed on `GitHub`_. -This is a Python code collection of robotics algorithms. +See this section (:ref:`What is PythonRobotics?`) for more details of this project. -Features: +This project is `the one of the most popular open-source software (OSS) in +the field of robotics on GitHub`_. +This is `user comments about this project`_, and +this graph shows GitHub star history of this project: -1. Easy to read for understanding each algorithm's basic idea. +.. image:: https://api.star-history.com/svg?repos=AtsushiSakai/PythonRobotics&type=Date + :alt: Star History + :width: 80% + :align: center -2. Widely used and practical algorithms are selected. -3. Minimum dependency. - -See this paper for more details: - -- `[1808.10703] PythonRobotics: a Python code collection of robotics - algorithms`_ (`BibTeX`_) - - -.. _`[1808.10703] PythonRobotics: a Python code collection of robotics algorithms`: https://arxiv.org/abs/1808.10703 -.. _BibTeX: https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib .. _GitHub: https://github.com/AtsushiSakai/PythonRobotics +.. _`user comments about this project`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/users_comments.md +.. _`MIT license`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/LICENSE +.. _`the one of the most popular open-source software (OSS) in the field of robotics on GitHub`: https://github.com/topics/robotics +---------------------------------- .. toctree:: :maxdepth: 2 - :caption: Contents + :caption: Table of Contents getting_started modules/1_introduction/introduction From e93ada6cb84ad6be0cb7dd70af22e4defe84b0af Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 27 Jan 2025 22:11:15 +0900 Subject: [PATCH 830/940] update README (#1128) --- README.md | 12 ++++++------ docs/getting_started_main.rst | 2 +- docs/index_main.rst | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index ec65342430..8621a40923 100644 --- a/README.md +++ b/README.md @@ -6,7 +6,7 @@ ![GitHub_Action_Windows_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/Windows_CI/badge.svg) [![Build status](https://ci.appveyor.com/api/projects/status/sb279kxuv1be391g?svg=true)](https://ci.appveyor.com/project/AtsushiSakai/pythonrobotics) -Python codes for robotics algorithm. +Python codes and textbook for robotics algorithm. # Table of Contents @@ -73,9 +73,9 @@ Python codes for robotics algorithm. * [1Password](#1password) * [Authors](#authors) -# What is this? +# What is PythonRobotics? -This is a Python code collection of robotics algorithms. +PythonRobotics is a Python code collection and a [textbook](https://atsushisakai.github.io/PythonRobotics/index.html) of robotics algorithms. Features: @@ -90,7 +90,7 @@ See this paper for more details: - [\[1808\.10703\] PythonRobotics: a Python code collection of robotics algorithms](https://arxiv.org/abs/1808.10703) ([BibTeX](https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib)) -# Requirements +# Requirements to run the code For running each sample code: @@ -116,13 +116,13 @@ For development: - [pycodestyle](https://pypi.org/project/pycodestyle/) (for code style check) -# Documentation +# Documentation (Textbook) This README only shows some examples of this project. If you are interested in other examples or mathematical backgrounds of each algorithm, -You can check the full documentation online: [Welcome to PythonRobotics’s documentation\! — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/index.html) +You can check the full documentation (textbook) online: [Welcome to PythonRobotics’s documentation\! — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/index.html) All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation gifs of PythonRobotics](https://github.com/AtsushiSakai/PythonRoboticsGifs) diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index db71960dcf..86049ac2bf 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -10,7 +10,7 @@ What is PythonRobotics? This is an Open Source Software (OSS) project: PythonRobotics, which is a Python code collection of robotics algorithms. -This is developped under `MIT license`_ and on `GitHub`_. +This is developed under `MIT license`_ and on `GitHub`_. The focus of the project is on autonomous navigation, and the goal is for beginners in robotics to understand the basic ideas behind each algorithm. diff --git a/docs/index_main.rst b/docs/index_main.rst index 8c967ac59e..b9f334dd9b 100644 --- a/docs/index_main.rst +++ b/docs/index_main.rst @@ -6,7 +6,7 @@ Welcome to PythonRobotics's documentation! ========================================== -"PythonRobotics" is a Python code collections and html based text book +"PythonRobotics" is a Python code collections and textbook (This document) for robotics algorithm, which is developed on `GitHub`_. See this section (:ref:`What is PythonRobotics?`) for more details of this project. From 6744d4b104d9281f0a6c3404860b996f9d53d0a8 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 27 Jan 2025 22:41:52 +0900 Subject: [PATCH 831/940] copy paper contents (#1129) * copy paper contents * copy paper contents --- README.md | 8 +++- docs/getting_started_main.rst | 42 ++++++++++++++----- .../definition_of_robotics_main.rst | 5 ++- .../technology_for_robotics_main.rst | 10 ++++- .../2_localization/localization_main.rst | 1 + docs/modules/3_mapping/mapping_main.rst | 2 + docs/modules/4_slam/slam_main.rst | 2 + .../5_path_planning/path_planning_main.rst | 2 + .../6_path_tracking/path_tracking_main.rst | 2 + 9 files changed, 60 insertions(+), 14 deletions(-) diff --git a/README.md b/README.md index 8621a40923..cb1816c2b5 100644 --- a/README.md +++ b/README.md @@ -6,7 +6,7 @@ ![GitHub_Action_Windows_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/Windows_CI/badge.svg) [![Build status](https://ci.appveyor.com/api/projects/status/sb279kxuv1be391g?svg=true)](https://ci.appveyor.com/project/AtsushiSakai/pythonrobotics) -Python codes and textbook for robotics algorithm. +Python codes and [textbook](https://atsushisakai.github.io/PythonRobotics/index.html) for robotics algorithm. # Table of Contents @@ -85,7 +85,11 @@ Features: 3. Minimum dependency. -See this paper for more details: +See this documentation + +- [Getting Started — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/getting_started.html#what-is-pythonrobotics) + +or this paper for more details: - [\[1808\.10703\] PythonRobotics: a Python code collection of robotics algorithms](https://arxiv.org/abs/1808.10703) ([BibTeX](https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib)) diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index 86049ac2bf..aaf304514d 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -9,27 +9,49 @@ What is PythonRobotics? ------------------------ This is an Open Source Software (OSS) project: PythonRobotics, which is a Python code collection of robotics algorithms. +These codes are developed under `MIT license`_ and on `GitHub`_. -This is developed under `MIT license`_ and on `GitHub`_. +This project has three main philosophies below: -The focus of the project is on autonomous navigation, and the goal is for beginners in robotics to understand the basic ideas behind each algorithm. +1. Easy to understand each algorithm's basic idea. +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -In this project, the algorithms which are practical and widely used in both academia and industry are selected. +The goal is for beginners in robotics to understand the basic ideas behind each algorithm. +If the code is not easy to read, it would be difficult to achieve our goal of +allowing beginners to understand the algorithms. -Each sample code is written in Python3 and only depends on some standard modules for readability and ease of use. +Python[12] programming language is adopted in this project. +Python has great libraries for matrix operation, mathematical and scientific operation, +and visualization, which makes code more readable because such operations +don’t need to be re-implemented. +Having the core Python packages allows the user to focus on the algorithms, +rather than the implementations. It includes intuitive animations to understand the behavior of the simulation. -.. _GitHub: https://github.com/AtsushiSakai/PythonRobotics -.. _`MIT license`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/LICENSE - -Features: - -1. Easy to read for understanding each algorithm's basic idea. +about documenttion 2. Widely used and practical algorithms are selected. +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The second philosophy is that implemented algorithms have to be practical +and widely used in both academia and industry. +We believe learning these algorithms will be useful in many applications. +For example, Kalman filters and particle filter for localization, +grid mapping for mapping, +dynamic programming based approaches and sampling based approaches for path planning, +and optimal control based approach for path tracking. +These algorithms are implemented in this project. 3. Minimum dependency. +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Each sample code is written in Python3 and only depends on some standard +modules for readability and ease of use. + + +.. _GitHub: https://github.com/AtsushiSakai/PythonRobotics +.. _`MIT license`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/LICENSE See this paper for more details: diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst index bdc7dc53e9..2f31834017 100644 --- a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst +++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst @@ -1,4 +1,7 @@ Definition of Robotics ---------------------- -TBD +In recent years, autonomous navigation technologies have received huge +attention in many fields. +Such fields include, autonomous driving[22], drone flight navigation, +and other transportation systems. diff --git a/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst b/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst index 4c60ab8851..4dd1d1842f 100644 --- a/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst +++ b/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst @@ -1,4 +1,12 @@ Technology for Robotics ------------------------- -TBD +An autonomous navigation system is a system that can move to a goal over long +periods of time without any external control by an operator. +The system requires a wide range of technologies: +- It needs to know where it is (localization) +- Where it is safe (mapping) +- Where and how to move (path planning) +- How to control its motion (path following). + +The autonomous system would not work correctly if any of these technologies is missing. diff --git a/docs/modules/2_localization/localization_main.rst b/docs/modules/2_localization/localization_main.rst index db6651f6b8..22cbd094da 100644 --- a/docs/modules/2_localization/localization_main.rst +++ b/docs/modules/2_localization/localization_main.rst @@ -2,6 +2,7 @@ Localization ============ +Localization is the ability of a robot to know its position and orientation with sensors such as Global Navigation Satellite System:GNSS etc. In localization, Bayesian filters such as Kalman filters, histogram filter, and particle filter are widely used[31]. Fig.2 shows localization simulations using histogram filter and particle filter. .. toctree:: :maxdepth: 2 diff --git a/docs/modules/3_mapping/mapping_main.rst b/docs/modules/3_mapping/mapping_main.rst index a98acaaf50..28e18984d3 100644 --- a/docs/modules/3_mapping/mapping_main.rst +++ b/docs/modules/3_mapping/mapping_main.rst @@ -2,6 +2,8 @@ Mapping ======= +Mapping is the ability of a robot to understand its surroundings with external sensors such as LIDAR and camera. Robots have to recognize the position and shape of obstacles to avoid them. In mapping, grid mapping and machine learning algorithms are widely used[31][18]. Fig.3 shows mapping simulation results using grid mapping with 2D ray casting and 2D object clustering with k-means algorithm. + .. toctree:: :maxdepth: 2 :caption: Contents diff --git a/docs/modules/4_slam/slam_main.rst b/docs/modules/4_slam/slam_main.rst index 86befa6e35..dec04f253a 100644 --- a/docs/modules/4_slam/slam_main.rst +++ b/docs/modules/4_slam/slam_main.rst @@ -4,6 +4,8 @@ SLAM ==== Simultaneous Localization and Mapping(SLAM) examples +Simultaneous Localization and Mapping (SLAM) is an ability to estimate the pose of a robot and the map of the environment at the same time. The SLAM problem is hard to +solve, because a map is needed for localization and localization is needed for mapping. In this way, SLAM is often said to be similar to a ‘chicken-and-egg’ problem. Popular SLAM solution methods include the extended Kalman filter, particle filter, and Fast SLAM algorithm[31]. Fig.4 shows SLAM simulation results using extended Kalman filter and results using FastSLAM2.0[31]. .. toctree:: :maxdepth: 2 diff --git a/docs/modules/5_path_planning/path_planning_main.rst b/docs/modules/5_path_planning/path_planning_main.rst index 30802fd7a6..4960330b3e 100644 --- a/docs/modules/5_path_planning/path_planning_main.rst +++ b/docs/modules/5_path_planning/path_planning_main.rst @@ -3,6 +3,8 @@ Path Planning ============= +Path planning is the ability of a robot to search feasible and efficient path to the goal. The path has to satisfy some constraints based on the robot’s motion model and obstacle positions, and optimize some objective functions such as time to goal and distance to obstacle. In path planning, dynamic programming based approaches and sampling based approaches are widely used[22]. Fig.5 shows simulation results of potential field path planning and LQRRRT* path planning[27]. + .. toctree:: :maxdepth: 2 :caption: Contents diff --git a/docs/modules/6_path_tracking/path_tracking_main.rst b/docs/modules/6_path_tracking/path_tracking_main.rst index 504ba08795..d7a895b562 100644 --- a/docs/modules/6_path_tracking/path_tracking_main.rst +++ b/docs/modules/6_path_tracking/path_tracking_main.rst @@ -3,6 +3,8 @@ Path Tracking ============= +Path tracking is the ability of a robot to follow the reference path generated by a path planner while simultaneously stabilizing the robot. The path tracking controller may need to account for modeling error and other forms of uncertainty. In path tracking, feedback control techniques and optimization based control techniques are widely used[22]. Fig.6 shows simulations using rear wheel feedback steering control and PID speed control, and iterative linear model predictive path tracking control[27]. + .. toctree:: :maxdepth: 2 :caption: Contents From 53f1ba35d5c1b981eca55a91b72c53fb1000263a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 28 Jan 2025 09:19:20 +0900 Subject: [PATCH 832/940] build(deps): bump ruff from 0.9.2 to 0.9.3 in /requirements (#1130) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.9.2 to 0.9.3. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.9.2...0.9.3) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 11b91abb1f..e8bed7b6d7 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.14.1 # For unit test -ruff == 0.9.2 # For unit test +ruff == 0.9.3 # For unit test From fc3562733814e43134da8a1d7d73e370d44b9f4e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 28 Jan 2025 22:25:53 +0900 Subject: [PATCH 833/940] update getting started (#1131) --- docs/getting_started_main.rst | 122 ++------------------------ docs/how_to_read_textbook_main.rst | 4 + docs/how_to_use_main.rst | 30 +++++++ docs/what_is_python_robotics_main.rst | 100 +++++++++++++++++++++ 4 files changed, 140 insertions(+), 116 deletions(-) create mode 100644 docs/how_to_read_textbook_main.rst create mode 100644 docs/how_to_use_main.rst create mode 100644 docs/what_is_python_robotics_main.rst diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index aaf304514d..07abeec451 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -3,120 +3,10 @@ Getting Started =============== -.. _`What is PythonRobotics?`: - -What is PythonRobotics? ------------------------- - -This is an Open Source Software (OSS) project: PythonRobotics, which is a Python code collection of robotics algorithms. -These codes are developed under `MIT license`_ and on `GitHub`_. - -This project has three main philosophies below: - -1. Easy to understand each algorithm's basic idea. -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -The goal is for beginners in robotics to understand the basic ideas behind each algorithm. -If the code is not easy to read, it would be difficult to achieve our goal of -allowing beginners to understand the algorithms. - -Python[12] programming language is adopted in this project. -Python has great libraries for matrix operation, mathematical and scientific operation, -and visualization, which makes code more readable because such operations -don’t need to be re-implemented. -Having the core Python packages allows the user to focus on the algorithms, -rather than the implementations. - -It includes intuitive animations to understand the behavior of the simulation. - -about documenttion - -2. Widely used and practical algorithms are selected. -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -The second philosophy is that implemented algorithms have to be practical -and widely used in both academia and industry. -We believe learning these algorithms will be useful in many applications. -For example, Kalman filters and particle filter for localization, -grid mapping for mapping, -dynamic programming based approaches and sampling based approaches for path planning, -and optimal control based approach for path tracking. -These algorithms are implemented in this project. - -3. Minimum dependency. -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -Each sample code is written in Python3 and only depends on some standard -modules for readability and ease of use. - - -.. _GitHub: https://github.com/AtsushiSakai/PythonRobotics -.. _`MIT license`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/LICENSE - - -See this paper for more details: - -- PythonRobotics: a Python code collection of robotics algorithms: https://arxiv.org/abs/1808.10703 - -.. _`Requirements`: - -Requirements -------------- - -- `Python 3.12.x`_ -- `NumPy`_ -- `SciPy`_ -- `Matplotlib`_ -- `cvxpy`_ - -For development: - -- `pytest`_ (for unit tests) -- `pytest-xdist`_ (for parallel unit tests) -- `mypy`_ (for type check) -- `sphinx`_ (for document generation) -- `ruff`_ (for code style check) - -.. _`Python 3.12.x`: https://www.python.org/ -.. _`NumPy`: https://numpy.org/ -.. _`SciPy`: https://scipy.org/ -.. _`Matplotlib`: https://matplotlib.org/ -.. _`cvxpy`: https://www.cvxpy.org/ -.. _`pytest`: https://docs.pytest.org/en/latest/ -.. _`pytest-xdist`: https://github.com/pytest-dev/pytest-xdist -.. _`mypy`: https://mypy-lang.org/ -.. _`sphinx`: https://www.sphinx-doc.org/en/master/index.html -.. _`ruff`: https://github.com/astral-sh/ruff - - -How to use ----------- - -1. Clone this repo and go into dir. - -.. code-block:: - - >$ git clone https://github.com/AtsushiSakai/PythonRobotics.git - - >$ cd PythonRobotics - - -2. Install the required libraries. - -using conda : - -.. code-block:: - - >$ conda env create -f requirements/environment.yml - -using pip : - -.. code-block:: - - >$ pip install -r requirements/requirements.txt - - -3. Execute python script in each directory. - -4. Add star to this repo if you like it 😃. +.. toctree:: + :maxdepth: 2 + :caption: Contents + what_is_python_robotics + how_to_use + how_to_read_textbook diff --git a/docs/how_to_read_textbook_main.rst b/docs/how_to_read_textbook_main.rst new file mode 100644 index 0000000000..3b92970e26 --- /dev/null +++ b/docs/how_to_read_textbook_main.rst @@ -0,0 +1,4 @@ +How To read this textbook +-------------------------- + +TBD \ No newline at end of file diff --git a/docs/how_to_use_main.rst b/docs/how_to_use_main.rst new file mode 100644 index 0000000000..d21b07c1a3 --- /dev/null +++ b/docs/how_to_use_main.rst @@ -0,0 +1,30 @@ +How to use +---------- + +1. Clone this repo and go into dir. + +.. code-block:: + + >$ git clone https://github.com/AtsushiSakai/PythonRobotics.git + + >$ cd PythonRobotics + + +2. Install the required libraries. + +using conda : + +.. code-block:: + + >$ conda env create -f requirements/environment.yml + +using pip : + +.. code-block:: + + >$ pip install -r requirements/requirements.txt + + +3. Execute python script in each directory. + +4. Add star to this repo if you like it 😃. diff --git a/docs/what_is_python_robotics_main.rst b/docs/what_is_python_robotics_main.rst new file mode 100644 index 0000000000..ce6e059dba --- /dev/null +++ b/docs/what_is_python_robotics_main.rst @@ -0,0 +1,100 @@ +.. _`What is PythonRobotics?`: + +What is PythonRobotics? +------------------------ + +This is an Open Source Software (OSS) project: PythonRobotics, which is a Python code collection of robotics algorithms. +These codes are developed under `MIT license`_ and on `GitHub`_. + +This project has three main philosophies below: + +1. Easy to understand each algorithm's basic idea. +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The goal is for beginners in robotics to understand the basic ideas behind each algorithm. + +`Python`_ programming language is adopted in this project to achieve the goal. +Python is a high-level programming language that is easy to read and write. +If the code is not easy to read, it would be difficult to achieve our goal of +allowing beginners to understand the algorithms. +Python has great libraries for matrix operation, mathematical and scientific operation, +and visualization, which makes code more readable because such operations +don’t need to be re-implemented. +Having the core Python packages allows the user to focus on the algorithms, +rather than the implementations. + +PythonRobotics provides not only the code but also intuitive animations that +visually demonstrate the process and behavior of each algorithm over time. +This is an example of an animation gif file that shows the process of the +path planning in a highway scenario for autonomous vehicle. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/high_speed_and_velocity_keeping_frenet_path.gif + +This animation is a gif file and is created using the `Matplotlib`_ library. +All animaion gif files are stored in the `PythonRoboticsGifs`_ repository and +all animation movies are uploaded to this `YouTube channel`_. + +PythonRobotics also provides a textbook that explains the basic ideas of each algorithm. + +.. _`Python`: https://www.python.org/ +.. _`PythonRoboticsGifs`: https://github.com/AtsushiSakai/PythonRoboticsGifs +.. _`YouTube channel`: https://youtube.com/playlist?list=PL12URV8HFpCozuz0SDxke6b2ae5UZvIwa&si=AH2fNPPYufPtK20S + + +2. Widely used and practical algorithms are selected. +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The second philosophy is that implemented algorithms have to be practical +and widely used in both academia and industry. +We believe learning these algorithms will be useful in many applications. +For example, Kalman filters and particle filter for localization, +grid mapping for mapping, +dynamic programming based approaches and sampling based approaches for path planning, +and optimal control based approach for path tracking. +These algorithms are implemented in this project. + +3. Minimum dependency. +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Each sample code is written in Python3 and only depends on some standard +modules for readability and ease of use. + + +.. _GitHub: https://github.com/AtsushiSakai/PythonRobotics +.. _`MIT license`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/LICENSE + + +See this paper for more details: + +- PythonRobotics: a Python code collection of robotics algorithms: https://arxiv.org/abs/1808.10703 + +.. _`Requirements`: + +Requirements +============ + +- `Python 3.12.x`_ +- `NumPy`_ +- `SciPy`_ +- `Matplotlib`_ +- `cvxpy`_ + +For development: + +- `pytest`_ (for unit tests) +- `pytest-xdist`_ (for parallel unit tests) +- `mypy`_ (for type check) +- `sphinx`_ (for document generation) +- `ruff`_ (for code style check) + +.. _`Python 3.12.x`: https://www.python.org/ +.. _`NumPy`: https://numpy.org/ +.. _`SciPy`: https://scipy.org/ +.. _`Matplotlib`: https://matplotlib.org/ +.. _`cvxpy`: https://www.cvxpy.org/ +.. _`pytest`: https://docs.pytest.org/en/latest/ +.. _`pytest-xdist`: https://github.com/pytest-dev/pytest-xdist +.. _`mypy`: https://mypy-lang.org/ +.. _`sphinx`: https://www.sphinx-doc.org/en/master/index.html +.. _`ruff`: https://github.com/astral-sh/ruff + From 44bad786829e713c44259bc18cc7ac24b6c1e24c Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 29 Jan 2025 21:54:18 +0900 Subject: [PATCH 834/940] update getting started (#1132) --- docs/how_to_read_textbook_main.rst | 4 ---- docs/index_main.rst | 3 +-- .../0_getting_started_main.rst} | 7 +++--- .../1_what_is_python_robotics_main.rst} | 23 +++++++++++++------ .../0_getting_started/2_how_to_use_main.rst} | 0 .../3_how_to_contribute_main.rst} | 0 .../4_how_to_read_textbook_main.rst | 6 +++++ 7 files changed, 27 insertions(+), 16 deletions(-) delete mode 100644 docs/how_to_read_textbook_main.rst rename docs/{getting_started_main.rst => modules/0_getting_started/0_getting_started_main.rst} (53%) rename docs/{what_is_python_robotics_main.rst => modules/0_getting_started/1_what_is_python_robotics_main.rst} (79%) rename docs/{how_to_use_main.rst => modules/0_getting_started/2_how_to_use_main.rst} (100%) rename docs/{how_to_contribute_main.rst => modules/0_getting_started/3_how_to_contribute_main.rst} (100%) create mode 100644 docs/modules/0_getting_started/4_how_to_read_textbook_main.rst diff --git a/docs/how_to_read_textbook_main.rst b/docs/how_to_read_textbook_main.rst deleted file mode 100644 index 3b92970e26..0000000000 --- a/docs/how_to_read_textbook_main.rst +++ /dev/null @@ -1,4 +0,0 @@ -How To read this textbook --------------------------- - -TBD \ No newline at end of file diff --git a/docs/index_main.rst b/docs/index_main.rst index b9f334dd9b..c1e8d22d32 100644 --- a/docs/index_main.rst +++ b/docs/index_main.rst @@ -33,7 +33,7 @@ this graph shows GitHub star history of this project: :maxdepth: 2 :caption: Table of Contents - getting_started + modules/0_getting_started/0_getting_started modules/1_introduction/introduction modules/2_localization/localization modules/3_mapping/mapping @@ -46,7 +46,6 @@ this graph shows GitHub star history of this project: modules/10_control/control modules/11_utils/utils modules/12_appendix/appendix - how_to_contribute Indices and tables diff --git a/docs/getting_started_main.rst b/docs/modules/0_getting_started/0_getting_started_main.rst similarity index 53% rename from docs/getting_started_main.rst rename to docs/modules/0_getting_started/0_getting_started_main.rst index 07abeec451..cfec5b3c73 100644 --- a/docs/getting_started_main.rst +++ b/docs/modules/0_getting_started/0_getting_started_main.rst @@ -7,6 +7,7 @@ Getting Started :maxdepth: 2 :caption: Contents - what_is_python_robotics - how_to_use - how_to_read_textbook + 1_what_is_python_robotics + 2_how_to_use + 3_how_to_contribute + 4_how_to_read_textbook diff --git a/docs/what_is_python_robotics_main.rst b/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst similarity index 79% rename from docs/what_is_python_robotics_main.rst rename to docs/modules/0_getting_started/1_what_is_python_robotics_main.rst index ce6e059dba..32b1ad4e5d 100644 --- a/docs/what_is_python_robotics_main.rst +++ b/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst @@ -8,7 +8,7 @@ These codes are developed under `MIT license`_ and on `GitHub`_. This project has three main philosophies below: -1. Easy to understand each algorithm's basic idea. +Philosophy 1. Easy to understand each algorithm's basic idea. ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ The goal is for beginners in robotics to understand the basic ideas behind each algorithm. @@ -31,17 +31,26 @@ path planning in a highway scenario for autonomous vehicle. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/FrenetOptimalTrajectory/high_speed_and_velocity_keeping_frenet_path.gif This animation is a gif file and is created using the `Matplotlib`_ library. -All animaion gif files are stored in the `PythonRoboticsGifs`_ repository and -all animation movies are uploaded to this `YouTube channel`_. +All animation gif files are stored in the `PythonRoboticsGifs`_ repository and +all animation movies are also uploaded to this `YouTube channel`_. PythonRobotics also provides a textbook that explains the basic ideas of each algorithm. +The PythonRobotics textbook allows you to learn fundamental algorithms used in +robotics with minimal mathematical formulas and textual explanations, +based on PythonRobotics’ sample codes and animations. +The contents of this document, like the code, are managed in the PythonRobotics +`GitHub`_ repository and converted into HTML-based online documents using `Sphinx`_, +which is a Python-based documentation builder. +Please refer to this section ":ref:`How to read this textbook`" for information on +how to read this document for learning. + .. _`Python`: https://www.python.org/ .. _`PythonRoboticsGifs`: https://github.com/AtsushiSakai/PythonRoboticsGifs .. _`YouTube channel`: https://youtube.com/playlist?list=PL12URV8HFpCozuz0SDxke6b2ae5UZvIwa&si=AH2fNPPYufPtK20S -2. Widely used and practical algorithms are selected. +Philosophy 2. Widely used and practical algorithms are selected. ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ The second philosophy is that implemented algorithms have to be practical @@ -53,7 +62,7 @@ dynamic programming based approaches and sampling based approaches for path plan and optimal control based approach for path tracking. These algorithms are implemented in this project. -3. Minimum dependency. +Philosophy 3. Minimum dependency. ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Each sample code is written in Python3 and only depends on some standard @@ -84,7 +93,7 @@ For development: - `pytest`_ (for unit tests) - `pytest-xdist`_ (for parallel unit tests) - `mypy`_ (for type check) -- `sphinx`_ (for document generation) +- `Sphinx`_ (for document generation) - `ruff`_ (for code style check) .. _`Python 3.12.x`: https://www.python.org/ @@ -95,6 +104,6 @@ For development: .. _`pytest`: https://docs.pytest.org/en/latest/ .. _`pytest-xdist`: https://github.com/pytest-dev/pytest-xdist .. _`mypy`: https://mypy-lang.org/ -.. _`sphinx`: https://www.sphinx-doc.org/en/master/index.html +.. _`Sphinx`: https://www.sphinx-doc.org/en/master/index.html .. _`ruff`: https://github.com/astral-sh/ruff diff --git a/docs/how_to_use_main.rst b/docs/modules/0_getting_started/2_how_to_use_main.rst similarity index 100% rename from docs/how_to_use_main.rst rename to docs/modules/0_getting_started/2_how_to_use_main.rst diff --git a/docs/how_to_contribute_main.rst b/docs/modules/0_getting_started/3_how_to_contribute_main.rst similarity index 100% rename from docs/how_to_contribute_main.rst rename to docs/modules/0_getting_started/3_how_to_contribute_main.rst diff --git a/docs/modules/0_getting_started/4_how_to_read_textbook_main.rst b/docs/modules/0_getting_started/4_how_to_read_textbook_main.rst new file mode 100644 index 0000000000..fb8db348c6 --- /dev/null +++ b/docs/modules/0_getting_started/4_how_to_read_textbook_main.rst @@ -0,0 +1,6 @@ +.. _`How to read this textbook`: + +How to read this textbook +-------------------------- + +TBD \ No newline at end of file From 2b9cc06000a4ae57dce885240d04e38e30cff8e3 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 30 Jan 2025 22:25:45 +0900 Subject: [PATCH 835/940] update getting started (#1133) --- .../0_getting_started_main.rst | 2 +- .../1_what_is_python_robotics_main.rst | 49 ++++++++++++------- ...rst => 2_how_to_run_sample_codes_main.rst} | 6 ++- 3 files changed, 37 insertions(+), 20 deletions(-) rename docs/modules/0_getting_started/{2_how_to_use_main.rst => 2_how_to_run_sample_codes_main.rst} (84%) diff --git a/docs/modules/0_getting_started/0_getting_started_main.rst b/docs/modules/0_getting_started/0_getting_started_main.rst index cfec5b3c73..cb2cba4784 100644 --- a/docs/modules/0_getting_started/0_getting_started_main.rst +++ b/docs/modules/0_getting_started/0_getting_started_main.rst @@ -8,6 +8,6 @@ Getting Started :caption: Contents 1_what_is_python_robotics - 2_how_to_use + 2_how_to_run_sample_codes 3_how_to_contribute 4_how_to_read_textbook diff --git a/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst b/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst index 32b1ad4e5d..8c932b7263 100644 --- a/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst +++ b/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst @@ -6,6 +6,9 @@ What is PythonRobotics? This is an Open Source Software (OSS) project: PythonRobotics, which is a Python code collection of robotics algorithms. These codes are developed under `MIT license`_ and on `GitHub`_. +.. _GitHub: https://github.com/AtsushiSakai/PythonRobotics +.. _`MIT license`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/LICENSE + This project has three main philosophies below: Philosophy 1. Easy to understand each algorithm's basic idea. @@ -60,35 +63,32 @@ For example, Kalman filters and particle filter for localization, grid mapping for mapping, dynamic programming based approaches and sampling based approaches for path planning, and optimal control based approach for path tracking. -These algorithms are implemented in this project. +These algorithms are implemented and explained in the textbook in this project. Philosophy 3. Minimum dependency. ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -Each sample code is written in Python3 and only depends on some standard -modules for readability and ease of use. - - -.. _GitHub: https://github.com/AtsushiSakai/PythonRobotics -.. _`MIT license`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/LICENSE - - -See this paper for more details: +Each sample code of PythonRobotics is written in Python3 and only depends on +some standard modules for readability and ease to setup and use. -- PythonRobotics: a Python code collection of robotics algorithms: https://arxiv.org/abs/1808.10703 .. _`Requirements`: Requirements ============ -- `Python 3.12.x`_ -- `NumPy`_ -- `SciPy`_ -- `Matplotlib`_ -- `cvxpy`_ +PythonRobotics depends only on the following five libraries, +including Python itself, to run each sample code. -For development: +- `Python 3.12.x`_ (for Python runtime) +- `NumPy`_ (for matrix operation) +- `SciPy`_ (for scientific operation) +- `cvxpy`_ (for convex optimization) +- `Matplotlib`_ (for visualization) + +If you only need to run the code, the five libraries mentioned above are sufficient. +However, for code development or creating documentation for the textbook, +the following additional libraries are required. - `pytest`_ (for unit tests) - `pytest-xdist`_ (for parallel unit tests) @@ -107,3 +107,18 @@ For development: .. _`Sphinx`: https://www.sphinx-doc.org/en/master/index.html .. _`ruff`: https://github.com/astral-sh/ruff +For instructions on installing the above libraries, please refer to +this section ":ref:`How to run sample codes`". + +Arxiv paper +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +We have published a paper on this project on Arxiv in 2018. + +See this paper for more details about this Project: + +- `PythonRobotics: a Python code collection of robotics algorithms`_ (`BibTeX`_) + +.. _`PythonRobotics: a Python code collection of robotics algorithms`: https://arxiv.org/abs/1808.10703 +.. _`BibTeX`: https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib + diff --git a/docs/modules/0_getting_started/2_how_to_use_main.rst b/docs/modules/0_getting_started/2_how_to_run_sample_codes_main.rst similarity index 84% rename from docs/modules/0_getting_started/2_how_to_use_main.rst rename to docs/modules/0_getting_started/2_how_to_run_sample_codes_main.rst index d21b07c1a3..eff54d3426 100644 --- a/docs/modules/0_getting_started/2_how_to_use_main.rst +++ b/docs/modules/0_getting_started/2_how_to_run_sample_codes_main.rst @@ -1,5 +1,7 @@ -How to use ----------- +.. _`How to run sample codes`: + +How to run sample codes +------------------------- 1. Clone this repo and go into dir. From a5fc2d039db9cdf6182d9fc97073b0d6e7388830 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 31 Jan 2025 21:38:06 +0900 Subject: [PATCH 836/940] update getting started (#1134) Co-authored-by: Atsushi Sakai --- .../2_how_to_run_sample_codes_main.rst | 94 ++++++++++++++++++- 1 file changed, 90 insertions(+), 4 deletions(-) diff --git a/docs/modules/0_getting_started/2_how_to_run_sample_codes_main.rst b/docs/modules/0_getting_started/2_how_to_run_sample_codes_main.rst index eff54d3426..b92fc9bde0 100644 --- a/docs/modules/0_getting_started/2_how_to_run_sample_codes_main.rst +++ b/docs/modules/0_getting_started/2_how_to_run_sample_codes_main.rst @@ -3,7 +3,21 @@ How to run sample codes ------------------------- -1. Clone this repo and go into dir. +In this chapter, we will explain the setup process for running each sample code +in PythonRobotics and describe the contents of each directory. + +Steps to setup and run sample codes +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +1. Install `Python 3.12.x`_ + +Note that older versions of Python3 might work, but we recommend using +the specified version, because the sample codes are only tested with it. + +2. If you prefer to use conda for package management, install +Anaconda or Miniconda to use `conda`_ command. + +3. Clone this repo and go into dir. .. code-block:: @@ -12,7 +26,10 @@ How to run sample codes >$ cd PythonRobotics -2. Install the required libraries. +4. Install the required libraries. + +We have prepared requirements management files for `conda`_ and `pip`_ under +the requirements directory. Using these files makes it easy to install the necessary libraries. using conda : @@ -27,6 +44,75 @@ using pip : >$ pip install -r requirements/requirements.txt -3. Execute python script in each directory. +5. Execute python script in each directory. + +For example, to run the sample code of `Extented Kalman Filter` in the +`localization` directory, execute the following command: + +.. code-block:: + + >$ cd localization/extended_kalman_filter + + >$ python extended_kalman_filter.py + +Then, you can see this animation of the EKF algorithm based localization: + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Localization/extended_kalman_filter/animation.gif + +Please refer to the `Directory structure`_ section for more details on the contents of each directory. + +6. Add star to this repo if you like it 😃. + +.. _`Python 3.12.x`: https://www.python.org/ +.. _`conda`: https://docs.conda.io/projects/conda/en/stable/user-guide/install/index.html +.. _`pip`: https://pip.pypa.io/en/stable/ +.. _`the requirements directory`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/requirements + +.. _`Directory structure`: + +Directory structure +~~~~~~~~~~~~~~~~~~~~ + +The top-level directory structure of PythonRobotics is as follows: + +Sample codes directories: + +- `AerialNavigation`_ : the sample codes of aerial navigation algorithms for drones and rocket landing. +- `ArmNavigation`_ : the sample codes of arm navigation algorithms for robotic arms. +- `Localization`_ : the sample codes of localization algorithms. +- `Bipedal`_ : the sample codes of bipedal walking algorithms for legged robots. +- `Control`_ : the sample codes of control algorithms for robotic systems. +- `Mapping`_ : the sample codes of mapping or obstacle shape recognition algorithms. +- `PathPlanning`_ : the sample codes of path planning algorithms. +- `PathTracking`_ : the sample codes of path tracking algorithms for car like robots. +- `SLAM`_ : the sample codes of SLAM algorithms. + +Other directories: + +- `docs`_ : This directory contains the documentation of PythonRobotics. +- `requirements`_ : This directory contains the requirements management files. +- `tests`_ : This directory contains the unit test files. +- `utils`_ : This directory contains utility functions used in some sample codes in common. +- `.github`_ : This directory contains the GitHub Actions configuration files. +- `.circleci`_ : This directory contains the CircleCI configuration files. + +The structure of this document is the same as that of the sample code +directories mentioned above. +For more details, please refer to the :ref:`How to read this textbook` section. + -4. Add star to this repo if you like it 😃. +.. _`AerialNavigation`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/AerialNavigation +.. _`ArmNavigation`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/ArmNavigation +.. _`Localization`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/Localization +.. _`Bipedal`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/Bipedal +.. _`Control`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/Control +.. _`Mapping`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/Mapping +.. _`PathPlanning`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/PathPlanning +.. _`PathTracking`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/PathTracking +.. _`SLAM`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/SLAM +.. _`docs`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/docs +.. _`requirements`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/requirements +.. _`tests`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/tests +.. _`utils`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/utils +.. _`.github`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/.github +.. _`.circleci`: https://github.com/AtsushiSakai/PythonRobotics/tree/master/.circleci From f225c1845775cf8e1d8c62d04164743c2e9e00fc Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 1 Feb 2025 22:47:52 +0900 Subject: [PATCH 837/940] update getting started (#1135) Co-authored-by: Atsushi Sakai --- .../3_how_to_contribute_main.rst | 45 +++++++++++++++---- 1 file changed, 37 insertions(+), 8 deletions(-) diff --git a/docs/modules/0_getting_started/3_how_to_contribute_main.rst b/docs/modules/0_getting_started/3_how_to_contribute_main.rst index 915b2155e4..296e4e8658 100644 --- a/docs/modules/0_getting_started/3_how_to_contribute_main.rst +++ b/docs/modules/0_getting_started/3_how_to_contribute_main.rst @@ -2,9 +2,18 @@ How To Contribute ================= This document describes how to contribute this project. +There are several ways to contribute to this project as below: + +#. `Adding a new algorithm example`_ +#. `Reporting and fixing a defect`_ +#. `Adding missed documentations for existing examples`_ +#. `Supporting this project`_ + + +.. _`Adding a new algorithm example`: Adding a new algorithm example -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This is a step by step manual to add a new algorithm example. @@ -67,9 +76,16 @@ Please check other documents for details. You can build the doc locally based on `doc README`_. -Note that the `reStructuredText`_ based doc should only focus on the mathematics and the algorithm of the example. +For creating a gif animation, you can use this tool: `matplotrecorder`_. + +The created gif file should be stored in the `PythonRoboticsGifs`_ repository, +so please create a PR to add it and refer to it in the doc. + +Note that the `reStructuredText`_ based doc should only focus on the +mathematics and the algorithm of the example. -Documentations related codes should be in the python script as the header comments of the script or docstrings of each function. +Documentations related codes should be in the python script as the header +comments of the script or docstrings of each function. .. _`submit a pull request`: @@ -92,6 +108,9 @@ After that, I will start the review. Note that this is my hobby project; I appreciate your patience during the review process. +  + +.. _`Reporting and fixing a defect`: Reporting and fixing a defect ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -115,19 +134,24 @@ in the test code to show the issue was solved. This doc `submit a pull request`_ can be helpful to submit a pull request. +.. _`Adding missed documentations for existing examples`: + Adding missed documentations for existing examples ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Adding the missed documentations for existing examples is also great contribution. If you check the `Python Robotics Docs`_, you can notice that some of the examples -only have a simulation gif or short overview descriptions, +only have a simulation gif or short overview descriptions or just TBD., but no detailed algorithm or mathematical description. +These documents needs to be improved. This doc `how to write doc`_ can be helpful to write documents. +.. _`Supporting this project`: + Supporting this project -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^ Supporting this project financially is also a great contribution!!. @@ -141,10 +165,12 @@ If you or your company would like to support this project, please consider: If you would like to support us in some other way, please contact with creating an issue. -Sponsors ---------- +Current Major Sponsors +----------------------- + +#. `JetBrains`_ : They are providing a free license of their IDEs for this OSS development. +#. `1Password`_ : They are providing a free license of their 1Password team license for this OSS project. -1. `JetBrains`_ : They are providing a free license of their IDEs for this OSS development. .. _`Python Robotics Docs`: https://atsushisakai.github.io/PythonRobotics @@ -160,5 +186,8 @@ Sponsors .. _`Sponsor @AtsushiSakai on GitHub Sponsors`: https://github.com/sponsors/AtsushiSakai .. _`Become a backer or sponsor on Patreon`: https://www.patreon.com/myenigma .. _`One-time donation via PayPal`: https://www.paypal.com/paypalme/myenigmapay/ +.. _`1Password`: https://github.com/1Password/for-open-source +.. _`matplotrecorder`: https://github.com/AtsushiSakai/matplotrecorder +.. _`PythonRoboticsGifs`: https://github.com/AtsushiSakai/PythonRoboticsGifs From e6f5dfe537d97cf79d55ad2803911a135aeaa1fd Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 2 Feb 2025 21:34:26 +0900 Subject: [PATCH 838/940] update getting started (#1136) Co-authored-by: Atsushi Sakai --- .../0_getting_started/3_how_to_contribute_main.rst | 2 +- .../0_getting_started/4_how_to_read_textbook_main.rst | 10 +++++++++- docs/modules/1_introduction/introduction_main.rst | 2 +- 3 files changed, 11 insertions(+), 3 deletions(-) diff --git a/docs/modules/0_getting_started/3_how_to_contribute_main.rst b/docs/modules/0_getting_started/3_how_to_contribute_main.rst index 296e4e8658..6e5c1be8ee 100644 --- a/docs/modules/0_getting_started/3_how_to_contribute_main.rst +++ b/docs/modules/0_getting_started/3_how_to_contribute_main.rst @@ -1,4 +1,4 @@ -How To Contribute +How to contribute ================= This document describes how to contribute this project. diff --git a/docs/modules/0_getting_started/4_how_to_read_textbook_main.rst b/docs/modules/0_getting_started/4_how_to_read_textbook_main.rst index fb8db348c6..1625c838af 100644 --- a/docs/modules/0_getting_started/4_how_to_read_textbook_main.rst +++ b/docs/modules/0_getting_started/4_how_to_read_textbook_main.rst @@ -3,4 +3,12 @@ How to read this textbook -------------------------- -TBD \ No newline at end of file +This document is structured to help you learn the fundamental concepts +behind each sample code in PythonRobotics. + +If you already have some knowledge of robotics technologies, you can start +by reading any document that interests you. + +However, if you have no prior knowledge of robotics technologies, it is +recommended that you first read the :ref:`Introduction` section and then proceed +to the documents related to the technical fields that interest you. \ No newline at end of file diff --git a/docs/modules/1_introduction/introduction_main.rst b/docs/modules/1_introduction/introduction_main.rst index 4561efd349..ec1f237545 100644 --- a/docs/modules/1_introduction/introduction_main.rst +++ b/docs/modules/1_introduction/introduction_main.rst @@ -1,4 +1,4 @@ -.. _introduction: +.. _Introduction: Introduction ============ From 70269fe9601b6189914a739c4c0d42b598c3425b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 3 Feb 2025 22:19:10 +0900 Subject: [PATCH 839/940] update getting started (#1138) --- .../python_for_robotics_main.rst} | 5 +---- docs/modules/1_introduction/introduction_main.rst | 7 ++++++- 2 files changed, 7 insertions(+), 5 deletions(-) rename docs/modules/1_introduction/{2_software_for_robotics/software_for_robotics_main.rst => 2_python_for_robotics/python_for_robotics_main.rst} (51%) diff --git a/docs/modules/1_introduction/2_software_for_robotics/software_for_robotics_main.rst b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst similarity index 51% rename from docs/modules/1_introduction/2_software_for_robotics/software_for_robotics_main.rst rename to docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst index 835441f85d..23f31da779 100644 --- a/docs/modules/1_introduction/2_software_for_robotics/software_for_robotics_main.rst +++ b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst @@ -1,7 +1,4 @@ -Software for Robotics ----------------------- - Python for Robotics -~~~~~~~~~~~~~~~~~~~~~ +---------------------- TBD diff --git a/docs/modules/1_introduction/introduction_main.rst b/docs/modules/1_introduction/introduction_main.rst index ec1f237545..a7ce55f9bf 100644 --- a/docs/modules/1_introduction/introduction_main.rst +++ b/docs/modules/1_introduction/introduction_main.rst @@ -3,11 +3,16 @@ Introduction ============ +PythonRobotics is composed of two words: "Python" and "Robotics". +Therefore, I will first explain these two topics, Robotics and Python. +After that, I will provide an overview of the robotics technologies +covered in PythonRobotics. + .. toctree:: :maxdepth: 2 :caption: Table of Contents 1_definition_of_robotics/definition_of_robotics - 2_software_for_robotics/software_for_robotics + 2_python_for_robotics/python_for_robotics 3_technology_for_robotics/technology_for_robotics From 5b06435be9e24a73c8ee9d0f0acb1e409a118141 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 4 Feb 2025 07:37:17 +0900 Subject: [PATCH 840/940] build(deps): bump ruff from 0.9.3 to 0.9.4 in /requirements (#1139) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.9.3 to 0.9.4. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.9.3...0.9.4) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e8bed7b6d7..9d4e7deb4d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.14.1 # For unit test -ruff == 0.9.3 # For unit test +ruff == 0.9.4 # For unit test From 7b7bd784093e4d46108b667c54261d054894e875 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 5 Feb 2025 13:41:28 +0900 Subject: [PATCH 841/940] update introduction (#1141) --- .../python_for_robotics_main.rst | 46 +++++++++++++++++++ 1 file changed, 46 insertions(+) diff --git a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst index 23f31da779..1ad5316f53 100644 --- a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst +++ b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst @@ -1,4 +1,50 @@ Python for Robotics ---------------------- +Python for general-purpose programming +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +`Python `_ is an general-purpose programming language developed by +`Guido van Rossum `_ in the late 1980s. + +It features as follows: + +#. High-level +#. Interpreted +#. Dynamic type system (also type annotation is supported) +#. Emphasizes code readability +#. Rapid prototyping +#. Batteries included +#. Interoperability for C and Fortran + +Due to these features, Python is the most popular programming language +for educational purposes for programming beginners. + +Python for Scientific Computing +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Python itself was not designed for scientific computing. +However, scientists quickly recognized its strengths. +For example, + +#. High-level and interpreted features enable scientists to focus on their problems without dealing with low-level programming tasks like memory management. +#. Code readability, rapid prototyping, and batteries included features enables scientists who are not professional programmers, to solve their problems easily. +#. The interoperability to wrap C and Fortran libraries enables scientists to access already existed powerful scientific computing libraries. + +To address the more needs of scientific computing, many libraries have been developed. + +- `NumPy `_ is the fundamental package for scientific computing with Python. +- `SciPy `_ is a library that builds on NumPy and provides a large number of functions that operate on NumPy arrays and are useful for different types of scientific and engineering applications. +- `Matplotlib `_ is a plotting library for the Python programming language and its numerical mathematics extension NumPy. +- `Pandas `_ is a fast, powerful, flexible, and easy-to-use open-source data analysis and data manipulation library built on top of NumPy. +- `SymPy `_ is a Python library for symbolic mathematics. + +And more domain-specific libraries have been developed: +- `Scikit-learn `_ is a free software machine learning library for the Python programming language. +- `Scikit-image `_ is a collection of algorithms for image processing. + +Python for Robotics +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + TBD + From 322fead45a62417c5d0d7dbb07ef17067122da7b Mon Sep 17 00:00:00 2001 From: Aglargil <34728006+Aglargil@users.noreply.github.com> Date: Wed, 5 Feb 2025 20:56:13 +0800 Subject: [PATCH 842/940] feat: add DistanceMap (#1142) * feat: add DistanceMap * feat: add DistanceMap test * feat: add DistanceMap doc * feat: DistanceMap doc update * feat: DistanceMap update --- Mapping/DistanceMap/distance_map.py | 151 ++++++++++++++++++ .../3_mapping/distance_map/distance_map.png | Bin 0 -> 32698 bytes .../distance_map/distance_map_main.rst | 27 ++++ docs/modules/3_mapping/mapping_main.rst | 1 + tests/test_distance_map.py | 118 ++++++++++++++ 5 files changed, 297 insertions(+) create mode 100644 Mapping/DistanceMap/distance_map.py create mode 100644 docs/modules/3_mapping/distance_map/distance_map.png create mode 100644 docs/modules/3_mapping/distance_map/distance_map_main.rst create mode 100644 tests/test_distance_map.py diff --git a/Mapping/DistanceMap/distance_map.py b/Mapping/DistanceMap/distance_map.py new file mode 100644 index 0000000000..54c98c6a75 --- /dev/null +++ b/Mapping/DistanceMap/distance_map.py @@ -0,0 +1,151 @@ +""" +Distance Map + +author: Wang Zheng (@Aglargil) + +Ref: + +- [Distance Map] +(https://cs.brown.edu/people/pfelzens/papers/dt-final.pdf) +""" + +import numpy as np +import matplotlib.pyplot as plt + +INF = 1e20 +ENABLE_PLOT = True + + +def compute_sdf(obstacles): + """ + Compute the signed distance field (SDF) from a boolean field. + + Parameters + ---------- + obstacles : array_like + A 2D boolean array where '1' represents obstacles and '0' represents free space. + + Returns + ------- + array_like + A 2D array representing the signed distance field, where positive values indicate distance + to the nearest obstacle, and negative values indicate distance to the nearest free space. + """ + a = compute_udf(obstacles) + b = compute_udf(obstacles == 0) + return a - b + + +def compute_udf(obstacles): + """ + Compute the unsigned distance field (UDF) from a boolean field. + + Parameters + ---------- + obstacles : array_like + A 2D boolean array where '1' represents obstacles and '0' represents free space. + + Returns + ------- + array_like + A 2D array of distances from the nearest obstacle, with the same dimensions as `bool_field`. + """ + edt = obstacles.copy() + if not np.all(np.isin(edt, [0, 1])): + raise ValueError("Input array should only contain 0 and 1") + edt = np.where(edt == 0, INF, edt) + edt = np.where(edt == 1, 0, edt) + for row in range(len(edt)): + dt(edt[row]) + edt = edt.T + for row in range(len(edt)): + dt(edt[row]) + edt = edt.T + return np.sqrt(edt) + + +def dt(d): + """ + Compute 1D distance transform under the squared Euclidean distance + + Parameters + ---------- + d : array_like + Input array containing the distances. + + Returns: + -------- + d : array_like + The transformed array with computed distances. + """ + v = np.zeros(len(d) + 1) + z = np.zeros(len(d) + 1) + k = 0 + v[0] = 0 + z[0] = -INF + z[1] = INF + for q in range(1, len(d)): + s = ((d[q] + q * q) - (d[int(v[k])] + v[k] * v[k])) / (2 * q - 2 * v[k]) + while s <= z[k]: + k = k - 1 + s = ((d[q] + q * q) - (d[int(v[k])] + v[k] * v[k])) / (2 * q - 2 * v[k]) + k = k + 1 + v[k] = q + z[k] = s + z[k + 1] = INF + k = 0 + for q in range(len(d)): + while z[k + 1] < q: + k = k + 1 + dx = q - v[k] + d[q] = dx * dx + d[int(v[k])] + + +def main(): + obstacles = np.array( + [ + [1, 0, 0, 0, 0], + [0, 1, 1, 1, 0], + [0, 1, 1, 1, 0], + [0, 0, 1, 1, 0], + [0, 0, 1, 0, 0], + [0, 0, 0, 0, 0], + [0, 0, 0, 0, 0], + [0, 0, 0, 0, 0], + [0, 0, 1, 0, 0], + [0, 0, 0, 0, 0], + [0, 0, 0, 0, 0], + ] + ) + + # Compute the signed distance field + sdf = compute_sdf(obstacles) + udf = compute_udf(obstacles) + + if ENABLE_PLOT: + _, (ax1, ax2, ax3) = plt.subplots(1, 3, figsize=(15, 5)) + + obstacles_plot = ax1.imshow(obstacles, cmap="binary") + ax1.set_title("Obstacles") + ax1.set_xlabel("x") + ax1.set_ylabel("y") + plt.colorbar(obstacles_plot, ax=ax1) + + udf_plot = ax2.imshow(udf, cmap="viridis") + ax2.set_title("Unsigned Distance Field") + ax2.set_xlabel("x") + ax2.set_ylabel("y") + plt.colorbar(udf_plot, ax=ax2) + + sdf_plot = ax3.imshow(sdf, cmap="RdBu") + ax3.set_title("Signed Distance Field") + ax3.set_xlabel("x") + ax3.set_ylabel("y") + plt.colorbar(sdf_plot, ax=ax3) + + plt.tight_layout() + plt.show() + + +if __name__ == "__main__": + main() diff --git a/docs/modules/3_mapping/distance_map/distance_map.png b/docs/modules/3_mapping/distance_map/distance_map.png new file mode 100644 index 0000000000000000000000000000000000000000..2d89252a70358ad1b60025d7bb3d9a217a2cefcc GIT binary patch literal 32698 zcmbrm1yq&m_C35Yjx81jAO;wKf*_zYqJoHoq>?Hk-3=0U5sD&82#R!x(rJRC(ug1_ z0s_*pX}pF~IQnuGgV3br1&E)};?wTvS? zdXb_A+vZ0VUp1Cr^EJfF3q``7P}NxWSD>*qy> z(r5qt`2^hphhM+mv9W3C&!0W!venZ4{P~H;Md4p>S^fX(;u{-HYm#OBb=@*ntXQ#X z_3DU`5l3zNYW-nW!>*JUxCE#BZZvJbzgs7Wzl5~)f`*W&sZBv{@z zPN5jv$L%eP*W9y&d2dP5c$!6nPMDOJwW*t?@yax@=?R+*Ev_EJ`s|FFWTP;h9A~4# zJM7NWlT=RaXZBqh8CnTK1@%q?t?YaDq{&y!d3tX4ys>P1X>V%1OYwMvk!wXuO>;}0 zG)1mF&>}bb26yhUu9_5ON5}N9U%%dY@F3xfdDh3aY2a5JYH~q)k5*~fc!{w1xI5w z+x8&JcH)k*eCa(NJ=>|#w(*myl#;zV&h1+!$Exx^JwG?wj*RK1P5TZWJXrHo|HcF7 z4))1*1^503!WQ)+;t3V&{I%`xn`dE~VgXU=r^%5s$^8E^<6gRyKZ=T z#to2W*6sA}BNvK`7cN|A`)-T>b|E1R9v+^tj}~rW7P+JO zZ9!E!E^@QyEmgr{TeWUow0&1idzmbECB67WXtDToEt6+YMjK0ydMO7-o7m)_a-HR? zB^{rW!ZeZ%AKsQ1l3|tdEXnH0)od3$i;2waO8rvtaR0nZSFUgh2&lcfyrf)ugR4rj z4L29pr=4lFk8Uf79Y1;UBzbsIYHe75zjep}?l}>gHCF%q-Rsw{E0I}h3wHR_F*KLL zcjVxrJKI9eDwRhnsGmCZ=uudhU3W&Cae?=Gu{Lw8$2D4(=T7PAF|e>CyncOP$p$ek zUANJ2YEVqB`P9^S4<{?@{+$}hC1f4;H5YV-`|HG1IO{h)KiBaoK2X4-K5lAqJoey? z)g2`dFHH4b5r5m*W2B*&I52XU`L?T>HsIrX1jzt=Lf%xO=Z?QIefu*fCCZ?ScWxgBC#$~OseFov>k#E%gW}oRS0-j zN!yv7yvwbdFgR!%Z25A5arM*i%Zt}N!uDKmlY3zvy)mBSx{r@KZoDEHPn{G&Q7)$EJf*y8Q$567@X$E;={qso=_gBQCrS~XTJbGXJN1?%f@ytlU% zas~0qCnsN3Jk^)ovSmwq>KF5Y(O@naeSQ5*Y{tqA8v`tg&etmyDwgc2RcyD3P|j1{ zzkmNw?<@LP+>%(*vzWWQ4QB_u%yUQ2;0jJvHE9;QIe0z{8Ro5Qjqcf|a_8`uWZhtB zHRCnY)NE~&i$n&FV2TgruMOc(K@cY^LM>h+oW!MDw{CURW;|nY9V|WE$-QI8U;_J& z9Y?NRyO#Om>HEQ=5(P*EQa^@prczC#~<{Q5|cOF+%sN`T|th4Isn{m5I z3F%)KdaV~$>&ctWb)#lAv|peXD1|vF~BVl`(z`7cELL zuH^9Z^J7Ouj8%&-LugMd4U;zcaF54#>GZ(~+@%tB>fjaeiGAB1I6lgq9M%*a{;Vf7 z{^MDS*%tx3jtUvyWQztd65~VMr!vg*Chdb=hpTJy-19yq>LxyVwArq^HlwgjRZA=G zS&@+JrcIkN$Gfxa3fUtKoAbTMWDVh4P5QpR@qHZm!1*wKS^oOkN`8YP=1UhZekb!h zZ^PLWT@7>;OH+q>ClVTC^QI?zIM~@syV4pGma|HIe?>2@VrUq(lzDIHK#{NlJ3G7c zw_DPyuu{K%Jr#fanH07{tbIN1X35%J65E0-&yy(d`SUSR1j@=(B~HYPlq#KAq)EBm zXFil*!eis&c5KQu4(nIRBf_s ztTVKD^S?j3!Buv736m|g&LLJkQD+RnzByjXA_|)_JR-sv5sHJGJCQef^ZJ;p4q0`X z(^KP>3EIM4^*NeM0;VOnD0jOe(}VY1Sw|2z>r-bnH8uG@E-O=V9q&pD5VDJr7iwq2 zgtb?y>sD^@*Lw8k#u^vh+Y7mK27O6RlQdvPXoI7vgX-)AvR%!1FO^cjxtU!gli5Bi51jo+! zwED6KqAqOfjbGW26o}^w0W7ILT;-0anAvhyvjS5jb7fd1aIe)PY?_=znM-L6Zki;F zcBeNlee>o`J2r2Yln+ZhzD%_($j1Be{&&NGaqW#SF4R+5T!w#;?E9!EcU<1e$|}Xp z-Fk;~LD6-c5!K_Fw$TY$-9p-qO_!X1Bo$O-JK0PQCAwGM+_ZnNkTcP+xA8?~ecJ<< zZdwY%?(BT}o=bV(zH{c7fQ&kG3o%OXNytLzZ3uKQ%leIC8b zw@ybKx&PIsXr+S4Nw)jpvi^*Eo}+Ez(?)FfyS}8U3-|14IIG8Yf8Fjg%r@~YEiDmo zaUX1dd@gOPe|F|0ukR5Z9UZT#4Xz;oiEolktIN(}Wr?+YyuZ8P5HE=}Jo)z)tlWAJ zVQ{^TE5)NG`YJ0TtDK*BPfbefx?LwcsC@tko@~1TT|x$?`h48i%ACPI&tI#TYFd4Y z?LM9^A%A?^wrzo!)%x)f0`;siwCWqi8IVHo27Z%Ijy~AB&kykeMnn{6L zm1+eb0(8X_xW{5xFmba$f>uV^TD=eNx${if?vp7NYpcV$NxAML?9k2U`(ZY{h+>zZ zbiSqD(!2)@#U|A5Iw{|G@7_iC=}1p!sYGUH*D{MZmUyy=)(rlrE^jmNJ))%*gn-h= zf*>J)@U>M~_>0RA^}I1ZBgD|^6chCnYP1=1qWqh@meS@LlSKY}=Bb`!NuXb&PjUC} zW6czcApY#`>+5U1&Y955B0N?Dyz?ZVDla`nolo)7$4x}&=DF23xMPd#aUC1vsjjX* zgPb7NwiFM&?Jtr3x2#gWPNOaUu0>f`ke+PM9Q#i7B$44d#5+AwAbz%Jy@2Vx_KN7+ z)IOjdOf3Va+DK5E)4&TAgdn(*zxRLow`kvBkXl97XCwwqSOyUY#G}NNx5J5BLb;J8{*~G&6{6pVQGm~O<`^F_!<5GHMgWGq} z9t84F-0q{Y!7kkyb^+6*xcO@d<6}f=KYxE0>4U0GKul~h+)osxk7p zND#3i;$mVtxTIQmib~vmp;dbLjtCY}=aJX5}OM3 za-UC`b|%5rh3w9a=jQP_bZY^+#4EW3={b$HM^*x`q?lGKVJwt^1cBBzhd64VL~sSJ z?HBXDaYNbEG>$qnj*2VUyiQ2l>J0<`@VR)b)pzWXL60zNYEkLf?uLx7IV&k6`w0vf>r6DkH;uj8FcrFpJ6mys`$W>yr%!Eh zGgTuQ26dTs_~w}83|qUTazM$~SC@+w#9R+XbT7NQob{|*@$mQ3{n!Qtp1}g{ku03{ zhp&ijYi(`qsCVh9jF1boMXVF5Yev2(&uDuP3wV0z^5qx+KLQz242oG$)V^=4#h5vA zHf>?wyjha$a95o?;H2Xh{#v5s&!rucV_?=0Qo+W{`&8+NRj8*b$q^fg+^2z^96guClz~8-p}z zz-iQK4te9jT$$fD=Zt*4;fxdmEPKYTr(RopY9x%BO(L33V1Vo7P?a+xYb9VB5I5BCI-QRp+wSB71F6piurUj=`O2Yd6lkv zJb_nAp4YBl_vOiF(gQAU_6m^}63Q2N4S4wwpg&}-8=L?8a2f(Y^zF`@b_;fDy)V@F zdL_!^#~QBu(}1m|4C-36YE9Okt1{neEeBWHjWqLkpd5J&NO55eW7mSN9KuMB^+zgqqJO@JL|{O!_)36m(O8QiE;FWa_!I}8 zBbB22^c287;VB3SBKJV#IKV?@M@+1-mgd34wCZODJm#x1UAzh2umW_np& z6EUKaAXMy`#KMpbqpcm6naoR228AL38%~Z51ppIpr8mxUMV&Wcx1Q1w_4Sn_hAN!C zHGeGw0|Wcco$)$0*cI&vYLTZsOND!~!)j}_2yjG=liBPo9FvXhDj*hkO*QJ{yw;9n zlyCTps=1+B-@tVjbp~-J>mF8y)vIaGxa)+3m#RCGY<)+vkNDIvlCSt|T8{vE8of9_ zm%m=Gy)2y6=$LcY+yxGUQjRH=2z=Q5EW1;yws?P0?6VjKlzvu}l=rnEHIph&S++f3 zk3|9?%Xjj7#E%@~Vw3U+IlsU=0(|zVM&(kdXJY!>7#h5-#~eEFwNdK2uBwqi)`z_o z{6M+Mv2B~QprBx3ad8zwS*UP#`u;5Yu9#s#6-PWY4TW{;PWO-Qe{EANs@`K))oNpf z!17s%r(r+6=;Qhv7j>tiq=n2eV-_*#>7TQlge}=PYU$>9qHb8H$7f!fez@|od7378 zl<94Ho(Pj?-G)(*j)+VZh)+H2@9#gHRV906#kfI;Ybv41WXga{w?tdpeZ2){h1$kI zXe$ii7&8+ViP+SL9x3)x98<4oTfUg<+>=AKMG>Vkw#ZdOL&I-Fg~HyZIfMx!+{N+Z z_v=CW2-U5mY@F;+&+`RAiNWQZG_8zLMd1`}6Zj+yj3Ws`?o$IH_${YJZFC_iaxj*v z#`^{;locw+r$~7_1sorZ*;dWJcb)zk*08UNU<8+DYFs@vp%-Al7}X-GnkukS#;$cF zt=8F9X$wsbmb>btg>klXfCWYR9cBA+g~-< z#=uMD+f<$M0;UeB^wmd^scxhP4WP=BXgE);yr-0I_FslTM$QBadGFz~@2-9(ZJw4@ z*pS4aS|L9rZ$40cMA9fcESKBE4zdZ%k*cKR`Rg}s_yq^Y zBQFniRK6b;pGVJlBcq{?lT*M-vOo>x2iIsn z221;PZJ5CWCn@q?)Y93;iGiSvNsc3n7X^nB@HXL8!Tla8dzdI+RS9k~<hF_6X%4*#dVRVeG8gP zv14%W9mFPv{$^kPYkO~XhH0c-`SdL*Ng>1iv z0{jMJxsm}K#9SKIrdttSM@3OFlz^zihYpnx>aeX!-nX?VIM!`)tQ}zV(|U*6homSZ z#TY5KNo}X9qM{PtoW2v)R~1TjKG!i@)SCuE(-Q+jH*_Z?$$O{98>Txhu9PnU0j1oM zqMd15YT-7()bj0H6abMBwbo_`JJqNtNbtJ1cWSB>CF%xHhY*^KP|KA%E;aAELgCn=d-u;fk{?i?HWm~Kr zRTnTDF8qci8?|jd@)L6G(W6JnfCHr92U&29nvI06T`V%-NeCGbS{A~0n_gWp0cVui z8en3J9b{7cKr~>tfqeM+XPNgXW6A38u#mkfL+EC$9=w_0IkK(M7?+Rb!La zcJ9bKaC^2bP%~Cei`u_LR)AyDmfUIO;#;)M=pOK52&!cpMh?bw`cV`bpD*A0T))skoAolFp3uHnoQNi1j}} zk#~>hRa+)u*^dP9y?gxl@jcLffu!ETuiuh1 zukON_34}@e2#{O4b-Lbd+^olG_Fs#4X=mBT51u6e?RHSm4;$0zsmWGwB)q{wcD&@4 zw{Fc3!d5&3jVuDW*QFl3nT2_FpHw;W7`bPgdZ)JgL_8`?w@bcW6?*F8<;wwNs<-m< zR~~sFQk@Ng%r7C@QItH3Cr>LDiU9OD-e6$|0YVQNp(++^_T2pe=+8h|N2fcd8wBc} zb?eq`<=`kh)bEt*KJseA5iEN-h-`o_H%7lSOtre^S+dETnHcHw`=nBt_l^*kTzM1L zWZKCvBC;ERz}CmTZ|f0Exz=16-QDn1QnhnW{ymII(PBovw+E!9$x6Y4o03&KfHm^T z(agvwIs<|32nsqfa5*ki0jOYc{TZ_*^hkipz-BoDvQO^)-JNm>wsOESAKu<#{fJv= zv@ur=dC@;G@DYUJ*GUn__Hh3I1bIf8RunbV2M!1cfh*Rg)jJ5`T1kmRUb{}-{ zCb`RVz3`_XtNe9ag@kGjNJ#}CzYu_5HQa0JrJ`>l6=wF_)H$ln*{a z1`~YcyP_fi=mfmJAF#f1+6ec6sGzQ)tUA4Q?%cVpgmge1Ni?VW;sj|o`9$yzF)CDx z<0nBl_(e{pt$+9q{7pVwbF#gds-}LgTP)*>eBMlU+9X>kRG@ z0=*D)i=OBEdm5%riy<99=cdsL$b-P-3Msk{kmausUcsTx&L86$@AiH^#rOg!3JOKS zgT$s4D_2%RkLqg31Eo-vH%J&zym`$#dkQ6{7utiYFG<%>Lpn&23w}PTVWM>p+ZVc# zximq0qXeHty%xPluSf1gzbwcIl9K|29n8HZP3S1|&k%KqEJ;_e5ga>rs$!aLLFS-# z>F%eNQRc8~6#mk@PwcBpGr=9J#p&khKsQr_poPH(k(i;U^9+0d2x$(K(CdY4OU}<- z6r{VI_Q@y)BEFBjgH~LDC1BC;PLI$xBpaY4F@e}h0xuCm1ZZ+AM0y`pN z-df5c5{00rnL)qo$JJ+sg^Zl}hliU@!4HAbi2FG2xj6al)n_+hBq#_cWu%OZ%#_Yw zjp^sl&k8=<|IYivB=QjuPgzG0$su@RSMQJac=lsQB=fpkStUVFKkJP$F&b=1mP3yk zP?6s_<%Rd&8z&l1d-^SXQ+?;#U5@&eQ~?8!1oqvvGQ5<%MavDAFJ@#dl9EcfTj-uF zu+8cd%Zl#jR@)Iv8f2r&kRvB^=I||t4uu-ndN9u}(2v3}+|!VV`+_>|;!_=Co@i;y zpm@+=Z_EXX3x^wZuzVN4a^qQ>Z-Ifu!_*au3gbeK6FGCZixtG%-`}SSO}Radi#zfr zt9I;^iOWH0{_K~Dr$eOQMTbDx@H{}V42m6@eD-80`ugGpLj%T3JBM5Ia1Rybnz~&B z)D_uoB2RQz7WGtaw^C~nkEu3NKlE^QePSkk%*X}zWd=JpH7#YnGK)XS{bs~sz{+xUV z5)_$s>Ps?;&C7P=r(F;a_QYeM14TkHjC^<76C(}^rD#D?vQbP@>D|9{h|gx97jf7W z^}T&7N8TfyzGF-6!IyO$zr`RrR7oD8QkTg49+D7I^zfzVuA@y$N8V*S4czhdeFRvI zK-2+sluGrbPz-smKEn-O*}I5R$%?nVK-tOQWPzUNV}gLhDlJ$}sg zF+{wfL3Z}}r3)NF+cy=>I`>M?iZXxk>*E_ORg&){@tmN?A8rwT0%@f1?b}|#2e)oL zT*4$UVx)>OUGn-kg%Y$sXs(BzUb#x>Eh68c)CV~uR?z(QtBRJERtrBED@5oaF)ns? zD_bv#T@QuU8){sACUL^*{adq>uauc=D297+-^Z4wTu4eX;^40q=)(xkS`AX4RI`OyIAV3*@ zckf0(_TQMIa#6T(8=FXZ;whIWipRXOESenZ!qOkU#3z}oNOh3?3 zB$QXKSP`>~sj^)qT@%_mWn+{oTdf(EXJhQt3UOZCw@89pJN({jxsC7Ak z;nYaCe5jl%$IHQK~ZaT9QSorB~}50YPF3Ifsg^c96w-p&Kn=v7=@UEwdNTv zr@SOEVira5+I#)zmvwfA-rv6)hFo;9^W+JD5=ZQ2@!DBx5cGyJdq4x;xp`AD(PZ{I zpf3qU1RPw$)XcFkBAP-`X`SyW{v~nZkGPj-n{2#0DhM1BHP`(y2>oamPvfa|n&YgGZvI+#?iUtV;)=l*=3<%;PcEO*xvc(!l?iyDqH08JO6Qz^R$LR)y-)3K zTMwA)oh+|tbd88U;(a$zBRh=smO7Fdo^Q;sz<~)a z&=DbIqTr)zAe44g#`=R+ScM&OgDdk8A@ceH!1}4JYY>Oi<#P5MTr!{G>r(*|*2(ut z+xDT5d!eMG^PuqkdjQFYs7{y%YT%8Cii&zGjH37Rd`=)}xw$*_DadvN=W^>RifmnS>CR^gXsEO8H#il*ug@T=Ml@ z5mGP%eG~hj;PdX@T?ro*qG){004|Vh*(8Zf8k3x?0%kM)FM5_Z3a%>4ZQ$@gdP!TLjP`0H#vWAL{bKS83hMA0w0^k1 zp9IpIT3o`F?PnjP+?d&^jp>Tuzp%x6n)OuE6yV_G&h9-=oIem-Gm5C4by;b5xwJLf zIx*_KGZ=-8Mk8~Y)jKmr7FN#ItKQzjGU@6CYs0Rs+}1&=2SgV?Utgufabmec02<0% zO`$|)>=@FGyppB;8}hK?JYc?Pr+%$?+MVcl8177}pXxiKGJ=K?4oO8u2?PXqh%GYM zQ5-vVRQPU@Ws?EvZ`_cZlL@l_=~LdF+LV`JmWq7Wz`2ZA8B+?7J<-KJ4EXDh-4FcXQ; zZ6mP+G`;Y+=yJk%L>SO><|RRLR{BiH6Y;H$XyPd=?+r)L{dVzU`l?e8h3XWW%&}Ac zj%gwbZxy^;6Kh6Ge$5L7`Ak2|c5xK^wLfQ|UP+h`zSAIG?rLrR%ZTXJtynnGO-x_T zU31v^>zj|!zB=mYauj_wBG&I%nF1qL095SNICK@!!uTZ5&siqZWVw{K=Dj&zZ}Go$ zG0RKPa&3>suPgllFVh(|r(F`_1|~w{NY}c{Q9CMP^2Y<@Z}CYgc~$q48TgBT6PLf_ zjrFX%_w|YAO z1ZI*h$r^|KM6$`;pJycTBB=SUtU14k)J#_1%Jw>Z*`jyWOg4?X3K3amUVl7H2{JmR zt=CCl*9_#Y4+XGbPWzF3!D`Q0cHF;U!p;4!W)RKH$CsT@>k(?~*`ngR+~s_pKV^={ zlpD%@V+O!>T&q{LR4G3nZ_VWpkW1m|*bHo#<2*Iph;2nlk>mzS=OnV6X1D0Xl5+G7g=%4qO= zDKXFw4VEhq(*on}Ge`F8VlbIce)BDOxofq6&Ri_-J_owvmq4c-_Jszl-6aTCO$AV` zI0tq0^}SeFa`NE4sTpMbTMp4f2|=VZ z(oB#&EFnq5t`n-u6=A<4b?Vq6cifzS>1V|je%ORc!B$6u$tzqNMyUAdi8gWmvm?FE z;_g_r2V~dbzj`j^6)1S#yngK{ZEru!Q?&~&{2VYiq?q+_>Mjil^x{!v5wGVTpn}Tj z-NvLF5_?ZtNM*Staeo67stdWpp9CFRb?Q=HdU|@H3zTqaq7Wox_aBDJr$FwQ7-C2d zz!DvC3Prwmt-nYFAbdV;w{of1jVG$_@nK_FwF-{#8kg*t;-}ICjuCb!9`qE16Kk)w z{DK1YvA8UgDlYiFjsQDHw-wG_sgK(_rc!m?BWCKQZruh7WVzXL0emvV4VY?P2j*YR z2o?=eb)*c@`a{ku12+~&aW$EH5^0C1HQzzEDIY#u$kRp=8Zv%y5+FS%L?Up5X-}sl z_R*?<>IBO~vx5>?Qw)rZ8ZEjbJ_*i=Hz9fDx{h}cR~lQp=kB7C1>1r`K@D{hsTAh; z3n7?afsEfn*u~4~tBfDMtgEo{{xdJNOlmQ$Tp9NE?I9T@HMP6Mf_wVi3Yjt#1H_xm zxqG)V@q80o3ieWE48zC1%ZR=np=YwLxR`OynyJ_{+PNqGuGc_R&@Wujx1{dj!-u|0 zskyT$8*kF8ScK@rn;|Q^m#p7pcO<Qc+|>$4Wo^3=0Br3fyvqJW2_ zi3|v`gczi-yg38~k1MrY_W(#XBGNDDM7u9$X~Y>mR+;D)E)GlK&vm!`0LvoXxKtW( z;uU|Fmt_&cG>yH3`Xs^R^t^8xWwU6cuwvvXFbSsiEk`6JWh7c$0}02TkM#Oo`M0TsgdHx*I< zG|>C(SD5N*^P{|Y7lJa!lErFuFSnlLH=ZTar&5x3&7+K8edgiLzvx!L@hJIiA8HQb zbFBY?72()NE!W|yrKD80_WkVhz=omin~P>mwf&vvJhWdQe?D!Ra-k0plmoeFgtn2O z*M3L&71x*jcr>p8r$A`~y%1`Q%r8z{kF?DVWqoFIpV8Mh>Z#AE zKdPu$awv9AfS7>X+@IBZ{-^xtDYvZ@?*kZ@{a3@6DDMZYbNw!_1ncg6!>_Nekv^Fe zv_XYGe#|^T)G~ynJuf?uTXL8GNobHMfd9E2!iGAsBLwR$GGI}zdwLEIba*uGr~gT4 zywNi%SNWTPk<{L_aEXzl=VH6%286@od-`91Po6m_ZikwEM7ljPbnuM@vBZamhBpSy>Qcu4)?qyh^1!ynU8-LVIqFM{tF;6>a^+WEu~Nb0?usW;(w+X+#La??>D46 z1A0o7w(dH*_19HA{wV5L{Y9PvmYyV6VdSWty%PKW(^|cWoQsDKo&S0a88)gYcPY!I z1K_beU*%K#!1rErJ$)h1--9BJWLD|a8S83XTGkM|H?GPh5T7f|92%xBT-GS5eRoAS z!Gbg?hW72ha4Lr0!)Av4*>qQ<@FH2yKT9gSkJcjy@<%28%UUp@>IW}ndHqXGxwn;6 zTFS=8G0+l7)6vdjPeOAQ5EctmO#_Veo`caxn3jG@AoK`lQ|`Z2m?|zGA!_l%3q91+ zpo>&f4&^mk=Jr;jH`f`KxFTs=&iRMKLaB-tjgW#HYq-@Alt{vZ_8nPhvU*mlXPed!rRZJh81x0lwQ?T~JwRc>##}4I0t6cnGHpTFp1zqav|(WES4jC! zT_C@B#lB%4)Oc>JEpuKevt zV6d1er{P9L6Vua=(MVCKCMr5Q3B>aI;}Qm%F8R&^T2+iW@LmK(4<3eLu>?80agwh| znDN?Ezqd6*dYZ0ot#XSMGFb;{;he)yxaG#6F;hp4IuTmW+igqnyQFZ0EujR8Iq7<< zax{nbg1ztR4Xs@Er%$sZ*AU?EOsr7wLWe9vcG`w9R01so)6N5@)^)^w16(WE%8!01 z5CQ{&sm?>jU~x4k})87;2VcvvvDqdS6EmE z3sjq{2!sS;-6TQ+oX1h5I}N&KSw*yRd=BdJ&#O*FySp3`<*2Pf$qf6zb{?LiT>i4? zkJR#NOVrLvEi5jDtbSB9#I^AeO2Lg$v`yLuZcSMe4hDZV(ofnp0)~*^xMI5u$(l5Y zLH1uIhU9%FAZ^$mqJ-Lcc6EF)Ge{3bAUwNQOZHT-t92vgMT*vve607@}zdeQ&q;>;RpOJVud|i+ZfMXcO;X z+q9;V(pMW15fLr0A4~GiJ-&Ex4xyT(qoYBvS7O8y2(yW)Cj3iWEvw?+-M$_h{lP#E zIL>yR|-)EP}oEq!&3k-|}-wegX#a#z=1X>Mao;*<`&1z`RASOfT8gaiaOJ~Ht+nAb)9wQk7UX0EjVV(P8cJPLP<%j zg-JJeLd;sasE^bbGcUu1zt`ZmRQ9`634O$-JUePruA<`edzQ-hru0hhaluUK|M0GJ z`WK|ye@j+8T%1e~o)WdnuaqPs%|&> zDjkb=%})JUD+!e`^ZKLM|0#^wt!ETyJts<=8K2WgsYPUsc-Uwm>Gaeq6M4=YAFYy?l5|=cUz28fh!JWlN;yen^ZEmyxk=_0>Fz$Q>Z& znhEnHY1f4v{~!!OhOF^3$g1KZE$$2$TpItWFrpAtfX}fK&JA^9MMOi(IWUpxE&S?Q zR+n<8#!N`xCt4I^kaol2-@VKQKF$E^oRv&25Ec}N@Woc22!96yMQw%+X<{QJhA-L9 z=x;lSh^=mKZy!FOj+Rm2iFSDTl>sZZ$iNC{@nH)sDS0r?#82Q9GtbQJ*#00#Xg&uK za5ZQXjOq^{VhHS&v_8KwnQiUVxI+7qs>Nyi;LLcRdohH#kM02mk?hcOv-9t zJI2tN6ODrQi|bL3trzz$8u1^^2>0}&+t>@_KOJMpu1CW`9vjT+vyU%Y!$mqJn|i`2 zPuSSm2@bD6s%mnNb-ngF3(x3Ojr!)kw=j$#)s&Dr@#L$^Mxgsu0SQyivizuvWXlNL2JPhxFY7B~Z z=w768oP4<+Oq92Hq)2mdxcVGYUP*ZD;&PcS@q8mR&KE6D_Yi^LxdO@Tup4!vd2on~ z)fwR?7IfF|MsGoEwgucI;Jv_{VXRQ;frg3h4k*@H$0~ zNYaa;XUvp4lHVXiDC~CUrp%X85FNTx@7%c)!}Mg6Cvfz z91R;@cx0qW)5}YQCj(FLC!I}BOdt)Coy6o%nw0^vXlEr5KOE$vv4Lm`9i&^tqMt&n z1S{wE?Iq}Xj3E@r=FN}Ps!rp41sH>@9Q7qEg`NuKJRGQ~^i$V~28U<(DegE22Zs^> zU9xq{VOX(be+gBhc__7jlt{lWk$^!een*2_2`qkJ8i!`f&Bb%?YHd5I$3k(FMrn5= z-hLOdI|59}TLNS;MeOk7xqRrdHvwiObv+RoOG*?&OyHLXL)K1;)JO0#N@?zTe}8jF>f7%5l&qXs0(2gsqSw$Fry1lI0^-z;&k^?)y#z^>U#LQhT{ zZ(90XjEL`^R_}f<}J!_?O6e8CXW^2LiC$@vy20QKTUk=)G}5auN=U zjg&a;tWOQHl=G_@x+TgnP7`Q)oB3he0j^6?O*~Jl zctHFqKqVdG)1yA{Lq&p#O;W4cpzu%7Wj=j6GJLTaj(mywpd@>L?AwnkAWI+azw&8p z0u*r+rUA0$EjGevqJ6eBNYExg>t*oYwbZh2AUV%U!Gf5Qu?M`Ar|04jJ#uCQtgh(T z+Gj#tFo%}+5+4=jY(fZAd81DdJL{$NA4{Mz9VRl21D2SkrpbRhs8a1iBqRt`Nqfz= z{#6Vtg~Ll|y7Y~4{yh$#4LviDLo1M%(f;ch-{YbBVLA5YZOb%vbk-qgi4~C040{1- zSMaVa*Zpk}Xcn4+i|GI(y~k0w7x+SThUu@g?K1>KvV7qj6Ly=<|HnKa5l@VK2+UQ0 zVq0X;Kw5zx{6a#wiRMc~_@eGVJ|~g>V?yVmsZ)`dPSG^>7$|E@Z`7OU>_6QH`||A! zKi>ng9kG;o+IKWrOxg6`OhS7`xn!VFYh+l5qjUF>G>g*#oFd@d`(mCQgkS;NQ92@& z|4P#N%zz%WoO(LaRmQb-El!SbC@+us1Fa9Gf9bpQ_mon8FOM(KO2mTy&?`1N6UO`A zKl?%Awwkgy4-T@i);N;%Qd59R<;}Jaswskj&GhUB_ry?NUuDrL9my^JOKQLMY;pAK z7LU3zku#ribI`2M?b79WMLj=g=tOc$PW_^wk)xZI=|)y7m{XxQ*M^IaxGb1YnE|%Q z%n)68e*zP3|4!oW_yO6BED?#@&)g=Ry+Ai&NYHfeOb+M}aR>UZ7k|A$Pz;K1{_$O) zG*PyCXkcLhg$~{QS1+=dU;5%kY{JXpd@W7*DbwY^uN* zNCFX<>|-Iw$9!hAXN!-~i625a*|&-hj!vVb%J#UMOQd28_Ry9P7M6-MtsuUwM ze31V46c-BRg!0w*^&X-G7tP_%JwK1)abXA5k{i`Ydm;-9i}}g^{qR!!XKhm|*cPPM zC5A%t^|sRIz>efj8`GDOY-YN(HnuFw!NL_4vv)nVE#FSU6#Xn*-dbOB(E~XV2xWP~ z2C|&@3pL@j8ik+9$lz7-?FaS->71nYA;hM*j@y%?L@*7?ztP%C^77trawaBdXT`vc zNcsUGCncklaTf*iYRUYYBD}F#2&$yAGzmdCA0XRj_wL+GcW6IveH(F-EPJaZPEVjJjo+ckvbb}Rg)=2r z6cII18pyysUIzYQG6%>wfbHuJQ~+>JNt{4=d5D-<(NI{Cq$f@6!)S(@(pljlrF4{d zjiMNlO?0@{*Y8c)_o_i*&ioUwp*dz~0k@IQ68{KP0)EIgq7Yk%#6+|%(zQhxnmm6L z^HyHJ^7}GUe2SwH&dWS!NDXL64ku-}+o7Y)_}klC#At}lj6ra?BQDn{%#wD(jUq^4 zk3HYlQxtdNrywnu=!nzG@(yaoc%2*#;-|#X8pQugj=Uf()l<-!#$B8!JHo;jm!tzl z-Q-z4&qEIs^1gh>A4`rQdEO+60p+SBX&@v0OGJf(T^~rIOwUI&0?4DYuV4e|ewoO@ zzV;UWn=XA`MoyHPwGSHzCqX6Tjv14qVu&ii5xo2K+hxS~R9f}d^W&*8< zaQnU1_i2S*j1=us_Pf|>*Ts@(HS>BtiiKCSgD3_7RJ zWBX?b&Vyr+EU_k*n?JcMeE5$N_X=6nmdhBr>1HSvxETn^Ng@y4n(Haue{Ag#WFeG2 z$TiomUR4CQiGGtI<6>+pGry29;+`238~6CRtANkle^UxsHvO;l`#O`9MAOi*s1}p!8ft*Fp(*?$Do41=+AtW`M-zvg#J{R#qWOUQbTiFaUY~!)LQCJa#-W5xwN8i zRKs`lO&>)E1kDDdn^)g$vVt;`z%<`kll7$XLhWe~A{)hToegk=v=Ur7BzawljWHK5 zD-F5e#Z&1f(EZ<@I%$w%@~-MEH~(H?9vjz?1P~*eo`$|%sD^$q)ec=Xs?i-eTR{ka zf?!h?%0F-O%xasFk@a4w^yGsZd+y(Imp29BHv(NnP`O5#i{HOjM(ez>Xz@=wU8Ktf zda@?x87qbu6xoW{_C%b_P)&IAu2DRqDnRKQk$X1(qDVm_F4kx{yVG{a;9>Ut}M{gjSPx42`r9^=&~~ zy84q5`d^!s@Jg1;NTz9A>)%I<2l>orm&`!ra{}OiDGad_6Og$R$_@97Ti%KJ4aq88#jIQLRj@8st13 z7{l{wNbyPI6hQtOzGj$hS@^Fe^eV?XG;i1uzX`yaSF%#$2u#Q`xni#X`65}^VQ^Ss zt4$ox5C7KBs6iRX?xTEeDqcwapHZ-KEg z-~b7__Q_>ZNt5%iU|Aet9v^A;!NUI$$w2qwqy5Xt?^AccfvMJ~0eL~5RwcHUJ``_e zpPxLe8RF8(J_g!gnjDCU{f_f=hNxv8p%pimDEK^(_C;^z+1#y6EG#;) zog8cRVzhj|bbaEl(h5UclQcOEgehAmG#XHZE+2SxVULH01X-R|vMg!APA8Ut-k~Q) zACMM$H2zSk71FCxx%B~biQywUz!lNKFQ$GA@fnbF7l;uGXB!=Y+tiOo3QAHrip8N= z-N~32#j_0;Vw@-lAbfxZ8!gxRNavULPIU@EkfrgL^#8+NA3hKk7B78jrbaiNEwuO=wUd?tT8kGt$T03P4+6iS-ck%WZjx;eQx-9G z=X5WkNQ8yb(jFYWG!y(Be)nxaFouOc6`(IWo6Q}c){?09FGzbv)N&LdScgo~FW=$? zS_Q`JQ=mle04n<5IR8!>#{`F&V=eD$u%_Ug|4w$4Kj0LtxDV1JPQ~x&Vfgh;p+XKl zLfTE@e59zI%1BMi^H-D^j66rZRJ}ejl>i2&?>%#w)y7`!ld<5hnbaZ;2MXH6xQ z2wDJK7R9M}nK%N@IQtCp5Yhb5nw$vx3)l!bw7vZ1^{KFS+GeNNqRj=L}hQ#gnY{J}6Mwd+Q0Wf~rg6r&ve4LRB3T|8Ci1)`8K` z@GuQRh{luy30~cxS-2Ry_WmnN&tMI8k60~Xkj?5T84w1$( zpum;T6`y7_9h&UA>&9f2?BTPT>qv))h)8W=?H_Krzcpj}pw-G0$|0eOygKN_Og7KS zk)e2bG)w-Y7JsR!1!DurbU+a2vqa*=CPa=eHLl1F<)mNemu1$}B0z&?F@6;|zb3|< zTHhAsXzm%^zn4Ne_dLCh*L+c6gvJck|E1f!wWg=iT>n{eXcFb%;u;oA{l`>h_3Z&_ z-Kzz9(N~1g4nkB_yf%IZ$;!#iUHppjnMbe-Mir%<694Jc6=SzLm zmH#DM{I|(Khq}a;+y-89Mc~{j(2PoQmM`I)AgFdAn%rfB=h^9YkMA9{RKYT3j6%Gl zH0%nE8OE8e6~q?c4}09Qx8#gYa{lbtU^_a70>`L5iQodqUVmaGj{-`O^jMKo66$bb z2Fbysd*Lmo0}G+u_Ia@Yi|!>OocTX_Cc8XPd2S~}Sk^6?tm@od@PDcxYyP)~!N}UZ zHiA}8%>lrGuh9l3cdD!JMuld&K_oN|-7>>#;&wG}Lzj)~qVUFSV6Dt_#@2`kd z2;oSS0W7ec`i;3vRdfHnzWgWl_kA{ESN7o;{qW(47qg%eR3ku&DjaBxqAd~Y^sq1B zj>@rPQ8>HdkZ->C`dBy>j-d%Cvppg(87ChQ*-Jre^z^H$4JSxEo_QH}0j5=8`SF>2 z+JVJKjI4yPM6tg`2CY&ME2s}bey&Dxm^BXMymRkf6dKYMLBB=kJvguTTY-3$wyp|b z%c^iL;`tqV|Km6q%BebOz3SkQfW8!h{9Wr@MuXbk z1yZg*H-L?JdwJawI}j*ht0|;TWmEhyM>#`94}&=gDuro1_?QuD6t#ut7g* zLT1_$VTPo2?0X*VZ~yl-^iJ0baMUhH7Wfy1`pV3Jq>I{f(7I`6#)`I*Xp4jSRYdf; zYyZjUem@#aRA<9^7?RyYn3(w(?ZI#Ul6vV^bpQ7!e>PBQ<;%;it0_b1yKj}%VwDw- zK7s$prF=%`j@g-h-^ZwkKPU#%59h}ocS_ImZ(^7Hc(_%Cu@ zOvKzrWOdDp&qy`@=Zt}Np*h=rc9UKBP(0%ym^b71{JDGn_!2?dvJ%X9JS_tBvgFTJ z-M7C?2=o5agh0SQ)HfK79EkW$3>{FGfStGaTuP+Sp@(`QTBSUuiS1O0)9H*5drXyB)F>zLydJck)798nG|3ItAew8;>jyar4s{ppnCHuv z3%l$)bH}^OaVD-dtys*&VH%89eh9iDzgcMEoS-GYpQbGwhm$t=S>%&e|g< z%MyOHnIA-O%;0^{J@wuR<(SWNQo}eJM9rbr>PkXp2Zu}<3aA9`+!0AswZxwjo4s|$ z+T@jSWTPSMBqhnD2*>u8xJ`!rMxW#99j1=PdfowAs0YXT-*b~wn`O#A?rDg-#VXzL zW{qxKUnV*ebzu@57F)V#k&SI|DsUTPH91!O=CTHEf1H2vl$DP{S^cX4SVEhe%76nn z{75SZIa1Jf5JkEiyl*v-MW7|9bfv&=g%i6i;=(m(dMG)39c)4*M7C%clL&esCmk_a zWP?PTeI6%b&5!{%WbFk+wiM1fcaB(No0Fb3{eQ)sc|6tm{>KluZE}ll3rQ&2NTw{E zva|@7rlzt-R7SF-RI+7h+B_Od+@y>_H;pY+wnkY-I+8|H$h9wL3Td$<3disD{+>hX zj{E!L{vMCt`D0Xbob~(td_V8k`}KOh9du6*Jo!%+PnjHVEpka z>_-)s4%vYDf-nn_$cWJl(IN(aotF{KSx-lpsMfpl#I$w*b_uSG2=rFnN|mzP@GZQj z`cU_l)c&oEp>mcS^cx3X*OcjKm?mU6v1lG68R5W)*ooi28#I zS0<1ELvP&k%hP;&6(OjoHPsqJ#gVjtl^B^6Y?iq&Gobe|@+t1G5$pkctc>=0qa>mu z&oSyC@+M(PD-Nr0D$ECuJr6hY8XiV@hGTmRC^!`6BshMBhmD`en)leJtM1Z&>(y|6 zy9|C0DTQ-zm{Kg8dLK1MV&F}LL)4QXi%XZ|tEZSt(h zvX5MT1<0ZdgBa3oFLsaAA`UMD;Eae}n$*I8Y5ggA4)+#K$p!p{Mi$6KGh0+y3G5xI z^Pu&@lMW{2&l!{z=-*-TbYJ=x>^+S-2FU4;b}s@$34M|CL>N>6YRx|vMMxSpiH?Dh zhN#c5>C;$%eUGD4g6C_{Dd5~zip#f3;C;M`;}RjoHHQq5_opEc9Y6o*@)Xh?dOnNm zL8T&s*Kzf4u-i?iIIsbkHq>yu)1U@om_JM1l?*Fp0^UOofSvO#llhIYojNtYN@;}{ z5A3QJY(5FDrd_PEYE=drP&@0(xm|>&Bg~qX*)*1aI?4O|q(4$^5}Q$|RC{DjqUa2z zgdoKjJY{k-NN{MkLh;hU>Ju&x?BPo=iz|^1Nhf z`tWzK;a<;BN>$!A8VKdRi(l7{ghx)xImMT`*38u=ssb!Umpy{}kJP=xC!hW{(_3Y^5-3Ew*8etT}U7UR#H}|qwk|$aP<@LSWL4kLg8->$h zClmbo%r~>|{35gYGySBvF45;h_j5@tuMF`09Eh>oYlF3CI@(2OS%47g0IV7o zU}#*+w6u1?ZDfoZ4EtBbv5D;VZMTL1FfX^^b&Df2UTZmD24g2KUAi<0^g7mc6>9C_ zk!3ixxcKgTXfC+C^HmbqBA%c_Me-_@`T|(Nh)UAXLyRB56Rf~|HG`DzUWaQ6G-WtQ z!8rTUk@or*teL&M1-u7cPxNKfS`bYv=n5Wjq1};(*8Iucq8);(v1OV!`ZcSWElA?k z=cN%&0QKeHK~SJcAo-Gz^iV~oWCeD zd!m#i!>o_f@t~!4uYz*G6-p&$`AS<(0>nwmuA@Fjf(N}EsKi(~`ho$J@Y2T1h_b7b z22ull$yfswb%iA4q1!Vq?LD3C{01(>*X+!X=dAMQ+6*mz%-eC;vB_umqy4?%=&+d7 zyo%+$eygkcJydussU~zC9F-wCP9URy*;RQ^a!q(cM{Uc{)M=tojnzMjY^KJIS8jF* zww3ZQ4QS~OkS)@^U6f}nEX-m=oE~@DZbzz?D%ruTGE++sls@|Lb8B1Ko%a4Gha;PE=w2SQ@UAl5v#opAfetTCnkR6Zyr1`@5 zG-N&NID7$%S^~I9iIa?}u9}jRvnvdjQ3l&l`3ibWl5wx~Kd`fL0y&`95>4bOhSVvX z;>h$1Pcr&L7}`EQdTw9!0bNB5ClW0@5NU%EZK&ZdI2DbMNgIkm4sZJ2@`{2@jF`em zXOl0-oDK4PNgjRdSB!V=j0C1X6S;9>DPsKzivzrrsI4Voi^Ag2lA{S1So=-T5krbQ z34N;l2r0~gfWmt385mk@dj;;lA=9Q&Q^5bOEjILw+rt0Qfoq{Zm&)Z4?9A=J(9(^S zRz9r~W97$Bq3J5=j zae2s9cS21NcoQ3SK!Neat|G@$)57nQ$jN? zBBuJcklF{fd#=v>;zdhEAmP&=nG>{zB0Pb$56t_MGZrBEP4yoC_L-r9=@|#FF-8cd z+*pBWa^uh%qfzLHGNH7QUmol2-N59RB&faxjzM!;qsQ#=3ZVybC3*pIo!C?uwlzx& zN>Hj?Vd~LaA@X`RpTT0QsmIw^Snm;#KAy14?}|xf>vQm&U~-K00Y9*nk2w9^8XGr& zN0^VNIpnEy%XJf~rT8~?3yK12O;&&iNUi}>#BK@fh_N1I9s%uv1lqT+HWJPXAA}%n z%{D|oo?%RU?P7a?orv}c?GJfxhk0qws%V%JEu7NWV3Ere3L_z1X$Z<>Ge;CHqojxu zLBm$RM*>-NDc-&JuxH8{z~7ou`GF&W?#6!XgL3`|1C)RWhzQAGy27gZ!=*}Fl`5yw zg3a7yAD{u(ABZ6!`PXfcbcLX4ie65iIbeB&fg&uC-4-`~+=o%jPBQ!U8 znxE(ddFpT(ctNbehyKjg=ToQkK(XI9;4Ngb{~uz{A*SDo-yeftF40dmgQd)xv+G$x zpT@2E-{`a^CZn5^gk9aVJa@Dqcg&KJNkaynky2^C3Hh;UAcFEHi5Mx`(Um4QD|jDtw&^ zXDQNo;Bi+0yt&YTzGE6mMETTqL-a_TPgE` zt5K5+R;2ZEHNY=Iq^1Ob)*M6`h=2{5zS7zZW@!?{sp1)xSRAqC_&oskUu3{U@4zFw zyDr%fV^Wxy9y+y8+=PEUC5>90a9QVXR^a~*r_O8daX zl@<{o<1y<394F-58A5rBc%!1S48pFu-22$=0^x4x6C2~^axx?wA0`ND-I z9P-n#Rc9x?!f)OnEbK@4%5p>8-_#`{K#`0ynD7yTGm+4lBSj)Cxowe7sa@Qp6HRuC z7F+SaQuOuP2Fi=bv=~fa1%1yJk+KPtpXV30_#wrnZ#aYgAPG)xpDUU;^6lVUAi17O zcxi%%6Nd~Y^LSED$RY=YAphcDVZ}Q+V#WLY5I)3GKx38~=}Zj9G5P4SiW>4}9Lrh$ zjwrdMYy#2?y6$^uu1Y;q)i75FS@4w*e&{#^U?{#E>>pZZ`M0sLUcSjF*mYjX0SCsZ zKDvhq3AJJ_=3vE*msgrRSFWV+OuTUez$jnQ-I&c5Rda~y6+eKPol)ia|8MLzg4yYe zYrN3(L(%&MdZZ%{OT<*}&DAfV1ECwN`Jy#z)if#Tsr-${C&d9g3FGvp6>K$UMG51QFL4X{WpePB3!3bHVrBj+Z?_Z#P-V)`VZEs7TQ!F78a5WS!C7a3*Ci5q6^PBCe{^8N% zp*!adwE-6i78!ouC!ExIK3{y>#3i=ZkFv}1w%>hP6IEmp>yQwT{zjD7+#25hv8jFu zsyo#Mcr`IgS7b08RTwF*|0ezj@_+FaEa$`#QBX+QaFDmz(2zDbd`zmP)t>Ug4r2{< z8w^~)z9SxY-JG1f90nnH_l+$s=Q;)?X&0H9xGgcjHh>8VDcqs@CMh-fvlg7>jl(Sc zg=Ok1tmA8L_O4aa3k-*l46Eq@tGin>b)vK`6k$Z)4RxEZapp*!MZI+tE^5mkmDjF~ zEU*;8eQZ124&RcD-3UrfW5c#jEj&_`a;c4XwE48Sspl39AF)2(r8~kcjYN6>rp@cb z?u}8sqV(ilqff5K|Ca@2g=Y$!U~XQ2p6H8ka=BA?`6CPg#1kD`$q{Yr7JH#V$Roe4I}Ie zoaWH9j66Mmf&2StQ-P45vXbl<(Kx#Dh6J%KSM#66+qtMZ2jB7Hh?Sgv?-?w~M(ih3 zXnG#jvOeh!STzVt0#wO>tKEqX0PVK}3qVf@EI@H%=~qiBUQDwip+L10pa#ZiM!2>U z@^2Kg?+9jFYGJACUs(2RzH63Ok;T8@wh%joK+Biy^udgzg6t8B6LP2g<1P}*6_n-d-u6uI^9UEVT9yQjOpxu1+IiI z#+W7%VsNdW@{(B1-U=gX#n4m$Kjn!mVPV&-H_Rgm`zte_c(Q)f>6tk7H#~ZN_=Bc8 z$9U}-9hx{Hpw*qpkNDd*=qX3>AdVOa0Vi`O7}Bz_V)jlUY)dt~S!4Y4E~-wNVc$Fp zo;)!}Owrn?qoX*~>&N)LCdkt4;W6a8YWg4{o?|xS9VqcHwO(NMCSoT91t#n^4Dm8% znB0cPU0qcD64#>GRd}sp_VikfAVN&I@^9iyJ2&2BqO@%wy>uFYk(T>D5{v6#Zk)dg zAXB***F&|1dmJVm!Sz;&1o%Xn`Qsc4f6JfDTbw>MgHs(mQcvozu8qizg(~*kBr92qhGAE8@_|aCrVO91R3CUW7S-UoA2~DgACu9zcjel4?m^;uBbG z7cn}jMOX>S{6`&joogGIFFsP6L;0lsHvjhjHsd>?5R(tD!fK9|24?!9p#~qsCDSzP z*Tv!RZ49D^#5if2Y*yF?cJ(b}$%+vqi3qS@a8a}{+5T}f&1^w;2%sPAZoNl#w}T}8 zRqVzr057o3k#|t0Mkl6@rK7tum7XAz@ysTk!I;6;h?F)DtsYL5OxdyCZ*$+|ztsud<&qni*UaCVaxrFfj*=_rPI9 z`Z(biQ1(;al>!}T23`R?hvFeDsjAT@5&uHs5`6Rj#a#COVR$F$VRoO-@0C9`M-a?m hO~OY>xBs)BLaGTf+b>>o`Ia8lKzHk=)Q!8p{~vM(KKB3s literal 0 HcmV?d00001 diff --git a/docs/modules/3_mapping/distance_map/distance_map_main.rst b/docs/modules/3_mapping/distance_map/distance_map_main.rst new file mode 100644 index 0000000000..45273cd3bb --- /dev/null +++ b/docs/modules/3_mapping/distance_map/distance_map_main.rst @@ -0,0 +1,27 @@ +Distance Map +------------ + +This is an implementation of the Distance Map algorithm for path planning. + +The Distance Map algorithm computes the unsigned distance field (UDF) and signed distance field (SDF) from a boolean field representing obstacles. + +The UDF gives the distance from each point to the nearest obstacle. The SDF gives positive distances for points outside obstacles and negative distances for points inside obstacles. + +Example +~~~~~~~ + +The algorithm is demonstrated on a simple 2D grid with obstacles: + +.. image:: distance_map.png + +API +~~~ + +.. autofunction:: PathPlanning.DistanceMap.distance_map.compute_sdf + +.. autofunction:: PathPlanning.DistanceMap.distance_map.compute_udf + +References +~~~~~~~~~~ + +- `Distance Transforms of Sampled Functions `_ paper by Pedro F. Felzenszwalb and Daniel P. Huttenlocher. \ No newline at end of file diff --git a/docs/modules/3_mapping/mapping_main.rst b/docs/modules/3_mapping/mapping_main.rst index 28e18984d3..825b08d3ec 100644 --- a/docs/modules/3_mapping/mapping_main.rst +++ b/docs/modules/3_mapping/mapping_main.rst @@ -17,3 +17,4 @@ Mapping is the ability of a robot to understand its surroundings with external s circle_fitting/circle_fitting rectangle_fitting/rectangle_fitting normal_vector_estimation/normal_vector_estimation + distance_map/distance_map diff --git a/tests/test_distance_map.py b/tests/test_distance_map.py new file mode 100644 index 0000000000..df6e394e2c --- /dev/null +++ b/tests/test_distance_map.py @@ -0,0 +1,118 @@ +import conftest # noqa +import numpy as np +from Mapping.DistanceMap import distance_map as m + + +def test_compute_sdf(): + """Test the computation of Signed Distance Field (SDF)""" + # Create a simple obstacle map for testing + obstacles = np.array([[0, 0, 0], [0, 1, 0], [0, 0, 0]]) + + sdf = m.compute_sdf(obstacles) + + # Verify basic properties of SDF + assert sdf.shape == obstacles.shape, "SDF should have the same shape as input map" + assert np.all(np.isfinite(sdf)), "SDF should not contain infinite values" + + # Verify SDF value is negative at obstacle position + assert sdf[1, 1] < 0, "SDF value should be negative at obstacle position" + + # Verify SDF value is positive in free space + assert sdf[0, 0] > 0, "SDF value should be positive in free space" + + +def test_compute_udf(): + """Test the computation of Unsigned Distance Field (UDF)""" + # Create obstacle map for testing + obstacles = np.array([[0, 0, 0], [0, 1, 0], [0, 0, 0]]) + + udf = m.compute_udf(obstacles) + + # Verify basic properties of UDF + assert udf.shape == obstacles.shape, "UDF should have the same shape as input map" + assert np.all(np.isfinite(udf)), "UDF should not contain infinite values" + assert np.all(udf >= 0), "All UDF values should be non-negative" + + # Verify UDF value is 0 at obstacle position + assert np.abs(udf[1, 1]) < 1e-10, "UDF value should be 0 at obstacle position" + + # Verify UDF value is 1 for adjacent cells + assert np.abs(udf[0, 1] - 1.0) < 1e-10, ( + "UDF value should be 1 for cells adjacent to obstacle" + ) + assert np.abs(udf[1, 0] - 1.0) < 1e-10, ( + "UDF value should be 1 for cells adjacent to obstacle" + ) + assert np.abs(udf[1, 2] - 1.0) < 1e-10, ( + "UDF value should be 1 for cells adjacent to obstacle" + ) + assert np.abs(udf[2, 1] - 1.0) < 1e-10, ( + "UDF value should be 1 for cells adjacent to obstacle" + ) + + +def test_dt(): + """Test the computation of 1D distance transform""" + # Create test data + d = np.array([m.INF, 0, m.INF]) + m.dt(d) + + # Verify distance transform results + assert np.all(np.isfinite(d)), ( + "Distance transform result should not contain infinite values" + ) + assert d[1] == 0, "Distance at obstacle position should be 0" + assert d[0] == 1, "Distance at adjacent position should be 1" + assert d[2] == 1, "Distance at adjacent position should be 1" + + +def test_compute_sdf_empty(): + """Test SDF computation with empty map""" + # Test with empty map (no obstacles) + empty_map = np.zeros((5, 5)) + sdf = m.compute_sdf(empty_map) + + assert np.all(sdf > 0), "All SDF values should be positive for empty map" + assert sdf.shape == empty_map.shape, "Output shape should match input shape" + + +def test_compute_sdf_full(): + """Test SDF computation with fully occupied map""" + # Test with fully occupied map + full_map = np.ones((5, 5)) + sdf = m.compute_sdf(full_map) + + assert np.all(sdf < 0), "All SDF values should be negative for fully occupied map" + assert sdf.shape == full_map.shape, "Output shape should match input shape" + + +def test_compute_udf_invalid_input(): + """Test UDF computation with invalid input values""" + # Test with invalid values (not 0 or 1) + invalid_map = np.array([[0, 2, 0], [0, -1, 0], [0, 0.5, 0]]) + + try: + m.compute_udf(invalid_map) + assert False, "Should raise ValueError for invalid input values" + except ValueError: + pass + + +def test_compute_udf_empty(): + """Test UDF computation with empty map""" + # Test with empty map + empty_map = np.zeros((5, 5)) + udf = m.compute_udf(empty_map) + + assert np.all(udf > 0), "All UDF values should be positive for empty map" + assert np.all(np.isfinite(udf)), "UDF should not contain infinite values" + + +def test_main(): + """Test the execution of main function""" + m.ENABLE_PLOT = False + m.main() + + +if __name__ == "__main__": + conftest.run_this_test(__file__) From 2234abf63d07e5496e37c1b57a1b927c303272a8 Mon Sep 17 00:00:00 2001 From: Aglargil <34728006+Aglargil@users.noreply.github.com> Date: Thu, 6 Feb 2025 12:05:20 +0800 Subject: [PATCH 843/940] fix: DistanceMap doc autofunction (#1143) --- docs/modules/3_mapping/distance_map/distance_map_main.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/modules/3_mapping/distance_map/distance_map_main.rst b/docs/modules/3_mapping/distance_map/distance_map_main.rst index 45273cd3bb..0ef9e3022f 100644 --- a/docs/modules/3_mapping/distance_map/distance_map_main.rst +++ b/docs/modules/3_mapping/distance_map/distance_map_main.rst @@ -17,9 +17,9 @@ The algorithm is demonstrated on a simple 2D grid with obstacles: API ~~~ -.. autofunction:: PathPlanning.DistanceMap.distance_map.compute_sdf +.. autofunction:: Mapping.DistanceMap.distance_map.compute_sdf -.. autofunction:: PathPlanning.DistanceMap.distance_map.compute_udf +.. autofunction:: Mapping.DistanceMap.distance_map.compute_udf References ~~~~~~~~~~ From 0676dfd67e099198c34c485e176b077ad6fa7374 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 6 Feb 2025 15:16:17 +0900 Subject: [PATCH 844/940] update introduction (#1144) --- .../python_for_robotics_main.rst | 57 +++++++++++++++++-- 1 file changed, 51 insertions(+), 6 deletions(-) diff --git a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst index 1ad5316f53..2f89f0c7b5 100644 --- a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst +++ b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst @@ -1,11 +1,13 @@ Python for Robotics ---------------------- +This section explains the Python itself and features for Robotics. + Python for general-purpose programming ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ `Python `_ is an general-purpose programming language developed by -`Guido van Rossum `_ in the late 1980s. +`Guido van Rossum `_ from the late 1980s. It features as follows: @@ -17,7 +19,7 @@ It features as follows: #. Batteries included #. Interoperability for C and Fortran -Due to these features, Python is the most popular programming language +Due to these features, Python is one of the most popular programming language for educational purposes for programming beginners. Python for Scientific Computing @@ -29,9 +31,9 @@ For example, #. High-level and interpreted features enable scientists to focus on their problems without dealing with low-level programming tasks like memory management. #. Code readability, rapid prototyping, and batteries included features enables scientists who are not professional programmers, to solve their problems easily. -#. The interoperability to wrap C and Fortran libraries enables scientists to access already existed powerful scientific computing libraries. +#. The interoperability to wrap C and Fortran libraries enables scientists to access already existed powerful and optimized scientific computing libraries. -To address the more needs of scientific computing, many libraries have been developed. +To address the more needs of scientific computing, many fundamental scientific computation libraries have been developed based on the upper features. - `NumPy `_ is the fundamental package for scientific computing with Python. - `SciPy `_ is a library that builds on NumPy and provides a large number of functions that operate on NumPy arrays and are useful for different types of scientific and engineering applications. @@ -39,12 +41,55 @@ To address the more needs of scientific computing, many libraries have been deve - `Pandas `_ is a fast, powerful, flexible, and easy-to-use open-source data analysis and data manipulation library built on top of NumPy. - `SymPy `_ is a Python library for symbolic mathematics. -And more domain-specific libraries have been developed: +Also, more domain-specific libraries have been developed based on these fundamental libraries: + - `Scikit-learn `_ is a free software machine learning library for the Python programming language. - `Scikit-image `_ is a collection of algorithms for image processing. +- `Networkx `_ is a Python package for the creation, manipulation, and study of the structure, dynamics, and functions of complex networks. +- `SunPy `_ is a community-developed free and open-source software package for solar physics. +- `Astropy `_ is a community-developed free and open-source software package for astronomy. + +Currently, Python is one of the most popular programming languages for scientific computing. Python for Robotics ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -TBD +Scientific computation routine are very important for robotics. +For example, matrix operation, optimization, and visualization are fundamental for robotics. + +Python has become an increasingly popular language in robotics due to its versatility, readability, and extensive libraries. Here's a breakdown of why Python is a great choice for robotics development: + +Advantages of Python for Robotics: + +Simplicity and Readability: Python's syntax is clear and concise, making it easier to learn and write code. This is crucial in robotics where complex algorithms and control logic are involved. +Extensive Libraries: Python boasts a rich collection of libraries specifically designed for robotics: +ROS (Robot Operating System): ROS, a widely used framework for robotics development, has strong Python support (rospy). This allows developers to easily create nodes, manage communication between different parts of a robot system, and utilize various ROS tools. +OpenCV: This powerful library provides tools for computer vision tasks like image processing, object detection, and motion tracking, essential for robots that perceive and interact with their environment. +NumPy and SciPy: These libraries offer efficient numerical computation and scientific tools, enabling developers to implement complex mathematical models and control algorithms. +Scikit-learn: This library provides machine learning algorithms, which are increasingly important in robotics for tasks like perception, planning, and control. +Cross-Platform Compatibility: Python code can run on various operating systems (Windows, macOS, Linux), providing flexibility in choosing hardware platforms for robotics projects. +Large Community and Support: Python has a vast and active community, offering ample resources, tutorials, and support for developers. This is invaluable when tackling challenges in robotics development. +Use Cases of Python in Robotics: + +Robot Control: Python can be used to write control algorithms for robot manipulators, mobile robots, and other robotic systems. +Perception: Python, combined with libraries like OpenCV, enables robots to process sensor data (camera images, lidar data) to understand their surroundings. +Path Planning: Python algorithms can be used to plan collision-free paths for robots to navigate in complex environments. +Machine Learning: Python libraries like Scikit-learn empower robots to learn from data and improve their performance in tasks like object recognition and manipulation. +Simulation: Python can be used to create simulated environments for testing and developing robot algorithms before deploying them on real hardware. +Examples of Python in Robotics: + +Autonomous Navigation: Python is used in self-driving cars and other autonomous vehicles for tasks like perception, localization, and path planning. +Industrial Robotics: Python is employed in manufacturing for robot control, quality inspection, and automation. +Service Robotics: Python powers robots that perform tasks like cleaning, delivery, and customer service in various environments. +Research and Education: Python is a popular choice in robotics research and education due to its ease of use and versatility. +Getting Started with Python in Robotics: + +Learn Python Basics: Familiarize yourself with Python syntax, data structures, and programming concepts. +Explore Robotics Libraries: Dive into libraries like ROS, OpenCV, and others relevant to your robotics interests. +Practice with Projects: Start with small projects to gain hands-on experience, gradually increasing complexity. +Join the Community: Engage with the robotics community through online forums, workshops, and conferences to learn from others and share your knowledge. +In conclusion, Python's simplicity, extensive libraries, and strong community support make it an ideal language for robotics development. Whether you're a beginner or an experienced programmer, Python offers the tools and resources you need to build innovative and capable robots. + +Python is used for this `PythonRobotics` project because of the above features +to achieve the purpose of this project described in the :ref:`What is PythonRobotics?`. From 9936f344635e146b9a2ee402ab1672b4e7216d6e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 7 Feb 2025 13:32:11 +0900 Subject: [PATCH 845/940] update introduction (#1145) --- .../definition_of_robotics_main.rst | 7 +++ .../python_for_robotics_main.rst | 63 +++++++++---------- 2 files changed, 37 insertions(+), 33 deletions(-) diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst index 2f31834017..fd151e3f20 100644 --- a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst +++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst @@ -5,3 +5,10 @@ In recent years, autonomous navigation technologies have received huge attention in many fields. Such fields include, autonomous driving[22], drone flight navigation, and other transportation systems. + +Examples of Python in Robotics: + +Autonomous Navigation: Python is used in self-driving cars and other autonomous vehicles for tasks like perception, localization, and path planning. +Industrial Robotics: Python is employed in manufacturing for robot control, quality inspection, and automation. +Service Robotics: Python powers robots that perform tasks like cleaning, delivery, and customer service in various environments. +Research and Education: Python is a popular choice in robotics research and education due to its ease of use and versatility. \ No newline at end of file diff --git a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst index 2f89f0c7b5..90edd5dc0c 100644 --- a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst +++ b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst @@ -40,55 +40,52 @@ To address the more needs of scientific computing, many fundamental scientific c - `Matplotlib `_ is a plotting library for the Python programming language and its numerical mathematics extension NumPy. - `Pandas `_ is a fast, powerful, flexible, and easy-to-use open-source data analysis and data manipulation library built on top of NumPy. - `SymPy `_ is a Python library for symbolic mathematics. +- `CVXPy `_ is a Python-embedded modeling language for convex optimization problems. Also, more domain-specific libraries have been developed based on these fundamental libraries: - `Scikit-learn `_ is a free software machine learning library for the Python programming language. - `Scikit-image `_ is a collection of algorithms for image processing. -- `Networkx `_ is a Python package for the creation, manipulation, and study of the structure, dynamics, and functions of complex networks. +- `Networkx `_ is a package for the creation, manipulation for complex networks. - `SunPy `_ is a community-developed free and open-source software package for solar physics. - `Astropy `_ is a community-developed free and open-source software package for astronomy. Currently, Python is one of the most popular programming languages for scientific computing. Python for Robotics -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^ -Scientific computation routine are very important for robotics. -For example, matrix operation, optimization, and visualization are fundamental for robotics. +Python has become an increasingly popular language in robotics. -Python has become an increasingly popular language in robotics due to its versatility, readability, and extensive libraries. Here's a breakdown of why Python is a great choice for robotics development: +These are advantages of Python for Robotics: -Advantages of Python for Robotics: +Simplicity and Readability +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +Python's syntax is clear and concise, making it easier to learn and write code. +This is crucial in robotics where complex algorithms and control logic are involved. -Simplicity and Readability: Python's syntax is clear and concise, making it easier to learn and write code. This is crucial in robotics where complex algorithms and control logic are involved. -Extensive Libraries: Python boasts a rich collection of libraries specifically designed for robotics: + +Extensive libraries for scientific computation. +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +Scientific computation routine are fundamental for robotics. +For example: + +- Matrix operation is needed for rigid body transformation, state estimation, and model based control. +- Optimization is needed for optimization based SLAM, optimal path planning, and optimal control. +- Visualization is needed for robot teleoperation, debugging, and simulation. + +ROS supports Python +~~~~~~~~~~~~~~~~~~~~~~~~~~~ ROS (Robot Operating System): ROS, a widely used framework for robotics development, has strong Python support (rospy). This allows developers to easily create nodes, manage communication between different parts of a robot system, and utilize various ROS tools. -OpenCV: This powerful library provides tools for computer vision tasks like image processing, object detection, and motion tracking, essential for robots that perceive and interact with their environment. -NumPy and SciPy: These libraries offer efficient numerical computation and scientific tools, enabling developers to implement complex mathematical models and control algorithms. -Scikit-learn: This library provides machine learning algorithms, which are increasingly important in robotics for tasks like perception, planning, and control. -Cross-Platform Compatibility: Python code can run on various operating systems (Windows, macOS, Linux), providing flexibility in choosing hardware platforms for robotics projects. -Large Community and Support: Python has a vast and active community, offering ample resources, tutorials, and support for developers. This is invaluable when tackling challenges in robotics development. -Use Cases of Python in Robotics: - -Robot Control: Python can be used to write control algorithms for robot manipulators, mobile robots, and other robotic systems. -Perception: Python, combined with libraries like OpenCV, enables robots to process sensor data (camera images, lidar data) to understand their surroundings. -Path Planning: Python algorithms can be used to plan collision-free paths for robots to navigate in complex environments. -Machine Learning: Python libraries like Scikit-learn empower robots to learn from data and improve their performance in tasks like object recognition and manipulation. -Simulation: Python can be used to create simulated environments for testing and developing robot algorithms before deploying them on real hardware. -Examples of Python in Robotics: - -Autonomous Navigation: Python is used in self-driving cars and other autonomous vehicles for tasks like perception, localization, and path planning. -Industrial Robotics: Python is employed in manufacturing for robot control, quality inspection, and automation. -Service Robotics: Python powers robots that perform tasks like cleaning, delivery, and customer service in various environments. -Research and Education: Python is a popular choice in robotics research and education due to its ease of use and versatility. -Getting Started with Python in Robotics: - -Learn Python Basics: Familiarize yourself with Python syntax, data structures, and programming concepts. -Explore Robotics Libraries: Dive into libraries like ROS, OpenCV, and others relevant to your robotics interests. -Practice with Projects: Start with small projects to gain hands-on experience, gradually increasing complexity. -Join the Community: Engage with the robotics community through online forums, workshops, and conferences to learn from others and share your knowledge. -In conclusion, Python's simplicity, extensive libraries, and strong community support make it an ideal language for robotics development. Whether you're a beginner or an experienced programmer, Python offers the tools and resources you need to build innovative and capable robots. + +Cross-Platform Compatibility +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +Python code can run on various operating systems (Windows, macOS, Linux), providing flexibility in choosing hardware platforms for robotics projects. + +Large Community and Support +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +Python has a vast and active community, offering ample resources, tutorials, and support for developers. This is invaluable when tackling challenges in robotics development. + Python is used for this `PythonRobotics` project because of the above features to achieve the purpose of this project described in the :ref:`What is PythonRobotics?`. From 15e106839285033e1fa68cbed6f14e219f3af88f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 7 Feb 2025 13:42:56 +0900 Subject: [PATCH 846/940] Update CONTRIBUTING.md --- CONTRIBUTING.md | 24 +++--------------------- 1 file changed, 3 insertions(+), 21 deletions(-) diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 91f6dfa822..3bcc499e6a 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -1,23 +1,5 @@ -# Contributing to Python +# Contributing -:+1::tada: First of off, thanks very much for taking the time to contribute! :tada::+1: +:+1::tada: First of all, thank you very much for taking the time to contribute! :tada::+1: -The following is a set of guidelines for contributing to PythonRobotics. - -These are mostly guidelines, not rules. - -Use your best judgment, and feel free to propose changes to this document in a pull request. - -# Before contributing - -## Taking a look at the paper. - -Please check this paper to understand the philosophy of this project. - -- [\[1808\.10703\] PythonRobotics: a Python code collection of robotics algorithms](https://arxiv.org/abs/1808.10703) ([BibTeX](https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib)) - -## Check your Python version. - -We only accept a PR for Python 3.8.x or higher. - -We will not accept a PR for Python 2.x. +Please check this document for contribution: [How to contribute — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/modules/0_getting_started/3_how_to_contribute.html) From a8f3388bbe80e41655acedc44c2cbb86d011fb48 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 9 Feb 2025 21:00:02 +0900 Subject: [PATCH 847/940] update introduction (#1146) --- .../3_how_to_contribute_main.rst | 37 ++++++++++++++----- .../python_for_robotics_main.rst | 29 ++++++++++++--- 2 files changed, 51 insertions(+), 15 deletions(-) diff --git a/docs/modules/0_getting_started/3_how_to_contribute_main.rst b/docs/modules/0_getting_started/3_how_to_contribute_main.rst index 6e5c1be8ee..874564cbb8 100644 --- a/docs/modules/0_getting_started/3_how_to_contribute_main.rst +++ b/docs/modules/0_getting_started/3_how_to_contribute_main.rst @@ -9,10 +9,30 @@ There are several ways to contribute to this project as below: #. `Adding missed documentations for existing examples`_ #. `Supporting this project`_ +Before contributing +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Please check following items before contributing: + +Understanding this project +--------------------------- + +Please check this :ref:`What is PythonRobotics?` section and this paper +`PythonRobotics: a Python code collection of robotics algorithms`_ +to understand the philosophies of this project. + +.. _`PythonRobotics: a Python code collection of robotics algorithms`: https://arxiv.org/abs/1808.10703 + +Check your Python version. +--------------------------- + +We only accept a PR for Python 3.12.x or higher. + +We will not accept a PR for Python 2.x. .. _`Adding a new algorithm example`: -Adding a new algorithm example +1. Adding a new algorithm example ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ This is a step by step manual to add a new algorithm example. @@ -112,8 +132,8 @@ Note that this is my hobby project; I appreciate your patience during the review .. _`Reporting and fixing a defect`: -Reporting and fixing a defect -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +2. Reporting and fixing a defect +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Reporting and fixing a defect is also great contribution. @@ -136,8 +156,8 @@ This doc `submit a pull request`_ can be helpful to submit a pull request. .. _`Adding missed documentations for existing examples`: -Adding missed documentations for existing examples -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +3. Adding missed documentations for existing examples +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Adding the missed documentations for existing examples is also great contribution. @@ -150,8 +170,8 @@ This doc `how to write doc`_ can be helpful to write documents. .. _`Supporting this project`: -Supporting this project -^^^^^^^^^^^^^^^^^^^^^^^^ +4. Supporting this project +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Supporting this project financially is also a great contribution!!. @@ -165,8 +185,7 @@ If you or your company would like to support this project, please consider: If you would like to support us in some other way, please contact with creating an issue. -Current Major Sponsors ------------------------ +Current Major Sponsors: #. `JetBrains`_ : They are providing a free license of their IDEs for this OSS development. #. `1Password`_ : They are providing a free license of their 1Password team license for this OSS project. diff --git a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst index 90edd5dc0c..65b1705150 100644 --- a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst +++ b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst @@ -1,6 +1,8 @@ Python for Robotics ---------------------- +Python is used for this `PythonRobotics` project because of the above features +to achieve the purpose of this project described in the :ref:`What is PythonRobotics?`. This section explains the Python itself and features for Robotics. Python for general-purpose programming @@ -76,7 +78,27 @@ For example: ROS supports Python ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -ROS (Robot Operating System): ROS, a widely used framework for robotics development, has strong Python support (rospy). This allows developers to easily create nodes, manage communication between different parts of a robot system, and utilize various ROS tools. +`ROS`_ (Robot Operating System) is an open-source and widely used framework for robotics development. +It is designed to help developping complicated robotic applications. +ROS provides essential tools, libraries, and drivers to simplify robot programming and integration. + +Key Features of ROS: + +- Modular Architecture – Uses a node-based system where different components (nodes) communicate via messages. +- Hardware Abstraction – Supports various robots, sensors, and actuators, making development more flexible. +- Powerful Communication System – Uses topics, services, and actions for efficient data exchange between components. +- Rich Ecosystem – Offers many pre-built packages for navigation, perception, and manipulation. +- Multi-language Support – Primarily uses Python and C++, but also supports other languages. +- Simulation & Visualization – Tools like Gazebo (for simulation) and RViz (for visualization) aid in development and testing. +- Scalability & Community Support – Widely used in academia and industry, with a large open-source community. + +ROS has strong Python support (`rospy`_ for ROS1 and `rclpy`_ for ROS2). +This allows developers to easily create nodes, manage communication between +different parts of a robot system, and utilize various ROS tools. + +.. _`ROS`: https://www.ros.org/ +.. _`rospy`: http://wiki.ros.org/rospy +.. _`rclpy`: https://docs.ros.org/en/jazzy/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Py-Publisher-And-Subscriber.html Cross-Platform Compatibility ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ @@ -85,8 +107,3 @@ Python code can run on various operating systems (Windows, macOS, Linux), provid Large Community and Support ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Python has a vast and active community, offering ample resources, tutorials, and support for developers. This is invaluable when tackling challenges in robotics development. - - -Python is used for this `PythonRobotics` project because of the above features -to achieve the purpose of this project described in the :ref:`What is PythonRobotics?`. - From e304f07a997bf40977a004ac2a66f476aa2aa861 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 10 Feb 2025 11:21:19 +0900 Subject: [PATCH 848/940] update introduction (#1147) --- .../python_for_robotics_main.rst | 32 +++++++++++++++++-- 1 file changed, 29 insertions(+), 3 deletions(-) diff --git a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst index 65b1705150..b677d2c59b 100644 --- a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst +++ b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst @@ -1,9 +1,10 @@ Python for Robotics ---------------------- -Python is used for this `PythonRobotics` project because of the above features -to achieve the purpose of this project described in the :ref:`What is PythonRobotics?`. -This section explains the Python itself and features for Robotics. +A programing language, Python is used for this `PythonRobotics` project +to achieve the purposes of this project described in the :ref:`What is PythonRobotics?`. + +This section explains the Python itself and features for science computing Robotics. Python for general-purpose programming ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -107,3 +108,28 @@ Python code can run on various operating systems (Windows, macOS, Linux), provid Large Community and Support ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Python has a vast and active community, offering ample resources, tutorials, and support for developers. This is invaluable when tackling challenges in robotics development. + +Situations which Python is NOT suitable for Robotics +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +We explained the advantages of Python for robotics. +However, Python is not always the best choice for robotics development. + +These are situations where Python is NOT suitable for robotics: + +High-speed real-time control +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +Python is an interpreted language, which means it is slower than compiled languages like C++. +This can be a disadvantage when real-time control is required, +such as in high-speed motion control or safety-critical systems. + +So, for these applications, we recommend to understand the each algorithm you +needed using this project and implement it in other suitable languages like C++. + +Resource-constrained systems +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +Python is a high-level language that requires more memory and processing power +compared to low-level languages. +So, it is difficult to run Python on resource-constrained systems like +microcontrollers or embedded devices. +In such cases, C or C++ is more suitable for these applications. From 610f35ff58e6535efa619f9ed73a113c6ca2c7f7 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 11 Feb 2025 10:42:10 +0900 Subject: [PATCH 849/940] build(deps): bump mypy from 1.14.1 to 1.15.0 in /requirements (#1148) Bumps [mypy](https://github.com/python/mypy) from 1.14.1 to 1.15.0. - [Changelog](https://github.com/python/mypy/blob/master/CHANGELOG.md) - [Commits](https://github.com/python/mypy/compare/v1.14.1...v1.15.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 9d4e7deb4d..178046ac0d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.10.0 cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test -mypy == 1.14.1 # For unit test +mypy == 1.15.0 # For unit test ruff == 0.9.4 # For unit test From ba307673013376204ceb5a6def16da0e3a86a15d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 11 Feb 2025 11:35:28 +0900 Subject: [PATCH 850/940] build(deps): bump ruff from 0.9.4 to 0.9.6 in /requirements (#1149) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.9.4 to 0.9.6. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.9.4...0.9.6) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 178046ac0d..f5f674d7d2 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.15.0 # For unit test -ruff == 0.9.4 # For unit test +ruff == 0.9.6 # For unit test From b298609b2832c8029baa98b2d3906abce0263ec4 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 11 Feb 2025 21:15:34 +0900 Subject: [PATCH 851/940] update introduction doc (#1151) --- .../definition_of_robotics_main.rst | 81 ++++++++++++++++--- .../python_for_robotics_main.rst | 2 +- .../technology_for_robotics_main.rst | 9 +++ 3 files changed, 82 insertions(+), 10 deletions(-) diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst index fd151e3f20..f6fba646b4 100644 --- a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst +++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst @@ -1,14 +1,77 @@ Definition of Robotics ---------------------- -In recent years, autonomous navigation technologies have received huge -attention in many fields. -Such fields include, autonomous driving[22], drone flight navigation, -and other transportation systems. +What is Robotics? +^^^^^^^^^^^^^^^^^^ -Examples of Python in Robotics: +Robot is a machine that can perform tasks automatically or semi-autonomously. +Robotics is the study of robots. +The field of robotics has wide areas of technologies such as mechanical engineering, +electrical engineering, computer science, and artificial intelligence (AI), +to create machines that can perform tasks autonomously or semi-autonomously. + +The History of Robots +^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +This timeline highlights key milestones in the history of robotics: + +Ancient and Early Concepts (Before 1500s) +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The idea of **automated machines** has existed for thousands of years. Ancient civilizations imagined mechanical beings: + +- **Ancient Greece (4th Century BC)** – Greek engineer **Hero of Alexandria** designed early **automata** (self-operating machines) powered by water or air. +- **Chinese and Arabic Automata (9th–13th Century)** – Inventors like **Al-Jazari** created intricate mechanical devices, including water clocks and humanoid robots. + +The Birth of Modern Robotics (1500s–1800s) +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +- **Leonardo da Vinci’s Robot (1495)** – Designed a humanoid knight with mechanical movement. +- **Jacques de Vaucanson’s Automata (1738)** – Created robotic figures like a mechanical duck that could "eat" and "digest." +- **Industrial Revolution (18th–19th Century)** – Machines began replacing human labor in factories, setting the foundation for automation. + +The Rise of Industrial Robots (1900s–1950s) +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +- **The Term “Robot” (1921)** – Czech writer **Karel Čapek** introduced the word *“robot”* in his play *R.U.R. (Rossum’s Universal Robots)*. +- **Early Cybernetics (1940s–1950s)** – Scientists like **Norbert Wiener** developed theories of self-regulating machines, influencing modern robotics. + +The Birth of Modern Robotics (1950s–1980s) +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +- **First Industrial Robot (1961)** – *Unimate*, created by **George Devol and Joseph Engelberger**, was the first programmable robot used in a factory. +- **Rise of AI & Autonomous Robots (1970s–1980s)** – Researchers developed mobile robots like **Shakey** (Stanford, 1966) and AI-based control systems. + +Advanced Robotics and AI Integration (1990s–Present) +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +- **Autonomous Vehicles & Drones** – Self-driving cars and UAVs (unmanned aerial vehicles) became more advanced. +- **Medical Robotics** – Robots like **da Vinci Surgical System** revolutionized healthcare. +- **Personal Robots** – Devices like **Roomba** (vacuum robot) and **Sophia** (AI humanoid) became popular. +- **Collaborative Robots (Cobots)** – Robots started working alongside humans in industries. + +Key Components of Robotics +^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Robotics consists of several essential components: + +#. Sensors – Gather information from the environment (e.g., cameras, LiDAR, gyro, accelerometer, wheel encoders). +#. Actuators – Enable movement and interaction with the world (e.g., motors, hydraulic systems). +#. Computers – Process sensor data and make decisions (e.g., micro-controllers, CPUs, GPUs). +#. Power Supply – Provides energy to run the robot (e.g., batteries, solar power). +#. Software & Algorithms – Allow the robot to function and make intelligent decisions (e.g., ROS, machine learning models, localization, mapping, path planning, control). + +This project, PythonRobotics, focuses on the software and algorithms part of robotics. + +Applications of Robots +^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Robots come in various forms depending on their purpose: + +#. 🤖 Industrial Robots – Used in manufacturing (e.g., robotic arms in manufacturing factories). +#. 🏠 Service Robots – Assist in daily life (e.g., vacuum robots, delivery robots). +#. 🚗 Autonomous Vehicles – Self-driving cars and drones. +#. 👨‍⚕️ Medical Robots – Assist in surgeries and healthcare. +#. 🚀 Space & Exploration Robots – Used for planetary exploration (e.g., NASA’s Mars rovers). +#. 🐶 Humanoid & Social Robots – Designed to interact with humans (e.g., ASIMO, Sophia). -Autonomous Navigation: Python is used in self-driving cars and other autonomous vehicles for tasks like perception, localization, and path planning. -Industrial Robotics: Python is employed in manufacturing for robot control, quality inspection, and automation. -Service Robotics: Python powers robots that perform tasks like cleaning, delivery, and customer service in various environments. -Research and Education: Python is a popular choice in robotics research and education due to its ease of use and versatility. \ No newline at end of file diff --git a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst index b677d2c59b..c47c122853 100644 --- a/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst +++ b/docs/modules/1_introduction/2_python_for_robotics/python_for_robotics_main.rst @@ -4,7 +4,7 @@ Python for Robotics A programing language, Python is used for this `PythonRobotics` project to achieve the purposes of this project described in the :ref:`What is PythonRobotics?`. -This section explains the Python itself and features for science computing Robotics. +This section explains the Python itself and features for science computing and robotics. Python for general-purpose programming ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst b/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst index 4dd1d1842f..93dc9e3466 100644 --- a/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst +++ b/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst @@ -1,6 +1,15 @@ Technology for Robotics ------------------------- + +Autonomous Navigation +^^^^^^^^^^^^^^^^^^^^^^^^ + +In recent years, autonomous navigation technologies have received huge +attention in many fields. +Such fields include, autonomous driving[22], drone flight navigation, +and other transportation systems. + An autonomous navigation system is a system that can move to a goal over long periods of time without any external control by an operator. The system requires a wide range of technologies: From be608f067cbd96f34955b81d3e5be9e22a46f588 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 12 Feb 2025 21:51:29 +0900 Subject: [PATCH 852/940] update introduction doc (#1152) --- .../definition_of_robotics_main.rst | 38 ++++++++++++++----- .../technology_for_robotics_main.rst | 3 ++ 2 files changed, 31 insertions(+), 10 deletions(-) diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst index f6fba646b4..63525057fe 100644 --- a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst +++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst @@ -1,14 +1,24 @@ Definition of Robotics ---------------------- +This section explains the definition, history, key components, and applications of robotics. + What is Robotics? ^^^^^^^^^^^^^^^^^^ Robot is a machine that can perform tasks automatically or semi-autonomously. Robotics is the study of robots. -The field of robotics has wide areas of technologies such as mechanical engineering, -electrical engineering, computer science, and artificial intelligence (AI), -to create machines that can perform tasks autonomously or semi-autonomously. + +The word “robot” comes from the Czech word “robota,” which means “forced labor” or “drudgery.” +It was first used in the 1920 science fiction play `R.U.R.`_ (Rossum’s Universal Robots) +by the Czech writer `Karel Čapek`_. +In the play, robots were artificial workers created to serve humans, but they eventually rebelled. + +Over time, “robot” came to refer to machines or automated systems that can perform tasks, +often with some level of intelligence or autonomy. + +.. _`R.U.R.`: https://thereader.mitpress.mit.edu/origin-word-robot-rur/ +.. _`Karel Čapek`: https://en.wikipedia.org/wiki/Karel_%C4%8Capek The History of Robots ^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -18,22 +28,30 @@ This timeline highlights key milestones in the history of robotics: Ancient and Early Concepts (Before 1500s) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -The idea of **automated machines** has existed for thousands of years. Ancient civilizations imagined mechanical beings: +The idea of **automated machines** has existed for thousands of years. +Ancient civilizations imagined mechanical beings: + +- **Ancient Greece (4th Century BC)** – Greek engineer `Hero of Alexandria`_ designed early **automata** (self-operating machines) powered by water or air. +- **Chinese and Arabic Automata (9th–13th Century)** – Inventors like `Ismail Al-Jazari`_ created intricate mechanical devices, including water clocks and automated moving peacocks driven by hydropower. -- **Ancient Greece (4th Century BC)** – Greek engineer **Hero of Alexandria** designed early **automata** (self-operating machines) powered by water or air. -- **Chinese and Arabic Automata (9th–13th Century)** – Inventors like **Al-Jazari** created intricate mechanical devices, including water clocks and humanoid robots. +.. _`Hero of Alexandria`: https://en.wikipedia.org/wiki/Hero_of_Alexandria +.. _`Ismail Al-Jazari`: https://en.wikipedia.org/wiki/Ismail_al-Jazari The Birth of Modern Robotics (1500s–1800s) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -- **Leonardo da Vinci’s Robot (1495)** – Designed a humanoid knight with mechanical movement. -- **Jacques de Vaucanson’s Automata (1738)** – Created robotic figures like a mechanical duck that could "eat" and "digest." -- **Industrial Revolution (18th–19th Century)** – Machines began replacing human labor in factories, setting the foundation for automation. +- `Leonardo da Vinci’s Robot`_ (1495) – Designed a humanoid knight with mechanical movement. +- `Jacques de Vaucanson’s Digesting Duck`_ (1738) – Created robotic figures like a mechanical duck that could "eat" and "digest." +- `Industrial Revolution`_ (18th–19th Century) – Machines began replacing human labor in factories, setting the foundation for automation. + +.. _`Leonardo da Vinci’s Robot`: https://en.wikipedia.org/wiki/Leonardo%27s_robot +.. _`Jacques de Vaucanson’s Digesting Duck`: https://en.wikipedia.org/wiki/Jacques_de_Vaucanson +.. _`Industrial Revolution`: https://en.wikipedia.org/wiki/Industrial_Revolution The Rise of Industrial Robots (1900s–1950s) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -- **The Term “Robot” (1921)** – Czech writer **Karel Čapek** introduced the word *“robot”* in his play *R.U.R. (Rossum’s Universal Robots)*. +- **The Term “Robot” (1921)** – Czech writer `Karel Čapek`_ introduced the word *“robot”* in his play `R.U.R.`_ (Rossum’s Universal Robots). - **Early Cybernetics (1940s–1950s)** – Scientists like **Norbert Wiener** developed theories of self-regulating machines, influencing modern robotics. The Birth of Modern Robotics (1950s–1980s) diff --git a/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst b/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst index 93dc9e3466..e460059e20 100644 --- a/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst +++ b/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst @@ -1,6 +1,9 @@ Technology for Robotics ------------------------- +The field of robotics needs wide areas of technologies such as mechanical engineering, +electrical engineering, computer science, and artificial intelligence (AI). + Autonomous Navigation ^^^^^^^^^^^^^^^^^^^^^^^^ From 1ecc154fbaf9bc2342671fe93a305e8f0e3f510f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 13 Feb 2025 17:19:03 +0900 Subject: [PATCH 853/940] update contribution link in README.md to fix invalid link (#1154) --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index cb1816c2b5..818d7b0d4e 100644 --- a/README.md +++ b/README.md @@ -617,7 +617,7 @@ This is a list of user's comment and references:[users\_comments](https://github Any contribution is welcome!! -Please check this document:[How To Contribute — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/how_to_contribute.html) +Please check this document:[How To Contribute — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/modules/0_getting_started/3_how_to_contribute.html) # Citing From 156483000524488d64687a853ac030e8d57c18a6 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 13 Feb 2025 17:56:17 +0900 Subject: [PATCH 854/940] update robotics definition document to enhance references and clarity (#1155) --- .../definition_of_robotics_main.rst | 29 ++++++++++++++----- 1 file changed, 22 insertions(+), 7 deletions(-) diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst index 63525057fe..265814e068 100644 --- a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst +++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst @@ -52,21 +52,36 @@ The Rise of Industrial Robots (1900s–1950s) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - **The Term “Robot” (1921)** – Czech writer `Karel Čapek`_ introduced the word *“robot”* in his play `R.U.R.`_ (Rossum’s Universal Robots). -- **Early Cybernetics (1940s–1950s)** – Scientists like **Norbert Wiener** developed theories of self-regulating machines, influencing modern robotics. +- **Early Cybernetics (1940s–1950s)** – Scientists like `Norbert Wiener`_ developed theories of self-regulating machines, influencing modern robotics (Cybernetics). + +.. _`Norbert Wiener`: https://en.wikipedia.org/wiki/Norbert_Wiener The Birth of Modern Robotics (1950s–1980s) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -- **First Industrial Robot (1961)** – *Unimate*, created by **George Devol and Joseph Engelberger**, was the first programmable robot used in a factory. -- **Rise of AI & Autonomous Robots (1970s–1980s)** – Researchers developed mobile robots like **Shakey** (Stanford, 1966) and AI-based control systems. +- **First Industrial Robot (1961)** – `Unimate`_, created by `George Devol`_ and `Joseph Engelberger`_, was the first programmable robot used in a factory. +- **Rise of AI & Autonomous Robots (1970s–1980s)** – Researchers developed mobile robots like `Shakey`_ (Stanford, 1966) and AI-based control systems. + +.. _`Unimate`: https://en.wikipedia.org/wiki/Unimate +.. _`George Devol`: https://en.wikipedia.org/wiki/George_Devol +.. _`Joseph Engelberger`: https://en.wikipedia.org/wiki/Joseph_Engelberger +.. _`Shakey`: https://en.wikipedia.org/wiki/Shakey_the_robot Advanced Robotics and AI Integration (1990s–Present) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -- **Autonomous Vehicles & Drones** – Self-driving cars and UAVs (unmanned aerial vehicles) became more advanced. -- **Medical Robotics** – Robots like **da Vinci Surgical System** revolutionized healthcare. -- **Personal Robots** – Devices like **Roomba** (vacuum robot) and **Sophia** (AI humanoid) became popular. -- **Collaborative Robots (Cobots)** – Robots started working alongside humans in industries. +- **Autonomous Vehicles** – Self-driving cars for robo taxi like `Waymo`_ and autonomous haulage system in mining like `AHS`_ became more advanced and bisiness-ready. +- **Medical Robotics** – Robots like `da Vinci Surgical System`_ revolutionized healthcare. +- **Personal Robots** – Devices like `Roomba`_ (vacuum robot) and `Sophia`_ (AI humanoid) became popular. +- **Service Robots** - Assistive robots like serving robots in restaurants and hotels like `Bellabot`_. +- **Collaborative Robots (Drones)** – Collaborative robots like UAV (Unmanned Aerial Vehicle) in drone shows and delivery services. + +.. _`Waymo`: https://waymo.com/ +.. _`AHS`: https://www.futurebridge.com/industry/perspectives-industrial-manufacturing/autonomous-haulage-systems-the-future-of-mining-operations/ +.. _`da Vinci Surgical System`: https://en.wikipedia.org/wiki/Da_Vinci_Surgical_System +.. _`Roomba`: https://en.wikipedia.org/wiki/Roomba +.. _`Sophia`: https://en.wikipedia.org/wiki/Sophia_(robot) +.. _`Bellabot`: https://www.pudurobotics.com/en Key Components of Robotics ^^^^^^^^^^^^^^^^^^^^^^^^^^^ From 77ad3344b5e9df26ca370725d3921dd354c755b1 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 14 Feb 2025 21:20:35 +0900 Subject: [PATCH 855/940] update robotics definition document to improve clarity and add references (#1157) --- .../definition_of_robotics_main.rst | 28 +++++++------------ 1 file changed, 10 insertions(+), 18 deletions(-) diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst index 265814e068..f54d4d41fa 100644 --- a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst +++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst @@ -70,12 +70,17 @@ The Birth of Modern Robotics (1950s–1980s) Advanced Robotics and AI Integration (1990s–Present) ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +- **Industrial Robots** – Advanced robots like `Baxter`_ and `Amazon Robotics`_ revolutionized manufacturing and logistics. - **Autonomous Vehicles** – Self-driving cars for robo taxi like `Waymo`_ and autonomous haulage system in mining like `AHS`_ became more advanced and bisiness-ready. +- **Exploration Robots** – Used for planetary exploration (e.g., NASA’s `Mars rovers`_). - **Medical Robotics** – Robots like `da Vinci Surgical System`_ revolutionized healthcare. - **Personal Robots** – Devices like `Roomba`_ (vacuum robot) and `Sophia`_ (AI humanoid) became popular. - **Service Robots** - Assistive robots like serving robots in restaurants and hotels like `Bellabot`_. - **Collaborative Robots (Drones)** – Collaborative robots like UAV (Unmanned Aerial Vehicle) in drone shows and delivery services. +.. _`Baxter`: https://en.wikipedia.org/wiki/Baxter_(robot) +.. _`Amazon Robotics`: https://en.wikipedia.org/wiki/Amazon_Robotics +.. _`Mars rovers`: https://en.wikipedia.org/wiki/Mars_rover .. _`Waymo`: https://waymo.com/ .. _`AHS`: https://www.futurebridge.com/industry/perspectives-industrial-manufacturing/autonomous-haulage-systems-the-future-of-mining-operations/ .. _`da Vinci Surgical System`: https://en.wikipedia.org/wiki/Da_Vinci_Surgical_System @@ -88,23 +93,10 @@ Key Components of Robotics Robotics consists of several essential components: -#. Sensors – Gather information from the environment (e.g., cameras, LiDAR, gyro, accelerometer, wheel encoders). -#. Actuators – Enable movement and interaction with the world (e.g., motors, hydraulic systems). -#. Computers – Process sensor data and make decisions (e.g., micro-controllers, CPUs, GPUs). -#. Power Supply – Provides energy to run the robot (e.g., batteries, solar power). -#. Software & Algorithms – Allow the robot to function and make intelligent decisions (e.g., ROS, machine learning models, localization, mapping, path planning, control). +#. Sensors – Gather information from the environment (e.g., Cameras, LiDAR, GNSS, Gyro, Accelerometer, Wheel encoders). +#. Actuators – Enable movement and interaction with the world (e.g., Motors, Hydraulic systems). +#. Computers – Process sensor data and make decisions (e.g., Micro-controllers, CPUs, GPUs). +#. Power Supply – Provides energy to run the robot (e.g., Batteries, Solar power). +#. Software & Algorithms – Allow the robot to function and make intelligent decisions (e.g., ROS, Machine learning models, Localization, Mapping, Path planning, Control). This project, PythonRobotics, focuses on the software and algorithms part of robotics. - -Applications of Robots -^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -Robots come in various forms depending on their purpose: - -#. 🤖 Industrial Robots – Used in manufacturing (e.g., robotic arms in manufacturing factories). -#. 🏠 Service Robots – Assist in daily life (e.g., vacuum robots, delivery robots). -#. 🚗 Autonomous Vehicles – Self-driving cars and drones. -#. 👨‍⚕️ Medical Robots – Assist in surgeries and healthcare. -#. 🚀 Space & Exploration Robots – Used for planetary exploration (e.g., NASA’s Mars rovers). -#. 🐶 Humanoid & Social Robots – Designed to interact with humans (e.g., ASIMO, Sophia). - From 35c08824d00bd9fb452d1ee951018b177e65fd00 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 15 Feb 2025 16:08:23 +0900 Subject: [PATCH 856/940] add external sensors documentation to appendix (#1159) --- docs/modules/12_appendix/appendix_main.rst | 1 + .../12_appendix/external_sensors_main.rst | 56 +++++++++++++++++++ 2 files changed, 57 insertions(+) create mode 100644 docs/modules/12_appendix/external_sensors_main.rst diff --git a/docs/modules/12_appendix/appendix_main.rst b/docs/modules/12_appendix/appendix_main.rst index cb1ac04066..89a7fa9303 100644 --- a/docs/modules/12_appendix/appendix_main.rst +++ b/docs/modules/12_appendix/appendix_main.rst @@ -10,4 +10,5 @@ Appendix steering_motion_model Kalmanfilter_basics Kalmanfilter_basics_2 + external_sensors diff --git a/docs/modules/12_appendix/external_sensors_main.rst b/docs/modules/12_appendix/external_sensors_main.rst new file mode 100644 index 0000000000..a1dba3b214 --- /dev/null +++ b/docs/modules/12_appendix/external_sensors_main.rst @@ -0,0 +1,56 @@ +External Sensors for Robots +============================ + +Introduction +------------ + +In recent years, the application of robotic technology has advanced, +particularly in areas such as autonomous vehicles and disaster response robots. +A crucial element in these technologies is external recognition—the robot's ability to understand its surrounding environment, identify safe zones, and detect moving objects using onboard sensors. Achieving effective external recognition involves various techniques, but equally important is the selection of appropriate sensors. Robots, like the sensors they employ, come in many forms, but external recognition sensors can be broadly categorized into three types. Developing an advanced external recognition system requires a thorough understanding of each sensor's principles and characteristics to determine their optimal application. This article summarizes the principles and features of these sensors for personal study purposes. + +Laser Sensors +------------- + +Laser sensors measure distances by utilizing light, commonly referred to as Light Detection and Ranging (LIDAR). They operate by emitting light towards an object and calculating the distance based on the time it takes for the reflected light to return, using the speed of light as a constant. + +Radar Sensors +------------- + +TBD + + +Monocular Cameras +----------------- + +Monocular cameras utilize a single camera to recognize the external environment. Compared to other sensors, they can detect color and brightness information, making them primarily useful for object recognition. However, they face challenges in independently measuring distances to surrounding objects and may struggle in low-light or dark conditions. + +Requirements for Cameras and Image Processing in Robotics +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +While camera sensors are widely used in applications like surveillance, deploying them in robotics necessitates meeting specific requirements: + +1. High dynamic range to adapt to various lighting conditions +2. Wide measurement range +3. Capability for three-dimensional measurement through techniques like motion stereo +4. Real-time processing with high frame rates +5. Cost-effectiveness + +Stereo Cameras +-------------- + +Stereo cameras employ multiple cameras to measure distances to surrounding objects. By knowing the positions and orientations of each camera and analyzing the disparity in the images (parallax), the distance to a specific point (the object represented by a particular pixel) can be calculated. + +Characteristics of Stereo Cameras +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Advantages of stereo cameras include the ability to obtain high-precision and high-density distance information at close range, depending on factors like camera resolution and the distance between cameras (baseline). This makes them suitable for indoor robots that require precise shape recognition of nearby objects. Additionally, stereo cameras are relatively cost-effective compared to other sensors, leading to their use in consumer products like Subaru's EyeSight system. However, stereo cameras are less effective for long-distance measurements due to a decrease in accuracy proportional to the square of the distance. They are also susceptible to environmental factors such as lighting conditions. + +Ultrasonic Sensors +------------------ + +Ultrasonic sensors are commonly used in indoor robots and some automotive autonomous driving systems. Their features include affordability compared to laser or radar sensors, the ability to detect very close objects, and the capability to sense materials like glass, which may be challenging for lasers or cameras. However, they have limitations such as shorter maximum measurement distances and lower resolution and accuracy. + +References +---------- + +TBD From e82a12319b5336beaff01ab9fd2ce7818bb08dfb Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 16 Feb 2025 21:41:22 +0900 Subject: [PATCH 857/940] add internal sensors documentation to appendix and create new internal sensors overview (#1161) --- docs/modules/12_appendix/appendix_main.rst | 1 + .../12_appendix/external_sensors_main.rst | 4 +++ .../12_appendix/internal_sensors_main.rst | 32 +++++++++++++++++++ 3 files changed, 37 insertions(+) create mode 100644 docs/modules/12_appendix/internal_sensors_main.rst diff --git a/docs/modules/12_appendix/appendix_main.rst b/docs/modules/12_appendix/appendix_main.rst index 89a7fa9303..a55389e1e6 100644 --- a/docs/modules/12_appendix/appendix_main.rst +++ b/docs/modules/12_appendix/appendix_main.rst @@ -10,5 +10,6 @@ Appendix steering_motion_model Kalmanfilter_basics Kalmanfilter_basics_2 + internal_sensors external_sensors diff --git a/docs/modules/12_appendix/external_sensors_main.rst b/docs/modules/12_appendix/external_sensors_main.rst index a1dba3b214..d36b852d42 100644 --- a/docs/modules/12_appendix/external_sensors_main.rst +++ b/docs/modules/12_appendix/external_sensors_main.rst @@ -1,6 +1,10 @@ External Sensors for Robots ============================ +This project, `PythonRobotics`, focuses on algorithms, so hardware is not included. +However, having basic knowledge of hardware in robotics is also important for understanding algorithms. +Therefore, we will provide an overview. + Introduction ------------ diff --git a/docs/modules/12_appendix/internal_sensors_main.rst b/docs/modules/12_appendix/internal_sensors_main.rst new file mode 100644 index 0000000000..13b8de4203 --- /dev/null +++ b/docs/modules/12_appendix/internal_sensors_main.rst @@ -0,0 +1,32 @@ +Internal Sensors for Robots +============================ + +This project, `PythonRobotics`, focuses on algorithms, so hardware is not included. +However, having basic knowledge of hardware in robotics is also important for understanding algorithms. +Therefore, we will provide an overview. + +Introduction +------------ + +Global Navigation Satellite System (GNSS) +------------------------------------------- + +Gyroscope +---------- + +Accelerometer +-------------- + +Magnetometer +-------------- + +Inertial Measurement Unit (IMU) +-------------------------------- + +Pressure Sensor +----------------- + +Temperature Sensor +-------------------- + + From c92aaf36d8665a3b9ecd1a661f151cfd6ede4c66 Mon Sep 17 00:00:00 2001 From: Aglargil <34728006+Aglargil@users.noreply.github.com> Date: Mon, 17 Feb 2025 18:47:04 +0800 Subject: [PATCH 858/940] feat: add ElasticBands (#1156) * feat: add ElasticBands * feat: Elastic Bands update * feat: ElasticBands update * feat: ElasticBands add test * feat: ElasticBands reduce occupation * fix: ElasticBands test * feat: ElasticBands remove tangential component * feat: Elastic Bands update * feat: Elastic Bands doc * feat: Elastic Bands update * feat: ElasticBands update --- Mapping/DistanceMap/distance_map.py | 51 +++ PathPlanning/ElasticBands/elastic_bands.py | 300 ++++++++++++++++++ PathPlanning/ElasticBands/obstacles.npy | Bin 0 -> 384 bytes PathPlanning/ElasticBands/path.npy | Bin 0 -> 224 bytes .../elastic_bands/elastic_bands_main.rst | 73 +++++ .../5_path_planning/path_planning_main.rst | 1 + tests/test_elastic_bands.py | 23 ++ 7 files changed, 448 insertions(+) create mode 100644 PathPlanning/ElasticBands/elastic_bands.py create mode 100644 PathPlanning/ElasticBands/obstacles.npy create mode 100644 PathPlanning/ElasticBands/path.npy create mode 100644 docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst create mode 100644 tests/test_elastic_bands.py diff --git a/Mapping/DistanceMap/distance_map.py b/Mapping/DistanceMap/distance_map.py index 54c98c6a75..0dcc7380c5 100644 --- a/Mapping/DistanceMap/distance_map.py +++ b/Mapping/DistanceMap/distance_map.py @@ -11,11 +11,62 @@ import numpy as np import matplotlib.pyplot as plt +import scipy INF = 1e20 ENABLE_PLOT = True +def compute_sdf_scipy(obstacles): + """ + Compute the signed distance field (SDF) from a boolean field using scipy. + This function has the same functionality as compute_sdf. + However, by using scipy.ndimage.distance_transform_edt, it can compute much faster. + + Example: 500×500 map + • compute_sdf: 3 sec + • compute_sdf_scipy: 0.05 sec + + Parameters + ---------- + obstacles : array_like + A 2D boolean array where '1' represents obstacles and '0' represents free space. + + Returns + ------- + array_like + A 2D array representing the signed distance field, where positive values indicate distance + to the nearest obstacle, and negative values indicate distance to the nearest free space. + """ + # distance_transform_edt use '0' as obstacles, so we need to convert the obstacles to '0' + a = scipy.ndimage.distance_transform_edt(obstacles == 0) + b = scipy.ndimage.distance_transform_edt(obstacles == 1) + return a - b + + +def compute_udf_scipy(obstacles): + """ + Compute the unsigned distance field (UDF) from a boolean field using scipy. + This function has the same functionality as compute_udf. + However, by using scipy.ndimage.distance_transform_edt, it can compute much faster. + + Example: 500×500 map + • compute_udf: 1.5 sec + • compute_udf_scipy: 0.02 sec + + Parameters + ---------- + obstacles : array_like + A 2D boolean array where '1' represents obstacles and '0' represents free space. + + Returns + ------- + array_like + A 2D array of distances from the nearest obstacle, with the same dimensions as `bool_field`. + """ + return scipy.ndimage.distance_transform_edt(obstacles == 0) + + def compute_sdf(obstacles): """ Compute the signed distance field (SDF) from a boolean field. diff --git a/PathPlanning/ElasticBands/elastic_bands.py b/PathPlanning/ElasticBands/elastic_bands.py new file mode 100644 index 0000000000..785f822d14 --- /dev/null +++ b/PathPlanning/ElasticBands/elastic_bands.py @@ -0,0 +1,300 @@ +""" +Elastic Bands + +author: Wang Zheng (@Aglargil) + +Ref: + +- [Elastic Bands: Connecting Path Planning and Control] +(http://www8.cs.umu.se/research/ifor/dl/Control/elastic%20bands.pdf) +""" + +import numpy as np +import sys +import pathlib +import matplotlib.pyplot as plt +from matplotlib.patches import Circle + +sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) + +from Mapping.DistanceMap.distance_map import compute_sdf_scipy + +# Elastic Bands Params +MAX_BUBBLE_RADIUS = 100 +MIN_BUBBLE_RADIUS = 10 +RHO0 = 20.0 # Maximum distance for applying repulsive force +KC = 0.05 # Contraction force gain +KR = -0.1 # Repulsive force gain +LAMBDA = 0.7 # Overlap constraint factor +STEP_SIZE = 3.0 # Step size for calculating gradient + +# Visualization Params +ENABLE_PLOT = True +# ENABLE_INTERACTIVE is True allows user to add obstacles by left clicking +# and add path points by right clicking and start planning by middle clicking +ENABLE_INTERACTIVE = False +# ENABLE_SAVE_DATA is True allows saving the path and obstacles which added +# by user in interactive mode to file +ENABLE_SAVE_DATA = False +MAX_ITER = 50 + + +class Bubble: + def __init__(self, position, radius): + self.pos = np.array(position) # Bubble center coordinates [x, y] + self.radius = radius # Safety distance radius ρ(b) + if self.radius > MAX_BUBBLE_RADIUS: + self.radius = MAX_BUBBLE_RADIUS + if self.radius < MIN_BUBBLE_RADIUS: + self.radius = MIN_BUBBLE_RADIUS + + +class ElasticBands: + def __init__( + self, + initial_path, + obstacles, + rho0=RHO0, + kc=KC, + kr=KR, + lambda_=LAMBDA, + step_size=STEP_SIZE, + ): + self.distance_map = compute_sdf_scipy(obstacles) + self.bubbles = [ + Bubble(p, self.compute_rho(p)) for p in initial_path + ] # Initialize bubble chain + self.kc = kc # Contraction force gain + self.kr = kr # Repulsive force gain + self.rho0 = rho0 # Maximum distance for applying repulsive force + self.lambda_ = lambda_ # Overlap constraint factor + self.step_size = step_size # Step size for calculating gradient + self._maintain_overlap() + + def compute_rho(self, position): + """Compute the distance field value at the position""" + return self.distance_map[int(position[0]), int(position[1])] + + def contraction_force(self, i): + """Calculate internal contraction force for the i-th bubble""" + if i == 0 or i == len(self.bubbles) - 1: + return np.zeros(2) + + prev = self.bubbles[i - 1].pos + next_ = self.bubbles[i + 1].pos + current = self.bubbles[i].pos + + # f_c = kc * ( (prev-current)/|prev-current| + (next-current)/|next-current| ) + dir_prev = (prev - current) / (np.linalg.norm(prev - current) + 1e-6) + dir_next = (next_ - current) / (np.linalg.norm(next_ - current) + 1e-6) + return self.kc * (dir_prev + dir_next) + + def repulsive_force(self, i): + """Calculate external repulsive force for the i-th bubble""" + h = self.step_size # Step size + b = self.bubbles[i].pos + rho = self.bubbles[i].radius + + if rho >= self.rho0: + return np.zeros(2) + + # Finite difference approximation of the gradient ∂ρ/∂b + dx = np.array([h, 0]) + dy = np.array([0, h]) + grad_x = (self.compute_rho(b - dx) - self.compute_rho(b + dx)) / (2 * h) + grad_y = (self.compute_rho(b - dy) - self.compute_rho(b + dy)) / (2 * h) + grad = np.array([grad_x, grad_y]) + + return self.kr * (self.rho0 - rho) * grad + + def update_bubbles(self): + """Update bubble positions""" + new_bubbles = [] + for i in range(len(self.bubbles)): + if i == 0 or i == len(self.bubbles) - 1: + new_bubbles.append(self.bubbles[i]) # Fixed start and end points + continue + + f_total = self.contraction_force(i) + self.repulsive_force(i) + v = self.bubbles[i - 1].pos - self.bubbles[i + 1].pos + + # Remove tangential component + f_star = f_total - f_total * v * v / (np.linalg.norm(v) ** 2 + 1e-6) + + alpha = self.bubbles[i].radius # Adaptive step size + new_pos = self.bubbles[i].pos + alpha * f_star + new_pos = np.clip(new_pos, 0, 499) + new_radius = self.compute_rho(new_pos) + + # Update bubble and maintain overlap constraint + new_bubble = Bubble(new_pos, new_radius) + new_bubbles.append(new_bubble) + + self.bubbles = new_bubbles + self._maintain_overlap() + + def _maintain_overlap(self): + """Maintain bubble chain continuity (simplified insertion/deletion mechanism)""" + # Insert bubbles + i = 0 + while i < len(self.bubbles) - 1: + bi, bj = self.bubbles[i], self.bubbles[i + 1] + dist = np.linalg.norm(bi.pos - bj.pos) + if dist > self.lambda_ * (bi.radius + bj.radius): + new_pos = (bi.pos + bj.pos) / 2 + rho = self.compute_rho( + new_pos + ) # Calculate new radius using environment model + self.bubbles.insert(i + 1, Bubble(new_pos, rho)) + i += 2 # Skip the processed region + else: + i += 1 + + # Delete redundant bubbles + i = 1 + while i < len(self.bubbles) - 1: + prev = self.bubbles[i - 1] + next_ = self.bubbles[i + 1] + dist = np.linalg.norm(prev.pos - next_.pos) + if dist <= self.lambda_ * (prev.radius + next_.radius): + del self.bubbles[i] # Delete if redundant + else: + i += 1 + + +class ElasticBandsVisualizer: + def __init__(self): + self.obstacles = np.zeros((500, 500)) + self.obstacles_points = [] + self.path_points = [] + self.elastic_band = None + self.running = True + + if ENABLE_PLOT: + self.fig, self.ax = plt.subplots(figsize=(8, 8)) + self.fig.canvas.mpl_connect("close_event", self.on_close) + self.ax.set_xlim(0, 500) + self.ax.set_ylim(0, 500) + + if ENABLE_INTERACTIVE: + self.path_points = [] # Add a list to store path points + # Connect mouse events + self.fig.canvas.mpl_connect("button_press_event", self.on_click) + else: + self.path_points = np.load(pathlib.Path(__file__).parent / "path.npy") + self.obstacles_points = np.load( + pathlib.Path(__file__).parent / "obstacles.npy" + ) + for x, y in self.obstacles_points: + self.add_obstacle(x, y) + self.plan_path() + + self.plot_background() + + def on_close(self, event): + """Handle window close event""" + self.running = False + plt.close("all") # Close all figure windows + + def plot_background(self): + """Plot the background grid""" + if not ENABLE_PLOT or not self.running: + return + + self.ax.cla() + self.ax.set_xlim(0, 500) + self.ax.set_ylim(0, 500) + self.ax.grid(True) + + if ENABLE_INTERACTIVE: + self.ax.set_title( + "Elastic Bands Path Planning\n" + "Left click: Add obstacles\n" + "Right click: Add path points\n" + "Middle click: Start planning", + pad=20, + ) + else: + self.ax.set_title("Elastic Bands Path Planning", pad=20) + + if self.path_points: + self.ax.plot( + [p[0] for p in self.path_points], + [p[1] for p in self.path_points], + "yo", + markersize=8, + ) + + self.ax.imshow(self.obstacles.T, origin="lower", cmap="binary", alpha=0.8) + self.ax.plot([], [], color="black", label="obstacles") + if self.elastic_band is not None: + path = [b.pos.tolist() for b in self.elastic_band.bubbles] + path = np.array(path) + self.ax.plot(path[:, 0], path[:, 1], "b-", linewidth=2, label="path") + + for bubble in self.elastic_band.bubbles: + circle = Circle( + bubble.pos, bubble.radius, fill=False, color="g", alpha=0.3 + ) + self.ax.add_patch(circle) + self.ax.plot(bubble.pos[0], bubble.pos[1], "bo", markersize=10) + self.ax.plot([], [], color="green", label="bubbles") + + self.ax.legend(loc="upper right") + plt.draw() + plt.pause(0.01) + + def add_obstacle(self, x, y): + """Add an obstacle at the given coordinates""" + size = 30 # Side length of the square + half_size = size // 2 + x_start = max(0, x - half_size) + x_end = min(self.obstacles.shape[0], x + half_size) + y_start = max(0, y - half_size) + y_end = min(self.obstacles.shape[1], y + half_size) + self.obstacles[x_start:x_end, y_start:y_end] = 1 + + def on_click(self, event): + """Handle mouse click events""" + if event.inaxes != self.ax: + return + + x, y = int(event.xdata), int(event.ydata) + + if event.button == 1: # Left click to add obstacles + self.add_obstacle(x, y) + self.obstacles_points.append([x, y]) + + elif event.button == 3: # Right click to add path points + self.path_points.append([x, y]) + + elif event.button == 2: # Middle click to end path input and start planning + if len(self.path_points) >= 2: + if ENABLE_SAVE_DATA: + np.save( + pathlib.Path(__file__).parent / "path.npy", self.path_points + ) + np.save( + pathlib.Path(__file__).parent / "obstacles.npy", + self.obstacles_points, + ) + self.plan_path() + + self.plot_background() + + def plan_path(self): + """Plan the path""" + + initial_path = self.path_points + # Create an elastic band object and optimize + self.elastic_band = ElasticBands(initial_path, self.obstacles) + for _ in range(MAX_ITER): + self.elastic_band.update_bubbles() + self.path_points = [b.pos for b in self.elastic_band.bubbles] + self.plot_background() + + +if __name__ == "__main__": + _ = ElasticBandsVisualizer() + if ENABLE_PLOT: + plt.show(block=True) diff --git a/PathPlanning/ElasticBands/obstacles.npy b/PathPlanning/ElasticBands/obstacles.npy new file mode 100644 index 0000000000000000000000000000000000000000..af4376afcf0e987bbb62c4a80c7afac3d221961d GIT binary patch literal 384 zcmbR27wQ`j$;eQ~P_3SlTAW;@Zl$1ZlWC!@qoAIaUsO_*m=~X4l#&V(cT3DEP6dh= zXCxM+0{I$-W;zN+nmP)#3giN=d=|8_M@a;}<~r z%~1IiD1RoD9|z^LL+NCwxEhq72<3}I`IS(%lCm`7X literal 0 HcmV?d00001 diff --git a/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst b/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst new file mode 100644 index 0000000000..139996f291 --- /dev/null +++ b/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst @@ -0,0 +1,73 @@ +Elastic Bands +------------- + +This is a path planning with Elastic Bands. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ElasticBands/animation.gif + + +Core Concept +~~~~~~~~~~~~ +- **Elastic Band**: A dynamically deformable collision-free path initialized by a global planner. +- **Objective**: + + * Shorten and smooth the path. + * Maximize obstacle clearance. + * Maintain global path connectivity. + +Bubble Representation +~~~~~~~~~~~~~~~~~~~ +- **Definition**: A local free-space region around configuration :math:`b`: + + .. math:: + B(b) = \{ q: \|q - b\| < \rho(b) \}, + + where :math:`\rho(b)` is the radius of the bubble. + + +Force-Based Deformation +~~~~~~~~~~~~~~~~~~~~~~~ +The elastic band deforms under artificial forces: + +Internal Contraction Force +++++++++++++++++++++++++++ +- **Purpose**: Reduces path slack and length. +- **Formula**: For node :math:`b_i`: + + .. math:: + f_c(b_i) = k_c \left( \frac{b_{i-1} - b_i}{\|b_{i-1} - b_i\|} + \frac{b_{i+1} - b_i}{\|b_{i+1} - b_i\|} \right) + + where :math:`k_c` is the contraction gain. + +External Repulsion Force ++++++++++++++++++++++++++ +- **Purpose**: Pushes the path away from obstacles. +- **Formula**: For node :math:`b_i`: + + .. math:: + f_r(b_i) = \begin{cases} + k_r (\rho_0 - \rho(b_i)) \nabla \rho(b_i) & \text{if } \rho(b_i) < \rho_0, \\ + 0 & \text{otherwise}. + \end{cases} + + where :math:`k_r` is the repulsion gain, :math:`\rho_0` is the maximum distance for applying repulsion force, and :math:`\nabla \rho(b_i)` is approximated via finite differences: + + .. math:: + \frac{\partial \rho}{\partial x} \approx \frac{\rho(b_i + h) - \rho(b_i - h)}{2h}. + +Dynamic Path Maintenance +~~~~~~~~~~~~~~~~~~~~~~~ +1. **Node Update**: + + .. math:: + b_i^{\text{new}} = b_i^{\text{old}} + \alpha (f_c + f_r), + + where :math:`\alpha` is a step-size parameter, which often proportional to :math:`\rho(b_i^{\text{old}})` + +2. **Overlap Enforcement**: +- Insert new nodes if adjacent nodes are too far apart +- Remove redundant nodes if adjacent nodes are too close + +Ref: + +- `Elastic Bands: Connecting Path Planning and Control `__ diff --git a/docs/modules/5_path_planning/path_planning_main.rst b/docs/modules/5_path_planning/path_planning_main.rst index 4960330b3e..65fbfdbc3d 100644 --- a/docs/modules/5_path_planning/path_planning_main.rst +++ b/docs/modules/5_path_planning/path_planning_main.rst @@ -31,3 +31,4 @@ Path planning is the ability of a robot to search feasible and efficient path to hybridastar/hybridastar frenet_frame_path/frenet_frame_path coverage_path/coverage_path + elastic_bands/elastic_bands \ No newline at end of file diff --git a/tests/test_elastic_bands.py b/tests/test_elastic_bands.py new file mode 100644 index 0000000000..ad4e13af1a --- /dev/null +++ b/tests/test_elastic_bands.py @@ -0,0 +1,23 @@ +import conftest +import numpy as np +from PathPlanning.ElasticBands.elastic_bands import ElasticBands + + +def test_1(): + path = np.load("PathPlanning/ElasticBands/path.npy") + obstacles_points = np.load("PathPlanning/ElasticBands/obstacles.npy") + obstacles = np.zeros((500, 500)) + for x, y in obstacles_points: + size = 30 # Side length of the square + half_size = size // 2 + x_start = max(0, x - half_size) + x_end = min(obstacles.shape[0], x + half_size) + y_start = max(0, y - half_size) + y_end = min(obstacles.shape[1], y + half_size) + obstacles[x_start:x_end, y_start:y_end] = 1 + elastic_bands = ElasticBands(path, obstacles) + elastic_bands.update_bubbles() + + +if __name__ == "__main__": + conftest.run_this_test(__file__) From cbe61f8ca62785a072652741d8b33832caee1942 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Feb 2025 10:45:49 +0900 Subject: [PATCH 859/940] build(deps): bump scipy from 1.15.1 to 1.15.2 in /requirements (#1163) Bumps [scipy](https://github.com/scipy/scipy) from 1.15.1 to 1.15.2. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.15.1...v1.15.2) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f5f674d7d2..ea4550edb8 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 2.2.2 -scipy == 1.15.1 +scipy == 1.15.2 matplotlib == 3.10.0 cvxpy == 1.5.3 pytest == 8.3.4 # For unit test From 395fca59cc1f9c44e9ea7f7c08ce41958e399481 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 18 Feb 2025 20:06:34 +0900 Subject: [PATCH 860/940] fix: update robotics documentation for clarity and correct terminology (#1165) --- docs/modules/12_appendix/external_sensors_main.rst | 2 ++ docs/modules/12_appendix/internal_sensors_main.rst | 2 ++ .../1_definition_of_robotics/definition_of_robotics_main.rst | 5 +++++ .../technologies_for_robotics_main.rst} | 4 +++- docs/modules/1_introduction/introduction_main.rst | 2 +- 5 files changed, 13 insertions(+), 2 deletions(-) rename docs/modules/1_introduction/{3_technology_for_robotics/technology_for_robotics_main.rst => 3_technologies_for_robotics/technologies_for_robotics_main.rst} (88%) diff --git a/docs/modules/12_appendix/external_sensors_main.rst b/docs/modules/12_appendix/external_sensors_main.rst index d36b852d42..3597418150 100644 --- a/docs/modules/12_appendix/external_sensors_main.rst +++ b/docs/modules/12_appendix/external_sensors_main.rst @@ -1,3 +1,5 @@ +.. _`External Sensors for Robots`: + External Sensors for Robots ============================ diff --git a/docs/modules/12_appendix/internal_sensors_main.rst b/docs/modules/12_appendix/internal_sensors_main.rst index 13b8de4203..18f209098e 100644 --- a/docs/modules/12_appendix/internal_sensors_main.rst +++ b/docs/modules/12_appendix/internal_sensors_main.rst @@ -1,3 +1,5 @@ +.. _`Internal Sensors for Robots`: + Internal Sensors for Robots ============================ diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst index f54d4d41fa..1e7a833b19 100644 --- a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst +++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst @@ -17,6 +17,10 @@ In the play, robots were artificial workers created to serve humans, but they ev Over time, “robot” came to refer to machines or automated systems that can perform tasks, often with some level of intelligence or autonomy. +Currently, 2 millions robots are working in the world, and the number is increasing every year. +In South Korea, where the adoption of robots is particularly rapid, +50 robots are operating per 1,000 people. + .. _`R.U.R.`: https://thereader.mitpress.mit.edu/origin-word-robot-rur/ .. _`Karel Čapek`: https://en.wikipedia.org/wiki/Karel_%C4%8Capek @@ -100,3 +104,4 @@ Robotics consists of several essential components: #. Software & Algorithms – Allow the robot to function and make intelligent decisions (e.g., ROS, Machine learning models, Localization, Mapping, Path planning, Control). This project, PythonRobotics, focuses on the software and algorithms part of robotics. +If you are interested in `Sensors` hardware, you can check :ref:`Internal Sensors for Robotics`_ or :ref:`External Sensors for Robotics`_. diff --git a/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst b/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst similarity index 88% rename from docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst rename to docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst index e460059e20..64c6945c32 100644 --- a/docs/modules/1_introduction/3_technology_for_robotics/technology_for_robotics_main.rst +++ b/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst @@ -1,8 +1,10 @@ -Technology for Robotics +Technologies for Robotics ------------------------- The field of robotics needs wide areas of technologies such as mechanical engineering, electrical engineering, computer science, and artificial intelligence (AI). +This project, `PythonRobotics`, only focus on computer science and artificial intelligence. + Autonomous Navigation diff --git a/docs/modules/1_introduction/introduction_main.rst b/docs/modules/1_introduction/introduction_main.rst index a7ce55f9bf..1871dfc3b1 100644 --- a/docs/modules/1_introduction/introduction_main.rst +++ b/docs/modules/1_introduction/introduction_main.rst @@ -14,5 +14,5 @@ covered in PythonRobotics. 1_definition_of_robotics/definition_of_robotics 2_python_for_robotics/python_for_robotics - 3_technology_for_robotics/technology_for_robotics + 3_technologies_for_robotics/technologies_for_robotics From d53711998aeb1d0b3aab7a62862ef5d358f2aff9 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 18 Feb 2025 21:49:28 +0900 Subject: [PATCH 861/940] fix: update robotics documentation for clarity and correct terminology (#1166) --- README.md | 4 ++++ .../0_getting_started/1_what_is_python_robotics_main.rst | 6 ++++++ .../definition_of_robotics_main.rst | 2 +- .../5_path_planning/elastic_bands/elastic_bands_main.rst | 7 ++++--- 4 files changed, 15 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 818d7b0d4e..9e605435ce 100644 --- a/README.md +++ b/README.md @@ -89,6 +89,10 @@ See this documentation - [Getting Started — PythonRobotics documentation](https://atsushisakai.github.io/PythonRobotics/getting_started.html#what-is-pythonrobotics) +or this Youtube video: + +- [PythonRobotics project audio overview](https://www.youtube.com/watch?v=uMeRnNoJAfU) + or this paper for more details: - [\[1808\.10703\] PythonRobotics: a Python code collection of robotics algorithms](https://arxiv.org/abs/1808.10703) ([BibTeX](https://github.com/AtsushiSakai/PythonRoboticsPaper/blob/master/python_robotics.bib)) diff --git a/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst b/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst index 8c932b7263..2a7bd574f0 100644 --- a/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst +++ b/docs/modules/0_getting_started/1_what_is_python_robotics_main.rst @@ -110,6 +110,12 @@ the following additional libraries are required. For instructions on installing the above libraries, please refer to this section ":ref:`How to run sample codes`". +Audio overview of this project +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +For an audio overview of this project, please refer to this `YouTube video`_. + +.. _`YouTube video`: https://www.youtube.com/watch?v=uMeRnNoJAfU + Arxiv paper ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst index 1e7a833b19..5d78bf858b 100644 --- a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst +++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst @@ -103,5 +103,5 @@ Robotics consists of several essential components: #. Power Supply – Provides energy to run the robot (e.g., Batteries, Solar power). #. Software & Algorithms – Allow the robot to function and make intelligent decisions (e.g., ROS, Machine learning models, Localization, Mapping, Path planning, Control). -This project, PythonRobotics, focuses on the software and algorithms part of robotics. +This project, `PythonRobotics`, focuses on the software and algorithms part of robotics. If you are interested in `Sensors` hardware, you can check :ref:`Internal Sensors for Robotics`_ or :ref:`External Sensors for Robotics`_. diff --git a/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst b/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst index 139996f291..8a3e517105 100644 --- a/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst +++ b/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst @@ -16,7 +16,7 @@ Core Concept * Maintain global path connectivity. Bubble Representation -~~~~~~~~~~~~~~~~~~~ +~~~~~~~~~~~~~~~~~~~~~~~~ - **Definition**: A local free-space region around configuration :math:`b`: .. math:: @@ -56,7 +56,7 @@ External Repulsion Force \frac{\partial \rho}{\partial x} \approx \frac{\rho(b_i + h) - \rho(b_i - h)}{2h}. Dynamic Path Maintenance -~~~~~~~~~~~~~~~~~~~~~~~ +~~~~~~~~~~~~~~~~~~~~~~~~~~ 1. **Node Update**: .. math:: @@ -68,6 +68,7 @@ Dynamic Path Maintenance - Insert new nodes if adjacent nodes are too far apart - Remove redundant nodes if adjacent nodes are too close -Ref: +References +~~~~~~~~~~~~~~~~~~~~~~~ - `Elastic Bands: Connecting Path Planning and Control `__ From 8064488a1d63a1579d8c9d786a376c8b583c02a8 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Feb 2025 21:49:40 +0900 Subject: [PATCH 862/940] build(deps): bump numpy from 2.2.2 to 2.2.3 in /requirements (#1164) Bumps [numpy](https://github.com/numpy/numpy) from 2.2.2 to 2.2.3. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v2.2.2...v2.2.3) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index ea4550edb8..8176364c29 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 2.2.2 +numpy == 2.2.3 scipy == 1.15.2 matplotlib == 3.10.0 cvxpy == 1.5.3 From 2b7080991e5289c9524a505244fcd2a4995da06e Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 19 Feb 2025 13:36:07 +0900 Subject: [PATCH 863/940] Add GitHub copilot pro sponser (#1167) * fix: correct terminology in documentation and update Sphinx options * fix: correct terminology in documentation and update Sphinx options * fix: correct terminology in documentation and update Sphinx options * fix: correct terminology in documentation and update Sphinx options * fix: correct terminology in documentation and update Sphinx options --- docs/Makefile | 3 ++- docs/modules/0_getting_started/3_how_to_contribute_main.rst | 2 ++ .../1_definition_of_robotics/definition_of_robotics_main.rst | 2 +- docs/modules/4_slam/graph_slam/graphSLAM_SE2_example.rst | 2 +- 4 files changed, 6 insertions(+), 3 deletions(-) diff --git a/docs/Makefile b/docs/Makefile index 9296811e02..ae495eb36d 100644 --- a/docs/Makefile +++ b/docs/Makefile @@ -2,7 +2,8 @@ # # You can set these variables from the command line. -SPHINXOPTS = +# SPHINXOPTS with -W means turn warnings into errors to fail the build when warnings are present. +SPHINXOPTS = -W SPHINXBUILD = sphinx-build SPHINXPROJ = PythonRobotics SOURCEDIR = . diff --git a/docs/modules/0_getting_started/3_how_to_contribute_main.rst b/docs/modules/0_getting_started/3_how_to_contribute_main.rst index 874564cbb8..1e61760649 100644 --- a/docs/modules/0_getting_started/3_how_to_contribute_main.rst +++ b/docs/modules/0_getting_started/3_how_to_contribute_main.rst @@ -187,6 +187,7 @@ If you would like to support us in some other way, please contact with creating Current Major Sponsors: +#. `GitHub`_ : They are providing a GitHub Copilot Pro license for this OSS development. #. `JetBrains`_ : They are providing a free license of their IDEs for this OSS development. #. `1Password`_ : They are providing a free license of their 1Password team license for this OSS project. @@ -202,6 +203,7 @@ Current Major Sponsors: .. _`doc README`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/docs/README.md .. _`test_codestyle.py`: https://github.com/AtsushiSakai/PythonRobotics/blob/master/tests/test_codestyle.py .. _`JetBrains`: https://www.jetbrains.com/ +.. _`GitHub`: https://www.github.com/ .. _`Sponsor @AtsushiSakai on GitHub Sponsors`: https://github.com/sponsors/AtsushiSakai .. _`Become a backer or sponsor on Patreon`: https://www.patreon.com/myenigma .. _`One-time donation via PayPal`: https://www.paypal.com/paypalme/myenigmapay/ diff --git a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst index 5d78bf858b..ca595301a6 100644 --- a/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst +++ b/docs/modules/1_introduction/1_definition_of_robotics/definition_of_robotics_main.rst @@ -104,4 +104,4 @@ Robotics consists of several essential components: #. Software & Algorithms – Allow the robot to function and make intelligent decisions (e.g., ROS, Machine learning models, Localization, Mapping, Path planning, Control). This project, `PythonRobotics`, focuses on the software and algorithms part of robotics. -If you are interested in `Sensors` hardware, you can check :ref:`Internal Sensors for Robotics`_ or :ref:`External Sensors for Robotics`_. +If you are interested in `Sensors` hardware, you can check :ref:`Internal Sensors for Robots` or :ref:`External Sensors for Robots`. diff --git a/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example.rst b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example.rst index 491320512b..15963aff79 100644 --- a/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example.rst +++ b/docs/modules/4_slam/graph_slam/graphSLAM_SE2_example.rst @@ -165,7 +165,7 @@ different data sources into a single optimization problem. 6 215.8405 -0.000000 -.. figure:: graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/GraphBasedSLAM/Graph_SLAM_optimization.gif .. code:: ipython3 From c7fb228d24856d6c7a0cb28c715176bfb8b17281 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 20 Feb 2025 12:11:04 +0900 Subject: [PATCH 864/940] fix: update section references to use consistent formatting (#1169) --- .../technologies_for_robotics_main.rst | 48 +++++++++++++++---- .../2_localization/localization_main.rst | 2 +- docs/modules/3_mapping/mapping_main.rst | 2 +- docs/modules/4_slam/slam_main.rst | 2 +- .../5_path_planning/path_planning_main.rst | 2 +- .../6_path_tracking/path_tracking_main.rst | 2 +- .../7_arm_navigation/arm_navigation_main.rst | 2 +- .../aerial_navigation_main.rst | 2 +- docs/modules/9_bipedal/bipedal_main.rst | 2 +- 9 files changed, 48 insertions(+), 16 deletions(-) diff --git a/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst b/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst index 64c6945c32..c77997a138 100644 --- a/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst +++ b/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst @@ -5,22 +5,54 @@ The field of robotics needs wide areas of technologies such as mechanical engine electrical engineering, computer science, and artificial intelligence (AI). This project, `PythonRobotics`, only focus on computer science and artificial intelligence. +The technologies for robotics are categorized as following 3 categories: +#. `Autonomous Navigation`_ +#. `Manipulation`_ +#. `Robot type specific technologies`_ + +.. _`Autonomous Navigation`: Autonomous Navigation ^^^^^^^^^^^^^^^^^^^^^^^^ - -In recent years, autonomous navigation technologies have received huge -attention in many fields. -Such fields include, autonomous driving[22], drone flight navigation, -and other transportation systems. - -An autonomous navigation system is a system that can move to a goal over long +Autonomous navigation is a capability that can move to a goal over long periods of time without any external control by an operator. -The system requires a wide range of technologies: + +To achieve autonomous navigation, the robot needs to have the following technologies: - It needs to know where it is (localization) - Where it is safe (mapping) +- Where is is safe and where the robot is in the map (Simultaneous Localization and Mapping (SLAM)) - Where and how to move (path planning) - How to control its motion (path following). The autonomous system would not work correctly if any of these technologies is missing. + +In recent years, autonomous navigation technologies have received huge +attention in many fields. +For example, self-driving cars, drones, and autonomous mobile robots in indoor and outdoor environments. + +In this project, we provide many algorithms, sample codes, +and documentations for autonomous navigation. + +#. :ref:`Localization` +#. :ref:`Mapping` +#. :ref:`SLAM` +#. :ref:`Path planning` +#. :ref:`Path tracking` + + + +.. _`Manipulation`: + +Manipulation +^^^^^^^^^^^^^^^^^^^^^^^^ + +#. :ref:`Arm Navigation` + +.. _`Robot type specific technologies`: + +Robot type specific technologies +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +#. :ref:`Aerial Navigation` +#. :ref:`Bipedal` diff --git a/docs/modules/2_localization/localization_main.rst b/docs/modules/2_localization/localization_main.rst index 22cbd094da..770a234b69 100644 --- a/docs/modules/2_localization/localization_main.rst +++ b/docs/modules/2_localization/localization_main.rst @@ -1,4 +1,4 @@ -.. _localization: +.. _`Localization`: Localization ============ diff --git a/docs/modules/3_mapping/mapping_main.rst b/docs/modules/3_mapping/mapping_main.rst index 825b08d3ec..34a3744893 100644 --- a/docs/modules/3_mapping/mapping_main.rst +++ b/docs/modules/3_mapping/mapping_main.rst @@ -1,4 +1,4 @@ -.. _mapping: +.. _`Mapping`: Mapping ======= diff --git a/docs/modules/4_slam/slam_main.rst b/docs/modules/4_slam/slam_main.rst index dec04f253a..98211986c2 100644 --- a/docs/modules/4_slam/slam_main.rst +++ b/docs/modules/4_slam/slam_main.rst @@ -1,4 +1,4 @@ -.. _slam: +.. _`SLAM`: SLAM ==== diff --git a/docs/modules/5_path_planning/path_planning_main.rst b/docs/modules/5_path_planning/path_planning_main.rst index 65fbfdbc3d..a0f9c30a3d 100644 --- a/docs/modules/5_path_planning/path_planning_main.rst +++ b/docs/modules/5_path_planning/path_planning_main.rst @@ -1,4 +1,4 @@ -.. _path_planning: +.. _`Path Planning`: Path Planning ============= diff --git a/docs/modules/6_path_tracking/path_tracking_main.rst b/docs/modules/6_path_tracking/path_tracking_main.rst index d7a895b562..130a2340c1 100644 --- a/docs/modules/6_path_tracking/path_tracking_main.rst +++ b/docs/modules/6_path_tracking/path_tracking_main.rst @@ -1,4 +1,4 @@ -.. _path_tracking: +.. _`Path Tracking`: Path Tracking ============= diff --git a/docs/modules/7_arm_navigation/arm_navigation_main.rst b/docs/modules/7_arm_navigation/arm_navigation_main.rst index bbbc872c58..7acd3ee7d3 100644 --- a/docs/modules/7_arm_navigation/arm_navigation_main.rst +++ b/docs/modules/7_arm_navigation/arm_navigation_main.rst @@ -1,4 +1,4 @@ -.. _arm_navigation: +.. _`Arm Navigation`: Arm Navigation ============== diff --git a/docs/modules/8_aerial_navigation/aerial_navigation_main.rst b/docs/modules/8_aerial_navigation/aerial_navigation_main.rst index b2ccb071af..7f76689770 100644 --- a/docs/modules/8_aerial_navigation/aerial_navigation_main.rst +++ b/docs/modules/8_aerial_navigation/aerial_navigation_main.rst @@ -1,4 +1,4 @@ -.. _aerial_navigation: +.. _`Aerial Navigation`: Aerial Navigation ================= diff --git a/docs/modules/9_bipedal/bipedal_main.rst b/docs/modules/9_bipedal/bipedal_main.rst index fc5b933055..dc387dc4e8 100644 --- a/docs/modules/9_bipedal/bipedal_main.rst +++ b/docs/modules/9_bipedal/bipedal_main.rst @@ -1,4 +1,4 @@ -.. _bipedal: +.. _`Bipedal`: Bipedal ================= From f343573a7bb9b99fd8fcfc72cef7336ccf859c28 Mon Sep 17 00:00:00 2001 From: Aglargil <34728006+Aglargil@users.noreply.github.com> Date: Thu, 20 Feb 2025 18:09:30 +0800 Subject: [PATCH 865/940] Update move_to_pose for cases where alpha > pi/2 or alpha < -pi/2 (#1168) * Update move_to_pose for cases where alpha > pi/2 or alpha < -pi/2 * Update move_to_pose * Add move_to_pose test * Update move_to_pose --- Control/move_to_pose/move_to_pose.py | 90 +++++++++++++++++++--------- tests/test_move_to_pose.py | 74 ++++++++++++++++++++++- 2 files changed, 134 insertions(+), 30 deletions(-) diff --git a/Control/move_to_pose/move_to_pose.py b/Control/move_to_pose/move_to_pose.py index 279ba0625b..34736a2e21 100644 --- a/Control/move_to_pose/move_to_pose.py +++ b/Control/move_to_pose/move_to_pose.py @@ -5,6 +5,7 @@ Author: Daniel Ingram (daniel-s-ingram) Atsushi Sakai (@Atsushi_twi) Seied Muhammad Yazdian (@Muhammad-Yazdian) + Wang Zheng (@Aglargil) P. I. Corke, "Robotics, Vision & Control", Springer 2017, ISBN 978-3-319-54413-7 @@ -12,8 +13,13 @@ import matplotlib.pyplot as plt import numpy as np -from random import random +import sys +import pathlib + +sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) from utils.angle import angle_mod +from random import random + class PathFinderController: """ @@ -70,14 +76,20 @@ def calc_control_command(self, x_diff, y_diff, theta, theta_goal): # [-pi, pi] to prevent unstable behavior e.g. difference going # from 0 rad to 2*pi rad with slight turn + # Ref: The velocity v always has a constant sign which depends on the initial value of α. rho = np.hypot(x_diff, y_diff) - alpha = angle_mod(np.arctan2(y_diff, x_diff) - theta) - beta = angle_mod(theta_goal - theta - alpha) v = self.Kp_rho * rho - w = self.Kp_alpha * alpha - self.Kp_beta * beta + alpha = angle_mod(np.arctan2(y_diff, x_diff) - theta) + beta = angle_mod(theta_goal - theta - alpha) if alpha > np.pi / 2 or alpha < -np.pi / 2: + # recalculate alpha to make alpha in the range of [-pi/2, pi/2] + alpha = angle_mod(np.arctan2(-y_diff, -x_diff) - theta) + beta = angle_mod(theta_goal - theta - alpha) + w = self.Kp_alpha * alpha - self.Kp_beta * beta v = -v + else: + w = self.Kp_alpha * alpha - self.Kp_beta * beta return rho, v, w @@ -85,6 +97,7 @@ def calc_control_command(self, x_diff, y_diff, theta, theta_goal): # simulation parameters controller = PathFinderController(9, 15, 3) dt = 0.01 +MAX_SIM_TIME = 5 # seconds, robot will stop moving when time exceeds this value # Robot specifications MAX_LINEAR_SPEED = 15 @@ -101,18 +114,19 @@ def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal): x_diff = x_goal - x y_diff = y_goal - y - x_traj, y_traj = [], [] + x_traj, y_traj, v_traj, w_traj = [x], [y], [0], [0] rho = np.hypot(x_diff, y_diff) - while rho > 0.001: + t = 0 + while rho > 0.001 and t < MAX_SIM_TIME: + t += dt x_traj.append(x) y_traj.append(y) x_diff = x_goal - x y_diff = y_goal - y - rho, v, w = controller.calc_control_command( - x_diff, y_diff, theta, theta_goal) + rho, v, w = controller.calc_control_command(x_diff, y_diff, theta, theta_goal) if abs(v) > MAX_LINEAR_SPEED: v = np.sign(v) * MAX_LINEAR_SPEED @@ -120,18 +134,35 @@ def move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal): if abs(w) > MAX_ANGULAR_SPEED: w = np.sign(w) * MAX_ANGULAR_SPEED + v_traj.append(v) + w_traj.append(w) + theta = theta + w * dt x = x + v * np.cos(theta) * dt y = y + v * np.sin(theta) * dt if show_animation: # pragma: no cover plt.cla() - plt.arrow(x_start, y_start, np.cos(theta_start), - np.sin(theta_start), color='r', width=0.1) - plt.arrow(x_goal, y_goal, np.cos(theta_goal), - np.sin(theta_goal), color='g', width=0.1) + plt.arrow( + x_start, + y_start, + np.cos(theta_start), + np.sin(theta_start), + color="r", + width=0.1, + ) + plt.arrow( + x_goal, + y_goal, + np.cos(theta_goal), + np.sin(theta_goal), + color="g", + width=0.1, + ) plot_vehicle(x, y, theta, x_traj, y_traj) + return x_traj, y_traj, v_traj, w_traj + def plot_vehicle(x, y, theta, x_traj, y_traj): # pragma: no cover # Corners of triangular vehicle when pointing to the right (0 radians) @@ -144,16 +175,16 @@ def plot_vehicle(x, y, theta, x_traj, y_traj): # pragma: no cover p2 = np.matmul(T, p2_i) p3 = np.matmul(T, p3_i) - plt.plot([p1[0], p2[0]], [p1[1], p2[1]], 'k-') - plt.plot([p2[0], p3[0]], [p2[1], p3[1]], 'k-') - plt.plot([p3[0], p1[0]], [p3[1], p1[1]], 'k-') + plt.plot([p1[0], p2[0]], [p1[1], p2[1]], "k-") + plt.plot([p2[0], p3[0]], [p2[1], p3[1]], "k-") + plt.plot([p3[0], p1[0]], [p3[1], p1[1]], "k-") - plt.plot(x_traj, y_traj, 'b--') + plt.plot(x_traj, y_traj, "b--") # for stopping simulation with the esc key. plt.gcf().canvas.mpl_connect( - 'key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + "key_release_event", lambda event: [exit(0) if event.key == "escape" else None] + ) plt.xlim(0, 20) plt.ylim(0, 20) @@ -162,15 +193,16 @@ def plot_vehicle(x, y, theta, x_traj, y_traj): # pragma: no cover def transformation_matrix(x, y, theta): - return np.array([ - [np.cos(theta), -np.sin(theta), x], - [np.sin(theta), np.cos(theta), y], - [0, 0, 1] - ]) + return np.array( + [ + [np.cos(theta), -np.sin(theta), x], + [np.sin(theta), np.cos(theta), y], + [0, 0, 1], + ] + ) def main(): - for i in range(5): x_start = 20.0 * random() y_start = 20.0 * random() @@ -178,10 +210,14 @@ def main(): x_goal = 20 * random() y_goal = 20 * random() theta_goal = 2 * np.pi * random() - np.pi - print(f"Initial x: {round(x_start, 2)} m\nInitial y: {round(y_start, 2)} m\nInitial theta: {round(theta_start, 2)} rad\n") - print(f"Goal x: {round(x_goal, 2)} m\nGoal y: {round(y_goal, 2)} m\nGoal theta: {round(theta_goal, 2)} rad\n") + print( + f"Initial x: {round(x_start, 2)} m\nInitial y: {round(y_start, 2)} m\nInitial theta: {round(theta_start, 2)} rad\n" + ) + print( + f"Goal x: {round(x_goal, 2)} m\nGoal y: {round(y_goal, 2)} m\nGoal theta: {round(theta_goal, 2)} rad\n" + ) move_to_pose(x_start, y_start, theta_start, x_goal, y_goal, theta_goal) -if __name__ == '__main__': +if __name__ == "__main__": main() diff --git a/tests/test_move_to_pose.py b/tests/test_move_to_pose.py index 8bc11a8d24..94c3ec1102 100644 --- a/tests/test_move_to_pose.py +++ b/tests/test_move_to_pose.py @@ -1,13 +1,81 @@ +import itertools +import numpy as np import conftest # Add root path to sys.path from Control.move_to_pose import move_to_pose as m -def test_1(): +def test_random(): m.show_animation = False m.main() -def test_2(): +def test_stability(): + """ + This unit test tests the move_to_pose.py program for stability + """ + m.show_animation = False + x_start = 5 + y_start = 5 + theta_start = 0 + x_goal = 1 + y_goal = 4 + theta_goal = 0 + _, _, v_traj, w_traj = m.move_to_pose( + x_start, y_start, theta_start, x_goal, y_goal, theta_goal + ) + + def v_is_change(current, previous): + return abs(current - previous) > m.MAX_LINEAR_SPEED + + def w_is_change(current, previous): + return abs(current - previous) > m.MAX_ANGULAR_SPEED + + # Check if the speed is changing too much + window_size = 10 + count_threshold = 4 + v_change = [v_is_change(v_traj[i], v_traj[i - 1]) for i in range(1, len(v_traj))] + w_change = [w_is_change(w_traj[i], w_traj[i - 1]) for i in range(1, len(w_traj))] + for i in range(len(v_change) - window_size + 1): + v_window = v_change[i : i + window_size] + w_window = w_change[i : i + window_size] + + v_unstable = sum(v_window) > count_threshold + w_unstable = sum(w_window) > count_threshold + + assert not v_unstable, ( + f"v_unstable in window [{i}, {i + window_size}], unstable count: {sum(v_window)}" + ) + assert not w_unstable, ( + f"w_unstable in window [{i}, {i + window_size}], unstable count: {sum(w_window)}" + ) + + +def test_reach_goal(): + """ + This unit test tests the move_to_pose.py program for reaching the goal + """ + m.show_animation = False + x_start = 5 + y_start = 5 + theta_start_list = [0, np.pi / 2, np.pi, 3 * np.pi / 2] + x_goal_list = [0, 5, 10] + y_goal_list = [0, 5, 10] + theta_goal = 0 + for theta_start, x_goal, y_goal in itertools.product( + theta_start_list, x_goal_list, y_goal_list + ): + x_traj, y_traj, _, _ = m.move_to_pose( + x_start, y_start, theta_start, x_goal, y_goal, theta_goal + ) + x_diff = x_goal - x_traj[-1] + y_diff = y_goal - y_traj[-1] + rho = np.hypot(x_diff, y_diff) + assert rho < 0.001, ( + f"start:[{x_start}, {y_start}, {theta_start}], goal:[{x_goal}, {y_goal}, {theta_goal}], rho: {rho} is too large" + ) + + +def test_max_speed(): """ This unit test tests the move_to_pose.py program for a MAX_LINEAR_SPEED and MAX_ANGULAR_SPEED @@ -18,5 +86,5 @@ def test_2(): m.main() -if __name__ == '__main__': +if __name__ == "__main__": conftest.run_this_test(__file__) From 64779298ffa77c918c63f9206b694f0d8d439c71 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 21 Feb 2025 21:40:21 +0900 Subject: [PATCH 866/940] =?UTF-8?q?refactor:=20rename=20files=20and=20upda?= =?UTF-8?q?te=20references=20for=20inverted=20pendulum=20an=E2=80=A6=20(#1?= =?UTF-8?q?171)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * refactor: rename files and update references for inverted pendulum and path tracking modules * refactor: rename inverted pendulum control files and update type check references * refactor: update import statements to use consistent casing for InvertedPendulum module --- Control/move_to_pose/__init__.py | 0 .../inverted_pendulum_lqr_control.py | 0 .../inverted_pendulum_mpc_control.py | 0 {Control => PathTracking/move_to_pose}/__init__.py | 0 .../move_to_pose/move_to_pose.py | 0 .../move_to_pose/move_to_pose_robot.py | 0 docs/index_main.rst | 2 +- docs/modules/10_control/control_main.rst | 12 ------------ .../inverted-pendulum.png | Bin .../inverted_pendulum_main.rst} | 6 ++++-- docs/modules/11_utils/utils_main.rst | 2 +- docs/modules/12_appendix/appendix_main.rst | 2 +- .../technologies_for_robotics_main.rst | 10 ++++++++++ .../move_to_a_pose_control_main.rst | 0 docs/modules/6_path_tracking/path_tracking_main.rst | 1 + tests/test_inverted_pendulum_lqr_control.py | 2 +- tests/test_inverted_pendulum_mpc_control.py | 2 +- tests/test_move_to_pose.py | 2 +- tests/test_move_to_pose_robot.py | 2 +- tests/test_mypy_type_check.py | 2 +- 20 files changed, 23 insertions(+), 22 deletions(-) delete mode 100644 Control/move_to_pose/__init__.py rename {Control/inverted_pendulum => InvertedPendulum}/inverted_pendulum_lqr_control.py (100%) rename {Control/inverted_pendulum => InvertedPendulum}/inverted_pendulum_mpc_control.py (100%) rename {Control => PathTracking/move_to_pose}/__init__.py (100%) rename {Control => PathTracking}/move_to_pose/move_to_pose.py (100%) rename {Control => PathTracking}/move_to_pose/move_to_pose_robot.py (100%) delete mode 100644 docs/modules/10_control/control_main.rst rename docs/modules/{10_control/inverted_pendulum_control => 10_inverted_pendulum}/inverted-pendulum.png (100%) rename docs/modules/{10_control/inverted_pendulum_control/inverted_pendulum_control_main.rst => 10_inverted_pendulum/inverted_pendulum_main.rst} (97%) rename docs/modules/{10_control => 6_path_tracking}/move_to_a_pose_control/move_to_a_pose_control_main.rst (100%) diff --git a/Control/move_to_pose/__init__.py b/Control/move_to_pose/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/Control/inverted_pendulum/inverted_pendulum_lqr_control.py b/InvertedPendulum/inverted_pendulum_lqr_control.py similarity index 100% rename from Control/inverted_pendulum/inverted_pendulum_lqr_control.py rename to InvertedPendulum/inverted_pendulum_lqr_control.py diff --git a/Control/inverted_pendulum/inverted_pendulum_mpc_control.py b/InvertedPendulum/inverted_pendulum_mpc_control.py similarity index 100% rename from Control/inverted_pendulum/inverted_pendulum_mpc_control.py rename to InvertedPendulum/inverted_pendulum_mpc_control.py diff --git a/Control/__init__.py b/PathTracking/move_to_pose/__init__.py similarity index 100% rename from Control/__init__.py rename to PathTracking/move_to_pose/__init__.py diff --git a/Control/move_to_pose/move_to_pose.py b/PathTracking/move_to_pose/move_to_pose.py similarity index 100% rename from Control/move_to_pose/move_to_pose.py rename to PathTracking/move_to_pose/move_to_pose.py diff --git a/Control/move_to_pose/move_to_pose_robot.py b/PathTracking/move_to_pose/move_to_pose_robot.py similarity index 100% rename from Control/move_to_pose/move_to_pose_robot.py rename to PathTracking/move_to_pose/move_to_pose_robot.py diff --git a/docs/index_main.rst b/docs/index_main.rst index c1e8d22d32..75805d1184 100644 --- a/docs/index_main.rst +++ b/docs/index_main.rst @@ -43,7 +43,7 @@ this graph shows GitHub star history of this project: modules/7_arm_navigation/arm_navigation modules/8_aerial_navigation/aerial_navigation modules/9_bipedal/bipedal - modules/10_control/control + modules/10_inverted_pendulum/inverted_pendulum modules/11_utils/utils modules/12_appendix/appendix diff --git a/docs/modules/10_control/control_main.rst b/docs/modules/10_control/control_main.rst deleted file mode 100644 index cee2aa9e8e..0000000000 --- a/docs/modules/10_control/control_main.rst +++ /dev/null @@ -1,12 +0,0 @@ -.. _control: - -Control -================= - -.. toctree:: - :maxdepth: 2 - :caption: Contents - - inverted_pendulum_control/inverted_pendulum_control - move_to_a_pose_control/move_to_a_pose_control - diff --git a/docs/modules/10_control/inverted_pendulum_control/inverted-pendulum.png b/docs/modules/10_inverted_pendulum/inverted-pendulum.png similarity index 100% rename from docs/modules/10_control/inverted_pendulum_control/inverted-pendulum.png rename to docs/modules/10_inverted_pendulum/inverted-pendulum.png diff --git a/docs/modules/10_control/inverted_pendulum_control/inverted_pendulum_control_main.rst b/docs/modules/10_inverted_pendulum/inverted_pendulum_main.rst similarity index 97% rename from docs/modules/10_control/inverted_pendulum_control/inverted_pendulum_control_main.rst rename to docs/modules/10_inverted_pendulum/inverted_pendulum_main.rst index e41729fd61..048cbea9ac 100644 --- a/docs/modules/10_control/inverted_pendulum_control/inverted_pendulum_control_main.rst +++ b/docs/modules/10_inverted_pendulum/inverted_pendulum_main.rst @@ -1,5 +1,7 @@ -Inverted Pendulum Control ------------------------------ +.. _`Inverted Pendulum`: + +Inverted Pendulum +------------------ An inverted pendulum on a cart consists of a mass :math:`m` at the top of a pole of length :math:`l` pivoted on a horizontally moving base as shown in the adjacent. diff --git a/docs/modules/11_utils/utils_main.rst b/docs/modules/11_utils/utils_main.rst index ff79a26205..95c982b077 100644 --- a/docs/modules/11_utils/utils_main.rst +++ b/docs/modules/11_utils/utils_main.rst @@ -1,4 +1,4 @@ -.. _utils: +.. _`utils`: Utilities ========== diff --git a/docs/modules/12_appendix/appendix_main.rst b/docs/modules/12_appendix/appendix_main.rst index a55389e1e6..d0b9eeea3a 100644 --- a/docs/modules/12_appendix/appendix_main.rst +++ b/docs/modules/12_appendix/appendix_main.rst @@ -1,4 +1,4 @@ -.. _appendix: +.. _`Appendix`: Appendix ============== diff --git a/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst b/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst index c77997a138..0ed51e961b 100644 --- a/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst +++ b/docs/modules/1_introduction/3_technologies_for_robotics/technologies_for_robotics_main.rst @@ -56,3 +56,13 @@ Robot type specific technologies #. :ref:`Aerial Navigation` #. :ref:`Bipedal` +#. :ref:`Inverted Pendulum` + + +Additional Information +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +#. :ref:`utils` +#. :ref:`Appendix` + + diff --git a/docs/modules/10_control/move_to_a_pose_control/move_to_a_pose_control_main.rst b/docs/modules/6_path_tracking/move_to_a_pose_control/move_to_a_pose_control_main.rst similarity index 100% rename from docs/modules/10_control/move_to_a_pose_control/move_to_a_pose_control_main.rst rename to docs/modules/6_path_tracking/move_to_a_pose_control/move_to_a_pose_control_main.rst diff --git a/docs/modules/6_path_tracking/path_tracking_main.rst b/docs/modules/6_path_tracking/path_tracking_main.rst index 130a2340c1..d98e324583 100644 --- a/docs/modules/6_path_tracking/path_tracking_main.rst +++ b/docs/modules/6_path_tracking/path_tracking_main.rst @@ -16,3 +16,4 @@ Path tracking is the ability of a robot to follow the reference path generated b lqr_speed_and_steering_control/lqr_speed_and_steering_control model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control cgmres_nmpc/cgmres_nmpc + move_to_a_pose_control/move_to_a_pose_control diff --git a/tests/test_inverted_pendulum_lqr_control.py b/tests/test_inverted_pendulum_lqr_control.py index cbbabb93b1..62afda71c3 100644 --- a/tests/test_inverted_pendulum_lqr_control.py +++ b/tests/test_inverted_pendulum_lqr_control.py @@ -1,5 +1,5 @@ import conftest -from Control.inverted_pendulum import inverted_pendulum_lqr_control as m +from InvertedPendulum import inverted_pendulum_lqr_control as m def test_1(): diff --git a/tests/test_inverted_pendulum_mpc_control.py b/tests/test_inverted_pendulum_mpc_control.py index 800aefd7d5..94859c2e0a 100644 --- a/tests/test_inverted_pendulum_mpc_control.py +++ b/tests/test_inverted_pendulum_mpc_control.py @@ -1,6 +1,6 @@ import conftest -from Control.inverted_pendulum import inverted_pendulum_mpc_control as m +from InvertedPendulum import inverted_pendulum_mpc_control as m def test1(): diff --git a/tests/test_move_to_pose.py b/tests/test_move_to_pose.py index 94c3ec1102..e06d801555 100644 --- a/tests/test_move_to_pose.py +++ b/tests/test_move_to_pose.py @@ -1,7 +1,7 @@ import itertools import numpy as np import conftest # Add root path to sys.path -from Control.move_to_pose import move_to_pose as m +from PathTracking.move_to_pose import move_to_pose as m def test_random(): diff --git a/tests/test_move_to_pose_robot.py b/tests/test_move_to_pose_robot.py index a93b44d198..7a82f98556 100644 --- a/tests/test_move_to_pose_robot.py +++ b/tests/test_move_to_pose_robot.py @@ -1,5 +1,5 @@ import conftest # Add root path to sys.path -from Control.move_to_pose import move_to_pose as m +from PathTracking.move_to_pose import move_to_pose as m def test_1(): diff --git a/tests/test_mypy_type_check.py b/tests/test_mypy_type_check.py index 07afb40afd..6b933c1011 100644 --- a/tests/test_mypy_type_check.py +++ b/tests/test_mypy_type_check.py @@ -7,12 +7,12 @@ "AerialNavigation", "ArmNavigation", "Bipedal", - "Control", "Localization", "Mapping", "PathPlanning", "PathTracking", "SLAM", + "InvertedPendulum" ] From 6e13e8292aad80661093603ed262c6f0bdcb4137 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 25 Feb 2025 08:07:42 +0900 Subject: [PATCH 867/940] build(deps): bump ruff from 0.9.6 to 0.9.7 in /requirements (#1173) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.9.6 to 0.9.7. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.9.6...0.9.7) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 8176364c29..b439ea4266 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.4 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.15.0 # For unit test -ruff == 0.9.6 # For unit test +ruff == 0.9.7 # For unit test From 0c8ff11645e6804db18bec6bd918e03ed03454f7 Mon Sep 17 00:00:00 2001 From: Jonathan Schwartz Date: Tue, 25 Feb 2025 06:53:36 -0500 Subject: [PATCH 868/940] Space-Time AStar (#1170) * wip - sketch out obstacles * move to correct path * better animation * clean up * use np to sample points * implemented time-based A* * cleaning up Grid + adding new obstacle arrangement * added unit test * formatting p1 * format STA* file * remove newlines by docstrings * linter * working on typehints * fix linter errors * lint some more * appease AppVeyor * dataclasses are :fire: * back to @total_ordering * trailing whitespace * add docs page on SpaceTimeA* * docs lint * remove trailing newlines in doc * address comments * Update docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst --------- Co-authored-by: Atsushi Sakai --- .../GridWithDynamicObstacles.py | 273 ++++++++++++++++++ .../TimeBasedPathPlanning/SpaceTimeAStar.py | 220 ++++++++++++++ .../TimeBasedPathPlanning/__init__.py | 0 .../5_path_planning/path_planning_main.rst | 1 + .../time_based_grid_search_main.rst | 22 ++ tests/test_space_time_astar.py | 33 +++ 6 files changed, 549 insertions(+) create mode 100644 PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py create mode 100644 PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py create mode 100644 PathPlanning/TimeBasedPathPlanning/__init__.py create mode 100644 docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst create mode 100644 tests/test_space_time_astar.py diff --git a/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py b/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py new file mode 100644 index 0000000000..7b0190d023 --- /dev/null +++ b/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py @@ -0,0 +1,273 @@ +""" +This file implements a grid with a 3d reservation matrix with dimensions for x, y, and time. There +is also infrastructure to generate dynamic obstacles that move around the grid. The obstacles' paths +are stored in the reservation matrix on creation. +""" +import numpy as np +import matplotlib.pyplot as plt +from enum import Enum +from dataclasses import dataclass + +@dataclass(order=True) +class Position: + x: int + y: int + + def as_ndarray(self) -> np.ndarray: + return np.array([self.x, self.y]) + + def __add__(self, other): + if isinstance(other, Position): + return Position(self.x + other.x, self.y + other.y) + raise NotImplementedError( + f"Addition not supported for Position and {type(other)}" + ) + + def __sub__(self, other): + if isinstance(other, Position): + return Position(self.x - other.x, self.y - other.y) + raise NotImplementedError( + f"Subtraction not supported for Position and {type(other)}" + ) + + +class ObstacleArrangement(Enum): + # Random obstacle positions and movements + RANDOM = 0 + # Obstacles start in a line in y at center of grid and move side-to-side in x + ARRANGEMENT1 = 1 + + +class Grid: + # Set in constructor + grid_size: np.ndarray + reservation_matrix: np.ndarray + obstacle_paths: list[list[Position]] = [] + # Obstacles will never occupy these points. Useful to avoid impossible scenarios + obstacle_avoid_points: list[Position] = [] + + # Number of time steps in the simulation + time_limit: int + + # Logging control + verbose = False + + def __init__( + self, + grid_size: np.ndarray, + num_obstacles: int = 40, + obstacle_avoid_points: list[Position] = [], + obstacle_arrangement: ObstacleArrangement = ObstacleArrangement.RANDOM, + time_limit: int = 100, + ): + self.obstacle_avoid_points = obstacle_avoid_points + self.time_limit = time_limit + self.grid_size = grid_size + self.reservation_matrix = np.zeros((grid_size[0], grid_size[1], self.time_limit)) + + if num_obstacles > self.grid_size[0] * self.grid_size[1]: + raise Exception("Number of obstacles is greater than grid size!") + + if obstacle_arrangement == ObstacleArrangement.RANDOM: + self.obstacle_paths = self.generate_dynamic_obstacles(num_obstacles) + elif obstacle_arrangement == ObstacleArrangement.ARRANGEMENT1: + self.obstacle_paths = self.obstacle_arrangement_1(num_obstacles) + + for i, path in enumerate(self.obstacle_paths): + obs_idx = i + 1 # avoid using 0 - that indicates free space in the grid + for t, position in enumerate(path): + # Reserve old & new position at this time step + if t > 0: + self.reservation_matrix[path[t - 1].x, path[t - 1].y, t] = obs_idx + self.reservation_matrix[position.x, position.y, t] = obs_idx + + """ + Generate dynamic obstacles that move around the grid. Initial positions and movements are random + """ + def generate_dynamic_obstacles(self, obs_count: int) -> list[list[Position]]: + obstacle_paths = [] + for _ in (0, obs_count): + # Sample until a free starting space is found + initial_position = self.sample_random_position() + while not self.valid_obstacle_position(initial_position, 0): + initial_position = self.sample_random_position() + + positions = [initial_position] + if self.verbose: + print("Obstacle initial position: ", initial_position) + + # Encourage obstacles to mostly stay in place - too much movement leads to chaotic planning scenarios + # that are not fun to watch + weights = [0.05, 0.05, 0.05, 0.05, 0.8] + diffs = [ + Position(0, 1), + Position(0, -1), + Position(1, 0), + Position(-1, 0), + Position(0, 0), + ] + + for t in range(1, self.time_limit - 1): + sampled_indices = np.random.choice( + len(diffs), size=5, replace=False, p=weights + ) + rand_diffs = [diffs[i] for i in sampled_indices] + + valid_position = None + for diff in rand_diffs: + new_position = positions[-1] + diff + + if not self.valid_obstacle_position(new_position, t): + continue + + valid_position = new_position + break + + # Impossible situation for obstacle - stay in place + # -> this can happen if the oaths of other obstacles this one + if valid_position is None: + valid_position = positions[-1] + + positions.append(valid_position) + + obstacle_paths.append(positions) + + return obstacle_paths + + """ + Generate a line of obstacles in y at the center of the grid that move side-to-side in x + Bottom half start moving right, top half start moving left. If `obs_count` is less than the length of + the grid, only the first `obs_count` obstacles will be generated. + """ + def obstacle_arrangement_1(self, obs_count: int) -> list[list[Position]]: + obstacle_paths = [] + half_grid_x = self.grid_size[0] // 2 + half_grid_y = self.grid_size[1] // 2 + + for y_idx in range(0, min(obs_count, self.grid_size[1])): + moving_right = y_idx < half_grid_y + position = Position(half_grid_x, y_idx) + path = [position] + + for t in range(1, self.time_limit - 1): + # sit in place every other time step + if t % 2 == 0: + path.append(position) + continue + + # first check if we should switch direction (at edge of grid) + if (moving_right and position.x == self.grid_size[0] - 1) or ( + not moving_right and position.x == 0 + ): + moving_right = not moving_right + # step in direction + position = Position( + position.x + (1 if moving_right else -1), position.y + ) + path.append(position) + + obstacle_paths.append(path) + + return obstacle_paths + + """ + Check if the given position is valid at time t + + input: + position (Position): (x, y) position + t (int): time step + + output: + bool: True if position/time combination is valid, False otherwise + """ + def valid_position(self, position: Position, t: int) -> bool: + # Check if new position is in grid + if not self.inside_grid_bounds(position): + return False + + # Check if new position is not occupied at time t + return self.reservation_matrix[position.x, position.y, t] == 0 + + """ + Returns True if the given position is valid at time t and is not in the set of obstacle_avoid_points + """ + def valid_obstacle_position(self, position: Position, t: int) -> bool: + return ( + self.valid_position(position, t) + and position not in self.obstacle_avoid_points + ) + + """ + Returns True if the given position is within the grid's boundaries + """ + def inside_grid_bounds(self, position: Position) -> bool: + return ( + position.x >= 0 + and position.x < self.grid_size[0] + and position.y >= 0 + and position.y < self.grid_size[1] + ) + + """ + Sample a random position that is within the grid's boundaries + + output: + Position: (x, y) position + """ + def sample_random_position(self) -> Position: + return Position( + np.random.randint(0, self.grid_size[0]), + np.random.randint(0, self.grid_size[1]), + ) + + """ + Returns a tuple of (x_positions, y_positions) of the obstacles at time t + """ + def get_obstacle_positions_at_time(self, t: int) -> tuple[list[int], list[int]]: + x_positions = [] + y_positions = [] + for obs_path in self.obstacle_paths: + x_positions.append(obs_path[t].x) + y_positions.append(obs_path[t].y) + return (x_positions, y_positions) + + +show_animation = True + + +def main(): + grid = Grid( + np.array([11, 11]), + num_obstacles=10, + obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1, + ) + + if not show_animation: + return + + fig = plt.figure(figsize=(8, 7)) + ax = fig.add_subplot( + autoscale_on=False, + xlim=(0, grid.grid_size[0] - 1), + ylim=(0, grid.grid_size[1] - 1), + ) + ax.set_aspect("equal") + ax.grid() + ax.set_xticks(np.arange(0, 11, 1)) + ax.set_yticks(np.arange(0, 11, 1)) + (obs_points,) = ax.plot([], [], "ro", ms=15) + + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect( + "key_release_event", lambda event: [exit(0) if event.key == "escape" else None] + ) + + for i in range(0, grid.time_limit - 1): + obs_positions = grid.get_obstacle_positions_at_time(i) + obs_points.set_data(obs_positions[0], obs_positions[1]) + plt.pause(0.2) + plt.show() + + +if __name__ == "__main__": + main() diff --git a/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py b/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py new file mode 100644 index 0000000000..3b3613d695 --- /dev/null +++ b/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py @@ -0,0 +1,220 @@ +""" +Space-time A* Algorithm + This script demonstrates the Space-time A* algorithm for path planning in a grid world with moving obstacles. + This algorithm is different from normal 2D A* in one key way - the cost (often notated as g(n)) is + the number of time steps it took to get to a given node, instead of the number of cells it has + traversed. This ensures the path is time-optimal, while respescting any dynamic obstacles in the environment. + + Reference: https://www.davidsilver.uk/wp-content/uploads/2020/03/coop-path-AIWisdom.pdf +""" + +import numpy as np +import matplotlib.pyplot as plt +from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import ( + Grid, + ObstacleArrangement, + Position, +) +import heapq +from collections.abc import Generator +import random +from dataclasses import dataclass +from functools import total_ordering + + +# Seed randomness for reproducibility +RANDOM_SEED = 50 +random.seed(RANDOM_SEED) +np.random.seed(RANDOM_SEED) + +@dataclass() +# Note: Total_ordering is used instead of adding `order=True` to the @dataclass decorator because +# this class needs to override the __lt__ and __eq__ methods to ignore parent_index. Parent +# index is just used to track the path found by the algorithm, and has no effect on the quality +# of a node. +@total_ordering +class Node: + position: Position + time: int + heuristic: int + parent_index: int + + """ + This is what is used to drive node expansion. The node with the lowest value is expanded next. + This comparison prioritizes the node with the lowest cost-to-come (self.time) + cost-to-go (self.heuristic) + """ + def __lt__(self, other: object): + if not isinstance(other, Node): + return NotImplementedError(f"Cannot compare Node with object of type: {type(other)}") + return (self.time + self.heuristic) < (other.time + other.heuristic) + + def __eq__(self, other: object): + if not isinstance(other, Node): + return NotImplementedError(f"Cannot compare Node with object of type: {type(other)}") + return self.position == other.position and self.time == other.time + + +class NodePath: + path: list[Node] + positions_at_time: dict[int, Position] = {} + + def __init__(self, path: list[Node]): + self.path = path + for node in path: + self.positions_at_time[node.time] = node.position + + """ + Get the position of the path at a given time + """ + def get_position(self, time: int) -> Position | None: + return self.positions_at_time.get(time) + + """ + Time stamp of the last node in the path + """ + def goal_reached_time(self) -> int: + return self.path[-1].time + + def __repr__(self): + repr_string = "" + for i, node in enumerate(self.path): + repr_string += f"{i}: {node}\n" + return repr_string + + +class SpaceTimeAStar: + grid: Grid + start: Position + goal: Position + + def __init__(self, grid: Grid, start: Position, goal: Position): + self.grid = grid + self.start = start + self.goal = goal + + def plan(self, verbose: bool = False) -> NodePath: + open_set: list[Node] = [] + heapq.heappush( + open_set, Node(self.start, 0, self.calculate_heuristic(self.start), -1) + ) + + expanded_set: list[Node] = [] + while open_set: + expanded_node: Node = heapq.heappop(open_set) + if verbose: + print("Expanded node:", expanded_node) + + if expanded_node.time + 1 >= self.grid.time_limit: + if verbose: + print(f"\tSkipping node that is past time limit: {expanded_node}") + continue + + if expanded_node.position == self.goal: + print(f"Found path to goal after {len(expanded_set)} expansions") + path = [] + path_walker: Node = expanded_node + while True: + path.append(path_walker) + if path_walker.parent_index == -1: + break + path_walker = expanded_set[path_walker.parent_index] + + # reverse path so it goes start -> goal + path.reverse() + return NodePath(path) + + expanded_idx = len(expanded_set) + expanded_set.append(expanded_node) + + for child in self.generate_successors(expanded_node, expanded_idx, verbose): + heapq.heappush(open_set, child) + + raise Exception("No path found") + + """ + Generate possible successors of the provided `parent_node` + """ + def generate_successors( + self, parent_node: Node, parent_node_idx: int, verbose: bool + ) -> Generator[Node, None, None]: + diffs = [ + Position(0, 0), + Position(1, 0), + Position(-1, 0), + Position(0, 1), + Position(0, -1), + ] + for diff in diffs: + new_pos = parent_node.position + diff + if self.grid.valid_position(new_pos, parent_node.time + 1): + new_node = Node( + new_pos, + parent_node.time + 1, + self.calculate_heuristic(new_pos), + parent_node_idx, + ) + if verbose: + print("\tNew successor node: ", new_node) + yield new_node + + def calculate_heuristic(self, position) -> int: + diff = self.goal - position + return abs(diff.x) + abs(diff.y) + + +show_animation = True +verbose = False + +def main(): + start = Position(1, 11) + goal = Position(19, 19) + grid_side_length = 21 + grid = Grid( + np.array([grid_side_length, grid_side_length]), + num_obstacles=40, + obstacle_avoid_points=[start, goal], + obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1, + ) + + planner = SpaceTimeAStar(grid, start, goal) + path = planner.plan(verbose) + + if verbose: + print(f"Path: {path}") + + if not show_animation: + return + + fig = plt.figure(figsize=(10, 7)) + ax = fig.add_subplot( + autoscale_on=False, + xlim=(0, grid.grid_size[0] - 1), + ylim=(0, grid.grid_size[1] - 1), + ) + ax.set_aspect("equal") + ax.grid() + ax.set_xticks(np.arange(0, grid_side_length, 1)) + ax.set_yticks(np.arange(0, grid_side_length, 1)) + + (start_and_goal,) = ax.plot([], [], "mD", ms=15, label="Start and Goal") + start_and_goal.set_data([start.x, goal.x], [start.y, goal.y]) + (obs_points,) = ax.plot([], [], "ro", ms=15, label="Obstacles") + (path_points,) = ax.plot([], [], "bo", ms=10, label="Path Found") + ax.legend(bbox_to_anchor=(1.05, 1)) + + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect( + "key_release_event", lambda event: [exit(0) if event.key == "escape" else None] + ) + + for i in range(0, path.goal_reached_time()): + obs_positions = grid.get_obstacle_positions_at_time(i) + obs_points.set_data(obs_positions[0], obs_positions[1]) + path_position = path.get_position(i) + path_points.set_data([path_position.x], [path_position.y]) + plt.pause(0.2) + plt.show() + + +if __name__ == "__main__": + main() diff --git a/PathPlanning/TimeBasedPathPlanning/__init__.py b/PathPlanning/TimeBasedPathPlanning/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/docs/modules/5_path_planning/path_planning_main.rst b/docs/modules/5_path_planning/path_planning_main.rst index a0f9c30a3d..0c84a19c22 100644 --- a/docs/modules/5_path_planning/path_planning_main.rst +++ b/docs/modules/5_path_planning/path_planning_main.rst @@ -12,6 +12,7 @@ Path planning is the ability of a robot to search feasible and efficient path to dynamic_window_approach/dynamic_window_approach bugplanner/bugplanner grid_base_search/grid_base_search + time_based_grid_search/time_based_grid_search model_predictive_trajectory_generator/model_predictive_trajectory_generator state_lattice_planner/state_lattice_planner prm_planner/prm_planner diff --git a/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst b/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst new file mode 100644 index 0000000000..0c26badec7 --- /dev/null +++ b/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst @@ -0,0 +1,22 @@ +Time based grid search +---------------------- + +Space-time astar +~~~~~~~~~~~~~~~~~~~~~~ + +This is an extension of A* algorithm that supports planning around dynamic obstacles. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar/path_animation.gif + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar/path_animation2.gif + +The key difference of this algorithm compared to vanilla A* is that the cost and heuristic are now time-based instead of distance-based. +Using a time-based cost and heuristic ensures the path found is optimal in terms of time to reach the goal. + +The cost is the amount of time it takes to reach a given node, and the heuristic is the minimum amount of time it could take to reach the goal from that node, disregarding all obstacles. +For a simple scenario where the robot can move 1 cell per time step and stop and go as it pleases, the heuristic for time is equivalent to the heuristic for distance. + +References: +~~~~~~~~~~~ + +- `Cooperative Pathfinding `__ diff --git a/tests/test_space_time_astar.py b/tests/test_space_time_astar.py new file mode 100644 index 0000000000..5290738eb4 --- /dev/null +++ b/tests/test_space_time_astar.py @@ -0,0 +1,33 @@ +from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import ( + Grid, + ObstacleArrangement, + Position, +) +from PathPlanning.TimeBasedPathPlanning import SpaceTimeAStar as m +import numpy as np +import conftest + + +def test_1(): + start = Position(1, 11) + goal = Position(19, 19) + grid_side_length = 21 + grid = Grid( + np.array([grid_side_length, grid_side_length]), + obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1, + ) + + m.show_animation = False + planner = m.SpaceTimeAStar(grid, start, goal) + + path = planner.plan(False) + + # path should have 28 entries + assert len(path.path) == 31 + + # path should end at the goal + assert path.path[-1].position == goal + + +if __name__ == "__main__": + conftest.run_this_test(__file__) From 67a3ca7138384b4a013974dbf22383252f83686e Mon Sep 17 00:00:00 2001 From: Aglargil <34728006+Aglargil@users.noreply.github.com> Date: Fri, 28 Feb 2025 19:30:24 +0800 Subject: [PATCH 869/940] add state machine (#1172) * add state machine state_machine test state_machine_update * add state machine test/doc * state machine update * state machine generate_plantuml() can show diagram by using https://www.plantuml.com/plantuml/ --- .../StateMachine/robot_behavior_case.py | 111 +++++++ MissionPlanning/StateMachine/state_machine.py | 294 ++++++++++++++++++ docs/index_main.rst | 1 + .../mission_planning_main.rst | 12 + .../state_machine/robot_behavior_case.png | Bin 0 -> 28565 bytes .../state_machine/state_machine_main.rst | 74 +++++ tests/test_state_machine.py | 51 +++ 7 files changed, 543 insertions(+) create mode 100644 MissionPlanning/StateMachine/robot_behavior_case.py create mode 100644 MissionPlanning/StateMachine/state_machine.py create mode 100644 docs/modules/13_mission_planning/mission_planning_main.rst create mode 100644 docs/modules/13_mission_planning/state_machine/robot_behavior_case.png create mode 100644 docs/modules/13_mission_planning/state_machine/state_machine_main.rst create mode 100644 tests/test_state_machine.py diff --git a/MissionPlanning/StateMachine/robot_behavior_case.py b/MissionPlanning/StateMachine/robot_behavior_case.py new file mode 100644 index 0000000000..03ee60ae9f --- /dev/null +++ b/MissionPlanning/StateMachine/robot_behavior_case.py @@ -0,0 +1,111 @@ +""" +A case study of robot behavior using state machine + +author: Wang Zheng (@Aglargil) +""" + +from state_machine import StateMachine + + +class Robot: + def __init__(self): + self.battery = 100 + self.task_progress = 0 + + # Initialize state machine + self.machine = StateMachine("robot_sm", self) + + # Add state transition rules + self.machine.add_transition( + src_state="patrolling", + event="detect_task", + dst_state="executing_task", + guard=None, + action=None, + ) + + self.machine.add_transition( + src_state="executing_task", + event="task_complete", + dst_state="patrolling", + guard=None, + action="reset_task", + ) + + self.machine.add_transition( + src_state="executing_task", + event="low_battery", + dst_state="returning_to_base", + guard="is_battery_low", + ) + + self.machine.add_transition( + src_state="returning_to_base", + event="reach_base", + dst_state="charging", + guard=None, + action=None, + ) + + self.machine.add_transition( + src_state="charging", + event="charge_complete", + dst_state="patrolling", + guard=None, + action="battery_full", + ) + + # Set initial state + self.machine.set_current_state("patrolling") + + def is_battery_low(self): + """Battery level check condition""" + return self.battery < 30 + + def reset_task(self): + """Reset task progress""" + self.task_progress = 0 + print("[Action] Task progress has been reset") + + # Modify state entry callback naming convention (add state_ prefix) + def on_enter_executing_task(self): + print("\n------ Start Executing Task ------") + print(f"Current battery: {self.battery}%") + while self.machine.get_current_state().name == "executing_task": + self.task_progress += 10 + self.battery -= 25 + print( + f"Task progress: {self.task_progress}%, Remaining battery: {self.battery}%" + ) + + if self.task_progress >= 100: + self.machine.process("task_complete") + break + elif self.is_battery_low(): + self.machine.process("low_battery") + break + + def on_enter_returning_to_base(self): + print("\nLow battery, returning to charging station...") + self.machine.process("reach_base") + + def on_enter_charging(self): + print("\n------ Charging ------") + self.battery = 100 + print("Charging complete!") + self.machine.process("charge_complete") + + +# Keep the test section structure the same, only modify the trigger method +if __name__ == "__main__": + robot = Robot() + print(robot.machine.generate_plantuml()) + + print(f"Initial state: {robot.machine.get_current_state().name}") + print("------------") + + # Trigger task detection event + robot.machine.process("detect_task") + + print("\n------------") + print(f"Final state: {robot.machine.get_current_state().name}") diff --git a/MissionPlanning/StateMachine/state_machine.py b/MissionPlanning/StateMachine/state_machine.py new file mode 100644 index 0000000000..de72f0f451 --- /dev/null +++ b/MissionPlanning/StateMachine/state_machine.py @@ -0,0 +1,294 @@ +""" +State Machine + +author: Wang Zheng (@Aglargil) + +Ref: + +- [State Machine] +(https://en.wikipedia.org/wiki/Finite-state_machine) +""" + +import string +from urllib.request import urlopen, Request +from base64 import b64encode +from zlib import compress +from io import BytesIO +from collections.abc import Callable +from matplotlib.image import imread +from matplotlib import pyplot as plt + + +def deflate_and_encode(plantuml_text): + """ + zlib compress the plantuml text and encode it for the plantuml server. + + Ref: https://plantuml.com/en/text-encoding + """ + plantuml_alphabet = ( + string.digits + string.ascii_uppercase + string.ascii_lowercase + "-_" + ) + base64_alphabet = ( + string.ascii_uppercase + string.ascii_lowercase + string.digits + "+/" + ) + b64_to_plantuml = bytes.maketrans( + base64_alphabet.encode("utf-8"), plantuml_alphabet.encode("utf-8") + ) + zlibbed_str = compress(plantuml_text.encode("utf-8")) + compressed_string = zlibbed_str[2:-4] + return b64encode(compressed_string).translate(b64_to_plantuml).decode("utf-8") + + +class State: + def __init__(self, name, on_enter=None, on_exit=None): + self.name = name + self.on_enter = on_enter + self.on_exit = on_exit + + def enter(self): + print(f"entering <{self.name}>") + if self.on_enter: + self.on_enter() + + def exit(self): + print(f"exiting <{self.name}>") + if self.on_exit: + self.on_exit() + + +class StateMachine: + def __init__(self, name: str, model=object): + """Initialize the state machine. + + Args: + name (str): Name of the state machine. + model (object, optional): Model object used to automatically look up callback functions + for states and transitions: + State callbacks: Automatically searches for 'on_enter_' and 'on_exit_' methods. + Transition callbacks: When action or guard parameters are strings, looks up corresponding methods in the model. + + Example: + >>> class MyModel: + ... def on_enter_idle(self): + ... print("Entering idle state") + ... def on_exit_idle(self): + ... print("Exiting idle state") + ... def can_start(self): + ... return True + ... def on_start(self): + ... print("Starting operation") + >>> model = MyModel() + >>> machine = StateMachine("my_machine", model) + """ + self._name = name + self._states = {} + self._events = {} + self._transition_table = {} + self._model = model + self._state: State = None + + def _register_event(self, event: str): + self._events[event] = event + + def _get_state(self, name): + return self._states[name] + + def _get_event(self, name): + return self._events[name] + + def _has_event(self, event: str): + return event in self._events + + def add_transition( + self, + src_state: str | State, + event: str, + dst_state: str | State, + guard: str | Callable = None, + action: str | Callable = None, + ) -> None: + """Add a transition to the state machine. + + Args: + src_state (str | State): The source state where the transition begins. + Can be either a state name or a State object. + event (str): The event that triggers this transition. + dst_state (str | State): The destination state where the transition ends. + Can be either a state name or a State object. + guard (str | Callable, optional): Guard condition for the transition. + If callable: Function that returns bool. + If str: Name of a method in the model class. + If returns True: Transition proceeds. + If returns False: Transition is skipped. + action (str | Callable, optional): Action to execute during transition. + If callable: Function to execute. + If str: Name of a method in the model class. + Executed after guard passes and before entering new state. + + Example: + >>> machine.add_transition( + ... src_state="idle", + ... event="start", + ... dst_state="running", + ... guard="can_start", + ... action="on_start" + ... ) + """ + # Convert string parameters to objects if necessary + self.register_state(src_state) + self._register_event(event) + self.register_state(dst_state) + + def get_state_obj(state): + return state if isinstance(state, State) else self._get_state(state) + + def get_callable(func): + return func if callable(func) else getattr(self._model, func, None) + + src_state_obj = get_state_obj(src_state) + dst_state_obj = get_state_obj(dst_state) + + guard_func = get_callable(guard) if guard else None + action_func = get_callable(action) if action else None + self._transition_table[(src_state_obj.name, event)] = ( + dst_state_obj, + guard_func, + action_func, + ) + + def state_transition(self, src_state: State, event: str): + if (src_state.name, event) not in self._transition_table: + raise ValueError( + f"|{self._name}| invalid transition: <{src_state.name}> : [{event}]" + ) + + dst_state, guard, action = self._transition_table[(src_state.name, event)] + + def call_guard(guard): + if callable(guard): + return guard() + else: + return True + + def call_action(action): + if callable(action): + action() + + if call_guard(guard): + call_action(action) + if src_state.name != dst_state.name: + print( + f"|{self._name}| transitioning from <{src_state.name}> to <{dst_state.name}>" + ) + src_state.exit() + self._state = dst_state + dst_state.enter() + else: + print( + f"|{self._name}| skipping transition from <{src_state.name}> to <{dst_state.name}> because guard failed" + ) + + def register_state(self, state: str | State, on_enter=None, on_exit=None): + """Register a state in the state machine. + + Args: + state (str | State): The state to register. Can be either a string (state name) + or a State object. + on_enter (Callable, optional): Callback function to be executed when entering the state. + If state is a string and on_enter is None, it will look for + a method named 'on_enter_' in the model. + on_exit (Callable, optional): Callback function to be executed when exiting the state. + If state is a string and on_exit is None, it will look for + a method named 'on_exit_' in the model. + Example: + >>> machine.register_state("idle", on_enter=on_enter_idle, on_exit=on_exit_idle) + >>> machine.register_state(State("running", on_enter=on_enter_running, on_exit=on_exit_running)) + """ + if isinstance(state, str): + if on_enter is None: + on_enter = getattr(self._model, "on_enter_" + state, None) + if on_exit is None: + on_exit = getattr(self._model, "on_exit_" + state, None) + self._states[state] = State(state, on_enter, on_exit) + return + + self._states[state.name] = state + + def set_current_state(self, state: State | str): + if isinstance(state, str): + self._state = self._get_state(state) + else: + self._state = state + + def get_current_state(self): + return self._state + + def process(self, event: str) -> None: + """Process an event in the state machine. + + Args: + event: Event name. + + Example: + >>> machine.process("start") + """ + if self._state is None: + raise ValueError("State machine is not initialized") + + if self._has_event(event): + self.state_transition(self._state, event) + else: + raise ValueError(f"Invalid event: {event}") + + def generate_plantuml(self) -> str: + """Generate PlantUML state diagram representation of the state machine. + + Returns: + str: PlantUML state diagram code. + """ + if self._state is None: + raise ValueError("State machine is not initialized") + + plant_uml = ["@startuml"] + plant_uml.append("[*] --> " + self._state.name) + + # Generate transitions + for (src_state, event), ( + dst_state, + guard, + action, + ) in self._transition_table.items(): + transition = f"{src_state} --> {dst_state.name} : {event}" + + # Add guard and action if present + conditions = [] + if guard: + guard_name = guard.__name__ if callable(guard) else guard + conditions.append(f"[{guard_name}]") + if action: + action_name = action.__name__ if callable(action) else action + conditions.append(f"/ {action_name}") + + if conditions: + transition += "\\n" + " ".join(conditions) + + plant_uml.append(transition) + + plant_uml.append("@enduml") + plant_uml_text = "\n".join(plant_uml) + + try: + url = f"http://www.plantuml.com/plantuml/img/{deflate_and_encode(plant_uml_text)}" + headers = {"User-Agent": "Mozilla/5.0"} + request = Request(url, headers=headers) + + with urlopen(request) as response: + content = response.read() + + plt.imshow(imread(BytesIO(content), format="png")) + plt.axis("off") + plt.show() + except Exception as e: + print(f"Error showing PlantUML: {e}") + + return plant_uml_text diff --git a/docs/index_main.rst b/docs/index_main.rst index 75805d1184..65634f32e8 100644 --- a/docs/index_main.rst +++ b/docs/index_main.rst @@ -44,6 +44,7 @@ this graph shows GitHub star history of this project: modules/8_aerial_navigation/aerial_navigation modules/9_bipedal/bipedal modules/10_inverted_pendulum/inverted_pendulum + modules/13_mission_planning/mission_planning modules/11_utils/utils modules/12_appendix/appendix diff --git a/docs/modules/13_mission_planning/mission_planning_main.rst b/docs/modules/13_mission_planning/mission_planning_main.rst new file mode 100644 index 0000000000..385e62f68e --- /dev/null +++ b/docs/modules/13_mission_planning/mission_planning_main.rst @@ -0,0 +1,12 @@ +.. _`Mission Planning`: + +Mission Planning +================ + +Mission planning includes tools such as finite state machines and behavior trees used to describe robot behavior and high level task planning. + +.. toctree:: + :maxdepth: 2 + :caption: Contents + + state_machine/state_machine diff --git a/docs/modules/13_mission_planning/state_machine/robot_behavior_case.png b/docs/modules/13_mission_planning/state_machine/robot_behavior_case.png new file mode 100644 index 0000000000000000000000000000000000000000..fbc1369cbcd71f278a89d38adbcda6da4b737e36 GIT binary patch literal 28565 zcmeEu2Uk?v)+H2$M4`wa2nbaYBqLEIry@ztIg3aV5ELXRk|Y%%C`!(VL?!1ah$13_ zhy+ED3<`oG^s4K7-}}11{sTQmzj4PK_tvR8XYYOXT5GO3=O$KPPva!{DRKe=f|FQH zRYL*-!n*_n2tHB-e8Q(lN>4z*Nq|*VG7chK3%zbl|DN$!xmWIu+~;U?eyJkwm@^Yf zNy$K&Ho6f7GL{FnnNh450S2HJGW2A!=C{-mQoO^OLHy<(b=%^jYp)Noo9v1|HuWgalaLZ1!U}Exs`ZF^# zDLLdrR>sSwpI>bWJ8oZjOhipU=to1K#l^Jwv>?FWzqhaNB&+0_wrEFRJQEWGLx4%- zDb7x3WH`?F{>-mmzYe}H#n0y-OITT0*t7)dy4ZGih7&ZA5@1r|e}-vXxqSJ7%(bt_ zG11k|j*fn-6P3s1-N)essqh3t-9V|UA5;gGBOgmjN=isbly5Vr6C*WM33y{wtB)^? zzb(0>tD}RoC~5iCpTK&2h2V$;$sA9hk0Up1ap<|bv9F=pQC7y6F>DgiB7){rq7TPNR#1*v`s+;?!m!L$S>TM==0~(Jg+;*DTZ6a zTn77C)vjH;ruIDnS$XCCQ_QptGc}5ni7*%Kw|zp3i`APs$rV4R$0ChB+^oLLNv8k& zmr!GyuH=FUdnJBtm748o!pRk*&s>hgkCB#G8)HHsONph!uT?5r*VT^Ryu-rFz( z7sKr&?&jv^aX->lLgb(ttd(_Z3+qYVvI}=|bLL@G2IsmIvExG|K`OGa9)&7;(wzFV zXXHj-guvZO)17kB9*ab+XHLW1#?J7tp?G6a?90yb@ZIqtQGMEHJA|K-6X8kUlIf^O z(^N^R{lz%oyB>?oys?%C1m2o3fmr`RG7_W~*Buhs2TAbVXMU7vs+A$(Qia?EX{xec z?hqj`G~GmxU*f-ODRV+A-&DSnbqv3)PWyEeM&L;2BlN!Fzgx*h1S95{JNXU2pj0yR z;fmNhTZ%m2;k)^!i4ibj>aDx}Fm%o6M?Q+VXyu^X)PsMfIq?6d`Tz3UY+ViS>+3r_ ziAY0_4hxgHD2AuNYb}$mBqJlUu&`*PJ4{PUPft%y4!^EMh|(v)$HJpUDeq62Sy`W- z+%YmVHND@|bdV+GZM?=oN&W8tk3Y3O?cH%&E=Z(biy7nM;=;nrEMQ)(m?m9Mh|s~u z*Y1=cKmREa`_AMuD)QE4-&R&!;ae;$@Gp$?^rfFQL35oE8NznOciiTXoQgsa zS6>zcZ=H8@TZ$keSvmS%S6z(~CcXGK2j*)9UV1Dm;W;T{V>3fYbYg9~A&K8Bg5%#Q zv|;~^rIl696)7U3+Y=L}+mWM0e;-TkA|)$(qcfZ^A|ir*hs^rFasipf&F^0mVq?h! zlF&#pSr!OooGRJVvND-lhe4{UszE{ffi6cAPi-o6z8}91g#VoHi5?yrLdUV)`J4Gy zPHaAT@?<1SYICOL=l16TQlnc@QBhbd_RN_xFJ8Pjefso_BEd{JK`gwkSmGAQz-TlY zgNfo(MRO%Sdh}>+Zm#9}W}F(K?BDy*CR`5=KDc|5b!d24?WI${1m@3ox|7Iy1mX)9 zK^hvd+27v}C1(8HJJH0D-V^@czmDXD9a$h5N0I-$R2*q*gXdKK*(Hrb`he|)K1k`Y z;Y1G!2x%cl&>}BfxR5pVGim>_W-c2I4HP!v7}9aVe_uqS3-j`n?4OobpQ52jfz2cn zp0OS2c>3nS&f-&>79>rC?BBv+)A_Wra;77!!*NL_lG85iPXN4fPuH258F-nA-xgfF zy*Hm-c|YWuY<^|w)nh?HK^w&g@_+wU-gn`S*aSyYQ&Xkov$#x(-ra@scQ{GIEFQH! zTA!MlsutGDa6<6oCp=EPIXI}fz;~LK7MGS*?=+AIFW`c-bnn2x=N+@B))v+F5m3Nx z-@e_^p>XRq+s$hularIHId%>XXI!0sZp=_oQN=R}_Y1%eVD3Hytf)ety2Alauc-7lp2_u7QEU zf1k~#8mH*N*f^=?#>O9;vthq}d~qu1*KecSoi2T#}WQ zO*|z*e&zMx;GB=NmzS5u@qvk{Dg2g_O?q@@<_|p2?bRbC6k1HI)~w2whK2_2_EJG-IbXPHsSb9mupWx?AEYC2NV(v9A;?KL$ue0+R# zXLXimJ35k*s3+96g!K*o+oHzAkVZDeamK)HA|ePghWmOE2!xKVZj?#3Lf9+EnvI#3 z=m0Y7#-_%`%m)wVrQWQrtjPcQ@wU2JM5poTQ?ISLE+r);^Yon1Eiv0p>jfX_#%Hkm zoqlF}T)Fc5$2U4Ars%1%va&aC-lW{Y%~4(d&$GR;yq90#Fq3Ev)R*okic_af0h%F= zOiN39V%Kr&$MT!|_wRrG`V~IkcSJa7Sw8n<@%jR9On~v+g$u0S7Og?sUtXlv@GJbD zb7>7Xpgm3~cNxAPeB;I~>7wTAo9yv@H@4;oy#g0{V->MBJ0}@d&cHsx@Zj`uIXN8i zFRE->`W8RP+K)FH z91hm0IXT|$?lG0r<*@W)V;}0=UPqf~3fr~&2L!wu9qr_M@%r`auCBbs#>VpUa)|YC z918hB;>!K>bQ2g`Bxh`FEG+!x%a@tcx9X^E`zerVcQ|9Js;ctx=66@$fB*jd&*5SH zvu6>w<}a-L<0=HaW!ie^JTwOfhh$b|K|uke&Kp0LAqzNutO0D8eever=4{9H%}>(} z-tQ+S`uX^TgYP|S#ki0J6(goTBV z)aH@w2uy&?*<59OIkVZ?xQ`=s6?1A1$2GIj>7N0ZTqqPoggHZsNE=_w3@69K|9~!5 zUNYXYVM0O%JnmaT$mr9;5Qz}{c#Jqs?3as%Uy&e<@p!U~;tQlS)4c)LGVj^=6P2npFe zH!#iE(2$mcL*d$29aud81av%l#-^qVnLTaj#*8~0l=}K)h!tgQ*zuq1&d!CfPbw>~ z>g(%UT0R^Up2bh5%$dDAR~kWCQpj^D8w&P4HW|O(7#ar$2Wob?PHrX(0+=Fgu)QMp zWm1t;9RImtG9~GuA>eYDPul4qpxpostWxe!8F2-hPC`Xuom1wFzD-~5jcI_W0CMK?a;Ub0@wlp^{Eu7M$sDlc~D(N};_AMP}5#SwJ zsB8WG2)bA~zgz)_Q1L9BARzAH4B zS`XL9rL4@%nAq792^W`^r0hEhY;0@*JSDJ7nHn2wl5)lnB6c_x6|}T2U9zipPf1UI zmw5Vuhlj@(GTTBgsBU_CRJ-3)SlG{=Ju826kMefZz-LIrD=RBh>~cYGi**?p8IO*R z)YR0tly0jlD#D!Z;yz4I8yOnHJLpg12!m!CkeZqjr+rC5fz#*ygrUqW`i6tGDe(xm ztCf|NiHV8Ozhy~YRYsvDB?Bj`9kerqLVql$5V-3TBk7|EpqG30Y&XO17K^CkorZ?% zuCB%TTs+m+j*tHIL{l3*QlekAy?XVkk5Bd1j)73d6)!J&=fPyiK6$(!#>N0soDbRG zYPzs_w(uxaVp`p}W@|2t&7+5;`^IMFB@Ad-Zm$z@)K{)y$Y@+VIyy`vGFoC*l~qQd9TpL1&@R!^-l zoHITA^K*7*fbVuxZ*TAM;gUkyB8{4iDZEZLHi5(>k&m!$_6`mak9p@c+i(69I(xRi zyW0^!9u$C}3-knp!Khp|Oh8~@w#>Eut}chJNa9P`aw$BL2LZy?jo~w@X5)t?X^&ye z;Qpnhyz{FP4$A=D7*Czz|7dGw))4&Nm4YH3sEnVRvlJAH6r7w4i1GZw`uh4Brvbez zNkJYSjdGDRo|lV$1^M}b>mSlnQ{R64_;Gx^(8sbVVD*0Y)i`m0So?eH)9^8*chA}O zw!%VHzh%7~c|o82JF8GkDy^IFVfgLaw;*m9Gz%)19Fv}wCScndG+t`({;5ss8A_Lm z`sdGW+e2iu$U1U!bI+*URaIB#?|N>Y3bbh^1li=b zwr<1InAk6f^i29waruDy zNvPPWYinh1?g{iL-}Xt13n%A|9r%1&K4fxiOziAg^_i#RTh{WSzl`ndIKrks4GocR zIvVDcmf~-``o1dc=f>&Og-G+XXo9IUV@pff&|m(SF1=n@a9mVV^Bvy&)CS4$?Ynm_ zbyF&LDc`(%2N=p_qA0ebm}2ZZ z_$_K(ym(PuT%3a=2Ns@^T`qIPHAf-L7V|1ue0gy=W6Cqo&reLIr;GQ8S~yzE!_(9H zna8_E-_PXa>0HC|a zDka3rTUt1(nqUbJSD8CT08w~Q-!9f?F zY?pzHhsRJyNq~t7Lxf0AvygS8y_3`Tt$CHZeZ=#FvEhci-yneiW9RGZ>nA(lxyvMM z3(+HTL49F)Y-|i#$ML0)$;>C0`%wCF7~lj)hK5#vzatP8MF5C`coD6k{Cv}UrWu;^ zfXz=A`!&c3wPL~}`M$k;AP)2QkrX2P1s%zSz_nym+>{u!=BB2m9=~mA>Qc|C_{S9% z-noOkdGqEW9g|p4fhm7`dwYhEjbTM{AMwr4{U@(nxgzb?J6~YBPF_&B4*fKXxO%16 z=umL(9u>+7*Uog8(lQKW>3xV*xcm>6v8S>Gn>$duf84nm}o zj*d={9D7*7!;GKn(@QHW>oeC`YEUqKjY!hrJjPoF{u34hlVL{p0+J}a9CcOIQfw=# zSOno`Fb3O0;~uktg$17{lVuFe{?{yTy+_hY0tMM^kS@8^@9n=1J1WSYR~fH08iSf9 z%|_Kq$2l!}9-8}o%O}#yN558u&z(CbUEe$3vlht0_YIN+tR6Zn;=bqu_bXS#&!0Dr z&hT{6o61v(KCAn%@Of6^&^=ZndY3%3P{!)=awZPf9lmcu+x>YUX&~`*1upOM`Q=)d zVP$1y_b(!i8U750iqUK5YvlJ8FC&-CC{r@j}O0JdSRl7 zBP7+-#X_mu+1`#AsNeY_k47V>&tloRS8}tmv%S2%sn4a4pLrj2Z_EHc8-OrxCMRQ7 zRg_L3_ZzS{C7Vj)_TL*Vot=u$$Sp>0r$^#!J8q54``Di&lSyJ`PvWW8#XUOlpz>&M z-Ri=HmbEoc*J!dg^Q4+eSb2H*>boaN^u8)vSUiA!`sIp8>HhD{4%iMSvfInBE106f z0*$2Rrlu~3Gsh0wa7oyrR`u2e4;Kd@8LGK+A39reY4HmSH`LePY2&8%(}85Z@v+J1 zO!4@DCa}m+QN*o0xl}9}F}OMJGz2v;GzR&{ z#@c!gr)!`QTUogdV3*!SH*~G_=Fe9X6O6XZ_96W(d9bX3JUk`$?osv=Dd~m73okA% zo-~K1L9D9rftU+9vBKm`77qE91~u z(NYrH_-lm6-~kOphl6(*@z)?IMw2(KU@#Dx(EBnlFzkC7;dwO{7JNGDT-XOH0qO|} zHTzt~>%+8hKy(HMN?Wwvz>`53tE-4!I>U#hMJX{oo#Ds+D}cTfC2g8%h#{2Zf>95BDqu;89z($TDM={%&x2y3}Mq} zX6dg-8H_;)eSP_$CsV%+HMsJwA~iMDfPSXYw*aCG&?>z7sw&~Qd`J>^@7{g-^y!Hc zCjdoNRaB@L)I+_Qp1uh%6F~YGAL-Pyy50GmeBU757pNy#Hv3<`d9!7ZAV)rQXx`_? z?(RSWYe_}L&G~L(dNt_bq<{*P%(@DlrL*&o_jY0Pu8@X2oSmJ$y=P%Dq0tkzX~wSx zbO9eez(#|mmdtANnOBC^3i7vY+l_67i@khh)zzZ_Z2-+qO&xrHtFwfD1hEnlq|7Go@6Du*y_6#lRd#)O zIrrwB@$KV3zkkB3*^i<ox$u*pBYx2M?wSG^j&VpCqTGbj|J`{kh2)AJx_zV@I9O`|$B& z;0C;{uLIyABqW?11=cmFB|3WG>qu4&zdH88g9i^EKJ>B)1A-iprpkGjmC4NA%j+&N z;X-HL%@%X5hf?0`dl?BEG=>Amz$}LTUTp1#^#;0ga3%si6| zZyXh?B;~9-aRJ&>|8PUPL;LUyUCeex%()!E@I5^$*248~nF!ycjZaLtdU++_ zJ%4U$XP2{2{Y*~V0R1LiRsGR1x@u#p+JWf!pzp`Gx9_X$l4cfx@*@Vi>u_H*E+6Cp z*c$`9Wlx^0K^embB zNsxLP01>h$y?^sY6yD^U0u3h>O-<~L8#kCgKLQkBcl?X#l@~K6j~BoXU|P?$Z2F`D zZEfwI4FdeeJu75)xGu-;4V2qfll?87Oan$;ECki=j~{E2-76~|jPYt)W|ni-ZC1B| zXUvd9w3(aGvZTaKN{~LNxG5(mw|_|vXv?dvt`l``mw0%1=+z+XZ|<(Rz^3-}Yz3fx z59c-8K2v4ap>+EMOk{8M{botdt!~Hpr9`NBKpz}#G%8j@4u{Tc^=(N~S=nWvji9pJ z&3C_bs~ws|CcBV4Xfoa0qC46Kz3hP^Q zbb&H#RC`OhoX)gsnPXEtgi^fr%bTOd`93_Uzn;uy~L%8V@fL4ODsT1XMw zeMP6xGLEY{M7{87xHgwdT79#Iz5C?~$gk?^>ib0xG&TVyS~KX)fH%iYkHoIL&UY7g=Hgd@ zP(FeNp}!(dur=hsuXL1e{|ec^y#T_}(&jY<_7jJH{=n*`J6K3&RhU)+Z<*xToU5jU zUtn`{=Jv@uvzOPtQ69x91_ny1W06;M_W4vEWezTi*Ba0!4H)gOu-`&D3wcjJ7lhu* zHNdg&)hoTHqnC7FogNw*5)crm?%U|)RT36Np>(kd0Jx|X4msHr;blO*+6r8g*?>4E zo55cL{ePS>B;noKV9orynI(oIJ zC^ezNISzwI;dkN%_xZ}ELyh+b(#wG>cscL0W%jUWjMzcz4D3_+)&;;TXE#!Tp1FE( zZ~&}fcZz0Xzv@5lwYvb-!0R1Az1@gx6BQLbtSYC~T(Hr;FAy6S*If}5G2;6B*Dos2 zOeQAwJ~mzBVls)D9#bu>-clwH5qQFBsJPR|D2)kdNs8-i95YSD;i|9N7MdV~;nDYT zTwGj%Ym-WRcHdTC0u~W`*Io}Tdrs)ygF#j-&^|9;Qnozi@iI`$E)~@6CDYzvR@(1A zX(#Y$-I3xRu6ag7?dS_|o0A_td|h08;Y}`3iXyB@O9NE4o|LD&w3YY5`uc6^^3HBh zb6|sDq(DQt42qOt_K54}mf~0|<1>ERbiUoS2DmTrg6NMLYR=VTlI-#!L2vTa#yleA ziclzREPzU=?GR_iJ{c3MUZ+@D6YkwZ?mfk*2mJZ9yI}hI^Lr)UxHv20i2Ty6`)85e z-8@Q&4KfPN_Q}W*SM6GudQ7d!^oI{?Yim%3IkRNl4G3YJckG(S6bM=>+(4DqpfkcFaRc^@O~MnPl}#%+GG#tFb$ z##_?T3KSuiR(WNmgt$2Ot!IW&Pv5#M7Z#$+GXK0t>Ub; zI}wX^mtm~N@q!}Jm?;glAZr#&$b-Sl(xj;Ggl$-uk@` zjUMJ_7yyys3}Gf7VMQ$0d)t3rw@6$*f`ac(G$UhjNDXmEPw($i(xh`%!!Uq(amHFD z4dO~KUcBP)>ebU{&(g`;$Ht?{=+0^eT<_`XQu^@t#T_OSl;>qG0Rh%(dTY-J;;~Pk zHXtEy44FN*SBgK6Y|cZ|t3f0FszaCQa<-^b?(^r8fCI~(%Yurt9;k51HN2pe7nhpa z*4CEp#vyQyI%0#btgsMx+!NFF#=*Bl-tB)zzKyyJ~-u zc^4ftHA&kYB#YRbTE!uLV54kJu&&bz(m;`howEA*vr5aB@x~Ug1VA1X`ALnxjmQZ* z3SJyaUtzfrT5vxNhhO?6_Jq)nkK5niHk$zRwzttA6jU6<0QiD7_;rqg*)_IhhW5g= zJC(LI4GjbBr0P|iCX4uv4Ek0R3E6w``R>NX#`gA{ib~wb!dzG^Aot=!DZ5!czan`R>hsUnAuFI-hWn~O|rNF}$q`NPMLkA@fd zy-BN|C_=N1UNd^*6DowIg7HOl_;SW_4e~NZbar+wFT3}BKwi;OR%Fz=@p})XD(=HS zJbKvB&^DkF8<~E^2IQI5kkT_T)lGQ@nHbfS^1pZ}0I{+RwH0U@)s5bAw8mw(J&-Xn zWv-oF|L9uYL%}GZsi)`a;ja^?t*)hPfNyM0OL)+)6{9!YH8nNEH&4eAMIY|{`0)dF zU9y7EJzhaXtr6^S0F@L>LTMfpW|#jIR2@E)xB~2{uH7-qSDB;%){8g%O-&hl794G* z{R|9m-uw+2Zr-$Eu*VUwTM~x?;}mfMztY_Dn*w0NOqeHpvpqN2c}$x(EoX&8a$#$>tBw-MFj*GhyrLq3Z4^QcRr=(~c`2#r zsCIg6w5Alj3YIqxSV7%vxr3I?cHl=)GB`^KuaAv1@&$?`_o}R$XeGUhT|Gpq=+&_t zk~w&V38vNo#OeL}jQj&Sk=`I0w1DbLM%0BG!;5Q=0gP%_5bqS8$<>4vt_J}KP#ZL# zHx71+8kw2HPW64>2JXqe?|vhZ;^I1V{1KZOrE(MtZ2BS?haNU*pUw{-WW~jezLWwY z_VVzco$9;Szw|n1dU{%%n^9fe7g}10D-$AO=T9Ju=;0aX&z+0!nTH4_7cLaw<+a~S z*n(v~`1MO{ZqD9=)LQ8J@@QVQ6oJI|3IY6(U=yz9olA1T7>-3t>B(NW@cHv+Fh;!2zBs(OxHaF?aqyM(i1BPX zFocv@X-0B+keSc_YG?23GJbM%s0jViZ0&m-B*3sgza%Ead>48_F%sLo4UsQdt!iEq zT_*MDk0{^W7sWLD-!YUZO~mH_G9*wi%gK%7TZ)OR#j2{;vKH8O^5Rw#NTvE#34zB+`4 z{u#|vai~1;ZbywDvdxD#Z?@lFQmC0)13tyj%nVfC`wqitw6wI6-k)@yoxiQXMYHw& z`)_EOR0EX?%2Aw2II!t_-`Sx$E&BtyQ(zjY*`)DS%faL`l)vS7KRmkvKA)m;|L#V^ zGd@u3F260t79qNa)PX?e=jA1(q#S?${yoF4xQK}T*bo+;*>Utsd+IXLZ*ryFwzg1^ ziM9lk&)D-1k+P)SIe=E&51=cg7znZ%=(q<5V|wO+hF$*lP1M!F0f-B*0C`@hDlJGw zUH}FzGBiN5(_-h$U;&yiho7GxXk8R7tyu7mv+p^cU^!b0iz$%z@Wzg}Uzivf)lXl7 zf9K}nO5{+mH8SE3S1=Yug1`@OpYY@gXResmLUe9XQBhuAL`P9U!Dr~-ApW6Sh1yPf z_(gFJ0`Vpcur*kGO>QLY-u$9Lf%?T8KS-;Tm7bC6N8*s2jW>UKfjFV3m&o=OWvs@T zjKl4K>Ll{*)#J_-ZmR(J^_C#ZRIbro#zkJfZ#g+J2T0vG#oX4`5NPG0D;ko{boZ#M zuLp{yxvlMS@saq;s~!f1%F5k9;4p~pcHT8dLUR{+`!*{pD@!2nFkNCvi5m#5a*T>* z2Bi8ixL2@#U@@r?CzGX*Rs@q0wDAl9l%kz_j*bfrv$uxB6`4^86JAgs<+-?&eN(9f z0&Xh;-2srDDA7LZj=qHj&_6G#naJoPDG$_3m9aq9Kp4A7y^Rr@0XY`DY-zqr#}{e? zRwn=^YcHFqsK6u-6^{rtrf6Vm9>Rt-oVd8_dyh74d~B@t+L9jG5>BhP9f;h~QT-72 zzqX?V6Ey~;ddkF;`1s-GfK~MS4;^7)SFcw7Vq5J^>F?{i`mr&^{KO5cVmNJ@Ke#xa zJP~-YM07w^A&pek(4b}(>71Noo^EKUuJ!?o()RXtrn9EzAV`q# zOrX5yzkIpVz)jk{=m*LEs;8%VBHM%HWE2BK6iaXPoG@upBB=Oe)#n17C=q-A8F*4(HIazjDnW_Uj}K8&fFP>kx%&M% znOO=Zn+YI{^U(8CT%(}Y&w^iVbaWIjzzGtPpDXVuF4W*97hpaC>e3*$_x8T}NJF3A z@84GjerR~*#3xQb9svl7>X@vlttF?R=o#4E*#Vv#d`{flw|nLx=bZktWM*OUZDXSy znnazkzCJb3yQZgq_naWGdhYpVe7rY@75~8XX(@OU7>rBz9Wp%OLAju^#dJpl?j$D{ z0*i%Lp@Me`A2n&{lX3Zez9s#D~qLrGZ7i zgJ_hH`0p0VF}?J`!9i-f<@=@-Ul`&EFua!m&ve&Cbrd~)x>5I9{&UA{z0Z6%@c9mI zTu#Ra>r-`0sh8w~e=O4!^Xe@^EJ3=O23D>k^oc+s==U^@g|xY7s_3_)qv0$p3b*9? zO@YpXc0V>gzURXg4-bETe^Op-5IrF^a0h>#S3f~NVvIM@*XQI6e~f|F9SB7?m>Qyu zt3nZb`1Tv*3*cPwJm&%F=xtnWU7dx%MD*q|tdI9(^%-8?!FTV#eny++`j-`YKRP-W z_6e5v0yB zz-=lj+!zcj!7I>PAxQ(<2B69NQ)|~+OJgG>Qpji})2kAXvcqx6;*VgXgLh1PDo^Vy z;zurM%jX&68BnO|^v&p5qHbQSk_5!$o}9P+G{kB>;t9z8v2@-LGc z`i3BT6c>L53H**5Q^qiq?k5!$tJh~kfx@;jG>m)^V+34V6zt-`@1zh?o9(};IJyDj zyP>XM{|TYCV1r=t;^HfVwnrn09scR7Us+uxIeF?1Yp?D$6H=XzpWm^@91I_sI$mBv z@qOLAWbeU(B_<(pl9aS_6JrD09yZdvU2Ql81rvT5m*KWwUp+oIN@^lTlS=}IAu;by zazKk6My`U`2`_*&(!QY~=i*JE3OB!eIq%SoJba!goesH*_0%cH3n#%O3Y&*Gs{%Y2 zKypC^f*u=4OpeeWG_N>s-MR(B25bf!GGNZNM+dM$uyJzh2$>FF%+T;v@EU!Vqm19t|tOtr-B zS<*DL$keCy&?}CPJ0R>v1eW6N5?tkl#kv7W2nyZu`>Gu9Q~+P+=;-*=x+%Y?D9V>E zl9QO27z~pNNBi88tE%N8jnBbX0T$z8z^-72gj5DK;ob`-CMIA%b^#3obKrvQ>wE`4!Ysh2Lx9Yin40`XhdQ+?EbNn&#l| z#XcA6lW)WP$g(sc`vdt54vn&^s-+xDq>C>Krjziw`Z!O55uo6%BFFpnKcDZHyjrlI{JAIn^G?TcgJYRNU20vlP`8Ja)B&bjCm zx+krzV2+6an$iV4Z9h5=%I;!v(Y|yqCnkVPF$Na=9M~q&66pNnD9SXnmj{@G`DJ7* z{$9}1$AL5z(2lAw&EDVN=iQvlf3^s&8t{x}Pn;PY4~ClDkd=D4`C2xOK91lKCN`@9 zNF_Zzy@eZjHo-6wKL5D4Bh31^#nRsLEZ3S&x z_W{gsqr!z;I0@1UNBQ)moD{LhR1culpb(w;*9BE6MuXB0{Dl?3K~PuF|Kk^N!;7FG zbi1XIavG{L>C?`btL7cSQIAXf(9z*=w2myxCIaBYBY(W$FMc9TRqk;+G(zL!#{a(H z??e;zivoWE!eVaNs~5%B%EXJ!GkWCJAC8N08;5c;ze@1;<5(|&eEqNp_}Cbr4seMz zlt1_x3IBmAY05mOm{aM&0_asj7u|z5kTp1R=JFx|gC!&+;PkkYjo1)S_v2)7nI3MS z+d|dWNl1+JHHgFsfeGRGD6~)ad^MT|0gx4B(SkW8EMJD?)eru2orGFVy`FBoN?2eG z02NKVHd9$_vf~edv9`#t8yxT$Y!8*-fOfiV8yj zv*@HA7`GZ4q;3-xTDlwO6#`DdoIM+;kf5lnMEd2+m%_qA{dJ$hTm^`zYHFzm!Fl9( zqJx297sM{&5owXPClLVLSC*GKzv~x#GY9EzaIh5Qtm31$udb3C7(zw@{0vNqR4Q5X zqWT;(T;PBzndvI$kLJ;Pgx6Y45}tZ}HjIJ3sj{qW3Tk*Y?&BjBXHIVJ&mc&x1m+IY zZI+u>xFNbZNX zZ2e<5qh(-7&&(u!J?HGgPICh+JK)-A^qEJrpHGKL1YTtZuJ{rMG1Ou@U#-osWP zgmF-ml9DPZE><^KYXEo6#fxnK;SFC3zuB;E4`~8E%z;Gc!93oP2AT=?HPrz2_?0x( zk&jR}x+oULbrQr{7yOz)JutcJQq6Y{&PIrwooS$FV34_R;kqyht&Y;%uy6-7@q$MA zdH!sQ*xEvnZrni1sCAE|x=7>W=f^K3R9v!o{`)Cj?EO1`j(%@KC!MZF=f51=35i@x zT>RU&3nQ&3v~U;)sPWX4lxcr2LJRo%k&Mcv*~?!g^l<`Y@z9`AQ)m2hQ4y%GwTG&D zE8#fjE-*A!D*XA8D)2B@Jo zf%Pvc!u;p1V5qilrGQ9-$QBS(6wkva_> zfQyTdcc?>`85DFxK6qfEqC)iNbM6f!+|rF#SlAn8iGSV*4IEa0?RuU%^27!a2K%@W z>J6BnHUD{@JvjY@ZCi7LQRjU)c(E&JXk_Wy&CW=8{4m3B0Y1LGFgD{PI83xc`Dbt1 z+b(oBecU5g@fuP+;S_P2sxnmsuJFXc;lX!+B!3_0D?2<6B2X-0wn(H zA|EIVXte6z+j>f}PGC}!Rba`KK0(6>=Rf|A5)R{-T3Km-=X9Tw*T;=x;~>OiV*YhU zumgmKUi{A;Wo1vb=WyevKKlN>_vOp~nK~f`dy?f31Gq&17OEagyQ2v4cLS~K5_p^O zk8(qzkfIV2Mc0t^+oxf*j9;i@#a&-YhyJP`za3B_;xd#5c=tNbZpRTo$Kv9%twQ>J z(|MfXiY6xMkjE9djng9_O2TODV`DI-^l)#Ta=^ILV2;Pq7)Ub0(2clx@U9#_GJU z;9%;*hn=8Sz~bx|Z^(gRTFn5ASa3Rb9S)D(ehI9%>&QdQt6^$4EZl$c#)FqHb$}xD zBszJNDgZu}&5mRCI!>RWe!Io(Ah1U7cmMe7AAvkyz&qqxH}dl3mUsbBy|3keuR-q1 z9C=q^_8L&(qv)6J9XEE%!9pqSm={Ek4-H;CqakN)DRJ0cSzVpn=QzI_uC1kIF2J}K zcL2@vt)qh_Sl~;LUcrG5J}M1^aWLJ0>P{=gmNoL}`Bm0WSHL>pJu6SI7A*G(JZW%9 zs;9df+~#-f{I{;5`a}0Ci-2maGk*dr8h!j{7rJ*I9+Cp|;UNX<>hWRDF`U}=q*sHj z1(goY;^}@QQD+2}?lcP3IXGI%NDsT21*@q!S?dyC?;(wG0r$}I8zQqX*evmV&DWNw z{^8QEeSIl&bMHxXveL-EbTfBS>*G%}2GhwIW)yjj^_dhCAQ|g=Jd-!V@g+`)X_(WIg0C z(%&c}m_Yi^^ZFcIW|?6d1De5)#0=)tmv_ppRB z7^d>&S{t-k8tUrM4sCpRMj(_=JRjDN)eF z!UllzSr>2BS?B(Bfvmxscg(m2P!VFC>owpeXcPXd0ZVeU?{uhiCL+gw^A~tBK^-H@ zPY#S=j^MNO$JV~mdu{?JY799D;Gi2-XV~w5djTw30xR+FIFI)s9AmnA^-mv@9k?SV zr=}bl>P2q@=f462F+Eyum^Bxe09}Br-?47$%EXg5@81I_1dcm-0G(&qn3*Rl%!EM* zcXIj+?Am;q|L?u4;^K917D-k{CXbh2zp}i1XKQQuZOLnRv9P_3sG@II8lZyjkAnfm zeKZ%UH(ldE=F=z&rcaH&w>jBTP&9*Y+v1Od7@6WbZ4kbWh;>CQBHZ7uEogfI>>te; zt9tq6L{_&cQJHeV zJ3w}BD}o{r9~UPkCbq?s#f*_Sf8N>El{~}>8x+9|DyMdv{3CjpCB$S72y;xfv1k2i zm^UcHlqN+%bZ6?Crvgsg&DnX*Y!#jZrzj7-nVfEs3y09MF7Vj>pf1fKU0Yw@PH6bQnE2K{1OihESqbXO@vrwC)l1o+JzI0$ zeeqp*7mkN)LJJQXDEPI8($9e-;+BknS50R10M}`{CQ_o)af#%P5pqs(Lp#b3$=~$o~s2F|`laQSA zLY4`R0C)t~7xdDGSH_IGMn|`xL`(`wLSqGI0UdsRhB&FN@&hRk-t0v~O)U1{OX?*N z!o&0BfQ-T-n2!ysz&{G?=^7tl(ts7%to5+S_&#L#m+heL#8@k2wC@O%z?$E8fqig- z`Tp*|MV}i91Q&=FMR|Ip`NPotSi@`gpfWZpn z{_#vk8_{+-iV~8j%BokBCc+Q;`W)0@gFw32UVWw(&p6*Q9B;LM*N8SE8gzTkvnXiI z2{>oWIDlt#=)SYDs2Isd3j50$q&@TV;D;|3ix3?rx zCYF|Q|2)q+yHhk$&F7E`*kT|CS*031r^G^RN*klRr7<)?gO{*K$NffgLS8IE@C0ztf*3bkw4?-M^d9 z3vY^Dt8qn_6P1f5RBW#DYqADwrL~@&-SI+SJnScP?VzB2AVwm7Y8lQcNTXAhjz4p6 z8OESj#0KXEawwZKwZLKP>U#D#$MJz~N>$L-oYGMrkbjB5N_Ri41N~f-fBq5|Jcy!q zf6;*cw3OFJ*m02dz)b`vgnhJrZGC#y*yq?SO?mj%F7x;7LM=!-d(-E z{z1am4TRV@E6)Dcq~HiOGizySagqd$Ef*9h?>#OEOc7HE%m)0xBgRRs8)L2a`@=M2 zzUz0Jcq1YRFk}Q=2JZ$3NpIr4B?K6UvX!;9AA5W3(mr!QvV!fg5SvQ6hU@6kR8$N% zZi$Cg9po9J^{U|V`AA2g{7gtep#x5ylLhttHM1!wAleR1E;Ge|)bagzq(=waXb#{f zCGkZoDV38@3dJl`48?ZZ8#Wgoc`ZC~;ZtN}M2g^Qx>GUV%Rvs4oz3(UN*! zWhKJGj(_~{cMPMSrbt6mWFLk}su=?R0Y_FI%LUgyf4&FD*06{D#f?i(v}Wx8x4WM& zDg=6hm6>@?n19%>k=HVMYIPj?T^ZZ^LN>qf%F@FHUb0o-GZNzC0fBZmkkhbVGGV=^ z+1^452DwXVm?_h!;vE8d`WWr(ru!G65PY2Fp{4Pk6 zUzoMAv)44aD#CTJ!NrWBku$jOY{l@<5b|^eJd!_Itdt*5&skK@K*OS{iY(^C{SQZG zl6{Hg+Ck0W(vyX34hlIdhSIp3T<1b^40rGghr5Qqp`oXzz_Dp}Et^m-_emJiSnjUf z6i}@|_D8r5h;2*`^f9D0x==4_}9NXee`QcvaBh2Ub`;D z)kC)kMA7MsH_{TdF+>Q2Ubb8;5d|@xUqn-MPfoC97AGYoWo1o+)!jw3Q1&$LIujWc zRp7O2S)xvNSGex`I$yeU$M!K+q;S&bV-SL85I2e=!W~iUS?`=mIkR0yzY5-aYLLvAax$0MukQJJ&g`R~vKfJDp6?6Tuvp5{jD2Ov)frlzWAD57D z^0b^wS`u6={tkb&2waEwXP!ni0`3JeX?c#XAOxOy@iC|$i0Qr|FN*VJ(Tad)TW8d7 zS;C$i_y}HlJX5lI`|L9s^CrJVh@!G}ZlX3K_*of9-QaA^u;DmgmJklMn>|5EkCqqb zH{qAB@$m-BePwD_DYcu_z6!S$BuD;xQ0G1V;wtoBkj-7*ljxFjga3PeeO=dqgk|-V zKF+!fPSQ!YnsPCL-jf&`djRRMY~^(7A3(zATJZLSg#k&6yCVrOQCQ)5|{hm)JYXTftr572?QGz2_v>#gaIUxuVir_*Eq0oLN6JCc7-uCwJI3?rvC0FS- zfJiv2%2OpXYQ~2E*%S;U`ehU=^3wV^L}EA;bU52Zb?Q7RBbJ{)_uYe1u-U;GrpIWL zjEG|?F@2ol*6ZQn-#f#?4k?9>qsA!=jVXm(b1jtGm$jfO3J3~b^k3Eoz!5lf3_+j~ z%u(bca+osgDDWXI+nOf+{*9;t5pOWgQ;3Zxu&&lM})PnrWq&;zpoFIV1_bG3&Jgco8 zgVUp4=zv8MhH+jEyuJCFp&>3thETU$9Sk6Ha02tm6CL7#vYluhEYMcQE&jP(7Mq_Y0Wd7 z%7YW$6+10$cYSbpKIDt7Kj-)h)A`fjENjQrX-N+q*{yt5q@kf9b6^8rAO7?yo1Bg| z1kM1jPu9Sx;{2?#+_4QfK?p|^)0;URw<@g~Km#^cjTXy-zdphIoJ1Rb46k#PkO7s8 z#6U|0NBem_XhXr1o|l&wS9^CFYzDS1fr7Rs#!7nLa9RwOzJ%8e-9X2|VF$;Cqqxn_ z$b(K)SX|8COV6A_2hzhB&?iR#n>6J)VlXowKblrrstKq(wv}l!Vfe@G0kn=EdkDRO zH=O*Fkbu9lQ4*uzv2g-S03dMA_#vNr;%!9G0D<>G9rfjZI6o|65);`)?8AYef3MKd z-QE2!Z^s_!&S2cADX$($PEH0E8VI07X3_2!FZkr;+08xzkz$KMefDdDxdA5ws+NwX zW(@e8qkDAci5637|J7Hgsa}(9qw;n;klk@qq7_D`<&t8ieyOzvVH)VHkKL@PIAzR zfQ8(m5gvu3Qer-HilA%5Kmhfgm6wNOWS?MccxM_F)do;X;7*L>1agCo3U08ztf1ie z2Vgz37tmqD0|O)#@P7Qu!ZBWE^w+`xf4YV1?Al+8hqb{Yb5LXee!$Wwd?d;i zaZm>Nb$i~2V=J;6e{i?$#%^3pjP%XDHMjxrXb`GC!Sj*v@!Ie`I6QG{Z*2-(KX`)7 z#0&!P`PFGKYWeJZ!D?s>fP>1R8Q2c+ydJ=TOd*?Qe>nIC=gi@phrJvx?WK8|?fY9> zJ|}bt=>Jz;R~`;!`|pQT_83x@5F?Z%iAjrzQAUJ8p^}iLvZk^nyM}Djki1zVq0QEU zq-+rtr6eRvWl6RqIXR!H_jk^9o$EU9A6@TNW9FIrexC3B{eCw3*dK8bzD4S~JcgY` z4oibFW7Z)d1)^be5>R_2+T(-&m3Z7}fBhODh7g-wpYMS<^6cDD-u-)^0ND4z8xG-Wdpo=8LGO(r z!NCM{tQ;Tz;$5$T*CuqXZ$f>LyOMa8C34!N6Cx{7}iax@kG zia_=sKD%5>suGYQl24FJ0@~}wrE^SqZe6t8#zt@J>LM0)yvBl{PcBl$(5ei|WIJ%4 zv@>=#=)zc6m}*r|pFgkn5$5_gX=kFq^Ko6>QAGCm{=x*Op`if=9H7;k+lO_a8pS67 zY7r2C-&^!T3#?_4{Nh9*p@h`bIry-al^R@7bU&C`&2I>~fZE25U?Q%5*KlG^`DByk zTj@475;1kW+}s^aKVstI>Ob*sRKRR6@|pW%Kn>@595+yaG&J*?636&MW$#n>lUzg25}vvc zTBs$Ywg{kNoBg{Q8ykHzT3mXhq!0@0519C1G&PXERZEen*}Up<{z=aDL=n07q4k_J7ld>u-w0YgH7pma1Xc)=uaTm zU}LA6e%KbNRjXhLi|Br}UR4#fa2OCEX1zS)e?AQjF;0f7EB!wzkGd8Zt+^`C{-3BJ zuJR7oGyvlNw6LwZuU})Irg6s!bG<7&z8~TebggWy8+0B}KRd9HulF5@B;1wefV=wR zb!NuL!7%R>3deU5R10R}3ZbVr{;{Q5ZNXKKCa1UyGZp|L=>GwG==0jeqCtWj39H4W z-t?v5_HBq*8=mjWDLxEKZ&Ff3Vnlc}%s9P|cp_vC{)j*{>rFX#sr`ELjE__+Qc_Pa zWG6a-CRnMNJ0vamP?=_T%`9sUXWA$nwp+LU!uA6S$G6Fvtq4#L!w*bOPgkBA5$pb} zRx`iUkm+X_y|42Bs6g({m;X_L$W(dTl-^vp+m!$N@Fw2h8Dp&4L2tm8A18F$R|+W6 z9*bD!JOCNwXr{xnp=H2g#Sn8o)+djx!Gafu?xq{6gI4y1@#Zqh8ABT=YOp^coYy14 zNTm{^=a0NfWdfE%!_@vcz|^9D73aBN=0L_j$Bu=(Vfo;Mg+yM+i2nWlOBE5fbGOxgC)rCF5kmEHrH0+LkaVJ!1vyfG(i}2$R{fS$MW`%tHeBa)JyZ}}v ziKeNTxNuwB%2b7Odi$QW>(>u@lE;_Rj?tyj%YDw5u)exMVHMevpt+E@MkY&%mzA@N zl-*%Ew1*u#9jx5atK(VC@(ba|rLiR+lq zq2NcNNlLK@QEHJPeRP|p{Bis(jz{2cQcgRLBFX9RYkhK%0i%iL8l%72Y28o=N}|*9 zjycB0u~?XEhK6`vr8lv~GQtccO$%*09S37z;I<@1((M0S$8H+br!^m0ELL@Co;rJp zsB+N)NvB!U5GP;>O#L)NJuIx(DmN~@zkF+2b?Q9#%dxBNm_$matOaP%L}%K3MqBc^ zg5bs8Lg>9R--e^rXN%Du2JX}IQ2tZwV0K&WEcaLmGHP_6wuc>6l$AsFySeW4WM$^S zTuwHlbDJkPk(8B(Fe;XkYd0!F#g5LDA|KWM#`2H61KCSZ2CjD7^_b!JY^IX3e21nlv_&md_Jm!ZExw*Sz?Ah2d&LlyV+kUN#GN|1#mL1*I2Df==z~ z+bhU6djlQam%)-w|2?bOYJJeAWb#TY2JdV6wkSC9;aKu-NiHwfHaC9-6N3MPn|FKY zF-*06NIHRfL2Qdcrdb3x`bdCZ!Kcj!Aqif$??z_Y`(q<&gGw+`fNeu=2m6jnf1IBX zJR5~Fi@t@e>sa-zWq8Y~*5nV)Yw1KWON23@PXU^YWSS2k?>ai3>d;cm5T}@X zLKY7jbRKY4zk6`f*}_8f(zB!m7x@pm4i3mwb2T>?`KecPzIZj|kl~X)*u61T#@hF7 zP*-p3=pd`8Txfa>6(MvTmUkUucx~`RO-)Q>g(~)jg>##xF-iPk*X+TEg7elml`iIf z4$U;WsB000y(IQCx;8#MG?Wuc)i-ah87ii1ok8sbc;M>a*w|I-BO-1}*CHrapc{LK zrqXgoY1nlE;1Ezg%NHF(l2BIFW)8;{tePc4%5`t{?%?A+d7v_nYAI`}K}yz1=a%}B6Va);D` z)Lo8&v8d}1T54%|AmPzgltiNRf*Hkh%c2NTm7);HYe_H0y@NZlz*q024h+gJ_Z&D{ zR_{-Nf`B)SzE=-L8%=jq+OolLVf|J-$|p}w!PWfJIArl89&$OElST6Wetv9&!3ixN zgUD(Kvv4e}xvXMfCJ4}sH+KLrCWvFqOwgP5Ioe%*%BSlsBi(LY4|FJX4r@#Fu|DYL zL0>nX;1K;-5Ifeu4hmNHg_Z^kh}knm8^4Q)MI0KUt-JL2ohoX@sSv%vBwUJM)D*&W z3cEy7wF&#(G>oOjG);+ui!IqSe>@vKf{0QajcQK z)#+FhOShrWScVM?XVyRx32Rkew)5+mAwY}~&Tg;wn*HcOWL&)PPa=9+B%wjrz2=6>MeqNSJM;Y6_!Jr&1ve{3nK@Jg->hzebASDfy@@gL{cZRzxE zU$bSOMKYIRw)<&x(j{lU*$&U`R(R2CEtyoj`Vy>t-jDMv1~ICjh25;BweFOt)5@qH zohgaC?_Z*R-*(HU>=;G{iyutR-;24pNNd*6tA#yx+H&=(&}_Mq3YIAvGOPLayD>AV zE5tKN1-J+A!c@NPHBY*?IkDnqacrm{nrVP9xXt;Q?YyzhYhrT)G!Sk&2+HhluZP>ZQ^g)4{l+RN>Ec#VaI+&SOvAitoZ|Klx3`__F#SBrimJQqrAp zO-5bsy7#rSFN+{T)U*zmn`XxoHO4%6cVY%W0;$$u?GYX~V$4n3hjY-m)~dhUvwON+h4gcnII(N)b+@);-*1 zlsvmT6C0W5y&di4LYbRV#@EU&f32&pp^`-9x=~7uI1;Y6C{ikMx8E98{}I0>-#QLI z`VjYP>$e#(^2}IOK;YQ2j{n*bSoQ7OuaaM>-4DAT0?WXT!S_+;r>UVaFgOS_!$kGc zy5whrljwmfD=Tq!WM9cN0@@0V56YRnL;KO}B8#;T!N}|Bh1oAUB@dqB1CmG(83^F_ z#O=MB?}DvXN=Wog_|o$&@}>4!e~H}@Uvf5C?@;|1=t3N+*u6~Ay|A+o|{7wg#|z5q%-5)?Q??9ii99ZnT9 zZ0a5X#vDOsCc4M&9YKmfDpFx!gtae9VPEFGk`j5LO`4kQtxq(dmNq|s4lAeZ-npmp zvJVc9jg0K6tn!8f7lsQpwFI&|v(XVE1uiCN#fdl;(nFjx&h8tkHZ*H|w3`O-VQhH# ziPttAoe#COIk#>JHh47&WAKLfAgE1AnT1=+9r-da50T^G=<+5@ zweMG-{5fA+OMP;6Y|I_!L|a?-bM+k=GLn*e-hjLo*=@;^*VNL2ZqHmr472COLoSXN z-OfkAX)7JSyVoS2_wOE_9fAhQ)7STYfqPxyGdyyDLnPCGiyl329WkuXbKg`Z)Cyag&ZWj!jk2Vo_jT3V^CTuPwbFdD?X+!OF^yTVYk!4t18n8ZFHkM~gq*}B53KhkK; z@e?PIqyuoJ&a3j;H4qG;6k=Te?W#G<2H$#nW#jrmsn^o3*f%p|8=IP<$t4xQTv0Yr zQQBiW0Df3n>KlCo_Vr@h6#qn-Z0?EN%Yyv;i2J}6<$7CfCj7Y$xNm<(lO^9%e(G6QS0H9T8Yrveo+xg?jLSG~;>e@2@&ayhvAju$L((GyoFJt~EQGFf zObK^e#%V&rbg9e@8?+zkNHesEbJ0j~N4(sgwHe6s6wq~jGl)(Gt>)_+8>V$Xa8QVI zTe8hjdklMGsBhyQXg@gEb91s)K@1cV)X-16!exmzf&}KvrUu7$)Et;)Z=gRbUS-`W zU89D3y{ERi%{usm1ir4ur#n}Np(J?qnYso@6`7o}ioua2v4vpJ_EeLl4M#uXBBKKf z#1vecj|0?v-qLb(hbom?kE>A6PYF!`fD6H0->s+0;X5B5cXPW*k~4L20fe$b5;@F+4JGuH{THV)twtL0m{U$wSA{yZh%@fNkH3wA~c=`h}}+W4-w z9+k)cM*YPgP`Kl1L4bl$tkT6sgnk_|HLbRwoDVC;_OVK?X59rsijZl6tykZ!-@biS zkiF!?QkOl#va|!whc~)|QH28A+uM8kdPsg2ybh?=5Heim<@ORfLr4hs4b@=nx3wLE zQJ3(d3UQo)5UWd+6S}Rw;0hyX|D+5csqNS7?47xELcYZ@50AqK4s0zF*ITFONl0+y zw$8ay13ME^W6+^1AGbDJDJ@-fZXsx&!QwpXrJs*6^dF!+Odx0$B2m$bD zvO@l0azX+udhw-Hp}bYNXF4aA7hOj?WvG*Iz|1TprGDWV!e6E18wzjVUN|SLVl0Ul zy^?E3m@(p`0mBZQ(D^wa;w_#Z0V*ND&ku~KsIsN(E@#{UK2BxnOaG=WZl73Gf=>j* zj7sGHhPrtk)CWZTq)X58*Jd@3uOg7dgW?*+ujS7o@qGkzK)Le zvSN+iX&fYwjBn>eMMef8beb(`yYvi>I$8Qf8Av|i;Q^-NtE|P;8e>BTVIZ{w`bvxeu%`na!u}fy=L6-_B=;yo@0Yh3lJkdGBhME zCYGF<3aLoaVm>j?2VDw#lGV1Sewu(ss2FGI{f+dKO9gTjWgAV^XgQWWX`P3c4iNY=SiyJluy03i>2sn$EfOc8@xZQnx*dQyiqBTBkJr z&?8oGu!4cyx|5n^BbSH|Fu*HkmxjrHB*^kGG>i^WaeKi=hpDqJy=5{Rzyo&1q+9NM zH7~C5hQTYcT!6p-lbRaj>RSuSlucqZ_}zWxLu@~%g=9D$XFY?f1|;>T{qp)$0Ab2i z-x`J5mYmG=CL~Y?c?+8`U-J*mCCWvzlEDB}l$Tp2NeOLr#d}}8%U>pl@dY=4S!Y1Q zq1d=M$N;AAw`jPJx9>j;4axDYv|U>DIOk|uRE*gDq`^!8GtV;(c$5E1I)?3-CNTsbbI@3*aRUiSiY72t$Q%zPCj{HK!V-(Clv3fQm4nd7)PvtWS4n1#E6T*7Bzz*#P+r`470Ivsk$|iR!eT8f8!0w8c z1#jtuFF4bATue+1$eo-7B10isPF&Rhz0m!++cO#WR@APv0;ShMTeZaTtpqG}NEYtfadQAex*#KMKt+T7UairyZgLsb=( z%Co=jG8m1}LFaTv^rrRIeb?&o)mz0>YRHbyEV!)1K{9r%vGb6m5CcyBI6OFQfV5l< zO-=My7ly}fPRB|zKm;5^yGp0)`k+(&=t*W7%wgf2no|;!lXsPl4iBg5oco=VK$Y2P zxyg*v!2ZXYt?B-hHebQ4LniSg{u)>n;cHe(G*IIo86B-W{Z*pKp->OWAP6pKL=jix z$M22;g`uXdo=qi29)Up@Ck}kiI#BHInC)GJMvk_cv4c~V=c}>Ffnl66-utw?8uaNX zl?OZ?LRPH-&<^R4Y=ew6ZDl0JU^MdhRV`1Nn@7R&qthEsKtkPJ1p7g4hi4DnCo(*7 zr^{8fX}Pl$-B(7oQn7NxNaTO+kH4G>xlc76PQ*>szO`w zp*a)VbssF2I72 zgSN}cl6R_%NO%BbRIV@yi}B`PilN z=`|EF^@!11J2<9Z~a^g6|v((gRxH|Auzk@&Dq3Xi+`vP@dF~&)MV&5@%a87 zFvSRwJ^h*g^(*vv*=0+AHh~5L4_N;r&~Z_HLj(L=vKeAR*B@XlS{~}au1{4Pran_-JnU<`Wc6pEQc6ZeqlX*;%&>F3|Gj%a7P2h*# zuye&uI|~YtlSbg_C6LFl@@*oDP_hyPWqYxEA*5g~PlA*$c5;XzGA<)USSsY%tK(<( VMQeA>!#)E3qv`LZ-qN)T{cpp^WxxOc literal 0 HcmV?d00001 diff --git a/docs/modules/13_mission_planning/state_machine/state_machine_main.rst b/docs/modules/13_mission_planning/state_machine/state_machine_main.rst new file mode 100644 index 0000000000..abaece1b11 --- /dev/null +++ b/docs/modules/13_mission_planning/state_machine/state_machine_main.rst @@ -0,0 +1,74 @@ +State Machine +------------- + +A state machine is a model used to describe the transitions of an object between different states. It clearly shows how an object changes state based on events and may trigger corresponding actions. + +Core Concepts +~~~~~~~~~~~~~ + +- **State**: A distinct mode or condition of the system (e.g. "Idle", "Running"). Managed by State class with optional on_enter/on_exit callbacks +- **Event**: A trigger signal that may cause state transitions (e.g. "start", "stop") +- **Transition**: A state change path from source to destination state triggered by an event +- **Action**: An operation executed during transition (before entering new state) +- **Guard**: A precondition that must be satisfied to allow transition + +API +~~~ + +.. autoclass:: MissionPlanning.StateMachine.state_machine.StateMachine + :members: add_transition, process, register_state + :special-members: __init__ + +PlantUML Support +~~~~~~~~~~~~~~~~ + +The ``generate_plantuml()`` method creates diagrams showing: + +- Current state (marked with [*] arrow) +- All possible transitions +- Guard conditions in [brackets] +- Actions prefixed with / + +Example +~~~~~~~ + +state machine diagram: ++++++++++++++++++++++++ +.. image:: robot_behavior_case.png + +state transition table: ++++++++++++++++++++++++ +.. list-table:: State Transitions + :header-rows: 1 + :widths: 20 15 20 20 20 + + * - Source State + - Event + - Target State + - Guard + - Action + * - patrolling + - detect_task + - executing_task + - + - + * - executing_task + - task_complete + - patrolling + - + - reset_task + * - executing_task + - low_battery + - returning_to_base + - is_battery_low + - + * - returning_to_base + - reach_base + - charging + - + - + * - charging + - charge_complete + - patrolling + - + - \ No newline at end of file diff --git a/tests/test_state_machine.py b/tests/test_state_machine.py new file mode 100644 index 0000000000..e36a8120fd --- /dev/null +++ b/tests/test_state_machine.py @@ -0,0 +1,51 @@ +import conftest + +from MissionPlanning.StateMachine.state_machine import StateMachine + + +def test_transition(): + sm = StateMachine("state_machine") + sm.add_transition(src_state="idle", event="start", dst_state="running") + sm.set_current_state("idle") + sm.process("start") + assert sm.get_current_state().name == "running" + + +def test_guard(): + class Model: + def can_start(self): + return False + + sm = StateMachine("state_machine", Model()) + sm.add_transition( + src_state="idle", event="start", dst_state="running", guard="can_start" + ) + sm.set_current_state("idle") + sm.process("start") + assert sm.get_current_state().name == "idle" + + +def test_action(): + class Model: + def on_start(self): + self.start_called = True + + model = Model() + sm = StateMachine("state_machine", model) + sm.add_transition( + src_state="idle", event="start", dst_state="running", action="on_start" + ) + sm.set_current_state("idle") + sm.process("start") + assert model.start_called + + +def test_plantuml(): + sm = StateMachine("state_machine") + sm.add_transition(src_state="idle", event="start", dst_state="running") + sm.set_current_state("idle") + assert sm.generate_plantuml() + + +if __name__ == "__main__": + conftest.run_this_test(__file__) From 346037a6e2362ed17870928ccf26992b60b0e54c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 4 Mar 2025 07:26:47 +0900 Subject: [PATCH 870/940] build(deps): bump pytest from 8.3.4 to 8.3.5 in /requirements (#1178) Bumps [pytest](https://github.com/pytest-dev/pytest) from 8.3.4 to 8.3.5. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/8.3.4...8.3.5) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b439ea4266..b46a0e41f1 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 2.2.3 scipy == 1.15.2 matplotlib == 3.10.0 cvxpy == 1.5.3 -pytest == 8.3.4 # For unit test +pytest == 8.3.5 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.15.0 # For unit test ruff == 0.9.7 # For unit test From cd09abd5e00ca29d15f42c539121cf62751ecd52 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 4 Mar 2025 12:21:33 +0900 Subject: [PATCH 871/940] build(deps): bump ruff from 0.9.7 to 0.9.9 in /requirements (#1179) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.9.7 to 0.9.9. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.9.7...0.9.9) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b46a0e41f1..3e2a1e7c7c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.5 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.15.0 # For unit test -ruff == 0.9.7 # For unit test +ruff == 0.9.9 # For unit test From 5f3be9bccd6366493ea8d159ceeae26d55ed5250 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 4 Mar 2025 12:52:57 +0900 Subject: [PATCH 872/940] build(deps): bump matplotlib from 3.10.0 to 3.10.1 in /requirements (#1181) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.10.0 to 3.10.1. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.10.0...v3.10.1) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 3e2a1e7c7c..552bf8482b 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 2.2.3 scipy == 1.15.2 -matplotlib == 3.10.0 +matplotlib == 3.10.1 cvxpy == 1.5.3 pytest == 8.3.5 # For unit test pytest-xdist == 3.6.1 # For unit test From 30a61add126e2c21c035d50a7a448ed8eb06afb0 Mon Sep 17 00:00:00 2001 From: Surya Singh <133056660+spnsingh@users.noreply.github.com> Date: Fri, 7 Mar 2025 09:01:37 -0500 Subject: [PATCH 873/940] bug: fix typo on line 6 of SpaceTimeAStar.py (#1182) * bug: fix typo on line 6 of SpaceTimeAStar.py * bug: removed extra line return on line 11 of SpaceTimeAStar.py --- PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py b/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py index 3b3613d695..a7aed41869 100644 --- a/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py +++ b/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py @@ -3,7 +3,7 @@ This script demonstrates the Space-time A* algorithm for path planning in a grid world with moving obstacles. This algorithm is different from normal 2D A* in one key way - the cost (often notated as g(n)) is the number of time steps it took to get to a given node, instead of the number of cells it has - traversed. This ensures the path is time-optimal, while respescting any dynamic obstacles in the environment. + traversed. This ensures the path is time-optimal, while respecting any dynamic obstacles in the environment. Reference: https://www.davidsilver.uk/wp-content/uploads/2020/03/coop-path-AIWisdom.pdf """ From fc160179c06cb4b57f821d83a9bdcf192379bd72 Mon Sep 17 00:00:00 2001 From: Aglargil <34728006+Aglargil@users.noreply.github.com> Date: Sat, 8 Mar 2025 18:26:23 +0800 Subject: [PATCH 874/940] feat: add behavior tree (#1177) * feat: add behavior tree * feat: add behavior tree test * feat: add behavior tree doc * feat: add behavior tree update --- MissionPlanning/BehaviorTree/behavior_tree.py | 690 ++++++++++++++++++ .../BehaviorTree/robot_behavior_case.py | 247 +++++++ .../BehaviorTree/robot_behavior_tree.xml | 57 ++ .../behavior_tree/behavior_tree_main.rst | 104 +++ .../behavior_tree/robot_behavior_case.svg | 22 + .../mission_planning_main.rst | 1 + tests/test_behavior_tree.py | 207 ++++++ 7 files changed, 1328 insertions(+) create mode 100644 MissionPlanning/BehaviorTree/behavior_tree.py create mode 100644 MissionPlanning/BehaviorTree/robot_behavior_case.py create mode 100644 MissionPlanning/BehaviorTree/robot_behavior_tree.xml create mode 100644 docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst create mode 100644 docs/modules/13_mission_planning/behavior_tree/robot_behavior_case.svg create mode 100644 tests/test_behavior_tree.py diff --git a/MissionPlanning/BehaviorTree/behavior_tree.py b/MissionPlanning/BehaviorTree/behavior_tree.py new file mode 100644 index 0000000000..59f4c713f1 --- /dev/null +++ b/MissionPlanning/BehaviorTree/behavior_tree.py @@ -0,0 +1,690 @@ +""" +Behavior Tree + +author: Wang Zheng (@Aglargil) + +Ref: + +- [Behavior Tree](https://en.wikipedia.org/wiki/Behavior_tree_(artificial_intelligence,_robotics_and_control)) +""" + +import time +import xml.etree.ElementTree as ET +from enum import Enum + + +class Status(Enum): + SUCCESS = "success" + FAILURE = "failure" + RUNNING = "running" + + +class NodeType(Enum): + CONTROL_NODE = "ControlNode" + ACTION_NODE = "ActionNode" + DECORATOR_NODE = "DecoratorNode" + + +class Node: + """ + Base class for all nodes in a behavior tree. + """ + + def __init__(self, name): + self.name = name + self.status = None + + def tick(self) -> Status: + """ + Tick the node. + + Returns: + Status: The status of the node. + """ + raise ValueError("Node is not implemented") + + def tick_and_set_status(self) -> Status: + """ + Tick the node and set the status. + + Returns: + Status: The status of the node. + """ + self.status = self.tick() + return self.status + + def reset(self): + """ + Reset the node. + """ + self.status = None + + def reset_children(self): + """ + Reset the children of the node. + """ + pass + + +class ControlNode(Node): + """ + Base class for all control nodes in a behavior tree. + + Control nodes manage the execution flow of their child nodes according to specific rules. + They typically have multiple children and determine which children to execute and in what order. + """ + + def __init__(self, name): + super().__init__(name) + self.children = [] + self.type = NodeType.CONTROL_NODE + + def not_set_children_raise_error(self): + if len(self.children) == 0: + raise ValueError("Children are not set") + + def reset_children(self): + for child in self.children: + child.reset() + + +class SequenceNode(ControlNode): + """ + Executes child nodes in sequence until one fails or all succeed. + + Returns: + - Returns FAILURE if any child returns FAILURE + - Returns SUCCESS when all children have succeeded + - Returns RUNNING when a child is still running or when moving to the next child + + Example: + .. code-block:: xml + + + + + + """ + + def __init__(self, name): + super().__init__(name) + self.current_child_index = 0 + + def tick(self) -> Status: + self.not_set_children_raise_error() + + if self.current_child_index >= len(self.children): + self.reset_children() + return Status.SUCCESS + status = self.children[self.current_child_index].tick_and_set_status() + if status == Status.FAILURE: + self.reset_children() + return Status.FAILURE + elif status == Status.SUCCESS: + self.current_child_index += 1 + return Status.RUNNING + elif status == Status.RUNNING: + return Status.RUNNING + else: + raise ValueError("Unknown status") + + +class SelectorNode(ControlNode): + """ + Executes child nodes in sequence until one succeeds or all fail. + + Returns: + - Returns SUCCESS if any child returns SUCCESS + - Returns FAILURE when all children have failed + - Returns RUNNING when a child is still running or when moving to the next child + + Examples: + .. code-block:: xml + + + + + + """ + + def __init__(self, name): + super().__init__(name) + self.current_child_index = 0 + + def tick(self) -> Status: + self.not_set_children_raise_error() + + if self.current_child_index >= len(self.children): + self.reset_children() + return Status.FAILURE + status = self.children[self.current_child_index].tick_and_set_status() + if status == Status.SUCCESS: + self.reset_children() + return Status.SUCCESS + elif status == Status.FAILURE: + self.current_child_index += 1 + return Status.RUNNING + elif status == Status.RUNNING: + return Status.RUNNING + else: + raise ValueError("Unknown status") + + +class WhileDoElseNode(ControlNode): + """ + Conditional execution node with three parts: condition, do, and optional else. + + Returns: + First executes the condition node (child[0]) + If condition succeeds, executes do node (child[1]) and returns RUNNING + If condition fails, executes else node (child[2]) if present and returns result of else node + If condition fails and there is no else node, returns SUCCESS + + Example: + .. code-block:: xml + + + + + + + """ + + def __init__(self, name): + super().__init__(name) + + def tick(self) -> Status: + if len(self.children) != 3 and len(self.children) != 2: + raise ValueError("WhileDoElseNode must have exactly 3 or 2 children") + + condition_node = self.children[0] + do_node = self.children[1] + else_node = self.children[2] if len(self.children) == 3 else None + + condition_status = condition_node.tick_and_set_status() + if condition_status == Status.SUCCESS: + do_node.tick_and_set_status() + return Status.RUNNING + elif condition_status == Status.FAILURE: + if else_node is not None: + else_status = else_node.tick_and_set_status() + if else_status == Status.SUCCESS: + self.reset_children() + return Status.SUCCESS + elif else_status == Status.FAILURE: + self.reset_children() + return Status.FAILURE + elif else_status == Status.RUNNING: + return Status.RUNNING + else: + raise ValueError("Unknown status") + else: + self.reset_children() + return Status.SUCCESS + else: + raise ValueError("Unknown status") + + +class ActionNode(Node): + """ + Base class for all action nodes in a behavior tree. + + Action nodes are responsible for performing specific tasks or actions. + They do not have children and are typically used to execute logic or operations. + """ + + def __init__(self, name): + super().__init__(name) + self.type = NodeType.ACTION_NODE + + +class SleepNode(ActionNode): + """ + Sleep node that sleeps for a specified duration. + + Returns: + Returns SUCCESS after the specified duration has passed + Returns RUNNING if the duration has not yet passed + + Example: + .. code-block:: xml + + + """ + + def __init__(self, name, duration): + super().__init__(name) + self.duration = duration + self.start_time = None + + def tick(self) -> Status: + if self.start_time is None: + self.start_time = time.time() + if time.time() - self.start_time > self.duration: + return Status.SUCCESS + return Status.RUNNING + + +class EchoNode(ActionNode): + """ + Echo node that prints a message to the console. + + Returns: + Returns SUCCESS after the message has been printed + + Example: + .. code-block:: xml + + + """ + + def __init__(self, name, message): + super().__init__(name) + self.message = message + + def tick(self) -> Status: + print(self.name, self.message) + return Status.SUCCESS + + +class DecoratorNode(Node): + """ + Base class for all decorator nodes in a behavior tree. + + Decorator nodes modify the behavior of their child node. + They must have a single child and can alter the status of the child node. + """ + + def __init__(self, name): + super().__init__(name) + self.type = NodeType.DECORATOR_NODE + self.child = None + + def not_set_child_raise_error(self): + if self.child is None: + raise ValueError("Child is not set") + + def reset_children(self): + self.child.reset() + + +class InverterNode(DecoratorNode): + """ + Inverter node that inverts the status of its child node. + + Returns: + - Returns SUCCESS if the child returns FAILURE + - Returns FAILURE if the child returns SUCCESS + - Returns RUNNING if the child returns RUNNING + + Examples: + .. code-block:: xml + + + + + """ + + def __init__(self, name): + super().__init__(name) + + def tick(self) -> Status: + self.not_set_child_raise_error() + status = self.child.tick_and_set_status() + return Status.SUCCESS if status == Status.FAILURE else Status.FAILURE + + +class TimeoutNode(DecoratorNode): + """ + Timeout node that fails if the child node takes too long to execute + + Returns: + - FAILURE: If the timeout duration has been exceeded + - Child's status: Otherwise, passes through the status of the child node + + Example: + .. code-block:: xml + + + + + """ + + def __init__(self, name, timeout): + super().__init__(name) + self.timeout = timeout + self.start_time = None + + def tick(self) -> Status: + self.not_set_child_raise_error() + if self.start_time is None: + self.start_time = time.time() + if time.time() - self.start_time > self.timeout: + return Status.FAILURE + print(f"{self.name} is running") + return self.child.tick_and_set_status() + + +class DelayNode(DecoratorNode): + """ + Delay node that delays the execution of its child node for a specified duration. + + Returns: + - Returns RUNNING if the duration has not yet passed + - Returns child's status after the duration has passed + + Example: + .. code-block:: xml + + + + + """ + + def __init__(self, name, delay): + super().__init__(name) + self.delay = delay + self.start_time = None + + def tick(self) -> Status: + self.not_set_child_raise_error() + if self.start_time is None: + self.start_time = time.time() + if time.time() - self.start_time > self.delay: + return self.child.tick_and_set_status() + return Status.RUNNING + + +class ForceSuccessNode(DecoratorNode): + """ + ForceSuccess node that always returns SUCCESS. + + Returns: + - Returns RUNNING if the child returns RUNNING + - Returns SUCCESS if the child returns SUCCESS or FAILURE + """ + + def __init__(self, name): + super().__init__(name) + + def tick(self) -> Status: + self.not_set_child_raise_error() + status = self.child.tick_and_set_status() + if status == Status.FAILURE: + return Status.SUCCESS + return status + + +class ForceFailureNode(DecoratorNode): + """ + ForceFailure node that always returns FAILURE. + + Returns: + - Returns RUNNING if the child returns RUNNING + - Returns FAILURE if the child returns SUCCESS or FAILURE + """ + + def __init__(self, name): + super().__init__(name) + + def tick(self) -> Status: + self.not_set_child_raise_error() + status = self.child.tick_and_set_status() + if status == Status.SUCCESS: + return Status.FAILURE + return status + + +class BehaviorTree: + """ + Behavior tree class that manages the execution of a behavior tree. + """ + + def __init__(self, root): + self.root = root + + def tick(self): + """ + Tick once on the behavior tree. + """ + self.root.tick_and_set_status() + + def reset(self): + """ + Reset the behavior tree. + """ + self.root.reset() + + def tick_while_running(self, interval=None, enable_print=True): + """ + Tick the behavior tree while it is running. + + Args: + interval (float, optional): The interval between ticks. Defaults to None. + enable_print (bool, optional): Whether to print the behavior tree. Defaults to True. + """ + while self.root.tick_and_set_status() == Status.RUNNING: + if enable_print: + self.print_tree() + if interval is not None: + time.sleep(interval) + if enable_print: + self.print_tree() + + def to_text(self, root, indent=0): + """ + Recursively convert the behavior tree to a text representation. + """ + current_text = "" + if root.status == Status.RUNNING: + # yellow + current_text = "\033[93m" + root.name + "\033[0m" + elif root.status == Status.SUCCESS: + # green + current_text = "\033[92m" + root.name + "\033[0m" + elif root.status == Status.FAILURE: + # red + current_text = "\033[91m" + root.name + "\033[0m" + else: + current_text = root.name + if root.type == NodeType.CONTROL_NODE: + current_text = " " * indent + "[" + current_text + "]\n" + for child in root.children: + current_text += self.to_text(child, indent + 2) + elif root.type == NodeType.DECORATOR_NODE: + current_text = " " * indent + "(" + current_text + ")\n" + current_text += self.to_text(root.child, indent + 2) + elif root.type == NodeType.ACTION_NODE: + current_text = " " * indent + "<" + current_text + ">\n" + return current_text + + def print_tree(self): + """ + Print the behavior tree. + + Node print format: + Action: + Decorator: (Decorator) + Control: [Control] + + Node status colors: + Yellow: RUNNING + Green: SUCCESS + Red: FAILURE + """ + text = self.to_text(self.root) + text = text.strip() + print("\033[94m" + "Behavior Tree" + "\033[0m") + print(text) + print("\033[94m" + "Behavior Tree" + "\033[0m") + + +class BehaviorTreeFactory: + """ + Factory class for creating behavior trees from XML strings. + """ + + def __init__(self): + self.node_builders = {} + # Control nodes + self.register_node_builder( + "Sequence", + lambda node: SequenceNode(node.attrib.get("name", SequenceNode.__name__)), + ) + self.register_node_builder( + "Selector", + lambda node: SelectorNode(node.attrib.get("name", SelectorNode.__name__)), + ) + self.register_node_builder( + "WhileDoElse", + lambda node: WhileDoElseNode( + node.attrib.get("name", WhileDoElseNode.__name__) + ), + ) + # Decorator nodes + self.register_node_builder( + "Inverter", + lambda node: InverterNode(node.attrib.get("name", InverterNode.__name__)), + ) + self.register_node_builder( + "Timeout", + lambda node: TimeoutNode( + node.attrib.get("name", SelectorNode.__name__), + float(node.attrib["sec"]), + ), + ) + self.register_node_builder( + "Delay", + lambda node: DelayNode( + node.attrib.get("name", DelayNode.__name__), + float(node.attrib["sec"]), + ), + ) + self.register_node_builder( + "ForceSuccess", + lambda node: ForceSuccessNode( + node.attrib.get("name", ForceSuccessNode.__name__) + ), + ) + self.register_node_builder( + "ForceFailure", + lambda node: ForceFailureNode( + node.attrib.get("name", ForceFailureNode.__name__) + ), + ) + # Action nodes + self.register_node_builder( + "Sleep", + lambda node: SleepNode( + node.attrib.get("name", SleepNode.__name__), + float(node.attrib["sec"]), + ), + ) + self.register_node_builder( + "Echo", + lambda node: EchoNode( + node.attrib.get("name", EchoNode.__name__), + node.attrib["message"], + ), + ) + + def register_node_builder(self, node_name, builder): + """ + Register a builder for a node + + Args: + node_name (str): The name of the node. + builder (function): The builder function. + + Example: + .. code-block:: python + + factory = BehaviorTreeFactory() + factory.register_node_builder( + "MyNode", + lambda node: MyNode( + node.attrib.get("name", MyNode.__name__), + node.attrib["my_param"], + ), + ) + """ + self.node_builders[node_name] = builder + + def build_node(self, node): + """ + Build a node from an XML element. + + Args: + node (Element): The XML element to build the node from. + + Returns: + BehaviorTree Node: the built node + """ + if node.tag in self.node_builders: + root = self.node_builders[node.tag](node) + if root.type == NodeType.CONTROL_NODE: + if len(node) <= 0: + raise ValueError(f"{root.name} Control node must have children") + for child in node: + root.children.append(self.build_node(child)) + elif root.type == NodeType.DECORATOR_NODE: + if len(node) != 1: + raise ValueError( + f"{root.name} Decorator node must have exactly one child" + ) + root.child = self.build_node(node[0]) + elif root.type == NodeType.ACTION_NODE: + if len(node) != 0: + raise ValueError(f"{root.name} Action node must have no children") + return root + else: + raise ValueError(f"Unknown node type: {node.tag}") + + def build_tree(self, xml_string): + """ + Build a behavior tree from an XML string. + + Args: + xml_string (str): The XML string containing the behavior tree. + + Returns: + BehaviorTree: The behavior tree. + """ + xml_tree = ET.fromstring(xml_string) + root = self.build_node(xml_tree) + return BehaviorTree(root) + + def build_tree_from_file(self, file_path): + """ + Build a behavior tree from a file. + + Args: + file_path (str): The path to the file containing the behavior tree. + + Returns: + BehaviorTree: The behavior tree. + """ + with open(file_path) as file: + xml_string = file.read() + return self.build_tree(xml_string) + + +xml_string = """ + + + + + + + + """ + + +def main(): + factory = BehaviorTreeFactory() + tree = factory.build_tree(xml_string) + tree.tick_while_running() + + +if __name__ == "__main__": + main() diff --git a/MissionPlanning/BehaviorTree/robot_behavior_case.py b/MissionPlanning/BehaviorTree/robot_behavior_case.py new file mode 100644 index 0000000000..6c39aa76b2 --- /dev/null +++ b/MissionPlanning/BehaviorTree/robot_behavior_case.py @@ -0,0 +1,247 @@ +""" +Robot Behavior Tree Case + +This file demonstrates how to use a behavior tree to control robot behavior. +""" + +from behavior_tree import ( + BehaviorTreeFactory, + Status, + ActionNode, +) +import time +import random +import os + + +class CheckBatteryNode(ActionNode): + """ + Node to check robot battery level + + If battery level is below threshold, returns FAILURE, otherwise returns SUCCESS + """ + + def __init__(self, name, threshold=20): + super().__init__(name) + self.threshold = threshold + self.battery_level = 100 # Initial battery level is 100% + + def tick(self): + # Simulate battery level decreasing + self.battery_level -= random.randint(1, 5) + print(f"Current battery level: {self.battery_level}%") + + if self.battery_level <= self.threshold: + return Status.FAILURE + return Status.SUCCESS + + +class ChargeBatteryNode(ActionNode): + """ + Node to charge the robot's battery + """ + + def __init__(self, name, charge_rate=10): + super().__init__(name) + self.charge_rate = charge_rate + self.charging_time = 0 + + def tick(self): + # Simulate charging process + if self.charging_time == 0: + print("Starting to charge...") + + self.charging_time += 1 + charge_amount = self.charge_rate * self.charging_time + + if charge_amount >= 100: + print("Charging complete! Battery level: 100%") + self.charging_time = 0 + return Status.SUCCESS + else: + print(f"Charging in progress... Battery level: {min(charge_amount, 100)}%") + return Status.RUNNING + + +class MoveToPositionNode(ActionNode): + """ + Node to move to a specified position + """ + + def __init__(self, name, position, move_duration=2): + super().__init__(name) + self.position = position + self.move_duration = move_duration + self.start_time = None + + def tick(self): + if self.start_time is None: + self.start_time = time.time() + print(f"Starting movement to position {self.position}") + + elapsed_time = time.time() - self.start_time + + if elapsed_time >= self.move_duration: + print(f"Arrived at position {self.position}") + self.start_time = None + return Status.SUCCESS + else: + print( + f"Moving to position {self.position}... {int(elapsed_time / self.move_duration * 100)}% complete" + ) + return Status.RUNNING + + +class DetectObstacleNode(ActionNode): + """ + Node to detect obstacles + """ + + def __init__(self, name, obstacle_probability=0.3): + super().__init__(name) + self.obstacle_probability = obstacle_probability + + def tick(self): + # Use random probability to simulate obstacle detection + if random.random() < self.obstacle_probability: + print("Obstacle detected!") + return Status.SUCCESS + else: + print("No obstacle detected") + return Status.FAILURE + + +class AvoidObstacleNode(ActionNode): + """ + Node to avoid obstacles + """ + + def __init__(self, name, avoid_duration=1.5): + super().__init__(name) + self.avoid_duration = avoid_duration + self.start_time = None + + def tick(self): + if self.start_time is None: + self.start_time = time.time() + print("Starting obstacle avoidance...") + + elapsed_time = time.time() - self.start_time + + if elapsed_time >= self.avoid_duration: + print("Obstacle avoidance complete") + self.start_time = None + return Status.SUCCESS + else: + print("Avoiding obstacle...") + return Status.RUNNING + + +class PerformTaskNode(ActionNode): + """ + Node to perform a specific task + """ + + def __init__(self, name, task_name, task_duration=3): + super().__init__(name) + self.task_name = task_name + self.task_duration = task_duration + self.start_time = None + + def tick(self): + if self.start_time is None: + self.start_time = time.time() + print(f"Starting task: {self.task_name}") + + elapsed_time = time.time() - self.start_time + + if elapsed_time >= self.task_duration: + print(f"Task complete: {self.task_name}") + self.start_time = None + return Status.SUCCESS + else: + print( + f"Performing task: {self.task_name}... {int(elapsed_time / self.task_duration * 100)}% complete" + ) + return Status.RUNNING + + +def create_robot_behavior_tree(): + """ + Create robot behavior tree + """ + + factory = BehaviorTreeFactory() + + # Register custom nodes + factory.register_node_builder( + "CheckBattery", + lambda node: CheckBatteryNode( + node.attrib.get("name", "CheckBattery"), + int(node.attrib.get("threshold", "20")), + ), + ) + + factory.register_node_builder( + "ChargeBattery", + lambda node: ChargeBatteryNode( + node.attrib.get("name", "ChargeBattery"), + int(node.attrib.get("charge_rate", "10")), + ), + ) + + factory.register_node_builder( + "MoveToPosition", + lambda node: MoveToPositionNode( + node.attrib.get("name", "MoveToPosition"), + node.attrib.get("position", "Unknown Position"), + float(node.attrib.get("move_duration", "2")), + ), + ) + + factory.register_node_builder( + "DetectObstacle", + lambda node: DetectObstacleNode( + node.attrib.get("name", "DetectObstacle"), + float(node.attrib.get("obstacle_probability", "0.3")), + ), + ) + + factory.register_node_builder( + "AvoidObstacle", + lambda node: AvoidObstacleNode( + node.attrib.get("name", "AvoidObstacle"), + float(node.attrib.get("avoid_duration", "1.5")), + ), + ) + + factory.register_node_builder( + "PerformTask", + lambda node: PerformTaskNode( + node.attrib.get("name", "PerformTask"), + node.attrib.get("task_name", "Unknown Task"), + float(node.attrib.get("task_duration", "3")), + ), + ) + # Read XML from file + xml_path = os.path.join(os.path.dirname(__file__), "robot_behavior_tree.xml") + return factory.build_tree_from_file(xml_path) + + +def main(): + """ + Main function: Create and run the robot behavior tree + """ + print("Creating robot behavior tree...") + tree = create_robot_behavior_tree() + + print("\nStarting robot behavior tree execution...\n") + # Run for a period of time or until completion + + tree.tick_while_running(interval=0.01) + + print("\nBehavior tree execution complete!") + + +if __name__ == "__main__": + main() diff --git a/MissionPlanning/BehaviorTree/robot_behavior_tree.xml b/MissionPlanning/BehaviorTree/robot_behavior_tree.xml new file mode 100644 index 0000000000..0bca76a3ff --- /dev/null +++ b/MissionPlanning/BehaviorTree/robot_behavior_tree.xml @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst b/docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst new file mode 100644 index 0000000000..ae3e16da81 --- /dev/null +++ b/docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst @@ -0,0 +1,104 @@ +Behavior Tree +------------- + +Behavior Tree is a modular, hierarchical decision model that is widely used in robot control, and game development. +It present some similarities to hierarchical state machines with the key difference that the main building block of a behavior is a task rather than a state. +Behavior Tree have been shown to generalize several other control architectures (https://ieeexplore.ieee.org/document/7790863) + +Core Concepts +~~~~~~~~~~~~~ + +Control Node +++++++++++++ + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.ControlNode + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.SequenceNode + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.SelectorNode + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.WhileDoElseNode + +Action Node +++++++++++++ + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.ActionNode + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.EchoNode + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.SleepNode + +Decorator Node +++++++++++++++ + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.DecoratorNode + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.InverterNode + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.TimeoutNode + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.DelayNode + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.ForceSuccessNode + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.ForceFailureNode + +Behavior Tree Factory ++++++++++++++++++++++ + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.BehaviorTreeFactory + :members: + +Behavior Tree ++++++++++++++ + +.. autoclass:: MissionPlanning.BehaviorTree.behavior_tree.BehaviorTree + :members: + +Example +~~~~~~~ + +Visualize the behavior tree by `xml-tree-visual `_. + +.. image:: ./robot_behavior_case.svg + +Print the behavior tree + +.. code-block:: text + + Behavior Tree + [Robot Main Controller] + [Battery Management] + (Low Battery Detection) + + + + [Patrol Task] + + [Move to Position A] + + [Obstacle Handling A] + [Obstacle Present] + + + + + [Move to Position B] + (Short Wait) + + + (Limited Time Obstacle Handling) + [Obstacle Present] + + + + [Conditional Move to C] + + [Perform Position C Task] + + (Ensure Completion) + + + + + Behavior Tree diff --git a/docs/modules/13_mission_planning/behavior_tree/robot_behavior_case.svg b/docs/modules/13_mission_planning/behavior_tree/robot_behavior_case.svg new file mode 100644 index 0000000000..a3d43aed52 --- /dev/null +++ b/docs/modules/13_mission_planning/behavior_tree/robot_behavior_case.svg @@ -0,0 +1,22 @@ +Selectorname: Robot Main ControllerSequencename: Battery ManagementSequencename: Patrol TaskInvertername: Low Battery DetectionEchoname: Low Battery Warningmessage: Battery level low!Charging neededChargeBatteryname: Charge Batterycharge_rate: 20Echoname: Start Taskmessage: Starting patrol taskSequencename: Move to Position ASequencename: Move to Position BWhileDoElsename: Conditional Move to CEchoname: Complete Patrolmessage: Patrol taskcompleted, returning tocharging stationMoveToPositionname: Return to ChargingStationposition: Charging Stationmove_duration: 4CheckBatteryname: Check Batterythreshold: 30MoveToPositionname: Move to Aposition: Amove_duration: 2Selectorname: Obstacle Handling APerformTaskname: Position A Tasktask_name: Check Device Statustask_duration: 2Delayname: Short Waitsec: 1MoveToPositionname: Move to Bposition: Bmove_duration: 3Timeoutname: Limited Time ObstacleHandlingsec: 2PerformTaskname: Position B Tasktask_name: Data Collectiontask_duration: 2.5CheckBatteryname: Check Sufficient Batterythreshold: 50Sequencename: Perform Position C TaskEchoname: Skip Position Cmessage: Insufficient power,skipping position C taskSequencename: Obstacle PresentEchoname: No Obstaclemessage: Path clearEchoname: Prepare Movementmessage: Preparing to move tonext positionSequencename: Obstacle PresentMoveToPositionname: Move to Cposition: Cmove_duration: 2.5ForceSuccessname: Ensure CompletionDetectObstaclename: Detect Obstacleobstacle_probability: 0.3AvoidObstaclename: Avoid Obstacleavoid_duration: 1.5DetectObstaclename: Detect Obstacleobstacle_probability: 0.4AvoidObstaclename: Avoid Obstacleavoid_duration: 1.8PerformTaskname: Position C Tasktask_name: EnvironmentMonitoringtask_duration: 2 \ No newline at end of file diff --git a/docs/modules/13_mission_planning/mission_planning_main.rst b/docs/modules/13_mission_planning/mission_planning_main.rst index 385e62f68e..c35eacd8d5 100644 --- a/docs/modules/13_mission_planning/mission_planning_main.rst +++ b/docs/modules/13_mission_planning/mission_planning_main.rst @@ -10,3 +10,4 @@ Mission planning includes tools such as finite state machines and behavior trees :caption: Contents state_machine/state_machine + behavior_tree/behavior_tree diff --git a/tests/test_behavior_tree.py b/tests/test_behavior_tree.py new file mode 100644 index 0000000000..0898690448 --- /dev/null +++ b/tests/test_behavior_tree.py @@ -0,0 +1,207 @@ +import pytest +import conftest + +from MissionPlanning.BehaviorTree.behavior_tree import ( + BehaviorTreeFactory, + Status, + ActionNode, +) + + +def test_sequence_node1(): + xml_string = """ + + + + + + + + """ + bt_factory = BehaviorTreeFactory() + bt = bt_factory.build_tree(xml_string) + bt.tick() + assert bt.root.status == Status.RUNNING + assert bt.root.children[0].status == Status.SUCCESS + assert bt.root.children[1].status is None + assert bt.root.children[2].status is None + bt.tick() + bt.tick() + assert bt.root.status == Status.FAILURE + assert bt.root.children[0].status is None + assert bt.root.children[1].status is None + assert bt.root.children[2].status is None + + +def test_sequence_node2(): + xml_string = """ + + + + + + + + """ + bt_factory = BehaviorTreeFactory() + bt = bt_factory.build_tree(xml_string) + bt.tick_while_running() + assert bt.root.status == Status.SUCCESS + assert bt.root.children[0].status is None + assert bt.root.children[1].status is None + assert bt.root.children[2].status is None + + +def test_selector_node1(): + xml_string = """ + + + + + + + + """ + bt_factory = BehaviorTreeFactory() + bt = bt_factory.build_tree(xml_string) + bt.tick() + assert bt.root.status == Status.RUNNING + assert bt.root.children[0].status == Status.FAILURE + assert bt.root.children[1].status is None + assert bt.root.children[2].status is None + bt.tick() + assert bt.root.status == Status.SUCCESS + assert bt.root.children[0].status is None + assert bt.root.children[1].status is None + assert bt.root.children[2].status is None + + +def test_selector_node2(): + xml_string = """ + + + + + + + + + """ + bt_factory = BehaviorTreeFactory() + bt = bt_factory.build_tree(xml_string) + bt.tick_while_running() + assert bt.root.status == Status.FAILURE + assert bt.root.children[0].status is None + assert bt.root.children[1].status is None + + +def test_while_do_else_node(): + xml_string = """ + + + + + + """ + + class CountNode(ActionNode): + def __init__(self, name, count_threshold): + super().__init__(name) + self.count = 0 + self.count_threshold = count_threshold + + def tick(self): + self.count += 1 + if self.count >= self.count_threshold: + return Status.FAILURE + else: + return Status.SUCCESS + + bt_factory = BehaviorTreeFactory() + bt_factory.register_node_builder( + "Count", + lambda node: CountNode( + node.attrib.get("name", CountNode.__name__), + int(node.attrib["count_threshold"]), + ), + ) + bt = bt_factory.build_tree(xml_string) + bt.tick() + assert bt.root.status == Status.RUNNING + assert bt.root.children[0].status == Status.SUCCESS + assert bt.root.children[1].status is Status.SUCCESS + assert bt.root.children[2].status is None + bt.tick() + assert bt.root.status == Status.RUNNING + assert bt.root.children[0].status == Status.SUCCESS + assert bt.root.children[1].status is Status.SUCCESS + assert bt.root.children[2].status is None + bt.tick() + assert bt.root.status == Status.SUCCESS + assert bt.root.children[0].status is None + assert bt.root.children[1].status is None + assert bt.root.children[2].status is None + + +def test_node_children(): + # ControlNode Must have children + xml_string = """ + + + """ + bt_factory = BehaviorTreeFactory() + with pytest.raises(ValueError): + bt_factory.build_tree(xml_string) + + # DecoratorNode Must have child + xml_string = """ + + + """ + with pytest.raises(ValueError): + bt_factory.build_tree(xml_string) + + # DecoratorNode Must have only one child + xml_string = """ + + + + + """ + with pytest.raises(ValueError): + bt_factory.build_tree(xml_string) + + # ActionNode Must have no children + xml_string = """ + + + + """ + with pytest.raises(ValueError): + bt_factory.build_tree(xml_string) + + # WhileDoElse Must have exactly 2 or 3 children + xml_string = """ + + + + """ + with pytest.raises(ValueError): + bt = bt_factory.build_tree(xml_string) + bt.tick() + + xml_string = """ + + + + + + + """ + with pytest.raises(ValueError): + bt = bt_factory.build_tree(xml_string) + bt.tick() + + +if __name__ == "__main__": + conftest.run_this_test(__file__) From e7f893ef1aa503df04c83ec6355d18dd05d36394 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 9 Mar 2025 20:21:24 +0900 Subject: [PATCH 875/940] feat: add linkcode_resolve function for enhanced documentation linking (#1185) * feat: add linkcode_resolve function for enhanced documentation linking * feat: enhance documentation linking with linkcode and relative path resolution --- docs/conf.py | 47 +++++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 45 insertions(+), 2 deletions(-) diff --git a/docs/conf.py b/docs/conf.py index 919fa9ac76..eeabab11b1 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -13,6 +13,8 @@ # import os import sys +from pathlib import Path + sys.path.insert(0, os.path.abspath('../')) @@ -41,7 +43,7 @@ 'matplotlib.sphinxext.plot_directive', 'sphinx.ext.autodoc', 'sphinx.ext.mathjax', - 'sphinx.ext.viewcode', + 'sphinx.ext.linkcode', 'sphinx.ext.napoleon', 'sphinx.ext.imgconverter', 'IPython.sphinxext.ipython_console_highlighting', @@ -184,4 +186,45 @@ ] -# -- Extension configuration ------------------------------------------------- +# -- linkcode setting ------------------------------------------------- + +import inspect +import os +import sys +import functools + +GITHUB_REPO = "https://github.com/AtsushiSakai/PythonRobotics" +GITHUB_BRANCH = "master" + + +def linkcode_resolve(domain, info): + if domain != "py": + return None + + modname = info["module"] + fullname = info["fullname"] + + try: + module = __import__(modname, fromlist=[fullname]) + obj = functools.reduce(getattr, fullname.split("."), module) + except (ImportError, AttributeError): + return None + + try: + srcfile = inspect.getsourcefile(obj) + srcfile = get_relative_path_from_parent(srcfile, "PythonRobotics") + lineno = inspect.getsourcelines(obj)[1] + except Exception: + return None + + return f"{GITHUB_REPO}/blob/{GITHUB_BRANCH}/{srcfile}#L{lineno}" + + +def get_relative_path_from_parent(file_path: str, parent_dir: str): + path = Path(file_path).resolve() + + try: + parent_path = next(p for p in path.parents if p.name == parent_dir) + return str(path.relative_to(parent_path)) + except StopIteration: + raise ValueError(f"Parent directory '{parent_dir}' not found in {file_path}") From 73ebcd85dc967dbb160e29ee4c529b7a64f11e2b Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 12 Mar 2025 21:26:09 +0900 Subject: [PATCH 876/940] build(deps): bump ruff from 0.9.9 to 0.9.10 in /requirements (#1186) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.9.9 to 0.9.10. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.9.9...0.9.10) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 552bf8482b..cf6dea3a46 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.5 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.15.0 # For unit test -ruff == 0.9.9 # For unit test +ruff == 0.9.10 # For unit test From 1308e76424723eb68a4a864117e60c0bbd054df1 Mon Sep 17 00:00:00 2001 From: Jonathan Schwartz Date: Thu, 13 Mar 2025 10:24:53 -0400 Subject: [PATCH 877/940] Add expanded node set to SpaceTime AStar (#1183) * speed up spacetime astar * forgot to include hash impl on Position * add condition to test on node expansions * remove heuristic from Node __hash__ impl * update rst with note about optimization --- .../GridWithDynamicObstacles.py | 3 ++ .../TimeBasedPathPlanning/SpaceTimeAStar.py | 51 +++++++++++++------ .../time_based_grid_search_main.rst | 17 +++++++ tests/test_space_time_astar.py | 1 + 4 files changed, 57 insertions(+), 15 deletions(-) diff --git a/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py b/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py index 7b0190d023..7416ff2f08 100644 --- a/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py +++ b/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py @@ -30,6 +30,9 @@ def __sub__(self, other): f"Subtraction not supported for Position and {type(other)}" ) + def __hash__(self): + return hash((self.x, self.y)) + class ObstacleArrangement(Enum): # Random obstacle positions and movements diff --git a/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py b/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py index a7aed41869..c4e2802d37 100644 --- a/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py +++ b/PathPlanning/TimeBasedPathPlanning/SpaceTimeAStar.py @@ -20,7 +20,7 @@ import random from dataclasses import dataclass from functools import total_ordering - +import time # Seed randomness for reproducibility RANDOM_SEED = 50 @@ -48,11 +48,17 @@ def __lt__(self, other: object): return NotImplementedError(f"Cannot compare Node with object of type: {type(other)}") return (self.time + self.heuristic) < (other.time + other.heuristic) + """ + Note: cost and heuristic are not included in eq or hash, since they will always be the same + for a given (position, time) pair. Including either cost or heuristic would be redundant. + """ def __eq__(self, other: object): if not isinstance(other, Node): return NotImplementedError(f"Cannot compare Node with object of type: {type(other)}") return self.position == other.position and self.time == other.time + def __hash__(self): + return hash((self.position, self.time)) class NodePath: path: list[Node] @@ -86,6 +92,8 @@ class SpaceTimeAStar: grid: Grid start: Position goal: Position + # Used to evaluate solutions + expanded_node_count: int = -1 def __init__(self, grid: Grid, start: Position, goal: Position): self.grid = grid @@ -98,7 +106,8 @@ def plan(self, verbose: bool = False) -> NodePath: open_set, Node(self.start, 0, self.calculate_heuristic(self.start), -1) ) - expanded_set: list[Node] = [] + expanded_list: list[Node] = [] + expanded_set: set[Node] = set() while open_set: expanded_node: Node = heapq.heappop(open_set) if verbose: @@ -110,23 +119,25 @@ def plan(self, verbose: bool = False) -> NodePath: continue if expanded_node.position == self.goal: - print(f"Found path to goal after {len(expanded_set)} expansions") + print(f"Found path to goal after {len(expanded_list)} expansions") path = [] path_walker: Node = expanded_node while True: path.append(path_walker) if path_walker.parent_index == -1: break - path_walker = expanded_set[path_walker.parent_index] + path_walker = expanded_list[path_walker.parent_index] # reverse path so it goes start -> goal path.reverse() + self.expanded_node_count = len(expanded_set) return NodePath(path) - expanded_idx = len(expanded_set) - expanded_set.append(expanded_node) + expanded_idx = len(expanded_list) + expanded_list.append(expanded_node) + expanded_set.add(expanded_node) - for child in self.generate_successors(expanded_node, expanded_idx, verbose): + for child in self.generate_successors(expanded_node, expanded_idx, verbose, expanded_set): heapq.heappush(open_set, child) raise Exception("No path found") @@ -135,7 +146,7 @@ def plan(self, verbose: bool = False) -> NodePath: Generate possible successors of the provided `parent_node` """ def generate_successors( - self, parent_node: Node, parent_node_idx: int, verbose: bool + self, parent_node: Node, parent_node_idx: int, verbose: bool, expanded_set: set[Node] ) -> Generator[Node, None, None]: diffs = [ Position(0, 0), @@ -146,13 +157,17 @@ def generate_successors( ] for diff in diffs: new_pos = parent_node.position + diff + new_node = Node( + new_pos, + parent_node.time + 1, + self.calculate_heuristic(new_pos), + parent_node_idx, + ) + + if new_node in expanded_set: + continue + if self.grid.valid_position(new_pos, parent_node.time + 1): - new_node = Node( - new_pos, - parent_node.time + 1, - self.calculate_heuristic(new_pos), - parent_node_idx, - ) if verbose: print("\tNew successor node: ", new_node) yield new_node @@ -166,9 +181,12 @@ def calculate_heuristic(self, position) -> int: verbose = False def main(): - start = Position(1, 11) + start = Position(1, 5) goal = Position(19, 19) grid_side_length = 21 + + start_time = time.time() + grid = Grid( np.array([grid_side_length, grid_side_length]), num_obstacles=40, @@ -179,6 +197,9 @@ def main(): planner = SpaceTimeAStar(grid, start, goal) path = planner.plan(verbose) + runtime = time.time() - start_time + print(f"Planning took: {runtime:.5f} seconds") + if verbose: print(f"Path: {path}") diff --git a/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst b/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst index 0c26badec7..48dc1289c2 100644 --- a/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst +++ b/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst @@ -16,6 +16,23 @@ Using a time-based cost and heuristic ensures the path found is optimal in terms The cost is the amount of time it takes to reach a given node, and the heuristic is the minimum amount of time it could take to reach the goal from that node, disregarding all obstacles. For a simple scenario where the robot can move 1 cell per time step and stop and go as it pleases, the heuristic for time is equivalent to the heuristic for distance. +One optimization that was added in `this PR `__ was to add an expanded set to the algorithm. The algorithm will not expand nodes that are already in that set. This greatly reduces the number of node expansions needed to find a path, since no duplicates are expanded. It also helps to reduce the amount of memory the algorithm uses. + +Before:: + + Found path to goal after 204490 expansions + Planning took: 1.72464 seconds + Memory usage (RSS): 68.19 MB + + +After:: + + Found path to goal after 2348 expansions + Planning took: 0.01550 seconds + Memory usage (RSS): 64.85 MB + +When starting at (1, 11) in the structured obstacle arrangement (second of the two gifs above). + References: ~~~~~~~~~~~ diff --git a/tests/test_space_time_astar.py b/tests/test_space_time_astar.py index 5290738eb4..390c7732dc 100644 --- a/tests/test_space_time_astar.py +++ b/tests/test_space_time_astar.py @@ -28,6 +28,7 @@ def test_1(): # path should end at the goal assert path.path[-1].position == goal + assert planner.expanded_node_count < 1000 if __name__ == "__main__": conftest.run_this_test(__file__) From 41187d67b11f06265431b87dcf0b9da679345249 Mon Sep 17 00:00:00 2001 From: Zichao Yang Date: Sun, 16 Mar 2025 21:40:11 +0800 Subject: [PATCH 878/940] fix "ModuleNotFoundError: No module named 'utils'" (#1188) --- .../lqr_speed_steer_control/lqr_speed_steer_control.py | 4 ++-- PathTracking/lqr_steer_control/lqr_steer_control.py | 4 ++-- PathTracking/rear_wheel_feedback/rear_wheel_feedback.py | 7 +++++-- PathTracking/stanley_controller/stanley_controller.py | 4 ++-- 4 files changed, 11 insertions(+), 8 deletions(-) diff --git a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py index d85fa98a84..5831d02d30 100644 --- a/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py +++ b/PathTracking/lqr_speed_steer_control/lqr_speed_steer_control.py @@ -11,9 +11,9 @@ import numpy as np import scipy.linalg as la import pathlib -from utils.angle import angle_mod -sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) +sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) +from utils.angle import angle_mod from PathPlanning.CubicSpline import cubic_spline_planner # === Parameters ===== diff --git a/PathTracking/lqr_steer_control/lqr_steer_control.py b/PathTracking/lqr_steer_control/lqr_steer_control.py index 461d6e3722..3c066917ff 100644 --- a/PathTracking/lqr_steer_control/lqr_steer_control.py +++ b/PathTracking/lqr_steer_control/lqr_steer_control.py @@ -11,9 +11,9 @@ import numpy as np import sys import pathlib -from utils.angle import angle_mod -sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) +sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) +from utils.angle import angle_mod from PathPlanning.CubicSpline import cubic_spline_planner Kp = 1.0 # speed proportional gain diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py index 1702bd47dd..fd04fb6d17 100644 --- a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py +++ b/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py @@ -8,11 +8,14 @@ import matplotlib.pyplot as plt import math import numpy as np -from utils.angle import angle_mod - +import sys +import pathlib from scipy import interpolate from scipy import optimize +sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) +from utils.angle import angle_mod + Kp = 1.0 # speed proportional gain # steering control parameter KTH = 1.0 diff --git a/PathTracking/stanley_controller/stanley_controller.py b/PathTracking/stanley_controller/stanley_controller.py index 08aa049395..bc98175f17 100644 --- a/PathTracking/stanley_controller/stanley_controller.py +++ b/PathTracking/stanley_controller/stanley_controller.py @@ -13,9 +13,9 @@ import matplotlib.pyplot as plt import sys import pathlib -from utils.angle import angle_mod -sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) +sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) +from utils.angle import angle_mod from PathPlanning.CubicSpline import cubic_spline_planner k = 0.5 # control gain From aa61a6ea570e013d346c40874f8a33890ec66d28 Mon Sep 17 00:00:00 2001 From: Jonathan Schwartz Date: Mon, 17 Mar 2025 09:01:07 -0400 Subject: [PATCH 879/940] Safe Interval Path Planner (#1184) * it works and is WAY faster than a* * some bug fixes from testing different scenarios * add some docs & address todos * add sipp test * spiff up comments revert changes in speed-up * explain what the removal is doing * linting * fix docs build * docs formatting * revert change to file (maybe linter did it?) * point at gifs in gifs repo * use raw githubusercontent gif links * change formatting on planner results * format output differently * proper formatting final * missing underline * revert unintended change * grammar + add descriptions for gifs * missing :: * add title to gifs section * dont use sections for sub-sections * constent a* spelling * Update PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> * Update tests/test_safe_interval_path_planner.py Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> * Update docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst Co-authored-by: Atsushi Sakai * Update PathPlanning/TimeBasedPathPlanning/SafeInterval.py Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> * addressing comments * revert np.full change --------- Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> Co-authored-by: Atsushi Sakai --- .../GridWithDynamicObstacles.py | 57 +++- .../TimeBasedPathPlanning/SafeInterval.py | 303 ++++++++++++++++++ .../time_based_grid_search_main.rst | 43 ++- tests/test_safe_interval_path_planner.py | 33 ++ 4 files changed, 434 insertions(+), 2 deletions(-) create mode 100644 PathPlanning/TimeBasedPathPlanning/SafeInterval.py create mode 100644 tests/test_safe_interval_path_planner.py diff --git a/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py b/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py index 7416ff2f08..2a47023f8c 100644 --- a/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py +++ b/PathPlanning/TimeBasedPathPlanning/GridWithDynamicObstacles.py @@ -33,6 +33,10 @@ def __sub__(self, other): def __hash__(self): return hash((self.x, self.y)) +@dataclass +class Interval: + start_time: int + end_time: int class ObstacleArrangement(Enum): # Random obstacle positions and movements @@ -40,6 +44,14 @@ class ObstacleArrangement(Enum): # Obstacles start in a line in y at center of grid and move side-to-side in x ARRANGEMENT1 = 1 +""" +Generates a 2d numpy array with lists for elements. +""" +def empty_2d_array_of_lists(x: int, y: int) -> np.ndarray: + arr = np.empty((x, y), dtype=object) + # assign each element individually - np.full creates references to the same list + arr[:] = [[[] for _ in range(y)] for _ in range(x)] + return arr class Grid: # Set in constructor @@ -89,7 +101,7 @@ def __init__( """ def generate_dynamic_obstacles(self, obs_count: int) -> list[list[Position]]: obstacle_paths = [] - for _ in (0, obs_count): + for _ in range(0, obs_count): # Sample until a free starting space is found initial_position = self.sample_random_position() while not self.valid_obstacle_position(initial_position, 0): @@ -234,6 +246,49 @@ def get_obstacle_positions_at_time(self, t: int) -> tuple[list[int], list[int]]: y_positions.append(obs_path[t].y) return (x_positions, y_positions) + """ + Returns safe intervals for each cell. + """ + def get_safe_intervals(self) -> np.ndarray: + intervals = empty_2d_array_of_lists(self.grid_size[0], self.grid_size[1]) + for x in range(intervals.shape[0]): + for y in range(intervals.shape[1]): + intervals[x, y] = self.get_safe_intervals_at_cell(Position(x, y)) + + return intervals + + """ + Generate the safe intervals for a given cell. The intervals will be in order of start time. + ex: Interval (2, 3) will be before Interval (4, 5) + """ + def get_safe_intervals_at_cell(self, cell: Position) -> list[Interval]: + vals = self.reservation_matrix[cell.x, cell.y, :] + # Find where the array is zero + zero_mask = (vals == 0) + + # Identify transitions between zero and nonzero elements + diff = np.diff(zero_mask.astype(int)) + + # Start indices: where zeros begin (1 after a nonzero) + start_indices = np.where(diff == 1)[0] + 1 + + # End indices: where zeros stop (just before a nonzero) + end_indices = np.where(diff == -1)[0] + + # Handle edge cases if the array starts or ends with zeros + if zero_mask[0]: # If the first element is zero, add index 0 to start_indices + start_indices = np.insert(start_indices, 0, 0) + if zero_mask[-1]: # If the last element is zero, add the last index to end_indices + end_indices = np.append(end_indices, len(vals) - 1) + + # Create pairs of (first zero, last zero) + intervals = [Interval(int(start), int(end)) for start, end in zip(start_indices, end_indices)] + + # Remove intervals where a cell is only free for one time step. Those intervals not provide enough time to + # move into and out of the cell each take 1 time step, and the cell is considered occupied during + # both the time step when it is entering the cell, and the time step when it is leaving the cell. + intervals = [interval for interval in intervals if interval.start_time != interval.end_time] + return intervals show_animation = True diff --git a/PathPlanning/TimeBasedPathPlanning/SafeInterval.py b/PathPlanning/TimeBasedPathPlanning/SafeInterval.py new file mode 100644 index 0000000000..7fea10c67f --- /dev/null +++ b/PathPlanning/TimeBasedPathPlanning/SafeInterval.py @@ -0,0 +1,303 @@ +""" +Safe interval path planner + This script implements a safe-interval path planner for a 2d grid with dynamic obstacles. It is faster than + SpaceTime A* because it reduces the number of redundant node expansions by pre-computing regions of adjacent + time steps that are safe ("safe intervals") at each position. This allows the algorithm to skip expanding nodes + that are in intervals that have already been visited earlier. + + Reference: https://www.cs.cmu.edu/~maxim/files/sipp_icra11.pdf +""" + +import numpy as np +import matplotlib.pyplot as plt +from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import ( + Grid, + Interval, + ObstacleArrangement, + Position, + empty_2d_array_of_lists, +) +import heapq +import random +from dataclasses import dataclass +from functools import total_ordering +import time + +@dataclass() +# Note: Total_ordering is used instead of adding `order=True` to the @dataclass decorator because +# this class needs to override the __lt__ and __eq__ methods to ignore parent_index. The Parent +# index and interval member variables are just used to track the path found by the algorithm, +# and has no effect on the quality of a node. +@total_ordering +class Node: + position: Position + time: int + heuristic: int + parent_index: int + interval: Interval + + """ + This is what is used to drive node expansion. The node with the lowest value is expanded next. + This comparison prioritizes the node with the lowest cost-to-come (self.time) + cost-to-go (self.heuristic) + """ + def __lt__(self, other: object): + if not isinstance(other, Node): + return NotImplementedError(f"Cannot compare Node with object of type: {type(other)}") + return (self.time + self.heuristic) < (other.time + other.heuristic) + + """ + Equality only cares about position and time. Heuristic and interval will always be the same for a given + (position, time) pairing, so they are not considered in equality. + """ + def __eq__(self, other: object): + if not isinstance(other, Node): + return NotImplemented + return self.position == other.position and self.time == other.time + +@dataclass +class EntryTimeAndInterval: + entry_time: int + interval: Interval + +class NodePath: + path: list[Node] + positions_at_time: dict[int, Position] = {} + + def __init__(self, path: list[Node]): + self.path = path + for (i, node) in enumerate(path): + if i > 0: + # account for waiting in interval at previous node + prev_node = path[i-1] + for t in range(prev_node.time, node.time): + self.positions_at_time[t] = prev_node.position + + self.positions_at_time[node.time] = node.position + + """ + Get the position of the path at a given time + """ + def get_position(self, time: int) -> Position | None: + return self.positions_at_time.get(time) + + """ + Time stamp of the last node in the path + """ + def goal_reached_time(self) -> int: + return self.path[-1].time + + def __repr__(self): + repr_string = "" + for i, node in enumerate(self.path): + repr_string += f"{i}: {node}\n" + return repr_string + + +class SafeIntervalPathPlanner: + grid: Grid + start: Position + goal: Position + + def __init__(self, grid: Grid, start: Position, goal: Position): + self.grid = grid + self.start = start + self.goal = goal + + # Seed randomness for reproducibility + RANDOM_SEED = 50 + random.seed(RANDOM_SEED) + np.random.seed(RANDOM_SEED) + + """ + Generate a plan given the loaded problem statement. Raises an exception if it fails to find a path. + Arguments: + verbose (bool): set to True to print debug information + """ + def plan(self, verbose: bool = False) -> NodePath: + + safe_intervals = self.grid.get_safe_intervals() + + open_set: list[Node] = [] + first_node_interval = safe_intervals[self.start.x, self.start.y][0] + heapq.heappush( + open_set, Node(self.start, 0, self.calculate_heuristic(self.start), -1, first_node_interval) + ) + + expanded_list: list[Node] = [] + visited_intervals = empty_2d_array_of_lists(self.grid.grid_size[0], self.grid.grid_size[1]) + while open_set: + expanded_node: Node = heapq.heappop(open_set) + if verbose: + print("Expanded node:", expanded_node) + + if expanded_node.time + 1 >= self.grid.time_limit: + if verbose: + print(f"\tSkipping node that is past time limit: {expanded_node}") + continue + + if expanded_node.position == self.goal: + print(f"Found path to goal after {len(expanded_list)} expansions") + path = [] + path_walker: Node = expanded_node + while True: + path.append(path_walker) + if path_walker.parent_index == -1: + break + path_walker = expanded_list[path_walker.parent_index] + + # reverse path so it goes start -> goal + path.reverse() + return NodePath(path) + + expanded_idx = len(expanded_list) + expanded_list.append(expanded_node) + entry_time_and_node = EntryTimeAndInterval(expanded_node.time, expanded_node.interval) + add_entry_to_visited_intervals_array(entry_time_and_node, visited_intervals, expanded_node) + + for child in self.generate_successors(expanded_node, expanded_idx, safe_intervals, visited_intervals): + heapq.heappush(open_set, child) + + raise Exception("No path found") + + """ + Generate list of possible successors of the provided `parent_node` that are worth expanding + """ + def generate_successors( + self, parent_node: Node, parent_node_idx: int, intervals: np.ndarray, visited_intervals: np.ndarray + ) -> list[Node]: + new_nodes = [] + diffs = [ + Position(0, 0), + Position(1, 0), + Position(-1, 0), + Position(0, 1), + Position(0, -1), + ] + for diff in diffs: + new_pos = parent_node.position + diff + if not self.grid.inside_grid_bounds(new_pos): + continue + + current_interval = parent_node.interval + + new_cell_intervals: list[Interval] = intervals[new_pos.x, new_pos.y] + for interval in new_cell_intervals: + # if interval starts after current ends, break + # assumption: intervals are sorted by start time, so all future intervals will hit this condition as well + if interval.start_time > current_interval.end_time: + break + + # if interval ends before current starts, skip + if interval.end_time < current_interval.start_time: + continue + + # if we have already expanded a node in this interval with a <= starting time, skip + better_node_expanded = False + for visited in visited_intervals[new_pos.x, new_pos.y]: + if interval == visited.interval and visited.entry_time <= parent_node.time + 1: + better_node_expanded = True + break + if better_node_expanded: + continue + + # We know there is a node worth expanding. Generate successor at the earliest possible time the + # new interval can be entered + for possible_t in range(max(parent_node.time + 1, interval.start_time), min(current_interval.end_time, interval.end_time)): + if self.grid.valid_position(new_pos, possible_t): + new_nodes.append(Node( + new_pos, + # entry is max of interval start and parent node time + 1 (get there as soon as possible) + max(interval.start_time, parent_node.time + 1), + self.calculate_heuristic(new_pos), + parent_node_idx, + interval, + )) + # break because all t's after this will make nodes with a higher cost, the same heuristic, and are in the same interval + break + + return new_nodes + + """ + Calculate the heuristic for a given position - Manhattan distance to the goal + """ + def calculate_heuristic(self, position) -> int: + diff = self.goal - position + return abs(diff.x) + abs(diff.y) + + +""" +Adds a new entry to the visited intervals array. If the entry is already present, the entry time is updated if the new +entry time is better. Otherwise, the entry is added to `visited_intervals` at the position of `expanded_node`. +""" +def add_entry_to_visited_intervals_array(entry_time_and_interval: EntryTimeAndInterval, visited_intervals: np.ndarray, expanded_node: Node): + # if entry is present, update entry time if better + for existing_entry_and_interval in visited_intervals[expanded_node.position.x, expanded_node.position.y]: + if existing_entry_and_interval.interval == entry_time_and_interval.interval: + existing_entry_and_interval.entry_time = min(existing_entry_and_interval.entry_time, entry_time_and_interval.entry_time) + + # Otherwise, append + visited_intervals[expanded_node.position.x, expanded_node.position.y].append(entry_time_and_interval) + + +show_animation = True +verbose = False + +def main(): + start = Position(1, 18) + goal = Position(19, 19) + grid_side_length = 21 + + start_time = time.time() + + grid = Grid( + np.array([grid_side_length, grid_side_length]), + num_obstacles=250, + obstacle_avoid_points=[start, goal], + obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1, + # obstacle_arrangement=ObstacleArrangement.RANDOM, + ) + + planner = SafeIntervalPathPlanner(grid, start, goal) + path = planner.plan(verbose) + runtime = time.time() - start_time + print(f"Planning took: {runtime:.5f} seconds") + + if verbose: + print(f"Path: {path}") + + if not show_animation: + return + + fig = plt.figure(figsize=(10, 7)) + ax = fig.add_subplot( + autoscale_on=False, + xlim=(0, grid.grid_size[0] - 1), + ylim=(0, grid.grid_size[1] - 1), + ) + ax.set_aspect("equal") + ax.grid() + ax.set_xticks(np.arange(0, grid_side_length, 1)) + ax.set_yticks(np.arange(0, grid_side_length, 1)) + + (start_and_goal,) = ax.plot([], [], "mD", ms=15, label="Start and Goal") + start_and_goal.set_data([start.x, goal.x], [start.y, goal.y]) + (obs_points,) = ax.plot([], [], "ro", ms=15, label="Obstacles") + (path_points,) = ax.plot([], [], "bo", ms=10, label="Path Found") + ax.legend(bbox_to_anchor=(1.05, 1)) + + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect( + "key_release_event", lambda event: [exit(0) if event.key == "escape" else None] + ) + + for i in range(0, path.goal_reached_time() + 1): + obs_positions = grid.get_obstacle_positions_at_time(i) + obs_points.set_data(obs_positions[0], obs_positions[1]) + path_position = path.get_position(i) + path_points.set_data([path_position.x], [path_position.y]) + plt.pause(0.2) + plt.show() + + +if __name__ == "__main__": + main() diff --git a/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst b/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst index 48dc1289c2..04001d4504 100644 --- a/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst +++ b/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst @@ -33,7 +33,48 @@ After:: When starting at (1, 11) in the structured obstacle arrangement (second of the two gifs above). -References: + +Safe Interval Path Planning +~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The safe interval path planning algorithm is described in this paper: + +`SIPP: Safe Interval Path Planning for Dynamic Environments `__ + +It is faster than space-time A* because it pre-computes the intervals of time that are unoccupied in each cell. This allows it to reduce the number of successor node it generates by avoiding nodes within the same interval. + +**Comparison with SpaceTime A*:** + +Arrangement 1 starting at (1, 18) + +SafeInterval planner:: + + Found path to goal after 322 expansions + Planning took: 0.00730 seconds + +SpaceTime A*:: + + Found path to goal after 2717154 expansions + Planning took: 20.51330 seconds + +**Benchmarking the Safe Interval Path Planner:** + +250 random obstacles:: + + Found path to goal after 764 expansions + Planning took: 0.60596 seconds + +.. image:: https://raw.githubusercontent.com/AtsushiSakai/PythonRoboticsGifs/refs/heads/master/PathPlanning/TimeBasedPathPlanning/SafeIntervalPathPlanner/path_animation.gif + +Arrangement 1 starting at (1, 18):: + + Found path to goal after 322 expansions + Planning took: 0.00730 seconds + +.. image:: https://raw.githubusercontent.com/AtsushiSakai/PythonRoboticsGifs/refs/heads/master/PathPlanning/TimeBasedPathPlanning/SafeIntervalPathPlanner/path_animation2.gif + +References ~~~~~~~~~~~ - `Cooperative Pathfinding `__ +- `SIPP: Safe Interval Path Planning for Dynamic Environments `__ diff --git a/tests/test_safe_interval_path_planner.py b/tests/test_safe_interval_path_planner.py new file mode 100644 index 0000000000..f1fbf90d2a --- /dev/null +++ b/tests/test_safe_interval_path_planner.py @@ -0,0 +1,33 @@ +from PathPlanning.TimeBasedPathPlanning.GridWithDynamicObstacles import ( + Grid, + ObstacleArrangement, + Position, +) +from PathPlanning.TimeBasedPathPlanning import SafeInterval as m +import numpy as np +import conftest + + +def test_1(): + start = Position(1, 11) + goal = Position(19, 19) + grid_side_length = 21 + grid = Grid( + np.array([grid_side_length, grid_side_length]), + obstacle_arrangement=ObstacleArrangement.ARRANGEMENT1, + ) + + m.show_animation = False + planner = m.SafeIntervalPathPlanner(grid, start, goal) + + path = planner.plan(False) + + # path should have 31 entries + assert len(path.path) == 31 + + # path should end at the goal + assert path.path[-1].position == goal + + +if __name__ == "__main__": + conftest.run_this_test(__file__) From 19fc48d60fea057f6c14365c502db4d18490c3a8 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Mar 2025 20:22:31 +0900 Subject: [PATCH 880/940] build(deps): bump numpy from 2.2.3 to 2.2.4 in /requirements (#1189) Bumps [numpy](https://github.com/numpy/numpy) from 2.2.3 to 2.2.4. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v2.2.3...v2.2.4) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index cf6dea3a46..3ea4197736 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 2.2.3 +numpy == 2.2.4 scipy == 1.15.2 matplotlib == 3.10.1 cvxpy == 1.5.3 From 764ba21f86fc0d5c2ae5b613449ca81ea6406036 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Mar 2025 20:29:12 +0900 Subject: [PATCH 881/940] build(deps): bump ruff from 0.9.10 to 0.11.0 in /requirements (#1191) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.9.10 to 0.11.0. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.9.10...0.11.0) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 3ea4197736..5438678f87 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.5 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.15.0 # For unit test -ruff == 0.9.10 # For unit test +ruff == 0.11.0 # For unit test From 1c1596be21f015b3b2c3db6489b93cd94d6eca01 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 28 Apr 2025 08:51:09 +0900 Subject: [PATCH 882/940] docs: enhance contribution guide with instructions for linking code in GitHub (#1202) --- docs/_static/img/source_link_1.png | Bin 0 -> 87987 bytes docs/_static/img/source_link_2.png | Bin 0 -> 237071 bytes .../3_how_to_contribute_main.rst | 13 +++++++++++++ 3 files changed, 13 insertions(+) create mode 100644 docs/_static/img/source_link_1.png create mode 100644 docs/_static/img/source_link_2.png diff --git a/docs/_static/img/source_link_1.png b/docs/_static/img/source_link_1.png new file mode 100644 index 0000000000000000000000000000000000000000..53febda7cbc62ba625f3f179b399552c7da351e5 GIT binary patch literal 87987 zcmb@tbzB_Hvp%|uF1|>B;O-hia3{DET!Xv2y99R#7DBKP++BhM2qD4Uf+V=R+~NJ6 z-#O=VFTD5uard*s4zn}e)zwu`JyqQssiYu@hD?AA0)fz^rNmW0Aou_f2pj}K0Iq0F zn!f^pP-QK}#FV7P#K@GK?9D7~OhF*2$P^7kP1OP1932&MIEc8g%pZAZ0+z50ggM}Z zB0@$ACIrh^RH-UI3b|ZQyz*ly**jur)mshR-aTzx6b8m^qptE+B(TejMmyIMm;2rI zNQVCp9`}t!KG4s(OBGA>&q%`MREoIRJ0k>X$=@klVNfk#cz+@``vmF^M!rKvtVFH# zXWh4h5ued_R~O&M17#3R%x=7b+B-<=%SBR&YMULu`iUt z=%Ts>Jh=|_Ns=+bMq38U zZ>OuvO&_gX44GT|cRL=jGNfZaa1O6d+53aOH;PA;KoQrXuqntU1Gq(VhzTd{lT_jd zV(=>y=#7%AG=-V4rGswOt~4#1ndl0a{LIUJ$lP|s3)As_#Z_#W_JtNZg$iIET;GIO z87@#D(fSEXQjy{bLZg&$pvCWqX``qPs~AY8k~S{;i~CmHMzf0jyyp#)vA?Vhlf@=& z_M=A+j|4}l7R2F6AAekZDstkace989Q1ng+7;fvR*dI|>? zj1NR5gF(Oj-Wk!;PJ-0h7X))aD^5X1O0>B&#Rzj5f6p7D=CmrJ;OYwcd+RHcVsn7A zstZMMT5kKODE;D(2#g2J^Fty2)vpWz>}#E$cka(`K-bwT!ZfY9z_fh(h@puE8wu`# z8bN>Ia&`JTu<{e>-x|91%{2B46D{o`DI(d1NQMxGxOHbsuZqqk{i}5QJ;RZomrX(@29UYRywqum9grJ3U!-2=`%16Q?pR|q zO%%5`k%$`eN$t)5J^^MWoPMumHhnQR5Wn?@?ClsGINxjdCv!0?DzKej`P_Rjf1TmA#TS) z_usUcJ{bFm(0Tb4CX~sbcV!R-+|KjI;ruVGu_3yRA^(p~G!L*46e21@6#*-4NO2;F zUGDrm9oa0%^8+L~VBHXn4l%P+T?yVT`1S+I%fO^%rbf8(0K#P!T>;`{_&*5yo#t>N zQV_JaWLFVLMv>E$KOlsMA}|RKR0z_dDha6KL3HsM-+Vs7X+cm@_kUHV>MCuC9 z#`Ap>`-JTo<0H!chIm3GMv2jdYEXj50-qpUL73wwy#=@#r1vg0FXazQExJIYzNr0& z-9IR`h_LAdeLZsQh|w{QRZ>jPW&2I0ZNA_$_A*pyf58;owASRC4E61a}Jkt-)?W75g{8v7~vg38)4hi-$Q~G`AM;w)-#Dh+DCX=cfCb_>K zd3(X2Q@^H&&)H6%f3+pv@TW7`U;MR8EPvXvg=9JMw;6sJ|4_e!(19pR6v=_u56Spp!gfH8i zrLtw*6}HVggV`;cEvhBuU<>039)hxMaMZK^VB>X(;GN{<&t}TT%3k0t<6UT;ZDwgk zY94c8bcx%l=U^{Lgi5}vL{W5ebVi?FpH^RKOx$z#_iS=Lay>Mq^0ApWU8AOsnmk`#Oj@cp zl;l}Plytj9S(g4a=diBvs1dCZFgqVE*|0fwIiA=U-dMn;!8K+!(;nBnF_W$`(J|95 zuj4nrTpXNb_+^!+);8g6EnuDF8t58xDnR%?reYW;Qzmn}UR}5rxL< z#klI&_gJn}@9~MB>0#c!G<);?d%AN~^t5yppYc-fWj}LN3!y!BMTEV=2ii|mZ)jT; zQKfV9zYtHOY-hRj5XkBr|jh{pj+R7+eR9r(M`8tV>e&@ zC4C}&BaNtnR1#Ujr`mBqd6{yP^HP8Is@4vyQK^0)`iEARc?ZWcO8s3+bE-C*zOCMM5*HL%j4y)qKheQ?^)43&p zV|a@G>d-d_L#RGsh7!keV;RS0f?2&8b*8Ug@Y%W@6CLxQY`A{wboi?dF>BadT~$>s2~cE-=@R%J|@mmU+-YObYPrBNCkdK{L+ zp(<&k^42BR&#dQ$x`zlRwZ7=I@5y?aUB)2azZ2L-n_|_!_X~FTIuYYXXwCK9mSN_^ zvc}_hm$^%4i=m7`wgIbQ!``=<`R!bj!F0zPd#-8y>f3Gff!MRp>7U0Y_9iCy(A-%{ zMXYf+vs+Z$^k#@FTk2E zmox5jKHjK0r6`$eCxGp?aWnIwrs#*`4`QKx-}b*jo1tIvX7ILIoAf?gJKFM`lx|mq zYcFVTv$Po4HLf}qRN2bSRh71DDC(m$x}EXvUlkBya?RTHEw%bGuB%_$uIz5QJMFbz zG2b_gxNj~}&NH@Gcy^owt^^M*+4?Vy?M?cfyzTs&Dp?h`Cy2}McPM_hCfgrWR9jRq zBA25k@7COYP1=0dy4{K%Vhw|xE+mrhNu^XHjC z+I%nqsxS63kX^hp)s!}qmj^Kb=MWGam;eM1oPmKu5KQ>r=MrE#5bQtKVL+g8OAy?D z-J<|}KD^?AMcm-w&8f&T<3EL>b1cv)H9-Q8K-IautS%vsracz9UZUa-D+!3^BN z?Cfdh^45dd&YAK*jr^Z>#7&)zoh%((EbZ;c9@>3tWbf)CKtb`)(SN`GBd4i{<^S|# z=loy80tU$X@C_?F3mfZyw+%eX|8SL8$ zDxhdVWPaBFo-{#Z?lDs*U>=Dq#TDNGpMaJ9^XdZr(gDZACve1X;0Fx&fpM^ z9^jp9L?4{jgndgWRC!!~DcUG0{K(WSjl|-OL|%J6i;u;5O%D@9XDBB8z70eXM8N=o zfx-PmDKGA|4^5os8tKz>J3nJ_A1KhvNi&#U$e5YQxS#YsTX5I?_3M{iUIGXy{^@rJ z5f~4CIexBa2l{WfS-{bOj)lp}me(*;!cV?&0z6UwMVxry2&@kv zqK|y33l#s-85p^fA3-Vr?#VZqIFb?w{TK0&-MR%nhAgt zO$Na)Ll>%caQ|(_l|UQpPfsH-4sw|Q7>9^GO}D70ry=0MZ15rJ!r|z|YX>V|1*g1M zLh(M?Ei?-bv5mHnpxNDykC`#>UfwbQ!HOpSS*YgA!@&*hPHFap{q<$MX1&u{2e z(alvk0zcsdtmygdOta@M*w5CMoc#Iq)jGp{(NhwaRey(bDaUci_gp$x(06BGpj{5k zJ(J)Z{J0%JkKlqBK>a;E5J5%%{kC(s<3PrtU4Y$i8`#T;Tcqg-N`05{>ka zEFR{+C7$4Gf}90D_q}95J>Dlswu%-Ih(G-DXo2idt>qXIdx07lKU<_Yx#R9i_U`6b z@$%+)g!oz#JdKHhE&YUz5<%czgCzK;&2u~@mb>s#y?3hmKUq(ecNH^CjDzDWLI@nH zJ&!k}SGq&9t5tjn5SaP=ZW<-|lC(j62#6RYOy`T<75(*N)u1o#8#^;KN8c#p{zRqH z!yBTYvpj`77i94kVEml2+w1c*W}W(r>1e5q?->Ph882YsreG1#EplSp)i0KVF+>@N z;NT4nyssq|o18aaVrY8c{l-6dCIi<$UX<&%#h$(l=-*_2u}xb5Dx0k@w>FY%pj~H0 zy*`vSwW?@7nEY3QQl*Ose)&x$_B7n%ZVUm#MB)Yr-CYJ)D=!*R*MGAT^-rh};|)ms&2!|xLXyxp#8>efm9Zra_Ny(%%bl8$Xph!sjOxiHszus^TPXhb zw+%M4wbF!@7&qu7{KclvSoL+cv8VIo?|P^e&|oSnz$;jcAcGD+y~%RDQetELEVMjo z=rIAw?lenmpws%GbeVQt&$`p!h~L?EbM^9b4Ibbi2Rv@U%8}07yX*Za(E=(O1h!a# zT0+;~{30!H;ZbnMMfH;z)MN-=S}acq#x`&;J%zgQR!CGbAis;1@O8k$NV0>u!=}I7 zAsgYJ?4JA`OZ93+>cnHwjjuB9?_-Sq_yW?MFBz9QXWy})!iC!x{rtCD`~-^ef{tC& zYp=7Nztf6sx)Yz()-N}6xx|4oTb21-tz|yz73XjYV;Y$qGwR&^-=bWf@^J778J0f) zFsV+|GRg7JIm|Rip%u?R-iDL_ z!xnP%_G{SlkIe-}b1)vi(;1XL1TgnIJMPUl9Rb?#HoHj+`t7#%En$|-T_JRp5DxvL zpoehrnQ26SjPHD_r?WwCy5!?#OBEl6M5PH5^tq_4wVj)++6KIIycM6AgBS}DjezRl z4`*f)2-SW7Pv4`f2;aI~EVtj#K(EDZqLtzFr9Ye@#CRx`If+rD{7guhwQY^uZo9Mq7mWXrp8o?o zr;aGRA!N(G{j#v>v&SZR@v3I~W{x+}Q1_hgYENXf&!tnpk3Y6AQYVt7dnocVlhIGo zSeTeA_Sl-SPsB~K7^qYwC^{ZifgFJ>$oF`d3kw%_gDVJtdkDX`Yw#u;zx{9+8$854 zUMV3Ysg4t*^QwMl43}BkB4=17Eaib_T$#-q-<{FHCMO z4#895&$Jutn6vrZ6@E7BMm{C_DHb3)>b{isG}r~3U1Ft;&}Mt8BG+c7np$~cb?iFR zzFn&nmR%EYP-;H6ou5W4UWDIR;?XF=SP-bj(7N4<6tZhC%B7r<(*j*Q^uxl#jn!p} zd1>zPxIDHe%c{Ljx8UjyGt6@mQkiwETq)LI;pThNxhnROp#hlnhF2$l5j31Tc3`{V z89-m>2uXe`D=TkU!M>No#|RPb8iFp6b&DmR_h;%F^v{h;gCxEf^`M@)MSGSGWySvP z$%W!>xN<8#WpT|97I%i5i+kvBnBmQa7F>r$DmY&y6HyMOWp|hXK*Z#5wHHQFmR5{u zS;N40g3`J>1nI%FJU>yA8?^h3HrN}KyeUbf83m%@$n56PBAlqlTi)kz8`pa+BlNOB z%*ER`)U9Yel4;F@CF3?5OqPaP8TLeAspACEmgh^Hsn(< zZ41?uLIUHH)1wn{FVk7gA%>v50iB&0!Sa;@MBwOTOwpPZ6H1CtF64K6s?qO@Y_IJw zg{FT9saZDhpl3Ji1lh9jpuP;pV{A7P;zR1>4m;R1f!4Brcxz(v$&mE-yeqFCp!?F$ zYlqLlmX9+RVHnFK;UM_syW49Nqodj3zZ^c^8NzAg`oz30-;C>SE|0BA8nmiSs@5*C zzLFiJuo^6?EM|gG-|l6*FJgM%w)eDN9&hsX4av)Z@w;EO8UbwXFJ>Y5EibhEs~t3o z+)z}Qi?H>}itVlmr0Z~8RZ**2MFu1h0dF%W=s`wcP6B0tf-mNqob?ggN;N8SaK&ck zJ$F=FeH@PD5SI#M(+KoC@lm1VB0H&^*6M-gyscrwuk7ZzFIU1zzf1SE>Vd-2qmF+_ zH@bU~*O(0xcpmoR#ax|a5b-#D3xY>Ed9CmiVG#{@82DnFw{;%U4(e=!Ju9>&$h18~ z)&4Eg0nd#XhQJzK1UWj}DmZgE6EqKCqrBY9wBDPEQjNN+-M^Y{Sm_CSrKFLEpfIVJ zN<=RRlFg9KLbIzg(Z#Uz&+)14xuQ55HS!lbVHbT7&NlVQSOF_#$oq5TVqxi-`NNrQ zDX^FU>`-z9N9PyzE0}J3^Olj!w)%K)xu8R{yKX44)U?i66Uuu47t)qOEOOm}VM93k z>gVjr@BLk46Lrkg+#pb9v2?$7-CeM6ab@GAU68)DBQG(}U$MlDRSLRwQ4@76`mFma=IqdPK*mtOj;S90{W^Y~perS$vU)P!1q!)7>F=F1CiYc?N9Kpo@dTirD#+gWoR3E*Xvw^FEc6CguVbX=q<%ikS#v zmk&0D){{BR3=2-D36KU`ysczx;pyc;Qv*+Hc)+y8TW`3mbi-Tz`WVVHkbZyhJFYJ9 z@FXM|H{ch#LBAA`Cf(o$w1u_@oZA7=e8S=_$6mSIu;jO$px@!=>v?y%S=V*FoM6Y* zbK4t*Obe(!%pwYpx{D39e)@w*u;H8DC&g3&2g0Fr;_slsewsnkkAZ&GWl0kl+IDhr zsqN|O(>|i4pr|$VaP&JGpiSjxdQ+~eb=|r|`MV?JbbAV=hpB~Ja0keKmaGD|mSWbm&xZ}*3s zuC3T3YOEAbd>RrGS4oKQnUKRQx^s>Ic5eplFfd!+?t?BF44Y`c4Zv2;wy`i34 z@reZWlQs+zZovKBwf*1urW)h^Ry6)~O-*XvUdIUmd0_4tD%#H8_kTY0B=FW5k#<2* z17H04m9LMu77RgWpC9lkLo9FRj&uEoMtKlI(LEJ5s6gH*)*t(^-995)E>2ocd`(11{c=|@iI(kL{j-}4<~Q($C%>e1C3#yL zbQr*sX+^_q70}iM{mt*r0^f42pJIrT78ya=QRmIL#v}177j6Fh%&T_%EfHtq z;bnC2()){9&sZ^$7oQGyn+wosRgz3Jt173Io66gvwd93$KJ-QpKN4 zq(2eDL}CSqAn7+kKeav=XY!B=3k}tJCyeve3xAE7hNdqu9KHs$Gc?u+BvAkr#x}l9 zqE(ccD%T?xkivELge+} z!Y=qszCpW|9Tm>b=ImvG(h;*(i9G0xlPs%gMFEB_R@x)>{(8S-BzP*6Krp3hL8v3@5jxlB`{$7b;*nTEP#C(n>WgC< zhdhcJ5Ku%i^;}DkY)zfo4!b}(9Mx$%tAvBF0+|~+v)^acYh`<&f>2=8`>t>E{^BL+ zTxX|_LN{k?BKe6ZU2VV0DfMUykTJf)Wo7{CYKcHW<~c>(V&C7fB9su3mb@6fW|v>n z-E-puIlgCFGwr@Ds;P!#)t}W$t$Z(U&zFcpoxeb;@E6CL$-jVCIr7UC7Q5*%6pb9% zFbIk&_HB_dabb3TWb?tp7V)r4=o&k)s1`<>3?%mEGZ>I#o^%7sJ?cbi%|fMMiwy;Y zv@~LgCANR%zNag~WV7(fX8J=f-DKLX>drmI>vtBXyhuMcj<}bWwc_0VtP1p)e)8t< z6*Bg^xp3rhT8pS>&St$jTTe3}=+AEON>_M_e$+##v_TT?zMcy-aQ%Aj3k8ueW)&+H z9e3I^iaA;FTeYra<>ZT>S<)|$qU-FbBx8xH4ZC0fw2EoHSdBWfsTcynZ(T$#rDSX} zz`VSfE6h6?n>`L!tKD|B@u3nU&(z1; z&R?Cq)k9|bP;OLBm3-gO*g*n+FMELdp1d8r0%YICxa?v6cbDe&nbBOtB>M`BwLrDQ z{e&g9L6jAKCzx3wn^!GLZKuGabwI%DUU~g^dD4@56=Y{c(r@JJH=zwXJSx*{;HL#y*2vsv_np2&B_lOp8KV!$4`zEH}C^e=btlRQaD+4P@|s} zcV%Ld6EJ9$?>MVPe1=Y+C{Fp}s%HSTim?!5Z;ucl)BB|!!g&FBz3(f+#e8UYFg?gP z7%~G&xB&7D!G;QRQA6=!l!*6cvM4ZYvr%jm&Kuv^xfasTsX_Ta0rIe3*06}>k#lXW z$bT4u8#T4lWM_bP4RQ=_3#I=xMA-xXeX7a`FF=`uTz%31-gg&c=#JnAUr0QiL3?XQ zX(iE9j!!@aeFN6qXXU3|acs7lUh=zf|Wv`woX#ojQKA?dCNWB)2eiPS1 zp&JODvN+u|{3UI>gperL?a7JOl{NgQ2LC|- zDn47MqkuC7H&9BHg-U$2^k2abGxt2-TPRQ|kl9dc`|*{}b7#6ryY=mL6lw^eCs1Ol z6Pbf1;eBb#5P%D5n$HpNUXyo?y{YqVFm6%CoeNq9$b$}YhnYtf?W0xYKqy5#6-;Hu z2!Ls|V1PODQse(*0!V~5zh+O!Yh8VV#l#J-)?woS?g+h$9RVOF&UP9C^^qe8`HJmr zvP?KP5;@_npz}tw$?$tMr_CSC>w_uSEe%d8b(prDXI&WAU{M+b+!_r1v^R5#)~BLu zOJ#6ss2>mx>sS3)R>s3|d#N#*or%D%p2COqFTwlivJh?FTpdU$K{fD@UE#Zl>$v>s= zQ9)pJ$I_p)8u8ycTn1K~Dk*Vk68~kTNO+bOSc==-7dv~R#{M5)BmzWt>**GMybArF z@km_*D>y~BzTZfmDxE)E51<4@kJU_N3IFTzz=P;y zyVxH`EPUl|Bq1#(=H3TOBmhV>KMflB~K^yQ=RoF z+itZxD9lflzY~{?;(MjexQC2_-DTj>*!Uu>)H0-zf+JE~{2ik+uA`}nzgG1-M(bCn zX?nUd&N7-m=2r(ZB)jbfY0GVR#C2JG$Fcw$q)G%PRUBq*>+$hG8Q|tMSY*F15^ve3 ziSN%*vtLgvb=|JEI|$A+{{gC7-N?^UqNxX^!V=f1#Y&tKt8A#{$rS1(9K@)gq7Q4Y zKYy5LJU%sKP?)N4jKR}kLMpHRT&x=7njWHQ%Dr^_Ts4cF7OmuSmR66I;nG$wYGaAv z?Wq(Ic@C3^<7L;D*U1`{d^Fl{uHCZu$I4SZ#LuXmcHap*xEZwLY`)%cF8w^)-5}M6 z+#uVhQ!3LpXDt<`Bhy!dPyBx_eQe# z{Z-9}ol_w$i#(zo_?5uSJP$4EO5C(cie7551T3u7iVq>{1B~VKTNo=uLAEkDu>#)O zMvA%d)A`|4XFtJ_m*%-gqKouZR$Ejul)B;<#C23RKfJK?+w64zL>M+iohArFpunm* z3}1rYqc9}Z0k_=dZMs24{l_l(VD7VYeS*D}qpK?g`}KWdacX)d!jw=RrJo9^YW-0czrMbf%*U&_3~nY?K;p^a52%J_-;>j&pwb6nCVxYQ6v zMKj1Ug!64WK>&+!!Dp zM>j*@HQ^4^SU&OEQM5Ek+l0}IdI<|=%zNn`y_nt<>P*Rulf;1OF6Gkp6ze6H_&;SG zQFLMNn{*jYUduQH%@>fHbn|{cQEi_q)^Y zPHD_^y`XY5{YGc5Ju$iUOMK~FLqA%8`aKwFD2esM)tJ~ydhj*1)eKBi;VMOc4)0qR z9wq~kNSmW{6RWGnMyCz-Q64dvJaJ%l>2~GMLLW7;PY|;9-ClA%Dz7CLYL)s_CV}uM zlK!(RR>s%KT-FlQcg@wCs3m^1TINPZYgc^}gNz>S0l6fs_$x0c_N~b?NdCreAoR+< zQ2)Yh@}SWSy@A-rHHsBDO^LYPy&Q|>yi;lNmsct>X;-Yon|?8ETD5{PDI z&Sj0Z_p&^(enXXs*Oz<~CJmn6xo-&Z!fX$%BfOpzc|3fIP=Q94P<(S#R`busvPZQtu|LXR7K8dDUYLLq@WPl~wpVG7 zs;Cyp@SqxKI{8nBJL92yEtbDdm|M82?EW~JBLu_oG>XURHqIbgw9?NeA&@ z8i|XT@llidV7MD{AXJmeFo``b_JH{E=yagdZa;Nm-8l-@&0}l18<8Lru*)(ZnWO#mLr%P;CeY-X=fNCo3Q-tDf$?{rxEPk75T}%L=8*R>UYR z7GlWMuOyACPN|w27^Ckcm6FQUK)Rm4OG#wPzLNIXl_;qmw!uM~2DnZ=_R16G-%p^x z=`q@M-F_OZRF1SY5A*iMY7^N&b%!JcxU7)n=#$i~5uT`BHVh?pQ&TR+CBJv#(H$;K!uMH~}h@WaQUKcT}?NvvFbL$8#hYRI}^@ds<8)o%W8II zjv1v*Z$KYFH^iN#MdHyWUqLJuJC;~eiR^t@o)4+Z5XP7>0)Q^j#J~G2^3FO_;_EX^ z!0vbHGIDlk%D>4`iNllx0RjF^72!1GG1eA%B13leou2311a?4kUBT*|_5S025EMVjy&yC;vu8qT+f0Ao;Ah#{me8 z9q7DE8vj6prZ$D50Ez?b-5H~JnD@0o?~0+i{dOG3mfjT37L&c7k}o*DMa6rO3loH$ z9;oJgPm{o7!v|ws#0h`j+jT0JWQ?>qi8mqUP0$sM5I)HzTpL|WquN;ZE7N#Bq?Y={ z*B}wqlp#!sbta`2;1CYl)3P>{kH#b^tj41iJ}1+&Hv_y5(c+6s3{=Xcgip$byaUz~rUDuoZn!apTleqXQd^h2NF zxgGu6PtG*8kRGCW+O!m|1Av@Z5f3SSNj6a>S$Zy`0V#{E<|=vMc5j+=rs*CVd*F%i z^7pUq?--3G22OhkFw+umycGwwe3uv+d-0hSPL)X_GLmIiOVg$%K$y>je&Ll73|6lE{Ore-qXse$0wM zNEc$ugNXazQg~FUrx2GO0OD3F)KoNG_@waE=`e*H%X_sL0J#(!Fjj| zz%vzCM(5EVZ!#UCn{)VC_u43S?ar)5N;924yykC;@QxOz@O=86lkXV9Zu+;;yf_o9 zh1WgnG8IzO`(zKa6fWXR(BqR0L+x-m%#KxORI>KI(&#~9H@SN-P zC0=<+RTqO-brUi~o2GVjupSUI#6gSmaREIj9V|zWvD(%(26#4g>|dwn#3G5`UexJ& zoq9S->Lo?5GsptWR|=r0f72l?IZ8m3!Ip{Lete6lFa<=HfJ@2<{g#qv@#ZCFox_9@ z4YX|+qv^tkH4>ocksX)RbF%hQeMb$UPH8g@RAj)6AbqHodCXnFSP^lZy}xdId@nzm zkaAJBfBdf44`+lynvC+bMfy9C6TOQ_{sP-CCH^&hlpWJe;6XT8>b|2#StAt`4hBzB zkTH>6w;C-MCuCOhH61qa143Fn$&=)59ltSz@S)jj&q$jqaXR-5Ula-e8%06}K0g{x zr8*5@E^3!jDAP=c+4`2$G+Bs&wptj{`cBe{T^WH~Z(!8*gNawIF)vMb`L!%ifav)2 z)b5oaspZw4w4=NFu%=9M zIMLo?pUwHG_r?qJQvWpi1>wmot^86vC6J9}*nln3$$Y9l9RE2J*Ru5ftV6xJSpkuA zUq;gvN!R*KO(K$RQYrQSOEh@>q4y)+noG{dqcJ_bZ^3XdG)m^XL?w6Io3mb-_SPTu zsZO8`$Y=?=5@7BoDOx{1z*0uypOUc?jtrFhT}RZ@{za^H=RsqT#D}wHPp8d3#k$Mg zXZs23F;{e$+)P@30RO`ME;0jwU;bcdLjAV6fCN)JqQ8_(ysCVr^&Ur#xTUd z7LAc)zB|q0g8S*^=QFxZk&+pPG(c>p8U9qp*adS?GQ=)D_hRyil0LayC#NXdo%)8l zqtF6vi1$D_H6f6g=-S6&X%!-b4MA!4$dg`My_BmSUP`7GOPm;f7Yvx5gM(-FtH&Me zASz(Hx154{D5^!zzhkfliqs2y#0!f;bld65^LEA0_Oa+4Y8q*M z=o0ztMXipS(cuj%EL8LmfcV=WJ5BajgFyW4_wb+~~A9n>q>JO1l2^qZ${;izBvQ$tL zm~zEM%*#K_3H+Bm0;cU!KlmdTVSoY@rCdES5MBwb>>?hIG7YFmI1%EvHTp4+J7Dl`5H;5oP>Jf0_ zO^65f&rY9}Hs@_o;?Ga<8!i$e|&t&2+adAi4fsIV99^7~iXCjEtt zB2A-wsAoc#5OF1(u+MA4 zi9WBmMgv_Buxe4t?*L zMy@)=uV1Sqg{v@AHuy@ifUkrwzD5DqwDQeB$DuMSYRaxo13qEP#~oHBCzB}wui(B53B6p9Meg*=mpKdq z(qJDvDtlP%mzGS{8Wk^I%^v-lJo@2n>0bLwX*;gU_$Hml`6~Iw`{2V!V!=>q%J+<# z3#KHJ7v$d-vS>>SN|OrPnQdp?t3NrCdqQ@W8Z=n+8x3uk%*%CEYBe2=dCEo(JY=`M z*(_)M?{0W_D*ZbOj*gx&$asi{P&4!3#**^U^v9C0ze*t&Ln!gEHZ|tKF&jNT7NOe_ zItzru5+!RBB%Ir4U0GRCX*VheAv>|o4yI)tykPZ9LqAVWvnn{gu2b-0z;P9jXxD5} ztS928HlCZrNfXMx-%xdIKKQY*S%A!GFS_wM4zJ`se(6*d zbVjK54o?mn=3tOH+~l&*A5AlElAgLD?YlKo_~>_FyYl*`nowlpLaN<@T1BAAVAhNj zpW{uV&DE`ju~x3-^o3v-29G_il~BZ}lfT>kEWQ8!(q>g@_xRmV0bCUkkF#`McPO<^ z{SJv~{J|wHsZ2#VG4b(9kEu{u%3SH4qJdn)*a^!wU|C&R-KS%I`z|gz`c1!%0)0_W zv2K%-H#6Rs=t*Xh#AibD7K+;bn5LVFsc{WzjDE?$?-piT)~1|J-`6FsUmTXQmsI{7 zB<)D+&*ZAA-HF@vE^tVoNUdGd^l(0+dM;p;UPV7|enui_$rRo#r|l;Qfxr7(hM_!F zK9IBEKX7KNQ_H%0CvXwBHew)b*IrOOZvB&PO~3Nfzn_(Q-swv(vgOnf9qdZXS1iY{*njX5+LS zgFpO7Eb3g^8-iZ8GGFc+NA8FwmJ8n8o>t#ad)g8%>{U>m+A$N|pZQ&B>n4TKjSRt4 z^bYkIj$qs_H{k)~LvoYAQp=!$TjpwCq}X;N;e?`EX{mh< zD+aaN4w+eM7B&CU@ZA_=O_RC}JO2}PbT&R^x^^rUZR)$RZ*1=4p2$-z+I0U-X+qXN4|{bz41t58-;d#v}*#Ngj7p z(-t+a1N)qZtg-uKJ`=gt%QQj zWs%is*<=2cOx8rgb2GyWD~Ftf-1fJOW6U1)-Y<^VpU0^rv80~E6valB4z)Q}1sHh9 ze)1CNm=ys}v&xlxRC*5$Ft{)b-VyNn0eV#>X4`aG_@&Q@ZrB4m!26t#ZX~YN(b#`y z1#!LTnUIG|Hn5(BWVuoS`mzsfxNQH2*DE)y0K%76Ou0-q zv!in-bRdkJ8ihMGax$09#hP}LA)@m+aYfnvvGq*!!JU2ktbN<9v=qeBXU8$7LlTZ? z`(%3}*su3ga#w(&TPUQF1{LS>Qs_X0i_65KHqTVu7g{7`l6 zJ;e_&Y;G3;Dluor~xd(O{^vSGn_&qH%iRXM4PV%J^UclJVA;3xK!W)gL9~P0Rw2S~? zkV2-z2?$m^Eu*hMLLfZprvqJ!(I1)yo!abBf%08DZ0DFSc0cKOVF$!zwNt^Gl})s; zs>!USY-+1~S0l+C&Ma5vD>dk*7u7_g%+7VfXu~Mm$COCUgl3^R=Z`%V@5XQwEIYsN zN2$Vg2W7zp(>Ul{LnERd-+<7JV*1ndgF?cDK}c+;)nYbec8MNqN`0EVpxl6InYp z15o_!uJrcWT2c%6fgg9py0k1)ffTcD3X>W1)Qyad*T)C2t1VXWs$C8#Q1Zid1S!Tg zeJrF=`b3LSI=c*$Ra~Pz9UHTRNbwpJ?7ud1mabQ1^PRl5MaFP!5jeIH61fq3&jIAk zKXlXI^8>{j#59g9c7`;T4a_s}h?D&Lx_D$O5X-!GhrwCQ&O(jO!yO$Rb<`&_)0rUt zlhA}w_n%PXa{6YiF+{~ru<(6a6ekx|0vEhUN=^qG45IqFniWKA0pu} zSBNOpgH7mfiM*yS6^oOcc@xjJlBThqdyL4;{8zQCA$dS`HZfHnuYH=wK>e;}aP&4@ zMu_e_t#u?ZRU1#&mlSiRsC7EmLt=i5RWKh!M4C6Al)DALT$A>3EyI2MgT=j8*SywR zor3F0Z+zwzR=`pYkEFK1S;#Wt6=6lk*0g&IC|dcgvAkpJ4x{Nnq8i0GNa>CMp{|o| zw3TIbC0vBApa$2o9iG;D@N+zttTg<(aywqh2+Qek{0|il2|8<& zgKD3IyMnyfhsIeznQg7gP{(QB24B&3z3S=e#k3_K*1D~EQ|YgwqNGm4&$^s3h2F%H z2!2@&AW7rcQWZuOOy_eav0b`2N^kR8f2Z5#)mx0-|E#g|j_07^%dKY$u$M%h;Z5^I z=_d18|LfjKHdm%U!HFw1J)DEV#Melagc`*jrI_en>F$?MuN?Pm=9h8K_3lGy{ov&?vbQ^Y)a%=Wv zs+@RBuvSqA@jT~a?>oLdV_$)5oT)^;cU?IhZkE@WuxH71YJ=uCKHkJgT4&Ut-|dZ8 zMJZd&q|^-ye&Jp`s(qV+?Dj(Bw}+gNtd1#bXF`XLZec0fabMWY<u=cR^k`>^iSpb6@rMHjr9xRHskvkDa;L4{<<`x2xw4?b}6!kDVM%-#T*eL^wVNYn{X|bO8BVKW;XnR)StU!e#>X7 z?5{5xGpkdMPjg!$Bnf&h5D*=w_Tj@V-V)ht?UCkuv+o&dfS9A8?P{hW~t7*P^ z^4)LmGmU)Z<|_eeRW)u@B95I0RaI)LK;K_N$EyX zML@b+O1g85?hxsg?(S}oZbo;Hjtv-t-`=0!_usv?XU}W9u5+LJT<1Oy#Q84`4~{J0 z|FQs39ZcYX7Mm66&vO%I{brT9FT4g_Ij6|Fu|+{bT{V*IhLLbYJTrY@JGjl?QNNCo zR`2&Ii^dh1YWXhw`~!|8Rm0N|IW?_>%{l+*p)erqmB4q;!+7Y_P1+B zfOzE#lyo86!d2IU)1*+3>yQ)F3*arp(j>nn%9C0gU;u*XJO9}cq5jL+d*Z&q>NqAx z-%b${O~yD*<2hD?E1kw~kWS0J0bJpt2`5k&ayc>&cei1uEPvYcf4mLfVMTkN(iBLT z&eSC;g^kOf9v|)5=6CyZ<<*r$eBn%&oX*tUAuz#C}= zF4dP){kCd@gq|8c=y-aSQUYUSm&=XN0{;tYh9SipGIX?ix6deMq(FF{-y3POx(2I_ zuY-yn?{NoO-iGXe!j zUCV&rwOWT^C!n(M0g-q6QDUZ;tBQkdwYMqcUcVJKR~hTUwKMKeS?^ij!stDE2HKsC zT~8h+8uHf5n>xr|c;31lkTOBv9CV+rKgq6~yh*YX%}%U5UBQ}gZ;SRc`{QynJ(|TT z5c+U?vOn$Cu_@2dm0Mv!f_^IkjDTBL*-^1M{qLlRaUWAU})5OyS_wXOyGTgHj`Ht#kdu_Z&af6FQKh^4TC{>f!syCtpUhKsV z4*u2QQ~eOX=pDLFZ3xFSdu*XTbY*loCT2fKR#<6B{-x-;9m!q<#~FDzR`MB2NBF)y zygs}%9m;n~%~e!@rn;S@DeNMYNIep;7Z6NjFi9TvoXNp;bfdWziSS3)v&vBIOHF{H z4d^2Me*V%_B&*HgG(`+1b?SS3PV3Ma!+$fpa_@ZHtA2zy`$asB%VkTrvS4GuZV+#I z+x8YM+icv0ft_;(O4CMLjJ9(}tejQ74zfzORx?#DagELF$bDijBNb;E^NZlu6HwBS zUo}Qd=+oo#CwTZuKql9bRss%hcnq!zP%aSas$OyxeM(PpfQGbB}7)sKpiG zbZ;4x@6F2+z59-++YnZfky5QDtU1#XEN;(dsst%m%cQ;bt17YZ=W~@#K#TIeI-qC# zc=zrr$|6&iT4E|as>9qZ+5J8Y^s}cG=p-t%fSOhQ4+~N8poY{YqCttAF3VU3+U)C?faB6-H#5P;J34Vk9=#oHZ0n z?JdaK7ucJgEbSwH@pyz!-Mgg?c_)^#g0?r+gbmPZsQ`$ zd;DwKzw4e1SQJkiCg-P3X8i+DV)Un!&$veYsExWv6jPo|Qy2d_8d`o@2evox-C2X} z)-Wxn#EYP-{_M@eU!PK3u;?}-hi+TSCn3*LbFEu-OO=N`Bv0!MV~oL87S z&NQ8k9|?f2Bf8XC3q1m$%{XuQPRjl9`;5?L{=H0cS#l3SjVhbleg`k+&38Ugl)|4| zVXbu3m^&U)eGV0;i~Ej|q>a-?v$&OS2;$p4cZCsvA&K1ePRh^o>yo3i94V-r?f*8p z>^kj@DO#7#=`QA|XS!m2uC_!v!obW1FURi>o#pTqnCwN1A{-1eVZ%P3^?Uf3P@0u@ z;3BeV{Pv_AZ!ai~n);zkT3~*xR~I7J;0s(+F}qWa%QC&UC&)8r5@UCqkl%v;#IwPPqRBZ#A}mOf+l#g#;~*bwydf3_IUJhVAQ94FZE3nl3c)MgI;!f z@WE}SRbmw}cAkjJz3JX2Pg$56qH<U{2%fa71F6Q*>GI4|6;QBXjj8Py!W$?AMqAT5RQg^xtUvP!T)5#|l zTT(@15S37w6>h6T)TfJI)U$;l?>QlmLsfw&AZ+M!YSn`iFN>_wLSgV6>4<2$TGF3y zMtm#v_Km}(wxQAa_?W9Zs_*8-+PX@E&aAQyl9a!)q;lbOS8Z@JC)Tsv^6qS0KaboQ zZf6F^2uHTexEXBIMai=)%GW(2FERKbt?F}E6FpO~bp}m-p=q49MyuJbV z8&%$V{vaIC5=ZuP`_KodT1V|nz89A%IkyKI|Ng8Y8`^;O%f}`Mxe}jG)iN0{>~#q! z$Ub_{{HGzNJ=w;owxRr!?Id>U&E9)&!cnJjCyd>t!Y1t*RQ+n4?s1*^KV7g>ZjoZI zo3oGS?OfVrB>1!!om|hq6DC2Q=hNSbX9L~VREuMF0pSo=ghdOOwWYV4D)ZOB~&zU0AwIu~YOmQzUUO)VfbVYmPcgcWgs%T@& zJ{H1$S-g^b`UGnpfJ}V_KpVuaG9*pVrGDcei-6f>;E&8UBtXs=d47z>=c!=7BuFVp ziMdMEBV&0|naO^PMByz3M}f#&qzh;I&34&Rfa4Q7^7JnJ_TVj^?Ms*E%~bQj)!3*r0je^$II`f=Njh^B*(z2tRL)9&4}(jvSlV-SYueHCeu=-azF|x~M82{!`fFAKYNt!5CZJ*$-8doAT@7IQ*V(d~cnmaLh$1 z4*sIoc$`>t9cj;WDtq4lytTv6A;F;TDyvUW%j(?eyj%NVpXE=qoW6GUiOI^K{f_>= zcpQ6759^gNkhBy_AXqGXO5f$A;5gYnj!& zp8i*Hp>{i~wc8>T`FekR>8E&gKxe542tIx%XplpK)}e5$B?l+oS+j2%R?@X^7o6RA ze@xs&Ex=Ya_N?zP%cWZqAlNX_A!pwo#XYp{d6^eo3%}4dedF^@1-h?Sd+<;29=0pP zM#Uc%YMnsfBQ)dv@M}~d-zRQ0fKc>#vB+c%0kazV$8?_XDR`&RT8(lu3X$_#Jc(d~ zKz!lk1^!@DQRkT|K=$8@{-t?5$A4o1jy}|NirFzcMC%4X%wILObiI@U7fr0%^*^rJ zy>k_Gvk#gXh&Sz{JO(OSDuq7qZ4ywUJgktOm8Y><+`rOj*;*uR*>L^pwJBAif*Of<1 zN??lce+S0>HjFF~^>F}2l5!c4NO1BF@wy3tew+<(9Y5YX$9K0)+d;48Nc}G9OZAJ` zoj~!0Ec^D3r)GFDb%qP&NtIOP2FFybF3Feig=FeV%HX~l21CvyWw0S;thPu}DBj7( za|O`Qhn?LLny8&|>MneW{>Z$d1X5lTp6zAJPB(_VrvO+EDoBI&d)T!6$@)ajKr%P*| zKg5(UM=HPy$#8Eh^zN_8iAHL3qUw15X|Y(cqm9gTQFt=sw5!PG`*$ zt&-Z+a+3@>S#y=ki)Z2tQ>erH2fs!w8fvQnoZZ24q8 z{ur7%M(90&h~?YwK2j}0 z-+mQi+-CIaOjmM0+2^*vEqfYFg`D4*Wp5hPV;V_3H}9_c!lMn6#bMb- z>o_%QLC6^!hS7;(om9vZE_pV9GU|!;`(m=8Poe2t;oa56(W}gQF20P;vl^tbDF7P$ z*yD1&!SAc;D^Oj-7=?!DVl(HK!#(ZD9>wJ^YN$ss)DLWMW5cZFNE{@!;-A`hVbgt25lsZm7 zJvt)%k2M$gUEs&SpV+ZP2UXIBacBpxzD!ffMDqYU4i_y2UABHVYJJe9>v3x*Uk8_3WzbAtq1rxR5g2vmAh_;%6F^|>rPR;^a6M@#y@=eqYlW*>18WleC;lYg0Y@( ztCB6RrkWkvom5gyP}W2f7Xwq{44PBUeq<4T?zlX{TqoX+ro+8-fB5iuiS>zoOiJzz zJ*w+YUEC!2WPW73%k9{96R2)a2=8`MIA>*7TGb!?5UM2kD!Y^QmW6b|&c@n}GOj6U zm8{wL&h$C{o6OD&oB)rOt*RZJ^1P8_+22~u$Z(G%)GGD13Kel7+QAeVls3$2AXOWt ztPko1O_yx~oMNs)4Q=vs(P9?a;^wA5+H&mM(U-q+Bwj%%&ADav)9Dx{ML5APmzr85a_DNEcNu>JXGMpyXSe z!SJR+ZdQV8#5sSz?NwV0R_yrH1}@LanhMn`kM;N9vtNF97et6=xrC>8Ay^`4M+c>W z=GiF*1l$v8-(XVfn5T=u(L9^y^JM=Z*Jo(f;9vcV;$XR8JA#+AWOtwHpUrRoTJj;b z)-ueq@MS?K9AdO0wu|jjb|Vz9ADH-0m~VADaHm3$0TdP!aIG{xSo{8B$Hf#4++tC& zMu?DuXuY9z!2M}+fMi=NecbnHa~Y@S;Oqrn$E&QL&+U}rM&jCc4a#higsb{_r8QBh zdu5=Se*FraoP0+1#wG&R{cotE>zu{%!;%YdOc5W_5)_(StuBHF$b9)PLWhf9^S=Ge zeFf|5bzeVWPnWz3kIP$!QMq;}+(rN{A!0UIUS!*NTL$Cl#zBzGX!z;V<`6GMfy&-W zl$a?Xe}-Qd^p5TZ>jhhYAhyzuK_)#_n;ZXeca-Qv9b%}izyXys1KlV?>cV57JG{DT zesoSzsj1PX$0r&`1GL@NDX5=*0=DLPjn>t}DUcSwmF0L~yT_(257IKju9X@dxv!W-F*tC_1gC3`W?MgYX)>*E~gQcSImS=RhL0IE|GY@vaPV4P7 z+*t;HEySBg^7s8~Kcs$Dl>D<9wxcaWv+BBVWA(|!h-S31dZQ1?HgQ3qj))y^gO!;3 zkJ`Y#u)0VNr_+$dCIT^imc#SWY=k+X3T8=lth)UEyhgbCq^s2alZk){T}{fvxcE(+ zF#67Y_g9?lYCA1_NS~N?gKp>YMH64uGiGS*XSUK`)GZvo?aH%wHzMD2-rU$~$l$E_ zxlw7v2({kY8_1L<#>_IAvu)6AJbRjM>SA>{e2G+Z4B7Hs7~tWgmeh{1*Oads%p1=< zub{=V|7f!7J;wU&S_TAU{5Vf*X&$L2`D@gPEnhK? zqUMZ{0oH~XHCyUD-)((uFzzPjUpmveZA#(~?W>>}Zta6KnBYY$#B1!?KWYei-siX9 zTwCTv@SkVqj)OWZ!hOn)LvPF0<$RSPRl+xsjTwTb?^72q-q=3m*EeUu-vIbp*P^ z>UW$7BRyunR9C6`Njmk{Sf3WXRe(BIp$6Y6;)vFJ)@{yW+jtyxCWlsJ+g-oEL}D17 zo%#pIIy2|HX)L;GyM~oNY5=#Z_MXPe1#)T>b-S*|$OpYn!P z{VM-~(W%bLsyzwNrt#nRbsmc)*7)Ojv+dEYBhJ^1T1ah(ByY7w0KtfhwZhz2;8ZvS#KWK)rbv@<=|&txQQBaPW15GOi0;6xYm*;$+4pT4C4KDkfP9FkHNxTF0 zXmjAgQ;rjYWK!|o(-0IAuHtCB{l$4j`p8)vlA_NjnTy9OU;ZHj&jvSx`V8NisvQtV zQqa91_yr&-e|iUfFz31JBJVHTsJ4rCd!kZ5pgUu1O@-mjoS4ky-e-GzKxjl9*O9qf zHn54b^98PY)VOCo?QFz6v$~*6M+F_X)49KA| z=LAiV;+zz%(IzxGyVBS$seIK*E4qRRrt)LbkM`kemN(je{$#=kYdnk~x>`x|JWd7z zgOt5|;R~u%S2xvf(UaB*++d3A_+(fankYyzR2Nu~P@*>5%bAq#l*?HABt!)puAkDYEwta1iy6 z?jU#Dz{IG-C-r(H(!GP0;+6exPhH@1l26GQ&L4hx16#OdD8E#?+=l44TA6+;87l*T zuPRmKMv28qD=gCcqHMiY0pF5C_~U_Y&)S;sNS?W~s@V)F2Z*7$K)*ox^+MdYZKf4b@^oxr?moOl&*mpDLSb-x(91>4=uL zE&pqd`ewJ<&IG=5Gxc6UmK`Sz?Z=|NLOXy|EsT zDd2ID-;?dy+&_P87q)gu|sxIiY2VsCRiAgU*P zswqf|6T=AJFr(>x!g1o0$a|0qbDm_U;=#9Y?(DiQP`&ktkW*0%%56orpw_RL1CrsmU4;+9+A9I}#` z|7=`I4nN8Go5{>d(oSM(jXz}sbCD9f?z3|<{^!df?a72fmQ#4~iM4JrSLF(>)|2Wlp$f3?lNvnk+^8 zc`eu)-5?0*S^AG)_%~-7NUs=vSj5;g$`D^$*Rcu`<%uoJqY;O0JbcN{^-Vue?V5H? zf1EeJ-8~vY2Yr zY3@JMfznI}`y$=Lu2>hw&v**G-Sf27yug7@E~8U(cLRG*|P4zwx_`-isM4c!7#b z>T$yNaYZep!e@QaAnSX}-qt4tMvFqd+S`5&ZAYVm)ud;>BejA+y{OiAeIPFblLQaE zvV^99In}IxE$T}$ZKP#ajvNxDB+dFCV?SBx1Ckmx!mZn#qJ~}Ln-A7JQvEwqqp7>i z-*;`LX;*Gcv+P_uS_qXLt(W%q%RxN*b(i#&rnpV# z-`6Y^ZAZ2lS+PeI16N<#LiTubw3J}H06hjq)FzFZfIvocWV+~S_8ILf=JnzgInS6$ zQ|2ieX`@YIeoYJ0EPCqsF_`!Q@`&{;SM2Baztk&!-V<7I1e!fMgj(Q>L7+pZN3lCn ze;<5svK^PkpO*MVP`Aj7(-HnFXWBs?Nw?MrC5}o3q-080i4542Hk~ekaH}+jskb+( zRgzG`Er>EtAx7lc$-JPyHQ?VwiV)gy)>kG=>>pBO$aecq@c$ww92Y4ps*QSj7{{Qt zCPOFeZhz>|MyOkn66}u@V31Z5IvITmCzvAjL1acG>L}qv2GB@jb0Ji}0@skW7#1#U zSMT+a>MxZr%>h+;)jsk53wkanzvRg#W`^CmB>3?Df#(Mbnei)!X#SOHXHC%{^Zt_x zH*0NYuKUfp;F-H8Og1Y;)M_9=Wc1}FE4nJ65g&Emb`}{^HX9^ve}7p3flrA|8Tvp{ zuhF89tPH?b>t6u|Eob~CKaMoyFT;0az5DgRu`5QmL%x-mUO=fpx|21{Dz|o+tNg)S zfT$0_)r!dSDm^{K5Rdl#ov8bKwOY;fdEXylr40VxjD3v+|E^IC+(^e#hgJIi)ez-- zSBWL@ur5lC3gFEhAnW-_pqD*A0Yeu6Z4$>SNnG@ntFFZCF*zqbwp?er-s{Aqxw0ne z5m^s#6zAm^Vn#Otos0K$lI9vB)mNmc@A6HAVE&8BbSXnh#y-qjZh|z?|9aZzv;ToX z-IA0E9lmYK{n?5vR~>+|{JQ9%US0O?1(O_mki7Jw^xDaK^_M14M_H(wbl4XUOo&_d z!>1GQyK9iRGd0+ro(BmldlXk3F&i)aV-%AIMBJ&N;W9&H>Uh9&9t=BHma@dldshY&M6hsQ2KJ59B z9S{eIi8h%O>nYOfbO zQ@;9Edy?<>cS3UDYaxfn097+c~agj zQZwWmoXCtOhBvo_Wq}JStcGq3D`I4saXIFjK#@v)g<(o1&=|xc9rhm37l=esv47A7=ni!Ann^*anzO?xXfRlH6 z$8-W2(lW7ugYu{bujmXi?T~6dCnuf32SM_f(MODzr5xC`qg53A9_@=$!8|~H4>ApQ z)j21d9cS;LLgqiPK~caSDX2*j@2`fg;XGt6Jg+KcR&mG=8J$P0G|&9LZMJi{*({mw zA{{IX|A$owu!)(3n8wFYCv=XiT;Di<;0h=q(uKRBYAY54Y)C8u=d+EFaN-xll)vV{ zA(desR!_LK^~rQuH;EouQgY{$alWE$;m5p|`D;wk0b=H;o?;HK zcQ+9@_~LCjnU+;{Pzc3LCbF4ClW)BOMe+VetTQU*o}daAkp9^Xp&yD})abP_Rkex+ ze6E`z^P%(R)|A9^ugOeXsEhQoV}Wsf;N*|snY_Y-7^!h~L< z8bSa?IXR(YvVhwCjXpOuoLsyEaZll%vFb{sseLpj%(!(LnlMQ65S$PZ;S7(=+!W0#UPP`>z@VevH`9 z+3zC&<-Um8R;P;)%j?d%n|q~|ar$}caj8s*=(nZ;a6L4s%1TJ?rj&zbEjof@MBG-$ z#-~D!!QaWK)u6YhjrWwq*LSg}ofoxKZ_@u@kuj)h7+KyWYyH)LM!R$xFK~sySBl`O zu044YYc`OHH}mGdp_4l2>%wUIuvtl6KgO1d<_Ppl&mL2L%u)`sS3G@oOy%JWe-8-p z`4;jc_!UJQ%22CaQ>t8795Xd1sVbR5r@gH6fMv;+!@1eEGK)pVRh?)y?4onDUkUs= zaJq$(8H8vigkT>OyULICBo0~q?%(~W*bt-_fq8GNbC#;~_$ur^ADI@MdNvXrt@lb{ zyj(_=dw6)BzQ;8)wj4QW3E8VW=_`&6A<|XViDv;^xB3IUm!w%5AFMAVO&K^-%17xb zX_8%z+Cj~`SC?=6?w^OArL4C%y&f+I()jEj*7iZa!ACK9iVjQf^)&nWBD!1IAnoy} zocIU}Qh?*v<1m!Q&R@&DPxR&1Oq{fSI*nFJ$aK5{egj)2aUWQPc2w++A05=WSFdD@ zhvaF%tXtMhJ%Gd&)xk$!LZCss^JTXXN@PxP?tMi%e@S;BR104SB}ESVGL+1E`&r^3 z=G1b$)DprxPZi(LE<}@kfL2-dY8bZb#@q-YZ7LwrTf}?S*7vn^w;n(VMmQd?Z}s1H zGeaqFntxQDH100~OlF~?g#{_L1?D{^*KCc~TrNl)V4uCI_9y2{E&)B@*i!Ul~#mWetYtm~_}EM5h}miF?O z4H}{n4fRxTFLf_kYg$e2nTbBq!@PUYh>WR_LVfmUbQ7E|>d*Rv6};dQ|HV71>|njr z02zrENBz=K8Pif{!QrzH0vl-&dw5*ifH%Wb@6b1lMmSJcFMU0}{p!*lG7|06b&4jP z{1AB%=iNvUQ-|*PF)bhBg39Us?``q;@@Epm6>J#(ec;t}BR6Pz_f$1{p7k||1>J}j z*x*We+CpIdQ*+cXI4#+7zYd`H-h$cd^zz3_;fo3?Nm6_LPggo&wrX!yt`gR@5$yWW z?fX^@Y|okBfXwy_?Zbuu67M}P)%H9}Tn1PfF#K&p-D#1YAAt4i-7}9ex{K;#0_2QWp4XEUP@f>{tZst1Fymx_p0@FHam1{8{Z%oDfORitRFa* zyb?MI38l?u!bhB_+J0|#J9LF+CTXkHEC$X=NekTamf*A0;3X^Ape(k6Se;lAW^}GL zv%P7yS`yWa(t5LoAiEqzs%5gz89%A4Zt0Rm6?WhOMV%6d{aBf!IP;)XBK%cFobFO} zRPI?BTTSg_){&U(u3vQ$`=%8ypaFmreZT_tJDZlt-1hH}ueD1p{mE!lOo;prCNq&a z2r`DC=8lC^!<^s0ZECGncq&mZPXGNQ)2JHPX)NSm`c9`$OOyH6cBMKL!|++0Aq1Ze znrWjT1UXiu(n036dRihE9RQ(VPYu2Q&c-9e*MH ziE%WqxC8vO;YN63%-5<&Ufzq}*NQ8y3C~?K zh#_DvcsgOKOB!o$m4?WSw}LRrOnf!C$q6HaNnBm3f71VL5${sI+6k1jJwZ$vf4HojPXJb3&)TJ zma~zo(jVz;@_t(f$>1TfC3up(96XR&x*$jxOI#rf-KgpJ1DIN0 zPCiH%L!H$Oj1?%u*|4LjG!@kKp4@xTj#LZ;oh9=YbQ{&IhnXb2ddKDrbVbP_@(Zo> z&YoBkvA5|;t$wPobHvYaI}Y3s%T)#Et#^GB`w^av~n1&NINvr(!C^YA+2#fzT(t@g1LzF znqCwXJB90o7#dnjD|BLC{J_7*Q0(~Zh~_%7U-YUWBHi}Lyxfq_85?J6G9ia;LFn;K zT_&T1zTR@v0*vQ87WIO^u28jakYkw@QjX9xtkr2>O&W}fZ7m*kiX?rC9T72@$iql` zixr93I1_Tv(|`%6H&r}rtAFIPSKBaG=!aCCy{BiOFCK`ToDFfEHvH2v76Xcz3T$z@ zERW0Z*mTnYEQBjk>e+{2xg@_=xRFX&#T2w%u4b<=tkYqCJA3MluUfg`ANv8LybUnR^U^^D6Iv`F*F4K2gLab`UEP6o}ruofS-H!o6 zSAjV^``mC%4=8Y4tXi;S#q825@xr*2DC@o_74c4y^0|OOacEhZ0@-##&t386KBjs_ zyA#<$o`0x048E|Zsb&Jk;0EmycIgC@Nx8@XWnRb;>Rsx`MDjI|GL?)`MXzr&j+iCs zx%QWz$waI8icCrwe@lB&SC*NS@?Q9OqBKF}Czuj3F8svoXLhl7e)30^Fg1y`Uu9Q| zhT!+>G(gfi1zewqHfXpagj|p8tTov$uo6>MnJ6??*HPU{GOF<75LmhC_^%B;Ckmu*I+y?x>d)J%7M&{af7EeDeT@`l#T28Q`S<=}=brVu;zT z>uD!eD5(@3jDDDIaIF4*P1Ko?R-tGG2ZBD-Q}A$_us>Bo8Bim0U8qKBC3vtf9d%HK$wF06U zOhF-?lzY@aT=BRHRn;Gqe*D!=vgoani|}(`I;;t;O@AB0%4sn!rqg_1t;fR}tNjI< z_Ue>TbFvVbPeMb8TNwz>{n|2voVA`3!O;!ePxv1Y(maMx7`z$l51&@E$M2)~G=>kR zt%pYb8PDr!Jub}jBirq_c@@Pf>k&Mr2dpOiI2j(P*JeWQJCu0(;(F{e$*!^#*Elea z*CsbrgYAldtUK_}WnZ_@8Ux!|o0Iji8!B$g>!XT6l?v3!AMqy9^YmOv@g4X`Ew3^) zV9%W>{J2y4tWwJ4guz1M{~&?LPyF7PqNe*Jk)gO;kBtO%&B6GxRf(dkwYr5&;Cr}r|5z`p^ zCN(W`Rh`6?uO*!i#-iw+YJYSG`11;0cAwS*#t^EZ#7@+3rZOF=yV{Y2RMP1Fp-;ev z4>&%&-L#}070#Mo@U_o_eT>}REmjQa7yV|B>VSRHdF|PLO=o$NChFrz;9lu`vBv2E zYrz+3k4lNeGBxfipEqBc2^(MA=$&h?@OgZG!#9T-P6xOKr3UMEl4OayFI>bId8ZnK znpuk-XIcz4fm?L3ColhtM|OE!R2FImiL*U!pe`d|ih1kjD{jhL^fJ+&PnWmPd6DJg z3-dN58P7SWgAGBUmRE7ZU)E!KrXa1mq`r zG{PtU^zATk3R@}Td=y6jtf{Jk-7PfAbVgwqU#3>}+2_<8!v55Kxw1Sj`&ZInGAXYj z2nS2?G1uVw=w*n2&CgZ%)^(TFwMK%l5_PN7-b*S$moIlq8|DvgiAm=RLJOWn=tg$& z!Lw5nYq7{#E<2459GFf#@_5?Cz|XrgCwQJFMfG z9kv$BbfHV1?&rNLMw%GMD$|d)PqcL!K2vGj48Q)Bt_mDnJJ`7Kn<#X?EL>>JNCRU_ z_?(G;6eF(Na8W!F&Xkia8Ag)u?e(pr$FRv;i8T%biruf7$0?%l$?c~t#D5XEe zTd_50(yp(2*{zsq-?^?-fk?U*dVgH^v*tCUZDr<9eM2NOU&k@ab^)`vf||>3m$W*Y z{_&NAjVIs^i?nY=k4;;aGjuSFCR~tI{b}J|wB+<-)eO=|HE`{ZpbBm(Ltgn2)Ei@% zYrG*Vu6gT|!z0SL-X%yS0t|jJvHWxF8o%uu+3E8ezf<%2A`a<5VuQ?Z1e@v1x!2}V+$G5T4)^4-Z^?n9Fh@As&1x8a%-OQ%2L(Q zEr&r9ZTxq|pL{87#a-4dbq~@PSBqWuH-vY+T57kf=hv)*T%!%gy^WIJ~#PDY?n>2_0cHL$Ha0u6D_%6fhl%v@aLN#e*krR}}@u{4PKH}G8Hh0(h z-Y#t8IPi5=xNk!aF)_huA;Z$9;-AVYb-|+q{;*>_rd*B2UX0`h<@u=r_RKHlbqG78sv4#9jfM8(M6{ezL zk^&k1C*j_vSL$4vgU*9rQMB-Wl7K6#4L|r!#eIF*?IhTE6dReWT2NHB98rR=(wLZr zLGCfqI#PmA4qel3%9*&9dQ9qq4TcGv^`pTM1b%|F_~IW1lU`+ZTE6W4nEd>$!oa4u zq8Bw%k$AWFi3LC-=JGp>MOCs*yv7WA%gp!xI!QD|e|2tb1zQn@5tMY~^Je)%buIq-gf{yQ(wWScKbuZ=ICnpoB&j3< z4I6q+UlkWL>q)O_`1Gk}?4YEIV{@U=L#zbdXq~Ui=sMEP2WiaO_oCo0=U>I?FT%4Q z%2;tk9yed$SR4Am1RV;8P=M4-9i8Kg84Q}gPaHBWcT3GM+~|A3k%&JyS_AspTSL*I zmg^4)r?@mVmhahO-h>*Y=M2ICJnAOETge`)@pu@~uS8hGVusw3&OvtKIb&a)H zqdCX*+mG>?`?0IYV2UrukY+FC8%TjSLWsy$72Q#nLo-!1)3?VnP)CC^dfrZUJx6n> z{1Ze(gH{;NQe#~Y%D3~DRjfZ#=-U~#eES>u8CM~cyTMb6LNoim+)33M%m{3L0!^!9 zsFjQ0RmAiL`<_A3pJ!%f)Fc!*bU zb{;GFr`d&B&`jmEci5U5Zi&#BU9%iI>(JDs;S58$FfirGX^?|;&C{KINU{FAe1eYq zpGs0#N`$BvS+={!U=1HGVA3igPd1;tnpK>@kB#%uhi@9)Xuq3Ov-6*qyid;_4hIwO zRUxm*L1%oj)kTJQy@IGdJ^!0gQWFaHE631pA$d@D3%gt?i(GbzC1`4&d5fPrvX$lY=&(M(oD^5&r;4lKU$HNqfqf**kAL6%VQZ^M zQRVPpwRFR_r6~&=keunaat>pYncw~YO}A7b!M(K~fPrd1jI5FtyG)@O_l*gt2IHU* zvYp!ej4U57Hu9W{xmMU-VKE!SN(>YSq*~xD;{(Y*D$_w6aQ{KOxV@63?*|yxPYVcm#$IrZ; z@25F>|2^F-D)$HYvKHBPztX=l1M2MiKBGOnl?-3zP#P@-jO}fItbdmT81pAqFH>nT zWX+#|TM=GfYQ$H;cY*+8&#A{siPv78wOGbfYkhE}bpiVBhli6peT%@YPj}zIy$=n) z#&ZBe(~zp$XwR9T%dlpT8o02^leM?D%6Wbuarq31L7o(ftHK$r)LO75Qshl8HM-Vq z(aVcYR;+A#B6t1$_xt_V#mkz$iu?FSSz_A`_i#pl^NQjcP79kNwkMy)hOQd&W9oqn z&RNKxGm8k`cjmaL5W{}ik!yY`)Ohgyzl%H{bZCQq&trWXyt%)R?cBZ^awcpW zN_)?`rcmad#aSmb4@~%#Fk;HO@p}7H8}fmQwbvsVJ>*9Ugek!8C`*1+r=J{E7G*yh z6_bvLjQbN|{)fu3rEkuKCF|K4`>j(8Bb&wKpQ9F-)c6yBeW%x+6f$dig_f4gU;iTY z8PaIVV=I%Qmw$&I<$mel&2_Ras(^L2Kal(VfSz{KOg7m_{Oj0@zoZpNq_^!7IV$iiXpnI zH|KR=h|C3Px?DPHL*=V;iz=oK;E76>(tCV#`%YFhO}FshRxK<4j} z|1*{^zOWRxMhLmDPsNvrurFz+zeu>d($?PKm)f%W@3_Q(J^u}AZB2Y$XT2MxfFrE5 z8$M8VIjl7+e}QZ>)2mqib=c@e*|@{m-L81784rExW}D^&jo6lZ)-u9TT#B@BxR z1^sLEpu*`=51LxtPnG*%8sbvhJgLfS^v#AN=Qt3u#hv`Ybg=kIT)VXyOvs3&_+x)i&)14Q{7q>8@&+Kmt_~;1|?NV+6?ww`cL0bkRLz^(axzSvDfwK}A zEXL9^RpEU=3mS`^E=pT;wVB&cef6k2m-->Bi&NbWY05Rt_w%soiBCpHX?QmtOINiK zTs&?MyV(0qHXP07JzC~>!6t(VU+bNgUT*~$bwE*`4wpuW3CJuP`|*b!jRakcK-@|b z7xJTERg1T_wTJJK0<#h&j1lhytXs*qN=Yd|&U^CJyp-eU7i}b!2^Jq_X-(m+uG>^! zEHQVTT1~5B#|s|SJHe!I!`_jku!pdB*V{r3I$6Rs;!bTooi)KnN#cC3vnftu0z*Tu zrgSIHH`3?H*BlaWmR=Za=kgmD7Un@E?nBpg0fV(orB@9uZh zE5p_|>eFGjP@H9}t_S2?W?9qyfnl^3Sx`xRFkht}-DtP|vvL7rok!Cvb&Kys`^pN<{AwD!4xZ;76I`nK%&B)L2r zQsq{U3FNY()>*Du!TeBpYXziCn0F~@lOZ7HRm@Oz;QKxOIurcYsq-XO70gc(A?5|D zc4#BI9taQYjZWv0(z;D*(r!fB3|v3Qr-ZUky*(J+-MvO>8fGwkz>zni=Bs$$IIDpypyL7DEKEapTo>kv0Xuy9bp1&j~8}sA-h>MB{ycRxmt!X#Ry6tC| z(;!dgztaZlh`H;?P_^F*$?=({9Bdad@jyPR>qF5i&CZ@|? zhf(+aB)3-j$;N3q1DoU=X7y8BxZO8w9>9DhURG@4wHb^!+s+WA8enFhV-o0?E z!1VlAMv|w~f`l=Owo?#RUcAA4UN73H_KJ-`41NVhZys5D4O zhX_cDA|NfL(%mpfcXum@N`rLF&kTcRKI z9+gsIIztAft#yf!v`zOsZ_EaX-d>=dygZF0h;*ZX$YC#UmxhJ>OdOwF{o#w|xZi@l zfGKn0MovP_{$Xq>CkUJ5=%JRvt4mM^nFICP)t2+ar&R1uR(cZBXdi0*a8#u4W$lPJ z_;|WCAv;#0_X#*dNzKT}m;GvyrQ_u49hIQ9u3#h&9g~^bYw*qp)`RPxt4j#-U)5=x z(XkS{Ot7ES;;zvHnPSG5LF3;Z%SEQg3;J9?IhUx2(jH4gkN{@fIo^OIg(b4aiA8hgA)TBjI0(~9Z#~U+H!90 zCq_HL@;+#@TYTMlTKQ-}zk`kjKpISOUaft-zUo?yveohL@>*Yz1t>P@a+}sORaZtn zoccmG=_Q?!)I68n;;%m6K}VN`v9DibP#?5#>E&|o(}_AAfJxb3CZEYzt@I6qpFP7v z`bYrqTw`mn5OdrXJTwjGOzDoz+9e1^u?=O#efUl_B|er_u(eLAwBIxBV!y zz9*h-m*>nzDVE29=-_7l^mMGFm^b31&}V$irw+UTHn?XI6VK-H8N7+6a?&|TM&*}5 za1o%`g*(BENzwA%sWE+(*G4r$ApN1vnZ(ga*a<$QywKTwRiO5@2IIFY###~FA7ly} zKpbMZJyO|a;V4_4q0o3X4iJsrk$iJ1kn%d|J? zA(Xk7XiCIuN+@#qs%F1|hKPV@(?Kw-nb3vteuXV%4o3Onc0L59rp9{hfB1g z`eCG~rDS0SW-KY7t)xdk9uR;~2yBz#rKbpbJp}`4-YQ^SV+BKdEk}+3URx$q9JZ3qzNMRbRB?@8vlx(N@4;#N6vo z0%~#}?Gd3Z<$_FN2H%?~FWD7DRxzo}!xs4E#)cm=sPB?WZ42>atv(@WFiElwjiTl7 z7b&+_jq~Ulo80-cPM`#Vd%J1f4%IhadalSiLzyni@~c)&S8EH*NuZVJ8bG3XoE?s8 zLVlJz)l-~z{W(_o39y-JmUNnTRMlO@E<`yMaLe&Fr!3Jh-Ubu|fkGqUri4uSQ)iW* zNlW?PrWSj?@7rXV*67N1+EM{7>UGV}GK;q8VSVlmt&pv)4|btCE&HGWN=#eVZz_OX zo&@VE{TewpnjLx10MdC;P6}mW>N-|;`&gdPE%s>AE6-_`9;EZ`>{JwNcq1;pMgxIL z^0FF|LXD?LPmFqepN=(l+u0r{8IDgPExDow{VUGExs9a@M0sd=x z5GwF|O@>cuutk7Wn;6%oi}Fj9v&H|EA`!8z7k~WQ5o~)^1LdV>aczywD=+v^G+z+5 zl^(r-peCWJphDme=IGy$-%jY?9(9Os1Y6g!k*d9qc+?m9Zj$mB;}IrubECNS{64W? zq@CN$y!+SlJB_>iAHLL41V({TLzL%M zCzevr2#0X2x@jg=>zyF**X-UYSim8I_&CDox6AckpXgMq8ux1Yo`kGvo2X~~6s5Zg zPvHEEI3LgBf+rnWT@J@88=;`W_JyPrfZl&ln*HLxzTrZi3029I0a{ZdAc*ua+eqjOcVy6sb6}p z5wo^}Yp?qHSv+5fbMOCRFqOo%$`{FNr>4^WI!~AE^PH*2Z`v4bP3UUt1Q~i_6Q(N! zT}4mnL9C-F`(7dhP%rafvfnP3B-{iSo{OO;bUHFlJ`5m~af3+k1B17geysM=6HQ`*U=yMaVE5 z*B^thoSMC_}g73I`P5CW4^l|%FT zZzhKiEg3}i7HMMeD)4cj}9qrioGrC%VBU>#{cqE z@OF0F!PyeOpItV?Tx5;xeE&B!!?>#W{e;X^qApZlf5Mu{e6*Q~+JFzMg}IOLmz1=a zzARS*dWqc5k?Qlyah>gDP9dFV z29!*#efD;Sr%e9Wzn>vo4E2WgB8U?<8eD$o;sfu?0vt~IIX>UC7fsn|4ow}8m-!TK ztU#!xH?&kocYeQ3-VoGWyrOEo5ZwH-&NIq@240Yr1e4zJsbz`jm1USMWPFw+uK(+~ zkQ<6}CRPr%xifZvITC^!^v9@t-^iJeGrZ6!GVkQV?LjjVOAc5Tad{wosbkZg4 z0ot+D`$>HeNsx*e=AD_}x@(Yc+DPYc(fP=IlbyTvrah?i^aM7j)q;iD1%7qUCH>6e z&x?%qi=(i+gFxW9C5OTvFMjU?xFOTHFv+ATQMSOH(`>j|2^1UBmIhDQ;aF1{SHaF~ zh#nSyDTFwF&TxJ!CeKJxckJJbiN%-7z)Lb_(>pIZr8jukocoXm4YiE0rqNVPZ~Nx1 z=@;F&@;k_fRSQ~KeZbA zp*vd>D$R>N+23VDS-;@Ed?tQtDzl6OGC%xwr$8g%$Euja88m4RTsPi)eDuz8vlN6X z3`nZ@a{=0H_8tC>=ZU^q>!I{q0fc7~AQ0&0=4WjC*S}9J+{(aeuzqpgIo8N|TDQW$ z`=tBjy-*)nQ%C|21MWAf6dOiqW*NWucm{@hyf1r{WphmK%fu+j_7KEKuY~nB-kjFE z=?`kVMD6OEyAGa z{$))BoC!NE-W!ih3vk0bd!1}?rF_A8^=yxTiQB@=)pD$;_0VO8c12>{+$hpCk!k_F z=G5v77b1kWqSPZE{M-Bfe7WxMOH?Wi3L(70_#@kYJ4`CDnfOuG-kRJjDa-El1h-wB)dkDUv$Y?L z+?y%+t)J+o?)AA}4wb@P2JsgSP7ZREp$Gv>NHB<2VD0$LZzlf7Ky#%GFV<(V2X$># zwB|fu*o!Rv8Mov7Mv&~?v2S#78i^I>GRdkmxwH6bW9o=!84~V>dS>H;)H&PrxzPz8 zrgrEfB-6ERF5N2c4Xj;#h4vcqvOPl2d4hS`X-rT13mTpfeIe}nf>bp;b1F*w;%&`J zszr;$^?uaeoF9H*UgGPAg}`zdEhlKwiqWk%E%_6xKt?_*_ZC|=>~|Ptd7ap~$WZi} z8i5GB_KXWxehtad(QwwxeP9m~nDsp5cG~zU-c>|k)}Kl`AdcL!-L4!9B-PaAQA*)u zR!V*Jm1`JrFGk{OUA1+;lP*iF{PLhTXfaZxxO-8dmDcfxlr~Z&cgm_-Z`>$|CbmQ3 zWsKPM+2Z_CoGRYww1cXa%ZyWNqK@_BmnEYf|Ii#?e@LIZyL%`0S%%TV3LV732By=J zO#17sq~QwMX@H!|^rLVC&#$HMkPIHA|6{pU^L48CjNB_&a~aN)52oE#Gb-m&ft$Wt ztEQ}}5Qmwk!FP%S#ua@Lr%k5;L3G|i^?Ti_-n^3E!qIEjK8CeCm!lyC?qZ)n$*ONB z)A0us+5uiUbg)=paP__hxSqUXP}@AisU;_fR(Nit&nt#X&m@|@<_3haqHKD6DDzcUsb)nAw9mQU+x7-++oddR6ltf#!;mu zv{_gYxIH2ch%RWe1Salr^Eu7>?g_$U*GN$@jhxPP&Ub#Jpk(JMO4-#(HLMY-!}<^1 zmAs*c`i!wgowwlhBFXg{e29wU@q|%TJ-tu&wlrY4hcx>$+^ctOD34Cp(V1`n)yIVx z_6iq%V5og%;N?`GYmAO+93u~0UqBsfT3ow=UBBDpF>YDWzo7GJp&Bx0HgVRt>&11s zKo09-7r+ja6l+2w2${VuN2HRG6UarYW+`T?7 z@d?OF(ifIA3BR{*>dLOYbIOJiZsBj^wW%}1cvS4t$hHMY1F+l6Pr$Yp>6g>1;$u#x zQd?T!l4^wey1^p|Pvnw-BZ0W)bL_wD-IoA(A0{0n%G)!H+b!vex20rM2K&)_Lf7j| zkyhgu)i{gfy7&8hTE25z?{t4U(K$A1|6@jboBF49d;K=veB>OS)wBQ&aemO}+Try2 zEsd^=1owQm7E|mV+m$cAXLcC9HT^3+r(Zj}L!OMNHQGDnN_6B5jL@`sf#e)y0;mI% zdxxM8bFWkUr0n@Rnieqh;VAsMUC&jK2@{fHI$Nh-T)eSUKfIgO)=B;_&%Q$;a6WPs z991u5DPYtFHqSiu>>a&xo4yhGYL8^~b+J1IpCgVVc{dq8PZ&2XN(lt&j$H+(o%FkBqSKWNJ13nwN;3pW*zPLEzJNAY|_1@kNx+ zB@Ea9yE`PmRQSFqZY#t0a?p~78w^V z4+jUINv4>t>bcA$)P|jH8r-Cw<9EDwJzq}3FY(&8XdTtDp;^hScRh(PZ6G)Bw5zH( z%W!e_taKDGbNf}GPx?yBC}3|z5casR;h-mvd9Q=Y=8oWuDwUJ*&y7cq{z%PrE`F zYoGX%7%$E2eeI3jY=gH40f{9gC{6}t-CV9}`$$d6x_ydrJFTD1sC;o^$t^%?92DdFQ$<ge}B0i57WYdnhpQ{jOkGO8h%dwOhV!b}fmoPQ;d!$}bYMgYgWfeA%ev|xY>hKODkYcp z+%;+{$s}q?cZewG`nmcD$gpf>P|p_WZd{?$vJ|K@A*{$USnOQ&GdhMy}l%UZfg-Mr=yvp>4 zf<9~=rb!WM5-XYnU-{t)-=6~Ws03XFj++>BcbRd?NP$jY<0-Hf>y{1#mU0j^VKD|N z1Zg$2Q-a~N9$PUnq*0;=^3;!z%C&g|+zM~X=L4xG->vVr(p}pc`Z2X76&c)Ij7^9z z6gF7aE+=YF!TEzT>8{q~=5ymz4y4RPI>%Ov>vvM?9~)^jW^nMjFrce&){UN<*-0t! zF|>AgxJe_?_f4#92~no28kJ{G_Bf*7H1!Q*oMFk#s;B`66QDlOy_a?IGrt@w{3FtI zZ0b9M>ApP|3-mS&k$j!P-cQWJ{O%@9U@liRXz2!Um~p4B&bSAp(qftNN6FG4zIP4_ zA*^H_F9O#~ypIbk={|fE_je8vNU9q17p>}k8mzz)5ZV-Ho;(h3nOT~480^20gIJ`k z&56ktq)nb^i0{6gMO=(lJ8Md5r3zgGj^sWwH0T>{Kr-hD$H5WJ4bAsftHr(jb=|)b z9?24j=xMc1%OY}{fTihB%;>;6Yn}hD*cd*<@hEEDJd@yama}EDamsSbrJU2WPv2?m zb9o8R55q!2Kp0>x3A$NgmB8wx^YIj9rFRm|3I2ueC(@QyY&IA=g*s)DWAxvyY<&_% z!y6vlOo9!TJCS7w0gFEUtctUPNXxpV*%b0Xi%d|582FWL8MI(fb>|S5ph1hyZT}wF zZ=>Ptm5x2_+8dTTqdNx3$uS`sdf3g?ZfkQ! z2tU_RJwfAl;-;c53mLDe&BZxUE*jk^p1f%qTR2LEGW0;y$FBAXewjG5{46HQ)Bi0W zLuUDjDc~!%s&Jx9ltvkyAaf*M34% zTizV2{358K9P8n>x9CI*--Crxm(Ba&Ka(MPbkxBacVk!2o2Z}=Dl0;kU4-`hsCEn! zr71*IkV*8s-w%xnG*CO4N>feO8EALNCDbFXo;AXT$_S-F3FoKdq*bC<(e}nF3uDe; zeL-))pxb!nOMym#L92x;^iiWf@TA`i}6`tk6BfV_x*?E)Xo6rsi!213m;IpDd@FA-^@D$F-kxN;O{{! zjpF9(T_UlA?DOrYms=Hs10VKi%JPJ)AHyS-fy--HqEF6JKC{OTdXl3V+4T3?>p{qv z%H0H_{6T2C=a{g3lbuMJ*eu{MQ_Hsv52MM&83nKuoN zd|Gt#Yf3g*gOXD43ROe=FC9A0T~TxuGMi9OCeBIGX|&`$FD^r58{;9AC z7I3K--Fakv&~l;lI;x-%Q}J z58nf`@>V<%lLF_pB*Ir9?yo@}H2w|3i{X6b-Xef3k{I#A6y^TLL%tHY?o_3<5M%C; zu@oNFaSyIW-dS9+HX})VNE6B`hFX#7$}Vcxm1)$GRf0u4TjrK*KFig;E#sby6n;tw zj|3IR#obY&Z=)AF1dl ze2z*2=WEa0c%gqV4llXy_z~F`jozmfL9a#42Q_J~SZt%~*em*pb=@Ri(#LZohISN- z)sV09D2_Mx++$$~Wf$h~oQOdY@^h4b>#5R76bDgy>FNXbQvg*z2#UU6p}2z^-V6duFbe}fzR(h8NF7|w1HL~=lk z(&op^=G0b*Q6?VP7THR8QnMIIHCG&XASbN!ZKEilSLAcc1C6HnSUB;t+j+AKlrBz9 zmXm&=Zv1=Wc4dE0t5DOZKj?E~K%YrD2ifi`sIA6m^8TUKRJ2gjnTrzR8-<=W1KkdW zm+N$ecpb0c*CHw0ex$`JjNV2s84I6`kR*yABf1>pq*HvB0Rr1DF%-K|qF8*^T}yGye`Ht25uMN!6kn@> zpZ6;ECqgucTA;*=V#MtD6UmU~h1lkIqS=+D*In6YFi!|sY1@l?ci!}$KFHOeZB9C6 z_fy13fvk6Ij6lj7_Vz0Uo)Foc`wG8f*@oQfKbf-0$~fez!rMUvtGIh{hJM~Nr$H4` zK?94tQj={d_o-+wEwyZ8m>0upwqZ|dAf*~p?}>l#g16Uo!T)9JLca+&)||ldk1?)7 zs|T%S{ig4#nW(PMa3_*$%9PLEydlm?<2kq3cU2sU5Jb32ru(laG|*qwGV;ntw`hG>sWhq9^Eb(NTY4$4}i_*`@ zCkh(K-uKuQEGNVfP1`g|N_Ov_T(UIjS1{a*>o8-W9y87iX^n znB~$SvLnGR<`m^O6zJ|^@V!z=jePx0At&z`qc^E+sL;lnY}>yPEO#lxQR1i|Ru}-Z zE>6w{0Ou$PD@`{Te;L-^f3VI4Hq$*%+xz)o_Riq!RTOt;!K*umN>{qcdlv`FzQ|3S zgvt0@044WsV(Qk%?SN(mKe|MWsktbmR*|6-RnY0+N`}lFj}WgBRuwM$9@ZAehkfI) z5-s*K_HeP)sLWiW$F38@3W@1y==L!hVNp{9+ALOSEc@aW@JghHTvo@oW@CL_E!{GI zS`_l#n@3gQZR$bI+=}zPxnrw63*S95{n^SvksMfd0WorG%k2v1hp*f+{ksldytB&{ zb|+%z#Q$^aXWE92qzB=cc6o9eAH%k*rp%gC3DV9!vlzrQcmhkiC!Sl;H6tORO;o~b z+gz8QX&AwAZ|djNOQF0TLDgsT4~+q+ed7&5Ry-k`Hco$Ps`e#hhicDc^tUf!Arw009fSH#zckP;U8&r{0>qzu#aeIXSB;T8NXg50VV<8t@S+N# zf6gpr5&Nl0%yQMYP4Gl8uGfq~iNc1t?|9rvl@cYryyU=5PPjmzsA88*81E?+b`?QA zB(BJNSu!2ZQD#yXoTRWK&MZs4Uw@?Ycl>J)7B0}v6yNRRz7jFOC)TfbPj2Wm=Of}d z_aHH{2WQqVtImIoi@Y;9bD7U=jW`z}gS}|Y$?r2-I>i{ zZ+^r^h4Gv{hn?weSz)UtP4CKiYk80J)(TA~$P60HUl5~`h=HMSM(zJS*sF#}!bF;j z2)WJ?)=ErvHspWymNE0uR~eA;cAFv90nK!2N9#l45G+Fp(9t_aYHOl170=ubAfvJq zb%SjZz^|{gD2-yYSOlkSW#GqtA=Nzviqhj1%2Dyk2YwBPhg1kF6G+>A@YilbBDhsg zjt^O{ZdW{SGcNReFRvkOaEqmFrL2>7s(-BEq&>-(g_FM2e?X^h@YGeJT1kxt0KiSN zQnbUU?ELYqMOJe@ACJQBld60@=#Mkc{BioO>W~ptNW)|Ea0by`_O1WG=y2c#AzW4B z%5ijdTtsyK-B>DZ+II#GI}f6=P*7wqLtM~YIM>^P5slrj-9>lw*&p&VRn-qZuc&4U zj9o|-diTGk(=+MkAKPNVrMs-*;LbrHvEEP5&Z(d`n_@H-Hv)>()KIlukh+wiYA{r* zs`E|YXZ4lrZh!qw(a?*wm{UAG;=dATZVE`><=D)8_a}U;!I{0zNaj6cYcBrI-3~5Y zQ66!McWUXR5XY{IRcjb?-`Pz2{6sGo_Ta3C<_gShAyCI(f#$&F^22h64Qbit3567p zSfimP^AaLI`O}9K8I`fO^guLmw1VP8SfN;*EH9(+tA0v&C;GDasYXJ)?G*g5a=%w! zlx@1nVcfS=*JRcbN9KJjTYmoQaJoe1o-b*Q)JZCAwxQfkV0ZpPk70Tc#K}{%o&_DS>Zbefrkp>0Oj*3o4>jxyyR25Q=&(xO7~1@_0Tc zagh_anxQ5^3#c1Z%sEXVgu&eBK`QWvG%#%={kk`($=o$XWg+SU-l7}r%BJt|8*c1i z40-K(PeJ)xx9gTyv?W9V-V>Oz9GQuZav9^GvTRVC`j8vU6efT3cMatZDJso}{Ru@b z$cU<#aG&QI%xIw=LB-N&)5-0<&m8m+-CZ>tUYIgpt5b|WD1D)CXP0~q_tFl=DkvQ4 z&MIov-E1t7K^-KP$eWeUCb&gau?(Y+a^)LL?j8^w(5u>_!-;%UtvkTngGT4Ab5YFc zS~O|xQSIG^V8!fqasyGEO~G8nb=6@6xlW@-4C_g{gnQosJ5>8kxW+s7=n1Xe@~_e7 z@B5gbZjrb?TGml%I1ZZgi-*_em&f{9hjwkNP7p(RON>@|OE=2S&fRgY{Mph1POKPm z8&6yumtgQz`oL`d);!Kn$kQEMQk3b>)F%gpr?Z<^D*5yRxFgNx3qatEyff8vYram5+|Wa ziw^#7Y-wmF?Uvtob&IH;00pah;Lsng11tn?yn}l6b`c{qdSJBTvxD!@9m@! z9iZ!6wYgDDKJRMPo_n0AFVI(eBEq}i0u)kvLnM>@CHa9w(1RW-*8G7q`uy{8nlDI< zifg{gH)6uFRS3h)n>$7hgtYVnHQylK8qcN zm$|V_!Pi6how>I^UZz!$vNR)fy2izD^L45?KW7;%MX(XGGY(4JT(WnCvK3Qk?bxWl zvf)q~;`zg-A{~q0w}wItn|>vQ#cx}cSS5D)+#`TLm?XGSc3V}JZ|mi(XZPF>GuV1+ z?8Qk%f6>o&<^NjHHX^Rh%7zl9FEk6N+IY?PT!g{nW^|%$ zd)H_*oRaIwB*P>td$oG1L$d#eJANbuu>kPn3b@F#qyS6)uLl+DE)}Ou7;a6RSVp@Kg{7&b=^3?< zu`JUs+IV$ujpv%z;>!8r@hnA>;_e|ICzWX&cI!N9OI*(qgHw=kjH@(pfmWfha_C0U z4A-AI%Xx?h%cH$dy7x@Mdxq83Jl0NA>`kVBtXT9%&$3Nr`6m(#w{WRh+y^pMV%U!p zCC|dClSD$eH&Hy6%BzF%rF3M;eAXw(+{eS)^`zV& zVD;Krv2%8-B}I16f2=_~+~6XC^0BD5FM4ZD_hBHn`F@SD&~WBu293ViXvLua-q8_v z7|c9#hdOKHa%KGds_heHv&f+jS9C*kBjx=_ z1dyvPm|mJikOcK2BP`J5CEJjv#*!{aVNKUHoo)@<)MHb(Xglp0pYOPPzlFZB1Y4Bs zli2FiNX%7nb%815jteYJ@0&5oR#v-Dnf4PSS)eS#hMWpmZ4{UD2MjO^Vd+76H<&&1 z7JQvPY7^<|q&oY>%wW&tLhg10)NNw*jN+KOibeOSuyOOyZ?zxRP z9B#1@j!0#aE0<}Y7-IxLGJ0X%HMDnRJ*F(C_=o^#%_N<`r7Q&6N^XrH=9{!rCU!WiWd)fl~SoYjG(+m z14)q%j>Rr4pG3rYL^`pIsCVvlxOkh(4RpE`*Um2L*Ni?t(1)a5(UJ>G=(~P)$nePU z;hJVepV+llZ(;8mP09ELpNKgeFz77VVSfdIxmur^wa*K~%$)>24|dIjFL{OR^=G=R z^VgaKToalOj#4!W37;T})$wyGL7&x{aU!Egya^H7VV97+)|!ww`>Zip1|ZZ61{F(z z79|dV!jbt?$;r=ZCK#jq=IM4%&AzrCJS%iiy2Q|P#+3%+bg*W54s)7PH6$DE;cJh3x$ejZqcHHQ%TG)JNMQnHU87?d- zA6$n=0X40?4NaK4B*~b*hgH?1V~q?cR{yZt`}Y}R;c@*{1Q>!fR>_av88WSL^g!gM z3HDi{KP(Y~MMs78ts9R=!~4oCqSq`J{EjZt+clgEWk83bio4nm-?s?PWx{*FV`WbR zNJ??hn?s}?wFN2Y5w*0C(=@if&&(6_dw$7pJY&Ke{|6B0+YQrbzBxI1|6ILT*>@#(q2EFt|QQLTk$< zpS-hy5oc_9v7smT)5-&gFuG(N>RTUQ)soBWv6x!}71f<(M$}}GH(KuwS_U!8^Tm^a zog_lIf5_A~eI$^kKY+{$>3yA4+imgPHCOLi6&WLNq;N=+nO)_7PIxWyutt&-CQo7R z&$sH(;K;$05uvsdxEx`Dur;H)#>;=S4V#}9LK~aXo&`M zo$bxos{eo-5Dv$IPZfV&FGpJ=Ej@oU9+fNs~5$&koW(jp*Hgdb8<{m?#6f zIASs#6Ua|yl1S2Bbs^G}ZBhJB#LwY#Gd3W(;7am^J1^#Bg1k5yZv8R4xGi$J5B6qHMvUzMl*S#(OcHiiW&3VsIXNZBbOXn{ANO zcjiodfJelY=&IpciB+SGIyhwm^Qx+AxffH31>`@xK)9$JCoXT+!`wzU+uT-qL)HSM zsQ{5-#4@o7VMQ|7sV)o3-ze}z8JdP!S`9uOA5Rt zHC+!|uHFe`cxE*s00i=>&$lT3HL!LAM#;jh=^>>nI9cE}5 zq%d1h#*pCKFVvhhPFdHRCg!Jmpi*p7ai97^?^`hI$$OKmf>TL&ad#xw1P zh)WUj_HL)brZRbcT@K4XO%sDCaGUmUCCeZVW*}fvHJ%nb_0#^|984T-w;-Ea&hEyGd;ZGWXj|o6vH_YNGnaz_81TH* zjL+gtJ^oO|$)tt3qJEjlx(2;-q}WRGUUj7DOQnxSjSydo`Ya&nu~lxKqf+eE8uz85 z`#c95W0jz^-q8{^ZijTRY^@9&=q5IJSWxf8xoA-s^N1L=fIaSsoLo#p<*~h8t4TGy zu{f}MP!kdC8mDei8uw@K;1Ph_76eV%4iA%0Ej@90mw|Fi4}{YPzu>)q@*7PzU292h zwE=Bu<;*l!g90})MN`w}g)a_UdDO2PZUD+oIj{e5atSMeXgq({s~#nNF>^_LZDaK@ zOzzQ;s^(0w-k7{ug3^`zk)6gxn%ypWwgb9-DoH|d=XJxub0!mNE8N@|4xVacyrMh~ zi)I5AxPGuqSwF8MBUEB zRhPT0{arx)iv`CUYO>)qE`73=bTQBvK|e#=r=?R<19Q)f$8#nD(v9fDcQ_! zWh2cyE7hUXV|y>5NrJ+6Md7EfgXmAbvK`Tdv6ssyyC4Q4M`iBC%OP;*F{OHta^>Ov zO+9;*p#t&Zz*RdnIDY9iuRGobrL{?Ew~=$#Ns68u&K7<8SGx8WKY-*XeE&iCzkd8L zly2acYZzEN|*p}aN&Hp*di(AObEBW2C^8aBTctGs1nVrl1KYXqD69B)YGfRzS z|9{WpKjQnHynX*8KKkG3P4<7Z?|1g#Kb!Zz^w9hjy8g%Z{m$2{{r})Pq&|xs_VLYM zY?j~yVGFE9249TCtS^~R|7t@s2q1DZ-135rTKuulRX6NkfSo5ylWYOruxZpS+sp{y zXWQJBH3*ad_`a>^mz|;MgQ+kBbC%Dk=+Kqt-8%(?R1Ae9yuYP zrKT02@WwWMvNnm5xONo+ItN;TMjPT$fc;(y(40oS9OYZ{S_(HjRE6gKxveI@Z%qjx zTo+3R#gRux8O9oebpSQL1?VD5G&%{@Y+z*55kvVB^b{S{^cdQ-1rWyYZgC_nyLQr6 zfN&95L_X%6k*&7`^p#AHoxMnx1|~RVIH^<=;x`?>2{f^*$Wrw|LuM%{7ewtYOE{#jRB<}>#t_I&aEf!w?dS)Zl41F-IF0bCQatMs9-7SQg3 zQ}AK^It-%gI3zm{q!HMFq_#jxRpW2MEQyTZ?THff$ybK42iU$6)b?|}n1KZ)O?AkP zTS{=l)wa#S&}jR*`e!YQ~0@%DToV_TGs2kjgvuNs)Abv*>(3 z?UsewdN?StTb!8nFwKWpdmj_Kb?)qr!eenq+y!Wp6U0aC23 zp&()&t@q-<%TZ9@RQ`I^s~jafqpQ`?)?Vj@wG3gyi>q!rE}D;)!7I!1@-Wf(fhV%X zEvX7!(t8ua%!^~Vf%gm(ZAdX4Xr%T(JY4v>t^>689lMGSgRL>MH6+uZ|lTp;OB>kU8hG zh^qWv$Upn0ym<@sR7LmOc6Pl*z7}+zOt~CexNjzM)g%Fm)jBV6bFO;&Lb+NR_J%R+ zm&t9{6VMYRL5Px`)yfDxw0ma{q+pmu>m&K*qv-5DA*R>otAn}{hVQR|oEaqHOC_l5Y{{p8 zxD(73@*s2beF46^oG-dC0)KKba6f{SDv`{F1w-a?nj2;j2e*{`3h$x~#XTejmM^{` z3BPCcasAw;OZANNrgsO>AamYlU~$?K2DHW*Kl$dfC_^d8z*6I@1?0Nh=AW2~A3IOJ z%il`zW`OR8gz1L_JT9h_Kb4OM$OwOm1NpZ&sBC^{E_U>Kg7`9NI1Sbw*p?J@es)b- z`0_N{`kZ$rmSTup;xJ|KrJQ(=3?PXb_WE(n6;_FJ1+v_op2vi6)8NEeDj)?e>?{9C z(2FBL{gud!a(Ba0za!gpy2ehUIcQs4rENbe=q2uC5K|0dLrxqT#DsaI!mx*m8qHY~ zD)j^egN9tg{NeJuiu%vi=hEHO12m*8yJCR39jZNmopefEmx;{D;G=EoFW*v6$7bYV z1n@@hO*IMf%|5?nL7)q-KKEu_}Q6|nNHfCy*$ zO1MQNn+_66?(muQL12K@u8?qMkPF74bE|O;E{e|b*r~O>xjGG+y<8F0g9+nsHQ0^` z<}@bzUIH%fU~V>KxAwNI0GJx$c>q1~uGy*EM2$SAOx~^-6xVj&a*MP)aafEH3y=JGA{+xz;4R(2ajw(NZRqn8RatHFzYs8sGWT_N`L z*n^(>)_2&0`@eRwGh2zMp;M`|ZBLiM115X4msqB^f=4yPNpB(XqW)rD$sB+LZ@vM~ zO;5=B6c^PptOb?vEbTddAR?$H6q(5-0xJ1Yh)GPi@A@VB(=|B6qi)%C(b6UE z?h;rygjp5;mKmYBoE|XQSTJh@D^xJEY5fX)eR1TO(`5xZs?_|+vJM?yiF)W0-2x#b zu;}#g%+?zjOoq7?QxuMV00`dru_qs+lXJX4 zDYnma`%j_Ot@}|+>QjbK1|oc$6}N9VbUmWZxDoC1MZqDV9!X*$Qh&!(FQzv5QRM41%^%MP5ko z7p%%u7I9p&*j=!DGOo(#%in!OB@LV)j)Ppz8nC1YZW>y*|YT09&yk+!mH}sj@ zyfE*0&7PiXsTrQfQO7YO3Y8y6B5UQTm2ymdehv^|F-Dw)*jw3#v_l#OGjXaU@l+hXmoYn4;OicR ziOxo1)VR)r5JE3&jCra7!Py_=tRu4K&yq7e&~82c>kT)aMB7&g!PE?iG6ixZ-?r?M z%-0uj+Z{7JI|e2@s_h_p2F^=ZCZ{{8j9Vh2^(08N(nwqu?K;5JX)B&Vj5GWG=2SYp zdpZpBHF-Hr+aIwg$Mn#JZLwDhnW9zXn$9^_RkL^Mo$*|7IZ&E2aXuSo@J)-^~) zohz`EB9fRQ%XjC7gh({idiAnH#IYs5u~)St)V87^kLm~Y5>2rw?)c!zm~_clXWG@z z+d3{Hhe>X*M+7?9`XEcZ`v*_8Ft=MxG@|?7g#LS+mE1Cwzzc^9OEz636&w1iXN@eWoF00}R}uKjtp{by7)DuOET*xXM(4?j*P zBIA`)n2gdLm``%tSesGMwfRTlC@=USu{8Kx(rv$h15l^c#1gApKf5~{IjaTnAmM0! z?2GNM7rc6Ah)Rl58bj8DeBMfW&5CUi95#2-EW>4x*#>>3FB+<5@_s~+z`=iR42oLDqWrbQ!QZJW(6QiT7 zs3{y_&ZLNK%li(I_QLuhPo6j_tzO9a6I^dcb$=(lT+WMaqmRR+>O-%w@X|P>6(Z{! zFnSHs>Mvr_;4JcZLjeH72&DAeFfR3WFXqu5Aih529C2NVq_T-GB)iu00{0p1D;N-c zJFlDNlc#D6MfW`GS=hhv;S_YBkmZDp%>0U^VHNMMPfS>&NDuZ&~Y9^$9&#k+>G3?=7pFbggC;>kVtpFLpB$l&bc8Is zNJ4J#%~SfvIu`$h5yo(J zHSHB6a@>dHkUNKoilSUQ7Lanve;4{_w;6N)z4mB5r{rnr9k_0t$qtsy%6|EZw!ilnQ1xeytH#}12 z{w}!PNz`@zZxu2cjyol{0lB;2gcSl`9O3J$l_PY^JwOj%xeN!k9N(xnH{hTxnIG@v zBci9UmX^PgTsFCyO(enUq_rWzavxwdHt4cST5ar1waSM6v=wjSzKI%gT5&U>jkIha zKBFj_pC$NkNUUcO&qnQKbhGm?X}L18g+jyzGEq(sAndy9E8)~$J4$b%Z$6e}(?P!> zWmeNh31jTduo?bxrd*v%LcK)W*fJh2c@dD__kC82%x(q#&z~#5*O1#0`%yXF9HT)d z$QnD&hG8A^^M~bjr?sv_!3gfLJ3iCC804H)tf3XBvjN6XnDXeV*0T_cYts(;2ZiW& zNGYSb3_d*8?NA|H3X@TLh*&K8HK{XCf58g)Q~_*oys>&kp<9EH7bBjK>*wipo^7K5 z$GbkfpP_qpfwV7JNIgR$cgTs8Pe10OWzewq+gslj+B-O}Dhw;}6r~(rQS{Y&z}?BJ zk?*boYn1tmF(d`b>MQPJ`VFhir>OhtY|F8_qsnqLHRI9rv@up8kmJ`f=ahQ zK8|fg+b^W(RE+MGw}@l=p->`b|c!`%~j={}kJm-OZ@Zdq++=2PvHuEvWFy)4z9&ZY>{; z*K%5s3$a?5S}k+q+Y1a$0LBXB2GH~hnDE5A;&-t_I?k~wJkHDil%IU^Xk&-}dJSo^ zBN)4i*pwzVOj7!suX~RC+ArPa7K*E5*N}LFas1-?cdu5c8mk}Vb zZhnQ2AEgpAZ1py};f@vy(bK;5fZWFu2hm$lHKn^|I7)&Bqs3mBxgF~a_c$>I*3PqB zl&op1PxRq5V>0DhrIV}5f|P}qknkUrE~W-tEN2!FoBqujs@UAm7%B8Ep>&tm1LWU| zfgTW5jj!$?EePH$z(mMoZ`-6;zfYsB!6p@+Tb`=GKnDh$lut$vbC%$YgwI>hseAcA znsX=qI2kF*dsGSs@l;_`zdpa1kjRdp*wl-pa2;SgJ9533l<43=$J+2mD`d1pp+gP! z>s>)f?(X_=G(|~(!t|k4hSHy@9fL4|{49)NrH{fX3V95~-BM&^1U@dZb*G~=!w*KL zi+;`BZ`w0zP+on`i)Y0XUDYdpr$9CMPQk@%R=PN>th@wcoO51_vqS+Yc6}&{3I-8Zth|2OL?tap8 z=xJ_f9Te#Kn16?DjpSxOul#ERd^V1R`DH&89qeC3r&!x>zG1SaG;ihy*I{irOu*cV z-|ljcuShLhq3LBzpbw|vOZ!H-%6YlceA!GJ9}5Lm#DRAiQjM5%GGcD92`cdApY$&( zo6<;Z2`6h#b?atFAQ6u;TaJ9+m!8C(=cT_;&gQoXPfOsLK7q8gN{Y~nPkk%fMQF{z>j4uS{*>@ML3IS^lHgVVN=T>Qd6aI)dW z{62y@sR+p!#~^(6zzZZYb_-kVf7bLyf?nB)b3VGfq|MM71>+pErzr(^<-Zu!mzTP0 z8MimhvasX5=6ctjKL}FW>l;8c$Q~C9m+;(h&P_r`|`@%zt`)Z$BVEoh1USd+@cYyVIIg8r5}C_F0PN{wjbRRUjd z9gok62k9PjV*MSFV*#-SL@8~F?!}Cc2{-1RVjFIvoL%;1+R3p|?>q2iWMf3HDf7Mr zsYGA1#-3*!B_CC{K+q`-3Om{(oClFdIXbu_!Mze^q4j1ik}C7d5^+i2^VN2~yx{;V z=5FdPs*=72X{64PMmxqwUPR4pI{h+eH_=`F^d$;Gb zapt^HM*mzV*1*Fj?MO|yWqM8)>s17`o+yT$u^>Aw znM6C8N!syteI6jheD=d6>Hl)aO;DM1zO00Ml2v{4MZ8gP(2^q5-hQyEg3hm6v&ZaZ zp76Occw6*`m=b8Q`)7lDzLM^}sddafO7rMeV8hjRQv+Q1P_{^_n^GyNc<)>gd{E=< z%BZLP^c&UB$$PG)cVPlK8CSDjsxN8xhu*H!;-9f?{L*1i;+i+ftdic_rV{)LJ^xz_ zhAc;*uW5P^t?Dp9R11Ho%bY)`s5lbv?2>7xgo|m3bf{Bzt}ZB}`GSNtToZjluLwo3 z!taL(w_hf-v+D>$KB6_@XsaJ|sesj#K5NZhh`J>wso>(mEom7zhGAH=X*Gd@i(FAzGZ*>Oj4(PMO)^UFdb9PL$=jLAASRZofkT@u3I!128_~ zRG3gemI?vErA|vg!)3Gf%j!uoG3cY80}duaZA>KjQ%zRNqY0{*Jka&J>ZdbJS=R?0 z*59|qv65Sw*Ci3U>)@Itd3PUer;gv=x&bJ8-t#H#eIQDd__bZSZYrDfCtrDu z23mzBT{egp0l78dvqUu`wNWBKp~q5C4`X~L3Cebv(W{jnf`nc$$I@|& z@^sx!s4sucMC&7d>Wnh;i$0KrY5smfrCM+cBr-jm(OLDmAs95d7 zd{WF8-=J_l@cDCvkno=>Dj#J~Rx9vOm-ys!WasrM2(3&FZuARz&@pi6JG$rSte{o} zmoKK`LZaZVET~OSeLoNlJzOE^4R7U}4!SAz}XDx?B02qNvTJTrz)BI5Re(K;P`BNx=pFE4-Zko z0!UXj)D!h>D2ptTQ>jj!QcpA0QS`QKMyt$UtntLm+cYlAwN?)nzw4qZ6j{ylCsTT7 z_U|XP3@~J0mpjwc5BE`Dt4|ZyQ!2Lj^ia38-rNxqv@;Kub4n@6@lL$eR4=xVm;KX( zorOy`tZI@}R6SB#dM5D0xLS1YcTO3VCZ03%g^0G5E@`-n%d;{hb|kan!ZdQ!JL@O6 znvt$?$R-~M+nCQNwyU@8(KBNzxsi=9{!h!;!P7%XTut~HpNU^t!)-7Et(B{l{ znfh8&9+>2r0J*>>=BjGD-uu}RmNtyosq01jb}fnkd*TP(*T^v><{tF@?q3nKAuqPv z<{Lxr1KG_};9|%N-9e?qYkC-eyl+!(;c1`TX?7nidS3X>w|DEu^rWD+^x+_hRJV(8 zo(i=xWa9MwYH$r>r`oJ~xXO}k5w--@7P_zMe=?~n%q@cvGys`PRbP-EoxV>xF);z^ z2jqkAQr_l$PE1r=h!CqqIYY~FR!ZpzianWisa>z#s0_K5*Hm=V{S%GC4W&|A)}1>< zf!y8q2;2NbC-v4+YME={4%#4-x1T%J@sos*5c==m*K)ZQ(wjR3b-#-ZW)`~R(I^&} zWk+m@gmSwvuB@spnes68c(ls3cT{AWD{kalskb4XEuU;>;hxn;kzqOy`X!4U_mOvj zbC#B3krk=C^}qG{%s#v`eehbbS1pVpM3}=_Gaq_vu|Eksa0e&r3B1`+((-

    }FI5g*{MKRy^eHTfm&J^8%n$^m!9C+auA@O(QFXFl zRw{O-GV^rEHoM%dN*h`E{-a&Ca&n*JBg;XF`gEYXu+p=E1-yZD4dI^WsZhj4TB~3P zTs_#7!1zMc-aCtZ(p)3v{-ODN)bl&5qaG7^*V+sYF&L!#yQYjM7<;LHEbLsA!?^G* zGN46#BKvIF2l76752(+2iD5bzKfVO+7k0&Ns9GWNgPwuPaKt}>i4qAl>O&aj054pj zNWrp{!?pI-pI4Y%NYA}&@L2UedNNrOAGLg{G%3$N6Ub!&s>&swQP=J>l#TfyhG*S< z8f7w{HZS4Wi@jtxjssgS)JS9=3*+>p^j1&Hx6a= z`OtOkG{<5FBv^I_9a$Dva@_8C<4PTG$Iq=?TL^zVv#xil@>lW#PK;~BD(;4Z;Y>Xk z{L1&^T32J3VsSZ@HsXjNT_{rA@KMu@zGz4sukskZbY%wG2iQ)kcCW|N4tP)ASZO4kkH&r$A~gPv-rEQ;b}7tsmz5032L@Bc!XK91*i^8TtVWy)}1S4LAG_ zMmA*l!*c>lA=l-#)xO&o{7Z31^d__44Nk~&+UpSl>w78!TQO-gUW@pL<9HBybvMtQ zWTJlHXMMUoo7BcR3DV-+USgcCj9}46kC*h7n>NpElsu`#<>Xy*ODoz4`*U}nxbM0ltuDZ5&2(bqeZs$%rdINm9SL$ zZ1lI0w;~$iAcko^(Pi%HQytLFqKmdZ2~XGBoi)loDrn)9p*0cSQ3-g?%90dxXS(*@ zW#oLjxYcwyKChOGRepP1uAo}!QY5cO^Wv%5j*Zg%pJZ*{)r-S=*gUt91vJJ!KPn$U zo{#g-|1;uF-g^;mzaqLLasG5?EcPL~tLRPyz}`&2COZ>cef)bLzf)8@sz=UF3&+IP z)S6KIXY$`jRh7f7y41bkb#}PM&{zq=4xZCjq`|*aaQLln%KKTx)@;q-4c@`kVl8q? ze0YBdlS*?&aAWWUaO$^#XB`OIOV8M|)qX5gl!d|drn04_y$>lHj1LZGyQpnnshR4$ zp(ip=dTal47rK)*tA*k{|5*x-H*h4uH-+nWdkRcp-;(Jp{#Vvr*Nw#Wio3f6uLY}j z7ma3>HkQ`!kczyGTj=<_OI7n!bfHX8az~QXmd?nZMg41dyA2KM!)g_T<9XE4OvDIs8Z=p+ zKzDSjR&kXe2sIQHVQ!~{(eB7|gWl)yn-plp*rvi^gP-_}FoDF9ti$)UH$vuEz{`!H z@-a-d?`l^Ea-T%n3A7*I0XhYsxH8eS-NFLpIJyZgvg1GXE;eKpDxOp>hgC1L;Z%yO zlD!MscJ8~4(AJVJyRVD1o)Epg&yXC-&M;&e*Yaa)wYaGGN2@VH!tzD=lZ`IElN^9% zj+k@octK_QZR#_DECC$B5ZNbQlsb8QpGp83m_9*p$KjFu-C~RCUeBFB+Mt{jGD@^p zUE1sI@_S0ruvDLj?L`!81qYcAv-8^D$f0`_&9Wrelos_{oHFjJ-2cyfF2KIm<16<| z7dq8`97xt_m&u?5UVEtn61mvGwl@p!D1W5!ow@eejpLKa#y^DDX&}GqZgb{%d3~7` zoT@N_RShko6i7k-+PELRGTBoe$j=-zfF(Z>dP?-RTD5!~eXif-9h74r7S^wgU=sZi0CF~lKFVR!`wBu@me(yG!IHsT@k`h5M~+-8@mBCkg7Zt!FG-9ZdP%Wds|4*>Zd{S=U)B43 zCrAa#br|r&`)K=&>e3dtz4x_r%BG*`5C4fD^H|wt_(`>fUhV@!Dgi6o$K@}_=SxDi^>S%%_>0lk+^vxUvAs_3$3x4qIw}sve_Ky?A4N6Pf|{C$m*6|N3C> z^kip6hjs^70^|c{Go*cJG|i2y!hAk5*6vZm3Kash-JKpS9%`@8R{Gv75pfapbfZ!h z%g6t0SibISdhuBwL11OdPdT54iv(-q89SWci2@5qS>AyeXPnq_{(K}5Ug5W;f6{I@E#vp#A?~5-w5Io?71YL#Y@87`>SLe!xoEPstZD;dPf!{vt^IzbiTlTF>3;ZiaQ4peh;MAAYBn55DdKE@)p94w z`eTj*cpE(k)a^g!wqaLh53VS8c2I1f)DT(xpfpwJQ&fhkg=C1~jT4pb)oy~8fFu!H zB4WnY`L>CdeBI-@ORqiT*$b8!ZMs&CxVM^~)vUSfDRqPGw+7ZwI=^=9On)~T4OjPAf#Q0`>hQaS47{X$A1121(f6p6xN&dz>&1y zIzXh$(sFgsM{9!b%>&vIM}2U1+PIbB5QQNpPXJ=r^*pyUn38;m1pVDB$Y!a!=mrDR zhf*nFVA@%y@oUBDW08J+EIeF^yBdzg53fX~zMa`%TV7MoO7E9><3azZ%)nuc%Z1DB zQuu>sE(Pvt8zHAhSE-u_9!SsnENAccu5^T}desgLndt>wp*y^=z>)UPw4WOafqIiN@BENjXhu#f>M3wmm!VOj2 ziQ%rYYYJ8!*g;5}J6=ya?B?GORKnct0USHLZthy)*qdx)dBxw+f*oWvbM@Vqhy5-tNA^lAN7nCaDth|O=T20erA=?_=nChCx>M^sk zNvzgy(SkBBe`O4WM&(ELL2BPtd1{J-%!*?Jm?Fq|*$G<4?TU#Kk5+Bhxs`FNt;!9l za*vEzaS!KmF~}t9(Q@$ydhDhI?p$N+Kk)Y2RJQWndo@M@Jogfe2-;s_f6z@*#5+el zP5sdIq3pjNyhp3o%>9Ok{jW`T$!Yq@(w^ud%^t`lOlVKrf5>+k7h4cCP}`=m(|$fv zp=N}(M}&p2sy={tm#!%Z+C(P!DTvw&X|*7?5}2nR>N%?*wx4N&E}z_VuH4@m+gg7d zLOZ-AlzkA$49IR^wV4pwX9=`JGieLQ+cO!Lq6}v+qRLtT6pyrhflN6>d}d}+pjY*9 zSCmYbIKg%3=p>0tSTkzvC{is6I)4_5fUG9EaM~cYTY*mzUJpM^94KYfA_YNAbS z_TmgXkF5q#$T|kFq^k0KJTT4)4rD9NPB-RTjAL!qJE!)3A!-oqZuGPE>n@X3u))jd z9C4afTt2Y3dW)KTGO~l7v1G;|+FIiZjINCMFnDi&R>&~BiQe6$0IrDB!K)N~;d;!T zIt03z!=04dpCiMKbOd1!f1$wSuNox)r8O*kDnDj#8?d@I+v#rDPErmde0A*0B!z|Y zRvkz)9@9fN%aH_gRul$A#qFzsc2QMoAHG$0z2!l|bfR5-763nPry8C~; z|5l+7)Vbjgp{IC`Z~3vxF4!=EN{qMJ-{9Pk$DcIVswKA(H+UJZBUjN}$W*D<&G76{ zYBggX<-+x&G=cCgWz{+LTFrjX?Lh9oM&=a)HyzTDz~C-`i&kf}AqzhJkD{1OQsdWl zX%_|#%q=NABcm}R+v=XC%&xO0LP3X2ScJyQtkz$Cf^F^+LRhR9P(3%i0p2fFRYPnm zrY+aI?h%wug;@<%k?GG?DTUI2mhx2kS{j+Lf~*$~Q6jY`t1!oTOH?NA#L&+2Z@lu% zn7E*v_VSRh8g9BxJ&FKv>L++q_q&F2N#r9|{KG#tM}P0!)e^~W4lP6=dk?x{LT z<_Kx-4XZx)pJmZq>x!7Fj6Pb?{Bx=--Td|XNVG*v^%VQLwfl%s=_96ET$FQQOTOqo zZvp(HI}yG;z*Nhy3pfROz@)JjF9&(e>aVy%CZhYi4j8(qz>XI4&O>X|v$Vm)a zA>^M)xHgsk89?Q9r0!^KRNeT8;>R~mT3dh@{3ntA9%0g-p>D;cd-lcfj&#jtXr!XoHtb0}#*Ht;%nGcLF<$sH zuL)lIn-COch4T zsFGc4G5nZq!cRqZN59JhDi|&I3TH8ANBrZFi>3b>S*P58i**f{9|z=ri_YEKhSCH- zoFj>P;R{k-&K07=5A)jf5${SJD*7+JT!5<##Ba-)JGp`Mz_<+G|^DgB6)FyQuQd=pw zL?Y-|IL{E)Ys&FJ9MLppOr!Pcx)P8dn3#YPbVI!iK$~j(iD#r=pTubznIVt>C-0<} z-(%hzr74{v5}|0Wtuwwj>3b(4L+c9^ba>i6@zHj9e$$C7QVznVJWwJ4y_CZ#q>Dh; z9<6f%5}DJa7if*tV+;C10ng4=Qm1wEj-B*MY&}Q)m~Lm!4PcS*dCPx1@?7I`t)|n7oeM6I){xNrH zoceY^2@^P@o;^|wqsNX6fCk&IXI4;dP}vb$5C%G;oeHd;SGXRqY}1Fs$?UYV#CY*a zh=~*X1p)epdmif2l$@ZvWq+p8#Ks4_V%vm%Xt&B7-=HUp2n_>#6!ME97UgeNb*W0d zYAd?I-6l=pqX4MsJiA5s+oJKg*Wav}K!;KSYCd0uezd2*a+VV1oVVIF-qFBckHPrz z1CT|_z$O0C^hojco!~}>S6Tw{XX-ct&PRqL6uT!F0Y6uHT@;2uu+cE0P2HPS)_oH$ z%?Op?G@ER9#@kQ-o>F}x-A4$Vd3rw1uJkBi-VxuyYkzbX>1%GYKDUh!{;b}1Q%`uA z8JtfhE{sV!(Y01G~1dRA2xJe8%Z-2C86OtYe1~$^4+G^H|rq zeuTNng%4iq=Skeio8(al%=$_O?o!f~jJ+JP$IWbKPSnnG#|%1=3~&Sg?rK#A~lpRg$~0RF#HWRVfN}n*0dAxWi`KtxkC}Y~4n( zln|r4@x@FR4;vxpeodbNE3JArYEfYjhiE=2kSCAB{N*1;TpE=3D`$flJw5wacj96C zuT=F)7gJBX05lbeoRRB&{oT+{;k?S8GUR;vlqQ8+IXb`F5Ls&P*R|s3p19qsAKI#4 z(fZmZ%>P)7_v%m%gEB^>^wfSrdY*=`CG8Pk#nhN%z{2}$iP!ywRH4*2{t0jyn#l(A zXWO6ozl#Io4?#)2JY_m)SvStZ-{VF=BBCHtes~Y?BwOgEMe?5VRnra%Tk3e{J9JU# zumIZhuN50`5l%iQPgY3dS&&bHywED~cJTS^hR@V$?KzM4P^UX(&yQ`&3EInkqUcmPpLs ztGw%0aVO$e!i$#kzYt|f2F)cZ-P7Y&r8?A*x5vxMY8PH_%d+!5In1Wm{$09cPN zfxVYNulE31LB2m9;yKWGE2jV9-8MV^hqQUUB$=fYNxYN@1o>_dx~{`EIu!7ZO1L%-E4MY7^qMC38Za;#&aWO2VmFG>eY3ff3g5;!ruL*e6N50~H^i#@ zbjye2kobDGBi#At0RKJ5hcOyAS~KNpc$|vGGiH-pMmVaG?w$4 zMrOvy^Jo}>vS<}kQAn3>Y!aomx9UFboo;;sC-_O6-C$+no{(JwMFd`HJ~Gvfph0J< zozdtF{#0R}2a8=q7sW*0?@QRWXd%T0P!h5XgeTszFxrfs#tdW|yfva^UCp%r#V}+( z8TFoDHzv&Qt)*G;OYMH2MX`;N=yv1AhEK&U9{g}Yp>aWM+d_}{s>lA+5UX^TVfsNd z4Oufx`s}=Ov;2sfkSTV=pi3k!MET6!r56;>cvSm+3Hi=){Bwv=Zf&{z zB12oyDfbb(;VnnH7hWxx>@)r_aZnA~!fQ9E{GE#X0~=mR00ni*cp;!siC3b>0%f~* zDfT3a7|mi)%j>r?{|IRH!CNR6eT}E>5`e*7{Lmfrg7Z9RYH=OuQ#6vC>9s^y4tNT< z3YL&a28hcqR@#f?TBZrK9hC&?lIuPE+=>YFtFD1|X_vufd&O^E6*Kv(^v3F!c%t5| zSN~C)`>no1p-5FxWXD`0f~cM32x@<@(1ayf4M3k`7V{iZ0tIzvq)_PYIA;v z!=i`TUO`T;TkR~mHDlFA@fgF4-PA1`Ja{F8))XByhLzYAe1eWC_63>+yOrg43%mNK zp1TJzM|F0-2THcR-K6Cu#m?Hj-Jhq~Vt`RL0F1Js$%T5@ai|dv%kNux)p!UhH}>1` z+%}CiJ-vfqZcNC)UZ%2Y9$Q|jyE)pk(gc`NWJWC0Y-wlne5ZBhC6~!p^MGTV5q1befSm+d3a(E<5y>*%QrinLO9qd5(dO>`iY|i8!;0IN%F`FuPRwU7TC884 zT1{()hqvWmBYAxno?%yH3IotY2S)FTyP@RhZF}N-B%~I(Bvo6jFVN=>`188ohg#!& z#7xmO3%8BaBBCybQvskbY;swKv8{`dbdyUfs2o^CX+H}o#??y7#=KY^owkI|*)Z5B z104%j@{-=GoTk4afl^1fC7B}n4^aowoM8u-gpU*D4)gjW%AA^%F>#zF)%)=U@s-Z< zNEu5~sS&GRG9+1VY%S6(WU8pV^mb}9C=t$ey3i-5+!Rv3fE)Y`0K;;A37D=TK82`z z994$$L|<`KNjA`oOj%d$|Fo+T2t7+vA0sPsF8RiI@!ZJVITC)G1%2}fL=y-!LF~W~ zL@R07TE~{vx~p$_nkO|`KdH)tZ8OS!gya`{d*^mBeG=v-xyWK#H^S}(+5GT8)gQY&*0E6ur107U z!+&fLAxN4i(YN!+>u*FOvny6c2B9-nn3D$4N-H)-X3x6(J2QkU0e8+KQMsv!y*zgi zjlL}a)blAWK1eFD4%q)FZ>Z@4KOREl59oz!o5gT9eR`kil>w<@9fg_)Kn5XsgLY&2 zaTsAEHMZz=HG_apfa9{6;+h8g5Y-#;eX0Lshrq<+ci8Z4dX$A6p32?F<5e*|$r#5a z!?*#KQ-}6EMAAqny2CEO_o8oK0r?=h@|jpjKgbc_wbQf9CQ$*uE%O4Q@d?00-^y=v z>F$r=+o#AcsPm?%WUTSx7|V67|LL5}{VzO~kCAXs(&nrJ&W29hAvSLe(n(H-?oZ+e zL358=5yk8(PhbG;{UQs~|4AI~I{F4r=7f7}MT}kzc)V@{wT%DucxzH&*z16qVfh1y z&(cD}k5Kf2#kd&m-VAlBuF-e7R0#ZLUZBqCN~>n_eZT)? zU>ap9*@79Q64Z_+?I)iJ1FwbV1@m03)WM zOI7v%134qZ1~6S@ZD*KF|NRC1SJZ^RE5MTZ9Ga621nYnOJ6Npz>*`Uuz;$EiD%3jv z^?&{^@R=iAfQf@GCc^%ozxv<)AW1cFU8-umf*|z&^D_VMpIrdJ=#7*<9{>FJ&Z_^S z-Ef%!EFNLAS{d|zp}YV0z5m-kS|i#=M%m2O=lWsa11o!R_(fI!&qyAss z&c{%I736xeXZ?S?tbe=U|N29F7~raP5;j7{p!7dK$T&6t?KwL6{ri9X9BBS{k-&BF zGT$hq{m&1QO9=$R;(AHRzaY#1&CS6`8}vlLb^m_|Ktjetz!Vh+0A_w^+{yOr1aJuC z^+4m>M!S^P&cA$ESDH?H$wOh)>dXKbtHBmfuP?7!<#@a5{$&xM-f!gwVq?HWhF2MY zg#gE4RTp;Pqe73^JG8jUEzYx=)K<2yj=iMcS00*IA33}LNCPH}xiDv$YS>A>auT9_ zx-Ifma0Cn`8MgUPPDHC2AeY4HqjWP+t!zH{(cB5By~$uiioYhQ(>j0^vhbQJ$(A1? zHX6VN_HkXgSOvHWov@`#1cp})1sbWFtqC#2`q6~X`sw}a=eGa_uw$A%AYbWN3NELy~8 zzXZ@yV|X9S3p9TkdSk2d-vaOnt2sbXSi2fEI|?iST-K9?$KF|mvblEiN;z~rbC|$4 z_LQ(o%Xxd!j@Sj<__8uG#_b{?SviKT3*Q2WQ8Eso|-R`;ckZ z)CO?&FRHc@6kUCBt_DhgSK|PHHmoY=0fl=PU~nfgSE>0R71R!3Zt($JK-Hn0)0l|c z&Fz@)%6TR=aP(OPluO-mWJ^uNy0S#mHZ4%@Me>sUjpkV0buQ8|R?CWcv%Jl12=#J6o z+w1GEPFV+DV=kk&Z3AyQ4Ly&3GPcnM!wfl7+F%gh0PM5Zo#OL=3|9?u*UJy7Ht`$e zF-Cg;>^wOE8eXM*{$vf;FYXhI3U?Hc(?Huwkq_r>?C=e|`Q8+*yb*@0CN@RKw~?9A zX}(rKkIcydfGBwMU01+68vuiXEJ5057LCN8A*TI3d6BXkyQ4d30MO_98VT-o2Xp$~ z4)u`PRN#que}zYo8v28kutifM-i~yFF@AC(1TaD(VYVldbjtqQA1j4{-{XWG4XA8% zp@{$=m$6OfPdNHoa`@9(bTei;Mz}jbL?!~xxmOkK*GKpkEAXp;K>p#SV!xsG5Em-^ zj`M{mG~rK2{4kdvMb;tg!}LTNKWreE3aXorY8lismUx8jieIcF2y07SKMKjN2>TW5U&GrCHWsuZhswlN( zi(v>apcDfB7Cl+qT&yrf0eNkYbn<1~3V22eq5{kGR|M^>HIJ5@o_eQ1WY)XSbx~<2 zbetRE$B5qT4ydCPCdWg7PvXdtV29w&QDZvKkdK*u2YB$>*C=(vJTJ{)a_4Szdre_K z*y~KWhM`!9jBh%LBRm0z~1K$^=LPJM}wtH#S zmn}OYV~Uv_^e;j%=$g(A9&wabflVbW-Te!k>xameNb2J_LHC@!j z?$YxvPN$V0_6%|V{WCZ}!=qBX_o+u;^Z6wgeIW7?}&c%D3<$m>YM_3klM^q}$cp~y0X}$P;V~=9PTi1g-BTt#J{&=-ncJO{P+G1O70Lt! z_TT4C>BqVPe?DcVu)-fc&BkR2JVQT;yoO)mZ0oI2yDR$il&wuExv%{PQv=M5a5O)6*+ztdO?91-1@CDFyqZ~AWm72Vl4C=bwQ3 zKP%PKN$9~rR9?*_Q304qt&@bcra8>eoQIqX2* zLF}>PE_{o3oz6Bz`i5l-3Ybp+^8gq zhq@Kjd0HQ#7cW#(zB?2WSr7NncJ;IJrP$5Wb)>#d9X|kk2p9aE^A@XYekD6@b$7l_k{QWfcc<$z8)R5j@K< z%jHu5JyBCJ6o)paY=?gr>LLF&7ud_1HP`~*%C3^LF_vmG6K}zpJqMG@;56_}PBn8! zhHGMdqXLXIlH7!R4+RXzbxr|hN4+gIFmYyp4mB4{E{N-~z{=T^KK@!w4{D!<6n?9_ zL24F?`ShD@7K5Hzf#YNaa`@IhnYy*e7oB9Kwq73V!Ne&!vEJTOYO>0?VfAKOpEB<* z+NQ2B-hZ2&a$NYZU_Hoond$lwkg2CH97msQ&gop6|ITa1oeUaPJx~pbX1@ClDDms(NfbT_;?A_(= zKTlQq<2b4wlZk^K+SA0_h87uT+?qMdFP$EJZRHP{4lOU>U>3P4cKrbIYYRc8M1?M= zc_A22X-DRC!lF8>pN)<^>)`E2<6-_?I_eV9($8vL~Y^92@@uhT?Z+46ir|u(qzZdXYmNeIpb=+w>70P zvjC1ESH~9K!K4W3H!w?QzxSmCQ7@7~Zf{nL=C5+kbX7Ud`Z$ttxZLa{okBe5sYD!keQ{G^C1Ml6zxo}?gEHM? zzqEwNmWA)#?g>Eo;mkqGLqQD@SnX+$?Ggr`v@trHFtJ+8=5mbe-PaE9gxQc8=G|cd zwo-wRvfunJf|~`@k00NrN&Q1J+@VmU$e2002C&EU$oT=Y%YbjPB)gt}cyr!{%d{ac zE9t%KEBtc&Yexmm1SN00%QxbUpLJvquISkb=oI5;(M2@p#M1IY@*-#m}VYfqm4VR)fw`& zjucl!E8u&GXs=8efgCCdqK3D@b<4hIc3yVAYS}x~bec@stFoXNwu5YXZuj0_`@wqq zni~=DA5e-93I{{Rzx1{r;|i5=7_~xp7GYyqaSE?{d#qf+|>iYaF}B&(UC(-jYZ}TFfj=so(eE)xW_{97;b2w-3Yp=c5+SgjwsQXjlx^}IOep`L*&A_nb z^BU*e2mw~cO2V#4Deh=Rnx9N0(xZOC8LU2QU==^7|;Mu&<8RmVU z$%YG1#MmLlA@L4w7MZ%Ps1g3_6LZNOK&)B5j1FeJEC2en*pQ82psZ^91Np$pqG%e8 z$5?W7Bp>^5)>X#n05==+5~71NM>F^*6-LqlN3k1mK4Gdm%5j|Q-jlN1x0soPylPKl z)9L~K-pEwCp`A&$o(TjV?Ol>cLkA3ft9^uPiV}da6OrXzyHR zB+x^$`9@8kB9G=7)Zw@9PlybB4PXOrbojfYp`c zeGkMkFTPqf7~W8f(V&LKMk_yEGL;)JWZh)eBq_}9C|Z>D;tD@ZccM1V^|bJ^R*v{bvHamn)v?S^*VK%zHIz9Uom6}(E!0%(zF0dDLIQG4 zSEA-kgKI03TIap=G?`t_^N#Q0&njyZ8^G=}jW2)@-8+Z!167*D52i;lYvwL)^++ph zM9?CFQxv}OQ_60o9;f+!5#LKPd}q2nqPwIYxWv&s(L57}dvc_5R43?#?$4)`gXt09 zCS~ugpErTqX^!P64hET?x7(J{wJ+Yd+2#45sbyuEw|iwLyX+gDzl`lV7E$lU6>k2t zwc^eG{L$UtH_vSWrqZLg2MNK9Q$|_+qAil%_4Y4ZnRCp()0yiO8cuNtntb_G@|&~<=5CuD~3dM_#lFLyYNdGh=I>Ue(I8Us{jscIhaJYgkKSay77{c4-KjsS8ach$im58ZP$7_#DT)0`zt{KA?;O{dzGnG_ zX^jFo=2K0_3g%8hcL!{o{o*Kjem-Du5H?L)pY>)*nDAA)-%2Plgcn0-d@*n{19^qp zUXWjiJ}$lUNA1^lC~jQ>X8a(s_(V4X+V6+7_M@U~JSGpweY;2JUia&oLVv8#-vN{H zl%EM{48;)~u+o#+UX$oSF_g0DlC6t|^j~4fe6tzUy_j7&oJlIe?K$Ja`BK2BD%zGE zUxo((ker1>?E9M6wFvs%#0Tc41z**#Kl%O3P@VBRXGwM^tFdHGWHLUv_RB!Ga*mfJ zQA1t)rkTP6a3hhcjq)dWhWDgjGWhsH7MJYBix{y6nku4j(K&|%inFSB1Y2}YcTq;0 z6?Y68ipRe~Z?UMvKBJMYuy zpts|L>&{OnM}h8b#=%#J1qK5)-qbcRFOzWXrJ@K$X8Adt1{jO0OR5g7)D~xG9OkmS z4Y`}*@fPI6JzVf&1(L~^?RSjYw2kL{;M*%^fg2(`H>1s(rJBK>6w9Fq!faidA|L@kD zEi)-Ro?6629J2+;{7}-lLPbGR3FXrFM?qx8v4@#FICm8&r4FA_^-l zdCno-SqqP9%ft(tjSF;zn*rq_vne$X8m)4R)&!obZYev>v#m3-yk2RQzEa8h`~>c& z(o~+tc{OWuQirh41H9fKwv+`%`WFz4E%vT69l*xm)a~%Zt^D4|n>S8g=3wh6l0Z-+ryae3c}Eo`w8MrVaH?IbSwd`JGCx ztvnbt2iSN9$vRb$b$v?g+B3v2f1o^))Ti1WwZ(rxJWQ>cs?LeK0$!BCx$zO%20E)c zIZ!+7a-|;YSY$E$zA%XQmDilxy!*UL&b*pm70zGsA%0sjq_)&ac5!Fd!B8VinX-zZ z{aKbJHNewWW1+_xo1P(EITJ0ZXkgsoSc%6ws_a(v^27&e=0G#x11B7xjF=s5OfVft z-b|5d=30fKqaESYkLF2q495^bw5k@1Wf3?%6Ax{BS3lY?z}Sm%e?}lWJjHiO1JC%r zXl-#6?FT=TpW&S9u{95%_qy2!Ho>82wu_GXS-5Ed)jZ%n#_T}i)QLu@aUk#lV?72g zULR{q3Mx}1vPA~^UhZ>znmL$me5K`N!IacKvssNtRQt-1LvopE?7%c-5yA7xbM4R4 z1dZh5G0ng}M|={kd|G+(eWp~DzpQY4CxH`^b)Sc$AKXZa}o z`XbQwW%Q<%X&zD9Pr!|B3vn_FE+X}V<9m9O=Zf-&m#8%BruieuUldK5mbuHa6w^r* zR(=g~%Ukx?L$?a-5iSPZR3>p?Kv?4A=bJrkjrYPX|1RFU+ZM|YqFZN~_HYqZ5R_J&X6Hir+wh~M^U6A|H>iv+QPi_< zqg6k*J;TCC*R{$hM@`d=4{ea&ga<0`P_{hred{6Xk=f}r_t~@4eIZ!>WPjfBMw)*9 z4GS~Kl?xH5%Pr5gc_9d?od>~rfKeIOZnJPMZnNlPRA48rNy~UGO)4Uo(NltL?3kw+ zj0`Z4!=f7RGxdI`UvE^Ac;2z##PEqfuLEAb`~=m76y7X!mLr7V1>6Xa$V$7g2+vQ8 zgX<6siy4PHI7t`$Dxx6aHW4i-68sF;Ce$K2q4c=7ixnfFwuD1`6a0rTUM4Da!k~O4 z5qkE=8Bw>l$o14r!<)iVKaADmh%=Zo&zXnV+n)?ssUCLi#f{K@h&9w77?iuso#asI z%6fpBa${3*!X7ao2*p0wMLR&a^rBck61?dZvM4Qh$n1C0p1^Ux%Yj+98vEJ`&4>?d zFqLv+hpd{O)R@K@HM9ofd6+(ab}%HgHvKY_L-x#jX1GIO!g1@XA>hA3hy^OW4R@K2 z2gU?Y@zv{0mm5fZx)3#!4x7fQ&)kXZ3dy=jojN0{z@UA0DRyRCX7Lz%-rrHLyP5Y1 zXpwSIOdQvw?W)3oqm|gHo7RN|&w?~0k7r$H-*;@hvHae=Dvix&1%jTd9vqM7Zz{af zoh1^OkzyRZSmIpbuGpd1T9_UrP(sy&1!xo7SGd|dP*M&bqE)L{qrt|N=<9ioW&|oC zE0r)2kdyqPrs0^1RGC!7xZnn3F-&jex6LJ5kEz8IROSd|YbC)g`4gka+$_MkS|BPx zx5hVKYr=jhjG3Fx0cugjk8x5Fvts>ss_w1KJr(J1%F;VdmFjv>TOYC)Hu;|{%1 zwm+gB-LCqDC^i!lssMLkpTZu|gz)_=5X8i~&bONQBHVs1h$&nL<(K><$SA@%k--%5 z7v4=cm%z^^rPd^4*v#uf<@*o|{CnJIlWC3m?2@c~JDXM9u?uARVgoQL)_Xv&T3vxN zmOyMc;iK#2g>kOANWG6y-vMZ%W!hsWUNp@-Rn>a`bwvt#E__ya;uc_EI<;7O&(GAEwAId;@%8vUBAH?*`LC7FC|xzLJKFrOtwqspW$Gj z4a5w%B>jP0jb?(VhCcW>HP0~yX)(*(*FE)`rf{mEI}(|zc`8Q{-QtSSTMI<*mnYO$ zY!1-hL_dw4&PhOoY+9`tQ7}V^qQB4S<|9D`5B4}7yz_%*y*0$7*5{H4?~k|yM`r|! z`St2|+C9~uspc+efuJOCw6!dpyHq$%A*~H!UAy@zGfG72V=Te>ZZ=zB=*=^;PZMO!5 zFp^tKsHv_U(8fbd4z=G94aVet40YchxXs1YaI?(vfY7&%bImJaJ?!c<^{k<5{q712 z%Y!5a3VvMjH6;SF%Vxb@sHnhu7dk8A$?OF$qTwh}*(U1dB@E3V5WhHIhY)Xb}r0gjh}zkYc-_2^bfE{dVtj($JJh%QVGKP}$ zG@I&@yZdaPrSxp|cp{fQTDGR3P&c*`n*EJQ`?<5szc9skKppkr151~qrqm8CksKGx z_X`OQ?6D}%VlI7`AP1VE;rg6mksnpO@^(H231d9zWgDZ+>Cd`&8Tw%CW?NW*97U4X zCQDa>-~bv)_WAt`po3S?+|H&M=Z=0DK{b0SBj&&mQQ%Rc%ne7A+GxIpAm%c(FvBbL!jJT~sJst!}LW^%~|7B2$T7p>5n*K3SL0A$sa~ zW*d5p_dyy9DQKCIqLz%to4jT)*;$6@MdD4GqB}pCW)kaJgF)mUSkzoQZIq)2jfh>0 z2TK1KDxZ2UkS9;^$2k9IB50athYqrJLIdXma*xzs7Fphlh;YX|A!dteZ}^coT-4-J zNpkYXPMt*Nx|CGceyrB!YyO}h>}i})Ga)_KqPJ?y7v8MzeZTZ3sJpU7FLz3>Y0gB` zFs#2-n=v}!MDe2fq`(*`t6R2$J03G}PuyY|#+dGqUDIo`^}4gjMDu5(6eU@=*}Ko8 zVfy`INkta!C&W^Uv&OjpfyyLAc0sTXMwAY%qBZv|cx=26}2AHpzd3-Q}Qt3lSisO`c&vX*YZ(S(JDO zreS9xU$<8+yNSLtqM-1J7x206&Z$L3e81t|&ncHXdEWJ7pBsA3J_|_}1-jLvPY?r| zy&(V^Z=yDYn5tT={`~nHx~otSlO|+Rm&|*xL4#4}2ouOK{rto9<@+l)>G}dV7bWhE z(&@MJst$Voeno*2AspM-PS;X!<%vO%}Vaj!SwXh`!z92%k+3;55DG zz|$kEpwhlWo_yT%%jHE@#Abc0!@60Se4`K8sc?aq=(`(t_Gpb<7E+YJO0eTtg$`8R zB+Bt9obsr~+ny|L~B;Q^N{;_=W3(fBcoDQ-ao8G#CHtqSeO zxHsf1{Es2&pcr39&MvFS;?x0n?6GvbM|TZRZ=#}Jx;hN15ItmkG2LpiqDeH$0jD9- zS|Ypq9b>l^N@DkPmGDdR$0!NJjBD<%L3L}zh|V%`-{elRk%5KS@YOWg-(sjNBOO^|o$bXiosR!H^c2{hU~fVJ|kO$J9Z zy``=r^A{GZzJCT#;aur%8zEi{vmPZBDbQX^H76cBILCziMhxqatGIUI*nN?FVD4}F`TzIPXYCTDsv~u3WuH&^GBru_yD;i)9 zHaFQ%4|;6~zf2z~`*!Y#>pfZvdM{Uf!HsIt?)v0c+nA#p>)&AT`ODXnha}l}``UN} zRY-4<biC2^96vXcbP%C!al9}d?FH0-&MOgC|lqx-T!r07#WL@ z;d@oMolq@8);~F=KDXXI;b!cmd#k0IF*!$ZdwChfN$6b*L}Uu{mI&ZCv3be5;&Hd- z%=V-U)~rZk5$qffKRh-0k*xaSo2VgsJ=F~t!~Di%y1Pr-ovwtPu9t_!dp9v9wg$O9 zzexYyy?(!JYS&&j=r#_bLvEj$*MPR zw0XEd$hiDsZpcq($ozKVYrl?B&ml|1xINj&a)u6%%t|jvT?@8W^jHRl|LA;>Gw_?r z@vv359Cf9*oh9#+QhJzl$)t&A%rgL9MvA9Bwdc3$%kMk@KU`VO6*2KbA?^QW0uZNX z!O}pqWT1@qIaA5bW%)it`hitRl>tGq@w&s@t;S|xBX~F`Kh=zfzKfs%SCse>6b%gQ zR*dK3@hUEiZQY?^#@E0^-P+p#8TMrV_*_YnCntmh4b7=_Cu594iaoi*gJO7?+@`7H zoa7@NEy>8$7Z`7_n_v(IWrxuVUvQIMc2A@5%)Actq~4-ru&4}NdUKy+GSR&ifZ!Kc9YZ@t_x9@}|3=Ec zVs~7wc|;4^vx2Vgf$-c!U%~;KuiAF1`3xtIEfIHGX8laRl81~3{&EOv^6RB{iK$rD ze$`{gBu;{@#kAy0VxwEz|K(zy#dNmDKf=A5Z|zm4#Lt%T+ex!=PCagpfA*@9$?LGE zHvX-YTbdAQiTiJ{*dE3Jzpvq%=E{WvY;}9)Jnq%1XX>l8kNn6WF9kz+{)adVeN}Psumk zh^Zn{vDC@1Y$XYGI1koZyY))(XG5oCxL+m}rW{eH{ru1)!%b$+{#Yf0Z5kx(QaIg9 zip`w@l1@V4HP9DHCdit9(ofX44`vRW3PY>CrX8`qBbV%5qZy! z1=G$;*E2Dg3w7fjihB*)HA;}}IvWyWh=i6PtRT^2X(7%E&43O-Nq7FfM(q@(>_Ma{ zCB6lPEwfBF%rVPC@39qIOfX&>1=lfWc*P<@m#SQ}fRa*@rVognsiDg6$`y5c^}Ztg zUU8npJm9(+*jABIbJFl2ROFqe5Wro;$0*&X=?d*pe;Lf*1PG^ZCrU0@a7XULcj@la z`Rk>9oW685U~ZV4%lv->KmpZHze=NV$C3w*WIDYHtF#7=q5WQEH0@W=tf2gSGb?I? zt_8xDpUHtBIYtgozVcODSU;xWDP?q5o$QhJudCC#tNNw#J`Nc*{=;buZc(yf@ zQaUOhTIw$Ajv@8*nfPO0zEbFUX2_9!@z`Y;=okfR7EMIPD1;?$w7k5?jAso-8HCKX z>K*>nflHk99?QOS?(}`?clEnBmz`2LH5i`aju^4&d``j1>Fj`h@o)>p^3q-@wPz_` zc1@S}8Dq7s*ZfJ*$;D1diqKLut$izVXQj?u#FGn8wmz7W+2FX*L&@%A`Pkc;CAM3Q zMwo-D^R+)-NSe@z(7Y7g2D`7t6<m%>5>6g-FqxkFn;oy! zUIx&`M8eyQZi1EOxd}IGff}7az>kThdW6P%%Ss! zvk(k)vbFt^q|DAmzRC)aM-r2$+tmvQ8&+R^0yQC%-23w{u`MV2+{hiQCjL-6>8SwjUpuHKY%K^0*`!_ z_aQ(dgzJ}-Wo$%rnaGgpefw61y;hyIB=Fwp@YkhBx2_d^vsfJ~Wyl3;{Vju6T|m4EaklUQUx!3Obez|SLR&YrD=e6y6k}ZU53FRdic7@9Rgt; zl2neXL4hQoeASdK!Ke%>FBxsmuFhW!djw;s88ny7w8#Zguh<0B+A~I^bFR283-4W^ zfz#aZ+Pb5=I}0l_&q zh)O$4Vrbu9)%sbx5#W=+w)^R3B)xLL{TM3cr7ixp+-HCAUG)dwUXaIaSfSh8O>>(l zGT(>5$)Z+<#WRHbxhbY}ZNqlWW09568+oKG*M)03MWag=z`JCuB-z@<1LtowS$&3_ zzN9LPp0f%<-z`8R&a1qEf(s%=cyE!PESZPuF zMte32H*@Tz!OcEKsVS*Rer6K|=SwmSy6em;Qh=&aLiWmd;Ve-cEFSgB+MUEc=$j_DVTdbO1l#Fs9Y6!Cw1G^GnN=_pVDqkq4krzExm|}nqB?wNIwCEVlIVJz z4IEt2^rd!P>^7xnKo>NRdF8G;(DKDnpS=5QHMtB|iG~K`$F^2XEIb6Nf`y=+;qRAN zn(3`W?nUw;`Yq*sxrKa;}F{vPOwAta5LVpvIN^qr7gr2p4p@t9~7 z$;>DHhj1CD;)^MuwMIHevYU6$-GizSfb$}-q{Km3w^HE0T=9ccc66M##oB@>r8BA-JTmOhmawd>g@IRhJcE|*WpHKdClL^Uj2%^A#sP^ z51FkVa)V7rSX&KigVSa;D$W<$7XTBF*-R^J);AK)Ib;g04Mdj6Ssk*3MMta%UOKq^ z>?lAsvg-W$OQOdFDJ3VV%4*MaoW3v;*EOdYwNU9ShVbs^JBv>o^suTkTx3c_rG0D3 zbNTSK`{QGhTaWN%PFT;_B?1a0X( z4VpNkKcu!cz(TQUU9*sT!cFn~J!5>*xF)OV)Q}|kt%b-K#?OL41fq_o8aZq9U?4Ms znwgK;!igE5u{yiQnooy_-)B|>PxY4uQ_a;pnupyp3pRceSK7L$`U)|5v0G1GDd>tn`!aAF94MkxaFZ$(OOFm+T6jh>a=6`8<+km|UVo8L0 zgMJ6dZR*@(Ofhrf2g#dU+FZRe=I`g|OWgs4ONmDI@+{M z^tJ2ZFyZ%GWHc7v2t~X_cw$FO*fMNlz2yPnp3xb;u(Dzniw{2;5}%e$z4EHDVEisW zwIfopFcXKV-%!^WeBEheia{@Jf|JNKat=}RG_?DhK}q;7qc4%En@`9&tKYH98$=BS zD^$PNZkNEp8!>wL@U|{a?|#xH9{5vGV5u_PIhhDO7s3=an?;Cx3Ze4 z%q$7p?jlaXd%j?U2S>@U-qhTN*0g-$I29VzaUTe=k6x#lE}5|{dAFH&#ziwMA4#DoD)g@#p^le#f8@ZB4D(&^O8zx zQ#4VYYz#jrU+5%_nUy+%{bFfkRIUU}hc0=cTFz}+vI-?x*P5z6k{x)iVP3Ah7+Wo~ z^CD{WEiFwzUR$oz7eq-H9K}zE(@wBm0cv>0+C`GS{7MvfF92HIw&q%6eM_AwNqm?T zkLcJ`%)S(Z{m5aN%I8yO5Q3vfb71%|501rs6$%b-H*Vyc&q-61D}}U`Oi&d4`fzO| z0As&+bT{v979Q_v{vmnIBPc?DUDPuN2(@TZ9-1Wl%+MF!lI01{!?izD8Te#QP9EzP zX6Cs*#{-UjmAP#Z9N{mvoEgW53|!kFjfyRujNDKJ^Bl{|F&Q+&KH^&%=legWya}tM zoxjrzgV5DjZ5IakVV_8ia~CXGkW(7pzxVSMhg2s6t?o)4kk75sk87R-o4Z`Dj{sO+ zHcd2z+F5c$e7&a|`%+WXH!`lI3*fcOAp9}2xHQE>3RoUjP3Xn_z;eu|4e}Q!ED)@L z-GM`_droruIoky;tcGPLE5krBh(?qJ)`uLLB=0IHUCo{Zt8|RCqJE?Ic)p*Rd9a+@ zo1zS&MfH9n1F!@ePQ``8OC~$sE{b9z(GyR=i9qiPn~@cU726ZCPFgTT@$k0b>@#bM z5?o06?aVIQt!5*jYF#e?W(mfy*Cuq~a=-n4bERzeCSBal;$+ToO@Vd$B(lk&5#q{~#Pte{c*XY(zfVBFT5e8RN?qWl zwKUDU46{H(#;j%e7RCw#M-9wC&Nz~6m{2ENgYpRdCfp8AV6f!YE&3(9_%g-IYTKN| ztc;#nZ$g_Ick6wSUQMh@GagpQcLSQB6E~oGFhxK;OUFy7@NM8` zGT&#Y9P{gp<5TZpZx-tO4UY2AM^`9aHixy57LFK0B@Nc<`}bePwAhhWqa zB3)<%*Ogo1cTe3~qQWtX2(!0luJDQsDfT@aYAu2wdD7axE=gS>3O&DnNa-GI+$&I( z+S^pmz+DSNJnmN7V)Uo@sSjs7X*y`rVA`?nji)nETgJf@Dz$&#Zd<)Kxy#A=t5XXl z>)HXWZ8c=*{s}Rn9Qe4dh@NrvJS8?)yYu>&34-8_=Lh&pCE;&=*1=37cwYH@uJZ>E zbqDWtd*KI;+RRGkyV0Mm@d9bBl}BTTinesryZmyfNmZDv!={&Q2MLh9yeaLBTq9uw zaoZ6lh0}=OYxMo?Ln4g`sGBik;bv08U460iIFb41A8D3{fI1hI-(Al;Prh~?#C`v* z@->I%^<{oI#6s@If4q-|-8Ue=Scvbq;O%Hk9u50eow4|859s9~U2l0cswL8q`vp*9 z*t`0)b!8=Nlw|xmfT*Tdi$yH|`LTk4$6BQ`Sg^DI5WK*myhIpz<*+M`bX|!5+N-ne z=Spu4Q%(?vzxFy^9NHLvWYT1_0r#7A+?G!MKW}*Xx)Fze?&o)X$kp77@ZJ%iRQqsG zs17y_Sn5!pH#}LHS#NK|1>8=gv0K~)g1(~e2A~Fz0jM6pZp4PXBB{PXxb)=wQf_jn z2WWs4kP8wC>gW5%K>qCmBMtB{+>v|b|980mc9jUeBbOb1Afy?b^}i?OA6IGEsR7xR z6q42wv42k8KdE=70a;pHm+}1B`_{*AjB{Z!q`|UlHL2P83JfR(zQL z^A!E{6%93@&@ayJj^KaB#b03S%LeelM&~)={2x&G*S&xN`|sfWbGrTv{(lGWFBtuO wdH)xAe_JTD-Wsl@=)u#jSX;!QI`ZKyfL>N^y60cb&l*90nhpcY6PJ z*Y~aUyJzK0GD&u1XJ=>UNlt{aqBJHN2^sD5SNc_2eQetchO^TF`1#d~9kPuheFedVpFFPxV&+xgb`+@9_y z()`8++;&!l5GGr0R4vK>po+KWixUu%45lX~48OZVc>4|UJrQ>F&C8~wH*emcekBGz z8yFZOhF7;8{hYnCc=lt_`S4v20Ra!uAyk=lFziMe;Z!5wiv|LM3Yy17+G|x>1N5p` z3_%o!GCYf7`w~2h-=}>N8NvLly>SSXB^S5V%n00floRjYno5ufMicPM1{?#p{XvHxGd_&yLXS!M88AO;LygWW#g{ zqeqB0bI#3zL>aEcm>k~-y!Vk8((MII50FMxze%7f{6PAJK`}B=3vrXd1L)lwub`vC z%V)JHRT!?;Z~UT4o(2{3%f1PIT6KIQ)xG}h`Nm?^){?QoEKd8E_$-{lVf<^EPKry4 z{=lmUn#^7!vhUui+xE;KRFo^nZ8r5EYR`fn+a?LyykHRSbS7@CETp z7!ZjG*HtWBZqRB`Uj z%Nuc|YJU`d42~Y^1Y|FoQxfdRPAE=7odAqy5KYXZcsHJp`*Nl;?xE4{5NarJYUJ$rq zSobeiQGXV$-XzB?Z`@egM0y+w5zJc{O`$It%?B5+77y&_{izV=E)j1cZkj2mG21LX zdP#un%khyp`{O!)EM#+g6U+bnKF_nQEt2e^oO1M<4ZOLAa4N#f&VD*W$ofEpa4)jK zv~fx}9*QZ(Vug??!mK=qrcPSkinE>(gyoha%8s^|qm!shzP~qRQVlzj#-gT= zcaouZeA5(nN$K|vs)C^|?V?OQi$)e#t%5}oK=)H^lGzzaCph`%$kgXrq?H)nU-Xj~ zd+N35KC#y(2x>j4sf;`RRUE7YF$KnHsTdh?KaB9TFz5a2I(NN^54%09-1u=V)|tUC z%GcS2aS7MCPH%5GThS`|0B349W)GsPVSaRzD50;s0{H@@Q$G&A8>LCYdygW75{6Q= zVQ@g#N{1IA|BGkp%}L)|V=Mz77^-qdD7~lrk-!`8 zni%_?^?S3d-H?^(n`(4{;LOj-@liwg+xpvi+j86V+t_avB5C_F@Dy-W&DAuN>(z7^ z2pLwAu)nbU;h9TG7az-I{iUG__+3=&_Pb(sc6M~Ob=G*U*9v{^{oHkNmU>IYwW7Z6 ziegqtc44`)VR^gSW8VTfMb+cFVw#(wJOUYeX2}ywrYN3e|sU3X1)C6^hOP?B{dSEMQ=E=*oPChs0u3D>+u=~tVjMMM)j;$NYzp$?%= z7!AbrfNKCTAcRCVhLCvC@i3^aPrEYD1*Gg|k%q0vmX%2d}} zx4c2vywkt9~dQ8U{Mg~a+Q~gKXdfW12I#87B@2nR6 zdi}bU*Iu)$Jq9)%L+wtaMwtuzLyhSU3uLoo{8%AaS6DEzwAk;leX$C$Z2h{?N@N{Y z4{2vPS>UYm%zB{}*LhbgH&$1m!_!RP_@{N%W5>Q9J0zRUopnoB1sQD_gSIswOt;Yc zk1*O3+mjq&VG&buOmdNIg6#clfJjA+%Ob~-*-?$bs|xXo*9K(<&{mOF^j2*5=Z&rP z#KW4A-ThaGsJ~D_^um`s7m$14)$zH>ZNa?{bOB;_FafJL^TYW{PKmLIdm3yqGPH5D z(~9DZmh_q&&AaDnXMBqsyF2hh&~Tt&U|rCgpprmnNNR{_$ZXhUNORaYstCChN)(DN zzH636@0-&Dcb|>yjf-xjPrs#mrN4X<4zG<$`cyCfkv>#OkLye^$t;QH4IJVIGM&KSMy|8y8_TnnO+)%ubfq$lS>F_x8WSnwK3;x%$XHXDnPJ7wV|Vb~ z^3w9b5_tx7e`vpDTI@XUmgnIK!=S%ETJ(ixrNOBl5v3l}5$G$ZCpOx!#;VQd8qVy$+aeB z+*kFj>SYh9ckEY1klsvF)Xr+oKw5)~D5sc-FX-jPYg+VX!cf*y{g3)dEqe>bMVoVd zek_UxU{&KU)s@>De7S40DOO3tpDWnTw5uVy54vX!WODi`K&`tbd97=?CN+;ww*zK@ zW*y$U5Bd-{#1XC(x6)IsDi2zR0#itx`csLOrga&s&ZGTUFHelMw)M#TQyp-**$E$r zuRE`{z%=isE~UY1SGic}*fa3w=ugR9z?>H!2~e;3Y>aNBP%Z3`N=rayjncTi-$xy`mxA)n{N^5?{;=KX&K}SKDVmeQaXE1n2$qJX>KO=Oe;wXO@9E zna=0K#fxfWMbwHpj{@7fi5C18u~}ClAkXo8@P^@H2X_{Xe{Jz()pt)5W{B zxJm_PY$@?**v#H&OJB3`1A!n@F5AA7kJrd&*g&zj!ro6ZPkSbALng~xk@R#*2ieWS zw#TUZO*b~@H7C2%yA+;sehYU#Tj&{tVo$iI(q3!%?I$VKDTscoUIouqyM{o&x~qZ9 zHLtAayPk~dhC4g!wW_r&kDQ06p|CUxSqdhxC10ys(zDxf@uyDzB(^Q=C$z8P9<@WS z)+e$MCRGu>b~;hJR3CWrYvIhLx#9#o2di5Qc5S{8M|>!XI}Y*VTX?b9K!(8dTS*C# zG89QXkWgG-U;5xw8+ZyXX8!2Tdn0J)cOFH! z|M!W9zkg}|%STKIML>rC!-K!>KVSY&ZY1ze#QzDuGKHrhNT^B5%EEm$6Gt;Mpwl-y z=K%U>c6bD;y^OXK0s;Z;-}i;AD$Oap{6)(zTFzPu@`5IIwyZ{`cE)C`?zZ-S%Rvx! z7la3G&76%W-ED1vPJ-?t@BWoT5FY*;&GwG+Us;^3Mc!#CC{s$>Ihs-Ova++XzY|5H zq@)yfG&L7g{V4U{xw*Nqx^c1EIa;uB2nYzUv2(I=gTk$3O@R`kEmf3?%h-SYox0y_P7 zx8NOQ`Xw1x8wUWX_L2Pe1izX<++N&i>nzmaPF z8z~V}*7LQyEb3Pv3Lqys;e2Hl z-;S1`?0h9li9sj(!ICDXyQHH0V7!TE1$K?ey%se8Nz zv3;g_NBL6jZNO`E0-EFFi$u8J-0^xSFa$j@|zqpTv)>iXBfbY8eW%0D@AHN5z) zGDgEFJldCaxL>7oK}P~ZdKUJH|3vh!BAu~c5QCe;YEIt0)K~mEU&6J;)dQu= z0g?ZKpLB2%&Z)g%6mI$eDPmCa$qc==d0M;dTKfY_)}=$o{iXJMZL8vfhafhcS_bXL z_>K@?pT=8YS>yHf?a)h@?tc`uNeOs&un3ml1QgOMR{&%&tRC;Kocu;;M))OlS*A}g z?3{M%TRNInDK+Ito2C9yY{XxAzJWK`a|Se9b7}R`X=hZyd^A&khKnIeTP9{mj1 zFYOu-p81;WKS?uO*1yWqPzHe#ZsxB>S){)n)b9I|)mh<34v>W zwDwSD(*+4Z&O5w+6hxc=b9%}k-I@-n0=o!07}ZCZVf5F>YZ0%!M790r4tWaw9k+YH{6!sefXDdcbsbkD zrX#N*(0W%;g4x~mm|qYOL;JYK*<{+8 z>7V8{eCB^cftNuNsPa8r+yr$rQ$WZvgNsiy9}$T;g<0&UUwNen{J+)T`>U=XTOV(bO^rgg z;mzYPQ^n0zMf;sqLUM|M_gSB@pzESh*rqQR)cba>)^zIEC;Y@l=N!=?ct$ObOiTp6 z8!C462b z#~|7^!>+wajNA9&##ENCdFjDepx`($#m3i)CkO;?x=7gPGA|I(DKbG!p@_ePu2syO z)glrtvo>ufC>9wTWWD6x6W0ZSO?OI{FeA%2rr=q`JRlH4(w?WGQtg@qJKH+j>aP-4 zhhzFqS3icxy^c=axGZi+(`^lO%%#54z#Wle6WxujV4{aB7Fk}3r?U6uUnZGf!u6Hh zxIhs*yXj`H?9d}jEFPcRh^((5x&HYl`+o?75s`Cxu9Rc2A=x`T+pf2)m0WVsSe+fX3k@q zoY*+gJBFs+?0e3cSq%Dl9jCGF#jRM`WF4#G?I3KrB$gnr_idI}AF0o6sW%x0@|lL& z0K0Vy2D@+bxQ1yZcAMkHb(SWM2P-6Y#>aMLse>)7N2(jkztuzQ(wnD6P25g;oR-W| z9Bc>7)Idxg2ca5F3nd#MG$^}oHrF^m3o-XMWzL1G0ahnl&0t=_N5o~ri=DA3Hd(7% z0-;X{TmCG0Ej26Y)Ry=`q)wMALxP9pTcFQ;E6z25XqbARH3_~yOj;9;Z;LWb!d9U9P{07Cgs?j?)^H=NVgiqxL z`+5t()zJ}TmM$uFTJTBNXWDi(ub`oAhHohK%j@=LE3WN?&Q1^G4=Jxrp6Tg2zW!}H z!|lVx#G6b0wgT)aYNUom_i25!=T^2h;%@CAz`nL>43H>7DuzTob1WIQvM4-fh15Vi zzQ{{o;2)jSrj%2VpsqnqN}>2j=I7)xKM+Wn8^j6)Vp`PyDH3<3}GELq_S0-u~`Y?lG`TMFb)9Lzm{++`Z`QOefc#7+z-z{i@G>DSqGx<51V5?Xw5PLo&i?zq=GiTP;Q)51VS6|d(WkMF` zyY988lV1r=a}Qq&cU~YL?MB-k78vlF4JU2K3Z0w>O{yU_24Q>@IUnp<@!xk*4SKk$ z@Vi2kOp~7+o<2ru&^lYwk9^YbmUXW0Vdk6e$R}ReY<-Ccrr1Q9YW`5mir3VSb~{3D z{W>MVBS!V{o-GAKuYGdAZX&bZE+&?}^?aDAO;>hgr}bj|&=HovWl`6Ji#?|Ht-PwA zWXNek6!Lv)X~{F=*k^#3-Sl!$cWdAl7m(w9Zh3wzf{qkyFKT0Ek51#cKp;6zm+>|l zpP{fuuv25{MZoKFhYO*F!D1T8(9#@I&p|iuN{8}`o8C7{8qN7;;|nFs{qEk^OCjf( zb{7e9tcToq*1K75pIyNmIT`CkIlgorw~)a54JnDEVnsu8-VNdz!BGzk;D%>CTid1M z`6$=KvLxmbg~N0NP~+sYXn7QC`z+J`R`}tVw1c4qc>fyd;A!^)fTFTrha*`!EBZ*;N z2gEbOPjec&EW{j}y~YXl3!`7Zw^o;D=sVVCnBmcA(C~p^Itu#4*~KjlbF-MWAt!CH zc11HYt{;anI}2#gNl`8zq=Q$z^IH-_mObXj7unCJVbTxl8KvxXD`Sbq`mC984a2;_n~ z4JQ@%b-fnJuB4@T;dj9&c6v9o3;uda2>y9W=}x!|H$&RSw~ZGXVrgeTT@iti`18*8 zi?TM`aQeu84(cR|M!a3(}d+s@2oRBI4en4|K6!dMy^`+i^X)$spH~E*9RO zgNqsh9g`adcrifB6YPl*Bb>+!E&0YJOyHQ zZ^@fkfHZQ6(eeq}nB`3RNFR<`Y8?OO>Gr&?ot)_1H^-rwsr82op{+*_sdu(@SFW_X zJ=nzHml3OVB8R11Z=_DYkd(zuA#cU~n8Fs;a!5ww;v>S1y{y-Eh*2h}sO&}?3Izby zrPe!g;Ktp|rb|tBgRJYCPs1k1ymKcHa$at-&L5@fopfs&P_uTC5e?M~z={NPNYPM$ z_eJC}yKdhfp2m&xgR%xez4c83mx3Qi_e<#*{3wA{czI^jwBCljLpG`0e5Emi(lPQ* zWe(Z}2gp#rbug3L_O7T;vZDQvM0OwKOZFX zZeC}kMa~y4-hwf+7^R+$fb*)d|Iv!9F{~Y-n1E#OU7?V>Ql{Z3$BAjR-SeG|6GcOf zB?YiiDf{Scidv*>*CT!T zriWcu7FmDlJ^0&oL?Ru2506@tf&3RlxAaG{WoePYrqfl^suG90A34q1hce2J)f6pS zyCN0b?)KH8)`-C{`Ns7h{*O|!c_WWf1x!l9N!CPHV)sWivuW8Lo4`1H*~LG2|Qk^Wm)%kwF@_2&4YS2 zHhKRgwd2AwW93f3MBGh}>!#gA)Hig^hEWMF3;GL(7J*nVlq6I1JkziNPv6}XMXpS9 z#_eq$GPV-MI_}FCV5c!QZC4towgA&?CqLhPGtK-1)b6XX)??lvT^p1L{O2)@;-VR; zA}?94=Bjz3e#&5CZK9w*xL$2-e$_9KHaUM>pNPNvw-Tngu=;0_1#R%HG_gZ605}McgeqEa<6(fHtW=lH} zE=3Gxt~$8x@LCn<`>xKgN#T3*T@iQkr_jS`Pr}s#TceP8nhRW7+|V=+1I(e9OITc2 zdumGf80Pcq*O}Hd9jDzmp*X@+-0PK?w#d3vwCkeRv0O{?cG?~lCKsn{$ z08T>v*(y3WxVHO|)94n4@)*$gG@iF@>c3W8l$m*{Tb>gZY*ap#%|@bs0y}BYzTHo+ z!}^_heoj?=aA7_uHWnXxewiFybEypnV$$5kIC;H}s#-cczh7!OB-KM0^e>yQfePh+RHRWxdZl>WMp1ok$4|C@do^l)u zO*;#Ll&Bh~Mm@dp+i(i*Z@1tfRHWJ)P)%uB7pAL6fsVue~?3E{Tf%-@cn&-r8ZefDa>Q0#U- zS@&j&JsP36?StONa_zML*Du)TR|_*yFcLxM-@0rz6nv7K`W+fttvCE!uCB`t(hZB( z&A|RaEisef{*3yLDJcM57_%$v=AgvybGGwDG95FX*DxdX17ngB6Tjc`HXjLIyYxwqLuO!|#fH&3t*!a#xXltNYvc?1$G22^4m z4CIHji%iRx6?WcRfT7{o`yQ1UC^ZaH@=|(MjkWTE&u&zCJ z4CM6TVTV5t)U6{P9gX3UTUN#bUL}5*UU*qbM}beR+uFk?msY9Q0ZFioot8IeMStF>NEefI>qu_1G=O(3Y(t&Sk_7{rt=2mwhM4)# zFH0B=f9RW%Tw7Wr zZp`25E&nhYHD%PKu;}}KExfIA{^IIG0y6}2%h31sleU32d?T)5_y}lM==JY}m@8-iqZ;Qxf^eS6VInB(T@3&^g2>5|A|?XkwJ+VS8I zNtC7VU9?1U*I3Fiw>NP<4;goVGi>N(*U}M|q0%0cp$()RTTh00jg2g?vK^_NoMpqo zrF$rNo|sC05xy2mE?Nz9l<$u>2kdqh7-&f!l((F)dO`-@FTi)WwspsuwGYzXwLdg; zZRfU2D%#JFm37TQ_dJ0rO>U{lYbYJ7o`)^MZJjA(Rbj6(L|c?vg6)E}LmI2@X6Fz$ zmP>al7kaMmfn{v3Soy&ACTGqDw7ZkJk`Lk>tfN~}P0QyrCE$TJz7b~S`Go7%533^} zS4`;e{A){C0QD_at{CBPp*=V`#B#x@bh#dPA^38s9%&VM-sQMeyT+oaE`biW^y4`R z*eU{0?`^_VUirT`Qw82X@<5FSl&rI(|gV*$z00b$a#6GYY_%a++YlIRN z+>U*J-FU2I&zh`rZZDJb*guHOY$S2ppI$as8@0uKCM1lgd&h+0a(cD!yb8T&(-Dy` zv;3tXr!Bt}B??7fARqf<@eq^ecV$5FX?KL?Jkkfoz78l*-~*NUC}xoR7^MeucD85K z+VAlvYZp%L)N>kcWy){ z-~Zwl9-SV(XvQw+5NDg(UFlfi6+@}^=F91kk%Qt74`cPmjzJmfdl#ow-5pE*+)kc* z-Z0m^jI5ZxmP)Cgj!-(Hq~VYay&3?xP$?&E)TKZ3Gv_36+#QVV%l40MM^RqUZkG(( zddBg0H1cj$mev`EU`zGvKI!yx6#TO}P5q4`wwct*z^EptaS^tr-4mg#mU5oQ;+Rld z9aW=_=T)J0&K!{zmL>0-WYN*J$J0Q(koFj^BkYy0T8j$CK_JWVinD<6G8B9#ocCz& z3%6p$sun#^c3E#SE)qK&+Ec$XmAAgXjeEZF;8(BqF+MUe80zj~sRuXbZ`fi2Gq9gE z&JCY$(RWw(*YRL9dIR5f5|sqzcnqv^iUUV}GF3E=-iOmEGI4YJUWs*F10#+9$HVv0GmIxsc*tiRwvA!ro{M}~Js$N)ZMWcI>G65E)9bAh*y=qrY%fap{DSI4mw0`6PK&4xZrZ`} z$B)o34a$wkNZe@=GbP&N+~(y-u3g)X#GI z`d8OnQ;A<7+vSr4fg0ND%&Ot0`Q4$YtCSakxRmnykn>|W(#pyhz|Q$n)KJ z1BGB7N@P>xL%+iCmPrl+@h$OY?ABLj3+DVZ@5&|f3{To{kqMz*GAIRjQ1#j*VuTGN z!0Y7dSn-ymfX&5LV2jdBLYZ4_9=Q)4mTxO5Xfc|)u}~#&vS{+~0m>^q z7uBW4z!|9Qn#-^WP!PPeP(vFvbdK#&fojpL1$f$GhY=A;{+SQmH2MwJ`+pL49@ysS*F0WkA z7mi@rzRkMs;Yv*DZi&DIdbBTCX@i1;c`gE{7&CkLIp^z8XR@i3^tI&#`rBGsfR(m_ zp!QnZU!`>d*0#Hg57HTF0pH*&7vs(geoBnN+|rnlbSd^>&#>8`0aB;hj%WA;Ii7F! z8-aNR8qdJ32j$PJUTZ#Pn6TNimXl^VtJ|<&@lOafXz|P`X8>TMgyUXr*bRFX9*3}G z0WZ_%>q)84hv+whD;+u`iH%?i(T5DwAjxCCKA}u*OI0f$z=@$P=!b-2QI_kUj!e(n z>XC936_;i5!vhqIgF$NGHOm#EV>jx6M;_%pgTV}v+UzoKlg#xi- zhC?88{bTY2L0E#F*n5#szPYj=SCc*1DP?hoZS8tKYI)U1#5Z_7b{1kLheDV?FFblx-}dSGEHy8VSzBi#y`*AH zB>a6o{p$Jgg>6!z;qzTX-^^TLgfF$316b+jk@rd+L+>ld8s8)E7F+@6A)XWnJ<(7Cvif$Oj~A z&;_SsuwtBj>D&Vwl4njd}rb_?@+jXv_ z5?Z+UNe6sZi^SKiw(8`*!(H&Lm0WT8(Xw*QeQPW$njf-=6L-u$Bhhhk2Z)@~G_j|C zj*r91#_oCd!58el74!H6xBHWX?~j~(#h&=OZ&M9z&q`;#^mn0he2ye$_5xMqv?Sl- z8VSiNzw(bZ^W7e$TUQ+B_g0}v4wISln4vo8?Feo-Aph0ptHAlgWZ({4LVYa2h4@VU zy`-ImMqY-9X`gGdd(P-L^pg^s#>(eE0QS>-0DnAP9cQ1q9Z_300oyQ7k_}3p6ftT9 ze0MU%hyaD%Z&2JmL~|)JmFMEc4(J}}W2|cIA>{1w_e&7~LLa#$Jx~(Wl@`56(tQB@ zpKKV=yX#!NU@I_Z&iG~iYQ1984ZR&KV!>XiIm?``cSMLLRS?3_kvd{!UW4OhI!i?A z@RaYRM6BQ4d##o0mB-nfuNa3rxfx5R8h-Z1*pkM^@{$3Ww)eRd#ma0%>AZEGHg2-L zPQKgJsdxPxhjJTHPVp@0>DuIICWb}CO+8afWolh#6lAtPg{~1IO9eY;?np6(eS&zT zFff+&y2v$EuaSUH>HGr_hOA10?-$cDTM@xV)LEE7NXLSXmQzkUuonhbubTBD()`1_ z?v)w^&DHac(f3!TD_=+8w`Ad4{sT+6qO@2OnV>)qvN~ykwI}q%d`-H-T5#Zsixt>m z@as@oA>l1)Nh^aK^pyr!^zf~LJ=m9uXjZPJyAZB&p-%SRa1j3i0Ra%|Bcv6|OC6LH z7;N#|)E+e3l!R6DlKq$_yn;WxS`n%+6%d!f^!$vU9&(Mb$MQ0ij}Z(?lMo6C~l zZ2Nxt&QpDTjtlj9(-^?3+87&yZZ8yDY+Z{53;V;tq92>%GlfR}T|DD`E$Vw=ZeO5R zy=vv64Yx(vu98Z-8#*H&L9pC4$!B^6nc(=bzmIAvx~j)3%3VF&x;e7DS0wJmzq90( zUo09MylX_ye4-3zd9IF@PZHQeEFNHZW^KPw6_bSHwsH$)*bX}@%S%9y!(X+HEQZ!H zbZw)TCQ|H3osO%`;jo83Px|Yrsy-j{SmdVlz>A)83UA!Iu)ZLc${8~xK5PDfAoF@2 zR=!D8XqgmWhTR{ImsbQqAWgNxrVmBz=(&2a+8zb?E2X8eQyq}*Wv662{#ZGg_KA}O z_%$QJ6m`f-0YqV>;}O(BLm$V$u+_M;;aoK?_dh;_llGB;ee#2$wcg+>Fp2*>r*ukNC@wv~!! z?q$YKUMF;IuIX%C6A5Yw$K8!EDMIOZ&Jp0zVwFK|OO$TBCmWw}q$1V_YWR6p z9CNJAb}HNo0CaWAO1}Jr7x@q0RP z2>Scc0IqwJSPN_#Q(pmQL||oeZKGi^)(`U()dnh4VF}wIeOyH54P>5nkg07Wfut zK9^Ib7GU>zms;~%mHy~oc>zJak#kZ+V5_zUb%HPp=`L6oGR2MJW;~VT10U}BR?gaO z4WRBe3}@C(GLL<1odCeHf75n3Ete+Mmk>_)+<83N1l;~2gZPk&d*0+!%(ck4<>qRJ zAf-t&Ru^~dzDx{s2FJPPp-HxSTXT<>t*>sO@F8-bg=_hvvY~>?;Xp)ZWibzQ+ro*pRk2Rl+QA*=}Fx_}ONpya&tQzZl zk8@ewyt9jShpBYRK(RIM`CeF}==r^26R~P5a(-r4OlvSM^(^r=N3`y!v3}ne%JO0x zVUnN(xhn)6%7Vhh6L^-?>@S$1t(PB%`)uTDKiIO-T*;!Tln>FB%BZHi*&a%41DNq6 zL#UyV638>Co_ZQwQdlgrc1+RZ6KYsgBmhSD`X$I6jju$?Iy#6)S#p7L=oLp z`;60$ZyvI_8dDu>m+JW*1p<3((Tbs3US3*6O8sAYjYW?RxVkGapGx4@l3($ zKK}}R!)U~0`F*W+;NsIl>fpMD9r+HqgI5V$r7irpw42(PB#gO`m(g8ifySl9_+*lE zUY5C!hY@&DYBhc{8bYXUwT$eLSmv)q^guc|z~lp0YAF_7mB6j_>5Bmus*SUcl0IEF zy2}}oVXn0;wmE5)^$#`K!u;^w$(AaHZDp_+yfdCt*JSkM%Po7F(}aWWdowr`i1C46 z^U;oXgk4k`SyxYLCJf4B7rQC?*X4Dy+TX5);2*Fpf5V8E8?kepUnX+{@29-1UI6)6 z+ed*idG)xUZV_E93dM0}`MA@+-ATSD>uml+TtTTq;@bp33uy-OXhOkv(h zs9oc@()V4Wlj?ENqMzYAZkj~kR9eCoTH%ox)`zL*M`YkWWN}MT-oW=3a$2)V!1qI% zLZ3+CGySnp80iUR{3YaZ>0Gp}Amrn5vw@3j8NngW+U@hms#-BhlZ@%p35{VbS0+!6w@RBt6DI!imX z>}g#Nj3F92TjXnd)D!$GamHI7X=Vci#S7~i6K!SHskM{rUK}K--*UukgMGfeEhGl- zIcIwghbz{o?FB#e5rb7eOfT9vQ6E(I#u7<-I8TTaP=eoHDv9d zks7$93Cukm$<}bKO^^Z<{4}wsH4T=Q%JQ=W5D>MrjOf0l9w+d0m#upD3ia+uF9pJ{ zkGR`uRqg*|6_{Zh4#Z``dc%Za^7^gAQtX!_)wl}{l`o1_F%F%qG-J!I(McE|v^(7* z;@Q~!b0#v-J9D0!&T;})f3#7hc%%9yAxw^hLI&tAr+CxBwo9P3}B)v5Q zsjuCK8R-c-a!Su%2I2L`)jCeU*Hu=m%+CMeo@}rj{eeJnfGAokrRD*vCTj?h;of8+ zrCv1l@ZxwS+Dng+3Vs+bb-tHZ;KBnDxDtkhWo;a?**~9e8{Hq9*tG5!>UKkXM-WKC zg`u49Su4sCkhgBi8aNVH82!2O_5Pmi5+S@n@>Mom4lt$iO!BAJ7x52%AtUhuk4bFU zr{bzo^rX=w^7sR29?dfUp^rauiYD7AOFo7$HYJdJvWRRy}VmaIMRAt`EgX-)8jD~mqv z@O9J_MOiC3vLD|E^FgpfYbh-!#C?s;U#gam^?M+NzS17Q+HWnhQ8g$eFUsi;h229A`SAA(AfZfrQ84q9j6?5^}v{@-HpT z&sH!O_6fy&p!(O-cC*%bzb$Cz`1sgYqb^H*wE;TK%9gFc-Q0Jj-L??soKiAj`$XkU zQuO&4>7IP1z3H>dF9k^!kH%HbscWCXo^3NGjNld92K~oeM`$>7_yBk~)&ribZ}|4S zwuj_4uxetXbGTGwBmDdTy=VBgHEk%HC~Wzz94g>;kxOx%FheN3b%~^L)CpK^IZj-F zAN4BDx0j)#zG)Z{2zAT&Nx#)#n*lm!8!4la3&SAh43?8Czd|N>&MWJobRp_R6nc4B z8<0a4tDMvC(_-Hap2zy~u|g8WgrOnZ65EXPCZ~0an8~5E&mDDi|2@ZM}&mTaWlVNv#DP(z^Bl;c7f0%v< ztz7P&i&``xcPTqeg>+m=5Pb@a>gDd*J1u#Bn%FEZ=WP_(GN;IbU(4yc56ObBF`Z5A zOrz^Yv%|m^D6t|Bcs*40C?B`z?N)9o;pADhtPqP^w4UG%+LRqnGA zFpCFF(f6U~Vv57>lxr-ttmzR;=r%I>^F_!m`mpC)lNM-|W|1PfLvE$VQ&UkCQk4j7 zc>$orZ-EKqw(n@VO(tc>h{Tx_=bj#g%Hy z8!XC|knFy@9#D?L!-NH;xt!X+9EdLOm*$;UR`Xi%Pk zB(~}u4L8~h2Cx_YRT2%~$oo;esx3W+x`m>*o#DEY7MVnzX5bDw zgiYo!UsULc7>$Uv8-j5a-SQwN+Ea`UN^bpsYCU`VaovtApOyV6s{$5R;kQLx*~*39 zV!yA1Xr@cB_x5-OHhz{Ab>(7&+Mj$cU2M%M{Dy^wP#%FfNLs^Ht;}is5Z#x|!`AWe z`TTNbqE~{`k1PFAc-Md=7vmQ*TJ?k|S)PlDqymZ>P?r%KRFBYKEvJ{k#FC>ec`rBB ziBz(^(d6;us9Jsm*G8j1F{xvQiY!Adgb6VWg}u(O{oH#e#!LFvHL$I%?aR1H1kDrY zV!wS9nBQxrvSvp@WKizKB;g(uGq5SGgm~K6M|tEwvM!8Q-9iP5zIsuS@PG1#n@H|n z;TE*;L%VsQ+E9%4inXQ}7M7gTm^LU#T)IdqC)v=q{WeWcszt&@7?B~aM926CpG+_J z##w1?y_zyL1Nl#G_|~X`uoxDKGfKIC30FaUH9C4omaJ9mldW4gnX(*Fj4I=@x}^2- zz_J=v(%L~8W6yQHk6;NF!#us>N`3APM&@ejSI8D#*FTt?;v?-+ z&Ps~e2l1}!l#8NUw~nQ9^k8qJFMyt=$-c{N;e^`$RIWrT%iXls1b}^SN1h!&{}_=+6Lh6l zWQg`Q>0RFG5sLm4lf7{rbipP=RxJP7KIyb2=4f_S(%fv`@xO=s;Pw&f^17+f<}r7gwjZum5!h@pz-VNYMmb?dl`l)X&dd3z-E1{(+u`-$7`brjA0kQCAputi|I zghw?rj5SEicpC}9z8K(D1cP7d5Wo-KL2B<4P61qJu)Eul+gczmT@z{|Vl`fnb?1S^ z&w%xo)6Kn^wP?s^{tXI@s094&^2CNFg{AW4MdC)g5NDr#cUV+KYkwJZj+O6)Ba6k{ z$K{eeAZJybaCu{i2d-MBFT@R&p6_~uEhhjz%2Fd!F`L!&_uJCglCrn9=SbZU%mP z^spNS{H{({nu1ob!c+-w`P$wOeQ$g}Xnp#zy?hG+aHqM_X1LR7y*pepCqc)~0`jIJ zjGh-ZW5Y;|Ww26xy=*rguV1e6yHi}i_SPs@rf8EfHSOb>R4;3JCQ2_?-fMfjc&xRr z!Vkh%s!NI{In9XO%SSxg@MPx(RPc|&vP}l*;|}*Z`DBlUz|~CAywPHawpXwfO=I<* znDs2d_Lgdu`|<$jiMaJJeG}&&#ADW9e?iKur(u|Quf{x~3oq!m_gaf5)6~kf&4Mm; z9FL5q$V~|`t4f2(AUxz7y=}%t!bG*^O^Y`s^`cka1Vgp1G5kxl zXF(OnR{2v~WV#qB^@gCS_T(Q>pwD z{ja`)Un24!?PmW}C4lSwJiDxP>*%u9Ot&gj;V$7@c#y<#b z2`JY<>kAMK=CSp+nhB^YAn{G1`XH-gaYED;h)1#Bpi3;we~@z4<5p$l@QKn~>Egvk zT99YwC3q_s2wb<-SoH91W)sYQz#ad>V*zWyL$QD&N?^+&0c94Sgz-Mg;YH!nh&BWi z3hMhH12`puppAx(6hn}YzPd8A4b#|2EXM@dkDsTWhuOXlw);iM&TzNC|0UmVW?D=t zd8A!*p|G^!vkttl5D!dNri796C_qdq!l9}Klme>Z*s6qA7A@(#5NVf_xs>dCxTT>6E> z5J*fk(UR+@yD$(?jT*K5T2exK3*;Ya>HYBL=n-V#-!y_KeEIj112< z!1S4;1$Lwz1|NmF7Gqy}%@q)^D?gLnn?kpP_A=2pla{v!MA=!(2=&_t@>xX0y)zeb zXJF*=%pr$MDAmuCNmZ2v34Q;V{Y|36Y(z5~72{PbZuxjh#P*klHw;OQ`ka}z{o%ru z*ll(YKLw>^)b4eAw;|^YD+rRL9`i-2gKtdr`j0TH3=cuG-RZrdS7u{PP85M@4sBoD zCix|wwZu9fGW{xQ`O@n57>K-$#v(WEGgyO#{OBmNrIL6eo}>$M$-kO-%Dd3XO$@}> zgLMByFP@Hc5&~|KAE97oe@UKX@=GR&@^9MmCqu6WZ_Aw5RkSE6uXbHFh~~~Z7yjsh zGf{Vqqu#u?S3)r*pWmrB*{K2&wOw7NcbW{k$t`%<&m7nvIH=pNiDG!oE9=B}ItZ?@ znSRc%(x*~H@HU;C!UwUg9D|qOd4(#})eEdsxp5G>rpQU>fMT`7_LH|TUTc=P8w(7+ z>9mb`4i|>>_x*LvSGzS45%YDO*uCe|{D~)xPsBxvdgvSSBRATPMtRRy#}pe5*sKUt z)OBZq?23et80oc{h`ND|f#2VX*`|PPq^jE9`u2PCO(e#=EEyTeP>>~hc9GK;Jo2?a z?{GsZYY5|M&X31@SO#}Oku{Ze48k2Hh#y<-Lj9hr7% z6iR{~2iu!cv5eJ-=AMD)J$8x|qbU=&B~?2z0@8Yh6gA@8d`Y~p-__YgEdzGU3HZ(t znjrd=gx*?y`o}DBe^6T2gDE&L`xPEX=arG~B)|iQzc- zBHSm62W)SqJ7wKf-@e!>sU?Zotlcs#E~qWO=?CXQxPC9kJLO$4&?%n!J-c~cC+OwQ zW14K`{wdwN{7{CaZqUj+*IFYNUy`CziKVJ31IVMiRLygQja5L@p?CX|_%DFf72Ld9 zzi{JuINbKoDa-=WaM>%X@I&SET{ZwgUDR$8hZXkZ@h|5LZL^~)mZToCTUabk`{B=@ z^b$Wqqp(p)Y>6c1rR;j^{{uS-s0gT-n!oZ_t*v&vsiClG5V$x{^h|b{6T7~-Qy3IE zv-V2IxT)PBentv>AN01SIC|z~{2(Wk{t$a_HS0V3)|*+T(w4BR?M-*bFWn7~C|HB0U1PIf6j%En*)ic~24 zVzBcGgBZQsS8-HoBB0VSt|d(KRlh-t?Wd1M0E%Co>dtz2U0o&ht0z5O&bswni_=gw zuU7AEJ59kmP@7e`y4aVzj$5hCNXAjM=TZwQV*6 z>%mEdj-J1H!6&n$rUE$ARHTOP%+ac<;?>Pxcrm2%#||1f54+K|fycpojS@YC$K@d0 z6s&EPcFAR$JHmYoB`mdrGU{+98@&ohx&F_`v~uaNDJ^^X4aoXu9}R|@T5-P&Sc@M} zItbSKxA)`gp|O-6R}D$~GNvR;T~Z_WqOp3<7!Jy3Pk$tv3{g{PH0d~P?hM`HglV!@ ztsCyD{%kZIQ`r+;*uKEyg3Vm=+th6@hP##y*(++3a%I9@X@g76HKT@KhQUFBRE|Mb zZZ?Y?<-S6aNfh|*S?RN$2Zwm$C*s}4m3ThW_CQzYqrj)L+ow)2#oW3AGVhs-L8r%# z&?(+m)WI3W&aFGcHBe{NHtKm6{XtXb$?(8Q-cH=&v@&!PP-a2lhO zzdLMkhr-iwi}yBsB_+*i-sKh^9$|h1w#mqlyQ(|Vda1bt4ZpiKzbh@UWikK#Lwq=m zouPho@$^{LI0ooRg453&YQtZIw&Qc%4nTUoq2AmKfokC8?Hrz1Z6xpMtP<&%GMuI% zq|N$UG{oEVUe4W^l3QHv--}=As@Tmx8%g)rtu<*6Qk5Nq(`e{;{!F1#BU1w{fSkw> zrwIE9lfq)`A;%1ReO^O}!1~5WsX~)SU9Ui(HbKAQ&P9@vA1l>8FWV4qI(*`&rVQzp z8B>cS&o<+v-mBT~+4UNwtOF+$Ly2t8-F-NcWoN9swd2d@jUB+wKiW=wi|lHheRJJ; z@&Hem=p_hbk673?>7sJ7%?@vF*~*D-*%?z5V|(?$g4GC}cJR#)!e^62bla;vG*=_m z?%EB3ynMz7!;;Oa$GX&fmVM9*mRx=FMkPOlo73TLQN*6gQvVKAq2Q1&u{vQxaRWgM#573Ja zQH%*p)q|R&vjoODbO9hY#oO|3lcw=pg^NL%rAhCUNuO(m=nS@m2$H|=7A#34{)0P6 z7y8LOr#Mc=W%|{za+dJf_0j2Jv_~k(Do^@Sn$xY0uzBARjG75UtHHP}kJ+yR7hG6+ zi&rzb^hlJ%%xNBQ3?3l^((HP%yjatz^nli_oEnnJC9O$PQ{I(Gx}v8QX8D>n5RtTh zMUuno=!BhWfuo7BZ%Q#vQ1+~2_<*YBMMQ&alHX?rre=y30A@yCnwmXO`Q9?HewCOK zF@6oDl!{>2Z5w#}n{3a__YQJkZENpRE<%ye29!tCln`&_k5G$0QwGAs%_PSDAjXMN z$2EaO&94ZEKLg$V@N38InEAeUwu~3C+?-t9bn!*E67;iDE=MYU@lyr41YFT}v6+d)NNQ4@#!PpVEGbp&skPiGwVJ+wu3Y{oL`=YH_@vZIj4WxvU8!{`X7MKBfY`dg0I-Ek7T#S&7$EG*u=8K4aKbyp&pI^j76 zETotug#)Eh%GK)zeRqgq8l|9&&|ZbMWvt^4C)%48+!~zQ^=qTG(AFIruk&V=jI{wi zJ=xEkl#q8!Zl}P30+YT>Dew6N zQwhsl${V07wY*|_UaateeBv-uC?2>i)n@;PWFU;-;~`MGX!0z<1LbVUF=)p+hLb+n zHbVHYYZYkJJ9L6g);R|eyHu}`m(W0>wF%~HA4({tE}M;nzg^+Smeg^6SYATb_PTm9 zOdFvzU?eG-fx!+pK!HLkY=qoTfV!0-u4T=D$5hL6nRdJQraBW2z`%Y#ICBa~mH#NC z(ql@5kmyj1H{5@O{2Zlj<-Eiv(S$F00Gu#w^NzfP+J;}fFOv9H zSak3Lpaa~j>Fkx_T+=(P@7KDz-|Ne<4rOR=G+Ouijis*4At;81aMZCj#h*CTn~rK+Etcm)t`lL2 zA&!t)Xz`XAH7!}2?Se(_y}x4}PdC?@P;C<@3=uJC+hD!|oRfC@_3l7H|4#*K<*)w>Y|jwD)&nqD+JY5^!3hArY5ru^I! zrF(*{dSZ06pOizX{skMrS(1LXwK}IQ2^>+9c`@{fiXtFw+DZ914LdOzB zvGzJ-rqb``9y1QxLC6_@usRDU*)nGyiL+ItlL5b0m91}SD%3*0O9`+%0`k)~No4ci z)5sM(O=!D!>q);V1ND4w{|L@k-6GJu>R!j$ zGM@vxRR=fp*++YxZN)bi&Fp-zgX{98Y^{eLG2Gknt0M=yJDt@iT!S1{WW7dhbHsSI zisYkHad1uOZ1fD+>^*~K$wGyKxGHDECv1wrE_S-MgG#mlh4!ZJi9d90N|T-575t3K#Tb0g?ozDlT!QLM+%~9c zTuAjOi%bLH-r&XxSwx*F7V&wMG}X%4j+mgqkl2~rfo3l`qGFl0>1wY&pTBUU^*g%) zfF*Zb^Lg91eHkoFgoEH_u-As;PK7KEHV08=m|oj}V-vZd{e;@o`PHmfXo2Y9 zfRuPI52t{lyO;rbYRW@Don4|hXqpOV5MZ~;YfC!QMg%MPW{v^x`G+Q7O@SWF54JjQ zmv_ZLR_4nREb5B? zpvmRsaG5z?Bhb)0S32;`Ct1oR87LrLc($O!da_QR(tP0wQ`Bo&zrYTs+ zHA!v>+Ynui+;gsR+}38GXeLZCXU5-j9!?5*_~3z5s)2CjTDV%jovwQAH)IV|D(ux` z*0Q~PLb=)+wND*ZgtpW@TrdbYCy621K?FD437m|9M;Y6%uax)`Lnz&*b`6_~zjw7# zSe#r^(^oEWxZG1G-L-XHd)KKAubG3qe2d=UZkzS_A6c`)hxbW!J}XvdV9g+`yIQx8 zY(dkz8)gS!(S~7g%LH}rBCWc``h*j_{HHxi=9 z0Ot8~ujbcy_288BEXH<&m1g^sI!rz@DC*!7J*Z6+HuVzlO-UQ+T}1ahx`w!PivY=w zi8ev91dG6Y=H+7V=U@(#iMTMPuDU{S*`5GsAs(sTVvY>ef(y7D>K8sk7`Uu=`}|1q zFq6}9n!{s|as#%KuU1wkG@RdP^?)9rp9~L9MyJMcFE}HXN2*7xFXn>|+vBf(%sor* z153K@oQ(%nTfqWv9KSpbBZEZmamQ(AGZr=*9Jv&O=;7gPeA-+&V%8w4NFG}z8$`8y zD$j@LE3T&|Nu~)0J0wC+0mM2Q-{8F)9|do230oh@6q_13pCJ=brTZHUi?8D5xKP)Y zs}`zvO5tCDNXti!+*9=rZuHfa_=8Rlh@)UPmMcRsFAMPvcUCDsbRdPtSj->NnK7XLv&Pbn7rnb_?)$I{oH$v>9M zsK2j-Jm&LKthd|5)|#khQ!R{|6AV)2aHh7q>N*xN&52}H))v_@e9 zRjb5qA`o?B0&I)TU^c29a&94_Lrsg%vubuMrKwHpA0~Mm^R(0xZH4zM7C`(Yt<&}s z{qIumNs+_@(0JR^oUG=E?C_`t%+p;uYm2T0XI%2r8opycLs$Rx8V1?H+;f7R&fIXMG(>xwwLI%uB0@lKN` zSD zoY;E+DFDl}g5@OJYU9|B*z?u`&EC#w|G`a+mP2T~i^1n>&fZ9A$^zwu!{_^a4WweDg4 zAY1?HDsV7Ay*kwg3WtFH=alVgc!?GNL$+)d(a$yisWqLy*9Jz^YT>9S7pR3 z58)2a#nb!!Rx%yOw0P||kK-I}DDw1zKjM>0^|-MubnOb@#7fHiT_JHRu;jNA;`?&> zFuux2^5$&6jcPYQlCrwwqiWV#Pn+W;H}(y(^v)x{As`Fg|Iw3;2ZgJ_Nbg96YM0(y zJB*t1`p1y`2|^%BWN9j2>kI_CE>`!$T8B#Lx*rJ{JYP>x)94(6_d7^BlWJ;fmjDHz zOKnF}vx7Y`cT9a`sebJt-BRNjOXSO^3VMz z7_$7L^xVXeW#>3k2bVOATKA7ig$j9>!xH%`W`RJU2-a@j>G7*P#wLx%wP3chLLL}T z*3L6BE~`jyajXUVFMDQq2-;MTbcZj^AK(}^Ae+-BLyrfpuM-!Ab5O5Be^(JRA$yBy zD5gH1=w;*sX>rWQK>o^=3qNLkx#qL+LIl4L(6_qNz4()M_sGA@8g%#l6niJ0_GH~~ zxkr`6|BA)cs5YFc}YGk>CxeK z9}&Dk;SR?vccAN9ZhGFui?DsrEX8p3p@@%(($s_7Ox}t8t~GO!U=R!vp}>#Fr4HL9 zH5+(?3n4ygra(W{&Sxo7=VZ-}kYvgSpWn!*&6=uK67hDZS3$h;_#ma2S&XL<-b0$@$94Hxc6z$eJKL? z{0JMSYW;H-oVb7U+I3Rt@D^8&%G~OlYxFEi!9K>kWcZ|{K)OY?vm_WU*}67ws<~bF z#F$d5mbSmrZ6Iv0oa@s2>Y9l?e8fB7@B)*s-c~n1HMg8*GI8Y^f3W#CbB#0$&wfO24 zwrMy~;!kZ2_Q9hjahtV!C>?y9Qekyw2jb`!fV?pU(M6bE(Ob0*lfJ z{Z#pcFBK@JRM(k~`rS@Q@i6Ivj09`F5o(5yfqK}-#|JMe@WVfgATHLlwhjck3K`)` zvZ{FjZt76ekrkU-n`xQP{d3gNs~^693_`CMMdS(KvVN`nwH~DpuLWFc1fhg zLw`&clRSI$5?QR_PRfMy`mN#bN26H&KmG#9-J1LIfh30QY`I#XM;hUXD%Q9!Z%m1c z{kAC#|D~KQcDrH>52C0QPsf}CHoxeKyYE;Xs@5OCZzwiX41crLhCe4)=I!|wm7CSK zeRq{#k3)62jN9^jKu}p2r;~3||BNj9r;`w8b1_>TuBXjAW4DLzh61+OFC!Mp)-MoB-3bACo=esDvql7h&)P@{)BA z+tfb|6|@qB2X3!D8l^mOfjuryy^JH)-3Vt^#|p%Oku5s zV)L5xD_#i?QkK!$ml4l%RT2T}qkBq1yFWkk{Z`$KiFdfoqKcbu>%fg;@*!J{O4hc} z0Cw0?mbp)#uRC`GJ#JmUtvJv;y4urLi5#@$Hjxk>hd$L2rOg<_cXMk z_t;=KR@ZiX-9z8)P6|?~Rrsy9L-~97!#0m(Kl4R|woRk%6TeF=Qx4E2C(1XJz9 zQa1!S^YxBDVDKcP}2;kpx;f+I}CAXXb%Tqy*OLrvr=#C0Y?4Q&riLUVe2Kps9phF)$|1 zy8P3d*O#Z_L4mHf_8ZTmZuwoaINyfZtV9=h0UcPA@0kwtH-#03F|du0t+t_Oav8o{ zuA54eak_=mB*Bd`epaoMj|JDrPUHkiIV*eGT-&Dv9!!k?9FzFeftpdN4>8wLkeE>* z`%@*;TAwOhYg|UXBptr}Ignc2rmmVB5=A=PIDGmzfU6g?!F{@k74kVmrz$K$h9kzHR!O&9_+Adeqvq~n!i(6P&L1}O7@!e2 zFsH`_Gtq-#x3fkM)k5759>)oU7!f`D5Z@9O^5>y>`>g4PPhVq4LV`7?+;+{KH$&Gs zz|D27*wdX#bGMq`(NQO9AULTgcH&1v{46{dv5zhZ)e>$XU2h_I)CAaT$W zQ;M#YpJ#!Tc4gcRU?TR9bJ1eEwHr+eIC$DlS{9^Plt1XctMC+yt0Eg&fTN~X?_Vgp zyKfI#Xp(g!b)O8PT$Y394Sd!aW6p_i=-eL8{9Z~=lSPRywQ31OluYMjl&I(2kBU2- znyZd_!k@pA~3BxZ(E&{$3Yb^9;lIe2Xu?Cs^ z6LA!DarG=X8%#0Y0XzMQnaieSFpB)~aCv@Vd-3 zB@;c3%WA}};~LR9dL|+ZHw-i9{QH2Ipj~KLrBAe<6NRAvY3f`}_7?%YpXs!r12wTC zWc$8LAxG*=6r2ihP14jFNDesyOVZ4y6b0|A<^~lPegd1O* zDJ}6eUkog>j*nyunZYzA?c!y{m$5H6+qEtFwvV-S8wuR>7VG}%;hZu8@{v218Spxm zb!P!zh7FL=D_$6+DZN@5N`^R(=X@71qav)4Y!Ww6rI%6j@9IeB`1Jm^llb5z^6A+m znQODM$G#Bg{{Rp~Uc@C4$x>B=HTIz#`~lQZU92LXyuHm#kujI=)h4&b$vKo>xZ$cj zMQC1xS+TK|qD*4;2-FF9sy}kro&<*VH9ITWQi_iA2#bN~eWy<-M%=i{>QX;xljf42 zlD}|7ly?!~Won*DYDkGZJu7@Pq{7`r8&m1L>BR}3dQ2^kGu7W!H@AopIvpwD z?J@7-&y$@@uI`i<7JeFSZH-f;jMCnjW?O=Y7j^)$z$9UIYpuNS+6JrC*RvLJaY8!b z4ion63s&wlp|;m+Q4O8#!jKL_B@=^KgPiB|F94>Q;;h1A(sZxMFfx|V@Gv}p%j>E- zW38?Ga3C-tTxFU1jh@%#7!6~8XIaQcE8F^;>XfIG-zCHO4>zNuL~a+Cy_WQtKmj%* zwOOLu!;;Ye4T#raTx8?!)0%)8r{*)?RldP8*zG0qN;PL9JOH12wP5_S)o#Ang>-(9 zaP7MmUnBgExdP}Qb1g68`-nKc*qd1={v;4|Y_L9;m!#kYN8P@Yr&O|<`jfjUeMLpj zQ)mWb&77xnQ1zIj+lJs)Li4$1PiQ>>mj3YF`AUYfu?0U#wOjoRjfSpTw^f9IlNI2T ztMjWNwD_|7B|>%U2_yM~aOfT{OZc?DN@reItn)Hdw(;y5TaiqxET-b2=HMFmAZCV< zb^M4s9muvrvdTW2xuktIqY%Y?)y25@@$CDjj$UgSjkJKtWeb!J^MTDCSA(KLg-1I|# zBBu!B2M400sne&)MJUZXap>2SD>%QSmUEk&gXa9_BVT8Y3<_qBe0U(*4G;`QZUdAo zY4bQxG8%x`>PE{u2fsXx)HA=l9K7Dk{JRHVNXYC%t<%bbPX|Nc&a&J@x$ob*G_HgT z#ge5J12w-FOo#-VP;!=P$_>i3$w08#3jMBjnW-gg(2)r=+j>!khcs_bqZ_2znK@GI+XYZt9X$`G#+ijfcf*veK zUETU!N!K1O%W^nrSqr7&!?ltEkdTe{jM18wKiGlBuKG^R`0pxGpLUUxuP6YbTqDYM ze4#&Dp=3|EgRK3CXGAn%M1J|jbDsdq#N28wUl3nQ9CpR>DWil zfK%+1rrOfy=}w3VxoFSWSA<33=OwD9B?NI8)m4s&4kDtDgKWF`t|{#gnHiq395mY^ z_{G=TnGIo6g=BP7S*=DXXRB490w$V<|4EmmX7G1obW=2$hb$Jj=Vp5LGK7rqX16~og47m>A-e;UNPWC2OAcepNbAnc-6Fnay&QRvL zO{G~a984+mChdyqkpcX3OF%uSaY4C?;{Dk!d;1Z3-R+SyF^!Xjv<2b5HkS3CE)gvv%XcpHh7}Yi_VG`03Z1 zppoi5C<1d52o%cZo{|_oW8Rz}-m+f1>~Tz!g{%MMl_wi;ggZ=`d^_Sb^yiAM7EaIW zCD*rXOt%Z;#TbfJ&j7;GLxErer7?r+(l1T@C!Q7d_Tn53oCg-6cp;StQXoZeW71Cyl?Q8 z4?7Jqh=-q+FVkwD$E>-G{J=QYnRGc&pk*f38M1W#>?(!Oy)Doty=dKR$Kzs6W01H7 zo)+uM>#ng2$G~C#N%nJgPC_~ZgF%YX>{Z^QizH2&P?A8+^fU71rDr;EneTF9sE8gd zx#xmJ&Ps@!8aH~rhibJKQ~MAeJ~dbRK%o}r$dQi6>v6@tQ)@=fF;-H1MrN^*vf^RD z+LN+=-b6;d)lXNhUCeK-asBwaz|%7zn=sZx<5uft#OeQFO`6B0PA64!!xqlvye~8O z0Y1gEZ0^F~K6w^TEDfa$qyV2NmHo!c##(TydeQ_k8-!xCRa)pLz*K$`={L%4!IT$% zIDa=MRI791AL7n@2k?Jq?ro}UsL|`xFNd(4n-Be3Ko&E0uaN0DD+ms(#bQk4q?N%& zUfgtl<=bb_yXwg3KCt;lf$n1k1&Zh{U0WaflqG0SsU3VUpePYK`ziT4>rmHtJWsS( z>O37Aqx^jn-Y0p@R6hI|OtQ-MMe@T-BEFd1WJlH6qvNkL8S!~CU4IPaU3?)Cw@(&a zs`dm}Kqv9Wng_gn2kF)uZ*YA1saEM{J+N-liyGQz#SOpVfT`OSQ#n!S9m#1H@(Vqk z-n&He6(i~iK~oK9g)eooXQd_(&=JF*s$UXtDPavZQzIKzPJL{vah4^eHKIds@CR8p z#q}jK_NUrx_+xo=Ls8OJTY>E^zQXVC0#5DNK(ksUj5pW0xnjI9|KqGaEl`!3NArU@ znR%PomW(3h08ajMBfd=-vA=s=H3e3O3d5#ZzQ7F=^yC#e+;2dt$P;hrN*c!(qai^0Nue~m!ebF~7L(FfXm|fqKhYdPn zlL4~GH_&ofBi{MJ4zIa3)MeXXR&7!sd6#{R{K$$|S<@MD^pN}D`Y_>c?M9#rqUW?T zF)xqRMeg!-G${N;bh+%ZarMdcOi|#`ep`g|)Js`*JP{X`CuLOYvh1~$?Kj#QVi69y zmp@Z-A;{uf`tAD5+Yo*9I^S=9f*<#a6o1+M5Pa%du}$hh_{9{BUcnCepbk~>!(@?M zeP;?!(d!T2ZSc2#db{4PUoxUOJW=w{WBg50n@Zk7#$!p0@gm3N@h_ex^*Z*xMRg?i zG*3Z>{qB{%^Fgjw_NarrLZ&nxSbk8d=czX}J*WNpb`EF|p>syVX;5q8!Z!;|GL28s zbl(^6a87as!tbS5;X{{_lZubOs-_he!e~;xyzLwL>d5qjo)chA zSD_kB1<-|7KOgQ#_esGr6V!FooWeIbgrcfbrdq$Trr#S4kIMScpkT<&tvdTI^BLMN zM(oPOhXE`+=u_>mH}S`m-n;BqZo3~H%n84+qUvnX0Mt7jACg@9yIm*2#_Rml61EgZda?HRE~!1Rn(8M`f58pow|8Pi|OsCajuZUOE29m5!vF4$; zsh7B^FXa*=5l#yamhyo&QHWKL&eWj5oSed_efDlv64l9qh60yc5-k!LyjcXkx1B|PK#lBj4=IXmW!})V7lWST}a)Iho zZt3(WTrESTN1~IXrt-QU_ZR?SlRb|b*9sCw&K)HAApZWfj-vP7MH~j{b+V@L-XC$T^y$+rdY4xf$8#ZuYI6Cj6v+OD}z5F+v^vvmcPCPR@rV}l6m@4 z#%bf(ydt$L&}z8abCTHTkHTI65XdXu@w2uADolIlHzn8Rai4JJl6_a^o!i2$Ju6sj ze!|{ob^!z5eCyRshk2DmLun{N&zvkY{q;;wG4^KeCKM1R`O4!BFwijqOtOtJ#5!UX z5!#Y3v5@=<4oKFf<#-k6jWn^qHcz*E!H6|PU4BuAGmwmqO&!B0{6Y*&w)UDlbDGG< z#q*VLd3AkZ_(e@~V_9Afu&r7(0%Y!qtH5&?GPCQB3j*RpR%uSTvFwKE0H=i0_xYjz zoAJIA?Md>~_#vt$A+*87*DOgZBs_ZxGq!Dbh&o3WMu1suX_B*dBOWR=mhTn}hzGs3 z0n~YC$mq<59N8n&C}e~Gm$FJF7wRl8O9{;9=nZ$V_Eam#)J&%SuRp(aL1TfI`wxjMWE3@)M)}W3XHsBCY(=fUaRtbpF*cWZ^+N-Ciw(@$; zRX4B_Dg2XM%6C8zX70V#8KL(xtnrFlO>VL|6YIhyQ{sf7|({A@~?N9e!s^p&M$S9?21Ms?v-dT z9#clLj@8)YX5tA9SvMqcn`@*E1|W2z{y}8wE&jc#73LCh@_A&!TecDgNyNWZWUQtf zQh4A4ttrJPvuO7Jps^Fr3OpK{=AO19ycK=DKPjc(mb=?BD);L6<7arW*PUmTPP&Uc zppcR?P+PB4W@~6hmiG4wRs`Pj3c!@j-v*qxH-?}Lx*7}Fxd|t-tUaW3!v=gzl zdCqA*h%f=jyc@Toj#>X+&*=HE-TnHk)yPBt{+8L>v8H-f&it!!8qfc>zW&cv^Y-li zF|U%4;m?N|&?`%{6AaXH{^4dyQNUs$CS?AGRrwedkQ5t8kLgdFnimXKm-&0yrgxbg z_c~O|97;W;-fz&3Qd>Zd@YI|}56@W(s;7UuQ0^6yXzvx0uvC?U-$DruI^lmw#My5! zd?#VEtX^dn`G=<-W&z&qB#T})wFLUBr-{f=aKC%X)O?s*eBiA0F?1^utv5pMKn17x=$m_5VEW_fTAV4_&1mRj!=>V3qd|>b(mn zc4<2)O^W>e=>GLrS2kd(Tz3j5eD6X3pRTW%z^ChcD|Y{B3jP|S)x8N>=@(PW{R5`o zKT4+1{iIXHI^h2|W7Lxc;7RYw^2FdDZ0Rr2y}5g_x82Mlw|^WU@PT8kdkC4;D8&3n zI|p9(=3_M3G?(?H?{zCu|J7syH;}r&L1)b`^M6op`1iT1y~oG zvZ6*_vHuq@30Q|Rz@2#3tdz6<8&lBo2h6?rFfUf&zxZ{j;hr#KT> z?h{WwL;Q)O9VRt}W~|5LV|J?NUTWG8@cass_y=`Gtwg}W*{% z4B71IJy93?`(^4%bC1<6LXCIcm@z`Tb#SpB_Q7Gt_NBny?n#{aLh2tpj||-FH|DRt z2hR%l3&X6XT~tMHB2@=pozi4ls=ZRZurqc4WwVKk^$q1eU*FE|NAish z2lU$b9kG$NNra`C+pQ0^h$qRfR(Q9v@#gpz_jtv7?%p(^1nHZ%bOb2g`*gOe-O7Mi zlb~r&YH*$7E}3ZBZ#D719bRiF3VMw}Rv0x8c1Jj|NMe z!S^(xo-z>`!uFzs{izsXDZS6Q^AsPM$rE9s5@6w@$){AsCZq|uNjd9KPobj{p#0|x zOA?I$A?%0jt=O3wbFx?qFRVP92GzOWL|N~&nY`XQN)0ZsEdLbCXpff9;unxhfzHQR z)Qy6g@e-wFAfEYHich3OKWWh^nlkPvyDGHX~y)of;cZ5;-W=REaD^-9?Ju0ud z*#d<%F#YWqe>{}L7EJX#y?!|7wm(hB!H-FR@R7tZ6{o#^^wt*V&ioto-`ULD&%jfY zplh-qc@buPwh7%c;GWL>n2aKNB0PLIU*{>Iqf{-!{)sakYAMF?m$I*O!; zxUsi~T22&5;2|e?|Je6e_og|LceTuDiqw@!%GF3mWQ=Ar4*87vDUL zH6-2B9#J`x7{{SkhLtA^UUwr4PJ0xU9|sflqlXx&-W*>!7`CX3ijqhSg%WRf|mux<<(r{+90<0 zCAUf)KY9n?cY>5|u9>?woyW}S>W`}IvZW$;{CFEjaLEC6Fa@e()_f0}KY}~~xCHz3 zfR$fw8vZE!8)Ky-p1gc0NYCTrZRn#2tGgM-s;Se#_?tIT@UrU(0$SO!IX5AZYwjn95)Ub zBt=5<_|(mrTBh78yZs-93xia|pPXlqVe^5-vP^=FF*JFLaL!fqTQBt%s!wTzUB&mB z6^XcAS8H}AZN&`bP>dNvQ3D}I9C{73w;50Gib?3DLOGkV9F7z-M02M~_4{H7>7{ZC zl(V%+k4F$9Zl}YkGxkiH6(-}AnyNBsf>jZxM05Z9YsUiJ512NYU!3yw60I2}+F1Rr zib^m>sARBJUF7;;uY3&{2dvvcqfM}{f%XTw64p`dxyP#4=y@aNdMXjbW<(*P^}IOzKTHqlH{{)+JsjC?QWDEFTn>SsgCclHOj z?x)v09Rz!d_C`y|7j?4D>2>eZq<5p=Ushj+HeJ7ot6%oC2Op)&j)RV=XBHkcHs!Qt z~A2zlm;CP;PbeIcLRT7GT@N9uy+8w5bZ zBpT@=Zt+IIj$zU`%pR%7+UkD2S#Hg%U2R?I(zia`^e(Z=X=9M8H%cUM#B=GnzXc$K z-1*w^e}|rV@ckS*Hyy0B=X6KyJbnFdkbS7!clmXWi)Lh)w>C5eu$dgM-9T1q9p~EE zPg$r7e!GLCYE2NRQI{II#)Yfyw(qy*r%EfrmFP9ql8&P#l3ukP;T)$1|HB2)Dj^jR zv8?*=wWdbNhi4%~BTde~K^>feGZyWNl{dfDvQHXu9x$on-c_dW``rch7^#Mb1~b{u zqT4+e{phpV*%-L45H52Rx_&Kg>&8?xD_RO|-{juwr%_I>F#oU`xq*)<;(C&c{?6_7_;IhWrBmQm4e{awyYrR&w6dcFyDv)Ga8-M2%tkIx_G$I|dC^6v@R zg=yhcJ}QxfdnuTHci*lM@e&*<*f0~cyR?~E1B@W^QDexZ>KWB#o$bgINg^7-FDML( z>HSL$6XHt7zDN`Kgl`qOiZAAOn7344D@X_d1|E$)uEm;CtRu{JVxvo2$wByX$A4p* zoa=;^4el=b?kw*4N4Z)4fsq}rpl65WGF^(-QpTO~k&VA}3tz@v|8kBLv7W7D2F=2H zn4H$P$wR1wsv*~Tj?s*=V4dCt^qMpwCzZy!lhE6v!MH+=Ahwgp|A#4f{$&cCud}6d z6JKYM=X#2GB)s~+nEDE~DBG^r?^~rN1&N{cNV9~<21~A{MlQs$Io9WzT&pv ziA1glKWdkB7(D3x0yQlUP}1IOedfX;u|WY$mRV$To|=0 z;(3>vTxZMf8N;hUx;;|VEGs&S%}+x%YpH!c)f>TXFVCZE^3-)*Zdq2vNVRQ-k23~4 zhjwG)S*H{s;RL zzZ5pE^bK(`U)stKg`g8GEUeEbiNopqi)M_zcbAsM+C$)fU3Y(f*ZX0+WY#PN|NpP& zC;TaZJ(hK)!hyD_8*VU8M##or?LujMHYkq23CXm-`nO@pS*Ym||D1QOMuAk2BZ-yE zU`m759$i$xPHKW?zNXbf?EA#N^p5@ZPJyp!4$Lp-{U{$^h`=2wMw>qrs{B+TC8{3n zd{idS{Uk0^rHT;}+aNI>X5Om%&1Puc^N~!0)D|>A-U@_kUCYi zJeW~2GHO{-=yo?oES!I@E0iwclH5Wqsx_}ymONgh*+aNK`$NQ{ZFgdhxx0Q5wL4pT zAGXx~jq)uXG!;GJgdVz6st+{RN=;M~V8cXnoOV5vAcJhh>{wknXE)3&cXWrpT&H)l?FMsPj5#|}Oz)@JVG`01+#hzR?h?;FmbU<_SR zv>Ed8AeM};mb~5-#ONHn-=uD?`L8>#J#{9d1Y?OT#GFKKmuX-g%#u^e>7)XO>jPi zE(Ot$J^l|M{G)+&Q2IaUxi^u{UpA@?zHrCm)azDIm9EpEt6K|`oY$#?-TooQTwGb$ z)GR)=m>*lSdBT5)+rg}2JMjpI@O9?qaL(v`Cm}{50X%%^w80|L{wS8uPA`mXXn36R zNz>g*lz7OFZ{n4td<qCftpXIT3kNuvek;$q4%GF;B3fedNy zbnu`yttC>lOm%o-+cOrN;f7Ot7cC7x3)W9`kZOAEAAp z$5XW2)1VczP(`qpF})H8~+9)6Z?yR#j2e=R^w%u-h_+FSpvpDJ={vhC;Fh*q)^(?{4h2%Qk)#J;LckM8**iD z=3S@CtHhaBl*v*&ui^WS26b9b0*0o8k+7f&@1u6=WzS1}j4be^Z&uKUc{a+tpNG_TQ)iK0_(np5R;D6mX;wG@bo}!>`nPf7smI*pvnZVGfJZ~ zi+p(R(3%=-DztdUft#+<6)(<=vobBVkZ*eQd$h&Dw*n!JRkuIWO&K*wEN4a-^}M8W zWjQni*2N+p`&34-W&RbXD?X z=(X3fYeR9U8%8j|YhU}1HzOvvg?XRBL-U&Z=6GGQfvL1O8VB~)Jz58B_}xQ4Bjd>e zf5GSWswnn3P16!hA7dF}PKj~LkiKKf*tw8=Vmy38#6|%`4U$%i8EWkmy=9+YI5d@w zJ22(7Fr4$(V1RPPgY_j+_+|s*zusP}Zfh1{Vrw&woNX%+lkKPRAJ{(Be!)~{#`jsa zmmOb+WYGGe|7Y%w;Ds|+<{q1bF7G);?ByP!MwHNpVPrRSOU${ z{M{qo@=8r^W)*Dyl9uDfpfbbzhSP8A2&COMQKt)sj?V&TXO@a=`!6=22e zS_qgpu(~z9nO*^r=pUD0Kq@@ZtvbfQ%E)bz!*7ANN7d=^M!TZ?V}&KqX{ zF6Vx-)*FXd?smCLk+xrceWm)-m7L`LxV zh4H~ykA}114d05V;+2Ftr^@&5j%$N!NA`HlQQsM)^D*v@eGMCf=`mgxaJ?RN#w|(y z)`R}rx3tGjjj-d#)M8$VLC>izQp?qAaL0=@WNDb?V?#zl7QUvI8xX8X8|cSfOiP6l zO3zQ;-Cl1^l<6P2le|%VN5WZ4_liNr9JylW-OOGyv=Wq&Bfo8Q`HEW9F&1oqdI!I+ zXEXI@N;r?}J)u7S(5n6LK;wYq@$@ZZM!PHr)c1fx?~ zY=Fdq6zhonVn&-QB!HCn^o6fkHxi+2aD%*NG<0-rr&hdQ9GEhQ4JCyXlPavetX4AI zY?Hi$T^djaeWnD!4_puDY108Klrp1QetxXRddSddBQh5PU;IW>r zVvGZ8bbHCuh=|_2^K#XV_2SPe5CeEr<&_#wp&+dj@@jM?W)Ulmat&CA;vFwI z_cF#gFS(qjN^pH5K54wr00HTK{R1}gW3&$9Q>;gy*3XLvZCszs&CV02QH5-o~ zcetd&)OUYWWTa4N_AV0}_iNl?v~to@wtiVP{z6YE+K%TIe4EFwGa<#a>}Z4s4P6A* z>N%K$85)VR6Nk&l@KXtwC;mND95nc$w7KoQdW#>ZI$qsXaAM_p{rVq7S{G%-TQV0R zBhjL4V%H0)G%#i0H`mEGPF_mhX2yGeavkf`8oS^-598J<2a>@LB1q%YKvl^^Dqmh? z+;NwYXr*g~GNWakS*46ul}ucOeu+e8Oy}w<=z`6HPR4Td6aL*P#FBSd5fkyTCgM%j z9FVu$S<{jR)#X^wW?$|M{&FfVk6X;2u@u8=W#1W_aHRX@+jnNNa)!SB0;J-El@A9&}_TI{WAsZ?dn80+YbNwj&q;8MOTB zvD}_>vNGg*lqFfr(fyOZ#z_dr-lDC{CC$K5qN62el6rfiH#WqhuAhTUN+9*A$VU_J zAC;Ze9%M(t*)}m=FYstCJaZ7_zNva+{mSe%YtL+Z+%;F68e>0XhQ&s6mq z*LpG9-L%y%TE1%)Gd;}YrY!NWXxpocX&vrQ;Pt`pc^p1j zyjE*ZZww_z6s+NE)GTk<=o-hyORb#v!f~UA!S}}>`H^o=p|<1s`W;Eh3BjOe%0%L+ zrz9@GSq=!%_`&--BH8+(Ukd$_M~N7RJ@Du>NnOv)vydBqjK@6wDCdmUb2H})N~USQ ztH5}qKUNm|9BTt+n$!;kHY8LH2w2U)m{AaLdc2nX{hVfp&&65+ivy)seaO6Tf1 z6(=kpeK*xWbO^@fs75IP!vT+-qeBeEI?x(lw$tbO+m z2YMwiR#A4KLYSe%rk2tbU$pG29g0>5A>Vuq4vFawm6koe?u8h}RUnpMjTGdh&ovfn zNI*rYDI4Czi*G#PskzrywyP%5E>otQi&VK2BOk8+)*-rWM@B|Z*cj?s^U`m@AM`S* ztYRt}<=$!str(!Dnap|WeOaUwK3rjQ>Z8X0%dUFrmmIuc3%cttJ-2)i$v3k=oocCk z)3WFmYGK3gZE)-<89p-=-gBg2@ndL(O-i`19+tJ%uJWbrsObScS3ikYl|#eBXfe4gz!c znVWHO%*th@dinAl74vK=07c*R#e=!4$Up|~jD0TiWc_B>2U3dU%+Lz~GLrdeYB{n5 z2tf}nJgB?lM%G*-d`J3C6LuY!dEf8+h!m=;Ts-J}B!T^ouygXxKA6zTpdVzKQZ_k(<0_`GFAA$6VTadr%<(jg#Qa4#grD) z$S@aMj~E+RV2D1jF;A2!I&849O*zYCIv-qoMLb~|*N{H0h4a*FaMY)AsvFEWgrgmq zDiV6lgy(S>1x6KFv|KFX^}e~QY~)>0syrE%rInjx^ms*@H&L!{iMm*f zbBXH;Q;53=wj?+-W0MYB?SzV6pof}0&&RBmY0c!KnRp}7QIxWj6ZUT--Qz5R!e8Z; zbU$pr4f5H`GL2gS7NgS}I#mkCX>%CkoQ*~_fV}daIa_|`wp8BQ4^)|N@lMgJ`D}IK zZ&*RhW~7MvM~+QPHobt>_hwiCeVg${i?utHNVe976f@R^ib!pTeAv}NzOifg0WLe& zyo7rLS!#(6l@y44t`T@GwA2gm|9R;{``El`n98IsM#ia#mqfpJ%fA`k9cnSAgA}5F zTDWNDI6v;_ZL?j){XZoDw73$U;W*7a9Voi9Bb>QiaGk=qNpD=hA1N05ln^%LnZ z56-~^&~_E%#$U6s8_c=!pdKc*#2@RD*7@AHocj8UgKVVA%`BFC^Iq#aYTj9t`CoAR zN?G-SF-DF@XFjOsh7K!cqR4;XheOvM@fb@)n8kYmNT@Wr*ltqj(2|YRRS9+dhZiz7 zRi3IUp$Dn-{NeNd*HSLiF9;oJT&(`P+HMo=uc`g?mC&Vbvm&EOr59#lJC%@s8xJ}4 z-TrXTzpV+Q(*aF8#|J6Zg)$gKv4?JJ{d%3TU_#IrY(}}gm08)Zx*|CQuWL13v(}>( z2py|{s~nc!{xXCGJIM!_@|oj$OU=m~eBTI$U-`-Vn#>K(q_yJhkW!kF+D_WGzO-%I zTRfz6JWAu}CjH>u+QTtdH-EXoa_eyw&pF(`Q8!S`G#7Ft)`$br@x(dk9jhC+JdsW( zel1cqtfpok_R>F=WVx_BaH|B%l~Z@F1VEe!otszXxF3*UhA>Vuh!}G!izsSP!4)_7?Uujsv}S>&{Z^LSrp*%iFFCgOPVI&n-YKTFptu% zjw=Cs_4F>&`WO=rW#~01+-jhLR=X&|ND#5ykK&2<)PugU z)mN%Vg69OQ^Xg2yR;)`eO1I3=BITFOYGqO$y{uwn-x-=!bVr!pwwQ$@La0^PG0tsD z;~QdCczci9u|L0GdiBMS0#QLn@h?bt+%HSfYFQ)C)T-;02zRpeeDevx@!?M-Wfcx- ze!=sL-lc;l_T7Qo+N%2Yk1VSf^NrckURK0G;?j)^Rq2vjKem`mcYsNzi*47!;$%2$ z_gNst#K_sM44HuVVhIjvG1y1A_q+=j*cBey>DX{99&@!8gm@k@lS!C%g|Sd!JK zR3J^ztoqr8;{Ls5hBuS%@h+x*RATX0JUgY`ylM5*RnGz1l4>Y`Ko6a1v6Ofhujl{1$CW9KX(EUc(53VWopADSQzZ{DKA3?Ka98^WI}D*5kz_ zr`vOV0_)VS3VQj@uNb0s94Y_LAVC3;#Vl4kG5;+Dh@(&LQUoe&7U6~Mw+f%4(r>Ca zI5vk@EKlT1jd06yuU3nGlju#3&#GZzZ6F=G<#4Qye){|R5nT`XuY(YY*maRNYIga+z8aEFH#ebf3?sJT9|2EAwf~y%b8cl2G$KD#botnE2 zFov;C=6J$|yngW=qW$O^?T4ks&*~TQU2Jk_N!TE{6LvGdwzd59V=7WqzgXqvHE8MB z4a9$Mt5*gH;Wz#%Q#fr_Y`Ny+8*55<&;p-UHc%j+kn?qdxyv&JirSgq+My``IH_8% z{vs{oP3oYfRQj3fI8sm<(=Wle8Ds1EU6G`g5OY$sdsRI5E$sz#sez|Q!KH83XUs{M zM8AxaiTo0kTltK9<`BgXy<&hJW`)D_dJp^ca<+O*{PT`&3KGYYz-uSH@j`y$FW2Pf!bT%}DiENQ>jAHJKYYE@c1nge=)< zGBulXVKyVwy`Pd~Zuc2EPrx0@Sy%5xf2!ED!}(5r7)(A?6+q)Pt+th#xE!DhAMyS> zF@DyNv@gn(uRTc_YjHWl#hKe`94P4x0>QJk`ny%1oONFvd}w{F;)1A6+5C_^@GtT`E*e~$5W!npKj zNP=P5#O`O~@Tw2tUqN5v!+~Z*BS%Ej81-Xp6tWcdqsh(KVL9~j7Gbkf&_kpa$o9vr zM?e3z)Gq4H-&SG}oMirLy$ zMvNG{xRZm@mYp{|I~0u4)upRuWNe*`9sk2h*YDIXq-;Tk)|%*m-+8mPR-Z^y(Gg&@ zaO)O#IB!!|nx; zYn)N~MxE{Pn1xezsMkRs)^dh@*Ll0&DIe$i*0ZbyXzvhDf(^kpNtEGWRx!E$>0DPv znc?xna5snY?iY>P01Z_StIz_Mx*y7XS z@(v}21$;#G{2fTd@opZUTT6sY>b ziSBC`k9V_;^6nm9QMNzdNW$hfdWkYwdAxEyDM%32>~(n*wAkh1Gj;ROd+os1WW+iinXBCcX zyLVU3RB__SJ8(Bz^BgaArH&VCIaP*pA>IN(cP~>)_x|N;xo9b{>T*lVhTJ

    jY`OsKJzo!O$8n=dKkK+!%wh3M$69v;wd{h=b=h}*rwPU2 zdfb&q|6i(d69h1wdusKBbFru{>C+xZ(s@9;_nL`_Axs=aPfi5A$F<2PA2$1qXX1Ub zd)cQ-GNTEHWOzwCXx!oso+*XcVQ38<`l5Le4i%j9St(8Lkv|;HGu1;084DHoWhW&q z*lHytANP@X8w9h1FMO46a=N#JmF|6RpYg|$uxe)V?alNa-Q?7~uRj82Wn1&rPe|Cb z`UPHCqlwxgd_iNSMjfB6e^q83J<0!0fU1VvY~H%&?nQZ%u4&=%C*An}0-=y=#$<;b zEFy&ZvgM*QYb7XP8mfW)vZ|CYYZVh!+Y5F8C1Si1qR6*SFdNSMz1!s*ATBDS;Dd9gP9GZryUK{H%_9p|8tAC*!jH1nJo7nK}M)W9xko zfD=t;imsaW7_=^S;#JpCHWqCWa}8TW%kTs7JcjouVUP9N`O=rzTpG*-Y*8AYG5B?6 zq?oDbAVbFO&_E5+dS{zDY=*uMc+BZkAWe8Er&Zr6DV~H3ysO8(;Y%Ajwcj+p&TsaZ ztm65DURP{F(y%p_w9541(If;s@Toaj^bRgTA>yUKKoYxig%rjPy;7t%1LNs-Rs7a8eJ~5CJIs5U)=<$*{^B9rUQ2X?M z?0G+WR$|wkb@=d@eqh;=a(ND)4K#h9j;*iU9Pkp&*&(8|Z8YGQ0;M)f*PNU+LavEC zPj*zb;3ZsX@LohsVDppa@+p^OYjdB?KAShu`FBtEe}Qr0kz&@b>9SsS8%@+>yGiWzq&jtrCHO*k&Hc@*pQJxZ0-1{E7V)x_2#k)JY0)m z2{McUYz5_IYw}C3&SzxqrPfQVv406R23WVwyEi21QSJ<3J7yilz8*A)-*K(-8>@HU z7R)cLL9x>A;pLa*(RA`#r@E+Xi^Ug7yzg{Ov&C%D7AGb}@{gHtbx1FI=QcQ+G<1_sNm1Ogq~4 zd~VFlirQHO#Xb#P?8ai|m_W*J-}Y_rDH6~;6bo6?4Db5Q(Rt3we0xA{j}9CSH274i z*Bn3b_^!EsLG8wH%?jwx>zy|8Atl;^U1?m68oQ$fQO=D+lUDOh_5SCP?D}=86Qz;9 z!c}kL6x@1MNlk6*yXnK^fdkjY2d-eQR&B$>pT1>azVk*;sl^F+Mj zmZ6RYQ|!;wAgm{=IL0=|iilix$A;hZA=qWD@c5?LE#{kQTMsb6Y$ols6KSJ46@MXK z;5HU8Im{lyo4KdixT&@rQZJpVJ+uH$Zv zFo>)45r5>cR)vvh@Cc|Fc}~R}f4O={gk~{m52&I-`)VUB1NM117ZxX~~y<RaNTsm{K-NPJ}5kmWE zVI<4gmMGq$t=JqvdU74O03jiuEob$nGpNobBh~#*FU@sS<|;yfnPN9z5c7`M#_Pfz z+a&evbV?0AvzvXjMjEoX+Vp+|1k~rHS8?+{l^vw`jR|JS6#!X)2ur*!N@KZ`sNVM} zzn^s+3c%K~b%aYGS9hK5ow%TDF{82;O9}QZnQucW>={6y?Ec6W$@QCkZ-UH5&oA#F zvuB9nNoKdCPa;1qC21V~HXH@B92{Gk!9#ZDX714G&U2LPw_v6(Nq86=~rDE^u zU%Zy5a!Y>uAx$sz4P9&#gTq!8wqEO`*mv(fE_b0OXjMbKRE!tMuP+=$mbCDYAO|#e zbH<6-exq6JNLAM#mm^S+yp-vw&GQ_Ui=CM1^{WQ*Ed6|#U>ch~XPz?6Y~kGp6jl?x z7@7R%6(Z1#V|d@{vSCRyzh8>jVR^TowKf@P|E-q!o%f&curXsM{DEgpWe4&+O9+;> z2=wnLr#*zbW~*BX+F$eF)u3^sBueJFv$%~x&fUl3n-zkchryq&*li%)#iu=5ruP}$%ps+`29bIZ~686 z8YqOh<1;el@S=KbwwBW&3uB)CLtF7vSEzZ;f`$%yvJzKKqYsbj{*qPaX~oZL%oUn3 zkc~b`c*X;;YTkfe{V!=>6;ENXrnukC3o4OtaM;uURjXZ4WqahmAcTmLMVlQ!cWNTD zb1WZ1cYp;qnpFXN2i#)o3mm}Bp^JuA=K1=ONSDNMKdHI*;XAjNlNsGuTGflLYuhBu zOBS=Wc7JJ;a#oFma>HCU1sB_SR)YPdj^LBcC5C0s(K(}S7^c6S96dGDV%9jE3y!Wl zoy+P74)=6sMj1A_eaH1SG5*+gxOKKWXZEAyK(jB*AzT{RmAp8(^`14O5?lZQ` zIs%GoIuZ<~{>LW;Df{k_x>M05Q%00-ge0^iL&reasar8;daX~owAK%M^{_XNt;jB= zw!6N~bP1Xx6S0b%#u|h)z02YHKTyXHFoXO=ugcr5jLKt{z2WbZ3)WE7_Aw3d6;Gk| zdQx~V#0?#6E|u7d)w|poo4_cSoq45419!b!gf*REJ;HSdzr5H0Mry$)CVPf+seSb* zt}n<_#z_+RM=KmgIWzD7apH7Ol|%*KWINE+TPxR_4C8swqwFx1-vJC(qJ8{1V+92( z{ik}7&wZO%J^`F2YZm~aQvq@b;cTKLkW11l(}hck*NBlH`mK7SS9l;d7169{B1dUT zFgFv~^y%^qfw?B9*CeH6C>9C^TC|al@8AiuormnCyZ|xs+m-PfZ z1?J7DLqh;VQJns0baCtoU~|N@NK+0`*oE&I1%!p6q*&eAQ1#Ugnv+khZAe4<*K}1u z=WA%q?c*pAJ5m4I0NQ5KE)!xi(YtFT+Mssj%!eR$64XXpbLo=lo*d>jQjM3r7PuQF zZ%fhm@QB}a99^ys>1Uq)b`i{cEIx4efP@S=*{>C05X79=7&#+7i*Epdtj05c#|uHJ z1_pjUPYP+yN9(C$j{^+%{uWQ$ zLQT5Da^AAd{OotMGUB-(A;#_SA==T@#NW*D&huVS^d6$^dfe-lt{UYiH(wUANE` zaF$8Or`DA1V5yZ?Rjre0+}BhQ^_-1O%%{95)BHAyZ0mZwAbk4@D`4+QxoQDHW4M!u zk0B#3%?bA7hD8e!f7P0`eO=hAI}ELWYuZJU!Od~{&5KXphp0HlL8vV}&RFxZhWx7= zJ$4<~IPIMG>G`rfK_p_Gb!!5}x(-ShN1r0cPuW{HN@t#hF6N6XG%Kz5O!%_89~so| z&Idklg!$L4yf>Vj(;`b1zuT1DoQp_|ib601^{+gJw`?< zWMP~T#5#_;bkCmImm8zJ4KQK5>Jc=+(p^?7*pD*c{oSIVw?Z@3o>7t_{Nq6_-D!WY~J=9t(xqc}n$dx_vP-p6HHE(hv}3Z+eixY4D*u3qeRnM$|@Az77mr*&&I z3ZT^1zbmtl9?^Yn^eA@2s!o%xG{~%$`$E{42|=gz6FHz`+fjBt=0!$a13bX~Je|Sd zXs*idCy-#~ZozW(vuB|oL~>b}+fgzz(&gOPU^q^={u?gT8cY5lR;+FCvSE=Ax?jN~ zn}VU5%n5P$ZbjyK;_8e?F{mBmYSA{Z+pAQQr9$Coqzc5g8#>A+MYZ|-Prbjee7XJF z#9N;I;8_5U!zZj7O2FmXBEGB?b7fDH=7J_lzJ&_$-vuB97^^=BpbRBg@69Q4QUMfD z&takM-W}*SCFrqkzs&)%>R*noPo`NI@){gJT+CwFY(Hr28?Clfj4Ov5#?|y{)5n6V zHlb_IJ5h}9F;q-a%F3gUy%+=8=kWm)eCk$}$gZtr+x#MaC-|w1JsxX|B$%<)NU)T&DB-{zKkVb2WgQ*x@VR-YizE z*@#%|K93dB1+m8R=T&}Fl*CyUYJ@uiOeEffG6THlyl^|Jq)dzy70%r5R{#jXP1+5; zZ*Mo`9r`kkA12Q%xWfp~7yb_S!4@SfV-GUq_KT0%og&dmd;d(%58-*)@1Fc&6 z={vDctmR2$8$apstOGI&{{7EVB#%HSnPQ=ie-<6;&@*qRt}(Tfw?qs$h~S+0jjQvp zJ5f^zdVFe&(*oaa##_$FBgWxDiGEn}HMeQL&J?n(woWTKoPMjoAH$CaMMu)+NQIW(`+Tye zYM^YknXDMTy*_7gVrs1U^o?u`_r`IPOg>$tzJC~-U;BNqa9f0Qnj8_cU}yIT*t{Mf zs3LDXq`E^j0%b!NWNM_I?c^!MtD_^SA$)r`u!0cF^fm!kX4KwPi~sgyop%B(Fn=If z-ejn-bT6FDrKZS~ixIHzKiBf}vlpPx|8kH4$bz2gZi(LeN;m|`B-RXxyTi(>de8)E! zfu1IPQz3=5{JrD>9+_w8vNRb{H!^RwJJU4(iSx`mOYj}TPDxMAG@HuE#ieXGpJBa& zhlU@eK4CaXc8dJIskry_PiPW)Ee=Jd1@z9M9r0gX8ll9b>~M&7V4$oX%O~H@L9VtE#Ea&B(~i^emVA$BDM~~1lbQq`F_FO%!d|VNP**p0%QYha zDZK`{^w^`aUV$G?kxScZYlrbGJzHL}-%R%rg6o;{LCn{-kRQj35K}fWClOJ|0#$~} zn!epVQTcYu3unl=$@Umerm=mADfBq@X&wSZ#a*PSkz%85&fC81v}QjcKm1Ml_*8?9 z61g5rp4G^zK?d1Nkp{b@*X>5elo|asJWQqr^hoFQ%AcorP|t7p&=8oeS1{YltF8U+ z(SIS`uT@Zfm5umZZmLnVvsTPyY$Qpx@m}Ady2{iM#Yy%AP^LP8-uvWt9T()U%9*L} zlB>Om4`C$Z)_Yw%4fD6vrNv8K3awmJetTTo!ZsXmo!|LaCek3ltJ#Um&Sn~<$LJI6 zv7+v{`RBXyev^`BIOA(|l8tXIe_CEdzy4I@d8(J{nJiB3 zXhK@%0V#EiJK%T8kvh!j^FEC#LFOPnR|m!BHt9wevMTF~o@Ijv-MPxsD2QHVv7nOJ zF&Ebz5cQ$Bq2pVb2tqX-+*x*7NiMK~p~8?cvxt7FfjLpCr}NJHSAlHzi$JZ(Z{!@C zy*yv=Ww9Z>My>1E@9>wBEfC$S^%Aq3X7j*Cq=L;{ezq&53cyyEuG{y_w?^^+@$#Fa zDg8D({}2;2tmPyY>@D<{a$;1DPF(Jcl-%96Uuf}`Apj~FX9FJbn|In3Q=q1}#cafD ztqJ)4BmU|TG;9#4(v~L@3!Lbl6-R^g81es+2fV0%NnxgFX;))Uic!x~W+dy;i%a7) zdwhB@xggMmd|>luQfvN$ho#N)h|S^DzV{yhUOhCXA>p zKYU{jR1Z~kxLM6%*a^|b{;zyo+(}r>HA$WA1PC=iuH!c~mni5$aTw#TFU07#wT96} z+0C3jIVEqLd;?`PJ?sIzOd&lpj531rYJP($FEJM$Pofqw*KcbN%fD+W6~43LQR4w3 zm=eg;u^b2;1}4BW9!WrgD0>+JkyE^bHf&MCPu(L;-^|HqI^} zQK5I2&oHNJV+Zgqzc2SFa_@hcz7G(!9tE7?tAyXbkwU*RZNJD4ffYtOmK8M=Q zDBeDK@m;z%o<*8hsy}&=iSd1sbbP&y@^IpTogY^tx0%G+j+nmr@m$I}LnLt74N%{$ zW$mWv|1<{5%He!Y=ej)ZmZYP~-~p}2>Qu}?&aFxB^-dO;4A~t8;pN!%x4?=>wsx0< zT0rr#MQT(Z_^S=8<2oOL-_WRftn)`o=Z|cgQeE;o9KY4SGw zwgTO#=2BBkMMnb-o6OM^nb z6T8p2(6-Q}{Bw!DzkROoer<=0mxAR`T7vX@dI6vonREmT>U=7)sfI^d)3?;fKd0c! z%#yT=cX2;n&7Yy zf0NU{#a%#MT5@%^v-5fvAi03Wf*e;o3k5QsyV=o(5IsgwWvYyYCUb6N4Q&D7eGzim zmZBD(X21Cq+$jzeYceM+?lC%`eOSTzAH@x2nsYTU4n}QGJ6U%5>1`|w+s)Rxggp7n zLI7QC!m!Z2#ZWXO!i1m~Il~GmmwLeaFr15O=Pf)P^M5_2Hwiz5*-&YsaOKjAzQy4f z|HbuiIWobEQVu+76RV}O#kPmV#g|L8BA=dmUnSkj5?7nF6+7n1%P8^#=;{hsz|T*X z^X5B)hCJfqOYPcA)>knhvn!umNqXF`RzbAY*VUqU)`A9T z5Q?2zBa+L9Dgz<>THBA3jO)D1dUsF2Ax;SQfi@%WtNwkFsMIQb!#qOLbc@5ox?^|% z_A(PB4x_tG9*70!v%UHnU!lVo)!?%AnrUvAKC!;E#0&^E^g}d+RoyqKRLjU~LPvGF z>L5&n4=oHdTHP@lso64-Z(8i>e|g_#v_eIRckPzr!QYTyZuN9(Vd1sp?W}#NZdeV@ z+$kJ=}iMI4 zjWYR9^hFrPtQR%>d^cRv!>n1*WM*4vL(ivodbUF~4{0O7fbkS!eI7pUv5948mpa^T zBkKa{A*tPZ9yWx?_i85Y9g#p{_h?{ zx8~&Iz;itmHO2#=Nd<^qulbmvKx^5Bp!~(|y=`#G>4Dm9a+5FMk2|EfkD?EmDhur* zUtHZoeTzU{%95pOB_5lzV5z()a`ix?pXNuj*W>HkE5#)k? z+Y@DM_>J%b<>QS3?Sjv}u`HTdrr0Ywdw{A!qg!%iC6UuqDE3gxfg6u20c@Q8Yq>67 z-qsvaZXhV+vy1Ab2Yyd;6fyXdG1boryK0L8uI)|eTSz_tp8HmZG8QV6SIp)huW6mQ z^re#Ko(B~y=7Vl+MQiRUsoDl+IhXCc$8CJHsB$7#@~bb3nAzIOWCkdBCWt9-6O4Tb zT2J>{Yw9D8$p$sT$vIEfJF%wbd1T$XmpX^4Wlkx&IgPIYBg=~{1}fH-|E@0iS@E=~ z+E3phoe*#x>H+%_@|?c1F`sh33h0X-OcUDF6+_a-1EgVPnNF6Up(2}_UxV|GHHIGz zrxY}Ow0C8d@Vx*J*ub*y;vmlXX-c&>fg?jL9-bdYTg0Ya8tXosElc#Zb&_)9@`^Fc z*PM#%rs?0)t=UPId{uym`@CS(*cS^U>h6QM7So>}3nP1-MrCGSJ7Z8VE9BFe{`M5{ zr_gONFZZ1tKg#OSGUa|yS?RE5684VDXkGPgiPNYrd6WR3);bSPKuYQP^S&1VxN1ok z8}350u4_&><7{QUd|bQRtSFg(*Iy9MqoqhldJBpZ@rm)9J*=)P@;Rps_xUq;-XX76 zt{562Vt)`!3FP2ZG+3r2{sXgNSQT4WkwT=Pjtf$!)>GmOu^Q?|(Zu^L=Wn2z3P$W4 z<`L)26U7Sx6S1L#!%^+pnB|2A)9fZh;@im>!Pw1%^q{XC%uxl|NLiRNcp=v_Yw zugF3dte7cZJrbp5OK@#E*zubU%DBrkS~+vn?velXQDHFtwvMt~WZ=DW@y&mB0hqNB znY7Vj^RH*&MR@hcLoc0}auSCb5JP7RT!WM1=NX4A4A`;`v#(8;K!#AyC(e7A?^T~% ziBH01=62m!QApJZ_f?f3PlHJBUQSiWi1^Sh4II!(zrZ6#VP>f5AE$=!_sHF2fZ^ZP z`NuW-3EMzBUgdg~tM_;npzLD$w>5{-E2H0oQz6thj)8>v~e8hq*3H9KR@!Jes64uwg z`VL;au2EA3b#quX4&U2<05YhY$T~m$j>pgQR0}CSC0s>N@J3Hse$SJQqUkZitxg*P9=vfh+Idijl=G@|mPFHUp4~Z85iZA(mFD^hX{y$7TW`Vn4NC2cseYy9cSfk)YMsyGG zRYVb#{Q0bq;t!L#H`gA2zO^}@4;tz-9#+JqsEJvPTSAJwgU`nD6v$jc*#EO{=Sv0= zu%M;wVZfqA@TXea>I~%GWpY(B}>l zgypaI=Ni!kpZ@BI5B+&5Zx4L$duR=I3Dp_Tu^%>ey2{R$bT-di>;o3EWcNG}w(ZQ$qfcqEV`^;arR0=RyB0mV-0QhAjr*BrM8`DZD|f z;y&{P$<5ojLe5j$P?b3xsEU*qa(iz=PzNK(^GWD!qwqMhIYe!J&<~Sma~`1+xQ+4q zZvIC9Dq#EfnpPdv2Nulr3!14Rb6q$yK!2{2yJ7~Hht2cc%IaPjv_-08T6}QccX1+9v)|atynC9AePkdV?7G zpt_ImlGdfd0*_y;0HKb77IBDWt5o~`s|}~U+IwsV)SbAWvyEK^n$59uY+ozzpuTuE zmn15$OjRL5t`qoiM-eVqq;iJbJq>!Jy3my19j z{6@@d8~%cnJ)W%k*H{-TX_HHv(Tx>T`kY1sYiSUiy6Rr3%gk-5&U`C}7#2M!!#rlf&aN)_2xd?|#l!2VDtOpzFaGA&`@&B>+R$*~%+qUpZ0to~U z7Tmpn;4Xmx0a6fL3JLD+9tf@p?hxFAy99T4r~-n!yZ)1X_F8*?=d7EvU;d|id72bd z)tF=S*+(C}x8B;%pv7qpDWi0E5s=YQ3gaTTe_pBvqNRC^YTo{VI!3R9)YEBv3Ht zRE1*E3NCWU^u)XvolC)8qf)b9xxj^RmzVZfQWyojuBA^Xu51E2MZqfbB%D^+RQ<92 z*R85J`8-!8wlO3#0?P zV`b|b&!LM6X}kPki{mpOx)3vZiaTVT`gkwO7j0+aVZ>rUW6W66*Bc=FN64App+dD8 zA!NSTD}xfxI@4!;u@CD&B3E*a@*!~3?~NXHJrap2P%>Wb2r7pFfmW>#_ViLH0HNQ( zF@loVg>nLcW*l&EvRaf$0O7cmDj77(9`g*MSVQ<6chf`34ilG3NVxx^yO<=$FY2lc;Gl;)UBdddj#83esc}m#?f_cp4&j=NqxuX(%M|FkfPU5m|D7uh3`X9 z)6TFvk9PCT2}Yd?B^^o^M?%YJDIY;BK0r<*8%h6t2KW-*mM^N?J#`A?gJ(pc54@{u4c$!OYek515r>-ZW z#9ZnsFLups%{rIzm~H3%eA8wL!0;Sj@MPGLz4#RYGb(S8w4}&mSFDv{+-XxPsN2`} z(#+KIxakL)6q+;CpKuI_@$)J_?!a;}g*Dn%r!c9!Wm^C#$E58>>U*^JR#4j!){~KF zd(ow94%A$-N=vSdtJZGtp!;^gMC1GA(y+q9n|Ma*?CxPF#>PVjdzHxTdf*6bBSaH; zGe!ebTAYk!{61429pwUYCI?*>`X$vrtR)SPhOV{nxOb^lnyL#lRG#AVucecry8&A% z?E*ll(7{w5MI$XP`U34^9MY6BE|fpNCw6MZ4LdtpQjZ6F!%6k?CF&c6Rff?fRj%WtaLb#3x|xrX`0$1XcE z)+;9ge*KHoO@xe@+}g6cw#R%&M41q=6Bk)QTvt9*p-Olz%Zs(bhdcmIT6wVP;DFa} z5oM~DZvlhKY&^EF;IkUI^SKhHAlst}dGt}{E+XeF#|8i(0=?R^&4u=IkP!~h1X14^ zg5GM`S@P0umo3~IM=_DxB%|{6SU(U9z*@Z0@F%Q<15k;^k{o7?%FK_JJH>$^?*Sdl z(R^_ycKks5@fU;~{FlJyXA9z;DpVP6t;#C+VWnoCB;?g>?~=FC0u)Yu@O}FEN1~ub z{Q`WQcAc$3;wg->js$SY3@&UyBi!)O4R?5&lzDHj&9Nd7AFeS(=NieT@u%QTrRR3?=5l^Xp>JvA83kTKYvE;cH9Prz+Vy2kwR zC#~JhxdpzEWir-q=!Y_eN>w>iko%n#Q0c{aQ7@_Us|cVvb7iTw+X%NO>J?lXY=b<< zF#9U@rcf|n9Cde57Dz(a*EUZ!X*D>8;V`PchtyaqDTOgY8YitrKHF|M-o7=dwoc;p zz|WS9>dFfs8b-()es7Fu3F4-kmVtgjQDA_`oV!f%xzTxuNUzwk}WkXmf;t+@Lvi8yoq%ul?=grqR);zx{AYRR*1-8CS zI!F>Lqsr{ZvpA7?e-N;PlULP)UaLCu38@|%GCY3i(t>}b5$;#M-gcd5m=Mau_zdU) zeftRe?IalHo>;r)$J1IXv==Gr-(C&>I$YS%HbigZvHzu9f61=?OuU^~2!Y}Ae8Ed1 zZH2`d6~0|9^ODjwRch+>GsjDQS!+9uB0~;a?mFX@6Og!d@|)_6Yv~TvG0a5?K^@7- zd>yS9{n$;RllQU3^Twl*2FHrIsC%?-)kVskJ_8EmSP-YsEv=6H+wDEvyoao3tcx+E zJviCsYNn1#T``Kt{C2k#f)|P(+PrEuX)Rz*oo_dn?95X}8x2vn>Z2mgI&g>>I!}_B zsbS1WPG4Pham)Fco`Sk!8k+MsFFjkd9s2S$?+K@W0GvAG`qubA>J9Q3o+QktmEFRD z)tx_RnYLpcg->XNpeDKthmIm0L#Nax16R!9xwb5?#O<#|)ay1aRAB^OsF3MiF#y+Q z*0`hk*@#Rl+cMLMU`n$Dw}lFqKXZ{;*RcRw3Nj9%_-LOI?bj^<;0)$X_{3GwyCJEDz50nb%&nO4jnY z?&qcQtNA=vWtzymHCiUfsiCw4Pm~}iBfKRPOas;RH11%mq#tHd%w^`&K?rok3!k2O z7YN)QVcN#YoJK%|!^P0v z&PI;7QqdypHk^R_D&1VS*%~uJ;LG6CnF8?8Bcait`WXS^tn<_sUmxs7u?jcR=KFU2 zoF}X?1}ix#$oXTtKeD~jfQ2X0FCM)+z{CZi2J>ESp&+D`jX8OpG9$U$( z;HTNivU1`Mt28n9x;eJVAIl~L7+r{IaNyO_b)*?90G2=3$r8;Z^`OqkpeV{}rIC9^ zt)g0;{BDEcG@&0UD0iA#JwIDG)S_?KHnc;LHdzLrqv3-NBvPPFMm1{{N*gXag8)wN zK88VsmXuUDICbEwrbjHjK}dVAMG`z$s_1JrN94g|9);M+G(1T6k*c9e)c)8kn^C?h zOZUN$R+F1tp>i=)sh#I9M=C_|=ty4xjEty~5sQWfzq+UZo-(Zy*o>adHc(3FC?Suc z2IFVMWMBBXNmh%8;4|V=VKP(}D~Hx+^iHoin-kj6CFUK_3wYgYXssM&O0+deeZWJ| zM5EjC0X)R|Q$XhPts;>yP8w|;kc(s(zFSx+<55rpmcDkxsF&y+5&;g?a* z(TFo^GN!CQ4fu7tVH@3BXr2gZ_`0n;!1F^gq)(Q#Qhl`XMzU>_ zxZ?a5*+p2(!CTA?m%*5Jrh38 z8sT1YSwXQ{*=## z?D<*z$@%l9{Na|x673e5z9ugpI7C{tV|}t<%pI^0e{p{a##IgF!@}xo%kSTSvNBom z@I{-h!S+OciYFfg(K0IcLu^g|*<}I%iWy9!l_T$^pvCzIP#!}@L^i-n03?LwN__qo zBkOI_BMWUR2^<$6CBWGxFx{N{j@u3O93Tpd{|ubB%+;!0=MQupY6i>21*#a?3hR@x zlnhGYy`8*2mlM8Eq(lsR&3UO=YXGG{@TGr(LoLMxF;P_kP<+Y98z0u~QDBqCh3Y(6 zYuO59A)z&3teRReeeciGPv@%-vfx8-`cH^_my*Z3;f&&lx`W=39d>SLzg~cdxOxL@ zr3wHFMnoNUumhx_L~QLqs&ULJ3%}~vO(z1Mhm5@XR~MBPE&x>_=9iU)s{wq}XemZ! z=#)smMe=C6iNqNle^IYJ16LEI`E?8UfaLrwDL>+6!BUq^Nte4fj?9n4B_YBz4iDgLnBE3Lg@bo5&c~1Rs^b%QheZR> zB+cXm&~EXKziQ;RVb7~$gZ9(Z zQEr4wwkO)yP)|XdFNtTcb>G;P@lb3QKljeFXoVNwo;pF-F{qjvZ?&107bmZxUcqflh=cw!BF&UZNTTxf8YxkR@&@tg{xWjlQpM_hZ9Pw zRT!RCB1S*^ixQ6Qsa5e(*Ramu+!-Kv;_9vtYiT~KtcGBL$EJ^Pq61JG4`8eS%;g1e z?n>7Gpd7qCAr=e4m+LYO!KSdyTj0X~^TV9r0I2SVKuhMWFTN~vBEA<;?9M;8oI{4E zxJ(-9G_t85q1-lfF2So zU%Y&y^HEziS}iTY=g&rP_jecC+jGS<0NZT{bvVh28ddbaa}obfj`BkS;G1vP<#-(J zFMH(d*LQhLXEX5DhEn>ED8m6K>mK|Qh^S2ZCbpvKfaiCiszUY*CFRMVCi6c(5P0P< z6_~pNJb!7V!s((+j-4rm)~8qbI_=lL#$IS(!3qCldurF5CUJ8?k}iear?4i4&0pv% z|GPW?npDmLTV1M)wY+M2;J)Eqh^*HRZsk{jrLFL zum+lklOX)fUXglrKsR3G`To2tl3zAKL)>ad8zg*p7Lf22^u6p7{whq0j9A*^xHV?L zYqQKXhf7;ow$j7fR=#)Q15XR!MFL?s{aXlAF)MBAWY{S|!U4>EOj=9ale_~b#e*h2K!B5dH#@_`2e{S%;M8JRRbmK67`SX?k>Fxh| zrSTc?pfx>1!>jr2j{nb5qB}kYBSer&@kOCI1hmMR?{>P{YxD z^go(IKH)!n=J^i4+JyYg7ypltMMnZ4ftV>1>;F&w`TwfPK7N?xL)xT`WJK0h#hLY6 z+W)T~eA3zmQG`|)@YA+T*2?kz^AbQ4PzVuqa%E@hrA%18I~$T#iMyB<7)-ssS@9e`3UNB;If6YBif&!_JAgh0%!lvw-~4_^@`1PXxL+Kmv`x z`IIFk8PKiBisn(E?u+9>qmoIcomp@D`LD11+tHwFz_mp$IZmG7GeXLOZ*OmXLSA&i z10N{%)DHZuuShg2)l)C)3|=YXpeCc&!%qKAra419)f0^wEr9zn80-p?G6* zjm|ccw)%u$KBp}*)Vu7U0>HS`a}r*1T+8}#em?;8Qh(uibSSl~L$;aL!m+EWvDs`9#yd{4{gN-0 zI!6|>eN_dA%9*YX1*&B}Uy4xst+Aehn)hbPqJ~^IeQR7DOcl;dl?V-7RA2lr4`@8q z(xFe%RC%#v_%xUv^Fcy)nsCRx_k3BlxkF z-<@gRaQya@KUcvK0t|Zb77CiM)hc20it|`rM?Nuoy&7-P0Mzfkh?uaTt?M8gwi5*i4FFc^!;#)%$-o{%K_brZ@u>exY*0k8RO&Oo znqOi+*iSHJF$L>>Gc8qSTPWAWs|4`-3>1?fq2fIaj)64sR^_`^(UY;!8UFr2^T!hc zMDC)csVX&q=n6oQ$!U>rK*6@%|}nV8%Tb6>>6(mo`x8fF3D44!M-vgVKE)>p^a z>ZR6X27{3a*JoQqQiVS&|Ced`l<>LzrDgHFV|rSPCk9kfz1dr*O4){C3#&b-D}sbT znfcics^QaMNN>E147=X-#HUo0_Wxy%5?(@h9C$g{%|-0S(Ht2X^F6K|Gf%ZCRb!NMc$Y%rsXZROG{GWm6f3p=NU<*_G{H0)t3djdIU-`$4lGXaf z@dfStAO8OzZ}&cYu=q*-o46GC6A0J?4WFPE_{0J2 zo=a;4TH*mqI9mIZCC`3m1#QfaXMu|a-rJbB)^?YWRdgiZrFHb0Cn3KZcbp-@mR`OHkb(4s0yiU3K3e*J~;mI~wt$RDuKTh`+ zy|%iC({wZWgE7hh#FCsZ0!C znQHlg1Sq`GW#ypSow#40Cfr{$EO}w>Iq2LT9IG51>;UBc7C*>XQ2*Y~!4UupNj*Z$ z>+YNL!6EzZ1}!mf5}U&k`V|V(5Y=>U@LYLr(4Q)ynQIqe$!@Vtc?SK)7EWFpgZ^~e zPFuSo&pDIXs6<0#W_xqK`?N2a4igy5 z=L~i9Ox20`S{DWv7ni7mlZ^}u#lC2kXE6*AKzL^uhnw5b)#LK=Tm9Llfg%By3}K>S zCh39AK1rg0Q!`<|(rFk)m+&!-_05nbKAX&i+rh+lBEX-Hw8%%fUGL)64JT*Pu?!tI z81|6rm3dzEP1@gGqpYANMgn!ckKVUe>{K}wpiduCm!%FCnxaq=*-bx9Zw#jnr*1JI zq>kxOh>y2RM9?;0mKq*+*tF6Iz8J<<<=O^7;}YHBY3bue{Jz8wA+Knp-tWy5)|`R4kvFp6W|mzG~cd2@5CW5wEelX)$sc zaz0v?2X@0e)lqWCCLy~G=BxlTl3pi>c3diTocqz3!Ca|LMbU~AY0b%*hm7TZMd;i~ z3k70FHwsV(%P7y54)K!K#jkq%hU@$^t} zG>ho-lQ5sU=RS~;Cod>#O^lXMj(AQs6aew&%1*deFj|17>@H*N(LpkojMLt%nPbY` z&1nuujdf>ovECzq`a?1~h|FsyZ?t&-tkQMQwW>)c zCmr2|&%s<4W03#CfA1OZVzmd2#X|j{ZUuY3!syr5XM^`sAV*HQS+6DZD~t~9(Tve# zHMUT7XBX{UNrjwV+k0Rw1$`rFWW_H?_`e=FWTHNYN73lgEn@K*rLbrB7srR<7}NS#9aV5}6WIH>3*42I9Yc z&EpD!H9QE%o``$e=zRZmvCUDe-lU9uC?4@zoKBvSYuhZs2dEmqf}FyOKPI$;Dmi~S zO#D!Jan#Gswb~gHH{tY?R82lt8C;;2nV6$2REQ0|#C!jhwAu5S4Gy^WhXE3Cdlo<+ zj}XmNY^P~9L#>_4A59H5ZP#tGtM1tnG7i*AXoBZzYVDN#m@3d-=5vzlwE|0a!wgw5 z8PEEzBl`ULhCLZCXM-ORzrAmz3|sO{8#yL-vSPc`E<2cK_`DBpXtXBY39CI zju6-IzZL!b$CJ2s;bGwP_6iAWw4whof7u&F{XR|-*ePR~0#J#0-x2XTPMYCrn

    S zZHWOo5Yr53L6``ZZ*z+fED+zu3ZA`2b7@*|Qsk>(i|wtqk&7cqIgUL0e=X$M>--Q7=S721t=xwU@x$OzyhC z<)8Ypj>ej@yewu00V-agl7dIWOzKjuFHgE+6z9h+?L*MOYJfYRj9h#_!(n0-=Xt7p zJ8x`)JUiD6Xn}3^hK<5OclWsiH`l1Wp zcfaGOu{b`jFRH1_n9w{q&alNU7?IY2rBj9{twS@DYzv%j4}X2JUbFWl4!V59-0>XO zt2l++1z;zw4pm}VQl(sqXK;E~L>m4q=51~1>I~h{N;d@ro-4e2m9Dvd{YPhJptC|_ z_$#Vl>5KQSA*kM%5+T0~C9U-cLDiFm3Xn)T?e9LN(2+Wlm8TFuz9itn*NtaCO4%Ko zM7G0~B~JDBmm|<@6D9@F_C#KBSuKn>SXoI?zH5ulmmdX4ddd1@gtXs%D3{RHyNj7g zANb0W8R&s2n_up{dMPNl%;Q1Lx#H5?AsP7*z;ZI4BkoH9w$tb`kkpgxda?VK$4 zw$@$@_!>aQuP@$#P$5jg^eDWaUZYW+LcSc`{%vi5`)QAa>ZdCNhKYxF$>s0Hu4&U% zg8==?Om9*9i*LobGr{!yl=l~&M`LRf!nK_GqiG5)Prf|Ef<|9phCq4sut7+^WR$q8!Ccg=-MZWbannSGR1Ez{ z2@zz{Zpa-7L&Xt7e1f8KHe<|Wd7ZX}F=;|M%gjT?Gz^^f2Mhm!;X zyo&H}?o@BtK4^&~o6LPsHFnWrD~jA0OytbDS~j!6`6WW{$I-f%a=G37*&4n(|6Oln z<)=|y>=+K8`Csh;#>!uSs>vKv4djdQjkREm_2OKEky9{T z7w3ltF;KGufxWV%zk|D$mix@l11>k3`$4Cz1qIZ8pHH|)Of}IW3f689_s`CDVJhm| z_6Kunf-U1YI|~@$l(l6`E$}-ySuP#TBFJ=w(sB$Dzg8k8m z%x%q?R%mDPWx9ARnC2_-sJS?TX}CGpf9W4*!Slff(03vgsVsFCJnVxy`( zn%=v5i8ET!qi}5&an?C~P^b(-;WR_v(?~`$^GWKSt(eG27z)dhPHUd{u0V4Z`ScZ3 zJc95o(AM>FJ_%?GSC57o4NlpCU3b>O1zJ_X<_md}m~$;wY2Qe5LaTJoOx5e1S%`R@ zKhm-CGO5=`2V*l>D(-W_Vho3qO%zKQXG%@j)_M{YAXwxsfEx@JlW)Df%9Crqw%uZ%#_6 z%N`n51K~k=Q-w88tVAtwg;TlGBdgOJVCR!%TG?XL-tzw{TZ93PuBu4lX^v$kPaVx? zyMNlZintQG9A~juC*5VV+zc|rVUSlf&+5*Ah!CFDdupO4yi-*VCt#D8rJS^Mwreq0 zs|db?55xKF`gP zjOvNk!KRPS%rg{p9#O|<32@r&VwN#K8puf(@q786K~OrXA=p6+XJ?ID0RV2NGpGnW zdQLIv*!&~(*)=oor&oc#F$Zco34<+UGK50kyc+zs5`HkFyk321(6eF8EPWpFnuXlP zT--Cf$i`!)&J67ubbn_k{gbESR7m4ZG8-su9%5anp8bj=Plapd8|{ID<1Ya-|3c06 z@t2l*oqUFeUw<9rEw%Dhnu&^a-t;JrHG7#V{*dA*REZkAyu0t&U}4m(7QyziD9hvI z!0r3nY)IR4z-ulGo?#Iz?z7$LdD~-Zvo!>9e|RhDag9nky@&(X$1UkcP!FU%$G6yw zvisSylOxQ}$~06b>4Lb-gRvM4#>m59rm$uY36laRb}Z;ZqlbnLhNx@dnOf_r7N zML&LXabR*XW#Q_RDo~=CK$EVg3b2xn6=^0-oobkG1IU8KO1DMNts%KOacQ5V=_<31 zBhBcJSW_O`wP;IXs}LK_T(Cm%g8$2%D#JktEm)GFmd;Ng*-d_QxpVVNtyh0s5X!b* zcQn0=zFD;;tU-ZO$7GFRszF$_ShLak?bI5k$aujb)6ZxbNR4^Uy~jj;>ij zGn2rXuWYe&uT7?e)VFu@vOB@yjEzu@yJGeE${k9^keQhIpZB~&C%B+ka;yeCGgvtf z*v28My$ZeUqZ%3dEZ;1Bt;vQFS0#YhiW37)E`(;GD@1hrG*v8z&IkCn~?saWce(q z+-Wa=Ywhl&d@1z?M*$9t1u34GZfV?MIaHm!E|Yxg!pZ6;FE=%6&If$;a8<|5zoCdi`)A}Eqbpj2-W($=;^m%2Usy$c4F`}5^Rr))o;*}Uw zB6Z1dokK1)qy}mN$cG^CzieeC%}t_N6sXq}iH+(S#*u5bSgmRWoBUhtb(veiJ4`Za z^pIApS2)Fl3=u0JTVxg)|DKbdZjXnHT_Q}zcKI>{bZoP{ zsEDT1>L?w!rq?YSZO|To9GNjOf|0rE5@xEDUve2X$LCkM)P>_|zLg6m^20s?vIz1R z7%##Z?P4lT&(!C<4!`oJys@kdt;wD^`gQ=J(Q)ViVIwhSYnfrJF$qRm+uF((_}tZc z1eEs8mn#jmAI)=z1BMI8{A~63WJM_;UwPI!Zv}7Hhj(U~C{VxO5!_P+xm)wI-CuZj z=8*__zLyJJS)uEVrdn(v_s438)Yqw#_dA}bm3uY|#bAV1Du)9}C;3!pU9@zR#QjHu z1s^fiMU7en##|RG;20L@AL0y2j$TaQN9;(04~ZS=Rp9MEb*X?Efck}z^&D{5DE`?0 z6lQI9_VWpQrMNW&P@f_abo~&nzp4BUhJInYl^d*JuGvRI52vDglstXAvVnHR(oxxq zxx4-p*ilTThYyZTqG6zP&(O{}H;PDD!W|IYP2>^a4JHM`&6kaFHeGqQp-b}fk?`1)nf>qhKHBP-8 zb*^`{Pk@&1c-Nr>r-KEBgGJlMi8E;@pU_n8eLUq6{+5S2HMW+Z<*1v2qgPR+_^6pQCby%T4@{iUY=BPG%UcvMVQ$ z#!0+BC7|t=^X0?Ye1S4qmskYqvY>qD;FkLp2l_$nIbG768kZ5Z%e#UoYrqwZ%;`5J}FjhvzV-O9R1xXdx&Sp#aM3UBaBwtXRm zTF`_#l4f)eofyhK^o5=Ri?9{tOf(Lnu#S?B3I9jTKyxDy{4t=1j26# z@HllVw_TkMKYK=#iMqNWGj@Mm0QY?crB;Yh(nwEd1Ik7C;d+YquO4nd(9P>>LEM8} zkL|=SJFt=>Jc)nL$NhEPP5Nk{0g>7LTb=5B_SQeF?^MZ0obn6`t1E3M@v9!5lU18& z=FwqycT#(7v0_InEWZ|XbKHW%Zs!mM;JNH{=N1GS{H(JuBQ;>qJSinFByNLrKs$2OUPrUr zq`L$b{nk9u))ZC_pCafWwSGau`+?4nPfS6wY;2_-GglUAl=OSPVXM3$b88sxG*IMn z2s5wyS%zB`#0YU-NsIa})_q36Wpa$Aq68f|*CPwmE4$+NG{>TmN?@xfB^;pT1UfDk zztem+W?WEpE>Q6_vMMnStyc55GC`=Yg1%z2VgV=v7tUP!WPPKH>8Rt2E9~ zlucbNUc-WcQ?xlxF4$bGYu`<6f*mWra?dBy=)(7wcxht3j&E%sfnub+?DYn;BBBvh zRE{P6ZB>R|1t5s&&I9YlRA>1)V%rDIn3!`F79ZGVIFUgDb$fDLn_s)ZGc)^;QtwYL z04%QfNgz=rzEAy3H?KI2-6av9Yb5$G*TO8KkpiH%@c@KF03oQF_(sKWnjR9`(${@} zGEGcw(>NMgy=*eOSeM>v8A>t19!r`sP%X|kH{f^PL;&*p`Gl#O2IZ3#I%D@;GZyxP z_}35T#{u~K=O?(#`qK$*<8J}l3*>-Sp1<{i+~ki&HXsg89QQ{_nwaM`%OP;s-fUs{ zp{$xfr}CYZ2%}6q+WxH1r7w{x#I}I=3TZQ|SD|ntfz2qxOodtM!topVLvd`y$MgLv z%XV?b+mv6-d4){)p@8&7-+w zGsmr-7KZ8$b7&r!!$E$9a?N9`(e#|M_DER5S9&PBje~|pp+w#Q{{Al**1uo)K0=y1 zirMWKdk8AoI#rIn!GxH5W7++tPK&t_w4S%l+jWsT{W-Lww|b~${Su2bXlu`HcWdus zm1o7Esr}^5N%-_crs&f zbe6d}!-k7ph^l2K;QEpBa&dQ}~!WDeqx6%ivR<3aDZsci{`<^zX`> z^mNePDiav%XX4mGTxPYLdg_!n${pp>yAM{Mvs2RqJ#v`HQ)y`SDmXls_3O!&InsB^~|6w%+JIM9hTPAXw@{41a(x zV;_W=oKupLR@3ruFRd)#wl4kb`OfPy2Lec4g4C^5E~i-K*jgc{c&74)sc?gcM)F!b zbrs8n^04Z?8M@pzl>=)cKn4i_@36ZR6cT1iuK0J5)RF!z9Mo6)(JGoW$vJuF9X5*= z)}VEEfM|X0q@4mDPJdT;k}yE57d0s(Bhyhf%&k`20V?Mdv*iFEU7Sh%_)95Yb z_~0Kp8?7)lltgPH^CGHbl+$8P1O@*J!fXs*Q$aqZJgS==O-5T^8lA*u z=kHoF*odL5QKr`!DF&!E%U2b|R86)<0vRC!QEsQ9FNs_xG z`Oz{834K0*g}>#kD4r-|b?NHThQHdkc@CmCI>2_tl!QPo&E8mQ0*V8uFT zvS(U{#eWQ>AdA_htF3#i%#-5~(J1UMTO!naTk*SLmD#n7g1u6YnyC+FWZ|x|oYfen z+B4UIUn48}&RsT%9HOjVqpPk%S*sClQ`8ehE<*(|1*yO3rWK6UNKO!HWvs2M4{{@4 z#$ipmvNKHdcs>XkHb2T^S;_7s<0_@@N}TluDbnIZ`QxbI)W;W(l{g*w)KM>9}gf;95da zKbaG%wt^cdtD(9`Ofpf_p)oektIm?An}wq5XZI}&jB}&$h_5K%?q7Q=Eb!N5hiDfY z6zbfhCnsS7&!d6%(YG$3q_}p-n8cOIntfN?P>cbsoc`f(g&%#E!Tfjo;OCWBpO>ij z2Z1UYtz@~PtCPtBG-0B|f}n|YueaWTAWxFbE5x5%?B#fnUVwhoxk%&6pbQnGc70$X zr$te6frO~jSB`hL5sXRpu}mCh)0rvcj=_yWlV#sK-bSv^PpMOOR@kxpprl41;uWT%T3Xe1vtW;>Qki2xh)^F5D#aSL>zkdrK zd2!!VfYcij!ampW5}9$cc3i1{0KN{VFAq{U)PDbTNzyeY<1M&u-Be ziuIXRoW`sxjEqBhyW8`x)^}`^?Br_-${;|2~60s~v)se+y z3)V?;Kafx(j5bOa&l1-|)FCzE2%J@9#V@I^(=<_Ii+^5_9K3E5pmCbSguf z%(jzo;T17I48_60m(ndWznKENDx)n-|4=w5ypFX~2N@8^OzM-jgNfwX>kz1Qi zHS(Yk35u*&dEII?XJz;y<%O{4UZav!xTa!FqvvMyJe*_nYkgiDTe}f zIF>4QFXL*GhfJ2&5-=w?E$7Hr6l`x4=@k0zr9#2s->Q|Y`I%MCIzLzzf~At*I`Z%V zj2KZFDb*gTeHCX56^qIfjg~mAmnj{VSPhOx5h#i8YFU+PZ5jZ?;o)1sD1hc8yJk6| z$#F0#mI?A*up(CD*BpH;Vn)@7B1kmPIeKtStp% z--#SBL!F%Ga)%^7tGRD#e3u0>e2t_ooAXlocMU3qM{H5|`QR}CGI2gxXRJHjlIZs} zqooQX;Yz$dLm`$XFhCXb2g-?Kogov|4h$UYv!-RUDO_p$2`n_g-n=XoM<;5xvE#Kh zOkn4s={oLxchB@5I9fI^Llc$95MJ+gG019pV8o?u_@C{J!uXt4_xNnC*{R;AKe(G6 z6gHgz@u9PY`bC8M5J9?-*R3K~L|u_~+Cnr(NQ(n)91#Fiiv>Z3)S~F(&|j#skE_?v zq0IJ$b#hccXNfsRTGwo_N1j5tmt0O+p?c@qu5S#^syb#fH*+3p33$~R(zpDx%X(!9 zphZ%FXEi`wNWVWm3&9$UE~gH|-$b+w=99`!UFr5fKQLr8Y8RA(xDloJ8DNK?OGZ(C zx6u<%BvK9%GOYH_`!ww$Q138m)&@ux7tf#eA_ecfm*#nQ#&p*5&^(Ux%XXrF z2Vb+!U9Gr3o-WgRv<7^q4ohC@BI*nJvEbq9wWd|A!Be1E$C{0<-RtJ&GQJKb=sj`z zz+!Ot6|jyWFag(C`jh&d_1AVBW|KKS%Vu|~WxC^oNn9rT$+M@|lMHo@^=I4TwTQga zPJOOlZj7y3!=~L%rWg}h?7~eQax|VHaqgBdf$>w$;^c=UtPXbA!5swSmiKl%R@)V8 zN_*-YmlNj8su2F%a+7`(7m8T;LZAQuUpUicXG7SGvMgY|UKD^8SQ{Gk%b&*!!CJkt zjJoR84ih7&nw#!!APB!*A{=9XmN+;9bu46~IBoP0v^%6->s#XLia*Jc%U@?FSFAqi z=Mevpa|Tp$O*Tqk1%BVFDIojS$vOQa3ngnOM|LrBdi)dU+~K){qGf*(Ms* z^yrl<19f7s0^)=jWhGMiE6*|@mJQsHvx!->mTSDKq!G2W}_ zwtIwbcImM-YTa9$+wU93GGE-C?Znwr)VrK;3XI0=T)N~bRn(_`>R*$Rhtu<%g2Hm( zU+aC?!c`78&#yL^KmQ}HzXdP+TW%InTh$qW42f1a>+x}(=VSy2rmXAMaL7^8OMqI&L(aRYlm)z#em1N64oWsm{^v5bPdNu9TJE!Nhi@ zsY>c4NUz;obm>GMoNq|`XD9VvIladV1S0@_jRytbPU~_`zwQSUqZQ3>En($vE#Z<( ztzK&nD*k`$y=7cmeY!P#7pXuCrA3MrDXuN<6e#X4L0VjcyVDkm7Y$CK1a}EeXp09a zE(z}LZqM$_+%t1#`ph|B-}gCR@(Vj*@BICewbn(-wmDKET(6jEZA$zDTt2Z))A)@8 zV&0&f2cGsW90g{o_8uSE)1A3*Kdc4SiD4sxt_%0g5GkV?HPZ+(Re+C7t^1Nx)G;8@zkGcWs@rYr_y z6G5@7vpXjhMCyKYUZ?BqlA`K_)>EEm=$`-(!Vu`4?$tShD2x#$SE=dzdVoB7Ur(R3 z5!3WtZ0CHE3sB8aL(+d+XrAi!WLwbdYzn{L1kuxv~-sP4q z@}9?b!Zce;yN!){T0gH4Ow-4WVqfsv(+S?6uk($e{@6}*IUQNNSZyNwlyu;QbYvC) zPp}Cuc>4|Q7pNJ)_2HQHZ0#BrxwBgkcS@I4@XaeuJ)q7V?45KzM!j#DL+3UUE(+9T69Y`WlU*deKJfj1rO>Ble&aK~@%@xh6ybL_$4a5J;Y5Sz^8%Ww0HjnYy}^Yb(Y{99 z%vqEVlXu&d8W$~))zB&8o@)f zCVKy60sI5MANUrCardEV7|pJ_NYssZv$Smav11fH`!1;>zMtSjMddbmQ6tZJU z;yP`MIp>t56T6Np3Amy8GZP zSqkUhqMrU9oznTmV&{(kNvCuFN)%8%N8?Dt#rnpYHv3lp`R{y#KM9B*&;gt1`!~gh zMG$~=Q9M)s*?>o#Q68o`2Cw!H#8jPI>n3)x$&l^0`bYArJ<^#zqaEofZD0P z{fSrjSL)KYtnsk+kIw@Mn6-x{tDb9=DcKbomdLHKVsQTFX%`TH`Rf_K*nqi8?s4)V zAX#kpmk+fVcW6AH#!s5SO|YQTb0>}v8$H?CiFz`DG)v)^X&|8em#!>>E< zkJcTL%J}*Dl{;aNl(?dl!dyW&KIi$GMTt?3D#a`s4*=p-F;Yk<-yth#q(Guk#Q>Y` z-k&l7|5(%i<%;|-Zd>C9V=+qKRSRq&0E4ECGJzThM?T&`L%Qu`O&$`eVpNP}m4mU- z-C0}`J+>ws_2BQ``zUopKOM6ReLGDk;Eq=HpV^W+60KQ)8co1CHsNpq5D}?)?NYUp zC;%pvv|S|Nu|g#Q&d)+!czcg{WB@g6A8o4IR*Y7j5Vxl0t?~b5WBRiZ<-q|zfaDBb zTwcQvH@m&3FhNgZZekzFFLq-|y-2m=A82G%zet9^hPXb31VGEShY^syHPZ=tfj5_A z2PAcJsw{+;DmO+86i16R9dl@nS^v@Vzh!5>js3-F^jOxD=M}M-FHs5f0oV}&pX?vD zeR~pa%WFTK1)y1q#7P@tY#$-pE z$0XZ=4zKk(d~U9i{cbLx8uI|W`El_5HW#OC)9zTc6@_F5qZy%iKF92r)m|(F|IOlc z!T6pt7o2+Ue?YbV11;*8^1xTrgW~_lEBo6Drc?kTeuQ-Pq=b+D2REN%0Bkn?p7d6M z-){hasxbWZ)9*BZ2lDO!_HOXM8S1}`|Ns8%f9<9JM|wN(?Niiunnx@o|IH%!>!h;% zr5z&m))MD`FkSyZ(?k14SGSFSOk#s4>Nz2`4G2jmc!hVn$4y-%YW+;`u{9)#C`^%6!xizOL`&*(wdnm-@g+8BbnezGHcFy&MOmW;`k zdIa0_*W&z1eE(~!3SW<6pOZE6^a*E>p&b@nrucEc79f}x_d|c|;i>M@;-QYcFd(v&Gx#-FeW@$vxCdRp69~Eip~qO@XnOsN zunJ^X2BepJ5?^h2Ev_i`q_Ebqh`Jsy5HRVq=0C!6!T1#i2NApl9SKD^sk(d93di*|mf z0*SI?0H^VpUuL6WB(+}u2(i)*QFCNR@Mi3|5 zgU$_y*dHw~@`mA`fv%EAqAzjl-4%1SwIDB@;m9OHGM{%oJn+N2T z!`&`VCj5nMzVrqabIDbBsN`wDtXzXV((J^=Am)1_e&FSIP3^UOsj5V*ex-DS4~NVt z&E8y#?Hc)0g}ugSSDo-!5e<#j9Ww6{XE$ofF%!vGwb2RaJ`^nI)^I%sG!zgGoQ+sA1B;4+VH|2i=lLAWark0 zEx6oJ7y>S5_kW>?p|KzxX{|D?kJjU*lKhnx>WG?TqlM1%v;C*K@swgdVbmhISUdP6 z&Ua6_-}(H;jwt`7uLcU`_wcrW1iCCH_Ak7LH2lSgAJF+@J~E~qp*47+2KhUJUA`a_{%BTz%DPE$<~_R~U*`x%EZFzB>~_yjMv1JoT(Y+KY?Zi~R0Pgg6(FA(>EtQB z@?cthLo}u>9_p9$nq1~9Qen^Rr=Cn240#QGENVITHA}L+{Yed}2Mp@v9_cpOtZEf% zR0O??yG1y&5;^~ow4Y&sRMdh$UH~uTFq%z|v64bxTU2I|V@sGQ39?a0{3f~(U;yyD zs<5RxpPAl%d%-nompEhG`v8p4E`e&=@bQ zK0__13JzspL4BgE!yIRCZE&Qj!|V+e1$U=$=T)l|Y8KtKn=0p-Q_7k!UhL=_DR<LSe*e4YNTr!`QE5=gew8VL_8h=AM8a(K>^0$gsIKu-ezV?KgBpC> zvFeJ)EX?YO#mOIw`lVeqMyyh}JekBCum_ayls@{mV~(=;mkp-1oA#|?7RZq)f?RX# zXW^=qG_q?IpB&q}K7G0k6t+| z{BT9yJz)#RQKzngSvzM)5smxpQ4mN*$RcqC&>jelD&3jbf2xsdE9vR9HfIRPpS@{K z7q5_fi&+a`y;W;AYL{0&&Rz9+;rj3E zErLy!ubpp%G+!<%@pBdTiJSDRG^-|&{ae%iz)<+5dVnUU!$KnLhm|hmn|QF=rwD}J zb4vtW*lGcD85mG#va>6=RSK8l4d%h}gK$U$cgV{?idp#ZwM58TyQcER+NOM{(`qh$ zdpKUB_rsULsgE6el`^T|o8#TP9f}u+WtRBt&gO$~KK|qh{pvd4-YCZkY!Q?%D#W5dQhOB4I`LZaf2KPl;PcNa|Rb`Q%sgO)Yr7JjtS#VuE z8wgD!KZ<;bbmRY<_B^7vKjT^xhg578v4*^W_)=uTZ)g}DAO8L$_RJGJ+p9I` zr`waoOJzAWme=ZGx2uogMeyv+!}&Xtu`!p94UUr#x3c~Cb0rD+jT(T7f|gL2p*qIs zf5v;h6zFmCVN+Ip;F)MhnUN3v{+zK&qEPPai$Gr-k4NwC;(i5ab6v|kgn&g&F6cgt&Ul3dx+RH$I*Tj1f`p zA2fYC6a-F3VLF|}k4#sCig=BFLN^Br%qJh>GfVAtzE)41&9%Fy2Vk^m3BYj_!h5&w zvIV^ESF3=u9@P$i9%REs!OZ$X6`vP?7!XnGgT>2QY_aM^{tZK|?=GHQVrZXF|5u&z#s7d%h`)~I)HCh8+|o5=V1 z0y1OL8wC1+@F}4ZpBONQc{c_yS*}=xCW5l1F4aqbjO{jZPI5=W)rOH_!TLDUFqvBV zTw)6kZqWHZW29wLZEG`(B$OG@f7r!B-dOROZ6+8 z0K{dg0oNWrRQKFF=Z`|xRi9~?r{!>Vc%{d3fm@I|*AKct0gHEoc6(w~r|<8P!<%r- z*gub0`Vd;s9iik~M0O)Ko;;`kmwOY)r88#eSwveXllOK!1m!=nt4i3x-bd&I=4trE z-ig0kyth?pGYsV_fi72uH_t}qFY`k%DT=@SI%(jut|nu`V~3go6DWZ=mv<2>N9wGn zgasp%OJ&T4?fK&Uii|^JgDcYI*+L%7Wqy?oMx8pobRuyXfbP8(e5whZ*orCnz@$;g zgi&Q!t%)zhfrCO{B#-6<@ z%_QwgsanA46z31Wp*JoyP-*leYoM3B50fgKF| ztZzbYEq4W`gFRmdA#w3|E4=%-hn|E1(3q5fg9I5_rHZez*rmhwcAkWDZ1%f;fu~>b zPWA!ku9hLx(8#CLWB*oW`dY{Au60?vD- z)j|vJY-)NWx9{SQr;6bT$BVag1evJ~uSU;WB4Xv`Ua<-fr7X}!m1a1bTO#dT*5mto zLfZSuFymzRCFhH{U_iY>0v6r;ZcVQGy4?yWEk4M?)5u541TvDH_VJiiWXI57w!h}u z#0ALr9B@^vPkwc;c3n5C*YL|Fe6SzC%TDhti$7Js}3pDIh&Mc(~eNF<gD2JG$Z~UtKJD3Hf0rYu+Cu`GoC2m z%GBVDK<0~ZVJR8zWi<%9oQfxl+8yYOzzmfN4MbkFhZgwb#`A~?T+X3eN@IEXyqVj*r$kIDxcAOf2Q5x>7ut=l$H#8^z5fFIBQp1RJ{@Gx7y-j%|#jfic~ChQicD_xN2 zm-o+R*uavx_)g;9;NCllcqj=uRUI+aZ*+13$bY#7=xsmA#PP=Y2$6-*!}i=>iaS`~ z(M_(HeIy{5L1!GGpQD@^2`5v^WMhpa<$g23s$pqJzk(x-2DtuNk6bqqm`j$EL2?g| zXImSp+}XFc$0Q8WvgX|Sed*GjQ>iwY>l;-YdJ;xqvma!dT9kwtQSF3d6p`*bUp{@8 z8`cnbJUeDDO)%vB>!oS)F2TmM>2qqCY|DC?s*p(SIJbgFy6- zm~t$rI>zjoEz+P`Y?5fz4#>JWG}iP&=fUC$9j1zH zv&MaUzDQ)izxe{?OGgBkAEpzAbvT%a9duvwYSiiL2^aBaBz>#~i+ik$RC|lPm{-vH zB+9ZAwG9JhlSyPo4t!}PbVUI@zC%(0oP?WN% zfVm>13Jn!!!}NzW%tb%>M-#E@N&!*~S#^%C)D=U))A8ori6Ef?%XuKr}1n-+=g1_^* z?*ajoe&3~D6X}P!KGc4s^pYPIo8CR-b(_{GiR%A|JMP@W&=v&{rSUosCR=Q9&qe&H z5C{mXq_0z4_uNsj2CwPG<84{vt0?m|%?{@{CT^IcnO{M%y9 z0@@||1y5qV&OTz-c(;<1_{F3rBNH4djvdF_~QFdXkwO|z4?ciWEUf+l9>41 zt}qf9i>fF=EiQQ6c7?b0LZ?1%YnwytnGn(DwA)oo&g1 z-<}XvDH=Fi#!olhhVg7Qi`lq)4kCC3!sQL6duWtK3f*uDwO?`4J|@gQkwGMueBs#^ zNFfVj9lJPLXEljWwxz_fBY^itevOZQ&KU(LPrXp?dyoz5C&vG#XoGq7{j?%RCchXt zgcp=bE0F*1Ae#FufOQi{OVo3H7JlNEp0>U}oHvBIRHrI2N}&4$CE|Z0UPH>GjU;4C z$_&Qc$pg1kP>z>YRWUV`=x|9lRH+G49{Nka^-hHy$=I&Z^`}BMN{4m7SW;baIum*- zxW`HAecK-G16Ai1_8)6he*efQd*jnKP@({jzQwB5*48fmEV-PkkgHH*y|MA=CRqF1 zcI2#uwV`cH(-h$5snz82KP*LE6#zu7Gxab*c{le-Z)40jO*Gyd~xE;jdjyd!K&#SPLLplOqtTB0mxuTy`v- zd_e8&W{=(8djZ;S2mAX}Zk*>preD`}enC>eW3Rl||N1KG=IT%x8tzr?+W+M~IGm6@ z3x~Y1r+#y!K=S(XI7^@3S!dZxUH2vE*!MAot>YIuhQ>vRQ zBRn0$T$X14C5iPyjVw9N2!j|;`w5wldpNNQ0Hvw<`ktjb(R6SUcPrNEwuGmk+sjF= zCP3lfw8VZf@*qXJzf8>R=U4QfmiLe=PwNwkq^@yrkH{nKMgp<=zLy`hU)*W7Jbewqc7drf{i;6yiW6 zY$k4sC-~g+kVpkmDzL9mAkSX>lR2JUTG-14>O!}mdE&M%4d!&YHD~r^Ay=%QQ=bY+ zoEs~aw9$LkL&_fmL!pcGRyChe3-24D+L4<8_4o6){MwQQBHUK$vAL`lBOZ2A z?{C;%5=eY5vQ6h?2qFzP)2&*K0khR?vS^n+tg#%6C*di!k2}jHNB8_q0R27|u#bsl z5rz3C@Y#09(qsX0#A_wL0>Vqa5*F!$4W3WKh=)Tf&AZ<)#?r@aTaVgH8MSHm#@t3I z2=bJTZ6fIPv=dNp)%OBYb}Dyik?P%ewyk-Ycr#4$D7@~qnPs&QxQu~$4o00q&N$4fKrt7s~#>z)52YgUA|vyG;BX7G(2QC z8|y152}->z|50t<3`q<5IIlL!p@RA_$S7AWQ)#=}Q{;j;@~b+8)WJuK}?5 zglbC$0^OQ-KVaIYd4!s(4%0#U{Syy?&q)7R#A8w-x!Zq{kCQ9vWQn-f|l@%-p zD$tmDYh~~V1B)pE z3l$7r!_^|~GOMk+2WlUD&KGEj3K(5CG^#xYeV9~HZrb%5lwE(vul?iAYf8Y`z{cQ` zUQ>f=Nz4athK$Msf`UH#Am!EUBC|%eAv4qBq*qqcJ(5x;LIAO^L}1OhcC<`AZmI?h z1{7CsMKQ)kixt_Mn;0}FIW+7t_RZNk-52@n(|`?XaoEDrCOomSY3#r(zF6j6GH!3? z9#frg-EmmM=+Dp@^jz&+OEI>uMkScyuC602*dxPvpfshSHWz`|0cP_8z}pTWUd8yQf2#_!0?hy&rVQ=?M=@L}t}4TN7Py9#F_7D0Tu01@Y~U3bm;a zU#Mk%-SCot{6GwA5E7}KS)i*r4d-PUt9)zq%*4T=h}C6z%cKztj7^{Rr9_@Rj=!ST zC@ylzcRxAC75ZJ0U+z>?RullvK`<1A_kA!OWn+j_m^+<6E2a{R|z^7(~s28YVPSuzc6+k~)Cl6Ge zR-d;j>eVcg2>VnzP^!lp(r0IGlGnjj@6rK zZJb*coh7hJKX3564#uDCPZLn8FxfOh)a^gDT6;MSKRkJYf`O4@uAAKP2*2~I2koIx zLEaCj&C}qis?Ls!bw7aQ>iXC=vRb~4(y-j&)vv5!R2-L;T7&;-@Y!2Rhh5|5_Bo8- zBtMFOffeLbqQ)W?i+!)jK|dVq%4SH03FiMvjkO+;-jGffWVGkQ9AR9oSZ8z3Mu;x$%#xY-@DB zo1tl{KI-%!EQV}KKtyRsruGRMH3KUx`Ox$uv>{3vS$AG}8CI71E#6hsE)FlG5mAY1 zzZHu1UR_E%@7r3a+Rbo|of_4=tQ+m(HN405K4l(eGOfElZ4CtrnjmYv3X~h8$ewTp zZ-3@DaohANY+1|-3fS-zV6)iJ8Q>uw@qPC-7@6jr^*BH@EMDdY- zLQ5$f;M@G%2G$jwh=|p3{URixBO|!ceV3;S(2ijw=B&G^ohoj7fOelU;E#WLDSJ#g zcY^h0Pv@#o80EG#^+MR|c)WIOzi~{hSca+*d1ZI@Ot*RLi4HLe4%x@9{h3N@;!gEs zUi@uYMc&VoJLtzcMXZK2vd$|nJFihXDJ~22m`Aa3Ov5~LgqFRnX*ZgV&9|voW1~0D zk#8c%CT(rJ55DJytcAEmxvF_Kcr+#$D71roc!NduL>_ zv$nrt$io_e0QxfNG|C|If7`J&a$G)@7EP<>Yztk z^UERwkTv0_5pPjknvx@G5hdP)gR7-2`Ex+AsM1+Rq&H4?*2n8c;G0fCLv5dkmG6xzW2d%q-Gnv+759J>#a|<}16r1+gp4S&A zrjhZw#UooXME$|FWKfg#_aQj)8Mue*TNNf!GK*4)uQN=9JC8OoP#SYzeJ~M2qk<8- z0iKbQ0W%K86E1o!*Mm<`nv1frl))oqY4U{$J#<#FphP{Nr;Dh1n_8MzC(FK~1_F@j zOg>MwO0$6y1Zw+HzSiqcB*IapoB)dG{6_H7_l}*Q-@#I7TZG*?`kl_VrG@SrM^@dj z+>psOgH~3)agB5!Vge{#CWI06B#+nm-?rqObbpz3PasYUK(>lWIA}SKw~BcaVeG}xr6ce^&kIu37mWIO#b}ChHBH+c;JR;R4x5W zFVvgsha=7}Zx$x3C_C6C(U>&~pqud}8k~ErSuf1fT}gRT?QBMEjN25@dO4JCQqiJ! zP>;xBM84kGOLeOS;`;by@FF7?WuB zWc*L+3OWY@)!{70D~$q^Lygfp7Fx+prC}1n_Q;gsKr;^9@ms|+SDU$X5H7k=)7}*a z?v5}IlGHl@bMohXSh6dem4|z8WPa29dUXIDt+q^<+_IM%OT%~SIY=vm3pw4iVFALg z^Efc9+B$6kZS{z!Je#!-pIoJ=!o?&Jdp$jR-58A)>ATj;u?(|EN;V=QHk)-JqzH?t zWzbV$686z$U*y%hzM;%Q`%Py{LvyJ)RwIP3$g9%nvTdd+h0%Iv#BAyICXK+T-eXG^ zJYq|X$9>=kN{zXwV~akU!cD>FQlH0IGP&l;UcY#2rsa9D( zop#@LUHpvbp%hJsEZ}IF5Qg?ai$sOsXB? zB{F7V)tiCc=|uzd;JY1)pJ`qiFFgxP_gk~>b36C!K07}X z%V-LOM`r@Ah*O!VnSq7O=k&)MRy_=-oHvEM5lGzMkLEuzj zi|320wlDpD-ksdsBx0NOV0vj4m=)+M!1hSLaocvTigKoE96p739ziQ!BmK3b4=r*I z^aamn=%Z9Qm&10$ao{?qId@6zP0hBML`W3?_}K8;g~~jwv%8!Pl=?ZA)q%*V)ZR_J zP(Cgwh2jA9ZY{Sv^-5>(+(T+g>Blur&9>E>PdgN(r%Sv}nYBu-fjJu`eTgHA!DBT= z?J&M0ydwDZ#{anWn?&HoRAJ;r3-*Su_4JBhqfN2S`W5H&enSr4Kd&iZb$KNG!HEhY z%6v#vW5oSKak>q*EeN#`MF81`C=%L2jHdf9A=w(9*WRuWp?aem&8nWoGkdJ9)R(HT zmA?yH_ys z(BjTe@sWaaN8)y!K5Idp_o3%GblnMQ4IW?~L9j+P`hc~;jkge{Pk79QG_MjrHF;dX zbnSOa>7Foyxj47M!KsCh&!|-zcn#^K=H$nB!CU@`yYk~zw7ob+j>dxT5qjK;!5>zh zaW4BPD?M*04HvfwPTjB_%<(nGC@Y5G*YvI?9J=>aAJcGI)Qz$W>4MKiei{^6WR-ee zbUoUH9<6pkx!XIF#4NqfL_Mr~ee|sRbu`SZrM?IhSKW?y#$f3#T^hmF@|2_rQ*n|p|(xV7ELC9rdDhf>L5uFVk9ix!@z=a?*g9mqF+pE)(}d$?0MGEe=u(&*X(01^P4LlgrfSGlXxM3U!9 ztW6e0Ukz17Pjinpel_QvdOllY^WyzoJuT+)zS@j|q*wAA+?J+_Q@%S>^@<`Fd&?0T z$mUCpb{g5ZwOjTkr{yp(gkBjuS!)j$ap(P^NN{&GrO>Z&SKt%gYpuKsmEES}6k<;E zm!~GqY4hfd8b#Jg!%3e0J6E29Uqcr=<*qOKm{^WGv&SYg zD1Xi4vSS@GcWCymTR$tP*y=RB-@e*A?+xz^Md#ubAo32?20YUo6Wy>T3i;fFWm;)P z#EodwGSjv8tY78q8Lh(;6Va>BJ;S&&L9lYP47 z&**d6Az@|Ba%lO;TwzAX$QX&Sm3DVdELe}w;Z5zak_ih)5TcQ9gYo1Ro@1QZO|bl4 zSv^%)@03>k8xg?=ME9b7m+itXQTWI&jS~f;YSm9SF17KB~^;KSKAS4T04a-EX^htcdDu2kK(qGMmJP%jyE*h-5BMOZt{`BRZOJb76prAkwvipq!npgyE+ySj>TXg z;IFsP;p;5V-9Y{ULXZz7q*q9yIV5C>Pvr#*L@HrIfr3v35W>hU^JMeUuCs7K^84ic z*40358B{5ICtwMS&Yb;7!AWnJXclDJ8!K~H4kcs-#3{yAG~)ns^ILN+7QR2SE}2EI z`ps!cOTPQNay*$MPP7Q1uEN;5ckTA=+`F-2eh$+$2hRJJJUmK6(8CxbuPYjBW!M*- z%|?roD&uowM$O6(+}-s5QO(dO<*(7tG(0UzFAtI z`uTo-^Vm+B$cv7l7=bea;TE%#s61ccdUxfWXPk=}s7CgR8F?nhSbB)%e$aSG-Z)m- z@$(De1m@M9PqWjV0uwQ)`w!o6o6mb7ve4vOI{eI9AiJBCMjJ;DP&?9uDJELu%`PiZ zsODw%^(y)YPGg#u2HJg2m!}u#_4Y#Hb^BjQt8fMf zem_UUS7$Gueel99)vsq7_wijGEAgjwTzC^JpvfegxYbNKn>kLLGR3^t)~(*rxXKJ5 z*YGGZtILMdJMGwwT8uF;qu1Rv4S4f+agj=q%Ua9d+rzz@Hm$t#)zbAgDMq}RD#It(tIUew2mVw#S+gp6u$LZ5KQ zA~@`OxlVp!50;Mz7kV$>2i@WJ?xXjm6ZW?Jalx&&hJ9&f_QQ>9#*uq-C;=!C9&_#O zjz_Z})%l&_zu4`+EciKYjQe%Xcb_W))<@tT^~)h05r<lfIl0-<|>XVh=l6Dc({M=^8wy>(7-!(3}S${ zFhd-OH_f|tT_Nryar-eKb?Rwp=Y$j0{DVUt-qH)%AJppNF4I!!*d%vqg{Z9MU;I}e z<4wE;Rs#P=EmUg>Yf>SlP8Jn=zdpt1tkk1!AM2H+L}a*VWf%Vf@*Me=+p__Gh3r)?){6T0DZ^|E9k?T>sPs zfBz-F>HQ|PfB+-|IjF+a$7kc)K6t7$8xDn(mr5I>MJBoa>ysd_lZ~R`8{8e4YRkdi%DD^{opPDN@#2!y>GN^zg^tKg zRU)9acN~+Z%^EP*jbeZbj2)O%13#o7ef*Ut+&ag zhRqsU#4{yz$Xuh56gK+)*~ArY(fCY|?+z@3X^qn@^^MZIUIB5zQYm)RP2wK|#hX?pUN zW-_+gV8td6JO&H)=>*Z*^aNrA4uW`5pPVtaBT*QeR4(TeUa_Xck>{e3f48omPx%zA zC{??Gi}i6a4=lks{@MUM<4I$s-j-l+NSY*>7qP1Q)1!3b*%UPCO2i*dChRMpS7vWh zBsySJPk&ydIJo-5?@G=(-tETSeCRv+kXaXYM=Z@d1z*2I7<`GrqJEqhy$7M4 z2^~HkWA~1}kSpj&+*L(dRJsn(77V$?l)~QXn4MoOj*QXyQ2%a5KHfmXK#8Xx^|^Sg z9}rlLpbo+jQ{07e>3XB-Y$KI+()_+BX>DP|>V$pi=831*uAgjgY#NoMBcEuRD?Df3 zUueFP^y_33UIH|{8hmCVWZlfn>C-6pCY`6tc>DL{bI~41mJo-pIxxkKunijSVvBL+{-vFF$>e zlpXYn=}WbJMf(p;kj-9^<0xvV(SS-@v$u(4mOUm?kX`1%i&l=l`_+8U)gffDO6a_6 zw#sPW4E^ETeNI_zm+GBi&9|2QJzs}lyLtv-Qj{ZEs!4<2>T;#^rfzz(g&4YQ`qlEl z+s=lJoMy(k+z#Yfo~X;7CgviwbeQGcXC-%P>6OuG`XDckOKJ)ZE3PKCIP;KO))+`S z5;0y^edJWf*;hPy6^@)cwesUTh)zwq&6~TfOw_JSOCzg3zxL#RTkvy=_klg=X`y|- z@}@$~FRQz_051RGKD&hs3JCsNkJ%KLrSY5GB^Jqn^M}0;iIV9o6?U0&bVI^x?d8*h z`y~5Z&M7T$h<~11RFTu)r+kaIcX|q0D)3nfoJB7%Y%c6gc{Q5D|Cgv)nnWI{FY)K-#RF79&y7Eh7hykV2hh|e97sC%WoQXR6ua9H0p0vI;7jWK5O zM6$_4wA%+liaPI2%CPEmH+?l*rOh7}KQ=v00I`0yyDVKJ))ZVB<3)d2I9RpHzEqW> zzWjakvLX7Hc~+mh!E&wr^*Ey0eDtu3-LB>5H3*QZtx|#AIP22Cf9gQW?;L$Z(yUmE zw8KCRHJP`vzEoMdfaB7tq&j$Ee?J?ynty;~GGPkpUT6Y!OaE|(8+Q>*)I#uMe*r3ts9JiWehQDc?WJwmWA0g8J=%Xx-Q^9!`; z0Jli`y!f@B%~KJ)Gvx>RJmxWptVXhWFiR$&RA3AsO}T!l9a!-0hqO%D%(aWx#LsU- zg=WrzscZ)Rv3Jn#Z8qU-!{ag=Tw^AH^wLory|U?HVhM-!k&Y}-4@M!yQn&PH>HAxH zTXb)rLR`Ed+yxTb5y4p_WE=5puup^>8LZh_A|8J3rQ2c+txUf2g4@|@xD;FMG-TOJ zXF1$7e!p2x5NA-~_6$jvT;9qNZiQlp=5*0pNn!@+lM4si$5c3 z>T){0F|iuHRMxH9PMc)O4*)ro76??|y%;$!+#g;3VcYHU+WbRBliBUQf03;(-(8ef z!~`{NB$V3*GC)OP>N#-s^*&xr_0oRTtz3;;_|e1GiC15NN^qbx4ja+=WzPJ7)P{RD zZ--C(Y|+8;W9jj^!dmMKSRLLRTb&CRo`uA*tbT@eBFdd+FC<7D)QR+JuhT|0>J)%l zmiwjGQ(2$*8&!l;0rMQf386@QB-oE+jVmDC!~D&H{3Gx!up+VVjv-4g0Ak*{X|IN$ z<3=?6dofo>-}tp1Qs~g_^D(R64J+*=VY|jymq3 zJg*B{MoKl+bCr@Ua}ClJ(ztYi0&nXY8Z{f^92R3Pc|HkvT7bEhK-V)$ihJ}-V{Yww zWPf=sG}X<->7n=}0m*}!vdKJd!~VzBth;8tbT-DlOjXZemwvj39G5gB-mL{L8O6KZ zEhgixsw#JC=k(QGVNQouRuit!9c^D#&dL#|gBn4@hPhK0FjwOJ>^L3!_WK@{#=A4oQje z>!1oa;Yk(pe@=-W{1DOyVwI1ZjDiBPA45yX1~8;p5KtmM+Tv8%nQ64(3CCxQjc3q$ z1E@}jm-lJRFTokUm{)S!PwD|Q&99Is7p{EmTG-Wrv%74%K!Qn(QqeMX2o9(D_v7`| zO5f!k0;ukAhgx+Pgbj%_FZ^Tb^K5YU$u_%%IzOA4707?Rl0fa;2JytF7ObCu@n8W- z*eHbC{T$rfX&d*^|2gk_FpS*)Kn!br=D_)!!J7kV3t7$UpB=mN*^E>vC6GmP@YP)I zfyU!J-&V?Qx2=IekBqT|QTqXIi=gEyE9pjDnmMxeu+{B7}$B)690|ZQPHU zR^m6HRkG`J&aPv*Ry8y>7j0w4cAReghIy1Zg|Any$M~IoDpIwci3u^l}(|kXv*xDX4gJVv=2eNnBzvX z7X1MLy+g}(U7Pi70D4k8y`5fkkj@6(NQT~c>3L6R9DU?6hLH>aWsle$7cjmc#;p$Qgu63X!;u&G|Cl$wdsjz9Ikz&?!7Pu4j&3$IlFVU0 z|D<+tbG9*L>6|i8{X8@-&+MT3|FHMgaZzsF+xS653_?*l6_5sLi6I2(?gmNe?nVV^ z7-DFo8>BlFrHAgJVdw$r7~;J-&v~Bj`Kr%(|NZ?wpZ7mz=4S4>_ugymwXSttYbRFh zwmogEU?y#i`Ks?_3K75c9}E56Ue?AA;1_8;?y@E3>}%^&<`zO0V%qQ!6Kd`8zWrwl zA5wT7#p26!Ci1v<@WBrmKfh!%IX%TK zpz*-Ib2xBT#guX|IZIj?!LUB~xvU{K7bhz7tM_+Z-06o}4&)t9yI6yP%~FL?T}vrX zijMwn9@Z_JB!8Bl(3Jo6Qs^TP5P$fHKyYZaI8=v`@CoZTsYjNAcbBn2WL<6ZVp79Y z!8sQ2`#9{T7-ycHHfQw%Wep${?nuIdkH3qs|NY)ez&|=Z+ndAKVyv#SU+QW~jM3>g zK5#m`J;NWDN%l|c;bGMuD7Bxwn+mJs+D#pnSDENkKKpT8)sz;`e|}xFJ4x+>P1c3n z@LI{@CzmL|`Obg;+atS!Lh)XM|2~*P6eJJ+bl7D&aNENx>kqB8w2dd*aY0vCa#;gF z40wo`k{xBN`veS`@PbjYSKBhkHGo&C`YHTZE;*!Hx zZ)4Ah#_>!7H_CFfsf5reS-?JwN;c_R@vhseHmKrzj(;3RHehu=b@XH?k%}!c)N?)0 zE(db}-F-{s#!Kg^-UUXCy3aN`#SYwGsb#2@eP~xXwm|Yv>+x zprT{<9{Bx{>bm~pQ6k7TTA)m+pvfy?4b_{B+QGOxj=fQr59jYU`E@h>7lgXk1Ga{_ zN)7m+Ld#zR(9bQs+Y)WpsOE*Ae9LygG_K5*5l7jg_4MN-6oM0s`VWnHKK%37vH-|z zbJbmLv%gmxS!raVgnV|6-x>GEeqo+Z`a!h-K<`v%M%_9$Ir879?3eYX_f)72fh#np zQw(s9ksH{lnk&2A$?R)2OHW=j%S-l)BW0bZB|9=`fH*quoL4PjjvQ@fk zv+^+mhe55_^-vDfS^~gMJy)0L*x}5SvUOc6}&Q z5@bN?ge3Be%Yo8qJ8}$ z`QB#O)lv*yx$*VO53m*&TLBhyS3MVc7ER8^Y#B%!-F!?~p8Tya&ncRYNd2>7xATW5 z%iYy;VyR-`$=xe-BiRZW119YaoVG@HnahCQOGX=ejx6qbOCNOIr>o4fReM)m+|#J~ z)A(o_T@lft9Rrzb1L<4O;~3Oq0Wt&+XZlO?3J&vWCBx2OCj5cac(=VJ-m#~@%Y+wZ z9|5)`mkuAd_U$d?+*&yeR^A_+*PnkqN~=h%KZl+3dL$4``{q?6AD{bXSZQnf>FY%V zpKD(QfCEdEKl_la7G8)0^59@ke|(!C_hs#ycg0r2GV0eZYx6h&sYpKgPSKptGGxN{ z2(dPrdzdh^f2ICCWxw04x=o}tZ-4!Zaxe)e_?!Hb%flX)c*CQLw$D^QQ(9z8~4o$scLpvm~*=d*k+!?C0wp)p2N?u}Xa|_QWd=c1ykx zt=WnMNe4xwrcN{JyiliCqg{*LwY`9)@W(~+|L~+p^5D%r6&upNl zZ;ASdAd`TdeFXPRX(?N#U?hOe-#3K=D$`4}^K@&mV;>aDp~-0IL*+I4p2 zQyT!$-}qp)1ZTz%w)dEZ$}@t$ft=H*L}!W(%q44)TB=%J0d?9nnKCG#yAN7SJn`&e`vxLKjHZ_uRkRk z&M?sxnF^EM(c$S6h#=#8I`4e0m?wC>t=ydmN(K($k{Z>&8b|@@GZXh76o_2z+s$-6 zWn?elJY6af(zrc?HIT%V+;B1|QdsFz@=cn!LQ^blZp1fd&X;MS#$)bLz4x-eao<_m z3e(E+kWq{Ga>nSTA-Gh!4Vt(O922&5&|<>#eX%`Iq8BfIsN+WfcR2nNX-j|}i8XiF;S-;yR0X7~=t@=H8#j}yTft4+y zqm_-yJRBh6BV^5Py@_dU-do&BS#Gg{lAld5p$x44~J z?$@0Wc*5)`7XEz58f+3O&(6zINRdjfn#22uHsIm#a5#YozUXLYM1D6q7dY-2zIB9* z{lKv>p0g#-X0Tu&X?T&mZ1=b4aH-t)O1VowVt@(;HPV+bqPx(_uEvirHm zvR$ASrG-swEF9-<@YneZR1be_C#Gn(>e-O+QvozxYRxo$@ajQ8X1u2toXkdy;&k}9 z6+T{WVnrf#TLQ>q$**jC)J7|$PvI$V8gb=W(!mP~pUaZ1q3>7&Gv`t2j`7~=CS{o6e|&^36SeJU~J z(y95jq@mQbOz;Yz@RRtOT|QHT+0U5{!i*{@l1ub1(RGu-LNr)y&*Lc*xt#X_zbkky zl!@F6+{4Vmfz#u7T_f$V*JoXCx2b>6?dlacFW5|nq1yO*(x;56lbX76Rq{Eyt4@5o zXK6@l`ALe_{mQpFj5suUP7o1gF3;`e?^+<$f{Wdn3D5Zer?;;_2YX+l zU|hCb`a+y%-3NH1>p@cb-gepBWR@Odu=WJmN3z3~WUn@wQEQ$Em(xppl{E%u9RYxjsob_NiCAesJI7=xC#ktyR)iOD3R$ z<$ZJYGAs2=9o$Mei2$2%gXHQM&R+eiSEEUtX6q05TRhd(s;x@i=|wcJna@ZZ6C$4# zh(HBGqiLgcaj%nWjYTF(9ekFbH+orSe*2sOE|)R4RPsHaZ=jA5pfiB1F)MoXy>-7X zGTaGym)dGSb&qgnLw?p~IzDi?VEolyv(rF9`uxOb^b>Raegcs9O5mYw?X=0PalvwT zB&Ad%#{SIZN%Y02UGNRTbc1L->^r))L~MR^vE%`J-9#0pL1JnhPq+4@xJMY%S}uq2 z6l7p7IzxA&d+)M^nXl{Gg!jx`MzgZdrK!XdH~OsgdU+-JrKZ)H^XkODUQeAV-&XK_ zj~ZIOkt7bm-tm5FXoLH)BlAlXZd{oZe!FDG#ESW*_@k9%wKL=KE?wTU<*wm1M7OvcVo?QBGNDI%--h8PV_O{YAlINQ6F9uH4lK%Rw+v!q`DLGV& zZBMoHxYbpnfDH}@Dz*^S2Y8GW$=s!mnp~FSBn8T48NC(5Inq5V!OPV4hRAfmh&T{t zoi4Yjcb)`%d2+_YV=zUb%D< z*jG%$&Q=LF{DSrE=r2k@%iN))5w$tafT_<*%)xgUoqn2j0XAhL$lGu6Dqv19=`wnEI%`8u+M;JI|u0qqKt5NF!>s66AGF zOVl@Cb&@pivneMV2zR+Ake1MjtlS#!ZS9PdeqyvLy>ot4Jax{lTweihYrl-$CTftJ zyaU=NsO&u^WQVD=G4`T&Q&}8J@M>h=;#pQ3i;vyFS=Z|)X{57efUzLtsfIg39OLfG?w~irDJ7^wPE}oJzf4YQnms3YFq@ zy@m&Mh~vh!1BjB5GDv8}N)`2;#98 zqSp6p$WSz15T7JYyCvRFV=W^m+n^g`JOk!!!)BU<%Vc`*mV1TZ6uVKpl|?#+!$F7a zto&G^zVwxsd$^`k$4MM(vgPVF517GBZmPk(dDdCw6{0aWz+_XQvX6+fn57#`9RqZ= z>)xJ`DuHuQk{&b^`R3#o2dkgx2MZU8P-yDl$@!2%BNYQK7QmeHv0z~6BjbdT3y6uduI?TWs zdu*mrNeuDQqRaTZr4c3G=RN-2%2d&N(ugDme(jomRl&5C zDS(e~nZ$G;8IDI!Ymf*xDvqG@E#sr)Imj86CM;{ zTO+kN-UcidCbSUkTMv2LPcuzhOSHXYHfw!(DuD_kmz@hPC55@BnmqLR*0@1|9**)+ z`Gtlh<)9$~dSupEwic3vd;0vAO(Z!eh8K-yqfIM*raSv&B?Jc~_5>6KP*Wuu=@0ro zCDWjAkNuEs@vK4N=9Knx_STlIx}9UShJ{9&Ycal z*CkiIwWT>*x%0SYwi|UhQv7%a#-dLkJvL2NYjer4!EQ2Expe=@sY*PP=G$8Gjc<}M zIg%ss4c#+S?AcOrJvC57Kj7r1IN5OKYj>%D!yIE%cpST~n&T5gBAjP(#`FplGry02 zhxbC_zCT#2FS1yDY{yRb@;CU**Ki<;wA;@g?enXMvz!j+s(h493!HwLf0-U%qC?%% zfupf``X}z%f5q|xL3Abf=;1>O%;Xv_SU918#6Ya0DtFaEz+<5YaS2DcXQ?*=I!NVLpG%wSIX+pml~shf#hpO18Q*7| z`z0vj%Aga;_&(u*k2+_a7IgYwa4@th z-27u1w5O+4qtcs^hcRS=C&SKi>AdtCUS8Xqu>O=Hjq)bOlxv5Y0^Qe?dt3ma2%}!G zFVCzCK9DY7b6qWIg60n32;iVszXmOB3;>?y4mYwVi*3E8EKs?Gx3HwI4lsaxwvCxn zb9@#j^WC-C-MGA$2qY~S8*xWjjZfcdR=T_^#YxE_eYeT}(j@KnFn_`06iX%U(_6hn zJ`DJ^R&guj-cF)tsb9}UQY*+pl{&8l z(+NC`U@M?9Y3Vj$8cq*#(T!$yX8O`!?mHT<(!rJ{Olr%v zkQ-l`!ZumKQC37PWc@BX?e@&vVWSzb9dUhC?kRz^!8BQ=I0BqV>9VPrd~j`Up>3Ro zP0ICZ+Vxa8Z{S}lS}2=3O{aWH)HculdSiE|RQZdswCdj(U8*Ohr;n122M41YoPQI}bUtJrY_tmo*^?RlEq@Pfp!Snh}fAp8{B+H=VDm*CMmW>E*L7?U0($Sx= z=z%eEq@}wTMGz0dM~BWH7>fX%On`}Y0s2qvi$4Gu-E!eN#$MCq@4QB2c{)p33t1vGh^pGgsd5t^SKj}HLn`Yf+-BBafL1uF-Joh^0xH}ugcVn;g z<(!r;uTLVYQT(XopoCeOe(iLE{pANE+&rgn+s&?vvj>QM!K+is0t3eC$tF$Z#++v* zaSkiz3g{!n8|vNy-rIR69~@P8fr(n8mMMgMW7KO(DAqbNg?x8*o?rPLo4m;#$YO2h zUXGS3lv`N4AD)(r0u_LGmL&M-ZerzH&TAMJZ>w;sZMGQa1agw`uUvP_q&rse&h@nR zGjW$@*Z7gwb3%bdZAlG%hnn&F*+mDntf=z35D{aY9c*}Fd9BiF2rj%x7&S#gu0(^* za#}M!t`hM4ca{V!=5&_wWB~#z7o}tbNe395XkFQN08Eo|uV6ySwCME(aoHa4FoH#XP61D5U5 zU+ZE=T--Ku^q1(EBi$-=N?l!VP^rWY*T_D(HWneoZtk(Wa*%Z!qN3bu8r*Q?WXT1@MWmua{72t-~&1EcfxQ zR5r^MW?i$rFL*fA7G3WqEaYn+BfXvfkVmsE7H{;_@XcDpJa`<}Y|8=Q^4gxyJ_z@NeRzNmzr@fy1YHgm zygNjUD5ra#!}s9~748Rki7(wl_Ugy1Tn@W@x>M+45^I<{H9i}lOf}i3CX$0=Y9HCb z8f{xwpz1={u5D%BIhQAhS8Ptxzb)JX6-;gxU!j`ztt)B4srt_S2eV_nt9+Me*Iz`$ zvyCRm8YCOlpxG+-kW*Yhd+}(p=JTz6s$iV%gh%hFBUrQAw6WBMxdW_iuQ!TqM%3i4 z%cYibC7GPLi(QEZ@r-gqoXNQWQNH&wWMkyMZ^4%DR3pT=OmViLB#&^8#I92Jj$L2R zG?>@>mb@)Pmq#AfeAI4X-~o_wc&0eiV;`fHL zS7W2?sC8bgo6{@8uyD+~EByBM%qTQ_ubWoAR3|zFx3~A}nd9N*hn3#Xi^cIBeAv1dnDFxx)_q zrLhB$EBKuNHQa+1vn3bN8kEY2`RaJX*Y~H!F8^xj@bIRk!wR4?6$`U|AqR~jw!96) zq55b$F-MG3b2Bq@KSV{3uLSgJunF?fm96)lNm^Wdo$}!4j(?eYDv8p(lHCJ1B(yuX zyAI1jwl3#YK9?S+TT&SsPgH)_BXFh^a}Z?jOGdSsV4jQV_?~BuQ+;8ymG-)rUoIU5 zg=ITF(5cWMW^ZNBvEXt_)cx>BftTX*7$=~s0wZRLC3DJW_2<~rxkz1yx}5T=VzV#k zjud2RGpz>_EoY+@Vb+1$lJMHIF&$=xf*n(+p zXZoJQ=CEXg`!AG1PClJivgIr{P;=F7|KiMX8RT;5C^kk4GEJ$nG19zsGWf-pN_!k~ zEysIolI)Y}rwu6;?Dq42=j<9uHW!z#sNb?&Gw~T@J96wv$axMATl$MKZe3*eJ7)EQ z3E;7sw*7B&l2o6_!Z)3v-ZSTi+s^?}$%yQ@?aVWP={d1xaXeimY1G#`BWTNr9Luy8 zzxN`5XcK6c9Sk7AqUn4-l8MjivnA5{Sovf|=-1;J#9e^uwr7GKB(xsS&Fdsh=JaJ5 zvrH80JCzhRO~dAsw0r|tgPh>{lQdT`phVSHRSQdISf0;wATv0Omzf3=g8NycW(7i^@E>V2Fo0StEufyxy+DB%RC^=H4{gh6f53)0GPMtkb zRimB`yXL0^dKP3<(sTAvT5JPBB!}t1^!WYMgYPjX-QV=Dhg0E9+mtt0)q6?9jl*T} z0pt3`O2%T|cU9#$E+padl0bM5W)J30TQ^_-iThPfeKKnZ^vZ1?)I= zxH8?OCb|%pQ%dEY+arTJBPx2=db8pBYAqM=i}Wq7o`pAADnksB6*(c&mXs8o{(dEG zE%zRqXkY6?i%&O(yJsEO`l^n;-Eefr{?hNa-@Pj?pCGi8!fOr1`BT2%1X@_VUMO&~ ztx|~~MwV$t0?6cs^1Sp(v8Gb?E4;I-iL$=KBZd<=EK?ckv}9ZkG`?AP*!jl9E`M|Y z3$Wmw@8ghre?pM{%{`?AIRVw8yJZb3{LjOS}YO(B~;l;Xk0 zdiqcw;)Wma;jFU9b_b1?jA&=UCUg=90XA~OCUT6F@hv)E2g|43m))xhU%*(k2Rf3k z<(1j5yV8pGMGzlMwPxpmlAuR?W}f?v*E))@(ul1+as@XSkz=gA}m#BNYpv2tJh8v-y_Vtw|gxmf? z;~xD&F406OOz1}bb!-G81X(0-SPxGoRUt9V+pH_fpO{h_Ny<2rOt!)j+;^tP!2o|~ zna2MoRuk~@{ezq0$r9@n_Ws~v)^O#nQ2p+jnR?U<;ag|*Fl;bS%%uQ}<%BI*SVVk! z%o#$fpPOA}1;DVZXV-81vmW4e1@`MAZhN&bGA1&pL~$Y*rK>ono0T((cQckVOdG5> z#-v$THZVO#6;!M~n!4T_hV0j}DOOrOukJWsD7!Y> z`8tAPx?{HT;m;sM$P6f1GmNe+bJ|z!*}GV-GGdc~_y^3eCq*f$ z7PVKRI5d&gHRYgt-JI62q65!b^6vBpkv&Q7;(cw99&7~A`$idhtOdIMC`0ray5Xa0 zP%d`Rl({qIkzYPWZ=e}c(OKsJu8oSUmhesEb<%Aq;+0R2)Hx16HI_1thcO$On>O$$ zPNaPvzbvL5+x}YMYcd_x3jg+H3y`>MD)j1419;S&WR?z;NTm|LBxtjB`4dhDI3~W_ zg;-TgfbP7ddh!CJ*VVSOp>nu!Ov)Qk-s#c2zj!Au@GTOx?()jC521*e%uWbfU zQBkSa(8;^YjXHCTyO$~)>P^T+YB8lPOvnk?4?>+XIi4VE^UQ`HC?Xq@AxYz0|jozBsS=+a?UsXnPveQj! zWIFTM=w6-1E_K|??igtfBl$0`8!rH*o2!jLZ1396`X9=fCx+7CCml-89XRiIBJffC zmprFF*Ke>~bqJW=i|GKLD0Nh8mk#P`$B~0A?~Lhd!~$^-i#kS@-x>>5fqfZZ(PAE` zmYRXzp>=hENzHC&+oY1I0vS}CX}%gHwp$>DUeYyW_NQ%F?R>)1aS5@=3P#)QowPBw zP_yuK)RvZs*VVw$3US%8F&);QpylMaFZg^H15&tr@PK0tw3P^?pXLG5hOTB93G!~} z;hkk{%och*Eq(fzm9VddRyx1qDo`8(V9SRVI?xR}eK*YS{v84DbAHj2$4nlv+!f?H zAMc1{anpY`+0x%PiC#JgswV(%v3LNcp>B zzU7V94U<3V&wDhqt;W%q7$7;HHbCd`R3KqI;K2W?4+f;tQ~(ixAH>uVa^oY){SYmN zUz!hX4~ir^Qg+d536FkPhy`jL{&qCLKhA*I?u6a^V`|$wq`W9X91l$C+;AI*^JDYY zt6>`J-xWn}-m|@_y@$(xVEtW!{687Pd*U0PwW`Rf@GFeBMjk(YWQa!M$=)b66?@y-gn;Hv6o6v{e|$vgF&Zd!w`uEEUjJE7sdwIywa>*D zB$&thzPHc(ZZxAlGEzW3hOOKyO)&KF_pfn$@Vyu_93~6n0;S`}m0qx&#|~G+vZ>6< z9FgB5@p~DSY04aB8zUtCXI=mFSCcBR%x&WYSMcW>5Vo4trl}-?_EKc$$gK!KKtq4F z??cO!#1#v;*=c71%bi<1ZtEXQuh;jCDj5MpLTUYAAls&7llKoZJiCB4Um1h_8QI|) z*c0yw)W(VUT<4ID1EaiBiK}73%>#$;g5bm~tu03w3!MXZ3_3Q`y!wf}ENkdyEh$sz z)nv|yFVp2~2NP+__=1>;`dnRcs{dxgx919h8bECi`9)~alzB{Uf2{ihNS*aet1EW* zfv{YqPBoooOCi7^$_#K`7Q>8w(j8Mz{~X)jRd2yLKp%iq&nDgxi~ik=|7PR?fP=uJ ziaf!UOXd+b?brN-o*Q5s#}FT9rODnK>WA;J*+;0^;t+l@S>L?UAJarYwKg$D6JE}<*^)TDRl!D708QUiTkhd$8Q?RKW&GwlzhmLu z{HVL$z@%i@o_Bb7ogXH8>1L(zdmoQZKA`^(?cWuItK*3K!V_pyC(3^8?&$2aa~!(O zXD5LlP7YE5dUL=FiQMltjQ|PR+(u_F^uPH!TNQvpN({%G?FT3~Oq88+gQ>@xL#q4U z7jN=)3@$sE*bKVtW+$)_FsbOT=|NJhP60x0H+0gpG(4lX!cT&goz2U3bgA^`B4vCs^5K&?N8^(EuCx=b7X+-T*f53`DA3R zQ(iyLE2rT<3zlzIA!G)+@}<3#_xh@U&eXkqx1%cnm(SS)wyy_fm$s;sNp0%qMDRZQ zP3ZeCbNiuo!y{I`TF`9*qz6t0#Xs=TOit380qWp>cdVd{oR5i8&6aqMP&6dxYoj<&Ar*EqzT>a}L{w$f{90L>;$ z)F+Y%1kIBeHJbX8M$;`!VUqw_CcCNPa`xYi_|JRm0lixgV`6%W?eo{sDusHTB)xfO z2U3ybe2MI)Dng}-2Q{XH*5}_?!5ro|l`TicKt@<$->bh5&^+sbUKTpdtCmc|!o0Y} z%fI^Ezb~X8I>4%2Q?qS04R%oNW0gtgPy;`gw8|ap{;M#-TjmLg*w^&GaDkWNnDwW{ z^v`HBZKw};_K#8>JAl>*#SG&%RWH`kCL?4Yx$&R9_)rI;rT-1BSNF&{ z>zJefJ%^^Nc8f!$yi`S7Y)8JTa_;}v$@udF9l&ik`Y)Ae9uZX!N{e+w;>)l0C#-Yy zS$6D49VKfV+Z1Wl2XI*YaJVOx*Mmiv!=MK7^ZP>)`4y9Vcs?VR>NoM*|LomZR%ie$MoUQ6>m>{4S%w%wUGCEffB80DQRRb{7B%}l7K?UKiRtBk_!Yz$Ne0x@^+ zjlJ*xmtgI$>|XDtFN^u&k=ef>RmREzUY`lA5L`NA?$!Cg$mlW4iLItDm!6Ul+nPsb zS>lmY9*664D7==-aYYk7KNOdpDsHsFndTyvkA7}}_7lC}U#(#&Z0UUf<5wxwo0#b= zksq)DGl+A6z8w+QcKJPRKXM1`#CSTJ6^GSOG?ffw1GbuJQtg4z(V+=IX@ExYBPex1 zBFw;`eo0rk#>8ej!lhtl>Jachlj@6-qbFrulog&vYHCidJRypPsHYdt@6B->S~H7)RA z{A&M90^HaO-IR&(>nV3r6@2?Os}5Z|0#m{`Q?HpunNqG9sVyj{ipzFJl=~w z`RTX({IabQC|3+{t^9nK|IFUMK6sb`c={+&KVS97t+X3%K+V&CR;m2qe;2sywS?%e zsNvrp0QlkjHv}Uq5v+f7dVkz{1o)-UsE_}btM0n}e}2Iwzl?F*I<}UK=P00(OL^H} zl^A$qLyzvw)H~`wAJ8rfJyT@>`aAKH4n4JJyFS&27=NE`22=P;thp9RD5d9L$D@Pp z#=D2sNWFcV-*h$|3O>-(k9@AYRt9mzzqap^Pk52xH8U&k1r{yAblpYkUa8*-I|v;u z-UqLApM{BBZj0(IKu~?V$vX#nb9yJLiwZN8i)yLd+0whzSHDxPvdqz|m(Iq5U#CO% za~`;rubwK7;m=z^TFYjla9%s~Y?Z7AO^s3U;l_S0$+AD#Job?)M~Y-Wd0(mI{3)l1R3nvvL4 zN6OvQ&V?(BIC?Ea6!p@rWxb4PL$ZZUdK@$R_MDFJbMN7*5z*NTc264VX%4z9FFNj9 zx2QdXBhF9J9`i|-&{KoPk1R@r_mLUO%x7!9sq_V5$j5Q;dE#2?PU+Ocj4R~^iEwUd z(Hx=(*4t#a(WSR`Mpj^)f{kt$^`4o=GP|?a%@NzX!h5ynUH2$8W{#RI*bdvznXRdw zdik?)3dFw?@0aR~x9#ro32$eSVg6+$f4c`5v;7hm$SQlY`h{6bE2Cb+#hc8LaiC0` zqY;gts-)}Mczh}mLBeNaaypR8474Ksd^{yYA#g9de}wI8FDd7zf+|Zjx~~rQIYR03 zEnqq^?21=smA(C{BIMGQ`lZwI5h*WObhXr@<8AeGeB{>kho#mZ#JaDJ-X0XG>fXoeqIvq|sl&yJ zq-M28>fzRiNC+PD6FH`5TfUQw>5=K%3W0vfsOWrqGHn=j@PSm-X|AIDAe+YHUD>m< z+L($rTRzf88^zcw(ESf3mvv2#rm(l?>eO!8l!nZ0FXnn+M)i=IE)fFa@>J*U6BEfW)2FhWRPHl z*iW97g6qZ&g}Z(iN#2>q2J>QScU^u$c0?JO8!sh9FKs1vXH;#X;17w{1AEJGwh5oE zd<~=K%FKrc4S-e|D|Y)EI|}+tngRk`Z z@t@D4_vf=<)YXq)y`{T7Lk8Wjk7oF$CS$KMw6L_ortY2OEMprA;+kHa)$8 z>H0C-b!q$HJ-(f?x{c3;8f@Y!fk_gFMkyJq7tz*OVcz)^#4<4S7@x{>JWPpJpUb^b z$=;pbge|DzI5jFtL9-U_I-9(6cvi%_wGn2%g0?)#-GdA6YcWTBC#|7$lp8~uPi@YQ z@98toGQ(WShd^%wk8BKbiozK?9=gD#@$Do+d;04iOdRs`86kZeBu4pdfOlg%s(X{V zJ#@Ffr(l69Qi5U`Rrw>WW}P)$2-?Z#I9Agh*rM2eS}o-qb-yli%@oo&}fL zgdl5}yl+>jcPG{BifpAOJ2`WO$|@?kmGiy=54rTlXRV~X)@4eztvZaZbpsKXe))hU zO}pt_y>yYgPc*P;nR8!4AWK|V)Ugh61%H3xer^jwPuyfGEcTgkR2c=yllv3%@4A{8 zoC_g1=~Tg4W83RjWRs{i|bG=y=BW~Q0*Y1k18Cq9<2sB!5qZnaTf?CsF z%t6^ZysA#ZT+cP>l-bH+X;XT2_h|Fnmw6PLQ^$OR!q;?}HeFY6m$?f*?p=JS&7b#! z@?jAT%+c*Z6SR8b`|>;`A!Q)iuRJqk5P3HQ&96BbnJ$1MWNCx;z@T$4Ms)1UH+_p> zDLmvr@MoIj#yh*nBi9W+gM2DBff?om&e!pb+JH=*^ojYN97QHTx3-Z-qaJlw=`07s zH=MA2#g^x_Fe)(k*I8as-=r*AkKHSWs}bKq>hI zrKgdyM2pSPaFQfzGf^EyY%Rxeo~Oc~n~P5K(4CO4u0FPiXR!Vw)~)ml^8k_a zrMSjy*~kqn^VJ9sy*%$}F}7@Jljj>pLG2eN(-)W?XD{Rd)+rCpz>evG$HpN@&a8i1Ss|8HW|^vKgD{N3!)!8xx##R((+N`clOCRp;tbyox&RD zQP~&9%i-GRyz0fXTT0N1DNy#XWvOG&9JU8VdKglzqhABz5GJ)g)Y5Rcr3N#KnnDOK zQi-kcC|HwToN=?+A8XZ`DGYd($#KrqjLq>)`+VM%ED7kKxoV*5u{Cb(IJPpn9niV8 zZ0F$e({}Puh@uAwQ8Q&uPO+_yZ9MC};Dxa)>SA-2vpQTh)6e;Qr;QE|>!|A;1Zb#3 zaH9+37~CDz-sM?kjR$rc+ju z3Y6{$dQCrlJ6Nho-5tYFdEvZTfg7s;n!&OngX28>jJ~g;kfX9U!#nxOgNaGMQXM_v zO5lYEnC8Gi%@>Z`plc(G=*8ar)%~QXPF_JPfr7kn19z zuB!~%jF|kTTwvIlSbA2}Q14)w7TxT!UGBA*w=MKRDD6V-ts!AC17Y2CqQYv83=#*J zn^-MDv*_+jGYh`Y1L6+VG42uHm_vdpA@ve3tx*;hc{3?W&oDA^=`f)btx@lbozOX~ zYvQ+ew46|u$(_?Ia6^d@%?vTC{1~4|=D5TvOyq3wLdUhxhSGiE-bGkP82J>*9{4R< z$60dfyED-Uqj14bk~VRneU1D6dl=O6JEzG8s)rwmhb}=cP;FK>3R@IM?`E#XXNg7j zzh-dRGg3FcjT=xOYY&Cc0podtwtaAW^0e+ExB0% zjOIrV7minya|gydM{W0Q^7o>ZA*>^#djR>%*^?yr?l*LQm3r;>h1X%&saOzV!?2T= z-e2yd=ItlDCa!?>>xXD~1s$VZGQ{OlT)Vgf$txo+4Hj+%H8q|D6gO#=i1Doyq@rU7 zh;Z8oewsLz8OzO28_|>BeRFkwkyCV1OVhdT(oOGu#Dk1D<^6g<02*Z^H?j5lSQ~NA z;|E2RR?H){7PfMhb{a2BI1|z*64ZMdj)B2+Y-*cYHl4M(-{G)zoI0qJ)3EMw0NEn5 z@KSLtaJh`17g=MPUW#floYgBT*{qX>lxd$$Ts0FGrZG5Q9>F52he6f^?d)34-i;l5 z4It92;kantpmUZ5(@&k59S?KWJm>QHs8kTiz2$-|TJD8uaa$)znpj(M8}%HPhQxkhqh(nj~S zrwjvkZ)@}4e{QyysVEiyS-Y>s2b$q+GnOlI0>OyG!hhq{T#eeJaqQIy*c={ zW19r4Oed>!PQR9ZyKJ76Z7R4zNI@Y=<-~Hu&Z~vLKIhe$1CB-Cb(O;rQT?Ioq=JjB zS}_Hv(bD|mXpNEO3Vu#~ttV|38Y zl;zG?ve{6TO~;HCAtNj2N$jK3Atbwatuu_F*kppv@b;}kej6YyvN&o}bW{f+m1w-J zAmgelF#?z+9__G?{XB@H!o{Q9KJBs~7_8nRAH>j615FEvbZ9;%vvCgRDOwFfEDSP_ zg|0TIu{%xcdp_4{Mpqq3&3jNgwo&Lhl)bpiOOofZ$~eO~E09(;;z}@4y8143$FR&X zf>p<4R-B}Cc&^?0;&c3Pp)gudZi2{*!Z}XQaj&JQwWchOVH1`iMVd}gY;I3%0nUq@ z%`szrfh()>u=KNQcVS8bB_&esg?A0Zl_JibxXiG0IX!a>!8)0|BE3wD9Zn?9A%#Ym zP!8Ewl|lSt3h8qi6;G_oJkOhzo<$bxPY&et zuyKYhW`vW;ZPuY+$_w9nEE#hNErSB@Rs$KduW}U%y zIV|%1@-dfNHh5^ndpbZi=5BbpeyQcr^#UnwqUtiPp8RdSJ{MbAgxFLjU8=9u=*4x? zVy#GCvHQ1UTOyObjpG*v20kh3B7NaRgDUjuv^a}1GDDy|_weY;HXAbhRA=LWyT^XX zjo7_dB0Q?8<3*YUkJDiaLG$sUi~BOFdm?1NVdgRJcFNUv?1sKDMeCe5 zCF|JfQ3=sI)~?>S#Sx-`PBLtNP8Kj~Q`xFF^+|3Cl=bZS0+gEu=y zJOYTR*5Zi_<(YN@d8^UiQ4%RBjoF*-8cQZW&zU}~n+%#zJ}^n#h48j{b&g)V5!+RQ z)X#7G$NMcG==3Y*?AcA79k3Rh$eAZzy7NIUx}HzITer|-#+9+x+eQ(UKVUC3y738PH6oShHVGm99_HC_v`H9vGoJ%0LP>_wSa8GqI zshFYXe0|DX$Svrww~&TB!@-NOgDk`PSHl_Klfev~Bc>JA5j#B4kUkHUf#%7%cBt+T z)7@R)5LS-l781`-7Gr_l!`aKC2W*r&*qfU20&h=T-ou~KD-^+LLE_0tG*&=H{0O&p zAAwREBPcs4Ovx}Znef6h{E)m}f~Nif(Nu4TQ=2RrM72%58G9$dw=@PeL0%MdzKjOAERk7RMHl z9g8!itQeaOg;PNRXjh>xcl%`7Uvxi zo9IWu559WzxYHldZYX+V^%;~U+1g#_4$P$WU_?#5duK7%qc)qnxnGE{@6WHP8^IY_ zi3HJ+Lpq}W2EP6Ux+>n(Y^iH#92H7DWZ^*P;*QU<0u>fh>dfJvv5BV&HI2+Q=H(#; zixV0<=(7+j%?b(KR#%b;?dx_^9H3Fx!LZwVvS)JMPO2j3)Y3`cmJ~#Y3NtXr*i4Kq8D>WUH^1Zt8dS2h zlJhckq!?A0j@TX>H_uiGy8{RP)lC zGzF)$9!BQBAsWL`Y%6hFOsO#05IRtZv}AvgaVrs#^g*!6AmH}BY_hpv_M{o zhqTK*z_*QKzFgfjy*>uI;$Pc+(vW%y1BO6D%{BBVQY)%(Zd%g63xK z`hfyo`3+t|ihSSfn0{<)b;$4eQfB7ky8>1(ke@fqSW4i!Qs+hdp1$|FAmh&p4ItBrA6aeD=8wJtULY4Hj_pCC`sju zPPG-%B`W_@%Yh-88Frm}uQ=ui;s0UpEyJSB+qhvx5flMM0VP#RTDn6)I;3+zrE5T7 zh@nM6N*bi48M=oCML@b4I+Pw@q+@`2FLw7n?!9*x_I!S%NA`Cp5p?HqS zNrPO?!i=(^Nni;6Bu|h)KBn4p>PBm(QnXye(Sb~mX~=wcATdQpiEon^sOk7%g>81P z30FHWbcP{#Zfod?OPlk@$SB4L3!>p##a({2&R#2j`G%#k<@M#$ZKO|QM%~OyP)Pie z`M@v#?R&1sL~4ADE`2YE!4kLAaKyj+J;{`lv}4_U$zrd>Jx2xgD`2x8!{}$k&{fMe zLMz4sGWB1MH;S^nUU!w5_J}Ni&1IAsf`F!y;o8!twQp(y#0seBvA1hb3&OwoU3YmU zH^Zsh0#|*E4P%N<8Dap%KOBe`>zk^3Y3jNSa@CiRliJ&Vzy$E2O)gHx>UAABlrfI0($}?` zqvqqP!^@tO9I~at{gswZ1fAg+xMsas%#t=~rXU}_E)mp2iFmqNN6GsQ-ot%b?YK}g z&w9rxQ3R;+uAeg^49*jzuHb_)b^bkP+kflH>5Y-RPQ76y;PhzMu@_tI_l|2Gl5JO1 zC%)`DVAMSI@%0C7P0=aDiB1SEc0}iG1cv#E*WHqdu6>?!)VrKHzXy%YAJ5#@h`U}k zqHS_2d;*W2&YYoOo|=;C^TpYSn99PwHjUSD!KQ5({+%xhqf&>^&@XE28|10*-ov!N7Eh7?T&I!pt8Cqji9nN zM#OgE7T1iA03M$kOVtwMj%Ky2!$?h3-i%Xzbff)=L9Bap-%9#eO)v*0dBS~3lBUUe z7*^S=mxwYeN;OMmH63Lr#O)7B3&~NC&)!tlRxd|L8{}gQ1*QJ zdq(eDu(wOCE>Ip!;-Q_w!D4LQU8Cseoey1?N^PX(H#Rvfw#Xyqw;D*Z$zei2#=8uc zR!LKEzx6~+2?`9<{;YUvKea2ZK#W^U>4JEDA8_1|KeLYdT#C~}b4@o2T z>dkc9azY$Pi{9sod*86j5f7-&`P|9yGe!rZq*wfxxsc0v5}-54LTeT|rHjS=RsBZ%jq)CQ{{YBzXh?BI@QXF0$16B=^X*%AU1p z&Q)_=)92APne(x`x?vz^1#bATU9&;25F#Cs@MAE@AG(+5C6wgV-0iO6?|Ndn zPGPt0M|hbJ$y@T*8mT5DVwul9Bq0R$Z2p>sDq7hEdb=U=RM-1SM@t;wH}7+FJ3Zg98+j!a3~`vT568-*ke>6oG;1JcbDArPl&*DZrLTel8+Z@lBn$Z+j1 zYn*18!s$ZP(j4(dC>4D5Bjggz2Z5ebgZzjSj32G4&kg3+zZ+c_on? zXECjvBD@Q~M_oLn$x~`*q|%%hC$H`w#T|;`SjLN6Y3!dI-hN^t6DtR#$xvZgeqK8x zX^X#d$Lz~}VPvI)xHkfB*9~N^{1#C|&b{#MzprXP6*H4L?Pf#`JM57_2vBo-ZECIz z*cLjJ@)MTTIG{LS1Ljp4N+NJR@U@PDiH{PbZdNj~kVia{hTSCTEE3T%V$Pb?KvK)U zoRLOPeo(L|*ScO3^7!fYK~Dbgt@7dc;GylFxVAhqaeP@THey2$m6-0+CKGdWF2e%q z{jdnY!}zco7O^_M*8C&agGU|ZFvfKs)lKZbw2Z({>DcZSDF~Fb3g~f|J^lzwRUCfZ z&})gVWrucJ72SQ2Fp>t0_2ZEtOo0&%^JK|Je;wz;t8rsbM{aML1(_Uo6=Q6(d({3& zO)WC&{N1m-3A6wPJska%KXQ*v)$b-X9S~;~Or-ayapcVLvTcv$gG)eNga*yJBTbka z2A?;?i%D>1C{zEz0-u0<(;{(=!%~B=;gQG5Q*94nky_h8o|LGg@1m|7P!a!FhuNp8 z!$9u39DMAj{utE9$qlWL<)iV2dm=skL%U3U=ph}ljfI{OtYzqZPNpSpBrie>Q_YAM zV;u=3$pxKyX>vP z&cvr;y;FrKzjnMs{Uu5@>P|QOP3J1!vItJPZMhR?xz1XAL%ztmQeLQ7$1I2ZS!kVY z_beQ6b49~&Xk5Qx;#Uy&#yyf9wO;l3A;vD2`ebgiqnjfxK6^-h}E2XZ7v zO9<|Ropkv;L9GPfIr^nn1G)HU;~#4k1YaIGqrNqqc*zYaMN+)QVd57yvv%X~3mhW$ z6xsCv(rugm(HJk}$*IHccGk@i_O+!56ywu+cIx{Cr}AEojA_$temtGa52{4Oje6u4 z8E4ND>N@a4XBem=qbsGaJ##vTK4*5gucVXWEtM(ALl6-~DAY(3aEFdFaXi%3c9)Yu@%_MM?nrmveZc6G?Z4`gVW1mToT@_2@ti+G|?t%usMx zZi-thR=C244TsN*L)KG9H4=U5JgF~E*Ek&rRLbe$*`YZ26v6@q}sO}1>2Jad})<8ewI8k;uoDN`-#fqlibzsTuabQ?v7U( z5ZtxgR)4DAvjQu`Sk~Maq2PnwgY9x1C1-dU&*a4Cpe=8PGPEYTMLcp zSe|1L-=<^`<=$%+zNSO1OlU!DF6yw6I|tQK%~G)Zloe^MGa!Ah2}-o_l<+MiY%y_@ zA_twq>~EWIy%br@(F;2bo12eoTsUs=qBS~Fk7!xuxUV;Jhd4~w{>NKdg-=b(ui~B$ zWP5bf1=}Go`i*pG41ao2k#|2AmrB~Zxfr-vD;>34?bzQ^(xPW6=}_k+tG|Bozq#vQ z@j!u6k&5c=zhUG*mn@09pOs=!qXZFWEgOISVK{Ex03U%Eu;CoB0>{k*!MCM)2$>!f6#UvPK8Z{Ab^3J=`tkosH~J*Kxe z0+=7{8WIusx9G_KQ0K>4p~8U+qT2Mr_qkkj*6>V5M|@tH_V3U9O&TE1=4PQo_r>pE za5j5`M~>;@nZ+MM0fPMa30jK(t7QC{)Ic>iJy0EI6{Y^}e^2T!F@{^zKp?QCt+t2f zZ@T<{{?0`as9-=mhW*PbjQ`V_Z(Ym|VLR2p+8#k44b=N%a0>n8#b?`bDKN;0wZq+a zqKER&?PY)S)PPcWV;~*{MUUm*UjQ;{AhIe)ptaYHT_)m)Hl}9Suw?5Dv?(Rkr|r)a zYAXz6$yzMHLY5N;Qy=|3Q~4kEO3nc|i=l&hH_{fUdmqV1KmAA{!Un%`1@c@})_r~< zq9xO))|pP?XonzLIbKlSbHc0XVYh3xYvi>p-D=LB_BEPY>{l1r#vg&uy@LorOK~*| zM1I8d>CXdKMva1$>B3FT>zgT)&uu3#?W*PVlQkY%4A>MYW+oMDg3n_-8l_Q~s@KJL z**-OQsFC*zWJ^3>J6EiQRRG3SjuP8qAjHRy7T7*9*&JA)BBTlCn zNE5=S{UGJtRsZjskqjootB`>rWkN>Xs<38k031Xys>45Y4m(5SUWv=02?fRKS@|)+l3u1MgQ?WV?#q6g;FlG ziB2Z0>7n8}aGPV-?e7P@(pB@3-s0|OMQk%EmkO!R(NG`G3hr|zMD}R33JjPdv$_YC zCW)=6rNLJKrzI=xr7&=R5@lQA*pUAbs{az+=DYyO-Jug3ot2L!)S6J=v%9by=RScUssGKKoR?Z~3&$VW;J4I)0BKcjGkReS*8 z)PX)(TICI<>Qe_QuQK4FiB%8Swbt|CR&^TBjv1WaSeV76tuKtM*9wZv9tbmIrZ&_T z5>QUa6Usclj-bObJy%N_!6nC>59ba?_hDcHS_%TTq&Mbyj>(XR6HNCmm!|BWJ_4iz z#PmH9?RvI(Zv)$`m-`BMj~nfDsMRSKT1ZJ}F_5umTzUHgAJ!M3gbZ_f#iL$SG=L5; zlOq+t6l6nN2Bip@2wElM%mi|v08-Zc1Bch^uU8{jEQq*t-cnud^!@y@K7~bxDE6g` zV~<7BJN)ysz7GSiK4Lv!=B>2Vf3j{b_zjaMRa4ysPEx%VR(b4KP@RGpAUKp^2Jay- z(P&!#*4~&gFW*8dzi2k^a~qf6>G&PR(a#SW8%gjyne08Ad=K7>jnN~ZhLxm5CI9j5 z-%>T^rWKivun5lL8Gp^t`@nXI!PGorNA&AG_08RG<7hF5y~Nw*oh$)K&?O3f7j5W1 zHOrSTuj=j2Rz(UVLn!uoa?gLk-+7!A5KT7P624UXkQ&XO4WGCa-MLK4_l8^jLiCJx zs$>OinxyM9tm9M(4wIc4bShO%dqAJdgeq-Vd92iT)uSBGqu=kBX8I@I7vr%oFcj&P9Ptt4wz{L)O(x%b2Eo!*33x@Zs1DjXmOf{>J z5?&PHgraLjo!sCTTDsge_rR{47n^RXv!)C4+eo@_!T}pp?bk z&y_OMgcsuxc^u*vysBYRsF`X=Hyjl-}VvgE$LyT03iLC8Bk z=qWPAcZEr+xGq{4P6=%Qb167IM%>4|euc3uB`~IUB?t&i&L*;b7duDq|Dgb50Q4F3 z2yDGJTCL|7e9weuZko;*X>tLYpcUnXBxNq z4UPC)D&erTu~L~47M*Wx46@dB!s8cWu>TbL_RCz%cB6oLWUZXOKmPt4Bl5dBxy5j1 z4Fe`5X)b26*Li^58iksflU|6J#S?D0hw*A63%-mw10d|Ns9Yp4vf39RyuTD<7{;#Gpjs`80bn zEbLabhtLbvOlSwAKj>nykp|S{^Vc!5a2z4%Bj;Yt#Y*9FEo}(nYIbCovLAV zSVVW8`ufkWRc~v?0dg!iHI9;rhBN6}SpOHV{nJm9Ksyra>vV06N8H@%I9(*{pp6m` zjX!?W>*ofJ?PAWSZ+CzV@cNB!n(373<~t4(6_TEe+fW5uEHA$;|8WkefZ-jJ24cS2 zI-=D>c^h?yGhh0+6A@87YEw>*(#S)|Hj0X5n9n^UKmZHCDPc1i6#&F78kE1w{K!N; zHsWlWdvz zA-U?Mqh22;lC3w$?17aTD_c)(lXkzLDKi0ZQ^hPrhPA0X8=Bc^Y=jaWpIs;fne@6K znsz!-&f&4OjwC-99E!(x54FemAh{Cp9!u2-W|>Tt^x&7;WNxL?4G!z^EVlh}g_Ht6 zBFyL=`Q2X-9UgqD9XaYtYbmWZ^s<_9l>oJMf&>K^%0kaGBC{p{JTtf!(!LsBKVbmu zO<)4{iG=U#^2LTERJJRnufFKV%Y+ zAX+28n`e8eU?)8j5dzy>9AoaQQV%rofQs|n)bPg#jnmAX%`Ua<+Pwpp9koto0_&im* z_Je1atG%{k^aUJc5U?xnq{71faRc$0je1~u79z4NOgSkdm#%4#1|iFg|9@;(^h#<{aSlnY=Z;##Cja zd4lMxNN+vpB;y;d?;ElU>4t-y?&WUw;)}@)aKq^GIMy;8P;g&E_9#|r!oJ<1JF`I#c zZ2~4Il^%8M2I5@oHKQ*%H!}F)A#nB_SCQ+MzHi@V)ELtETW;U4w_u85XGndRTKZc} z;l4>y(OXlI+WXDZCth)aMju%WiAOr6=wP$)hTW?XhjG~pfXg$FhLCrqr9qnxO*_oj z%Y4M$Zx`cC%0ZA!bV5P|EiR5Na$|kz*^4<9FB^=R)sDi=-=d}>VeEA|oekrSDR(W# zz6x$khmdoYy}O;k74y14Pkt=)tDk4Zjdx`w4nyXLCPz0xY2DKz(2YvFz{qnU(JkLI zSaJ)Ipn-F3I(!^IUPmK_O+)qC9=eZAR26%E+;Q0wd#d4+h=#id*UHvU21RGwT*U-_ zDSJ^;-uWb^VppWoeE~u1hFk>DGw%U)s_1FHhPC+|s94EsbdNhAxq);wHE4{tvT=eH zKbRn=@ss}og>@+AGqf=SN!PrBJ0_A#9eZg0?f|E6{beFur>8H`h7+-Yaem zscnt7ojmW}j}i8O<|!$Y`;)SVD|(<;)|T?rV~EzrWn153Q$VL(1!KfIJs8Ix)taj6Kk2v_AYhqYE;>S&mAK|D{4U#q)~ zrB1zRy}~CV-W~n6%7RSOkX*L5y%jNS&yy2xD)1J1AxM8q7HA-3174{fjxsY+s^n&i z6=rlcNYbow<#M%YYJ=)^H&>RwGODigYMj<`C^uo(lRC2k*Y7ZlScvT$y(k)f5}g~H zux-E4_i#+)Ra)YBRl9(^fq9>J2jTsBUKgkRBgmoa)?EQ$tU?Zz%O2fs*;wX4HVs`+ zyw=C_6^hiELU~-|%xv4Al}^RUS#TRyduPEqwu7Cld9=csoYz@Tq%nRVOJnp_6wt&# z<12Qk5Ub@-3lo@5B#kcWfSGg$wnRL6^=#?U8qKd15(*E{G&j%^kL_Ne)3>yP~K6%hpvZZO^Ih#o<=jk@F+#dU5QZRL0# zi;(xj-hh4Ese=6@Vy<&QmfW2A_| z_9o_AGUdkJ>K^4n5w&NZNxbbC3#`lpA1?e4D-Zs#ll^D4TOy5Z&>dyBy^f|-nq2`m z2jlBdwxq#Sb}NIKkwuHWcDN%a+r5ng zIW2BSRqn3#o$okaE%jYL_7xXC(~Migxs0|SsTS-O+~}1eM1C?XmrKofG2Gws!)J&2 zIZlc=B`P_SP9CK?Qwx+j#`T0MG_8M065_0N)VW>*>HHL0P@_)8*P1Faw|>lNl(lxu zl7G?-x8}qGk9}oUI(KC&(24-W4DbAULq+xaCixQLb2U%s1cStp{M<8a$Q@qrG<{0Q zb-ZiF9br#Ny5d%!umJl;H9O0793W#`3mr1bG%uHaMoMB~f#qg=nt`Qik%Fl7}3UX-`lXOWnB;-$d zZ5xiQuO1GiEe5G=w~ob9O9ykmeFM*Y>3g)b6ZGCuXt*x|@sTo?m{oUGU@Ag*H>w;x zyi9DRf92mec;X(+wXJ80)A(C+G9M6{r{$;Bej5^sUgWf2zQm|mUR<4ra7Il>5{Ast zhf;~X%FLUivBkNji*~gaV~=e0wEWHJ5dlZ5{#kC9MGXmTR#=^lwot)LnEc4Y(#IGM zQP>1oA;PVsKYo&p=vihwLSbeqZXRyyx%OO!UoxsfU=tg_KdLzt(kUj4FcopCiY0(n z+4bn#2eL{!U?G5!XrF75&*z3Ddpj&S)^>jjq>+~KseyEXM$QG^9A~53{9YQBj-Tx% z4Vz1+on2J)AIzD1gtLoc1>)&WGJMWd!nh;#vz6ePSM)l__~AU+iIHx)H$T2l8uW8q&<%Hu1kUHb0Sg@~V*Uw1yRgLRnqfIL@-eyC7^XX|?O(}w zARzWeVAr14Vj8s6=G5hL;&f&A!xyHDOGQ5!iX4$l$|gP5z|GQ`wK{CemO7#({PVdT zBq}P@5rq*&i$bPER_8f+KKITtl)hCQpo$w+lp;>ghF-oAa99kxxiTm=z&P9&1x(kE zE?Z&)!ZE$yfk3xx1g$L9iuR3%zYK|i!x5wqeH`HKKHnP0b=2rsZ7-Y4qVuS3CxMjh zd&r;}?Hgcq6o;XxQIhaiBXyq_>He!BWoC50fIyG!PQLtMc~M4ByhcRUo3-J^!qQrV z?e}iHrQMR%I#}@Rq?(l89eTO>LVk<$kK+Mw9M@jJfLO?nWbayUy~)}ey60wEf6)Tw zQRF(LC*TrRi4qV-$*-m3J})8nf$JSJ-r)I=HlcLU{pR3EqKetx0rV)t0{@dohEAfLays`f7PMhjlc z)D-2j2s5)n=d}g4YvJ-+W0<_^sWIT+KGhCpej+Yl*2J3VgI>u%q`Tf5>_+0b_5q) zUc8A`eAe_UE`F_nfdQw@qP|YKux_=e4&0AnPy*WhqGZz1qzwVVw+UR)T(ydAmEL~(IJ!NCLZ*~Kft%p{E-NH*f! zp&0mvEgd+KpVMjnmTc7HRFKv%ZWZqBN2Ae)kUq1f7h|<3@4`yQQ-y&0Tz-bJc2pPA zXI2c5#1}gn+JKJ`oUl{7@dlVxM2mn6h}P`)rZk4#(6B-}*?XZwc92uM=@S_jUhIMJ z^;=c%)8JDL^2!39Kcc>UB$g-XP9m8Nx9*{WtZV^Y65|RUmf|TJ5!(rCJ-I3uZlHfK z>wC#3f$&M8wtktxooY8!!+dY77THJ^Y9OvDQnYu206xn!Z*$v0Le7x4Q1mAl_` zCW1HH8A=_$bX@`=1EqGZU-Z1VVBp#v9RWieRz0ILAo*am!<(2X@=?-=Fu?*4E0ywlvnE zkqJN@&3RgSGp*E7N)x>kf3!e^-RQB2IQQtYs@m3y9I~&w{ zvI0CrLP$s`Lb>p5#&g%;z0rj___7!7t*XN-?HajvnNNZWn9H&iBP6ejRZ!+7g(Se+ zi_+UxN)13l9s8~h6G?p3z^?eGt%`}cLF47-X$ViQ6tnZn0e;ugOEZ47f??i>a`S~sUy~C;9a!-LCJX49LbKHg)*vWMbGNb&| zqR@S1i`ZhIw4SXag&n|KlRfV79v9Nb=Mq34>`TlUd3&ou+Iy738MP&z!>=cfY(_jO z(fjWl*GBZHk9Za5b7tr}jzSV3^>e;xU?o*tzT&TcF>B%gdtQ3`-gvihpE_###DAI1 z(RxDl25FZqg3=+3_qB{y`>}>p?e=QZ)D)XtUcvhE{ot+(3q~BTjaiYmn#5#Qtn9lgHS?V+k{RtSq7RO_g1}yvRPwhQRbs9>C z4lWGm9Y3nb)q0a7arr_+>W#t1ojkT(AmVXGjWL{DBZTkL0jIn9Yp0K9B>%m{(S8Jw zHP9wp7fpa~JYHfq7%*|jR*q2?Q+(;1eC1-IdjpCFyQ`DV661E9u|v+SpDgNTiby%w z{2`k{l|T=x)9kmtCy{WaVYhz`1VlZ_g}V1*kSWt)c|~ z^9H2;es5fBfPtGxGDR*vOFKG%AcY2egh3ZmWE7yU538Kp#pIon0|=sD52hlyNcD?9 zCf`ju{|`-ENJm_Qe!w zA_3@Ytuik0_XqmZD$&VCcGs@c=N&a=7+q$n?Kg^-5az0#m z-m{MZ++$9}BmB$eoa&gbd zh6)&GjC)t@@UbsumiG z_Tf$oi@v$h9r8)>!(GqU{sp!@1RftJEH5dU$JwU~R4nN%A7ajISQus8@#(3si0}e1 z+o}}WeQjkrv);HfVyqC!I_?zXu*AMx$`aQYF(5`9Yb<-G6Q~n21{Td!J^-(MPu+Tc zRPKbZ|5I(sKTvSC3{dR7yll>k>w3ercB8*<7CUrTrOexa{Hi zPkHbE{_X&<0gLeP&Y{PkhIoUZ`97(K4t zj0RSREdOv!$qqM`jr>0CfdfgfRD>T@SjoIkkxyVZ`WJ{rco~aN%v*n<96+K`OoqdS zLiY!!7=Gy3Wg{{vfQ7bL$;ziVSN&SrY?oXjSmES8VjLLVgw zgi1yQdECZnWutznO_Yp}Rk7u-7Y7u?FK_Co2Cu%hN^wI%{%G+-MctfT60HQ~I%2<*rl zSU_sAn(E5pJiPHI)A4s`xCBUY4@keXTx;e_DeAMys6dY^B_x!w>S!!d09yi+}L zBq*iPalcct(QLj(V5dHkP@zZig|jxX6~4kjljt2WrPP6&dppm)Pq z;<#4WfI?phzmQ`^R32p1R59T(u;^{54N*7~c1=+ac>>HGmyIPTSZH&1-Q7%YQ_jGA zp0ockWZ|KoFZ0v_ksCL?gmbZioHaT4z*)e(f7I1F|oA1GKWV76aeD=J1NG z*sLApvbHUEs2ny`vhR!J+mKCdQMo|+RB5s*VyFXN`zhd%R{$*17JFd&I zxRW(|aZDHrA$G+C?g$EjQvX0LyMtf1|iBTnM`J zCqu79i(|xy*2^SKPH^HUPA{mk7017fxSvxv`*WfNA*(%@8oeLWsb5I^>S>`KFSq(` zLeIZAvB{TwCZx5Asywbz#a{T;SCZaM>of+mz}IKrFamn$R^Zi2@B~BIQb7bTltLyY zne~}UuWwc!pgafiO~hQc_X-@X^^`eH709{y(lq{2z@7!1-M;Rz*7Zq)Iu|-%e?|EB zaGFE31rU2<21}iI>;FWx!j{>6jLNh+w)OVckiY_qYCS}Z3^;tfQ=s&E9du72ttFW8 z_9MyS=#o26duiCyIMSlP0}797tH+{ix4zUP5%a%VLu!Js^E61|IV!#x zwYD=g@{4OG^8=a40k{_4%1Gv$ut|nuatPnoV%F`&4=w@5%-S-d^3hB$Y*os@W;(@o z1$S8!wMO#eDROKE@BO1PPE|ak)3mnCHDHeLDd3E4#B!Mxbp*v0?W##~c&a2L6WB9l zeK{i@cv|~2xc&MC3r;Fm_?S{>TuX29LzxbVNRe-@$)tmpKPEuDxaEiy#8e)IX6O}~ z{QSiylZbASfnZ^-Vm7I^*4nUKyoXYh#f*?LijUpUGVq(lfXqgOm~8TZ39aVwRkknb zQYXR&jDeJ zL2xk`J)T(*aZskbzQN`EQq1-ApoC36hOIuz(pqO`urT6HvEzK^s- ziQ{MLMwcT=L1MO?2^;P;t#;j6FCS>=3C_p%{lh#YFGgQLC6KtCG-v%hO3VI6X-%1{ z;8oJ2L9?RR7Us&s(d{oDWO9`(D{DO|{16?%{dg8Cs${2ykt@V?A@?TL0sqc|^#|7n z?80?XmZB8lLFa17aur3&e)cqjof{!$ZSG3kcxIXY!P0m1Gh4T4L8pjgVrDmH{J3Vb zP%63D*Uxvl6N2y28Df4JeRup8TAMt+53h6Cl0>Lh3dOLDpnI_3wTMEwnHypgy1@yL z!*@Up9j|B;EsNA{%U7kpr6m4!b(e&~XCi^mmhMd;_59&>tZMd1FDFD*%)f0_wXRs$ z?clrSv_n6UY@%Su`e+ST4wSh1%|@aqMI$Dxg8#dyub`b8WiK!#3)sK(&K=#YRqDL- z_JJD-**})xH4UG|>3-n9mz?EwJ2m9A-87xD;zJ62p-#bFc2*YdlS!tdyMIEXHk{pdxwWhnsBLOB*vRL-vkz2-iTgW2L6$ZeYl) zh#k66-2yh27b;O-e6NaCx6~jPv6_=I%s`EU`_G6S7bw&NQ*WyJ3fZ|KPnDQPmT7E5 z825%`$~l^KWzyblt|g1Vx0*&&j@M#<&?u)Gf?0(&w%k(p%SQY|nx*zVkThiM*g}L3 ztS?nPb{V_*vQGldR?OkH@k-9^Bgqm$NT%c9BEihMUM$-xBfXke^jL|{t;g3{X(qe4 zsfnuS7x0lQUUQ(|fT%_=+=GlIg z;eJiTpmtHW*hJm)1mnH8AvLSt`fcbS9p9W{LDf#u@#R#o&Q*1GwrJ+78-iks3EiM7 zSzs>WV;&~b@YQHagbycT*Fx;c_%GOcD5KZ*PPP6FI#jsMPJ`+`rpkjz@kf>tTMB6p z^BdJM%#SIw2NqeCNbMWx!gY~Hq3knZOYn^qw-)6TU7`$Sx^{cBNZi{rE{*TkM^A>W z1R9-cg@wH|l4p1eL#Px*W$zh^b{=KYV%YNfH68UpD4~6Jf#g1{Qg1S$JMRghLDJ+aDZQqKA`sJZotR>3zobZfX6DxG}_j#4uZ~wz(k++q2svWIuj=PWRmJ=0}7cugOgf^T73am z)yCM~GUNVU=cO$ZF@&8O=JwY(z&YEWZ9Oa_8rBwLJtVzPYm_WZ;PYwMbELPeHLB=( z*{=jOxBBSLyig>BZhys=jb}@8-|U8`jR@@Yl7SJuNzw8c zsz~zIlxV&p!xguz?ikQ9xiP|aQo^*`fbn`rqcqrHY@^;vDHM@E!4^ubmo=n;375$< z43wY$zUNh$Xdv^?jtww#%MuGdoQL?HI~>DP*b&7>mnn~#XRvr-cxTc_uWci8{s1OV zBs9WM`cjJB>x2{Z5TBgKuyW&A+O0sJ{{;}is4P=M)eFHzLG(AI?*=sd*P9#HLsN4@O|Yp(~Gd>>g+A^7fR-Q7Q{Lw z-M+FA1I)61D>D`+L8nv5(xZf3wRW%p;w-VT@&K)5b!WJMmY(`6;~R=VROy|qZ4*8Y z=qrcxSn}^^$;R^*RBN9CZbX(-r9w#dh+)D|L&20QAiu-r%N#H9SG$zZk7rlW^Xv`pI`CC;RLL{K!X*aTy{TCH+|Vs3{M-8@bASZcb0{f zDnbswy3%C23v?d2Pc!RY;Ukt=WK~nrRHP`%yJ@f=`%NjVNplL`q*$QE-+VyuSPzwO zW6N@PgL&*!s}Ie%x$`S*!Km$fjH?4>Pqg)@%!pD_TIX;))Y3*|JL_$i7=v*aFt7NcqfE?>)xJ?`8s%2>LiHROzHvYT%H@y*H{NDpAO}Wn`#c&n-B7;-i<@ z7*p{-uB`D6!h078Ozlq85jnXr_4a4{EWxBDA6Y))6?zlRGVpm%xzq%Gd#nugPT1>I zPE~~;N z5NZVbgZZEOajUvkZ_0Za&3}NXrDvIv4juunik`k&`21=b1BDy;ZY0OOk2}4y1uUA&GD-jLL{-`|UnD{*=5ORNLDlAFO^mqX#|=chz<4w2RdXUk=+t9&B8FGb zK#1dJibRh%Avgg@-6e9|W#e&wT1Sgf+x%Xp{D9Rar^s7HklWXL*LhMy7J74`$<$u3 z$Nfg%q6S;d3(HzR@KwMnbw4J3-uF1V-PgqGHuq>tuZ+H?deNv=E=xG(_R9urF!hnr zkYa14wJBce(6S_tJ+fywuhi|3vsQYGs;b^&SMErY#n#Ps)gz-bS;BxEWxn6BP`Sl> zhd~~iu4p#l{q#;I>QYdOEiy9h3cROmQKsz~X0RL9l&eriQkmrexZ02F<{(xpx7~B? zv+7*w>iZD@Qf%KK?%XYh<QX?yJ|ssPf&!t9x~-p{-=VpYim>fWVb7xwc9#MQ zhiu#okV;48?Iz+yN6@>86JiE`Pn;58b)&Mtr$hd`(g&xacF7h+HD_? zUk|^G`Rm^qJ#iXIMt5p)W}AypzHX5@hDF6s8WOpOj~C{Wo$MX=c(fZU#4Qezgf*=X zEY=h8I4Q_l21{|_Smv(Z!9#THi5l(N)P?fbLYCjL6!kw%K^J<6wD*5bn}(mh=(R^> za8M>$A|@&eHN2|J--K4R97tN)Ca|i!9#?L6LCw1cyi#Du&dRzOY|~OTW1S8@V$)+x zp;z8OnRX+1sYJitThVB8Di9cDGRnWMmA`@RPh4zLR5XG~+3H9$z@EU&##9BH4vze( zpNDumRL1$zX-E(6_L^?Q<{G9wm0;9qOtmo%zhV3lJYjiNVrKca)uOl5dmGSFSLC~P zwPiim`-4Pm6ugp7YLjyEZ~lcX=| zsqcr#E0|z^Q5~pmJ<~t3OQXlzjsi`Ge%hs~f`x;uvXp?iq5c_6_cVI#5V#vd%(z{C*{c$`o~1#0Q4*ERN+zTvlceGz*PsPC@_yF(A-T0N@;Xh2)tPU zY9^_1C7c}M&KQ~9@zThXJ=CFvh-;Cm-9lQ*6s6!~G zb#!@)UWu+drkor6OVtJ6J3X(y%ioA(8jD^aDvrXPMR z(le716bn(`#kqXF4@;Hr@zJVY!lHNH_YZ6l4aS}`xo8)*2R;d*A@>-Br|Y8I$2wM- z4r_SAS$J5{xw9R6C#6}kwjPD^??fYxysCE_ygXTQ`&2i`Q{$-w;9vJ|tDRc(76~qf z^U+kUN103I%+C~ne5f72|8gD4AMjk|_V3J3^}jJZ^q3E6N-&x0w9a}ib>qI!F`#^k7JCtbCovednWKEUE?SLntDS5nCgz*})A-Cqi;8-MOMraT%v z_P{{4c>}0AJuO=@)1}9=g4f`$qf4k>aZX*{u5}>!l?$UUPy<5=C#CpoGO}0H)$;eW zi$}rn>ca;GL8Qjw#GQ@OOprB}L*@pIbKuEfkTCREortc&#hELscYPu+bDxQz?JAgn z_8;>a@9ceE+^)iI+X-70xwa$v<$hH?w^W%%&a3P4>V}P-ak5Yd%!C{}6{}i`ReJOp zJT9{K%t=$%P)UDfd4Eu4+Uu7jHAa=KG3SL+$ZPGxCGc4B80Sf%Ah63-^3Y-PC5S!8 z>wrOKTRG|TMz-xbih^I|G^tE3^w_f4wnXyDv8XW`&_|n@$gSBfI#(xja-HXndcC;^ zvRRFErB}bevK_9NH(ryT6_SXFG_mC8pUh>z8A9pbUM&V+wVdJ2 zW4qr$62;FLc?225Nzp=P!(K?+q&u$@!yl_0507-3DccMlYM4(L+#sWIuCqm+ezMHh zGr3R4-D)nhjT7rm?fy_8M5`NoZ*kCme_UflZ_W&q zHDaem1K6dS%Noop7Hq>i{@v1{!&U_lCe;@RHMKjr-qJSI+e)n!mJhQ}rQi z5X^&<#n`Xp=}76rE^&eO){an5r&2MeiFNLK3YF}o!3KF#*(vi(hmoQ-rz#tp;T-EO2$it|qhW#eRB>iLLlQGlsq6T(};0hoJ&6R@1XH~77&d^IKN}HabeYzH( z-E?drf)kq;vvU(_mKPMfQ51yb2soE#t8!M{+I;>6WTyrH7d-M7YpqsjcR!$u50|7n1`6nYGd1BwU>Q<*mx{ukqQ3{HU0-2E} zN9tCf8PQH&+lSAsgbGVWi)Gp4IIOB0b`H}ehJUNb6!r?&Ksf;9RCk{ZyD9r+N}-mQh~MGP07j=6%mOuX$b9 zO_0#HU8U(PX!S;CvK%H;S|njQc2K-_QeS*zii+d3vT$tN^+&a7{m9$rH(!>7ms+c{ zy_{esfl@a14RtsSo-kCcxjRZHi$3tNtGy(zb0>ZEc3i;5^+ve(ApVUeu}n05V}*;h zP%tTfB^!LMi?ebIZZ<)q+5gSOTNM_mzksUUqZZUb!o5^WhZFMO3HR!D+2=$SA%D*i z@xL}I!@(S!D)gR+?06?AD{oBM*fu?|tdXeYNZXZYfGVDOEOiqd{bYByK_r||u=J^>wJg0KB{7UT0B-?3~NIeF9dUc?E_Wj;Jwj$t2$v0WWlQezZCwjYP%;| zQ?*t4n^#<>-C;Pdo`KRJ!cx7z@e(X$lrF2ZTh3qBAmvUgs(`&BX}&!2@@mtH(gWv1 zjYi-^DJ}0%8f@yrVz7fvGJPT&vuZIk&U#e#AjMax#Z|N6M*S@bXlJ@NXkL!UnQkC}9c?0Ozey%g9f8bodTJRDK^5%ZTX1squ(N}ukdI~sTWu5hA zAxWUHb-WNX^q)rI9pV2NN$dda-VP60QGQq$Iep$h#sVyJvlb#6O_RFu@&negNEPHJyj5%S1e< z6zfuqes6WTUZ7#vifnEogu@CY=*=s_ihzZdjQ)Lj z=3Vc;l$5GlDGu2eH4_AZ5$eGyboGd7bi|{peeze@>KRHb+VuPE`a4WyeMAXwKf^uC zuf=;do)&mSrpMHV-T3(V-k_Yf^%gkC^32Lbj`SEq1L_F?Y%NBjGiWF4#qJGfN60;o zMG!`JoWYL=R_|L53-F>H}G;FNx2#b0@cUntyW2_GiAxZnHtK z>^bt}=G3IkGbi>p`6X~uPiR9Xf53n~qNgeLMNLtE4J^MazmOQQupStW&#dn?U&DoY z)^9tQvU8=eN-rCjnjqFcYkT7}r1L}4YN{%XPX}D0_n~PESCRdc(XP?^BIcz0B(x<@ zGE%?NdD$xnh?{Et@|N-)&t30EpZyZ-GDtENba`Ys2H~4fD5x2RR^S=>R#>caSLnEA zV;2ZY_i#aT>py^=diZ+!&@o3(sz0M}9=<7Cma28>Nap<4n5x=8FjWBnQ{5G|YuFQY z(nh)=#$G^A;U$rFd*>3{bJmq2HuKf~gzPJ=2Al`i=sIjt9vy?JA{lo^l{d9Dy@pp# z#0~Wh(|LB|(iNWxHZ1cS8aH+=iAC=rjwZb;p<2}5mhqri8XuIpVhaBy`r`$<6^~az zsU#kNN~b5(vPX#HEVKGAAI%MrP^Hzpb-{&txjw?(WiW_?UcOz_?U`vohXVcA2VwWq zrHY@gC2J=ZtS+edi^-!Z>5=;~wHYD1a;m0%G-+n%<$B0k+gybfAyh+F&93y!1}i1R zI=#$cZV?l^^J{~m;XTMOwQ$T(7t1S-!S=83=$nWN3aKXuqpXgVmR!z8#K~aQ6=jPy zC$>lNv3RmpCo}VabA@Az*O*g|=~{718yvSrBVC(I2|T~a9+P7Uo1OU0YNxg!+#eTb zj!V6brdX_zGqA>)6WK_+#r$#ZO;l%Cp_C3%F7&=h)g|XUmdw^PuAyf*DYKEgR{||w z>w!7L78g_zWD^SCxS?P47s{(1m<^#UeFDEmzub1sD&xg8c}310_4tMYFQa95L%A9j zrX|^2?nE-67K)==rMN;TZ!%T$&n}Ba4KL*`FR0M75dR3k-Y$T#L?N%?k9p@i!WQ$8 zDEXu}1_oy}W(ar9I=LRc(*c3ENT}F6_WG zXAAz8t_r?DLu1OB;z!U6z7%hK3Y&cgSoCxqVc5a(13us?)_KW30C_CryNh2p&+nm~ zpi%LKtz~}E(|7!ECs258w(OnXv${f;K_l5!11Z@A>f_>%je}Q%jkuX;)MCw<^0n0QBQ- z06g=x1gyU3p@Akn?R>h`Wt#xnt#QvSoy^qq zeboR%D?OoOWZUG|itIcmb@3!6IEg`glw4w&+~6})lUc$|ST~BePEXidHgK}iKu%@8 zpQ4VH;}ZHT!pf1@Bf=J@s<=OsJ)Dv+$lbd62n?5LFPd;5-)1_cAXT z&B9oH63vJK)VXTN+6b0VBGGg_hp^X^U(u>_S(2c9uQ>p&DGVgWCZiEdWSszO0FBzU zW_<`%sp|oXn{2AG9w%kIw|)0IX8Iuu%xtG`!6)gRbd84QHr-$to}+vCf&P2@P-2jJ z-BfMIFsg{UPcw?C+w-;U?dZIWHe|-1-Fe7!=`8c$eL!K_Ba-o2xm3FFY6@QQpkgMQ zl!^RAsw*=@D8HSWDNw$|1cP;UVaZ{eD%JzE(lP4Po@Bm>`n;2>aAWykcZUP2{OnC9 ziPfI+SNSqiRM{uX;mmMam5%dCHK@`e1~14`x0u*r=b#yivg)Cz6RvZA2Mouuhl@9D zM9fluDy4oHU%UWL&WaVKR~X;C1@J{{tA%3OUi*Yud{APe5-!4pD_-c0nf9~oT#TQ@ z%SnY-YdB)f4P;ACRA&QIf`n?Vs+k?p21lv0ay{c}E~Qzr_G%@+IUi%~*@I&p{}zd3 zsor5z)>lH{Cl^270UA8)uD>GjWNQ3_M51Sh2`MVx*ruMScox60y!`^0(C;YQen!2C z+tV7;!adzYg`=J8%rq?oeqDhjw-+iTzeYf~oaxmOBK0nE8dC>sO5sYo#PrS%?&!Vx zbSss3Q`--{Q*8?MPQl*@#vRXCKENM{?*ep2>uEH_4Kll7GZ zzKOK4;HI#hV53K<&CZ)SkK_Uo4>Iwz`bEo-wRrqitvsG;&>I)C>+-y&*OKBzgRI^3 z`1Byvdf%fa5$JV+O^JQ(K6O%xcBr*O&zXyn;<%DXg<#ouMXcUZUPq6L!n4`8SQFGl z3Z*k2JIUL!+hEU1mGA7hUqNupOYz>D*GPKFOoY;{fo3Ydarf4y%ge!M8e=pR!^xd3AK+iuG~*sk6c(S zVo-nE&S-_gKqmd{ltv~330vk@N0l$FMp=wnoANs7`5w(qr+a|UG$Vyr}njboXXK^Awx@xT{In^== zYhyyK2aXj@TrHc$^a@c5RpvAC#h>w?Jd^E3J)z9Q6Ke2Ik>}_TuDNP(PkA3{D%w21 z;qGWMv!x;sM_LcgFWcM;N=!_on1_M@N`>J)K@zZEQqiv3l8fP$K=NpD5M)Tyx=!l= zeM@MWD3AOc{z!5BSIgf0$6Cdxi$YYB<-Sehch%B^T*;QC(;}T;mJ~2 zg^v7>h!RkrgJwbKDA$i*!-JxDPIEEQ-OOusYuGxAzG@!wM_3&>YRW8_jJHgW5`aY- zSg)Ov^xRBK<0eU;Bow@^RYI|f^iHAP->co*Wtvt_{7eiX{kHvZcSKr-3DFU1Nj zgs;#{ZNB(|=o2fc!1N0iwL4~~RKm29dwhzG?iWAplV|I*^9lx`AcdZmh(T#|Gu|Oc2zD~0FQTAk0AJY3>^qx=BX(3 zG!CXjbWgY5Lu!A)(r1n!H$JpD;cpyQE9M>o zGQPY|KZRH^{i4@|gy@_Uc$g$teIL+rv_kdePeJ`?SfMufEUVr zAz==lMq%gfSLcQAL&Wx%_U4ftv1dg`}Hl~Nt#(G1ruqo_bd5$`3bFGt-!l2dq$+VJ@} z7MU6_^Nn1NRf;Uhd(jLG1)982>MJzz1^G6YGzka3=Gt&hOgTq0oY=l@r!w)H!q$B1 zg_c|?lkTqsQmsndv_-x=+)sAX`V&vN4`XQ#hiRb#R#qz9l!f19Rj)2W61TVzCdEr8 z`8RFBW4258WXwuv-FK#+1w$_Ne*UGhS^9Q=dazi2)8F( zOV)TNHRh_Xuf`+qSiF=6f$q3D7#9tCBB}Z=`CqLi9!YeLA0NK{s~m)N58x}ae*c(< z0+i|4E`Ry_|Hb+DyCq7W;jyO!jK1G>gnzMZ{TE*vn7Xmy)qzUk22`T%Y@LBPF>XF3 zy=zSSkyOGlifN59b9@}8*C**^W2~sZ*G)VfxcwyOeQt>e%GT%q;+0}@wFk}b|6YE@ zX+K8T8^d3UjhNc%e74N=@BQLY~??G0+ZFwk5#9n63wddN~g12 zY9-VDU!=uEw?C`Cu{Cztn7D69xQC{kqp!3qG}56e0)l>FOT0bZP+3f6vAAsM!HJh}|N{iU+rTKWz`LDz5 zzcedPsqX8(v{U;HkV5-`>cez}y7$b0t?*3gMh&}hZ zr8(zG);If{N+y)ezBncZ=*908*tN=REQ3kd^}n`I)|kOV;)_j()0-QpCzyz09+~<8 zm`gTi1MB-mY~H`6F2B`({tKh_Npa%6^X-LZPxCM*Pv%>>aj;t6_BJi(6_Z>4w{>fo zSUTq)0k%vgjZWK@6oO~vd)Mq1Y6Ma|V0EPsLMFp7o6wihuc};9#5?|S_5J&{e6juq zmpsMJ)phD-uFhSKm{sqEpo^Ade87ngio<}aP(3phFj0L!H#c`8`eL4b|8K=l&z~M) zu#wa;;_piH)|C6#HluO+4hiVj`zCge&U*!p&hzgL*->WzUQ9BEu+V6kbZI6UbHmFA@erJiD2;L6pCc zurL7gcVaCGor(fH=1Dbi6xoZn_g?9S7Tny5C9ko^$jA8plK1=XtwyYX(C(s*RlR7; z^6%HC-77%K3(@Ds4f*%Y{y%zvKmGNT5J*MhnX)PWzQA9nCa>rF~udmYrtZ6LT=G>GQw7*Ygn6;V@qguQ}avrYr9B|GyR5}fcxL6}sXmm?j`sJ%HXr4h@<3M(bo&AL>rOA>TImL8=SLOPx3F?e$ z(h)XVxr&2D_^jIMK`6rKcBo5*UQkv_;CZ1PPO@l4{1aMBDBaOzm$moh$sD#$y>q@k zJh*ag*c)Xx)z=b3tH#tU3U1f1ggNFd+|+13u~e`6af*L+!GWx{{`xnOM~4vQ+vyI;AIgzV3ekJ-<`ZyE7WOvRpS+UzZC0800}hG;Laa^2~pi9giF91==d%} zb!v;xYTmf*$K;)Io5Gl}5_{psG9>k7@!srlEgLzv&G%cu?LqPLa&3g<(eKe$-c5#Q z)cEWWibiXGtXqB7GWzQH7d9g5AcIz_xvK7P4ne>j;*j#s3GBabv~B-XZoTc&0wis(l#3Z{ z=NEUrD*(&~#7K1ZSgEG3o_f9+s8GAme?fCT41YWo6 zU#7}`UTG1aN_!z65}CX1%`)E&iWu<*k5*^Kv1tvIE&kin0caj7`g z>J8~~+$-Ds!%wq(!RpH|Nc2xu2O9EUfZ%6keH+*)B%>@;=55v|DUq&JM?>@Ps3k); z=z#rW1P%1=M`sAZW@=hl6JU?bI>m=?1}(rQ{}B9-ae{R(7O)C-d|{B=icQW z9rVqhuRYnB99`DfIGrEg;^q!1bw-ytp!WECV=kDs)pKoFfNGb+QTY!yjKDdd=3^#7=OE=-+5v8xXS>8ot^zwNUrb6 z>QeHd(qjKj{wtW-upWaWG0UV9U`9>7J!2l#H#TE z)XK}i?t0_&AFax6V;74Dz?==UaW2V$gNLL&&d5v1%XBkS$BWfEw-qK!78zQ@GfIXF z4fnUJ%ww2LA0-Pxa#+6?TbFFQz&=c|`ZT$5`cA6nBb5KIJO!*|8_xFVgKqfq(1N>> z50A96-YcS8kOz0i%$JlK9o4!c$1+ox)L*UlsTY({=E0A*Oj`^f_PeJ+q60`lUy!%@p0I`}S3TBISvs;9Gj^4kN2%+gG8Hy=T$wtlI zJRz_B^=pxCOCTd(hV{zRIsW``wRfXbaBXUI)yX~UOGe+GWvmxCDE2=ukK6Qr1_bXJ zRp!dpR>kUAp(pkHl>dF7xFLkj#ms^0fl!WStGL6~FO_^}kR7kpv{>(N34#1g#=oz@ z?brZ8=Ui8=91z;9aF@L?Z}k^id0}Li69!63N@P3^C4i+8tjy=q?a%};p6XVQDMa+~ z|K|<)HX45erYeKB*{?N$y6GJtB%#5j78x_rOXaKRoZ~tY`@0`0W_RmMllTVtS2V`| zb5$(BXb@s_RCA>KcOUi#M*FQditgCl-^+iW%L9_?fZnOTcYj|K-b)0wC_5QP>c3s| zeyfy%)NxiI~wBEc_Gp%gj`h07QLPyEV%DA9$1S!%R#nRh;R8EA)8y>)+1PSJjF=f zlvvJxuYdwx4dt4g|K$3(Phd}?y8NKTik^bL<*hn6z zrsJBFPeo(MYc1&0(-REX&=ZI=@He?`Yy-Yh7vQX`Ta&=KdPmI+TlH3`SNyhIzBA){ z!}$bXley|soTnAW-Y*N)XyQteReOhN9c9KDzP!VczGgVj)TQS4SgCwBNG?SuTaq+N z+1KgWUS~<317Etp!9J#|j!~6x;EM}7^?w47knIZ0rl6|QTg}K(3JSql-@s_`G<%YP zG-$O?MB`@2e8GCzi{FE+|A>`-0o*q%7eQs)(rZ0X{h`JDMnJ1??3afhF|E)qWL1;XNsE@5? z_Z@ZsACWf%Yxd!wH7ivCZ&pwU${QhH- z@-9(7@BQZE*^;2%)0t8RtD z#h*t8t_iFl)o`%K*88IdrFkHK5~ z#o9M;y=|~&{d27=kfwGipY2O75kFhN_x@8o@%$2K&jO-dg^iBhXkBb-U%hEnqR76> zeVqM-ntT6dFYV!+Lf1`C>-A}IwRL8Ab)V{NP8i_$~aop zIAtgct%*#ui=1>JA(O}TG1(voa?bHUxPSd{++4qWvwm|xLdfFYfu!jg+U!3&dlN&e+?-=Nt|_j+<|M4wLv5kG8wbAQmPB)Nb z<6jPWcQAF?f`nez6T+?WG8NUdI(4 zc;%GJ&Z{dsr2B+;H5kPX=+$W?lwZpZsd~v0Ge0+#B~ROnbr3uNk7}S(u6(o=omt`J|(vQip)I8dUvs#3)0bU9plBZ8m)Q7;;3%X;FTT zJ~>vHeVo3%Ti){i5lL7YmSIQvhvS+OP0Q4T)%T1#l|PnzM#oMYaE3(>*Fi)w2HuSdL(0W55N7*;2-{3q^5S?O zc(dl|=gmHE*F}bXb8xG6Zv;=H_NktMS2IWvr1L@FM~jLvcba0yWr^)wrDrD=xcZYv z-jAB?k2S3O4{A=WeI{^0ES})8_%}xV7n=s?H3U**(mB{MC8Ve{%vR+}0Gg`c9H{#AGVmqD;^NEh|&}YQy)qM7cf(D$&1%iWF+7#kkRX&+iYu0wK*6zSIKi>cDp*Sqe z9Hi@gabHy*%a`+NhRq>`_QMJfYg3*G;Ji%* zWa}gA&Els)eC$*GHp*9>oFE8kYJY+-nj@mtmiOv8^OVo-TuSI}Sp#3$Fb8CVcdsh= zx9yNNTWc{m{4l-iUa5kP&$w~ceQGbdnMgs&GA1X#xnh*OU^(6V^VU3DsiX|wD?M!& z9|_EI&0UT82YYpWg{*YVPz)Tn)GJ7JXMmNEzmG@NGq`>ps-1bllVKw1xdptczug-D z`JF$#{7S?>J*q8HQIc`2H+aa#3@WAdy*|y?s1{#N=u=)!2zfgH#83TEt#FGPto({K$zJd+!{PhgWlqS^+uB&io5^Vn)ut`e zq2~JOGvMU%?}J#${I2m8As3W|8Y`fdY>O~G0f_QKk9G@95*T6HAmW`d?ps%q7z=%z zWw$%+S$Xp84Xcr^Y5ZGDi{Xa!w{&aeEANDBUUI736D{$Ui4dmKFeJ-W#LtZ#SRi(w zJI1Wle83YUXxk{z4eybySACb(e7`*juItsV#pxn;*Ux{fU+jasd*Q~c<<2iN4AVtx z7%tO|e3JM)bv!!$J9kKh`6hjcxzi0w`}?|^}6Ixd|tw*C&~J<39k`tJ|w5Rmp@LZjuI9c zrgDN79ft)J%p!aRAa9kD>_^g@eRsHe?WpJprG?|O7W>D+BI?~rdMsPyEjrg9;a5L7Y-Jny zXel}ZwzKgdD=BhoqxpeLoI{3t0hR9Ha;iK;7p>UiKZP+6(tfYf{~&@$c@gCfE%^t? z<;Wp7YkD3;PDMXjCwP3KV543~hJUFb(WX&1n08r`UV(jQEmF`oHkaD>g#tX>g-~8c z1835onjl~0xj3m)qyX^`QER)@-@~5*y8jca7W&$sb!8 ztxkePi-{bq*FUe5uMLi}=H%d)%$On5Mc2M@mQvEn-KR}$sgM@AFr9*s3ETS_XGm+A z_Ykek#!Y;2|GqP*o&1?dgSu?``~9t_I4&0Y6K=uinpJ7%K)4#B=hqMWgKZG!2S&H$ z3w~#>qzd76L@w&t9C7oEN~LM2-gcnlN)$1+Mj&A`>LY7vV2tHXn5lMD9e7Y#m|V{j zwP`RdP_c^T5DqeHW;NQ;IVc;EeOpamyHeSgCPBL>vB@{u82_OF7pu4;YbTx&Gp_Ed zIiUG>N^!!tb~Iw1d*0M#_29gRTZ5)lvzVk}7SiTebKhQyW6}0T>uBChtlbHTkZ?-d z=yMMd<3q-%T9Dsoi-Wn&Ju6ms$|u(t#m_<1!>}D}9VPe}rhcqoFn3KB#23WIJ+HEB zZ#udjKjRqvhInrj9B<^B$o?|s1*atnGvXt5v2{h?Bo8E$WrfYRKi&$|r%(2J<@?b- z?0&PchBOW(I=z#U*<|$0aAbc3CrrFWhq1jfk)uObp5pQR9K@c^I-N6##RG95R$s!wDuyezy2myo$>yr1N!;>q5BN^ zdW8KuJ>vSKk5@MGZpIbRZm!zBv@(ujvFy02m~RY*anVn07IojWYA-i}BqK7+D>HrP zAJsDabB*~sxi35C4~^b@r$mA3lKCztgAb`Uc>5X|nq)S z=vv3e-9}rD;C`icTzDe7%{gl#o7lT5brKejw|sw6h2}Ig|J9o4|5$w`5@O!Exf5~qRSplXEpVv) zx(CxI2im=n`|~aM`b{Q<1ZMk}0WBRPFyGiuv$CwKIib|@D9y(0r7&j$n~1yBRtR1) z+2`q*(5?_iovM97`k}I`{OC_Drgu*6x9-=O&k>XMs*B%jHxhTs7fpVO%>MIV#)B`W%qDnOa-lZqI}A(N;*$ z59gH#`aSRdp;e~^+qx=nA458VW0Z08WTxNvGBTs#m;Elk9bgVqe_^)j(u3;;Du&aq z_M|n2Rb7Law>U>|vY*v>f9MWujEa5cIL%S%G>ATGMswfhQ6&H6kosPl(*Q!LTOS2YQ>+ z9{peEtHYnYqgCewAxjy*n)t1gSCvYC$gZ&twfO8VEAqu5!;||zUhXYiNp%;OvpejK zNVQR4Yl|YS2C7P-YlC7JOD^W6`-(~LNsQp)S?5iA3I-uUr<7+dVTqgieABqA{1pn* z4n;)KIMn0CVEqjH9|!M!M$Bvo)|(AyZAM(9(|pFQVHtkzoCHwCn6BhL*1bjsP*d<6 zulG$h3`cqDU_fu%tqc9*uqvCvHB8)w07_ZVi>sI_t)_5ppVh^eb$O*n>53HO-{X^J z)Jo$!RCFOf$@um7dYq>RvYF(065Gw59{-+hugbE=d_hwh_bSR$sM-`h6h`JK0xaGZ z=pvp~qt@c#eMGkFDcT7YUJS^T`X6!oD)0|8_52B-)X_*~ zd=%S)+4Y z=KDQWH=HaxuD*v@T}{}tM0{d=Tc$Pvn}>OX!XGCTG!+C){6Yk z36a+0R$TNHaVC(v0Y%GqO^d)b0dRBj75e+6%RgqV#&C!o({KWGUUrqGjof{L$+!O7 z%Jx?_BmJy7@Hi-GLSYEAIKdZSrN8sVe((^w0N zdlKo%zmDG*pC8H(KDct`KP+jC_u4$i zy<^JXT(blII#EMubZ)d(|iA~k+NYUW90Go#V0 z%F#@li|FxgcDbTcd8-KyXAJ{-Cq_D=El=1eV|y$%*>M@Plg#`pZ;|DKWhyqAu#PQv zt^I{qv#@>=-{7PgR*IFJ48cucdF@VVH;?a4Y*DP9qPu-JcG%Q~`i9MO8&E)%QC|WJ zi+QR`OfcuNZIXZtsTLMyYAd(hI7@Ta){12se)lJVAxE$`Vxd&wNjsSu1a{TMn=7}- zI6J%BB;dK*+3nmf*RwG(r;>A}Un-)mV^^9O4s;JXwg?dXNk;+5X^6)|)Q3k1V$C7= z%BU6}8+NwmbfsHNq>s8}J=Z&z#B3HW&9ECjN!m&sJUvE5bHE8+UQ+w+$8tTU;=|qA zray?7Ss7hW9osFbao|pe!P7y_yAQ~&y@ZGNI)nGgR-lpf_M=RK?R%QZJskOuq`9mX>-)f6;+=lRQ+ErxCx;c!sBo1d!ZHZQ8Ru^-|hG_K7WuC&OnMHgdf` zhV#m+ltqtJ@0_6zS9F@hbcUMW@y{nrkd54~Gugc|^b|>-mt0K<7*KSLS-Xq9G zY-62A-jn|Hr`K~iyzd>Xav)6`v%^fyderA5^#1$~c2=y(N*x}@=KY_ji014L)&$H0 zd;(yl>A!Wr$|`HB2@tVsP;jf`oWWtlydimXV{O5EaOf-?AZaQzf%#s8+4)a&1$~zFTr{uZQX~SDI2K$-@c5L6^Vd>Rk z&uu=^_!yZUg{Py+ z#pnWRfS&z+z@agc*@zILY?IjKa}W#H;bUMeq_KmrGEHsE<+Xv9IydwTv;cb;CaiyC!s&s+7I*+*)W(bP~E zZEp|v$2{U?XR1DaX~=BeLjRId(lJf+UEUh+V!>`&ixfn((4(E!ysL~>3dzsx|M_e#CxyrkJ|R4x=h(=mwl~# zenn_o&CDuM+zLbf>V~tuX=W3LKL@+0&)z`E?=fEDxWepj=!YxYJ>_F}F@$QK#G3_u zZOh7$6`Uf==PS$lRrJ|?=U#XC9E_MK0|&s@62J9u>u0D3J~97zOLA4Lc!x(=Bfo4)U$pnJ0s}a)3^hfW0HOLq>$F zO4P~H6mae+W9!mpCOu}zEFG^|yh@ylA@dv^4wz+KwyW&BY@S`H01oG{R=i+n-&c{y zY`2dnR#ETAmuQtb33s08Kn}@e7X~y{Y{Er25N`dWC*p1-6U9W0eWPn#muCG53RZL8 z+38qhxrpTRbGiSPbZMdjunIt`mfS*}tfhRhl9NSX%*{(^DI7|By6dt=27$b6QhMJe z(y0IjJfcdczFQ8}6C3zcfzTDhLWT2AcHP%kzC8iWRT{38L%S5j@TyrW_SNio1GA+8 z4o4o6AxsrnTDZ=GAy-cGTDP=Q!d3oo-i>DbXifdhE|tp-c^d884+M>e~~`a}u2Gv9$t~)okHhV7QPv!C>{|7!6q%{isV_$!WU2g?eTC4?lcSaC z05GQFJrTA6G6=X)>GuivD8zh_$Ee?ONVQm_Hj*;U5iANjBZF*vv71P?24Or9?gS#8 z@9ACroMXK;UQ0A~ZS?A<`-9>WJNB!RX>&J8OUyGjv+mT$)v=%FKdX`4yEy4jtb-m4 z;#Br%Hu}J`hw0x~)@PK~g;N7$f#ex%D1*{e=c=0(A0@XY29%SW z)vg4;v+cM##IRm|-}~eT*!2Zylw9{wf^R!5{ywhO4xINGezACu#D5r**D&?UIQ~4Z zhr(Vo2O9RqO%R_vP&fg=SeF&8MjzvjrRE@c*GqRsPQ1xA`mZC8Pfa=|Y=wo4P>>)K z=an<^^#x${4=;$OIaKfRk8<^zQFinBG?7xV0YIEZ;Ke7r1GfzjxNz%SCfDxs$A^b6 zdGD61 z2QSzz6YKJu&Eue|PW4h5R+x|AID34mdO^Te&1zm0`~;{pkbr`^*{%*HJpS3e$N%3g z%>Y8VIW#8Ml6mg+!yfSWFRx{(YaFKSBgSxSy0o4Kq|9#yP-4yyNYg3YJii-jBkzm6 za`7b~x%@{VjAP<#G>u8-IlbHo)LsyrSoK)Ez4Om!qurw2-<7>CxPcNlEil>1a7T3X zyc?(Uf98TtB><`I92R0_jPQ1j$+k;5-Jff-S6wD1o$=)nV+tVu5+T`!@#2$;K8tR{ z5ZfoOP`mO+`^9KjB;BPd5k;_Nb88BRqnJ#$xhN}^?-}x?s zSrS7w5XLJX!-(D3dLFon>rYY3!R-H3^JykY9KYH9<<4--hHM3oi~_}&2amS4G?xP{ z28%eby5|sWZ28R?9YaIQs&z(PVTF$Dw3{Rbw$5|Q?C~8>m}{1BPf1PA8W*AFT#r1O zSMxu=Rl&khFj$W0xk{a89vGpnS6DQ%6%3mz#)D7Wit6fgTVytframYea0P>4l& zwB(gLOACmvlDWU{!OO z_-v;7*r@xncsG^H`Rl0yo!{*St%+vm5ic#MONWLW$J(7ajUzd-tAz!ha7A~-5nW+C zc^LJ_pI&XzQow_HRj%l@UNC!AQ`3Ps3z^_N+n?WM9_RyEb0(C2D7=x3pxR{E3&ioA zsW7NPjX=^in6pou-s1r^UwKOl!|E!xfw|c9Ls|mpSFX33Sbsbd73}M6Z0^F?uX|8Bu?oNeg!e9|iK{Fd zN3}UNamd$OWYZQD8z|F#S?^*P8vnq^SFC!WZDF<7JvLcc73=k}vU3XT>rxU!-z8U2?6^*m*)F4Cmu-HQN0d{Cp(< z@4?HPLTn9;B%Z(teMy!3rZ`^`x(BUmFjho#AMxgx#(n+;TQS{DOFqshfs-D4wa>@h zU2ekO8H{@pqRB8e;`2LEx;?<{5-ME&=JT{Tsnt=CdAEM%A$q@=Y#2A4YKr>1UW(6y zke|R{WP`@i))JF8U8gq*CxHCO;z;+for+A^f3`!No~tbMdxvi0V5Wl2T+_QAEThuW zY3XXc?`dAsE`~kPJG0|5S(l_{`{09)gk$;%sbs!(skHUns;@1RB|cpH(2ghRSxqFI zjf?NDBh>*c%@wbYs2ivX$9We@lj{EXY~EchcS5wYSD8cuz=l5_)fTKik9GH?Fq^HL zdQZ2yc(wb_NP_ia2au2Pp5oB5#Fd?q4h&^@Q&vYx8iXCP?EHbS9vGM7_uNsln`U=%8^Jpo6U3T zP03wX3ul@7nV1K`NAoRpG{{M8wXTa?PSlUB%_OQ3H{4cwC!?&lWg$iDpkM?Mt&Q{k z@x~CNReb2>8CswJ@XP927)+6vb_wr`x9u2LgsAQs`+|C$7zo~eAmKiYpUVP6ZY)RADivKoV&Ge=$0RZ?m)P^u`S8AZ zFn-%tRTqn5I_HBZoWbH}=EIAL^h1e(V9D8tf)7&WgOFfsv zdc})JdI@lQ>zVIa)$T`-o<(2;E1elLn2NrgKRBd%_^(pq6y#r&*Tz!hr!Jj$O2h$^ zJcc!eVz%;MZ7Nmw)^&tR)y6)YAr{%!4-V*Le{Y<>^JXv&cJ!4y>^JTEofpHZ!_zaQ z%OFu&0E$7Kg(s%S6@I)Qt~TpykZ~Bzko%p0eRh}QMsU{h1~{L?dG;Eptc}w-=to3J zJkKr}B@QgeVL0I#xC=Wh_t}Jp=en;@mY(*07~07^HE? zt3t$S%>}RH0#jj82iaZ8*Bdh(rzae&>l?ert79Cj0+F%p?8A!FW=x{9I%dNLtVI2K z%*H5QyN-JHom#3FvY&RKlgQiok>%pQ=10TVgIu2~_kgymfGdTWrzKdp}Wo}0P?PN%iwW!OT{~{)+TCd!tCI>R8^Kq^-p=$9r*%%al zkDd+51*RCOP2u^t*U>`4nZ4MUYelcJ>7QIef2H@YLC6_Fu3`*bOdAIPY>US+mU6I( zrPYNuvYvQA^Ttb^i{U9>EHUA(mrNv!c7`Rw_7=vBnmc_-Znu#0_|F&MO{&EAWSGhC zM~3yBy!Sr%9`}4+%OR*DXXj|$zvk>7bw2+2&NN3Szl1^Q0E%<=2yc~vUQ|ox=xj!2|WfkL_`)6FksIDs6!8xV|78*SEr*wLdfrG zwF!H)eyquUmXh)8%^2BmuPI4JY&EIRto|657hln<1e5Wf?%MV%kk87mYYGfrC@KeA zOzdd8zqkJppZ6mO!{tM{hw5vCCQc4eN}+abP``R(T$xJw+c%lBB%T_R9Mh|C4N>g*4A*b zdV$g-%n-fI{ijj}C~L$v2mrw9c=r?kb3b3pB_TDopsx{jhRzMJm3J6G46p)-GM^VWjARrkehaywtLPSI)C&@u_kR&-L z$xuiVs46IOE;2h=0c?pYF$; z-3-!L_dP{{-fh- zkMWXX^`p_|2SQrR9Zi%!^jZ_X$TZA!wuFvGlZ26IL-xZ{OJ?^H3_QQ?TuLa5-A+NW zE@qb7yuznMPlv@=Y7>M))*4mB#@{+NraE<0*wV(!hO4U`Ok5IM!3S&&l8paSl<3{S zDR3Itc-DI!`_H)Y-&~us-DE@XQAm-o{4=lP-(3Iit^dM)xq0t@2ju_ufN)31ZPo2q%l|aGpnO@r(+78mQvfo z)Pe`4)kEy7+1zG)-!tPKTv0k5j)2e(L2i00_70hjQ}T{r@E= z_22wC7YRK0QkZV9MG!RmC{p~l{A%Sw+VXOUcXgV0Cu(SYr`K;{JDOHR)qTr3fRl}( z6fO<)F)BrUa~kl0q*F;XJ^c4`@gFNdUKxObKka|S4YWOES_)rx+!SvWSi9BdH(TFw zaMfK!&F8e{gle_PX35zC<@yEZ{!20Wzk9?<8E}50jDKOFcaYriMZaUDuFf>sVVO<@ z@A8@@G;s+Zij=px_G<+oQboS)GyT?CX@cJU)N&xt{m$xQbP3G^dk6w5g#{7-t zG=R%C;X30pa2^!up2*9Ds|4jAzD=H$v^&muJ!td`^%t&Y-V3c8rB*mm~Z^# zjgjyHBXiGI;5#`+fqAei-Flb)0dAs0y07&A^DW=wya3Lyg%T4CiCB&{s>kiAL({hc zag3WQ@=1qwT=nL&I3S_C$piHHj3MCe-4qj-i1{}M+&?E*fHM6uyzR5PnMKD^VFT@q zXl-oq9pmjrQ&g<)v8F zn2^O+@-_C;zVX(Bb@+VX^T()K>u9^2PW}?#;G_5(64C$T%eMJ{1m>)6T~-35${>9m z=v6T{+aI5UmVM?IZwb@i>3!eMZPS`y=p7=CY_6pBJ5+D!7$y5F`1)@jBFzDO|94*I zg^j<5-QpJ~LVW#jz?Vf8`FPsV_V?Hxt4A(&gyDcnD!62TYJ^z=$@3RQE~Rr``CB*LJm+K`#)oc zEUqpuV1Qxqh9Wf8%KJ>}IJI&)wQ_jhE&IuT@)&Vo$QP1m_XLZz{U33{swPi44EHT< zPTyqbc%>h08+cs?QO2I}MtIB`y?VeFMEfr(!TE>tXKi=&B>mn))SXzB+zrz26GwVH$1}PB1++q~{PtbIfG~e}9&6XAV_wV{ozvq7k z`(MAn{|@#)O^-j$>;FG9`&?-TIFZbOhN(+G$<(5*FaWMf_!`qCN{a(Ib+1kJ)d2Sa zhB))`+r~-VnF&^Xc{~1Jp30)_S_tKd9i;Pya|-q zYWjv-w|>jJq&xo*e|@x~+*LWhS+d_PHZY#3nj?d9aoOTc;>SI8>Z1IyG3K~jMa!ZX zFZRWfE!ORcq{p6~Zp((92>a?&jY^k2`H?eJAo_AI;hI}}irHy38y#@nrq(F?UBU~N zaaiFzee<>CToEdM@z|?eFN9I1G7fpAC{p<**ZjFXzpB4*vbVhVcDAlcHBak1E5Gq#5P?%l&%FT=s~<-MCo( zpavKw;fq+t1b>i@0?)-?4tf>m*rrLs)(^V;mcR3>9qoV3MKSt%<@A|&`E|=VFQ065 zUb=MKu!x`qNqRI41xh@Es~oi_Y8I*=m3wWfHC)W4S zl;FqlVAPxh6g{r1lTQ#x$v^s(1Vqj z9l@Qb_|&MCphweP@7DAYV9Q*KJdp|J^}nXd>r+v*YhiR$2;{Tqr^>$;h-BV zE%h(NBy?B7B9fR2quC!-GqP&LaZeq&we-8wIE*>G9{#G^{W8kAloAdvbW-|-1+Cxb zEs6RLNV)jxFxmLNxjmxAYzUsa_;AJaQf-aj0D;ik#N35r{Y_mEDlpwv>Xq6?R>zRB z+3hUrJxV4&iW%#`xO?Mf9{rUn>^=B%zX2U%W@6*Y7lKGC z6ZKog!HtY>>YSDOI%ifcmDX>qlN2~%j%&ggQFBP8hhBYy+CA5`09<#1Jo2pf4|(Cn z9;oPpQiy>M)o6AE!s9qRL?XZa2{0C;uMe5HzPJI5hWinBYE70tu>Y z!?HS1jG_LW6Z7=3=QN48o?`cO%2%B#m&4!rvSC82RZ60|0SjMO5wimZW4#?Wj(DwqT)l+@UeE2OoZeH zE4x)i!dyVBniMjJj%zqWuC(>+-ctjf^bopxiqrL>lF<})Eq7CoJj|kfUGziPbAHaC zG}GrlNvu#p>QuG;(P_{Fi-c5moub43IM(ml2bPtwA@#G(t0Z2avtV1h5l%Klq|5nU z&jx?O7Xz>8xVnd}R+!L`w$&l{jvt5hDu5DRUz0&N^e?In3O8CT;}pCmH&<38n!#4G>f}xDi4|A&^q@D5b&J1?mw%GI!@w9kwqtY;v^VG0BAd?y4zDzkB2E#M z3k?7h9PDx?Dxd5e5Z|>wVcge~;mg#^JDRO zwWb9BP9fw$-r$gq@G2M}YKih4k$53;&J=6g@B0C;%evNm(C^oAMxSGxq$o4Cq=RyD zx7`n`TRY+A7Q}2OQ)ROiR1BGpR|}gZXNd9vEq@KgW(*243^k)Ta=1i}gdo*fgJ-}> zvu}Ayn-hQFUJ#vK>Q}7T&D2Cghg$&$U@?ZorZ;M!)^M~iNE$vRpw$~`NhqeypB`p8j;hSts*+|suJVAj}&V=h>ohP*S%+IQ-S)4x46bx z-gA7-$Wgo``9LS>@XXiKLUwIda7RQu8k-n4yf4?;BbQ+ zu;Lyc1W90I+KI+9g}2wHK%(O9TEhnvvv_&LlObo`?OnV zsANN*3@LmP@xERASK(|d%nH`*l%xz~+= zX->cS(M2%0@w(DerKuL@8b^x_7YOoAQzizpm^A%%8|cT{~B=V)#%LO09m zAKM6av|K6YKzcfBt}@Lu$Izs5iM$Hq9(QX*(~H5cp8M~ve^UA3h(x-Wrl(?gk+gV> zfj*$|*2WSzkeQY0g@|fr)ROCwU-%wdce_V?J+losFe3Qw^n)YAro%<MA8GqI! z9r~x*OQUgQu)vz*9O`@^Eg}uOj@kv|k|;+YM+-%7s=oqQGed6#H%On9-)lpFTJ+q4 zE@!N=WVzu{pE146LLTzFTH9;}hPwI((P}LYF9Z9x=S0;=F<98UbE(S1 zIk&baPfgb)mN+>F%P*t>p2GPUFP69dTXW1&1EloGZ!{A;Eu4?<$njNl=#wqxDD+Hm zdSkdNm#7C|JV&0suIj933M%(8sg+y6;c@W4-ud`DlDLk4Z*D?AX^?}K?+z+0uMifFo5c)&W zCKOb!I_#{GDkhn_T{@%Wh@@C8;NW@hw;G?{oQefEG|Y>?f4>p?IsVb6qmKo^HKxsP zbmV@-eO$bQSTvhXtz3NDz;%zV#bNZ8n7Ena+tuns);vOgMTh277uRC{>>PZV+c^8& z5vkNmgWk7H55$7&cL(YT;jy@U0|_I9h@=E$DheY%%v7*zxhkScN>H^~ENqpiV=Gbm-S`a9XB6n+_XVyvU-sC1zAh zbYnL(-$Ua|H?~FiD6z7otq^q%#qrAQd7fw|=OAVn>iA0%w#2?xmS$O0ZtOQ@41KMC z@q|wXhp=F*Vd#_flL|4(s=jtxip0Ct(!V^ECRAbY4k1xbw$CWx`^6#r)<_v`!hnB>}n?)32}S(YpRH%S#j1#d@&?Ce1^=TqhZ<(FWh-ePzH~ zoB~?*N^AAhytusP?WCq{zOgwU3~+n^cNMMO{n+O8t6=&=Ja@?87CtC!8_Hv-RnByUe*^v9)PO}r~z4T;O6*OW5k4y0#V-Ua#hSK!W>sywEkm`pZd#Q3%i zGg{O(q-Zgm_m`SY7ApKZ5AoDt?Y;O1OMNxjTO4bfFBZYVuhvO;>I*C{E_un6RTkE; z8%aE6k&sgvsbe>MX_3~&M)b)*4a&0A0mQPx`8^fGMwM}@tMkaYp}vt&P@vn zDl_p_3!V@nvq-n(%!_~vt~1p%P0ymu)DB3el|0;m%#>tO0Jp&Md-UnOlpF?+3>&1%$n17K=?Y&9_5;X8wa&;*qn)da9Cpp3RSNi{F`$PL8V&9l2-u2kXy& z@|7+ik{RE#y??T%KtS8YO8)#c;dCAlh(e`FvG*DW*pCUL6%>;`#pCm!(u*EZk;8C{ zGc)Tx%6M0g7nPBb=TA;h%e9(P1T7g$_wcE$V}lC$441hr9V=dFrmX@pkl4g zi?pFWxS3)o`Gad&pxcoq5s+&vI33L+ImNQLN2I#aG zR{mQ|&5V8m=fS)(RL@F$fGqK)S*D(upvN3GF3?w-lQ3{jxu zgUWv1?5n{Kk+x#WKfTsw@12Q`wBBU0>>pG777C68o5S1zp6OO+%N36ee!mITp?jcl zdP&*H)pTt5>*00bvO!1h-WMp0V%PWc&{1^OAzrT%CjIVgQ(dMh4$^G*!6^No(Zm;y&#ohA~{V6$U zUp#gKFSD|b91gP~8FhE}+Ce#Ny_16G@K}rNNOJvGQ_)_Q2kz~CBPT39%2#dMwNjr) ziK94}kCW1F@LbY}K+>V%3_&UAf=eLc+XmEhvkKUzybkOo+BG1=InewyNq7uk($lv2 z24@<-^1p-q@+mBi*R!V~{;g?`3^SCc)o#);hGyHoI55k<1%T9tICSIu%u-o~&z*la zsOKiGfr4mgN$(?5d+3g(Bya_g^?qU!tkuN{U+`&`FDNa=?eCEs810I^k{4jck7eEu zJziYSCGMBmZT_N_X)W~Hb1{W}xE-SjPg%%a7P9s?X$>XL??AP`;@+qUd2Uww@cRu( zJ=D_s)uGELDF4bmV?2P=%LZsAl#T;Pet=ucTzJPa>0dsgr`q9cq*{wr0 zgAU#Tm{u&+9nlJNG8^SuJ0YTK9#{)+`=j6q>X(qlg>{<@iEU^-VcgB_i4C;#mUD$)PrGP6 zY8Fb}dePG3tiyl67guf^EbDp1i>jMnNS90ZK#b#sE`Aao|3c0p#VHo)ig2n}%r{Ou zXBr8Z8sz~*C2S?l^qfpXg~xS4LT)Y3|Hy^uPO*THn` z4Ln!a{ex)jrk4`aw3w;VB-%?z-26ZpCj8$hd5i72l$A zLOjA6TlUTiLg=Zj9lNL8KZrMmYgmdom+Bs;!KbgYKB>~byTn{|MAv;={qmRZ`B0-T zC~G1kR3u=A(fJ=c zc-zOdl^QZaD+s-^acWc>Um~r$KQN0PS||p5{Z{jlPy4LaE5AauZX>ce>RU}R7_rJ_ zv{`4$5!HW!3PkK>Ug0r?>Bc5e8hOL}A~hZh8>tTuiPCf6orSn1vHk&c>_sX^r^t^2 z1&f)xEebgG7mEmX6sz#h-BD7{pc3{zJyS;=Sw!wlo{}@ekMDJe-B|R5fAr#>ns=tF z0?;WjVts)gDf?-4lmA_-lKqt_CeWgoIKp+eIbcWG%pTl}eRkzW6Sk>xitx+O(aYnO zOJsDpQC4>jn_g7XhnRE}&q(t%b$3O_|iNOfh7&%F1W(!O?})>g0|m z(8|&M?n*PMTbRj{eD1&;-Ng_Hu`#Ck-NGBPm;AqsMz4b)bYm~4hxF{$pi^JWFhbAAjsW@ci8GceN6U99->ZWgkZP%C_&39vi zSo}cjUAyxsy&vyBfH}iIw7jsHVkmy?R7XUvx3c&+K5EyA9q}qGV-xCtyZ`yT;nq{z zPuZHpw}TP53>tZku-naG-{0P#eab103svsj%0zo@*ypuzk39kHi&-%sm~upWwz_RKIpV&6WC?z%VYX?84M$;rOh2^D#RsLYX?S zrEYtL^L7~B zmdi>m-;wfYP!H1IKGB%@$2u4={a6K-07SFLHPW0DKbgf0679wkvi#i$T4K7a2&Saq zq+(C8=9Q^`ZEI5d_{J))??m*JbqtAjQe`)W>s2g>Cu}=s!5yP8;K_I);=V%h9~I?*!RHYEo}rcGP%yJZJ(Kmcjx!KOVxyH|NeV ztoq-+pv7Hbc9+;AR@PWdufpT6nNYibBc=4Dk1a-cjx3N^Y<~#);jv>h-L&j8y?+q^ znwu;8llw3u<9Wrv@}9rN$%JnZt@f$U*;fCh)GI$X`E)yyRLzNNy+1hM554~cWJ0s* zh{Vn~#w=1q&ls*Bd}OP`?vV22SzWxCEqDx)Fto*%P*gJ3H0WMiJED&f@Xbkev(cIv zP)bc}&du>r$`l^%e@-Nrt2fgEvuWQ%E%!h7T5Nh)*6Uit-?@d-5%d>lUE$fNlb6+- z(tk3wN}IGcF867+mLC4mURPx5?Et?7b3Z}n?C)c#G6w2OiH960RLd48N%_Q=d%~Me zju8$IpG*j<)wHKCTagQwt0ej;Dfsx@0(P0!(!o#ytFNY^YW98sD9x~TZIQ{Zpc2Ol zlzM{palgu>;a4|y0W!hCvT2xel&IP^r1~XG*tFizEaYcZ-@^_2EX;NbFZ0u9n75$d zY9qlS&}BK%@7ZR5TaQ$N_a!Q(kaK&_!D(;inJ*hAtGpL9)>11OLpA;h!AHMYyNAwk zRmfJKCiBB;N~qbUC$w{F+G{8+iWr20djU&>*?la1zj+gT&5S&*5vu|ce7c!m>F&AS zx$nT^(PczFQhzSD5bUjZ(pLxVf{nt)14H0k*sGq@lv;09wQ7~^Bwq0mZHKaviRt}u zVO5$L4bae6Bto=Ree}&2{`#D$SkY3W;oor$wiqR;?$TIBeZ_`F;!$FRsk38-U9z=O zAL~wQxnGrzQ77!BsrgxR-qH3iD^cct*@`>EYand0wCM_`b#L|Ox9Je}{9;z~EE<42 z4Ge03w0H!aJ-krUm|Mw%Wnef;UYsgeGN3P3BgSTp2v*}Vw}MA;{y45i89d{W_DE_s zr9RmTx_B}Fm9$V!nV#mUU#QgG*=uJ9M8Y4=4yNxg>+{2tN>n7Y=Z7*zcTc7@?!i;i zz|%~kb(1xAPCRBX+3H;Ls0y1u(tDP<6@@dz<%ZlfE{G=gd|1O3Wiy2^Vh>@~C~iL- z(ehgmfNTe-mPA%|uQ1 zd4pX7TGHOcxGxqXE+wl|cwdx+kXV@id;1tu6@&h5 zdjf6Hw`Ksm&x?~k3spmU`z6x&n|}OMvkR5XANsj|Sv~Chwza@<(2Et2LtDxodFeR- z$|<2%AShlr;{9sPXoEv2JnV3kO3ysN+iKZnO@iy3Hw&mZZTuNpW?t?ayErIQArhS& zf>H`w>u%t4fJ=ebRviY4WaQP4*t><$FMC9+-EHF{#BPgpo3+s}#ZiqMI~Tghsnfxh zklLm3-w`qyy5{WjbJW-?5zQ=OtB)Tm&Xz3ktv5_3?Xno}N3|Sk7z8U+Dl{fooUprA zlXhwMCLfO1RJtsea2}OhY{3}TyB&WZ(L+UdaM0@ld6FO45L+&Z=Z`l6`La`OUw#DC zngiyX%Z`t3;XrRZ_3jBcK#<}?Yu~p`47^Yn)9z4%6c$PXF+Ndk+J%wuD1`%n*3dnW zC`s55d%s_lRaaVsaZt+o@r+eP@`)hp&E01f#JBy!v1aejHSf8&KGpi3dF@u0QTD+p zQo=Lk(AuX}Iivacc##!deB-dd9^NSt=F&C)u2$W01owpBufvX-X4Z=U9qJCC7Urdz zqSInO--OwE%6(Onre60%LqiKvRVzs{Ww#$jM^bumM`ULHoE0%%ij$>{vzEE-{3T>K z%!Vw!>x5vRrUn&67by2Mf1TmtD>r{nUM~~#Pj}DD>cmQ{=KXE$g%>tEuXvZ_)-6__ z027xu(vHdGc#PqN4c@k!GsBztuWQtb;|z(%c7K`x^jNfOKky1?Sir)mD(|TSq&I+! zWpcYnMK$3T6P5AZ)n*NbkoNOgnTN(C6>8X&cgJ<>nezj zL@cR>3pi~*MBM$pbeM}2K=mc3XcLZF$u}&DzBvZ!FH7wZN;=}86hk}+RVJMpo%=3F zQ#oozP47?^>oI8>K+YPWw$vk3lG5WEb`$5p9RJCDlwG#CST&Z<&L_V8tbbNpFIiBO zhoAk8IpJX$lL@=YYz9n*&f2G?jE@T_kHwW-rlM1rQnoe%t+W z%ViZQ&+=H@4{+)4>*?8R-yj=&AGnv?XN^Vc05~ZGmr1U0RrbjPU_|2$?+7t*yb=W*9YQuT*W@xDWK{FQ!O>C8gsqk?I^zS9NLfUiJ)MK;>Scv9yUqpYP4b$aj5~JpA6lshe`3$WoA2vP&fT^d~CyqCsod3KA&X& z&Z^wJ4+EB=0zo{BZFd=A`al^Y}&Tv)c?bz zA(J*r}7Bg6zqhRM&SxS3=<7MHWx$;$u}1iLfeI}hDAD$f?c0s{v$;Ej=QQwr3h zfWU&%5Gk)V*x0(S!dCzfn2}M2ozO|SSEPUZusNt*_mUd#;gx!rsIjVdfuS3-3Wm|) z5mR~q-~bv;6S@?t&;j^v_%U==p5_%Dw}D0vk}&Qkf1DokiD6f+fbI*3YUWfY9g_>e z_)a}3PymhJ93{eV?e|w^?3GK@Z*9Xvb5cKgMr<@HA>Xhv*Yltxn6YNBj|x#N+xRzn z;UbhACDD9*YFH&OuoKh_-T+F;XK4K@+(YC(Ssv1g-G9-o`n8rup<#QmvkUl#k(_RQ=s?fb^u&cE)Q0MI2 zR=IpTVA_x>Ovw`64mmyP)P2%D73}HXv|?vQ2Vm*?VJH4o`FY=v0!zS3*)r2%NOGN7 z<*0)0nJpc?d#JE+CA5fVm9hEkteqdFh!``%be`Vtrt<&XY1eu}kBuBRC2eg~Np^F_ zO-SHfcH23n7aUUcV;1wOAh8p&DMoSAd0+^IQaw!e-(~ojbkIc@Yg(37;>@fEqpmmh z6$AENE&Y!Tp$nVzR=A0)L*rx+=k%0>keC&gO+iu6O}}*GY#eM=;WAh1RgSZt&OP;# zA<6)Ch9dZ0l<@jvQK_f>7;bw8RQzN)Se+{AzzKGgnkeAq+Wlab(+GD}IJxFFbGN{z zur^!=u;IhrAwRMCZL0hVl^1yQY_>BmL+6VS8ONyO)NzK`NWp4u-J+5^gFrJ7fGGOU zY2msuD-`j@;@d&3+o`jHVTlJ|r>`2MW>BXCQA(mc#6j;t!^Lm=Us4uTKn=P~e(+R{ zD)=#wSH_UkHXd-^G-UwyKkIIr2!qWtfYC%@)zJ%qomOVs7bELlKKF;vqEYbGpA!W(>{2po zt5Pp+U^DUW%A=#VU%ewyCc~d)e9Z3*X9z&!Erf|MG-g9jtd|p1g{3}d>E9%$Od5Dp z(4kUt=CY5q9FxEsc+TeT?IR)vCVfOh41oGpm81>abarS5qug%+Lse@rW(xaZl5r6yCn80Vk-ds{w`kq zw3h}vN#s-|xPwzMnW<;kb$?;v6$D%mIDetNdC#YQhiIcX&u6yC_XnC z`TpS_vlX<;yHV|>{b4*(f$Yw$DyBpIKEjU^y9w3?rfSl zeP)sqAQJd2%Dk77H$&p3l2|zqy}g-v(GECmI&VxX?de^ofF%CN45`pFIEeFT#RVW@ zt3Ak~4TJOi7>X2-%qo{LZT=zG3X7_mo)*zQ^_U@V4~J2Wt=VR=b-DRN>dMqQBU*8B z8w0m<$9v@zW{%B`9b_Hb68`1|oPF;QVZWf8oj0EQA4CUEXVu`dZ`CZex#tG^tjnmg zy-c8k(hE1n)6_`0g4n~FaKep#@0uzhiDS`z_^fbLzeXgdz{xm;o)txc|Xa+2zWu@7M;h5 zYpp`8Lll5nM}K~ijx|0cs0p|+Jb3u9Y06y%bnx)l>cW;;m5pUdZUoMprlUm!EC-FDx_o-aK z+eSZ*+z~`MbtIv8;X6K6uP1Zt7A~Auxy1T@OKzHUr2@WR)8XKf>N4`e_GMpQ-kvOJx=GoJp{te4Y$#h`_RGp z_q-2z@wkfLJf<6D|0FO0fJ#2KLBIQEnE>A-ve?}6om*n}n3`0NhAcV&2N>q23!efC z2e4ng&M(tv5ruZ=xaw{&3wbceUy4)z$bzp7HWc>cL;p>USG1$D8Q&a5!dj;5B$)4~ zl)zS`x`~7~Jh525OIU`ST@r}VgROq;OpOy$x+^aT4be%_A--Xeo!wJ8aXQ8W8+97t zp-Aj?3CRa*0v`2;iS32u@&UY$6EOcUR||%Wy3Dce1;jMtdvl6Y;*`UvVC!0sH6W=N zz4jJ3bQ0gHc+=Qgqa9<)-rMYR%&fwoSjBcM5y$JjbrQzia;}JPPr^D^bG0km-8-^K zYeA#UQhK^Hmg79K*Q(HFR2`7OThqzU4`;j`7=`=%@S&|`J&5^&pN!5lGmNhvi?ATm zmzNuS%vMw0;UESwNGZvWBHsT{BCC;zYK4)@#SW2PN<#(8@A`{@V;DFJ?3ES(Qro-k+Txwa4H)^|ys?a!T6H_sa= z97yjcb5cb!YnQh{sm58T9;(z$;}$bzS_esQMM{x4RMt8l5Q7{?4Xe>KVsF>%I++VP zi13q1G?r}kejKS%S4?~knOvF_mu1fGmiXMkX`77x(g-9`f88Ow-A+?YN3EFwn6KEt z7%WNi;FU^ygPC0A%M|HJvZerqR{iXH`rmz>otDWtb#aUQJ1OMbu)8BNc(vVEd_lJ| zgTkknYrGQvQH5-8syI#^i3V4$+5G}DW;**HCY4~RtNy%+eKlk3%an(DqFHwfAaLEB zlxlmQ)w||BfCnVNjo1>OgZ*5t zB@VnZj#$4{-&5D=;O_|?s>3m(u`dp5A;0)|y*OxQD^}{;m#CB@_=fYE=_;BZ+~nU5 z9|Zwwd9&`vo(^LcSyj#DX1nFfgNkOFjl(jHRkiB1N!f;;!0Xp|R1t)=tN3)HTWan- zAOn?a;0!l_vH+5SxC|x`Fh|U>x}vuYqDj|mylSr{Zt2`he}+{0bo%Xe-Siy?NOs+Zm@3x$>ElckZOMjZK@h&hQhJ>}Kq8+b2G|ZQYq3wfn*Bt!NGbgtX z)sEU)PVYU~vY~yk*VZ^*jrr&9d>cV53tNGDFGL8ZBx$MF)4k66M7^GrJOAMIQ&s{v z;O9^Yt~rQnE;>tF+SX@RWI1Os&1aGND8Rd7=uc}DQTur?AU^n_S5ImtR1RkXbQR7l z1%{F3FB;*sJ3EP@g|Am0P#?dOWl@d`z3x+p4%Lc`{`8XrJPkQMhy5k#T@?(fLT3mbQwX{ z@9iBCE5KrgFGh<_cOc7=`V7OP+jc1;d7=IVPn}_#Sdf;G#OzqsI@mgr$2R^O!YI3# z%yPMLX1U|Q)kf%`>`%J9-zKD{GskA3%W)E-`4Tj-`u3Z#@Xpql8LXpw8GAV{HqzsK z>VlGEL|geP5OQ;vMp+a|0I$g zJbwwu>>4R(S37xaWVE7U!%`0w@7fC_Xf%ZRrQDnPd~eIP)qT75WxAs=JF`I?(857V zOr>ffv{Z_xCW$Af0%0Tywl~A5Og>9D-reUTFmmM9x!=Dj{L;op{VY(w2%xq;WZ}o> z`pvn;w7S%PcQN^zk=0`VHz%cSs#;m+MF#@;Y{2L8rAmx*%%46aQ}vF2YBkWco_Z`j zvj%T~bXEaqFy~#porUrhZnxgmCsg3ON2jYR(fOZxbA%FpiX5$0?L zWM;49ESatV8$0C-Va0M zTLk9I^{y%49R#}5wF!#;Z>;)3=)2NK-aJh>Qm+8oh~5za7n+SOv-KCJ}f z%!?#{AkFxhY0y)cZYL}&?H2%=kgkg$95(bp$9oan-xxexA9;CaX*fZ^OiA)YzPm+Kz2#)X zPR&1mx%Xk@WC^Db(k(Dwj8mbF^nGS?;k`sz);YmkM-EoH__nJrSgSq4rtc>ThsnK6 z-!_fb#@~ymvUWVk&0bECcA?a z%y|KkiTY}07b{yaLif$9Loac4QY0GamqY44*NonImid6^U0#6}(HWE3K!3aQUQs+N zRzP@(KoE=XFTzbNZd1ee!`R`ty$g|&9t$`rrp+6QfR(sykj6#ufZ}BSjw@m)C|QfS zL@OOIz4^66?Q{MpVuK@~FYw=ok)UK9g9m+D1yOtbGKH z-tKPxc>gnk72)mSDNSFZ4pShZG#z{KmQ{R$LpABy&egOSnJ0U&;Cm^GyFbWBiZnDv zAL;(E2!9>@{mGZ-g{=AtId7i-h*l#cVRyAcQ6Zim8V|%Q!8VH7&Ca zJeOngepz48uAwz`Y~!;u)jB*^mch|4DngWX>~uUN9FIQjVdr+neT@iOp|oCA%2K+!x6BFG&kbg89p{?nR~qsZ%MndZ8pN1g zM(|@DS6)%n6?dA$THkE0CE|yTjZUyPH&n$1Os-HYtx^u!YFgP{U{)H9Kl!e@<|7@L z*V%(SClx*w<0%hnTDr^pyr}hvk?6pQ*wEc9O&1EUoj-{sIcPmmk8t2`OOB**u21zl zo7c`L_3x|k=Yo_7+0i~|c3ec{9_X;d8VjIWL;~7w=OhFl26o(XDE!)NzKN|fyU=%> z;D`j_94tRiZNRUlDYIn~LR*u)(|Ju&an^}arU4h*G+wwhct3`HeAmdu^!>dOh6EP5 z8-K8w@^UPAQf7YpkS^TUxe6I}Uz>`%$l2pe_t55{bT1eC_K3gxtTJ0L6 zMyoA$pn+Jf9y$gUm>)Bo^-E~NBQLfETTZ!eEMooV9)M9N&)m+JYL|AIt1Y@UFUFPV zv&%yLzayON=&20opI zjJ>ek z@9OWytukm1V^ubtB37TR3Lo`>JL@yuID;dE`!kWPy^)q(Z@tFq%e1}J0PamZ2i;&n zl;!$9(%iW6UH(c7#r|#ByHjp9uxOouH7=tlDbl}H(emgw{lmuNFN%`;O8IvlyX}{n z_uT_yRU@_=msY!ADPp+h?K)D^`x=wqBe=AR%ndHbqlqmCM}qb*B3t{RVmpi!>{}1D z*y2NVBiu|*0;g?G28ya<%tX)Phh7*~EBfTA{JQV4u;^4^V|ds({4Rn&PSjFEueJDt z_WEZ{JmylfZGz6#Au6`&p&JjAM;*W7%I)a6?qBGH+p5Aaw@JQLGxA1%XloT zM~u_6&t)d0%b@e=BEgfjtGri(*=H;6fb>i8~<^k6cVW9sAJjntfL4>nXNZJ|oBMOT(=~3V{t1 zk7pr`S4Od%J9?0+2%%#`-G@;T*zDS$C9cXjVL@;D1BRb!dN12XV3FY1IgI3RMX`O3 zeWcN+lZTOETjP<_g7a!oGkK2RBCY5SYiR>5QBPW~;I%rMM)jbqR zPkh1iHTj+fQQYyf%4E|<$N1)Z$z;7RzPjnapYu0PPP zReJA)j)(||bm>j0(v?mqL8bSO5JKpkgdRvp@>}k2pL@RFbH8);z5nImS*$hZm}87N z<{0lgrjp4WulwO#~_G_kht&#nAr#q#v#PQW_kUzVO!w{vesq=#&%FBc3UAK3Q=sJz>H( z<*`y7A~`qTS^ZzLVGAWf{!-iIXrrt~=j#Nrp{t*6zC&F8o-Es2*yOR_PqZoMB;{5N^AX_NfERUI53 zsIcgdj!mR;&IF|d`N$ed<#}rv0j=Vb=ZO6MopzYEz4o6o9+eBSrcJ=;k*(q6e_T;` z@|QfafZ=EgKYbJNw>;^I7{&0M6|*iMy@K{0f>8C=p8aAMZ~sk%onrUC`Z~u~S`eaK zejTLm)uEAR4*jmlRP2#|KgGs=g~W~e+ly}9<96gy7B*`SO4RSqt$?`rj;Jv`AZi6_KN@aPc~U# zrB+to^8M44u3S^P4_xrePIvR(ZM(>NNjt%m0h4o>a_W6F#xe7jj;%DuK)0+?k-UMvysH;GO^Il5t0>kAg+Kxf` zC}0laTOnKvo#sXHSb%cwylSjsrNe!FQqqn|`uO19MEfL9t>X56BXBDQf=aD%ub9@7 zt7CYa)~;_NKa5h{uRocym@sXxzP(>p_^_mo-?Vm5JQKfBnq~~Rtu!G}8pX>^mK)_1 zS*MHXN8_c4LCf_)jb86~-|@rNTi1gLtAa-he5~_-`n0aCeX(WFRbQa<@>gz_ zhCSd5Gvhv`{K7j-F$ew1DOk9zZl7;+EN5l|L__zvxm9(fHrUFZRXv$M7FynJ8frBY z)Mni0?qzu6N-F#9&o6;gB5O2_cM|Ml`{U-UOYO@59}jDOGAlSur=vhJXaHGm8%;i0tR;AV!g zCA0`Xuk$N302O5i-3+C4d#Y%s%|Inhe|4B#ctaiQhMp_BJQ*jh#kzs$-`U*8irhCl z3-*u-$D&KZY-TM6`l@XQ&y75{g%4d>;2U(AgzgpTZIiQp2Oj5%+*`c4u1Pmu!7Rjn zyt=R(k*OWEY*keB%zI$Y^waBcPVB39r1UWoR4sEy6X$o=wE8kAc7^w zO?X2m?b9*OYBNGXdt~!oce*R?n!4bjEbONVsmBkBwa7jl>x!fyu`ep`WzE7oE=zX3m`(7H4nZI{B z@20-W z{Zrkj_a~aYU;>zj5lg%JUO&`r6>29Bp{wXBNvRw zi22hHz~Wn0GoLq4Z*qHJ?FZ>Ho&4e?Pq$Ls2SBXB{MQzks6&rA5?$twf6AOpg&v(Y z4X%}sl=dw#jvQC5OxUl$g00Usk6NjpRs^Dcy03j!uQ8J$5|6z%3iT($k{XiT^B6qV zXlzj^;mW%FK^v9Elpv2~6`zgitoquPw5Lf% z)Wm+IW4I)?e8_FPn>MyOez~TbCp0aaHs`4t;C7@m&hfdRjDZlOkGy*!A1zAMM8zb1 zhbSd4o4?{i;!k7p4vczUz_N_9k7c%<*Nfcpjs}D3=K>OGk8+6z6V+~PD?VfP*nZo} zVqx52Zn8arfBQtkcx}^aRxOt!Xzpa4+k<>m31!Ao_lAVTZP~^@K1#mUR&ZKDs|2bo zV^n3Gu+VXZsHu-r5ga0ib7%Z@T&r(eDg;vUyJMGCEp;v2?9Q(z2N`8CTyhnp%=Vty z9>G3G4^0jS@3uZDRX%Y#fkFUu3ewF zI9kXRtOYx)vr$lT;}$?l;^ru-vX8Q23KN-6ibO=Wlr?H4Zu#j~);=#?9lF^Qfw z-D=Ud8x63^5_5c*%4hhoOmG9ExI}lGfsQ5IfW(b8>@1=U1pYi^cF?|OW-A!fa&f3S zjeas(VbQn(&UB3@n#%PZ48>bee6cXO%iLU(6YQc`7h9(k9YraJ8(Ca^T5g~&SvpO9 z&krAAXiQDB)AZ6covgvErQGa@Ot+5am zM^9HLQiXb%5GCc^p0|pD1J~PTUrMWo=DdORxx5z4ZL1V8GhF?wY_c5w+>D~!So>_z zTRih{hKMn5o^|4D$+@Qqr^h*09zr*CzqeWFj#_Cbp;0h;HgVa0W z8GJrQrpB)jB}2? z%zN*#-e#=#V5z*et2YVg$y&oBAoJ1JWVbn7n;%vOa@*OrQrGJ^4RsY1Z3pgeHfUc%-zd-BW1N)q*`w7``VV9il8UCkx-ngsfMvMA8vt_TK zWfp#mj}x#qH|syh5(dn7Pse&1Y>w(BYkviUfbCOv#NE3n2Fo3AwoYjiIfwJVOgdEt z!!b^HdbxpuZoZiqI4j zREXnlDiCg@^_)8QwUoqtIN1-g>#(n4J%P;wS?ep)MJAKDV)clu&?BODomvN6^{K54 zZGNc!d?P;wZ?8{gm^8yr5%YW`;*aF9tuo5|Oxf=+R2aWp76vt&>TH9$(W==#Z>ZI3 z2H%j>`&!*D(9|nX(3(NRPnIo4;HYWC$DEd;8(3x>dP(zTlY!FHYuoeFCqR%yW<9_e)Fm zZyC?OGZsNON^9)4>&jZWVChWhjVfwO_x1AwgIA@|99W_zym5YNl2qSl1YhgnNmT4B zvyU3gABSC&oOSCT-WS3j55~{D6h>IS*dZ1c6Iz9bXfuD>KjX18Z$8%9-d4pPmdTDw zsbS$}O&ie_tUrEEZl>FXy6kpN6gQ+?^*$GcO83<2HZC4-I>v)`jik9(fd`_Cv01Zh=xO9&m$dG}f>nC9x^_fbqi8~lxebh~Q(O1;VgsIvMnft#VRvcE%00&`YO2LD8f z1zD@LHmNJGM{LPPh>#U#F*y695N#7JD+}kSwD_%XGm+;Rs`nEsJF9@OUfK9VWJPHE zNb+uL!wvDq(Lk5k;`Uypdi{IT5kCb|kAgnl+T)fzZuCKcMr5Iq>l@LuZ|9$*;GbfB zy}48p0_nHxp3E3Ge1Ij`-#m>w z+B&r?7+v_5}DWyy?bxui4opn1M$AZ4}I1 z+6n@8O6ujxbQhk+baJvk3pXnn2-nQVbLo>^tg~e{ewmyuT%SwF)2cL|1PgDn%=JDL zi&pK{Cu{NW@tECMSw6#h+hHnv>vcZuej6dn=)M6&-Dg$AA@IT)YKuy*5cG_mCkkF{ zOt>DNJNe~>JnU(ykDl*=%xLV4dy)ZaP&XY=k|B(W3~ps#B2ifyya;Lav|!Of(rTo+4KoP>WDw z1GQ9&RE?aN&}?Y6DR)Es7PWD0VM9Vp&$enw3MBoM!8wkuBPgL>0(BO>KgcZ{)gL;I zrZYxfJ~9Y9c}dnMC7dKmi0uxa&MXy6y^i)H&oeAc5sb>47w^(y_4zh+kPX{>Y)qU# z-X0;4)Y{vY!yPwo9JF87K^X{<8jqXfar!dUk@bW#? z3rKBZzmyuS0n>be!48}4zZ{WB{sm9i<>o@@D>@fTkM)p7xQ`vu7>4OZp#&iQ0=c}I zQhjjF%IyrX<#}mx;nIxAyXhx)T~h*5sQs| zjJKWXj}B)pKECLUeCVZKKdf!X(&@fxU2M2t5NCLNOg}7}8mLQu%;dAsAhuPOaQ5xZ zp_+BwxSfmlXNFaY(>+a8w$RBZ;F#DjT1bw8ih6q`k+}88$C{J$*N2S=Lgy5LD37jf zu*n|E9T5e$^`5}JA6)y87QlTl<&|P`7_i)JVFSmUdW}bJ_D62!@)!2TD=wvx+OnmX zsHrS%Ow1m1?o1rLRk6FhVC6+t4WZR77#Lzx3nOu2+%jMEZ|>t3_M3 z_M3A&^Z@s5cMWJJSO`McO{XEJVH&9sHD56fDO~u@7Z_Uc`P%|Bipc~YvL8U^vZ-UX znxM#%^JsEsRH8*aFIbo`MvF z5tyMK!jPgd3{E_fpWQWUp*!F53=PTF0h3Bt?wsw;aTHA~21&RFgs$EWTsw5Qxstob z5=anffq#8=n@0vx@OAn6EKFUDKMc74GQu}|0D2H#<2BuXkUO*!5RxtxQ>DRu(|2Xe zSinl^q8dcugf#nZx|S+DmvlyyB9r3XcnjU0XZ$ z;y%s~{91b9#z^Mo)4Tqxii~6wQ#D;}@+|ax+c;ope73Ts!#VfQW73uIC=!v5PVJv< zU*M0AhGJ1s*VrMJKFRRR&qP}XAk4yBwGt9HshA4i5BdX&q%c$T_Iq2a?f9!!kM{SH zFU0h#D9sm;X49LONRL4qNssMGgv}0{F@?EAOuh2XW?7lH4IT=LgNlN<;BNyIt}WCv zgO;``A}}q-q`m6HPC>#@}j)kVR2d(RVs^wYEu%qz` z#iPAO-%uKytH-5pBgKrgs2FJ8$38LCUT`GC9<1!>4;OH}r-;d8rSaiimnZ!MDKt*i zX=e6*Zc$g^A1RHQdg#1?FV+VRLplAy*^oQiZo0q9Q5INIQxvbJ)wB?iAirFP2A2*3 zD(C^i_Yw0uTeOYWABO7n>@DPD`@xN2k4GQgnDE+52f5PwG{uz6migI{ZN8f1+9skk z)ZB6 z>&f67%%Bo;(VIVm;L8>Km6tyP-7!AFal5qlKW+OhGtc!_ps6{uk`?-ku_bL3~Ie3zUZ z@o5YjbvUfijUWPzDPNhO)D!4G`7S&s&>X0TWlmU_7Tu_r>d-i@b8B#06eU;iwGZZX zbrU-NWBX1;&ydZZg9f`YR!b$guw3Xwpx&tzv}83NJXH1^jacj-p?45Esb{n3EY{eq zq1gEIZEhT^j7%>|ScRsU6C_ZZlo|Ffr)Hwmsnu3&m>V1jW5Oxg#>>~phVXl@<9k`d zl;ZrSGE^&Dy#@9@)&(5P&EyK}L-~xW-|x_qUy~pb9L`DCZ!}WHid)YF+cO=a=V2_A z3whv+J|^!W-K7zx-8;WB)wes%MJqzB()GW+GJLs+psDB^P>B*;zx)`}UW` zw0lm2K4GJ;n+g=-;N71)vsjtfKj+kVSfr1GIJqVYco*q*C}dwR>1>z$!Iuyu%<$(g zK@&Pm$c*$}c_*@wTK~yqR^cNe(DY`hTgR&7ZpWeeY_E@#(Fd~SMx?)LyvfDgmC$23 z!rC1LCmnywDTJ_Kd%m@iZ)Edq)My8u=bCq4i2m^}?A5_A6XxdOn!O9WLD=x?m>JYJ zdpM2T?IRZ{Zv`f_^od4vuB^kN`Ngbsv0~=x9}$lzC3be0yro}J?YURXk|BObTBwk0 z=vZ@Qcx!D6y)p@1>lc6HF-)C05{omO5n#0=bp+mU!jOU8-vOU&T4fUj;p|Lv5QUl6&Hm!goNId#PT=x2k$GX|^=Fuw9Tt`7QCse0yBMpzt?ekYvRK&YYxk64#bB^5R8?m< z>)3V)k5NeRsuuw7Dj}d3Y6Q7ggge?#yX~e_2^^nO?YpIoB zr=8Y&Ok{{-b2Z5+iTWxZ9ECA55H7vQrHqZKX7X!C-gCC&3L+L3e!R*pnXvef{hJ$h z0rQ*%WdFj?iDcQ)T!m`C(#6!wQsVyC*%QppSr7qB_XAtC;a|*@&WfwXp++e=EZfhn zGm(3*fwkOC#U+}MjM~MzG%T5Cg68L#sxCc@1*i#!%E*a|=&%lv+mIMbe8B`d%`TJr zB2lm0Kcj#j>_2PlTNfQa%-@AMW=?xH)LcS5&cD!yRD3)sn^M^Dzj*Pm0B7etbbkT8 zga}bJ!llmRzaXJFWK<_SiZz6(8AwfilBeYkw;^@2;=hrbF}r21XcM1xGY0N!UVr6- zhzW4@qxkpW@2Ti_=clCXcH{xkaG;byes||UAt3taeO4M~k23kEpg*!kE8O#_XexAO znnw!!=zgRQLNT}U4W_~qtt*HIFF)@7;TZhwqscby0eQYp+`6C~h`Vz<=HNN6$>*qd z3@Do>h;Od&I<>6h#*c9{o%*K=Jgs4YDp@f%Sk|Cy4!Id}a={m3Lr&ivxd z$$>iWtd3*$nqc|(qs#A}=S8plnYIJZB2oBHWPPApo`H2t!fZJdnu zkd9#`E~ZK9Qn~)%z^IoO?B44mf(g}d2zq%tJPa+fU1abu^-HHVY3uU9XoLWhw+8k` zb+AJai~0q*%@DO}Qcjm^2@wx{zTjHmMmO549=ciQzc<%J+=PVb+UMV=4$lq>!??kf zY@{>&Z11J`KJ|2nO|FW#1RI&p7bx|HRadGq7Pg2fUlc1A7g8M2w{HJntBV!;0%GTP zP!rYZeK3b%(})am^V_oWOa~zzr{CD%YuY!wSozn#iC*F#0gdCQOK_0Ok?D_=i zeqhP}0{eM-joXSj&`Hj@6m2OZR}Fq4dbGSf5%$XlTM2%9-V3@KuQzsXwtjlkO=gBm zZk^ThbnwkLy%H_QUF8G?FSLt{-N>Okd?hjQ(*m{E-Kd`1)h8Wo&sOcbe2Wr6`EpPW zPWa)?@%Vc;brsK#%Mr8Lh41JxIZ}>0{gpVf);K@c*4~y&NmnwYync{vD&mj{}nQCpj@M)U#%eRcpLBywc z9+~-pkjb5qklCL@o~`94$S$&XKDB|k%|-R1AgW=Kjy)5U-tJk)_w-+dpNSKAoJ8UR zbB@t+cy?3nI|_BTJlEZKyRT7K;#1Yd2cAXETz{nj*j%dtrMsS)o%FQewNb}+G6!#3 z2uMk6Ml}a#%3piauA))}$YSwSoY@njs_~9hbH8`}q`qO8 zw?;N=jmRCVZOV++I8(05=uI#~x5#X`ER~_UhOF&kN@wD#{1up2%X;2>^FYUYRaQ}u z4PlAV8>WNmd~|w8)ln3vRX6ql%b`!+rO0~MbJw={hKUIy9bD{>W4P96keWO^Q=0J6i3Iq zC!}+9j!eMTB@lvPEE~EwTgDXpqH|=SVIXWbS?(t;fHrd-3UKc6VQ?{tU{7R zml>)>N{V*>&6ymZ_(=N%P>YgVZ&o=1vhaG)0M_itiq;&iCQI1Jj)mNMn(Y2sR&}XK zolkvB{}8c6M|J+kz30=Bw7cTWr+Fq03=7LM6`Gn1{;rFlyEu`p!x@!k`#8%C|6CDq zoS@Z(^~VDaPJPE%bEbd!2@{o0gDFSDz2AL}GQzhyB6BU!8zItT&|$Q1VfS z6!0;Lx>)q@P3*)E>3hqFsSf*+>J}B=fm4WEgx^(%%WM?0naddQq`kL~%B~jk+crSQ zJkTb@HOVoYgO}eDRLl<7R*sB$Z%-uwy*5i`t9~4T{V!U>P9#42@Pyf#6~UGa4v z$*qU!3Lu|D19QICEby)zOn)AUBOgS>tnDS^rUSe8)x4HfG1G><9ly=WLJv~GnJk13 zBSj6@XmYf~%|4uym^^ibcoaxrrCUMRnbLaqqq55#= zFr%EQ?j@xbd4UEH%aI(_s2G204aT(Y|A0GYdLU``5iPZe|BB!+p?~dg+54_ZgB6JQ z4RG=6u#chVhqVIIQ0>QP4iLbZm^38Y7VtAJ-9eYP$`|abXmgJEOp#^IFQ>(y31-rp z{f^a|yI^FaKCMd_sz9bjUT?CXu@Xm9gNsswp*(DZ=ww(~eM{L8aWhGCsC=!pA-zr| z!e=T7Pa$5#ajYLWk-BSq?oHewCyrP}vtD8rE)q@|Wd*#JxhL?Fa+h|j;WSyrJ_A&9 z%V|1U-+pFcm!-GmJfeMl++bo8+bd_(GC7_zq_vL6TxEJ?$vGiL6;$HFcyvkd#px4g zKlLbbnNK8{^gDrd@$B8!>YVawjnz{kI z69&%v-A!OShJ1aJRTSy(gHZQC`x&j-?nA4Dlmz-qw%-7h8o6Tx#lpdo5TKB&zFG#* zSKsf3^>;xRl21-!w)p(%LdB(AzU{TUm!zlAPXWQVEYm%XcMJPh?b0>tktK4 zD1L1*Dege$wf3LEQfpskw7Tq}PT^*n&^&w7cI@UcljPQ`mbHbA0$X=f1mrn42EK(} ztr*07xDAi_7K?<VR>%87Z)kYSq!|jrU>v`M~(+oCj#{&yM6PJT@;l!sQuEy{oWNEb_w(H z5a|&+l`zGeUY);7`V;IE>OKy2ctcWeWUj5t5Ebt2nYX2D?BivF&q5eQD5Mq zNjpaCwk z<`HaxC}RUR7Z)xbgPXgB>BOH%wv;0Z#j=qfnbPgiyM9c7GU+kXw|u2_B;>G$)+NeA zY@>m#OMHB58SXJz^?jt_Hgv7}C}9mVHM2>AT)@VhVyA>#_=MRbBN<4N=a%VQBYo=O zoDgZw8XY6K!yx(N81{|32f=NCNZnoR8tulHG!I&uAj} zn@0>vWUQ5$Ki!J(^u>nrWo&t2m8=gEuHn!`G?*DhfEdb;`%Oo-&e~fj?;lNUXOZo< zUIPQg*)NRk!Jsq^zx1Sc45LUIIX6PQurPJTYOibj=uvJ-CEB>L%ChdBuK&1S^ER(X zuh_&+h(*lK9vQB6ML^oaBDL6Up=l!wk%UYd&-D@*QUeM8{Hc37hgdGDI5)W9BY_WC zwO{@!9<=JVyE;50ZOXj1ljYL#lOITwEi$`h3XoMZaq5$mSvA%1m`X;^{0=1%{>HPI zPy<$7W*e^32(Qb|!p~>{$iYJVj6dM;ut~gT;=|C1&_c;MS@oj&-qxSPOfk$w;`7z{YReUweB_zs5h5cl z?y({X$ZWOZMQ^^#x^Mh?Dmt7(_{kIo^RQE(4&Kc6Borssy{~f1GjT}~K(s({z5#b+ zceVk8Ymr@Tr-&vC{MQGtJ;sm+b8LfIqZVE8Tl^?RhbOZCyiLdi{N_JKh;|T zhY-sfv$XvmV$G#vfa*vBcAECxrJVhU`#8rZ`@T{`Nd+BKV$QG9B%xOATvP?VyS^4I zL5NSs>oQ&fd%rkW@&!LkTJucj&Yf-qsZxeh5#iqkhxT^d2esVZRclS`>hd2W&#~aZ zU_kk#5vwp2t(av#Q9diGPr0T3sdD{+yiYI)-Mo8b2zJ}f7qAmz2+<7prkmnty zUh|B4^@Hu!L`qq|n>VzGzi^x@yusDORw7tF&qcC%s~qc^0eQ`x>_r|ZvgmVt;a{0G zv&v5>ak*4LYai8WFO`s&nP)Pgr?M}WwX)kmG*2VZccC|)8f>GhPe1G`N_aav;yGd5 zo_N5dNZstx13Mo~D7CQKHOo%=CiYkXRX-q$NWe8Wa+^m&P|*jJ@<+nkS@$*qbBgzg6Yccw`8+>z@>^~V;8radtCv;FxmPmD z#(avTj82bfwDaQw1)qgyhkYo9N(>f{=UX3;x;f=*n63Q)zwCnHCBs6Y{SCJ-hFhed zmvp~D+BXoO7(V3$xeF}-*{&?#!|dj{+>@lrMoT0Pf3|k_&UCNdxSzXY?@w*9=C3El zAQ)+}59j+>O;VAVFBOn3x2~6WrFw%?xqlO)s_Q>P?B@; zjf*WS6UD?ZkKzbzd)BJDP4Ld8MG{9(2NO$9$eHmM$IQ6mf{^TQmv3PgxywKx7Z-AQ z`dZA-)hlC`wbF@u1u~`7a9n&2 zo`)FdA;npUTzNthg_o@gcbD($9X^ZtrGb}Hq;8>D+6n;nqir9kr-=IS?5Z0YGO7x$ z0d7@+khqz$N+FlYRqNZmpXm9f2!xx}dY0_MPF6=z2Csd(GKY!8_ZcBxWzcW_Dwv*2 zp}gqDklE^BC&roqZ7z^^yY;Mb|C##bqnt&QbrNv6n}gTj!(N9?l5_a3)%=wORVICZIoEE$kVR$F!#qBDhkoAe)m*sT+}pJ z+L$d)qT9~okdMHynJ=XQN=DUuMCD4+(?U*|j)YfNHe2zdzZ9qg72@$=cgaojU;Q^0 ze4^&9!f>fR0#wbMan-*9hu(H-gSL@(*!JtcEU6FY=!GZWaPl#9d-(Yy;^oZMLFVku zA3V`kv)?C2-dZ~Bk>|ha7DuPJAB$AuspXbKao7FUm##|9w|Jn^uqrECctG<0CSd{3op4(cI-7p<>f)^lS2zjFX0EU*MMN~*=|CWA?Ff*bg zOgb4UF%igSKDNBcH!V?TvQ(0Dss6-b9oh5^BCoYeCgW#B>b0$hr|{#?u9o}aTF+O5 zsR*I60zBp6PY;X|i5osCXW+XWkp@;&aOk{mM&WKrjgSSI<3jgmevM)ZFBEq+j6Gcy zy*u!^G36qTP%pRDp|Bs(>gR%cC#N|7O-*$ca!!NO2C9tVDYT*68Rp#Wxf7%x1Xu%= z+8Jr3ur{j(g#H;aMg;A5FOUyTGKjrgr^$dWdAC#} z_|KNlH+uU{+k@`M*`56I6gurTt|a`84A1v@?*EX5WT>1;lJGvr)$X|U>j^|5W$pWQ z;bQz1L)($qru8dRf1gK-PI;pGtkJ%d-w46WG>&l3=8Txd&db-Psq0PCyNW|9xAq_I z!&sP`4@Kn&5S1OKIlf1CW%l%14k`=ZY`z(j7WIwyY4LOE`h*C@(>Vf13?-1LPx?$b z&~R9_f9rF4xmdwG>VV}Q)6}!7yV&T=o3|G7r;na8$Q=zV%{l5gfXzIX8-!!eu%~;} zdX6X=B4H z4srpwOni8&+FgG7VV%)km7gZ~?TDl{61&`>gd}@Qe?fo0ENWtq#^!N?cfvhr_05Wx z>mdXEn{~(!{*wODr6jD$?GNW}zA3&iX?pi{*1e1A)IomQF$(pCA6oJSF(1ArZUcG|>-ZT1cXkdMm{xA|uK z@WWovm&SC)0Nj4)?Ymp<-x+@v2Tr$lRR*TNza`jY_g|Ua)A?@6%6084w4w_Ym(^#m zaUp%X-U%btGT>C}Pe|qoLh$32hwgu%9|)WOj1!=0FPby%56v!{A`87NM+;`2?f=+K z(MlthV+L#(3EW-C4_P0vUqe0?#HvS^=lffUJ9=wOemOgwQZTg}-40A>JKMNq%Q=8p z@Sm9FgF-x(dS;trA=V-2j-csm=5{ZWe8Ri{PWA+5+GbN+RgsI;wWCPEm814qI49{R zvx69m0VoOSVMR|3ngZZ=$XXsmG~|mdn@U#Cg@?lo2EMl^Xr*Vr)1mnB{zPZ$s1=QB z@YPy+M5+yJVXLsIv-L!}5XBvz^i=%>_xmZmm$OZJ#|En>g9t(L9*s<)VhbPYFpHL; zlRUnnea9#h@oLKA{rE9nXIx7`Q1BZID+acm0Z;F7rs3;6*KBp z9A3TVx(WN7rA)IAx_SYG4!!VW*WryepX{j`ebKHCG=D-&<{uP8_58e0)j8??l(f%2 zUzAJaeyy!Bx;(|m5JXT{=Bf>N9zO}5!+s*nZ$zRNIRLIJi&Cabz7lb?fgIVDD93u- zq~DmaA~KiP?y=#EqU~zEZ^73JIgeHP-CB`WZK9p-WJ5O)6pGz#I zmVU-9vHCHLV|^M0b|hKGEgS57(rQx9!UJL6X$5aKtYCo&kCsb1M97&nstuAyy{8@` zz4Eq+hnp!RQ5p^484HwRI7Wy0kX|B-P)fqM?Qd zXQFwYUbLAf^2q0g(BqWR!Tp+D|A6m|;J0l%Hn0VsVdDEzMz_?1i70_;sNLt}jBW|B z9^i;lZ?h%6^4Qgly6)+S)HvovQ!R*ebi}F%AB_++1n-FFc_xtyXP)WevXqte_7mL% z?qC@g)31G7`}`DOa~gfI(p~Gi#Soe>6d2Ulz~tHcqRhBS$0o`%BR;^tO8c_>lSa-r2n7&7nG{^)cMkUz>4;&Gn}q$S)KD*U=Yk3L-jST7GY5$mf?^dbF6zzKWPPIQza`m@l=6 z&X*%B+y^N0-)z5wYa#|!kvqHzI(eL{+)&Po>w!54L8u9D)8c96)>;~EpHo1e?otVJ zdlIE~I*(u&6?@U$zjJ8<=ZOeO))0>05E#*2XA&dvJKqf<)0!o1<{q|460>uqJrDbVu-abel+ef5a^TFZv{BQcg7Hl#2ed zZc^#Yaco-Ubh)BQGZ)88I=&_HlrYb_u zF*XNrAfgn=V$Vew#erzeYneH-2i3x~CQ_XpK%)ZB>kF?!&`A@e zwhi`#L!r%|?nlp^L#hIHJ-5pm1-vNCGut79j*Y{f8^~F0KSao`vR7Fd?ZoFroX2PL zY1DY4yXnvU`DG=(E&eP#$UwBuxp0~U(QkbQGa-c2Cz+Qol=HJBvntcoXK=< zEN?T3{%(6HhH*VSIK(c&3M|F~@)dRWol|xMug!KmYv6*r1hlQSZ3rDT#wymP01%DeDHAPr z>*>TU?(;;A_9mM-cdr-6i+{PLN}Db7AIdUFN(Pui*c0q~MO2u=&~;)zSx+^@@i9rt zP;(z?vJ2MUZ%h+l`axdoxrb&mJz+Y2`UT)Y^BL4cbO9vTq-zeU-Av360BS?UUfVH+ z9Ve1SuUM}on2cTOy47xUUSov!vsUXhJPf3Kqhl;1cWztYu_`WOTKM+bB;i&{GG}3p zlMn5l&b6W^Rk~VHp8>kaoH`4TRRKo_mv!Ad9$E6dKTZ|C3v*rlPc-tx-xT)?>K`mbR1fq>7TP@o z#sgK3`8H(hRZc5Fg-?!mksC*}K8PjFqE*Rns8Kz%)>rJ*L@65e!t?VEoSTxO_2C9} z{s=#m>K7f!7s^Ib-SM#E!tL_U)azH3*+s_d1#C1#JeQJHg8*djXz!YZxb8 zn)~ZH#@sVd1*zXB=iB^R-iBz3EUD$ijsGNRq2H+iE=OAWe?F3AI6aQ!0 z^@K?N(|rGZ)QRdq@=ZuRyZPV$_#ay!)W!odsthW&x%N+Vezp`~Rc({SJpWlr%)pFH z&>HSM_NQA)djBN>DkYrOkM(f_xCzGn;f-6edaw;!qFsWB~UWAgTgv(f8Y;^py} zpt`-MfgnjB3L^F{4M6{lto85L!1~W$kFy0fi$;vHTxDWQez5cD?=miSwsNcO7s6oW z=JjZ@|4mTxSAP%lk2N2qq?8m6i&iTRvnIDVzUIYth&o&fOXh}R#eEHiEY&SZCT|pw zkEUA3JJI#usC%WgwCkQe___3~fkX#%_#(i|C*ie9u}b>jyST8qP2boavJIWd?Va(X zJx$hMy>pXpsQ}@z0pqFL&eM+3{fYs(y9ruI<^2C0oUPaV&JwcAg ztVs#6ECvwuv$KUj$Oog^c@H=>({6fglDGj~S5k69clyIyY9wptmi6ojrXAFQ*RBzX z-?;L>X*Zh~U<2PS{$zj^52k5u4tghGoI?UNTWXz46YD|Yuq)Wvv?TDY>)%$d5PkbU z?7ekVlyBEBE+{I9pduikfGE-+Al)FKbPnC!-L2By(%qdy4j|Go(lszN5<~Y8=jMs` ze4q3BJe+m@`u)~=`RiV+Su^*wuN|NL+56fTuouC?54ir*hIv0k1=CWYWp#!`n=mx% z+8ylvj+CnrTZu@1ZT+aNO$ZfO5c!=)dH+F^WoU1V?aKtjpbyVvr1Y!#bW;z;w8A`I zDd4Sf7C1Bk3tJ@j{ZFq!S$bnJZAo5k$8Jo{lNziPvt>XZmhlvsbZK&H$>DKMj_O$N zK5~Plaw2sl$8cc77RD(0x&8jp!D-taR59%Zr@owZDi694W+_XuXyQ8RJMslXE0sD+ zTE{N4nR`C>S_bkND<$gmy$N^{xsh2|45f;oBTNU`3NvB7t`feQYU<$Ku3I_=a&hz` zc%?y+`SfAo%hhciZ2SWn-CvrAZR zyIK6qSC~IWIPrZN5h4`N2|{-Bi9FdK$h2AsE`wmfz?_KZ>yBqRZOnxKNmp(r=J@=5 zwvlXxBctWT64Q-tcV>LO|7pqZfw07mw0In$fST~s;7m$379a9Ly#6XzO?bygp5@r* zX{A+7AqdL%fBg#%H!j2ix=BfNeJbQgrv^$*{XoxN$q@OG4+(p;|0@fpB%Y?xK5pD7 zIWfQqcFTMpA6-cx%02bGwBt*rxO{+B!NCr;AX>M#L1x=lU992SevaQBw+fC9i#Kys zPf%cYzAbcg+zcxsyBN3H;*;UMviBKi`zb2YGlxt4Ha6)o5v$nD0hema02ZIZ{liB3 z0_)w|f@{zlz_Nu8OUg8>K!cmVrg9;UC6~)rPursgd+@b9=qA*iqK~}V>W##^j@QUv z;St|5dx+l#fC?o6z!?f@9vU199s_xJo{|&C`nOeCyGp=RsT2zp6p%$_2nsFF=3mor z_oW(J{i^oNh7QzQgHa5ybQxmd)pgi$iow8i4JhLHVmYv~9gFLuBr=;KEmFw{LT^;V zD}-e-{ONeA@k^E-^B3CFi$|N_ADV8xr~bqNRLQ}F=y?CZz1+Zy^zT6I z1>MuSxIjzmbGWpupyGp^G1_|U5Hs2VE<8|LB5Ym6sdd)rbd?jMje}Nn(RJp;MEARFbO zJ~^-=l{3|z=eLUf@8Q5?(dWO<6Z@B?Kj{{`L7MwDQB=2zUg9Qkpc?*p_f|X}d$Xby zGjjP`MV~+hY^Qv7;DcL@o8~5*_fClA-YWY4pDC!u!=;-UU*@n={}{SP@z)ZsKHsL> z!e0U9%G^u68L`#i*dn6v2`_wOwkT<|q{@ppkBHSg#s=qI&lhM*1i5%T+OcAhLR=Np zoE*5-Tu|HZ{;i_+0#st(NP$v4zZDS!LM%%4?Y_R7BXH^ZdOMz8jlQ{Thrw*T^f99o zHqdMrKXfv;PJH&y34H&mU4JpRfSY$_C&j%_L2aG1dm3HoAb$ADGCEJ9<}+Q@QrJFh zIZ&=rzlU_)>*_2o*-po3s@f%*#SA!T@zUj|j$FMh`PtD#?Edih0%bG@}$7R~jo^U)&!`h4;PE6%WktFZBGc&cOMGN4A_QWEd+wGqR zu$CPECDz9VeQ|%AKjEgHjWPWL%@j_1E>+sF>YCIE1b-?zDNfI%-1zR>0xau|nW9-8 zAf|SD=5?H=lI>d-nK-fxf+N(M54PQyjEze#^_GZZghlSKtzFhv&L1%7L-$v597_^y z4U0yybvrx+FZTYJKL6G9BKQDjbjD15NM8!6O}ps~P8$3N>_q>3U^k)}#fTja%*9Ew zi{m~!w0nJg4h#~asy{EJS=#rTIt1dXAo?rBoV)l|m0T;n@#pUtWbw ztbRWEU9qIU5nO-LSdfD;F=*=1pa3(nIy-J8S&p4ByzgoMK;5_b7&CR~|8^$@t+@UP z9S8pb9aladbR)aIJscx$+OaH`rpS7<_WHwZu=i(U$?$ywOFgQc#}eJNy3=IAf5L5B#h7uQMxs(qMBx7 zO6Ac6O{B$vA%q8YKt^=S8b}#{?{`UfjvhT`HlC=H%`*69 z?LP?l!QWKPrCQ){FNU?rm070LJ-deTsV#>!?!4bp_{>9)04E6|5nwp4*@1ZHEt|+MaD%%e?9qvC z)u_!I)NrmOasO6nV%z|>FWKUgw=O|N`i7Wn(Pg@I%B)NT;M#HDYW(oK6^6Oqz_2Ua zXn|W{*cSi+myoVMW4#pwj^6~oqq6Uqw<%WoA^W$F#C_3F^SHQ`7n z1!Pb2so~q>Tk+!24PLyYdH3~J*`wV+b%9}W^IOGKOabWdrWPZ?tvMIvCqVWXQS>^u znzud=ASRXTpdQj&W&i&v6&2IIK^BeBqe@4FYW+r`rLFanh_?^F&(jw!JD2gQ(NiMp1ZdHY9kQuaece*l*ve<*{Goemy2e)rbtUmFT-Nb^r1iSk^LLo5UVm-7h~Blf1`Jqz=By9P8qP6eo66au-ygw-;}!15b(%l>bI#P- za};3K!sC}$d7sdM5vNn+Z%iauqC$z-dOeX7(XlP1F-2}i5nTS*k}TcT=X}e*4EK8| z(pJ&!j;v^anXyawn2^0yT8=6NN2SiCUqrdp$_;k&2G*a|E z6%jt|OBK|FCv_!PS8fUR`&6tDgwvF;=}WKVm=g6V-U*XgvEH%5SQe`{vI|O_OsU4n zJC{3L1h7k7qN8XM^>+qNG<6!G>)mO7d#(8oazvqK=GJi93-#k76=n^AJo01$=4*-~ zFD;99SEJ)brt`K6P+CAMVyERgZrWj^58#H1;nC8(jO?scDpiKIs(mmkN;>p+5p@q? zqh8*a1e~x2jk7)`DkaPCx{HNB*LTu?1K1e!aV`M^_Ky21n?r=*91GkdpF0hUVH7>* zVROm+ZKGef%5bW_>XGcU_O0f_HShJl+1Vn%M=jyTYmix}rmPm9`tn2WF#*F}F9InH z#s}`2t8zB+$~(?D!QDp`6<)dTZ%b#2a&Lo5Ly{c@zW!~)gA-dNH=zv=SYw2PA+fBh z^d(eK?%1cLJtF&CRnVULH86M%=V={qmK1-uTvmS53f8Wdt=HAR6(PZz*3p(mjHB9Y zxNUh5c>*J!ZPbu`St;Z=HyDZrm41*XPJz@H=VTk zk6*@6P;>+HCtrfKUJ3%u>0plbotW^hkeV*Vjf&WO3-R=Pbl99L@)gI`H$1%Q&1*Ns zL=w0DTD0%dTR_)wZp(RMvS()k>*0^OV1_hvqmm;u1Xu5J5A;(g;n>QI6{LUKJ&N&9 z4q66w6ON;vz5iRzB)9$4>LzDWELtW8$7>z4nom+%KzEE&UO9fkAz+{HylB$al0Y|~ zYEtoZzH~TqXfvwR>A;xEv(YPXJe1As;#qa`Pny!H)*p1M+$bv3ADeh&fK2J_PIcHM zycX>%ecHPbCz+%_)K|ZvV&iqR^<3q+?Ez@saryCtf0GZjKgqjBh2j^wpiyF8ce4s} z)|1RL(>x6^@hn3{kE|z`FgCA<$D3DirZv5vk1qTA)=22%p}jx0jW9Y zw6F6%F>udHN1lNDNg^4gK0Dlc&|R@N_#2dFDdm$Q6Wr*fIoIzM81-6xsA;Q9Ics5Cu7dJL zGYo7mcoZo{-+wR`4=Rz02kb%Q0Pi~mnYG){DAEkHMl5`G^}ueWjS+jwdi#|Ncx$7> zfq(XHc0s`sIOlvf%Voc2L3R*!kl&@Yalp0HA6HM}`Ie<0r06-j|rn3UykcHjrg(f88hA7H+@kb-6}3zb^?geLusnBG{L&&Xr^ zPXmN3`WN2<_m8=D#A*r^SBAwIDhypv8SjgS!ohQ{Go3B^>vA0Bni?kN8!d5pwGSPm zMEBSF-$^)2aB57C@zP(MGZ)mrJqM{bc0><&YfYT6!njK76$%xqH#y?*J^utt_-k+I zMKmkNe`L)!d;xBC0nl&2vT}xRuvLdXewMCw{(0nG=+aS8qwdG~G8Qv^S8!4BFB9j${k4jPRz6^)I0B^r$rnvGoL8jl(q8;R}$f3gbmNp{<8OPD9m@FVwAb|T$Y z4==WTFNv>`?bPSeT@RX^&-(9*I?XXw*Esx-jh4Ob;GI06mlj|rEqJn*Y(*GFb_E*r+W zqq*W$5_sDaz17CI>Q_Js=f`owJPl4AKhbsEc#XpO-1Mdo6S{Nmk*L)g`=vIYCrUa@ z{t|e>-g<$}H+u4`xb2$x{^9kbuMZx-zbD_3;IX*H+oDvt+#|Ce{_M%%Myx6a&i?t> zqX43bx*u*GL5jxHu>ByL2js?e#%V1e0wT3^;X6PC1~wMu9Uqnn_Olii0|BT1v$vvfSJ88fTCNR;Y}Xt35PDJv6etm?&!+HkOfYBn|4 z++{R3j{y6c2kP_=) zJUR?QNBU)_y7!IOhwH$}5pmise42jNVlABC>Z=UO0mrWzx?RcG6@ZD|`h&^n(y81X zsm(|m36+w1vo%l*o&5B#iL*!evgz8gbY*sVSlx*%kGAKU{eiFt3|@0)t#jLS^%fvB zL$zc!8fddKsEMzm*MNK(NJ=qKy*GI{a~EG0^aWJ<{P3E!TT1XWn9y3jaUh<7;boCx zTcgtsqshJk3laT^#eE`$ z(FY}f)5vn3)XtLAY7WAs39?@w)?E=BfikYq5n+l{8A65QOL_Dio@Sek6r#yd7j66$ z6ReR0D1>sSldwD2GgQ26Cc_D!ni{K#`^-k}ZXgGGPpu<6d;`q7Gu%aeC zy1GunZCrY*0VzlaA6_Z5Q=w}}rcv_8@YLt!De1O2uH!i)1SWOU`&8{Ve{z((t zJgz1OMY2VuW%2RxtY99u6B7e5Yq>rpoL(^&I1!swA$YpT+G?^cVf;8{-%hx>!4WCH zYE%u)H9TAGQIc8BDVN-&nGO>7fcu5N$Qg6nTg)kQzV0wuJK^g+g?J)LV*|fEiy7;D zzN5q+Ux}enM3c%z8PDl-RJGaU;3kt;f%T`|N#}ooL7LrV*h-fze0O`Ne&!LKF{}A# zoi`1V>J^V?<@opxL-?h_3PPIJTDx0@&UlqA{hjj1ClZgl*ZW#1+q77`tXi({&=|^; z3&va)DEKq1TD_Ar+hag?EklC`PA>PSUKG0@|1QCM!Ub6?bD1s_WY?}?R?h)fg+$KwonBknN$}4H$v-qi6Uuvj5`d{_gR7tY5d%k+&}t3Yq0r zTkqKxYqrR;5-{67++RUIH7Bjv3GZb!t0DT}&wfoOlAu z)N>n}(&B9~;;lzA#YO+CMmX?;v)y@UQEmk{HF1$%~ zvS0)A@oGjqx@3wzE{APD4!gB1%h_q=njeQ%c}hDi%W-J~Ni1zY&~i)6W9Rc7J7?wv zE^AKY>@y*0o7Xb|n-f<2=4@yEM?PD?084VQxLCEwAd3&sWX@GB7CJ5S_%qEZSEc5k z95#%4o-+-K18X#Ywv5xK+O2dKP52<_$BSXi>ZD!6(O{cX75|w0n8pTTGt9?96m=dfH)fqO7H9>;Y^WF&%1= z!dWzi>OnW1$F>i)GO8fHYq?5`prQL()JLRXm5OhHjD24u!&0=~Umo^VJX0(SX1H=5 z(*4p}9z@Z`TSYa`Zr{z1NoagtypaaCn%+?{&s4vsD0U@_x~N{uC-xoH`P{L$kX9mr zQzH#m`+PUUgA!C7(7_qWGam=^OsLn}4{l8rDHQp<;&RLYl@Ka7y832ZOzz<@c{^&N ztKPR?hmOnNwLG^Q89n(-qE7VQ`h90eiuS`FEB%*An7L>l;vicGc_#sQbcwuu5mFKC z9NaN?RDCg4%00}Mud-0uzaIGg6*l}6L0o)9#jF#aXG4yzSH1Y)UhV$nyv8hDG5DQ; zXW}@babYi-Vjut8rV^dNmhys=uUG_05Uy81YjRV|La_gX%F%qEeVopOP@5SS8pq>P z`PEI}9r@LP>u)39Yp7P$o`>jj*pZox)1K4P4R|MsWRQ<~t0Bf)G7QodRUwJmtpjiO zKq|rs>?UF^BXzQOX*DWk$T4;mIqV+45dkJ_aIDkB)2g5XR`Ii}C3n0siNy*n54ULf z@{3DVjr;X8EUef_b@WA*1~Ru+I;GO&I_vG2sVpSEHIBfD``M#D?^xrvpw^XvXri8| zcfzCjvI~V5VDr}2*Oe_PT*P9(W(EaV$u`*C-KUVKEt3a z$`(9aB(QwlOQ3D!h5a%&rR{j@?BLGk#-p8Cr=jUkLS|X5pC8cr?}0eRBi4#7OeW@v zCG-K$qt4|o>E$<*mDN@49(k1-Y*d%9SzuI0_tNQSlT1%RltJOe+Lry0ZaptEQ`*A2 zRCykvVwp(zQTVIu!#wFUcj;vAm6=8;9J08@awJiLM>q3g8v7NiAPtTMWG!gRsP4>( zHC1SAV_3#(HPL!&!YjhCh%ZZ$h1dQx00eP^YO>5I@jQ^65|Qh}S!)kGDR)S+;)BNE zS~5u|SLA87T+52AUdk30C*p1?F&Z7&G3zX5YoE0H{ZqOA52UK*O#>q{elm7Bp!UId zT6J)aS6)OS?E`DKG?U2&?bc+o(l`m9E4%GlKk;&H@#z8j*6;CGPPG=I7u6=e%+uEG zvXt0An16G`O7irbY3wRhRxPY9R&`x|xNIz=1@ABXpj4M&=evRd#&O%$(T^{&mFo+y z75VYjrk~a?$3?&op3b93EZ>DuvRbD&>}q07p$rLlT?7^vqp_uX2kl*{GIUv3#gc z)FOg-J3yI0(j?2f1iyMeKad38_vq0o&!;^=YUZDupUB;N`PG$i9#4U4JnO%5%74lb zknDn}x0;w=yQ063wBw^b-QetvJmTUUAw!Dd z{_!8n=DY+{>d}Cl&G}-Uez7BXZD(|Nda8YFOffF_T$iThV2$C$MjD?JM!nt2hvjCs z6Rg;mFKzahsp$ATT)7e;UT|SZ5QAh40wtbSGksP~j8?hsA!6Ezm8MV)%nB+|HjHCn z`qG%QoZTazkt~~c#IX+F`#nD9ZeAkz9;a{p$En+ltmp_@bkJLe~aav-YU{B(oE_)02ShS&bZ~YEPeoXW|wtztNiXiln*d4M2+c?EbNutrMPkYk^g*e1> zF0ZnURGM1IqjH(hV55!>)2pJvnjQVqN&~>n@D7A>7+8<(2ztkA{Up3B5A`;RoITEi zENB>(c57#x?V+zo_}s^X+Vxr`NvabVJuo<{t%?RFtTMH(1*}yo#2z)Q_jz46zvv7* z>w??W#VE=!m9y!N8ap?g{9=n;SFJJauIP(nOtCTs3Bx^1I34E^zH{{@i}- zzY7EJ=kc)M&!qxU7ZmxY?mydh+7_JRl)K-eOD>^3rqDbG@olVR8UzxVpOTR;_vCVZ zFrXK2wilwPB%pHov|JH;qvKG#28;pLV1p)`B{CM9NI}Bq*r8{TlT_*OI_mA`kZP0R z)^XNY7vV=7WRv@c>&&nwhey1;yq{90LABvH6k)#8I`QPIag-)vbnKJ44&wa@Ja4w% zJ#XzM`%ZUnk`paVmRjap}v8f#`h72hT-TiVgv`ovRI8_N~T>VM#9R$XC ztot*>&v*zG>-b*LlJ)rSs!EJOiWeeqJ*0T?3z<2>;CST{{dmSIOnSsjBM$jBrB1~h zG{)tuS8;hjNycs2&B>BfqoI152d53+c)TfAoocE=h)W`kmE-hP1vwgJqY)eApR)k| z8yELHo&Vbtz&Hh)B$MBwQSN5l%f+4we^pd=k-trMJhQs-%m(|K4u=r9HxM`dO{`TG)3cmrNJ()j!8N z;J-c?fF@8rr2!rzRkWw)Jtpf{P4jtmlUlr#P%X~{9s0{((AJ@VF{h#y=8o{&68E!f zj*mnq+r6{}=)8zaS_%?f;A5|N8jw6F@n7+bfHpV0?7- ziI?WtJsuD(N@EVHOv*0fQ^UVMt}^_b^-~19qxKk?`&m0z*`DxJ<;XM*Mht>8_8M(X zESmSJZYM^HUGo=azS@jG#hshqBg?yU*D~_JV@3W?T)@8&q2Ho_k7nE((E0BK>0jUc zf4=m8WcvT4QXfTpJdoJhQ%n@ul1ca5{jjihpXN!VggwHi|1nfSXgY3dAL+ zmbB*9^B~L>2n6zbvVf+ksp(gqv@{T$>6p0j(tQ5p$3MP6xep`jSHrEuxjY{uN^9b6 zduIuYKzwfo^qw!Ybq$&p$z!AmYuWj-(0*T!|GMR_`!U)h{0t4`V0oa?SO1e8Qh_h0 zDC6P3eYGIx+GndYPkbVngtxTgIoq(kvddo_`18g1q7+|lsr)9BGh{Ite+FDDA@VnN zU~~1;S%^F3|4~)=o6$VcL<8`1*-l8BOQ6u4;lLx%$*baFD_zjSYnc z5WFFbdKYxizV_nTU1j9dqd>+tf+Q5uDIyh%ocN*T4m}qs~QhgN5akLPV2M;^8j*zJyf z{a$sBT4^K}bSX~gwe#E)7z5~e?0Ne0N6(#`+7y5iWz+dRles!;|8uo8y=MH)L)mb6)rxt-17)2#>?xj9X0K zL2#)A?xz}@PSv9x+1<#C4kG!u)HtYIv$>&ut@uTI8V$RiNVT_`HJ=;bOTJ{xa>D`6 z59Tn5!Op~;0c$1?sjq+3Zsi;8-cmD4KGmC`=*6hDWU6vid|+=17c1I5JHS^cnw6RB z3VDh{G(rD$QcSKHk3r2R*6b=8JU}=my5uLI^*QgjO$kG0e(f2hd?^_gF?R^ui^1*T$GxByaPpZCHb$q8bRx#U}vI8kq{!?B4WkA#QO$`|`mtVOLOPYVIGA z{6aE{IrC3JCsGCw_ow~b!Q`qZNy*@zyaYZojNyw!RkuncJ@!yW(Ry-@t}up9w>LyJ z;S;y>=|cqPHPwOGbA}+`egLKzfMVl|_AU!&kRq{f3k`JA!xc=gc?l7+X3t?n3RRpyKYRScVJGjpCiVA3i{UWEx zytGlDSLeRZ2*B-7AbOLD`iyp8sZp0ea(+@k8Q8tHUaMO|q7YFtonJNLvMJ?Qd33u% zO$q}0-Hw01Dot@C8_6j&^Z{489_Q}&uZ8jc9C=_B$t3B1p*c0Tc+li>fcH5nVU^`P z?dk8Cu7)%M@i8VSfduH;&&!2&QR|IEf^2Y= z(E2dBY=%2WaQItLoK~GP`U9+&--7$@a=Tr-t4mUZi^YX zTcCm_8Eh%EFYASDq*MX$OR-?Ef9nUC+2T>V#5(-O^)JdYxfKWMZ!F;I|&AOXdij>kF zfx4*-m3Pt`(eMm?D)|V#g$oYjxh9i4HE%#em6Gv8ZZO`e&rp(eZ_^yaz`k(j_*bW2 zh1VdJT61-l4~WK&V$Jm*>*eOjZ*)JhVK=C7tp-n|cB@#VPQ8d@>cy{W-`^Xf!}a}~ z3g`i`*Kud{I&&nAl2ky|eYaz#tF}Pr03D$RI`iJ1hS023UqjIDbqLDk^$(z->j{sm zeTf)&n}<;^_sqqQY*+E7*gm6Es08F4HkTV{KSPmpPmpH^MnF##>Qbk)LJ@)H^;Hp= z3Et+%_!#%fi`liG9rNV}g*oBc^xB*?1L8mB-4C$=qTJWtX@P6a`ggZY2%*{eiu&IQ z?HQRW;ksx^%02H&h3)d%Srx?+j`#N3(siahRHMO7f5g;gcxAwSR&bo-+&%SE>^^{T11Bup{|MD3M+few6BEi|M)0Oz& zli+nf%*DWq!FI7M+skCK0u86K7XFjOqH1KJr0p9?zmHFfR$1vGqz4@sU^KVH*N{rv zo}C=*x)piQc8U_HHjq?foSQ0kE!d9;KeY$f&aRd%lIG+PAsTY=K*&EdMx~A8%|=gj z-lyon>cSF_M%M2fdW8_=!xUbRGpgj1BwisBUXQj)Nu}k3do1(ssDon-kEo55Kw#l6 zjJ2ZPAU5o&uBNA0*0g%W)m4uD;b{=v4cn0^+svg`{yPiPDe>ijICl{nYtecIT1>g0 z-zrTMoakJdB8;RT*A*NL{=J0mb1D?`Il9GTTYY<0F!4i6;n=cSZvT|cH6&OaO^IJ+ z$j~SrYX{!ak#a@mr+9igP^mgy zRWjI|e?<&_l|(lvtnk$q4P#k!fG~`yuGXZAIqVe|{S4+SrYB$TA1gIhpBD11S$6D` z=WC^@39Eh6efLLY5CCGD;1lNJhVv@u9d-HI@@EsBEPYS7YR?!ZItZ+QPK=H>2EjBo z2E7r)1s3uPr#;NJ2FdIrB@PGg@-?awY1aT%Fh|wmb;~l`PS~#yF1I*!7rpBf4rTyq ziQl+|he=JVDg7!V9@YhF&$O6r3Yeo)m16HS?K+KIFPk=IQ(2U2TiLB_36E^NGsxr0 zG3O~wbs+{hZ}$ zG-PthD%L`TS?NQGBZg_Kr1?Ufou|-SC0^`BTQ4L!+6L`6|4Ikrj>Yu~1(g-NU$~=; zM;;%unPC9-T)%6%SXJw~V*4}1WZKkW2XdJ&QxTMX>a@sizcVfj{gP0%nr=Qd+#NM_ zDoUwa)YB=c)@}Dt_$ymk+8a&ok&_ZaYv78~nX_*$UNqkTnyVY}Dvj4MQmq?knZK!L ze&uzpwYo-$DVry4h_NGJJ0`Ip2h5VbHc)-LS}qRW?4fc0&Pu2+gHbGBCY3^69c{wl zjXLn>UK3z!LCGwOjIGltp({1N!T8z!3 z03yBoftf-1GPl1>6@uNaj{+el9Ai%C%C=qNH@HQDB&_ zzp&ccCPb-L8b!vYB-?QX3{~;PHEI_F{M8(S1G?{ z`JLGbq61@EpXPtLfevo4tG- z^$r|+rn}j<(C+trOy~Zej4hqN`-a@8OwE{^`O(o=;d&{;vHd+#D1sq;55H#Po8?@? z*EuijxT2|#nw4)q$JpiT&I3IY0WHb+N-Qh!J}F$)ab6w_%%{Gndsae+vV7B*DVVaw)NHY0(Erkr zKeq#el~J@}LsETXbJom~-J?}_bpSrAK1I(2ktosvr1{#eu*XQT57iAA%#M|u0v1RX zIQrF5?V+n}aS<0!sRFW$q^LdR%DP8OwuC!6AJ02q>-AYrAF9voWVM(X{etcK8*G1X zds_-c4$VQrgW@UGydmHrNvsd977M)06F^FdEau82eev{6H26hRQmLGwjZWLtG(SoD zN+^ZN+1S`cBLo!IDGClrB z&7R-u%g>&Ly*VLIts2WQ^)t<@YqpwULCNr!EF!h|YeNHRMxLN#S_O!+t1C5)ykuGy zZ?l_jzwroOxhaPh)gO4UJ7|KM0G5tmdt5`@!7y*iW*mmy%P_u3Gow;sqiW2kyt=aD z%lTNXS6i+B1ta5jTE;Yo1qq+WkKZ=Y*87Jl99GwZ-j8bh7x|w*6!Jk7m1=kXy7VK+ zt`!e(Z^;urGIWWgE?FtT5h9zfJ(Quj!PW0;Cp(83yX+Gt^2J|&*pO4sT?^$6krbC$ zt0o{kwPW@)c(uaapx`Ix(K;~9Vd2;7X*peuNJk^$=7GgBuX*mtzu8q|sgubNVy zBSMN=)kKmBZ;a`#rBccanMo$QpMP@wBCX#5JJ~@h3Br={zzqlRZwNBE)`4kgDxo#d zcu7;L&Y1`7Q>k3ZeSl3vyA1kJGhDGmp??Q)apv7J0g%Q)l?GychJf?*V%33adN3Mn z*b7-(w6?arV0J_uB~4D+?_wyB%aixVI#f)?2HQ1OwH%eg>wJ>yC5py{%O&s4I{(>O zUEE|^p2a)Zh|8E~Z;60v{>v;+1flU*W?;vj+a7UyTm#>h9;Tjd1SoVZ+Vq9wyB~PBAfEDwm+ulK3 z<_iG?YWv+(@*w@vn@`_W7q0OHh1url6gW`(__sKUL5}8+x1F)BK){)_WeSt*_ilI} zbF|6#5I|osE)%7i@41$GWu|_FdNww`3nkL+SwzD#6}~7=zuy9wP!bm>sSfwj8lXQ` zX=rAAZl?b%?T>=PuG01y<{fvgJeK>kluK_eNyn&baqva4gB-q_=N`6iYXz~XG38O9SHq?IaTl`UJqeJQ?9pDR~xx( zj;v*<1=MfzJIpG)DGgkdFon?o)tt+ZHOi&68Y+6RQ9ZygLX(^JGiW_`zRgcOB?h6B zW#Vz4B?G&zq~+JsmY+eyqq)i%$)aNl9Pwg6Ih8ftHYZ5Hl7>1}9)yWYs~}N(6Gaa< zrr!KI2DqQ;TG!0VhpsnGq`w?>RD1vfp8y|M;lsSuu2H@+I>PRq-8pBT9;M)PU#1j` zrDw1L>@ydRYP*|$^@7Pcol~J)GfyhXhtDl>(4NQfkQ4)-`bDwlWWb+z1DRF~6a%#% zPnxL}N)R+xd*>CXWwY>4Mmn?gqVPKpkWRf4CEH&ggwu{Ah8kNyYkl#+HTLhLQTd8m zOZuQ5MfwTU*OCO~T_G7tmn@a$axJrl2Bq}ds%l1g!G8O**BT?egD-6vV*-iD1M*^N z1o%qa;kiVrkbInEad=l=__zlY-m?Cz1V|HFAJ;igFdCaQyDj8`Z>0t#{tj@gx zQ(i;o!ADaIOcn^EGPiKeeY9Gr} z*{E#1)(p&N0I{`9ipw*nqB>9oo0P3ksfqPA0bGu;i^;G-l*?lxwvqiWNiu7%Axbe8 zIbUZU&-~d_D8FvSwFKRxXqQ*aQ`{^cHHl4@+acDFftXWy<$(=0u_V%XwBo?#;}0Ki zB-SR#5jg|7v1_PW+sq76AP)JD-kgI`GKicvYLK^b&Up4Is{6$*ftNy02m~jTrlIq2 z(&r7A)jvwA_3#b}jbI{{DP4mSi^x+Y!Iz$BMRvAed)c)C@HN3mmRvPe> z$F%NHfx=+Gh@p-K)*Dk4@bv-qo4;4UgiG@kx|FUc(WY#dBh$Ph@t@JaKJp>B>^m>e zfLqMZdY&E8mQ5&klTjx-mTsbls7a6 z8XV@0o;mLwHe2C$;X-DVwDyjikqEbq<|s|xqi?mD<_Anm)GRvL_d2WhOK9jnvyzZ# zX|23ur_(Bqcx3FGL4ePlHGFy)de2+5?I=@geeOgT+}CZV+K@6;FjNSB)=;F- z1bQ;w=S#L1Ysx4k`5s|_>5wfY%6#N}uEAqQCbxyd zWedVbBi5&S*(Pt4u(Qy*0Ih2uAw-}&mG!SSW(JKh<#F-$pEty;|uXq=fNy*0`W zx-}pM)oSAaA_}azX0Ni9j&OWzar{BSE#-=8?st^CRS&tHJp9KE;*GG7rSHNwCZDt|ZT)y^*x>n~h*4o7Cwf zrBqd~zm@W&mIy*qiPISC2HwGB1{35N82M~?+zvqlf(aWcLw3dM#Z+|ipWSybz(&y2 zHx7x1m3@(K{4(KikE2;+l4i9r`gHXsWgmkkduTF;?WvlQ)|028Is}I!Nhs2MTzUp> zk34r_Y*PEI0y&z0RlU)om}|BD+xy#|Cu4QezhIR|+uzTnAnto2dm`d{^F3T1wGv9S zsl?)49EmIb27W-08J6V^+n%YBF8I@#`2I`MQpDgm`EF6$S}F(u@D&YnnN$aJ}Sf}HV8 zA=NWr`123Vo8C}QJd|)J&F_r*e1k7tN$+ZTrZuXUm>Un*JdDb%+*5nI1EofEUeve$ zViiSE!~DMLEg~$b*5LT}mIM>TiFsXE&*gD9(raS0oo}{wVWrBdMFAhB+GpgIc075( zxJcTQ8DUFRcN7|>NpFC`NJmPF7Kr8ZZdps&92wJz!`?uT977oyN&PgE|HpznsSR7tkJ*p zG28>XTYeyBoG{N)xE%OTwl%7~VWlZ*vb7Q>Dx&{vWjJs>IU|aGCoNnQH^6AMO`E`` z|Jyp`CCmNCMB`oiIk^^Z#{_NwDb}mT`R=C&XVWuAf?v-ahKh`^f68Bd>fAY6?vc;_ z94~7a{)!o++3j*2jIs0QEWtAZ$glYxvNk!=crIKnc8GJ^dZ0>^?;0ji8tq9d}f9SuI@sz)9^5s`}ZpL?*m(S{`VH`9(SLJNqVLkH@LW>)>{dc?Kx5bPnijSo|)_VPL~lpd#yr!pp~yisB~5fT1BFS?=-egbm4!Nnz*RRdi*ugb9<#!bnoG>V-;ve*%44L4URg>b6U z5dH9?dOmCgoN{V)2y{d3{vOhMD<1c}g?edbI(J`fz?#qfCnY8kuh`&GE--I;YqH|; zO4FZf-lsMI$9T!Eb}VsIHRDGSM*-g<`qnPEB0+^o$PJtcife`NaNSMTsah?Wuhzxo zbTsx~A9?pcnXS$@tqCH?aUZ&|Dx3My=k)8hdG!jfK$IMp>=tf55A<a}NNrV5)r znWDi#-x)K{xN=$2c)Yj*KcWG^u3WL!#be=Euyh=!==k4c7vEBEO6*1hkvApw7x&17 zS_gLd7v|q-4WKzM9$Tmlrb|&dt?Jj=Zwkv45p5t;f8BAZ%zeKsTuU^uwzH>JVzu^M z^}rq7Tz9d=b~U|5$$55gczR9SmlF2I`(n|5X%hIa<_VwoxBy=- zamK+8G-)tD+M2Pydwo@-_RPEqhCXz6l6S|*v2u0Fs=mo@!pO=jvAaQ6yjy#l5*=wD z_+&HwHz=GSlFHnijd1CoIeRJJ*M8x(OdnVIGUV&0; zFoMDo>m~QM`UAWd`^?$k_U@98PwVRHT1Q6YK@7^}cY0&#aFj<# zR6Tzm3MIE(y`+lzDg2dss>Q6h3p%GWF@&rP7g4k$9cPI1@^kSx?woY#T3FgNd%+;t z>ujt+QT7^|n1l?6Yac*nDnBF7&n{lU6M0o8Tz#IA_bpCVEcyA3I3wm^+@0X=?g{Qra0u@1F2UV(;qC-??o99AXYB6IzUTdp`-Cl6%sH#-|Le0FfJ3KL zhTosiW5gYNnPcgVCRnFk?~DNCBtK0~JuckN^^2x+J=LVs8RuiLmN`C95cIayW5w_( zDW2#}-?s*>JD%|4+%3^QHPtmo!f$CDU5t4$7!|Xwlu_z6pf56Ye%J7kXL0$|9$etv zIC%6=s7la!*n^1jCnShknKJnG5OF&}ft9mxo3!>sNcl&bVRH z-}}E1o9F0XyH0t)giD+MshQa9kH(JzadnoHHhY{xK3)^N2N=(A?~tyQyx+MojDqjO zcSrNyLHI;;Rjhh$ye{jw_}mXFjHdFb6_mp?xx2e}^M8?TYH1m6Acp>(R^unG-4})- zj1erw{7F@>hj`<5ZUt)m>D(;3&1stqkMA5762uw@ogx3hrd*SKpsl&q@0oVh^Sb96 zyB5%<)O@4?s>A<$X8)8?fU5unv{Y`v*TXZ{S@zvn85`cM32DN)s{E; zPJJ}48aA*-8nsGdxi!C<)t(2(No}qXYF-^8Y`fOG1BChW79xU5$L;43G#arO{G0R8 zr|N^wFYrwek~Gh127q$6Q#_sMZ#eh;(jR#W>G>a-gxP9#npf(P%BRU|ANBVU-GXM7|cM$zc(Le`hp| zj7s9l(&BU|UA3Zb8l!agCH?TNhh9gsT$&W0*DJs!<1N9RE{$Et-=iKLXl=SCND0R! zK`qu$vYEUvNl-|;xrNfP@0$}ae(sJW)w+o#9BprIeqZ&x-Mri#X>xgioX(dC2Q@nY zN-AnV#a*a+bvKv#Z3T1p=_Rt&oMsq}LQelS-MwbLSm{;NYgJvN)>stqT)cc@X@Wq? zZ0j2em$Mt$WfS3c-{KsMMAgmP$6syu)skw}w za*C>Dg&WI)Z5KXxj=wMax1#@FBEAi8jQyIqq80S4POl%|*-`9f^bEeo&0!r-kO}4FJ~KkbF4}tccyJ({0I-Yp*3pv`%hQa$0=v-a^>z0)-cd0l2x0I zuKd$5O>@Vz9KnPO(|iilj|SXb_|QiarD&$1Ksek+13!y{>zLVotECYiEY(zbSh}4u z8u757G#d}1aR8=U!7x($u}eB*bu>FifI%#W;v8XFf4-e-R`3~Bw^udMbG8Z33*EXe z_w!=I+6YA@JXxwiRwSzz%=%qm?RkT7tTrB0{DH-1at`WPr)yMC5@~hr2%UR1wc_K)QQ;H*2(OB{GkT)rX<~i~F2Aj$9^Z?kcT{e1jd30Q363YP;A= z!XVqMozTt@cbOPo(Lt-^N$4wA7(J(KxN2LTJ-vCpgPYe&kclG;i`2xZ=>oJPyk3up zPf@KK1vOh^=4~Xy7+)%#OCdqC5g?7Y?5%U`i`QSKqq@$zWBm^ZLZ5E8XUPYUhT#ir+J-zRv3FDQI=ip2}+Cluk9XgKK=p*&XkqG$3R>t{^bhku8s~n2WExCos*5nD};N0BZiK1kP9}8FN0}1T(JQh|ISD3F&Ye+t;F^QGmZzx0V0nzsMpjB4uK~nM%{JEJZ&}l zPZHIS*4^A>_eJ1dm-`aM2*pTED)g~nS7MxIT7qHan8!{W5M1I;Pk(e2Gs_xMC;vc# zlGoA*Q0#aLt@JdSPc68dR$APdYQ!b2akOsN#nQePlzWPrd${PLY0>F847!xElhzg==NCG)A^%XVXl=KTx-7+ROQ7dOP!DJ6n(Sw4I$tl6s{GrS z=eH<<9WHPba|njp5t~mpjI_F&;@X+!BC>l8sam+-&C%^JS~Fhx)46c83B**TclFmu zEO`=0(EDk9?7x&6KrXKi^pBXBM?{Vy>`Nm*lrA* zWIJO&ep}HmEHE(*E7oFkk@vIymGDzbU?Cc@saQ)cj7uH1DADFDz|vKBm`alx3*zW1 zIrcFi~Nb1H3;jQAaGplbb<*=i9O zNA>c>bI`mdp^`FkDI(mw2I(<9wh~67l+o-m1jX;oZLEk4*U^#!Uvvpe^;0vI?RV5H z8<_79!~e5h|7m`DM1XFGQ6H&U5Q|W@GaaUcTE&&z#uA_SGjF16w08&;+6kcYFS ziuglK{>JvUe`H#t{=ixLazO8JhBdBCDNmg=fPltBlS-uH;h*yveYHBu3$?Q=iU6|4 zAn&hh_eX_+GzH^N)qXOwSnG~kihBQTJa1cRtRNQlm>DKd$$mlwZm5NwxRqc1?SJU4_?V6d>TJjAeV-bj)1@9`3D+78;r4mMk$9 z>$#WvJ!Xbj<6=dWwH7@Ua11;XpB=xx;%j_6upWVJ0NydGB z*y8djy~uq3Ij}3e`D(JbmWj{^h?~I}P7-dk$%v)OeSpmdQeq5-m6ha4C?$fCPUB5~ zX_Vk*ey}lU9h~(|9?v~q&U**xLTht~Lc3QC)=29TYA>O&xp!wVYe{mO=|(v5c!|q; zsdXm~1(=O=0-)s9vOTapM^zd+u06}`I>J7SpT{nJhX6fi&g?ZZ*uPD$qH&c#dZ&q1 zC+?>XvDH@qX)B9i4sMNcfZbX`!7EJqQ3t#5hxn`-Aj&=B8F2rjaQ=7g@%KR*z-9yP zV=I@zA1?SyW@T-zQs+atCM(Q^d1h;~{$<@#lg~CLzt1D-MD}nR4@D}6c}R*Q=0<<{ z%3$gez7jd4HBI|FC_^F$;-YWrk?erwk(0-lr}T?=0(-fZLH{+?AL~)Im5=g>{u+X64=)b1^B(EZ@Ap+Z!Xj}h2$)-c#kKD>BJ$I9ZfbiUb()S7_vR9N-@_~|TTFb3@MKlMj<q$2jE|BeTxnCGf%6XyEIGOA`O~pkb zE!;2v*_OnPv-8WATbtj0eM$Vf@}BH~yyB1C&gXJY`x}J~evt+}iwROGZH=E7(}u~j z4?KJYz}6=78)5>xmT;EBC@Mw|PJ+PN z>&GS-jYKecGtqgmbI1}>3j$R9;7kU+(5iY?BHst8H;U8alaJJR0GFe{%cFC(!2{~4 z!a0z(JF4L@>{-3LlfG0iC#4CYvjx~3gH9=(MVZ|XFEMtW%44J_GT9KUSCZem`y4;C zBgq0IdgDtfXnt~TPv$KWXB4e`FRVKzlr*0U}WU$jHdHyUWX-ZsA}i!#yif$@GtK zSfgxpbL$5mJd2eI`$P2o6(lw6G1)AXn<2`U3p*kuf>patGlG-gFWT(hC<__IH6m4H zxLj#dYc!>MztXQe2(SNsB5V+&RikZZ9|Oi^tJg8aaJ@FszA~jN^|iSQIM<1c>0w_u zuF`}5hZ&bt+cj^YAH$AD?X*(zHa9z|5{aXb#EbLJJM_(uGTv1&uuXiP4`A*k6G^Kk z%6``Ik4fU2pmo1&InbKnX%ud9;~p>jM2RW%V4z8tjQ82a#qc*RH#aO!sJ{c#?Z9~T zh=h*oa65#3MEpo?s`XEgw}5Gf_ddRKCjZL1M(Qg-E@kRPI=MKh>=m|y`v?#|>|oV# z<%ateiyelAAnxh&D-PRvaKJw%256ff>EiByK43^GA<-^ZOv_5IR29L=Y#q~hB%xtZ zH;d}OJbaq{croTg31r+_j$xRc`K*BTlU zz)#k@1k!$7tmd?eADFoelI9CoDxDy4{b97&KIw&F9nYUu^^^>UmpJF}XJ2tDB4lkj z2xxuFno6_N{rA?%8jR4p>kvF`u-^xuJ^m1!Ia+^jlk+0AUwXjg5uIIn*>@seXuw`a zP@}V_w?2;;iq^{x7|4%OtPJw?vgSochhIjTPA_rV2TuD!!{tUxLVoH29+Ao7DO)K< z`U2Hg@onR#;yR%7`R23$`|Gc?}uBXE}9Uy1^Q&|{N_b0Dr zxpDrvySJH#9tpquv=8o{veRumjw^mi>eH3#C;&i_ZJeG)dfuIHFV*h5-JS6PRAM*1 zP75JKbwI*Bzh_B$s2d>uy1&0CbhgmSlZl74-|7u@iplDvR2?2>P%|F+l?P);qH`1= z@$o!K;wqh3fWq%9gRUoach8Q*$Iq%oyek88diHO>aYM>U<0&hO6E=*8^X!FRn9>M3>k6vfHFc0AKKWH_ARIQhBFX7M!qvHo6PZ2QO{`lJ4LGRu%CP|72DkGir18R1}PyFw(u&@A`^zab`9Hu~Xjq!WSVF%cNkglYO ztSZ+BX@Q6HFC8^e68feD#4k1R8!$j0C03@FLjoX`f@d4Q1{gxh>q2qZ9NykO=o_K| zhP-M)F?b4$c5koEn+KY$-Y^tdlV0=xoa@AmKnX{=c;WNeV#TD>`aV!02P}egS%g43 z8l}#qE2|~w9Xq@Ii+4%xfULoBlnwyAlLOm=04MXAjm9?j$sBXx-mshS&Qo<@)qVc> z{e58A=JNxbNk(g@N6`K6?X=yeq-sDDFQqw6`@j2EJ`xCw|G*+dt<%U(wCO42>e$ zu1>Wodn_40g^t8FO3$4it(l9sHu1Gtst|OV3lF zyIxN9-kB%HrA+oRQPh}77~D4fAp+`*P3=ye4ME=5VlX0o0#j|p3iWk-IGjctv*%nM zNV=UblvjZGI;?XUoh_l1L%0B6vEMhGv)b@007)Q&RhW2ll=cbwlov)Y>@nKB!lXBS zeclc@n93!xF1eS;eJ*_#7XzHIcwajKysT$BGHKVb18DbreM0xGG-!}u_oR%gt&>oA ze(yYZ?u@3x|7uOFQ>P$h&gy*p*4ckP(^8^BM1wby3{@s7pgcOH22+3`zX!^<2P=rRv>W%8Wz0&rpoub_7X`JZoUWKfW94^c^kQv<@n z=@iLt-rm%1@f)%3@LNh{UcAR**ip!@>5gr=;Qq6C#tH&35%ev+YzjZrip$xp>pUP^ z=*elGi3O5TYPq#sPx@!E9se|8k4}e-=Fbww_1aed#^+s+4F3|3G63Rn9S8wZKv!3{ zY9bD;qN1Y48nBaJXmzx`S)Nn>ES30i@KV(Tg>-h7Nh@nd!P))3dv%qL6I|lk###4! za90gpiOCImTraHq&Qc1NLkcFJMKbwzQ`45xQqPw2Hjd3v??$Ql(~}eVa*JJPo#)#R z98(q>s$7Lxt~{g>1S~@P`$IzFKW!gI-L5X1H#x0-!Q>6bjF}xLP9dE9-gqQiN_V`i zw|TYM4Eyz=f^G9_Wo%!G($pgy znY{+9t&~;DjKFEw3B;`%@fhSsb?Qlb9T@vA+M^|YluI20oTGr z5k)BLi;!>VgiI>4jmON9yW+ZonI=i2%3Q8TRyiUf>mK^fNk^ZIu)`+5*f*4~;2**M z?E~R7NmqatX-nWf{e8~*&rOHEsa#R<)#W*bf&{)ZP%~6z`C60LoZRj1NIY(ZA=_tj zWT^EoYLlgJ$V;S(71lsnKpZJkgVoA+rNRj*&+PXPj4pY5xzXD!Bwf(Yj?iUVjbMNZ zIUWlhX>-r>5cP7Gfp~x}`TRSO9NBT4lVbN&aS>$h;Mh|xGDdF3FBIUwN<*!Wfeq7W zn3lACN+UB=XnUHu4v~JTOOe)B!XZ*J+I&s#E}KA%0jpMGYVd@CV;yV-RlHJ!J{XHf zcf2RMRyK4&y+Jar?Ga)AMK(t{wvIetWj(7iN8t1U@;iH1KKL-YOfZz(`qybcG)R4R zOEWS~)nWR5b_x)HC4N8jryl0N`H9LT(iF?=^2+^%*zD;Q_g=Ux8aCFldbEcC69bk; zF$-m=63qt9BPsDUFSYgT4YjmEFV>pd$&otZJJ4yet5krzqL{~$zTg($^Dei zY}FTjq)u?ld!Oqdgsgq2L>A-xa$$>NZ>n;t{oxle?(m^D`ZLrP9iOA@tsNcY&L__u zr$wqKvn7dEt?Xq}DI5B9Y10?Gpc&ssyaOJ|zkU#L08h3H7vYdsX{@)ILPz*?{IQfG z@JmL}SR`^h4|^rs&;+{$h!l_CL;F$A`ICP-7b_X~uD#`S4+MjrIc%EB7rt1^?86cA zZDMVG@Q>fm!@3$#ZPs{Pay$@D-R;IEuu_;!o-2-xdQMw=a0`aUU^sACJysw{8)Ph* z`D@T@$kSk~($_l?&iGjKrA-^_2aV6aj-4jeWZZd%g_Wxf^CgihT5CJ^qGaRE35kqR ztp^vG5nOvMI`3enKib6F_%E+ym&S{M;y1GiSEbl>sE3NS9;`OmT05>;C_sbv11+k| zWw}n!yayuiY@v2=74ip?cXOu3cab`ukQt(G+AO#?#R8UOvZBamP`HfNjY9RWR;KV_ zw)+^Df2|_wj}Nodw7biCqmNixUY}y*DQ@eg8MWG`Z5_;&Bu|Ma`o;stRSR+BYfj-Q zBzk!eq1bTmiTIpqO-sjFKbrKn5Oh1CuqO-$rQCegW2`SL4bU3lc4ri%1ix_*4hTEp zb)Xp6btjgwES!tYD_@f{eMuF$I89!cINjp@kB9Y-M|Uwo^pE+v`vMi+wRDBG89Qlg8SV>PRljt>;F>EGTmS{>8$s|heb)i zS#-G)n;R-nEqZ3A9!ziC8}Uv&-iIid*0Y(S+a5nq9y0xOW5gpL31-ongRdPlDb;Mk zk{b40+VwsY@H%5fXLSlcH%%!t8vp_#IJSFr|`X=lP3Ov6tZK74CuMYGecm0v)z(4$it`RQV)E9!LX0tid+DJLG z2!Zg_l4?c8+H-omz|iEh2zB>NAEs^2fy|>TB#&5k(l^{i9(XIXW+arq>3W20lgSel z%u&(B?kHZ3~Iq!)TfzKBAyM&VL7pp5I%7Pd#(!Arja4D zC!U8RAdZ4MOcjA2ePa&o>G$IjNpBb~!Nag}{KCWa>!?VNvXAFjAOUSY>jCLaT|_~WIq>uHj1$y!!1Hg;Aq zFEz)(N(Bx(Or8Q1a-Sn~RK*_kkY^!{^B##CMR@F7rfG^zY=X-#WrS78ywvjp2?Z{S z6qg9)7fsVOE6L5;pD@j7=o!i+IY-ZX4dmcSYj<)%38WaQnZ6T_(rn5M@k{Eqb^$AW zmJ{;XbFhaC&E`b#hxe^aLDWcD9ird4GpAKM9bB3aib;=wd9WievFla8_eGC*u5F)< zxhFhMp>smINiyXA-xs0(8rR|fs6&tMq*M5DdHP1YsN?%1(ZK~|YBODDq0ydAyo@SEFc4*jzL>5o>*b(c9p*GN0a32it zOn&d6u*6cBo>7iPx=!CGSSAB-Dhj888NU;o#Ud)3_1guRelFplYxPbWw#(fy!^JX{ z9$|o0NWogDv@}YnZ+6nUv(aI6p9XJ#7&GOG)jB8`WJ3Ru)1j?beS_)|u|gMon!JDv z0WN8x%kT9ZalLCQS&Nf-cKfnGxh6kiE~3BXYo~Cj8V^pVkKdFrvcIuRylZ zherEp3Zf&}C1vp@=;|JV7|&?%^CL9Pri;;xA}!iN&a~|ze%^$&B=6hJ?+-1BlM+sB zwEMN5jf{0Bf?N#_$C-=OU&G2ugF$38J?^0Qz3`-ba~&azh1_})Hw%6tWeaE(2XIPXoLF6DYSprLt*CwZir2TNJnD@;{-iT&kZl5G z>ebRQoStXAuvk?3i`>pu(I?5G3t-v~K>)2vrDP$((Uf*$fe9Pvoo`TKe$z zcs|QCN0K*$5tUIiM`h;rMNl7MA70`boGYQy>sCz#fs30gJ9LM#hJ&Qv$*)!p&MK1* zrYNs5m_|8*HAA$HD9tPryh<~lEHhapQk*ba+C-WJi zS}8%c(`wece88mFAbK*DP5D-)!Mr(@J79J=t+5PwefCFGusLt-J9#f-nIy?W@bSAI z4A`*$N1lq?Qg7mwwnp>K9Vd7Rlor!-{saa!)d2B`k~G0y(G&+nPOp2)5M>^pYeEMj zB-moN!%O3xvBLIu=aXv?HY|nMhGR6Fz=c)ga##l$zKBgavLAP?rrsJ)`h+1c?IWFrS3q?pRw-x1vpnV)mG6 z`5p`^FvQ9FkZ`EhO7u&1tN5hr_rW|LL=9uTptiuNF>e-w-f3kSx#vnl?b;g1LlfC1 z>#L8^l@uc~z zBkF+35PKnScvRL|v}mxMFn?ok%oG8B6sD2BmV?kV)WPAzS9EbHpM-mR(d6{}2>59X ztBjc8TF7!ClRjnQs<>^gIl(FZ7@jr?Ldg!aalrh`#t<%gS*rm1G6(fH6dfszh}JjG zcY#Od0S3YS5KL{3l4w1rJIku_j{e2^RL;afPBO z`{m+OjqOkXPSLgJWP6;Ly?Wt~Nvs9DCVF-=O0x1&xfX=OOgv0@0;CelGc zou^BJq1CAS!R}_+c?ZM2m^=y>jO{ZhYRob+DT*A;-XG;Y6vgf4h%Jt^Hj(FKDHoT# zB?@lF1_=}0rYFjGqIhh~KV6Rv4z{(m5mgd-WctE4skR`h z-8G0W6>m@;ii=KkK;X^H6l|_Aj%f~KGRdy2qpv&aC3c$1RU^n1OeM8kn_@)pPb!1t zIu_3Oe#7JKMtqz-*1GFIIJavhAEmk6pnym``NDygp%0NUvAGSI;&IBUEkXU0>eQbK zDn-^5Rg82#%NI#z^|2T!0sr%4qzf^4!3?9!LveKORkkx+wShE}IZoXpqoV0pxeM;i z1+q=Tz*v2A0f-q%?Lmt26jF6wh-KlF9~F_V1!qAXhC^{B_DGg)f&kPVbM%lG+GD0_ z`&nR~#3AeGMyRCph*kv#WBTI}&-ooXhE`>QjrR&VheE-T;hbG!RAPJsc&1B-0nGncRCQjU+1D@yNEFIFPK?4@sVq=JtXF`ZK9p3Wh z)8uZ~sbIFY`8+}w)D@GTT7(Q_z!mDxL~Ks;Z{Hh=gzJ~&C=39V(f>F})a?tMD`xQ? zGZv-3*XLdi(eXR}4Yu3L=>$JI@zz{*Hko=VolR84P8l;{qfV(Dcsr`^XLMnj5pZyuV*b~7W_bqfP5E?`UO%OJMOZgYs^#^I zl!#~^TNjDEOTfujk68LG8*=5t&50~k3NwOjv)w!Crmsm*Z1Q&Kw(F$%c}Bux;%G$7 zhJY@Vyd8-2_|4;hgoFeH;8VUSG*TY_GQkgcqCQ>s0IHm_L&KL^K;GEBmaNq|kupsh zu>bKiMc;`!5nXaiQ)QKkUfcL@!w#t8e1EEVj#iV&D!Ci|d=H;0r54UAccb|A!PE}o zcxET1MD5hiDp!$~a*Yn;&X!WjflKqCbG66j*BnPXFaG`&`D z>U*!#N%TwEX6a|(P?*T%g(CKMXu&SSGhU~Yyjau60F4?WG0|YygXMZOX4B!kv`EK4 zX(ir4X;X;h4hI{$DY)aQ>%bmQ0kH{8>2}0AYiSavIBp=GG}(K*kGak;F%G-h%nJcc zUAbqBmp1RLC^(lkm4mEd)SPh4V(`lWr(z2fR?n__+VffA$`iM%P9Os!EJEUnKeI7%BLJ}1rBP#LrT$hdGm=VN(rXX z(X+89SB(YkZ3Di(6;U`}HFbFmM9~(o@_p{A%EF6)YwV+~-eR5v-4OpUg*XxIRbp}2 zt&+^!S#dy``~4ShJ`c`e>4)%8ZC6dso)A!>PsZf9)~$|sT6b#Ls-XzREM~8gdf4L& zGljzS@94~S(bwh7nx%dw0s!$d%(lxN_Y|_$0GxV2LZM39pMH&Q<2+KPqZbfM9ndqCQ=f$M5V61pW;b{)Tdo@n7rOZVN)%_UhAJ z2mu4WDt(GAvc)6jthV)sr(1!;xMhZz#?y=L2#w_tY#iK+Jp{nF@d2rkO3bWPl{jlf zICf!-T!EPBj@Mg?pXGfg-upZ;TqXzB2FM_N6)>}H5Ns`|ApCsIHmKP>d|tgnND10~ z+>zs?TSbBmIOIjKboDdKW1FHb59i^;f<2d7NUt@kp%@m&K`AlIZ71B~eSBV+$uxcL0W5}J zhi|rY^UxfrmP1uh%#G^2X`~;Iy(M=?QzUGpgD_KsY9r20*H?q0lZO=8 zs_dAlAx#W_=&&bVLfc&COau(S*3Wu5uGn<8YUT983eC=PppN@sXf_SO@pb!0>K!VT zr5#P`&3W^FiyeB6p}Z`d+E$L9z7ISxv^wMwi|8K<7~bER+joD3Ke{t>Y6N`ngjVh~ zlu7zOq?TDmidAi-kF?gdU>5?Y>+|Fb6{miQ?p5$(0W&p*3yUf^P1mU>*r6z6=^#Ri zSZ-?9v>N-OqVJ|W91Coz@!*89%z5LfmMvUl=$?Qnx_N&?S$QSn2U^TH% z!B!qg_PR&TDD67+2VfotV(nM!>o$3)GZMM{t&;7ow!{ zw<5uHe;*r$kk&}QuH4IwuUILq%(O&g3vPOXNmH#moL8nyXf~*r{Qrth|DUf=!N@_x zLr|MDg>prQi^>%Z>aju}xtzZB4Oi-PhSKvrNqTNW-b_vxSC*Xkft;^p4JoR(03U(VA8HH0|r}c3j6>szQzJWk&mX5s88RsmhePmx9*=Dvlnn9r!CN(h2P(!}qkfEz!5FrBrZxe{h zR^Qp_@i~K{z9b-RUp6_QB%;VWXutL0{()zwlueIb2BEy9g00EJ;pwpE%gbv~2bA2Z z=*t;yz9drpN4!lJofyYXs5r+N5&XJl%ZV3~09?8=fTpOjtr4l1(Wdi!Jwj7K$EtLUwr6-Be(a8@<+y(_UAk>|gXF3)<#_DT zS|V0rQ0yev6bLcEk$5Jznr7u8yk>!)vfv z3ZYJL5tr)kTXz{7=218o^TDkMhH66)0 zSZE07`HLqiLLzyO;o3`ipGwP;TTG~P* z+4#Lx+>Ro;V2PDvOQ+ZABj}r*-~sTpAh^>|DUlPFwsjdr^&d6`yApY9 z_orsj0l$01p4Bj^>uS|9CmBJj3)oCKX>n)Uyio?raY{A50E~@36hCbtA$drM2oQk- zd+iHk#jjekl+4<+H{NoAX+G9$+BtV^L6pf#Bp;(Im)a0zyfHjd730xDlH;d^+pQ z5Z2|1GR&4Q-{0nah509eBg{A)ffNWm3@lr!OBY0UnEvJcW6D(b;rXFfl2hvH6%Nb$ z&*7%#E?F#S)+=Trnax@5Pg>9%iWg*(CYH=|CY1<9s`WLYW18F7`2$5qImNFoAy_LA z@Aa&-u2ih`AOuz0Hi@xuWa$Qg_SF4jiCAWokxTEY)=92-SshvA#V9#Lrp{$j zrra@3C=v_^HbLO_f!n-Yuhe6zQx$Z7`I+(!MYk}P)|z~d6o5I!sGEMbR-~2Vz@k8+ zjTKQIWRcH;D;%;zwc?dRI(FdcWFSL>5`;s9YP0{6nPYIA*pKJ2n?(pZ3*&VVeSbBG zLRD{-Q&5!0)&y&NZtWlj=m(865RV*#GKsEf6-J^3nx;JVU;~$svssnGrJAN{ zX*=b)6`Lm7mf{SaKw{(*?e#nrKd&f(orOh3XAE@X9l=}wMln>CcEDkNPAT3T8?Z3u zbpO9Cj8ha}cNRlA9ZmwY?K^mznE;%dR03JA;qDV>!0-6FNqHmn4m0{VQp92Xni*4u zg3)9;Zx$0|1~X9!DaG!SC0FG5f@Vq2nmoxWr|+$0SKm?Y=a8Fx-@r;1%KT+Ntz>uP zlAw}H6B7MQTAwi;?Jb(xHu8L|8v@SI@rU940EzhhxOZrJzEuqg9-H@_{k8>z6BXXc zcmH5U%LX3QmBp{$_qF4zEriK#74xM66-Y!nsIoc3QORHp`ohddi=(n1Kg%?sG$%Cf zc{Rf;MgR>jrg7oepYuA&Qut>M%halOs*9N<(unKjJTkYUtn&ziQuNOuB8L1B^M% z3TtMM0{&9d$E2vUYC@EJrHxHs7UQ&7PB~en^N%J|J9eWU>>gUz&4o!d#jaMkur#l& z=ZHe-bF_QYNv;9ZCl;E^1CiJXXaB{UYu36@6UvabVt{g+`+2>#cxj9KRE0iRo?Id_ zkh>WK@TbX)=agG8Ij)AH(1`$A$ioP3z!Vx<}82?Wj?%JK|z=a5=&7rt4?7; zX3=#kYAs>k*Uv5&&KbkKUp3szP#MT%33%p;8+m+ixVxe0piaMZlBN&4{?Dq!FF%@G$wVsHspmsFT?t+>Csy4RG0ODx$UuVy z)TkL2dzd9(c~WRDi{!D6vjq?NpKR=zl)ZqtyUE!a@|=1{03|^jcd4&<#z|fG_F*Jl zT7tLcH~=@cW(G=yG=5IV$a;#mVe34l$PSP#{JSRR4}j>S_+QEh_Kh)IR@+s<6415r z01yv$9`GnOcDJq5k(s>|op2Arzh9PmK5jZUj zaV(X+e@iq|Y(=xrv0JFAjzt9_R`2EUrplsE(Ng%;z9$lM$}k;C)vDdfnUAPlTkT3_ zYGcEpRv`;O0okdq4b*&Lq)$VIVyAiKSH-N`ud~{a;5f7=)0pv6W&G4H(3%Ubg@(D- z%jrE>rqhK{2n7I119%iX*Y_Wf)-MR}8u?y+g9pN$8xO zB5TE&nw=*>J9nGb-{7Z;o+dR^0LVvW+at6pL2w;RF}hDC`D3(=c`xEa?3nWef_F&Y zgBDEV=PW*_yixW(vSG7gkbTlRT05W6)C!H8Pc5d#nCKarP>imzIBG%In0+dk5uOZkZMt$ z)=BHO#(6{1+RrJ6h)5tJPx$uhwF%)@YmBhmz2Q2LAo2a7euzRijP zLbEj{!=i^5uTK{!B5p_eLI~pdHD=n*%2XJ6N6Ii9ePemcRZ@r%Cz`_+9kLmAEZE4> z+qaofA)i<@8G(~9{yu()KmUPeYCP`&#bncjUVyN;pKjBEmP9fkSc{9(_jVnoRU?O2 zYIN`lB@@3{JBw<`1n2}bdZqsBl9Xeh$Opb_-#MEshHG;@NysJ{<5Eh z&Vl{jGGn+LtIS5V$uum{UrVj!^m)w=O~b(%%Oj~0lxqC0beD$g)Iv~ve55jJlUO$6 z?K2BJ8{Bd&m7G{q%Vm88M`t;ThVp(XK|gPgJ5@Fk-{vDTb|>;J(yC0P$@M!{UJstl zoA{qkf=0^6)mNf}L$D4Nw@OJQdMOsyRL#F8_D*}#<6ZZs z+e8}2UsmtZ>f^kZzpHgAV2nXWj2oW)b%)F%%WG*v9*{PYN2b^=&UHS!#k+fim69jjYH^v77ij#&)_-lhPoY*DGu~OzZ~>tAIm`+0`Pp9ZSW8lc z1Jr44<7#OD#(1xEN*_U1*G)u4@^SV0kn(sQ@xK*9$Ma`V-PFC5``hy`96}kD`GlX^ zkyhibK55UxFENw;aE2}BGM<7N)wN#+$0a6vg4PBY7Bg%2Dzp+79WJvuL8h}ys{pSh z85oOvp5BtjHcJhPXyx5hBtjuNEexbz(svGPMTD1W+!8PghGo$xLQ1X$1k}=>Hr_q? z75M&oeSLycOqwG8bkNZ-v_&l5-#bXm&ysLnE!VZ8{cg z{dbOAz~~=@iO1cab1$Hf2sSr!DMAQ7<0~!|AQO?Ig+Ehg2Okl!fdHrQ@5^19ozd7a z=r7ok*&D_z?@_|ud4IN9?T8$R&LSk-Kmhy|#NI8yY_2vVdc&}FCgAgc@3dSHaqFm* zNF2sApUD#hwACa|8L`gH!!QYjL7153<~Q2O%mO5)WvAlaVD0)Qd=EMIeaA>mZl_dM z@qNMtb)m>?5t~DlPWXY*o-cbOilm|b%0t^E`fVTQ>7PcH4p^Qpr}%iANd_YV0AQO4 zH)kLMgB(wnw=I0&bs0wep&1d^w{#O|2i6|M$@Dzp*cpU>vtBuLS{hh|JsvVZ45^5~x47v2@?r480v zzA}g$beTzzK_|>o)y0%}bk<+ZV4d4P?6Hv6hWeLbTlJum&oA?Su89oc7&dl&dd(V4 zr$?EF3`%{8U3jLme0sW4E57%<*@xO0Peso=+wJ)`o!{c8t92QSZm$-}<+ zy$f{9laE$zXyFiu1rBr2ohf1K8JqRjiV#>t0Vr{P)yQKysB4WnH0&!4HUD^jwjR0@ zHG>H~Y_Q>!yF~SNJIvwl*g89fJOAr@#{PLv;`8?HM3z4qLS!oBpU9@Zu*NA93cdhq zA`#?B6GOt~GHQ#y^_XG@hk}0w|KWYsT4y|LOL(xW0U%6KT>U|>CU~vaz|lJ;-4qCo z8q|TL3)65_DHDP6zDgiTsUewR==1p-Z{@PL*c=_#hmBf-{(`hRdh4d z;iy=wBS`V*-~S|noRyzeRpq%)YbsmF`>@WgTe~DWM4fXCi^a literal 0 HcmV?d00001 diff --git a/docs/modules/0_getting_started/3_how_to_contribute_main.rst b/docs/modules/0_getting_started/3_how_to_contribute_main.rst index 1e61760649..30e3001f36 100644 --- a/docs/modules/0_getting_started/3_how_to_contribute_main.rst +++ b/docs/modules/0_getting_started/3_how_to_contribute_main.rst @@ -107,6 +107,18 @@ mathematics and the algorithm of the example. Documentations related codes should be in the python script as the header comments of the script or docstrings of each function. +Also, each document should have a link to the code in Github. +You can easily add the link by using the `.. autoclass::`, `.. autofunction::`, and `.. automodule` by Sphinx's `autodoc`_ module. + +Using this `autodoc`_ module, the generated documentations have the link to the code in Github like: + +.. image:: /_static/img/source_link_1.png + +When you click the link, you will jump to the source code in Github like: + +.. image:: /_static/img/source_link_2.png + + .. _`submit a pull request`: @@ -210,5 +222,6 @@ Current Major Sponsors: .. _`1Password`: https://github.com/1Password/for-open-source .. _`matplotrecorder`: https://github.com/AtsushiSakai/matplotrecorder .. _`PythonRoboticsGifs`: https://github.com/AtsushiSakai/PythonRoboticsGifs +.. _`autodoc`: https://www.sphinx-doc.org/en/master/usage/extensions/autodoc.html From f466f25f5328e019bd1e0ccc62b176ff2fc72187 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Mon, 28 Apr 2025 08:53:35 +0900 Subject: [PATCH 883/940] build(deps): bump ruff from 0.11.0 to 0.11.6 in /requirements (#1201) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.11.0 to 0.11.6. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.11.0...0.11.6) --- updated-dependencies: - dependency-name: ruff dependency-version: 0.11.6 dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 5438678f87..f3e6c3dc51 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.5.3 pytest == 8.3.5 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.15.0 # For unit test -ruff == 0.11.0 # For unit test +ruff == 0.11.6 # For unit test From af0442d358b1deca5710c0c6812424b12b39f7e7 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 1 May 2025 13:08:29 +0900 Subject: [PATCH 884/940] build(deps): update cvxpy version from 1.5.3 to 1.6.5 in requirements (#1203) * build(deps): update cvxpy version from 1.5.3 to 1.6.5 in requirements * Add ECOS solver and improve solver handling for stability Added ECOS to requirements and enhanced compatibility with cvxpy solvers by specifying 'order' for matrix reshaping. Updated solver configurations in rocket landing and pendulum control for consistency and reliability. Improved test behavior by enforcing stricter warning handling in pytest. --- .../rocket_powered_landing/rocket_powered_landing.py | 9 +++++---- InvertedPendulum/inverted_pendulum_mpc_control.py | 2 +- requirements/requirements.txt | 3 ++- tests/conftest.py | 2 +- 4 files changed, 9 insertions(+), 7 deletions(-) diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py index 239f3629c1..1918dc1cee 100644 --- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py +++ b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py @@ -31,6 +31,7 @@ W_DELTA_SIGMA = 1e-1 # difference in flight time W_NU = 1e5 # virtual control +print(cvxpy.installed_solvers()) solver = 'ECOS' verbose_solver = False @@ -462,11 +463,11 @@ def __init__(self, m, K): # x_t+1 = A_*x_t+B_*U_t+C_*U_T+1*S_*sigma+zbar+nu constraints += [ self.var['X'][:, k + 1] == - cvxpy.reshape(self.par['A_bar'][:, k], (m.n_x, m.n_x)) @ + cvxpy.reshape(self.par['A_bar'][:, k], (m.n_x, m.n_x), order='F') @ self.var['X'][:, k] + - cvxpy.reshape(self.par['B_bar'][:, k], (m.n_x, m.n_u)) @ + cvxpy.reshape(self.par['B_bar'][:, k], (m.n_x, m.n_u), order='F') @ self.var['U'][:, k] + - cvxpy.reshape(self.par['C_bar'][:, k], (m.n_x, m.n_u)) @ + cvxpy.reshape(self.par['C_bar'][:, k], (m.n_x, m.n_u), order='F') @ self.var['U'][:, k + 1] + self.par['S_bar'][:, k] * self.var['sigma'] + self.par['z_bar'][:, k] + @@ -536,7 +537,7 @@ def solve(self, **kwargs): with warnings.catch_warnings(): # For User warning from solver warnings.simplefilter('ignore') self.prob.solve(verbose=verbose_solver, - solver=solver) + solver=solver) except cvxpy.SolverError: error = True diff --git a/InvertedPendulum/inverted_pendulum_mpc_control.py b/InvertedPendulum/inverted_pendulum_mpc_control.py index 9a5fa2ab41..c45dde8acc 100644 --- a/InvertedPendulum/inverted_pendulum_mpc_control.py +++ b/InvertedPendulum/inverted_pendulum_mpc_control.py @@ -91,7 +91,7 @@ def mpc_control(x0): prob = cvxpy.Problem(cvxpy.Minimize(cost), constr) start = time.time() - prob.solve(verbose=False) + prob.solve(verbose=False, solver=cvxpy.CLARABEL) elapsed_time = time.time() - start print(f"calc time:{elapsed_time:.6f} [sec]") diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f3e6c3dc51..e9c68be7e6 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,8 @@ numpy == 2.2.4 scipy == 1.15.2 matplotlib == 3.10.1 -cvxpy == 1.5.3 +cvxpy == 1.6.5 +ecos == 2.0.14 pytest == 8.3.5 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.15.0 # For unit test diff --git a/tests/conftest.py b/tests/conftest.py index 3485fe8150..b707b22d00 100644 --- a/tests/conftest.py +++ b/tests/conftest.py @@ -10,4 +10,4 @@ def run_this_test(file): - pytest.main([os.path.abspath(file)]) + pytest.main(args=["-W", "error", "-Werror", "--pythonwarnings=error", os.path.abspath(file)]) From 1f729cb8cbd5075871bb52c8fb31df2732ad6641 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 1 May 2025 13:59:15 +0900 Subject: [PATCH 885/940] build(deps): bump ruff from 0.11.6 to 0.11.7 in /requirements (#1205) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.11.6 to 0.11.7. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.11.6...0.11.7) --- updated-dependencies: - dependency-name: ruff dependency-version: 0.11.7 dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e9c68be7e6..88cbb21f81 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -6,4 +6,4 @@ ecos == 2.0.14 pytest == 8.3.5 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.15.0 # For unit test -ruff == 0.11.6 # For unit test +ruff == 0.11.7 # For unit test From a2c42c3d6837658edb734e9f16ab64c1bd2662e7 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 1 May 2025 21:53:12 +0900 Subject: [PATCH 886/940] Update Python version to 3.13 across the project (#1208) * Update Python version to 3.13 across the project Upgraded the required Python version to 3.13 in configurations, CI workflows, documentation, and environment files. This ensures compatibility with the latest Python release and maintains consistency across all project components. * Update Python version to 3.13 across the project Upgraded the required Python version to 3.13 in configurations, CI workflows, documentation, and environment files. This ensures compatibility with the latest Python release and maintains consistency across all project components. --- .circleci/config.yml | 2 +- .github/workflows/Linux_CI.yml | 2 +- .github/workflows/MacOS_CI.yml | 2 +- .github/workflows/Windows_CI.yml | 2 +- README.md | 2 +- appveyor.yml | 2 +- docs/modules/0_getting_started/3_how_to_contribute_main.rst | 2 +- requirements/environment.yml | 2 +- ruff.toml | 4 ++-- 9 files changed, 10 insertions(+), 10 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index 9f803ece4a..f6eff674de 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -6,7 +6,7 @@ orbs: jobs: build_doc: docker: - - image: cimg/python:3.12 + - image: cimg/python:3.13 steps: - checkout - run: diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index 7b3dc14751..907d36452d 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -12,7 +12,7 @@ jobs: runs-on: ubuntu-latest strategy: matrix: - python-version: [ '3.12' ] + python-version: [ '3.13' ] name: Python ${{ matrix.python-version }} CI diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index 5ea15ac72e..03db65f43d 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -16,7 +16,7 @@ jobs: runs-on: macos-latest strategy: matrix: - python-version: [ '3.12' ] + python-version: [ '3.13' ] name: Python ${{ matrix.python-version }} CI steps: - uses: actions/checkout@v4 diff --git a/.github/workflows/Windows_CI.yml b/.github/workflows/Windows_CI.yml index b9c8dea649..5cb19699b2 100644 --- a/.github/workflows/Windows_CI.yml +++ b/.github/workflows/Windows_CI.yml @@ -16,7 +16,7 @@ jobs: runs-on: windows-latest strategy: matrix: - python-version: [ '3.12' ] + python-version: [ '3.13' ] name: Python ${{ matrix.python-version }} CI steps: - uses: actions/checkout@v4 diff --git a/README.md b/README.md index 9e605435ce..6d04c90bc8 100644 --- a/README.md +++ b/README.md @@ -102,7 +102,7 @@ or this paper for more details: For running each sample code: -- [Python 3.12.x](https://www.python.org/) +- [Python 3.13.x](https://www.python.org/) - [NumPy](https://numpy.org/) diff --git a/appveyor.yml b/appveyor.yml index 05ad8a2820..72d89acf11 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -8,7 +8,7 @@ environment: CMD_IN_ENV: "cmd /E:ON /V:ON /C .\\appveyor\\run_with_env.cmd" matrix: - - PYTHON_DIR: C:\Python310-x64 + - PYTHON_DIR: C:\Python313-x64 branches: only: diff --git a/docs/modules/0_getting_started/3_how_to_contribute_main.rst b/docs/modules/0_getting_started/3_how_to_contribute_main.rst index 30e3001f36..0325aaacae 100644 --- a/docs/modules/0_getting_started/3_how_to_contribute_main.rst +++ b/docs/modules/0_getting_started/3_how_to_contribute_main.rst @@ -26,7 +26,7 @@ to understand the philosophies of this project. Check your Python version. --------------------------- -We only accept a PR for Python 3.12.x or higher. +We only accept a PR for Python 3.13.x or higher. We will not accept a PR for Python 2.x. diff --git a/requirements/environment.yml b/requirements/environment.yml index afbb3fb8ce..023a3d75bf 100644 --- a/requirements/environment.yml +++ b/requirements/environment.yml @@ -2,7 +2,7 @@ name: python_robotics channels: - conda-forge dependencies: - - python=3.12 + - python=3.13 - pip - scipy - numpy diff --git a/ruff.toml b/ruff.toml index 5823ca3db7..d76b715a06 100644 --- a/ruff.toml +++ b/ruff.toml @@ -5,8 +5,8 @@ ignore = ["E501", "E741", "E402"] exclude = [ ] -# Assume Python 3.11 -target-version = "py312" +# Assume Python 3.13 +target-version = "py313" [per-file-ignores] From 22cbee49218a1f8acb07ad488416db3c952c19d6 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Fri, 2 May 2025 10:01:19 +0900 Subject: [PATCH 887/940] Standardize "Ref:" to "Reference" across files (#1210) Updated all instances of "Ref:" to "Reference" for consistency in both code and documentation. This change improves clarity and aligns with standard terminology practices. --- .../rocket_powered_landing.py | 2 +- .../two_joint_arm_to_point_control.py | 2 +- .../ensemble_kalman_filter.py | 2 +- Mapping/DistanceMap/distance_map.py | 2 +- .../rectangle_fitting/rectangle_fitting.py | 2 +- MissionPlanning/BehaviorTree/behavior_tree.py | 2 +- MissionPlanning/StateMachine/state_machine.py | 4 +- PathPlanning/ElasticBands/elastic_bands.py | 2 +- .../Eta3SplinePath/eta3_spline_path.py | 2 +- .../cartesian_frenet_converter.py | 2 +- .../frenet_optimal_trajectory.py | 2 +- .../potential_field_planning.py | 2 +- .../quintic_polynomials_planner.py | 2 +- .../state_lattice_planner.py | 2 +- PathTracking/cgmres_nmpc/cgmres_nmpc.py | 2 +- PathTracking/move_to_pose/move_to_pose.py | 2 +- .../stanley_controller/stanley_controller.py | 2 +- README.md | 42 ++--- .../Kalmanfilter_basics_2_main.rst | 2 +- .../12_appendix/Kalmanfilter_basics_main.rst | 2 +- .../steering_motion_model_main.rst | 2 +- ...samble_kalman_filter_localization_main.rst | 5 + ...tended_kalman_filter_localization_main.rst | 168 +++++++++--------- .../histogram_filter_localization_main.rst | 7 +- .../particle_filter_localization_main.rst | 8 +- ...cented_kalman_filter_localization_main.rst | 8 +- .../modules/4_slam/ekf_slam/ekf_slam_main.rst | 2 +- .../4_slam/graph_slam/graph_slam_main.rst | 2 +- .../bezier_path/bezier_path_main.rst | 2 +- .../eta3_spline/eta3_spline_main.rst | 2 +- .../frenet_frame_path_main.rst | 2 +- .../grid_base_search_main.rst | 6 +- ...l_predictive_trajectory_generator_main.rst | 2 +- .../prm_planner/prm_planner_main.rst | 2 +- .../quintic_polynomials_planner_main.rst | 2 +- .../reeds_shepp_path_main.rst | 2 +- docs/modules/5_path_planning/rrt/rrt_main.rst | 8 +- .../state_lattice_planner_main.rst | 2 +- .../vrm_planner/vrm_planner_main.rst | 2 +- .../lqr_speed_and_steering_control_main.rst | 2 +- .../lqr_steering_control_main.rst | 2 +- .../pure_pursuit_tracking_main.rst | 2 +- .../rear_wheel_feedback_control_main.rst | 2 +- .../stanley_control/stanley_control_main.rst | 2 +- users_comments.md | 2 +- 45 files changed, 173 insertions(+), 155 deletions(-) diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py index 1918dc1cee..e8ba8fa220 100644 --- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py +++ b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py @@ -5,7 +5,7 @@ author: Sven Niederberger Atsushi Sakai -Ref: +Reference: - Python implementation of 'Successive Convexification for 6-DoF Mars Rocket Powered Landing with Free-Final-Time' paper by Michael Szmuk and Behcet Acıkmese. diff --git a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py index c2227f18e3..09969c30be 100644 --- a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py +++ b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py @@ -5,7 +5,7 @@ Author: Daniel Ingram (daniel-s-ingram) Atsushi Sakai (@Atsushi_twi) -Ref: P. I. Corke, "Robotics, Vision & Control", Springer 2017, +Reference: P. I. Corke, "Robotics, Vision & Control", Springer 2017, ISBN 978-3-319-54413-7 p102 - [Robotics, Vision and Control] (https://link.springer.com/book/10.1007/978-3-642-20144-8) diff --git a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py index 2bab3b49c1..e8a988a270 100644 --- a/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py +++ b/Localization/ensemble_kalman_filter/ensemble_kalman_filter.py @@ -4,7 +4,7 @@ author: Ryohei Sasaki(rsasaki0109) -Ref: +Reference: Ensemble Kalman filtering (https://rmets.onlinelibrary.wiley.com/doi/10.1256/qj.05.135) diff --git a/Mapping/DistanceMap/distance_map.py b/Mapping/DistanceMap/distance_map.py index 0dcc7380c5..0f96c9e8c6 100644 --- a/Mapping/DistanceMap/distance_map.py +++ b/Mapping/DistanceMap/distance_map.py @@ -3,7 +3,7 @@ author: Wang Zheng (@Aglargil) -Ref: +Reference: - [Distance Map] (https://cs.brown.edu/people/pfelzens/papers/dt-final.pdf) diff --git a/Mapping/rectangle_fitting/rectangle_fitting.py b/Mapping/rectangle_fitting/rectangle_fitting.py index 177f078871..7902619666 100644 --- a/Mapping/rectangle_fitting/rectangle_fitting.py +++ b/Mapping/rectangle_fitting/rectangle_fitting.py @@ -4,7 +4,7 @@ author: Atsushi Sakai (@Atsushi_twi) -Ref: +Reference: - Efficient L-Shape Fitting for Vehicle Detection Using Laser Scanners - The Robotics Institute Carnegie Mellon University https://www.ri.cmu.edu/publications/ diff --git a/MissionPlanning/BehaviorTree/behavior_tree.py b/MissionPlanning/BehaviorTree/behavior_tree.py index 59f4c713f1..9ad886aafb 100644 --- a/MissionPlanning/BehaviorTree/behavior_tree.py +++ b/MissionPlanning/BehaviorTree/behavior_tree.py @@ -3,7 +3,7 @@ author: Wang Zheng (@Aglargil) -Ref: +Reference: - [Behavior Tree](https://en.wikipedia.org/wiki/Behavior_tree_(artificial_intelligence,_robotics_and_control)) """ diff --git a/MissionPlanning/StateMachine/state_machine.py b/MissionPlanning/StateMachine/state_machine.py index de72f0f451..454759236e 100644 --- a/MissionPlanning/StateMachine/state_machine.py +++ b/MissionPlanning/StateMachine/state_machine.py @@ -3,7 +3,7 @@ author: Wang Zheng (@Aglargil) -Ref: +Reference: - [State Machine] (https://en.wikipedia.org/wiki/Finite-state_machine) @@ -23,7 +23,7 @@ def deflate_and_encode(plantuml_text): """ zlib compress the plantuml text and encode it for the plantuml server. - Ref: https://plantuml.com/en/text-encoding + Reference https://plantuml.com/en/text-encoding """ plantuml_alphabet = ( string.digits + string.ascii_uppercase + string.ascii_lowercase + "-_" diff --git a/PathPlanning/ElasticBands/elastic_bands.py b/PathPlanning/ElasticBands/elastic_bands.py index 785f822d14..77d4e6e399 100644 --- a/PathPlanning/ElasticBands/elastic_bands.py +++ b/PathPlanning/ElasticBands/elastic_bands.py @@ -3,7 +3,7 @@ author: Wang Zheng (@Aglargil) -Ref: +Reference: - [Elastic Bands: Connecting Path Planning and Control] (http://www8.cs.umu.se/research/ifor/dl/Control/elastic%20bands.pdf) diff --git a/PathPlanning/Eta3SplinePath/eta3_spline_path.py b/PathPlanning/Eta3SplinePath/eta3_spline_path.py index dc07d3c84b..3f685e512f 100644 --- a/PathPlanning/Eta3SplinePath/eta3_spline_path.py +++ b/PathPlanning/Eta3SplinePath/eta3_spline_path.py @@ -5,7 +5,7 @@ author: Joe Dinius, Ph.D (https://jwdinius.github.io) Atsushi Sakai (@Atsushi_twi) -Ref: +Reference: - [eta^3-Splines for the Smooth Path Generation of Wheeled Mobile Robots] (https://ieeexplore.ieee.org/document/4339545/) diff --git a/PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py b/PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py index 4cc8650c89..482712ceaf 100644 --- a/PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py +++ b/PathPlanning/FrenetOptimalTrajectory/cartesian_frenet_converter.py @@ -4,7 +4,7 @@ author: Wang Zheng (@Aglargil) -Ref: +Reference: - [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame] (https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf) diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index 248894c1c6..4b82fb70fd 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -4,7 +4,7 @@ author: Atsushi Sakai (@Atsushi_twi) -Ref: +Reference: - [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame] (https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf) diff --git a/PathPlanning/PotentialFieldPlanning/potential_field_planning.py b/PathPlanning/PotentialFieldPlanning/potential_field_planning.py index 8f136b5ee3..603a9d16cf 100644 --- a/PathPlanning/PotentialFieldPlanning/potential_field_planning.py +++ b/PathPlanning/PotentialFieldPlanning/potential_field_planning.py @@ -4,7 +4,7 @@ author: Atsushi Sakai (@Atsushi_twi) -Ref: +Reference: https://www.cs.cmu.edu/~motionplanning/lecture/Chap4-Potential-Field_howie.pdf """ diff --git a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py index fdc181afab..86f9f662da 100644 --- a/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py +++ b/PathPlanning/QuinticPolynomialsPlanner/quintic_polynomials_planner.py @@ -4,7 +4,7 @@ author: Atsushi Sakai (@Atsushi_twi) -Ref: +Reference: - [Local Path planning And Motion Control For Agv In Positioning](https://ieeexplore.ieee.org/document/637936/) diff --git a/PathPlanning/StateLatticePlanner/state_lattice_planner.py b/PathPlanning/StateLatticePlanner/state_lattice_planner.py index 7f8e725e0a..05f8df78f8 100644 --- a/PathPlanning/StateLatticePlanner/state_lattice_planner.py +++ b/PathPlanning/StateLatticePlanner/state_lattice_planner.py @@ -8,7 +8,7 @@ https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathPlanning /ModelPredictiveTrajectoryGenerator/lookup_table_generator.py -Ref: +Reference: - State Space Sampling of Feasible Motions for High-Performance Mobile Robot Navigation in Complex Environments diff --git a/PathTracking/cgmres_nmpc/cgmres_nmpc.py b/PathTracking/cgmres_nmpc/cgmres_nmpc.py index a582c9da81..ee40e73504 100644 --- a/PathTracking/cgmres_nmpc/cgmres_nmpc.py +++ b/PathTracking/cgmres_nmpc/cgmres_nmpc.py @@ -4,7 +4,7 @@ author Atsushi Sakai (@Atsushi_twi) -Ref: +Reference: Shunichi09/nonlinear_control: Implementing the nonlinear model predictive control, sliding mode control https://github.com/Shunichi09/PythonLinearNonlinearControl diff --git a/PathTracking/move_to_pose/move_to_pose.py b/PathTracking/move_to_pose/move_to_pose.py index 34736a2e21..faf1264953 100644 --- a/PathTracking/move_to_pose/move_to_pose.py +++ b/PathTracking/move_to_pose/move_to_pose.py @@ -76,7 +76,7 @@ def calc_control_command(self, x_diff, y_diff, theta, theta_goal): # [-pi, pi] to prevent unstable behavior e.g. difference going # from 0 rad to 2*pi rad with slight turn - # Ref: The velocity v always has a constant sign which depends on the initial value of α. + # The velocity v always has a constant sign which depends on the initial value of α. rho = np.hypot(x_diff, y_diff) v = self.Kp_rho * rho diff --git a/PathTracking/stanley_controller/stanley_controller.py b/PathTracking/stanley_controller/stanley_controller.py index bc98175f17..01c2ec0229 100644 --- a/PathTracking/stanley_controller/stanley_controller.py +++ b/PathTracking/stanley_controller/stanley_controller.py @@ -4,7 +4,7 @@ author: Atsushi Sakai (@Atsushi_twi) -Ref: +Reference: - [Stanley: The robot that won the DARPA grand challenge](http://isl.ecst.csuchico.edu/DOCS/darpa2005/DARPA%202005%20Stanley.pdf) - [Autonomous Automobile Path Tracking](https://www.ri.cmu.edu/pub_files/2009/2/Automatic_Steering_Methods_for_Autonomous_Automobile_Path_Tracking.pdf) diff --git a/README.md b/README.md index 6d04c90bc8..05fd0262df 100644 --- a/README.md +++ b/README.md @@ -168,7 +168,7 @@ All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation EKF pic -Ref: +Reference - [documentation](https://atsushisakai.github.io/PythonRobotics/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.html) @@ -186,7 +186,7 @@ It is assumed that the robot can measure a distance from landmarks (RFID). These measurements are used for PF localization. -Ref: +Reference - [PROBABILISTIC ROBOTICS](http://www.probabilistic-robotics.org/) @@ -207,7 +207,7 @@ The filter integrates speed input and range observations from RFID for localizat Initial position is not needed. -Ref: +Reference - [PROBABILISTIC ROBOTICS](http://www.probabilistic-robotics.org/) @@ -256,7 +256,7 @@ It can calculate a rotation matrix, and a translation vector between points and ![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/iterative_closest_point/animation.gif) -Ref: +Reference - [Introduction to Mobile Robotics: Iterative Closest Point Algorithm](https://cs.gmu.edu/~kosecka/cs685/cs685-icp.pdf) @@ -275,7 +275,7 @@ Black points are landmarks, blue crosses are estimated landmark positions by Fas ![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM1/animation.gif) -Ref: +Reference - [PROBABILISTIC ROBOTICS](http://www.probabilistic-robotics.org/) @@ -321,7 +321,7 @@ This is a 2D grid based the shortest path planning with D star algorithm. The animation shows a robot finding its path avoiding an obstacle using the D* search algorithm. -Ref: +Reference - [D* Algorithm Wikipedia](https://en.wikipedia.org/wiki/D*) @@ -346,7 +346,7 @@ This is a 2D grid based path planning with Potential Field algorithm. In the animation, the blue heat map shows potential value on each grid. -Ref: +Reference - [Robotic Motion Planning:Potential Functions](https://www.cs.cmu.edu/~motionplanning/lecture/Chap4-Potential-Field_howie.pdf) @@ -362,7 +362,7 @@ This script is a path planning code with state lattice planning. This code uses the model predictive trajectory generator to solve boundary problem. -Ref: +Reference - [Optimal rough terrain trajectory generation for wheeled mobile robots](https://journals.sagepub.com/doi/pdf/10.1177/0278364906075328) @@ -390,7 +390,7 @@ Cyan crosses means searched points with Dijkstra method, The red line is the final path of PRM. -Ref: +Reference - [Probabilistic roadmap \- Wikipedia](https://en.wikipedia.org/wiki/Probabilistic_roadmap) @@ -406,7 +406,7 @@ This is a path planning code with RRT\* Black circles are obstacles, green line is a searched tree, red crosses are start and goal positions. -Ref: +Reference - [Incremental Sampling-based Algorithms for Optimal Motion Planning](https://arxiv.org/abs/1005.0416) @@ -426,7 +426,7 @@ A double integrator motion model is used for LQR local planner. ![LQR_RRT](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRRRTStar/animation.gif) -Ref: +Reference - [LQR\-RRT\*: Optimal Sampling\-Based Motion Planning with Automatically Derived Extension Heuristics](https://lis.csail.mit.edu/pubs/perez-icra12.pdf) @@ -441,7 +441,7 @@ Motion planning with quintic polynomials. It can calculate a 2D path, velocity, and acceleration profile based on quintic polynomials. -Ref: +Reference - [Local Path Planning And Motion Control For Agv In Positioning](https://ieeexplore.ieee.org/document/637936/) @@ -451,7 +451,7 @@ A sample code with Reeds Shepp path planning. ![RSPlanning](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ReedsSheppPath/animation.gif?raw=true) -Ref: +Reference - [15.3.2 Reeds\-Shepp Curves](http://planning.cs.uiuc.edu/node822.html) @@ -477,7 +477,7 @@ The cyan line is the target course and black crosses are obstacles. The red line is the predicted path. -Ref: +Reference - [Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet Frame](https://www.researchgate.net/profile/Moritz_Werling/publication/224156269_Optimal_Trajectory_Generation_for_Dynamic_Street_Scenarios_in_a_Frenet_Frame/links/54f749df0cf210398e9277af.pdf) @@ -492,7 +492,7 @@ This is a simulation of moving to a pose control ![2](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif) -Ref: +Reference - [P. I. Corke, "Robotics, Vision and Control" \| SpringerLink p102](https://link.springer.com/book/10.1007/978-3-642-20144-8) @@ -503,7 +503,7 @@ Path tracking simulation with Stanley steering control and PID speed control. ![2](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/stanley_controller/animation.gif) -Ref: +Reference - [Stanley: The robot that won the DARPA grand challenge](http://robots.stanford.edu/papers/thrun.stanley05.pdf) @@ -517,7 +517,7 @@ Path tracking simulation with rear wheel feedback steering control and PID speed ![PythonRobotics/figure_1.png at master · AtsushiSakai/PythonRobotics](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/rear_wheel_feedback/animation.gif) -Ref: +Reference - [A Survey of Motion Planning and Control Techniques for Self-driving Urban Vehicles](https://arxiv.org/abs/1604.07446) @@ -528,7 +528,7 @@ Path tracking simulation with LQR speed and steering control. ![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_speed_steer_control/animation.gif) -Ref: +Reference - [Towards fully autonomous driving: Systems and algorithms \- IEEE Conference Publication](https://ieeexplore.ieee.org/document/5940562/) @@ -539,7 +539,7 @@ Path tracking simulation with iterative linear model predictive speed and steeri MPC pic -Ref: +Reference - [documentation](https://atsushisakai.github.io/PythonRobotics/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control.html) @@ -551,7 +551,7 @@ A motion planning and path tracking simulation with NMPC of C-GMRES ![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/cgmres_nmpc/animation.gif) -Ref: +Reference - [documentation](https://atsushisakai.github.io/PythonRobotics/modules/path_tracking/cgmres_nmpc/cgmres_nmpc.html) @@ -591,7 +591,7 @@ This is a 3d trajectory generation simulation for a rocket powered landing. ![3](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/rocket_powered_landing/animation.gif) -Ref: +Reference - [documentation](https://atsushisakai.github.io/PythonRobotics/modules/aerial_navigation/rocket_powered_landing/rocket_powered_landing.html) diff --git a/docs/modules/12_appendix/Kalmanfilter_basics_2_main.rst b/docs/modules/12_appendix/Kalmanfilter_basics_2_main.rst index 9ae6fc5bcb..b7ff84e6f6 100644 --- a/docs/modules/12_appendix/Kalmanfilter_basics_2_main.rst +++ b/docs/modules/12_appendix/Kalmanfilter_basics_2_main.rst @@ -331,7 +331,7 @@ are vectors and matrices, but the concepts are exactly the same: - Use the process model to predict the next state (the prior) - Form an estimate part way between the measurement and the prior -References: +Reference ~~~~~~~~~~~ 1. Roger Labbe’s diff --git a/docs/modules/12_appendix/Kalmanfilter_basics_main.rst b/docs/modules/12_appendix/Kalmanfilter_basics_main.rst index 6548377e07..a1d99d47ef 100644 --- a/docs/modules/12_appendix/Kalmanfilter_basics_main.rst +++ b/docs/modules/12_appendix/Kalmanfilter_basics_main.rst @@ -552,7 +552,7 @@ a given (X,Y) value. .. image:: Kalmanfilter_basics_files/Kalmanfilter_basics_28_1.png -References: +Reference ~~~~~~~~~~~ 1. Roger Labbe’s diff --git a/docs/modules/12_appendix/steering_motion_model_main.rst b/docs/modules/12_appendix/steering_motion_model_main.rst index 6e444b7909..c697123fa2 100644 --- a/docs/modules/12_appendix/steering_motion_model_main.rst +++ b/docs/modules/12_appendix/steering_motion_model_main.rst @@ -91,7 +91,7 @@ the target minimum velocity :math:`v_{min}` can be calculated as follows: :math:`v_{min} = \frac{d_{t+1}+d_{t}}{\Delta t} = \frac{d_{t+1}+d_{t}}{(\kappa_{t+1}-\kappa_{t})}\frac{tan\dot{\delta}_{max}}{WB}` -References: +Reference ~~~~~~~~~~~ - `Vehicle Dynamics and Control `_ diff --git a/docs/modules/2_localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst b/docs/modules/2_localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst index 2543d1186a..214e645d10 100644 --- a/docs/modules/2_localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst +++ b/docs/modules/2_localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst @@ -5,3 +5,8 @@ Ensamble Kalman Filter Localization This is a sensor fusion localization with Ensamble Kalman Filter(EnKF). +Code Link +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +.. autofunction:: Localization.ensemble_kalman_filter.ensemble_kalman_filter.enkf_localization + diff --git a/docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst b/docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst index da214b6de5..adb41e5e40 100644 --- a/docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst +++ b/docs/modules/2_localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst @@ -23,28 +23,40 @@ is estimated trajectory with EKF. The red ellipse is estimated covariance ellipse with EKF. -Code: `PythonRobotics/extended_kalman_filter.py at master · -AtsushiSakai/PythonRobotics `__ +Code Link +~~~~~~~~~~~~~ -Kalman Filter with Speed Scale Factor Correction -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +.. autofunction:: Localization.extended_kalman_filter.extended_kalman_filter.ekf_estimation +Extended Kalman Filter algorithm +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -.. image:: ekf_with_velocity_correction_1_0.png - :width: 600px +Localization process using Extended Kalman Filter:EKF is -This is a Extended kalman filter (EKF) localization with velocity correction. +=== Predict === -This is for correcting the vehicle speed measured with scale factor errors due to factors such as wheel wear. +:math:`x_{Pred} = Fx_t+Bu_t` -Code: `PythonRobotics/extended_kalman_ekf_with_velocity_correctionfilter.py -AtsushiSakai/PythonRobotics `__ +:math:`P_{Pred} = J_f P_t J_f^T + Q` -Filter design -~~~~~~~~~~~~~ +=== Update === -Position Estimation Kalman Filter -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +:math:`z_{Pred} = Hx_{Pred}` + +:math:`y = z - z_{Pred}` + +:math:`S = J_g P_{Pred}.J_g^T + R` + +:math:`K = P_{Pred}.J_g^T S^{-1}` + +:math:`x_{t+1} = x_{Pred} + Ky` + +:math:`P_{t+1} = ( I - K J_g) P_{Pred}` + + + +Filter design +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ In this simulation, the robot has a state vector includes 4 states at time :math:`t`. @@ -82,27 +94,9 @@ In the code, “observation” function generates the input and observation vector with noise `code `__ -Kalman Filter with Speed Scale Factor Correction -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -In this simulation, the robot has a state vector includes 5 states at -time :math:`t`. - -.. math:: \textbf{x}_t=[x_t, y_t, \phi_t, v_t, s_t] - -x, y are a 2D x-y position, :math:`\phi` is orientation, v is -velocity, and s is a scale factor of velocity. - -In the code, “xEst” means the state vector. -`code `__ - -The rest is the same as the Position Estimation Kalman Filter. Motion Model -~~~~~~~~~~~~ - -Position Estimation Kalman Filter -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +~~~~~~~~~~~~~~~~~ The robot model is @@ -137,9 +131,61 @@ Its Jacobian matrix is :math:`\begin{equation*}  = \begin{bmatrix} 1& 0 & -v \sin(\phi) \Delta t & \cos(\phi) \Delta t\\ 0 & 1 & v \cos(\phi) \Delta t & \sin(\phi) \Delta t\\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{bmatrix} \end{equation*}` +Observation Model +~~~~~~~~~~~~~~~~~ + +The robot can get x-y position information from GPS. + +So GPS Observation model is + +.. math:: \textbf{z}_{t} = g(\textbf{x}_t) = H \textbf{x}_t + +where + +:math:`\begin{equation*} H = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 \\ \end{bmatrix} \end{equation*}` + +The observation function states that + +:math:`\begin{equation*} \begin{bmatrix} x' \\ y' \end{bmatrix} = g(\textbf{x}) = \begin{bmatrix} x \\ y \end{bmatrix} \end{equation*}` + +Its Jacobian matrix is + +:math:`\begin{equation*} J_g = \begin{bmatrix} \frac{\partial x'}{\partial x} & \frac{\partial x'}{\partial y} & \frac{\partial x'}{\partial \phi} & \frac{\partial x'}{\partial v}\\ \frac{\partial y'}{\partial x}& \frac{\partial y'}{\partial y} & \frac{\partial y'}{\partial \phi} & \frac{\partial y'}{ \partial v}\\ \end{bmatrix} \end{equation*}` + +:math:`\begin{equation*}  = \begin{bmatrix} 1& 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ \end{bmatrix} \end{equation*}` + Kalman Filter with Speed Scale Factor Correction ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +This is a Extended kalman filter (EKF) localization with velocity correction. + +This is for correcting the vehicle speed measured with scale factor errors due to factors such as wheel wear. + + +In this simulation, the robot has a state vector includes 5 states at +time :math:`t`. + +.. math:: \textbf{x}_t=[x_t, y_t, \phi_t, v_t, s_t] + +x, y are a 2D x-y position, :math:`\phi` is orientation, v is +velocity, and s is a scale factor of velocity. + +In the code, “xEst” means the state vector. +`code `__ + +The rest is the same as the Position Estimation Kalman Filter. + +.. image:: ekf_with_velocity_correction_1_0.png + :width: 600px + +Code Link +~~~~~~~~~~~~~ + +.. autofunction:: Localization.extended_kalman_filter.ekf_with_velocity_correction.ekf_estimation + + +Motion Model +~~~~~~~~~~~~ The robot model is @@ -178,33 +224,7 @@ Its Jacobian matrix is Observation Model ~~~~~~~~~~~~~~~~~ -Position Estimation Kalman Filter -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -The robot can get x-y position infomation from GPS. - -So GPS Observation model is - -.. math:: \textbf{z}_{t} = g(\textbf{x}_t) = H \textbf{x}_t - -where - -:math:`\begin{equation*} H = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 \\ \end{bmatrix} \end{equation*}` - -The observation function states that - -:math:`\begin{equation*} \begin{bmatrix} x' \\ y' \end{bmatrix} = g(\textbf{x}) = \begin{bmatrix} x \\ y \end{bmatrix} \end{equation*}` - -Its Jacobian matrix is - -:math:`\begin{equation*} J_g = \begin{bmatrix} \frac{\partial x'}{\partial x} & \frac{\partial x'}{\partial y} & \frac{\partial x'}{\partial \phi} & \frac{\partial x'}{\partial v}\\ \frac{\partial y'}{\partial x}& \frac{\partial y'}{\partial y} & \frac{\partial y'}{\partial \phi} & \frac{\partial y'}{ \partial v}\\ \end{bmatrix} \end{equation*}` - -:math:`\begin{equation*}  = \begin{bmatrix} 1& 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ \end{bmatrix} \end{equation*}` - -Kalman Filter with Speed Scale Factor Correction -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -The robot can get x-y position infomation from GPS. +The robot can get x-y position information from GPS. So GPS Observation model is @@ -225,32 +245,8 @@ Its Jacobian matrix is :math:`\begin{equation*}  = \begin{bmatrix} 1& 0 & 0 & 0 & 0\\ 0 & 1 & 0 & 0 & 0\\ \end{bmatrix} \end{equation*}` -Extended Kalman Filter -~~~~~~~~~~~~~~~~~~~~~~ - -Localization process using Extended Kalman Filter:EKF is - -=== Predict === - -:math:`x_{Pred} = Fx_t+Bu_t` - -:math:`P_{Pred} = J_f P_t J_f^T + Q` - -=== Update === - -:math:`z_{Pred} = Hx_{Pred}` - -:math:`y = z - z_{Pred}` - -:math:`S = J_g P_{Pred}.J_g^T + R` - -:math:`K = P_{Pred}.J_g^T S^{-1}` - -:math:`x_{t+1} = x_{Pred} + Ky` - -:math:`P_{t+1} = ( I - K J_g) P_{Pred}` -Ref: -~~~~ +Reference +^^^^^^^^^^^ - `PROBABILISTIC-ROBOTICS.ORG `__ diff --git a/docs/modules/2_localization/histogram_filter_localization/histogram_filter_localization_main.rst b/docs/modules/2_localization/histogram_filter_localization/histogram_filter_localization_main.rst index fafd578333..3a175b1316 100644 --- a/docs/modules/2_localization/histogram_filter_localization/histogram_filter_localization_main.rst +++ b/docs/modules/2_localization/histogram_filter_localization/histogram_filter_localization_main.rst @@ -16,6 +16,11 @@ The filter uses speed input and range observations from RFID for localization. Initial position information is not needed. +Code Link +~~~~~~~~~~~~~ + +.. autofunction:: Localization.histogram_filter.histogram_filter.histogram_filter_localization + Filtering algorithm ~~~~~~~~~~~~~~~~~~~~ @@ -107,7 +112,7 @@ There are two ways to calculate the final positions: -References: +Reference ~~~~~~~~~~~ - `_PROBABILISTIC ROBOTICS: `_ diff --git a/docs/modules/2_localization/particle_filter_localization/particle_filter_localization_main.rst b/docs/modules/2_localization/particle_filter_localization/particle_filter_localization_main.rst index 20a9eb58fc..d648d8e080 100644 --- a/docs/modules/2_localization/particle_filter_localization/particle_filter_localization_main.rst +++ b/docs/modules/2_localization/particle_filter_localization/particle_filter_localization_main.rst @@ -15,6 +15,12 @@ It is assumed that the robot can measure a distance from landmarks This measurements are used for PF localization. +Code Link +~~~~~~~~~~~~~ + +.. autofunction:: Localization.particle_filter.particle_filter.pf_localization + + How to calculate covariance matrix from particles ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ @@ -30,7 +36,7 @@ The covariance matrix :math:`\Xi` from particle information is calculated by the - :math:`\mu_j` is the :math:`j` th mean state of particles. -References: +Reference ~~~~~~~~~~~ - `_PROBABILISTIC ROBOTICS: `_ diff --git a/docs/modules/2_localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst b/docs/modules/2_localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst index bb6b5b664b..a7a5aab61b 100644 --- a/docs/modules/2_localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst +++ b/docs/modules/2_localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst @@ -7,7 +7,13 @@ This is a sensor fusion localization with Unscented Kalman Filter(UKF). The lines and points are same meaning of the EKF simulation. -References: +Code Link +~~~~~~~~~~~~~ + +.. autofunction:: Localization.unscented_kalman_filter.unscented_kalman_filter.ukf_estimation + + +Reference ~~~~~~~~~~~ - `Discriminatively Trained Unscented Kalman Filter for Mobile Robot Localization `_ diff --git a/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst b/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst index b27971225e..a1486ffe1e 100644 --- a/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst +++ b/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst @@ -578,7 +578,7 @@ reckoning and control functions are passed along here as well. .. image:: ekf_slam_1_0.png -References: +Reference ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - `PROBABILISTIC ROBOTICS `_ diff --git a/docs/modules/4_slam/graph_slam/graph_slam_main.rst b/docs/modules/4_slam/graph_slam/graph_slam_main.rst index 987eed385c..a2ef513527 100644 --- a/docs/modules/4_slam/graph_slam/graph_slam_main.rst +++ b/docs/modules/4_slam/graph_slam/graph_slam_main.rst @@ -17,7 +17,7 @@ The black stars are landmarks for graph edge generation. .. include:: graphSLAM_formulation.rst .. include:: graphSLAM_SE2_example.rst -References: +Reference ~~~~~~~~~~~ - `A Tutorial on Graph-Based SLAM `_ diff --git a/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst b/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst index d306a85352..9d9b3de709 100644 --- a/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst +++ b/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst @@ -13,7 +13,7 @@ You can get different Beizer course: .. image:: Figure_2.png -Ref: +Reference - `Continuous Curvature Path Generation Based on Bezier Curves for Autonomous diff --git a/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst b/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst index ffc3cc6451..82e0a71044 100644 --- a/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst +++ b/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst @@ -7,7 +7,7 @@ Eta^3 Spline path planning This is a path planning with Eta^3 spline. -Ref: +Reference - `\\eta^3-Splines for the Smooth Path Generation of Wheeled Mobile Robots `__ diff --git a/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst b/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst index 38efaf2b53..371d536e3f 100644 --- a/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst +++ b/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst @@ -35,7 +35,7 @@ Low Speed and Merging and Stopping Scenario This scenario illustrates the trajectory planning at low speeds with merging and stopping behaviors. -Ref: +Reference - `Optimal Trajectory Generation for Dynamic Street Scenarios in a Frenet diff --git a/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst b/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst index 1644ed00cc..bf82c9f391 100644 --- a/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst +++ b/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst @@ -63,7 +63,7 @@ This is a 2D grid based shortest path planning with D star algorithm. The animation shows a robot finding its path avoiding an obstacle using the D* search algorithm. -Ref: +Reference - `D* search Wikipedia `__ @@ -74,7 +74,7 @@ This is a 2D grid based path planning and replanning with D star lite algorithm. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DStarLite/animation.gif -Ref: +Reference - `Improved Fast Replanning for Robot Navigation in Unknown Terrain `_ @@ -88,7 +88,7 @@ This is a 2D grid based path planning with Potential Field algorithm. In the animation, the blue heat map shows potential value on each grid. -Ref: +Reference - `Robotic Motion Planning:Potential Functions `__ diff --git a/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst b/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst index 463363ddcf..1c5df1c9cc 100644 --- a/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst +++ b/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst @@ -16,7 +16,7 @@ Lookup table generation sample .. image:: lookup_table.png -Ref: +Reference - `Optimal rough terrain trajectory generation for wheeled mobile robots `__ diff --git a/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst b/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst index 0628719176..f816c5c1b9 100644 --- a/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst +++ b/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst @@ -13,7 +13,7 @@ Cyan crosses means searched points with Dijkstra method, The red line is the final path of PRM. -Ref: +Reference - `Probabilistic roadmap - Wikipedia `__ diff --git a/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst b/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst index 0412b3c9b3..66c3001c05 100644 --- a/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst +++ b/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst @@ -97,7 +97,7 @@ Each velocity and acceleration boundary condition can be calculated with each or :math:`v_{xe}=v_ecos(\theta_e), v_{ye}=v_esin(\theta_e)` -References: +Reference ~~~~~~~~~~~ - `Local Path Planning And Motion Control For Agv In diff --git a/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst b/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst index ff377eb91b..a4a5d28e01 100644 --- a/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst +++ b/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst @@ -380,7 +380,7 @@ Hence, we have: - :math:`v = (t - φ)` -Ref: +Reference - `15.3.2 Reeds-Shepp Curves `__ diff --git a/docs/modules/5_path_planning/rrt/rrt_main.rst b/docs/modules/5_path_planning/rrt/rrt_main.rst index e5f351a7ba..da3a4957a5 100644 --- a/docs/modules/5_path_planning/rrt/rrt_main.rst +++ b/docs/modules/5_path_planning/rrt/rrt_main.rst @@ -53,7 +53,7 @@ This is a path planning code with Informed RRT*. The cyan ellipse is the heuristic sampling domain of Informed RRT*. -Ref: +Reference - `Informed RRT\*: Optimal Sampling-based Path Planning Focused via Direct Sampling of an Admissible Ellipsoidal @@ -68,7 +68,7 @@ Batch Informed RRT\* This is a path planning code with Batch Informed RRT*. -Ref: +Reference - `Batch Informed Trees (BIT*): Sampling-based Optimal Planning via the Heuristically Guided Search of Implicit Random Geometric @@ -87,7 +87,7 @@ In this code, pure-pursuit algorithm is used for steering control, PID is used for speed control. -Ref: +Reference - `Motion Planning in Complex Environments using Closed-loop Prediction `__ @@ -109,7 +109,7 @@ A double integrator motion model is used for LQR local planner. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRRRTStar/animation.gif -Ref: +Reference - `LQR-RRT\*: Optimal Sampling-Based Motion Planning with Automatically Derived Extension diff --git a/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst b/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst index d5e7ed17d1..bf89ac11ae 100644 --- a/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst +++ b/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst @@ -22,7 +22,7 @@ Lane sampling .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/LaneSampling.gif -Ref: +Reference - `Optimal rough terrain trajectory generation for wheeled mobile robots `__ diff --git a/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst b/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst index 92e729ab29..65e0e53465 100644 --- a/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst +++ b/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst @@ -11,7 +11,7 @@ Cyan crosses mean searched points with Dijkstra method, The red line is the final path of Vornoi Road-Map. -Ref: +Reference - `Robotic Motion Planning `__ diff --git a/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst index ded187e972..568ef9a0df 100644 --- a/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst +++ b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst @@ -134,7 +134,7 @@ Simulation results -References: +Reference ~~~~~~~~~~~ - `Towards fully autonomous driving: Systems and algorithms `__ diff --git a/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst b/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst index baca7a33fc..831423f364 100644 --- a/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst +++ b/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst @@ -113,7 +113,7 @@ The optimal control input `u` can be calculated as: where `K` is the feedback gain matrix obtained by solving the Riccati equation. -References: +Reference ~~~~~~~~~~~ - `ApolloAuto/apollo: An open autonomous driving platform `_ diff --git a/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst b/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst index 5c7bcef85f..d7354cf8fb 100644 --- a/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst +++ b/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst @@ -9,7 +9,7 @@ speed control. The red line is a target course, the green cross means the target point for pure pursuit control, the blue line is the tracking. -References: +Reference ~~~~~~~~~~~ - `A Survey of Motion Planning and Control Techniques for Self-driving diff --git a/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst b/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst index 70875fdc6c..d18cd6fbf7 100644 --- a/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst +++ b/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst @@ -6,7 +6,7 @@ PID speed control. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/rear_wheel_feedback/animation.gif -References: +Reference ~~~~~~~~~~~ - `A Survey of Motion Planning and Control Techniques for Self-driving Urban Vehicles `__ diff --git a/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst b/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst index fe325b0102..69089ac33b 100644 --- a/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst +++ b/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst @@ -6,7 +6,7 @@ control. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/stanley_controller/animation.gif -References: +Reference ~~~~~~~~~~~ - `Stanley: The robot that won the DARPA grand diff --git a/users_comments.md b/users_comments.md index a2f798eac4..1674f21377 100644 --- a/users_comments.md +++ b/users_comments.md @@ -10,7 +10,7 @@ This is an electric wheelchair control demo by [Katsushun89](https://github.com/ ![1](https://github.com/AtsushiSakai/PythonRoboticsGifs/blob/master/Users/WHILL_Model_CR_with_move_to_a_pose/WHLL_Model_CR_with_move_to_a_pose.gif) -Ref: +Reference: - [toioと同じように動くWHILL Model CR (in Japanese)](https://qiita.com/KatsuShun89/items/68fde7544ecfe36096d2) From 5392fcff4d555421b4417827dc67c611ad14cc06 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 3 May 2025 09:25:12 +0900 Subject: [PATCH 888/940] Refactor module links and improve code documentation. (#1211) * Refactor module links and improve code documentation. Updated documentation to rename "API" sections to "Code Link" for clarity and consistency. Enhanced docstrings for `circle_fitting` and `kmeans_clustering` functions, improving parameter descriptions and adding return value details. Fixed typos in function and file names in the ray casting grid map module. * Fix import typo in ray casting grid map test module. Corrected the import statement in the test file by updating the module's name to `ray_casting_grid_map` for consistency with the source file. This ensures proper functionality of the test suite. --- Mapping/circle_fitting/circle_fitting.py | 33 +++++++++++++++---- .../kmeans_clustering/kmeans_clustering.py | 27 ++++++++++++++- .../ray_casting_grid_map.py} | 4 +-- .../circle_fitting/circle_fitting_main.rst | 4 +++ .../distance_map/distance_map_main.rst | 4 +-- .../gaussian_grid_map_main.rst | 6 ++++ .../k_means_object_clustering_main.rst | 6 ++++ .../lidar_to_grid_map_tutorial_main.rst | 6 ++++ .../normal_vector_estimation_main.rst | 8 ++--- .../point_cloud_sampling_main.rst | 8 ++--- .../ray_casting_grid_map_main.rst | 7 +++- .../rectangle_fitting_main.rst | 4 +-- ...id_map.py => test_ray_casting_grid_map.py} | 2 +- 13 files changed, 96 insertions(+), 23 deletions(-) rename Mapping/{raycasting_grid_map/raycasting_grid_map.py => ray_casting_grid_map/ray_casting_grid_map.py} (96%) rename tests/{test_raycasting_grid_map.py => test_ray_casting_grid_map.py} (71%) diff --git a/Mapping/circle_fitting/circle_fitting.py b/Mapping/circle_fitting/circle_fitting.py index 2eba550127..b5714b507c 100644 --- a/Mapping/circle_fitting/circle_fitting.py +++ b/Mapping/circle_fitting/circle_fitting.py @@ -16,12 +16,33 @@ def circle_fitting(x, y): """ - Circle Fitting with least squared - input: point x-y positions - output cxe x center position - cye y center position - re radius of circle - error: prediction error + Fits a circle to a given set of points using a least-squares approach. + + This function calculates the center (x, y) and radius of a circle that best fits + the given set of points in a two-dimensional plane. It minimizes the squared + errors between the circle and the provided points and returns the calculated + center coordinates, radius, and the fitting error. + + Raises + ------ + ValueError + If the input lists x and y do not contain the same number of elements. + + Parameters + ---------- + x : list[float] + The x-coordinates of the points. + y : list[float] + The y-coordinates of the points. + + Returns + ------- + tuple[float, float, float, float] + A tuple containing: + - The x-coordinate of the center of the fitted circle (float). + - The y-coordinate of the center of the fitted circle (float). + - The radius of the fitted circle (float). + - The fitting error as a deviation metric (float). """ sumx = sum(x) diff --git a/Mapping/kmeans_clustering/kmeans_clustering.py b/Mapping/kmeans_clustering/kmeans_clustering.py index e18960e990..cee01e5ad5 100644 --- a/Mapping/kmeans_clustering/kmeans_clustering.py +++ b/Mapping/kmeans_clustering/kmeans_clustering.py @@ -17,12 +17,37 @@ def kmeans_clustering(rx, ry, nc): + """ + Performs k-means clustering on the given dataset, iteratively adjusting cluster centroids + until convergence within a defined threshold or reaching the maximum number of + iterations. + + The implementation initializes clusters, calculates initial centroids, and refines the + clusters through iterative updates to optimize the cost function based on minimum + distance between datapoints and centroids. + + Arguments: + rx: List[float] + The x-coordinates of the dataset points to be clustered. + ry: List[float] + The y-coordinates of the dataset points to be clustered. + nc: int + The number of clusters to group the data into. + + Returns: + Clusters + An instance containing the final cluster assignments and centroids after + convergence. + + Raises: + None + + """ clusters = Clusters(rx, ry, nc) clusters.calc_centroid() pre_cost = float("inf") for loop in range(MAX_LOOP): - print("loop:", loop) cost = clusters.update_clusters() clusters.calc_centroid() diff --git a/Mapping/raycasting_grid_map/raycasting_grid_map.py b/Mapping/ray_casting_grid_map/ray_casting_grid_map.py similarity index 96% rename from Mapping/raycasting_grid_map/raycasting_grid_map.py rename to Mapping/ray_casting_grid_map/ray_casting_grid_map.py index 8ce37b925b..c7e73f0630 100644 --- a/Mapping/raycasting_grid_map/raycasting_grid_map.py +++ b/Mapping/ray_casting_grid_map/ray_casting_grid_map.py @@ -48,7 +48,7 @@ def atan_zero_to_twopi(y, x): return angle -def precasting(minx, miny, xw, yw, xyreso, yawreso): +def pre_casting(minx, miny, xw, yw, xyreso, yawreso): precast = [[] for i in range(int(round((math.pi * 2.0) / yawreso)) + 1)] @@ -81,7 +81,7 @@ def generate_ray_casting_grid_map(ox, oy, xyreso, yawreso): pmap = [[0.0 for i in range(yw)] for i in range(xw)] - precast = precasting(minx, miny, xw, yw, xyreso, yawreso) + precast = pre_casting(minx, miny, xw, yw, xyreso, yawreso) for (x, y) in zip(ox, oy): diff --git a/docs/modules/3_mapping/circle_fitting/circle_fitting_main.rst b/docs/modules/3_mapping/circle_fitting/circle_fitting_main.rst index 1892d1f8f7..e243529a9c 100644 --- a/docs/modules/3_mapping/circle_fitting/circle_fitting_main.rst +++ b/docs/modules/3_mapping/circle_fitting/circle_fitting_main.rst @@ -11,3 +11,7 @@ The red crosses are observations from a ranging sensor. The red circle is the estimated object shape using circle fitting. +Code Link +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +.. autofunction:: Mapping.circle_fitting.circle_fitting.circle_fitting diff --git a/docs/modules/3_mapping/distance_map/distance_map_main.rst b/docs/modules/3_mapping/distance_map/distance_map_main.rst index 0ef9e3022f..ec60e752c9 100644 --- a/docs/modules/3_mapping/distance_map/distance_map_main.rst +++ b/docs/modules/3_mapping/distance_map/distance_map_main.rst @@ -14,8 +14,8 @@ The algorithm is demonstrated on a simple 2D grid with obstacles: .. image:: distance_map.png -API -~~~ +Code Link +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ .. autofunction:: Mapping.DistanceMap.distance_map.compute_sdf diff --git a/docs/modules/3_mapping/gaussian_grid_map/gaussian_grid_map_main.rst b/docs/modules/3_mapping/gaussian_grid_map/gaussian_grid_map_main.rst index b0f112a871..50033d2a20 100644 --- a/docs/modules/3_mapping/gaussian_grid_map/gaussian_grid_map_main.rst +++ b/docs/modules/3_mapping/gaussian_grid_map/gaussian_grid_map_main.rst @@ -6,3 +6,9 @@ Gaussian grid map This is a 2D Gaussian grid mapping example. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/gaussian_grid_map/animation.gif + +Code Link +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +.. autofunction:: Mapping.gaussian_grid_map.gaussian_grid_map.generate_gaussian_grid_map + diff --git a/docs/modules/3_mapping/k_means_object_clustering/k_means_object_clustering_main.rst b/docs/modules/3_mapping/k_means_object_clustering/k_means_object_clustering_main.rst index e098ca5409..0ece604009 100644 --- a/docs/modules/3_mapping/k_means_object_clustering/k_means_object_clustering_main.rst +++ b/docs/modules/3_mapping/k_means_object_clustering/k_means_object_clustering_main.rst @@ -4,3 +4,9 @@ k-means object clustering This is a 2D object clustering with k-means algorithm. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/kmeans_clustering/animation.gif + +Code Link +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +.. autofunction:: Mapping.kmeans_clustering.kmeans_clustering.kmeans_clustering + diff --git a/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst index 1f62179efd..29f5878e48 100644 --- a/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst +++ b/docs/modules/3_mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst @@ -196,3 +196,9 @@ Let’s use this flood fill on real data: .. image:: lidar_to_grid_map_tutorial_14_1.png +Code Link +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +.. autofunction:: Mapping.lidar_to_grid_map.lidar_to_grid_map.main + + diff --git a/docs/modules/3_mapping/normal_vector_estimation/normal_vector_estimation_main.rst b/docs/modules/3_mapping/normal_vector_estimation/normal_vector_estimation_main.rst index a4d1bf0df2..68a19e1534 100644 --- a/docs/modules/3_mapping/normal_vector_estimation/normal_vector_estimation_main.rst +++ b/docs/modules/3_mapping/normal_vector_estimation/normal_vector_estimation_main.rst @@ -25,8 +25,8 @@ This is an example of normal vector calculation: .. figure:: normal_vector_calc.png -API -===== +Code Link +========== .. autofunction:: Mapping.normal_vector_estimation.normal_vector_estimation.calc_normal_vector @@ -67,8 +67,8 @@ This is an example of RANSAC based normal vector estimation: .. figure:: ransac_normal_vector_estimation.png -API -===== +Code Link +========== .. autofunction:: Mapping.normal_vector_estimation.normal_vector_estimation.ransac_normal_vector_estimation diff --git a/docs/modules/3_mapping/point_cloud_sampling/point_cloud_sampling_main.rst b/docs/modules/3_mapping/point_cloud_sampling/point_cloud_sampling_main.rst index cbb5652f56..8cb08d4b78 100644 --- a/docs/modules/3_mapping/point_cloud_sampling/point_cloud_sampling_main.rst +++ b/docs/modules/3_mapping/point_cloud_sampling/point_cloud_sampling_main.rst @@ -27,8 +27,8 @@ This method determines which each point is in a grid, and replaces the point clouds that are in the same Voxel with their average to reduce the number of points. -API -===== +Code Link +========== .. autofunction:: Mapping.point_cloud_sampling.point_cloud_sampling.voxel_point_sampling @@ -61,8 +61,8 @@ Although this method does not have good performance comparing the Farthest distance sample where each point is distributed farther from each other, this is suitable for real-time processing because of its fast computation time. -API -===== +Code Link +========== .. autofunction:: Mapping.point_cloud_sampling.point_cloud_sampling.poisson_disk_sampling diff --git a/docs/modules/3_mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst b/docs/modules/3_mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst index cc5a1a1c5b..bee2f64193 100644 --- a/docs/modules/3_mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst +++ b/docs/modules/3_mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst @@ -3,4 +3,9 @@ Ray casting grid map This is a 2D ray casting grid mapping example. -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/raycasting_grid_map/animation.gif \ No newline at end of file +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/raycasting_grid_map/animation.gif + +Code Link +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +.. autofunction:: Mapping.ray_casting_grid_map.ray_casting_grid_map.generate_ray_casting_grid_map diff --git a/docs/modules/3_mapping/rectangle_fitting/rectangle_fitting_main.rst b/docs/modules/3_mapping/rectangle_fitting/rectangle_fitting_main.rst index b6ced1dc1d..06d85efe61 100644 --- a/docs/modules/3_mapping/rectangle_fitting/rectangle_fitting_main.rst +++ b/docs/modules/3_mapping/rectangle_fitting/rectangle_fitting_main.rst @@ -57,8 +57,8 @@ This evaluation function uses the squreed distances between the edges of the rec Calculating the squared error is the same as calculating the variance. The smaller this variance, the more it signifies that the points fit within the rectangle. -API -~~~~~~ +Code Link +~~~~~~~~~~~ .. autoclass:: Mapping.rectangle_fitting.rectangle_fitting.LShapeFitting :members: diff --git a/tests/test_raycasting_grid_map.py b/tests/test_ray_casting_grid_map.py similarity index 71% rename from tests/test_raycasting_grid_map.py rename to tests/test_ray_casting_grid_map.py index f08ae9277e..2d192c9310 100644 --- a/tests/test_raycasting_grid_map.py +++ b/tests/test_ray_casting_grid_map.py @@ -1,5 +1,5 @@ import conftest # Add root path to sys.path -from Mapping.raycasting_grid_map import raycasting_grid_map as m +from Mapping.ray_casting_grid_map import ray_casting_grid_map as m def test1(): From e1cdb24ecfd68ff4eaf51626e5a3f4854da588a4 Mon Sep 17 00:00:00 2001 From: Yuri Harada <55676955+NightzDev@users.noreply.github.com> Date: Fri, 2 May 2025 21:51:20 -0300 Subject: [PATCH 889/940] docs: rewrite internal sensors section with detailed descriptions and references (#1197) * docs: rewrite and enhance internal sensors documentation * Update docs/modules/12_appendix/internal_sensors_main.rst --------- Co-authored-by: Atsushi Sakai --- .../12_appendix/internal_sensors_main.rst | 41 +++++++++++++++---- 1 file changed, 34 insertions(+), 7 deletions(-) diff --git a/docs/modules/12_appendix/internal_sensors_main.rst b/docs/modules/12_appendix/internal_sensors_main.rst index 18f209098e..fa2594a2bf 100644 --- a/docs/modules/12_appendix/internal_sensors_main.rst +++ b/docs/modules/12_appendix/internal_sensors_main.rst @@ -3,32 +3,59 @@ Internal Sensors for Robots ============================ -This project, `PythonRobotics`, focuses on algorithms, so hardware is not included. -However, having basic knowledge of hardware in robotics is also important for understanding algorithms. -Therefore, we will provide an overview. +This project, `PythonRobotics`, focuses on algorithms, so hardware is not included. However, having basic knowledge of hardware in robotics is also important for understanding algorithms. Therefore, we will provide an overview. Introduction ------------- +------------- + +In robotic systems, internal sensors play a crucial role in monitoring the robot’s internal state, such as orientation, acceleration, angular velocity, altitude, and temperature. These sensors provide essential feedback that supports control, localization, and safety mechanisms. While external sensors perceive the environment, internal sensors give the robot self-awareness of its own motion and condition. Understanding the principles and characteristics of these sensors is vital to fully utilize their information within algorithms and decision-making systems. This section outlines the main internal sensors used in robotics. Global Navigation Satellite System (GNSS) -------------------------------------------- +----------------------------------------- + +GNSS is a satellite-based navigation system that provides global positioning and time information by analyzing signals from multiple satellites. It is commonly used in outdoor environments for absolute positioning. Although GNSS offers global coverage without infrastructure dependency, its performance is limited indoors or in obstructed areas, and it suffers from low update rates and susceptibility to signal noise. It is widely used in outdoor navigation for drones, vehicles, and delivery robots. Gyroscope ---------- +A gyroscope measures angular velocity around the robot’s axes, enabling orientation and attitude estimation through detection of the Coriolis effect. Gyroscopes are compact, cost-effective, and provide high update rates, but they are prone to drift and require calibration or sensor fusion for long-term accuracy. These sensors are essential in drones, balancing robots, and IMU-based systems for motion tracking. + Accelerometer --------------- +--------------- + +An accelerometer measures linear acceleration along one or more axes, typically by detecting mass displacement due to motion. It is small, affordable, and useful for detecting movement, tilt, or vibration. However, accelerometers are limited by noisy output and cannot independently determine position without integration and fusion. They are commonly applied in wearable robotics, step counters, and vibration sensing. Magnetometer -------------- +A magnetometer measures the direction and intensity of magnetic fields, enabling heading estimation based on Earth’s magnetic field. It is lightweight and useful for orientation, especially in GPS-denied environments, though it is sensitive to interference from electronics and requires calibration. Magnetometers are often used in conjunction with IMUs for navigation and directional awareness. + Inertial Measurement Unit (IMU) -------------------------------- +An IMU integrates a gyroscope, accelerometer, and sometimes a magnetometer to estimate a robot's motion and orientation through sensor fusion techniques such as Kalman filters. IMUs are compact and provide high-frequency data, which is essential for localization and navigation in GPS-denied areas. Nonetheless, they accumulate drift over time and require complex filtering to maintain accuracy. IMUs are found in drones, mobile robots, and motion tracking systems. + Pressure Sensor ------------------ +---------------- + +Pressure sensors detect atmospheric or fluid pressure by measuring the force exerted on a diaphragm. They are effective for estimating altitude and monitoring environmental conditions, especially in drones and underwater robots. Although cost-effective and efficient, their accuracy may degrade due to temperature variation and limitations in low-altitude resolution. Temperature Sensor -------------------- +Temperature sensors monitor environmental or internal component temperatures, using changes in resistance or voltage depending on sensor type (e.g., RTD or thermocouple). They are simple and reliable for safety and thermal regulation, though they may respond slowly and be affected by nearby electronics. Common applications include battery and motor monitoring, safety systems, and ambient sensing. + +References +---------- +- *Introduction to Autonomous Mobile Robots*, Roland Siegwart, Illah Nourbakhsh, Davide Scaramuzza +- *Probabilistic Robotics*, Sebastian Thrun, Wolfram Burgard, Dieter Fox +- Wikipedia articles: + + - `Inertial Measurement Unit (IMU) `_ + - `Accelerometer `_ + - `Gyroscope `_ + - `Magnetometer `_ + - `Pressure sensor `_ + - `Temperature sensor `_ +- `Adafruit Sensor Guides `_ \ No newline at end of file From d2fe5ae8f0e414f394c00570771c07807d167e68 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 4 May 2025 09:50:49 +0900 Subject: [PATCH 890/940] Add code links to SLAM module documentation (#1212) This commit updates SLAM module documentation files to include direct code links for better navigation. It also adjusts imports in `test_iterative_closest_point.py` to reflect updated module structure and adds a safety check for the directory in `runtests.sh`. --- .../icp_matching.py} | 0 docs/modules/4_slam/FastSLAM1/FastSLAM1_main.rst | 5 +++++ docs/modules/4_slam/FastSLAM2/FastSLAM2_main.rst | 6 ++++++ docs/modules/4_slam/ekf_slam/ekf_slam_main.rst | 6 ++++++ docs/modules/4_slam/graph_slam/graph_slam_main.rst | 6 ++++++ .../iterative_closest_point_matching_main.rst | 8 +++++++- runtests.sh | 1 + tests/test_iterative_closest_point.py | 2 +- 8 files changed, 32 insertions(+), 2 deletions(-) rename SLAM/{iterative_closest_point/iterative_closest_point.py => ICPMatching/icp_matching.py} (100%) diff --git a/SLAM/iterative_closest_point/iterative_closest_point.py b/SLAM/ICPMatching/icp_matching.py similarity index 100% rename from SLAM/iterative_closest_point/iterative_closest_point.py rename to SLAM/ICPMatching/icp_matching.py diff --git a/docs/modules/4_slam/FastSLAM1/FastSLAM1_main.rst b/docs/modules/4_slam/FastSLAM1/FastSLAM1_main.rst index a2aa521216..b6bafa0982 100644 --- a/docs/modules/4_slam/FastSLAM1/FastSLAM1_main.rst +++ b/docs/modules/4_slam/FastSLAM1/FastSLAM1_main.rst @@ -22,6 +22,11 @@ The red points are particles of FastSLAM. Black points are landmarks, blue crosses are estimated landmark positions by FastSLAM. +Code Link +~~~~~~~~~~~~ + +.. autofunction:: SLAM.FastSLAM1.fast_slam1.fast_slam1 + Introduction ~~~~~~~~~~~~ diff --git a/docs/modules/4_slam/FastSLAM2/FastSLAM2_main.rst b/docs/modules/4_slam/FastSLAM2/FastSLAM2_main.rst index 9e79b496a3..59ed3b9f75 100644 --- a/docs/modules/4_slam/FastSLAM2/FastSLAM2_main.rst +++ b/docs/modules/4_slam/FastSLAM2/FastSLAM2_main.rst @@ -7,6 +7,12 @@ The animation has the same meanings as one of FastSLAM 1.0. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/FastSLAM2/animation.gif +Code Link +~~~~~~~~~~~ + +.. autofunction:: SLAM.FastSLAM2.fast_slam2.fast_slam2 + + References ~~~~~~~~~~ diff --git a/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst b/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst index a1486ffe1e..3967a7ae4d 100644 --- a/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst +++ b/docs/modules/4_slam/ekf_slam/ekf_slam_main.rst @@ -21,6 +21,12 @@ This is a simulation of EKF SLAM. - Blue line: ground truth - Red line: EKF SLAM position estimation +Code Link +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +.. autofunction:: SLAM.EKFSLAM.ekf_slam.ekf_slam + + Introduction ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ diff --git a/docs/modules/4_slam/graph_slam/graph_slam_main.rst b/docs/modules/4_slam/graph_slam/graph_slam_main.rst index a2ef513527..2ef17e4179 100644 --- a/docs/modules/4_slam/graph_slam/graph_slam_main.rst +++ b/docs/modules/4_slam/graph_slam/graph_slam_main.rst @@ -13,6 +13,12 @@ The black stars are landmarks for graph edge generation. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/GraphBasedSLAM/animation.gif +Code Link +~~~~~~~~~~~~ + +.. autofunction:: SLAM.GraphBasedSLAM.graph_based_slam.graph_based_slam + + .. include:: graphSLAM_doc.rst .. include:: graphSLAM_formulation.rst .. include:: graphSLAM_SE2_example.rst diff --git a/docs/modules/4_slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst b/docs/modules/4_slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst index a30b1fc99b..772fe62889 100644 --- a/docs/modules/4_slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst +++ b/docs/modules/4_slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst @@ -10,7 +10,13 @@ points to points. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/iterative_closest_point/animation.gif +Code Link +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +.. autofunction:: SLAM.ICPMatching.icp_matching.icp_matching + + References -~~~~~~~~~~ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - `Introduction to Mobile Robotics: Iterative Closest Point Algorithm `_ diff --git a/runtests.sh b/runtests.sh index 12d1b80453..c4460c8aa7 100755 --- a/runtests.sh +++ b/runtests.sh @@ -1,4 +1,5 @@ #!/usr/bin/env bash +cd "$(dirname "$0")" || exit 1 echo "Run test suites! " # === pytest based test runner === diff --git a/tests/test_iterative_closest_point.py b/tests/test_iterative_closest_point.py index 3e726b5649..cdfa89cc55 100644 --- a/tests/test_iterative_closest_point.py +++ b/tests/test_iterative_closest_point.py @@ -1,5 +1,5 @@ import conftest -from SLAM.iterative_closest_point import iterative_closest_point as m +from SLAM.ICPMatching import icp_matching as m def test_1(): From a38da41bafaf82bb56d4491d94a0095c1019ac4a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 4 May 2025 20:32:11 +0900 Subject: [PATCH 891/940] Add code links to documentation and fix naming inconsistencies (#1213) Added references to related Python functions in documentation for better navigation and usability. Corrected inconsistencies in module and test names to align with their respective directories and improve clarity. --- .../rear_wheel_feedback_control.py} | 0 .../stanley_control.py} | 0 .../10_inverted_pendulum/inverted_pendulum_main.rst | 12 ++++++++++++ .../behavior_tree/behavior_tree_main.rst | 2 +- .../state_machine/state_machine_main.rst | 4 ++-- .../cgmres_nmpc/cgmres_nmpc_main.rst | 5 +++++ .../lqr_speed_and_steering_control_main.rst | 7 ++++++- .../lqr_steering_control_main.rst | 6 +++++- ...l_predictive_speed_and_steering_control_main.rst | 13 ++++++------- .../move_to_a_pose_main.rst} | 8 +++++++- docs/modules/6_path_tracking/path_tracking_main.rst | 2 +- .../pure_pursuit_tracking_main.rst | 6 ++++++ .../rear_wheel_feedback_control_main.rst | 6 ++++++ .../stanley_control/stanley_control_main.rst | 6 ++++++ .../n_joint_arm_to_point_control_main.rst | 7 +++++++ .../obstacle_avoidance_arm_navigation_main.rst | 7 ++++++- .../7_arm_navigation/planar_two_link_ik_main.rst | 6 ++++++ .../drone_3d_trajectory_following_main.rst | 5 +++++ .../rocket_powered_landing_main.rst | 8 ++++++++ .../bipedal_planner/bipedal_planner_main.rst | 5 +++++ tests/test_rear_wheel_feedback.py | 2 +- tests/test_stanley_controller.py | 2 +- 22 files changed, 102 insertions(+), 17 deletions(-) rename PathTracking/{rear_wheel_feedback/rear_wheel_feedback.py => rear_wheel_feedback_control/rear_wheel_feedback_control.py} (100%) rename PathTracking/{stanley_controller/stanley_controller.py => stanley_control/stanley_control.py} (100%) rename docs/modules/6_path_tracking/{move_to_a_pose_control/move_to_a_pose_control_main.rst => move_to_a_pose/move_to_a_pose_main.rst} (97%) diff --git a/PathTracking/rear_wheel_feedback/rear_wheel_feedback.py b/PathTracking/rear_wheel_feedback_control/rear_wheel_feedback_control.py similarity index 100% rename from PathTracking/rear_wheel_feedback/rear_wheel_feedback.py rename to PathTracking/rear_wheel_feedback_control/rear_wheel_feedback_control.py diff --git a/PathTracking/stanley_controller/stanley_controller.py b/PathTracking/stanley_control/stanley_control.py similarity index 100% rename from PathTracking/stanley_controller/stanley_controller.py rename to PathTracking/stanley_control/stanley_control.py diff --git a/docs/modules/10_inverted_pendulum/inverted_pendulum_main.rst b/docs/modules/10_inverted_pendulum/inverted_pendulum_main.rst index 048cbea9ac..58dc0f2e57 100644 --- a/docs/modules/10_inverted_pendulum/inverted_pendulum_main.rst +++ b/docs/modules/10_inverted_pendulum/inverted_pendulum_main.rst @@ -89,6 +89,12 @@ and :math:`P` is the unique positive definite solution to the discrete time .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation_lqr.gif +Code Link +^^^^^^^^^^^ + +.. autofunction:: InvertedPendulum.inverted_pendulum_lqr_control.main + + MPC control ~~~~~~~~~~~~~~~~~~~~~~~~~~~ The MPC controller minimize this cost function defined as: @@ -101,3 +107,9 @@ subject to: - Initial state .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation.gif + +Code Link +^^^^^^^^^^^ + +.. autofunction:: InvertedPendulum.inverted_pendulum_mpc_control.main + diff --git a/docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst b/docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst index ae3e16da81..22849f7c54 100644 --- a/docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst +++ b/docs/modules/13_mission_planning/behavior_tree/behavior_tree_main.rst @@ -5,7 +5,7 @@ Behavior Tree is a modular, hierarchical decision model that is widely used in r It present some similarities to hierarchical state machines with the key difference that the main building block of a behavior is a task rather than a state. Behavior Tree have been shown to generalize several other control architectures (https://ieeexplore.ieee.org/document/7790863) -Core Concepts +Code Link ~~~~~~~~~~~~~ Control Node diff --git a/docs/modules/13_mission_planning/state_machine/state_machine_main.rst b/docs/modules/13_mission_planning/state_machine/state_machine_main.rst index abaece1b11..3f516d46a9 100644 --- a/docs/modules/13_mission_planning/state_machine/state_machine_main.rst +++ b/docs/modules/13_mission_planning/state_machine/state_machine_main.rst @@ -12,8 +12,8 @@ Core Concepts - **Action**: An operation executed during transition (before entering new state) - **Guard**: A precondition that must be satisfied to allow transition -API -~~~ +Code Link +~~~~~~~~~~~ .. autoclass:: MissionPlanning.StateMachine.state_machine.StateMachine :members: add_transition, process, register_state diff --git a/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst index 23f1218a94..914a4555ff 100644 --- a/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst +++ b/docs/modules/6_path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst @@ -17,6 +17,11 @@ Nonlinear Model Predictive Control with C-GMRES .. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/cgmres_nmpc/animation.gif :alt: gif +Code Link +~~~~~~~~~~~~ + +.. autofunction:: PathTracking.cgmres_nmpc.cgmres_nmpc.NMPCControllerCGMRES + Mathematical Formulation ~~~~~~~~~~~~~~~~~~~~~~~~ diff --git a/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst index 568ef9a0df..b0ba9e0d45 100644 --- a/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst +++ b/docs/modules/6_path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst @@ -7,7 +7,12 @@ Path tracking simulation with LQR speed and steering control. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_speed_steer_control/animation.gif -`[Code Link] `_ + +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathTracking.lqr_speed_steer_control.lqr_speed_steer_control.lqr_speed_steering_control + Overview ~~~~~~~~ diff --git a/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst b/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst index 831423f364..fc8f2a33aa 100644 --- a/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst +++ b/docs/modules/6_path_tracking/lqr_steering_control/lqr_steering_control_main.rst @@ -8,7 +8,11 @@ control. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/lqr_steer_control/animation.gif -`[Code Link] `_ +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathTracking.lqr_steer_control.lqr_steer_control.lqr_steering_control + Overview ~~~~~~~~ diff --git a/docs/modules/6_path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst b/docs/modules/6_path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst index de55b545ba..76a6819a46 100644 --- a/docs/modules/6_path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst +++ b/docs/modules/6_path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst @@ -5,13 +5,6 @@ Model predictive speed and steering control .. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/model_predictive_speed_and_steer_control/animation.gif?raw=true :alt: Model predictive speed and steering control - Model predictive speed and steering control - -code: - -`PythonRobotics/model_predictive_speed_and_steer_control.py at master · -AtsushiSakai/PythonRobotics `__ - This is a path tracking simulation using model predictive control (MPC). The MPC controller controls vehicle speed and steering base on @@ -22,6 +15,12 @@ This code uses cvxpy as an optimization modeling tool. - `Welcome to CVXPY 1.0 — CVXPY 1.0.6 documentation `__ +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathTracking.model_predictive_speed_and_steer_control.model_predictive_speed_and_steer_control.iterative_linear_mpc_control + + MPC modeling ~~~~~~~~~~~~ diff --git a/docs/modules/6_path_tracking/move_to_a_pose_control/move_to_a_pose_control_main.rst b/docs/modules/6_path_tracking/move_to_a_pose/move_to_a_pose_main.rst similarity index 97% rename from docs/modules/6_path_tracking/move_to_a_pose_control/move_to_a_pose_control_main.rst rename to docs/modules/6_path_tracking/move_to_a_pose/move_to_a_pose_main.rst index 77ec682a30..19bb0e4c14 100644 --- a/docs/modules/6_path_tracking/move_to_a_pose_control/move_to_a_pose_control_main.rst +++ b/docs/modules/6_path_tracking/move_to_a_pose/move_to_a_pose_main.rst @@ -3,7 +3,13 @@ Move to a Pose Control In this section, we present the logic of PathFinderController that drives a car from a start pose (x, y, theta) to a goal pose. A simulation of moving to a pose control is presented below. -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/move_to_pose/animation.gif +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/move_to_pose/animation.gif + +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathTracking.move_to_pose.move_to_pose.move_to_pose + Position Control of non-Holonomic Systems ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ diff --git a/docs/modules/6_path_tracking/path_tracking_main.rst b/docs/modules/6_path_tracking/path_tracking_main.rst index d98e324583..742cc807e6 100644 --- a/docs/modules/6_path_tracking/path_tracking_main.rst +++ b/docs/modules/6_path_tracking/path_tracking_main.rst @@ -16,4 +16,4 @@ Path tracking is the ability of a robot to follow the reference path generated b lqr_speed_and_steering_control/lqr_speed_and_steering_control model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control cgmres_nmpc/cgmres_nmpc - move_to_a_pose_control/move_to_a_pose_control + move_to_a_pose/move_to_a_pose diff --git a/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst b/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst index d7354cf8fb..ff6749bbbe 100644 --- a/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst +++ b/docs/modules/6_path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst @@ -9,6 +9,12 @@ speed control. The red line is a target course, the green cross means the target point for pure pursuit control, the blue line is the tracking. +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathTracking.pure_pursuit.pure_pursuit.pure_pursuit_steer_control + + Reference ~~~~~~~~~~~ diff --git a/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst b/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst index d18cd6fbf7..56d0db63ad 100644 --- a/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst +++ b/docs/modules/6_path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst @@ -6,6 +6,12 @@ PID speed control. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/rear_wheel_feedback/animation.gif +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathTracking.rear_wheel_feedback_control.rear_wheel_feedback_control.rear_wheel_feedback_control + + Reference ~~~~~~~~~~~ - `A Survey of Motion Planning and Control Techniques for Self-driving diff --git a/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst b/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst index 69089ac33b..3c491804f6 100644 --- a/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst +++ b/docs/modules/6_path_tracking/stanley_control/stanley_control_main.rst @@ -6,6 +6,12 @@ control. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/stanley_controller/animation.gif +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathTracking.stanley_control.stanley_control.stanley_control + + Reference ~~~~~~~~~~~ diff --git a/docs/modules/7_arm_navigation/n_joint_arm_to_point_control_main.rst b/docs/modules/7_arm_navigation/n_joint_arm_to_point_control_main.rst index cc6279f681..56900acde1 100644 --- a/docs/modules/7_arm_navigation/n_joint_arm_to_point_control_main.rst +++ b/docs/modules/7_arm_navigation/n_joint_arm_to_point_control_main.rst @@ -11,3 +11,10 @@ plotting area. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/n_joint_arm_to_point_control/animation.gif In this simulation N = 10, however, you can change it. + + +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: ArmNavigation.n_joint_arm_to_point_control.n_joint_arm_to_point_control.main + diff --git a/docs/modules/7_arm_navigation/obstacle_avoidance_arm_navigation_main.rst b/docs/modules/7_arm_navigation/obstacle_avoidance_arm_navigation_main.rst index 899a64a5cd..4433ab531b 100644 --- a/docs/modules/7_arm_navigation/obstacle_avoidance_arm_navigation_main.rst +++ b/docs/modules/7_arm_navigation/obstacle_avoidance_arm_navigation_main.rst @@ -3,4 +3,9 @@ Arm navigation with obstacle avoidance Arm navigation with obstacle avoidance simulation. -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/arm_obstacle_navigation/animation.gif \ No newline at end of file +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/arm_obstacle_navigation/animation.gif + +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: ArmNavigation.arm_obstacle_navigation.arm_obstacle_navigation.main diff --git a/docs/modules/7_arm_navigation/planar_two_link_ik_main.rst b/docs/modules/7_arm_navigation/planar_two_link_ik_main.rst index 2da2b0dc30..5b2712eb48 100644 --- a/docs/modules/7_arm_navigation/planar_two_link_ik_main.rst +++ b/docs/modules/7_arm_navigation/planar_two_link_ik_main.rst @@ -11,6 +11,12 @@ This is a interactive simulation. You can set the goal position of the end effector with left-click on the plotting area. +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: ArmNavigation.two_joint_arm_to_point_control.two_joint_arm_to_point_control.main + + Inverse Kinematics for a Planar Two-Link Robotic Arm ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ diff --git a/docs/modules/8_aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst b/docs/modules/8_aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst index c3bdc33cdc..1805bb3f6d 100644 --- a/docs/modules/8_aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst +++ b/docs/modules/8_aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst @@ -4,3 +4,8 @@ Drone 3d trajectory following This is a 3d trajectory following simulation for a quadrotor. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/drone_3d_trajectory_following/animation.gif + +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: AerialNavigation.drone_3d_trajectory_following.drone_3d_trajectory_following.quad_sim diff --git a/docs/modules/8_aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst b/docs/modules/8_aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst index 6c90d2b44e..4bf5117500 100644 --- a/docs/modules/8_aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst +++ b/docs/modules/8_aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst @@ -1,6 +1,14 @@ Rocket powered landing ----------------------------- +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/AerialNavigation/rocket_powered_landing/animation.gif + +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: AerialNavigation.rocket_powered_landing.rocket_powered_landing.main + + Simulation ~~~~~~~~~~ diff --git a/docs/modules/9_bipedal/bipedal_planner/bipedal_planner_main.rst b/docs/modules/9_bipedal/bipedal_planner/bipedal_planner_main.rst index 2ee5971e7a..6253715cc1 100644 --- a/docs/modules/9_bipedal/bipedal_planner/bipedal_planner_main.rst +++ b/docs/modules/9_bipedal/bipedal_planner/bipedal_planner_main.rst @@ -4,3 +4,8 @@ Bipedal Planner Bipedal Walking with modifying designated footsteps .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Bipedal/bipedal_planner/animation.gif + +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: Bipedal.bipedal_planner.bipedal_planner.BipedalPlanner diff --git a/tests/test_rear_wheel_feedback.py b/tests/test_rear_wheel_feedback.py index 895eb188b3..eccde52358 100644 --- a/tests/test_rear_wheel_feedback.py +++ b/tests/test_rear_wheel_feedback.py @@ -1,5 +1,5 @@ import conftest # Add root path to sys.path -from PathTracking.rear_wheel_feedback import rear_wheel_feedback as m +from PathTracking.rear_wheel_feedback_control import rear_wheel_feedback_control as m def test1(): diff --git a/tests/test_stanley_controller.py b/tests/test_stanley_controller.py index a1d8073764..bd590cb51a 100644 --- a/tests/test_stanley_controller.py +++ b/tests/test_stanley_controller.py @@ -1,5 +1,5 @@ import conftest # Add root path to sys.path -from PathTracking.stanley_controller import stanley_controller as m +from PathTracking.stanley_control import stanley_control as m def test1(): From 73e1c0bebccf4f4fc67ae59ada53b783a8533096 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 5 May 2025 17:29:45 +0900 Subject: [PATCH 892/940] Add "Code Link" sections and rename classes for consistency (#1214) This commit adds "Code Link" sections to documentation across various path planning modules, linking to relevant class and function APIs. Additionally, several class renaming changes were made, such as `Dijkstra` to `DijkstraPlanner` and `eta3_trajectory` to `Eta3SplineTrajectory`, to enhance naming consistency. Minor fixes include file restructuring and image renaming for the RRT module. --- ..._rrtstar.py => batch_informed_rrt_star.py} | 0 PathPlanning/Dijkstra/dijkstra.py | 4 +- .../eta3_spline_trajectory.py | 14 ++--- .../bezier_path/bezier_path_main.rst | 9 ++- .../bspline_path/bspline_path_main.rst | 8 +-- .../bugplanner/bugplanner_main.rst | 8 +++ .../catmull_rom_spline_main.rst | 4 +- .../clothoid_path/clothoid_path_main.rst | 5 ++ .../coverage_path/coverage_path_main.rst | 21 +++++++ .../cubic_spline/cubic_spline_main.rst | 8 +-- .../dubins_path/dubins_path_main.rst | 2 +- .../dynamic_window_approach_main.rst | 12 +++- .../elastic_bands/elastic_bands_main.rst | 7 ++- .../eta3_spline/eta3_spline_main.rst | 7 +++ .../frenet_frame_path_main.rst | 6 ++ .../grid_base_search_main.rst | 50 ++++++++++++++++ .../hybridastar/hybridastar_main.rst | 5 ++ .../lqr_path/lqr_path_main.rst | 5 ++ ...l_predictive_trajectory_generator_main.rst | 7 +++ .../prm_planner/prm_planner_main.rst | 7 +++ .../quintic_polynomials_planner_main.rst | 5 ++ .../reeds_shepp_path_main.rst | 7 +++ .../closed_loop_rrt_star_car/Figure_1.png | Bin .../closed_loop_rrt_star_car/Figure_3.png | Bin .../closed_loop_rrt_star_car/Figure_4.png | Bin .../closed_loop_rrt_star_car/Figure_5.png | Bin docs/modules/5_path_planning/rrt/rrt_main.rst | 54 ++++++++++++++++++ docs/modules/5_path_planning/rrt/rrt_star.rst | 6 ++ .../state_lattice_planner_main.rst | 17 ++++++ .../time_based_grid_search_main.rst | 9 +++ .../visibility_road_map_planner_main.rst | 7 ++- .../vrm_planner/vrm_planner_main.rst | 6 ++ tests/test_batch_informed_rrt_star.py | 2 +- 33 files changed, 277 insertions(+), 25 deletions(-) rename PathPlanning/BatchInformedRRTStar/{batch_informed_rrtstar.py => batch_informed_rrt_star.py} (100%) rename docs/modules/5_path_planning/{ => rrt}/closed_loop_rrt_star_car/Figure_1.png (100%) rename docs/modules/5_path_planning/{ => rrt}/closed_loop_rrt_star_car/Figure_3.png (100%) rename docs/modules/5_path_planning/{ => rrt}/closed_loop_rrt_star_car/Figure_4.png (100%) rename docs/modules/5_path_planning/{ => rrt}/closed_loop_rrt_star_car/Figure_5.png (100%) diff --git a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py b/PathPlanning/BatchInformedRRTStar/batch_informed_rrt_star.py similarity index 100% rename from PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py rename to PathPlanning/BatchInformedRRTStar/batch_informed_rrt_star.py diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index 8a585e4b18..f5a4703910 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -12,7 +12,7 @@ show_animation = True -class Dijkstra: +class DijkstraPlanner: def __init__(self, ox, oy, resolution, robot_radius): """ @@ -246,7 +246,7 @@ def main(): plt.grid(True) plt.axis("equal") - dijkstra = Dijkstra(ox, oy, grid_size, robot_radius) + dijkstra = DijkstraPlanner(ox, oy, grid_size, robot_radius) rx, ry = dijkstra.planning(sx, sy, gx, gy) if show_animation: # pragma: no cover diff --git a/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py b/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py index a73797dacb..e72d33261e 100644 --- a/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py +++ b/PathPlanning/Eta3SplineTrajectory/eta3_spline_trajectory.py @@ -29,7 +29,7 @@ def __init__(self, actual_vel, max_vel): self.message = f'Actual velocity {actual_vel} does not equal desired max velocity {max_vel}!' -class eta3_trajectory(Eta3Path): +class Eta3SplineTrajectory(Eta3Path): """ eta3_trajectory @@ -300,8 +300,8 @@ def test1(max_vel=0.5): trajectory_segments.append(Eta3PathSegment( start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa)) - traj = eta3_trajectory(trajectory_segments, - max_vel=max_vel, max_accel=0.5) + traj = Eta3SplineTrajectory(trajectory_segments, + max_vel=max_vel, max_accel=0.5) # interpolate at several points along the path times = np.linspace(0, traj.total_time, 101) @@ -334,8 +334,8 @@ def test2(max_vel=0.5): trajectory_segments.append(Eta3PathSegment( start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa)) - traj = eta3_trajectory(trajectory_segments, - max_vel=max_vel, max_accel=0.5) + traj = Eta3SplineTrajectory(trajectory_segments, + max_vel=max_vel, max_accel=0.5) # interpolate at several points along the path times = np.linspace(0, traj.total_time, 101) @@ -400,8 +400,8 @@ def test3(max_vel=2.0): start_pose=start_pose, end_pose=end_pose, eta=eta, kappa=kappa)) # construct the whole path - traj = eta3_trajectory(trajectory_segments, - max_vel=max_vel, max_accel=0.5, max_jerk=1) + traj = Eta3SplineTrajectory(trajectory_segments, + max_vel=max_vel, max_accel=0.5, max_jerk=1) # interpolate at several points along the path times = np.linspace(0, traj.total_time, 1001) diff --git a/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst b/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst index 9d9b3de709..19fb89a1b1 100644 --- a/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst +++ b/docs/modules/5_path_planning/bezier_path/bezier_path_main.rst @@ -13,8 +13,15 @@ You can get different Beizer course: .. image:: Figure_2.png +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathPlanning.BezierPath.bezier_path.calc_4points_bezier_path + + Reference +~~~~~~~~~~~~~~~ - `Continuous Curvature Path Generation Based on Bezier Curves for Autonomous - Vehicles ` + Vehicles `__ diff --git a/docs/modules/5_path_planning/bspline_path/bspline_path_main.rst b/docs/modules/5_path_planning/bspline_path/bspline_path_main.rst index e734352e34..00e5ef2fdb 100644 --- a/docs/modules/5_path_planning/bspline_path/bspline_path_main.rst +++ b/docs/modules/5_path_planning/bspline_path/bspline_path_main.rst @@ -105,8 +105,8 @@ The default spline degree is 3, so curvature changes smoothly. .. image:: interp_and_curvature.png -API -++++ +Code link +++++++++++ .. autofunction:: PathPlanning.BSplinePath.bspline_path.interpolate_b_spline_path @@ -133,8 +133,8 @@ The default spline degree is 3, so curvature changes smoothly. .. image:: approx_and_curvature.png -API -++++ +Code Link +++++++++++ .. autofunction:: PathPlanning.BSplinePath.bspline_path.approximate_b_spline_path diff --git a/docs/modules/5_path_planning/bugplanner/bugplanner_main.rst b/docs/modules/5_path_planning/bugplanner/bugplanner_main.rst index 81c91c0313..e1cd2fe353 100644 --- a/docs/modules/5_path_planning/bugplanner/bugplanner_main.rst +++ b/docs/modules/5_path_planning/bugplanner/bugplanner_main.rst @@ -5,4 +5,12 @@ This is a 2D planning with Bug algorithm. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/BugPlanner/animation.gif +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathPlanning.BugPlanning.bug.main + +Reference +~~~~~~~~~~~~ + - `ECE452 Bug Algorithms `_ diff --git a/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_spline_main.rst b/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_spline_main.rst index 72e558c486..fa2a2ff72b 100644 --- a/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_spline_main.rst +++ b/docs/modules/5_path_planning/catmull_rom_spline/catmull_rom_spline_main.rst @@ -88,8 +88,8 @@ Catmull-Rom Spline API This section provides an overview of the functions used for Catmull-Rom spline path planning. -API -++++ +Code Link +++++++++++ .. autofunction:: PathPlanning.Catmull_RomSplinePath.catmull_rom_spline_path.catmull_rom_point diff --git a/docs/modules/5_path_planning/clothoid_path/clothoid_path_main.rst b/docs/modules/5_path_planning/clothoid_path/clothoid_path_main.rst index 1e8cee694a..16d0ec03c1 100644 --- a/docs/modules/5_path_planning/clothoid_path/clothoid_path_main.rst +++ b/docs/modules/5_path_planning/clothoid_path/clothoid_path_main.rst @@ -73,6 +73,11 @@ The final clothoid path can be calculated with the path parameters and Fresnel i &y(s)=y_{0}+\int_{0}^{s} \sin \left(\frac{1}{2} \kappa^{\prime} \tau^{2}+\kappa \tau+\vartheta_{0}\right) \mathrm{d} \tau \end{aligned} +Code Link +~~~~~~~~~~~~~ + +.. autofunction:: PathPlanning.ClothoidPath.clothoid_path_planner.generate_clothoid_path + References ~~~~~~~~~~ diff --git a/docs/modules/5_path_planning/coverage_path/coverage_path_main.rst b/docs/modules/5_path_planning/coverage_path/coverage_path_main.rst index 0a688b5ed2..eaa876c80b 100644 --- a/docs/modules/5_path_planning/coverage_path/coverage_path_main.rst +++ b/docs/modules/5_path_planning/coverage_path/coverage_path_main.rst @@ -8,6 +8,11 @@ This is a 2D grid based sweep coverage path planner simulation: .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/GridBasedSweepCPP/animation.gif +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.GridBasedSweepCPP.grid_based_sweep_coverage_path_planner.planning + Spiral Spanning Tree ~~~~~~~~~~~~~~~~~~~~ @@ -17,6 +22,14 @@ This is a 2D grid based spiral spanning tree coverage path planner simulation: .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/SpiralSpanningTreeCPP/animation2.gif .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/SpiralSpanningTreeCPP/animation3.gif +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.SpiralSpanningTreeCPP.spiral_spanning_tree_coverage_path_planner.main + +Reference ++++++++++++++ + - `Spiral-STC: An On-Line Coverage Algorithm of Grid Environments by a Mobile Robot `_ @@ -29,6 +42,14 @@ This is a 2D grid based wavefront coverage path planner simulation: .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation2.gif .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/WavefrontCPP/animation3.gif +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.WavefrontCPP.wavefront_coverage_path_planner.wavefront + +Reference ++++++++++++++ + - `Planning paths of complete coverage of an unstructured environment by a mobile robot `_ diff --git a/docs/modules/5_path_planning/cubic_spline/cubic_spline_main.rst b/docs/modules/5_path_planning/cubic_spline/cubic_spline_main.rst index 33471f7c85..a110217a2e 100644 --- a/docs/modules/5_path_planning/cubic_spline/cubic_spline_main.rst +++ b/docs/modules/5_path_planning/cubic_spline/cubic_spline_main.rst @@ -171,8 +171,8 @@ the second derivative by: These equations can be calculated by differentiating the cubic polynomial. -API -=== +Code Link +========== This is the 1D cubic spline class API: @@ -199,8 +199,8 @@ Curvature of each point can be also calculated analytically by: :math:`\kappa=\frac{y^{\prime \prime} x^{\prime}-x^{\prime \prime} y^{\prime}}{\left(x^{\prime2}+y^{\prime2}\right)^{\frac{2}{3}}}` -API -=== +Code Link +========== .. autoclass:: PathPlanning.CubicSpline.cubic_spline_planner.CubicSpline2D :members: diff --git a/docs/modules/5_path_planning/dubins_path/dubins_path_main.rst b/docs/modules/5_path_planning/dubins_path/dubins_path_main.rst index 12172fb51e..5a3d14464b 100644 --- a/docs/modules/5_path_planning/dubins_path/dubins_path_main.rst +++ b/docs/modules/5_path_planning/dubins_path/dubins_path_main.rst @@ -62,7 +62,7 @@ You can generate a path from these information and the maximum curvature informa A path type which has minimum course length among 6 types is selected, and then a path is constructed based on the selected type and its distances. -API +Code Link ~~~~~~~~~~~~~~~~~~~~ .. autofunction:: PathPlanning.DubinsPath.dubins_path_planner.plan_dubins_path diff --git a/docs/modules/5_path_planning/dynamic_window_approach/dynamic_window_approach_main.rst b/docs/modules/5_path_planning/dynamic_window_approach/dynamic_window_approach_main.rst index d645838597..ac5322df94 100644 --- a/docs/modules/5_path_planning/dynamic_window_approach/dynamic_window_approach_main.rst +++ b/docs/modules/5_path_planning/dynamic_window_approach/dynamic_window_approach_main.rst @@ -5,7 +5,17 @@ Dynamic Window Approach This is a 2D navigation sample code with Dynamic Window Approach. +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DynamicWindowApproach/animation.gif + +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.DynamicWindowApproach.dynamic_window_approach.dwa_control + + +Reference +~~~~~~~~~~~~ + - `The Dynamic Window Approach to Collision Avoidance `__ -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DynamicWindowApproach/animation.gif diff --git a/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst b/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst index 8a3e517105..d0109d4ec3 100644 --- a/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst +++ b/docs/modules/5_path_planning/elastic_bands/elastic_bands_main.rst @@ -5,6 +5,11 @@ This is a path planning with Elastic Bands. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ElasticBands/animation.gif +Code Link ++++++++++++++ + +.. autoclass:: PathPlanning.ElasticBands.elastic_bands.ElasticBands + Core Concept ~~~~~~~~~~~~ @@ -69,6 +74,6 @@ Dynamic Path Maintenance - Remove redundant nodes if adjacent nodes are too close References -~~~~~~~~~~~~~~~~~~~~~~~ ++++++++++++++ - `Elastic Bands: Connecting Path Planning and Control `__ diff --git a/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst b/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst index 82e0a71044..9ee343e8a7 100644 --- a/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst +++ b/docs/modules/5_path_planning/eta3_spline/eta3_spline_main.rst @@ -7,7 +7,14 @@ Eta^3 Spline path planning This is a path planning with Eta^3 spline. +Code Link +~~~~~~~~~~~~~~~ + +.. autoclass:: PathPlanning.Eta3SplineTrajectory.eta3_spline_trajectory.Eta3SplineTrajectory + + Reference +~~~~~~~~~~~~~~~ - `\\eta^3-Splines for the Smooth Path Generation of Wheeled Mobile Robots `__ diff --git a/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst b/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst index 371d536e3f..0f84d381ea 100644 --- a/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst +++ b/docs/modules/5_path_planning/frenet_frame_path/frenet_frame_path_main.rst @@ -7,6 +7,12 @@ The cyan line is the target course and black crosses are obstacles. The red line is predicted path. +Code Link +~~~~~~~~~~~~~~ + +.. autofunction:: PathPlanning.FrenetOptimalTrajectory.frenet_optimal_trajectory.main + + High Speed and Velocity Keeping Scenario ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ diff --git a/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst b/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst index bf82c9f391..c4aa6882aa 100644 --- a/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst +++ b/docs/modules/5_path_planning/grid_base_search/grid_base_search_main.rst @@ -10,6 +10,12 @@ This is a 2D grid based path planning with Breadth first search algorithm. In the animation, cyan points are searched nodes. +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.BreadthFirstSearch.breadth_first_search.BreadthFirstSearchPlanner + + Depth First Search ~~~~~~~~~~~~~~~~~~~~ @@ -19,6 +25,12 @@ This is a 2D grid based path planning with Depth first search algorithm. In the animation, cyan points are searched nodes. +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.DepthFirstSearch.depth_first_search.DepthFirstSearchPlanner + + .. _dijkstra: Dijkstra algorithm @@ -30,6 +42,12 @@ This is a 2D grid based shortest path planning with Dijkstra's algorithm. In the animation, cyan points are searched nodes. +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.Dijkstra.dijkstra.DijkstraPlanner + + .. _a*-algorithm: A\* algorithm @@ -43,6 +61,12 @@ In the animation, cyan points are searched nodes. Its heuristic is 2D Euclid distance. +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.AStar.a_star.AStarPlanner + + Bidirectional A\* algorithm ~~~~~~~~~~~~~~~~~~~~~~~~~~~ @@ -52,6 +76,12 @@ This is a 2D grid based shortest path planning with bidirectional A star algorit In the animation, cyan points are searched nodes. +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.BidirectionalAStar.bidirectional_a_star.BidirectionalAStarPlanner + + .. _D*-algorithm: D\* algorithm @@ -63,7 +93,14 @@ This is a 2D grid based shortest path planning with D star algorithm. The animation shows a robot finding its path avoiding an obstacle using the D* search algorithm. +Code Link ++++++++++++++ + +.. autoclass:: PathPlanning.DStar.dstar.Dstar + + Reference +++++++++++++ - `D* search Wikipedia `__ @@ -74,7 +111,13 @@ This is a 2D grid based path planning and replanning with D star lite algorithm. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DStarLite/animation.gif +Code Link ++++++++++++++ + +.. autoclass:: PathPlanning.DStarLite.d_star_lite.DStarLite + Reference +++++++++++++ - `Improved Fast Replanning for Robot Navigation in Unknown Terrain `_ @@ -88,7 +131,14 @@ This is a 2D grid based path planning with Potential Field algorithm. In the animation, the blue heat map shows potential value on each grid. +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.PotentialFieldPlanning.potential_field_planning.potential_field_planning + + Reference +++++++++++++ - `Robotic Motion Planning:Potential Functions `__ diff --git a/docs/modules/5_path_planning/hybridastar/hybridastar_main.rst b/docs/modules/5_path_planning/hybridastar/hybridastar_main.rst index a9876fa3d4..36f340e0c2 100644 --- a/docs/modules/5_path_planning/hybridastar/hybridastar_main.rst +++ b/docs/modules/5_path_planning/hybridastar/hybridastar_main.rst @@ -4,3 +4,8 @@ Hybrid a star This is a simple vehicle model based hybrid A\* path planner. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/HybridAStar/animation.gif + +Code Link ++++++++++++++ + +.. autofunction:: PathPlanning.HybridAStar.hybrid_a_star.hybrid_a_star_planning diff --git a/docs/modules/5_path_planning/lqr_path/lqr_path_main.rst b/docs/modules/5_path_planning/lqr_path/lqr_path_main.rst index 788442ff63..1eb1e4d840 100644 --- a/docs/modules/5_path_planning/lqr_path/lqr_path_main.rst +++ b/docs/modules/5_path_planning/lqr_path/lqr_path_main.rst @@ -4,3 +4,8 @@ LQR based path planning A sample code using LQR based path planning for double integrator model. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRPlanner/animation.gif?raw=true + +Code Link ++++++++++++++ + +.. autoclass:: PathPlanning.LQRPlanner.lqr_planner.LQRPlanner diff --git a/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst b/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst index 1c5df1c9cc..76472a6792 100644 --- a/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst +++ b/docs/modules/5_path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst @@ -6,6 +6,12 @@ generator. This algorithm is used for state lattice planner. +Code Link +~~~~~~~~~~~~~ + +.. autofunction:: PathPlanning.ModelPredictiveTrajectoryGenerator.trajectory_generator.optimize_trajectory + + Path optimization sample ~~~~~~~~~~~~~~~~~~~~~~~~ @@ -17,6 +23,7 @@ Lookup table generation sample .. image:: lookup_table.png Reference +~~~~~~~~~~~~ - `Optimal rough terrain trajectory generation for wheeled mobile robots `__ diff --git a/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst b/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst index f816c5c1b9..d58d1e2633 100644 --- a/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst +++ b/docs/modules/5_path_planning/prm_planner/prm_planner_main.rst @@ -13,7 +13,14 @@ Cyan crosses means searched points with Dijkstra method, The red line is the final path of PRM. +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathPlanning.ProbabilisticRoadMap.probabilistic_road_map.prm_planning + + Reference +~~~~~~~~~~~ - `Probabilistic roadmap - Wikipedia `__ diff --git a/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst b/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst index 66c3001c05..c7bc3fb55c 100644 --- a/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst +++ b/docs/modules/5_path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst @@ -9,6 +9,11 @@ Motion planning with quintic polynomials. It can calculate 2D path, velocity, and acceleration profile based on quintic polynomials. +Code Link +~~~~~~~~~~~~~~~ + +.. autofunction:: PathPlanning.QuinticPolynomialsPlanner.quintic_polynomials_planner.quintic_polynomials_planner + Quintic polynomials for one dimensional robot motion diff --git a/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst b/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst index a4a5d28e01..4dd54d7c97 100644 --- a/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst +++ b/docs/modules/5_path_planning/reeds_shepp_path/reeds_shepp_path_main.rst @@ -5,6 +5,12 @@ A sample code with Reeds Shepp path planning. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ReedsSheppPath/animation.gif?raw=true +Code Link +============== + +.. autofunction:: PathPlanning.ReedsSheppPath.reeds_shepp_path_planning.reeds_shepp_path_planning + + Mathematical Description of Individual Path Types ================================================= Here is an overview of mathematical derivations of formulae for individual path types. @@ -381,6 +387,7 @@ Hence, we have: Reference +============= - `15.3.2 Reeds-Shepp Curves `__ diff --git a/docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_1.png b/docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_1.png similarity index 100% rename from docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_1.png rename to docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_1.png diff --git a/docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_3.png b/docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_3.png similarity index 100% rename from docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_3.png rename to docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_3.png diff --git a/docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_4.png b/docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_4.png similarity index 100% rename from docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_4.png rename to docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_4.png diff --git a/docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_5.png b/docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_5.png similarity index 100% rename from docs/modules/5_path_planning/closed_loop_rrt_star_car/Figure_5.png rename to docs/modules/5_path_planning/rrt/closed_loop_rrt_star_car/Figure_5.png diff --git a/docs/modules/5_path_planning/rrt/rrt_main.rst b/docs/modules/5_path_planning/rrt/rrt_main.rst index da3a4957a5..1bd5497f4c 100644 --- a/docs/modules/5_path_planning/rrt/rrt_main.rst +++ b/docs/modules/5_path_planning/rrt/rrt_main.rst @@ -14,6 +14,12 @@ This is a simple path planning code with Rapidly-Exploring Random Trees Black circles are obstacles, green line is a searched tree, red crosses are start and goal positions. +Code Link +^^^^^^^^^^ + +.. autoclass:: PathPlanning.RRT.rrt.RRT + + .. include:: rrt_star.rst @@ -24,6 +30,12 @@ RRT with dubins path Path planning for a car robot with RRT and dubins path planner. +Code Link +^^^^^^^^^^ + +.. autoclass:: PathPlanning.RRTDubins.rrt_dubins.RRTDubins + + .. _rrt*-with-dubins-path: RRT\* with dubins path @@ -33,6 +45,12 @@ RRT\* with dubins path Path planning for a car robot with RRT\* and dubins path planner. +Code Link +^^^^^^^^^^ + +.. autoclass:: PathPlanning.RRTStarDubins.rrt_star_dubins.RRTStarDubins + + .. _rrt*-with-reeds-sheep-path: RRT\* with reeds-sheep path @@ -42,6 +60,12 @@ RRT\* with reeds-sheep path Path planning for a car robot with RRT\* and reeds sheep path planner. +Code Link +^^^^^^^^^^ + +.. autoclass:: PathPlanning.RRTStarReedsShepp.rrt_star_reeds_shepp.RRTStarReedsShepp + + .. _informed-rrt*: Informed RRT\* @@ -53,7 +77,14 @@ This is a path planning code with Informed RRT*. The cyan ellipse is the heuristic sampling domain of Informed RRT*. +Code Link +^^^^^^^^^^ + +.. autoclass:: PathPlanning.InformedRRTStar.informed_rrt_star.InformedRRTStar + + Reference +^^^^^^^^^^ - `Informed RRT\*: Optimal Sampling-based Path Planning Focused via Direct Sampling of an Admissible Ellipsoidal @@ -68,12 +99,20 @@ Batch Informed RRT\* This is a path planning code with Batch Informed RRT*. +Code Link +^^^^^^^^^^ + +.. autoclass:: PathPlanning.BatchInformedRRTStar.batch_informed_rrt_star.BITStar + + Reference +^^^^^^^^^^^ - `Batch Informed Trees (BIT*): Sampling-based Optimal Planning via the Heuristically Guided Search of Implicit Random Geometric Graphs `__ + .. _closed-loop-rrt*: Closed Loop RRT\* @@ -87,7 +126,14 @@ In this code, pure-pursuit algorithm is used for steering control, PID is used for speed control. +Code Link +^^^^^^^^^^ + +.. autoclass:: PathPlanning.ClosedLoopRRTStar.closed_loop_rrt_star_car.ClosedLoopRRTStar + + Reference +^^^^^^^^^^^^ - `Motion Planning in Complex Environments using Closed-loop Prediction `__ @@ -98,6 +144,7 @@ Reference - `[1601.06326] Sampling-based Algorithms for Optimal Motion Planning Using Closed-loop Prediction `__ + .. _lqr-rrt*: LQR-RRT\* @@ -109,7 +156,14 @@ A double integrator motion model is used for LQR local planner. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/LQRRRTStar/animation.gif +Code Link +^^^^^^^^^^ + +.. autoclass:: PathPlanning.LQRRRTStar.lqr_rrt_star.LQRRRTStar + + Reference +~~~~~~~~~~~~~ - `LQR-RRT\*: Optimal Sampling-Based Motion Planning with Automatically Derived Extension diff --git a/docs/modules/5_path_planning/rrt/rrt_star.rst b/docs/modules/5_path_planning/rrt/rrt_star.rst index 6deb6b9172..960b9976d5 100644 --- a/docs/modules/5_path_planning/rrt/rrt_star.rst +++ b/docs/modules/5_path_planning/rrt/rrt_star.rst @@ -7,6 +7,12 @@ This is a path planning code with RRT\* Black circles are obstacles, green line is a searched tree, red crosses are start and goal positions. +Code Link +^^^^^^^^^^ + +.. autoclass:: PathPlanning.RRTStar.rrt_star.RRTStar + + Simulation ^^^^^^^^^^ diff --git a/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst b/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst index bf89ac11ae..9f8cc0c50f 100644 --- a/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst +++ b/docs/modules/5_path_planning/state_lattice_planner/state_lattice_planner_main.rst @@ -12,17 +12,34 @@ Uniform polar sampling .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/UniformPolarSampling.gif +Code Link +^^^^^^^^^^^^^ + +.. autofunction:: PathPlanning.StateLatticePlanner.state_lattice_planner.calc_uniform_polar_states + + Biased polar sampling ~~~~~~~~~~~~~~~~~~~~~ .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/BiasedPolarSampling.gif +Code Link +^^^^^^^^^^^^^ +.. autofunction:: PathPlanning.StateLatticePlanner.state_lattice_planner.calc_biased_polar_states + + Lane sampling ~~~~~~~~~~~~~ .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/StateLatticePlanner/LaneSampling.gif +Code Link +^^^^^^^^^^^^^ +.. autofunction:: PathPlanning.StateLatticePlanner.state_lattice_planner.calc_lane_states + + Reference +~~~~~~~~~~~~~~~ - `Optimal rough terrain trajectory generation for wheeled mobile robots `__ diff --git a/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst b/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst index 04001d4504..9517e95b31 100644 --- a/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst +++ b/docs/modules/5_path_planning/time_based_grid_search/time_based_grid_search_main.rst @@ -33,6 +33,10 @@ After:: When starting at (1, 11) in the structured obstacle arrangement (second of the two gifs above). +Code Link +^^^^^^^^^^^^^ +.. autoclass:: PathPlanning.TimeBasedPathPlanning.SpaceTimeAStar.SpaceTimeAStar + Safe Interval Path Planning ~~~~~~~~~~~~~~~~~~~~~~~~~~~ @@ -73,6 +77,11 @@ Arrangement 1 starting at (1, 18):: .. image:: https://raw.githubusercontent.com/AtsushiSakai/PythonRoboticsGifs/refs/heads/master/PathPlanning/TimeBasedPathPlanning/SafeIntervalPathPlanner/path_animation2.gif +Code Link +^^^^^^^^^^^^^ +.. autoclass:: PathPlanning.TimeBasedPathPlanning.SafeInterval.SafeIntervalPathPlanner + + References ~~~~~~~~~~~ diff --git a/docs/modules/5_path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst b/docs/modules/5_path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst index 3c9b7c008c..aac96d6e19 100644 --- a/docs/modules/5_path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst +++ b/docs/modules/5_path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst @@ -13,6 +13,11 @@ red crosses are visibility nodes, and blue lines area collision free visibility The red line is the final path searched by dijkstra algorithm frm the visibility graphs. +Code Link +~~~~~~~~~~~~ +.. autoclass:: PathPlanning.VisibilityRoadMap.visibility_road_map.VisibilityRoadMap + + Algorithms ~~~~~~~~~~ @@ -64,7 +69,7 @@ The red line is searched path in the figure: You can find the details of Dijkstra algorithm in :ref:`dijkstra`. References -^^^^^^^^^^ +~~~~~~~~~~~~ - `Visibility graph - Wikipedia `_ diff --git a/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst b/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst index 65e0e53465..a9a41aab74 100644 --- a/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst +++ b/docs/modules/5_path_planning/vrm_planner/vrm_planner_main.rst @@ -11,7 +11,13 @@ Cyan crosses mean searched points with Dijkstra method, The red line is the final path of Vornoi Road-Map. +Code Link +~~~~~~~~~~~~~~~ +.. autoclass:: PathPlanning.VoronoiRoadMap.voronoi_road_map.VoronoiRoadMapPlanner + + Reference +~~~~~~~~~~~~ - `Robotic Motion Planning `__ diff --git a/tests/test_batch_informed_rrt_star.py b/tests/test_batch_informed_rrt_star.py index 3ad78bdb23..cf0a9827a8 100644 --- a/tests/test_batch_informed_rrt_star.py +++ b/tests/test_batch_informed_rrt_star.py @@ -1,7 +1,7 @@ import random import conftest -from PathPlanning.BatchInformedRRTStar import batch_informed_rrtstar as m +from PathPlanning.BatchInformedRRTStar import batch_informed_rrt_star as m def test_1(): From 0c82dde2be24e5f3955018caa061750d7404978d Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 6 May 2025 07:22:51 +0900 Subject: [PATCH 893/940] build(deps): bump ruff from 0.11.7 to 0.11.8 in /requirements (#1215) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.11.7 to 0.11.8. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/CHANGELOG.md) - [Commits](https://github.com/astral-sh/ruff/compare/0.11.7...0.11.8) --- updated-dependencies: - dependency-name: ruff dependency-version: 0.11.8 dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 88cbb21f81..e78b9b8d51 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -6,4 +6,4 @@ ecos == 2.0.14 pytest == 8.3.5 # For unit test pytest-xdist == 3.6.1 # For unit test mypy == 1.15.0 # For unit test -ruff == 0.11.7 # For unit test +ruff == 0.11.8 # For unit test From 292c9dc613d1b0ace3d25ca8a0295e19549516f2 Mon Sep 17 00:00:00 2001 From: atm <72185056+sutatoruta@users.noreply.github.com> Date: Sat, 10 May 2025 09:34:19 +0900 Subject: [PATCH 894/940] fix broken links (#1216) --- .github/pull_request_template.md | 2 +- README.md | 12 ++++++------ users_comments.md | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index b6ac52efa2..c0d9f7eab2 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -1,7 +1,7 @@

    W4dI(KFNqnSFN&(5qD#9iYJv?;M5mMvk zNZiJyrKL?>T5Rc4r1mK3fA&KfDy!F9A&}(GET#YprYNTWID|W(|Pkc zl3KBek1sWxT_REQsCg*P8piWK$tG*cV)jYE%|><8U3e?>#b;$@MXDvr6A5F*m0&fx z&3r&APw!qEh?7~4+j?QT$jt#$5-;FH<11-jo$v|VT_sYr;Y_vTf0#jGndFoCoSRkP zs7R9pqX(XzmWn(M4i2TzWG_6me?9}(vDMC)6nlw=IX6GwW9}b|51cy}i=r_PRlXh^ zW6RjWOEc-|>4}()j*q^5+hqI1Ej1`zWa0Au%z>)Oh@3%JTfNxkAjm_S9{@iIB_f6-& zKuGAefOIdqmmAbi>3+XptCo1pUM1Mu#GtJyhGv)YX@ z>HYF;9-P9p(QB70z#9FnUrL@Bqb#+wdM$| zb8@PqYZt7ImW4qQC39-hE_gC7lxo~NM9AVbsVf<#bm#taTeQSMW z)!u0&40LJYC~zdg2n<-VqG)KWnu;SkdyZ4vR5xBix+q6cp~#P=*GEh>{-$84?$`Rd&!?F%^e~w|-R2qoR>;z{29? zYJF`6x^RJG8XB9y+;{*$%u90Zv$*2}*4J)S6H@g=ZZhpJ@9>Wco)JXQ8A_KmX6<^X zKVu>bK1*78#M=G7%IZ}gYltHqMpP-tjMZCRJC^nyppjr3!=n{3?tx_c$LOf-v-z%8 z(b=G<>H?{OH+a^g6@t3&nP5MV<>>f7tSB_^h_n2izv7Fh@qB3(`ln0H0IGO2Ob$`c z_kEEK&clO(RoGR8>#4kLZ$o!hkDh3E@jR3Rkwkgu@Zm+r7(Tto#?iS6A`l@n6+vS{ zum^MnR(wHfzvS;WA2GCk)2=$R{fF+DkM*TNvZhQsPpAy*^5qAPA1~R#s|9ncbmUZp z^o;%Zu~KSmWF+?w&dXc?m*=Xx%%Lq~A_>^&NmhNk4e|Z~U0vNBazXsGJ6MZD{~(I3 zIFbRgb!+s+0AM6}WV675dU?kDtH1P|r|-khf41@kOq~qyb}d(^`Z<)exv?cInO$V2 zcMdVdYzofkA((KL457x@ojt&Cy>+9O-zX&|rT>Fa(R(QH+^8tw?l9LT5^e@z@`{&T z&s}Pf0<;!i#>Wc?cA34>35H=`WRl?y7EYwtO0)&q(2xz*8?3|C8 z3LV)~GKGc%hyP;?%?|dzE}(HYii*N`1N~peA=CY8l!Ff`Fsy>H<8ec=3_1}hDJ^76 z$FNyw#p}BvTq$ed8j7!uOVuP$6DB+icBB?uUM$@Q_{PN6y1Q1DcJAB=u?2NZVVT+f zlLNfdT~`1H&sm|B@Fid{o0vs_q1G-mFS_WGrGl*-H2$Ns_>T|k6iPsdPre3qzkFL| zUqBLWYf{IpE}p;vI6E&)c1Na*!+78RuW=ZY9fp}&_Jf|X4>!)G=~zfatC!UFj+DcU z!iVE%WEMN$MS5qF>NxF53M&5L{I1dvS0W~sb6;ax?Y;Py_xi^Q;Q!vfmmUZ(i`6wS zIHa%tTvtzzZ7RJxwS%FwD%blolSP8G>8mbwxeDeQQ2x(8v>E?#?$*tl+Z@VIK2uLP zdwM*wVc}?Lk8501K!7x%4L+8zOKNIrT50Ynks$%ET)8_dKcA(|*`K|I4lQ|BpV0NK z1-x)JxZpY%%h18lYCQqx4PDH-6VQ?yo(6m;7hsP@S82eWxgDFY$p6>H`R5M;_L2&7 z+idv|GHs&`U-&px89X;PkEbXPwC$a%uhs0hNqqbJhKEI0jDB|E%tP|0;kbrKZFJxe z#_CtOm8M`C2`Ly);fHrTo*(twy@`l}>-p_$)BMCHkWhXu{?4G3+^JSw=h|8gBrL_f zSSKu;FmQvJ*Zci|8CSrbA=m}y0&=|5V;cWFYYFr+e=@GnKbAhzRQziI&vXa={;$(@ zvW%Y<+Bj>v5H1kFy9L{P&9_(B`VK)}8!pAAj4|iC@RM+DcS{Se?K*_unHv^hG4+6H z@5(6(E@Ud2#yW#dAK&YTz@{eh(hJbG!7CkO41Ya zc~Ap|E!ql}AtA>iWa$ajfHbnr4htF+jq+i?-Kq#VmyD18-9>-`0zA?zmN9VE&v_Y^ z=``;Ia%!SeUjkQuTB>Rp72#Y9?NlDlamW|Q*(7rKwo?QH2?WLrH_huR34W(2 z8jzf48}@M*EjfMy+lO&Sff`7s#NK^Cj`z1`g=Eq>tf&kfRvVS@dw03-GF| zyn&mK80L_v%uFLuAOs7L=gNqD*|%?BBX+?RtYN^7r!rfbnhu~}=T;o)mr9xwB&P+2nN@xvmn0vI67cA2K5B&Z*DyLAI?_EcgY~C;^+H`ojA+W z5hBsZ$cXY_7|i|&Z8RB&iMRC8XxxK7zJA-bV}Kpju^UzN+8+FPY>YTeqhBU;rMo&o zE4OI0heUAzJ$Ohtsi9#)SF>Zl&)0VgxCuEc(Ugr#W@=umZ92_iY0mdHz5OXmeK*aY z)piD+?W7=8h1>qQulH3!P4&66a{FGOK>thWk{p1`V67FF|2Y?E)Tc9d(5g4BZ>`Tr z`!O=I2Lofpie#na3{Vd|{YE1L!QdUs>v0$sH-vp|2-)P!aWW)w@RE>e-xlcmx0#&@kHlH!AWqtSMxVl#zWnX3 z_8cdSx{ErhD`u)PzYPI@!U@RRoSnire}13v;&NA~L-S8TlF;1DGg_*h1~Zust$ZDK zi4C?7?DTl4{z$e+js{Cv@;yKCE7zr!F?k)owszyuP9U*ekfJA#e*d%hIjMQQH zx?m>S9uZ@tPJI*2x{s2!SnO>^oJUPpNEVLQBRGh<@$Nm__}~Vx25d=_Tj=Ip^f}`{#4> zaopa$UeD*_aUa+Hx~@An8qxkCZ>FDgt2k;_UvUiA@GKd2zHEV#I|fUYh)D%t*Oz^LE10n40M5gRo%iqEJEOwSTCW8!hld^hYpA;g{B{ll zO}epNSo(>n)b2(kHmt0&eUq-v1}qY0KU%g!od)F(ho>R1|Co9*TnX_1wIxdEuPR`h z96`IRJ1aRy3ZnQqIHUliOS)bfT-|tYHy+Jp!h0~-YhGib6P|EEj$>vvA07%1CJNa|hr z>#?4D;N)8y&W!*;w9JHB;HON|MHX6b%fOI^M3xa`5siLti4_E@5VF zQ8m)tM4RB{^zdz$;dt>u!2`g-Ue}`#{`BV%MnkeGsi}1)8;&eQgj3|FN_}Nc7P!F9 z@I!8H=s-1&Asf8fH}R}p`}}BsAz2Upk8g-lCe-SnJB9K4hQE?-hCdBGJ^da92L1*# zLB!LFUHA0~baGT7S8Ire20_$`aTigB1Gu&nK5?*AgKxF=qoB*H!8>B72G9~fw2@~U zGpI_M$XYQp?Es8t(zF*4gx_N{KlrcnWp3mQuV8uw1{8J#6-XMaR$oCK&Zk&oZiiLZ zsF@xtAxkp4sRjsbraPryUQI8+8s9iWU~VVJX%a;>A-B)L%Hs!=8NnTB0f(sYYn!WeeX!}j3z@ZHyM`bSMs900m z+FF2Gla~Z+mh8kdjn`(r?37Gfxu*64#+W&TSaO#z{>bVy61ad6?1vq0vf`@+G~T@C z-}`hw9pJ$j-^OsItad#0h@?37F`%Qhxz$se?fK-%lSw+dMT;!x3L!PSJQ#j=cr=gV z@EkN-_3p2Tx|K%^HYM$wdn1NbDy z$n(NI?=Lc!q)K&`HCsE6mUg4*>LQk%HWf8l!K#`-q8z`yU3IGh6@{#z9TfPV$slcp z_%?^4wv)NU6S|+T+kA3ZPMCBDD*~QMFf<68)oa?@+t;4WX74n;i@)Da*kJ1pSI4$kMO4+u3t9eypbSsy{~O*krLwxWdXeRe#Q zb?A(pa`I?UJ#v$zi^0j`aM>r`U$K>nEWVjZSxlZJ<~3E6s~b=7LlJp{aw$9Dt*%ZR z@M=QW`!x-L_O(nwqY`Y_L#JRGbP5_IVfuIpi-*J#$Do9ZuobrC95ba^!DSAMkxzRc z^o4=woY|w{X-C^S+y~b1XAJR$v=lMMxV2J370^*;$r;($*54jaJ(OB`m(TqTKV8Aw zxS(k$CPt_#^7tkDAK$;Ylp#>^IgAXP31Yjnrg1*i_^7A5yG>cCwzf8L-TgW=WWD!5 zuE9R%++10L8l?2+OWgPM)oyz~veuheS!B*lY2elGZ(m2;vV9)4pD_Z0_K5V-5g-M5hEIUQ zzD3@!BG9<-KmP5X!PE{wPkbQP$>~L)RP1a`v0C4U57#kr$=(HZxjNJit5i0dH)a^x znNv}#GV}2AZk8WN!}1;6*K0rQezqXlx=I@BsIh@Lj1bgB+aAYa;C%o_&|^dK>B1e^ zqtn0VKfWv}SDc}WYpyq^fAS1%>hKk&YJW&3I)F(bvZAXd-W|r^GUzqBq~C3&JtE_` zwzVFO_rWshO)89AEnDv{HmoSA&O3@}k1jep!fVG{6Y0pG$tOS=Q1SToyy^7L9;zZ}BD{r$1X9|Lb%G`d40j{NyjOwI9)7RgRC46bvjLgdq z4Dui$iXyMT=rV-QS$z5zq$IZKzx&^EWb(fO{=oE^+++XGcnV|>WX^*LvY;g}#@!75 zv6)Zy?b(x%dz5D>m>6oXme>yOVTaAv*)I;1Vm`Gn{6v`{f>bKOj%duG{~oCPa*fZ|wu2|H;5`09*vMB0c9 zp(le=yD1FDQNEkuS+jh*eZmYXpIOvHSnp_Rb|{n5bmY)4#l670{|w|E%o--*eTM}} znNfp>mr?t2HMTbm!LuCe56)hx8G^Won7D5jEuvR6lla)Z51~R)LPq~+fNClDqt`ET_aTK2CGw zBh*-v0kW9ffYSYoY0o7&NnEZe@D@8svqw-T%{bbJ++!51=SD=LFJKc@c8HGyu36QJ%Ld4={FmqCxO=y`FAS#~H5ZIvuB&52{9a-W=9V5Tl}=+M1G5tx&rd|I~CX56Di%K60Nuff&d zZ2!3EQcYYxZFd6aAvhg@OdUrb8y5YR)!f)I7tKp1XN?pU;46u5r|c_4)3f%bew3h$^=%MZA?P-FO0YkBWj3Bf;B zE1q-)3bH(q7BJR(LLfbZ{KQRaYphgfz0=V-Pv?9y(|44OCfNyJeC4w~5F#LpbCGQ&pXg7V`dzsz zl_5_uC(VbA(=&?V7Aj0hCY4`Iu>gDyqWCwQlc_>m>P+ZXoek*?dI9ji1q)4irE&Aad%egfsr@6^V)rJ)Ez7-+`G_{xqSh@gjL8cCMWEA`wrE! zX>>FUviw2Bv1`2@ZLGFvEA|Xy%khVR(w{TT4ScV|47Y(IhN@v-y~D89C0;$l1dZ6qS`XOORx&*R6fJ0d!)GTMsm)kM-SL%FL{-5`{}>*;B6toJdP|y@19Sd~gMl;6ioM>n#}& zL++t~eUBB1Gm4ewvk@!9BM+8RcK=#&DJm*TnMdTuc+fge&?nd>XjOcRPal_44c9b? zZbqqoA1e;&7A$D_KzNAaG_|HlZ^qvq3n4p5oEZw!UM(r@^9)EV$v15KSvBJF%JSYvPM49lxNU{TKmp z!=S;^J1-ajR_f&VrXGEv-he(-fNOYDP@Qn%Uq~bJ=|G!a?5QD zxX1}gNl7u3ocjlA!9=IP%QY$=!DW0zXeTSKu+whcDRrrf)m*TF_{5Sa)-LI8iRSbl zgM#F&5wdo`&09Ba+{a>@_bB;h!j@ZPK565hcBzyywToSnpn6vj#Is$ycN+L!h+bdNZ4-oyP~2uJLEjR)2avq?_~T1CF|!pe;zex+4Q^WAWEsF8v)FRVt$n zg<5jW?I`x2X(T9)tmIrPAyLzkgv50a?P!Q3I}4_ggZN9ef}8cUl^RlxbK85~^yO7l zs9_G2|FSEVMkn6XC)YzDm{F{NDLLEQHdd@PlZ``~o{YM-Ep$Jarv**x-(1JvD ziDsKvt+t{f2iZCTFmyS3b!!OTWnl1l>CffNi143VT4Vr$F@8cpnvl|&yf*yL9LA{B_1--E@fi+05I`IWMpAW9prg3 zIA~|k$<3ubcQ!#wZ1D3C#(p*L+vS8&M4CHo-MzY3$JyI^g%~XLp9coI-#>T${PMuK z(UFli%GWc{^bs9U6ci_KUquCoerO|;cmUj)OuvKt7NJr`w6@p5xKOFa?f(7eetsF5 zWax;re-R~lrFurm+pg^I(BjF!PKPt(_zE~B zu$u1>*-NG5OQsZ0hahID_|F0^@~YIUYv-y?a%BF6-er8i5%Wo*lBHylaz?Tl9_qQ8 zr7b-@lP;>~&VSuOcf_nB=>0>K5)(GVlef}#;4ZjT$$i#`C8$lgp<*$C4+dyPvQ5!o@u8nBH{aXXV$Er zhhFg>S^D}JFIdFv`^X4uU_97vvoP7WUQ%ezv9jPGg$s~euSi@s$dc1d!M-Qzba!X!CstIE+!vEUNMW!ye= z5zWT+EtJJwHDVHT8?T+sEFn`oTdojIFN5dL~%Xn%R&F6PB3_ zfZ*hE6!g)E+3fB=kGIolT1sZ*69GSj_F;Ql7(u9reC~$i!WCO5lNM+(Y%2*-is(5V zzAn!Tn=KDo&FOsaSL!Db{jfHt?Iem-F36njf3(La=LD;(svi^+=3m=*g=L~j9+pT8NkE?WP z2BO^{jDuiFL>P?!*9itWN}l4RMk7AHCF?p$)FDLYMu9gYz-SiLC`kPAPu8uO-jaZF zJK%Ef)~#D1wjCde5%WZU7-OXjLh<2uMYZuY;Mq2tIgWbeQRBB8&`{bmT#4SCOb0;< zDOXK0jWEZ8m3@^7`-X)NfT9y>G7OLRf$+6~zYGN?vg&&DSH;098#V~utfr);f6rs_ zWXSlaCi~g6KaGsbAWMVLRHW(ML)~`Je`hVa1?6S$eV}ux#f+@HUOzbcat5+&GyYOd zl8QrI{3tawHQ%8p{x=Fs+R+N}lF=ui>&Nn2km*o!6RGNdrV7e;ofS zj;I@njbGI|f$<+?@&O%bAM%}NxIb7raMIgAs6{hiPv8S)0f(>&74-i(;+y<{QnRU9 zWB3hl^~f~f!-o%xC0}W2{G31G@v*cKt`tV|HT&D;W)Y6nH zCz+M_Ec`@Qf{iE*F`Zyo6VkGo{RCV71dG)O`2~&>XA?)(FQYn*>=#kJK>wQ7?(XIq2)?)>F%GWg z7}%A;Fu4o~gX<)svbMB>9N`X8(3#E@oLLlPN3dhF{9BYXvX`3Fs1W3S0Db+IN*i4y z+%8OGc0IZ{`J~kHwxS*3Qt;J0ewrc824pb9KZ@p2i7u{8vI@bJ>Ak10k*r!NG;~DW zwXHvQ%Zz$6j{oHnn;&<6^JW)W{)Ey~Czc+~4xB-lQB<*LuY9paF&>XDq&pRK_3t$e zKlChiLMTbnx5}z(zO)IEPCtH>DURau=qBC3D_f35b}8_%`PkKEQvKw&#AYOxd{jH# znvQyu1@$b^m%(9w(|5G8#0yI7%8_&Bz-`V0 zGcYj?ExJFbJPb1;jRad6i*JfsHpnZUMy zRH73+b?W)dvhk7KXpV%3oOvnHeD-Xi%5bXTJ~;&!KvW^%I3zR%^DL+OGO3Un#~UIB zRncu^s}B&GLuGTGy4TR5M0=0V>1u@}tU#P!ot>Rcqw~pr0oqs$+$Th|N{FL{m!yp8 zqfMz!GkJ=S;JIPy5$3n(=Up(Dc1HZZ>HA!>7?jlKs1q_jBq9e+s-}X^H-o{3>5tC_Es^ovhp@HHGPCTP?S*}0pfp*bo3Du)bOSN zFVp*Yz&TqAww;{G2x%5|IRd$9p2Jg^j!gzq^Tp15-j|MBAqvW-B2|Bni%F$pJJ%cduYvLcml^<5ty6PmdW4i5Z>7wd8~dQuCp zmMfZkWnBsBigcGzDtAPYohoez>)K3vcKy1+yM3 z4s_da%68v8K)5pC9s#(jk!4!8j0Zy;YfC!ol@s91--BtzcT_sESq{Cg=b}kN@ShRZ zht22&QOegow0>F}Y)Xu`Mrx8lV^W79Y2FpqZ$6uKWd`SdrgvYm6@kQihhu$!9tKW$ zK_b4qAL-@Zc7iKwo~+(c6&?7s>H>UZa%UjMLC%;*654Aye+pPj9!TvW0vg#20zfDG z0KnXfPuvRK0_=V>+ZSdt32+kj49qfguEg#I2M}|r=87{QRA5iI0xJ(hH!<}Pt}Vyr zx7IJ!1qB6tM*dR2%^|a#J;|;1U{jl3GCBFsV8N2^tq1=!As4zix}d)z{YP0ZZv#*r z-iXv8&ryNeOKPe|j_@E66BVofqQ72NTuMG{>M%C1FFjFCI6)qpPP$ljRu+YB=$W3) zr`H_Q4mGTlrz%BFJ4D6MLH0P&b{QIB zSFey!dG52a!_3tA2yfbU!@wOrkW@4O`6LXmOq8~;R-qBLd*H7*)3Y!yUd)Lc`bcwN z`sgAijo3LNBFtwK$(>n+S4#*0c3s>d6w9icw5yz(b&<^(njuo z@xa-sAC*nb>4np9fSS`%dtZ4=X>0oeLe!w2H_yay-u(FwfC_1Zx1jxe4++g@&=+0)P0zr60PU`r)`a`m8$T(>D=>hPYHqot*#I&^a9W=0*D z7k}s;*-RaW@YdD;k|3}!SsI<6$@6F_S?>znP*rJwsJ!&PeK#@b)om|lOD1y*qANg? z<54aQ6Hw4LU^PB7+`?Q36;5|@d?>()$sq5|hd|2Dx`)s1tlfbFcr&nYY5Gj>!A@m_ z7ayOwUGYlnY$1+t1)7&Z=z8RL?b^i`?SukThe(sbO%@6xv~&!@u@QSF{9#0gVHT7V zKkRbpDP)D~)Z`Z6kt-i@_LZ*zO^jPLtCV&smxpe+>)`>|YdsTlP~afxt(LsQo@i2v z3Zm%R5*CQ6mni>>7;FC0El<04e<1>su)x&+d4TWsC3@=r-Fk$uFF@ZtzU3y!5^%?m z!yI6xCe_(Q;+)Wsjz;%Mh&CF zHcqsG?j7OD`RePoP+-}AdMZDE2N4ByQ}&m57XCaVwY#MhOe+|nPz3ev0djX@)-Ltg z)WU!pwEu`<)$9Y1u#fB{CuB@y*V1D&9a==!l4#j>pR7iP@cC3KwUK%e9!mIf)`eK# z3*|-WSr<>8AFt=GdXK0oy+che46|RNE+>XKGf`6@_gp1lSntAFIX`2na}pz#89jd< z5TLsCIJ&vDJUl_&H;!}B@DUfjS6*j8q9qB@xIU%ou|6WwX4BfOS@P|TMUWZ`KoNEy z2HI(s0T50S2U*z4ik%xuTE1OELPID;2N>U$<9MlO43oE1%;MJ~MS}V+pfp;};!6shp3Pwrjy#g~{oA+wF#36cSYxHkP{MI+CI0kw)lH(* z$CU8aqO+!^-70P=ec2nx&>%~;Gvm;fEnAuq;gi2+7Zk*MK;U3{A7f;R$cssA;(~$- z1DTh-y}d)Y${JWmYQX5s=H0dT;BM*?vNIY7uL7m-yM*j_00H$7vj_lzEJ42G)aDr+ z-3rj4x~oU`4gS1yjVGvCH`bv)K)F+`%)V&RF`C-c)Ko2Fl?OMW?gZA79}yJ-XUKJs z-X_YqV-YpmPF*!a0^jWFg395AZin1%*0U9U@tAgh{X)##KQSV0N5ZwsokOAQ!@jfJkRM;c`*HF@LHI>7&FOCzUW>f05#_I^dl4mN^ zG4Yzb2U}I7cHaPXFgOyshz!l|xj1p7wy>!+4Gav-!S>^GDjX@N;>ZLP)~+i=6MgoU z7hH9z9{j+f>*Z2?P~L2KaFEH-(eYCk&eHj&D=eKt$-*v0QWLNSB{s!?o0U#Whv}qi zBarIiAO%>|L+k4@X}>VDdYx7iIZ)yW1LY-U&=I%jh>gaHgx`vn2vPxL3{yY;^RI`u^&zzl^XYiS1gooq)LO#{*kY*nKi>qDj^PYescIl zD2Jbln^vF40-xZ%hlhGor!ADBALVyvFygRCTyRHjSdZnko8-$b0G5`%)TnC0`mr43 z#lF5inH)Z_J$H3oxpIZ+QTI>poOxqSJ^S;?gsuly!ma5UPI{==*wXc;9W?vYYhRUT+Lcc|0fqE0abP4Fe-)5U8`8L#JvN;)6;quZ8s69bhExzG8@8nLl(1zZm4 zLsOt}37&R#99UeWJWnXJ9vLwB6m!M|P5WWYia(tm?=CH=fq#)k?CNbX6=aVK0gCOh z8!vzwhNj8rh4vEu+RTa+DL*cJRHJ8^!j$*ov~o7^NwPna>Gm=tSinJ1pN!{UaUwHv z4Ks!I;Abd@K7gfl3ZFtv?qy(1M@XmZ4k9Pr)g@YI=_YsH5jAf!$b=hz)S{m_XOIle z8tD$hLYhnU*(G0SS5zlib+Bsbl-wk`8iJ!i08naq4Fw^wrXgJZnLKiQW+@XA=Jwt( znxg4S&=ETxp+*FEh#P=y%3Sia_Pl+3QRD+O1qV&``7HHU2rG1}9<+jJyI4#(H=H|` zg;0L3`YyYGO@-RgBB^?rx0b)?!I0MWMsge(8i7CBeoCv%=XqzIob47RfFy69l%Ii8 z3VHVSB=P&R9vf7D_tWx}LVfHH*4j+WoNNtz|!W7=_6V4Pq*9y>&5 zo5H$@|DY?IDC_uuos!vt;&PHZK~ioTw5sC-iFd#*y|ZnAm|*#qKb^4LqXDu9-_e-; z7_gocA0t9YRJ_2{W_XxD&_;2+?!#8fx0d3cJ@EVl!wMAQGC;ox@DjV?Ue02322$!( za@SoY>ToPs*-c-aY8P)@9dm#PDiPaN;;vl1nuCkYkJde0m7l=>sKD4NfGS;!kB|S_ zPlS&^(@)1{o;~%Yv(p%eZX$1`_U0#Z`cIxXA!8K3ZzZuI05>7qUFU*P$JN2}-J;!=KMsetsP&OyQ^9Y&_>h%F~>09MNFCic_T z{QDL3D{#dA9Ey@tFsM+ga?1fTKoHVd_u8{L{KCPUVq)q)1_F01uP`JI_0ROkzn!gq-jgQW&P}H?Og5 zraX7bY1?|xY2t0EdSC8ej+T^Pa~yNT^B)q`-9yP|5!iBm(rP-8jTog0*fIFcK@H7l#cO~OA!P6O2BDhPOz#dUkY`+w1QZazWPw59oU}-!KEb*R6B5UtGDV(Ky%No zv~lljYO>@GSE4$l1a>ThAs&_s2#X8(V~HeF+H)or7KqR!!%~fJ!VwyN*c|eCHJs*0OWvFFSTC8Y`o5!(R?Q zo^NjAjLVS?bH;UGHU+p5Ph0J}I2iw7jDwL*h(Ot7N+B}}z^@y~ed-np7~cVE^>^5v zxL&YjO-+j#L@_rohrVQId*r2h8rTG3m|Jm9Rr1ONcG$ZUA<*qJH74;y&pc!16T-6= zx~+(VCM{F8bDeAbxEXa4&q|XG5P^%A&!PH4UgfCdH;8GQ3mkt$=luz>iyL^mYKa_@ zRyw=8u(Bt$omJ99b9a}twDb$dZZHqX#Gw{NoC=`vG?Dcj=@&WPnJuW5WJB#RNGZ!%X66fPPtib&-G>=f494%rFY(;-3~NQ)3{ z)DKGa^J@$?0(gn5Dr|5sdwP5n(3cq6U#%yRudpCWJ@S~deSe;4fG_c5{@})) zGpUxV(3L=3cF$2&X!_sK{12C&i9jVMDPCQ)3D=~c6x9!k8N2=-n{5#ITvPA!Mak zKl5PvmWU&-b`fuYF)v_U`X#8_HCI+jlcQPHNZf)3s#7TzjP_ib6Uw{2y zx8!H%u_$N*(xlb8yls@12Yg!qLK>P{;rBtWhae%SGC1Y3Gb0gK#izp&G!wY>F{WM* zcy8b~0);i%`%q*a7l(kcrd0dK`Xz)lewE#JKUA{!+c&xERuFzE&P0ZqAGdex8RV`iBCPo)XuWInAe6z1^RIa@FhGvI=tsf zu+==~aZcsZ8!ELSTcuX09DJzyr~2FlF4vwJ^K7_$c^1`@`-`F`?pTa*>#iHttF!M( zjp#r3`QBZ-v@iDg{k41CQqsQ=4EGMKH>^5eWmQWh)5Uo?*{Pu1ErFUS0#`!Z`V43w zp2*`?4lSdBi96p5VUHr`u#1S=>mkTq;^mbmKD#LlU};Pnump4U!@wV{;A2Bd4uP4- zoREXf2;GMvd54;4XXHc)L8QRRza@@8j;5>RzJ+q$gAwcB_r+1c1aux6BX zgB|4Kljj21x~2NKL7VN)Rnwq@f#U&u%bkcnS(Zoi($W&Db()BQ{Kk|N*x1mHa5iqD!nNW) z0!~jG*f??h+75$dNw8Tvbul%jW$`i)9nyY`7)gA89T@L*Z1kXDYUws<;WweEk1L2z z*}l!k$5AP@ADTeZ^Aa_a^7`DLvD<>ND!Z$q~LWHSqUV&Dzj6t;4 z50FiSxKmHxYB<*Y{`fRD<7B7W|FNDTja;-Wn=4jFFyVv2;%A1;E?dcVE=0My>3u~SK)Jrx(kff6I(Hlk`lRjbab!G z0vMKUlmc=4WLU@Mrf;F4p{%2X=fzmFa6z0`NsnAm-Q{+m#9B!nZ1cJSC|Gq>m+2DA zy%~IggZKgt2BPXyFN>q9@CBVtd1}P%f7+>rq#?(Abn5 zK75!M6MkXp)RX3l+;P6|b9+6SEk%In9tm`1AAW>%3PldBW?eDmZotj@D5kxi((Tq~E1{jHWIa-w1p`l1^~K%X8&EJ$KZnp7bdadT{lxxb)N00nbi5*~DqZ))&fgk? zPkuyub%YSX9swhYoH(6%W8ge5B^M*Zt8+Jvv)+6su?v5(Ca&q)YTt7o=_J7>8tUh& zWM^kLRX}d(#hEOa^ENdWm9QLqgQA+T(rP^q&-)AZuV=Hg#+1m1Xd@_k#eyWp>b@My zUnOO0uQ!z(igf+be>Wvf<2pbV(VdIGl;yQ6mCogKWdVVd~PrTRP* zgS+zY{PRiM-n#~$S9m^0MAlW69eAKs#CR^pFhvH-4tfT-?DaShUadrv#QV{(NuGWspkhtJvuhN zRzDjbrv^IAfZCxth{(>#xsx=6H*3{d2?yar7f!#u=rbub9#vFgf^xxjplF|Nn)_pG z%;ehH^vK$+!S1@6s(C>#lE}0fMPH<3Zpabk)cew;Rsz-VLuhKS$E*~w*B5|`id1Ts z43`G~z;r7K(=WKTtR;uY$d!je8T!xKS^-_o@a4@GQ_*n2V%SI&qmJ)-nIjzg{P|jJ zAQpdqBD;64GoUVgfV9~kJ``akN7wyT=*$?FZ{7n_j<0j6Bh)|bTjj8pkw!G{auQ0y zt}M{bN&tkU>aD!WVt8=`-^S5OvF>tV9>b0RR{-MxX0!A1VxPeCtUw5zlSx(7yJlOt zR>zNjUT=rLT+VOTLi|LduA55~Osz)DD4>yDW(8X6P-(O0QAj@E1t0R(=fd7U&r0$g zd(%bA_1rubC~TslpP0X)1E9p(WWBKGN=TcGjLZOhck}_J$Ax^qaMy{yPHwrxA@H8L{cK1Z8@6Sq_UVohD%m)DQheL=_W+P}fM=0_ds&3e4mLwk?zocwJQbAY#jhL5 zqQf+k!hvyeDxk##Sse}0%QKRkoSY(!2*cf5jPyA3;nvxmB6&uo$f7`!JK8Luxuu0y zQc??Q#-Y!|ZYsB|`S$q~UT-tgmQ5x&Mz(Mo>dI_BCL<^>H>}& z7@T=FclG+|KGc-Y^nVaY!6o>YrM;wIQmR=gC0gT#G%a{c3NKi>Y*`QneASG%3}}U} z08$N5G^ySs*I0A8l9*6gxaDF!YB0AwESNzzhz#KOTfA40pFcL%Yq*8W7cGHAJM_DQ zFljdc4pt2Z;v5gtgr+%chCTluPN;J=;OqYR6vhtd{;13DeknQ%2^yxLhj#gWK%FhR z+{A6cHV|7JKpM5aot>TCUXth7@72%>ZohGHBAfU*Ffk-e(o#}t7wBH>;%eLu3`KHc ztUo(H-&*V)T%$rED>L}>+Tt0Xyjt?we5d^KXHh+2fjM-kBdDJ3k%8*w0Ah_B-CU%U zfE=31)CI8Bc-Q{`4K!`UvOm}_!Q(5~FNIh%UvKFqdh9d!Tpntn8=c33<3PYm1=n`S z&M!nSjk_L7UgBh-Y1Mq@Uti?({}2S3=8*WsqLq~HzgL$aeQe!AJ$VN*Av08l09H`Y zBUTKWj^sZ?p8Bqn_1OH**V^=GSz8yVq3v+`3Q%~WU2w>2C<=zW1YMFpQNIIAevc+u z8Vr8u7tS*+w?e)!>ihg*D09`+MEpPNLLuUxpE(Vy&j^{F+m?gJbXZ2_hU{bVsL)&NC=pK4zmNy%ycb<^J?*u;t(WN>3gDxPa!(nYAzkX8 z00=`3u^e+K)vcQ3aHy;0(HYpNKTAffKXvriH*6VS#w(Q{TlEt&4wGST0Q zF^qok?b|m!jop~SWP)QLm_By6WmMH9ulBhGwqP1!-iNGV80YChnUGICfa%AX^1vJk zp*%vOV5&)VoSBfy%C`vK6%n}_Q%dkbK0EevPU*q&+s(g!D((eb6S=1S#g>% z;d+6QJ-ZbHC@D8wT?g9-52c(&{IV-geyO*mfkpOl3h(|4;1i(^t89Zyco_IP!eyn_ zwZ+AU(J1ESPk@MRfT?9Qh}k(}dBdSNQ7XiMsOtB2;*+73)Bzqe-pMG?@XZoc>~5s z7S=J9xJmJ|rD5edcCias)0+_OI+>E= z{^KXYNA31b^;{givqB}eYTTVq{TU>Gm8<36*VWQm z;H{$QXhXhHhI=`iE>%m5Ck{h9B78ZjJAy$ZuCPI=>WQtV`I5t$GmcTdg!_2jLT@TY z*~<{_AukV)B2?K5VK?8MlgBgt5-KTNa+!{C;2n#OK6oF&K|zYTFV0I-w*fMYtY72$*#L;L&%vJ%ksG(wP2=kd; zK@3ZVeOIFXE>uy|(!JCb;1MwzJOnv*2aG{XQkk{Dic>If9I84U3lXRL$;UmyV6v2h zci0s5+wEL`1q8qEcn_iz?21&B7u(1}&Gk76ytIdp9tESLm64NE0Y_XX)JM9Uto;*x z!rAg*0MoAOcOGsvAs4&B2q}hrg;JojR|jC}XJA=n(|pOv&NfWl&cm}meYCD;0Oep! zk1!M#lrZ!kKlPHG!u78dlqp6?wC7T#Y;BXyo;@2}u^819MtJYwn=@VwzBVaZatmIn z!G*RRMZ78|B>Z0+OKM0X)egkZDr5lq9Z7gIi13(ckH1zS?yryyg+iNAqN4U6cW!!> zcNMqXrqV@m!PG;#NsUtqr?9$1?&auQU%Ys+9&95P_k7P5l(CLPTQ3&4I-rZQ*0L+Pu+A z3TLsaDjFtY__V$_tB z-?9EA1EgU)O24CO7&XkTgJ%IbT7Rg?9H6|7{|Ml;9EF4<%fR&c7x%(heBR?@cJRwW zTK&{_)FL}t?42YpZ#L?*bMe5Udg{|XgLm|#^bZi!jmfJ6 zXH-?A46J~mm>~=a7yt;Nh7e%+4mGAxRg`Y}j||pDegp|q*#7-Ffccib>bDY)dp3bf zL~#03zB&O5`c>7{U!w7n#t2dEYAZTlvcpz~|KiNDUmj6teed-6va+u(%!rOsk%w87v^NvZ-bCP|5XGV?NrhdG!p>`yxF3!XY zW44LPW24YmT7lJCzFZHN!xPIanfZ=z^vf*nj>B}eJt{{)2~wwI_d*JZ{Qo@F>7k8= zmFR`moY;&#^*;}u)cEXNx&mmnKxnoRBm0yX61@B*@@x=nNAtB+!^q;n3Xl*U+`a2Z z;%L`wxJrb?^K_`z#KR!rm|x?Z)nKBZ%$CeHWu%L~S&hs)t1&`v$f& z=!B;Z9c5T49wXmh{Oe);?Zf@gM`uL>N^NqvHSIuLqvkR;ls6Svzy6GvA{xHxUufl$*Z#OV|k5jzs+y4Y$l$Nm(>i?2s$S^R1|sw=$dUi7?rTJ zY?tp9{s~y{*6!UT`i{tqUZ!p0+PwKNmnI>@$7fce>LqhyJI`c; zmgmF7#?g0x?6UmFaQOFUTtMKsTU(;1f)H)#ZoinAQs0khaOqqVjzn?@A*g*5ulrWH zW3aP~TWhfe{sg^qN52A{TF)piBD%3KW#2J`2@;@Vj=jFP=7vZ_)G_MrSmA!*3Ct*z z$b=T<8_@ji@hlT?e=r3666XlwU#bWv=j*Nxxhzy3ZN!iq26RNl>xxYe(1cmBUi#Z^ z(_aVSe|}OVjJCn}Pcpy0@AP{Wk0=G2+)TIgSHUHZJ$A zw)T0HQH21Txo93uiH>dCI<2!G)|t9$lo?E-BrGNJ+rOW3WtU8nuPB*W)cDI-b5v>y zL!3qJ$`=VoX&^GgcMr+EPetK{5tGU1s%7Dv==<27eW@}+@2f#3J+_$8*Lfy@be4q7 zWrah+yKS2$1}PPi!?pgH@hfA-8^Qjz)}DCSNCMpfFl%Ad87z;ioz&#QrmU`Ru!E?@ za5zHcPyXJ=e)2;8(}(7P)lDem@a&sTz@G?p#|DcNLV03joEFU@tkMUJuno&rilLsX z<&6Wxkc8YJ1V1oLPui~;VU!C`ZL%X(UZP6~fwwg5%$@S}qM~ZV>gz%)uHz%RvYFws z8KX!Bb`8FVHch1sr+LmW4KacMWZ!@x5}E>+ZvcFUajpNg2DFEvqOl zBvg95?6Ca93>dHpV-`GG0Giu+5fNr@y+z-UK?Wdrsp++WKfVSNl<^%zAy4`~La`Tfh?<}X<;{W)F8UFZSlG%Buetj@s z=8c@g5M5)ns0_x-K~^JCQJcqMHWjCU!a-7On}9%mvz4#5TSWdoto)D|MQ7hi>U$hg z_&&48&)diy4Ptf~DNl1ZtQI;Q5*k{HKL`SrqmilWt`z{y@dz}n@KSl`w$6lOUo9(vkV z#{p6ehPz=&c!=cB0GDJ9SF=>d88-J9KgTq@~x3i&v)w zmJ!Ru@va4FX94Yupw>9quzjp|HwJqz}Ne{ri2gnx-A4zg^j>=Qvs61tkO3 zO!~Fs7PI6#0HeL|0YY$BK6szgs(@Pc)E^n}z}XzAJ(q^2)QUE}TOlF!M~xYEm5Q@< zfBjgpK%Vz|Q+fUL&-V`+2RR^44)p<`9i^XL->aElP*8!$7z@KIjpXmPWND@qj02LS z521M>ycN*2)!Z(mt!sP7`fGQug^X7$hH1!6; z^Fl!$Mc;QDqObuRhML=459~3(ehHyeVHpQj<=Hx5xHW>9U=ms9U8!AB4(X(i?q2Qs7Uo}K?B+2q6*c_+dc4EI=Xhq2yG!`fh;{;L%4%;10 zju7srpH(0^>^<%&nc!i?&CR`G_3Ae+LwOa^iRa&?9DUmqhRnEt0d;e42T?O=ev+5s8N^s4{+BT^$}Oi19E~s6EUdF) z%oI636daHBEfu2%iy0aHVOrPyq4;&7e%Hnwy)aW(_`?C-I zx=}{oxOPnufTO1E<6{=;>Q$WMSUgpRSLR+}Yd6<%UcA?r_h149!jaGrT2qlyEb1up zGl6VA857d2P@=t`Q~d|E;r4~um+SIE=ztIg@3c7kDtdOYMe#${EQa~{_3MIX&?Iif z`ge%}$}Sob?>zStARRz?B-L=WXIng+9@Zqmgo#H?Eb)4<1)EHwom;Rn1)TPgliL-tX|?yt$`^>QZj~ZQbsV)pr3x1qB5ibw3D_j4wmz zwCDSZcz0stvF%w}!&r-`A;8%%E3glD1JR|2SYGU2P0DbbDwC<`jtpXiN)LqKI=62S zI7=kHX~%j4(y(Jq7JFECxhgLUos?mW@O(6WzJ(W%26?do5OmGpP$5V2;Kbz$7XEv1 zV?+7#cF@QsIOOJbgs`x&v;HtDlzes7mdi@5=Rv)UYggl{WuZ%^4(8ue%P#~$%CBm+ ztiWd!r4^v627o+Yeq>?OkX{2X{jWdjwQ}aQBHf zIb4m}Ox6+fDH6h^#=FKVG%Z|-uklK}65Ew1=n4TJ4x;!aJ??G$8}O|&Ko%QP9wHKu zV?O{q+W)C7^86dvz@xhfU9ii};_X{hD6xX8G3#V$xSYhqpC_kP^^{ot zw+fMbdAZe%@)du>7B-BmrLs6YBiImzN-wsmOv52gu4>EpNgn=orHULWXPytWx`W=0U9iKLjy z?-A|E`w~pu)e>+iz!<1kdrf@AZLt>8uF8TJU(0D{=DUzf*6~~0k9{E@YEzEM8;Vk$ z_jH_BDqMRZK~>*8$abxDyz?;C%W+|zu4V7`{y8Gb8}jeN%&GINAL$h0B+)c9hjGjF z2avZW61x=b?%OEE0?$OVolhBIiI%pXgcP}#icT2RB6{j2hj%FrUqQFKqAPOeGKABWz?FC!y^HDZIH zUTkEus;5ZH!FKpi z$Td|{1@}b$k~srL##Dz-dF@BdwVr3|`>r!>t*fX{>S;Hen#ZtU{^2{%+1neQKAH1^ zp}6sOR*=f$(Sk0n4Y!U33?$+SA0gX01pDS!A+{@~&`^Z=;C`Eyr zcjH<`$*ken9vIIw@;PU~w_T?D zjcISl?+guk<^^=gUcJfRy_3TT3l7rnu)4hKA5myYK2rcJXtXWS0X#RE{re*;_W1Na z*tNuHVWHQBhq~{o$4A71`2fvbaB(>S~m;Siq z^^!G!B8Qr)qW*8}HxJHeqOxH#bwrK-z}@{zsprdi)BlQfXNGs5wyG+ZMR4+YiEk(S z&HB%&7!^Icf+E4lr_6gU<$|RhTRsG|5T1`l{kIhw?_=!+! zZtmc^1J}{!?ZZBx+fv>qm{=BV7}XX|Pr78m8!$D{pSr`pG7aS?1=>*U)T3l?hEKLj z4aO{|Od8Va7%jHUofgPww<-g04XMw4nS-t}R`n>;-5n`z5c720DbE!~7L8gc?P{yd z`8Bn+_`Qc!0Pn$@TNCT}`NcUK=R4orl|=3qS; z;9x;mJ{-|B1liSlGkMbqOr}+Us(rdGA%Fe4_qW#2K)p|D(HPVKEmh>?{GEr7&!B76i zva``|Mm0Z2xfHM5@K9oydA18p@Rx6CLy~z_)Fy9gf-LO0XV0NA{FLvSUDuPMM!zNY z#k&{0;a1*5OFN4Kyz{PZyW_*(nbJ!yq9c*nS zq_KYHUDB?+1Y*WAu>2pQO)xMpDt)y)*JE(@r^pQfws8?1DeSzDU=pTlJmPEyFge90u-%odly0 z^{@VrCy$@OY!Q&sK?UZ)pqAUm@^FcKX6x-m->|{UxIR!P{X#p$BWnzwT?=5`XlF81 z8v{0r8u+quqRa7*XV8pcg|HuJ#VhSPU)>J6zS>hYV=Ue4yJG^n5FSp>rv}_72lQAr z?(p(>Qk2{D|4RGvK&aOD@tbrbMUoVW5{g0*MVL}4YgD!@p{yCon!%V`Qny5@ls!VS zCCk_bEmGOD#bA`OHkL4!G5nrW%}`zU`h7qCI%k~op7(v;=Y96&oJgJeus2S?XM7(7 zlJg{?TWNqtArl?F;Acz&dzI&?(U!I>U)GlpW&CP7 z=G7GLPA8QK%&fH#z3WncLLV_^7Z#mTHZ!-iOoVy!utF0-j+RlQDK8n##m}I6i6pao<&k8 zBAhGtq~;Chgs|NUs)I-#b@o?7OOlkVT1|Th$3a7rR-yiFA6q6x=>GCyL^@s-{yeWa%%o~$W?k&d_ zLGda($KA5nV-F?@eJ5r{Aj9DG6qXA5UO$zMGRz$s^&*M=rj&A&zyHi6#v^oK*2g|)-^ z_v}-14}p~lwz<*V?^OqsxX99PIakULCdE^#`jUuK+b^u4_!cW(Ze?|u1oZnp!`Hy_ zc@^SMl;r!%DL=&FUfAbQU(5OxN1pA7;P!rYoi}aUlLnP7IP=)#l*^Y{l-?_0XuLn#Py4*^5B+vMYDO96ox* zbF-^{+Cx*`x}mizv=k2A+%D92RyBuEdD_%_5%Bf4LQih6TA7|Tb?5v*nMB{u#YsdL z^2qhMLipUBB0~|;mbPtQDrC2UViN0^eHB*0=bfRUkwY+iALgq2oLupiv@Mtm?YM?w z6?WSRlTjl_d83xIo7lO4@ft&%jbt=tp%!Sb%`RQ|rLEeueCt_$}dauQ3xmc~Rk% zJjjmknK|x)Q~2V0_WOT3<*Ud(zjy}Rw1U}-<2SYR`)Uq4v0fquGAr+X4{;v&zRobm z>#9Z3URoBv3GDEd`@uaGU2mnihsw zP76lWzTNiMD`Ka;@TOV=a7=6N?XYa&tNTCz*VY-I2`?vzrHGSv>5hhqbbAUs$I8ko zi4ST8l*>#9ODqk*m-~V|M(gvTVVaChc8@b@DmCIwDJiMY1-@O1@3dS(#+cUh zs0+o-p*gpx2Tj@B(l2s5&_$@FUx?4p9~PIk_%4sTa7%wln10neR(vB@}V->^|a+a6n!|m4<$*L1@j&PlyLjYWGYl+;l zbS`cMWXij`YY9W?wn7^%$5xE=!LA$#tWCe*otzFc3oUisnof{-B{2)(ed$ z2wK;^lR_ycZ59Vx7Emf$uMx&7?+@-&oZNMEr*94JERBYtVl z4{oJr{YsYskapOqY8=REC}-fDMbRRvmU& zH2hI0Nk1+7+LyY-;O8%1cw?R=Yk?Ad0z#1>4x}zlo#z0M=}W$21Ee${%FxiRl0)wc zN!_@>BV8h|dlP8oc2M5kjYLR<0I{l+s2$}MhF~wzg?umC%yF}`9N6(IZ4*A(CPoe) z+=fYCeSLkcHok6+N(!EtJgI^B!_oFsCNul z@dB%=E=6)nrRk+ZV=$^~+j_Yt9&TCXR?OuAc3_A8`^F7DUENxe)J4x>q*V2N@ENRFR|fOj=}U=ws0RNoG%?(yFJng+WdwD4I|@ zqoQipl;s4tj!%HokY*Bwr}dX8yFEImZwLh(XkveLy7zXv_W>h%59;UBj0`fVyqr{N zQz-caYDjeXYMTO*b1aAqHF{`4MTO zZ;BbQ;Gj`B<@ruL^9FG%yBsV$7b>oHioCQ&KM|LZ$X=8Nkyg7S^4|32kNcHnNnj!( z60*TY!J}KoY?cy{rqIUgh#9xbp*flr8hFcN5WR72NJIFia(eTh`E@YC_EM&PX5tEt z4{pjnx1PAnQH8=cx5I8b+a=~^G`HxO)t4t;Zu5E9TIsE@Ypm;nQNa+#p|UAvD#lwZ zX^Z{=194$h(Ihi}A9*~mX^lF=-QE0IXsgP++Gy3_9IiU(nOQBKst81KmKf9_S3mSal%bHVK zTG}Wt4lK)Y+0VrVYLdOOmRH#np0uuGQwd7*wIS;fiX3}EE4?y>X$Ocng-H*Cpb8J8qnf?3s8&h0${dY*GrLl*axlVEC^<6)w zy1k0IWx&I}fD-aWA2Pa?@+?zV#jZ-Ct_iu*{eJ0Xy&38?)~Kx#n4Y&ie*m7H({1^7NOC$Tqnm`Vig7K(=AfeR=$KoZPEtfWl#g4S-XEauVLL5u^u+wZ zt(aA=^+WpL7YOVv?7vK`c+(>=wO1R%=6r{@abK0`(D8s_1dnMGX2-sCM06O$_gb|x5iRc#dJdNeu!acS~NNP(K%@I z)BL~+whlzQ$a7X}=74#n)5hwxA1GW2+v@X@o3#x&SeG3wdm@KY zNs6w;bM{0jaCk!o2zV>pMb|fJ1hq0Zb8&HTgQ_q}#nhKI+FW?GEdK^Baq&oZ2}hDc zU$(2M{;^9$JP^WMZCYyH-8090puRx+#w`BzXyvq-J)VPOV~s{&;+1#Y4t*8pT6zDO z6;ywh=U?2QDh;QyP)i(>{f7YTv6X7BvfDM zjq&s2=e^=?9ic_eaC)(+b?TMF<44I)gfIW;-+L*w)ZU=cTt2ln-A*9*qh62e3jDy< zme{}$?BfBs?KQ6=`0kv%oj@z0CiU%ZeyFTzc>ZPLm!6dYok9|Cn+`329zKDwRnkYa+*n)8}GXbgNPRL=7{kyuCwDbn-qx;ls(GR zCu@~_jH&9B#y7Pma%i~W1e-cvXM6r&Crrfao^L*}>f2162Q7RE_#6M|E~RhKI01q| zim=Q6n6qWR(#*UHEk0F`WC9cvvKmUZw`OW{O;4Mpl#iR;qndS4Z4K~SFcEvQTEpAW zNLncrbn9E5ERy^@{NZ$!KwE8TnQ~2M_;%HZt+JaA$*m~T;bAXqzf#(|0*}p^vefi) z*Bu=_qH`qg)B9_6(uw}%;~SUyb!9kbjQShO>5aK^qp_c266Is7da}eg(T>kWIaL@{ zzWy1RzD@q9HXMo3OC3MeQ?@b2b+X{YxIcXgu^W6jaKgYC&ExXo%4$WAbJo-$2o~G?6s`ZW)5%{_XjK{)fgym^N z8E5_)iC@v<6&{)UajRdw6Yo?*>q*!C+AjSnm7G?#$i2505?zT>gn*aE#R2MbPeJt1 zl2Gv$wBGq9Y4MSgw`La`x|W|!x-Un`6o9G%VuFIvLp*(cLg3nsREbFmK50l)HXKUq zpYA$9?0TA_l|;ufyD`c1tsAxFDFBv(hHji7IYpW%p5m@2qQjic04AGfVEKo$u2qeI*l; zeGvoJ_Szpn+ZuWyPZ+b!O2t+N&NKiWu%U)G*k6h_`FhxO=GN0yD|}Abj20;uIH&5y z1aqt#pq&xuu9^w8Q0C#`Op+Aw((CY&^x9(*UwDxibAo|7bMKEBf0O<7168bu$(Ew;$t5u@4l*iUUS#(;33>} zx|9Dj!6iXVJnpXfKF{I1ZSoIJ-X=M`NDx=9z0@>g-N?_!8Ji%9)%Di(6sR|Mf40Fy z&N(^z)0F3}$tYFLcS}mcv4=^P{mNQrKA)jD2bz4na)`ov?sZ4!YRYirwD)M&v}cWq zd`8te|B=K;$<-rirtj3viekk5O&{QkunC^!ct@{eiou@i-xYxgBBUttL06&2vl}(S zg&A%6XR=9T1-1ntJp@an(ZBofjuea48+cQ_4^lIgFa#wtS{&#f4n=6z){!wj(_@E^ zzTUVYWSYDzrKzyNCsosfFM!u6RnfN9cq~D>lvqU?pR6#-G*74P-Xe84WIg8QpYiNL ziD#TE*W9mdl^(NttZLy-kades_2{vqxtFGiei?HhsmA)7#OaxH@-|QGrsn2dCKj2F z1)!zFrD%Yz=U?u=s&jSn zbjx1q1V7cSJ8vDfI-78RS7l?7in5~j1ee>5#x(^GM3uaIg9|sayO)R ztjZ)gB_F?G$IRj`?R1>i!ZMF@HXhx&wK%{B?E)r}KUbN|J;>2LOMurYJvzp>;)}<~ z6HlEZer}z2Yyg#?Qr758_9rho=jrJpcQAW7dUA<^%jGEibd0vXPdqnKPt3AP7Srqr z=5ZsxEL~8vJQGIV^$@gcqcbh-OrGT{7bM8>5aO;Ah^u*5Kh91e+8yq)+%*)AfpE5j zXJJaijXo(Un4Mqt4y6zu+viKj<7aZ^8(w8cN{p)> zN!peA`XspnfDvY&-F2ofJus?zEbQ*1N12Bmj52kMj34vYGWY#&Tbd5myz6SUIT^=H zJSB~zk}z#;(OLKXvK^z?IYZ^leV?mfSDaW_B@3O`(O{#Xil^K(%};6 zSmk9h`Z=uzU1Z7H!KHWYh>>R6=LE2BkNY>==?o+mhtA`4#=T%3zqnX?ZdB6B!El7^ z8cK7`Rm$o%9X**th>3Y_x^Arj)wWku%kZ(QVNqmpfBzfu31PyZ;pO;({5R9mTje#B zm3LmEEkxS;rUXaB*ElSsxqtfFwxh>#ydhu)LX3_>mN7Jov=csiIEU6(k8!OzR+dz1 zHd7~cFl)J0*mCcGjqjfUv0!%*+V{aZVtcm2rT{p=G7-s_p87u z*>n(my`0oyZ|PeX0w=pOrd|Q1UMpRQv{;8u*yy@Vn9OmhEm|s@qX#_F`k0n7kq* zmMlbv0p5563Dmqd+pZ09El-_11ueYgp&Z`{$Yy~|vlBOO-c()E1L18D9q3wD+RKL~ zMVLJf?l*gELRI^clQ0%g&xaqO46HC8oipjVV5Ez?KYsJ|2Q3w|HoRx&JC$h19;1(O)-aF zU3@_%=x(YL%KfZEy?gtFo%X)OhSS_{!<&7a!p`ehx617FOZkq!P~JtXqT;xwto-8t zkfz!Rz~cyW8oq^|^gXWY3`KP@=}4OFiY%!4cOoq&9^6BRuiOd_=7wr{=Sx6OGI3K% zR?&62w;}K0waN`^^&8cD=zXI9YXhoT;G=wtZf=|lvtmUYEn(+ zI)6*`O(xE#!FalGrIBp#|xH%h=hoy}`0X8OGKB%dXBn=c%At<*)kq zQw^X;At*36>LnXIc=zs|N-CmtH{%`CpgyIF65`w}Ur?n|_{vlfrQa1F&^O69cx%hG z`0dTN4)z^>dV~1Vuj7wgKcFcnE4f7?UztwGt{l0%JVq#`lDTosEX2M`FLy$0KETgw= zO{`JMD@d?f%Eyh?CQZ2YAPUB(1{x!Ac?uqEAuD7OQ74O#hEk0H*VaJV0Xl3 z(V)6ER67fZlo4ua<2n>JXF0!&hQRLIw04TauuV0#;d6#%mX(#Y@b;z=77w)M^F%>8 zHEmu_^Z;wDCgU|0<06#!rbDSkEBNUn&HfMh1x10q%8--h=VB~vZ4N57<_ZK8b3{^0 zm8W+=@AXz!?dN0@u4V>==D!HCUG#yX5vV=NE_QB*mG=zUMlyaaZfCBnto#Vo{?9?##B(-@$N%;uYyh*LqV4`1 zg6MVGjq^cqcI~J2P&tYjv9-JD2!irqHsaiI>+e3agTp~;6s56Q{EnJ7W)*s1YeL2B zd-G2CK6pN>T3*X&FhCQHXCgnDgsjUBh_D&3>9ERJ2SuRy>rLZ9nA&M%w^S@BQrT>0 zwY|c1#?t1wSZ;*M@vi<@Da2S<&?+26H<$GG+N~E5FmoA!W;gdDBMY;^Vv-in_G}jT z^GzLhoP`CSV6i-uvG0P_>NstzRbGwF%eQaUz6=Z$Id{K*Z-C@vcu$C7MDbkcfdfZY z&;bThP2_y1MUMrT=ZmL2kkjR!jXuPHOFKU0!& zod_{z@DCTLY~&p5l5AbYfJe^l;mgP##Q^jODv8j)!z#b*GMK?%Qx?-z%QAZ2XQ`k~6~!uZ)BOsn&wI?{Ds+xXa))fPTJN>)}@7N<{dPA?=ac}}LS z$yT1Tc?@v=d?DD%^qkxi8Q4FII4+y3&&pcb+l$M}$;Hx!6C&M$2)c1{+{Z z02GbF1I7!OtvujF?T)1;v)=`rc=hTP;6!lb{s$}B*w}VRO9vnKBp30Zizu8njL*-1 z;gkaKZG1c6H2ZyhE*lx%^vukWni3%)As!qBWFDKPEg6F>cx!Vt&&`ZOKkvneHi%Hz zY&Q|c6V>`S5d7Y^wt5d-2dU$cUXsqXHB?WZG&vshK-MGL0)W~CK&@&ha8YM0rah&& zsmXA!_oNJ@@<~pg1j1{SvgY&oJ;4xwbANqU`~nWIBGAc!b#Vc+6IgC~3UI4=X4|%H z2jXA>F&Xjz9!xTiYSY0hwVFxNtnfP2*6<#bFvHSZS1 zkkgeQv9U#IM96L5?4lUc_~in!@IYY`oc&dI(;#+c413PWX)rtN>eZ`{8vB6M>b^6_ z5&>P((pncVPg|I$Hucg7LyimL!$GTa10$oqp=k!3fE|1G+z-pgONzBbCY{UQ_S>%f zLSzL|?TQdDD7l33AWmtSOjyPHmX_;kapyUWv^`CWeE6XR`4KU`w-1tJaeSQ(3&_o7`4#?;rzxXk!` z@lxhyGaEA#lK^PZ$uZeda6x*5vd?-TT2o4bVE@RP7cm(a%JS(X2wtRNcMN^5xD6}_ zP~X45LMD@KW~LGoOw&rCRtd(bchCVa%1hc+i2m&NxdwUT^bU+4-AC!_{&NNhac)Lo|)Y3YXWfWkMe$ODRl<5OyuU2cs>_*Ic#AZO` z7?Yj-cg|nM)6+gsHvd3u&0%8`u{$w(Ne6R{wUR5Gfr&>Z4D|mpF$N50FK{d$+#F{W z6r4H>l!t!_5?z7U#Ljc|P{GFngk`ZiY8EMf{ru>>TP8??Et`leA~K|Tmn}{{KF}_L zFP%W(PtofOP69e;X=Nn>LU=4KBS9L-TV?q1S$;h47G6F9w8cQQ&y=w;MNXTgP3~@P z5`U4ct*x(Ov@|sj0&L;1y);@funY`SP(x_m@#z1WSOer`Y^s$Z-?wwkA+TC55LKdA z*EgC2xp@Ex4mKE8n*J_hD!*U+KI~#9$F_p2Bp>Q_IJObpwbT2lAi`*9Yl}9Bjb{S? zkh?UyIrD)y$PobMRYf8*kVZ+c+AiyxGUDkusS^by#qWiMU4y&;o0%^?rofjmDhmG% z1?H#QKvMkN(-T3TL$o7<$~w(Z^qYBjcz`GHc`GOf^0DE&&h_@ssv5u17&@^T4}^8$ zar7~L!8SV$wLV^fRzjL~v#{9IJL-8`P1wqNC6L+0kGC^cH9v&cA!0%GlT0=GN2LsK z(0h6u>Nr?>c};-?dhFP-iw=U;39R_8v+b#~;sgB!`s5g>F)o0_Wi!)Zj!IIuaqlZ>I{E0)8u^GG|FL{T;>%=@)`8;L&v(A{!V>k`Nt)ZYzl1 z0mVeGr9DxGerD(S9`z>yIX1iCpf&IG81p<#fJb{(AMT^mBOH1OI|oNBf4Gvoyr*>% zbV-9$-~-Tekt76YvSDBIEbXMv>$k52>A<7c*|mra9FAbiRH;=^P#D;rb79zOug}zO zX!<5k(l|pxq=rNGmh{ihyLexe2s|piLqwB72VH~^LO}8!Gs&Ex6=@Sp1EB_xdj=s( z5%zO{^P$81JIdU>}}^ zDcqcQrxRE=w)l8cv}T3=IYa%t zh===t>8?0dy_k+MC{@HBm!6l$OHRwic3+qpKX+R#?gmBowh}CDq~d@oV`=kV;PwHD z=g=h@GM><11&T}!yOO~A^clBDxJuVX?}0Lqa+}ecF6ZGu_}iWT@T?4OL4% z5#)n_w(77y177o9;Cx^TW5*iX7*FuCfetG!Ef=7G z0{hG7{7#s@zdwQWr(+Rq275ufl_g1k6i@-QBM^`*F&G5^ifCiz#V>c%gx9QDV*!@@ zSQ_^kRTy0%>vUAg8$Pu5A83{PMssBJ_l-QC;W$Xrfd;1|! z?q5#7{d~U8E^EsjwX0dno+2jGirk)Alj+x!w@dMli%eLzJnjD1M2*K0*&t?!aA-jlFN62U9yFJ2egCm`r2t}X}LpLSpc#D0&j9+_gQZ+w(jB zQZQ#A22y;#K=A^xt(97$NFVzAmM0+W0kRCVOaT~llImj&wsjtTdB=}PfYxO6$L71h zc>xf*Fw__dif}_eBOXV8X6j#+t6@mw6wHhbQ3o>h^<8q%7>_QJ_href67Y2pm)$_kKa`k zRsBnTemr$dXU+ z7vDg*xZ_wTcm&{-jJC-JV#!|VhFNvRdKfH54e9ic*?z<7rhv3UAq0I<>Oi?DmNLVWN3)5n7JV5>5<4w=zM zw_me+&z`G@$&Ew`BtgGKoy6m*xk9BJ!Nom2wwW`imsn+le0M?1^N-3C=c!VfM3diV z{o5}QfH>}*59wwFFlh`A4;y@EhBjHvQGZ=q%g1*ut#DEdqz>nf_Lz%2;{Yvg60~wH zc?NWHj6o-VLHJJ^#Uz&78Mu79zfF)25TNN^umqi!E#?IKVE}l+b}J}g1`5C`X<%Tm z_OJl^n*_jorLO*l1zk3&7E!_5Plaw?|M!Kbud~7Fg5g$IDYHt^8e)jQD z>`+Z%vzdb)dY=U6Yx@C~$ zi%J7#f)TbApwj_575x1aqh#UGWbBbMp&t(k&br`DAA-K_?;DN^0gNwo}Uouo2u}EQJq9IzW|6@fu0{;uzG=XMNRhjJaLyLWQ032vbL5A?Eslbzb z_~7_xs>xHe`DRVMT3^UeSqGRYl=t0~uD9rS8ExLr{UlZZKy^ieC{EOx8XcrO(^WfY zSa$`H5+ftEl24#ct%OBiJnF{aKfgns{)-?19_@(;sQeB#-0fu#6Vl zMesL5ML<4hXXl#fCKbW$@VM>$OG-aOnLgT2N1zcLS3ZjUT0f4{&TT<{PSiJVj(9Fj}wwr}eoCEwIz!RnSE=u75C7Sv~tAVh9p?@K1gL;B&A1H1aAR4CU=3b~7gFMPu zFabibV2xWSJHWAH3cLZFg4G;2N|Z8RPw6Ylzn>(O8-kY#3K2h$s&TVZ>jw(B9D!1* z7kJZYzm-)Ct;CH3mx+jc-uoy2P1=__&7^cl`t)K~ekSJ2pi6nLjqhgvzTL&BC8^>q zZJ??m4l-HUk5FRO8yY8DM~}I!#reSCV<+EF&x;z2ddJkutU4#k`@5*7n=lIl(q%CaC|@1r%o|lWXCIG zDBDa6y(ZddkL&HqD=XQ*w6SlhM$B72Y{aO4M2eqQ5rl?EU8+=}#5zJPQOlP6$&V%h z!vH2Ywi(>7doO(549+s$M-PRWLO}K{D!9-6(+CVYF!usy4w8*Pylo!achE?!#O?DZ z5<@1T& z`O(S>3fF+HzMRHF(UEIuc)SW3@e?HLqXg~Y5E_Qv^H~6qB7nVRASI#o`xfKYvy6zf zw6QeQVa4z!)h=YW1=oe(N zWL8>g>MJBl<1x}p4J>ZX54#^Tw;^ha-fzqP742#aBK`jOV=3>E1N)9MF@Ht$u7Qbs z#qV=)T7pZuOgx#QhnO;6y*dO2e|Ig3J8DDF=}_Fok`?y>$npQpE%7?5_{4KE_@fHO zjetPCQ6)E1wY0Unnj1b3|2&DgSoSMuAevEu{{NhZ#b=(Afw0xEf9W3>5RKH`wg$21 zAV6OJztFkpU?=Lt#D(Ovw9?8-txTho1CUVK55W%>*8>B=2rVd;4Eypz-f(P|Mbanr z8$P?h@o&2yEcSy>Ls$VBg;99#U(wg&$K2Ix*~93@fuzq1IM)!pFU**&Pw|-CNKd2BD5Jcu|L%py93I= z6`*nAU+h?aGa1lVH#Ah5buCI5nz|a3#d`>9DR4CU^Rk? z8|Y8|3l{uBYpVTSx@~pJziC?kiSK0!WBy%9-0u68Scz%$>tvIk{B3c}v{WaG>0p%OI zi7ttXtGNWLBVaS#ef0iWApYs7J(U0&JIdPogI9N}MMLBkvUD=I(h-AZ;0DEBJI8CR zD|5nu0DLYuzJNh51LO04FVd^@1DWEOftYrH6#x~MM|3S5V aW|8^*L^lphSm+<{cjTbffz{Xw4dia5;C=A&%dM+2xmWdbueyea=x4tqVY@aK<|<|9 z21!aR7Yz-6te2gdUG<7_uEjlFs+~=8b9Z-tfBe>ljTDsBJGm8aZNRb9pD{{ExcMU5 zTl4G;z1<3NqMksAtS6>wrNyPDTJYEnKY>rj@B4-wK3&$(-o z7pUJ+QeRPvEi9B79UYB}kKbono1LAlQ|NSqk%{T*4LOEg$PmyUpV2D|)1FznF|d2$OG-abDE{qq}Q85A#HzRWUjO!8wptD@3ZG+XPd9K!E!>G@uFbv9<*qiA(N zH1PiY`)8bDoqtRg{U+)wDvIwE^n(ZYqKAN^?s2N4_+^|QpZ~b?x|NlmoI5dcdF73H zqsd4^qK1J%q_dv#D-yB8Ch#5|%js+hlH3A8;`ydYd27z4i{U*Vw|z!Gmh8np?OsB8 zw?j@8Js-tbb)5g6qZQr^0w(owr^M|CKNV>nW3^KE5j}9gHy|J&TmidwcSqjPK)I&m z-%lj_4P((QTlcpZlWp`U3mdyoOiWCSFx1r4JUIGRD#p?673ntJ!G{9!)82OLq=m}* zcqJ-A<T=wwyF{)f6T_A1HJ{dp+rs(q z{evBJc`O92)}3Ud+{ta5t7vmF;T8Gn;AH7{TGz$Amr)MUy1>em!Zg}4dwNd)G7=+(j1GY%hUi%xfT%OicY z%=GVGBjPD0<6ZZDQv2Ue`LhY`?}g`Wl}sj^KpB?q&6_tLno=%SMkSOQyI*K)?;-Zv zP)zoDRWYJp{2ycd{8R1Doz@F?$!3DPOyl6}T$y{LgNFt$s-G)-?NhjTx@)#wL;mfF zs#VW>9U-N3d1fcN+5e2}*Nn-3!!1McZlc{zk`Dc9{>O@zmX=Metx9HQW(8AmadF5N zef;E!fBySTJ7jlGc?`)kj+K0)5`7qmUF~B%JjY_KzB!uH7L#M41%K;io#hlh^M9F& z`Xn{potfNFk0>J|B1{%0J6VTRqh+NpWg5vP~%1P!NWcK=Za>mp!*%M`l9+Slqp6wjR9(UywXYQl9-`dpF z&)%rmLrnMv`^&D~RetCdlM5TwA~W{?T9@#LFi?i+)Ul`Nk?vz09vSg2C@8pYV^bHNlAbQylCH~8US7V> zfX_Xd4sTZ1ph~{Fx5~ayx$WaQJl7aWzBMWNBX8NR+%4>9<45_Qq7!8RhYa(cqtU+^ zGhdakgZ@t?%mz=cyql1=V`co$!2W(_?S2R?H21W3$|U!d!7-*ZrIbJgV z#8I-bv6-x|kyzjR`1W%{_SnJr1=HN zIj&8uqm~fD>@MR4$-YTG>mPsG9SpnuQQlT`4Bde9U<9yInU-|zzhnB(;)GvEg8YQf zSQz>b4Ci5mD2yCL$hHys6F=>t*ac=E>g2m9MmEZ=TJZH3CKdn3w>RLjSYUbG?GK>w z;4MW3iq6hX1kE~f^$^oTA|CzyV)EZyF$5q!mcUQ$P|s=Sh{TEv!@{`yeCd`9!##X_ zd?%uMBl{pYSDPRDKMcbyCWHj%cNQ1OKDaww5sDS?d%km#QbF=ps~_*rx;aq&Hd_9L z-Mfi9CWrobe_1#!tiFY+_M6>g*7{Y`8PtKMv4aIOV zF)`_mXywTr@Zb3`#Eveh*; zTaGz?f$Xv)qFRw`P0*qK--p1s-c9tKwz*99L8<+(EL$_$3Y~2}Madjx7S`FBqA8Rn z1p#|Nk`*;k$_m5Sfh`ITQ|jEi@>-v7AbSY%HrzNZHQubX(Tdy{syK+<5M|f~+lS=U z@;o(l)Xt(11I})j)N1EcMbnV{(F<3v_GOox`a4VB7yZ)G!Yt!F>G$M-_GvpiyNZ+V zCf?&6`O)K}?)Qf55p5uN6}@weH{ecmuU?bH&ZlLqmaORf9o+hZ6m4v5#@k;D0K(;2 zT9_MYjL*$I62Ga3C|mI2EFW1w?t#6%qwcdVdX69YaD$mxIW~p4=i%5!HSyWeH2W0E zoWEB!@swl!M(+alLF&LQM~_4G z^WW{%?^jl$?kPm{9F#C?dOZr;ph4RHX42_f@tR%Y54xZA`(1;O$=|Ws%Ac<_ zHlQLByxiGWtF@QYdx~tZGS$qYoUO~k@ZtYB-S=*a;^N}^wzlvtf6ssYZPzSdp71Y} zXzOu{eWiePwj2KP-0$jz6io!|2^~04r+eFWjt4@z(wT`J*Ci2CAQkL+;!4S(G5pBQJn{>a8*zYTyNwATRKW z2Gq$z;5PjnaTqG3CY$|$lkA?PqpK}k58b%ilzZQId}-$t6PFHMYx|t5M~uIC|N)DjN?Kb}@-`udhkh=}zZlmM6^C?rA9cQ9~$Z&>;}6)mM}2 z*NT)~r&%n$6VE4;I!m0J`#_xNSSgxauDTZz)e*u$c;F6>rCsYvHhQr^3V(n9EVH_3 z`Bq>D{h^{=SPBQUj1i(Ei{Og5u8fSfrCR5TAnf{reSkD~#9uCc&{mtwD}gW+4$lvh(!uQm;M}*;yU6U5aLweD`%jJpsZ(7$j7+&^eonhai2Rv5$<7s~X6=FI+ z+RO^^lWVr-%5n7S%pLgR*?;C(Ti5dU_jfL&7B6(Y@Oa0t`EU!_*8LHiaN{&ctpkKq z?{IzmP^4sgiYHK(L1z-*=^fnzhk&>Ljs_P(G5LBj|Cg`qjwk~XnWz2wC(Ev{LcTRh+WwlbVSyy+$F5-`+cn=FE3V|;faKy`$+;)H zy6^t0nw3Wa&J@2q{e{}BrejfbbNzIER^0q}&5+1mzy4U-f^lVX(YHIWo_%-X_;B@zG z#ha~j6CL=8RLQ*9aoKzCHYRH>`mkSy`#JDOz7$oH6IBN%fA7+~ z(bO~(Kpl29BKQwEtwzs$MP7KLM+0QH2Wi>iRk3Mn#^w3k{#u#%ffwxz#@DRQynbynx{J(1@r{P-n0NJFbd2uT2rj*dYd@vGze@;Sa1 zcFi9IlC7A6A3fKyrxcZ5D;+Qd`>C$Wjk1&YQVwE1d8z+ndcd34D{;x0y#jAP6fBbz z78bTcRyXuCII3U>*L4jm#|CSo_Ruj4KhzXD{QaaZ`(8ry zDbSRBH|A)r}A*Cf$0!&x>)iOYVO9jso%)YAfd{0ZusG`bGIjy z%R0%eh)fGeze1-8pW@_BPtm1FPXrl5CapKji)jb{y4M*;K6f?>IXStJo$g9XN~+I} zh>&g<=H*EpEM2|XL#*Gx6)5e#&&2BJ=G}n@Un>9hUT#sU0QtG|FcSOT4-dz%1nipG zNsao4L*g4z7W?_0vV1CNznS(`_}h)QWjVxpwr5|}xNzZ+wblP9pmuM=<>uxBmvZt` zr1Wgl92CfVZ=6Gig;ji6(E4H^tUtcc{ey5b3x-`~vdI3!Z20fd{r5JKMe)ZaS^f&Em+*x2HFlAiT`sPNxseY0na{LV(B z)!toorsRDx1Sp?m9-f>GNJ>fq&hxmDI4~B?0~dtJEU{Gy3TG*cT6EhDXzT4=&Y1C~ z?++e$^_rWdyDs(!rlzykv!6qi)<0*XdgVvy2XVZ%wiY^KUQNK^Z+l?t-en+k51rv} zmDwV6+JPZi^dz?$#!iHl`fb82{=-gcue@X<<~sFyfN z;&J?7=TrczwvqJXi)3Zd&-k(!Uj}&mGx z1!_LripB{P%6TLRXa3qHGf(VB62qd!J0V{*iuQ7l?dC@uxai#6HjnnJ_4!zA#a(-& z_2ssO5%q=qFGXOIYoyQJSCXk;|5a)6zbZ>odlmg$X*)|X<;{G_McyM41G*h0ys^b>3_LK5+NsgF-m zpv!#mVt0>~se6I#N}HShjRcC~T|sOkytU{^8Ak&Fb$+b1atyP+>{1~S9aO&txGVnj zEt5DokvWu?mI+e7Sz8^-A~|M`*$AiF{Y$%?7FU)mhVq1Z8Q=iY+apHCI4{J^CAp z+?kZ;cHlAY6FC3?I;|&M9ch?Q%cK}U$J;aaS=*rA?8)Jy-Ru%Z#BBB{Me-^LTm?s9 zfWBcMcuK`|UuB(OMqC^Zhpl?zg?#Nf>H|Oq?2T zAY#|Aq);vBHfkTU$9HXL{Zr;OP1KlvuJOl>xI0^RoIY{l#2oyi`!`gQ+(^Diqu}a;guk>BT3j1`qn{78X7g6&1r1YSFtq5qeoeUtj-Aj42&{ zsPXlsm*_WeiwWbN-|x`Z(=&nHpmFIE^H2=dE8#-dSvKY(G*%V7j%!ik^q#PBIT0gw zaBW!0wEA_7;TMu+z<=%VXdCWIUk<=oK(%s14nQ_4Pqi5h$6%na=+nJQ-i!Tcj(dB* z!`;m-?)me*+c{-jQe*nJ-3GROzya%nR$-L6P+Ju*k4hP7hh@$ArDga;I2T*Wp3Np_ zW5FoM{;)0zC1@3u#sffuHY+o989%3W-PcdIU9laABoDo=`^3U+5lkmbY%{Iz>WZ#! z^ziZ#+oo$fWj>&M!R^z|M)>8rNgLr^Jovn1nk?vu%d)I6N|3d=QpyQ!(`Ms^(@CV3g*z z9oFym>6~)MoaQTUOezm{9E+P#RPEO8QPl$+!3<+B;&y8d`j5G)e z301$`T=9ynhbaCbml5@FN@~Brvh(jIl<)l_@=QYXOZf`%>d+YUV9OFhf3`v+cI9JG zo5#{Xz2kS|(@gejlT#+OmKd3UX5EOt_DCTGf($_O7T-+~BDT_7?rRE2BERFqZY_R- z{OK>DX#BeYH_foyB2R9q#RGVZ7@LE<_*?o2BLMAq%!x~A3|uBfE$KCUqJDKg(=1(f zDMj6%&zZ36R0*~0cJ1U?P>O0J zPvT--6eqUf1?F@ACG&*k@|g@~25*y<;S8r@=X)NQu5^g%R7Q0F=MES;mio#H3e51P0V6A?hINr_xXxnpH z_$QLm`tHO=mW_B`&1bG33s{(@`t}q{Y879Pnz~CKauE}V-BP@{Wg1WqB4~OX8d{Nk zwI;5hAfiJT>8sI`S?TgZMpNG3cN2n;LoOI2I% z&V2oX#pLe?*}a$mw6~zEIJSs1l!$aOIJiTKZ*Z0FSwi{plDe zMpMu6AC0IE(R=cA2gN=byt9MDNrcYrj#F5HF3XuMgifA=T+vh(C@UCCQ3!xtMMOQ# zW0G3{zI<}2Qn@ejk{m`L@qvoZw*O;L_@S$3kIzdQeTMWGR^&*Q^o>7Jo~E}}_pvfJ z_ZHF5oztCyCa6h}A#LTjp5C7ZEA)?<+U!X4c5}}k9Ab`IULC58+kthl^37uV@2YcG zQUt^-{WTCOfmgsogL?GSa9V1r5GZ%FY)JuE zPXOPTazh0D*qyssa8`FaLf!>(DR3fsEZ$)+Vvm}SUH%(pRO8I}F(sSA;@j&b>uY}P z0_#;VAA)73{Nj9kH1yivka_hF0LUWcFnr#vl~@w6G&`gOoblw*pm-)){Lt_{4Q8@+ zyQ0pm4?X8K7bS!)zzy1cCX<@;kzl6u*BDG(-lXF z?c=?HSlJ}mFo{C~!KVd6nT>d!AF9zde z!qlQ6^vr?%Fb~{+G3f(D0v?(?nfuTRmG_V_BO?r8H(rq;bai%ejJ5ut7q;U1Kl`vs zT$H=W3Z@K;x)t`~x{cVQB(@ zSR9B>8sVVg7Eni+ne&tR!AA|8)q{?ZBY@``Z7xL0@~cHK)`W=$_T$NXc1h5-H>=X5 z=7}~@clkDegVuOy3`_2*?R(k8Nj{vORtEUzuCKPR>2U09*IV7)&R*D%b}&qunZ#1qXbpYaU3yZu~2nCQ{Z3@;d{tR^xh?a z@Xrl3NWYy7`9bl1nG0Y@o8_ZNj#PYlDzPu$FpA6s`8=VP;7ZxQhydS=)A->xFFsqF{A*stE?PgwJh^ai<5*Kr5e_H5s0eb%-j*3f1gk+}??*rjXFm}QD@#Dux$R>Ep zq%FUH2E9TT>ss=jo-FD-vDw8({djs*MwyB@c~-p*s(HP+iGyw zNoN(6)B5(^tApXBbrSYoQ-;xh_8N{x_>tAw(D9b&@vmMP@dX9PIIPqsKTPb#f*(wm zZWcmsDp(oj-GR354GqAB_Lku`jZ6mHEQ=!E10wzE&Iq!z6ePNFul1F_FGov)#A8R* z*Cj&!|BMzKHvBhbC5gIF~PY$V|44@IuCGbP>sSSaQdKgvk@J#YpM z?tD{C3!WnxW)zh7dBlu<;2A`T0VIV^kxQ1%@{WNxRupBU*z%)sF`l=!{K@rVicU75 zDTO{(T}sCiG2*^s-Gs^S14 z`UOPwMCTi1hi^cM;pT4oBPM))CQ%)}&)L;jF0!rrm*WPz+)*4X-b&Y zs@j~pq^bGXpYL-JB0Cqp6G2W++*CJ~eLs<({G10Bg81V=W#e^-*lDkRdMxBph94hj zUJ_@A)K4E5kC(B+vGf*^qO4LW~*^zB7wTWRyY-24i_t+AQH-lv1 zbk%Ou18B9rE#BXjH9sIa^}3h}-^JD_T9|%bzm)}zc92Z5kt(<@9&kb3a1oSp$O?eM znBhEcsoud=TX!$R9nEMk!<|gU={Z-QH&cBe9+W$VL$>cG>O2M|;^UhYtc6nFZX7*_GF!+K8>`{uv>@)ROBgVR0OQTqu*4FtF{;eu05?E_0e zLi7%8Wq-8)04JD{k&!o^U1I{;<@%0i1b$1G9wNg2e*OBj7dby=CO4)_atie@^_uCg z(jAd)b+!iOTp*Ntm&-`xI7BY(7(kXiYi`UbqnYjQ<)a?Kx0O zZ5mN)MHr&y=4Pr^%-*BC1f!4I+BRfEj4SJO?&fgray8?XNnP(KCFz5xW{2w#u|M*# zWlO^Q>4h$Lo7MIhk}mUsacru=cKj3+)xg|5={juOoT>#4|HJ(J%&3As_B++Fg$ZAz zLUZ7f4z3?3jAaJ4XL>pI>>K{C#8yxc*Do>D+uM75{;}1!OVAH|k+pds0PxbJ0o@aH z!s9lhLKJwSUemsfqN}9~#Z%?>(X)}4?{)0pl4oZza=BbkXX81hkCd;0%60j>t<}36 zQUEXPOTMQH2joma!E?t;;+pDrVU!>m(#Uwpe2diFXPawHn0YfSv&v+N%msPE=MKv> zTa=?BKDdkOoHcu>7273UUFlsk{3q+6pzS?mNv1%1&vM3z5xZ1_;VfPHY}1R7{bL!0 z2RY7i)z(gI+qP}Q*yHBvu#$og2qSw~j@*^77bmP0c9RYsJ9g|)LHIF8i*%hV6Y5S@ zGMK80i&t2)8_(;x|7nYlj|oBxdrp_PkwqOyAi^|=hDgQ!DgQ<8cAO`m(BvcA4~UAY zcZ(OjctNeb5!9qC-%d5tqkSrS|Mx^u&;9a{qbe9;7C$VGLZ8O#j&WWO5tK>`cI8ak z2{kHC)}>P=E4^k4E4q@050?W!U;@?ZbR0{uU`D}cYI+yvL6-LuaDLJkSV5v|3bUvY z`)jkh+QF-m=)KHvCKg{PlWXLt71@@}7eA)kYQQkNwl*d3=>DbupjtRnga`-v&-E#n zfwB|$BZSWKuvVKOQ3IZ|Ks(1R#Zrnw=cxdeqHk37?d`0P-i|i*%=YiL&Lj0a;0i$6 zWh2tTHjQ{Zej%S260_Q$Hx%t|0;+1={9}l(uysIkN$I3IXEWE&LLFR2p2klwwXJxo ze^{&YI@0$>c_@knfvRVRYB@$9lZkhJ1eJFZ_8cehF%b2;1NT_x?Unls-Kstj8&?$rkLmJ}onYUN zKICvG0lQ8bsf?M89Qq)juvE2|m4CK$oitS^HH63?ZDzV})`-|ms`F~8#7*Ph4k?Gh0qk1!ax~}!L@HK@srRO>6T;!WT zF}95A$c?XzRog)>g2)*l2r{`WFl5R>b>;lo5iM=O9jD=y$?0}zRLe3c_gQSgmoNdT zkX#EhlWR|rrKu6XP1GDLM9%XCY1I7ABiQxj)>2M&k6wl?S~iCSQ)Vmn*o-@SWWYJU ze?q=__BOPNo7G0@yt!TcXWAXJE!}|w?wXJLhJ&8Wf4g=J=MW@vFuy<8;rsFd%+gue5oPsb?~(2CR*}Cu z5Bs$-npxmn9&AW6qNVR#?EX*L9${ zPIAsA2L{|f1bEr(_?GtKAXT47QTR--Dv){b%?aT8M090ev#wBTTS)fR` z66M2|5Ayc^9K6NdW^ftP?`G>JO*;2Mo7VT4O^I}TY5i8bfUlurv)1&p?p6Nig`%Ny z$N_RD-8G`6vXI+iUiT2Yy1E<$6=>#SJP{BI1?9e_2{iCi#8N~7y%!o*B3Tf~`FZ!D zh5LI+yK&iWM# z+oyn1FsY4{-j^%(Qx@~l6W8x+ltK`_cn?zX$Gy0H3daG#6&)5^MtOcF7_iwpu!TtNaw{Urg0q1vgcxh!%xOxu} zfSXRKmnUy&oxG5c5Kk7~^zFkKdj3Cq;Jg@x`&5Yx5j$zmN>bI!5en_{bbkCPT5hly z4!lX{Q~e39Kk9WO>OY0W~7q`tne1)bu-+60rbaN+G=l;EN}2OwT1N$N{?+x^`{NOn&z1qQd&ndO~IC zq+_Np-pu^LTMt^iK(T-fUO*;q!4aqe0cH_B%~y3I{;1$6=7Q@hUH7yq9*j_kJg>=E zelh9f$auSkrY`GiqowNbnRK&lUfIF{jMjBLNh!Z#5wt^&@?2m@)b#}PZEQlzF5@H& zqA>vadhi;VB3Q^&S}LV+8v3^W;YMF7cFs)^vFs`>#4Yy)7J7%;Q#> zuCJDDiL)AM2wxSz(udT_h+fcj+jjWEE>H;59*ZFx1vO&;a#RJuG|Jn~N95{lkka4e=@tas8NZ#myr|>7EG;!Yhzm(k2e=MTMn8NO12slAJ zCZqrj6kyC|bPf&<3C@-_mXHVBeyb*cTHD%#uIOG-+f zM5rN4W+tX`B%FcH-Skq}y_*>1W{S)pS~6cZzDu#hX086Us}ze}R*NYK==YD7wjcC6 zUpew8W>NbkDz3D=wELch@z2Gq@*pL{nZ!7ts8U5sq!7i+V-QTrRR$_`o?=O?Ir{`? zP0ZR%BwsFQAK$E&uCr8n%|08punqvFlVED9Pec3b_?g>uCZn@4Tp=+tkB{fH*MHgh zpky{mia3T*S_$B&_nfFKBTGWf|D$ipObr zF9YKGsibYkKyys^=Ls>ohT|9CBWDUrq9n+s&aF;4BTb0jX#)rM^z`%&y@3t8hmPgo zr;xN*RTPrizE)FuvawR0xtKJrb4k+mrtsQFr8tjrpSHQxq2#wd$*SJ7Ty8Jai$IuR zG9=Tr>qhC?{H;7Kb$31C1rk~(n(Pc(_pCuCN3?)Myza8n(P*l2?bE~N9rEFCn>`n85%t6Hbt_ecP$AJk^Du+p zt`s?%4+4P#&lf_mEBN7w(X)a3!T6!;V7U4OW!Bk=m3{%!Zn=fXW%ukx_vRQzTS`Rv&HJkJ- z4vqqzSub{&BshGLrKyhbWbb~pH@B3SgZS<8^B)OwZFi)CbZ%O{^by0G%5zQ*3G0%; z(tGFIxLvF;s0x?`v2@18u}ktjG#c(x#jJgIJLm?UrtKhGP;RkT$k|dLn~^g%_O?I7 z8=N} zw-z#LoWt6x{4*)rsp9&%tiUL@^h{g#O2}Gmz8H33KsfQ^uVehHurmUrICi&hxHb}Q zM*^2|Xy=sQrlK=}(@gITD_j{=0pQ&>w4Fc` zM#em}jA!#ad5mOGte7C>Z+%kd+2)vaS7Fizf#n+q+T}bOL3(LFMD&bVbKq5|5;q^H z)|sBqj0s7>7t0-y?PIOC?>*^8fG)9AlKlG8`=rkAbICDZX}p%!*Sa;P^D3jn!yv7g zNBtM+oHhok3_)b}E&4`A(Ip2Q2h1_qbC%Bm<8)!w-7{M98zBV8 z==Z|G)kZI{&1t=DHeMka*C(HKF}}vkM%Z7%ue9g`16%r(v$3^yqN97U;yNgS8v^SJ z1|z~37O)D&_zt6$uh&<~Mb~U=9b3zb@Fk9A_RD)-jkwnN)_Sfq><~p7CqUoM`8|g= zW|AY%@0b4g;o}~ptK*6Fz{Y0AL8ZnDa@qiBjuee3KhFogGsYnD>d{mOm39E|i^y543o%Jg|L658464R)cRK>vrRkAgB@l3M2FG82RqfSK zzSHlBepCC~g1Xnulj`aPWxSfvcWde#d5_O7mo7b0s8+%pcS=E_soC=vvV@MH00aIUvEfws5#oS zxU5|~+H?*y{+k*CM{WW02@$!DRiVnV9OO)AoSIa;@HsiBK*P4&Er2~I-_nW|2#oS5 z%EW5J5nBjes!tE`C7p|k*e;G7Tqr()nOW(tt6D#&82tT&vaboG-B0bR^m_@;Wi@3$WiHWVIivZ7apDr=-cj9UMB@ zSG?2I|Io;a+o_vKBQdAzxNPb>wRf+M)9Z7&^5&NIY#UK9yD>zBCOK(+44XKl`p;O6 z{6hZ4nj`;8OV6%5(_hOZy<_#Sobqth3*m30z%F~?@Av=w}IfwmK(p0 zj!#_uq;MSay}-wNEo3S~{%pm)4?1LIWcsoyImaZ*UV*CAL9h(fxGP(vweo0rjdY3~ zcKIqS*N4xHo5j42ecw&89xqrLoC^o%2sCsvcaS`i#Fgn<=WbG=f;nbTLPHL`f z(}>;0wHZ;<=}P&~HRrnNzO0^J-+26M2~szmO`%8P(B<-+lVf5fv<=QE ze7l8Q4+eBLqNNP};zqAyV{I+J?^D;j($q$Q179{)S$6RDmt3!pLylkYW;$zU7_dS; zdls8j2shFw%CwTHJ}Q*BmuBVw-8E*G-ds7XZF6#Up>wc8sV23Z8T7ijFP6x_Aoma@ zEdaamuhEoygY^qyJpYx}5C-LjqJwCEcje%o3w?m8QYDv96im3n*-G)T2+LaKFN-_Y zcYa=9&Kwbk`>LD`u%7Im!_VjXBr;2m4FW@UE1|=PG2@2 znY|pG%IkSrCz~U)5?naxGYWOCXYF+Nx_oXlb1r5j4Rb0rA)$N8soTwxeR=Sxy4*oR z*HJA~Q`1$bCC@x)gI>wn0S*&&Co^Zimx=)J-0%w_Zx?vyyrBO7aXAH)VjLYN>15G? zo#o6V+a>4&gN98mzM+4+9yD)irbnM>pMf-W&*3m#E(_jYuuUZmb-dS<_xvyjNv6NO zy)&Y}iC+nFg0NAM)HUFJPQOFT9lse+JSdre*+wc^AoZ+gsz|n8EZy?6ja5+W&RP!m8dHr`d_bLCRKu=+k3)1`<1u$`OBQc<& z!bSM$SYTzfjh94q*ue?=45XmS1wL|Dah2IotW+q$)l3uPG0obi-tFoIEFF`*P2O|k z7;Z>jBZcOCGT8!qi3mwJBFZ(@S$NdO{hZN7ete|5SFr73`?~xRzTbH!_*fZ}JR>W%ock7u(?^9U4JnmNK-XK%XqNREAkj>3c z?j0Q_E#0f1S^Mau32PnQYe#}(Vt|_&QFN!bg35f)f`BWeB!pxEDRP6%6M@p9x)|(e zGPI33E+~+kF<6xfzy3)~6-PPT#Ks7^i*xIds|zEg&z?Q&gN~hMdo;*Rs!N}o6_NDs3 za}#fjfX7UB)(g}e^`pyLk6D){b~(1Dl&ZN7N+1Gzj#JIe_4)43Z{X2(pNpr-LzL1ijb0K*Te2CQzhi?9Jq`oa;+VTHQwWkS;vx8pWYN2j~@TNc2_`lFI>wa zcBw}Hr=X|bU-2d;Mq-`oTG!)@^GLZQrNX^L;XHF{vM~_2%|wiEQmvc9MowHk+|I}) zqC1PO9&RbtQX|%_y>$RhM5)59P;K)-wDwGSBx9lg6eDWo;?B;j`O&n-zGXVRK%gTu zFJ-!?1Fn;n>gq&{G#MqLbkm)SOULH`)n(*#+$ZOf@k!O5yY<1yGH9QtP-NY7gZCZyy+Y=P9JNdWUc}oob9>dRJD%D@w6;X&@x$W*2aj8 zx-02J4!b#HrDDHyb%l z5_C1QSLRzWnOZK|OjG96+_yGR{QB3e*VG9~NoV0`0ntb)YB$I3-NV8vrX1UO6mJ&Z zv0}W;gZ^wh_4$~SfikCV7IHe@3*V`@VI$?wf7z&=0svg@8H0|`Kk#a94R@*D>w$brVA)UKv!4ylIvx-uhl|%9OPd? zKzCa(mBHx%LC4XitZI*pV=vBnXft(b%@o3aG1Jr2m()D8-8%pniu90rweM`+X5dJt zbM&|6z=l%Zx6ayXPdQ5+{;GVW>22t7u-T2>J!qT3r!+CQ`iY~@?5NORZBtj&IASK!9VY|GYzOVC+8*_n>NV%hfU`5TMovnnPwtr=0F zAG%U53Z&@cGx(A(r?XK<$~d1hF*Q9v-;E{BYrp)bG%;-!=m$&X$zr$pV0l;pymhC= zPLVLFf(-+r?4Db^xqdI(IUIptFmYFmz9q^Y8)dG=iU6+l*jhQ>&u&(fg)i2-v*UOoA zap#jt{iLO(^>~!*?6M@S2|5vy<|ex^n~(qYVB~RBXC)*C=5AA6a2S2en4EBCcA%zQ zMwT#qY9KL@9<(6R93=Y~1K+CUQ=yh5u0X*iKk*@2}C*d9) zH}J}Eax3SGQ*fKeyVRQF!66}6r@D%nnAWr!3KR7jlhkr}owb?``3lk=@Dd0F;lr|h zXp?TB*i1265?i3~Vv@ngDkvxj)X3V;@7=PdI%C~B(Xw+l+LgF(-Abf1fU|-{MFtlx zUd-{C2+JKFzAjXuJ9?@@3S|tiWe>fLtmUF+jaI@dx>Y^iv`7;8_4E?_J9S=L}#IMSXo)w z*X>pF+l3xIeVW2on3n0w)KwRwfEjCkv4yw5VI)pYtR84;jVeA)PR<<8u#MzP=u5$J z&|v3$v~JY6hq=A8b69xzZZPCVx{Zdkj|dqxH}(qt#~D><^W1J09=kxwEL}UqJx?UI z$mjJA=JR20_}xQ=H9K4+#w#eno8eS-^_%USj$>y#y+|Kqc>W=HdL#()ojQcKeiGN; z@3Zk;x66sK6B3MPl$BG?Twfnaj!B4(jlHA_iBbel;DIw1EvXg{?%iv)kUi*Rjq_X~ znkR31ad%aPSLEG++ox- zy|BQdMeW;|;8HxSajV}+Zjx4fFDk^s40JThnnOBfXJ$Zgyzg`xOG}!zIdMWt*%zM<$4H|Oqc1AG*~3I&Olu3jiv8r-8nGXb&hFp*~4 zw&v9Aw7W#>&H`m1B`jr`S$IJ7E3QE^1$(a*gKaLc_*zs{^yZ}V{8vq;PB5_B^xRzf zh^@hcKbGA|<%XoF9NBj`(p#yZ;2iCLLr} zOa_o>Am6YZw(2U%Z_31!R+Jb#L_d6x?y*rG_fTtQ*tlU~g4o{UuqRIuI?MM->3HbB zd30-!^&_`Un;)7LyAAFb{UFz@wp1s-q6&%$UI^un{QUgbULFw>JD=wBlD@rJyEVhm zQgS=XUgLnWsnYd>-JT0kR-FY}5c{vy^6{?_Y~OGDYPnD=GxZp@asDM!J8|^JlFC$c zb5+%aDu@d4#@$UKb2;rHt*DXI7&wv?SC zlasYUL(J|u;ycj~Zn~t%5mRE_d29)aO1=)f&C#V;Ypq#ergg0gM)=`Yp}}VTFO?!l_3Y@+=-8$pLpQo=GjQLr8e@N*U@>QWvQJk zt=+;Vd7T?nf=rG!kM7@!MuNxedsF>NK1g=461JTrNGqQ^7Yd@o5D9k|morzcBp_E? zSJaDhP#k99&M&@ZZ9rz@bNkO9uU)ntgRQit*yGgym=?9CC|kCjZPR-0u8{fHXt>^6RPTw?lW})Yyt7SQe6XEEi2kdL7E`dO1FZFU# ziSq_zQFNIRZn6t&YSNVUTy{v@xV*S{#+O;-LtUME4BcKK%G90Q`B7oiC^v!7daIG{ z5y3jI94h0R{U3K}aNRa+hqotlsGm83-~?N_jq{nepN)w;W7-EVyTl@>s`@x@3+JPo z`*wsM@fzKqqF@!?Z2GE|GS!Cw&2FLKuXMDusZ3|z-`|!9!e706#KOq}-z|1&iEwgo zCtQIR3!Qll6$hl6$_ecs7)X@cc@r+%sD8BfgjC8)JvWEbfAEPSh9dR4mWM}C|Im;& zTeuq+2Pfx2AaIxUHq>*U-v&`94R=bLd{s79GIHm4E|#REZr{Iu|LM~9BDiM)Q(9tb zEv11>;op1`D}f7XOja2T71^vo_5TR_?szWS_x%qcBUvFU%Bbv6WWLE>$=*~(w#>3= zs6^R2GNQM=S5_sXWbYX&Tgi&>J8xM}e|&#`Jg=8WyxsS8o!2>z^El3H$RR-T&99)( zNkxhR5SyPr6J3`DQTkc2%_X%W9KvJA!ob!(!uT$>=}mnV6_ujwG+xZltUqRQsx7yT zvW%(?m0t+!WSL6K$S72MZJI!@r5$P#O9KV-!w;96gK~2#j}vs3@0|MdDkd#0O;TD~ z-rhdf^PZ^-7CQq(5o}^A%)`!t7zGj&rjpp<1aKwt%F03FM>U#Hv#>~a<~{h2{ic_p zzVVMVG@2(|{1ZLUqjiRYE5c_cJLC7L;2WOHmvx4{w>^Ka&*VsH#9b{*ftt8fp zva+(D_&b)in|S+DFaNpPM;Qsi7^~(nwhQW z#^?bgZrmO9JzB`5r*S<94qO)*H0gXICbFvlRZ`6g$f=kYq~g2v{1|fJ@oe|rAYCF+ zUvjN9E)owDw^uwdB}K9#A({T7l9Jx=PmdzSn8AaiA)+UJ$RH8ZY<&!l zEZk1g%t`}LI4PK~XoA>qYqE|Q9 z0w`TZ^v{ngb8JFF1GAI!m8*tSq8_EkPIA}GT1`S?@CqB$d93KN49V4LzGZ0XU4J(L zuz4s{$Xef3*AFKdK7m;3UtKh6H*fs<^{WG2w6VV4e-87Nc#R8e#K7m6=)(>c9)6Yy z<>21+1E__NHXKW)gYkPDzRJ&?)QT`g4*h6u9BO{JGGwjyru0$k^=>`Y?<)fw{LysM z{SXQxS`Fiwbi+{@r2RX|#vJiQwKJpCn0a}5i$Ck>ts3WHu4YDel7^p<+>Q?8*#t5_ZH${K-rsn2wnAT}2HwTFl zw>u#Og>c9pn$oW&rvS2LW+WqnMVwxV6ts`$5r$|=O3M3L4Ej5x7|{Z^&k!X=aY(~Y z?A3%=){KeDO5oq}n@v9X`NTsGQ9>r%ad<;u?|YRY0RGB^4JpD}U0igyM*!3Fu8=;t z`*ca-kZa@7%!%l*tF~eILPx(gx4s`*QxPM167wRWBA z!j1b_M~}w3Q*9EXAX3&pqmR5QwyD0cy~fW-G#nKZ!sNUM6f`M zg93;)*5FGdWo^Hk9yr0BuSS;;2UA@)eeQ~L%9n5s$RuILXq~_1H??*$#1|#@V@`iz zEwMDJ!$u;;Fc$v!IJ0d7@p&#*9^9;-ye+buN9jBD8d%2Vu3n8SbNt?98J_9AUf6dV za?c^%)Ro$MM`Jw+=}1sumLSCqYZ2Sl-+g6r3UH+8(_p(7b0?p`8VkhzZ}mQ%?MK{`yUsF`5&m&mAHa21sCoOPY;A3I zQ*oE2{^MHE*viVWEYTxgR;?G(-CZARm*!4mIJI6G(of(u5Ayg?do<+vb7M`(s;Vj; z>t1f;R1N~?+05X|SuA33-cT9B_*MB~&sBrV?kkx(wFqOH$D*BSs=p{hXLIWQesqC_ z{eZ1r`xvQq9m6XQ%6 zzZ3WnD+kG|RoW#;6r#!5!~eCGNW2pi6!O;AnQ*lVRYUq}FK7%=$1oxR6&Xq`NvJy% z@L@}`!GbERW_dFt51zl~1!mg!=Fq1^Vtlx@2$)u79bLMyF~BRF?3kezD+(EaPTq|N zf7ZsInbq}VXmL?pc1Sr!#q&OM%L$HiJ(-H!CDukym;kD(u5Qwe**St2%Ayp)X;2>3 zm7siRn@h`U;Ak+NKR?BT;~bMOsL?ktFwk{ZyE*{e-252V|013pHXqzlKg3pYKW35~ z$_F;^CT9B>dHyiU6{W;$Xq1tT>JFjK}(fylK z8WEfq-x@fCY$1bz8ex3J?}3-9!gBQmJFu#f$#8SA4!O8Yw&%~EGeCcVlAoX7qBA`h zL5?;=2r;xMVNJV?Ff#X%v>mr-j{#YjfpMtLnM2;#<%H~=wd;)=E#Ak@r1Km5+^<|q zqGPP^m*lHl&$08B9zZ{~cjw-|mBpWi;J6!^mj*_CB8O zjf#>I*YM3Lx7TNr?`&oG;c__VTKFvp$`X@3w3?_k9(ud+XLMDOLBOa_5Zc&#NS` zjeW&7u@Mthx5uRm_&z+PV(dt}8VStm*#Dj}fe-||NJ&j?1UNxz)3692K|EYs`xH}R zHq3IUe+(!GP{gz(s+7~4OO?ZmN*YGe!iTx&9(>B=|@?do#FBeka!`4QNt znDPC+|2Q}Xz0OwbccBuPWzGUs_<#LS#5)=CI-ahkF(`k_whuF zxEE`d<)dGb4t8n9!|P2q?U>c>y0?a-5TIY+w!~+EaV_-4#l_q6O%-mty7p-N!MgW< zqDUpUH|rR%v9Wdi++jM?iuuczFG(pVSRet3h=0_!Z#YmlyhMGT9}3~KjcaR&X^uTx zTQX$Uk?y)MoW)!OcN-R*K`)OZ~)->9M51_on!KJirHUC>*Zz;t|#piUU_eD}}K zdQ*T%HC9rO9CEjA#0`y&ZKuAmb8=py3M#jIHJ|W$;}-0G`U`M2UB8kJ=MdfG=O{@W zu4Gw#n&dnW@$hR2(6|i{4Bc`LkerAF9}?ui?W~Le{*PBmkpnlz6G^3?K7VuM=rOa( z>8g#C#-~)50$BL@wKAUm0U?#T8?OO&Cm`NbVqR|sZ`adZ3V8Myd2?pCvVwDN0S$5k zb-bjlY&XEwzXA_GJ)ev2(8}cc`v`u~9-?;5X1*NLtri`cF+< zQ;T?<&kw`H!X7~t?Tllte&_@_oqJwo86Kxo+RDJQ@JcE5cg4aJSM8{-WKI5dv8}b6 z(L%1-pnTYV?NkLN)yJn)yb~|n=kwh3fdU7m8%wUkS9y-cO~7TsC17J4@8gjblARY8 z7Dh=OFK$C|Nb5Rp%d=u!6PD~ggkrby)px?Kn$#WQ1Q+80spmm6&nP! zQ2Kym()<5n{{U5+cav1i{~o7cFwZ2vh^r=T$O?5#r|-K&R+zvVIAdHy^b8!y!p zR$Ou_s`ItAwJXOXf0NkXfoGxfBGB1?kex?LWb}0)x!rM1c$+}Vu5nJ#w0-0Q3CSUI z6C@S*z0?u%d&m`s1bf6S1KPVI)4^5STN{fYiILOS*H3j^o@~3KU|Bs^Jdk;cj0}0& zizK~8R*?~-RoCA=WaUZ_xSf>l@BG%Q*ZeIga8zJ4#|&03PU(W=k? zEUKJduNgT8>Wp`$s6i&b6K_C5D9^RJyc`ZAX&T@nJgrcRQXKe@+_IX*uOGiQ^N)0f zJYcm#ucyk}d(Y<8Tc2ViI|#?6*(ev6VkRc0NAmXkU4uhIMMp1Ok&w`*d=k!RjEy|2 zPt)^%o^>4wGhQ3PF)^%gDo${5acyANeme9+of3%?gO?xEUs8P1(SA%CkBV1X;zM9Y z-DJ2Cnp6znzl#7JXBXat)>;wP8ps}NE%Ug!VS9`TeW9km3j5%{hspTu>#ZN($3? z4vwrS?I90M`lZ8fXwT#eotKIC_wl5!*k1Ck!UC(Vi{y2k*XPI+;pHu8&+FQt4ae<& zr9=}@U*iM2)X`Sd1z~r($db}&oGz6os@xeYI7Dl_>e0=PN23Ne4nkBno5)Itk>9kyks(T3XQk7 z_W<@g#lwc8%JAi-Khwgf_`Pe{)B-9oZ+=K{$W;GXw5#6KgxpBWv}+7*mC4fG0Jwu) zQ0yKOP2EUT5;%ZKB%|PvlW720GLPdo#cK&0tp{sNoO>Sy`B?g2@ZyWQM1{Py7T!FB zliX}@YTe7GP6s=_^A#PWCAJkxDqa0Vbb?Hv<-iF=z-P!@N-HV`I2p_i;U0+(F{jux z8=|EGj%Badb}OEVjJ12DWW6A z5etwx(VK4?0F-AX7%z5<$3sKO5k@}p01I3>(DA(zi`m}Jqhv7QMzW++vUb)l)drjj z`6R?^PD4<3ePnY+cJGJ&ZisI`f^N`M#u$M5fD^9q3WkA+_b?!yrU0^#6m&f8aGJ;O z`)j60p-F*@YKxZU_ML`tII?G zDV!UDfEw^;rZDDbvClj~qdZ0C)LlsmPW^L`&V9~z>ON>l8K1_`2owyCD}Ihn!K?P$FYbP$y1TjDBPDWDeg~Q= z)i;LGqC1DsJ1xc%8q$?-mf97Np89Ra@q)XCSN8sbPXcW)&@%405u_2PaIV|>*z)P?5b)Xp-o1UBaxGcW{T+ zD!VFr;bb4wGLJpBJ#YV7%KVuL$x^Z+BpqJBu?fAIKK@yw{TsAtEQN_Ek@J(yfTVYK z7aPyAZ34kTdvLbu1AV|=f`wF%l4o$w$6M%K? zxW7{#Kg6}Z-`K|#eH8GJZZ2Fs9hhAveh-I~gyf6rDRv4B8N~Ztb9o}LpWy#Jsg~@J zWd}~NyIcndkM^>|`^h^n=@Y51^{hE@4m-6#S zM~~A!f323*1gtY9Lp`{3IGW$?h45knW7nw!f*oVqG8*m8yUAnPbOJ7EP)KD*KSPgY zD~Bc@SZ(P;l)U^Cpj)ly*SX!fb8Ge0ba&PaHEt#;#!+aB57l0JYX8rZ@74#Iw;!Mr zLF8fPGzk&!+G7z2R)5n;a6#4_&*^E{egbVEERsf%Ze=V$)vm_J(toM;D1Ac!SJkbh z$zK8YoTu8QK*G!ffK>L%+TX@1&`manHk#OS)SDdP){+Jge5C*vl=~ofl=>imgQm}U zn1`ZgV{Dw5zM%?5G-s|`#3P@ZP?gU|ZAf<>Z28VtU67JgQfq6@yFs7u2@w%jyu3!k zBj_4K^O#Mh=EtEQ*XMlx=RH}-@;f3NcBmIwn!hz?P-uYwWd}Tf;ScgTG`wa{frqaG zB{TY>X#CCsp(%O+4HVv7>L8_|vC4OZ3o;P1PZH%#I#_OjYSi`XFVo%Cp<+$)q5#^1 zPZh$JSluF~`{yKLBjwirk{&!%p+AL={RplYhY<%0OV-J$@PXNllZO@?O(C%TH8Nyz z@gokMh@W2y@b1Sb$<&q^wr6fHPRK=bU-yIlZ`;I01Y@@w7Dg(@zVY@Qj5Bc^6HY0D zr~jS^y{c$9J3r3}dXwO@FYY9*li43o34Pw-fkN^LYq2Ew&`p3(v$sXgNE~_!*nD4I zSbakU6oHW!!nTl?=Ml6FJ#Cs3xyJ=yQA&@xe%J6|oOR|c)K0i` zVusYBD^Yz;tS>jC&0n+yUFPo+bed#XfL1Xwt-$P=!cKF@w;%5f+*`lcuD~S+^+2QV z3%BX>9F6e@41iH>OjaF(Av+jqlaT_sZxFd~+Zi8JDmb`bn1}gzkT=@9LA+TmsROQ& z1JFE@eTx7I{Ij{aOvy)bX!F8R(=$0AjS@V~a#^;6=$IYq@NYZ1@>^8`gQ*;*7%G6r zQCy)1_>^6@@KNlX+2eKu$I8vDfw(EjoV(ChP(M-gOnC88rhZv_J{j);Xz$a7<>25T zIb_Ak$=Qw0tAGFg5sbL$`gYS8em@IRz~W`IOaEPM3?U>1Ji5gCO1+B@h?#*b|NFhR zc8gvDJzjg5d#ingVIwVJ;(ge8Y5$-*-|6tmzfu&u@?4)vGX*7O_=@MRW_|>cGz*l0 zmJ1x=8Qk=i(};un{i)%K5~ca6mCox~VsG*!7>e+V( z$R(t7bT+}4PeMsJ3m`(p=Bf|wflt`^DihpZMYyk(fXA-e8?}UTtPF6-x}Khrhm4L? zhmHX>WfkO^zI^d#-fj^i6f|(&-fW-fGjATFfzBLURM&4Z0@G+4-##EnHLCVHczyx| zy#`vivBMeXm_bS-kJHmyhnBhu3!i`hkQXQrq>oqul?Q>_jl{_aF>yO(p{+ulcl&VZ z4e#s22yN-?ks$~y9jw;+)==JsgQvEVk%jVYKLyTxSkq_vabmVT73azZpB-oOi2Kzy z)R!`y`ay5j2%}!U4%k&+>{|d5Qv|a@ge>5Z7b9w-cGk0qSmms3dMLkQQDP#)Z)kjc zg&>+)$F7fb-u~7q#&W((OHN23>Ld$eJ1t-y?b#!Gq%ZP_b3?&ET>Q*+|1ppOq?s-> z6Z0trSYqG5D?p;30t19DQu$dOdTee5l!nza`b(c~jpRo2rVfv68%_xzl-l$sbJg2h z6^&ldJA8wb?q+pJQx0Bu12VTtT>~}}AC(XK2V87>Vgsw;P;M3jI-SQ%EG+Vx znwqI+rZMV}D6v!0*n7Zfqw^-x!PtAXzsU!R9M0y<1~W8um|%zt)V#?HsK>_->bfu3 zA!*9tnR5e#-6VqLefd(-fz-}@jaMQK6Kzv+^vhInj?+&5P~Is{?6G}; z!PfAONQ@nLlNZYdgBfL-U>2inh{FR)EUUe2X$a56++0CI!Y^Xf7F||Rp`fiDb^reT zNlq_JiU0Y=AYE}sq3pe%-d$&VV&p|kl5uxhw!3z~hW}^z_xBLXl%#SQ`&>SwV#PoG zg%d%R1!kjU_XyqNo2lAMSy{oO?>X$x#w$Zcdk`y zcB`kZ0J?D7kug4+k_7WJ0&MWkvsxWWbCA_5RfPP_5PAiF?Ey)@iha<%*{mf-eVBsI zAr0hgl1~SZwLqH$m_AJ~5LWlP^U{bwO_A4-UhtV1g zJOTp85b}a!doK?ZCn#0BSc@aW!=sOV>gZ4d-Ye6&bFxOYh!fCOhsOwT;Q5#Qdzv)&u>6`ew8pQ)i$=VX^bIG$BF+O0*q1Ruvf^&p{;o!v|QXeJMjA z3u4P!oN1qAKZOJx6<@e5ph2B%+e}}-9RLIt*m$Q_a?(qC$0AY8Hzb5qPF9w9+3-#N zt9cSBY3U~j=f}s#5our!ZhV|RbdV8GBzb?rrQVAQLbW`w8cfX0w`U;m6K0)@yX@UF+kmL5M1Loluu;D}YZ zLY?0PT~?*+xz}kgLI9VY^qRxkA^NH~`a;HjZTpmoiAfag1i*@67A&Vi(7!+FKi>Ob z$bO-JfRMx5J3815a{qQh{5B-Af94y9WsI8Z}&dFXTt-73uE;u@@Dlha6i>N7T+@zfR!oYI*sppT_RZ zX=tdG^ifCQ?tE+&<}}8}JAb0sV`DIBGbEbVyq{mzY`^PItAbpJ8xk9K{4IBRMHB`ri)v)yabY2fXE{aDg z-+R5$xJeM?8y$TGTpPc7d$lb<{Sg)!8GGz!L5pZ8R5N`Jc%OE-v57}~Hx{amI;$~W zQRB@E_A*KAg+G5X6{4tm;ARC5eEg_@oF{JX)-T;sHMrVZC{Nq3W<%$lcmx63?!$e% z_dC1iF&F8WbQct@Gyq46TL5zq4&;Uk@40gg{T;lbdp6+Xa}PgGzet{kl9TVzaI!Mp zWBn?94^XG94X=)Pa{+(;Qkm+q1%4T zpr4pQCSQyjuAM?U0JN*a4cD8PK)YB>a9<$b9=mbR&gi0T93K_$tFaa>Akr~PKjp@w zA|W{qy|OwNoxrg}%N7x%l0UxsuN^T*t1Evd_FRIM=dDe|lBjHtMceI#XM0?_$FR^9BOKb*ZpK^`q@Uqa1sWcM`qkm1=I)jz%zn#y2&6dcZ+&*!j1 z@df$&#mL$f4}Ur+9ejL5us|s`Q9ocC`g~CT-qiL`qVMdjZbbwD1t-1;9MqU&x5wT; z&cD@m#+}{w^3H0~O8Q{A9_>5#b}vn+z|}9c7bhhnONE<)0D`uTJQ;NYVyGUxZ~d@X z(*EK8YmeN(>2cwGKDh&d{dImm_Xwjz1HdA0@rNLuD~0@C5;aq1)=bjRP9kq8}kSuIuRNp!mYQPu(+i^#v9@LWYOD z)FLlE;a-2S&BvB2E+bT!sG6S$qWDIH@y6~c**&bjmPl=<#9h9#u)XTQ<{Y#ZWDG@i z>hoE9%MF(@ZfA7cgU$ZD3>QE3vmfeFcrm_0+5EEm3{Mh_(7Gy7z;~&fhG} z1t0dg^7nMqM?k>krKKODO(>MG(QmB(tU+X|#hh~_*#Fqk zOiZ-H2Jm8zMNpEGo`Iavx!bgW6Y55U&7_Gk{RbPy@I;E4oXuPlK4_!%UxU%Ib)t~K~woT0xCXx zc2$Z#d{z`FE%Dh=xjVnR#A>YUw;{Cf=G~FsZbPWC-AvC{mjF_eCiwl7HSdKsjnhdD z4YJo(ZIEOFuJv^hm{&~b#0Z)0OH!UPAX2`GZM9RfL8qmN*mMJVrh{Nc>|zUr@E(dUHZ z_E*&znC!<1dMF$Mb^ga1*vgQne>V_j+ebe1^+#7tKfbq`QccEpcUyWc17Yp_5@0a$ zz{N6!fq3Meoh{Ev@aBOf*G@XfwdFn@mBD1Wx63t!NJ|w9 z8(SPfJUg|K61d~`>3?D$3#ehXn>Sl+;DUk@J++w{xZSdlk+UmD>ynt57)Nb1JPW*uSKUc1 zmeLW>!nA{~GkHdZ_uR0sZa$yegZ4Skx=+M0l8m!e)KLEvmJWR{6-yxyd%tl?88_ zrOV@AnQvZw5mw4;{?t(H#(P|(6U@2s!cBV-WbWx}yy2r>Q+TK=50AC6W*hZ`!s;sw z4vz%z)6zSWv|A>Sni<%|g-DEsE?#=m9QrlZZzS7VnIB?0(!L>L2YYdpzzjHi_H6HQJfI&CTDRiT0BnpZoA2tI80$-f({P)7q7s+b)e?3 z(4m7bN=*YMloM>7-tvRCH93VTc|bpvY`NCP0^ASN0Nlh>=uP!|+ksYPzG}mEZq=aNDHvW>BaVg7rk@Yt6RlJtDll+5 z>Oun95I-^y2#j1al6DCesz-T|y9@Y$U!QbH>XSZ_+Dielu{$kH{>ljTNzB1)INiN7 zXRwKBp*YDzijxXwtf0M;;BN#mM!K%w2Zn-aU!+mSLZ;h)9tn<1*Vps)tIz z?2@w`>8~i^le@~V-9Utm&GU8gS~7w9;|av9Qv(2)H8O!4xRKNR42IOHrYX|_@8Kyz zxY`&7<{AQS>teffsV^gXNe%rp)}MxoNm_V6ruzew=*F|rA{kAt=y;$>LB{v0MF~Vj z`r5`oebqH>3djP&HX_O1ifx+X{45OVMYMI7nLlj)mf>ze?^6ppOU^jy7UMDlFC0PgR)HL?wS>Qt!fBbAUt)C5YP zA~8MS!zsoITuX?RPzPz-Y5SE~ojEN3fIz?uXuHT&wmH+i=@pAcyf&2F?Vs#tb3n%# zvbxsQA4pDCelk{YZWi2Po3h|eLEMcH6{yiq{~OC064@YAbS|RPB$U>8tEjAeNl*rq z)XYpw@BeH0%~+r0Y+Hog)Po3VSiB->{k?7%-+ldh@hW52AR>e51A zi@@!j>MKY)Msq21j42W7H#sGxuBz%Ab@)JUo-iGEg>DFV^yJMx2#(B>qxggiZ7SJQU!cpno%7ios=25J~ z+;6xDjo>S=6E=_LCe%QD*EISvJwV|&v|%B|5-j`Q$Gu=Gf)AYkTV4GH1qEz`SK~uy zsHk*){wO)sBcTYqVOnr*LiM8g`2V$TUwLFDvLgN0i8VDE)T<5qfcjh16wP|!@xJXa zB+~n$Lk3nkb(yxzU|L+sp^|@5_P-8xTF%kreLiy&y$8ds!tr*HxF5d5&dAM?%dX zElW<(kuh$43I4$I!5g3c=57;%)-3^U9u+h-mLT1rnTA;x?dU8cYsebM=H@*6_%xVH zT0kZB!fV}PE(Y+xkFXY2WGp>re0&IDiAyl@1C%a6ZiqCPo@Tr4R!x*-*UNTI(AWy8 zM=paIr=+E62^I+wmO#A(@bAqT;%Fjx7syClD2F{Ff>1?RO;Y#YKKzfu$;S)+N>7Vn zFAwSR%UQrpo+|etT-3}v_}BlOhhY5u0o|sh6_h9 zEbK%wa#2(G(NlN+cYg0^)g)n}&pluNeP!s%g|5zxX~6tJDNr~$cnmpHQ3&OyOm%7R z-0uFCy*3BX5OS=7u@;dmI)QDb^ED$PN)iSq2D2nf$MY{|$lF%K@ONZBM*qc} zs&%w55aTGGMPqN%}W68@T%dNcpBKg5%0Lnxl`K?35 zQI2gbW*tS{`G1CqLa4heor0Aq~}JHKmvh(XV0pF)Fx#20+W-$FLM*oSp1 z`N{t@x}g$aW@SZ>y_~na`gTWJ_W<$2+~?l?vuBf6Vb3<_9%nJCcFDqoFQ)0d$MJ17u+;pRh)BU(g~I7g2Ll=tQ6g0KX^&w!Gc zx#yT+zFBL5;Hqyp1rKL)B@C9Gk zIMEmy=u(bYFTn5~UbO)`m@%wBn#2CvCo05uw#{^I7%Vdw0PjF*^96F;{y%t|U}p`S z5C=HzPogx6T*7J`uyc|6hJ=cbV10QC%dKIYsW9{#_yDPxSkfiI# z?nk;7B2c}~&RWk^(_FGX2koM+kYS^{U&$Xod)Bk%0Uc&lKue80m&4&IzQ`Y+JNLK% z6=wi)NNa+Ys7+{ZG_;H@5#IS6AyuuguSLfz80K9N=rTW2UA@BHRTnDxi6+=^FJv?C^>+j+ZQtxHZlJOnsg&=5){ zeLQZ<9K2T}gyKbo4puGB>O?0*yvovN4y6~cuQ9_%`x&UHJjcSqQvdWDbbd1PkknrW zq_ppL`cZa-fEW!0SYJ;oa4B{>-ZkN8P6D>Dq7s(3(t3rc5oBMZ^0b-cyQav_kf>aw zkv4!0Tm=yK?$u;UWZ>T-S0N&waWD0<~A}hv9 zyX76U9aJS>r!#UQ5Scx+7K+A)fi(cEiRsf*(EckvGYP~v1L}*G6WRd`y8a{$pFSbO zOLVr@#)*$nZm-T24j=RSh( zQ(QM8KJ=QIEGiITL-X?TzrMw`*#b`>3!{y)C=^VOWMH{2C#IllY|(H)ob$nf%?-f7 zy$DbmRlILXfnuPn#>jh<`6$t;u);#VGW#!nPigo+PhcY;Bn;uu^6&;Z2LQ0gE?{bs ztpP0g^;N7b>9S8%Ua`}ZDwU8+X4f}!U|Rfb3n*hO`&{bkk9V}wA;kP4K*^xG~>ifnV@H_UM660QVp@fQ%SY4n*RgHDN*eBi`S>tnsXtf&l$wSP4W_yXP=NyU4w+xw*lX3=bNeFP2>^DaG;V68 z1-xE;ML7~F*sF?*(7m~#e2b?%;3(~sq<@<GykUYEW}Rpy+pvjiU3N#`OSf zHXneiCkpE;b8JU&ju8V1W3EM=`4gfEFNR5CZRQ|4Z-Imf#y9oL3+~$ zkjh1vvDR(r!MT^z*ORI=&VqS5z)iXzF^TZ-F5D#zzM1v>7V?}VAp>{G{{j*FWwt;i zY?X3#9fe*Zy1{jQ$wE#+0g28Ez$B>qV8(E8k~)wV?8!0Wx+?lR1>tFA1ZAg1fc61y zd3p}r)o4BoQaF|Uv^T_S6fwfzYysI$7QnnZ@@esK1dd%GA_I(wpTA_xeY)@=Orh=k z)He0d=PQ|(KuoV60e2#HW@xpTUEtoQ-;AP>qm+T)glJZo zo53%!0BZ-_yn`z)KE^LB9$sG4pJR3X8?{X^?`>$}rT-~(`n2uvdv-Im%D1wAkQ_?VeZOn*>&K5)*4u9G z?m~0@&^g$vb@+W39Z2~3ZQLMFXYErTiqj$wTkZv@7p5hER`OZw6-8Y2D~XwziYp5v zT!^X^BAk$r9>CJ601zdija(Ln4FIXv2_%_%;`0^TWq$B{$?6p2Z)|Lwd)vsMB&3W{ zPulND#u*{{4MY(!{k=CJ3#34#r%q*W(kdWMnbrXIL1sjJ?7y!WheBy2Kq-^}Bok>p zLa@Bt*T;+RgHrZdxH9J^!`c{Wy3?3(tlXX~Xp|e%87OWXirq=)IrwZd`W@itOF70$MHOwj?Qp2AoWA66D>$jd^>UQf6Xzom4n>$xhwM z6i=Q$4I3RDwKTYD4pxq8LBjl9*GC619I`L=B))*FJ(9=0*2SdmaG`OIGykWc-nU)( zcYeCMgDOJldH8UeUH9$2FQ?TTEg=#M^SNk+=<7&3vtny+fE+Og###}bp00!|L#_hY z$OH}M>Or@eET+;K&v%cIw9?+*7g*hmP2p^T*<*0&R``XR9|YF$@%Dt;pU7q5eBuyN zKY|>kEV6aycW{w9=SD2UFpBJCJu>=X%2+K2)KVISzRfjI!l|GU0gM zB@GTc7+l=n5(ubg2y~EwN9T!!WDtE6FlB)l(EyjVu|U}5(?&sWU;>h{a1eZ4{xFf zX{%L#@dNNlGNHhU4haimLR*f(8F6Mn;U4<+(ib)JmmQfVlb;=>FzIT z2LQl?mwckC(Cd?L^|%YJ~po1RfROCPF_OAif|| zCsg6WuuZP}xPQ&uUL3)vu5Cv^f316B+S9`WXpPeDk7AI-t26}Sa(3aseun?onpz*% z0IqEUpo#+mV1tH$jg`0iQrRZJd=UVl^-r+M+4eLN_;Bz1e4I2Y)n3rh(=_di`Dt8% zFqEeJliBK3Lkn$vYvR>KUh|YMYd;a0xW8^kcr6UNP#2Omycq5?`sK?@<}xnr+?tm? zQh!P8>l7*p{zFh&O5a1Ks}zMw(f(9F;h90UOE51YYiMcdIi<|T&YtO%__r7uA6e|b z?TC=I65(x*ms;FMv^@tIh(Nv%I?=1gz}15Oy$uu*XU?2qjZhnyaJe`P$+TUK8swd5 zOdL?({%LB{nw`G)JuYth=7Mr!#<`aIXJUPFvb{%qb02bGiK|?zt$w1;k?y0}rrO%w zo=~*DvDuWDuHns~lIN#8W6{-LiOsJ1S zD<+188rery<7idPhVQ;;5t1|eCi<(&G~~q#+nkz5h>{dJ-Nd=CYmDaKsFmCHPmm3D zKf%{&El7Lwr(Ud|Z?W~=`sh6(WNZVE3-tN8s|rP6+*UhWJlZOBL*ei5Q=jJsRoU;x zt6n$CdqAan7NnatCeN(*8bz9Tw1Q3zQF)cNU%3j#CpS$1HHU$dy5u;U$Vn)sNGu)d zes{(G&?H3)kL|tK> zTu?kSJJ*lMV@~UfT1HGWKgY!@AL>WFi(`YJ5Myy>@D!lD&NBKMao1cmeX&iQ*oxW7 z6UV9YQ5qWIKSzH9c=3G&dYWNzakQs+{4*OK?!L_EC0`=3KPr$ux)CEu~j8u7g1}WZlCnLo1w2<^&Y?3#-*GtvB0wF(RY2 z-YUt-UDyH?+Oa`dxiM6LBsZW2Zkhe+3zGtYu7E>$9;o>UNBizXu#BJWM;u%M4b<6) zDBw9*tgRp0znd3{hLS%SCiC;RzVuO1YytELo#r068?gr)c# zuoq`u@ik&Ykq&puNWqo$BQ$xFn^B+b`#@C;#6SKjARw4|kW*3yRN3cvTUNk5<4Db2 z+~CVVoGXC}==EMHNQidX1TuCbf7MSyw&My3yXMh~N__KXP@7OwYjv?_>4g9z=D4 zq#`RKMySZ*o?nI6JCai2%$R9>aoWpRdkEsh^xUmKI>}W`i_6WrS=78?3%DfLCuZ~< z%~vr|QSgpCbTR z79M-dGyL9?=ZB&*>drM6c6~8BvC%KToS>a?9r~PLw z7NJ6O4gPMYF#mQ*MmYd=P~fPC}GIf&C+RG}QnyFT(YxL%0_&T==P< zHwR4)M4YcI>wA(Uw-N=!s#F+1_Xuunv*j_fAS#+_B6BV%hE{Cd!nFR&m3kN4UJaDd za4BTB$e3i&)6={qa7TG<_DeF#zY#KsqP2y1>4AKKoWtjDKlFjn-8V=%#I#|e% z!@Iw~Mh4!z8pVA&Q-{-;VimY}U6WU|G+ISrFxoX#wbq~bk&lsFk)T_wxM1V(_kbt% zVJ%^Qf($-ZIY^B%jG_Q|HwJKXaF6wE2LvRm!2{bCx*qoE@RTep;vbLTola5RqD(0> zZ#jj~O)Xdi-Q5AOHh9i_em|MmCP`;I7bqtmdfc^=jHJ1-T8tyjaU>M#r-lWu)rv>! z`2(M!<_&>cF{!V|8x3x~qu){iiuf!A=TC;wbH3!DWCwBm)2QW*sr-+e1VUSY4ZP4Z zy$=0NhgxjP`$LpMXN=8#fqSL~8lX|Ku}36~PZy9fU&#Ne^+76+^N|(-CMN| zNy=182(<{w8+?s1={{h3Z3`t#;TW-9!m`uOfu;!ou z0WTh5ZAlBdiA05knf%#=%j0b&AC%huJWYgkhU6re1-oAHCvA?5d2>~!O;3>gs;a0k z@Q-*Du8R5SolAUl0vrN(R{M#fgayoc9WS<6$%Sh^3# z*!L^A8bVBjm;_d+9pYxdoRu9<7arEsQ_Y%IwN?ZWtTJ-%uvF?*At$7z?^w__V_gag zTJE>SVu3auvJ{~g=xGmb^=Wt+$)45NGlx(w;~L$Dx=ZRQ{@ zfa@(rt{NYa?8?&P2ioiLlOXn+B>M+@QT0wCsD-B9XoLRk_ z-Muu$ptouxN(vpSifd(Op;uHC-aaJk#_$i+&tPAi!V-BK5~7c)`V zmTp3_-Snh2FoEPtuSM{^Eo=PFKSRlqY{4qC zpXL{qR@1jc2|Jr83#LbJF3vjogwqU3RNH@q|()2LY&i)yq znQ=}w6vMGB&n*9Z?1of_l~^UtvCdEPfy;s-+QF+Znhb_pwm!)X6upwiTfyJG!B}|} zzq7E^z}%kSYF+4blulyRmAqfBcC<~KLtp`t^o4qD61(4s5AS*NrT>A0ciQl@EwZ~| z8$ui_Z4zhLbeUXU4vtKD^y;5)N}SOfg2gh0R9ieTmrU&R4TDS!i6fxl0JM-N$^~WURoF#Ip&%xVp|hqSPS2hVeKbnu?51FcAxN7*O$G~Lp1)2`oq&374~z5+2T3a)WufW zWztSXeh-zjBwHhUle*62b-0mc1>$yodht<)&Bfd0`|85Nut2YKY}f85$SmrM>dt@Z zpSqahg>Biq8U3)@ecXN~JIVA^wgHo~R@)Pi6G8><9AI$AdBM}WyQrIhn|z)*u+I#tL0KIExm0=V}6#MU8<{s&zf2|l3_T}I+JGnV0demvubV3=X(IfA6pQd zqt%A)oadnx@-!x%70)zWjjB|k$}(As;csE0>5w>)@uVM2N~h4TvLO#ps*i?--9*RzDhF@5*kuycLp?~_ zI=EwxOZQ$Fb0tq7vE=aMW+Ux!)L0<8R~a@+be2>oP^kB)N3*AQnu{41|MYLtS?odJ zjWnVEA7kGgk9GULpF5t6$|j|fT|z?f{r-7AKEnMT*L7a!d7Q_29E(F`SZpg=;qhCf|^kQ+c z9b=!TJ$JN6x>j`7=<>wRt-EfdC?vcqNQv~*VAC9IKNk13ziD@@eiX0M^-tk-E+bme z?>@;RCi=RM=K3jrnfqaI-8}}2tMY;8@uRoGT}<*p=g zW_~jsgonS6q2TS#_QYcrhYi?kT&^VZ0)o+yrkx*UP3p<}w0D4jK^~&?53Qc3sriA1J=EBxxx<4uwf0$N zP(t6b`S&&V@#}oNa%GL(jm8CI$-`{f_~zGoO-c99)hQ#%`HCv;*xGW}ud)03^~Q&kk^Dk7Tvv{Yg`|Uu zJ}?v~eUZsAaxYwt*YAR{T{9;F3&S1+X`(Dl|^6N@4Lv>-Uqrt^JSfKQgh7iF?0vE z{d^IZoR+t2*Y(Ygnn&{2MO=Bo&XbLaMuSF>3NE|_W@*c__x!w-@fDv$Cfs*t9=h_4 za<}ZCNtB*D8yzSbNAgGNzC3JkFKrKvi*o;11>#H9gif4ca5FNs~fVRof)%zrSi@=%gkyx z6PcM*h`WZmSr?1(QU`et$3E)+3h>)F$g3EO96hu;H^JUcU z-6#92Cd?f6)m|A*OC5$M$IiF7yDT8TdX4KUdq5Op>c@OMt?3)}mgOPG%u9?x2 zf|0LLA*v1f=EC=j537v_2sOKB+HQSQp>knO)<}KLV;i0i2k$$jM>M!;$R*okRJX5q zVpCliacM!CdCFqj@kXw(t!MpzeHp!4fqIPXNpK0zPlz z-4`GOI)@J*9@KXwcNKkwJSRsIUo3-{&c+qBPd)odH|kFK@2h!>V`sE{Gh1Vcjlp}b zHPWJ0@u}Mu;7=z`-^G6){R`a}y=1N)Ix0I%%!g)b3mn(H9ln|&TPbYvT=Xx`B4fAh-cxGRltq*+>Z6uxu{9 zUqb_0W-w#}f$1CK%rf%vzxs2wb(MsdwVE6iwb{xwP-q?*_CUx`i4_ot`r~gQj#^ue zvmM;<^`Q1^=JjJvlIt!%o)lS^KPh#zyMsm+dk~mRe1^ z@cR=D$HS_>^Nbdey6ImK8@)vBsuT6LOnKqqE>)`@zIhMz7xlDyVLT6tuk}W ze9xR}fXGmA?7?~%Xp3WZXim1&kXq3tN*?QpvZgfIqjL77;X_2}&zA%d^q#cBHd%u7 z>GwDk@}>bZFl-^#bVc!>Iswm$rCcgV=6katd0cB?toU=ZFH)^a*5WO5kp zV+O=(AboT%1Y`!1iuB|^iuM-_U*EoEFsA>wg#9U%@lJi{A&a0Nl)nDwhn;(epPgq` zFm6uGZVGL1$S;*U4b*iblyj6NZfVl>+|&((WM$uZuH0j^?gq6Vzgre3#?P06|50p+ zi@^Okeq|Ww_zW(BMo_OaC#&w3YAI3t68flVgRGb_wN&KDcUkjc0C7+-dx9 zyH3+c%>?^~!HXp^N;Ulxgvn|OufmY7*bvZ<$0@*PLPJCMiAG+(E%dpezX-0^AESkH z$qk+7!C7_b+2->90Ouh9)C*Rc*e}rY$0W?EJzjDfJEw+rBh8v2)s#nCzncZ6A2?pV z8h%`VUs%IGA>FNSZnX^#4VN7@+OwzIBUVK7{A-X!tWifgLvKJAO!*T-@BYDVS?F&u z-evUt(T2sx2?}A44!(%UTZ;u5v3|rtO1qq6;I1lkoMtapHU(C5oEgTv z!iD3#js-euP1I|a;a7l6Mo)d_TTh=)1zsNEwz|jg4}L$eMLe3WasEfuUR8v=DbaaR ze{|KFH7$t~7e*!D?!U0X#-200+SsHuIQ&;uf#~BeGtTK9vi?0;|AzI>vL@@}F~wu5 z%h(-PP860sNXZbNb;$SEv&Dow`BEGx@l`TB_|WqT*}WfF4%`^6c|5d+0M*|L!RfOr zSpnq7>tMr>ifrS7CuwExA3J_hzUisG=g^_Mm<%reb(CnI5oxqdN&2x4I`<)mF0kR4 z9EOZYK+Dl-hQW63 z_>NhTm+mH#qhvHFkXNd!m%nD&PSOg~9r`dfY2u36^$Tw%f4`e#Twew>&Kd&!$_=I< za}eRsPSF3#73#3}ABha0)%^y&zMZn4pFdY8(jMDC_yAfwHn|oZx0~rifZ`{UOn%QQ z;{L$?_KK1DQYoXfQ}hL8#JtPEKw$V`UQ5@AG-L-Ltt1JGY1->BQPMP)XGXL>vt4x7 z-%;G(4=n{>jkyh?HxP+3!P4dt^yM>Cb7ujTT zimugpL)_09^TJ-+0xokh%McZM0pRGJXV4aY(1pdU zKJ3&7D7|%m-u^v^jklpMF)KLSYOrm-*_so0H#b;_c?kpRD_erRTV36jWwWJ zWQ1wP^4*_REjSL=UMq-MP32$|ouiDlJWN~Vj(XqkGh`Eu2ZP#wY!$TL2j)#SI?8?3 zm&9cMvus?*vRPHDS7e`cjhs~IxcBfa`!;>~rNVKmbGo;H(diM6Nw3YBevgg0THT>-sxN$uadeJ-u`1t=~j#%iNZTlM3l%+mo4@ryPB>^2%$lsYKVT;oU&}@F*6P z2pJ4Z1pjj>9mqo#dG9VTjt?g^Ihs=sTHJfLK&KlRf^8WbeyE7PLVa#{l8 zjK_b(PF{xWls52mYR{c^>6S81XfNcphU!{@5}>?bg_n};97?H3oON!>&)W4vf>jZe zyu52=)tIs6Tj3AvkdWUY^HCOYjtjgTp=M_U3Nz)Rgufh8nT3Ql9Z|CNk70C8x(57E z8!4auZur`g!I}z{KU4s3u#uJyF-ZOds)KdOwUsyeUtguK?``_ckagx5FQ`vn>7^vW zN@A4XM<#@HViCQ=%&b>_m$Xd{?^Dl}^?f(BkK=OOa5)7&|6Ke#o;5Sz+Z$HAo~sL! zl*-NiUV3_Z1+U>d>bQRQg^&=p-J4HMYxB#+Qsv%JxG3@$A#jEWdzhJ1=T^ug3*j!m zvXf-b@O=4J_YH2jR}mA|q^V`m7}Q1k7`)5Op$`n-Gd9lzBt!FuF?(>1Pg8xEdRLbS zXW@>}m`JlE17C{s2Pe+u)1em(5J`s%^TifwY*$rTUOlU?-Zg8U8O0!cQ{ptQ&zZ#e~D239`SUS z_N^81_c5iR3wb*0S2y-gExow=6v*Vg)LD%*Q!a1@7;Fm~G{Wp*k20|x+qGwSx1!W1 zkZ;;Tb!85QdMeOuC>=N?;dvD#lNV6e@NvbpR`QWKyW+C4h+u9j=zsCP!!@o~-3w$t z7&p+avW#@_(c!?T#nc5-zuHT#Qd}_KSY{it!;<=~({mm@;&HN{VT3k+?~9i&b>LF7 z@@-5^V53{{2qu_{(VN}>XvMtSAz;cl6#O*2xjUAcQR9z4VImU*5g4m^cLpT;iSp|>6{&7LQ>JGjrk9;k~(KPLe3-bmIXv_%PN9~d9)Smf2SGIsa1 zf{%R9)CkkW&z8yc>k#Qlrv=xiCnhC9aPcbq5j?BUJ|{=h|NjXc=~rmn;Py2i^Scc` z>paXNeLCMKViGjakLA_Nmv2bsDj@F=4bihxXPz0-9W~?yh&!_oyFuSS$m9&E~ z@>ITGIDxv;E&2U1QXbSaS(S;=1N^<9REyVHK?{$Ng|w9e%ZlZudNBP(O|30Xgycn> ziUH8Ga646RKN{~U1wJDgvkK%Ld~W5Ox4 z$4@8xKbJK`(gO1@8|7}W!TPM2Xu7gBqJ13UChn@3HN^l}!5FP<=k@IJnpiBKkCM*! z?%ZLKTxC--kBk|)_SUbNz0RG+<|!(mU>8gnzYH~UoT$*;3|P8YNEPvZ3a8e!WC z!REnr^D?sKLsT@$Wj_*kf~GKrPkxxxw^CoR6XCK%!=Y>H^-;e{BZ2LwT2CIM+uDav zF^qlWdbEm=nQk2U7!XExsVgz^vrlI z2Pq_0dU+u$)R!x1ayZE#Of1xj#3=3hqwyK{yALJNo{=L-ElQ6_*!}g4igw}=c^%3z zyJU~HvHhpVALYXFkhD z!n~CHXzB6+WRt}++1EF7GvV3%D01?oT?`D-Ib#MBPRx zeFV}zwONY?0cxwXKIVjh0N!v(C58uh}i$TC(1 z%txV8iH)ihm#4j~r(B*Gd$YzEmGT&N^lM;A04nliZ=U8ARiZ{gg{`W#c4Qd3WA(Q) zdJ;z~ip^=l7ytL1Jzw~sSs-{{slXV%gk9h>?|hIl&0-Pa^1pj`Ssi3L^f~>#Z4O@$ z%`YFSYMCJFoDf}UCARG>+~TLQME1}kaq~)lz=`_}_`MA)(#Ko)3olMi^iK|5WA3Dq z;MH}hg&>@mkA3W1whsvFmBGQm0}IdiP!ncBVLUjse*#y~wGHG$liw` zM#F$Dtt67)X6NAvP9X~I;WSE<(QRm?eb;_~p}6;ny8IpzpM>&B!M*CxhuasOC!nxk z1)AED!*4g!UV4sp(WjnXgvE=HRLdpAF!E^!_W2`aczuprBKW4bgoG~22Qm1ppS#)Y zMEx~)5|`)RRGm%xBhwrEDz=uxQrQ@Je_~bw;#y<7R$ikAN;jMdavOOBr!1oy#p9Bn zb)@tvvUQK>-COBuSPgZz>_ovU$0uO;`i4#RktI)d_ws%Sjt1!zy3z#iz-&HbXGh=& zFz5MVod|$Jq;k053(@Ru7O-}_**7|th;u)lJHMk~DV0216h(HnOJniW#0sq{8Mus9 zdwsrxk$5tbZC>jzTq?Z3S4P+omF@5Y|K@oioC;tXLE^f`mS0-513$Ju?|Vtsp|$YE zS_kLsOD+&EA^uvVu4a{8@4|Ock_3Swc%JS3t!!Tl28JZM!pl@?59^e4+`Fe=T3Vhq z#ln0QPrGpmUboWAOUvoi($wpwAeNVPe*VWF>_=^YC@M=lSEUyaIHt$rfp`CWxJL5;+F5WRONK~Drnzq=~mDXQqHpQ;rFx{@o*AIidY zr{>b*L3oiWcA{Lenq}$8SjO@pka@Md%O;^_D+aTb2!q})H`pMBj)`WyPsLp1Zs4)$ z1(e?S&(%h1`n3#wJ<@)=g1?;oLbnae;aV@`84nLPtR0<|s7a5tPKl~uYlAZVt2IgE zAO?(Gc9rQFd>^bbvM2^IZOdVwfs>12(6L{zZ8M?U;V@Pg9{AYrV>E%b(J$9;uSG7r z4%1f_(5~sBM#*L_|G+@jI+$2t5bfpe&O@LkghogAg!X97B!s&n9mLMm4~dTS3!q0! z5Pq>zgZ2sqNV0$?rWoY)EJ-)BE9D?6gzbu4AL%RFFN!J4;o~xs1Lf&IJ1fuDy&9kW z8{0~w5Q%|_V-RF`Mx~E={8*>%K)u!`zTLUbi3DR&X0EHNi%)(=(yRpmJ>)%KVB_KC zJ-4-b$DZVSB9qCTJ-sH)ixw>CKCATXvrvS#XPo1kKU+|NBM7U&Taxl#FVGpHAcr?OU{_{D3#{*TQEM`hKH5aZLZ1 z98hJGNr#TeQKZ(^&@fsB!OUi*bUNu!hUXXFy95Dzj;~re$iY3u1&9JQkf3d+1;V(f zxtb7zw?hFKrIqK5yM`)_8)m_@10}8{ZQ!Wc$gjnH>wlXFHKd6!x@5@e1kB`in3~#0 z<^vti$oba;Xf;__>#+3&k-0aj*zNV_o0q=+ct?A1+U=bHq7}b*rw_fgnAm}q(5u;} zpTzz0psq1ZmX0+qnD|XCM=2Aq&9!=camo2NXDz8){V8|(SUhGVp%AdUXzpNy8_C4Q z#m{&M4N;l31HmLF2^`}3`y_oNg$UvCs;M->$jIm|Ce$>7?#^F3?qmroS)No9am)Lvl55ouVpcIzx#<$phJG|+KaUP>l9KnIsR#~ z7`x~A_oKf)pKXIova{ZGQEJEqDuG7B7cq&9_784epoz{)4zaPa3YehVD5$Q$?mEfx zt)I44r_X`&B)9vfrbY2#96WgvwGo9x8N83cTv;aJaGj*9KO`=Q zFa|7zV;b)GPEHV%P8Xgt=CVSn(gJJ05)yX+Or9Qd<_5T*A z!hA8QF;_N=RM=RMK;T7A0mqW!sl`Y?1)|9lU*N1Sma=#el_YCBK9B>mfa?#0jHfOY zqa*hUh9Wz{jVs446NnhIhCO_1>8Mk=q(2VIH<;V%%Xo*ux8=i)F8Vh|_tDDmF}9B7 zy^4GCw?5{&oe4f(o=1Nf>&>CXJA_F+U@w6;+k57e-+!WMyflKrLygXN4iqq?Kh9#w zORl8TQ3}OBaMv*N;43*c0rtC1)|aKe&8@~v zBKxCzlqt2Rff;BAL1}=wpAI6_}!tY^1TiPP4Oz^)}NAL@q7gkHMDS*lh^CI9oqBoA zVtBR%a`mlKV#s)%5Q>4W4l#t;e96nez@TUb1T18Zv4_RP94=H3pi7phki+{T1}?Ra z963@T?dq0G1aS~;{HViwe$PmT)CP#=rBU2fkj6`@)57l2ZR7&ZV5wJZOJM)c8{LCY z=+OOniNe3%4`N!jY?*oxm!w?!JjGLeu&>j-S>%o5nj!lVmzecxe3p=Ji;l%E z_3H;a!XMM#DE*A~zlev&9uYX_-|w1AZZoD*v_&%A()ez>!QD^ORlsVFvQ&_7|j{$115uS#%T?Io(s7L+w>*1%av2FvmyeQo(^ zGTyy=*9s&#$n0Kgs}`cyuF=FPh#)1*Pb|5;D0#ey>_N4EFc9n-je_Rh~hxtzYh;74Q`P}(G4UEii z1`hXsQkjl2syo?s?bFL)XTqO6FJW!j0p@vyI0;LzoI}B>Cke1d%2d=&8 z`NHTrjB?8mZ84Gqmu|Aya&5Kk`I8x5S$}F~%2I7Gt~53gdfnSZ0?*c8;XdG4CJQ8 z$TH4y4Xxdt3ERIIAdSIb14(}#4J1u|gorNMe`YsF_kKy@y{6*(7%oMx2jlcN{Je~H zBX?L;kT#8os0_af<3a0`GrfUQX%~Hee_0&TagG*{Q@9k4eot7rzzctgRAPoGYiT=} zSr;WjdTs5W*4?=6B5kr#4?YZ7Q%^A=+8Jxtp|mPUgPmdm<{Cl)3-+qLpHelb-KBbu z4UGp$`|QqNah3+I6;fHM2h+- z#5V_4L{$!U}1ztMt0S&*QP7fK}h0e5tRKzp@K*4MRgJ_&X;Q} z{)|No$&6$=)P3c3%k0UZBF-B zD6QH+{oG&NlCYsc1@r5-3x@PU!ma3MQSC--3#DMn%0HhDHqh>6h~|lpT&L!ojGPoU_PhxkV7j;H-+y)0?sR8lsb zj(`n%@ccDzer%pWy?(h=KR$gRUB3iff!h$QJ!#GvS`#*!`}XbID_9#Ld%FbsAU2s2 zWi4K2MMGn^<%VbH>M?Mk1aP-F|nra8Gg+YO)a+ z$}_D2f)ASQ8wY3~0c2&}ADf3fqvm7CMa)#5i_T;6N1d!i%HQyCT|k0~plXmZihi=j z-C;r(S%jEH%}v%VvAd*nx=(KdYpKU05(fznC5SKIE(%lB-!y1DJua7VE%c;tWPM-v z8>5NGZCoAG=B*>nrp>PYk&*M4Vkv{FrHxb?rF;1=8hy;qZztL7U9UO+b6%>xM#Mb3 z<;9sryyYMsJ!2o|NJvAE-wgTHhGm=TY4@mLWQjCn2XaYS2I)gNFz$_s;<+SmVo91d z5b7ho^>D$=su;_dNqh1YJo9M2X?f=1qg+i%dQqOa%8})RXjxt7DKFM>ea{v1C?T!0 zgc!X3OqiujMTBzHu*^MzMU4MgX5`s20wj#7oXIdrLAN0kzY*aOxB7R-S*oHq*$hrp za~%S;OVrY#_UKED+c)bGnJ^SJ+z$)&l}FSuQKLIj=J8nMSlU!3n^mOm^PQX2i~8B` zl*dxm4;0O;P!=2~k>NV00#LaQqr-<&^~=bP1Wn-B%M zn8rg)ar%|@P$sY3QdiH>O+Qsi;CBDt_^d4YYIJ@;-Jf-^@y?6T!cmS@j3f_NL$aRT+o)6ppl< z+Fou|?drZbrtR!hqjZSB7B%vLOV391*ycaH793vHqvBJ_`I)pWAS(8At~W-Jior@2 z!%!x&kYY5e8;hJb78qJdXr3dAPFOV!5SV|?kx6Xca7ldbi0AQT$!f390U zAlPL`{ZyU&>+4PG&_+Po_{&}ptVYBt9y+fRe|?BYa@n#_G;qckYiMax%!ZTVcWrpD zLB<&%22=12fC#H#)dOMV0~s&hJfW_?XxVh^yj&QKcyr}~oKNb#GX0CQ$)jRpdIRfO z6%~tRQc~lKG>p2t&#l;e|L z|3TLLGPBML@ceL}42F!!)MT4qaMlZAaioWc8!WKzWW z(!EO^+6Cz~DE@)^)fBwR75u=jti{;Gq^mNyY(mkpXa@Si=f87yPK|>Lb1Hx?h(6k@ zTWscAg4C<_jCHLW#F?-_qwh(5W{tTNsZg(P@cO6WG9j$t@5fy)A`X<{=Ev?_2z)tbpn{CHpCdOG`?w zi1BRw9gY1aCM6XV8|AQpllpvBRS{uD|F_5bP_-Eu;Di0I=2l*Z8Bro;kNE_z$j~lR z6+D*A%uM1bSfTRH5&i0yYzO5SpK^MFCW}TeD6aoBdPArN{0y*w=aucPrAiPNoum+2 zF6m?{N64By)FQYid*H=YxQ_u@lCeP6FC0|8LebHE2Wjvc3*AH26aZX)^4aj#KeidU z_+2EWo5}c;o2Y*ifgjg)l&gVdwc7N$&;KiLdCM1MEU`i$bqB}Knos%6dSGuUY?j&} zH^NqXI<3Q{J2jgCC`7;P^P=CB2F#rzHv_^@UKiVD{ZWc81wqbGGM$`c&xwDXB1Ga0RI1q`L?X`dF%c&hjJ$C)tvE7CnFNQf?W;!ppP8j<3Nd;ZO8zGV% z_(ufT#Cba{?J88U$L!y*9k|hPUr&K@>~R66A0TnyUYI|Lt65|Ci++GL>o;T0;4;if zKDEdG)VK=~ftjS-_uQe{-%ol^Bt7_EGo~nQZ`-y-|N2}}!Wi;2$1;2uOQF>W)8|(o zf!)XVZ#h%VMzrTqt$EK)Sp9VFycMcIXH(fvh|qsjbpu08mA>t;T`k}lF%glO(u~Ww zJz?|P2DLdABhQ^4aS;4?3qd8@x+9%b#Jp%B1q_)`kS@kVZx*T%ZC?*jZN4;~+q|6B zo1NRr>&2IvU6F$2w(F)#kVR;Ct|3Hwd~%t1!FtkVbg{kZ5D;k!I6z#Y-A{(6JmO@Q zeVy=?D_4~3G7nTdm2@Ixz`b7+Xw{3K8RK!?gRa)RW_uI&R(^Vm2;j~Vtzf#0^t;LQ z4cZ%TUZ*3Mh|kFSvG26*tmubW0REC}R@Ty)PWHI>c-=to~Lj^WmwmrLg?V2PaU>GoITk$C;afMx$ z;5Ipf%zCWCj`KODrUfH8_bP3-gj^87^4US;4NhGNfhzt}Fp@9&`<7!uz8}I0U zowuwJ{JjwVB!YDL?I9RqFmJZ&=~VC*^TedT(;iyU4qT#iTcQj7RGNB}N~D>2cDv9& z*~}fYW3Zds-&e3lqx)Bu((52#N&9W5;36cb)(}Ba{sxf6&{cfbe2U)EZP|JHn>KAK ze>U+wyihK%8QFlK>z=jLKkam{h>(sz7rd{3!twElxU6ojM{V(JhIe@SN1pCZ+{D)C zcH$x-?N|>t8mm5~-q>ec&7$-3$EKGh?SU%jV9jdI;eS$ZN;);pE-oR)`#|1Ydbs}K z{iDxM(RizVN=$@wMM$06TP+lI_4Pe$-&?hL`r|A*$G7^>-gg^@8$}53?u&~s^>p?h zU?dVjpfC*79j#6=UWFNp0Yz&<94-f~)RS@7QP$xc9omSXqk-ajcrtU|( zy6KCZriE^^P-Sb_zi(e~{Is0A+y&KVRlB<4b1*?K3O>Zq6D_w<=0E^NK9Kjv_wQwg z*Whyq1rFraS+q_UJ1cZcDsBz@AZBQgD|vTvegafS9JtEkhtLVEyzKgv!)y+{-~-tY zX=!`U)QhFR=jrT&nxT__T)#9#M>oRWlEb2)%r*Crc;W!f^j#u0}lL~6dcL<@> zL#dYfI{|rQqNa7{>olg=yiIcmjOUbB1TT)nl#~*QIo<-s7CLl{*3ZwEqz_8}IrvP; z=uG$7YmD?W85g16iaaMJ4ui%rGUv3dy)*Z z$Q1r|wqxH)I);8PDA@6Y%W)?yP1z#>q~?IK#zp-6w%;l`>9&@(q)*%PO=QZFlm2A< zIS`B48P4hbeU(APxZ4`_Emcif=_yE(ZI?6`-S45|XW4~5D;bjHg(ynC zda2+1?|Q1>g?6dFHJBOkFZw_%`2L(*U(4Oy-IaZlBlV}wa}osS`T`74R0SEwwn>{m zs$F@MgV0Afw5TZF>MRK{F$Nlwe+Fd2SB7UwBDrr>e?j8E9Hc zJG^`ICKS6|aW!W=jSr3Y#SxH4LrixqvyiXb3+X8?Kr<^bK&~tB%KrAqrO1x~-eq3`A8FBhAxea~f2%@> zkG_x6GgVUq1`a%}R#PWDCO-?Z(ARMsm`{MH*Erg|=MougRCSJ#LJCxtJMHARV}uZz z5V8~b@0~DqX*}8<;|$@fd~p>nDnQ0@6lbS3bVHSS5TBwCe5NKY=|M!#4|_xtvPJJs z<8~xE>ob$hHi^>N2&N*~Q+8)U)&E|_jK6W+Wx4*UmCPMIQHpk#j4Q=nATBq``8)B@ zZw33nh`EG@*d-s!1!Sm0Mu4?J)iJvyLZvI3^P@yv8 zpx06L4;acjSatV`p0F4s)zfwSiaDUHWx+`AagkL+-*O~m&?o-59$xbEdF=wL$zz-_ zz0v}Up<^}?jidf(z?No&KTJXfy;j`o$S5c@fT_GU_k73gDz(5*JXq4=^K6d1f)Mv6 zYG`5>F9*H$=7GWAS0f^pBB|n9uwa3`2bBktz6D1`_3k@6ES^^sMrDE{CZOOH*AYAY zQRk6bR2)g*|MMzw5erC5^UISZay2Z_h$D=NccuFhGWZVe^@0USx3kz1+Al<^(a&sw zn?)PetusbvOcc$Uhqd8na0oy2>lphq=~M1{X70jeL@y6b5XO&JX}M*O)QTf5>PHbv zyeTE9tS83D8swdXky{wCb$EwA_S|W1zG%fef@`6=^%QtjWjnK&nzH{t^Pxrj<<`e= zoFt%C3enQOBXejBAyuJclu@oaw356PVUKom`<9JrMS2uKHJ1oy9z2wjNp7I=yhX1y zgnt9AX;#MViJ71_*qRQr{KhOrC`1%$j-T)I%0W0z`BKh*prxfjsFBiIly>8%6L=bbXr z?aMf0Y15{#7cc#33vM73tH6BzVduYDGwTW9 zuQ}`b!|4+%oCORIRg_X4VFoDM5svbg?|HwmS%qRUc$=w@00t)?5Y;h4<=fAvM?C=i zTo?y63J|@HF|f~|5X_|sLhtnfm*!jhq zxc=Qj)UTNT2h|Ht2ejg6b;%g+v_`{qD|75T&Vb#`*fq)9TQSBmFZ~`duISBbK*9U# z*ROyJy0h?tW>BixI)3Cs4yB=86-YW{ka@aiHZucQHYNyG1^>CAz(C4;Q86)Xba;>6 zug$P!Jx3$*k^YR{oznaNZt!S{ZD2Q)u|)-Ns>VIWKSy&?KLf|n^%?SvkRuE?pj1^= z#b>ZodtU)K4!0XCL|wy$p+21HF{;|y=RnNb)`Yqt?tW*`Vv}Z{VzKb)EfZ;E3Ay9% z1JBsU81JK)Cu879dYr;CAV?+zvLg8; z{`R-1TWJ*75y+D8nJleEM}YFlnUl@AWYOOt$^SM&(jvDVit0kb4C6%yFub+HsPQ`H zfk5Qo{8?N^f6#cNO+2J0^=N#k!I`icW&p!p&Dw~~(yJ%=fE?!bGAMQ2i_6M}&OvXj zZWX$vQJVUmc;}*orwmbR(vW7Ht%Oj9NjA(N&|70dwc`+YmGf{s{c-Q|0$6_s;*@neOU2VFapdpRdh$13t@D;Jr1bM zRn+G4-YW!A@S84;lU47^(3W-@u7M#XF&I^J@9EH)8A@vx{V$S{s(4y~4I(Z3Z5iXm z<4zN5deZn$*v!>uJ1)-LUoq_i;paEZI59C?_}1=Tf%w=^?`l0C074}b-365=g0a9h zQWRbC%bI@1VcM9YicRmHEk_xW(EO!h*YI6}aSkT13NDeB$f{~te1TP|Y zPXCW8H(qg*db!{~$U+Czx{%_;O1o`NKp8}cMmPA^(wb(}v$M!l)%Npoun+C6V<*68r$}QYk&>-g%KuCNU{8zw{N|l_I=;;Wvg*@0USZ z(>wkaE1+uhrh)OV-a&MK=^d-|dqvOKRhA>|`oXfzsI~mWP7(?^=8(o1)rU1H>1Bru z#sJ8Paq!^5iVjG0(XK;?6-!K$;nGyMY$}83A%I%JtFs-CB*(q%!f1Jr@X% zx1x8~om=X*ZdCiz3LfU4^H)Z`N+7i;c@E5aKs?H$YgwoE9qo}7J;5VW@*H6Pm`Ta& zxhFH3{C0-CeICyMCVeAT7H8hn-$%Xj5MBl6)&Ml0w2`M2$i`S-jJUlZxp;{A8e2!# zCVD4b3v6_9c4FLnCY6Jx%FWuLI{;rfWz7$DjlN?IpVsab6~rY(FN+)219TS#8qKXF z)kgZ$5fa9z(EL9aJl1Ir0i0^sSF$MXf~c`6iuXh$W)d@{tGg?2T~J#sVo$rpc&Vw@ zj{YrvGuKP#ov9C74xRxK4pOT^Z2U4Q;o|@{WdLkn0gdhGuG8drCS>;b4`6T9C=DRO zT4Sn4Z}DtRepx(OyX!O3R=$E; zG~inwm<#mQBv__=lcX`mw%>U{#D+_;7~0Ij1m%>P>T?}zT`8l=fe?E1PrJZ z8TC&^_`#AqQ?q)d7Z@r_R$x4*`0d*t73Bgd?WIv?X>4e2Rqp z==)QboFtLIpCHYL$t+0G z@M?dTwu}FSk5j6KMoC%q^OH|MQx~?q7&%fQ0GrCc6R}srb|uCqR9h*d587ZDBAskF z?mN^sQ~Av@yWhY3&D3-`(0BLU94Y5|5wlP+ z1x*b-7NMSyMFAL;0bb*hD>A9Eul;+Vh!ABT1 z$p7YM*MB=Tw(y835{1h}I8QbD-#+Z@PJn5QHXu{AH-5!*xOEF$dS+EtS;_nxm8oCx zvR-T~@O-L~ZeLU8jtDN;cHk@mxUfAP(`}RGO zW5wi#svaXw4tBy0AUaEfZW6RHASKGruG~HaUrZakRhb;o@1LzIi$m=)1+npcf;KlF z!>qO{Yr?U@!horp*KM;SU#Ipk?IKT+_r1ikBI1EHfhiAhHR{JGwyin~&8SWkWY+DQ z>G017b=73{L%f^Xt5IL`c~>!BcHtNZEdp_N%f2z7m(oac!OmJn=+LI_b=Kzd{T;BC z{L6Wf{GUYAS7F9%p!Pnf=E^npeq}zD?$_k8eL(nB?2Ikc_=RPq<-lJ2wv0NkF`aAr zmvaf_Zg`j`pON{P2(Q3WG5_f~4B;3?$~!uYYp^^Hw%lWcVucc6&bg7*+KiO##1p_7^>@%jvYyAn z2l`oCbaaT5tJ=%+3l{`@<|cGUjsXhc1cJO&Dpp3=Mo9T*D*I5>XZY8%k-V?bE(T;H zS2EFk5IAM8Qqq)AN%|?g>#I3i7^f7O=oh|i0Zf|gZobN8{-sG=xYjx}O6K*Zdsns& zVU`mPxWXbJ`MM!!r;Vmuuek?7pt!i~I zFv@f!wuu-e9ic6$n} z2ll-}V`q{(=Z*wk zMg;CMIxy)vuCNMx5mjr7?$za&z%Xq*Zk!z0B?4l}_wV1ggyws@q_w0?79w56SjI@u z^A|7t$#+TVZ6pQz)+}2G<>1N;Rh%4*%eV;73Ee$HW4fXW z>4k7$Yf)y-Q>g^UZ?e)R*Vvr-^X>VmhA=9R5AGzIYwD9Zrp61_9J*W*y{_`6ilp79 zN8)dcYP1~gZ4J0bOL@o}XUz8#e`{l7leZ-UGZo8!vknEl`%T#)1f#p_N52aEP&DS2 z?F~yO9esjrE(dZhCQ!Mqcmp`&0K$lCF3anqTs$NOFjMkQM!E2|Qx)EDG^jFPn1|*N z8zqnX{ExW`WgpL+J*$hOo4Bi)&zr7XVB!f|*ft%`zqpb@+s;yO_VVeO*68#SdKm_P zuN~?gJ!_Skm&RLVlxBKR_!xv`Tkj^PIV-{cYE&D7-E}X=(R{o&_z3oi=g`{B|8#e5 zf^)vnJffgSD-KlS&NIo~u*0OC%uQ7FJLBWyyAdsz=nbu8_ zqVe<>QzC2oOz-ddQtsuXcbVjiA6X8ZXd~uC|G1{r`v6DR!m3_)!Z^q21`&07D13*k z+@^;Icjgk8E*#lz@&cO)e6U<-1w6rw@9#UUmXJ5^09cQF0oOTzVXg8BXgK~Q48gmMZ%{-Ea+rs zafp{(1O^>2L3hI=DF!kG*LxdQ)7VE-_4y$&VrNCL*#x6|=A?g?SA_#MzcoHcX4NYn z$m_psoY#?attBPeIb3Er`$HpkBkCjT!2~CAI$a0g)4fZWDeDw_T}W{WSF;d3093Y1;n$YYv(8S7*rPab~-5Z z?0DfaHDQ3W@PE*J?-!wjY9nI{AU;LPe}8phalhf>yu$+^=9b(y$sLEuY&bL)i$xO; zg>D6=s-C>c4Am4oG5ZW-`vldU^ObZ2Px}2NZ1~c(aG-n9_N4pWB}AP)j;rW3lqwSi zut>c2!=Y4QW8|cGgud8ZrmM0RGRXMlL>8&|n4&JQQBJ#i$V=n%!Ji)93sZ*g50zeR zRkj4HOiPO+bxR6M->5GYdAUm=Vy488UZzsz_^%cB#?*dlKY1j*G%koSBO_y>`~4%= z10M5VL`peoGR**GzKv6JJv%+VOugy5yyYsYb~{2Q@-Y`h*b@X4Cxjko23$cy^3YiM zOma$@xM@dS|ML6H;hiFQJ!W8|-TWFYch%`2d1cBV+`-Xr0> z-Fu=81v5XMB%~voOIZ@q;QK7{{e5JlH~W*|R)E1VZ_{RvM(zn~3=0d}AaG)TGFSPD zv7bWN|5DUO*rMYD8^gD)(auV9Kl$(k_ex=o+muno&6Do!kGQY6JTghxWbw%}qgF32 zl7otiAlT)=P&|LkP;e?B(9Wz=DMbXK0P-mnTln~iGFtjS%2{3dvT&A~63-kLPl9`+ z+vi-iuKk+m5Sd@t<5*yDJ=zD1+H;1PKN1eE`Gt`}gJZ17S`Iibr}#_9X=|XExtrb< zHnHWKT(M-jt*$FA+Dej!oH4Yl-+l-S4J8w3H?*Eca}EUg$$YP_39XmAW7e;h**Scp z&&see>7Iq#_Uyi3qO<7@7qs;B6&YGPCo?mV6htz5c!z8uW#=aCW_ZZmN!NOTRaqME zjy1%XRRm=zJ^$#tkurTiK#eW+Pto2Bg0U=4y0OzS8>c%Z)U(5mML{AP!ak9`H9td+ z>o;wA&p1M?V=={M%k?F*E5Rjdol8EEnqbJ#wS2zyjH^`0HqTelZwwv!eSl{u^ z`S}+G&-!UF%5fe*G?`n`bs`GW=-T`C#cSAXyheNAyOzgkKZMh~c*GF;=wB_oJ2tp# z3|A7Id`1e2qjS^AwTjTuN@^MZnddGuUs zlFscdoSewl?uZ8SxNc4eImH<>{3c42z67r}P0B&XOtfm7!7i zAUP^Jz$*+#k1F2h~KL0WbK00@8xe}q;T?eZu@m9M8;INaGZOQ7w2*?A7Idv1J8u5 zV;;*C?Kedxt}3tF*qiHl{|%yAXAOe=*A#%9#Ypr^U%^-5D!Q7UwNYMYyVKN7UVJo^ zHh+g1+f{5uhYh|Q-hg9TtMBoc1F>22ig6)ntK|}g@uRod>S7uoj6t#;zDSlE*b?G7 z-RI?hkDqU+&?}@IDMYdS9fC9h6+MSzJ{92Skn#9X)v`JaEd1`&_r2>H<+dRWrT*qN z>;(SQtiDu`8dlWhxg`e+uG=vpLK7 zB(!qnN@XTu#;5Hp3(yFKz*}HFrJg3mAG7vshYX#m(-S7=I_vOa5OO;zJv#)kum{fi z86L}$Uj86tl1Pq{8Q}{~^FSWyVRZdw=IZ(|S00@Y`VBPk0XAreAN>2ScAKh()gLza zwCGsJ4V~UcgBL^Uy!Eh}{&5FwD;@MPM?684bw=r3EpYX5(*$~!iO}sm zzD3WW=Il#?7X28(RC<)?FoJ50vHfg9RQzQkgiQr(eBl{V^jgDM`SGI23FM)y{%8(W zoRxWqVT32s=>I?-F2-CUkq&fBZNX7Wmel})Bt`>t$z+uE4&RZt7FGzWNvqxho{_}U zzUSU@VZ+ch;(x`(%WK^feXm2$L+`f5BhUM%&Ylf&V7TYFuPW+n{>%k zkj;|pwW;%oLDY|LL~0qZO6tyF3*T`Ab5Q*;_poOq2T0&rmfq3&y2qVQUG$u5bnX(` zMNt=pwDm(4$SZEy57CaV{edL6^PO)$c$R zEZ%jXX8&Pn_^6Y?guIx1@n_Hh8h6Ghqb|m$I*0pVUQB$^1k=8t6uHlr@vCsBw!<*1 zNQ{u>L55VA7F`eSJQk^L&rveH_O-$fD*<6P_^h&a`FS z3G9t(@q}i3WToaT!aR7iGB!^=4O_}@l3yt90lrTrghUR1boW%9F@Y+ zQS*pH@#Nu;750I3?n~?_f6bq(G=jnJk&AJ=i*IT%oMS}~-xE%I}(fOjNVJ~04 zd}W;*2&%*{y>P4jA{W%YKM_0C0sj1M8)!Q%^zc2`*>U{I*Dhl04dpRa2rF)whpSeQFCG*&^^vTrgB z{*A@c2p-czCi4X_j_wjp5xRZ+G(HrI)WmzF7?`4F#R|X{wnI2A1TJUbk$%k2Hje@; ziEuE>qZ8W?9!u3p>V7g;{4$VSYT3ffC}L>TiiOkm0c+&s_B#&6p@ItYD!}@|JDq>v zEWx(!2L}^UjrO%7@QPX?VR6``!TqEC!jh(jANO(>{n`vB(H!uRltHX9S4dP9MAm(` z^5UvV?CXRPCJ*VM)%<_+)nsCcCBqeS{nIDd5|%Qgo=BEe)v0w{+J`Wk%Y1s*-&^2A zpMGH`$a3@rwiF5_K)O(rP08I+9j=iW*d5i9)=h}DfIsTYZBs3i)Y@P}A6o6S{!VIh z=jK`!&G+TXZZSRDhnpo|X(T^9dh}?tmQ@+XGaJS`9}Zd**CDjM7T^lpe#*tgRf4;~ zvm7jgBN3V41CsT;x1r3`G7uI7x794JbqW2M3N0-VljZQwE?E4kVbHn)>}t z*m0>{u<9WHxDwwS^XF!5%?BXGzJx?G`{2W8r}e z?FW5Gwb0-C)mOK41Na0kj}p||RpYKFziRX5+&`smO>nG&!unb3W$bP-Cfg3ww6r4N zDADJ{Qvo2f66*_c`pRW#_X`||7mLOjm+qUn8_h}&LA4_u+B2x1jTKuQWL*6rgmQ z5_RrY-7Vpri>l}B!Q^xc(Z6F9;=S-K4ENN3T0$^IXjKf0#kcUYX;2I@jgqsiWTCQ3 z%t(9H5v(w5e*O+HWeeeX?~~HsyTsMi&7Cu6f6~3}s;ZIK{3IVY=2)~k(`?fde!4^B z^9VA*pNOoH53Ok&AFdTE!mY;)@b!_Z_$({|q+7@p1InFQ(He-c1tiECFtXm7q3 z`|NC+@XcqJXYwuhpSU-JffpB{M__NRYS9V`^mJq?gw7&soKZm;nRhEB_%-P7LwmvA zLeG5j>g1C(DtnSH`&B>i&KXu$;wWI{RXFCC-5nd->`vBV74uuz=X&;9`nsFZ3hS{* zv6TBT0M6*cCq}dH-?6js%{fWQ8@)&7j>NwZtvyd}CDp}n;KZn}*sn+JaY1A)MyrE- zcSa5IU(hYrb=gr(bxZw_)Q!G49FxHJhj=wf{!Us@$+MI+?7w* z@HJY87z~)U_Oea_!`|MC7+4L(D;%1}c)u54FwOHX`tAd7krCMKnL;TpU|V3*zG zmh7<%BNb8eD)&8&iI2liH^Bwv=gyx7^2W)@R=e|rTCB`|mqZCA%L5U<52Jp6;ogSy z?i&teB_$h-%rgho#q( zU%Z=<7KfI~&lCW8#bDP4EC{_#Nt?BZlXE5DRPNM+le{Fn3?^$*ZY_p${g%60Hubl9 ziMzePGTNLP6+7C3nmcv1=`bK&rL>@{&E&F)ge~s%n3<-i}^?bH5*A z@QER$n5%#?h zmVfq$y@D;ObD=Tf>KTsFP5g^d+ZFiXrsCg$XOLo&Kj zsZBP9$MpNEHcj#66C!c=r5rx5{ZB-gi-=%zBSDOMuP{J&3&&SmU40}Y(|G5)e z^_4^t6amW5DpJTf`7D4PEEdz?1CnbrMDAI|K=qq2BeJ7+7w7#Luo+C7H1&$YdxS>2-rtPYO zTuk&RGjXAUHvgGN=e^?P9JCVpC(WGDJ0O>eHU0rgV2|RsKFhs)J1QW^AGf!-k-PvR5JEsa8YCWYjZXEI*Q)oAh;V|9%H+k<*j$TUbv^6mVC$= z@{AP%0;%#_;--6>gnQmXR}?Wj{rU%2qp#8#y;}(gRPsIbdV%t|hF395Z!S^gHae{E z=9UX>-GfFiOHOBb1!3V5kCPyH**93kM+V=#d6QTnwFdUOrRW*gsbofFkUh~E4Y@Cf zwucl7v|PJQFz1oF?>1n$Si$2V=sp>5MyrSqajc@cquoUZLzs(U@hLB+nznnCT!N8g z#hdeQ->*RteH-{*YtYXR-(sFllsLFQ=@=aL5N;^F5T5!AlO%ekncZi>z8>S;gt;aB z?jkKC%0(fSK!EIQp0Rk^EVAf0#lXh{#<)j3M!pPUi(b+;UEj=uc|sT7UnW>c_Rf6eD&+eVO1*>cOZc|L12(W)qG&%Z4M^@J2Xgs26_z zuxg0tenfCi^w+BZ)2zL2VmHfp=^>zogYSHppVQzk{P;Q`vF`X+{F`c#3z) z?=YjeT&UuikD1?>Bk5b5ucUGQ8IS%}`S~7Es9LCVukRvU@8w^)@I0v^?rwirA-@5e@V~(_6vqk3kY zfKcIz@J}-416eJ{-5{)(2iA(j>dK)EH{=$sj&VnXCYlOIMg>F<;zjh0au@qVJ0P}e zf3nVj`hl&|ebMN9{R0OMgl(6$`LGw%Rq?2nX(xP&DjGngoCVMRGqrD#z~?`?O}&_D zuK^$UvY6fqUp+;?1(W&*!WdalS#rmqZh!Pi`;qg~O?yA9?4(%+2M0$aB&@FKMW0Y2 z!qU~|;NYOj(bD}MZl8ijuQ`SPzAW|#iS82M<32Ciih6&cqWX;aupa4$rLAeY&<%0$ zxS?91g}J6~q&ury3VaXt`lH<6mhM1iHu+iW;y3=V6QlSDYh&s7u#5Qn75QgB)sBQB zv#5hOI@4*%GtLc^%jK+*>aXeM8>}S1%?MKdUyzxavIg*#RQl3g0xebyjTc;zzJ)Aa zW+YBm8p+z|72yv0ZZBo{`w!1}cHW=XMs*12$L1hxT z-}84XixI$u#-Er~L{(Va9>V&X$l!tHddXS(j;vj3$8eq{)!GS75jFjb&^^g=&XA7T ze{b2cC(;wE9E`gnfP?Z$GCCfeJNmnefE3a&1W_`NTW3X0VyhfEjl^7v0xH?@?1c;A z7_(g#e>9VmUcQnfJ$-%YN1I=~sN`FS*PIz7+x=2PSwX1?5?^Hakny=drP#T!V~tpK>HVtgW=u+|u_kwhuXX@0mdka}x3>+GHgLyX`OcMV-d*zqApp8VzM8KKXKZ{@<-V8G>&Dc3O1OQoy zrC)Y~KYHm zrR1cJUUwrMZZ0lAx& z7x&buByqkOZ}S=}UgiW0YbOSJmQvF4`#9c9Js!<^ZxdQLKH8hv6U;(7QKC@t@CnX; zfx$GRy%Ple^8op?~g4omiFzcc!w2M-2B7xtyA z_}T0!QA(HL7?@b;YeLFj?Wc+*uk3Ey026ZzY+|V zqS=Ld>QKYR?lz3KrFB0Jd`48s0j_3M*G&Q{_6*($#?)J_T&}OoV4(OFLXh{IM=+|f z$LK%Lw0&z7#?`)nxyMCpL8Gc_em+QZIagKB0x)dT6lxz%lD2)sIq&}jc{xG?+_V0| zcI3%9bLME+PdYnz%}p^WERail!$r_r$M(v{%{SI703Y}sQTRud6rRolRe~^-7LEIZqe0|?84F1M=LzeZ~iQZGg_qCLdsqg4LMiZ zpEx={_?YPHeUnI~U&l%17gs)a$Q23d_M9m)Rij#xZ{2;CU3?;JPnI#>#iVxCc)>jR z2Qw(1T$Nw;817CLT}TVKy)*H;_`Ik7r;FeUA`->t3?lL#T_Z!Z{p6sh4*YR);cGm@ zkIJ=w0C-a=FtFFfpf83>H+$@XE#^wdFW^-#xM4%JM`}XC4oswIj6+e9sY+zJ5_NbG zC3oa+^C$1I98OSPzR}V3wN(9O{jj0K=fInbd_DuFGxx|=o0zL5_wXB)!YCDTedpx* zE0x8H2}2kpx>K;Pddu8?P$J)}s`zMFxPJ-oo<9~hn9#kE|(pZBb` zn>Y0~l=zsj8SozY#t}VYacYUUCf`$wz$Z8iYXqT-e_*_Op7+hcVA7ARa5b( z8)aw#-7rt6d>zKj&t^^`a7$}xMD$%0Ri#he(HY%F+{k2+78XvDySHC9@AC!O!=Qb! zj9PBZ6^gQ|N$QIFkQVku-XdzDqUWCzzlRFPMKN`2jqhA0ndAArbV>upC}_(*SX1nJqI+tf+f%iDz$hql3M#W@Wrxm#PyQU z60iymgnl=Ae}}o%KuR7b+A$Np@S)~5Rv1iijxIK}GGHIY1z0{m&$aJJs3cleO^2AC zKe3-X-WsGD8G;5t=VPGfiyH5`3c$uK;<`LuAS>;di{@QkI5IrKL~i->7mrC?%cGFt z**n)KIUQo$xxf7Uly{g7VNmiS)^sL22M3Q?df2NOjANLA{N7O4FkL*m8 z?V(qAmoK+bxIJDD5jbhTD%17+uSr^50%E}nZ$#aXSE96&6oUw1g@_2=+u8BqO12~x z5qcS6>6cmzH^^bWSktpKFW=ud&UcGcG99HA zf7uZe`5fH`8*YGPn#2Q@q6mt?jorz{mYF*ZYr10%Gc8+74|FUgX`k=(#1@6rcLl23 zw@07mLV^2B4;SUNpubfORl@M#Z%+OF{G>0@pH+X@A@xpLkdTO#L87h~3*3aFlTz!X zXs7E>_mL%ya{MM0_e5XT-g7KNLMlPWx(ZBRUFV$Rhdu1VX3XH5p{BA$r&;0MeY2qU z3IW>PUTjf?Es)qk^$?D&+bngXxZvk)Yb9EbUHqpzS~G9a zO=wu26MIFcCbD)@wXM5;FMB>lM z{2kn6tWS*C$Zn3rD`~GjHDv7kPPX7V#Y4d!-Fw_{LvE9o})Q@+Svqtf`Vd<2syeAzS@mOh#Vx$xt(e~>6v8#^8MW2%wwR2-`XFlL; zlyZl5y*Jn0bocH{g-;Gl&|mQ=v6?u#>3eKu{WJI^AMm?B64jXYQ4OjuQ1mFw31l88 zphc{{Lt83rGONDz2)rh|m6VvwcXy-RF*+y%K%BBd!B>gz?L@DSzOqbmz_`+xH-WPe zJ?CP!8bx$f=DMF@%D(B@%~wAg2;;i-H)f_U3HAtyDO12hX5vm^t8e<@p&bbT{!g9m zX+oBjXJosKBp)7XO?7n{!^5IB+#xGy31+)Fr%MUGBaD`TXG|muk1iKyAf2id`yzsa zVd(x*C)L>6-P$-*L1s3C2(vi`FP7Qkqc*pH1y1$F353fp74})~?@gM#Sfxw=JtNgs zW0|Orhz+z#wxSjUZvg=T-oX(w=ue#@5=&-&Js;eLdS3VPbs6ie$POvGD6su7+I69W zv}5&D7i$1NVIcFDAD5`wYm?K;6=8Hn5(1(3)}r8sH+l5Y_H@t}{O;9l(efG&MGY*@ z^06zw5?tKW%_~2#*fBIRW9d=xYHEq*I(|>JD++&087iSuGPoUJnp~y)_r_qg1S-9X zOEGLrP7JA@iMoH6B7zVC63I;LV$zH_fV~ekNz!C`IYcp7EKe9rHfz_cSwFM0TprV{ zfzcMub6}Y$zP!9HQ(e_|Nji$u?vEXX0Dv$n2rE{ z)`ncae*BWjRYRb}w?Lutyl~+ox;CHZLG=By7DCBry}zVcL%odV=ly2YD_F?*Xnbs> zmGg_!V>3+dmo0cZaP%ow>aIf8vbgr*g(-fAcRH2e_^z(5EREQ#X22zC@P!^Mt}~JJ zN!E`VNIrf8?z;+iT4#^Q)bWRrFXFB1wrS{}{&&=Te3C6*fsrJ)(d$n(M+!E&h=uKR zxz9HS_8JB_W?yeulQqC#jEpGEU=OXu9GQ4Z5+QqVVqJq1w?Fb} zWCa%9DgkFYw4e$93U8&mOzjn$+nhl}dx=#a%h&EXynKsT?A*^pVeev=lz=^CI}s#( z_xp5AWsVpE?B*;!`k!CDmuT^VjMhDwHmnGVi(5fh9YHD}2BNfQ;K#6eCPV7|VN%Rr zl$4=i=n3}FMWE3&ZR}*vuh4;$K*)AOOpW=@r>pJQPj)C03E%@TS}~J8SMPb`h5XVs z1qK3Nh%XzS0Ol%-<6T1W5wnHl8K|^$;nQSGgM1_IlnIqJ{Q!(p1ylQB*K_$rh3?tEN5DvaXWv@DD zM9@oZA`-8PBZHt#mS7iTOXWDO@UjJ8B=3z9_RhIQ>z^F8t0bE67I7cM(jA4Kqx=25 zP~9EIc^jJ(WXEo+t~4%oE2!q1i;mv&EgCG$9_{4)FZP$eW-jJnQ(QtEHKMEceDTq3Ih%uSp~<|GUaHY{qWt&G!9+?p<0aBm@8SD=-O_8BteCIor!&c)1PR%5cO_m%vhigN1kuZg@tllsYSQz0KbH=pF3OG`sK6mt^k)FH_ z?t{ntJHJKMrVWJ+(n340qkIZFyMQb$TFy=wFlW#^t%^+b;x!U+F%J zb}U=;bn-Eb5d^Ckle5lP6$AyuOy#gHs6A~Ot+s!eeir)Q+2GH6gckaP;eVc9Jq`=q zaj4n39|cglUE$Sfv&$AQAF?hyj`MUTw#i17bTp8GbPiTTTJp4jlh{g7BW64N3At6r&bmivt+&;prSC&(K90%6!_?jFv4}TZd&KdW(0fsGKI+ zD)8oJu5|n~b(ko6=!?AbC8-l^jlUNK??V(PFMp+)B1kil-g-Yj03AAGqN$;A84hRO z(}YITT|Q`UUJ=GtT>Udp6zU19+aN!GqwK&Vm;?U=P3I*bKB7xH67P35DbvK^wbV~| ziW%yJ+$FEDf{{pWVanhr^8;2sacWN_sgx~Bz04q-z3%;yWB|7#QU^SF@`S>F?BMh- zHzvQlP=z}E9_hhT+YrBef&$udL5Un9EKGT#EbG*H_)^%^C?BRX3$Mt!q>)ZT=ojR< zGGI&n-fMDv3^dc9Cw50&mBAf{KbDD#NP%U|&ThckEP=o%lT8e@%N_90aK%T0w75?H~(J;^wv-8=`X3XkOXbM8CSxdWnj}QQ^sR;@wM< zR{nZ{|HRf``*1%LO=kFQ=To6dt^rs|L*enN>VE5PK{lG^}6mL2dd`rSA^^kJLUV^2n=iR>DUtoRz{cQ7y*1>cmn%q;XD}xZppD_b+7?j!8gt3(2C!b|-OdkMQ4=wSMf&xB;R| z_#Fm7Pyet3xsIqyW13N6n`QFZ7%BuDgF{L@%5|QN^hm` zLtK8Whw)g@2jQ~@Ug=%sBE<9UH_!3&`xZ=XC2sM;IT`huA3*=j&?z8tL?FyGYrHFPbH_NkH7&0P zW2w74W%_>+XdVhgJ3x6-3an?F4d zs@e)MgYIa4F_-q?!?zOOkPUkgix$&~f8=*Eap9MrYTdcvKU)*8{`?sVr`sjZZNjf^+A=i>^F-&}$l5;df3+)o+Sxci z^{LWW5#detcOJ$#ZMUA@*C$o6TV{r~7$Y+!OsB)OLf^?@)}No1-jr5T+1ZULi^G+R zdX^@bpsAhKnjnWc@Fu+a){wzU3%QQ+BJtbADP{|;O?%Z{Ze4PD4RLo2VEZ0j1WNQu zY3cd{9*sG-Q3YHI32DiGxM*tQ8q-Gd^1IJ&;QgO7Pd*}QyWJ=c73m6L^iqko?Il+g_o|gGB)To@UcUeOq?EHR_Ol>bAGt(P(T*@Be>4$&Dzj}wAVO6&})5xLp*jX zclMMf?iKH>|n>yr}%g4$ijEF6BK;n)bDMd5Qo>WD*mx; zVboCJ7a*b>vSY5@My$b+eH*FD;OBgJ-jzw~5k75h@~VmOj~+Xx{_;x~5vcH|#3l;A zsP-;Z@ufRJd%^w_v0Epv$l<@}tyD*elDiprw;X`pE}*P4vD@aCnknA>PcUqwt1>%t z!7OcnBgA10G|Bk#Y*Vk4MfEd}H9&*qh{YugQo#FO3DzmUT8&nH2$a{5Ulok>$dYro z-`9f}S7GMG@~tIMtevrcr~oC7Zw<Zr$bvE0H+?(vQCze1d;2XP|G$ZPfznAyE$ z-lX4uzqqR88Wz~BQ`7ugkqdL|1^YkotxYpbrEf#79E$_TOE-B@9PJMcB+hb2^cfqi z`2_@&fmXk68&EioZU|NtB5u7$tqdBSNDU5quwQnw<`DrVHLZwlG68E>b#F`}66f)3 zmb9I@>V61&W%KXB!uQHYK50zd;{*Zx@-C*R1Jj3@{&#;?0ks(awst+Q#78&qKj^kr8WSx`-&bqB}zKu`(Y9Tkut zl+5RnS>;biXCLwrz0B}n_fk+KnpRPwQeq+_Ej*7uD2>qy=$Lx6?>lgQf*)?0x;7JO zyXY**3_p_CB`A+qk`WB%o=4AwT4D<{+}#-KPe;xths(R3nlZ-_*toLS$B!SYv7{pX z{Fd#gL?nC&y&v*A(JC*gdqytZRo6KC-E~4gNMY6~woRt@QJ;!QG&X?c9643@aUYI0 z|3+n$UuP(|6nEtYYWIkll)~r`bE8_e?@8WcO*QT|jiP}@gO7HqADv9gsMdhCtmgq6 zbgCXAf43JHvUBqOHJ?=Y9x{>*L!cx(N8S>Ww|KJ0(b3U%<~q7vuFn!?Y&)WBNpgt9 z9zhFb>Sc78ZxR$W0mk++gK7L!=Rke$9>bu3fOX70S>O|mJD(J+{KA+(@b9>(!H1=}emgaqPRlhQ^Z5hYLCklO+6plY} zs_q7$yX4BzJ{_nOGPj+p9^1Sm!-}p(3kh5L=IQ;Ka0UYDE4ENt^2aug2E;0mJc(wW z@W|~!MS&NaEz??f14^#f*@-hLe$#&zs;uu|Zo_PrmxU@4J8m{MYdqx5pl)dlQUUjzKUtvvLJ zi5gA!_aXZUvGI1Z2CcUPD6XkO1oR5Tq6me(q1!MH>+nx@IZ8M;sB5fr(}2ig&`HinuFptxlcC1#2V7)Eb8r z>_#Clbat6)#?9IVJ=07{O;nHR%Nq{>H~`WX}Ns+qKyh9+(k9Kxb{$||jx%K(9LMs1~IfB@yVuP&zlxYHp; z_*kvj0Tu%Ii)aE?u2>QGB(Qd^2Aa@a9liF~XKihpzPnPuar0j|{?pmg--{_HE=sEX?Ew1h zjc+d_0TYD3@?a|PCz-V|2VRSJO4b}ba%88maZJTtAnU8JdLaG&I3eZ}c7)&E(PTTT z+s5>xj!R6RJ7FzN)%EcP>={zw5bZXE>D3n^h$j;JTREmy%WiO!b?hz&*cdd|2u)0hhj`z#i-2D2%2QFN&_rpaSV!%hQwcUHV8Xu_52rN zWZtsS%a;YoEcfSrT1$Q3&A2!ZE=3;yaBqcpqQ_Sbb?$G5PjDZpM_i~1!|eh&KqXa0 zvfpPTi-hYRt*7RoF5U@OxO@ro8G~Ex-DemtgvpQ!m5AQq3E&*rjn(b^I0^IF8Sm`d z)5C;>L!=T}balcCZTb>+k{&x(`Y04|-!FIz=~>vb zA1`t%4mGwEi&blgx`o+fLgvX7wV9C9rQAOxj~Ta=SaF7V)mF%I_qFC=DHD`P1yQq& zpGO+pGZM+xuaopS0S_%Pe{;|}AL`eE2P+E1Kd$bifPlbjytixPb!WdzQj<6mj@>vj zhI`I~uU@OE#Jw9m+zv8yt!jqNv5XiGh;FLovb}OSkX!kB?h16U&l|f6CdnYvJ{l`z zJmoj+^R_!KJEyc`F0l(I%b4>PwST$^oX#&}erWoBrQR@??grg4_xL!0fdLZ$k^4N# zI3_AAT(9ZOIeED!YD;Ygyeuo5;z*z*iVU>&x-W0>o+G7A_>pi-@>n5u9|z|$3fycBjb-k zt$ouXsL3C~nV0A$#AX?sk7hi{KU$mM_;WZ)6vT^Gg?GPCgQx@lr~K1r&M-`NY|D`@ zF1js`dHRv5mLN$DbL^+D4gIyjqXu#1dqe=HA4QskOdqFq4`6TW^*R-Oz(sQ^VQ0%9 z`>HdF8p}#Mn0+#ZvsccV)akF@f^P1ard!!<2q<1qN-DFYFT=hEb3nQIuTno}9&|%z zku0ZI$O?1nPWy90zocwFJS=gLKHl^#WKoBnw)5~B}q?2L# zS zo-tycr12Z9QJ#eeIY}umc|INHmp|FKMx9%wtGB--s!6X%{D*r0WBeM%T(|8Fpf_(Pu=BT+AS zC$+D_F!fGgQ`9nJBhJ0Fv>K`dt$*;#jaT!BM{kWcD1K9nS7RYVOgPRJpudefh+_Z0+qfQyYpHy>Don?i+I{1&9LQe`nfS}4@5a&VH`NbQ zhKG+KjzYSp-FnzjdaaT6>-_rz=`s=%$rNLD(5mG7(_|$6ljk*YY(nzBXe?q-pKBgw zNi$7JaKg=AvhkRC$8UCz#<}Lc4XFP-Hr^H5r?1Z_jyg@S)+)0frCQ%{;3E|Wf9e)T zsoY>qjY)g;LpL)_M1NR#o&`kru#9_ibhO6KbPi_Mdr`3WEVwH4tzDA|{hzItDNZ`d ztLr+hw&0?DK_s~hwOn4kMF@|oy?cm}_MKDkeCT(w1sY})$Mctd!4=7PVAw#3qXA4T z9xh&e$s?fMsqlXDZtD`+IzE{S;rW0{?7T?+e?B`kgiPNY*E2Cfcm!yy2Ki}2U1oQ* zP^J~-rVwKd+g)Z9T6%_OG?T-YF$?fbasl*pBeU*A88B*zv{=Mt3NchKgU`}9flKRO zj(wcJ%7ts8d8TJ-ZF;?5*XQ|8<3l$p;*mr1sBvntoGX2QD;`{d=9-%Eqzg*v!#xii zXJ07cng>FdK0v^Q)rzueHmoUaVpV)>!W4Snx^!ciS+4k_@4jRbbK^;ooCtemVHo-v zbsHO-ux-QA9HZ}<&oG=2o+^Fb5V3nheQ^5}E|mtd_k5iki#uly=Dy&8CFRj z&n&r;`f0BcquM$r4ITGO0obddTQYDX@LN`J z>RzYDYro$-U!Qf_W#pO5=-%{1V=Wg01a8!Bxh2Y(Q3s5TjeoDtU9^QaYLV81Gy;wq zCF#K5hRAkOW!J3O9?L={o=&K*Ir59E?-Ujj-U4{-tv9>m>%FjfsT5NT-P!DngKQ|d z1_$^zQ+;(?0$0U^Y+vsB%*+j1l2l?0@OZQJ*H%AoF)mFlt@J@DYYaO9$Zz`N>2lK@ z&pKJkGASWh%={k5MmIK{P9)wg1o}-|m5=VUk?C7wo<89T3SU5AfAc!_+=5Dq!EMd! z+~uj@YSt-i&oJo5;S{-cUFf&P{fzD#YTu%mXvu~Qw1&!O>M+oF&NO^?<-vySL;#|@ z6y)NrTW|&WxXCEC5@oPuMXPraC!riK)HCL~m{~;l89>e&Y{Vt78L^u|~hoDx% z?dRB8t7d}@KUK|%lI*~{vzw1YgXX!Ell%4?jbK z6NSmyF`H>w6cd$j6CT^~L^6_=e)`FkI8n>?^&>1K&jDx1_v|6P{1XZRd9krd_;-A* zc0h};5{qd{*qv^i7NWLCk3|)w1$IRh*{C1MPT${ksxNpL4Jk<-6+EfN`!RDf*!H@kfbAu80+^}iI5q-IU}j| zKhg@J*F`iAszj0VQH}^3h*tW8T`^DiwRmyLs+>mdq<-YPI%dd)v7*^_6WJ*jHa0Ik zO|ihnn&G4o8IEHaMY{b8gLz6pl)HIXGSj82rclmu^1N67hQX;Ce2#j?fh@P(O zyfXa3viepaB>fNNH_jf`i@k6494EzfqYs%Hmc+ zGZ=8;0?X+&ZZdv*R%~S~Xo$635HA+D8h-Z}LSd$CnAzCTGsB>@@cx}ZL9i2E_0-9m zB=ek`DaW-5`&Ee-XRBPQQX|Z#f=5165uB7l-%Gt}Ea>QMCX+aLCar=02g{p8cQa#9 zI?h~#vZrXK57EiO<#K;HSvW{{>5W~*GM|g=qK~X!Uruw0Bg=~S@%=O2VKT zLE?YAPM>jfz}Mn2{h}s&3&mPG9clD4Om?Y3o6iws&D@=3c`r;gQ8yxU*j|^G{K#tH z9p(c+k9f8i*_3YA*}Hc&z-lM=<--o~U?|5i3k_erRfiFajZ0cddJqfZv92`3x;Yds zHli2%0AmcH$i_Fs+MGB_!j|GGMFO1;UUmkx|L7oLQf;s>I`K+O_r}2fyRY?36s=Uf z-glXw?7n#E(m}33ZfHkn~UA~ zLc+pU0&aJZQTFm|uV9b5He;z0b+l$nAvc+=69vO91QC|Ly3-HQeqUkqCj5M|wPWq9 zdBaDkgp8X!r~S!I6!wiPJsLCpxN<4bbBH|b+G;QwJ$oqk#>jrtuYXS_n;RmGf0NYF z7n4VIqVj%8SaJ3dSD6LaYAFV(glTafCJz3tSyuI$KuEZ19az7-vfyk*G1pgF(kW$; zo9YHyx$Dycp%Yg>b21oRu_H8jp4oEyu6&d`p`me3&Axs%^J?Q9NtSEv6_M~aiMSy3 zaXYtc6&n+$5Bf08BNZ{CxygY|vn`%CqeAoV5Z`zI**9AW^U7H50|#R81HD_Rj*p#n zbS|rZI2z-6=MP4~;nA!N?)pk5H{s*>GVfY7afqJC82@$;Q=f~(7E2fg{dHrcsQs0f zeqL}%Xq!vdoAYO1Ii0vC$*e4rVHIZq;mP@JZv^EU^^ABSFA2x_s!QP2+zMUh_6y6_ z=drfm%*e>t*4Wjzk7HLxT%JPlK-s7{N==0D$bB6qTXD0A0g7yHu6`a zkt{(uwXmg%gFaXDeozDt3SmG=4nC3anv(nRjKiDphPT+8ddqKcirunF_6{hHf1j;o zJ`P>}jUBv`&-(ZOVGzZWDVZ$yMSIT5=x8{IUpFT-ap3#`n(eAB4az#KEQCz$dS(!G z8`knah05rhX-;Oe!8+-F3npr=x1Q=7OQ;KsYufUKvhdLj$>{uKZg{|PjA!B$gTF=V zmDM*hNK$?Gkv-bjnfFH(<2{i-kw3w&R==)r(l^pO2iQX$qh=se*FK)KPY_%j=Mt64 zChKL0W8B`+vmAxjyn9$~%d&M?1>xLZao6W6`nhnr@<|{gfEe!oJl!Vd)rQA}>2q1N&-Xq^){%$6Ndw zCG$DNmYUdW`@e!S+}S3p`?j(tVmNXobhd5ty9~y@RuZ6QvBJ_*M_-iv<83;n{Fz8@ zljm_QA(^feFB6CxCBU$aHrFsxb3?rSl-7~K zfpQv{;c!3BE6wOX8YK3uW}{=fHrc}rKySsBI~Dr@-}uCGRT}vSH@xnIUMw8KcHxA! zbvL!riJ2|`Fw>~t$n5y{KXn>8j{jJ;z!IWBCgu17*=!KEJF0HZer2TK zc0}iE+S88kPLLzMZt+bF7MsyH>z22kW4+)IV#*pZG3S6?h2jM0uvWE8{hFYbxOP_J z*aE8+ZvjCWu|PI<8(>k~Fv}(iLlBes%4Tlk6Ibs2kddWp)%8nlp~S za%Is?kxb{SpVfbV?Cd+?#Zl>Xy}y}5)cLrT6;V!s0LLr&8WIIHE34#t>jf1QjIn`X zcK(Yr)=IJ8CMO5Nl(RifiULu-WVG+)`(SGSt;+~f1{v+U{0q|B{a8-YI%G25cOe}B zVW|tgzlsx?wMcFt+U^$#+uo{`Q~(Jrg~Ty1M)N8C zlHScKiauVjhWLi<_ykjnFchzQWo4pOo2#n$v7rNY?-mcr)IiVw3so2G!6Fj(o#C$k z!5%coazYCmMjw0+&0GNJLFbYzJ0qIqxu(qIvd}(?~I)Okt1Z!R-yZUcQkjCg>{Xhs}4|) ziD(-diePuVW*>MgE^c4)tnZC^eM0AQIV&s6cpi!h*lHYdS@LsxQ8FcW%XX8e8I?w| zik*bXY(6yTFWs~>Qot~nj9C@Z^+u8tU* zb_H#iNsfWH1@(gB*oogL&fK5hd|m}}r;W68)apX-0@&%~8)COFi(X$Ia++%>JylakWX>L*X;*HCf_ za`g4})m>e460|T%6~tmj$N&mCF7i_Da8-JFWtyH`eI|vIlXKga^Dz%&jhfcjOAn;3 z+(c!W`=@t&EPcP%=)ku4`WR&`&8jC4d+Y#;zcPz3@>@oKsO!w_y|z%8vFz(`f2zzX z|K;erVUx|ndATvZZ)$75ge+UyHQMVLI<=6iWiGDw$s6TSlfmt8iDt}+jZDcO)`D`O zz*TvnxS>NcZ}AWhI)iOKdCR$bf|X?zt=b*}>0i=8gF6KVaZ;v9ox1z>SuCt#dBfkp z`}!p_gUHI=N058Jt&h5c!@Z-7{e8|TCDNN8yQd{AEzX>& z82v)to%hPr5c|6eo^EuMB^1=1e7oz)>E9i z2R}HNAIRf+D1oo5$k^ZP-dOqRSbO0(tZf|ahbj!U^uYVu!?f zF_TT~;O=a==X&>oUDPi$^n#G?&wQc*fU00&B_$fA{+6Kkd56xOJ$niCvck7-C9dRg z&E>@qa&`NV|9Op5t)&&OMPnP^0rN5=>oA7rX8Opbv&yj`FC z2;Gsfqv74r48rb)v%u$7`-ZiabmoJ zCLNPJ%czTyMQz+*dxO8ylLa|8_*71MLecQ1yA=0a2HZ4lxFOnDu0ePIF8IXUqDy{KV$TsS7j6j#!{D6s3Xj)-KYB z-iPhv=h+6|u7MZjD3M)V8CORXZ(lcPXFu$@Dp`TSF3O&aV=itYjl2g{F|%(}?P<{6 z9c1gbq2Ebcy5N`k`fgyXw~^@dJKc5`!>Pgl$>T$8w#nXOvaau~vtJQG3Wj)Lm6h7@ zeOw)0bZv&vJ70PPzY}c&IiOg5og`WFF)Usx>6gs5HZYe?_It*?&eLD7!~}?qUPh+@6jQ>R3pVHB7h5t z<$J0UD(3bP)rubwlNyqZ997K~i@?&aXo2q&C@~VIY{O$|OWRWW@p$niCDV^5Kps!f zaz9<`G2Q8yu0b3Wb;<*+mMX^=d*)+r%9Sf>)!omytq$_Qt{F|O@SMR0t5!&)N44*?tY5ys+`{4_ zI(!RMi7t$d9>;J}82^XF#lphpf}s6)@>Mo8ST6G_01U%#CIO!Q&86#$V_5@(X7ii6 z`*e0%CZ?n;lz(;b?u~SD$j48~mpLke@sf9M{pyVy-~5uWtX*C6e23E5Dst%Hv=&@j zTf2zSjsU_ZwR&a6a@$wrz{Piz)%zU1lJQ$C@7G8-X=YEXb)76ssnI@b(jSoLm#?N+Hye0(&|RzA6gZ99r3;W}*JQ;K+8KJcS0)lFCJAKkBY zNCp@gS#N(4*QsLG<8Soa8qT&CN+Z(Gu-xn1mWW_pxj^QZVMuP32NExuxlbVm(6f+f zB&iN>(-fvJITstQ1w}d#t5a~kryprQdYncn#WYNx$GOdq9h1D^gRQxud|DbB{chF6 zw}%N5CCfUrtYMAVnl)-Kf_cRewTy#<7!laL82dA^yI3bGI{Liez`zj@H5M#e_N`DY zbTP$-tFoDw?C`0&(A}sk9q7?z*nEj-H(w{Or@P5`hk?}G*jqyESd7=SAFTicgA8yk zY|jJ7Z^L;m`X=;tzoO*IRVEMn#!lq=(gpkb2 z5a^F8MwGF?wCn8IIT(~GTrK1ZY5V$hCu*E}T4!e`Mv`B?=Nc@Fe?GV{%57BdE*~Xp zL1q2&ZpqYincPS}^s?oQnD`Tq=1cAE?Z&Kx5-kTKvKP%fUVnZN#T3G}54PXpRr)-o zT=)1HNLpn(HX={@0#@VJl46S6SwmdyAMa!(Btl=$QYheE8~nFaX5!=9YA0Jk`R7ZJ zZ&JvOuhDyaJ@X3hA|}R+_njzmm!-WqRE(A3=fqw#EpJ#awtDr;_62Q06!+t8rEYi? zEDZAUTZ^@ghx#)e;CZ`kyZS7OGh0GZ(j}Nus6&0c%%N<(Jsk36Z;e8Qx->qeEK;JF zMeqxqDY#C<2R1SCmB@cGO1?Zm34%+6qKJEY{`W;Q@3YhE70Pm}-6eIPbpr zK{0k_TbcbrXR!Sp*ydh3V=lIK?H89dtS4Nw5__9-U9b8&v96Gi znhH1G+tEx8F^PndI4~xpbjG`|ao5j@LaoS#JY@HUP`JL#+pd)NKvz$1Fc->>ZGd&o zi9a@4JTNfuqUx)`-L%FKjIv51I@7%EMNzfuC`or6YkIT~Fk-F91+b~nX#B7^w)TQ| z9;4%-D6V^5fx=*Q<= zIbPS$(CV0EFiglW75c5fx8k4sYr2RW_nATd|KU^Y-GlII)g&EdAvzFra&p?XnL|i}t?^lv16fZ?Y$?2UL@c8R8M(E# z@TPfrC|LgM-Lo+)8zARkO}8oRaB^_PcI@Y+AO~vrPR6Q z@(sU4M4jtDxoEDnO;>zClGm7UY;+eaB;0Pt_wu`Keu=e0f26Fhf2pgjJ?z2N>s}o) zD>Ncv6^^+=V36uRk#R0f+l_r(HKMK6&xudaO^Vp%OLLL#u8Nv3or+>hNd-GJpEi%KO8wnjILCo|m#cd%yR}}8=U2d=_ z0z_i4N1nz6&n5q92_`i2OH@DOaBVvfV)KTXh2{Sk`wp<4+xP9K6j35lw3Je4nWdeE z6@^gJG8&|zy@wEzN~pB#P%7FxBGN9}i%O-5cB=n*f9s*1_x&I5`#X-G!{hPr`F!sC zzV7Qfuk$)jF-7Cdlg6f|+jKq08GCL>!l9w!or-+c3S8Wxtr&ONa;-M;1IP(Ij8vUY z!=!&po~iID;51AE*I)w~E^hdF z{>b6OyN?{X?e7(y^k8_0cnE-nKbLphHEgM)sp@YjoWtfOYMnI-4{4^d-k+vSp*E}I zja)vKe8u`%Q3>Dh_VpFdIzTz*w#@4`Y*;3|rnslu{3-ti=*qqReiLl=-^yVUABuN4ICfn#YMOw-R;QrjIpOR}-PBXzf%>B`eFa zQkt~1G$nD#?+X>Rs(ZbC?kIZS+VwZ*<8IbQR0;=Tjg$2E2Uk(lk4;S{m!YB*rEC*g z3((MspCht40`!YU7cRr^pRqg8s*h3hzLubV2JCQ+W#t#f(7e3HB0k7byLKCjBf(8^ zS0rc?)W?bPU8rnn(@LaWzx%!9ZlU50-m>rkgmCohLc!3#epNU6BH#3o465`xYh~ zSMK@%dA8e(7SeiHIS*HwgnP!AF?cZ5ErCkbDC5R_Aiwoy|6+eOC>~CpJ9@HOMLxop zux$|8mIRFqXAR4Y)|9x4b+mLp-jzgofLx~Pcq3n&^Rh3)ez5GtFiQXTGh(?{>k558 zH?3FMyZ3sNFqA=yI5xbTy#%lDA|lH-6G2`oBanP}Y+kR008XI#Y-7UHk z2ya>3wQptq)3CE^*p~diFI0UTTgs`)?bY0_$~hkFDPglM zd(e7ZKr=vZ-SblmEe`-jnMVnZL9hljHP(sgE{Deyo$;44A^;d4ZzT_SoAh4>R))o7 zgH`OcT|q&i^$PEe{_3=S=eVe3Y>5BQPs}0i(Fn9XJd%AsGIpT5F*f8g(Idf*-Kf^D z1fUGZ?wAL3!&M0X*lPr&WI^PTug>W`ZotNG@!uBwiGw=rtAz`hnwn-l`Iw*Y4*~9l3=Gyb z3y*8Zx)RT3`z3vcgnc77vxr4VXty`7uVS>D(znP{pV)$rbGV;q?YF-&&lpxV)GP}>aQdBs9D zjf6*D-p+^KPECwYT$Ymnh~lTLVpILLfkY?F`!a^yvi89MVnt7dPAPwIBmhU^>NEOY zZn8}9!QH!TEtwfk9hpQ=qodLM=J-x>RNdtkhFX{JA;yoAj}jnYOyrJ!uRoI9{vf1a za6(J%AiFWicd8$KcqV9;O}p>U3=y~fGQ8b>OJ2Hpf3E%Md(;Z|s8jKsV7y&64Js-n zU%x()lYPNqll$mffVN(Lqas6{>13Sz1quhFtn+Kg*FjBK9HJEs*@7%8qZ>DFu=G6T zM7@|qm(ZO0{Q1WdvMw@JMSB^hmX1I`u9c8WF+L}?|0!&C5(2Vqi*?|Eku> zjNBB(m!9!(LScD)d*Z2#_zSPl1Ow~Qu7GXdS1Br)69(j1Va}Iv7Bu4vlxTBj-O!rojLuSp?{ zbl>l9XqxyylDm~x<r*Qw?aowKsU^u7=I`Aj`5C2>zE{zb%t z7+88)k>P|76tN2~(9%Z-^Bts|Y)u7ux8z{B*5&qzYu%dotf99mf^}6UnlJXKNVjg? z%CP%kSZ(5|arwT%>RHuGvl{l*ctryrE3%9~xsH6!C!{yangi(8n+-3N@!U7LsvVUB)6 z(0VdmQlyCVa*NoOK~6-MZMyBNDwmb|7}nBiNF{Yy;UX*U_*QF&3EX^epV#i?8fa zXJ!jt&y5#!_6pd9YEL)Al2}tm-g|xG(?j%M$Jn)&MuzE+-yj@DjCh3V?p&ZBCAZ}Y zK*bE)z#IxZZ@zp{)p125QMU+X&$Ltf6;ZYb~<*avZxP< z&+lT4qz!_e6PiKaH(ql65grkt=8qPX1ZhFh!W{Cj+B<-~o#I+9E}yA~KYaMWWRw6A z7vxsfDYDzP9RU_4_thb_)QNhvbHB%LU>Dm|4|PfnOgKR*ejw7ex>Z#y{s$p?;%-NtA_9lobb><(Gj!EQ@B-aRK8~ z`*6W?Sc|yG+t?)D3JjETiDvnHrd@M79QM;B^zZSmAHRWUkZj%mX}@Z5nrnM&>uzi7 zf&L3^Wx7m|s`ex`MR{qdg}sc7hXKx=*Hm_vok{W#1c;Eeza&0XIHwKN#1XF*4R+Z1 z6%+&zgO-7TRq4LZpKo~f^yx}J9yla`c76G`Lw)a)*1vcfDj-CT;fb}BVe?rl#dJR< zERrO=5XsZg(b<`7)05U{)$y`jYin>&(DrlB3GN8UD%VEqbmTh*PaF5uLl?BkU0y9O zuU1{U##-jQq8E$Q8CEqr2H|s6spB_rajT$pDRoDmQJlVG=PS@3j#~$4l^ldGleNcZ zr{ONWDXn6eVQul)!f7X1ItCF72qF+aHcl?$+u1U4mFGcZJJ6z<&S!#S5G=j8a5EtL zSqdIY<(sE)UlprUDAa#9Uk=y`G^0d72n-~RvI`8tjhJxqhY45#&MC1bH0$}UbUwYx zd=ot)9)Sei$m%e@Q(c-kEC4H0j<7HFG%?SglFYz3ZAy5%M^tld8wa8LBq(HKg z++CBTzh2>el$n`XRi5_aJ5JpuN&hXAYB@FYbFW;X%P%fARNt;P+bU@c_<6DV8xrN; zXhb~8QpS|T^nM_BavUvmG1|~dW|g^-oP9scH3GI4FnuhHYqztdde>ui;xzuSeqO4c z`WR(8E$0}$M_!jNr`^(V({YFO235LJ!8`mp?gxdQu>03bkZgtiA?^-Aq_@4HcT?-R z?}aQu{{L-b#p=oa1!N@PdUn-v4MN&Q8ULL9=;=k%Cx0h@9OeUwjTWZ}f@}y8>);Lf z%ha+`2b0#J=YI1L|*Da zL6Aj%=QbsuI44?KTB>htD!P7sr@{Sf-*eS*J3xIkHQZ|7CEK8#a_T)JYND;GFHg@3 zBkt~2h$9Y$vwsOMWxrpZzRDcHKSIVWILUtQ4AdsYEJ3IMD6i3T{&A_}M@9@Iz@rtd zj`*#o1+Ep2^<&J z%hJZovQP6oYU);~3R#X6CK#1)UG?^k*S(-LomtsY!%#Ct8}{Ce4nz&SI@%!eeuS4z zhug2YZ_$Ook#6>ZVLIIZc^gG$%}mEcNSNzF28BqC**Jd2K{v6suKH1xJ$VE=TwdFq zrj|TRX)sXW$A|Z(`&3m$^extcdmzBnwUAS*x$*O3&aSr|I|D;Q3paJirm_p6Z*R*~ zdU69INtHgQn3CnwB`jb?z=wg9cEJ|X5Cw8ZNBTPf)dL?x>4w3 zRirlPCP$n@8c*wiW=UC0tRxo6dFZhtB7Mi|o=PrG&K`xG+IVcN1v8cKlUlf;#d_Uf z+qRcqHFWoI>HUAk`ZuA+yz_k>1f1%xoJ3vufVM~G{igREyu`I^$-~oUrXPTV!rviI zLmaLa7|B}YBiz0D?AfzQO(p5#_FYa6X#ePx3#iR{Txot>v+s?A|D%|qpF-W!(?fBg z1>0{8R24EX0&+G*eY=ZvSY5-L4}7SlPI^q&x?L;2K#=!(z-H%71B24rw^y^O#Pj2I z^aVXo-93Bp!sc##)`AWvs@za&3~t>fc{m$8`;rAKv0Z_O`Xi-p=|fS|iWn3KV5uQ= z&(aknKDnFHVq9L3c;+cijy3&6rQA0xG8UYS*&sGHHpjN-5uUJV8T1-Kq}+MM2NjtPI;t_&TBD@UN(b z{4ViBK4V>*sNuWQh_ZD@BHeB2;h}1^Th$wr&6e65qE9}&X%xPtwq_7fI}mM$16s$A zbF!?$=q6f)?Ci^d;-7XFJ2}1c_4z%Z#e9gccf9-%6!|gRwNdrdz;Ic4`5KZ#78k2} z9Zs}Lx3!r53ug|@{}$s?*2SHx+3WygZ^jaWb820QX^7Zqd9jZuVGv@e;$cF^En_+l z+pVMyuC}kHUn~Jd1wmeQ!D-|Pst;9B24jDF8z`kv_IEB*=`d9fM{QZz32hcOHqugg zpp)Yzl_0O8MvZo#SejQC|N6`0G{hcN@MyFj0E%bNpD*jl=sOn*+u)z5E^l;jrHN`8 zPOEL?q~@TvWRjsa$T`Mk2iig1<^5_U=ZAE;;4sRZynvRrChr2p=w@d9ERwN)y(|W@ zlz$dqXnpm{l%1``a+Zpjk9f=@>s`;-;}Vcm+6dPi%V$;X@B-~D77^|0J{z=cLT&*X zhb^Gi70pA3$^~mt=o8mB<;^n^DH=2hPEXCO%fDI+pId^2veFuQk;{6hW0kcUlz&R@ zfG7lJ+Zaql)MQ4Are55RkUrRar*q1>g=zDtz0t?Nv3=(wT}dMPpZBD$7XlEBEzD89 zOu&N1R$&gm;H;}2V_N1E&`2`tn z^X?tYN-}c!dpxID0CHsaiPrpu<(DP*H|LuppXPsB1;PV8|*cIn4=k0 z8LQW4Q3Rat9P{@B^|C^$T!`2#%d0b;k`Es}%61Tv7auXhyFbh$FDk6f)6;W5r@(9S zHymX$HaBM#KD2tzrZn5LqN1X9yN}R+9dbzVKe{y=_e0eR1X&^OHhU+exHM<$SYWB*FEcW%dLk>tAFxj@gw%nvnv4Z z<}^}JvrltC|0X8x>=bxuwd|V_;wu4KOL1Gx)Ohw(-N=KhUu^@|2jjr+6Nv-!2_KM2 zc<0uxQfk=-kl;R@e*64=;xxqUEO?KzDI3Xzu1;M#@5ho7BH-CHf881x@49)^N~#fD z;$MTzf^YLUJUhsn<@%HrS~(wowiP_atVENF^~1ihU8_x{MdX*y^lbDGQ3>)1d~Au+bvMa!js1_K1=$(IyK|$XPt2J3gBt9Kg3&y zx@#Fz5=(WPSpe$c>xY}~dvV=lH%oc_cB^{cF6j7> zq>A#xNIG6=($y<}re{^LsQS!ZS!?6;6)RDrYugV`Aw^_|iXH(tiX^yMepKFZ&;F-6{v$*HMGS=vWF3WY9`9byus#b+7vKO72TQEi_2A)_VhZHDYNFoTBFx84XMw*58%4N;h|^b zxn2yBn?cREg!jDZ8R2E6EnQ1EC0jT8vm}{NaZfLBJhh8B+nHUqJzR}43H_OmAHN$( z|L|dV$^0#aH7^d-PkPDy-T@S=F_-o{s0>K4z2X-`qBCNm+vsOzpNn}Awe*aFRMSEt z$oUExwbwsTh**oecTh*)O#7HxQdvo(j9mP8rxe$ti9e0bi!a+mxo>BdSC_!WCZB}< zPK{wXygGSb|H}oSS)Ct8{->N?`MsU9q42Yn@$fkIW=kxA%OU5#Rr2dhTPg0E`{d+3 zojO55K~9Cq@un%WtuNz#mhNN+hdb{~K=Dot0%FcdOG5eNtky=3B~sPny?2;4&TR9U z+eQcZbI0{9#eTq!TXr{rWur{7P=`>J&ucpI8_ouI6ZaKKWgMFCV4M5E8X05KjI8 z*BXwWDXlkEuJf}Tg2G&k9hQ z2Z1UHHf}pP7gZ7xxu?hV0#bsFZc{Gg*7|+JD}@bF z7y5&?&$zMY##xD`7C}iu{a(yav`%NbW0_MgGQJdE-1Gf?ln|+dnM+xH?d-T7!->> zR+B`6aW6ubA0&ls-ga5=OmF`zv=h1s*-~+(GiXsCO#d_UrMFB9-g_EHQAq!{1z3ultaznR>~r_ zU$6SreXPFsDd5Hy>5;divs00onCPo|wOXrZR63Xe}dULj%XiuVu>-wSk~ za6@+ba`k-nb2(N&*)BI#vrbbEp2lVQM@&O~U^Xm|8N~J@tSr+qSUJn7`!a{aLmj_A zV^r^Qx@T(*qQH;0uegHM<;+=EtN?P>;{MAd663gA7nbs#oSQfOB_UAm%YT1pBxFSP zkI|sn@vb0{6QTwbzPu~eC!Ep-`G#h}0$=NeD!P$6gP0T`6!<&WBkqxnEl6kl+7Ya( zY|ecZ6%}hYZY=Gve69?FVfx*(UY6!J!r%4m@Sr+0I>O*98rxS!bjvd)$GW_#$}c2C z>kERD(!cG#4^%`<9wva#k04FTS0oJlP@BqQBtC8zdK?*44|B;zy4S)cg!x3&(V8m8 z*>RWM3=Zxb^l>uVGC^68%4~j z_8)~+;iksO@f#R6edwn{KZOG7bn2JO>>1y36sG@bd#z^FG6BeEq+I%@K={i{qB`cb zW!0G_HWQpgMGrXDf>vT`NjBQTg+I0m{+fa8-NPB$-;7JSqcRpH2(e9eKH-*6Z#43q z;vVC`BxUsQ`M7t2U5RO~WEDk4&k9Yvk1GfpEh!`6I)e$`;kF+hSLY0pdQKhtGpG0z7ueyEVr(zqS4diK->)XFCk&f6!{X3RpMhgD zJ;&IEBn_Q}aiL_i9pU*CvSRGJP34!YPldb2oFh!|MKV{{!lDwn=B_k`s#)m~8E`{i zf?Gs=`X!rLsn3NCde`lyP)Zu`?~=#2xc_F_7?}fcKPBJYc4FOFoW@2GLVNBpY_c;J z&ji3`)wr8N9r>+v4;-zI=H7Fp4UQCnLox*;)vGR@Xk6L2&aA3Ju{X7yiwuY@i98I> z!B}K_>3$93Nd;VcAEQQ@+M#Q3mBl_IB@9D8nE(IAAS<8O|+1g z`dVxH^lI&Pb~1gb3NegFf{JUUH-wdwqt5%$bwP zHTVi{U1iQrjNlgN)DJTIV<0gf4x&ASPPrFmcAR4K(}y>10;#V(vA*GVqQw^l^NY>p zY-3zm5ZWpWC=c}kpw%+GYJ!sxYyUp?H!?4lF?{*MtSv@1TRmy5gm4FA-lBfZy#~Fg z=g&inAHVZJbYI58^6gGy^!BT^H5Fz~E?!*hv0`8g9o^?0M8ZP>oiS57OX@J^*f8n1 z?+9XXu=AZB2OhR}CF{dSlED_W5^x|5GsFRl?<1S-hxW0VIG{%-4Ykgn@cOMk(Fwdw zi?m#H`=+w4m_IdlQUF>A->d$)_ zvkp^+{8n++^<<0|N|&gvp>SLKFOtEBwhz3%x8R_%ecu#>4GMrUcV0D+5o?Fe&~yG)I2n~(zWu6qh{kvFnDSEieheI~=&RRkIYxjJ_IPsdrJRCIVHh?*Y!?1S3F!oXp zhA_oGcZMag9PK#xv-q-YZN-DV(|3~*Z9ueM%N$$_&pnN9l$4h5R%m=6QunAY?h`r#SCLOXC97Q8pXeU0O5|d_pb8ws zL&O-IOwazZiB>!|1;6&ZCub&p2i?56#&OxoIW&f7a;4hzuJE6mSkhfT;Qn=p>CO37 zU_tGd_nsGKlT(2v$`G4F8f+uxrzTmIxU5QRkR#x%3n%h>?@@L_9oU`h)x% zv870?h)mxfLl=ZjL(bXr=`4$eI05``w(Zumn%~>Eh+fW7`$( zkdou~ae41I*b#=zZe69rQNSe17VidQATvwM>G_tkC0}hdJ}Y|8d;Gg>xzCw|_%6ZN zj5Qdtq@uNmd1EOgb=w(ef?yi9*(sNv-uL6I%Xf%+2MbU)p-^hs|N1g6r1f z$Z*cz%81`j1(xQ`kdUrjH8+tNaqFv62~ReniEywwrtkRJ-HbC8{14Y<^!2xn-xct# zTa5u8f`>xruPIdAW2On$@8`}Ei(XTWs*ziJn4J=RebGkihYfIoP?qBbbq`@%{rY0N zIao@+8c79yW!;=zui|6KFTt-nNaCv;qd`vdC@!vaM8S2MCU^Eu=|1*dIyzyuFkkH> zihJzl&71q!r6`rgeB1c2M5A4y10+#_>9PoMh5#Kh#PC@U$gr0ort+>}=# zu}N;$hN5E-lE-|)(%H8^cGchc1WbqZ)axEUu5xf_WA9y-17~>*n(kj>sLj;zeLRf| z+iU2fn5J-&J7xwl(_de=NEFQ)Q6OVr#1A3V^5c5m&`Sl=7XWxA7|>}I&mQ$r>__qX z6L_@>(Y{?Sg{g!sEX5+~1T5wXQ>YdT#ceXlr0VPWJcIpj+2?-n=E! z+{j%U8T|*RzgmB44m!ok;*Nuy0%6uSe}nzD<@5MMvqyEW3{+x=e?pESAIfl;ql`Gd zZ1#=)|8WVRop+HMk&&3yMQWIw@MJkW4Rhfm*VL>h%8qGScR-0YQ!0Nm1at&e4>!TN zjHP|}(pX>!hGKgL-ui|=eD*B=in^EWEj@6)$gwne`Eu#>w>Mly)NEQWvzuAat>@!Y zg14Zl1S9f?Y-HKc9aJq{}cP z4EftDHsj8qXxCx>A9=R9(3yg5NoEaanbn3kYaPTzMSY81lAMqFApnmYl9x($8~Nf@ zURi0ook5tp>dg?!jMxkT49*jrgETNE4ne_WFIrnf_$YMfOMw7`2_+fDyog+UI21%4 z^o6;+M>9@TYs9Sbe&j3T$RQvG@t1d#%HYrUZ{{aEhbDjP>|eyc{+mYivr_f2L@8Gx z_sRRwQ>&~^-?6fnwe)K~8X#UV8EH4U_D3KlPAUge2A6W4x!Wp<3JKjp$KT6m7m9(M zOruZ}l6gK1s6dwpESG7HvA=%(nm8jA0OM8()bMRw%uj)&fLg+s`7~}O#uHrU-!f4Q zo4YQxj7`39gE?WL>MrNm58AAZr_a1nbZGW3;_0&p+f}?b`kH$fO~N?z+r}LqM{}AC zrdVGdrzH&>%!{iEsH&=p-FP|^SajvZ?I63M%*e4_KUBBeuC=xG3QK{*SEc1HO_@Z0 z0^+rP4{u2BRZvg}<&W-r2QAXgsz+xiF#1LwWRsz9*LACTMn%K^b|lbXoUZHJYyvDn z=F_M$+B7@%ZHz_b^DR?c3EBp;UtrdnG#{4Fz8?Ghx#d_qsNcJtouw_gmJ(r4;I6t` zOpF?lKE&Fw56C-`sdPHco%a$GKd-ZhjgFT7ofaMY9;1vq?`yd!x5w~}pbY&0#~TB{ z0(n~r^A)nzlKUK>%SvQ8+x)*eYJ6>|aEvj{+sb?6#D0D4nMIzkz(I zGsX)KerkU~O=a@kNBV3Ji}ry7+**g9@d8ro_!vcdd-^WK1nBrZmK2j=+n%(sus-Ma zr$W*jU50g1fqAsT|0(n4r^N;h0#CqiFCg1qAl&|e9gpTrnG>+6-nwGHWs}RWgi>V0 zed~%KSKGn7(hIf?Pn{wC>(vIFUI67vBc12AIk!M7fkJ-IXPQl>#$rL;$u*Nb#RZFxy%8CqJ$S4tqQ}@eP zD2l-5U8&V9P0^?Lhf0ohq(EaOBtn1o^f_(A5r6r> zD>NeqWgk)4;LYOH8OozYFZh_`NXDmz*fhJ=#kTsr3t2jG_-kJ5k(MS&99m!AVyVI* zayWIYE*42S53YhFyMIW%vvFFPjYt8Jq&ZW}bI@lLTz5b41P{AT{)!kLD+4uEgcvhn z;Ar*aI3};lE)4fFK`Y3rz4$gpe*@Lk3xA*H7NcyRSo%Lig3J%S*1&|s#0kB1R6CYQixrG4U%6>#ZI|szH_78es~HC~eia9R z^q@0feG9rE@7A5`ld`s|z((?Mcz=BrFR?)(5LcFJ;NWx)vGH~e899RQi|v&?a`9(h zJ3(b)SIg)9%`?z$pCqPz00*tdC*|_FG*gO9KYETNp89yZF4Ous!Gg?mf(OLI5jbnn znlI#l#E(KnpTdztE?On(fB22}@#2BAc#k$ApbyxYTw*4(e&^jlUvejvV77EOoGQtT^p;EerIk-+ z^;K`Htl3<2ywNYuO=eyBXN-OT{9x_rsI|Kejz~=EH@4AUyX>yZ#=&It9v^6G`F0co zr*TRcuZG#yo_PgEy6@U(fxGB^OtgPu5fG%EKYy>5)?FeKC&b7<2O;kwqk#=h|A(od zBHqE}$^mHx{2dsk#30JUjWQX=xkltnhJy}w*_rS0|cN?l&B zvx`n6+1rf47Tqe80siEqmQha=y>XtlFCt3Mme2;0c`fEl>+76T$;jW6BM)l!_l+n&o2BCAOAjij3V1@sUc`5S?NT{|6+Id``KXW})6rvb z50&vwFZr3OpN7zqC9w2L;ukORxvAuZ+C-?(C$hM$ThN%^5Tw}tStJ1vk4RBIVe8@B zgS?LZpa9x}HoL6|MuwR!6*R_M(c&rjAx&L5OBuGMsk{`zk7?}`x*alWY#Ep z>#KAE30e~(%d!^|%;oidICltbfUcMbDQk8`4|Ae6da&#HmcsQ!!2zHN<7*tHkMM?7 zl3FmGh1U!AN9j%MB_QR(8%4LOSIe~A$v?iRN+owefx*w#{7kWsR0B(X3R)ze<4Xgs zhA1(iyjvD3VRag_3}yvMsj0`VUAy)Ofv`ye1U$ZJ;I$!1WcjSP=I$7OqC3I!kGH`%GZ^UXu zI)XV*s38#>lkp>uec7Ffc~?hY_m~|tjupL`8LMkpcmyO$=KO!<8tx^-5BPB?i7%-2 z7u*HChMZr*%`-jcG~B!GTHQE1LU^7d@I$lX0axc-JF?^<+jRrx25|l3*gB?8U3)mF z0%-<}2T^84T3uf)r<)+}e!`5ZA?O}Ev$fK$T`I8Gym;|qkd*NQ(nS#x@(T$uvDWZK zaK9QVTV)#DeazvGbt302j2x-MQ{h~4QNhgmk9hx^RjXDwV3k@Qc#Bv%JtyPZFcaBc zh#_Z9GP@?T&3g`(N_Slepq2mA^AxABzdPRjF>+_VL`?6;1dzl2THfUrFf* zjom9;FN-&3%L9!$SQ;J_WIU;Vl_-zIrN|FEwFJel_Vath+i<5SE7?`VYeV)OZ03)U zs`!%R5IobJa$BnT^5ms@%K~9l^<%G2U;RB+l|8ik?wCU=l*>Uh^BGMHf+e;h2Fhe! zaRtnV+T2~pvz27>tIypbN#x@XRR(OQ=3Uk?PU}*#XQ03lBq(&n%IdYJoBr-{^qBfN zLhRnk1b**Z^V6*(>2TN4qMOB)^In;mh*b9c%LQnVl$aQ(Xb=;f*`4|}9(IimyNV^d zgd)#S=wNy5=Js3Pfv$h*REimO3Cu`P`TEAZZ=HQ4^$CE}b3P)UqHpylLy1cyEs?AV zK3~w3(ZhP2lvLSif8g}qn>fB0^1wn!ih?e*0eJYt0X`T5Y3J`(o|Xt$A)b zYfzYwBa~d2Kl6Aao;mfYR&B7>wY+<6a)Opsd*j!wC{+XziJ4#cYWmU7P9$qqgwjlBDDKB-k0L=1 z)V91zL*u2=-5trdj{jZTfhDe^(OW0_;y1fZIulX2f?u0v23se&<8ap#AD4>5WG?eq zmhB+rGwU5GN8Y^Oc^=y+f96Buu|=S#nBV0PfHTe2nhT zneBuf!pUiR=fKt6BEok%bnMuAg7Uh%|07;fOep_Y5#l+7{83Eo+NCFM8apFwBUSQ~ zSu#ZzOeTE_YJu(G9Wsvdcr;~(+lrHvZu=q>n^RRiSi_?oacK(4SoLTh6VsYz6U;n94#S#lCzK2yJxXbGsH~EBmGzKP z3gH3=hw4WzbY}LbsCZI}6a66S+J+oj(^`v1BtQRl{`n>^;+ zDXl4p${>pf#Pf!G%`A97E5-E~Vofe(MKvy7uC^1T#sLz>Zkwi6odv15$g2H88+U+F z?Ij~Hrx{OL!MLv&Vn^S|Pd?RD9^0;b+WB1GV#J`R0{KvE%Js_qsRzb6q zjrJEdJa2f&obCRP#~17*Sq@>YzdmKn5*|=H>8~Fs1krJb0DXn~8(-i|ZkF|=F6!^4y35^0fpLHxEKx^_|2V{BujX*1p@C93NN z!rYSg%dI}ft`)M%^ZVLWt;erb?fTR);0LB`l+|jc)dacq?L6wt()Sa_K_r755|~yP zyjWj-nwhCX0_a#tFB8NLP*QJ(t771{Zzt!(WBu)j$4hp3zn>kuu`-&6P-?0)ie1>5 zBS`JzN|RX-~3Qe$F5AL#69tNx@})&Zx6%NiW#m~Ui zchDvX-nSL#ma^w!*!zASQY}Mj$MUPT2b#be{!%#j$U8JNR5#>x!o7(nA!f@ajt$#S z3|9F(uoo`2G9Z&3mf+f@ZKkc7-Xj=eCNxc4TVZ(<1WSy`9ID-6RbJEp5CHDB+d57; z{LN9w&k&_B-R`nLlcJXP=X#aTX~E`m3Js!N8W$>$Mm4mt-<_$i4HJ=&sIin_>iOVR7`Ps`SSf$yT^+^r5sH>%8@aYb*dH{ym#Vp_C1g7PZ zsj`!!fJh#0cSYWtx4OaJ786_sG5qTcW-up z?%8~siU+n0`cEPp(2c>Zb-L8V{y*>ZXJUW$U5(!VzXSeA&JyBuyt~J4kg=$Og80KC zG+k-#l!H>d6T9qSLOxl*?sXQ>7$IhNZSf_t0c2=-;%Q@Oh>`|Sr6fcc~9;~-X=ODz{P%~ z0ChffYSo-3DL^7@9>XlDxBrDcS+HW1NsE!&^2d*d5I#i0)717-(wR1@R+CSsHTmKd zzX^tfU_ZZHy$Cb^?me^#yxo{%Wt0NnWA~|3r!Y^UDz%^JJuqr%iyz+C;B5P5p}+@p zw#G7BF*bb%bTsRy>OYAh97&}G;(!*A)=|gKc`5diis!K8euxDTGeT8-8yT+ z77BlBaH&Vs?=GjD>c2m9kk))SCkAx<++DxKa;C38*X{s4xRcB&cDA;X`o`_HJ6gBuj~mOW5Q z*ezAF>J&qs>?oWMXZYZowG&Az#9g* z(|#BMQGwoPOteA7_VWs8gYbj5f!gkt4nNZwMOA-`JHH4d~cg&+)kESKk%O~ zw&_9J=Md)*%R*@BlAV5iKGjPSGZWga2@W7DMR_8rJoYhAw6AvICd#9)@qqZNGAtU; zY`W{J$FbGe53tC!qmDh5FGBD}ilD)UNyejBbq1C&zcHFC_Ws$Cs5{WVImEWrxcO6R zsl@bti&<8xKaSw{g0Tvz4}@oYJ|9Rk`?P=e?zl0&=Y_=sE*U4^UHhgyO|koTH%cFK zw@4SzH55JH=H;g@AhBgdg`?Tl7nGd5xp#- z8O-71cwe^Yct`qPI$jtM9JBm zwVKg%6%R>@-Zml8iamUL!;$Bj&d7I<5ec!ug@=O|nA{#>+jcf6GM2O|ry)Jc;Z$Sg zuJ7&CxH38$1;DZ}Yq?uE-Cx*Aes8~^2Z(~irU9Zs?@l(r$C|&nxBJ>VSK8u}cm-2x z(ja`@kExN0!X1LiChiSd6??yf;VKf*)&C{84YTSWZ0d<`H!xf7F`2v5AIn{Q(Li65 z9#JZ>`3|G*ZGBbXd8;SIc9jSt`dGqiK|7EGPPxbnmoYQ9`fM$n!)!gB%z$)5YnPjO#N?LkZOMxU*YTd8*fLIq8NoB7&O?hZCa{xe{tQ|)98L$%%6s@5 z)F4z4__6V7Id+zO-rENr!;tEwmbstWcPTzKQ=rG5*%ynujRynM!haTcD9|r86Wz+g z$=&>!n(dn4u~&~YVm{6TIUVctb&a(ANhaj)wRPQH8!9$O(K$g%m@~(a1ZNoKx<1rn#-)d~^(Xy|abJ9&% z05jw5ZU_48;cZ^(0a$GhB+o||xV%V!{>OQ*0TqEso_i-quKy99y}~RU$Xx+661x8C zmC-2AofVpq65b(NTdEPVVWu);O4q)Bjxw6i1?foH^K1C0-s~yY^b1|S(m$^}+pRXk zbgiI;#Rf&HsOXF=ZysAZ6Ei56~30+{Q*z7>ynLfvmZQ8 zL_Q^KdI;w4smN(Z=o$aL*3g4ab498CPkjE?^2aL2^n9;h-|A}s9YE#9ROvJWlV$Es z(As$S13UdtvYAf$*cWbc+{38H!c)ln9GH0fA8VMrPz{qj6ss#kcu1e3k5zaw-tqH$ZWN^n6}0HC-h>AJtCdQg zJ(w!D>}?+CRi}pX8X91e=S<2sT+v#5FltRX*}iHlrTw8tH#fm+E%+O_qivW+W>N1g zz3+)Zfs%m0HE;qhd!TGvbpGuXCUQrl-)JKr0bf&F_&}Dkg9I$!KA!*rwvNmYkKQ$V zB||zwC48ydT=oXfuXA{HD=L<+Wp?;+-$Fx|ETwo`b~Yk`KTvuv&igJMMt)Cs6`B~` z%ng9aZQH(_zTX+GZpO2t4hw7|XivILk+;Rcbu%OBWFO|2h z7C|?(N9Is=;C@i65olU|%pYq66mOMk@#TV!RoKQ87c$^AVar*tV|w?e?7at9J|c)6 zm793>^Iq7vL`KJk;i^PO+pp`Bb;XOzZ7`glMn5PY-aVFXsoC&t!F@RqNQf- z-{feRVNFPP5noA-I3 zsQHL2Et>KE{b6tkHJ$f+_E(0dJqR&_isE|ZYs}}r-RfkYbv?jbG!@Y_FklP!^ey@C z3%W<)jHGLY{#e@2;Q{*JN6758LMXxT5Zk#bcd5l57wC+0WY(>F${lIRi2t;Cvj-63 z0+ZNGem0Ae7u(L1zZHzSyIR8X?O}5{Y>0*@Bz?E;sx0blk(iNDHliEoZKyl9A-;0& z?F|Nvb1Z>JPrSSGPJwMoi?PBGy9;E4H+to zvr+SAz}MY~{!wIP0Zhb|=TQ;RLFSm@G=L$`Lj(V((;Hqvi=ejqvGeH9a^y2-u)}$F zTJ}9-Yh1nU?BOi_A4uSL^ulgV1_8~^uYN^9toE>AW_ zC~soOaa%q%fr_=Yb>)=TrAzs4lfPCw^uJypW5+WZT0^KO2xlxtD}=QUi)g3lCyKwY zb^6)52NeIpc4Lm|rjPt<8iE``yfC{cpuI4d7mdrnWo!2`pZlkH4*EyqOcH=4x`*%l zC))YxxLZis5g`J1_b8gJ2cE@(9Hp^1e>?VJB(+wi^9Mhk2lrD$g}J$N4x5V}jSl)0 ztEUGWc%J=txBie=|H5({3#=Kfk~@L1g`-tb{9s|r8oj zUvTXs7hEV$92i-_@Lvl>pdqsc&;8raA^##=(9XK#*o8%-CyxWlx9+L^eDVx{{yQj2 zB`_KC*`RAaU*f}=LRiQHvce(FX)m7i>5a*T)nLUSwX~`DF5|>pd`K5tuOUi=HDH!l z8rd4_uKe?5=)%+UD=We^_zIn6nb8AkHyi@uYQtxrAd4L~w3D=CWeAXp5IznCXM4;0!w~VK9}@?W)Qk>qWY{2J%%jV0PH;$z1U;%Pk{b8HeU;x>qXnFg^e3CXgJ$3 zi+pTxL}I&nl8S4ZPkLauX1zvCC}^{3_NOoZvZGoYXa-^uN-v>xPqRAu>=tzG%6UnR z!X*&BmJj%=g(NFK_GrDOGyYawYy)6%4Z(2W^*>)KXAT;HZ$u66`VUR|EsA!-4{Je(mOnu5rB6-vFK@;N2SpMZSguS;)+CHu*T*|tG8wJ?oj(`Yg z_?f-jA+}+|-sgv(y{U)@wJ`0N(|5^G!Ev?I5jFe^vQlo#1OH&rXysd&X)<=}11^II z7d+`lP<+2^U~rlck}k}%c`a6FP?lEMk*C+r#~$K*t?u~ z3`zeg+#)7WiYOT@ZmwHdHTX<0xKBpw8L3!JE9% z_FZ^UEA7q|RBB5e<1Emzf2R79Ppnf`c`3 zF9#Fi#A?ZMsQcLR!pi33#Vi~gLL}iO)k&Xtx$$G|7eOKMiN<9Luqt4!Njd*;t4U?y zx3C8uZ$K~UPguPAcl_I%Wd9h^6PTa0s6ukDb4VNl#(DO~Ali{c9&WV8Bhpu5d_&nB z`mlX~yLxWVsx=Dx*O;eq1_{oI{mmiBAYFc?z1lznC8yI!y^cmDR6alA{oJm8jR-68 zbN!9#^~v{>`ug_@-W$oIZd^>&z_;b(TRQdg+D%;vw?*}I6VgT!g|SKVZg86X7|*)z zH+95#qfTyD+7Dr)kZmS+7}&P%cAXqGIs>9fOqj`S=kUp!Zf?coQ2aikk9z*7XIC&6 zk?y$8E?&IBH>>@4UB*tA6DN-QPQun);W1Dclz5Mq)mBvQWh91jnV zWrIysJ~4_RQ@%-Usi(6bYP;qB0CErSA1J&906J{RcEjF^_MuMV2Twwh;2|pCil%wa zjRK|cCnUXgQ`O%^;!U@B6ffI1y$PDlIKt&gMXHGAH5+OFhA7I<+L6%O#fWC|qI7wl zl&%=IiSjm~YwvjsW>1b4Si5zWuPs~Di_4(qa>dyeqCyCSNz#N(wyclHZNRwtrKSqb zej5}<3dbh!dfrEKF$$TK+KbHi%A^qGsN;H3mlxMUJ+E^|MCa^sf-LwU$=?I?>Cx%@ zo6Y|Tl&$JOF=StFpP60%_o;KnaU(l5Z9A1m*UImA{PPe{F4zq4xliBQ_P28gZvyx5 zF{{e`+Jtv7wHh<2GL8dF7n@f6WJz%xd`>b3pgO{gx~Z0rVKu(KYj|*rG9tMFM5@H3 zD$kB#!xTB`-ynN;X}<%x6=6{7-7$Xkg&1f-WB{-*kc<*R8*QLd@V__KIJQNd`8)sV zNBR?BbT{CFRuSc>*qL+rpCfgt+cJ(dBWh6ei*+;8E?&Ci@as^J6sCBWepu@7?)=@D z+X+H$q_T_NvV>zhH;f=CH8TC__IQ(QX>GwTumUbS*+bGTqPkJzswdcLas>Z4)$ruD znb1mE=M+7ySH|Sqc}xl1>-)?pY3*m8JyFS@4`^Kg07UUv+U2@LM<*pEn%P=LGAgODDB}YN+2M)vG~A{^bHZ;w!u6 zivW5XaX7en0|=+TRpb@B0D&cH4xsEfjco3ljB2*H@ueRKt$R}~+kVr3po)?~<@xMG zOp{%#sTQppR;C>J=eg`y59P&KddFqt+P4xV3AVeDlua`d;hrVl1X%YcV2E1n-}tDQ zIp^={Vl$3C_;CJ_x`{s96EhsA>D6c^*A}DvBl>^0)y&OZ!h-lxQ{`2|+ahc!tjYfjmfZspci25&@=;*xI)M->ZdgwnAnru+VrNG7*E#R^RqT@fxQ% zLR^Qqc74E8wLdyGvMX6@;S>&Mf@Zfn)x6V~D`&}$ZHgL)n>2I^5*BW?@7E_fXus$A z9igOkE2&(59zvvU15qG;{VT&Fw)Hw`38QId2P#TN#~%FWurTk#VR>D@oszK3ybE3} z$D16MvUew+)3x%%A(czD|MB46!NaEQl|N2Xy{L2rnh>QPeLOkF_{c6mvLi`3aM(JH zy-ubO<4d_@9D@QAiNNc6-Ha4-&lG(dC{&BF(`>zEZ|V)_i0rA!y0e47;f%Hld+qZ9 zXT#OFrihDQsy;0Pr5D(2=7ESnp&et0;-%zmQ2dV}_d*VLH?}KQ>qRE`EEtJtnJ&gC zSp|O3B?VuU=<0x3at!3f;>i6hvzNouy`A2;S`?b0Cm$R(9sX_7-nV5RcsdP1{#*2) ziLkk!DZS@GLrXg(4amZMmbJbD%4$Pz``oN>zOlq3^R+OkCZ8Ms)4c*pFdMUYh zsqu=VY}DaG_l|_v_0+CqyIWYZmG0pRE?^YR$EnBKUBG`P!#V}vzdcsEx(o2!Ng@k(7`ZC8*=R*^H4HTcLlVitk|EV6?OCl;_g}yD|&Va z8g8IOs~bx-k^U16BeC@I;a)YliBB{&ut+SbkVoOsa^-&K+-8-$yb@iq75kqUHy!du zGLYm(WWNnHVjd8(C>@3Ae*DLlas*~D>rR5zxNJ*gHmer6Z?(o)j^ zcpQ3mXswu5d&J$jZE6o`lBeu>`(MfIMj)sSb+O#PhV3X_0;n;a#{V9c%6lB$x0sP} z$Zkz#pE4;JH>vTIj!PO<#F-$Yru$%DHhB6uowlIGAj~9Th9Pw9mC`_VvS}SZvILgh zT0f3NxtMU@_{QdeJsHgHRGb9OnNBFRga;5urGf4mb%1#1epN$5Q~i>h+8##ok)_oM zU|ySKDu`=4QQ|ey3GMj|E4g`icpj+fY&iJfqLIkuV{;>)EH_?Zfyf$_=~em@`aV!# z1Ul+QVT+Oe6B5A3->rdu(<6ND#?0-8eSy^A?fOHPKFTEaz>jcHSxR1 zfLyO{K(>jd0jKB^B`#}c|3t+hqyKs-Wq#9ykL>1dNx!pai%Yj&9U$3q%% z!pi%9Jx^Y=17-bCg?p*hCW+(&SCfnVpiogDEn(;a20j}2^hg-*nl;W2qtT10B9>_q zuZ2*Fitl$xJ4wuVg{ZD}!YezZ$u4Jm8WVy@OX}>{|Iqc_aXIh*`?^m#B@rn{qOvkl zNJ?5HBPz7Fw1-Ml`|cn+83|E|L|aR{h-feEiKaAE8h7h^z2cmsKEK}|pU>kwJRZln z-|zS9^&Hppx~}K$dR+8%nzfCANwDB|hQ4Y&2D8L&i-zleBR54!F@9hyv3oRguenYl~4&X(9J|xOQnIFJ>gr z2vHTiT*|WIW3*2FpQ<00PN+zWSbb|qQ3AkfxR({^Osex*wAgyi>LL_f-u}L<=?AQX zsABGRy8*%2pJNB?WcZ51*w=Moia`P;;)B=T4FD8X7-|f4` zuaV5JDz8Nl1@>f{T)cwbGBO?qjrQXyv!946oi#@?GA~my)){GswTL&7R%dVCKZRRYL|U{l3Z`4ZhwJ_ zZ~!i3Z7#(CWsQZ8S&v9_%^1P7*w8gfPhx{+KGuX<4mXA#S-t`WKbV#!nyZkV0i)ub za{^m-624OJqB(_75W!&w{qHf*lCzOdS|J37AsxS3jIJM)$x4+Eys3hWTzedkLOB~L z5Q=LR^7sfUh_gOaNr$~MMS7l-iDQErIOGwxD@Ha+C~V0n7eCkn{*XV!vsmhRX`(qd z1g1qKW8Ln%oC$}p0XP=7xipdb2!E(NQS?fHj~qIm<)aWSg`#r+HQXfLuJPVe#ir7c zu@j+kyFHc;&33@y@eKpqC4PAhDk_~_j~M7W&TcrxI3Y#HvJ4WV6Uf=?cI;TnLGO0p zBYOgF;Lr<(Q|Fw1{gsj_N3Rlpo-vN9PReVn7&yRrM1V#Fx568 z8zM~kQgIXHrICS!5_J!*dMvJ{jw2}<*rkHrWvrcX(DY|UW&aDvDOmx~9t_NN2}@FS zlvZ^jo59@Q9)Syy@((@ypUCW{i(g)%cZ!32wzC=8XsxjX z=qddB>ls~r27)zH@-!25g5rWbRqc`hk`gu$>{?gf#0g+`JXGuymkkW*saeG{jwhxL zKODNN*v*HIKRJ+x+i}-|J0^YL%C%K{l8$|`*)aoxxz7NEP(J2kYI8cUpA>%x{LY%U z+@EsIE(enL@6hAsYi(eAv@HhB#_Y82F^27>pa+ZoPcd$Q`8!(9SXq`P*HKbtT@yx|q zzaF_mK6?@&JE^u34gbcz^g$oMUXigmXRz}IGW|tfWEaEvDpauM6$eCCU_Qb)*HL^i znNNEyzp!a`?q?KL#d8=)bj`%)Y-h@HLEW8nBM-gmFfw>?BJ>LV{P|*7dkj6(ZkM6w zOp$!+*42Ehd1W26)4HiaxoHuG!9_Tilk(s#bik^DwHF>~T?%*^+>k#{_v9 zdb4fr63h4GZa-WvG4oWSdeU2DxW&(wE_~`&7oip-fGvUcQ`y(3)F5Wl&|wVT3or*b zEw>B_{J^!pcnMf!x3y1iitwJmCP-5MfZC!JEN90WiXK#eXm(CTPnuo$gxOZHzCk(J zCf;&`0<=DwC@6;F6QZziQNkIt!ZxfNFs^tm)wC{h7D*%h0N!u4_T~*UX2dgrYv%us z9YY3W@cSZ8uPx|{tbj?`(x_+4!S(<`5gkOob`8)bqL>G6LU2+{8_s55yGNm9Zoz)3 zjbvyJbF(YnO_qtoIuE3-6}tjPKSTwykN$88!@>xy;~;mm!gSKEbF;7whF$995*2xH zdyMLnUD4PLnETkE0)8PpE!`9%t$I9+c-o%&5%=hxfq8XwPxrdW+3VB#UGSrIJ()B} z{Qd7)sDS9s*AFiJ+>P8tTDrD37nqIrVN8D_)!vNFUJ!JOj-$8k^R!S%jjWXT2zjBH zT^&^~0TM~WHa}c7>cJgBJ<0lD=v&GG#&w}zwBwWM6IgBvBSSa5;@aHG5^gMo_wO{G ze=zAscXa{cZQIPfh?-xYn4i{UJrh2?(i!dw>RJ8WgFZXS*#>wl0f5P9a@X~C`TQlb zemeCa8B$*=$X@q*Y{L0`xCvG9{nVlB)Gzb`y6GD+!jJ8YMW3CbTJF%Wu=D3CG`*QY zJZZJuAUB7k>*ncN#LlAdVqL^l;=0xuv$L7)9>{+$>Vo1){!%{f1gY?{Kjts=MHSmt zm*`zD+^WFtbWo3u20UMHNomlkA7+~|f5>+@jO1_=;!jz!Vnt6wtoyh4iQhP}4~I)n z+n8h4{Fia`6)74sry`qN>5-6I;Y-WGR<$`*GlRT%JU(?TJxbY)g#FL$IWel|@H4*KtyCu>M^-}?(|$F`-b0q-5jFUWm5tM8zrA6P4$EFq=Ib(QK$ z536M-AG7nPvP!R3{x9b~!vM2ja58YTT!JkVUU($!lk0`8?LVKZXQ_ZqGB@z69 znMLBnvP-E$rh|OqumzS4$;Z7HuDI2qBWORCaw)brSlEeAG@le}9L};ht}r zhh9mP8T+Y>gBBm3f4b$oolwqNm?$Ueuk_r<09^WOb&Md&y_Yd;KKrsu7!qvL zRBcKuX+!7GI(^V_YHaJ+F_kv4_uTwEls8-Fkp;Ub6P=g}A-#~#b_W?H#V2eeV!kMD z(i#84t9!}Ibz=Hf|EfgUf)E$&9_@pKm25@0iOFZOMfkNj^S_pph^mX`ht5seC8YFl zu0H>h&W*tgj(hE91(RWLdaNkDUS3`d-S^^I`?u4vyxppkstkw3(+)<2wTg2rH)MAT z^}sqbeedbj6+GyHBCH4JB|%j7kJhSvePdmFvfg`O0Sg(CVNXKg59RRW4z;`RNzM+S z=ipc8Ar%o`bgS5D_r=xndr{LgC5X4rNn^ej@oueVnKR(=|LuH8$?dV$1_z>ynwF^g zcpt+H`P15wxY{=rJgXKKXFHFgcf=UqBAg707hNnFglHP zfrOo2J2ky^xrp@_7aR?e)ESb{lIm`+A|d`hW`L&IzoPWNN%ptd^yjFLENVd&oLG(H~<-%$4s}zLytiGz?Gk z_V#X1(^Kf@ri&W&1i+%spN!k?ta{Ap*)7%E)vm5U} zgXHvt-Fojl1;b6QTaMB{hKU(&54awSBqx;;gp2T81Dn*#Z)6cjo_d_Ag~Tn?;gXmUkri zsWZR#=l}66#yxIW!+7=?ffkw8%x7S5Zl}NhbLqlCW-c-NL*9#4Z3ay^{++n6Z^QHB zYhhn=6Mkj+AihYrY&}{mL?4JXF@!j|b%PK@2n21f=SzW$meM`J#^B@TDoR=QAlJ`_~!@j^aoJA8EKBr$45i5@1r6~b|^KwXd z^dLOR5&_YI*^{Y><0vSkbRDX`u~7IF1Mh%Y5s;rsAbGfD|J~bU^XVS3(nD#A_T7KC zUHb<}ZAcj(vhta263#X$pr2yz*XnHs&stb0S(C#7rVcF+dx)$E4NcD4yTKzg5I@K+ z!w~(E2GZ^q&iAGJWB%E<4fhFUsUJQv_ri{~{+K)xic#{Zz~Y~cJ>$IDwI~sKV;oTS z&iKWwql69INY2$;N>U|sr2k;iOzf*uMcg2y_b|mrKY8BChg-l?fiq3e2Y8u05I#o| z@~Km&l2)i7lcD}yhvBDP#nBa2S`3(tZh)<3!o5tZ=ccuBq3`*-A*KuQYnQ@ib@7g; zih_Ubwtb5AfRZH!yUB^L@t&DbgA{ldDPem_?~^A_+K3fAA;?`>E*RMHoom+7$NO|e z`QzUAAa2d912xZ!3xA%np0!_`+J zS&rqs^89FA#+!fzPPF-HJ(ng0hA*1iyw44oYkz>DxJIz#Bj<7?<2G!$W1kfARjY`7 z?%j~cxr5wWn+w!TC&2FAFz-kgzsL+7QnXH5eyo1Zei6>D>5AVEJ)U?1Q|2^JT_@E! z(4`-)NmgnDf7KEComA7F<3kwtEsOeiP-dRj8)hi+@0(WvlnYUm4d!hrqHIx%zB4x1 zQLp_51DQ5d_8aaryfipyt-IOIDLxyQW-U6*jCcHKOirs&8&*|Fo%wto8z422t9(29 zK?)1m>+asw@l(;UkPOTMj-_SVN=6mboyC0o7U-*auz24BGPGUpola~`{{1~ zFC96$Flh4ljx{`&=lj@Ma9*j9i&1v|5!KxnU73J#8ndO7+b77%Buv)qsuKpdMhFZJ z3?|PL);8id@UzWTKj<{`5!8tKgq|2|vza%;@GMZL>V?ulQq~2go_KPArHs$H?DxkZ z2NAhUV(vj3BnNG3X}q-HG7|Gl{Th+qtZ}}-U5Gd{bw_Cby6mx>ZGSIj#0&$}se^^x zbsS(^qNVxa#U4lRxl|omA#hI=05w_1zp?-R`5h^|l`TfXR^~8RxDzWO4AwZ-cFkYF zV(H=%u*WGH*trsh+z&dGt<%3BV6!FOV}s&%A=sPe)j(f`EwlJ@@6H3k>6*wjMy0`f zH+)=;Mpz|W`DS)@cDlls?pZf{MpFbMA%UF*Gw}1jA$Wp_QKa^NW_T*5i zpq^7*g1aL9ngP7}tz;@vw-*8J>AnjK82TOxEwQ;tweoNQ6h>xSAuD&mlcccXPg}{_ zFC>)!;F1H-ti4mn`}=Y_mJ3?-Heq}FNhI6y*HB3rp`4&yiLdE5JWU5;z&2jkN7XsM zqupDFrou-WA^_rp(msA&LcaM6ALi}&%Wk0u9=yXltGOU&t{Q=>!{gtl`T05fomU^% zy8jOs00~CY^RfnTBC_ETv6tT%!S?hf%ys;uyt~%4I8%^PY(dAkdf7}m83PgyI{gwY zI-vm*x+og$Et}#ctB=V^7cN{ljP;X8Rn*)adg@frZnTvsM>ghBfE@V(**9J(+Xtu0 zVdqNYbj)|kY(Qe8KG7oW9lQ3%`9%r_W+(E`8gZ8ph-{-t&sk1!|K{2WY3CEj#5xJAVV1M?HPL zH6-+k0g{8?w|h-Zju((+>#Cu9zmrVUXf9&au#xPof~Wb$l9Y?+Ai;VNAf{!Q!gM%` zBjr;)nSdEVn2-lrm-WjPMGwwPG8vH87EmW``Lc-FnUi&6EHHCQ#hE$$Ch9AKFWlYo zPJD8&bj}sd)S_A-;9C*nM*gH!T>_IIv_3&VHF099=n@GkvwrX-D{7L`aTS?YAP1!F z7Kf5)h>3o8J&Q;K58)00zjaM*`-^_T`hLu63qaPjEW0?>bdlRb{ds1i^8g^(qM%pU z*^%X}@B{$w2H$W&a@>Lg?l@GGfCjR^Ic?A!RkcvF)Q}l#x>HB!yXrZ;Y&1LK$K?M% zek>IQ9*COe!>Qa~0~&fRzJCUVm5b2Bkx{;F!^xrZ(sT?UM+!i|<%j}PCJFi)2A@-5}eyp!Fr?}MSE9#2E+e-(`Y4(o} zu6BN#jzQ#r*h6r_s5h7bDbLen~R^iI84L zNu|a-C#pyaq9*DP+|E3-#tWQl>?4;;TJa}6{Uz^b@Y+c?U4N9Fu8+0!Yfsf?i?2bi zK$Jg(ts_qS=QU^#sq?*;3uw=1JPjE?58spt&E2C3(O_1WBN1%V$?=OT^5d z)L3A|ozDCr2B`|CRZ&Eub+c}h+h9@pqWJFa^YuNaKJ(B&6z~lU6u@$%8?u*P63zr- zPuPu;d5oh^q_JDl)W~vj&_CWx_!}b1*ji=_$9Q7hET8BYRcsZ}mCH97IrdRW@vx0e zY=B8&|J3Gf5TC}UtTAzg$%r9*J|uHORvyOQ5lfHZ_^__r=Y?{;I0kVY%X~1i7hGDJ z^+)-!aR4Jdfr(QRH>Vn}PCZgIuHcg(_ydHFJ-rwIm~)C*3C!9+wj}=-f3TB@0gT0? ziBT{Wsay87?8!xOJk!|HkG|!g3=fK5v~dmG&qbwHGnvYkBK}=J8U$ zp$XBGFwP<>uEUZZL_U{-6ZgUvGZIWVllFDX3+ z_~pjJ)#5dlr<+@tK;{u{TO7vJgb}dBi#hgsD)=?USBJ&7(r()t8sAW=2v_6-IOG%Le;N? zUnYByWDFFf%RJ_h)-8ZSqrZzgt}&UaYVGvVRlt89ofb(Cq-7bTUwoSOc9Hv;2hl>4zjG+-denDV@*6CpGfaB9;h(y8+thTGBr>R<}UDe~XNoK!x9o zLeDYiy%+M1hZm*_52Oa607`V-0Sl6_O_xf+Ibd3_AYZHx1%CUq%)Wi!dawS^q4)r7 z_mS%_Yqx(cN%p>zSQ$muUO$MtK z(2~+D55?QqKI~!i0&={c@Qr9IcEp=?MxjR4;H?3>i|rapRo7M9*SYhwY@^HI!>+BB zSEmwEoslWHcKPr*K9!2^Iu^o*%I8!LzN9hIY$Jf1k zaivWIt4cwCNh|pTV)E<~V*ok~iL6sx|E;AZcV*NoJ9zK8qtv~BglWDm&?Gl>{}!5` zfKFZS6%Wnt$F|VSw7~pi+L;ov#LDTy4g((Fv}|NGBa}lNe|C+qx*JL$Z$A_aR#YH{ zj+I`c@ttm-o?LrHlsdihQ0Z$msvn1$Lm7`HY9ey`35n{)(a72yhN0CSpki({2Iu6^ zeW*V!mNadz7{`}6`awq|yrzE5+O=fI3QxU841FZs(N z0zf_mkl`4VgR?U0_A@S12GehEo9OI@vi}UxZC>_1egtYOhfpw8?xN$+*_qG}5=~9$ znU-v?$gkd*;+-p?97RA(73VrnRbo&G6yJmc&S790ynXZL{1*ll5L8bDWutg*MO&|W z7;DA!2i>`4=m)kC;uD)?^>`1k@{piE?2@R|dBh>X2xmP+aR7bL<(ZY&nCKLrGT*A1 z;0tZRJGQWI3A?*W+%>y2&hRt#`gNB*Fy{}3hFKBwE z7*o2rhqgZpcFuzd+><1g%z6)0As{h(l>9SiM@(*xzjj&Pi^Mh`;z7h_6B~wA!&@Wr z{Z*}qt1;7g)0R!*;@arKw$d(jgYH-Qcv@X9xiK&zXFH>)+R5fj_W_J#G#8e~>dP=O zGuuI330+eyeS%Ax>Y0+-o!Sk-d;eg<*l;0qSqNvMTERLp4%L~90quT(xzIYKUcn)C zdnz@a0Yjn9SOQ)O-=DQXApu4N@+?DgP!aggU!N)d}v)lrDKb`dGii%tbZ&1yz| zt)#*UWQNJ>lE>dQJqtK)|A!_i(I1@%+0QiSBr+EZ{BO`R>jjNIr>cHVM?@}^x|Rv= zw)U(ZGi;Ug1pzBSM!3*rY``cYO!#!2GTEg`yYXzyjA(*z;4~f%V1dci`D27#3#M1T zqCXb^-$hGFzvayNHc|eM1fn`EWweJ+!Z2KCM-UsP|i& zEkZLx}JLZV9--FkgBy6w?a0xJGUw8&-@bcU)sX|K!pEyP3g#tRT%|@ z{(|C)E$Umqy~ za5gpoh~_v~_58RD<~(h6dE4+Q4VgM~;{Y*fvX_1B;j|Co_4TJp(n+JM=q$_m`ZzV^ z*p{U3k%{dFxrZ(+U?2E;D`suW8467!w=QF5V>7N#*O@_w>hnY6UQ-K4V8~CZi9unO z#-Zo0>!9VxlNf2Z9b>oqFFH?-QK+SgZm&-`2H@+@0olh=SATq~tq|82gkSSlCHEbB z7Gg!W=VIkJ!#ua^uV2p!Gq_aC!2fXF`%(1I|6UgUsb7XJs+a8LWjhw76z0RP9xI)H zcWbxJWq4I6l_^E|NPz#a1L~Qy_hisy+P}`k73lJMFnpgkSc$Cvb4|-JFYvxUphen( z!g;%Al2Cw^ZkaDV(oVx#6slH%;lb=+zjK-sy&MMU$tI_+eHEtA#^lcRkjjFX@!2cw zFMg)TM5;5gL`64VV8a!vuot*6`S@RC(-&o~SIdabZS4MW5uP9k*IjxdDj1E(uXk!> zjhdDRnDvc9i}&-c1+Z?_WH4Ai)Mr1{;W>3M&~4yw-iHsqYb+QB~K~?Owt59&~ z`#A%uW$JiAUR|OyT#|o5<$i82Fu+vE+5tAXWNhYY15K4<^1Zx?FpHF#4Ot<53lJZN z%U_cR>oJmIvl2{Lw~FW3SuZr|k-n~Q!C27DD*=AUV|x3+JRI_)v4?{qPe47U^hkX= zz+2jiLL6O!s&|NRU^=7%SBHJ?Jgrs+u@gk|Xuz(bQ|_Dsl{~wOQpr%?2=ed^=L4F< z%j*oF*_QvHqgPy`UF0Bxd6CEHr#}Zx4xj4*AGxUdBgm7j;6v;RC|Z5Cg^m#BO_!Xr z5aI6lc1&vVfrAGJKl-^Hwwt{WkPM}fkVttst3Ki87{w5ch}zn}f23U+#VBxhM!7BW zj1gF(U^>)_!1pZ9m&FmioK{kE)Gr*Y{MSB(`lk#<|OKBT8otq0*A8s4Qcy z8o%Afn5@c!T?DWacyPKDv;Tk~9n)dv38?1dVBatXdj=ys&T!D^H1`UCnt07YwQh}( z8u4yHB}|NGQ?pTQ6b0QNycz@#qURiYV2h@|@OJ-D$p;cZ9HKp%K*tJlzNKmvg)Ytb zkATdQ|7lok$Pm%#xzL7L8K;GT0$lPAAq5X{tH6~=qYI_MW0NSlF?7*KNO=N$%v3jA!{WwV{Pf068MQn@O|XngOWeACy)3Bf#2jE( zTIF>gT1F&>Ok*n^7|brb0J|sSHC()1{%cdU2 zC2k>T6b29Vh&g;!x8DO7Ji;!c|C6Dh&cPxS@aBcp5B~MAAy;Zb871r=?Su71Kt~X# z@ZiV81RGOQlxPc+i>O?Uml+02Q_S5HYNDd@?E~G-m?OPNX%BfCp4dE0a0`Zo^%4 z-0gLqP!NP-c`E#nG=rUOW=ojCTwppo@PSsJg~{7a3N+(-;u zoPqs?Lg28$G_YFAibGIWyk08!t5hU(K^4lTSxIj?2=>s@0=(c^ANu-$mc1~PaNapg z#BE^R9T-9(MNdKZqzqL7VwhfGfrt#qUh)ong#ShlMUTwTz4doj@H z1v^$1&qx-23yayG5H?mR$X%S3YpEm5KwJ;_aP2-dvJX4EH==|1Ag0TGF3L|rxM2!Y zT9fXBGACrb7v}xoR{OziijQSfcJS05(!!lz<37_S;m)W|eq7M#+cpt;t_>vR{%~!Hdet;DNq;_ZCUXOzEAxyu2Gan=rgcL3AzhtYEeAo0;q2YTtiRtXtE^1_PTLObOiufh=V2 z8`;JZaHLXdB~3S)f%zwK_P6Ifdkfb^F_p8BVRl`?O2-n;$H!MM5ioJSK2eFK*rHQs zT3-YWJn>8+L`0I@$$lBmMQ04xHuN5nr_J~(^ox+Gb3k|ytzQw2e&r}Wb9_kf8RoFAdrxQbtufvB!Qd#v3yWU?aa!%@3H>Qv!#x{<|_ zquI(CRq~WV&lLCzOa2fmeq%v+-v=3g^>O zn}avk$j0eTt zs_VQ^y!Jl}9eu0q3AH)f#->>Pa}#()#s)_EngB6heD%Px&cm3$hJq=5q07h4U0K?* zxQuli0*DQs6W=dl8vwg`C<&Q+kxjF7F!f#w4&Yskwf6mR?#ZJqTkZaNKTzb_^G^b9 z%(l-#{yG~+j(Db6A(_hle*JmLlfOB{hbQO3u47Es%+Dx{4YbLJN~1YAn@P1&Abw>S zvT7Vvl~LF1y4yZUA!hGb*imMAp!`_a{N3pM;{rKcrs?hZDh0$iS<>hs;6T& zs7(h`o%aPT?FV#{hd-6g`F!CtV4;!)2}JFK9{lnf$NSx5fFea6J0A3Ie)}48F?$_h3pXBm@{3r!T**>VcUr=?#K+C=N zxBa`_t2fw8jGj@tt`o%A4_U9#-)Bk_B!ZR-8FrHd5__f0U?7|Tt|`{w|-mrwS$7Zx=a7+!zf7O=ub^f zG@Tr4;)A6b-EIuX?M|7y)^;?Yosup6Nk*o;^e z+;Q|FIJ&$P1gN;0w`u_QFJHYn=(}Ra^@kK%$`H1(-2t@IWcigWgq67o6i&WIVzBb* zVYaf8jGZOyrPnueo}5NuQW!%k|2pksnaX=?%XBk9s`AG&f4+c37Rz&%yD+-T-L+bm z38Sg5BjbrlUC&DYDEnpk`QKZxBHj`k&U(+8ve`VsYpK={T1vT3_*s}Dy|g5I!b0|P zlY{S1m^a|*y;tt73UAu^6GJD9>G?kc?{4>thdM%mklSDrH`x1bhb#TVb)`=ZE+!`M zvVF)oCnD9i^IeyF<+F@5y+)vc#5wk8vRP%?wq049CgOep4*9WZ9#f}b3NmILHLx0% zj{Pq?w^`FgeTb$TMlV`Fk%~EDy5i>SC8-9TsDIJaDpR$+LCMX*P_xeGTs!G>*-Ne}Qm5 zAw%V>SI;O$EV_+3K>@bJ#Jjs=0&WXvF|ygBDLn-X$@DNaoA~0P@5i`I`XmTWJ6wiL zuL}JzV??cELFdxC%xQrs`!}-eE^~@zLC!j%F}|oM%bzB-a|{XdP`wa9#&XRQcI_5O zn%e8&BYRH|!bRiFFT2@H?Y~6DKTtKP-aJY6+mK;`Sz|xc8{22li4DP*U}qrV)!c%+GJ%Tybu~u?Y?jK<5OWt&{>U1 z+h)S6Ml??Gd{YSZ#`010p+|j%OsZ+PCem_mrWKPo^wsKn4zgmAMXm z>sD#OF)7&yYl{yOgMKSqvW7=cd<`_eyz%hN)P(cp8#hE0ZA4km{U-2%0N=ztnuPg)OMe1VHnzVpV@yS=%b5t*A4Qky zbhLoi;Hz;2cF!7sI`RTRM$H|U=?IMZco+bv!F=(9H&TWjK&H%dOUdE4D}-O+1M_bf)INd6QcE+zlowq8 z-iNn}UOKF$TE&&>{dfQXSR)}^d`_+=jDCc&Eo!$Met&Re_ZmoYii>90rkL3z`e464;kVH-h0?AtOcb}c_!r^zR^4i2MImDcFx-b5;5cc95+orl>pT}Ka!~T2JN-$2Qi;}YTcX(6u3Cj z>xZVPux3+t1br=F)Ga`M19w$Mj&*jt!2I&YBW||;c@lQ~Vx7l@ zvo^bIO6IlEAxpVTuHj{qsVqPdz)OK20M48*8a+8l0 z#Jpp*>$mM@=;XRL9OK=7CXKVc z2bG%`9z3~PbYdpFXm1E+uTP{zCH_NmENK5+@`o9t!nq!Z#J1Drq370YBh*F0MGo0Z zD#T^FkcsD6a^}_2M*6I$j+V1-jLiQ2<-L5O6N`BFh!e{j3!W+PzuFzpO}|<6>3c_a z$K}F&VmeZ^Ahz4&8u7Y5IuFE@TJ2^il9wm^7Y=mN%;|JvFqPE?~zGK*Xx3eRu1~40`z#N&LC;}-?RS&!+3;ecp_?;ji z0wz+#UX_V8P|C9@9fSX(5yCyaq$(4G8e=DhGN4)ZCOIrxxvP+#Tc{pQSK-Jf3oRmT zi6!J}ANGwf0(mIruvsgNSO!dh>gBWQQWF9HgGwK-EF?ocV4OmV$IAS@pEy)p$Q0=| zv2C2VGZ@PLCC0t(O1yreZR-5Q#04o+;W5DWj3+fwISfwIEKoN>$JC^(SKaRdjX|%ukXp|b5YNvWV%L{;Q-DKg;Ru$+#D_1J-ZLS6BkJLk|5EaOzMi#d&`y~DncIust*AsJ+zno}5KMb2scD_Z#x!94T=R$6M-JFi^6d=uku z;;>QQt-qJvP4*-L5`!xT(&8efu3o_axy`?1>hF)x=seCu_8K~$g z^1`V3K(*`4b~2=pe_vxJd4tu_qT{pQ;4g3Uoq-oJ15D$~(Y99u%fRoR$9 zp6Z@qMWXQa6L`vNp-7+E9oJ3pT%D*=w1#3Y7fO=ZIP0he@@AZ@*VQ86*`}{EQ$ifx%VcNl$@&^;A6DWbF4s5`#8mJ4OM!#SGBIIJR}Hx zCkeP5crSYkaGTAO=~V%Gaq;mHm1RK^u&pR4dY$h5d#j6U;6@~>CAu!VW-mn>^+83^ zoKp4e;~)hGURZ3UKR4$vOb_Bau0EjvPJJP*qG(krOL{o;+>TweACD%$*SLvdx4_W_ z>m0EoGo|W>dCQFB*R5Mi4Hmg)xnfQ4S1pCmj<$}D0+0b^|A zf1`Tk0%VpJ7ccz1`DkxCVoSln;|EF7#+@z_dFJkt(v?(*4ftqp1HunLfe4+{N16$1 zfn^{}&u54E=TAT!6#M&(=x?7BAC~$9$ylrJ!SR<43_Dv@G&Rj%dBH0Qb?B?!XV2m2 zWxhVxbL16xb*Q`?M0ImC!Cz&YtUM}X0jHYq*7kNzBQyVxAj|DXYU@^RC+Cm8BvHoQ zUqHvOv-I&&4i43@-Qi+qA=)E2_ZV1o*JTpy(&BRl6*k>D%-X+~F5|JHb;Blp{)GBT zhzQ95YIyIGB>0W9GYqxALg0tJ@!3RCT&e@HIzcY)<~*8ob~VXhv@O)h*(0xCmLof~ zc3zO)yVnb11@1+OZ*z0y03yjBUn`5phvj|e3%Zdwf%Z1Fih0i+ZA2uz^SLGJiYdh=)f zRmAiSVEln7y@58_g}->Z{%fH zBB3_K#N2jK^2I6q%*?_!O-taeh8)i+WuWX9uHt+TyZO+i-GRqM&%S;~PAdnTR!x8S(H>l1f7v z(q`>B9-vfhyn~+gd0IBs>ylR6kq?`Fw1*CGBfO0UN*_Od6YXbAdC<9h3$maNp>%Y7 ze0=rNJ##-y@O=F4^!>koD?E2Pk?2?Jo!Vu()C(~wA2Wbe;a!yx{`BttTLIP!%a!^JU_QRnvreS{coU%K!1ty`FB zZCD-QjFJg7f~5xT?lIVTHKk&(6-DgLW{>fx+%E)X2jC;TI_yu=Rp>Jk_ar@kerRSJ zRD=&^VP*4rw!UgO5wUwWJUtrtf<^McEPk#3nn=ah`)hxm*eCbHhpR)e05*NcJn1rC zt63{YSdqF1FoM#wtmqs~$UHi3fK6N(=b5S8| zOSW;^6bUcw4NFQDo+0ztB!8DJU}j|W1@v+F*fHOO;aj<_7DM#~QFmyr7%`G9%Qlyn zNfVZWF>vK-M+muQ>;xiWGQ)>NCo}81raZ@pqfnyX zXHojEg28lENNi$9r7ymr1=wz&G_CQ)5*c(}_)JSLZZ#{7z{_7<`xQ+9*&>ycsOQ=v zyw*mq(MB~{$9nz)a%-p=;h#D>_?GL~-y}9CYbE({xD(lG;*74s#x&b&o;Ixgm^>54$3qc5JMe^KAEsW$0Km z6T5TJze!~!$f1uCOv~Pk?<(}cxLsk!wgj>^H5UauP$(4m4i8FJ{2BK2DUq&ODoJ49 zeMq0ik5!y4WF`6aiiqw84@{6bKfQ{Ljos}3wdUm$(wW1pxm#;d2iTSY^g|oiSz=YW z&^EpzSfjj3>_V*X-OICQj~0CYHcd@Ug-A6ME$U-_^Z&_^wur}Do$@yRTB!F=Xb2{7 zU-#zR?~EUHc(5wh@mtL&n~?e9PeMYzO7fZ@K~^*UipAfC*_SOdq<@`wE-me#u5KX8 zn%b)49(c{RwMPDxY1baS0sLc4gz$&q^1N>6PG!t=tj;%Y_Q8a-0IM;N_lXhmNrNCO zv_9mPGUJOTk~(c$+ZAsnehk(bU1(j0RTd+BTnc?z4G8)s8kq=U(bW@Y>P zTE>qDc!Y$Mpu+rOV~Thsu~aikzK9E$eJ}e)0fAj&cb9W;a57tjeSu{w?Cor}k?%KCY8IiP_>U!a2N`%3m7Y_!UoOtt9}W|IUSbfOymHW;^4@^3u5r z64F8ASJ)iD~mwFzmOTlScY``t<3g`FQ~%*1g|v5z9bgNLfkNNbLr* zyjw+0<E-ZYHmhgwuLF%m-YnkdIqcmQs>$7&#oWmQGNhl(p3~C zw8(!>75S%FQa3Nxi8!(3yIonsQH$MlEbc_d@wgXqA?JiG@ohYt{-Wb%EnUrVnBT(%M|^gWzbQbm?Z_0SQA4aRSU0M@N#IE=D?LY_GXZMBPaV(NE?Rmv*QU zpBRw!B9U8yr<=$|!=7EN?Ck5&8?Z`Ad7Mn@^$WGtcg;t${?uc#<-duNBEt?dra z827OYubbwS$_;A}cDEMt&#aaIZx-5e7@;fhqseK#C1hVHmy}0?RT^iz7^cbY7pU%Q zs8m^og!loB1!U9WznYdmy-axcw|sq%MXbWj`2Yc)Ax4KuyNUDx-$JOk+GZTcwh@K| zA^Nnq$2#>y+Yfinvr$!_ASKxrGqY!%m_*2UVa-skJU>Qgl{U7C9yJ7jbRG4R`7+4c|KoaoHH^^!+6gIO{#yEa_&Vl0eQz zH|QOby8Bzy$wW?AP_|heDFy5P)hGN9l+Uq2}wexeOM-m(IMW z=(q$$a&vIdCz|!c^mOq6YSY9sk(Y21e{)c!X4l-u=_QcuY7^Btyo>%|T%EfSI{xcqPs=u7IRL_5oNYI8!)RSNlBYIkfs}|u>p`>SG*poTgZ|KBz}w- z9$mhEJ#mk0^UB1l<6xIvvvI@L(rXeIuyeyFV7q}gF?ZT^TND0mHy&9kpY3sWkQw4MC343K?_&xc+2>T8&-az0wAKH8NJ?Y zp>73WvA1ar>Jus(!%$y}x9%1nNR$uvrVlFcMZZQ_8y>!#jXGFy3Rx+ar zcz~eH3Cq>9q8m)t(ZZa0R2$mCfEBdY6yDQ9=_=vcrggSru<|(OjQ4bqnClt;_V-+{ zA0{kVm=lm;pGHFWa*Fu3QQVyLxhRn*BpTfsmEk3(+ZP?h1rT#LuC#ymw4`IwK^gV)ll5@)@=T;kOU! zux+06QEbS(pYPm`Rg}afJa%d;*F*Q@HO)@478U?RoVWr0^yMp8c4Sn7h)YT@VlfP7 z4M+PR92-;VEK4`kEHjpxQ(8H(bu7B?i8Bs{ThE&L7=XgGQD{z+_#?;WbUaj#mHF#M z@C+3s8HIK~DyR|=0ve#PBl{TU6!MIskTG`1{v1~P3p};_Kzh%BoOtg{f)Qk`fiTH* zWcZ3qTDW;q|u%bq3*jt!8Ry~hJ-*D^B z9m8_-O>+}ET{D6E)2ag>%|Rc?u+2n3c;yUO78^^dMN4emV7%mi9h*E*#rtA@>gr~~ zDLxH{k9AwN6m%A+Vc_~?TExG}IE2HI0mM`a< z#(GHcOtl3N0Hrb$8+>$`CQhfaJSGjH;&TYP27lS?u9*yUv?e^G=m*t;a@LZyLJaB1qXxgqIX#{tXRj; zG(a)@ZlmlUJ$0CT-51LB93LAy3?U{-;-CBa^bAsnF$F&?7abouS_^g`m2w-k!IBG` z>vlHy;P;N41ZI@0#Fc*o5(qM1E>hW8$}Q>jP<;8L?hZ$wOQX5w@j0xTEM$!4Jcj~#j&+Bg{fxHREEM1lA{1lTF5BmrR|%7+nz(y<8Lps zC0X?#=^hyM0BpKL|IK-^O0tJ;41Mo4yPfK4lFB03!v&lyroxR2P*os%a{B{|R^*t3 zEo-2pMJL)@`$l~g9XH2^;^JL_2_cFXUzm5A#5NtR29<&P?y0$Qb38oKSW5Jtm9yVJ zV=^p_)0mIl|Fz~rkfW66;rx>77(MHHqr-|=X@FAOhDzR8v`rYWH1*5v$Nwm4d&@}DAm(QQ~Ti58L-gjjfV%h?q zwx#a0D^r=_OE@?-Anvoe|GfYO)*R@gkeqPw>c8dY{JHiz{JCuG(Vq@P)a48K;Tr@d z=6a%(=uyb|W~8H+Xg7|U(hw^C5dA9eYnX;QgA-+`WSXoa(<@dC?=N^zY0Et8&<4i( zB>UcWgI3_biCWvm#59Ro!NbGDD)M|NE5M}5bOm{NcK1{{2bmyNR8}jeJZQrO7aC_@ zM`Ss?#>0XOjpj6TqNJf4Epnk8|c2YVcHBqhorB$OCOjHwlwBRh4EL!hA`7_U9J*BvbakY#YCb8KO;MaTabKa}KU@G% z6>Vt`j=~SLnEf6cdB}1)t8!$$C$0%o1n8<}x^w3aS$%@)IK57GXX$Eg?vm!i)jA7| zXIE?pN}CYWAHDgoZq73r!`I)cJwoPm6OZqM2b&RV;_9z>Cl~MT;Igh+?TY^h+XCz# z&V%snDHt%HJ4U1$gGXRQPFUQ)Tt6@@*FKs4r&)FDgIsXK4eYh5dcV~b31eZ-&YEaF z^b6$~u1>J|x&@PxL-^~>A4KamS8r=VY;8l+kvm3Pt;ykCc`|K&1NPFMwDJNwEg$=B z`i?#IuK$s79)UA@iKy#vWM|gFfq{W=ZD~(c(~4);VYN{%EW2&?J{J;5Macp(rQP=z z&b~j{*YE<0&Z<1m3n11WmR^N%?x@Y=P^6`s1$@KU;waCtmqOj}86Ym(e)xj5jEQPo zkR#kiIhRkGJUnm0_%PYdfT$SxFNC)lMkxgC4Vre5(NvL?7$lAAfE=Z*|z3W6WM~kH`ZO^UdeuqEHN~U%ad3BHh(T1?fHU z=1#*C6K=5NxLU@m;ki|6&6+jW`s?6TDtoTK?L9cnmO6e}qo0|HC7tQU=!uQY@5x>} z#`tEJ?x@@|y_|$K>IT(7u5F!Bk{fFuoPAm^|J9qy8hK7yf__NiaM~+1F4~>TFx>fQ za6kdIPB=ZO*#heG1J9nQJcBtu+=}^tpPZbHzu{z3FQ8f1>O6HE+dzMh%F>hg^Xii8 z@vP6IvJs9Tzk1(m!*Xu}A78cO0w2-~n=h+@pLJ_nTOL3*b2q>1NN7i(gxUXxC9Ua+ z45&6X#9IdFNL_5XRi^LgW=d&yy$9H*nDd4(Ig(CmjVynAh4JhQYLjxr>tTra zH#B$jqZ-2K4x<|J@V&Id`fKVLs*&+rgh1?4+t!Vc}8Kk*t%#0s;!? z&(&j2B!1}zf!6e4J+NkCA^qKzf!}B!z<`U0Ls?)Vw27_s~)4EZpjaC?#_V~ zSo=34Iq5p=u0=~Z>#`Uj(mCt={G*o5UMH5Ead-L%YrA|nxvWF81}i-yd)=5ma$!ts zlrMVM;g~3-{HW6E-t(xSxPoVz1ZOl9xtyF06@sg9V|QSlkd~cRut5J5+El-6$U?Tb zhraSm@~5jhHJ+Zt__c4N=#p?8t2R~i*1VL-oSt&s zjX6A7v!rmpLgjX(W};leVEiH}DXAw~X;a|_C;|Pv&2&_l2hq4y&S;?k_?LX5!ckcr z(EI#Vh|~LmF#!P%0bC}MQy7;i6*|yaQK_#MXuEWU#(|IBRU04n5IC_ytuYF2LU1~PUKSq5 zj{%I8Y#K~8zlH9Kw8-(5k3Ts=i_(cDRAh5VwB`e64AAaUKy|!}L?OnNaq=}~g_MWe zR+CTL=-m{hrLHc9Nv_KmjoM3C(}RYpIp^g2|9zDT;|sI;G6elOjWLHQP!Z^k zay#py8|xnlPXPliz&&ey`F{0nCbkWt7MlJ=@z@(d6d0!mv3-@Z@w9{XnRo0&0qY-C z^cEFnJXxItqq(L}*~Cf?8|^d)>AAcR2LNdkeP=5mp+#voZrtz(QGi=nzuKI1Yz+{MPl?UT;jKA$oRzxD0=x(-wOss%F48S&SOS;oUjr{9)RnL7E z!wnplOWV4~h?h?>O23=dJqhyqu|#UN;Y zy>JUEF0Xusq2?tnY+COEjDF;8rS)B=Qs;Hfi3X^s-=iiOuVFAroAp7cf|!nuyo)Ff zY}`aVCIEGLHQuUA%z%ofm;YQM{>39RYcri1&RhgJBA;DN`_mmAV>q*cKYdN0!01uw zqa80-ZXoVg>4?cmehE)bYxKup%fpT{pZAL>zg~)CbG!xZeu#d<6$4B;2LJ?6z<{e{ z>@4EN$=~Hu>eB;Kj~^h7!vFo@2MK+n^MXnJoF7gIh@lZhx)QvxfOqmrN?vKD{={Kg zFWahPjGBJ*Bv209PZyR$f^m7;=XspR zIO&pT+3^8y-94U&X!f#S5wWvwOsl%ag;Fv9pBkpbo`{JKkV~-o00y_5V?% zV`U6-V1>`DC;m5b@}~t7F9?E9S|XpM2*mT@`e@z^Qp>&wV_-LHDPYo#!p`PJz&4dR zKQATNn}Ozu?a?vhN+9T1-xW@23jxq(7m&*+{szhXH9>wo2@O%4BG!kfn&93O#A%ax z$7s-k@*BHCsx(5@HnOvfPKTS6Kc1jnq>CbcqdvQN1hWsqLl?2VQqS_}dI6~NCZPB; zN$11Y!2t#o`WE8L0w~*QhZdy$#Z}7OppBD@)9IMr_MT6kGr#lcSMVql3&+w>JmD`y z4R6KsV6@hbU!HDLRv5i;VE&ZL>wY_cQbLW{K5Y9}<;;iHT|izwt36nr_zA`H5Vx+o z{3lw8sF{|4gLPa1-HTR4#r$sEU9ki&F!9vu69Ypq?vnBA z^TY8ibkO1O*oBW(S3Vk!X0a~M84dq#0`hIz^sMOhXn%|Cnfj+so?JR6wE`AWqhy@? z>Gmn5O=hp(No%2|IW<#a3|%ZlhKF0^zzOB$3aZOY4fB2poaSbbWIF9TsN z42jDcqI|=&Y$d=4S1@)eUgw@1Y*%(86gUT@b<2Z?(^Mjh)8QJ11}i%ZVf{}yrP-mT zMQy`gZouW!>v4}+ecH-cZL!dm>@S^Z;yVBfh4mz0@nYVn1oOZNKad^n>U+HAG!p5{ z!ngY&W+#Jftg-E!t%Q1l21nN(%JD^WmaHQlTXuB#jzSM1e>BvvWLe2_JS04jVcEA# zxIp-+Ij)9Fnp_0UiL)mIOc!p%Kj3;ytsaCK_7?S7qTQu=%-h zvifepIlAK~P80zZwu-6?Df!ypFK%yd4|!eF)%$YGXB~B9+j)|Fm@5Wm>2p#H$S{Pw z;wCNfU*%GZ)hdsZa1q-xtBn@GW zL<2{{gMX@m|Ld)xqH+z$%!;_>Y-}pHZNGc;jwBm?#zimsAbz5J?*w`<+r-23&x~_F z%UA4=VGrYw*@uaFh}kwe=C(AnlBYKwT+uy6FEU$htADk zb<10&y)tUED;2y^Us{4#wDRqn;}A)CiJ!~9N2q+figAB)E?HtZFUb*Y^PG&1qIs!_ zl=Ohj^$H>NX9F)7VzzGL;#gFBHHWFUF`26|NoME`A7lEBvmMzcp0fW}5X%we@s9QNCHPa_M)b9>2%zRis*1a#Y)TZ`5t#q|v6r_vf&R z5}l4N(Ng5K{hVbPO5prDwOyasS;{X5g5c;FKLX>7r|+27q5^1KM-;_mVreF%>q>gD zcOY+CskNhLJ>trkWl8tzf>5NLsXU{eC6KcpNL{IKFE5XFv0Oq&_h|AE=+VUN8+QXo zD!UM1uU?vD#53fK-hA?ONGbMLOG$mnn|*XQ4@9S?YB9k?ozZ;{|61Rgmn*Ymw`=P!j{a=%lpGY;jnD{T> z!i$xi^mPBjpN5$IPxCN83SFY^nQV%U|p5r2x-jPLd-qZAEe* zdA-I&)oAx=TZOSfT_$eIuTP4_97Qg>?DYoEW5@Q-Xrv`i^}-`onXx2X_6D)21N7IZ zcffi%YU!3QEmOZUj+>e`?5Wu6F*aZfCX4}6Sw5s3&adB7j78Ea;D@bWgf`VoRv%c{ zrBTiW)H=({YwdwQ+aEiKR}^o7^kqWJ>TbC2J?Bh=>;YD)E=vy2BhAOmU)ts3=e3+q zPuVgMpMP+fRxy)04b@{_;LAQ13WXRX6D{ZIGYcMrWh4TPrH%GDCPT+btoTspzGFxz zTe?nERN6b`&HzgO*Ga=wsW)rln(AQ)q~CC7Tx&75l8=HiAxQ%uIJ3x-`s)N;=5C5l zA1Sk&zHtmyQzYh7B`z|%=>=wd(5+jCdfA6IlA=9EQ^a`Aiy;3x8>#sBktE2|R37GA zl$u!pP}KxmpD71=J{jwU#{+^7Y^DxfN>atuk%@#_cU3nA=1<>8DmC;@5d39lPGL_u zz@m4>Z$MQEbT5%WdZDe8rTFU0)q8q5ti-nv*DV4YtyGO&01iD5?7n#4H9t5YREHsL zS=b|cONP$iZ7@2q)|7i-Av^vh7|X4$$)vfzjsf-9CVwy;<(M26`d{sV}_4pt))G}ebA|j}ET+nQejgKgURG8{mj*M|kG~&+%1Vkm zl2oH~NZ1l8hVwv9<()G6FjoPjPQRLFz0lt3veB=yF;Tn54<)B~{n;b%v=R^4(yHTP zf32`*JAG|LnjO~EEhH62!4x5`-X|>dRL(&(2&>r1R2Y-8EEoF|SeC_f7_n%gcID^z zzzuy{BO-lVwpzQ|9)~xSGS}7-H;zBN5fZY7xSW${>GZq> zbkZM_(?SBtRsjqN5$!8}=O=3+3uHj#t_sM{O{=>#q%ghZ(xN-Khhj?&l0`TWKW#lE zO`ic#S7DRND+kW|#xu9b^jnd*k9Tpvi2dT6nqIYm@op%Ytc2G zWRZwRe_M;aS}(K$JpbK%A}A z#wI2>lgBOVcB`sNW~cQ`h~UGgFJ8UbVDoq<|KKv!HFQ<`S|KJ+FWWt- z{z2%r6#N}8Ked~q-XLw#URkU#=fTg@+2J!DhyiOWqjl%q<7)I~E1WPEWsx2EO|w1A)2@L?u?19?)r0px#y*LK>&La=8AZr!@2 zJn8=OvUgYcqi(R;IzD)Dp>0NI!Hb6}-_y%xyJ7{hat*wOtHqMe76S3|p6*@54725K zZz85a&)n=M1;4JRQRj^PIP^7*G0)nb|Iv zaEUDRcWf8ucz+2xCoGU`Z+jg|!A{Tw-XL&9fRr*#i_SFcR8><8q@sN+>~}G4 zRE4h6VE_DJ;G{2Uy?>9Hwh2aE+#dCNAjM}g@e_l@d}=Y~^6-%&pJuJJGv1}F7Ou}} zjpt0o@P6X=BcND(Zi;6LaU~zVag#BO!h;@`?yc50DXUW-)>8Q?FqqZ$nMR&eCYc>~ zPiHK+EdAb4##5=$8#3aP;I1CWf_6yT%J*aCcvM=!ls!@Q)e zYxQE9_X2Qm0&}t=PJE4!Q1}BWi#dcfvUC1^H?z;{f3*<=qn6Vk_9>E}*AeF6C3$R1 zaWtyIC}!(x2EN+mxNuDQO!ZG)IQLY9lVe^jQ=bl(`}UVOv;%)g|I*#N*VxHUQ%#K+ z52zueisM-tW;gH1coYyzdRD4_j&}&7kB?6lT0K&1SPrbK=8j_^(n zVjhr_H&2Hkvc%2rRPXr8IDSxj^$-_T{8WC%307kulU{C

    bjmsldSB1H^qzJir~}Ka)bT@ ziyqx!HU9HA?ES@+s}0}(YSf!FGFkW~>UbP}@sWYPX-{<`!R*TnN5}b^iTliJ&|Ao- zBMehNQ<4rJ&1TlptTg@1J@NghvZ%te(LLC>tsR^o-2yLN+Gib)z4J+*hVi;5>!n7j zmZi9%Tga~I+CkaLg@JjYq5jjF=hZ;-J=N3gOY0+3t-%ADKC|=M;APhP%*)m89+WK1q!))>ni7)#L7|L{gX78uwXnEe*k=ZYr*#CIrn2zqU72I7IjLPtz;F5pbN zXjkvJ>h2VeTS)skhYS2T32egzE>iyTZ%W&2-S#eHc?pAT##xSxY|FZVM#cob=r1{A zBCU%&3^QB|`ZRM4e7kFzHwL2psl_ zRrWBogO8UL={_JOALQa&&OR8MO5SPO6oB_&dCVqyDw{3Bbwk|N1Ewu7h=X=l1HG@2 zK0WQf4!}{V{_^eSe7I>^SjMf3(6gUuJv6P6&IbJ4Ia ze)}6@>++4Zrlljf0iSgyna7xmz#zQgHX~x!PbFx_`hCQftrEiV>BaoFbG*gMK0#$7 z&OAEPDt}PA93$5cl-|lV>QTTR-7Q{GE_&YIFSchKe$xR_Zfoh! zHsPS1aro9Y(BC|8MmHi5ZDJn@aLBLQ+g@umqQje1$bD*`Nf z7y!s*rOlqg)~s0Qo!pM@83EO2jXD=?B_76)C25G+t<&vUKyw}xeu=!f(V)ka{nk6s zM5OF1;vnTj5VK)9UtvxHx95`n)0bCXaJzn%ZE)e{6oJ~g35oKX zD^+@Obmcy*wOP;;5W%%^%;07)2>~gmXWh_~ZZYBc_LPHVExi+=^W>niMIEQtoL{hm zQ^aouodfdacUsY#nDmmgRf<~OZ2p+w;TZiBqe%q(ha?< zr8jV7dB~jV>MgdJO-yV`oMi;sK@QAPkBe7b?i90sE=5S1T0?EJM?oR#XBE+#+VY;x zS^FvFd6u;)2(K)H92uikX~ZV{8-s;@RcN*GjYR3b@W*Li#K0sbi}f&b!_qK^p=o-N zYJ-6xElaY=7uq2`?LTeDEioUp!$4OPaH6G!^e3zkwd3E~PReZ+6U>=Lj^udSqPTHKn}I7wZ5}kKy z>4`Iq{V3gVuvD-kgKo%WhGo20iBdq+xi&h&g^}*LrPePmMSr9F*`1}Ig$?FDP82rF znp3DaMx9N!vCN!q`zE3<7aM=$vcOFs62i1yS8|uUKnteQ+8!fZ>ap^>ry`JX{+{FF z+{AcYMf?0!ihw)3IJYsW2A$E<(SuRk=&92j81$-$*C6lY1BD;xey5#<2VF>7EInFR zX4)ue4H1a%u1CdG6u%O@yAG|kJwZ&p40#bY1cZ8KIY5uv*;6AJeFI%1f)KJO1F^;~ z1Bw9d`)2gV$@x|eS+&u(47fmsdVI7t9k(!P^!v*0BF<=1E(Jp2PzC-!AJV4XNbbv) zfcL>Z#1Ku()sp5kvbXJi&MpUS$7vLVcTwGe zj!%r7bN{gwq8+ch|wax6C3TNk{B8xc}6ch**cdgZ1DNBBWGV$)i4wVvpA zCe8Wt?d@3C2%R>A|B-7MbsAxFY&6+AID)9%S_{e$Zb9h_pDJ4J4xp!(as9s82MKHn zk@SCba!>2h9k9-5tHAg6oh^?cmb@6gIwkW@g{aS4tSY%?$4BFWN?(x6ldb!wtvcJ7 zEhFt&cmq+b(s3;t7Fpp3g|Zaudn@|4y22fTp~wsu1?A$}YBbt!dM{z`erZ*_sK&*t zNbyLf?SY5@%SuD8j1b+)ZfmpHIb1Lks*31grcUi*kiqgbfmPJ{u=SjUtGP1Z=CSzdGmz$tRZi2CTUX;GWEjs;E z{3`OeW?{>3IuVZ0^Pa*S4G(I&z>f;FlNI@9^y+eNmB~5-oza`R;v#Jp!6Mqr$|t^t zn8l`8)woMy7>x!bVFgRco0&;Ei^u!YRmf#+!RTV044RdJ9LIYianbjTVU+G0qhG$5 zFFGXm8U;})uZhmL8tbR{Gh6#$h8-F zm8Ann_S1uU0t-i4H>K8BaW3cEzHKaB32dgPte3q-dg?yqJ~$XW6e+x~ek(!s1nYTo z=Y!7Ehq8{Ng0$L9TZbmZareZciz^Kz$} z+P!Z*QP#57sjUO3J#S`cG$&nL5GUEbk9c#Ym1xOcSiw%gh51n(2qe1<#hqw`JFOS_ zYs2@drG%2Dmw7^p{QVk@w9i6fnjafg zD_%YSd~!alrB*OP@|h+fuw)BzQjc7l6eMd^u{aLc^>fC5`xfDGa;j=&iN1^HGhW;a zZNo|THnk8J!I-!CM#M}{bURZjQ!pdFtvV=?4B=#4_YGa)qm@P0T}~K=vFvo020a)=my;Tz$rlZ%?e z84CH&l9GC|$hb&S#~pJJD{qfR)LuabRMUPs^Mg3y0-E;^@HYY;yarF2Y=!cC1>Xu0 zoQ9~di!2^E4Sc@oT!U(SEkp7eWtcBx$pGSNW#i# zzTncSr&SUrrIFK_M&7GJ_E2##s3O|l<=tb;;9n(%-TB&S!qPE{kGg|qwK$-Q8y^ox zDC}({-%GLaR(F##-FnEmGCn*2<6K+Ga;5N{_D%~v7rionw5M$5_VtogU%Hs|r!e0; zd2U2Es2CEQzb)zL&j2w(y7X_m;Gj}oiRXOKZs|32SNcYKPQT0z{%HE>M$&KUf>T)1 zhYbshiyTy!TVy-h>r6CQ?=jk~=%1i=+!wfEZkL0w4<7DaeiBrQd}9{CY}o~03~tRe zOPawHD#(~;`h{d`G_x0LrG-eZRcU3dPe58lk{uRKyR9MT?wNi{9BbW)bBOyZ8H%Zj zxl;)vO*^rqQL-Hx=@uTh9$?QGLb7^Hb^YB0mD!P&BNejd&Fsi!BpjFIuxO2zUlS*T z=s7#=dXeF{p_>^BFsxq`h`oEFbeo|Zo(4`E-2X%m|57 z9Q{zv2j=g-!7KX|n6OLLZQqfWd)7H*Nockc(^zg{h@CZ-c-v@A`*X!@w z?yRkk($DF4as{UUuAIO5Pc z=p4Jvb<9O!IFrZrfKr{nYr|V`jI2OIw4lGzYt5jloJS-v^}{+PN-)RqC&yaQB6Ia; z|GJNs26b_RXdF7Y+xecs;r6sbwd?H6nG9Ctrj2p=Q?+`~0Mj>p`+Aw7>CDMW*hP{| z`k^A-tQUE$wR`IxtnMMh1zOVLIrebrFy9OAjInmSpB>KzU2V)u3q40@U#n*4#wXZl zhK8qiY|ckkqbO3DVMmp#HW+~wDSU07JoX6!Mpir%{~%R_jF1sdJaj^BW$@| zG)w5m(WB@$lr5NOn42~61Hsi*G3&{_Klij#9tSlS9V}I3)-G<`7&#KN<|*P#R+o3fsM_xw+ZKE{ZoieY zIPLiBQ_9_2S~IfWSDv72k};Xv>BW1ty8&y5@S{RgjHlz1BKg!8mO=52toq)is69ul z&)=Jhn#8+l=Tvk+KoBQzSbS^P2%pqb@-4veA+jUqI}>Gbmzy&7mRL{D0K z(6o1p%Hh;)JD++2PzhEs%*HmhZ&qzBf0{kuKj4q#mNU8x4nnT+V*us zvxl5W8pvVHek_IlX)bQ=q3}!Y-x@^oOQoXK}k4+oV1PBCI9ZNrJ8ZxpQ)v_i|5~$IYN>hf)yHcEM%0oH{6+L zk=iQsuEi5bI56c|-IYa>tlY0doDp;Nv2Df)Tr^F2f0|MSTBJJs;%M!zZUA-7-V(#R zrx2mqqZI>}q)`Qb|6=M~hkUs6i(xpj=t;4;0?kZZ1^>nj;uYS2Asg(A1ebI@p?&*e5PuA>x3lQeD z9xQPGIrk*ILlkjR*-$%7pGGj)Y8=)>OE`6MwAZ;gUZqQCcbhQ4KIY&d6aP;XCdg#8 z8hD%TsvU0t1HVlIBe=NbwUJvUvgp;VnB-tksJk7z_hBs^xz(FF4Di?>W+UJU0FC-^ znU|N9ueE_H)PZ|BKOU;d?tbTXHn>7WQzDs!P}4 zKsR)I>vKRk$`Gl_8Pb0Q;8851+ay1f zqLt~ieKT26qQ$OgZP#7*{H(IzM6G&`tzbJ&6W+q<;wG59VVl_{{`ok$+qM6OZV{sY zMw!mAjpzAMb6upLIZS*;j$!z@=L6K9CQDR$w`cc_c!`qz!n&;>GD=JRn*CsKYql|7 z-L~RwOFrT)u6!d$KD+h6is$BH;xLJoiPGid@13}*MohA8X1Ee# z0VyvK2B3VPY9Gad+{=DWKIIN)TY1SyEKId$4x)zHhV~XbC&$%`$IDID^`pwDeh&jyD;=+fy$8nC7;IX z@ooK;tf_>(UK^#fy+zLjM;OioGv^SLF*WEDBsd+AEv!e2N<@IeAh&XTCe0%4VW;32Sbay?J{(-z+5fD z1C?O|_TAEl$U6mU@3=ksE@jIO`kivfIrnxY;>3guX*K_V57=0?4!b>m)%Ur!S#F!Y zHUin}xiDU4(K0dR=oW|6nG0?| z;N?QE4&`@}@nyeW+u}E;0GJO+@Wntsul$CA$xaC5GHBiOo$X2(S4^;6gcP~LJ4~lp0)LpObA#NLIxY#cKO-^;W9)5dbeInQc$gZ2o-qCa3R-L z>`pDhH;gfi0%NQ*?1i0=GIc_f<{Sz1tzc{dPj&VVgG{>K>?OmWUFY)`{8fwEYaTmH zpJH%@ZxmoQcrk%zx%M6kdZ>+7ouYmlg{+N&`v4)Ll~v%FqomUT&J5mZX`DauIq8U6 z>;daNIQXE)vA*+gYjnuCNUM=x)jj7g@oZ24s0ykk8R}jdm$Wm=Wk!- ziZdg za)}-7?mb?BP%bju}O&RR@|mZbA2YNvQ6f7J(VL2zjpAYprb2H)cegKeU;) z3A7P4UwETi`qQCYxufxtfDiLc9g40W4^szBeO(Q<2} zBZY~Ws_n0PXj>1JNwkO!{uAAqAQ~mBL&B5_ z6Mptu+FW_<5aFe_Yh2{Nlq8(yS+8lLKc7vwLF@T(C8c$jTu z)s~olKZvJK07ruK$A^~Mqrpu@UXZ>tG(arhj=(kV^@Eo2?d_e83rloIDJsqC3xXK?C#@Vuj`Hq!absE1&LSC7?*)K&lWxgQ@Y zqgOA&EP9#ifhCb2=7Wm$TeZ#%YPuQC(I#U{{XEH1+O#_d-Wtumam3!U?{tQ>NM0ot zeMfvB#MTv>B4u!5mhvP3oqL1?xj4gzm#I$dLR@;b6< zQppgRjBwh${>7Avn`RM05Jq)JVoL4lT~;JR8DH5qF)l7K`Af^UZgWpAA@e1u`1TGg zCMiduTcn&+wA3d|8FOK-EVo5$ujCNCRWeS@mqPcQjF)e*NkfEliWoV#cCD5A4E{|G zn5=B3b^?i$!OjA$R|OA<26d7Qz@waD`d&dw?(hm7j)b3Au-{p`_9O z^P`F;hU5!tMB>wLw`upir4~fcIdAO*!#JQNQgCbu? z|N3xyjaHSYD@u|UD|Y-8z3|PdJBjDl;M-I6lE|3t+iPI+$=g7mrn9f$4~ zj-Jdj7^%cPb!!8DR&Xalt#7K_;*T5?9(@12sPja%vtV@aDzV);-9mlVyR?jushO6* zDCR-RU!bP?zdj!{2%n4fZ5UJ_h%e_4;eZODKA1t&f?<;d5OLydJi09r)|A=08quYGP z4vbcR3>Hc{N!kbl;W9kJ%IrRsxoFpSD(ay1pC7G`_t)&azPB1(cwDISXzZh5v8dBn zxf{U88OB1G!jI3FU7UsqtD=xi~Z&)ikNQKy`OcY)-4@P#*{ zU!sn3_V*t=pZCkQ;O4?%x9T(6r-=qS6Xnx)gZ8tjI4*u`MNQbOD7AnMk>!bA zK8yPd$gP-t5%Zr>mS@u?PrDXpfco`0E#?yDtCpW^fWt((*qJOCLfyj+TgRSedETe=BeL&~8rTX?VKj8X_S?cBd1- zJvad@fYw3O3+9pDy&7=1=`isqnOC>31$GFl=9|T1#F$lZRP9=nWS52Q-le^oVOM`9 z=zml!XoJNrCOT_=1&iS<3yb1_JWqw!r_XT&E`5K42O_*ij-;xtKq6Jx{kzAcJ#+G_T1;vH2Kl+N+%`CF>J!Gg)iBXJO(ZvNm4L9~rk(GIzVc zd_egwKw4m#uz%`a^p1hLVzX zR~#8%j#tuAo|WnUFxUUF+xQ>mEQzFDrWkVrx8<@vY+D9ygnTinvYUVRlHxKL3FkZJ zSk^*F=<;bUzuPkS;FszNDAgt;ehDUJX56jjLd5=vBdz!*I$596{`z&yHt|(vy5oZl zhI(b;TW%5+lP*nfbni?6v?fHIA+~|NDrwFmft#U@L$2ykFj@F_8GQuZqGYWtjo z(dHZ&87W3Cjp(b?ghVRZW*ABX^aKB9|ECUOGTCrNDqB6T9d+KV4|xXh)a+4Fru`{~ z)z#&S~k*hVs}IbyyGMR<}_2DP-tX zIpY~fv(v8hXE8`SjZwKlzsju|0e-ynrDhxp*%dYsFi1w!WlDDNUN09FU@!SrPxjv4 zcBNDj%Gf_#TC;y_-|1Q`+OYoVa|bMj)>#D;Zix2Tns_youMtJ7uUH}9^60;N{BMZy z_iz5xXn$oT7@WcB3hXQWkZ(EZJ%X-Gzch273cvOXBbOWHPtCtQQQUp# z{aq{I&gS<9Rb1!V1} z%yp`|7r$FN?Hd-#5JU z1BE!BUYWzJxJo&r>m_YzntEeSDkJ2{!Fw$6A*HPD(y!nKhkubBg={ijGfVUu2hD^no`v{PfEuzN!+7{ zEuVyXqyEt%UJY-@q1s$iJG4^;$p#ho;=Y7{0yDd<*dMXfoI~cCqHwwj_rhMe$z9ST;Ko&%dD(|E?%o++Rmp+VHrF!jtRgG2F?VW>?NZU!J38(cdotbQH z_UE_zbniA=C&+cJlr(~o)jU*bbCWl~19IGNn5KF4EmO*|1MlSleb~<=*LEQcyPBU! zp%k!BdWyqP;wNP{oJvlY{S!Y)X6auwxtGQ{r^x|6l)(nM?TeRWOX zk+C#3GcS$Q9s40aL0o&mY435sKfopcq&^T4M%R(n8gI~Zan3+a(C~Qx>m?SI&D5UC z#Ysny$4EO*q<<69Ucl>3{_vRr<7V!tldhO0Slx_kjZls#Rkr}{C_P8TZ|CVq z#8}jipv8EZNB~VH8n$0DGSD$t2D!`PHmmAzK+FjC>(y;5GEGil!P%t#U|?=nqFMPC z_ZN2b6Bl=!&ewKK_khzk863%$^K{Cw;Lc7r)ZC#=IJXK&N#8Q~oy~k2NEpi?LNQXT zFQevz%lDq`T=F7qSe30Ovt<#ms^;{{#y8Mzf_Gb?cn>_uJn&1kF>7a7xJo9=pUb^z zQH9!Rk$-%CWU{ZdS+07I;GSuR?%g)XX$Kn4;riqOfZT$vrQTrMCQ+S9OpmWUH!!{h z4cu;+e`}~WzCyw!?a7+PV8&uQ9e@Dhrn(i{)tv(w$pG{-hXtZvpN-dxp{$n}* z=MU|NMCq`tD3z1EqrK^~=cijtqEA&Bm4p0Nry8o_i80hjEQ1BWzU`{`0#V6_j9L8#1qnjl!^LU-_^I`tI@f&`O(p{$h>eGdqTo@Kvn13>ZD9gcG8E(5R_uRC29fv1943`_FYWr?{FMj?{6Hg(t&!U;+j4RajYkv({SsAywOJ3VG&Dx5K2 zbpd#+PAP<$p)=Vga@jM+7HykmZda;3RLm^nl0CSY@;DqIU82|b$GyV*mU~jH`ZJ~M z=3^h$=)?nql0#4Az=3S%7C_xBg5fecDpDC+4I zf|!bP%l$ksi}d;l7(`BPOvkOrzyhrf@FBmPweha^AXxpj&avtVIhd(olpL)mz zos0j;dX@B)WQakf(>}-h(OAg&sV=Ec7~>a`Gzu5R^yXnD%#?L<|8;5n?2TVhLy=Rq z4#UP&Ae+6?zhcMbBNlcb9xj>u>)QneS{<{fkY^3)(cN@*=7jE6^{GLnSn@7iq85$q zJLx8ZXr4Qiuk~+7jkt~8l#QmNIN95!OyulS5f#4qq~?X~kh#$Vs_!RlOO_X>-~H2p zP>rE#e?XbvGWI}(qppj87eL{R*oRY(-Pq#J29$A|Zfk{Uk$7W%;hpJaYevoehs)i8 z?LABt{@YUx^cA;wMLGV6qF{6K@&|!no!r%zFyMV>hZk1}zmUx{Ffi~zgFF~z-R7j% z8dM@2SGqeMi(&E~$P&^-lf!EZJd5h0L+-IgxK32x|KbRdiTXz zt+M!I9?r0Oh<{q&uhsbXaQ<4l6=+KCtpIP?6$fL?oRa4L(o@|{Vcyk)JU6rjuYOtK zKdml!N>wx|sK4k8B5niHkal#@IN~63sONy(JkW0=b80$ppevPy1HxxUO_k_L!qihJnlKQ96PuS}D2PSF(WX3+xyGv>VuaSvi; z`=WQOIwM~Jf|6^KhE}I>wKUVScY?3s$?TH)FikD?oG z1$Xmm2!Q+@8XUnkXb>%5iEdD*6f&)?_AdqjC{w_}x@}W8OIUgkbzFlUIQe%#z}qoa zVcnTwpSxB(X+VgUmc8$ChtR!SiDvrsZE+z*D5o12gOL2o?>) z5_H)T5dyCi;-n2T6O5VmR&Vmza@uVG{$glK0~_H^3Ip{uH8I@&IQ96+82Is`+h4aF{Pr#_yS!n{SV=RRI{w8TBB=_Q@gf$bR_ zZ57c*mo;t6S8<(zCQ?Fo;C;jp*BC7P@^nLy$f~!htRws_-ej;sjEe(HGMtvSCbJ-QeXU_C6AUZWj$R$Sq-Hc?mtG?{%Zc{-l z8EoCuwMA+w7&9&Xm2EA9mGU7|>>`Lb_*{EyK^w9NiMkV4YOhO6ws?il3OLaYPIrQ z=tUjP6=nSEsub9=1DrL$tz*mc+kGfhB?x2OuwaOu4rhFGEp`gX0Zm3cR=0wg6B#dj z`r~uQaG`ep0Z|*bVVGZWj!$Kfg7>a!m18X$%;1>5k0{{R-`L7bLndxi-RTJJTnDt)* z`=CsqJpMuKxmD1m!Az;%DT8u7O+Ko{XM~7r^|71_6od>^#?;)h@C&}z@brQSvvr2f z4W&{c%~@cBWc?51;d=6G1)^?qs#ye-4^6M1<7pb`M-RIHi#_}opBVO@MpH&>8jMF{ zcvAhG+HFhp#ZP|Ez0d=Z(Jmn4!$n4AI5^bP>soga&HnFr)IN?u?nGA_fw;P^B_4u)tnUmRn67Ae=G zRuH50lPj26&JpKpB(kqaFsZ;UAMtU9$)4+^+kbp9t@}~qh&aYNG~WB0 zQ`5BN{=Ff%_ZN@c%xM{xEJ0@=sR@X@nlur)8ctnD60Ls0f{h@S*UF4N)1G*9O;0r4Dx)*nQMJQ*1szIlo!j_HL z=PaXz_cX6n&5TYO>wkL;=n~pLm$kldx$Y(*=DTgSC)M|h$|IwM!k0Dzv=^L9eV)fN zf4>$)aV%0V=zM@yBA$KU6Kb~W&n)*?zE7K3Av@zc8{Bz@L%EK2Vx@Rhcv}qr-CiY`$}u$tR@S_Gzh;9}-Ha<-7!ncVBGuPO;(I+z6NIhSo_D`S_~`gVr3Wp&(TL1X zkiP};Tm1W|*|sNchkG@G!CHR#gqZuC#MdV>^G(-Tm-1v zNf$e-J{xagnxl8KDE0 zp4ExoV@(i>Zre>MBU<1|Goul1#Xh5rs!)BzuYy0CsEoCQ-!B$7A#gC{pg#FAKB3i# zud$;YvAWi5)18Em%ZYh2alMvj2F}!A-C)L7?%hbJYbYo02W4w6oZ=7hel2ZC=_cv6 zGn9ZprA|v-&FG;6H8_S(2JiU(-Z1!cEWe%dstq>p&*8xZ? zLi#QkKIh5H*u)t}ep&EU#ybi?1;U^~yIKdQ^C5m9(*c+)ij}DPr!(st5s!c?g0 z5xuan<{k}q;MMw7&>#tF5Zr7(m^=TkTuBh#t@y|k|Kw2vXGTkrcsk;@XXYnI7@jY^ zfKJz1qlz+V1*V>tzRbAd{e%n}&<)OKF#!J1HF~W*bGgYLu$nhVJIdw`qt3I2Cs<*3 z=B+>h!vW@^S79?))@+%#J-|AMTbK(`Nub%#U`-|7)bD;zITr!m z>TK{q+wbh9D$%<7JL$0ckn=MuP;kM^ZV9HeO_IU@GNVdlS8CM5yi1M+kLT`Qzwzm} z7wCaF(F@vWJgt%bdK>WSws`fPPr+1mfEyN!(@0=-fJAGrkgVMk=LHDF+UP$2Z{PH4 zvZ^zo`(&+iKLZ+oSx3m9!AXtV(@i8?^j%o~|Hpeq+5ohJXFGsZ>IB!9{%j{o#rOn- zA$^0Q$v;n*MMB7+A!iM2A$SrRPxU4v+`|CbEn4j~F1`trPV*c_ispf%A_p_gnC`dyfFkK#c`Xgbawc-Sfjt`*wmP z8v_7w!KPeSxY+|wK%mYL?Q*>t48Dr|i{S)AdFg?QMkn4k8Ii-l$-KJQ6;BR$rK@lmkbW{f z0UEB%(d<5BRwT5M=UcO9LU=vV%IfT@Ug4&Qd-2S#{_T3zmw=o~zy3&N97ya5=SLNq zUi&SKb0U2zb^-=$yuy>ERx5oOyjK=II?VOwZiRdQf9;)TG~ChJ_8EiGXY_6mU1anw zdWqg82u6?SMDJ~MqIaSvA|xURqJ|(*5+b74Akm|QB=4T{lyjc-ocHtl<;^F{TC(`h z{_lO?*ZsS$ox3N|muE$2nE!3Jls1nFJKdB56vX>zdR$O*{dr#fvFr%@Ogl^S_JC}< zOa)s~Bt7){t0>rIp3cspO6<=OCyw7taZ%3m42&@BK>tpxTPQ{Zx-j2aP@O&|`AMu? zUslM88;_if84JT~67@7s`Ek_EjJb=oak*VHT#MUJF zjxAtoT>;4o>a$<~4cVqvMN&aveVG2v1nf2$Vd@E5?4Bj+$=@bH<3}I}R(uzOJ(KRQ zMgtFv7&G_)S29${iJsnh`FL+&czy2H|2_&b*dRji@gm6^^Pqdk<@<#bFXsYl*}!;k zVP6WYYVN+~#4%mc)-+$MU#2JrN+XrCy#-^g>26BUGPDh_Wq3S0g0;=Iq6d={S5onU zpmwiTRq5Xbi=L9ja`DXcQ-3&tps(xLVHxW}&9Rh9jNicTv!$g0S)#$5GY`jK$=fOA zki)M_e`YvXsC5(%fG%O_r;Tp-k_cV23@%I5xvS{#z*2@Eo{$LGgr@hQyW1jNY}HS! zASr1*X9am7hZtg;v!e{3jAc$f-oM|N-4;9Be|%>9AD>#C2}DOK!Sn#U(v)Buid04KhDT=?fkYZXAADr2Fu=lV)eBZLJI zRRe)PqJMQTx&I-T_Wf2%U~K-A_Ukp>7UE5WpM}A@a^pv8$+Z7CYLiv1sPPeX zi8%Xo9(weAz1J93Wo{gly`9o9od{AQWaJQuIwKdrU~Q~A`6za5WmYr#E&qQUe`0}< zmJL)VwrGC;egHfA8olx6z6YN5dMbOyA{lD+_x6nIS%v)7R>U9Ya}YR^AyjahhXOSb z*Oix_TaH%G;482vNn%@AJ5ZlYM>9TRr0v@iz$nj_^cc@_*4Ua3O+*9}dgCcpq?M=8 zu+SD`$7n!7e3tm2twd4N3?7w_lS2@ki%7^5vc8uPsNZyphof7VI`J$cjbJ~;YiU4e z^HAtHg&Vp-I;;&*Lh}RsYdu-GWlt0yEUK1aaZ?2W7+3Uwcr$K@y0W}AW> zx{MfAj~C%*-CA0t3c#nw%R(-RU257S7P1_8F@uhwtfD6|5JTd zj`7__Q(EcYb5=x1a!!b-K6JlCW8`|7Ms!%VTW3UPC3GG&S)jHh?=RX)^Pk5Mpzu)y zeS@*kRb?Zg@lG(7-SYitEolo8@&k$pw;X7xW-1eYa-o^cbOE*r^V!w)9O&2}PNiVv z_3XZ=5y!mS0?l$$JW0Q*3zQ8MWp=|E>=NrYAE+)xHt*CrDlLQAAIb67xa6)sV=L@6 zjF&Ztt+}QDvwx*}>f`H}?eZSw^Z<&bFR;PR5ZF*>UR8Aro;Q5}73}>zQs+ZkenGzQ zDS!hwWw{*au{Xk-bjs%|eNzIG^avJZL+jXSKeDrvtP+RZ{&V4bL2fj2(1>at!8UM9 zN;10MYJIYCQW`RgREsPl!i#j=pZy|!>og`NQ_im)JlzO0hDQ~`CK7*+iH^tq-2H4m z&VWewvn|ndRsa@FQ>b7>zFO_R4hSDhjoKkN}@D3oM#XWs-B>mttythx2O2GKcV%qR_p!9!4PDK5*l6I41Z-TdObu^{S6075cUZRmUG+iLtJfm|xgu%m6po8P1-tj>mut3> z2OmaJ7kcnD0xL@G|2enTZVa)0fBaDK`?Z!aI^3NkCweU7X68BfYi@1>()(C>ee0`Qfj21r^D`M5 zA$$V#+W|u?0VX%?=TcP%Ry98`&}`9`dh6+JHa>M9dTw>YzoFrHPf-&Ro3OhTKX z+Gv@kgQDLFZES9KVKtB>MIL&5o_0hI3^~Z!<{u@uDKYkU z?mQ#GRiCqcmmn_tGt4S<()*UPz@(aVtnA{=o!^Vx%fHt{l3v!34DOjV01krt)1lCl zrv`aECem9+*43h`01Is07xtG*|MVk}(6#o6)rk9uY^x|G4mG(OC%?*hF|10uV%_^N zPD^5epU68cZ31*dMN44=HuLKfyn`%R6zL8RbFqx$h_ou2u^Q74`h^$1&37I#o4}(? zpg`+}dHUT#b{+z2l+qABnnelX&0jc|M}j*avj7Gp)BSG|%XQ<1Y$~D0529|g$A8|n zc>7bn`zglT!sB#*=_ZzXmXS6g*gSIJ-)C<4%(sPYcK1Mkp;q);$7bAo^ z5BerL?@ghgbP9dM92xo$jD%RUC%FIR05lR)Gxebp7B%RAi;cXZ^M~VZ{LkW5aBwLE zcm-u$vpG)e3KUhM3@KnYpsHPdj&S-LL^u4NJM z>=Q#0Gz8PXSt;Vwu&V^cP77CZpDV1UQwYe(ywZ$OjDC^`xPvdR9{SR#B580J+W|0f zCm|-?4+MNIs*DK8bbv0@S*V!zD~u9jJo%~H3T8{{GkX1%g+{^U_aVlQvOMSEMt@hW zPwakWXZhVRFt`79Gdjca!Bn%l^;4jONF;J}e*q(~r>Dw76t#UHdS5~j-t^}9odKN@ zq2_#a_2Y-+9fPRAK)QwJ^dt@(C2gTg3y;AqSDbK!0Jtewb98(+nkHV#^JZQLJoAIk zW~%q7-7F`B^IRk;8(})c?5p$gr^I;P6@rfabKP8T&NRy zED6-DU9y)#*C2!Jk*E}L8WoS*0a52bXLzwFA8fb1ouz11y!CP7SrQFf*C<$wwc>J3 zyftXd^e>Q}84(L&dWy(cqQY%hUx=g-g@jtn#NIy;jlv*6&6_wwv=|%JQ zwZ;H4arjbW{kN*vrhHZRP)LF-HFy4o{HA3Jm%tDaW~4a1Xdp{Zrat(nqi|1c=pJ{Z zFh!r-IB~M4s?E-H%C$II+I~<&H~6=#ab(!bErGqRpt0xJhi%Ym8_?q|K94}#|3L4( z`R7TaYoIToE=$_ef*vVGs^2&SHKN35hq&9!>`*QRZccZz{ZOGNvH`D7@D}m|o}Xhg z3$DzyCKtO|N!sf`#(^L|X(AWN^B$}#f|G`Pf^nEnjJMgVqB)vPE_CmsMei@>s5BxI z^>kME8TB@n-Xl3vBn4xI1;RctO*7hGn9N*ov#F4sjZrT2W+E{-trauYgWL8%np=jKv?bR=Qtc?=Dp5u7{$PTU2?Ehj!fQG3R}`xHb`T~$z&DK zm64{`jrwaifIc-&sO(k`3I?D)G(~%O2!FF<{@DljHt0N|utym@`1gXZ9sLuVN0yYw ztdv1Zyeiu*)$bz>zGt3gwem0dSe2gae!k)NV{TgJCZo{1zTYCBi2@Z|pcard{=^52 z%JM@*@1LkM0<3dn1P3IA`B&Ms&}2HlJtLEkl6E7YV7;Fy5>sao4)&S6CDD&8$%^XG z`7c+XSk)=7JWO^Z!B@ypp4Udb=FKfW8GhVbgfQb8d5A*;uHLxX!rnRbikK}&oj(>B zT3Nvwv<8(_BT3hhLY_L2$|KMmx_R99s#WF8V*gztOX8+EGk!YY`%A^Bq z93^S^$PM6#_@N`!?~^YwHhNu>;4mO-_h66GTU^PRp~S&&$GDY)0HK*KmEujr$=9Ts zcHE@;ixV^{inle_yN(|4?6dBtypepzRr~Ap@WWHQRjy+^tSoS9%}sV}Xgi(8geP;I zexou&9(PC1ujXU3YCEo53*@wS32!|0sK2c2CTHo5@tKcC`h8@BShgl!BDQcjsVH=ilH7c0|N(up4V?V>I2sCgn>+TL`gz6@G`GNljZ-*(T$WlMB{gO+^yP(fkpP#=1a2Hn zvL*dWNLy>qD{7KzK&*~i;V**?nY%mPf*c#9m{u$<9znj1q0Ib&DF0zCcVSN0*w>n7 zWbt(bRCBXjv1MR5)>H0>g{oGAX#wZ*)$zDw9>JGQ>v!8h5~zV3DCh0-h@qFXKUrji zrE|5)*Ag)#Ogk1SvybeF-Rw^tjW!*8SgPwIusdm4dm}F-h)YpPZ@n^+ekg;P`(}kv zg1(w6dH~HI7)pI!J~hiC;(!S=nVxvRyJq0@_gc^Ex3Yd8R=>7gNJTqpkEqi~^C4;{~iU_+r-T-r2fMZUU*N*+3< zR8x|%siN@_!&p)Oz6+nb5VTXir~T8*`PCamoprBQ`0?G8Lm5Ti(dQOJ1tktOk_>bP z9vdh@iM1lnG9L_p94+b^{W1^E5SLvJomNmZhJu?4MPq7}7gbb7i+mu5VPGJ6`d7D$ zsF}W!HPD&yTWH^MiZts4HR_6e#7D|Fy1GaY;=QfFv`_%MuM!zuw9;rH&i)6@rBjaL znc5xqRwx!LL?j-P#o7p;uB4ML*`FJI2l9b*TJ0-}Q3&|eC2{$YVkr9Ox_B|~C<67H z-^#9HI2$U2fm`Xt!RXn`92-aMkmUBb?4Oryx_yr^@#MJ!7L1cpcCZs{oF>X=eR!wf z_%}S#pin>IAJTK4E~Khr1f@jr&Z^vvl~(1UNReCAT~SvKvAGF^ zX0d`Gx(2sHh!4^Zx8=PaC(_+Z|6D(+l$3fIn#&r-6k#Xk(_Gi*Ohs!DYAX&M$k^5| zB{FdBVPk#KapO+Qa6G>c(V}#G7}cTaAW98rP9)&(@vksn+?uj*_{PU#kdkXB#jo&z zLV6wUCUx|5^lc$Noo=T-pvarG_H%)(6WNrs4USx*0YOALsC1aXGJa7}-78RWx> zH+JmsGm*XhJrQ4i-?2~c3h_G9WGrO*C6fZ~fF`#MK!Iy625azQ_T?bLS=Lw*m5fc9 zHGy#+o!xo$y9Q(W)^TE%yTe(E!$Y{ z&QH!AO+fC}s#|Uxwof~offp*PwUGXA1ZN0FS>B&c&)^flkxkRaJX35hD~+ebFzx1``70ql1Qnd z@A@6}M1rMW%&ZCB4nUc)ojkn>9a&|DTe@H3P*_;HFpeyiUOjQ?JH&4pUw%yfIT2j+0)VBI(rUr#>q=j9 z_pboOxAUNaSe8jebVv7Gu-2I6Fi&xThy*?7*tU6;czwY?)e>&3afAuf|4P2bHsB~m z7+OZf@U(#lI(oeEP|>P%TsOcv3i_M|!`A?cv8^3~>ne%|mBZm=Bu{$i>Po{!Xk_M# zY~N$SwJ#YcezxzmM^O`iwaAMFY~Bz*jgPmHK1B_#jXJ~|FTCyLmDorjKqe%vcFf;A zkH1F7FhUmOACL=m2{EK2+})Q*CO)Y*#jlW$=7^Hvh9?~(7EHrnmuqdpHH2IILpo9A^uKaJ^XAl{~S>~y$?B= zH?*^CM#t%v#)u0?K?=XA^v&vzv$C0T$Ol`<3JbGzQ+e;`Q46g0=UjU5KPwZQ(DNpqQATF#Qer_!0?%g67)Gcn1V6g zxn-#Xv7kY}3<87L!VT_yAzT%zk#4MMfDKJFFc^A^YBZUTXP*=T=&zAsY&>zr!%)<0u@O=fm ziX^WVo3vs2fg{5lB4(8c>p8c1B&?$tYJXG3jUl*yz>ky(;IFA+I$e`GF$L*-S)W!o zVcOW!fd}`M&yYENR?#^$@r2*FLUy;|#aIAKcRhV~6%uj*cn~Qz>QMoT?hsh}`I}3S z(@DM8ed%$DYw>jX7Eu7awk*8k_SNRms9B?xYqum@__>{1lTo;#)8TKq{mx^-zg9=n z(mC4Ttlm(#^ts$;W2m9h zvC<6~@3l&V?Z$~ia>TPv%a#}nn2;4RhJJU4 zeJ`7Bx8{fk*%i4usUb8&p#($&7ge`egD&bAK+xP#R$0EM@?I#`4wh)K4IMN`IqC`7 z{oI+(y#WzU<&`l46o)4j1}mu-J}Lemi|k_K69OaZ{DIWCR_`Ub6gT~Y80yWmo-Kh& zK6vQS@9Q_{^g71pVMv@~_d$+)q6Ruaiwtk|PB%Xs``)xCJlu+v@)ZFn`&fK!4EtR2 zjc$6U@ly9na$c1{A*=(_pI6vf1q`uC9)vj-V@tl{aTDoW`lwqp7}pfkwJof{6=>P7 z(nSQD<_CgLK!HpOHlN40)!5BODa*ZXc&N}|x`rZvvolIF{RFtP+*AhODTfgY;PH6@ zQE^tMb+L|@*>$5h4QFP-;=!?15>1muZ4B`)#RwAmDim~M7v&argC-`{FI$0;92-53 z@3g^ zHqJZSfEXSyoEA@hj~(l-07OzW;6YnsW$FY_m5cKCfRT|LV3ZmzfGTRg5?pXjgb$k` zH(!rRmYk&qb8;dPjP)8K9F(IbajR72tnq46doCCuxIHF5-Q`Lx0HE~el8h0j0yZzC#5d!id7L914pA#w+rWAY(!suAt)|e+m zSCSi}3z0VFqY((j^1t9_8JDijzjKy<-A>w$$+08*8{p5Ab(p22QWYLx`ukajQEgn9 zHUJ~qxo-g%grV@nHjsZtlW71Wrt!jdXd32d3-FC29|7>uMK?EyR8%CU`!aH4 zS!12CWkTeggQsdpCtklsWg&&DcX?VnZREI_u}9y5irC5xLJ59l{a3~Ki#xJTMdPLi z7dDy#%lVjHvZ@zXK8;jE#&hW?R|C135=aYYDSDVfK}-;vYaUuBvV!QRx;h63vAq>? zbmjgwozQQ93A(r7a%vV(^x>oDise9M(4Mx*KW{CtRfz396VuYfVGvUPEl$;#XZca- zjQxTKLmhxgCglEDpWbtTij@^?$d@8@WS^4J_471~wt~Mo|$S@HBs!{<|@#4t6?Qiq%U+(2!vh0k- zD@Gb7v}n1KJhgt^I%jkJO{%9%rVr&Sz4MoYgu-8;GU171l`67MSZB|L&iC>^fJ~j~ zZ}FXE01HPnn7RZvHA*ie?g*TuZK0((dtw@pbB#f^XC#%Rz4&`xgACTB!q4uI{m{FNc4sr0YDS^j; zecy%&y@TX$EV!d8Vt&z8wgartL4j#S*_r8Sb%RLW_ftsPhnej|Iy;ms)A=qToZAbY(V4f_}7XlA&DS+kYF>mT({0Z0jqP2 zznCi7)Qn`+y7Kr%TKA6!Men1pFQ<(T3!6A!2+aU#vgjAjj}N(+fvHwvfXSSSltD$z zgqIYz6qklWbsA03Ft8SY`WmuQseeF3bl{r&^8i>}C$U-AW;(aO)1HvU&!9EW z@D~JbJ6osUW*YfjbmXBA#VAFrow^Ci55)%bX9eC|b5;zU-ye>9R{)rjpp(3Ua5wkf zWLMb7N>N!O8%Lv{zQn)0dvvq^EXyY=6G56&jIxW~DAVqisr4Z;AOt;K`}iB`2x)gt zQu;bJIly3SrlmcnXik$LrtQbbf?-RsE^&MmiDLygd2jWQ>70iT{qX7DZuxw%cyt#n zKL)d%V}cD@wAh>K6hZQMLX!)s(j*9v@p!4zafDpGhF&_nqfDMB+90IDr}E~}=+gOT z6+shK3_I7zW8VZfE&a7evoZ*;vn};w`khOIYHmwx`QetB2t(^S4ckKi$Me2cGKqs@qO!E3raWO79-EJc7eutl#A#E2n z3qj-Nugu$B%@n&5GBqwzrQyG}om{g=twlzEnVMTWHb%j)`P)MIg1$%qX&EXGg58NHc$^W8^o8kzKmf5VZ6Wa!X!H>U& z12?@M@{y!L_`lQ!92r!&`>9=6%o^NrNcH068fPf`T2}62*GD~BUD^TZ$)^oj^gD6L zlnoS(c<{NaE$X#+mU`Q`U3@tER9&B$%s$};4g{a31C75(sA|VpWT zy_*+Mpe6jQ`xgMt5I#ZATrd+Z%)pCB_H}$y=pEGx)=l&(v^lB5*b!U$P? zM?3Bxnce|HKtn*e2@DKF6ohQL=Qq=BwF(k8xHniTLz`Hg8YvqRyss-U)X7-a%k_@5 zQ7o!8#Cr=Lf~%w~5`JKP)%$#pQ2XEB@s!=)ulp<@5TmmY&gK3JP`aQ0)H1x&=#rzW z$nQ7BBFXVk9bstZyY0@if(n&RZ9j=+mCPh{p`6qt z+{bK%=GfXI=|zJ`e*ia2nW)oPlRD=Hb)yIUJ1+pA6ND~1Qo$1tdVr*D_W~nWf_Od3 zd^q8o->`vf-;`Vfc+`DxczlS@ouW;`p^Z>@1e;84?FCRMmYsXL7(ekAhGJt(gXcZ_ zFt7ZZd*f>p5h{^mpC23whAFR!7LC<^S^;#~X?=i~t^L;6cln;#1Vf{?_m6(Oty2h` z@~E`l5-wnJOt54#{`|-|v4b+p(#RamhMUJWkSx?Oykl4DDRR?2PYBeN)tC4EoH;V+ zAf&z4uRKcH@oizS97PD3%as^8J*tQMvAtA5G^~oF2kO_UVnIg5@KE!Hf*BW#$3t32 z4R3eFFDKa~$gK?aDF-~@4obnLG+-S{#iT5E8L-3q9*#vaS{O|c5( zV;#dq9v$x*cFSXO$dshWT8 z+-5M`{gSn-X}aF51Btv=fm7@8*MMnrjT`yXIszsq+( z1pCJ4#LE#yfET{)VvxcpJ`x`k24O<`MjLoTO9ZieMND<(q6w~Q7hRUUB5fQ2el*}s?%TTPWEe~u1br0 zqO@6F(Kx^>L{VBw6rH&KwKK@~W`iRGR^(Hs(0+A?0qRAhgsW5e0N|FAHx;Nm3M9Nr z9-2chGDHLuN)>`H=#{k{y}nIUm_>@-r+uQ&pMaff^!zF&B5Y#Zl%MMidSS{Ncq1|F z^7JKuL)e|_H@Zen^J0fffv#8`@m2?yew2Q2$wnk2Qz;G494 zZG@KCZZ4xIIRBKOlKa~M`V;Ta8)Y}TU0EUB%&f8^P%S(o~pyt z$9h$ek5H?2MLv4w^<%t}+88v)gSC%B9=kxOXHPyD@`^U(+?6B#K6iy@$FgkJPrXUn zeg z(Lq|Q4`p?>et_P^{kS4S*xf$BJ77$BD4)jruF!0cXaTTDv`;)@wuR!dXg0DBXrr2R z4_XUfeYJRGJdqd+`;L|uYOCW!(2QVD)T6Km9mfQ>fQ&`(`0Tsk!K!8{LF3uMiUI2r z^s8TL@VCT0A*Tm}!$a9`ujlrkbWTYrox9!T+7rH_B|&r7sYKRnjg$N(NHV=CKms9U z2nKl}WB1NMc->Q0_4TfSMcJ_oq2T0tq=TEQa&W`1{Ow%-u87-mNUjB}I`8gf@`*qp zp`eA}Oi~A};!GR0&lOEr$(#n#o-Q}13F717mG@obR?HGSc`Ad>KRnp^^p4xAwCLwIlx?@qf;!Jqk``&x>e|P9p4iqE+xHh5=MUP0t=h^2+9{>cVS{dhzpe5D2 zVEC*+YZBIyetEX<$sw%Z$?(3;Ko(b>(!l&tw@OI*5l%(^FKQV`Ct@Qpn{DxJC7C7w zW}6d_KfS0LerPuHDa*&TrBtKW zD&Sl@Rb@Q=ebA-)y}}*kx!8#c`{n1$@D^&!Tq&>E9*@thJu+go>q}Nt6>i;3G?C_r zR+}5N=v{*(Daxn+ViDr*c<_Utj*3Bn*J>0=Y_F6e%%D#Dsj~jK%^<~MOfp%sB;lx! z=b62TB6pK&k*yHpyvgcfOlDPk3itbi)|>{chqO^+wj&$npxlFx4!+p_S-X-nNZI90 zTI>Bpo7j%{KE%~!_y|$GTpL+?P}@|?q1iusJ)s^dLY?4#m7$>o-T>zAz0WI4LN=CoH0=hY3vUiG)mK95T&s?^|%c$vsOW5bC$*`{?qmhFHfW z-bSWDK?_7iDr#=fNb+U})I(D38rXO(Z=W5Bncn#!pbN1WJ{)U~wKI~o;y?V+zY|A5 zS_0L{jrM0w)#@&*hwRe^9sC~TqS9tm_e+{QUtvLu=v`58l4~RN)C@20VX1L$8JS#t zNT@6y)AoU~No9W-#*!$OZRbxY+oALrFA1pueSN-Lm{8eSW2Y)oE7DW$nAEmq^{sJL z?=;oY2D?gpJ`?ZUOR$CZU^r$->i)tn)SJtGQDy4+a{OfRgYFEwP_%rh(>APCE?bsH z^%We&_z`dDgQoZ5rpoVV0`QOYJ1VEI`R~ApyZH$ zJx3|`q~$+YVa5BP0W7>-)Op)6^TTECzM}IGaLh4&kUz6};?VRI2@%HSuMu-WL?ZT^ zsC8-J=>?jZA4vJzvh&*BSM(;MFihDdxOVi1=_}ry5yh1TrO>9Ner58g{6z6Xt}#it z&A|CrHk55-YEOkqqca_V(}CzC(to8XO$@J~b5AuQJ$ zYX?79-+!bqR96hHnxAY~l>Q(a|C)PIv|%C0*%*KE>-mCij{2o44y4l!){D9K56o1I zoi@6&2qS0R;n(~jXb!6CKe5~OP7-&=?$gSSk%wW;L&B2o7Hw>4LHn$8G_<2hx@CJO${m~(dyKJ{(Ms*DM3yVsah;PbknkH)F|z*`-QP=# zj)RgaT#zm*NvlNv#7=N8Ft5pi0~l)E`>?zr2eD9TQ?4PFt%7fSYgn~*SjVHa@GkF; z&!OGtTe65hrG$&qXT~s5Tjf_#Ne6l&(x)?NjHiQjdSv-rWDQCW7pimy@?`c|m)bW? z&2lk)ZMo&TJ+jr4q5z=SioxL!`f*!kr|W&eQ-3~3UJrO39tXMTt&~L93y+WWO20jT zBD?}Zidr*mLtkL|+Z{cy3>O&q2@%5rxQqxfq4TDx$nxf-2xP;zrkcu!LqnNjssnH+ zS}@vGstuLGs}n=}Mp4Yib@u3R>=du$Gh6N0NOTV<37+C=4}y4nb&YPk5_&LwQIZ0O zv~IpVNRvZDU_wvKpS2PVyD+1IoE7j=*RZ3a25ncdwXfC{azqmak+36RluQ8aqj5d z7g9SIf4-1HK4?lmb6@F;o95)GE1L8M(O7P~!ABQPq21elRfbO3v6kHc2Jv;nk?1EdW+Qn(i{;x_lciej z1#PJ_r%D&=dT_LIjcgJx=Vk-WIqc($q-FJi9q0-kZbACJE8$b$m()@D zk@`NvUKWd8%CG?wYS#vXAcvAV?CT9^8M3FJRU`Mgmoyuqwl#b1kq3a36fud5KX&h8 z4ZiQG&ZhsA=JbP~C;&Imy*K@SjcCWAbzO`67w;v_mc|Q9l^xkCMa$08(g@TQ3?h{*6p>)QHR?JI9jgqgQUO zz6T$sCe@|25*YWzHw5-Y_mTUe#}GIloov8fgQxFf!iq4C3{LPjN=JWm{cqP;9A{); z0zUN~7t({ zv-&lmrBiHF<_(MernH=zwPMT^WJWK$>e63p4BJ-q_wn!Asw>z|mX7zt7J<8ct8cGu zh}vvSd%;l92vCQfzPADiYyOdkyY#E+$oWbQipxdzrVUD7&O}&PTa7`&Z6Ru=KhmK# zJi3L{9sncU(Hd{!sIiYei$_qU#41YFWJO~Rsr(gW?lA}_7g5LB#iCn-KEod(au^n3 zc58cM2raj+?}PauM)41}pJvnExb|NTw+tSLMRq6{405+D?_FEC=HGrd?JbcCH6pSZ0bzU#K_r2U9iY`-w@p=5r8(B%W^rM)`>(@>3au zzvvA?i~3(@o*5goX|`A{=sA&Fc1*S}bVLgDBF>@vyk|a$fNfsR8=+^MAJ}IB9sN*I z5H4yIt#_xpSyga6G1NS9QEAtM>s%qL)Kfh3_{-31jgqH;JF5T_5s8k3G%Ix|)>04& zTgQsMSIs7R|NTLNFVwgrQGE_}ZN)v)(5!JlN>4Uq()T4j(;FaTtP>))Ux|Ga&R7l` z#Pm@rCS4&%za6zX9c7ZAx4d=NQs_Te>Bo*HOD3K>j)pot>12dQ0rfCW;7P+6Lz)dH zQc@JhLD5xs!k0|$_iR^xQw0UVMt`U zKl*u*(xZ^fAUxwVwZ<5mSd9F4p%J{4xQykbw+AVSM(qYD&v}{P)5FFDdUKUx!?|QhGtD(d@IGawS){TZO@s7-WpGf z3t+p+TR~I5O8)iH{>Rs3X*g6dy2VnH>bIy@hgNDJc6-IXABX^cpNH?wj+D%hTTp}U z^@g61mpJ=XA;MPuWv1Xshy?Gj=yW@o`voMRPeD)tEjFVaPX)=%VhElF*ubziAU*Z@ zH(8}o(Ui7m8E${aDphb7NXY=!bkyShb;b&pdR1oR#T5~1g&AS4uMo`B%KVm$dZu5H zVRFrb3td6qJbOLSTUco;wpJiQ`4>KiK?hcA-g_}w@_)_i!AABdfrDR&_pYPRf4wNk zfAd8(cC7FpbkM(#Q3L-|B#b&6Jjdu&)6M_=82|a5|Nm?Kr*G{4Kdt{*6#p;Q*40h( XA~_G;K8>F^;GdS7o@%4AZS?;EdtcVN literal 0 HcmV?d00001 diff --git a/ruff.toml b/ruff.toml index fd02032f48..578864b33e 100644 --- a/ruff.toml +++ b/ruff.toml @@ -1,7 +1,7 @@ line-length = 88 select = ["F", "E", "W", "UP"] -ignore = ["E501", "E741"] +ignore = ["E501", "E741", "E402"] exclude = [ ] diff --git a/tests/test_normal_vector_estimation.py b/tests/test_normal_vector_estimation.py new file mode 100644 index 0000000000..7612f22aa7 --- /dev/null +++ b/tests/test_normal_vector_estimation.py @@ -0,0 +1,19 @@ +import conftest # Add root path to sys.path +from Mapping.normal_vector_estimation import normal_vector_estimation as m +import random + +random.seed(12345) + + +def test_1(): + m.show_animation = False + m.main1() + + +def test_2(): + m.show_animation = False + m.main2() + + +if __name__ == '__main__': + conftest.run_this_test(__file__) diff --git a/utils/plot.py b/utils/plot.py index 3499694821..d4bbe29ffd 100644 --- a/utils/plot.py +++ b/utils/plot.py @@ -4,6 +4,10 @@ import math import matplotlib.pyplot as plt import numpy as np +from mpl_toolkits.mplot3d import art3d +from matplotlib.patches import FancyArrowPatch +from mpl_toolkits.mplot3d.proj3d import proj_transform +from mpl_toolkits.mplot3d import Axes3D def plot_arrow(x, y, yaw, arrow_length=1.0, @@ -84,3 +88,78 @@ def plot_curvature(x_list, y_list, heading_list, curvature, plt.plot(cx, cy, c, label=label) for ix, iy, icx, icy in zip(x_list, y_list, cx, cy): plt.plot([ix, icx], [iy, icy], c) + + +class Arrow3D(FancyArrowPatch): + + def __init__(self, x, y, z, dx, dy, dz, *args, **kwargs): + super().__init__((0, 0), (0, 0), *args, **kwargs) + self._xyz = (x, y, z) + self._dxdydz = (dx, dy, dz) + + def draw(self, renderer): + x1, y1, z1 = self._xyz + dx, dy, dz = self._dxdydz + x2, y2, z2 = (x1 + dx, y1 + dy, z1 + dz) + + xs, ys, zs = proj_transform((x1, x2), (y1, y2), (z1, z2), self.axes.M) + self.set_positions((xs[0], ys[0]), (xs[1], ys[1])) + super().draw(renderer) + + def do_3d_projection(self, renderer=None): + x1, y1, z1 = self._xyz + dx, dy, dz = self._dxdydz + x2, y2, z2 = (x1 + dx, y1 + dy, z1 + dz) + + xs, ys, zs = proj_transform((x1, x2), (y1, y2), (z1, z2), self.axes.M) + self.set_positions((xs[0], ys[0]), (xs[1], ys[1])) + + return np.min(zs) + + +def _arrow3D(ax, x, y, z, dx, dy, dz, *args, **kwargs): + '''Add an 3d arrow to an `Axes3D` instance.''' + arrow = Arrow3D(x, y, z, dx, dy, dz, *args, **kwargs) + ax.add_artist(arrow) + + +def plot_3d_vector_arrow(ax, p1, p2): + setattr(Axes3D, 'arrow3D', _arrow3D) + ax.arrow3D(p1[0], p1[1], p1[2], + p2[0]-p1[0], p2[1]-p1[1], p2[2]-p1[2], + mutation_scale=20, + arrowstyle="-|>", + ) + + + +def plot_triangle(p1, p2, p3, ax): + ax.add_collection3d(art3d.Poly3DCollection([[p1, p2, p3]], color='b')) + + +def set_equal_3d_axis(ax, x_lims, y_lims, z_lims): + """Helper function to set equal axis + + Args: + ax (Axes3DSubplot): matplotlib 3D axis, created by + `ax = fig.add_subplot(projection='3d')` + x_lims (np.array): array containing min and max value of x + y_lims (np.array): array containing min and max value of y + z_lims (np.array): array containing min and max value of z + """ + x_lims = np.asarray(x_lims) + y_lims = np.asarray(y_lims) + z_lims = np.asarray(z_lims) + # compute max required range + max_range = np.array([x_lims.max() - x_lims.min(), + y_lims.max() - y_lims.min(), + z_lims.max() - z_lims.min()]).max() / 2.0 + # compute mid-point along each axis + mid_x = (x_lims.max() + x_lims.min()) * 0.5 + mid_y = (y_lims.max() + y_lims.min()) * 0.5 + mid_z = (z_lims.max() + z_lims.min()) * 0.5 + + # set limits to axis + ax.set_xlim(mid_x - max_range, mid_x + max_range) + ax.set_ylim(mid_y - max_range, mid_y + max_range) + ax.set_zlim(mid_z - max_range, mid_z + max_range) From 5b14e91bc46a1bb7a32c736c534498e723ab24bc Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 14 Mar 2023 21:41:34 +0900 Subject: [PATCH 585/940] Bump mypy from 1.0.1 to 1.1.1 in /requirements (#803) Bumps [mypy](https://github.com/python/mypy) from 1.0.1 to 1.1.1. - [Release notes](https://github.com/python/mypy/releases) - [Commits](https://github.com/python/mypy/compare/v1.0.1...v1.1.1) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 35798d7e86..8ed129f345 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.7.1 cvxpy == 1.3.0 pytest == 7.2.2 # For unit test pytest-xdist == 3.2.0 # For unit test -mypy == 1.0.1 # For unit test +mypy == 1.1.1 # For unit test ruff == 0.0.254 # For unit test From 9b70a6e1c22f68f8702e013962256a52b56e2d02 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 15 Mar 2023 08:25:06 +0900 Subject: [PATCH 586/940] Bump ruff from 0.0.254 to 0.0.255 in /requirements (#805) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.254 to 0.0.255. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.254...v0.0.255) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 8ed129f345..3efc1c87fc 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.0 pytest == 7.2.2 # For unit test pytest-xdist == 3.2.0 # For unit test mypy == 1.1.1 # For unit test -ruff == 0.0.254 # For unit test +ruff == 0.0.255 # For unit test From 3dbf2a4eb5b6ddaa113548d126429475128631ae Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 15 Mar 2023 10:36:48 +0900 Subject: [PATCH 587/940] Bump pytest-xdist from 3.2.0 to 3.2.1 in /requirements (#804) Bumps [pytest-xdist](https://github.com/pytest-dev/pytest-xdist) from 3.2.0 to 3.2.1. - [Release notes](https://github.com/pytest-dev/pytest-xdist/releases) - [Changelog](https://github.com/pytest-dev/pytest-xdist/blob/master/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest-xdist/compare/v3.2.0...v3.2.1) --- updated-dependencies: - dependency-name: pytest-xdist dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 3efc1c87fc..fc90ceb9d5 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,6 +3,6 @@ scipy == 1.10.1 matplotlib == 3.7.1 cvxpy == 1.3.0 pytest == 7.2.2 # For unit test -pytest-xdist == 3.2.0 # For unit test +pytest-xdist == 3.2.1 # For unit test mypy == 1.1.1 # For unit test ruff == 0.0.255 # For unit test From 1ce148e4be6e0c2cb619bc2c865f41b55a32dcc0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Mar 2023 07:11:27 +0900 Subject: [PATCH 588/940] Bump cvxpy from 1.3.0 to 1.3.1 in /requirements (#806) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.3.0 to 1.3.1. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.3.0...v1.3.1) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index fc90ceb9d5..001836e72e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.24.2 scipy == 1.10.1 matplotlib == 3.7.1 -cvxpy == 1.3.0 +cvxpy == 1.3.1 pytest == 7.2.2 # For unit test pytest-xdist == 3.2.1 # For unit test mypy == 1.1.1 # For unit test From 53eae53b5a78a08b7ce4c6ffeed727c1d6a0ab2e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 21 Mar 2023 07:11:48 +0900 Subject: [PATCH 589/940] Bump ruff from 0.0.255 to 0.0.257 in /requirements (#807) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.255 to 0.0.257. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.255...v0.0.257) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 001836e72e..59a34902f4 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.2.2 # For unit test pytest-xdist == 3.2.1 # For unit test mypy == 1.1.1 # For unit test -ruff == 0.0.255 # For unit test +ruff == 0.0.257 # For unit test From 7d1365d08d272aef76d7cb88a8044711bacf3461 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Wed, 22 Mar 2023 22:47:12 +0900 Subject: [PATCH 590/940] Clean up README badge. (#808) --- README.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/README.md b/README.md index 4ad19353e3..bfde2f9295 100644 --- a/README.md +++ b/README.md @@ -3,10 +3,9 @@ # PythonRobotics ![GitHub_Action_Linux_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/Linux_CI/badge.svg) ![GitHub_Action_MacOS_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/MacOS_CI/badge.svg) +![GitHub_Action_Windows_CI](https://github.com/AtsushiSakai/PythonRobotics/workflows/Windows_CI/badge.svg) [![Build status](https://ci.appveyor.com/api/projects/status/sb279kxuv1be391g?svg=true)](https://ci.appveyor.com/project/AtsushiSakai/pythonrobotics) [![codecov](https://codecov.io/gh/AtsushiSakai/PythonRobotics/branch/master/graph/badge.svg)](https://codecov.io/gh/AtsushiSakai/PythonRobotics) -[![Language grade: Python](https://img.shields.io/lgtm/grade/python/g/AtsushiSakai/PythonRobotics.svg?logo=lgtm&logoWidth=18)](https://lgtm.com/projects/g/AtsushiSakai/PythonRobotics/context:python) -[![tokei](https://tokei.rs/b1/github/AtsushiSakai/PythonRobotics)](https://github.com/AtsushiSakai/PythonRobotics) Python codes for robotics algorithm. From 5093342d35b914c125f1a857d254083887574444 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 28 Mar 2023 07:36:24 +0900 Subject: [PATCH 591/940] Bump ruff from 0.0.257 to 0.0.259 in /requirements (#809) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.257 to 0.0.259. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.257...v0.0.259) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 59a34902f4..bc27a2cb7d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.2.2 # For unit test pytest-xdist == 3.2.1 # For unit test mypy == 1.1.1 # For unit test -ruff == 0.0.257 # For unit test +ruff == 0.0.259 # For unit test From 32ecd546a45587e7634c0d321d3441057e1ebdf0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sat, 8 Apr 2023 19:15:17 +0900 Subject: [PATCH 592/940] Bump ruff from 0.0.259 to 0.0.260 in /requirements (#813) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.259 to 0.0.260. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.259...v0.0.260) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index bc27a2cb7d..c8b9725def 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.2.2 # For unit test pytest-xdist == 3.2.1 # For unit test mypy == 1.1.1 # For unit test -ruff == 0.0.259 # For unit test +ruff == 0.0.260 # For unit test From f97fc0a26da22ac3eb51472cca5b2858bf9067fb Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 11 Apr 2023 08:17:07 +0900 Subject: [PATCH 593/940] Bump pytest from 7.2.2 to 7.3.0 in /requirements (#814) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.2.2 to 7.3.0. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.2.2...7.3.0) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index c8b9725def..4019b31e0c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.24.2 scipy == 1.10.1 matplotlib == 3.7.1 cvxpy == 1.3.1 -pytest == 7.2.2 # For unit test +pytest == 7.3.0 # For unit test pytest-xdist == 3.2.1 # For unit test mypy == 1.1.1 # For unit test ruff == 0.0.260 # For unit test From cc6245cdcfcd6e35f5cb789a7aafe7fe57fe05c0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 11 Apr 2023 09:34:13 +0900 Subject: [PATCH 594/940] Bump ruff from 0.0.260 to 0.0.261 in /requirements (#815) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.260 to 0.0.261. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.260...v0.0.261) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 4019b31e0c..ad78be529a 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.3.0 # For unit test pytest-xdist == 3.2.1 # For unit test mypy == 1.1.1 # For unit test -ruff == 0.0.260 # For unit test +ruff == 0.0.261 # For unit test From 90189c4711eba64d5ce902170277b9887a5f7cf5 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 11 Apr 2023 12:20:02 +0900 Subject: [PATCH 595/940] Bump mypy from 1.1.1 to 1.2.0 in /requirements (#816) Bumps [mypy](https://github.com/python/mypy) from 1.1.1 to 1.2.0. - [Release notes](https://github.com/python/mypy/releases) - [Commits](https://github.com/python/mypy/compare/v1.1.1...v1.2.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index ad78be529a..9d43d13eb2 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.7.1 cvxpy == 1.3.1 pytest == 7.3.0 # For unit test pytest-xdist == 3.2.1 # For unit test -mypy == 1.1.1 # For unit test +mypy == 1.2.0 # For unit test ruff == 0.0.261 # For unit test From 2394e776f628cc0bba35b176e74e65345bb870b2 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 25 Apr 2023 14:56:19 +1000 Subject: [PATCH 596/940] Bump numpy from 1.24.2 to 1.24.3 in /requirements (#820) Bumps [numpy](https://github.com/numpy/numpy) from 1.24.2 to 1.24.3. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.24.2...v1.24.3) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 9d43d13eb2..9f88bd9bfb 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.24.2 +numpy == 1.24.3 scipy == 1.10.1 matplotlib == 3.7.1 cvxpy == 1.3.1 From 1efac6795ad75e7f28a04b049deab7038712efd9 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 26 Apr 2023 21:23:42 +0900 Subject: [PATCH 597/940] Bump ruff from 0.0.261 to 0.0.263 in /requirements (#822) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.261 to 0.0.263. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.261...v0.0.263) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 9f88bd9bfb..e05a591dc5 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.3.0 # For unit test pytest-xdist == 3.2.1 # For unit test mypy == 1.2.0 # For unit test -ruff == 0.0.261 # For unit test +ruff == 0.0.263 # For unit test From 28004c7b9c6cb0050e9b6e01a7c284ea631e9c9a Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 26 Apr 2023 21:49:36 +0900 Subject: [PATCH 598/940] Bump pytest from 7.3.0 to 7.3.1 in /requirements (#818) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.3.0 to 7.3.1. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.3.0...7.3.1) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e05a591dc5..501723248f 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.24.3 scipy == 1.10.1 matplotlib == 3.7.1 cvxpy == 1.3.1 -pytest == 7.3.0 # For unit test +pytest == 7.3.1 # For unit test pytest-xdist == 3.2.1 # For unit test mypy == 1.2.0 # For unit test ruff == 0.0.263 # For unit test From 80124f20e814a03baa440481999847bdc850be62 Mon Sep 17 00:00:00 2001 From: RyderCRD <39330401+RyderCRD@users.noreply.github.com> Date: Thu, 27 Apr 2023 22:04:39 +0800 Subject: [PATCH 599/940] Fix the rewire() of rrt* path planning (#550) (#812) * Update rrt_star_reeds_shepp.py to fix #550 Add step_size attribute to RRTStarReedsShepp, and a method set_random_seed() to set the random seed, with two test cases. * Update rewire() of rrt_star.py Update rewire() of rrt_star.py to fix #550. Since the old version didn't assign path_yaw of edge_node to near_node, the old rewire() doesn't fit rrt_star_reeds_shepp.py * Update reeds_shepp_path_planning.py Limit the range of phi for the sake of planning speed, and simplify the the calculation process in straight_left_straight(). * Update reeds_shepp_path_planning.py * Remove unnecessary cost calculation Cost of edge_node is calculated in line 221, and self.node_list[i] is replaced to edge_node, so no need to update. * Update reeds_shepp_path_planning.py --- PathPlanning/RRTStar/rrt_star.py | 12 +++--- .../RRTStarReedsShepp/rrt_star_reeds_shepp.py | 14 ++++--- .../reeds_shepp_path_planning.py | 13 +++---- tests/test_rrt_star_reeds_shepp.py | 37 +++++++++++++++++++ 4 files changed, 56 insertions(+), 20 deletions(-) diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index f875d3a76d..b2884fe21b 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -225,13 +225,11 @@ def rewire(self, new_node, near_inds): improved_cost = near_node.cost > edge_node.cost if no_collision and improved_cost: - near_node.x = edge_node.x - near_node.y = edge_node.y - near_node.cost = edge_node.cost - near_node.path_x = edge_node.path_x - near_node.path_y = edge_node.path_y - near_node.parent = edge_node.parent - self.propagate_cost_to_leaves(new_node) + for node in self.node_list: + if node.parent == self.node_list[i]: + node.parent = edge_node + self.node_list[i] = edge_node + self.propagate_cost_to_leaves(self.node_list[i]) def calc_new_cost(self, from_node, to_node): d, _ = self.calc_distance_and_angle(from_node, to_node) diff --git a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py index 66185017a0..c4c3e7c8a8 100644 --- a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py +++ b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py @@ -36,7 +36,7 @@ def __init__(self, x, y, yaw): self.path_yaw = [] def __init__(self, start, goal, obstacle_list, rand_area, - max_iter=200, + max_iter=200, step_size=0.2, connect_circle_dist=50.0, robot_radius=0.0 ): @@ -55,6 +55,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, self.min_rand = rand_area[0] self.max_rand = rand_area[1] self.max_iter = max_iter + self.step_size = step_size self.obstacle_list = obstacle_list self.connect_circle_dist = connect_circle_dist self.robot_radius = robot_radius @@ -63,6 +64,9 @@ def __init__(self, start, goal, obstacle_list, rand_area, self.goal_yaw_th = np.deg2rad(1.0) self.goal_xy_th = 0.5 + def set_random_seed(self, seed): + random.seed(seed) + def planning(self, animation=True, search_until_max_iter=True): """ planning @@ -147,8 +151,8 @@ def plot_start_goal_arrow(self): def steer(self, from_node, to_node): px, py, pyaw, mode, course_lengths = reeds_shepp_path_planning.reeds_shepp_path_planning( - from_node.x, from_node.y, from_node.yaw, - to_node.x, to_node.y, to_node.yaw, self.curvature) + from_node.x, from_node.y, from_node.yaw, to_node.x, + to_node.y, to_node.yaw, self.curvature, self.step_size) if not px: return None @@ -169,8 +173,8 @@ def steer(self, from_node, to_node): def calc_new_cost(self, from_node, to_node): _, _, _, _, course_lengths = reeds_shepp_path_planning.reeds_shepp_path_planning( - from_node.x, from_node.y, from_node.yaw, - to_node.x, to_node.y, to_node.yaw, self.curvature) + from_node.x, from_node.y, from_node.yaw, to_node.x, + to_node.y, to_node.yaw, self.curvature, self.step_size) if not course_lengths: return float("inf") diff --git a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py index 1577d048d3..c55d2629e5 100644 --- a/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py +++ b/PathPlanning/ReedsSheppPath/reeds_shepp_path_planning.py @@ -53,17 +53,14 @@ def mod2pi(x): def straight_left_straight(x, y, phi): phi = mod2pi(phi) - if y > 0.0 and 0.0 < phi < math.pi * 0.99: + # only take phi in (0.01*math.pi, 0.99*math.pi) for the sake of speed. + # phi in (0, 0.01*math.pi) will make test2() in test_rrt_star_reeds_shepp.py + # extremely time-consuming, since the value of xd, t will be very large. + if math.pi * 0.01 < phi < math.pi * 0.99 and y != 0: xd = - y / math.tan(phi) + x t = xd - math.tan(phi / 2.0) u = phi - v = math.hypot(x - xd, y) - math.tan(phi / 2.0) - return True, t, u, v - elif y < 0.0 < phi < math.pi * 0.99: - xd = - y / math.tan(phi) + x - t = xd - math.tan(phi / 2.0) - u = phi - v = -math.hypot(x - xd, y) - math.tan(phi / 2.0) + v = np.sign(y) * math.hypot(x - xd, y) - math.tan(phi / 2.0) return True, t, u, v return False, 0.0, 0.0, 0.0 diff --git a/tests/test_rrt_star_reeds_shepp.py b/tests/test_rrt_star_reeds_shepp.py index cb6b586b33..20d4916f96 100644 --- a/tests/test_rrt_star_reeds_shepp.py +++ b/tests/test_rrt_star_reeds_shepp.py @@ -6,6 +6,43 @@ def test1(): m.show_animation = False m.main(max_iter=5) +obstacleList = [ + (5, 5, 1), + (4, 6, 1), + (4, 8, 1), + (4, 10, 1), + (6, 5, 1), + (7, 5, 1), + (8, 6, 1), + (8, 8, 1), + (8, 10, 1) +] # [x,y,size(radius)] + +start = [0.0, 0.0, m.np.deg2rad(0.0)] +goal = [6.0, 7.0, m.np.deg2rad(90.0)] + +def test2(): + step_size = 0.2 + rrt_star_reeds_shepp = m.RRTStarReedsShepp(start, goal, + obstacleList, [-2.0, 15.0], + max_iter=100, step_size=step_size) + rrt_star_reeds_shepp.set_random_seed(seed=8) + path = rrt_star_reeds_shepp.planning(animation=False) + for i in range(len(path)-1): + # + 0.00000000000001 for acceptable errors arising from the planning process + assert m.math.dist(path[i][0:2], path[i+1][0:2]) < step_size + 0.00000000000001 + +def test3(): + step_size = 20 + rrt_star_reeds_shepp = m.RRTStarReedsShepp(start, goal, + obstacleList, [-2.0, 15.0], + max_iter=100, step_size=step_size) + rrt_star_reeds_shepp.set_random_seed(seed=8) + path = rrt_star_reeds_shepp.planning(animation=False) + for i in range(len(path)-1): + # + 0.00000000000001 for acceptable errors arising from the planning process + assert m.math.dist(path[i][0:2], path[i+1][0:2]) < step_size + 0.00000000000001 + if __name__ == '__main__': conftest.run_this_test(__file__) From 033e301498a12a039f95a990fa9b831c5015eaf3 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 2 May 2023 20:54:45 +0900 Subject: [PATCH 600/940] Cleanup cvxpy related codes (#823) * add normal_vector_estimation_main.rst * add normal_vector_estimation_main.rst * cleanup cvxpy related codes * cleanup cvxpy related codes --- .../rocket_powered_landing.py | 17 +++++++++-------- .../model_predictive_speed_and_steer_control.py | 6 ++++-- 2 files changed, 13 insertions(+), 10 deletions(-) diff --git a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py index 37dca15b98..239f3629c1 100644 --- a/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py +++ b/AerialNavigation/rocket_powered_landing/rocket_powered_landing.py @@ -12,13 +12,12 @@ - EmbersArc/SuccessiveConvexificationFreeFinalTime: Implementation of "Successive Convexification for 6-DoF Mars Rocket Powered Landing with Free-Final-Time" https://github.com/EmbersArc/SuccessiveConvexificationFreeFinalTime """ - +import warnings from time import time import numpy as np from scipy.integrate import odeint import cvxpy import matplotlib.pyplot as plt -from mpl_toolkits import mplot3d # Trajectory points K = 50 @@ -123,7 +122,7 @@ def set_random_initial_state(self, rng): rng.uniform(-20, 20))) def f_func(self, x, u): - m, rx, ry, rz, vx, vy, vz, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[ + m, _, _, _, vx, vy, vz, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[ 2], x[3], x[4], x[5], x[6], x[7], x[8], x[9], x[10], x[11], x[12], x[13] ux, uy, uz = u[0], u[1], u[2] @@ -148,7 +147,7 @@ def f_func(self, x, u): ]) def A_func(self, x, u): - m, rx, ry, rz, vx, vy, vz, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[ + m, _, _, _, _, _, _, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[ 2], x[3], x[4], x[5], x[6], x[7], x[8], x[9], x[10], x[11], x[12], x[13] ux, uy, uz = u[0], u[1], u[2] @@ -176,7 +175,7 @@ def A_func(self, x, u): [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]]) def B_func(self, x, u): - m, rx, ry, rz, vx, vy, vz, q0, q1, q2, q3, wx, wy, wz = x[0], x[1], x[ + m, _, _, _, _, _, _, q0, q1, q2, q3, _, _, _ = x[0], x[1], x[ 2], x[3], x[4], x[5], x[6], x[7], x[8], x[9], x[10], x[11], x[12], x[13] ux, uy, uz = u[0], u[1], u[2] @@ -534,7 +533,9 @@ def get_variable(self, name): def solve(self, **kwargs): error = False try: - self.prob.solve(verbose=verbose_solver, + with warnings.catch_warnings(): # For User warning from solver + warnings.simplefilter('ignore') + self.prob.solve(verbose=verbose_solver, solver=solver) except cvxpy.SolverError: error = True @@ -569,10 +570,10 @@ def axis3d_equal(X, Y, Z, ax): def plot_animation(X, U): # pragma: no cover fig = plt.figure() - ax = fig.gca(projection='3d') + ax = fig.add_subplot(projection='3d') # for stopping simulation with the esc key. fig.canvas.mpl_connect('key_release_event', - lambda event: [exit(0) if event.key == 'escape' else None]) + lambda event: [exit(0) if event.key == 'escape' else None]) for k in range(K): plt.cla() diff --git a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py index 59e69aa999..3015313198 100644 --- a/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py +++ b/PathTracking/model_predictive_speed_and_steer_control/model_predictive_speed_and_steer_control.py @@ -225,8 +225,9 @@ def predict_motion(x0, oa, od, xref): def iterative_linear_mpc_control(xref, x0, dref, oa, od): """ - MPC contorl with updating operational point iteraitvely + MPC control with updating operational point iteratively """ + ox, oy, oyaw, ov = None, None, None, None if oa is None or od is None: oa = [0.0] * T @@ -406,10 +407,11 @@ def do_simulation(cx, cy, cyaw, ck, sp, dl, initial_state): oa, odelta, ox, oy, oyaw, ov = iterative_linear_mpc_control( xref, x0, dref, oa, odelta) + di, ai = 0.0, 0.0 if odelta is not None: di, ai = odelta[0], oa[0] + state = update_state(state, ai, di) - state = update_state(state, ai, di) time = time + DT x.append(state.x) From b877a9d5ca15b794a72221c33d52d13bf3bf8434 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sun, 14 May 2023 17:15:10 +0900 Subject: [PATCH 601/940] Bump ruff from 0.0.263 to 0.0.265 in /requirements (#826) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.263 to 0.0.265. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.263...v0.0.265) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 501723248f..4522f6c7ca 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.3.1 # For unit test pytest-xdist == 3.2.1 # For unit test mypy == 1.2.0 # For unit test -ruff == 0.0.263 # For unit test +ruff == 0.0.265 # For unit test From 18a7d1b75871d9f12fe5fd20a93f5c50f059e614 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 16 May 2023 07:27:24 +0900 Subject: [PATCH 602/940] Bump mypy from 1.2.0 to 1.3.0 in /requirements (#835) Bumps [mypy](https://github.com/python/mypy) from 1.2.0 to 1.3.0. - [Commits](https://github.com/python/mypy/compare/v1.2.0...v1.3.0) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 4522f6c7ca..30c5330b90 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.7.1 cvxpy == 1.3.1 pytest == 7.3.1 # For unit test pytest-xdist == 3.2.1 # For unit test -mypy == 1.2.0 # For unit test +mypy == 1.3.0 # For unit test ruff == 0.0.265 # For unit test From 57943ae6f598ca14a0aadfe706bd7762c94ff36e Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 16 May 2023 20:08:06 +0900 Subject: [PATCH 603/940] Bump pytest-xdist from 3.2.1 to 3.3.0 in /requirements (#837) Bumps [pytest-xdist](https://github.com/pytest-dev/pytest-xdist) from 3.2.1 to 3.3.0. - [Changelog](https://github.com/pytest-dev/pytest-xdist/blob/master/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest-xdist/compare/v3.2.1...v3.3.0) --- updated-dependencies: - dependency-name: pytest-xdist dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 30c5330b90..616e3c3fc0 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,6 +3,6 @@ scipy == 1.10.1 matplotlib == 3.7.1 cvxpy == 1.3.1 pytest == 7.3.1 # For unit test -pytest-xdist == 3.2.1 # For unit test +pytest-xdist == 3.3.0 # For unit test mypy == 1.3.0 # For unit test ruff == 0.0.265 # For unit test From 29e0bab4e7ab380624c4c6f7fe068e67a5c71718 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 16 May 2023 20:39:26 +0900 Subject: [PATCH 604/940] Bump ruff from 0.0.265 to 0.0.267 in /requirements (#836) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.265 to 0.0.267. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.265...v0.0.267) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 616e3c3fc0..6efd6fcb98 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.3.1 # For unit test pytest-xdist == 3.3.0 # For unit test mypy == 1.3.0 # For unit test -ruff == 0.0.265 # For unit test +ruff == 0.0.267 # For unit test From dd6d046bf9b6458a8bcdd947045806af8c86e788 Mon Sep 17 00:00:00 2001 From: Erkam Kavak <70749779+erkamkavak@users.noreply.github.com> Date: Tue, 16 May 2023 15:42:18 +0300 Subject: [PATCH 605/940] fix added for checking if a neighbor is inside openList (#832) --- PathPlanning/HybridAStar/hybrid_a_star.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index b87fe706c2..03db0dc167 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -311,7 +311,7 @@ def hybrid_a_star_planning(start, goal, ox, oy, xy_resolution, yaw_resolution): neighbor_index = calc_index(neighbor, config) if neighbor_index in closedList: continue - if neighbor not in openList \ + if neighbor_index not in openList \ or openList[neighbor_index].cost > neighbor.cost: heapq.heappush( pq, (calc_cost(neighbor, h_dp, config), From 874ebff495b088e0aee48ad29e352548dee65e8d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Yangshen=E2=9A=A1Deng?= Date: Tue, 16 May 2023 20:43:57 +0800 Subject: [PATCH 606/940] fix: set rrt_star to find the shortest path (#834) * fix: set rrt_star to find the shortest path * fix: code style white space --- PathPlanning/RRTStar/rrt_star.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index b2884fe21b..dcb1a066eb 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -163,9 +163,13 @@ def search_best_goal_node(self): if not safe_goal_inds: return None - min_cost = min([self.node_list[i].cost for i in safe_goal_inds]) - for i in safe_goal_inds: - if self.node_list[i].cost == min_cost: + safe_goal_costs = [self.node_list[i].cost + + self.calc_dist_to_goal(self.node_list[i].x, self.node_list[i].y) + for i in safe_goal_inds] + + min_cost = min(safe_goal_costs) + for i, cost in zip(safe_goal_inds, safe_goal_costs): + if cost == min_cost: return i return None From 7be69c13cce0f518d3ce5521b4bafcc56bce1445 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 23 May 2023 07:23:34 +0900 Subject: [PATCH 607/940] Bump pytest-xdist from 3.3.0 to 3.3.1 in /requirements (#838) Bumps [pytest-xdist](https://github.com/pytest-dev/pytest-xdist) from 3.3.0 to 3.3.1. - [Changelog](https://github.com/pytest-dev/pytest-xdist/blob/master/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest-xdist/compare/v3.3.0...v3.3.1) --- updated-dependencies: - dependency-name: pytest-xdist dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 6efd6fcb98..389107f0bb 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,6 +3,6 @@ scipy == 1.10.1 matplotlib == 3.7.1 cvxpy == 1.3.1 pytest == 7.3.1 # For unit test -pytest-xdist == 3.3.0 # For unit test +pytest-xdist == 3.3.1 # For unit test mypy == 1.3.0 # For unit test ruff == 0.0.267 # For unit test From 390c1cdd9fce482f13280724d762c9f9000baaba Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 23 May 2023 12:42:52 +0900 Subject: [PATCH 608/940] Bump ruff from 0.0.267 to 0.0.269 in /requirements (#839) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.267 to 0.0.269. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.267...v0.0.269) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 389107f0bb..649b331e1d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.3.1 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.3.0 # For unit test -ruff == 0.0.267 # For unit test +ruff == 0.0.269 # For unit test From ca82a4b1dff20dba0c852f4e0ac41501cba6e9ab Mon Sep 17 00:00:00 2001 From: Faizan Alam <51821426+Faizan-Alam-1@users.noreply.github.com> Date: Sat, 27 May 2023 17:00:02 +0530 Subject: [PATCH 609/940] Add copy button in the documentation code snippets (#840) --- docs/conf.py | 1 + docs/doc_requirements.txt | 1 + 2 files changed, 2 insertions(+) diff --git a/docs/conf.py b/docs/conf.py index e7c64d07b2..0cbf3471f9 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -45,6 +45,7 @@ 'sphinx.ext.napoleon', 'sphinx.ext.imgconverter', 'IPython.sphinxext.ipython_console_highlighting', + 'sphinx_copybutton', ] # Add any paths that contain templates here, relative to this directory. diff --git a/docs/doc_requirements.txt b/docs/doc_requirements.txt index c01b596539..04c30e6037 100644 --- a/docs/doc_requirements.txt +++ b/docs/doc_requirements.txt @@ -2,3 +2,4 @@ sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 IPython == 8.10.0 # For sphinx documentation sphinxcontrib-napoleon == 0.7 # For auto doc +sphinx-copybutton From 5ddf70615ea35c366199ef6837ea88eba94ba6c8 Mon Sep 17 00:00:00 2001 From: Faizan Alam <51821426+Faizan-Alam-1@users.noreply.github.com> Date: Sun, 28 May 2023 13:52:35 +0530 Subject: [PATCH 610/940] Add dark mode feature in documentation (#842) --- docs/conf.py | 3 ++- docs/doc_requirements.txt | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/docs/conf.py b/docs/conf.py index 0cbf3471f9..df9b8fce22 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -46,6 +46,7 @@ 'sphinx.ext.imgconverter', 'IPython.sphinxext.ipython_console_highlighting', 'sphinx_copybutton', + 'sphinx_rtd_dark_mode', ] # Add any paths that contain templates here, relative to this directory. @@ -86,7 +87,7 @@ if on_rtd: html_theme = 'default' else: - html_theme = 'sphinx_rtd_theme' + html_theme = 'sphinx_rtd_light_them' # Theme options are theme-specific and customize the look and feel of a theme # further. For a list of options available for each theme, see the diff --git a/docs/doc_requirements.txt b/docs/doc_requirements.txt index 04c30e6037..a8cd2bde40 100644 --- a/docs/doc_requirements.txt +++ b/docs/doc_requirements.txt @@ -3,3 +3,4 @@ sphinx_rtd_theme == 1.0.0 IPython == 8.10.0 # For sphinx documentation sphinxcontrib-napoleon == 0.7 # For auto doc sphinx-copybutton +sphinx-rtd-dark-mode \ No newline at end of file From e4fe460e02f9f29ea2553e579e7599a652ca5207 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 30 May 2023 07:56:26 +0900 Subject: [PATCH 611/940] Bump ruff from 0.0.269 to 0.0.270 in /requirements (#844) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.269 to 0.0.270. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/charliermarsh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.269...v0.0.270) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 649b331e1d..4499e715a9 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.3.1 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.3.0 # For unit test -ruff == 0.0.269 # For unit test +ruff == 0.0.270 # For unit test From 6bade5000dca75b91cc9de94f797e5d558082855 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 13 Jun 2023 20:46:56 +0900 Subject: [PATCH 612/940] Bump ruff from 0.0.270 to 0.0.272 in /requirements (#849) Bumps [ruff](https://github.com/charliermarsh/ruff) from 0.0.270 to 0.0.272. - [Release notes](https://github.com/charliermarsh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/charliermarsh/ruff/compare/v0.0.270...v0.0.272) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 4499e715a9..93a1b8bba1 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.3.1 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.3.0 # For unit test -ruff == 0.0.270 # For unit test +ruff == 0.0.272 # For unit test From 3be53ab0e0802e908544e274278ed0390ea98597 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 13 Jun 2023 20:47:31 +0900 Subject: [PATCH 613/940] Bump pytest from 7.3.1 to 7.3.2 in /requirements (#850) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.3.1 to 7.3.2. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.3.1...7.3.2) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 93a1b8bba1..470180c1f7 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.24.3 scipy == 1.10.1 matplotlib == 3.7.1 cvxpy == 1.3.1 -pytest == 7.3.1 # For unit test +pytest == 7.3.2 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.3.0 # For unit test ruff == 0.0.272 # For unit test From c06e4909c865cf3912cdee4610ab91afcd3b111c Mon Sep 17 00:00:00 2001 From: Yichao <111082392+YichaoDeng@users.noreply.github.com> Date: Mon, 19 Jun 2023 17:02:16 +0800 Subject: [PATCH 614/940] fix: [ValueError] setting an array element with a sequence in [fast_slam2] (#851) --- SLAM/FastSLAM2/fast_slam2.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py index 7cd708df81..4c6c103325 100644 --- a/SLAM/FastSLAM2/fast_slam2.py +++ b/SLAM/FastSLAM2/fast_slam2.py @@ -405,8 +405,8 @@ def main(): for iz in range(len(z[:, 0])): landmark_id = int(z[2, iz]) - plt.plot([xEst[0], RFID[landmark_id, 0]], [ - xEst[1], RFID[landmark_id, 1]], "-k") + plt.plot([xEst[0][0], RFID[landmark_id, 0]], [ + xEst[1][0], RFID[landmark_id, 1]], "-k") for i in range(N_PARTICLE): plt.plot(particles[i].x, particles[i].y, ".r") From 94a8072b11fb2198b03ae193c4a3499d7a004a0f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 27 Jun 2023 07:01:39 +0900 Subject: [PATCH 615/940] Bump mypy from 1.3.0 to 1.4.1 in /requirements (#854) Bumps [mypy](https://github.com/python/mypy) from 1.3.0 to 1.4.1. - [Commits](https://github.com/python/mypy/compare/v1.3.0...v1.4.1) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 470180c1f7..bbd3764998 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.7.1 cvxpy == 1.3.1 pytest == 7.3.2 # For unit test pytest-xdist == 3.3.1 # For unit test -mypy == 1.3.0 # For unit test +mypy == 1.4.1 # For unit test ruff == 0.0.272 # For unit test From a0bb72e000bfcbc2442303c0bc39e4e6696f793f Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 27 Jun 2023 07:20:25 +0900 Subject: [PATCH 616/940] Bump pytest from 7.3.2 to 7.4.0 in /requirements (#857) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.3.2 to 7.4.0. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.3.2...7.4.0) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index bbd3764998..580a4ba731 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.24.3 scipy == 1.10.1 matplotlib == 3.7.1 cvxpy == 1.3.1 -pytest == 7.3.2 # For unit test +pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.4.1 # For unit test ruff == 0.0.272 # For unit test From 81c75f75ab987645c733952bbf277d349fefcec2 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 27 Jun 2023 13:25:12 +0900 Subject: [PATCH 617/940] Bump ruff from 0.0.272 to 0.0.275 in /requirements (#856) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.272 to 0.0.275. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.272...v0.0.275) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 580a4ba731..9db6898463 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.1 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.4.1 # For unit test -ruff == 0.0.272 # For unit test +ruff == 0.0.275 # For unit test From d7fdcade2f0a86cbe263d31530667fadc9ec1e61 Mon Sep 17 00:00:00 2001 From: neriya shulman <45920392+neriyashul@users.noreply.github.com> Date: Fri, 30 Jun 2023 15:13:09 +0300 Subject: [PATCH 618/940] Fix broken links in README.md for ipynb files (#859) --- README.md | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index bfde2f9295..bc0198f78e 100644 --- a/README.md +++ b/README.md @@ -161,7 +161,9 @@ All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation EKF pic -Documentation: [Notebook](https://github.com/AtsushiSakai/PythonRobotics/blob/master/Localization/extended_kalman_filter/extended_kalman_filter_localization.ipynb) +Ref: + +- [documentation](https://atsushisakai.github.io/PythonRobotics/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.html) ## Particle filter localization @@ -532,7 +534,7 @@ Path tracking simulation with iterative linear model predictive speed and steeri Ref: -- [notebook](https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/model_predictive_speed_and_steer_control/Model_predictive_speed_and_steering_control.ipynb) +- [documentation](https://atsushisakai.github.io/PythonRobotics/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control.html) - [Real\-time Model Predictive Control \(MPC\), ACADO, Python \| Work\-is\-Playing](http://grauonline.de/wordpress/?page_id=3244) @@ -544,7 +546,7 @@ A motion planning and path tracking simulation with NMPC of C-GMRES Ref: -- [notebook](https://github.com/AtsushiSakai/PythonRobotics/blob/master/PathTracking/cgmres_nmpc/cgmres_nmpc.ipynb) +- [documentation](https://atsushisakai.github.io/PythonRobotics/modules/path_tracking/cgmres_nmpc/cgmres_nmpc.html) # Arm Navigation @@ -584,7 +586,7 @@ This is a 3d trajectory generation simulation for a rocket powered landing. Ref: -- [notebook](https://github.com/AtsushiSakai/PythonRobotics/blob/master/AerialNavigation/rocket_powered_landing/rocket_powered_landing.ipynb) +- [documentation](https://atsushisakai.github.io/PythonRobotics/modules/aerial_navigation/rocket_powered_landing/rocket_powered_landing.html) # Bipedal From 67edaf8b026bee1c502b09d92249c10ce760e22a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 1 Jul 2023 08:29:34 +0900 Subject: [PATCH 619/940] Enhance rectangle fitting docs (#848) * enhance rectangle fitting docs * enhance rectangle fitting docs * Update rectangle_fitting_main.rst * Update rectangle_fitting_main.rst * Update rectangle_fitting_main.rst * Update rectangle_fitting_main.rst * Update rectangle_fitting_main.rst * Update rectangle_fitting_main.rst * Update rectangle_fitting_main.rst * Update rectangle_fitting_main.rst * enhance rectangle fitting docs --- .../rectangle_fitting/rectangle_fitting.py | 108 +++++++++++------- .../rectangle_fitting_main.rst | 62 ++++++++++ .../modules/slam/FastSLAM1/FastSLAM1_main.rst | 2 +- 3 files changed, 128 insertions(+), 44 deletions(-) diff --git a/Mapping/rectangle_fitting/rectangle_fitting.py b/Mapping/rectangle_fitting/rectangle_fitting.py index f54ada1e3a..177f078871 100644 --- a/Mapping/rectangle_fitting/rectangle_fitting.py +++ b/Mapping/rectangle_fitting/rectangle_fitting.py @@ -30,6 +30,11 @@ class LShapeFitting: + """ + LShapeFitting class. You can use this class by initializing the class and + changing the parameters, and then calling the fitting method. + + """ class Criteria(Enum): AREA = 1 @@ -37,15 +42,35 @@ class Criteria(Enum): VARIANCE = 3 def __init__(self): - # Parameters + """ + Default parameter settings + """ + #: Fitting criteria parameter self.criteria = self.Criteria.VARIANCE - self.min_dist_of_closeness_criteria = 0.01 # [m] - self.d_theta_deg_for_search = 1.0 # [deg] - self.R0 = 3.0 # [m] range segmentation param - self.Rd = 0.001 # [m] range segmentation param + #: Minimum distance for closeness criteria parameter [m] + self.min_dist_of_closeness_criteria = 0.01 + #: Angle difference parameter [deg] + self.d_theta_deg_for_search = 1.0 + #: Range segmentation parameter [m] + self.R0 = 3.0 + #: Range segmentation parameter [m] + self.Rd = 0.001 def fitting(self, ox, oy): + """ + Fitting L-shape model to object points + + Parameters + ---------- + ox : x positions of range points from an object + oy : y positions of range points from an object + + Returns + ------- + rects: Fitting rectangles + id_sets: id sets of each cluster + """ # step1: Adaptive Range Segmentation id_sets = self._adoptive_range_segmentation(ox, oy) @@ -60,56 +85,53 @@ def fitting(self, ox, oy): @staticmethod def _calc_area_criterion(c1, c2): - c1_max = max(c1) - c2_max = max(c2) - c1_min = min(c1) - c2_min = min(c2) - + c1_max, c1_min, c2_max, c2_min = LShapeFitting._find_min_max(c1, c2) alpha = -(c1_max - c1_min) * (c2_max - c2_min) - return alpha def _calc_closeness_criterion(self, c1, c2): - c1_max = max(c1) - c2_max = max(c2) - c1_min = min(c1) - c2_min = min(c2) + c1_max, c1_min, c2_max, c2_min = LShapeFitting._find_min_max(c1, c2) # Vectorization - D1 = np.minimum(c1_max - c1, c1 - c1_min) - D2 = np.minimum(c2_max - c2, c2 - c2_min) - d = np.maximum(np.minimum(D1, D2), self.min_dist_of_closeness_criteria) + d1 = np.minimum(c1_max - c1, c1 - c1_min) + d2 = np.minimum(c2_max - c2, c2 - c2_min) + d = np.maximum(np.minimum(d1, d2), self.min_dist_of_closeness_criteria) beta = (1.0 / d).sum() return beta @staticmethod def _calc_variance_criterion(c1, c2): - c1_max = max(c1) - c2_max = max(c2) - c1_min = min(c1) - c2_min = min(c2) + c1_max, c1_min, c2_max, c2_min = LShapeFitting._find_min_max(c1, c2) # Vectorization - D1 = np.minimum(c1_max - c1, c1 - c1_min) - D2 = np.minimum(c2_max - c2, c2 - c2_min) - E1 = D1[D1 < D2] - E2 = D2[D1 >= D2] - V1 = - np.var(E1) if len(E1) > 0 else 0. - V2 = - np.var(E2) if len(E2) > 0 else 0. - gamma = V1 + V2 + d1 = np.minimum(c1_max - c1, c1 - c1_min) + d2 = np.minimum(c2_max - c2, c2 - c2_min) + e1 = d1[d1 < d2] + e2 = d2[d1 >= d2] + v1 = - np.var(e1) if len(e1) > 0 else 0. + v2 = - np.var(e2) if len(e2) > 0 else 0. + gamma = v1 + v2 return gamma + @staticmethod + def _find_min_max(c1, c2): + c1_max = max(c1) + c2_max = max(c2) + c1_min = min(c1) + c2_min = min(c2) + return c1_max, c1_min, c2_max, c2_min + def _rectangle_search(self, x, y): - X = np.array([x, y]).T + xy = np.array([x, y]).T d_theta = np.deg2rad(self.d_theta_deg_for_search) min_cost = (-float('inf'), None) for theta in np.arange(0.0, np.pi / 2.0 - d_theta, d_theta): - c = X @ rot_mat_2d(theta) + c = xy @ rot_mat_2d(theta) c1 = c[:, 0] c2 = c[:, 1] @@ -129,8 +151,8 @@ def _rectangle_search(self, x, y): sin_s = np.sin(min_cost[1]) cos_s = np.cos(min_cost[1]) - c1_s = X @ np.array([cos_s, sin_s]).T - c2_s = X @ np.array([-sin_s, cos_s]).T + c1_s = xy @ np.array([cos_s, sin_s]).T + c2_s = xy @ np.array([-sin_s, cos_s]).T rect = RectangleData() rect.a[0] = cos_s @@ -151,28 +173,28 @@ def _rectangle_search(self, x, y): def _adoptive_range_segmentation(self, ox, oy): # Setup initial cluster - S = [] + segment_list = [] for i, _ in enumerate(ox): - C = set() - R = self.R0 + self.Rd * np.linalg.norm([ox[i], oy[i]]) + c = set() + r = self.R0 + self.Rd * np.linalg.norm([ox[i], oy[i]]) for j, _ in enumerate(ox): d = np.hypot(ox[i] - ox[j], oy[i] - oy[j]) - if d <= R: - C.add(j) - S.append(C) + if d <= r: + c.add(j) + segment_list.append(c) # Merge cluster while True: no_change = True - for (c1, c2) in list(itertools.permutations(range(len(S)), 2)): - if S[c1] & S[c2]: - S[c1] = (S[c1] | S.pop(c2)) + for (c1, c2) in list(itertools.permutations(range(len(segment_list)), 2)): + if segment_list[c1] & segment_list[c2]: + segment_list[c1] = (segment_list[c1] | segment_list.pop(c2)) no_change = False break if no_change: break - return S + return segment_list class RectangleData: diff --git a/docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst b/docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst index c0949ac4c3..50a50141b2 100644 --- a/docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst +++ b/docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst @@ -5,3 +5,65 @@ This is an object shape recognition using rectangle fitting. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/rectangle_fitting/animation.gif +This example code is based on this paper algorithm: + +- `Efficient L\-Shape Fitting for Vehicle Detection Using Laser Scanners \- The Robotics Institute Carnegie Mellon University `_ + +The algorithm consists of 2 steps as below. + +Step1: Adaptive range segmentation +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +In the first step, all range data points are segmented into some clusters. + +We calculate the distance between each range data and the nearest range data, and if this distance is below a certain threshold, it is judged to be in the same cluster. +This distance threshold is determined in proportion to the distance from the sensor. +This is taking advantage of the general model of distance sensors, which tends to have sparser data distribution as the distance from the sensor increases. + +The threshold range is calculated by: + +.. math:: r_{th} = R_0 + R_d * r_{origin} + +where + +- :math:`r_{th}`: Threashold range +- :math:`R_0, R_d`: Constant parameters +- :math:`r_{origin}`: Distance from the sensor for a range data. + +Step2: Rectangle search +~~~~~~~~~~~~~~~~~~~~~~~~~~ + +In the second step, for each cluster calculated in the previous step, rectangular fittings will be applied. +In this rectangular fitting, each cluster's distance data is rotated at certain angle intervals. +It is evaluated by one of the three evaluation functions below, then best angle parameter one is selected as the rectangle shape. + +1. Rectangle Area Minimization criteria +========================================= + +This evaluation function calculates the area of the smallest rectangle that includes all the points, derived from the difference between the maximum and minimum values on the x-y axis for all distance data points. +This allows for fitting a rectangle in a direction that encompasses as much of the smallest rectangular shape as possible. + + +2. Closeness criteria +====================== + +This evaluation function uses the distances between the top and bottom vertices on the right side of the rectangle and each point in the distance data as evaluation values. +If there are points on the rectangle edges, this evaluation value decreases. + +3. Variance criteria +======================= + +This evaluation function uses the squreed distances between the edges of the rectangle (horizontal and vertical) and each point. +Calculating the squared error is the same as calculating the variance. +The smaller this variance, the more it signifies that the points fit within the rectangle. + +API +~~~~~~ + +.. autoclass:: Mapping.rectangle_fitting.rectangle_fitting.LShapeFitting + :members: + +References +~~~~~~~~~~ + +- `Efficient L\-Shape Fitting for Vehicle Detection Using Laser Scanners \- The Robotics Institute Carnegie Mellon University `_ diff --git a/docs/modules/slam/FastSLAM1/FastSLAM1_main.rst b/docs/modules/slam/FastSLAM1/FastSLAM1_main.rst index f19527c453..a2aa521216 100644 --- a/docs/modules/slam/FastSLAM1/FastSLAM1_main.rst +++ b/docs/modules/slam/FastSLAM1/FastSLAM1_main.rst @@ -65,7 +65,7 @@ represent the initial uncertainty. At each time step we do: The following equations and code snippets we can see how the particles distribution evolves in case we provide only the control :math:`(v,w)`, -which are the linear and angular velocity repsectively. +which are the linear and angular velocity respectively. :math:`\begin{equation*} F= \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix} \end{equation*}` From 4d714706312735ce46a118bb6782c2aef0ba333f Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 1 Jul 2023 15:30:32 +0900 Subject: [PATCH 620/940] upgrade numpy to 1.25.0 and fix bugs (#861) --- .../drone_3d_trajectory_following.py | 13 ++++--- .../two_joint_arm_to_point_control.py | 11 +++--- .../inverted_pendulum_lqr_control.py | 6 +-- .../inverted_pendulum_mpc_control.py | 6 +-- .../histogram_filter/histogram_filter.py | 5 ++- .../unscented_kalman_filter.py | 4 +- Mapping/circle_fitting/circle_fitting.py | 6 +-- .../batch_informed_rrtstar.py | 6 +-- .../InformedRRTStar/informed_rrt_star.py | 4 +- .../lookup_table_generator.py | 2 +- .../motion_model.py | 39 +++++++++++-------- .../trajectory_generator.py | 6 +-- .../state_lattice_planner.py | 2 +- SLAM/FastSLAM1/fast_slam1.py | 2 +- SLAM/FastSLAM2/fast_slam2.py | 2 +- SLAM/GraphBasedSLAM/graph_based_slam.py | 6 +-- requirements/requirements.txt | 2 +- tests/test_codestyle.py | 2 +- 18 files changed, 66 insertions(+), 58 deletions(-) diff --git a/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py b/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py index e00b3fff48..029e82be62 100644 --- a/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py +++ b/AerialNavigation/drone_3d_trajectory_following/drone_3d_trajectory_following.py @@ -8,7 +8,6 @@ import numpy as np from Quadrotor import Quadrotor from TrajectoryGenerator import TrajectoryGenerator -from mpl_toolkits.mplot3d import Axes3D show_animation = True @@ -128,7 +127,7 @@ def calculate_position(c, t): Calculates a position given a set of quintic coefficients and a time. Args - c: List of coefficients generated by a quintic polynomial + c: List of coefficients generated by a quintic polynomial trajectory generator. t: Time at which to calculate the position @@ -143,7 +142,7 @@ def calculate_velocity(c, t): Calculates a velocity given a set of quintic coefficients and a time. Args - c: List of coefficients generated by a quintic polynomial + c: List of coefficients generated by a quintic polynomial trajectory generator. t: Time at which to calculate the velocity @@ -158,7 +157,7 @@ def calculate_acceleration(c, t): Calculates an acceleration given a set of quintic coefficients and a time. Args - c: List of coefficients generated by a quintic polynomial + c: List of coefficients generated by a quintic polynomial trajectory generator. t: Time at which to calculate the acceleration @@ -168,7 +167,7 @@ def calculate_acceleration(c, t): return 20 * c[0] * t**3 + 12 * c[1] * t**2 + 6 * c[2] * t + 2 * c[3] -def rotation_matrix(roll, pitch, yaw): +def rotation_matrix(roll_array, pitch_array, yaw): """ Calculates the ZYX rotation matrix. @@ -180,6 +179,8 @@ def rotation_matrix(roll, pitch, yaw): Returns 3x3 rotation matrix as NumPy array """ + roll = roll_array[0] + pitch = pitch_array[0] return np.array( [[cos(yaw) * cos(pitch), -sin(yaw) * cos(roll) + cos(yaw) * sin(pitch) * sin(roll), sin(yaw) * sin(roll) + cos(yaw) * sin(pitch) * cos(roll)], [sin(yaw) * cos(pitch), cos(yaw) * cos(roll) + sin(yaw) * sin(pitch) * @@ -190,7 +191,7 @@ def rotation_matrix(roll, pitch, yaw): def main(): """ - Calculates the x, y, z coefficients for the four segments + Calculates the x, y, z coefficients for the four segments of the trajectory """ x_coeffs = [[], [], [], []] diff --git a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py index 012a7f72f1..66d0ebeb23 100644 --- a/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py +++ b/ArmNavigation/two_joint_arm_to_point_control/two_joint_arm_to_point_control.py @@ -14,9 +14,10 @@ import matplotlib.pyplot as plt import numpy as np +import math -# Similation parameters +# Simulation parameters Kp = 15 dt = 0.01 @@ -50,15 +51,15 @@ def two_joint_arm(GOAL_TH=0.0, theta1=0.0, theta2=0.0): else: theta2_goal = np.arccos( (x**2 + y**2 - l1**2 - l2**2) / (2 * l1 * l2)) - tmp = np.math.atan2(l2 * np.sin(theta2_goal), + tmp = math.atan2(l2 * np.sin(theta2_goal), (l1 + l2 * np.cos(theta2_goal))) - theta1_goal = np.math.atan2(y, x) - tmp + theta1_goal = math.atan2(y, x) - tmp if theta1_goal < 0: theta2_goal = -theta2_goal - tmp = np.math.atan2(l2 * np.sin(theta2_goal), + tmp = math.atan2(l2 * np.sin(theta2_goal), (l1 + l2 * np.cos(theta2_goal))) - theta1_goal = np.math.atan2(y, x) - tmp + theta1_goal = math.atan2(y, x) - tmp theta1 = theta1 + Kp * ang_diff(theta1_goal, theta1) * dt theta2 = theta2 + Kp * ang_diff(theta2_goal, theta2) * dt diff --git a/Control/inverted_pendulum/inverted_pendulum_lqr_control.py b/Control/inverted_pendulum/inverted_pendulum_lqr_control.py index fb68c91c45..c4380530b8 100644 --- a/Control/inverted_pendulum/inverted_pendulum_lqr_control.py +++ b/Control/inverted_pendulum/inverted_pendulum_lqr_control.py @@ -50,14 +50,14 @@ def main(): if show_animation: plt.clf() - px = float(x[0]) - theta = float(x[2]) + px = float(x[0, 0]) + theta = float(x[2, 0]) plot_cart(px, theta) plt.xlim([-5.0, 2.0]) plt.pause(0.001) print("Finish") - print(f"x={float(x[0]):.2f} [m] , theta={math.degrees(x[2]):.2f} [deg]") + print(f"x={float(x[0, 0]):.2f} [m] , theta={math.degrees(x[2, 0]):.2f} [deg]") if show_animation: plt.show() diff --git a/Control/inverted_pendulum/inverted_pendulum_mpc_control.py b/Control/inverted_pendulum/inverted_pendulum_mpc_control.py index 6b966b13b4..9a5fa2ab41 100644 --- a/Control/inverted_pendulum/inverted_pendulum_mpc_control.py +++ b/Control/inverted_pendulum/inverted_pendulum_mpc_control.py @@ -55,14 +55,14 @@ def main(): if show_animation: plt.clf() - px = float(x[0]) - theta = float(x[2]) + px = float(x[0, 0]) + theta = float(x[2, 0]) plot_cart(px, theta) plt.xlim([-5.0, 2.0]) plt.pause(0.001) print("Finish") - print(f"x={float(x[0]):.2f} [m] , theta={math.degrees(x[2]):.2f} [deg]") + print(f"x={float(x[0, 0]):.2f} [m] , theta={math.degrees(x[2, 0]):.2f} [deg]") if show_animation: plt.show() diff --git a/Localization/histogram_filter/histogram_filter.py b/Localization/histogram_filter/histogram_filter.py index a4aeb419cf..17cfc2e14c 100644 --- a/Localization/histogram_filter/histogram_filter.py +++ b/Localization/histogram_filter/histogram_filter.py @@ -15,6 +15,7 @@ import math import matplotlib.pyplot as plt +import matplotlib as mpl import numpy as np from scipy.ndimage import gaussian_filter from scipy.stats import norm @@ -114,7 +115,7 @@ def motion_model(x, u): def draw_heat_map(data, mx, my): max_value = max([max(i_data) for i_data in data]) plt.grid(False) - plt.pcolor(mx, my, data, vmax=max_value, cmap=plt.cm.get_cmap("Blues")) + plt.pcolor(mx, my, data, vmax=max_value, cmap=mpl.colormaps["Blues"]) plt.axis("equal") @@ -194,7 +195,7 @@ def motion_update(grid_map, u, yaw): y_shift = grid_map.dy // grid_map.xy_resolution if abs(x_shift) >= 1.0 or abs(y_shift) >= 1.0: # map should be shifted - grid_map = map_shift(grid_map, int(x_shift), int(y_shift)) + grid_map = map_shift(grid_map, int(x_shift[0]), int(y_shift[0])) grid_map.dx -= x_shift * grid_map.xy_resolution grid_map.dy -= y_shift * grid_map.xy_resolution diff --git a/Localization/unscented_kalman_filter/unscented_kalman_filter.py b/Localization/unscented_kalman_filter/unscented_kalman_filter.py index dbcdeef015..4af748ec71 100644 --- a/Localization/unscented_kalman_filter/unscented_kalman_filter.py +++ b/Localization/unscented_kalman_filter/unscented_kalman_filter.py @@ -69,8 +69,8 @@ def motion_model(x, u): [0, 0, 1.0, 0], [0, 0, 0, 0]]) - B = np.array([[DT * math.cos(x[2]), 0], - [DT * math.sin(x[2]), 0], + B = np.array([[DT * math.cos(x[2, 0]), 0], + [DT * math.sin(x[2, 0]), 0], [0.0, DT], [1.0, 0.0]]) diff --git a/Mapping/circle_fitting/circle_fitting.py b/Mapping/circle_fitting/circle_fitting.py index c331d56796..2eba550127 100644 --- a/Mapping/circle_fitting/circle_fitting.py +++ b/Mapping/circle_fitting/circle_fitting.py @@ -40,9 +40,9 @@ def circle_fitting(x, y): T = np.linalg.inv(F).dot(G) - cxe = float(T[0] / -2) - cye = float(T[1] / -2) - re = math.sqrt(cxe**2 + cye**2 - T[2]) + cxe = float(T[0, 0] / -2) + cye = float(T[1, 0] / -2) + re = math.sqrt(cxe**2 + cye**2 - T[2, 0]) error = sum([np.hypot(cxe - ix, cye - iy) - re for (ix, iy) in zip(x, y)]) diff --git a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py index b5eabbb39b..92c3a58761 100644 --- a/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py +++ b/PathPlanning/BatchInformedRRTStar/batch_informed_rrtstar.py @@ -23,7 +23,7 @@ show_animation = True -class RTree(object): +class RTree: # Class to represent the explicit tree created # while sampling through the state space @@ -132,7 +132,7 @@ def node_id_to_real_world_coord(self, nid): self.node_id_to_grid_coord(nid)) -class BITStar(object): +class BITStar: def __init__(self, start, goal, obstacleList, randArea, eta=2.0, @@ -189,7 +189,7 @@ def setup_planning(self): [(self.start[1] + self.goal[1]) / 2.0], [0]]) a1 = np.array([[(self.goal[0] - self.start[0]) / cMin], [(self.goal[1] - self.start[1]) / cMin], [0]]) - eTheta = math.atan2(a1[1], a1[0]) + eTheta = math.atan2(a1[1, 0], a1[0, 0]) # first column of identity matrix transposed id1_t = np.array([1.0, 0.0, 0.0]).reshape(1, 3) M = np.dot(a1, id1_t) diff --git a/PathPlanning/InformedRRTStar/informed_rrt_star.py b/PathPlanning/InformedRRTStar/informed_rrt_star.py index 4f0ec31988..b6f9d234dd 100644 --- a/PathPlanning/InformedRRTStar/informed_rrt_star.py +++ b/PathPlanning/InformedRRTStar/informed_rrt_star.py @@ -58,7 +58,7 @@ def informed_rrt_star_search(self, animation=True): a1 = np.array([[(self.goal.x - self.start.x) / c_min], [(self.goal.y - self.start.y) / c_min], [0]]) - e_theta = math.atan2(a1[1], a1[0]) + e_theta = math.atan2(a1[1, 0], a1[0, 0]) # first column of identity matrix transposed id1_t = np.array([1.0, 0.0, 0.0]).reshape(1, 3) m = a1 @ id1_t @@ -136,7 +136,7 @@ def choose_parent(self, new_node, near_inds): def find_near_nodes(self, new_node): n_node = len(self.node_list) - r = 50.0 * math.sqrt((math.log(n_node) / n_node)) + r = 50.0 * math.sqrt(math.log(n_node) / n_node) d_list = [(node.x - new_node.x) ** 2 + (node.y - new_node.y) ** 2 for node in self.node_list] near_inds = [d_list.index(i) for i in d_list if i <= r ** 2] diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/lookup_table_generator.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/lookup_table_generator.py index 6cb226adef..4c3b32f280 100644 --- a/PathPlanning/ModelPredictiveTrajectoryGenerator/lookup_table_generator.py +++ b/PathPlanning/ModelPredictiveTrajectoryGenerator/lookup_table_generator.py @@ -81,7 +81,7 @@ def generate_lookup_table(): if x is not None: print("find good path") lookup_table.append( - [x[-1], y[-1], yaw[-1], float(p[0]), float(p[1]), float(p[2])]) + [x[-1], y[-1], yaw[-1], float(p[0, 0]), float(p[1, 0]), float(p[2, 0])]) print("finish lookup table generation") diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py index f6c78d3bc1..531bf91ef5 100644 --- a/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py +++ b/PathPlanning/ModelPredictiveTrajectoryGenerator/motion_model.py @@ -1,10 +1,10 @@ import math import numpy as np -import scipy.interpolate +from scipy.interpolate import interp1d # motion parameter L = 1.0 # wheel base -ds = 0.1 # course distanse +ds = 0.1 # course distance v = 10.0 / 3.6 # velocity [m/s] @@ -22,7 +22,6 @@ def pi_2_pi(angle): def update(state, v, delta, dt, L): - state.v = v state.x = state.x + state.v * math.cos(state.yaw) * dt state.y = state.y + state.v * math.sin(state.yaw) * dt @@ -33,18 +32,20 @@ def update(state, v, delta, dt, L): def generate_trajectory(s, km, kf, k0): - n = s / ds time = s / v # [s] - - if isinstance(time, type(np.array([]))): time = time[0] - if isinstance(km, type(np.array([]))): km = km[0] - if isinstance(kf, type(np.array([]))): kf = kf[0] - + + if isinstance(time, type(np.array([]))): + time = time[0] + if isinstance(km, type(np.array([]))): + km = km[0] + if isinstance(kf, type(np.array([]))): + kf = kf[0] + tk = np.array([0.0, time / 2.0, time]) kk = np.array([k0, km, kf]) t = np.arange(0.0, time, time / n) - fkp = scipy.interpolate.interp1d(tk, kk, kind="quadratic") + fkp = interp1d(tk, kk, kind="quadratic") kp = [fkp(ti) for ti in t] dt = float(time / n) @@ -64,18 +65,22 @@ def generate_trajectory(s, km, kf, k0): def generate_last_state(s, km, kf, k0): - n = s / ds time = s / v # [s] - - if isinstance(time, type(np.array([]))): time = time[0] - if isinstance(km, type(np.array([]))): km = km[0] - if isinstance(kf, type(np.array([]))): kf = kf[0] - + + if isinstance(n, type(np.array([]))): + n = n[0] + if isinstance(time, type(np.array([]))): + time = time[0] + if isinstance(km, type(np.array([]))): + km = km[0] + if isinstance(kf, type(np.array([]))): + kf = kf[0] + tk = np.array([0.0, time / 2.0, time]) kk = np.array([k0, km, kf]) t = np.arange(0.0, time, time / n) - fkp = scipy.interpolate.interp1d(tk, kk, kind="quadratic") + fkp = interp1d(tk, kk, kind="quadratic") kp = [fkp(ti) for ti in t] dt = time / n diff --git a/PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py b/PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py index a44e1ac956..97c0ad8b80 100644 --- a/PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py +++ b/PathPlanning/ModelPredictiveTrajectoryGenerator/trajectory_generator.py @@ -106,7 +106,7 @@ def show_trajectory(target, xc, yc): # pragma: no cover def optimize_trajectory(target, k0, p): for i in range(max_iter): - xc, yc, yawc = motion_model.generate_trajectory(p[0], p[1], p[2], k0) + xc, yc, yawc = motion_model.generate_trajectory(p[0, 0], p[1, 0], p[2, 0], k0) dc = np.array(calc_diff(target, xc, yc, yawc)).reshape(3, 1) cost = np.linalg.norm(dc) @@ -135,7 +135,7 @@ def optimize_trajectory(target, k0, p): return xc, yc, yawc, p -def test_optimize_trajectory(): # pragma: no cover +def optimize_trajectory_demo(): # pragma: no cover # target = motion_model.State(x=5.0, y=2.0, yaw=np.deg2rad(00.0)) target = motion_model.State(x=5.0, y=2.0, yaw=np.deg2rad(90.0)) @@ -155,7 +155,7 @@ def test_optimize_trajectory(): # pragma: no cover def main(): # pragma: no cover print(__file__ + " start!!") - test_optimize_trajectory() + optimize_trajectory_demo() if __name__ == '__main__': diff --git a/PathPlanning/StateLatticePlanner/state_lattice_planner.py b/PathPlanning/StateLatticePlanner/state_lattice_planner.py index e26fb8288c..f4b1461b7a 100644 --- a/PathPlanning/StateLatticePlanner/state_lattice_planner.py +++ b/PathPlanning/StateLatticePlanner/state_lattice_planner.py @@ -70,7 +70,7 @@ def generate_path(target_states, k0): if x is not None: print("find good path") result.append( - [x[-1], y[-1], yaw[-1], float(p[0]), float(p[1]), float(p[2])]) + [x[-1], y[-1], yaw[-1], float(p[0, 0]), float(p[1, 0]), float(p[2, 0])]) print("finish path generation") return result diff --git a/SLAM/FastSLAM1/fast_slam1.py b/SLAM/FastSLAM1/fast_slam1.py index c4beaba257..7b89f52df4 100644 --- a/SLAM/FastSLAM1/fast_slam1.py +++ b/SLAM/FastSLAM1/fast_slam1.py @@ -194,7 +194,7 @@ def compute_weight(particle, z, Q_cov): print("singular") return 1.0 - num = math.exp(-0.5 * dx.T @ invS @ dx) + num = np.exp(-0.5 * (dx.T @ invS @ dx))[0, 0] den = 2.0 * math.pi * math.sqrt(np.linalg.det(Sf)) w = num / den diff --git a/SLAM/FastSLAM2/fast_slam2.py b/SLAM/FastSLAM2/fast_slam2.py index 4c6c103325..aa77aa956a 100644 --- a/SLAM/FastSLAM2/fast_slam2.py +++ b/SLAM/FastSLAM2/fast_slam2.py @@ -193,7 +193,7 @@ def compute_weight(particle, z, Q_cov): except np.linalg.linalg.LinAlgError: return 1.0 - num = math.exp(-0.5 * dz.T @ invS @ dz) + num = np.exp(-0.5 * dz.T @ invS @ dz)[0, 0] den = 2.0 * math.pi * math.sqrt(np.linalg.det(Sf)) w = num / den diff --git a/SLAM/GraphBasedSLAM/graph_based_slam.py b/SLAM/GraphBasedSLAM/graph_based_slam.py index 5510a41110..4d66ef6732 100644 --- a/SLAM/GraphBasedSLAM/graph_based_slam.py +++ b/SLAM/GraphBasedSLAM/graph_based_slam.py @@ -117,9 +117,9 @@ def calc_edges(x_list, z_list): for iz2 in range(len(z_list[t2][:, 0])): if z_list[t1][iz1, 3] == z_list[t2][iz2, 3]: d1 = z_list[t1][iz1, 0] - angle1, phi1 = z_list[t1][iz1, 1], z_list[t1][iz1, 2] + angle1, _ = z_list[t1][iz1, 1], z_list[t1][iz1, 2] d2 = z_list[t2][iz2, 0] - angle2, phi2 = z_list[t2][iz2, 1], z_list[t2][iz2, 2] + angle2, _ = z_list[t2][iz2, 1], z_list[t2][iz2, 2] edge = calc_edge(x1, y1, yaw1, x2, y2, yaw2, d1, angle1, d2, angle2, t1, t2) @@ -188,7 +188,7 @@ def graph_based_slam(x_init, hz): for i in range(nt): x_opt[0:3, i] += dx[i * 3:i * 3 + 3, 0] - diff = dx.T @ dx + diff = (dx.T @ dx)[0, 0] print("iteration: %d, diff: %f" % (itr + 1, diff)) if diff < 1.0e-5: break diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 9db6898463..4f226facb1 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.24.3 +numpy == 1.25.0 scipy == 1.10.1 matplotlib == 3.7.1 cvxpy == 1.3.1 diff --git a/tests/test_codestyle.py b/tests/test_codestyle.py index 2ad3816ea1..a7d11d270f 100644 --- a/tests/test_codestyle.py +++ b/tests/test_codestyle.py @@ -126,7 +126,7 @@ def test(): branch_commit = find_branch_point("origin/master") files = diff_files(branch_commit) print(files) - rc, errors = run_ruff(files, fix=False) + rc, errors = run_ruff(files, fix=True) if errors: print(errors) else: From e0b7ea5a0ace961fdada3bf524080208e36875ee Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 1 Jul 2023 18:40:03 +0900 Subject: [PATCH 621/940] upgrade scipy and cvxpy (#864) --- requirements/requirements.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 4f226facb1..30ccc4765d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.25.0 -scipy == 1.10.1 +scipy == 1.11.1 matplotlib == 3.7.1 -cvxpy == 1.3.1 +cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.4.1 # For unit test From 5264c68542306e901fc0585219ade6f6f573d2a9 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 2 Jul 2023 22:12:25 +0900 Subject: [PATCH 622/940] Update dependabot.yml (#868) --- .github/dependabot.yml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.github/dependabot.yml b/.github/dependabot.yml index 07f1bc80e0..7d7e6723cb 100644 --- a/.github/dependabot.yml +++ b/.github/dependabot.yml @@ -6,3 +6,8 @@ updates: interval: weekly time: "20:00" open-pull-requests-limit: 10 + +- package-ecosystem: 'github-actions' + directory: '/' + schedule: + interval: 'weekly' From c14bdda136d76193e8fdf2f0322579c0e0c71571 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 2 Jul 2023 22:25:55 +0900 Subject: [PATCH 623/940] Update dependabot.yml --- .github/dependabot.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/dependabot.yml b/.github/dependabot.yml index 7d7e6723cb..c6fecb796f 100644 --- a/.github/dependabot.yml +++ b/.github/dependabot.yml @@ -7,7 +7,7 @@ updates: time: "20:00" open-pull-requests-limit: 10 -- package-ecosystem: 'github-actions' - directory: '/' +- package-ecosystem: github-actions + directory: "/" schedule: - interval: 'weekly' + interval: weekly From d5a0512568edbb12c7020e578d2b484ec48f8f3b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 2 Jul 2023 22:27:45 +0900 Subject: [PATCH 624/940] Update dependabot.yml --- .github/dependabot.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/dependabot.yml b/.github/dependabot.yml index c6fecb796f..6ffedf6f3b 100644 --- a/.github/dependabot.yml +++ b/.github/dependabot.yml @@ -8,6 +8,6 @@ updates: open-pull-requests-limit: 10 - package-ecosystem: github-actions - directory: "/" - schedule: - interval: weekly + directory: "/" + schedule: + interval: weekly From 64c7624760a450a7163723b37a3f2dd7da09a4e0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sun, 2 Jul 2023 23:12:22 +0900 Subject: [PATCH 625/940] Bump actions/checkout from 2 to 3 (#869) Bumps [actions/checkout](https://github.com/actions/checkout) from 2 to 3. - [Release notes](https://github.com/actions/checkout/releases) - [Changelog](https://github.com/actions/checkout/blob/main/CHANGELOG.md) - [Commits](https://github.com/actions/checkout/compare/v2...v3) --- updated-dependencies: - dependency-name: actions/checkout dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/Linux_CI.yml | 2 +- .github/workflows/MacOS_CI.yml | 2 +- .github/workflows/Windows_CI.yml | 2 +- .github/workflows/codeql.yml | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index a7b5aba5fe..a92d022e96 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -17,7 +17,7 @@ jobs: name: Python ${{ matrix.python-version }} CI steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - run: git fetch --prune --unshallow - name: Setup python diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index 6f0849a43d..f983cbbab3 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -19,7 +19,7 @@ jobs: python-version: [ '3.11' ] name: Python ${{ matrix.python-version }} CI steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - run: git fetch --prune --unshallow - name: Update bash diff --git a/.github/workflows/Windows_CI.yml b/.github/workflows/Windows_CI.yml index ed267045ca..5ca29fc632 100644 --- a/.github/workflows/Windows_CI.yml +++ b/.github/workflows/Windows_CI.yml @@ -19,7 +19,7 @@ jobs: python-version: [ '3.11' ] name: Python ${{ matrix.python-version }} CI steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - run: git fetch --prune --unshallow - name: Setup python diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml index 148260a835..ad173f14bf 100644 --- a/.github/workflows/codeql.yml +++ b/.github/workflows/codeql.yml @@ -16,7 +16,7 @@ jobs: steps: - name: Checkout repository - uses: actions/checkout@v2 + uses: actions/checkout@v3 with: # We must fetch at least the immediate parents so that if this is # a pull request then we can checkout the head. From 38639fd9c21999b1c45f0f2e3e0aa6e74d4c6ed8 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sun, 2 Jul 2023 23:12:44 +0900 Subject: [PATCH 626/940] Bump github/codeql-action from 1 to 2 (#870) Bumps [github/codeql-action](https://github.com/github/codeql-action) from 1 to 2. - [Release notes](https://github.com/github/codeql-action/releases) - [Changelog](https://github.com/github/codeql-action/blob/main/CHANGELOG.md) - [Commits](https://github.com/github/codeql-action/compare/v1...v2) --- updated-dependencies: - dependency-name: github/codeql-action dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/codeql.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml index ad173f14bf..d33545c90f 100644 --- a/.github/workflows/codeql.yml +++ b/.github/workflows/codeql.yml @@ -24,7 +24,7 @@ jobs: # Initializes the CodeQL tools for scanning. - name: Initialize CodeQL - uses: github/codeql-action/init@v1 + uses: github/codeql-action/init@v2 with: config-file: ./.github/codeql/codeql-config.yml # Override language selection by uncommenting this and choosing your languages @@ -34,7 +34,7 @@ jobs: # Autobuild attempts to build any compiled languages (C/C++, C#, or Java). # If this step fails, then you should remove it and run the build manually (see below) - name: Autobuild - uses: github/codeql-action/autobuild@v1 + uses: github/codeql-action/autobuild@v2 # ℹ️ Command-line programs to run using the OS shell. # 📚 https://git.io/JvXDl @@ -48,4 +48,4 @@ jobs: # make release - name: Perform CodeQL Analysis - uses: github/codeql-action/analyze@v1 + uses: github/codeql-action/analyze@v2 From 46d9809df367979c3d8bec8d44a63eb3e529fb23 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Sun, 2 Jul 2023 23:12:57 +0900 Subject: [PATCH 627/940] Bump actions/setup-python from 2 to 4 (#871) Bumps [actions/setup-python](https://github.com/actions/setup-python) from 2 to 4. - [Release notes](https://github.com/actions/setup-python/releases) - [Commits](https://github.com/actions/setup-python/compare/v2...v4) --- updated-dependencies: - dependency-name: actions/setup-python dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- .github/workflows/Linux_CI.yml | 2 +- .github/workflows/MacOS_CI.yml | 2 +- .github/workflows/Windows_CI.yml | 2 +- .github/workflows/gh-pages.yml | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index a92d022e96..a152972753 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -21,7 +21,7 @@ jobs: - run: git fetch --prune --unshallow - name: Setup python - uses: actions/setup-python@v2 + uses: actions/setup-python@v4 with: python-version: ${{ matrix.python-version }} - name: Install dependencies diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index f983cbbab3..c8bfbbcb7e 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -26,7 +26,7 @@ jobs: run: brew install bash - name: Setup python - uses: actions/setup-python@v2 + uses: actions/setup-python@v4 with: python-version: ${{ matrix.python-version }} diff --git a/.github/workflows/Windows_CI.yml b/.github/workflows/Windows_CI.yml index 5ca29fc632..13fdcea8a1 100644 --- a/.github/workflows/Windows_CI.yml +++ b/.github/workflows/Windows_CI.yml @@ -23,7 +23,7 @@ jobs: - run: git fetch --prune --unshallow - name: Setup python - uses: actions/setup-python@v2 + uses: actions/setup-python@v4 with: python-version: ${{ matrix.python-version }} diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index bf46598633..d5af3b87c6 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Setup python - uses: actions/setup-python@v3 + uses: actions/setup-python@v4 - name: Checkout uses: actions/checkout@master with: From 49dd1a93f37a47a7e5c91376947b49282cceb3da Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 4 Jul 2023 07:35:39 +0900 Subject: [PATCH 628/940] Bump ruff from 0.0.275 to 0.0.276 in /requirements (#872) Bumps [ruff](https://github.com/astral-sh/ruff) from 0.0.275 to 0.0.276. - [Release notes](https://github.com/astral-sh/ruff/releases) - [Changelog](https://github.com/astral-sh/ruff/blob/main/BREAKING_CHANGES.md) - [Commits](https://github.com/astral-sh/ruff/compare/v0.0.275...v0.0.276) --- updated-dependencies: - dependency-name: ruff dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 30ccc4765d..2fab6f69c8 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,4 +5,4 @@ cvxpy == 1.3.2 pytest == 7.4.0 # For unit test pytest-xdist == 3.3.1 # For unit test mypy == 1.4.1 # For unit test -ruff == 0.0.275 # For unit test +ruff == 0.0.276 # For unit test From 0fc769421f66a6403f750781dc46534d84e7c424 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 6 Jul 2023 23:12:43 +0900 Subject: [PATCH 629/940] Adding NDT mapping script and doc (#867) * Adding ndt mapping script and doc * Adding ndt mapping script and doc * Adding ndt mapping script and doc * Adding ndt mapping script and doc * Adding ndt mapping script and doc * Adding ndt mapping script and doc * Adding ndt mapping script and doc * Adding ndt mapping script and doc --- .../extended_kalman_filter.py | 28 +--- Mapping/grid_map_lib/grid_map_lib.py | 125 ++++++++++------ Mapping/ndt_map/ndt_map.py | 135 ++++++++++++++++++ .../grid_based_sweep_coverage_path_planner.py | 31 ++-- docs/modules/mapping/mapping_main.rst | 1 + .../mapping/ndt_map/grid_clustering.png | Bin 0 -> 33111 bytes docs/modules/mapping/ndt_map/ndt_map1.png | Bin 0 -> 23081 bytes docs/modules/mapping/ndt_map/ndt_map2.png | Bin 0 -> 21736 bytes docs/modules/mapping/ndt_map/ndt_map_main.rst | 53 +++++++ .../mapping/ndt_map/raw_observations.png | Bin 0 -> 18305 bytes tests/test_grid_map_lib.py | 11 ++ utils/plot.py | 71 ++++++++- 12 files changed, 372 insertions(+), 83 deletions(-) create mode 100644 Mapping/ndt_map/ndt_map.py create mode 100644 docs/modules/mapping/ndt_map/grid_clustering.png create mode 100644 docs/modules/mapping/ndt_map/ndt_map1.png create mode 100644 docs/modules/mapping/ndt_map/ndt_map2.png create mode 100644 docs/modules/mapping/ndt_map/ndt_map_main.rst create mode 100644 docs/modules/mapping/ndt_map/raw_observations.png diff --git a/Localization/extended_kalman_filter/extended_kalman_filter.py b/Localization/extended_kalman_filter/extended_kalman_filter.py index c2fe8e3a87..d9ece6c6f3 100644 --- a/Localization/extended_kalman_filter/extended_kalman_filter.py +++ b/Localization/extended_kalman_filter/extended_kalman_filter.py @@ -7,13 +7,14 @@ """ import sys import pathlib + sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) import math import matplotlib.pyplot as plt import numpy as np -from utils.angle import rot_mat_2d +from utils.plot import plot_covariance_ellipse # Covariance for EKF simulation Q = np.diag([ @@ -135,29 +136,6 @@ def ekf_estimation(xEst, PEst, z, u): return xEst, PEst -def plot_covariance_ellipse(xEst, PEst): # pragma: no cover - Pxy = PEst[0:2, 0:2] - eigval, eigvec = np.linalg.eig(Pxy) - - if eigval[0] >= eigval[1]: - bigind = 0 - smallind = 1 - else: - bigind = 1 - smallind = 0 - - t = np.arange(0, 2 * math.pi + 0.1, 0.1) - a = math.sqrt(eigval[bigind]) - b = math.sqrt(eigval[smallind]) - x = [a * math.cos(it) for it in t] - y = [b * math.sin(it) for it in t] - angle = math.atan2(eigvec[1, bigind], eigvec[0, bigind]) - fx = rot_mat_2d(angle) @ (np.array([x, y])) - px = np.array(fx[0, :] + xEst[0, 0]).flatten() - py = np.array(fx[1, :] + xEst[1, 0]).flatten() - plt.plot(px, py, "--r") - - def main(): print(__file__ + " start!!") @@ -202,7 +180,7 @@ def main(): hxDR[1, :].flatten(), "-k") plt.plot(hxEst[0, :].flatten(), hxEst[1, :].flatten(), "-r") - plot_covariance_ellipse(xEst, PEst) + plot_covariance_ellipse(xEst[0, 0], xEst[1, 0], PEst) plt.axis("equal") plt.grid(True) plt.pause(0.001) diff --git a/Mapping/grid_map_lib/grid_map_lib.py b/Mapping/grid_map_lib/grid_map_lib.py index 85dd76e71d..d08d8ec5ba 100644 --- a/Mapping/grid_map_lib/grid_map_lib.py +++ b/Mapping/grid_map_lib/grid_map_lib.py @@ -5,22 +5,42 @@ author: Atsushi Sakai """ - +from functools import total_ordering import matplotlib.pyplot as plt import numpy as np +@total_ordering +class FloatGrid: + + def __init__(self, init_val=0.0): + self.data = init_val + + def get_float_data(self): + return self.data + + def __eq__(self, other): + if not isinstance(other, FloatGrid): + return NotImplemented + return self.get_float_data() == other.get_float_data() + + def __lt__(self, other): + if not isinstance(other, FloatGrid): + return NotImplemented + return self.get_float_data() < other.get_float_data() + + class GridMap: """ GridMap class """ def __init__(self, width, height, resolution, - center_x, center_y, init_val=0.0): + center_x, center_y, init_val=FloatGrid(0.0)): """__init__ :param width: number of grid for width - :param height: number of grid for heigt + :param height: number of grid for height :param resolution: grid resolution [m] :param center_x: center x position [m] :param center_y: center y position [m] @@ -35,8 +55,9 @@ def __init__(self, width, height, resolution, self.left_lower_x = self.center_x - self.width / 2.0 * self.resolution self.left_lower_y = self.center_y - self.height / 2.0 * self.resolution - self.ndata = self.width * self.height - self.data = [init_val] * self.ndata + self.n_data = self.width * self.height + self.data = [init_val] * self.n_data + self.data_type = type(init_val) def get_value_from_xy_index(self, x_ind, y_ind): """get_value_from_xy_index @@ -49,7 +70,7 @@ def get_value_from_xy_index(self, x_ind, y_ind): grid_ind = self.calc_grid_index_from_xy_index(x_ind, y_ind) - if 0 <= grid_ind < self.ndata: + if 0 <= grid_ind < self.n_data: return self.data[grid_ind] else: return None @@ -101,7 +122,7 @@ def set_value_from_xy_index(self, x_ind, y_ind, val): grid_ind = int(y_ind * self.width + x_ind) - if 0 <= grid_ind < self.ndata: + if 0 <= grid_ind < self.n_data and isinstance(val, self.data_type): self.data[grid_ind] = val return True # OK else: @@ -138,6 +159,27 @@ def calc_grid_index_from_xy_index(self, x_ind, y_ind): grid_ind = int(y_ind * self.width + x_ind) return grid_ind + def calc_xy_index_from_grid_index(self, grid_ind): + y_ind, x_ind = divmod(grid_ind, self.width) + return x_ind, y_ind + + def calc_grid_index_from_xy_pos(self, x_pos, y_pos): + """get_xy_index_from_xy_pos + + :param x_pos: x position [m] + :param y_pos: y position [m] + """ + x_ind = self.calc_xy_index_from_position( + x_pos, self.left_lower_x, self.width) + y_ind = self.calc_xy_index_from_position( + y_pos, self.left_lower_y, self.height) + + return self.calc_grid_index_from_xy_index(x_ind, y_ind) + + def calc_grid_central_xy_position_from_grid_index(self, grid_ind): + x_ind, y_ind = self.calc_xy_index_from_grid_index(grid_ind) + return self.calc_grid_central_xy_position_from_xy_index(x_ind, y_ind) + def calc_grid_central_xy_position_from_xy_index(self, x_ind, y_ind): x_pos = self.calc_grid_central_xy_position_from_index( x_ind, self.left_lower_x) @@ -156,39 +198,40 @@ def calc_xy_index_from_position(self, pos, lower_pos, max_index): else: return None - def check_occupied_from_xy_index(self, xind, yind, occupied_val=1.0): + def check_occupied_from_xy_index(self, x_ind, y_ind, occupied_val): - val = self.get_value_from_xy_index(xind, yind) + val = self.get_value_from_xy_index(x_ind, y_ind) if val is None or val >= occupied_val: return True else: return False - def expand_grid(self): - xinds, yinds = [], [] + def expand_grid(self, occupied_val=FloatGrid(1.0)): + x_inds, y_inds, values = [], [], [] for ix in range(self.width): for iy in range(self.height): - if self.check_occupied_from_xy_index(ix, iy): - xinds.append(ix) - yinds.append(iy) - - for (ix, iy) in zip(xinds, yinds): - self.set_value_from_xy_index(ix + 1, iy, val=1.0) - self.set_value_from_xy_index(ix, iy + 1, val=1.0) - self.set_value_from_xy_index(ix + 1, iy + 1, val=1.0) - self.set_value_from_xy_index(ix - 1, iy, val=1.0) - self.set_value_from_xy_index(ix, iy - 1, val=1.0) - self.set_value_from_xy_index(ix - 1, iy - 1, val=1.0) + if self.check_occupied_from_xy_index(ix, iy, occupied_val): + x_inds.append(ix) + y_inds.append(iy) + values.append(self.get_value_from_xy_index(ix, iy)) + + for (ix, iy, value) in zip(x_inds, y_inds, values): + self.set_value_from_xy_index(ix + 1, iy, val=value) + self.set_value_from_xy_index(ix, iy + 1, val=value) + self.set_value_from_xy_index(ix + 1, iy + 1, val=value) + self.set_value_from_xy_index(ix - 1, iy, val=value) + self.set_value_from_xy_index(ix, iy - 1, val=value) + self.set_value_from_xy_index(ix - 1, iy - 1, val=value) @staticmethod def check_inside_polygon(iox, ioy, x, y): - npoint = len(x) - 1 + n_point = len(x) - 1 inside = False - for i1 in range(npoint): - i2 = (i1 + 1) % (npoint + 1) + for i1 in range(n_point): + i2 = (i1 + 1) % (n_point + 1) if x[i1] >= x[i2]: min_x, max_x = x[i2], x[i1] @@ -211,27 +254,26 @@ def print_grid_map_info(self): print("center_y:", self.center_y) print("left_lower_x:", self.left_lower_x) print("left_lower_y:", self.left_lower_y) - print("ndata:", self.ndata) + print("n_data:", self.n_data) def plot_grid_map(self, ax=None): - - grid_data = np.reshape(np.array(self.data), (self.height, self.width)) + float_data_array = np.array([d.get_float_data() for d in self.data]) + grid_data = np.reshape(float_data_array, (self.height, self.width)) if not ax: fig, ax = plt.subplots() heat_map = ax.pcolor(grid_data, cmap="Blues", vmin=0.0, vmax=1.0) plt.axis("equal") - # plt.show() return heat_map -def test_polygon_set(): +def polygon_set_demo(): ox = [0.0, 4.35, 20.0, 50.0, 100.0, 130.0, 40.0] oy = [0.0, -4.15, -20.0, 0.0, 30.0, 60.0, 80.0] grid_map = GridMap(600, 290, 0.7, 60.0, 30.5) - grid_map.set_value_from_polygon(ox, oy, 1.0, inside=False) + grid_map.set_value_from_polygon(ox, oy, FloatGrid(1.0), inside=False) grid_map.plot_grid_map() @@ -239,24 +281,27 @@ def test_polygon_set(): plt.grid(True) -def test_position_set(): +def position_set_demo(): grid_map = GridMap(100, 120, 0.5, 10.0, -0.5) - grid_map.set_value_from_xy_pos(10.1, -1.1, 1.0) - grid_map.set_value_from_xy_pos(10.1, -0.1, 1.0) - grid_map.set_value_from_xy_pos(10.1, 1.1, 1.0) - grid_map.set_value_from_xy_pos(11.1, 0.1, 1.0) - grid_map.set_value_from_xy_pos(10.1, 0.1, 1.0) - grid_map.set_value_from_xy_pos(9.1, 0.1, 1.0) + grid_map.set_value_from_xy_pos(10.1, -1.1, FloatGrid(1.0)) + grid_map.set_value_from_xy_pos(10.1, -0.1, FloatGrid(1.0)) + grid_map.set_value_from_xy_pos(10.1, 1.1, FloatGrid(1.0)) + grid_map.set_value_from_xy_pos(11.1, 0.1, FloatGrid(1.0)) + grid_map.set_value_from_xy_pos(10.1, 0.1, FloatGrid(1.0)) + grid_map.set_value_from_xy_pos(9.1, 0.1, FloatGrid(1.0)) grid_map.plot_grid_map() + plt.axis("equal") + plt.grid(True) + def main(): print("start!!") - test_position_set() - test_polygon_set() + position_set_demo() + polygon_set_demo() plt.show() diff --git a/Mapping/ndt_map/ndt_map.py b/Mapping/ndt_map/ndt_map.py new file mode 100644 index 0000000000..f4f3299662 --- /dev/null +++ b/Mapping/ndt_map/ndt_map.py @@ -0,0 +1,135 @@ +""" +Normal Distribution Transform (NDTGrid) mapping sample +""" +import matplotlib.pyplot as plt +import numpy as np +from collections import defaultdict + +from Mapping.grid_map_lib.grid_map_lib import GridMap +from utils.plot import plot_covariance_ellipse + + +class NDTMap: + """ + Normal Distribution Transform (NDT) map class + + :param ox: obstacle x position list + :param oy: obstacle y position list + :param resolution: grid resolution [m] + """ + + class NDTGrid: + """ + NDT grid + """ + + def __init__(self): + #: Number of points in the NDTGrid grid + self.n_points = 0 + #: Mean x position of points in the NDTGrid cell + self.mean_x = None + #: Mean y position of points in the NDTGrid cell + self.mean_y = None + #: Center x position of the NDT grid + self.center_grid_x = None + #: Center y position of the NDT grid + self.center_grid_y = None + #: Covariance matrix of the NDT grid + self.covariance = None + #: Eigen vectors of the NDT grid + self.eig_vec = None + #: Eigen values of the NDT grid + self.eig_values = None + + def __init__(self, ox, oy, resolution): + #: Minimum number of points in the NDT grid + self.min_n_points = 3 + #: Resolution of the NDT grid [m] + self.resolution = resolution + width = int((max(ox) - min(ox))/resolution) + 3 # rounding up + right and left margin + height = int((max(oy) - min(oy))/resolution) + 3 + center_x = np.mean(ox) + center_y = np.mean(oy) + self.ox = ox + self.oy = oy + #: NDT grid index map + self.grid_index_map = self._create_grid_index_map(ox, oy) + + #: NDT grid map. Each grid contains NDTGrid object + self._construct_grid_map(center_x, center_y, height, ox, oy, resolution, width) + + def _construct_grid_map(self, center_x, center_y, height, ox, oy, resolution, width): + self.grid_map = GridMap(width, height, resolution, center_x, center_y, self.NDTGrid()) + for grid_index, inds in self.grid_index_map.items(): + ndt = self.NDTGrid() + ndt.n_points = len(inds) + if ndt.n_points >= self.min_n_points: + ndt.mean_x = np.mean(ox[inds]) + ndt.mean_y = np.mean(oy[inds]) + ndt.center_grid_x, ndt.center_grid_y = \ + self.grid_map.calc_grid_central_xy_position_from_grid_index(grid_index) + ndt.covariance = np.cov(ox[inds], oy[inds]) + ndt.eig_values, ndt.eig_vec = np.linalg.eig(ndt.covariance) + self.grid_map.data[grid_index] = ndt + + def _create_grid_index_map(self, ox, oy): + grid_index_map = defaultdict(list) + for i in range(len(ox)): + grid_index = self.grid_map.calc_grid_index_from_xy_pos(ox[i], oy[i]) + grid_index_map[grid_index].append(i) + return grid_index_map + + +def create_dummy_observation_data(): + ox = [] + oy = [] + # left corridor + for y in range(-50, 50): + ox.append(-20.0) + oy.append(y) + # right corridor 1 + for y in range(-50, 0): + ox.append(20.0) + oy.append(y) + # right corridor 2 + for x in range(20, 50): + ox.append(x) + oy.append(0) + # right corridor 3 + for x in range(20, 50): + ox.append(x) + oy.append(x/2.0+10) + # right corridor 4 + for y in range(20, 50): + ox.append(20) + oy.append(y) + ox = np.array(ox) + oy = np.array(oy) + # Adding random noize + ox += np.random.rand(len(ox)) * 1.0 + oy += np.random.rand(len(ox)) * 1.0 + return ox, oy + + +def main(): + print(__file__ + " start!!") + + ox, oy = create_dummy_observation_data() + grid_resolution = 10.0 + ndt_map = NDTMap(ox, oy, grid_resolution) + + # plot raw observation + plt.plot(ox, oy, ".r") + + # plot grid clustering + [plt.plot(ox[inds], oy[inds], "x") for inds in ndt_map.grid_index_map.values()] + + # plot ndt grid map + [plot_covariance_ellipse(ndt.mean_x, ndt.mean_y, ndt.covariance, color="-k") for ndt in ndt_map.grid_map.data if ndt.n_points > 0] + + plt.axis("equal") + plt.show() + + +if __name__ == '__main__': + main() diff --git a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py index 31dc917566..ee192e9200 100644 --- a/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py +++ b/PathPlanning/GridBasedSweepCPP/grid_based_sweep_coverage_path_planner.py @@ -13,7 +13,7 @@ sys.path.append(str(pathlib.Path(__file__).parent.parent.parent)) from utils.angle import rot_mat_2d -from Mapping.grid_map_lib.grid_map_lib import GridMap +from Mapping.grid_map_lib.grid_map_lib import GridMap, FloatGrid do_animation = True @@ -41,8 +41,7 @@ def move_target_grid(self, c_x_index, c_y_index, grid_map): n_y_index = c_y_index # found safe grid - if not grid_map.check_occupied_from_xy_index(n_x_index, n_y_index, - occupied_val=0.5): + if not self.check_occupied(n_x_index, n_y_index, grid_map): return n_x_index, n_y_index else: # occupied next_c_x_index, next_c_y_index = self.find_safe_turning_grid( @@ -51,19 +50,20 @@ def move_target_grid(self, c_x_index, c_y_index, grid_map): # moving backward next_c_x_index = -self.moving_direction + c_x_index next_c_y_index = c_y_index - if grid_map.check_occupied_from_xy_index(next_c_x_index, - next_c_y_index): + if self.check_occupied(next_c_x_index, next_c_y_index, grid_map): # moved backward, but the grid is occupied by obstacle return None, None else: # keep moving until end - while not grid_map.check_occupied_from_xy_index( - next_c_x_index + self.moving_direction, - next_c_y_index, occupied_val=0.5): + while not self.check_occupied(next_c_x_index + self.moving_direction, next_c_y_index, grid_map): next_c_x_index += self.moving_direction self.swap_moving_direction() return next_c_x_index, next_c_y_index + @staticmethod + def check_occupied(c_x_index, c_y_index, grid_map): + return grid_map.check_occupied_from_xy_index(c_x_index, c_y_index, FloatGrid(0.5)) + def find_safe_turning_grid(self, c_x_index, c_y_index, grid_map): for (d_x_ind, d_y_ind) in self.turing_window: @@ -72,17 +72,14 @@ def find_safe_turning_grid(self, c_x_index, c_y_index, grid_map): next_y_ind = d_y_ind + c_y_index # found safe grid - if not grid_map.check_occupied_from_xy_index(next_x_ind, - next_y_ind, - occupied_val=0.5): + if not self.check_occupied(next_x_ind, next_y_ind, grid_map): return next_x_ind, next_y_ind return None, None def is_search_done(self, grid_map): for ix in self.x_indexes_goal_y: - if not grid_map.check_occupied_from_xy_index(ix, self.goal_y, - occupied_val=0.5): + if not self.check_occupied(ix, self.goal_y, grid_map): return False # all lower grid is occupied @@ -168,7 +165,7 @@ def search_free_grid_index_at_edge_y(grid_map, from_upper=False): for iy in x_range: for ix in y_range: - if not grid_map.check_occupied_from_xy_index(ix, iy): + if not SweepSearcher.check_occupied(ix, iy, grid_map): y_index = iy x_indexes.append(ix) if y_index: @@ -185,7 +182,7 @@ def setup_grid_map(ox, oy, resolution, sweep_direction, offset_grid=10): grid_map = GridMap(width, height, resolution, center_x, center_y) grid_map.print_grid_map_info() - grid_map.set_value_from_polygon(ox, oy, 1.0, inside=False) + grid_map.set_value_from_polygon(ox, oy, FloatGrid(1.0), inside=False) grid_map.expand_grid() x_inds_goal_y = [] @@ -203,7 +200,7 @@ def setup_grid_map(ox, oy, resolution, sweep_direction, offset_grid=10): def sweep_path_search(sweep_searcher, grid_map, grid_search_animation=False): # search start grid c_x_index, c_y_index = sweep_searcher.search_start_grid(grid_map) - if not grid_map.set_value_from_xy_index(c_x_index, c_y_index, 0.5): + if not grid_map.set_value_from_xy_index(c_x_index, c_y_index, FloatGrid(0.5)): print("Cannot find start grid") return [], [] @@ -235,7 +232,7 @@ def sweep_path_search(sweep_searcher, grid_map, grid_search_animation=False): px.append(x) py.append(y) - grid_map.set_value_from_xy_index(c_x_index, c_y_index, 0.5) + grid_map.set_value_from_xy_index(c_x_index, c_y_index, FloatGrid(0.5)) if grid_search_animation: grid_map.plot_grid_map(ax=ax) diff --git a/docs/modules/mapping/mapping_main.rst b/docs/modules/mapping/mapping_main.rst index 1c02c75cb2..a98acaaf50 100644 --- a/docs/modules/mapping/mapping_main.rst +++ b/docs/modules/mapping/mapping_main.rst @@ -7,6 +7,7 @@ Mapping :caption: Contents gaussian_grid_map/gaussian_grid_map + ndt_map/ndt_map ray_casting_grid_map/ray_casting_grid_map lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial point_cloud_sampling/point_cloud_sampling diff --git a/docs/modules/mapping/ndt_map/grid_clustering.png b/docs/modules/mapping/ndt_map/grid_clustering.png new file mode 100644 index 0000000000000000000000000000000000000000..c53590287af100b42c31afdb7610a825c4e3b589 GIT binary patch literal 33111 zcmeFZbyStn^FDfLl$LI!rIl_Zl}4nyL_}J;LAs+D{rTeK<92c% zJRH5CrT8l&wLCF+Un(8R$v^cqpSqB8v}srTYBcver!Smq40MX}l(DVw^VhViK2@oO zKKFrpCZ^n0ZuX1{mG*fbl`o6KFf{5dy=3V@`bSJ#{iwYYYKJXTm+f_0*JCY=fpQi} z@YVTJ*NKpd8hjnd!70Q3V1x&e0>8b8gb+qa5})eY!4I5-voP41U5adD>3#MR1>&;D$B z^^i8+Z$0Z}btxBW1_mQ2lpd{8gnE)LF13rBGl~ae@>XLpbJ@vrKj^AtDlV+iT9%dU z?d|_w*5ZO|zn&;9=~=fkg@lKOwyz)aJ)jWg2`lDQe|-BtAJns2-Pq9?Cc7d4x3}X! z5(B?*f>a=Qu$M&tFJDHhyM4aK+$x!I?cWAJ`%DI$D;=c3gFg}@iAAg1H=u8E2ef+L zzPUP6ovDesW_EgIbB(#cwoUPpmYO=3Hyw#(T-I4}AEmW%Q?T?8%X)E?{#r1`@6CVs?G-?KC2M zn+_t&@S&j@AGbp#B|)5M4;{Qps(FBD65wE*PX+|wjwxd$bTyu%a3Qkb;S0ZZJeQ`X zc~tDnkSevI+}LVw_WV5eg+{8m=Oy|*5kd4t?sLOv^?CJoL?Hc>;YXOTz#j4$3=V*XsnArV7*~ zdOEt(klFVVV{w|H)}e4UulIX;-n1O@IwdkvWBx2diB?Z(F=jaZLuq)iOQ?+wH==(J z4_;l(u^MmeYrH>01kVO}r<=I0XP;DX##qW?OKPZ{^EgddYMD3`9~!Ls0uoyJuC+2r zxLlA(n(=NbAi&>5s$$!Q zbN1|wGpeON9^O13*?yt-L^qREXCD`ea!!1)w;StTC?==-JMY7*z7nm9eccc88R06E zu$}H*)*BwEF`w1@HPcy8OzkxB(nHlmVtPD*47ua`M_Cqf0b1Bv#n4_$<}Bu;C~uH* zcy~O1csG48IkKb4C-VwZ<6ZJn*|lAIz-0ha?S(cZl5$xFm_5O4?tNA;U-CbP*_^Ks z?`bxR|7>K{k1gwc@yt>+kfXtd&sjf)%+0Gh(4V|#-kaz4^kMLrVimizlp38!cs#v7 zZ!^agiriW*KR$j~UZad-M+;n;r`ADC#)Xj&I%0*anfmJMSeH)iX${t^$2-cGN1nwIEUmx@O-65cfhLj-egEfgZ1j<1V2Zm7avMAMueHLLd{m@f_f z`y0|)+-FI=7u};g9B_%G&Q#b7n8-wWCm|PZ4palL-kvT+;1dpX%eWaz5oKW$-5$Rz znjuO@V4<#tZ7y0A!`bR!RS8GE3mRNa!?kP2sJ;zmT!IrJaM*&ugZDq3X+KQ7WV?T8@%0gCC`&LD0J|V>Qukk&V9p-B+p#iO4A)>*M9zMeMLH4 zAaOSKh7%+OanjUQu@cW!zz!%)aFp)Z;;ZeDOX#!_Ikq|YMD#OZAcO^5fnXm;woYsVasU0& zb)n(|v9ssdyN|bouu!9os`jy~UGhBqv3ste^R-nW>PznU4VuML12^oZqoTr6&CmB@ zkWoZSwJ$DqXtB4MnB4qWgB}~~p1;AUjTrUvA-|Y5QPcRhL2f`3ac zo_V`uyfj0a-1LFCV&p*b;n04Ib=h~`?CzE@wn9-&?fKNyo~_#X$2!XI7Iuy1d}=|{ z|9hc@iCWZ+pNW*6R>F~+qTdH9K6Lhf2WutbswHU^{Q?}r? z@mrz?Y)X=3vTz`DDULnc8rKj8m%YM!y5+Yrrr1kwqnT|{;1L(B(Ff2k5O-;@dtRXv z(y5Ig5&Cc;26;yagw3$_z~vQa2aVLUZh<5aQu$OfCw?KYE&Fli^;I#=0=H1~vD%nW z+c~%h3#6k9WBM_L(D7NYiEC3u-b|*P<3WP*RRuMA=&$Z*0&iv)A_7Fu97*zEDl)XeVw=G7LrHC%Q8 z)$r+RP(_(bSS4N1u|gz<72<)O`rENd^J7oVHYCEqiUxTcJF0V#XuF2f!>?TV=&iWqeim3z z_1|eMbpOC+3J82_BdLwQa{?!C7NtYuVsiT8;u1+0522}O_ftzA^<9E+T`a=8Pn>m+ z!g!qXN-3*!g10ISa(FmF@34Tk4O*g_98L=Id8@)XWauHbF6fwZIPaow30=~@zjf`r z3>Z=i)$?QaSZ?n55Tjo)jleE5OiN^MLEJE~JOJbdb!5yC@u24!}V zA(E3*0U0BYiUJN;(|}lidJO|lZc5LyXodLx z3Q@9uueaNQ!_8cOX!BGeU=mPVFKV0kVon(4Urg|Fdmd5~G8 zHCwG}(A5bC$I&rMzmMYWDB3Nv_aCse7z@%K~OMtVL?~jYDwP7nvE;4Wj{Q8 z)WOx&75FYSrlUGaYg!r^ThrM)w#K7&f@xmsg*Tp_o?&|kD403U(4`{1hU%t)I8NQx z@>*W{X9HAt54+UVt!5kyY@t3se~YAj^vD#+As|F3{j{&C{=q!9$)0XK2m=jCa$=H9 z45zF|OAztyWPrWGVuJoD8k&;ZVXH3!XeY37aVOT?YOELeY*+T&Ek9XW=KubUA$)Or z51E{vRy8nq9K!Po{CMM*e&LuIO3a~UUau+Wh=RXEVM9e`x zrRZjZ_}lH#vr&Z7JvK)C^s#$;bL?ouyZloRCd+{FLakloCx#|o?RV~6me6YD)Xbl7 zw$P=f1;=SU7K7$AOmYDalakw`4y@AwgNKuxJxY%wI29F@<(Xv%daY)Ux<$H~!=^~R zS&F4-xbvP~qJ=~yo2K}1Ur%CX@9?`%d5k57D}OMY5@!$79+qZ2|6)JvfA$$&i;7?G zskn_*n%TRYsBI9qj$j*Kdx(_L@^~PwHL{4sQ zP%#oboceF=E~xjT`;zyg=kD%qUO~a9F*KK>mDlyok2malg)u-E{kWYtE*0lCWUmFS8s}cn+TH6UhS|QdOm1TH0?N5V`WO( zoAQ-qFg80c*)|M(<^@J&?ydnp>Nj%vUAmv!%LR_7?5y>-!oMRAJopw771I1X69YJe(oy z-rL`QGdCR(9!~q}6|gW^S>*keYQ|>t zMY(kgmPe%BE%gozWas1{+KgmeT|gOl1xcMHB>uXBm%6rXNIdEv*%?}R6{QZwikjxc z4?Gi)TR~&P0n9}(E#SB->EYq=_omWfB1zbt$Ii~qMTp|VP>PhgIzhH{M0vI;zyFZp zL1djJZ;Kpdh#>ZNHfnfhs@9Y<`7K-dTZq6nixg9HbIymA*Cz?AG`xbTVwy)iziaY> zmqJ2#G#IHBoz+X=A2cZ3_g^+Y-a{RRxTiU+7x?O(p~Iv$jYiH|_JQ@x{VR77drxW? z4Yk05)csj^WPjLvv!!ffxp#Q@!`;>K28Dp6ovduw_B%P*-ov^0#>U1`eP7Uq54~(j zS1;C`U9$_qB-gC9eU3)RR+&r1&n&cd3twYo_(#(t?qzwGoq^>mY5ViU^S_z+!&MB_ z@CMo>qm9_KV7Y7kvK~4$F^jctBqej2_^UyEo4Ue-zIB6nB0<%xZMeFK{?b0Iq9nQxz1ee-C{-wh?l+m{E`ufqH!tO{qYy#7)TZxa6--Cn6VO?Rq1rkSV)1iQ__Z1DWk*^^3$L9PwEJlcc8uZAPk*Pf~fq(?Q zyIj1`$Nloq$~lC3O_>Cq;9nU+Og`}hGEMo|+r)kc=S(HmdeBXd%CS8wg@{R6T_;B&1UCd-HA1RvP?Pg1LcvVTum;UWP%@5D6OIR&IgR02>)Q8&YNZMFt zi^VlY=GXA|X_SDhBSPDTHZxm;7Fuw`lOE(3{FvG6(s@5=jFz;v)YP|Fi<2lP>es>= zI3V>LZi7bfa;>_EK*u9apUcmccX4KKww464y9g*xt?S9X>;)m$YBHdnlSuyc*2#(I z#iEih%H%lm>T*&E>ERFwf5L{uW}7=Q7HVM2NOebcRA9S-sxqD(38+1)gD<{{G+rtx zaRM_Arn{jy>@5r)J57uDVE*|s3tmSP|g{ymHFKp=)Z1l@eEB2&DA3~9r)1>jbWR^>M>>{mN4Lhch@snqr|NWsjs7E zYen!LDzUy-#J^WBe<&mRTc4&n{Tc^UBgkVKc!#$Hp@+aLex$WA=|EBF`%9IW? zgM6{D_#LuDU60OphWWpc*LqZbSTL%Hkrs)ueeF_{yGaUwJm@^mDl%U_XOC(;UO!ey z`X2H95djH`XH<(Wt-EXWa!}B15A$7pCLy{nw(iXFEanLc76cXJlAf}_=c?B5s=>+L zc6hm1Z)JXXNw_OZEI)v1O%lY-@Am)@kt@EE>?AAaEaTL( zK(0Wi5EHpWhoZsZ59diQv({GvG3t;D+fJbdoo(oeuiFIMGRAQv+WVf?X4xeX?n+$# z7R|M>g({%39nRGISNY$>isn)N$yiG$^o)(^P2uomAqk4)#!@Adb%5oN@&cdG{__O_ zRrFSxn&Fk^?F?FIK-je}ep+T_H`hZKbMNf1Eiu{R3PaQLsxGD#qw^P6(;7y#XAgYw ze$Jtc9@9O+a!scCTR&IGDFZYf(2E-){qt)Otf_oJK3Z}~H&inGBhliwpj-aX>^C;8 zhOLaHYtZ$ z=QI@Spt0BK@xnED6URJ%=ZAdUq$A zWJ?u^))gNDi@A}SvyqU{LuZD9$Fw*^MDXA_FKs?}N1f)Cu;#3~c-an9e%-n=vzmVr zxEF^e$kn2>F$psHTx&xU?;F6bJKq!5En0fN-+?&?kC=k`E$cyGRJe2}psJ?beP z9#D!JICarpu|;g}yKY8Lxa=0NXjaWUU~A{HDz0ly7?Nm!Dd_yl_>E{JL0s9nA@%3` zZ%-cYsdAQ4X@0>gC)ueo-UT=kDOij|#&wcgii~3rdG?uwU$|73N^FScKp3e{Sj$R# z^OV-pC|*tmNQp_1f0eSe9w|JU?lD>oUs^3kYC)+9OPaS{KMKIzS#A;CJSA+E!16Uy z!JP`RR#ExJ7x~-2c>UB@!>FF7mql0Hs9Qm^n4^@0=zi9zU7-7T?ECW^^l%2tT_rzn z-yVOnl<;P0iDv4@7cg|{2xI20iZ~g-i~{hDl)1Pu*PK_X>UheQ>1y=*+H$Lv36F49 z8hwjP27m3>yH5VXG=KkzE2JjF+&Sc+)e+k>_9J#HIMR zKYI({J?Q!h$hxDq*#{UUVSJT}cwV&5CN0E|hDnD=7|6wj$6r>XB<%fPi0@pj#Va+n zJ;;%W#@o5mc)UftFdJDGDf|(8mkFL%dn4VRSI1g}l| zq(AkofPWc1zo=kG^1*zp~; zo0l37=PitbwaI>~sw>LkAIpNx1hP@oHs-$r2t>9g>HvX?hdyj$hx3Z-ju=@nRaz}b z>b*MXZrI0-pgogxo+ua5ei)NngB<^=Uqe3m6I5c_r{IUwUij$I3uh)0@ z6_{N#BCnt5pydq zeCsc$@;EsT>YO4sfv)l9r#+JcIOWTiG?1ff0z)l&3k&C2-LlG>;+jmE&CHsW?VdKY z2nWc$iFdfUDSAfXaE4kd!^KVd%=)y@2zzKso?;uWJxPawxGQl8K7Q5_Z=Mb@&BKZ1 z)1`&iAH;=RgxXr2lM`{?z778<^j-$+i&ZYn3g9+v&7M~jqESCyl)cB;BWi4}dm5J`_rLcZ^1r%Day}M9a7=YZL`%>m);7egqL`+rw-?v!0dv5CD}|4OH8Ij zY@se;{r~V!Rt-2_Ssm?w%V~{S&7U(bsJTf_XO0bL{712Et#)mxV+F9INvv#qtCDk*3;fm*z0A>RR%vlcJ;4agy(o1x**+PU2&W~4@olDIn#V4$p zEj}sBcL{M#?s;!zt&d%wY?}Fu@u6@$z07FRbY8|-T^;ge|L%D!IhP8%?X?G5UXixk z{x6gFzhsVAmm7yVT7B@1RvP#*ZI+vP)L%Gp=psLC(oGVmsWi+-nV(Z0n=g`)!6Q?L z@vfNjxm=|2Z^LDd&i9P5zwowxadmIIfePVPQSn&v7W?Qc6KwRY_9G5J!H$MnTH6E2 z^zYvPW#l`*37L_Ap@A#|v=PjuBA$``&&jpPkWg%0H1VWrI&H5;?@ehfM8z16<@bk< z7u6;Yi|K#3m>e0KTp_e_1pl2{4c8uWGqy1RdE`j~KDsZW`*r_1uJ~$+$&iY`)MRDS zc4AVT zes^r^7%D{@r(%Y*T}tYGLVhS~voaJad?Z>x6re-Mme?S!f#*9u8F>3KZCwM0kg{H% zf^hlAcF9DU39ZOAZ3v|e_3E%z+=zkL><=jjS+gzm@$NZpSvsH$=2|r#>En0EL+*ZL z%u%d%elE!R_=zPx^+A-0Ss<|5yNqSX&Yna`p1-OqHD5v42o6;_HRiQx=EqOY8tVpj zZs>5{j*816(-71o+Tj%9h0(gkw3AvFmPF>-5Kf-~qy#Bo3nJ+-ebJ#)Tz+8~Uo#%! zen;onYY2@^TuUWE!61O${{D(+=|RH+E?D(^FKF{7=h|)pdDJqajq_CFs-`DRM4~m9 zua1Um1nW(bJ=(^W`1WudEdz@CEeqPf6cIM5#a&Ci5;#~v}2lS3j6H3|;KeM)CJr{b# z(kce13J z4!kD~4%TYDU_B^SW;dkrdRk0sqO*^p3F6+)U=d4!tgXcu3plOh*>3CchEW#A_f$8y z{BU1<_fq-7#cepYxkl8)RpXm)JFM;x(&67ZvXI}P4()^$@XJn?nZ)%lC{vIU&JD2d z{vv(heIH>sLZ$q$@b1~K1#!Qgi67fal8Of4fvrZrw97<8?UG1Hwc*I-(C606@?Vw3 znrXYx|3s|ueLF<;!<0tPpc&=yx@LuvGa_3s5+|>y+>BBT+bs=ob+b5_q*E}tE6{j+}uXiWQ?yM z&v*jA&qRgcq$#zHM%Ul~4M)0r ztZn#pHO|k1Jl-NF`L5`Saf(s>BFt#ss;NdA4C!e6 z;D}$`5id_E64r(9Z3gyYL()5H$A)~ZZvZzR%lY`!3?u6(XaIlzy5Zi*u*S>#x17^B>q93c_kNcYQVTl4kF0G}tg^pKAknY~)#AdO=az%HMrYIr8QOohHF(5Si#)>Ic<(VAg>uI^DY1l9E^-d%r1-Yh*uY5Bf z?)uWuyWkYZJW_{wgT%L8EI2#CCnPV$G%+>6VE;!I)It8gj27KIG`W=i)=;A}O=Q1u zFMbAnZ0IjO>6FfZV~Z562&rG%$vWEBx|iY5z3N$zHO>6XQv#2P@!0K6x#R)!y3HLZ zgEHkIHF##cw29;!Tf)`z4<@LU9E)unSA)8g8~S7Co4f07<^u#vL*Vp%Zgf{$DF3-O4kXJE_aSNYR>T`R&BYOH9$3X-g8@Zbpz#xQO!td8A4pqh6pBZ=ZL zD8ssc;=nNK<@NXK#kqhAjTRhkqZW0+)6M>o-!|2%Pd}rPS1H(Gwz9n0eV-0RV&}?$ zf9G^>GIKosP)UbVy9~21l(f-r}>4)mHUJ zCjzE}Va_t=BfM{m*#Bt;wniOK^AyMxVHO{{z1{s0wKKoYxNt!S91OYDp7@NV(8Svq z5fqib4GNa&%s*mIFnDElk$OeBTA3bk%K&}Dk}lJ(Tm{R(Wtnl9|j87rY|PW4+I;nJ(6miOT8 zSrz_*dT~Hwb7_5YQvWSI-OBmrcqFK+ZO8bnGn%3J3onupNhDTKriI%Nf}&o+6ccGP z>@F1p7e;^S>sy*ZouvEtQOHdK?6+s^u#2(Ti|jodtJIk)Q^-adBJO$MP% zpKLbTecQ1~ECUN0I=#g^lH9QTw>3bV0QO}~PrGYrt!=-aj>38tUe2pMLrS7Iox^v3 z|1%6rcFrFkzMEGVR_HUeJa+Snal@=ZZm;Ebq*Y49vmNt!KE%s&ez*BR;(@V(;g6Du zVnZ~6TjImJjAacqrh8{Yw9%;5eTL%Qy2hM=79a{iN6`0--_g<I!`uZc^Zoi&Ca&pbM`*O$R-#VBtRt)t0a&3IV4C&MKNUf>Byd&}f7xPeTMBwrjL?Dqm7Wy-=RVi{8Gc@T9XxLt$Rzz`21qn1-J-_z5h0xQ@>J(Kn4^$q>%dRFDNZ{!{TJE;D`#Yx zmBq@q?GTXe46svLz+q%I@w!*L>%8%Kqk(|P@&+vkr9(3foBXNw`6}D5q2qV9?FITy z2Tu>TFXQz^L1yl4`4_mLL5og6X49aktE-b|WTdiL-~%M<{-Of~#4|je!K#|syam(^ z5WEK?QJ`b__TJIQQuH2$2>DU)!>hhBwu{4JAFLVv)C2($=)<9T@NU z&6&)4w|DLA%J8bN$k?swG3VMdtcFEoli($gggt>F75#e6X~IpZycdqVTpV6gOfKhY zp_ZR|hlY?w#j%5)BoXwLkgr>qP7@cX3)FX#V`B^uZ{(N^>|Pg zH{+I5q8C3KPDT4WsE=dOP*IJ-!Ok89m|f{`qSq1<2%@*MBej2jgw0f2k){hc!mnhw zAFeJsFK<>&>(dAbq$G2i+n-NqoQ}y*&gwR$sR(6^2Cb`?AX5RRjmLVDfTKMVdD54j3Y$4k!9$oR0{+5I96 zAMeN8WgQ`}!@BLib5+cM<}?L-?0XH3(?QOWqqQ)0dmwaxl$!QE8|L38`}13;Cr>4N zpHXL+!_~D7iR#5-!@B1Voqa`x9WU3{4ECjF@(C_LQu(tkymRe8Liu`e*ucq*R!zBH zzsVu^Q`9+QH=x=6U2yOlowO>rqr!s1Lb%|tFa*Q(?g+pvJFEr}1|GtwN}z-Ma4=Vu zi|$iZRW38u&+}HGApLCV$pO6og8@8BRUpzW6* zE@~K>hS|N2(Y&q)3^KmlcM%%UGBNGWztC57H}E({;*O8MB3+hKc#hqQOZ@izXBJ_% zvnvhu=jQn>2aYPr$U&C=6Ti(%ynL(rmW`}-vDZ3Cf+Ot92B2&1eQ<1w0(;(gVQD;{ zK7FcP4J6GgF79?{=b~V+lf*IvQi@E^3oXXGsy_%=LahMTmx#Lef^oaLU&f>&-4Ujy zrz3nypNV{q`Zsgk1l6bB~)TAfUYP(=R`%=0hF@tr(){4$9nm$%l zASRYCO|ZPYc1KlnyD-PVgC!9&s-u#n*|}}D#USVZ!ZA}q%!kwZ3?6SZ03j|l{=~h^ z5xSIKUoTKlP!Jpv@WHDss7ImF=?0aHB;- zeZgnx4so!zcRB7Nblv-1^LP9w8VV*EgbIXaB)Q--a`K`72lhHa9Wvle3$!JP15$tj zs~ZuKv(qM#rt;Zz^0!!%lcT9BRs_-&$&E^fKgg{Nndpa^+(zwR38oWSwA$lds6t%! z%X)0Oilt~^BE**o+h+bjJ&kYi>007Ni6Y79Vs zef|%G5ELW@1sJrOv~Os*dvO%oZFq6CHSVXJQ9mBvDyle4W9&=d8~jhyH8Oz43W2L6 z0-_j2cNoPM=5^moDhfC}s#>D2-Cb1sOG7SzHwX3u68s#D6DKGpvM`k(FK_KrKEYJL z8kP%F0E+|LWv!zCslFl#>|x>(6A6Wo+2{ic3YcW+6*puE^@GbyQ0ho|*Q^#Oq$Odt zgB9?$z2nki+ziXEfy(PvyIbm$R{@~#=y@&Ce0LZra^4RjOuhhFQmDW>!cdmX-f>#98!<_!AL<*vMm!67aU=PGEHkWWe5uMpaEzEPh6C?Agw0Yx6CXiE_&ysHyGURA7ym zD?Re%rC@@Nq`Dnl2g$qRAgQkzlxq77C-rDk2wPupSwQcPkldNfh>GU} z-kpi{&kLKNkT)3E!Y{fGU%{N_Us34TH3eYRZgSGMlMC}#XT*dExeD3VmgWF&oUpy( z^8vlre?9N%`VhqT9=?ycxP0~iTX04^7T zA&_Fr`Y;oZ+c5r9Fap@@Ydd8ioG-EvC2N3Q1LUY=M#6F3i34^!gnt&c;XRH@4s0mr zB6^U=T`-E%dnEd@`_;RP;x57*ISj0y?Vny8Q~3Ugqtuk-MaVBFUP(Ng95!wQXR{Yz ziE+)gsDp;}4|JcQJXNYM@(L9D%nm7vqyTWmC$@hEIZJ(;6JNjN zMS){62C1d+4$o2&4rqIl>xD=XJahZ@BkWzhJK_?p03SSex4SCI4Duf2iVUxR(oXHC z#6^K-Zuok+`GVjDNFezCQb4+(KeHDp0;LZC*WbFGi33}7iEgQbb}2Os794MdL5RO^ zYD8QgK;(N&*vb%vbhJKpHfT1*9Cu2t+bqCK11&p<@qesH;6Q6j^V4p58sm|kFO0Ln zX0=CA$;h{DoQwi^H!Kr3)9myhmLg%gW!WBQjR28Imf5cik4kMr-&;-^&5dpTkur|J z#s*5@##VS*2Wxp5^UzBP$7T_l@(N^jgL`7dqp z)4`N5?*JFWGSU8csVAA~LSZXG9>Tutui~l+hO0eKhFN00f7Tu z%c5>EzYh=IM>YSv=Hu&Vt%Q#&@%;Mt>M3lh1cyH)&G@!m**8|Q$Y$Px zpPfVOk^6>*=-AnzaU(!%7M+?pKa3yJJ1YzGF2i_A`f?ZCMUsx?i_ocsCM&|bAB1LV zW3bHBVjM-_*E`)mG}N_e|I+KuMVC#3aU%jc5!C2?hrr20pdpVA8d`8-XP%rkGqJN{ zO>p%M4?jdfZ?Srv36C8$rIOAXFh0)&fl9AHp%W91x`u_-J%FD~&$ji0^ z4^6OujhhtpEJb=GH$=^ZH8Kcm7ks<6%(Ryvs;qBCyI6PVm~=b4umUd(S66^WIDYbF#5Ns0WDH{3F-h42cP3L>GeQ z54t&9yOs^KBFD;bwGgE34lgu`zEPlCU@l@9Zd)^Y+q~Kld6F>Ext*hH$)ssE^`s6=SM(=l{mb=9A3K)S+ z_Xc;#r|#_j>4L`>4Wa!>=YXu=oOw_yy?cp{mh|k--6T`@b&;70SJg{w>w>ITp1ASN z3OSwft1IrvU5j2rI8G{BRS7dmEXKytND}J~Z6%K@bTud9BdNWAiH1nk$~w1-&78J5 z{&+vJL^U5d7PufQG2uENJf-ygh-F#OY$`9mZP==FLTfTCXRgrw1_I=vSec(q4=0I% zLLD9z=`~KS{TGPGX1oSWz#2x#{$ZmxTIk_wUDxBd>+^DRda+)^oL)xSmj3-F!v5mL z3&_@@vubHmFiuC{>jRt<13l!{zn1t9Y5lguSBZ((sEB#HrBQGe`gfo@xL=pvomiV8 zYL2KMUk|6`4-eaIp|anUwP%q3_~0?oXs21yYa};_pl2S+Y!u4w3(VI0~KFzeo?0k$NqVw#eUoAtyYx?4v>(Vnwx$V0hoyA zXE*-Xv)krYXA_oqRg)bsL$WU1alA-`VC@fvfZ!NYo`tDQFYM`Y*P8rY-^I$@xO=?z ziy(JXj$ew#B#+4l-1Hnsi0;2*esp7B>ph6~C}7+@_hd5R!RO!=j=gIu5$q?8E!KE3~Y|prrTIZ$h8BKv~=A zl|Dc-6Cf*Z_er#0uney!&ybGf;6-}XMyZSx({C~0O5}E;7eW=JJxNGA!mh4Dv}_k0 z+gQJn5c`V#8#ZX==pF8D-9AO?FtmFqN611|Q-p4#q7pW8>e>Xxa7?$iVCucPh*fq_ z`k%Q;Q;Dg4W?Aa43vfTwR-B9Jz*7^FlbBgPCcq!Nt$KEi&qj(4T-= zE=&Eyx5P;XPf&{yE`SD*YcNCDnO9Lt?KiD>$LFMqp%zi10yFaM9-o&7ds%AaYSZ0L zf`NB>*W<&q2TV4~y^{>uFwNMP&%h)Yx;N=`1-)==kIkK(gTLs_-?s-uDjG79dU}74 z*LfcRy_De|Gi!vg-2Lbj%^7Io4%yq?ovF2>0qS+JzbONoYwc+4rT~QDQKvT#-J@_z z0s>1(ATxa@=zpP!=5l8b&~b8*z-#nkoXP>A?Rvi33o)7P4LAysvb4|?Z)T` z`Y)YTMTHjk2YHUaV?+-N){Rn93nzD{8xfRBAmmLEW+R%ug3g$om6cC2Edd$(sWa&9 z{sStZr2UFQFftmty!L4050sK>o960?et$=tpRdDVUCJ05OlM_*za)3N+5|-dh7909 zUNw5HzOy*l-r*tx$v2h%9nDjGdNQ5;=YGyJhR(eUbaw@2Y}Q`5lJo8Nbdbg0?GnZbI% zFR0hsY>eEiM%_0i9t(YJ$~;eEsOE2q&7pYUfBrWTlI zuDtvWp-We4g_`_cLd*>EFh#5-&thh3`q0;S=HzdQg!SxI$52bR-=1Cm#}^A^PwkdO z$$zcJK-{gvF_3uC5e5xW&;DDxMMg-{e9rc}odd83-AI(|g`Ka$N7qL!L0t+J9HqYd z$;uyo8Bj2~CoH%j4aQK!4gCM9_5CaM6E$=!lGDi9YSwj)a{A0t~|o4a;^)tO9t94C zj~-C^To00cxX=3mry?4C#mvR6=%d`x#PHSV+Uf6e{|7J)-Nn8K1RR zvtW;=rl!_-{zr$wb2#4(5*r))f}P!Yfiw?z_2xh#r^PsJdq>9sTaU=?#qq+R#g(8; z0Q~_2C5yRD4Wcyn@FS-}tje^mjYHOf3>4$)q@$@#pKaxD(5?7%s$v-2Rneu_AM%?t z3ST0CS>W7Om)f@@c1Mu*%#@kHX*RiWCz!nia~tX<`a=b3g}~_KDx6%$eCJ5LcXqM^xe1P@Sz*zp$8LiOLDyzV`3HLtGL-*iW%Y4or_dr~7;n3&X!ZKi*9G!;f4KwrfGtyKk zS*YRY+({o^LE&_OKF!v;iRs-mp~soWEAWYRk!Mt!BU2!bn{|xeyseAny@rcAd_hA~ z9urYjc9-ZH*C0Tm>&+4#rHex=6IfAGo$>f8%DAiR_@mm<_6ZoB=)3uX8zm1Wr^ZxF zrJUEsgw4VuBaLa{4uy65O^%y-c^8Y$r)_PZl81*@%YLGsC9sL9BQRt{OUow!5pY7~ zqo(!?4@Xxo(!_b{^UIfO4`KXaQ}WyL^*d<`_t3(k-| zeeWlz#fVPEr2N-StC(mVEkZNvQx-n2?@>te<=*C2Uvl^ujx1+U14NM6i4U{z(&$Hv zJEipcl81FoDwxu6fH4Mb@%6y+PmAG^%T-m0y?1_YSS`x3t(?21`Wt*=TDo%SR!V|+ z-UjM(9;7*dA)9V41>ihd^`F#ip9hch@SR$Pmaj9iQHX1H&~1ExG6=4>1c$hW6cn7l z*C?SGa_3!objIJGlhR&p{w#2&%2fEL+-BMM<~-fAU1QmPVykvWUN`Wy*_8IXcZa4m zC7cb3-raW7^I!gc8??J<|6LRF2TBos!wbrBMKyUQhenzwnu|#;?SaGD9tMVKrC2Nf z8J@wg-hOw$@a^SS_mUR8?C0TN6v~juK>w3O{ z8hm=MYkwg*{ETq6b_coj;}UxP@%ebHK5F{paY@e4MJbgr+|KSu+7}iAI=D+6@(T1r zp1k_dqOIvSvh8w5&?D`xoS*u3T)NGRyg z(KtXSu>Zc{F(Dh#*gb&9i+)rLpmBF7 z@L_XLxX2t!{Dd5NA07=<&D?dWj6D&LWCX3#%Mn)9_J znrR*XfolLY6J*JfJrIV{)6E89UFiZmZL5-m$RYjFxAK53%|{wqv1X>m&jZ) zh4SaioFd&~bo7a*m>($)+zV0oATnC}T%E;JMnuEhZ(g@v<_*X`sVm~FA9w0KgWt_3 zXtY4`4PGn}7wGRa5ZLa8s4G8gq-(fwg49)#z=@z*|0O;Rd%Bo2nt#(VZ(W|X-8;lN zay}D388%M@EhpfXiFQmfy=TXAT2cR_;9guh!|-U1>Nw->t{@0c0ylFk{igyRbK5g< z9d+Bm6$H01I|0N%u5`zs!mt^lvnM>fWgk&_j-)vRDK*j~mIlnZ0;AZ`d@>Yc=Fb6& z2f}*?WWO+>FaH$TBJH2@dj0q5&^2F96FEPii z4iS=AV_gxo)yi8mvHR(yTX%$nu;y`r_yglN4JlHQz>oIs!-a>*yj_j1q{Dj(oIFM2 z`+yW=_D5yr&=xQ3u(nk;Ui*qAdiXYV!kUOC3V3q;n%y^@weD3=9xUWow3Wo?1l|e- zB#5QsE8|t~v^DV~UE1pf zNvCI6a%>QHX7x1Zi!X7Q9a5g1hKEXu3_O+J}xG_EFTy+^nLK!;Y4f0 z;>aFZOK>|pFRD9U1LSOndUw4IWYbk6bmrb_7$% zB8v!vX_&L)&YA5c8Ysj4~yhdaR|m$}bA?*7(d9xaO5=efMKR+k@gc3Uk9-ucIL z;SGIYWbH4Josslk)NF_Xs200YULa8vXKjRa3m~bGa34#_R%dOm-FL-Ke=%i}rZ$*G zMTEU8AyxVix8-kk?OUh13;JhtAr+URVjX;?*k@FWLq;kSRkGxxyv0?wZEb#NPB_kL zeXjM>UZ-)6SLP@~cElWu1x-<0z_IWW-QR`kk_IAyhpJL9<#v*weOECOyQRi0ZOKWr zvLkE~GLrGkbZ;|#@8IZc4wP4P_9)y6J59rEi!4Hra}jaidlMc=Bx@Ul{`hcPN#~Tg zYQvhJnr!HgejJZ`ibOQJswL)9cNov8yy@@N&KPIwemRx2qe~!I?zM(gYJ~|QX;+Di z8A zG$~D3r1dnKg{1!2PCt}=J3yH1_tKQGHMl?8{ljlU_7HWs5akbtM=T-eex-7ylW8vm z&PUY=GoMj>A3p6$+h=(?9qs-Oxfbz=53lhorZvl0-|gQ1kbREY`zt~TH6y34%WhCp zZDNu}gF}Sp-l#7jul+iH15Q_(gh%tD93fq1^X}QB(bMGV>YD+=Chlu1Stb3# z09roi>{Sfgos-=1REL6YMy~3@$@L$)#HKQh%cqnZQxRxAd)1UZV<=~Ca;zg}E}8K@ zp=z3MSB^Was&~s>F^Xsd4|Zfhg99 zXu}FSH~;BeE#T8>jziZ(w_%B8_P@OFNn~g(f%R(t(tJbP?49t-z@g`sZ=ea7d82M= zrk5=J>)0U(^Phz&B33cRjm>v0p4O+#N4*!Gx*rxz*hw!;RbJpO1j5Pj-9J3I_ICg( zw2wNHdDrGz{wvBsJp8BAr}IMp8g`ZUo}2q$-Az2X!abS_%8(A|KwhXFKeinB3Xj6y? zsi*5F+=Xq_EKK-%nG~c{D)tAow^{DvqrjX-$^<$0aP}m-!6eW}LxoVlxgR!g9qB8p znEXsJ%XnL8vaCaT(3%mgvzn+pV{ImI%;n=je>~Cb*3$5ebqit0TV7JfBT_}X{(`as zc^VgKq~mdIB7Uz^rBlz%=UHRfg4$Yp zDCVwcrsnhhdXBUAU3Iz3sG-HK<+|rAfTE!pItooeGQMW{)iu+?&fPK2niJX$byU;a zp|U1uEps?4EjIdC;nXXhvDj&7@q~swRTfyI=si5sC*aqwYFps`XlY2vR(Fp~wVo*S zaZ_S$u`AT~?>1*Q&X0SFv*F8Vs|m-AqM>!tsCU%qz_bl1VWnh4QtVu(tF|Y|drDb| z10IILvNWBX8W<9VE!Y#WU4lo}$RI-;8WLEPJHAP9$sluc#r%5v#nj%K%F5NBTb(yJAUc2=``5}S z76O$WHQ0hYNBZ`W6+ILIazsA!sMK9F@^vI-lWFA6Sh+p5N`NJ2>9>2H@q04?@vtMj zI!IY0_3p&^H-(2y*&bZ`@LVmzu6C<({QeK+C4=Wlf|Lmn2N;YZqQu78OD)TDYz#w= z#29yHi;kN!3h9Lt!?)uRkR(2Nm12PIBiAQqG9n*3SZxi?O!%2QzwFD!FIBKcx=fCu z*Ic&f&i(UC@wPFNvb9Z+&q)P!v0+okk`M2?gY4Wevt>?QkRtzJDIQo3P>{Efv=R(_ z${H9wrrh`giT51q#aC9n6}TTCSF|9^xG}$R@$hv{{?bE8u92<>B^@1hV)V=EEYMSY8C}={T-xF1i2m5;?BLO$1IjqDHX-gF-Od{zR}sSyL#f>!rog( z5Xf)&ZG~?gJ56K!;D~=-eM@P+{UWRokqr|blfggdUI^lZ3avhk50PSs)}?Naz2d(eTYxtc2 z7l++1178X{nr4K+A;x&=TvDTA3PIu7!!MneoVoV;VvPQXSJ!$KQu@D@d_Ex}QL@ca ze>F15e}8WChbj_yEFW73T4Fu;`axWDWOTOGyfUdPl$hYd>)qTu!!Fx6eqMcNz0po#qC*5}WObGo zK$a4wh@=zBn1Ivwho8(-H46uyU3Gf3oF;wt@snrdtNXku7}W5dp4%Hl{yn_PLe!8Y zjL*bJzucMnaNFHt%Wg&FKhjUn1YWS`lZ4H#Q<0Gj64S5n8`(`OH($HZD%&OyzRco0V##;(obyJ)(3#bHdKi0@6-sCD8P15n& z-oLI7-<$;n>}B`XOpXFLglp9c9v2yKvr%(%b{)0Z=UY99D1Q@k3DyJ#Q;beKD{z9q zka5Nrg>7Pwr%RekiM{7m+O;gr_C9DeDxFzBY~{U0>E%nz%}2qEoL*20DB?h?(4^$yq6N6st=Us1wp>UDA<4`0jcfZP&*xH9Bua%pWoS81D`$k zqGh%ip=mc`Be!oj$A%f}K>Rh;)W{LXpBPoP2?T4_mOCtY9@m<90hEN{e`Tj$`0G|- zIra6AJltz7+&2!qX>X>hxaPhOELM)N&%Zr*YsT6Zj?dOGzWr{T zX+s_>D-DhrN*?!XIiKJR|2$#K%E&14-}g-R`*R~;yK0P}(Eg_gJPGfupEluPVHTb5 zui1}QC;F_L58e5kWD8uJzh-zuZ(`TYPIR9us%8l+E+2z3C+Z9tf#!x+TD`y~ zcbR2kBK?7SMx>iz)PY#(M# zyK80czE}2=+RF3z9=7j;RRTRTRAhlwo=aBPAfnV!xj^u_8s98q377}w@m%FCqPkG_ zfY)FGmB4L^9}lJud$>s8`Ub$~A=99|NnBCT6GVIV4O6Q z+Rzg#@j9E?*gl$DiVbx&YI2$I{6eVJ&mO)U1zW3p;5mb%Yi`X@n(gt97Pw>Ym6~l4 z>u<4WA8jL}^>}jdp+%g=ex$3WlvJccOM^w)yRfM=v-xjsuIhi`=6YS5i;aGi5?#D= z9Qd&aJ6AAD#e>sjT;BP?zQk?~fv~H=xgqmGZQFvGN^~M~^4-Q)pLnEWwiw+}+a&U8p0&0Ki)Ty1_4s^bN z#V`B^d+bV)MnqI%qK=MyFP;7i12Zi{g=3-s<8J>}zWoI}!A>(DO!q3rQl%(BQ33`8 zk+084lT*!s1%lq4VT=zEO^j2A;ZH&d>u;y|Tdz)|xv#ENuOpq5=4f`Cv0DFOH2zTR z4!;e5dBj~JB6pU~lqY{&L6p5?gTci%lZ5W1ahraeFekYP+4p?ZMO2$z{{6;G29SO0 z585%RSZ8SVhKD6(K<2x2-sKA=>f5Xk2LWFR>UdBy_I%VCYa1V{SDESKf#X)u>g>DU z#DvX-C)I57s2C9b@K4|mC!Z36=E8o$3r2D@icxTGsK2(pQ7kbb!!nV6=WyeqgDepc z9Og@%kivDRH7E2a_tHQrvv2eVvff`-+TSHrBzFsIrbV%3NXsU}F$hIZQQU+G&(|DM z2g2@>Qx*DC^)I?u?;r(lr5cUPMWh~zA5z{uAnKuHR@0oCXV+A$6Mc7;M%11MTsTnQ z6`LkmxCA$gS6&e=3Q5wFqanA1{Hle8otjO%FhNJDkr<)yx=$X+k+$y=DyU+WpR=m> z3>2LdUgFiUzq6|KBfMFuT*pXPvE!QQ*J}Qy9`Ud+zg8sce1E~|&fHYy-ElajCPsZB z^$7gfrlE@~>G?w5B)IQ&=cbWgq}jgMnsPMu?*j3W-x^cK2gQ4FNHHCJM9=fcU6Xfd zC1)i}K-NUl#JDxH9j))?A~RuWDYlR#_3U`p2Y09$C}o8>t!M>~(bxv}C`W|-B}pDa zL;m>ujh0x<7;Kn3Uk^1f0xYfest?xzdt-5wzKaNmG&grI)N!ZUWl9|j zglBN`bIr51)@lf(cKYDCWr19YPWVQJ8-2Lfh_dGG=1yT@L49Wfi8fa9@QTg6nR9U8 zM7~?nY~WgR)~&(q9=#x$thm)h$nFv3AnfdfnEpjht&A}>fX5~5E*#fT!|h`b&3f~f z%D|hd(Yj#1@>}2R#Ma4CNp-N6i-dLL-K>g~kkR3(>M2Gl_Kye}D6fp&O9Yo?f2ixz zkC3YGUrzMo8f!PVY1CHCUpV!xHG95?j6Y&8jI@5?_Z5cD$AE@q*x(saCed>3b^7Mh zLJ6`#)2^Wk`$4*Zy|_CdCz49rxP?qkC6%vTnEVZw{D8r zGfpGNrD&)eCD%^MBcCMOSuGWNKd62wKRxCftD$D|jiiy=A+XQR8h{4)bhSf z0}daWA%re}4eTDg%}rH*SS#+1VN(c3y!S+2we~l7~GxKBd6P&+?-Tr+b37ioRUS^b6X6I$i%Pl+f* zX>bp!_)at5Gm9rq$hg^;$63K}jy}ZJ3MlpJI4#7tMegtupoL+<2vCN+v)$4LZ{Jf< zG2U3BC6kyWE!b|=McYC&tseE!#tj+06P#9jP{29Wb<3z5czcMW>KB6759!TDo;Qv7 zd&Zyl9IB*!U^Z>{`T`{S|LE_xde8q|F{_l zohi4YFH&Vw=53ZVJ6G1B$llDJ&ykuI1V#X;G?nKc?vFfjUT7{1E0H_=1=<3>J+o^a zS~9#3c_tGp^|6aT`Ei@uyb?O{_qR13c`P@jeFw`v+i&y&lLpraTqGrLze5KUa(5O7 zDb{reWWdEvEhlB2Am7l z6agJSz63IeA9C-g+7M}n+_+AdGXi6@2e-zmbw{MHfj{t1(ii2C5CCvV=c1nQhG zO1(oYhyz&UBct~2uwR)-zCYwnD}d|B0JU$$DK8{v?R zq8U+ru+u*=3GT-q(^ZWZ2^c*#c*6T}oy%QHjaa1JMl9H%Y}w20>}UhqvT>uF3ej%! zS6`$7opgE}q`(!XudBRnb!Xp-Sh9F{)g$c}8m;_o$O!r}ao;-oSYA_ke^kj39Odi(Tx!436bOq;zpSSKQ)&BfXInp#P5(t*`M)uxSNkuoF zkHg2}>E7T;UaWt)mb`ZGnn_W#Wvqqsv&RX46B-6>AHW{yrj<@Gs~y(*Gddn&m2+9q z*O@h<@v@Rm$9?f{j$rS-E%2n56j0h+WMaV)Xib}$`mXf+%nb;UZ~0EsWOZ?# zL?3IwgX^K;1Q7F&wEf{)0AHm4}DwQO)ge55> zl%XGfWoHE$H-&`_$Rl|xy^~=ZE*PPXxt^3tH~G(@^1#Kw^5eD;G>0u;yz-<) zo-tU+Ko_^{fi!u3+Iy6+LV`d-#2c-5kf5qfPA3fMr-VtoLGl+mmP2mTW!MOrLuE1R z_n9aPev`9N!#Z3<=ae}& zdo6S1oqZXS$g9CFaZ(Hy`}8ftOA!3Om6u8cN1j4yK{gH=ZTU*c~m1A?P3nN z->W07>}l7#dwManm!Aw-Vbo`ZYU_S?lXzmjZbXlr<-Q;G2%nUn8=3axj0V4RW!)7? zn`Tc)>{y47l$0(1Q&Cb z@^$TFy*p$Y&2S7RjIRwUz{zKl_PR;&llq|kwc5{7J>uk+A4g!QM>o=<5SR=_S!jek zA*ni!H!&o^J^XqoS}|M}&%Jfgci+Lvj`L&WUsHP|^=nQ2I>|5Ud@(H(I9cXZQ>kY( z;h+Qp{1S=b^zVe83{PRB8z>(X)`?h7t(@Jz#wgc3y4NVCsfuly{-v{>KL4xQC2Zem zdv$P^c=QiXz_so`qRT0lbi2ZhI$VJJXq`yR@`*tivJwJ%Wye}5}p?!Ej< zTh?-MpvZl$^YO1=_h#DP*=fhP-v8#$s5eZLw4UG#)nfmLa*B9-fq!ZE5-jz5E7U4$ zzp}Ld-0zU#uTA6IoXFQ9O>(Ou(f12NvMR-Qn*`3l9o<;`x&C1x0Fx3S_&E#&<6@4( zM}i1MzMUMfXUqIo?B%Xxzty~;WUeCNH=%(9UG=G>HctLlRS^E&Uyr4*lYDsjX*vSoCP*a?ClqCq}(z#R(Ei4m@C4#B;fx6 z2(bm@8~q!bSC*95ZFM2cv_0i)z&u~`_*L&#Qj@n{_%T9;eSEksAYEoVUE&j9U-+}IvU?VE!QT5-fexA zk6y)+WGz~|2mONyURBbbO8f3*_2KDLh4&t}REK@dX4cvCKXKvIyjNtZT1%dS-FwYk zQzI3v&%>2gXAfr_J7ki<_|9RMRgRVUnzJx4spmhe;M)pwX|=fJzQ@JIfdl=T(8>*U z^{GL-g6Vf&qgV+`-za&Gz@er4e}1*_n|_Xc>r~4GfHHztcFKV832{Sbk@ee=TPD!Z z(#ou^W{GaN;MV`2wfbL5_q;0f4~cU=vT+F<=>ho72~S{lC||x@6f7Enhqp-0ei+5A zZg!k>6E|J$L%P0P^(^aTuTR=dDjb<2(jI=ds?J|xCd_t=fvvzQKeEI5F;SBfxXih z_k#3G%R1gc-VC3={833oJ~{l5S>xr9S`=gV^qDOb#mM7O( zD&r30PgbL3QeAx;a|f%p%5NEpT(kq`*24GkbfZ^q?Bm13mfF9;Y$?xf-z(nD6IXQt z39zdSeHA+&KeE-=;D3Lb=ARZZIeptPwLf+6)fS%bCw?tDWq={u}ESu z`O2WO^!qyM?P8Hd7k)th?ZAC7%)9r6Dz(J!*Nt_&$lXw#J!@Vr-^dbVa0v|iI*RSV zv?2b?x#LC7w44^(5l|_XouTnHo0|&E*<~jtiZlMo^d^169B4rhla2j%qi5F9Z$ko4 zaCx(sEEibLTVtCzCmF%l<-X;QbqE+I_3P^0nXyaeZ>}VBp8LDm*!Rs}qJqJqDSpN- z$IjB46{6Q6(Kstf?VUmLFP0ju=eUloN|Q7gC>ObuQ?D+311FrM@5I$yIlnIbRF4*P+Q;{>w72js+`lz z2Jy=6oh*(8?Cl%ntqR82ievO#viMV<(uNUY4;HCPpa5fJ|H**0-fY?kp%s`glQ~pZNO_+U(~b0vTaaJ0+Kv!Ddn!i+n9lz<1(df8YptWGD`FQM6YQJ7=L9BakvfLga^==XN-147^+7oT%5Q# zCG^a77e9NTy$D(c!T(m;4nto9mL6m?&ICwdn43K%)Rm@Rt!xV>>gS3)tvQ_g-L z9Yn)x5O*)c+7K2Yb`*0VJ|pk3QllpnrJQ4hna|(5bvYiRgvvhkWCh?n{GJR0#_z)< zlHop>Wy<_Wi0&)|HP>Bprj`#}q{_|P32TmDDFou)Q^QzQt+tb^-Vo>X?}K|HVjl-C zR48(_vGPg<8keiE8^z9)t}v;vgUq_LxXgvR&InaZ#c$bDYqJQzj4+oYZA)p<}0f@iOGi?jou~5tcHUf;!MPi zW8jFF3+czxiG*S?4^qd=@}>q7Fm`Vk##Xh-NhB|L-kb7d^3>-A-^HW{pVmy~h$;R= zm75SGi8HvemldecxbP!S#QX1of;ZYf5Zt44Iy;VlrUOIxx@yzSw&b1^Def(xvDrFl z&MJvN#S0UD@d{K7wHT|Nd3Ddk(RblAjcV7)LKu=}O1vJw!ZF6&`nl&UTnBO6K`ia< zsbA*Qj<*vi0*<%X>8@2$K#*Q>wnEKM;W&Ra89fs=b)u(ekjDg&Ok`?Q1%q3TFRd4(W2BsHqmw>x75^aKA6m9*g%@ibcVQ~3WMh)zTGlQZv z{dcF?sJ9NDzAI$>>I@DBU~CNP|X3ydIz2cER~4S8ax|B z8Vh69&yw;Y)7i_UFF;qdAuuu#+)oi*eAn_3zJz=BuFbeMxJq!Yq0*PSQ`kY$i;9JG zC>k81QNmPC1a(G+p)p?46?AP+uCFSQ%#yt!K#Kh%u6S^u?U5HAW5PGz6^G_Ca%}Yt zm6x-3eOwBwD=W7A8fU>^d*x*ct(oqrr0w$kCW{sGtzhhK5JD117<6xWhwPkpW2&{R8CAnsjbJDP&f#t`g@b1Z(5M0jCgqGnqwKx-YR)TlB@42~@S zOS4v0v89i#4N*IX0dM(i(VLr_Jv}|++xukH)a6wyLomQ6TL2k^bj$e2;Aqt0$A)j! z{NLj|u`yh#sOvB*wDJ^);de1tU4N1O`0>Lt!IGlE)%C!EtNY4N3|h|gvpZIpvZ~cq zAIcr5qPCVtB4C2(e|vRHLweOHmQ5w6z|1mQ(Ru4o*zfwclI7LLdmUXo#p!54M0_p7c&?BRX zvIPcHz*h(UNJIiw^*@fS&FF=pQ%qOgc|t4;f%-t-;s2+FJCao@9;QLPNJ?rOu5?@C z{bPLF#H0$_1|0VRHVMCuirl@%U#kGPA_P3{o%ultXJJFK$Cs?^yvZ9 zuJUEDh`QexM&mx;^%VNCt{~hl_TS&4-)4~uNCH!~$*HON;mXVXCT=I7)+))K+*<#? zN0}w{(Pw0240}&K2YY<5kyfo;f45R-*$~pX9&f$2o`O$elX=t${~bnlDR?dq+um&& zgR-Cwf6#$1*-6~R;P){C?Nc6V#!2-2Fi&*7T`F${h#&M8{s(K#sSCZmy?QWtD;GwM z8H34J;%1k+kRhv-X9+UfZ2#FI{Q*!kK4oeoTGilj`+dtJRe9y3k6M2Zmgaas+dpL4 zMa}q%&+c?W9&kDqe%hpzmN||*9Pu1-(9_U}^ne*vRqFeCrl3vldwE_xw?lTnZLr$s z(`L^A0pi0K_J@$v8!>fXAQ z2Y229DxWHa{&zj}q15bUy1Kf#ytgt97WxaypFMk)3-hMN221Vq=aR<`X2kW}-AgtT zFb7S8#nurXaD&EX1^rh&7hgY*L$3!ME|?p`c(^{qOssWw-LRl$>rF3=zOADC{)$wC`9mz6zz#$p<^4H)PNRs&LzO}Y~0?RirEXxIFvITJ5qZnC- z+S)j<)N{$G>f3=HtE6k=@BV_6QZQ7rgIQ3isJW7|3V8N;m+pS?TUyVwH3Aw%Ih)U~ zn9fr0bK-;5|7boVVKBYX(+&P@1h2;~!Vad-m5TcOxz}2p)Jva5c!Ho6{}T$G%B8X) zZ`|%IXxFdK@0Qy2i-5=x5CesN!P*@w7|*3;ZEfuvKe!B5dEpTe6f&N=#y!2gMJ`h+ z$V|9S(S+8frwnFa;W<0x<{sYB*C%{3N&)00sNHInhbTcW3d2`YN*zG2*^rT7HaKZV zJX_i{sg5SXAzh~8;nSLoRHlci#j=uDG=p?OS_uD=ZX+0s>`?>9Z8 z16+nM5MYhM``^#h0)66G`@@KCXfz(A7{oV$?(DU!|J8<2YPo3{Fh_fDT<$24FDfJJ zJYH9BmTu~~G}shGM6uJN9dPRN%!e`_AtCOQq)C4kWQJ<{&`nn~muvSO+vV_n#MEq* z$MNQ>{|uoU{Z#5;7O-nA<}la@WxijRo0eTfS{f(9mfG7~Xx?AJbg+62W1;?T>B>-l zJd;AGwNtx0uZ{k;*>BzfD+Nwgn}I^hVgKzBjbv#iXFX%YqKSw!;O?1_H6i>y$h2GF z&LrS41>t+($a%CKuDeX)rmZb+f{81c+`$Aj@{a8PGSMQDl$7)XS{AfnT0Il2BEY23 zwcpgM2nbuiRNE}H}g!YB86 zT^L*z(DkhLh`WPVS-^=MWI6n}hesS7Y%V|AcmQbDJpJ~&d51N0%!?O*M#xV0``^T%#Xv6Q_bB9l`rr>y0di3bgoDs)K3;4MM+%{(R zaC^*4!x#m-KiI89ro5@ttz9y--yF^Q04M1T=gFguIhxP2SOURTYAR|es;rcX^Bw`TmUsGxJtt=7eartEoKH%l6SFGLisM!=W?uPNPrGcVg zz!Oo`Wg`*#1VzQOl9(L<1a~R5nwKnoBJiG{YuZ5TG*k4l16%BxHlpRf{^Vb30)@Pf& zjd?wote6L$sGZ2E4lov+F4jK{JoY7B=nAbRa|FoA$#V+}g%|oUxYAO$SuMMt#nyVa zZ^v$e8N`$2-S18Tcbgg;4V-E=<2Qk+X`pZ7(qve<*#eqZEAW`)D>>1IjMY1T?wo)($_5o6cOmA4vzd4nN+yhg?wm@mSh<^>~9iUc6Kc?ck&m_|p_V zf>~>jBN!wmCia1;!lK~3@wUfGF#Oz;Wl4w{qIbVg@`;J{L7*wl|NQ$edc1+eTYpj1 z)jWYwpIKJB)p4xey?Y--;jJyqXQeoR+q|L_0e z@SY3uDEK4)0<+1%pp3eFj1(oz6^Q!Z`wPLz57y&rc3)2;A9F)lODSK$BIy4Bg7An7XP02@xF;1VJPZ6y+X45DpT8 zV3UOS;1!|n(OK|A)JI=SGasOt(rWTx0}Sf+G_H3aE?d?0uCiC4nfn78lc zy{WUUfz@ZxQrGsF*`4SvWuV2K3AXG*^){MdRa5-5;46UkGt=RJB_)Y{D;>%D)|tY+-7Df8#MjUQ~s=g~j#qQJ0Gy9UZ>gZ5+h3{HP_auu!%o zq7+4Zsndg*S@e$={Xn6eWl+LdS-Tt|ZgT2NV0(@AohnRy)kF} zvr)6_V#qK`ce~I~TX4o0a-3rAdX%|+Mg&dQ^g_7U@+e3t9i8p$a6+3VzY{QKzYA4V z0;VJ2mQJqGlHY)pIBv*TG-}?vs@$Ns&Yq8v+(hQ#yb9$$?`v3(NT13NiY+Zw?Y%$B zM%yT|UNP&Cdm=B9$KA*}O?2MT<2~C0F4(uV@J(IbgC8(B}$ zPD<-{BK#!@S9VAvCC2c0>u|xgF=HUOVYY;880IwdhMZVT{VGM28|du{XB}Ga*k2k- zTrDcFw!t>LH(Rm@CoJgUpFCP&{Ps3fQ4CKeiuk}+s>)*#lBqMK#s|F}`FLydD^7Aq zKj0n~^~lLP4Li5S(@cfVBxrURvm)bH`vN^QWR0m_S!Vba7TQ{O8Ir%%n_Y4l*|_8n z*ZCqz!{_ns;dF`Oi|2@S&`YsZR2AM|n?B9-+!#j+5z$UQhW6mQWlpirwW42WTfcLn zaHhZx<~oka==cO)Z_p9UN0(F1Kl?6==F86xFxF{0?3|YM)ghhle1-U})aueQd>8TC z5+%jg$n4%&f73^XR=mVXQG9tcqV3ZUms~BfPZ6D{ap>g~D;dnibH7MVF`y1MiTYWO z8bJ;>GAxjVDsHD^=XI&=4Vyyai_6q3ta+ay&Uc^D3XJlR47Ot-V;(~hk5#+-q$6(= z5T{f$`7>tz_mp&2iiqNYGoJErkJ^(mhdpmYe#Mlg5M*u2QlMO;5Y{43a}3*4v@AZv zZObAJ5bvCj_+7g)|K@RvfOzsi%R&hI-nh62TRA-?{W1Y3D{l%IK$gkdq>O}jS|#Nr zPyC=--b+_YOl4h!;|9T$DV$-zOv>`C!~vMKSv?d~NJ8%x-#G(j5#56WYrI4s$D}A{ zAOllplWiU@{nfZWW6^#~#cT6!#y2)z6H;24PHIfp2eZZDzQAE{Y#sxPycIQp_{zC3 zxRZedZd6_E&+pRJ@8!-qY)7uWzahpe*XWEj{Vl|vnT3{?-jKD4%HikVr%4|Jd~Lkc z{mf*8WaJw0urn?}>^m&S#Yba;QTZ~7C&6A5b!}_26sa@!{*6e#+(Bhz<6_A^#&q4l z9lc+XI@jKV&L)v<2@b8e*S{bwFDKQWmyz^vWMVjvF-P}Hbj^S~>uT(6j@(6NRJlT= zN4gX%E05PS(PW8r4?l4by+g%S-TtmF)NEVyQg0UJ;o;%yE4N?1dPTIrbweRt@x`}^ zV|?UW!xGmGqd5K1OVp0H`t#UMsM|4I~(nTb?0&Yo(fcbxqi zV`SEyDqn*hwzV6p`Vh`r)%scQCj~b{`mi93(_W(n(M)W)d@awElomCDM$2HFgS0{^ zC}OO7UiBea+!~ zJZZm9gvjT&rK|MnFN7dmlgR0qHUp>c zcnOI0O6xgptsEA*H|Zb97)0KV*CLAThKd>tRYc$61@$I-&_UihSIJWzmLEwtj+EK= z-VvI*O?-dQLVO@6@NkDQHzt&@Wa=(UrxfPqMjeKCqh{x~)C4ylABVVjd}?ZH$+p8- zm4=a#KWf0v&MvJ`pfXLoudff1`=XKBy%^}9qw=uEIKOt|B#T~x_H>WW<$)nAXZtV| zy#!~nWoD$gVcVYrONq38r-S)I#LuCcc4%w7)B8aNyaOB<$H=|4iTm)$`HuL?)1#Fe z+}ziMh4*&?CNIW`xpR3=`0Y#0DSfDh(Ct{KyUG>sNxK!aFMeSxJ4Qyc^O{S4XAX4f^wQxZF`KLpAZ;+)VSEne=#v zRP&YyFm;!;(t%sP2TrPzdrvsN-BkFdi2IQj4@Jf%#vpjlrbC+yUncNXl^9e-hwqR0 zmJ&NbRz5oYv{X(Gd4~?F5B+r8a(d^G_VzPk;J;rpNyh0GKNB_N5&iR`ftJUkc&&xK zD=wd@+;u?}s)~EIO)HR?9TBQX*NKbLHue*;mlhU|QDE|Z0lphQ5j_|oC%Ue-%${YO znc45VSCfc-jbn(cFq{u>%E@lV-dv{kK1?!Evb@0EE-;|P+AwR=gZAa$E1V-Vl@hco z%?Y3;nP0p+LGvM(DYUWP;q8Rw30;#S9?I)(p!psJO{{eCH%SDv2(dk5xQN8MF|0d( z%6jSQNKykAQPwF^Q&Y81F@ZXaoL)Lf3{g&wP$z#IpPWBZ|JSL1A`E$;Ox!CMu6kPS zA^Mov*+@jW_7mND6d7B3g1xqW_SZ?dMk?&>8I_#Oa5$nE{`=H;nn=*)#f9KO+qCAF z3-`8dOb{S0$qfWBfbZDP(n=P4cyq)s9@Xd#-S?`K3sWIC)JOc`L}ITFcO zzr)x;wnXl_^X#XwSKtQ=iyYnJmtGR5hth0+Ufuu}%goFqL_U1Ux|Mv-sND?|_4#DtrcZ5)zW*iL(=C&rxRrOELyUjg9f$iUTuMTA^28BBki+CpwSz zRuc2lL(Q?~deUn(b}%OUtvEmmRbmZBt11In3!0SmH<=r4%rgI`(8!8TIVGc-e z48V-IE%$~+T~pXzF+Pja*3M6l^HcM>NPW{OHI6lJ@>3~Np7aARI&@-8CtK>R7lT;u zXS%SSqM{t>+-@(12En0cF`gk$1|UC?R%JGvDSj2dqs>2vjV;W?SyGI#|0gTKINyhA zlMIu@leClGlN67XcE-l0ALfP*V7E(V&jSuvKLc`Qwa6@4tvo>T=0Fm`ExK^iBVW1I z(`U6ZhVVM#orPl4W3OlN>=#+Q!x<+l0^wI&PY-<&^UA9HD$9Z1C{H9K+Lc$Bc;0vW zf>g4@^Ds}WVL8?H9%gu~4VHR37Uk^J?k^KXhLk!^Fd^r4UgMjD8;%bw^l(lR^PH_1 zfAXLEa2(j%xFU&U#yNvCR6ir}ouPjc%kF7zxTS>KNY3B0F!S7dXEO5(DPl~1R1O5o zN?o-nELWftnV9D|mfUO+Tvh@U2M=>n{*W#nHPiFk#Xjy6OZ7XL3Q_)aE4co2FTbrQ z3iWgnCns8$;h^3t;c$Pf<)Y4tEBrliPP1<9yM)<<}TQvu2F=HWsYj=X#C@7 z_U{Ard6aJy@a{OUG25zl-KxHcd!T1<{Ucv`US0&ahBsTUMUqFhY++6e=)#@poo@CY zjcmX>VQTPr{o~av6bXtpIWh+fo?YFyNFE&Vec# zd5?%PHzopZTngj&*|j>|Nj`&|1U6T^5}0C)eo80%ee~WE;e*lZ9V-(|61@C=P=ER% z8aR|ANd|tI`f%1+D@rV+5y?$kxMF3qXV+W}I_vCx*tfv=row-#Tyk4>_}80}uJqx0$E!flsX#o>*i zFWG*qXLw-3K~$u&5~}jq({Ijpq<61K4o7i?DZRKye4F^$r!3nBSs|gW(;@9+^fQaC z@~xT5--1I##NjR8+dXQPWSlKkr6Xh_6twd@-Ij;jyD0;8wa=4V1MWt%gfZl(6Z%SV z=~IOSoFNu_6qNkEb@^L`pZ!+m9;S?Jm~JA~Z2dalxllV^Te)m&`~`Ex(y5T~6dM1r zEL;h#EKd}p@&h*xPj){EtC^~?$)2Mf+85qCnL@8irr(&1{rL0FIH~O91?3;~Kv2X5 zeOK4pot;S?*4jpG57OHVQmXn~*YRGT9N+AefX_5DZi~GtaR;4zq7{y)oj4?g64z3n zCZie^O}5f_+G8@-9P!kcDJ#W2AMJ0qOL*;%0W^u+03O6~b;0{9%4L!|nM}{G;>SkF zR0El;z5KA$9t=Q(=-PGL8~v}~VVcZ>mj*}5`UW!AI6hu&FuLBTWNTX?9ZPTfUXy*i_yt^PlbQm1hgmmgvz+w(&h^Qli1cd!nwU5+Q7&@=lWA zfKKP`#&me@M56PI$*$F#bt+L@?B%EV7%t<95EkX~T2$w-xyD;q{rReWJ)MNBrWc6! zK#UM1T5Q?VHAsjuF_GAW@wW?x)nj-oD=Uw8U*A4>pnIhwKYBG1>3*zptIxTGN)qQqw$cPq2!& zT(_5dN8HDKAkT0Vu~92=yxGt@;>R2U_cZlmslr3JN%Twj-*&7FE?%z{-ovT-$>B1H zz3EsPnkUT4;abM|hF`zBxu@Ts7DPPX)I*ftF1TW4CB&J=lbM@qG5_n+C?Lrg(s*4CFZFP~)$0nsi_VMVYNx;LcyY z@MC4h84@!kK{_E56_9x51LR%V$!*`DRc)R!U()OVFD6Gazx*V#Y zs`$>|`st3!lv?9;L9%m?dYqAnFGJaHZ-V@mz>s0XrdrHFIAOctQNa8qzsBWhJ}G6G zN!>P4r=h=S%kD;}d;JNIxW}5A%s`&RZBv{`z;M(fRs~*~2iMz8`j{{}g-oa&EN8pN zYd6YccffnZ@fIWq1$*fBF`q5!_%-4+zcJ7EGq^k`uOZ^1jq^!5IbeUiBWod{;rd0I zBBn+BU-+kUJlqDwoEU`T_nm`hraql}y$780sE2omYQ z_??ULy?48>?a1*N$K6LZ$p^j_opvSz-2|A|twi_)|p>YHS zb#+PN8#U49zs15A3RS7KarjJvYaRz$7T&Klej!v3E)W^Tz`aB}sNDq`o6Tf55a!Gg(93SxZ>4 zlUFVBIZaNfER4YvYscO?OEt(QkjX>0)>>~RwyfKGVs@u#wYxA3YDL2Gq?xc(mC%4e zL-N_NCG=cp%F!@}S9#bp_t`4E&hy8G{%5qW4#X5WgW>gn?m*z zyliO}N)9~^`9$Jcj!RdKOnHc6S1pS@a{KstgIj{E<0L%JPDZ^340{K6sHn}x#{Djt zw2&6TVg4dEm&?aJ=s)+UP3+4HekyLIkjGvp!5cMj9VLV7>;cx#pM(S?UanpEPLQi# z$8+%Ay+!u8N6mZTYfP+!I~VurNbQ9_v^IqkmDAYm&Mxy`u?@x#C`8$?bEXLEa$Yw; z5g~^>oUbuxFrLmST@FK?>~nZh-t8jD6Jd&ri_RMM|dwakY$OWb|Uce@ceOS zF(>?XgHzdQp$snAlTH|NuKv24bRdv1cn{3;%IT?{AZ^8?2Az=+5T zW1jB}DSa0jZi0zOoZP!c!TsXpz13eGb734wlb-b$#$?~^2irHs3hr)pXGsW?2K?oK%P@J#FLbHBn7-O6IF8h%(=asYvyX$@7SR|TT?a|G6aJ}F8K%}c_VdmT6 z&Qidz^{)n^fCU(Lfx{u%XI(V6k9+#B@q_vOqAlQB)>a5WOz}8@yUn?+vbR`C7zD!iMK=Ij(j5Un55SP@8Fz~4Z>dI;X|&;KCi4? zZ(G9h;e7C*?^TSFzFyDvD59=?{EJ`AiY=on{EK@0e+7ecv6be5e#kPicH-N*DEqx1 zvtjA--~ybt@`XZ@*YoE2XD{J=FlHR-d9QMQ}I?(Qxi&f+1IjRm*em6 zi4%FxMJUoB=YzNdPQ*55Dt(&;Aca^?->vBFd+_L?A z4Yj*u%!#b^Sjknc+BcFa+b3{e`caZ7e#Ij0nB;(cQ}|K)uRR=g5~g2`WKt=v5_$SH ztlO2?`(k&yop0lDKL8RJ24}>|hBt7W+OA^)ifVln{PW{A%C;MJP{zgfnCK<)O z*e_4FOgR;)T}2IDyYIA@so{$Wk!DlZv#E`6*m~7UgWcGlh4SmF)P|flY6$>9JK(;y zPEM+?9jLzu!)%-hV?$mP+ACoPxxYGnSEt-}1O5YTi{r+_J0CKEVbUJ=x&|0FwikgOyMJSj!6F}by(qH9(Zanw=B@YYp-ku^q{+$W4gq5S{omp@KM94O9WO}B?XS

  • IQi3HOU|8_T(h&fRRr*uCcCo_gW=aK?n1_e! zB(#!>KQhX|Ze5*gfS267xGW`k$K+b)*U^jW=Sx`)O)ntFT3NPd)z4x1w!Nj5$)iK! zW&kd78o+K;V*Zd_vA7I^-uB$`<-~X1nM^`G+!HWvJwLH!aI*|T+z+;2_-hCJ;sd-oR>29qG)&WaiBSWPr^e7Xv#0L8T;PQNmh2B~R|dEvWv|LEs7 zq_b{jB5qcHj*Tfgysncn0*gwyHLTGD$dS{^Sz4Ek3 z;PG6p|CY`ojgEv0_xI4{SVP>ePgY)SiMY1gIGq(=@zcVBbDB6Pco&p$|5Izew`TJY~W*SR?khKm4YC_$7_R5lxXM?);J* z9#Xa10 zQ~SD!CU_E*+C1Lv@H%mT>67JDOiUmgw9M`RwGau~J}N~wRXlNkD4n2*W@YwfT>)o| zbo?}$fx)=XboL7xR5%+vk|=9qYwwjwc;aU}pa-fLJ_$!|Y$G2j#n2zi<@GL1rGW2d z-3tzCwlHA~TD;XjRkdcH3~b6R|JoJyqx&XYjhupPyBLi=W5yJ_pdQlPVe7zrA^UTB z3$`wG+1=FH>mGBN7h@iWVkV1$`5vP2PCM&b=KFK9BQwbv*c@=k;2{kPb^kwGXl+HQLz_Xx1g0t@9 zN2OZh9t+jYUe|GQ#bv?e->SI&r;~YXw=Kbr1E78Q!KTQLE5F%{qq!xFCdj2C41zXQ zYcOk*nQF&J6F_X`P6P{#69-k=YIt}D64R_<_5pMTnodMTlH$VezIS)5!kB1OI+5G`xhf^;^T} z=H19;*t793?&}#w(OP|mzV(P0v+BRI-|~2?H=#kNI&F7YPV;=gzIF0@T3GEJE#pQ1 z`un6;W=v=0>_IZo^>>TD&PwYPxt?UGiJk=OqgAf{v;A(WP1}7L5q{>M(S{{i$>I4S z{nt$rR;|^|Qp;pGTInBe>}T~mj}7{z7G`I4E-dlo^EQPwP50fQi{+}B|92{YAD~N? zqm%IwXBl#t0NF z9F0P=y3<--@Fw|gXHAFy$-h*UQ6l+j(X2arla3ZJ~ryLa`&#pP%%G!>ps= zv+O~{5R=}hP5pn01?(`(&1C5rQ#9wVRj5Mk*R8hKOe=kATlGs&B3NWX9^9jKvp%Qr z%I{?!3e;z5C9x?P8(^K zPRtNL#>}fd7y89Z7{=*5J%GJf%&D5MGpWkaO-fiA@AdSS?lw|9e2O6RI%sZD%%__Hvp|0|nOeU0p-f7Sc@?C95X&NjnVM0~{q zu(`D~8YQyr<-q*^X%23i!PyW=qbR~l{^oKWEHjPXYEv9=f=FKiOL1^ z@2jimZy#-cErl6{hliYINUR$9zwA%`+DQ-yJIIvnongNgH6EEpWdeFhysVf8=KYjb z5+6)uyMY90<@3P^pOKAQh@4KYzWgAege86R_7h!@EfJ0BL6Ulk6TfnTxrn-MkZU^7 zuzu@1d439BqpwCRmDGE5vh6wDJO=%neuMa?w2@vNmskYK!C4#!94;LJb3uLC|_sup*m+-o+*j- zW{OS*^Z}s=jb}KI6Z6IPeA8wU%#?682|ZVS_0WgkDb8%xqCW#UAc#&TuUTa?uw2a- zrU4rxqCL1M{Vc(mf-ncHWIW%-nvKfHs{TsvU?Okbi=y5hpB-vPJ^bd2{~tMMZglUvv0 zB%c9@?Ai&l1!?MHlVKofswxrSl4Gw~a;_C>{bBMPhG+ zyoasPfLy1ok(Vvu8&sCF*6HS$Gh|O%0gxKe{Udoo@s8^I$5Q13py>U|W%%qGWc+Wc z0MNyDDF$I~Lzl{=mf#5`jH=ip_3QX+(4%TDD;7G>>jikbo)V>NZUqgPy40#&BMn zhM@GFS1Ul@t_2!j5&PW1<2FFPZK0tkv!3mAweK9YiacaQbOLj0#I z`JH=rYT&Chx+jw0{>Sb_msStQ^7|{bM~`AwAK<3c@!;@1!Ym3r2-+0((JwPKZ1!3s z6CD$nwpaI4O*lEF#ryO4B=p{ill+XI)|a|E_Vw}=xu3kF<#}>6;CgJn4NrqRR`{rd z%TPH^Xf#;_#KLZsMIE$ni^E;91QUbB`PGpu{WY=ch=N`hx?s(GYCDQ*q5Jg~g+es5 zK9kuX^#hzKsot|CBOl#}_BgN_p_zRyj!y_sfF}GLny+#|5=4p}GZaOEZ_vx>rLeU6lgRTqFk5{@xD2O_3Y&ng*ucC#UAVF5S`ox{&ZQ zhyQsG#Fk*Hs5;(Kp+-1e^um{}#%V;-dAKzPs;sh#*ZE#4xm~%@Y*@rhop0k@ySjJ% zb}zA0F93`FgQc``^Kp^bYgJR%);s@Rh8nDw?GUu*T4?~a+b!qMb~P$4`G#6}=Z1Jq zSqKZ=KB3JCd=j_9u$!irOt6fEFZwoibihI}u(m%VN+=ydu?#{cLSUu3 z=;sc=jxq(r#){e+Is7_eHkodV`6AeGI(EH#prI!vx!vSOa=vHspuhwH&;Po{)=)5V z`@EBSRnhHeZ{V|0>-Nq2E;8ELy(!o?7i&?A+9iL}wbY!cJE=<2)l z`$csJm=3O*63zw$D>(p($qwIptjY>3FS4HU$!k^-RwqQmTT`T!{ZD{zV_v0_1hMJ% zm8DTkJw}uB1@U0}UY9-BDUX}j%($=BCXZ3BnlJ%nSN?6+bULx!ltbeQa32U0;3w$s z&uAokGQJ6guE;j*$N0})np^KTMh+SHh<{y?dA|Ap5mQ?(Kx?@~_=OeRBJ4XXa0CpS zbX%HAP_;lcwj(g?U4V>#winhfKqR~V&doJIOa)s_Hk!Ia(MQ^W4c!Koju$;eLFG9qpE3g7x2ya_H2x%zqlv^%VM*uh}FWN%)74ec7;d(;?3cvs{XWr z_)D!9Jrg1JHErlyeE53NF2=lx_3`Mqs`w2>MxlWM;1Ww%<|-}e>@DGo!p5Sw8JeK2I|mm@Mgl)rrptGDfTYu|%SS zZuTRVm0jS+rgIvyQ@@Gfksd#7*NRykYn~&U_L)w$$f70k!U5^KM2_(5-sZ^g0A+U4{ilSzAZy6Uq)~JUxKW4WRotU9Qo9%omNku&b)7`c-)X9)%l+%#3M4O z1M2i(Xf|vOzajUx-35;&yTCO3LncMb6PJ#NGSdlg9Q7RAf~`}>FGH0VLr2X+gNBCR zVVr)5Jxm#*IfO-XTg+?A02v8hI;bO-j%%D@S{U<;In@heXuIYnH0=VQ93%Uz56$DH z$Jk9%?HD>gUUabf6ZH9^o3>xzO*2tLYB^8jmLk7xfH46HTal)w;&uSpsvYWC)V$Y?f>fqFG1#x*vE@%ZzaI%*wpZUTNP+OAIH%2M@^0x{w&#y9GBxq z_IiN+l?76MAV00kziA1tv09v+^*-c~Ozah?v@M9*180&fjW(&yi$0jggVnb?eKg&o zT7Y(YgRkLrf-~NDQ6@VEpTM{OI&rH%%quR&DiAnGJU#fInp7fpoEW!lSR zQeRa^d@(50k9FDx0_kZ92+e7eUaJ8i6LC4VYlaD_A78`!1sXRn$CAG#q-Oks^*Sng zo(UzL90G7KT=)0@FX+h!WEgkqcowi+hA&R{WYW zot@-g?husEhBw@TulN1lt{eS~Kh+%;=3Q!ZR>SKWM_^w^0d^IaIY-$2#2Hmni~uf- z@(O-=Jw7}Z)eo(7n&^9Uvv>*tVPl*o5o)n(;FCN<3BA){2Pf>$`g>B|<`4a1h5Vd9 zpXI3#)Wz;vPx8}d4GT>Mruqk)n97@do>(7frf4#Ad;|W8_ip!Bo?aS3)XPgO=o7zR z-zPcRqYRC>U zO>u|e$kh15^z^Sv9hPwA?nNGrkcWYc+{dtzMJ`y%4lCy21J6U!%0%?$nF4U@EHi0p zPYWVX7s$CQ_P%r{#*xb0Vd_0?WD=#7Qz>bLtTbfN+8M2P4n2szk_&X-QIlZ?8F)0v3B46pON$!d`tlv4@UX7^Xhn= z$>1$kn8qQrdT$^+%IN*a_}7cLk+1VI)>vsOxVoS$&;Dd&BAqh`5*SCoKQ{+M7PiA* zV_A(m~@cQ@Mga4YcCJ5yNgbH{G7Y0$M3ZxXWsh2 z>CxMIotAG8_;FTDeYZ(YZll+%Ikb8$CwX@Oho!++FI!lj$Jc{0A?4i@Lf2NH;hBPw znM{5j2HtY`jgA$&8F=iU2x#d}KM7gean{?*S4m&x;@qSgRo#8@VV>ZmE^%71sy}D6 z7|9Fc6kB!E$uup#z{F@h^{gVjyHX1h1pVo}G?C7nuzf1G|AN(G88)F~EL7!PEub@X z*r`}<#`hJ+LuE=kUD`{o4E6DxG{~KOql4$%dr-DL&_ce*KfAac?IC7czxp#g{K3sY z^=wz7*_PaI8;um*=mnB5Om69B8D~-!_iC&M)9vFuM?s*r`X~N<3jjaUW>_p}l50I{ zdrr^rzn_0tTt#KdpIGFtbIH#Z(HXWei4(JLL$qG6SRUtE7k_oN0X_}%URN?pq(79S zQhbwp^ST`n=-!xLf$MAt&G--!ohjvQlIdzf zChGe$L4NF%v8J5*z1+^f(e?waa1oRz9s={%758sz=mL&rp7W2|zWN^KXZr4Xuf+IK z<{J~)n1r$~j@ha|>bJENKA%3CkkAja{ReIoWkK3(>A-Ym!-tPI#1eV(-bGul$-=AC z(MhdzU&9xGPy(;~L6HFLHA%QUjm_4t8rsQ4nzJE_ZQ8Wr$s``u09 z$}uK7BKq{ULYc}0^@&#WcOQ@{hdm*NbC*B%L=0terUhCW*-z{}O5wwbif4saws z1sj-*H%d3Et2fUptEojwV1LG1Se({Uq^0vQ7#}6UnzHQg8kj)V9dL4W&ERzk3`Nn= zT+5W5_^@Cgj8qNr)aqavrt;T{nTYMrP83xlLD#P~K?_p%qk6p&kEC_p9@r9))EbG} zDgBh5#7>ua9(U?8#TS3r>8~n1qTxA3;JgqC_;`!Tn$YLXtfBKKp51S#{jQ{4OS#?c zF*uWf6;wmLD|{I%w4EJ(Bd%>&(W9g&{(}93CJJh%*UD_F3GVuzg2h=r3W*Qdx%?2= zuXEt>dWE|z3|6t&^wuZN(4s;J8o4FB2pG6dI@fBiPwki0|CyrE=d^=_cA*)B_Xe?4wn}y zx=TcP9Y)-=nv&--y7$oQZ7I|Coz^xx3p(|>Kf;27rj$iaNca{DN$lc;8nhqM-z zys~(Pgff-tU$>9*hSF5jOw3w2TLwp~!^JBKgoZ1=>Yo~|wzlI3 zlN>jr^+?#P#_c$3t(>*nS@-$j3dZhr>i-ARKrFwVnkKKhR2-^(%_I7>qO+~5OP244 z=7FsO!0GyGAG)i!>f8v%mHyDYdyCrZ26|C)@2ZV_Y?+3s`ECb$IeGVwj& z9$eyQbYoNlQ0l$wWMDNIy8jqFMTYvkhVU9_Yw<*U+n_1F&V^=>7kT0T8Z6@oKB+|s z!zs~Q*JRZZzLM+63lNy>+VZ8Q@FJsLK*P2i_6W2M4EQr2Y4dKPNz#KP<$Lzb)a0Ci&8GotPxr-> z_%EUpgG<7`eZZd&@-`A2c%B9T?q}7qc2$OBv^WQlMZ!)fOM6A=A{MUbc~Wp}&4S-O z2+^+(Drl9w;nzn`>}A-Xsw)PN*foLB*ymh-c7(PpO24LVwT=p+ACT8x{gk4L@=5|_ zj@7R@!m*-kz4Du2{Vy9EASO@tln<0W7BSY|sXo^gz1lHks*A`>UDA-QbxYSDFS${gpbh3r$B}*O^P=A$s7{m2ou}|Zws64Bi7gd=-)PWANu^;Lo*QKqf~UJHN^lakt@3Me8uu+dU|lXst7PO!W>R zIE*%(ss;3ndTcLK=P8lbWy<@*XMl=hf!@Ivmxa9|@C7`RX0rt@t!L6V_{+|&o33F4 z9rejqU{!PkG{+{G79>+PXtb0a>Tq67%F#J`8?;2voY@P?>QfvB83f~ymolDm$&hYi%?RhWHq`h4|&orvE*R35F5R5?TQzzaW zx-G+=D4b6R*Yks68us#lI?2!5#D)=NN^wyE)3jl*mYkBbRdq1WMxS*1b=1{b@?Fd+ zA9hf5no=f$D4Is+Y4YqOAF&0E>CHZS|F^#NLYGmk=%4obFs=G5dJR{An>@bPPlMEp ze*n9ZO`$gVSX_bBAw7KH8W?ra=DNp2pHHwQqxFyB`Sa(i zfA|mo;p+E(@AoQiT&!o}vZmysDZ8<6Ms8^fdl-lJ0nd*Fr7Yha%SOtL+YZ@`w(6sR(7R^@o|0meK7Ru9wX z{6${d_GGHlHJD@~TR;bpL9z$#S`=`Y{N%BrY%2b&9L`GLgO{eD2N)2EOJp(AxW|WC zTw(DDWt30Eex_Ah)uV{+2^dUlbuJ4(lJ=RYB37TFqZsow#}Pws`)R6dFrGNlHUX&N zfD`383CkRGohXiKb*X_5Mto5F+5Ik3)}XF^U+1Nx`$2tx7s999S?5%CeJShy>yol% z<}BqFvY-L}s%z?;&!U)}kx|Ex&y`eC-nmR&Me&NYr-SLNJ|z?)Cq=h~SpGNwnh{Ox zK+|E}pW5hJUuf~byF4)6(%w~kj{NBd@rz&nbK;t~JP3c|QY3{e19tj@>xidJX0o=!1^w zJ;*zJ4d^M&C%`mOM9%=41}?jD55)@rc62C01ZPy>bjli$z%K4+lHa4Yl`jH1*3-br zSG6|a@$r6Ik<9$h$MmRnP9Nuy2gZgzmJb^KbI!y%ccN)IM-Ef6cq(sXIGIsJw6cxM z%7+ibS32Khfy`RVOkkE=*PT4JkgfYjzVxLkyWLXyrppI!9V4W#)a9RafxZ-u_x6@> zYpDKWXhm`(JHVqF==0^s=fGcIQ>i%Zdz5Rbt`ml0&8KG5($+^2a!u(AzVB7jbg`-1 zL9a3&a0S^0 zTNLC5H5=zT^4E$7NH7q4RNj^@hE2e)7Y#%-qo;g>`n-P($OnnWeVeG?%Y5h{Y>-y> zS6R*bn{SS43UkN-ATKkm``d30Ya1B45AzOR0MEwH7J2;kw+FS|3-I&U9A?Nul~=F& zA%FR&@1tb*pY1oV`tjsr;QuV|=KZAJ`P*%y5%BpW)675l{?poy#B*|N)FvORe1G)m z)9?W$4URccfAY-_qt70P`~nQuqi~V8(8Km6<McwM?ohA33s(Ey}D8<_mK2 zfEf9;2&7_9VqymAkB+i`?D!Ko7t@z`CXjpru*BldQy^M*)C9iXqyt2mk;;07*naRPAxJo0(BrpvrbH$%<@)muSxUlYm3Ou#Izn z&;OzVdI4H|OqXo7NGmHK7dhpPhJd($vy|bb$F#e21Hz=_rJNm)1GGvsY15|KprG_l z{wFuuU(q%F5qZz@6;O*vx06oOuN@60qp~p_tB=sAhs|s#0?M4M>u-PB(&bUM!P$&? zX;;)b?*&I=H7_4bz_RLS#Z&@v^(w!qvY|`63fx9T`&QeN&KJwmyqMH_+Q{Ymp?ToS z05HFWdd74=n~DDH^B=DMp^JOKz4pHNuEq@m)y3U#BNF`F1F|bO zl!Nivpxw52{(SrkR!F2pA2k3eu`swDxj)VG@sX`h2KSB#^#D!tSO~%nzZ><_Az9P3 zlYR1l%6hIZWowF{X~KTqZ9v873XrPTdC{A6Jx7*apvQntm&*E{+I3b=%H_?eY>BK$ z9%3g<cIH2p zGJNOpev)~<(=(mfPKCWwj4tg8Z}bhYSHLO^?SE0x=uF+JtUe`7Z{*5{Q$_3o(D{pZ$t5&<$mU-v`w&^&Nu0O&75e=z;v zzxZpb|LVX0Z&&~I?#}9mKm6h9KmYs}tAFt?{?FAv{>T5r>YxAf|6}!c{?6YyGZOgX z#f#OS{n?+be*NoT*N?#u>bGBgwfYbL;XmXeuDjVo>ywY#UiYuF$gRh7K?_~Z18&-W zCwJv-8Xsz<0nRmHz_}{%%{KJR?J&SvVG8g8XBjp#2yQN517MAX83ffYZIIL)r`jXQN0J&q zi29A^{0cOrZcSldMSIH5)DMJIyH&mc24zb4-Dj(WF%!{OQ6cBaZw|kE6OfhFZB5#r z=zL>8y%|c3Pf`$Jpo;3eBc;Jm6qx>GtE#JwPKvwjl`ls(jg6j_tGk3!T0D`1g-S>1 zYG6MVMnMC3{aK(eoj?Zw_@wq4q_FE=AEwhPne2M>rdHxaExvky{!jnuKji{G z>-PBod+8EQj%(xNO9(C^*Wv+vabLh62fgbLg^N1Rb$V^UcpBskxX6H*8N4D{213sS z)|jk3nFij9>LgRNWDLYL*r&V~Y&4JQyShgOjSN2bwE+yIN8L$9o9`ZU)xV$3mJzn5 zWagwmL2R|}Ux6z+b5E_vTR=(8kVNKn?LF87{m{_B4}j`>XSdvU0|RXagEK+X)wCTA$tfsK5{YkUG7r6AI1-@X@>(|HemFeMrV+UQ;9}!`Z zDP=YmsGe^7+|s6mBlY(*eNQ`!Dw41EOveIykzqUiW13i>)%HBQc}_A4s}8`wczu;f zfjDi8r%LZm@wYCvsH>ur(aj!h);_NV9Q`jKBAr9EscmX~G}qL5BCcgam?B5JC^XE!(ef!_f73_W(TT)S|X=o@Lmt(F;KcTbDpLu>%G1; zZ71I}^GZ>-7>hs**+dL*z5yLQyb^?#pQ{khRZ3P-B%*lA3P6f)@h04YW zUL{?ofKHDYi6p4901G}3D$Polc)V{XX~Pei2kSB zBLKi(lIe>SxOG#MjaGWw3KlZBPfu+3C$^OgTgN4`#xI@m*}G^+M%>~uaI%GarV zYQNM%57`4-1Aw-Ev3hDZAkdFa`WL_W#p*Bq;xATz{jdM^{I%Pw)J{9wHZec@+0Ra7 zfAPf^^~|8Zco({y2Rzm@ZU&dr@Gzy^MBT6NlmEu}x2>q%UAZz0u*jfnur{a`*hrqC z&!GEu8hq<*5H*P6$)H|?cLvo$20&`kDF7yDHE>(d;hC>qS=^vWp=Y%`SBJ-Lzx0t& z_d#9*_wq#+fYgY;0ZvC*{80cej0SJ@n(A%2)R$Y2eLs(g7R!W1E?N?;ZW= zBRv)Q0{U)b9>hqcHLsn*VbuTT;f~HLag=3wE#-;7WdqbFRH@?~osW z?4F`RF?XXQBbRJ%995Qs(O6O!evYkv;FNB4n%)KQ*u;E;zkB2B{NYT0CYPhP?}Mh90hMQ;?5+0pcO%nLx`P9MbU#^r_W9FV z1?(NZ>xBoCPk#2hpRB(B>0W_?@E8P(sx`zZG z!HcRKiz3R#w1F?t=mUA60fk&yb)o&> z2R~T-vp@Qy)!+Wxe>*FJpI6>lKQKD_N7O&yckzt6mgCKOz(K8WVNf6UiZPXD+#8?@c#tn5f((8Gv{XdK z=$X8diGSoNFP+I0RT5zW0O=Hzsx64aV?YNO?dxZdr^8o8?V`8j64ir%xL!G6QuZY6 zHE&k)j^~`4C*aILpM3O0)GP&co;r5|qC7YF;@iAwDMdS3aQ8M*AJMhllsyeF)1)={ z&BKbf(}{up!_hY9GY=U1AM?y0nwbZ%M|heiDP=W_}6whi~Mvx z=Nb9)dW!kf*N~Mx>N=esJmaWbx;&K%*7?$Dq;uO4s=Lx*>~!}JN9Yq^T|%2(D}8;& z4(a?W+33`|WLuk$d}tt(%B2WuX> zDj$CmV|sFA;w_#?DKAhrUC1>}r;b)weDw}m;4!uqZ!lqR-BOBbYZUB&ADbTsU_GvM zx5Yp`03qO~+*?8(CldMe`EEU5rVjh;Rhzrvbxi^YV1bYN3#d-EIrk5!%l|cv^NOaW z06X7`?vXD*Gvlv57&_NlzMGg>zEi;a{361YW|b`lr2(`WtfU{~)L~2Y^W=ZNVNUnk zyJ|UEZB6G!NV~2|YOLRLE}wU)1Gr6*58%pH*I->=W&EbSV6aWE$MkYqR{y*I0N`$8 z^ZO4I ze;IW3we*^1*PJ9tDoRa(j{&--V}{29jo~rS8n{oB0lD>b8J2nfwp`n_mZhue9#e9y zzsh6S05h*E@))3yMu;qqtx=u@_#GZ5@)$%W@@Klx^MP#vK+>so8!3)q10c%>4yNpY zs|E-I{IzXl@(G(Zh@t|2fT3yHnij=UJ^@GGO=VBLveug#sKTuVn^jW&@{r+j(!h`{6vItSIY=OlX>PA@%4yQhB%XR~XehwXv+?eWT< z7#H~IR^u`jx&gKgO`VghQI6+Lp8KomxeWa^ zfG4m1<+$(Jy8yjmw>nC1DzRztT>GY;@DyJILuvAzo4k}71bmbYAl-l;NN6wxYI(k} z<83*a5&I`M%yK))_oh7C<})nxOkDX$nMhw?YLv}?BSXLXqizC34Wg@-xmu0*0MY#} zdp{t0X7SwC(+vDq)3*#igKEmW?8%q5g=hTnLc$*~e#iBwz@%c>-kXglb7Y*MUsme_ zJXO*E>{;ozFsXcpK7W8fRdNv^Jkr0JFh_zK8muFmj>>Y7bHU^3b# zuRjgG26us&Q$wY}Qv@dJ>vMV#?r2U&?dWXKWdTOZkgDm+$@aQ$mSz1_AaF9M{-BmU z@zS-omuJEfDLTwTl&0?v=GD^Z(7qDwrgz)5)jzgPdb^#iP2R|7+n9o#Dr@KFgl%X& zkVKy;(KXSZwvJZIuf9-mo%A^y6Ywlw0!6L^_Gr~nfU_-BoTFYmqaHo9A?0gOw8{Qx zsp_}*rvWVhmNrbz8P`GiyxJMCH`&i%zVGKjooOXKr+k_0p&QqSXzHr+t#tWr?!XTz zSjz962evi^eD6GSiyM^tMA7&`e{55kQ#SQj@UhKV>YqFSIO-RlZC@*+zpvcolYKSv zPuEfDJcr^jm>O6IjX_tI!L_3wT?$z6$-J(bo>UxOT1K^WnwH#vpp(~lgC_v0fr+}* zJ*NUuK{o0D=uSq#QrmhIo}>Vpihwn!Q%v@x-nZ+;9>CwLEKX3Vo>=@J;- zt&OEm@~a2$h)SxfLDa_naSbTDZIot}@7P>@m?P?IrrXx%m0e$0syr<}PDh#UMGbC& zVHdFLE|I-TSMhtlD#{oReLXr+Wcqbj!59b+G$GNLl2AO*H-q069qVBrO3^+hMpb(E0RL00-6280=8{SL5@ zIZoc&G|V(|FkKO__9}X80n-sasu)V5<(vaGp8NBfIMc=>Qds!~#JWvZ1n*^gRkqZs zUGs%>O+KOXdrx;(-+yX@{+7WD*zIL8$u2uk44UpaXOt{i_r(L}y;io}-pgED7nK2IJYP0Ije)H| zM=}f0rF>3+MJ+Oz5NEJVffzgh8$budS*1(o7&yN^JYN0!Q6UuHw+UuGXb zI@OC`jmFupzBybSWY0e!4vqX*iO9Xm^LnpR7d}+LhT2qKz;Cx#_dd;je1`|UFCfiN zpY7&3z*>hJc^aGllPn7Po$o!Zz4nF=@zeXWA3R_E?q^SP)&N)gGywns4r}p6G}S_o z@Bo|7vTe-XlgYPOk0lPzO_l>!>fOiOnG*Zi~67k~l! z4&!G$*Z!@uaL4Hsqw9)2iyE1932f4ztgnkNWCA{Z-;SAAB6;Ea~D)+Ti@8Kw~0| zS?OD#GOYFl+|9my7J(qRj0%A9lV^Js0c0a^)mx`TSJJ9b3%w$dri0OL%F2YK0gJAu z0U4Pm)4qSBJ!Hz-`f5NC6-D#_cl?E4{pw>+x~B4K55JTr=vWlI-StO@2v_%CmjNpU zn;CLNs1&O#i+V z%`>`BR0DW;kT#6LS(?(GCT_bEgf~y39Rx_@lP_+@|16bn0uYq z;x=r&hz`-h@*DIvk$wiS>k$V2j_=~yBEGDCNjH=g_wtAC3n$SJA_1 z^U~7E1Itf;xfE`b2Qns|i+}?_sG@(70E7^6Q;Pt{yQpAD*ar~7M=s-M5gU}LqXCpi z3!aH#;&1MJE1YN~+2*sG{p+4(n$-~*e0}Klkw)WO+5rEE{Zkp#MVE`?kT*ce!}C5IK#w}{%xfh(qJ99{@v&`NdhWBH>5I&~{;IqT=oDS0Q~eMd zo6X;*z^mBUxvnwOr+b+iM(c=9iapzBF42@PeFl1}Eb#COH!9dU07NOs7l1G#bIJzD zrbF3~;V0gys9=uH2Ds2R<*f8PB^}JKa&4LFR%h!3Mx3!pP1@4W5GubYxde#amf!S6 z?Y{^=@6`LBbF|=Q_>&Irvaa_R>It0@r}VYmfc>%JT$cK7p@->#1pwZIes{BT)4Qn~ z9`IK;lzZU2YKpH9P{z$_a*f9y;Jr%mdF{DM9ov$HF%0I{?UU2?0zd{bZ@?HdfP$gy zecf5GB?BX%fwyQa&;#T;J9WJ84;{Zd1O(cX57h(xN!Ci)GRG#-#431HS2tWcZAEM0l*v| z4ZzHFzST#-v)^Q2dc4sEfVez7I*(%2s)A1LQhlC%uXO^#IsWsRlT0 zrEh$WK*)%0nJ&X;8dAipqF4CBc#sFkew*j`zR1U_OMG;Qu>CqKeZS6!Q7@B69@tX; zBK${3o`K6?93AQ`+fC;teVPp95zAtaN2}*q)jNocmBj4*;rE}dKL6hS+HTkR;qjZ* zXL&=&k3Zcj`&v)8P5OsfN&HD7gxZ?_Yfxb7_j&S1q;Ay5P_H556LlkYNdpYpznAhl zPfNP287pcRer4*anSw+c8>BRkbVd6nomIgZUoCS+!8x+nbe&XfPjk+5f4L4j-sPK- z-+cpI_qFKSNiWuU-5VK|#8p7{b+l{IdGj7v0N~C0eCsvV&-vF}G z{c#<3UYAcVqgOP~IB}77*0^$+%C0EWUE6@hG^c@2Uad6Ez-$1N(crJ!rAqm>Y-w=P z&r5-WHeWstkg}g&O=(X1u93$}?>AYI`{>c@M6*hDKn(uZtC!g#X86IhFLY<%JvcaC zy$lHCQ2YKNz|g8)hS=@{vAyii>67fu_H_SAO&7COUkGxFl9B!NlYqHw1!F*09?9^& zN#4%td$x!P;-WQ0CCmP2nR?#OwDFtl0xiEmLcl=m*!Ldc0tu5$%8_Z}0%?8Pbwya) znXO(_-<_;;cCI6y$>E2yhz)ezWzshvi@FcrU3&q$$-j8#eL1do(ZZ=4->qmVx%VDe z0N}mv;@jImH__|3k6xGFt9a7=*q}YY!c}w)*#-gI)j4$E+M^4m2DcvA3Xmnwpl5LF zs75vue%o);a1MTnyLBX_`=J&}gkK~~pVT?MbwL7$ripEa98gm_0-B=3fLhPAg>Nrg zvH()Yc_Rnl<2gU8eQP@yN^>C=*qOF&DZ7&g56X9)_Es%Pr@s2gWJVuq)o|@Im=PNY zl)o;k_BPN`rpnRAQWE={f702S`#S|)R;S(UP9}}NoIK^U9)4suU};*{(fJ^N&lzda zKhwOZ`=pZh;;a02hgvfF$Tf1hU++*e7E`am1NDc%HRxSbE*`kE9(YIK;%e>5$T%A- zucm8~HrQ^4->azvN@{$#nwo2u=EKaAR=X<#RwuyE+uGYs-_?SUjCCHB!U?PZA%I&& zrBY^bMJ<#Fzk#vee$jl@i163u$SJG0dgN$vMA(ZTPl2suj8({<{{slw*wCjm^;h!P zP=oPQDBYm0GhXN2T(3=;=B_Mi4HwSn0($s!&c7`7+clr8Q9_U{AShX+p-Zl>`0Pwc;$YRe&^?<>) zK3lfJ7(2}bZcVd@&lF_Yn$Fv<2*9X?8G#xAi}esd3I93=@}xHl5BeMw0saOb0P_fc z6cqmy2?U15vusvTj%Zzj!PJ%d2k^mbm8*WB@Ac~#qdXBm=WJb5P5`3;8s!(To0tHy z0m^_#Q^l1RJ%cu>&MEo8Ir-X9x>Kujvhr9lZu0n*vA4h;UYWCVGO8?KXDWPrBH66% zcYJ7oN9l@;N`ypIfl>WXf}MS>-#1v*2itL*Y#GMtGX1{L;(_6TWeRwBVmWTr12tIO z!F!GS<6Qt%{EKeu{rtN6UweTt0L2H;075L#fNpAqWXjdA+$9JYJ@+}BV5|gjRdS+kRx;H0?d?E^pj5}-KLh21s|`-rL2G} zJt>-si-#Q+hlrG-vZcfu=ry3Mq5{apv#vL16kIbER!%b-hM&K(vMgWxx-A-@`=YjN ztNyd}6sVv2p{}#KLeAn`@*au@765pUd)jY(n>V%dx=Ovq31i9@@2MxM|5$B1VZ`j@ zrtKMlp=rFIS@Q9d*V+FAAZfpAYXCD)&lIga?tqhEj{-F{wVV6`D9O(ge_6Z{aF`3! z>&_7VqkuT?3a;Nvkd-G0Q$^{qIK+E`JuldGMt@3=vcF$N08^P~|Jt@*urcZ@C4@>a z$B@^$Sr}4Nvup;|Qdv#?ivGc}$uPBC;4*0|fuCm4#?wrBdvzL{0ZfqaX||VRqzXP0$>$UZg(e`E2vIv`t+XY0G(d^^NPN0O5HA7M^?Sfdv5G+pcX8=EiI= zyh$<$)w}91P^lX*x$_X-j9>Ma{&{82qxUL27qRCeZGD$bmmTchrEi=07w!LaWrK_l z7_lC>!e_N^_kACa1N=k-8+i1!r2HtWdk1oHe*6Xm3||~LdpV=Hbv2+n$|T%ob6Yp zm*N(P%j#c8gR=Mi+Uyxf+YL}`{j0oDWOwzW&!4Wo|EX2LZ5u;H_kNshV}6qDUfw?1 zDW8--^W|uZm}k+cJwk?6UrtOj?@a)Yy})S9Exz4=$$CCg1(P1hLHNTyfxZ9uc%7<=rH`%rPbsl@pYAc_Ut%2w!jlKnS4SxhTeUN(KYPO!v z%5_k4Y!d*B6XV8?WF;;7ckC~b{$D;;j_Np0YA)3^Kj0r7lR?6AA!h*QqdXT#nk@jE z=~VmwInQZl~&%{YINoLhB~VlLGcduKbunM`nopaRJcj+_QV{Bjv@H8pa0GV|w|d919kD zp9i?wb(1c*GF6|%<>$FK;$3L*!25sci+}F42QG6@G473N$WEyEvkUBHcNub#^Tn(~nzB^lwdPhNnzfUw`VF>LZ`}46gN@UwDAG5g~M}2qL9tP(=!p zUsJZ)5k&*&D)UDYP%C{DU|Y}o`RzpJIC=SBG=S_dkv$FeHWlOL*FiP?D=*4MKA8aq zM|$|No-2$npU^e$pP})hwt@Gk&m(7!8m+8_QHFeu8eY293rfKUOXWY$82 z919cyX;Yc@0$kb-#8}uM4Xil&yo>0nRloFx$vJXli)deir14x^>n$eXvx!DTaPZ3B z*q1g`!v^=sqbjFr*EVc4Tg;L2A(FNLifL{UJN+|tJAkT!vO}FIo43FGF_p8gqKna` zoqPzWmJf0c1hyaA=jG4v&`mX6Yr9l>P9m$X-$nlT)WrKtqrbP+#%=4{mR*aU+v$O2 z3ix*R%dN1g?#=JHLEj1^7bCvo0R!v%1_A@Nfpt6s_ZdkQ^Q&*uOizC#ZaADa@w(Nq=Rd6;bq5`t2Sx*Z;P-@sYdO8RO(@Va&`I)-0F<|4dv4+1Xin&SX~ z~S90dn8I32FGCs!1X$dPP|3L{(<8$0E9E0_^2LOB7h&&{oAYjJU7Z|ED&6HFO3`0hxp#BEAu45ZOyNm}=8IK6kg{pl4iW{KU zyq=r0-3v%2O^2JHyl;>4?%q&E(^B9l|3&f-4ze-Kq`ZDdVYLeQ#fzg_1hSvS8i1Q^ zTlSysbVQP}G+z7PCK8#a3bPXU(Q1ExXR0G1w;1{)bM_XF0B@gWmG7rn)oUsj2(((4 zjlkw-(ffl>c56y|w;YjG&Z%!N@?Ke2GSN|BuBv`p`O4@R1Vr012iRj93QOd8rGeex z@95q*YX^k2sOlLfQ{H_)a66j+emduJ-~2zkJ2W^S{W9{Fxur|C%XZFPikSxuxq_=Bz1q1?OZ_a!-~@MZM3|0mRw zLjG$l%{lL%A$uQ=+Rt6ux((t%U3uzq{Lc9{>RNOx9yqTD765o&Pu&B)^WM---=wzH z^y|{gzPe%OsEv1luJZidU2E%y`a_q!%O4}cH-M09=uH6Jclz1rnoNBB^C1F`Y6>^J z(nk87M8GTrVUN)o)S-4z>0M_8TqW}MEKxZilbw43b`^0<)X+xH^2XG0y`Q-98)ULy z#L(6&Z?d5@Fa|sVSnL4`OJ1`W5TK^&@<%e-%E$!m0dEtI3!}v zUD3jL=RM#zzR==~3c&0>oN zFaay?Q64n~fX1G8YrPRFP*nqUzQR~<{s=!n)R;%UBG54P`Qg+r&;D5P5OhR+_WY8>7w%{ zsQO^)`Zm#PpbAvVDUOFPMR&?>ijkopUCT>llK*fY) zDq>X;uZ~QCF{cSoYJhXP1ej?sr+fe>zO0B?$_&!GkMs78Ox2FOp+$raku94t%6i`K zRo*l*rhUop*rnNZ5u`SN67W>}|E0iNK9n1zP1{NUqd+8mbkqQzy1ZwYoq${I|ChYJ z<~qWsJ*cN)JBn9!=g<0e5JVyKD@OJjgV%078fC1*Bue-bD zO}drljg5#IXQ~qb18&}j8QxU}8vsc9t|D*IBAwaJHAouZ(a~z-0r)xs7BE)wY6yr7 z*n9eHXZ7{hM`h3REZ(Ro;1s{ASHz`03oY0ieZa}s2atx!C{5uH_yb`{fM^3~Ad!9pKfM-s&@mcSbyYnD^HN6ur}jGl$eYW{KD(j;2ED*{iY4$>k2Nn-Z9#{b2 zaw#kxSUhlNJOHE!NQtl^1G<6z|7Y*bqvgx0I?wZa^ZO0?%aNQ&NHQ4{Pz0etX2dSk zD%%Mt+P2%NN~)K-T>6LNTHUS7Mg>ckwY19WrDbWk)RHc=TWu5sQO43$kfO{Wl1!ON z&Y8dI&Hep+_uUcq#fx|^Uc88S5%1me`$gP)&)H}1efBwV&iCyz++HEa`y`3!R8eck zMCJtm2|Eeo0H}iByoB)F284i$l&QRcEj@E(DmQ^2@9td}6TEre1d<9=3bNbRQ^&|u zesl*EE-cLY84>UTY|Wq}z)P=(11M33d_^4qkpMlwm}kH;<-;^4HI84VAzHKz8)nG-4}9?T&H03)Aa1~-cyJTVy)+hL1gN^N*G7MM;8 zGyrfq>+M)*tufGH)KeNBTp1id0Zo`F3nbtHsQ{Spg4F|Y#H9DCp2k3*04@QV<0_D3 z04Ew&?QxvS1?~0?P==>0*1!S!F0u>w!iqr|Q@rFOoO|R_Id^`=AdP$+2_sGX42YVW zpKqfLwJ%;72LJ@@arDc&Hi4iQc*`u+{uY&XMn}pplT1JoAPtauM(YaCE-eJeBVKs{ zh^Itgcf{*yUdU8{C!i0T@+!A{`v)`*)eZJt)&>_xqiBnu zqMMRSdPt{4-A2vE0wcFT0{};E;^QqquXg1=2oE-ByMWH|G)}=GC zc^%+a-`m{TFiAxIu6r~=ev~5TqXRvbbLBHHmt5$e zyecrD44K@ErFB3*h`CyyDsO^V(g2OK0%z##c>RR|52kQAZ!iRhx07^(M_prGpQd63 zz(QA@PpHLn%33zX1AXAbKjQc>HNCMZ(5MWVju$ZX4qC}jWK4|;)`|86Uj*|E-sl0~ z=CkPyB0)0lZ)_XB*>Ov5L~1&HxSR=}nNt^gWzsG@Yovp^bdwT^&y%fL$+)3diO zptx%Ey3@LFTGM6;Udt9g6nO)oRetML@pn6s0suVAx2^%!98>8Yinld|7X8`K5ug#x zVGlfuKs*4fWoIQ&4n*1Rx|*Imx<{{dFNU)!72n`RdVs+8Gnt5o2Qsj+9{p@8ctW6n z9;u5X4&h5G9JxSUy6GIbk~IaIWD7JNz)7y1U3AON!UMoAbbBQoH2+@woAj{2Fb1t* z)fHno?Z=pB2o*GpvUOEMisI1=uaic7J)?UZQ4+u@!5mPJv=%lH_-oyhrVo60g<8B} zH#}M-kdL)+y#o0FRiD&yKO#@Ag$3 zK#=$VdkL!4oTUQ+NXBLmXd=HrliYT^z7EeHX9oiKNaL)%+^B(E%EjT(%hi!E3AC^S zn?Dwn51`63k~aA551f z_mo(GF_3|Dlz~Bk!C|ieT|b1K1L|IU2TjK|yA62V_@Y}sW$l)Cx43?7xEqhdOv~d) z0AJt|Knp2+ zKD>H>6x|xYc}kUsN?#vzEFrU+()5%tNvd$Xb$}*7AAxCKj!~%|4WJAX-8N`w&~c5x z9rkG1q@7fwAQwPOc`E}N{Fzrp#>IJ=1cslcqE|Kjtm#$&9UNxl^)r##pvTTYIehk? zxY%nb5}p&Zp@%)AVi`a;Y(_lb(|Us=Fa5w85!8FFGX$TA)9vg?CEd8LCU>)lYv7c%O z7$rCwg4qwu0x$z&!aEh7x(fIxj&_`0K!A-sVHGWDWKAH$J?Q|PIe|pll|hp<^t7ll z01i9Dp1&1kF{r|5RetMC#wxS!T!!=`;_ZVbJ%DU5;Xd2YQslpFx(Kp4My65s>?lkeyS z&_rsr)-4_lY5+EP!2ozUO$xBF2T*hiS|GQqwQ~f{`Rg`NL$Ck6gVJ)%9C{^~B7^fO z9bg6MLyt`iES&+Syb6wMi`I9MF98_kGhnOA$vwYca*-xKp34S3n^TYhkoCGh(b%J> zXM^902fn@fx9)4oYi1BYMFKZDSsSgt;^+}L3$YV4i5%32K;f^FxIw38FK0pz(W;o z30T>4$Agq(cW;0sfLlz5+6(Bq2P}p64G;*ORtXxk0i2fRc6No(Y%3=Q*w%Iwfi1+3 zU^OIn+dnEEvZ{@<2_)0gE0}rBgfHZ9@ip@E%x?wo#yqXIxVRo5!3NkSZG|4_?y`#+ zWguGsOKb;41lvh@y^c~u09JT1HQa=QSzuVdyVQbR@buw)_6qx<-HTU~esnF+{K}7R z-F7Y6wgIgx#rPuW$j0G4U_b->A@8utkKA#TwO8%+F=q72+KPwAIKdxaWK{w=q6K(m zfFna1+$e@Mf38~r7u#1A44@%0ym7HgpP(GC*I3-Ds1hxi%Kq z`Dbrqlg0x3umHe{KB-s7v==J|uYLoa9Ag@PS??zxVw}LGmu~whYbOspZ`k-CJUV#} z@;pxY>FERT`KTAo*y5Q27)F~5z=BTD5E4l7%yEnu-86x#Wt90rJDoE}5dD-Ws= z2cJ;^K-w^J2JI`NM2G)vTrG3%w;wvF=C$UsgO%-Ci`|X3M%LUOa|<*8aLOA%3{vCo zjM8lT#A2Cku&V|S{U0bydxvQK2QBzBaT*a9!^LcAP*Lo<735&JFaz z(Sfa$SDBTMf9P68+Y<+1#M`zYa0fV~9C!#RA3K)K$Dl6WNvn{>ksHKtpkG3mj&LgzRz2r{6uUogC$!&~azi2JE&mpyGfM*6s1JXUg>tv+%3| z3JIR-)UDpmW+MTB09%9vfqu|eWIqLy$^D(jV z)_(xH_dn6VXWqxVNDqNIK%UpuS!`$${439+;^7tC1MGU&GV;)|`cPiHf3QiAjIIQL zqS@=7iD0C32J2O!J$qAOtbi{1KeCYe??-@&8o+)(nYz$gc9-~mqB?cJM5DA*KRPuu zjRl5bfd&8$!-|KRy9M2ooZXWW@vYR*x1R&GPnvTLl?lR&>;Sag;vIR=5+ zmCP&ZyzVd*vDc4TTV|SB6WId8C{+cDVLs$>AZB~O!-(gP(&3Rz(CIg$C>DJuB~TWZ z=MWV_{sft1U`sT8>A?s1T{ak0#ljvK5M2%abWpj z)TV(iS>MJs&O%)KlPuam$FQ-r6Bt=+w%`zDJdC;SFZmfLNe=q8LX}7i`7d5tH`rWU zoU=aj+Wk8t064$CT5kFHUzZpD*Eg5PfBvIoW^F|vPdk5=URExZvmg80^5{SOkLB|J z`pz<|XHOw()J6~FGQG_jK(0K;lrWRMdag!yiVQ$aAllNg53E9WFI_Tkp=g&v5NXX3mVp%(T zMY;B~UoNL_e@j^x<1gI&RKKR~rcZpbJpL1JFAJ-e%EcRQDvQgfw2@>%;BKodF3kHw z(fxWi8niry><;!?LzQ>N#YJy6mS7D)qb}V-mB7WDY-*NDtUmw%KmbWZK~(mlEaM7@ z+Uxg8J#?w=o+|E_z9*vzO2AG%>vDqhY*d*Z3ycH+Mjy1j*BNJrGCk%Wj;7gxR!5Ev zhiM;N>H}sUEkkZ1Z4b_FvM2E37Fso)B))O#Ju zRPT52bQ$nfwA2ZnI!`H!UwY4o?*=xQo!u1ZV!dG81F~YXhO?lTgd+FS%0@YLN*+Jf z4@w4rkhsfF&X?I!C(A!R`8j1)XAeH%_CGBr-}$@c?x(z{oSa)ITc3DuxpV!#a?dkg zRvx_KQDyUfnyK;_(MLSun}EikUZ1u#eG=Z^=2o9gWxfR!z|@c?N|QG&I+ z16GZnX2&$TQ=VHs^T563gMakvf%z_ z_|hZgviH5GoSc`}PhP-N0*zN)et9{4=CX3~e6e-rF`<*gJ1(LXx1lcC|qBM{HNKG?53ez|a98Km1Et+`Mw>k~%$|-=)7?mzS5- z5osZFy+=8K(oNQ#7U&p!VTFNsOhYFAfan~=N1-(gy}n=$f84j*D3Z_=)?HHiX19v^;~_4Dz(Ki{+J9E|t?y zI-?!Hv*rBh+sYkJeO|fe@wb(W+F^X@{JC=J;`y?E;k@jyUe+&NDCZx3xSTupaC!LQ zhspyF++V)%+0TSd`}hXvU3U2u0*OoIl)Q+5!o|f!fk^>Mtu+Mv@rQeSmXyx@l0A=c zRi5QD@=TI{u`Hexm=vHrbuwrGl*!Cl7s`MC@|Txq zJmag%2X6mh`RV`j_2p+@|I_8gFMg3a>)s-F{!FLYw3DU#eg^4rXii-p1au5T$NJ#X zi{GeqJg6t4m)_%yA5~o%l&J!Q2Y?FEVD#WK>?D+U0&SZ=BsRC0&TPlwF#-sB8kT$D zh-qUdE#AIB5v*lXK0XQtXelqE{B3!tAz5Ar=m^w;Ph`d`miOqn$}8j)x4b-W9)ML( zy9)f>@aYeg=Y8Tm0)>m^^I!KvPQT^j?=H8kK2+|w{A_vf$zNI40J8$NGnyX0LSDT^ zz591%5d%5K>;(@iJ>`>*eCgTDf%Lk#gaYN6PBTg>q3K^8ESp<)L%u z$^#ERTvjhUR33TcT)9t2(cE{>m&<29{pngM`@4PA)mN1>XRj*DnwmZ>0JtQN;*x;m z@{+(HU{cp5rmqDY7tmXPl6bs}Cj~4QRA%T;D&MK)1?3lD)cwh&h44V0x-6!#^#h?D z5CS~$AcThX-R;&PH>J~&K+~sLEuC(V2 zt)0CxtniZO<>+6S)@AA!Vm5lP4v+Wi0{ln^9HM)6g7C~gX30by>Ee8N@n+MP6$LH^~STO%Gss)&`Ww?6I58z`-M+y zb4jd?R2lW|;tc`JOBXMRV7+W@tjPnpCY`vh7*K8sEEahbFJ4*|aD+ad0hEtixFi61 z-k!&E=L8^i|HwIg1RBqsdqkc`c^@BosN8qoJ>?%i@u6~l1w-{8(EHkJuPtY<5Qx0& zY&mmE-bHyNm$i2Bq{;^{T+q5lc0C(V;+YhfG-wpCTn1FyL&@~FypsZyfJy_<%4^9z z@yoJ}>(SPVc7(PUE?h7GM(eAud6YpX_rnVG3xtpz_nqJT@ke^C8Fi90&y58}YJu$g zh9cyid+sT3dCObM@BZ%ZmB&B+@t#(=?Y7&>i(d4i@~3b6^YYE#{67=`U}tD|x}7P_ z^RO(?bTY%TWQ`AtXIG~fhj}QG}rkPm%&~@<(id;ZbMsIt8A7JXk-eQ z%z{}u>u`JaoIGQodDmCHpxpJS)8*=S{ZU!^^he6MCq2Dv z2ms;Y+|(B2jg5FKNy_EACNHBfUL18JoiNiJ-Z!laWcP7yexc~8Kle&<;GRzwT24gi zd#S9g3PfI7F=%96_p0;;K(27r*@Zl>t?^mYTT0mt(f z1R&4r`bY~zK5+m2<@W#fetU02lm5QhvwXvik1khTbG4?RS<84vYa6u*2Jd3EhH*(i zdRfn>1Sn_b=Dh};b&{+_N7uXVy0d)oi(jx8^=VK4%JTBB`?_+=Ew}2AGp$_||J{~_ z^rz+CR9P2$Q#KTh1x90mp#eZTK>jj3qaWi9H(akpz;Uzyo!<>N+)(b-R0Dr?bqmnY zx$`>%aLxpc+V zWlJDtQ=TsCZ&@KTU~32teH0_vsT(QOD`j=Rs=}~|gTQkH^|>lTZhj#S?w%b^1``tLDSdg zeZ5dFXg%aZ595V=q}+f1edTZe_HX;rX)mJJ|Lhyf_x+21sdegS69?~=W!Ln6e#`yP z>?)*5Y%Fj<3k(GS()sY$-Z`x?x$e5_?D>nowCRLT_<2KrB{Dsdf$o<6gghVm(1*&W zKJ_Ub-n#A%l=Uj_e)qe}D_-%6ByX-0VgbgzVRl@!0S1;~^6WI#uyyX_Kb6lmyfo*B z*d0Gi-F7Y;ul$B}8s6LYr9=SS)0C4L$KsESv*~_m9JxY3Q(-5wN=J zu}?8OK;H=t7i3E*1;WdxY0-1fc&>jJl!HT{+n`T$CfqI@(1p$!Ow}?F;4mI2Dpq5}$|%a2j-005gH+ML8beaY1V#@4V}-a_60Q*+a>i$&;EYzVps6 zmG`~(-Q^qq=|3x%U3OWkoHezY+r|P%(gH&PfLI3CIy=c8(ZXY<1oDT>mFIc6-}&pf z6{1J+5Ankv{&0EcJKt$KIvL)t$!_B8a9Vkqn?tt%9r^ab<$x-|&kXm^hrzTLKuK=a zcR>Di9^BJpM-lca!zg4@mfgI6m~6Lt$+R@dUi5>M!9YWm%-T9Ue{Cx%J>O7LsmHa`LeQetOfJp~JYE(6GSge- z5WfWLFoJ!iab*m_DS`KqnWu~L9O6m**vCFre)U)XUAg^(A1IfdJ!@|xyw|mElIiW8 zWlzc7ul@8v-E;OAJ8J&@Y0*#}RSOIS0P>^ZyuY*hLEWXlu?VxPF*^R1OTf_Jd$5rN!M0<`2$9o6f#hdNDkV}X5J zU?>1ErCzQd+cTf}tnz^me6T$G+0QQ5U4Ok6+J33re*5j^SRG|IdJ5EUcR;cGd1&MD#GGW>59XLvz+WBqoBHi3PjWMLOS zDURL8uX@$1%Q?+dz5o61w;iAJoadHr`}S9stFFGf&8Ck#sz@drSr`R>>;m5=G#0=D zLj{13ee7e)w|?ull;8SK|H&IcZn@=_^4|Bpul$$)=l?6e^IN}O9`l&T*y^pn;%aq3 z2SmtDET3y6&243YVFMC8A%MwYbqsVe=BX-e`kKRQw$uR_d8h;K7>nb+pi-WDKnvi6 zb$ogBOE-0Z1oR((CfYRj5Q z?ce@wd;Y%WdCx1q^b2n&U-LE3_Zq?Mj63y#2Wd?hzXj+JhG}|undkV6(nzdXfIk$b z`4ai&gKrn;Lr?@O%#0M~xw6L45@UX{EasYn(fxr~C{MkS+mHtjxB{31)Yubd{K6NoN7Hjcz)SOUWoss;H}Swh2k_%c z`+~Q#DMxGCmCTCd0)ON}M*u{T08pd90?@J11A3mxLq9mj8bID-Cn$+54w9Ce(BSX9 z4qsl{(xy2b6_b47gQu<%gQ#r*zI?!ar~r5)pc~KiAn{snD4)J|6wjWh)?JGR8xqK4 z&sbFk;?R*Me$@J4PTlGB0&2g9L;bB(D*mwu$E29YqArI~$e{v26vD;MItxBcXe=(MfnC)kKA7Fgc9&I*Q+CH;u8wDBF5B znd6KbmmSAhrbgCyEiiNdi2C&oF^hB5{<6$+HP_KtV3%=lPl1eU2g%<}z_9tHi~u%( znv97n@`i|CTg)w{Lslzs7&k-G+dxOqCiD%k2Y_L%8sNq8dgh+byg(UKvINrRbk83E zt8(`M{73=V`F9|xf-ilbvfDp!FHErFTW z{O_E$0rOfmrhLh}fYN#oz^NNfe=?u z;d+u30%tTwzXO=_U5FI}Hh(~i#}J^!x;@?n?CEGt`5L5(AAcmL2NPh*Gv({m8j#2b zFbN&yAcXdD-|f4tX_Xp6%q%^f=!xjG%Z@zV7#|=mRoIJ#%;GSv-$B26?WOlY)2Um^ zz84ss6nzg`-X{OySzsgp@bHS$NS;&+(4jHNOj4&c?g6G--HdB+>n3}@ad_qS8kF|S zvll%+Dqsoi1-W>~SdXWrb@J-9bJ+_7~uooW3O1S7_I#=ue?A@G*^)~LhXyhGD3p4<5itCjDiw=B09pxZ-`Y{oD z@aYxyqhl`~!;YUsorYb;Veq5P0EX-g8wSHZco^JiAhc{<0Xejg#~t#rIb4iMED>=hFal2WGFRH1#xaV~j`3jj{&(((a=^9%Fw z+BX!CYgsEq*^%Kpij)hsOj)6hv)P(z%U6oyrE(gGIS;v!X=<4?oR~nJ8trd}N zUc~c(2eB?Y+$IF0pz(#`8Au~|hyT^ zo<^|_52NYetKWiTt?}Mp>(`zFhVOzvAbCRP@b>Y9j_3|x#dAqnnGVh~3zem3zz){m zT*8}a8}-Z)33v=6ugZsA6-{~5`?^Q=Cb`1`*lxFa>L70(8w(t|1sV_Fp;y7+3iz)& zdhLCLz4B-rs0M|7Fl|U13k=BufF!^kUN1S>9OTsVMhb&NzXKS+7vPLRmp5*3#WU!` zlJ%QN&lYsPmnSVfh6$EnoqANeP7J;PLK;x8=^_A>A-D!aJN05c-V0-*T2R}kg zeaaK22mnxGpaeqzDXIfcxXevU}}J+IF5GV4Ig;^0BdYEQMBn>f|TDu z2`iVh{aE_?JV0$-CjW(VE8g@$xzHUDi_QR6Pf;r~<#W2yMB;m%^8^9bvd&3(TX;P*;f=r`y?jKqdT_6t|$bO&tSckSIH% zBLEHW9cutRm8*E<*wcphOtP$t;w`5#JfM{ix@uE!SzF!kq0n>k_;F4lUPbs50Gph} z$Fw(P#LKy&E3#eoie^O{Nmge!?DgbW7|OtJboE60eHRH1;fY?zU`-)*!0U)U@D+?T zFrDRv#Y(ehQhIVfNCRFJ92p^Yo%?;u{N$(gFO|n5}Kib7C4fyM3lqPQM7Em|PgvJ74fqEx)P@6EA@Yg>B(6j_} z9es> zy;a1#T*MYIOK=D%X5)r%u&-cHO6_t=34=Y-;RoM}mo5&xnS{W1f@}0n@1Ya-`Gt(S z4KsVUxJ)~$*M7>}56waBLqDb}Z9-##T`kaf0CzRdbSKgY(9viN7<)h@a{KA%=%?^r zFr#(|s85$(tv@wt7ix6Je;vj%ENccB9PNW2ucR z@&GagjBOV5i8qKuTSNaD(NZRg#eJ`UJ>bu-XaZ#cu{(x5r6@bv_5`jnwM@%AV$tIzzaZzsZ8Rc4lB6egvuPl_IcRs-!JYI#r&O}^t`fd&8`;aYYlFeSY}3}6SVjPL>-jK?JA z9%W~ar=txI1}{AW<}m88u7N?DBD{tV^i&Hxf&&w<;Dh6>83X_o)HHnnRW;)oAW(7S z&8gp%p=eTC-`nFIoyoO_%AKdgQC&QbKMhftja(O%tia z)kFS-S+8hN>O=sg)--BU32}fz0_y?|ZpA7*f-wb*MOfuW9Cd{xgI}_xfGW=Mx<8CC z(zdQbQ}_LZQR=ame7Da&_1ueBlipZhHw!cXa5w8TX;Wi?qYD1UQUMb@*d#VdFvF&c zI6OHvfG}9%(MkYR2X5(210W^JVdDqjFL6)uC*A)P5pm%~4WO`~rhsEzAN25GonP_{e!7cn!t=<7QYBc1Cjs3Imi27AR0&mb5FMrO5f_YRmbN{x*+#7Ef%R(` z90?0FYXFZ#H8zEyNd<;OD8;%p=4zFTi$TQ*Z7Nrv=>uCaG(Vjo}y=Kwt*EX~={RyJQ1M zMyl7|0VWmC5h}b1#QN&MXp~&jCJz7?>0G^@(JIe)O&}XX5|F_W=jFzhb|(uga@-4L z1oS4rTN4nypx4W_0dD;5&N{{gN+X$Ua$)lcCD_zMyCh)`$_7j{Ae8-PW|=xxj50?% zh#c@biXqC_E?JhdYDVpZ0q$lkJj^>`#M{*7agA(iH!eGqMcKpi!q zvA{Siu)UWYhr~w4P%J=aksZcR7>=0D(7c=1QV04q6GQdjvgh}lJ%I9o8hW!wt}R&U`*Zrd|cG<()8TXH2J zJabX#6V=XLK%QT%CVGP`+K_082VfDmAx9Z{jBON;vPkKEEpwwllnAGp7=SauUUH;tcoTCP-C$D+P9g}T&iAOo?FFB}r&0foCa}njN{4KLW(xR_D_~IZ z9)AYSJOTOW>^$;LfG((jKGtbS`i!G~Ce4OJGF?|T4DNX95`=UT0b~gM)Z-%4unGVi zgG$}!tK*!|rehFLq`hkbGzsY7 z)rLGfIRlDj<=so*$9ljyt;HiAV3gCt06l07{FIj7KsK?&CXoPxben95m!7NVGq`Z^b&vpwB?9CdlBq0z{ZEh+5#iu5#VJf zv%T6hO*Y;D5*sLB&2(x08h9oEb}F$3b2;^k4v_F(U-E>PEkNE0PxX?!9op*vE3crE z08{YE;AcIg?f^1mXSq4%CV?)(; zngt$Bn0yQ5+Qw-+TB6h21W02HH26{D>j_HKU}t?yjF8U>ALimpN{DBBh$fw3><(Vi zPT%GE_+*NIM|`(_rCT28pzrL1 zy3roRIO;Fzx_jwJqkT7_vA}*T&;Y>wSnG(mPrWS%j{rkH7DlAJI&B@^ zO5ECHBgBjW7(mE*^@CtqcTopDF9^V`=v={Bj%N`%0WcwZ3%#_J94{t{>c4jcvkRDm zp#gq)6e%BIk9=(0xTv%X9QPtHy0#t%Tm!}cq`9$UMLf_k%f2Wb(F;!_ae!8AMVz9n z&xz_sZ2hY=T^x{2FsL)V?)6OG$RAgUG#E7TFuue;B=614bo~X^zKg0;I zF_oKgIOG}6Ai==2;$ievDZ+(KBrccvia(XFFvE1MKG3*KiUWAz{qvNtu0FUq`6@kf zk~_+ZTvPx|qBqw{Oc3?)4G-2FCU36Ti))_8*aw@wNGNM%vcBlYO_a7%wM?|0-RwfM zO8vW~H*t*x8UT2V+5nvaox-FA^{q|V#R3eF(`=)I=x-n;+WC!bqc=beLbOl&}zdwq~X<5zzLQ_Y6?Ry{r9p9AgARW6FOr( zA6~7Pj%>G8`1@68vJLmU2Bl|P_xd|MV^;67C8HhyIY2r7@k%*Zq6=^QNbm<(tczM( z)20qpFaVGIUi&8s9{{bq25eFe{W;ffPVb-tXmOkjKRUnJjjMR*qB6#NilK>nJbQY7 zv8I1X*Xlv@Lc4eeasXSASXP_^s0WnfLm?fwsp6}c&P#en$;9sxdj+)Rb$V>78D5|) z)ax(;#Uu=gT`;S@2mS4m9lfZRgYc--XfBNfhH8NZ01nlh<7ehhPhWJT2MKgg^qdD| za}X8An%Cu}$YUrlveLeT6!I{@@i6VvOaHy>5}*s?QBMJY+V&G9sp0`m82~Bz*cE`gjy0hJ~IYjc;WzqTUrN*G(2sK+BwWxKBh&v zf{n;a`o`)y;uQi60u19^Kmh^C*xUe2>i8CU^^g_X>04!4(UC5*l0#S*GPKSr7v(%J zzN?Z)@sOo0$OeVhLC-|NZbg6;9p|83i*3v_3XPHA*~yjoDXf*i)twMmEy6v^fMI6Za~oXcxC;%CZl4#-|2|3ojtx z?DW!HIjtjKIItz)9{^BvN;`RS-s|;jEM!O`s;=wEmR0TMMSdM<0q`!IUzPk=eFJ!s zDh7cDqKot8+y$jaaVbDc@B0+LYNLgW5GD|*-NKhIEf~PAi^;4!l>jyX>+Fng}5j*eKsgpTR;S8@ZJ@2GYPw1KLRA&h{bQ73 z{Mxz74omp>i`z(?A`3JCaEdCco2rxExiC14s_%2h4*vlJ>;-rkI0oU{t&T<&hmL#> z3jVw4*H60wxL|tIc4IP~3 z5n-O`*Mc<|+5eS?@`i^GKCL{;1{h=-nE-DkD^vgp;wqRzUyjiifRJ|+16WC0m*=jt z-4V}+jUi6sJU@8qzrmRjDJy(y<)|9Ms@5Fp(Pc(eclPwsr0giFBCM12So3i%mA6s+k+BnAMGW3YlG*e@ z8{^pXf)49;IHjpXoHBA`<0s*%i91SQ8kfe;Zr{b|2_JjxWo6uOGvB30NpnI=3z2#{%pD+vHof_3ZF{<$gzN6H8!m4QE z)$w$z(2KowTq}(|S*vHJh0_ydU?P|UP$B?aNXv8jKsNwBKoS8!W3Z!pI77=n+5lHP zY~m0+ss@+xY1hJ8kw^IekrmrOTIPb32nnP(Fj_3F8*!B|A12Mza3vA4JuhJr322$yRKz_ z-1FHHL=0bc2Af`oRa=fg20M(=$q?W+#lRUI2|ZXi?WlZB!|(d2*t#jl_$|-?!13F>kvIYi zFzzuxRd`?o61uarOeJxh^ni||R1-h~HW($qggL5FkV8+W}7+heVT>JWVSCfRO9mSt{_R`(D5(dAc6N5FlvJq{@K) z@ZI#T->_q)f@P40aswQ_K2Oi^3m_{nsQY>8!;~#_CpKd(AVi*WuKh5u1^N6>wle61 znL_I3N0*P16CYRDut_-bRGCb1G{351kF0Qq)o+cgKn>%mvOog>r>eT9Pgy!R28~g7 zq#n2q$vm~Obyp2Eo>t&xSF({MdI1 z$Pc&5z$J93Jg1V^N`^rdxJ_L%u0EZdaRSk^mz+Y}s84Uw9$QoZh7nX1O=v8zZwoX4aNj07J{fY5I7laTki19H(g(3edTEYxXU`NUpn^4f1OQ-l za*N^wh-6^wV*qCgyj6fc z5v*uaR6`RQ3+&ed@h9zmb2aow)&g{_*}2kn_tSqvxV2XLb3jo8Fz;#7y@&J_y zyqut~1ZMV<35Bu)m?=rTd!%`jM@5_4uF@w%{1U=1N zVJgZB4e~l=;GvV2=7U_38N6{%n?anXP|5G|W3!NFZ=ccw%vmw#VLhaSE;B-u0Bf%= zj97oCK6ovgFkB1J$7U4_mvh7IxLTn3l^*e$r^6Vu(_nz<2W&Ac3@T$1%s(yqcLSu; zqWiGw86YD(lZ40n9)^SRIWPx#)o?yU3ES$pqu-tYC^XHMX^VHor z=Yq3u@gh(U_Vhyo5zJq#Q<1=zvGNG5>f?~a6zLipSx133oWBmkm`N(ztK1)gk=S+B*cVOUCLRj~!8Jlfl}XNO`F&gWqij;jBu*KxB!>7I zir>m)*Y?43O9?<(M-Zl(y~M zO`8zwVHM2F>8wr+w_ZMaUR5i;uf*N};)WEo8+3@_qV@lzzVH+tNu<`kCyKJKCY)$H zn4il4Yg3OvPCt7-%bD1Yn=Rla<=%QW@YLrvd8ad@j=KTyU^6%0>Ag`4;N!<9FK^E1 zWoMtg#@0Fek~#Q3BmMF9LgAE~8+{92)%7}?ZX7y*J$ujiI?QVq+k5__YHsEH3#QY& zkoFvR6Jx`KWk%{jd*ep}e;E|y%!#|=N^v3EDejMkiYFqmm`tbPbX9KGRSCOn%(+RX z07oQ0%7dQFJ~Ptz(BgZT153WJ@nnA!LK;DvQ_BH%nc$avzaP{0v2T^H;(vk~KmN z;9nlp;=Zf1X5PEzB~MdK2XK6P3TVm|Gw`$1wI0M8^XFJ2@7LY^w0H}7Ay&lBQ+~U@ z$!@&3VIY7yJ&J(~sK*F>!OA1_GlsmVVQ9VLkX3jj96RheUUGyj3$Usw#{EpF`swP~ zDFE1}sc}||l__H}TW+6#5B?F7tYi9~n~s4HTi~X-jhb1wS9^UhpDxUhxp0smyV!V> z@Zlaz&BQcMu}GuDOzlj|vSADGt$kwCki<-goVS6%U(VrSiJyY{OoX^RZ&S2{Y-kkW zYbPoh2l6VJ&%^QliQ!pIcp;z0=t(@;>0Fsw^X4g))DIlZ*!A=Nwq)>?b!`_`wz2(N zFNWFPxrP^>?Tx9#D#EP1P2XR+{%~QY>jmJ3(WhE4hLMGtnuS?drmNUUxh@?2&;Zl| zyzoE2Z4!V`Hn&I8aj0&-TCGAYkDWfvH~8?U7oh!ea6cE+<=t;sV}d2otN;*}{(=zu zJto)J>~WB!_A<|oA3I4?(D+F49KJQd)5d?7uJeUi*D_}HJ+~C5ibDtzO zE&iD%cVp~cku)o7g|%NN)B;Zb(sSEl+BxL~s4u;Q7tjmf^}>1EOfqTM>fB_?;Nn~J z@G}9ow3~ddP!4X;vjKC>)7=o~>oov}H_Yfx(&}5bGC}h_fI?us&E~A)aJjW?=)%Kg zR-k^|e<^vh;+S9l&Hmd~BmW_DLfZuV(Yfa!2bMX)rG;6?>s&5fx&G`+wcLm(-V~Xl zeGzXC_1-c>2A4<#kBO-kMG@0J#5<(ZD6Mvf>EzAZyHlbgw&#bF?3Le~c?CHB%||ps zox3m;DVA`|5|);|JKMtNXw)JeKQ4g&{a_ask+KaGpn~PtCL6yg<^gy~x%eS2+K@yc zm)smf_8G;25yKOPBA<=v|8x!)dzVQ3Y(cKh^ZQL-)6}` z**F#R6_)S>PdLj2%UzhAl_VW@s~f|2wmsc1nar1gStH)_u>gt9#aAYjf4(1I}SKlO1X zcWHUXDHWWuvm=eiB>j>nl!rLON=>CAwFPrmT5ibhsw_5vB7}Y^Bk%Z6PhBar%)aQP z@u_>DQ#my0Vv1TNj7&aw(T#J*A2;gaN0e;0vID0Q;_sVCS#ErhAJ?|v{J-2>87*7!6b~N+A4!)=KIq}lwhZq3uk$IW7DIHXEf%?{ zCRFBSq!tYi04N7x{-g2LS~WMB^$UmGJ~q_wjQP8=yjigN><0=v?^b{ufc~1l|L=o$ zp98R;4CBLuTXkvh0C8Kw*Uxfen};_Eis^KS0PSvyZ#qj#u!9|j30mhGB#PNqpXk)n z@Ot{QTROW|mX?OLTsEr7djfL4!v^@wrpJWFl_a8P+^u|X_l1b9T@k4o;CPz;}V_cA|eZXd7;1DIokRZ=84mm z3+7_H#@@vdVB?dIr1I2DhoqvF&{Rq>%>a#cMOg^70bn(mDC12Qz6o^%7P6wDy(uz@ z+*}W2Nj{ju2?HQ?+Nnm?jR}+=5iDtc$7+zY#>*v8JtV^11pd1g)3wjKi- zWFi(&J_<^eWHOBnne+tW3HeC{5zE_zYO%!<33Xl(Jk2yzL8Y=_T5AysC3xEFQ zlZB)y)C#?=qp;A~C*dRctz7v?<>uQewKp!#d#jQk0Z+3t0Wt{6?~zO22FT?EgZZ1n zjj!G=DGhHoRmxcgyBeF@vb5=QiXBrjz419B^YX?Q(Dp$5IepK%4VQQo;I~0a_lrJ? zmnwjigPPL;hf`n@qGc8b-O+CLy3guO47dd zQH?)V%JW`J9(LhuMGNM8eipxeNN%>SNM^1j+)wS;fnH3|lA#lS6>$9!;q-J-5l6dx zgN#Nkjf{&~1j0q2Id<6&T z0a$PD$l%z+a=CJ{b&Qmc9#7XvwTKFPHI|P!;$d5m$p~H_G6R$)Q(T-tN`z82>6N~>al&S1pK5PEdpN2ECbK_T^+za*@oD-ImXYANZzu<+d4t3ENNSutSY*IY7_( z3}c)gX$8BJoIBu3%E&fj-(5$dS%bIRj7rsr-NWe*vx;SG?&`}u#{8!GawVs%CVg0; z9YSTc*$0<)Pf0%F0YdB@ix$LV^BhGPwgK;1n>H@$>wshMK98>p1d(f zx))W&wrY92@Kco$Z$iVc`d?Yiees|8chiQrr}N?!8$DKEDR3Jmg}PUMijW6eDVp-8 z)Wy-!>EG?sMi4`W?JRfU*gv3^zpr1Nt;Vu`Ed_!O&v?XNa=33#xTJQs#CXn@MWqTZ z*e17PF7%1bbYs8!=R0RRBMU!3S8gr>a7z`2tnRl4rf>P04h4%EHcpo=`6bDyTwg8P0TqDc4IJc@gc zc9uiPFaMUWn=(HfPr~!1$X(K|z@V|^aBS|&Ub*fk?;IM>CN*~Rez~R^(VF#PXYlOk zMuIR1bXCK#j|1)k=fr15VPQ;5XO^c(X`s*g>?@X|XRB|z^dsKR?QbjbYd=#bhxr&Y zoqal`2pOjGJ$C#CDezTA8_&lz<-r&a*4IoBa9x%;2)iK{qlJ}Ir^EgGeUV}1&0NQj z4{t^}^!R+F(;gBKxgZ^B9aT|EEQNoLF5YB|oE9?8hOL%3DlU}$FgbxqiQ9L5NKV*V zi&Z!zAt-OKj{9w=y`j<)*lMRf=c#fbwQrE(I%;JoWz`_#_44w^5vv1BYy;jUF620- z>do)_`Gyg1`nZ^@Zbld08B?zSpAM>Qo#f(8A zb*;q)6uyG7^dL0LEm-Czc&vLXu$WYf=*$%j?0U+I`Eg+Zuo~o{9O>wGHF}z_>juJ= zBG1fbmr;`Ph@GoI_M(fIRag7NX)WTQw%FUzQ1+XGgTacy%c? zLZ({SSf4a>sJo33;O%LbZ{qf;xU`sLH@0ZBP3N*nL(Um|3ej>Tc}MJGH=E!m2l{OT za$*?685DYQy^-dgO{(EhFmmPF@q}g7$YsMrh^)<=)z=5|nrghh+QA%Fz&B{yKSXi{n7DHfn^QgzSGdULM>hX8Qe9o{damYI{pcw(mERa=Hx zG)3s7wyl(6m?ibx%=E7|NMz)wumm3HIrbU2J8}@h38KviY+QaEdrS^&Cnu_9Kjb>w zo_{rG@@?*s5^MOQi85$umy5OHs_n9Fl~<@7qQw=YCs(Vu^gpWYQ* zRJ|@Es3Gm5jH6Y;fhTxcw;JswAu%p%=bjtIYo(`uPg6+^V>h=cn9?hwtTlyqaA(L= z5i7((J~Au*YI(VupjiD>;QZh|_P+moVUy&{;`@qek^kTqr_22VNlc&~=GKfwuqhU6 zmKyqEUOmk)5N5wNW8$WH(+))DeHz$cDe^KePtguUBy7v8tg#HwmC;D~RVS7$pPBDD{Q0W#K`1x6(ds+Z4xGCb6eCSFxmjBMeUXYyG>vkoioiZZW8+d{}y zehFj|xiUdYy~h%A#J#(bwW$nSywbxn#xuv9Z4^F_sx^TpyHBM)$>V(#Qe2Y!V1kDX zS7(lXjEkV5x!@pk`jya@mL`E!?=8aEXZ}~y$t;`dlRUxtXeW#A>1neq0A`fOe(MxY z27d}DL13S!{@zOa4jJ2`6|!?;I55*K@U_z$|3#yHz>&ZCcJHNR_B7RR#c~RTm3@oH ze7kepD-eb_vwKbeEgP z&h_AB#D{p}tenPpy;NzygpX7JiC5X^l{xiO2wOu!1Er=8rPG`rlPG$AWEd8+f3X{b zgx&`B4~-BGzOXk9wQNAw>#!);+?>|D7$TBuPtc3|#>c=pGK(X5hy_GfoNtpqb-bci zW*)v?q>ZG~Zl~O;EK)asumG1BW-EA7{cxU41&u$>^3zd-JXzwYk+Ul>>+-w}?c@Uq z=xj$7ei8G~Iq&{Gz*%P|qRHFdA91(%hY2lJV#%t=zzuj{$v|t>*)rRg9pI?HN2qyu zvuu*@Kl?>)c=A!pmtLA@aKPf69~ZWTm)OR2o@i{K!E*^tJW3&HM0{9p?g;tV#cQx z2R6ucBIm#O!V-=p^~0%_g(k;I!^>~foJ|{xg`B*dB#=Syy*P_RiSlV&{md zoH`ME=$fEAUDjueD-!VJO^f&P;~Y`T%vE-d$6~2^eLEM8HC7^d7l!UiO^tl;o=tOu#e#-h=*Kdu@}m9%r@e4u2K5wAmke$fGsjwT;o|(fB52w;5PTx>Xi9;VZf3k?C7LSCtSOG_gta#)ISP zbg}GV94S?k51G+V*`L}}-|kiQ7C>&>8W#(h97hBbe>efKy|Gw6C zTS_HMrHP}i=~BnmtV|p*J>|)@wEJ1vWqw2dqLJ@q-hlJva-ASIXGm?T^N?-hh`D)+ z;M9jR#Ln8a*<~mr~ik4 zNs0By-f9duR!l&+A2vYBsqRyXz77Rdv6el$xw}X?2xyxRF9Kz1{W9f!&i8k1#=aHU zq>!Nkh+h{g5yh8#l=-}fcBfyh`Bwb!rQeK;i^I^!WX})LmM)~)qwos0)re-A8vXbj z0@Qi3=&#K0Omboed;Tpyk|H0^s&lQsbD;P4oOB?fJLi^icUbAQSY&fjG*3NnW}8nS z3UwkNil0Sl@<+sGi~X|MQ;|AIj9q?fd3eG2aogEUrhifGmF_QEY(YozKIw8T+WEsG z5NZ$6%N|R2r5Ad-^(*iK7eeybdk66#Wr?IMH2U_qX(W2Lp9gw=;g)l2@{iYH$P!Qc zeW{&OJKNENwb{ENkB368uLiMlH?)$t;L_TRCk;Zx#U_#m!b7$)TJ|#fw^GbnI9tJ= z3MI0E&vQ?PT#!pYE|#`L?(cF8!W<`pJ@&G~=bK$JDBV7=&07t|pwrJADlU_E}d#0_}nBNNgpM~G)2T&mfR9Obbq+7i%rVc z_|s8#H!!}GoY$zJnnmxO*G>A`CiiqB$Xp(|7Lf48n4URq2j_RI^;qCd9FWl8Vn8GJhoW9F zC*V*;SvYGwBzpyY>Gi7`)$?hftPWXpdm0-AgQ1RG_@RDF2mR0M7RSk(Xh;tpw4O<| zPOzv3rlJqjnMaLRkkg2N^N_6zXiz}IUSY=JS4S&J4l&`^q65-eqFaz7;Qc9(zep>q zDmvyHVJ$V4A6%t7b6D^8Hx&6BVY+f*dU@^0&ajV@wI1%fiL*~=eluAlYbc8ti%kOF zp3WrEw!ptqT{HH{Tb+yI!tXB3?mcd* zXQv(?zzTj1hK6xIYGS%-JI6cv?%A2R;!5g$$luQ%ggoD~L^1Xud&tP8KepOn2BVy@ zsxV}Pk7gwBO4i+OFMj0LUp@m9SDzUx4ZG@%k5(oHD}%D<;@E8)IwM(D(hmU|){yVe zdnA;ff2`)YL+k@#4zghIc<$hj6?uj7;9eN3+i-OMMNnD`ZG{H;`yJ{Q`V>LQoPg*Br9X;4RXfPTF)dd z*3uhi>?Ex`#y|M(XYAb!{uzd%7wOGL60T6=Pgd@te}Y?nqdt%?MVpNm9($zw8revn zr)48KV*Rz6_fPvcp&s+Yx2Vyde7&!v+Mosts)iT-T~k)m6OtR8m3PH&z|XXoSnO!m z1yiV8MFak72|jsjAAF_%dW~C~$nJ=2G?`v0Ce-+RHAA&5xQV5yJags(e1EmY zPaxY#GWV`3e!FJ$zW?u=sr1b6iNZ~Nn(4zlK7xE_Ua}`jZ;DPl&0^K*vu3o?{f8aK zXL3%x*RT$8rPPdDty_k9gy~bxvqt>JCij|_W;R|c@BB&N$T^!=%aMFq^O?*TzSbgS zChG-G(9Q}PKcq1znmcI82JaZQp8V|Fflb>@4p&;uHAj1 z9wJkLr*8i))^sFgl|1|68Z5Xk?6)*Ckzn?p?wJKGlWS(t7>}B5&SH=FBAo^I-Tz4( zNFQ8f3EyPSNILDH0&U}K1BX@!UDeeit+b9phNRU(V90|$f zpQFLXw~(0fx#l@q3j^}SPHP=uP+i4}m8ZfCPYC!#|5g~IzG?fvZ@AgcXx`_VD6BLI z+0ASfN+zgyvTCR8XVie)FNt+o&S&;5I3VCvy|GwhSi zt#`Lj_8Mq5w&Zzg-un%l);La?JvDHx@Q{bpuVcge^E~hVoa>)Oi9NF0943||%OO=x z2+ePJ?$~m)lcK@>Zd~0B1S2U)VJv(G%id)%jpBikdeuh11Vv@x8&1xhN2jXe~KJ! z?70)4|00_hXemEXt0m^pAFD}~$^b~^oH`@Q-ylZCXf`<#&HuX`Xc_!3PJ)3rY83lT zNP+mqqaw2%yDRpZp_kR&#Ntnf7b<5fD^(T-HJfY~J~wrg z|NYd2`oPvU50ppSd)puxb0FktDimJb8SQlwfJn&UPSNMHn_00tAqlwKz>qO$ZpICl zPH#q1M$j9eWCEaf1!e~zFZN$IOA1vx4=b~iz7WGEfvuzs3(_%&#N{N}pwET2yt?f@T0PAKWYl>11 zpiQ+}zCVwP&&d5(akhZyHQ*u2*mxtW$am@ojW6i*n>Lqr(7ux-QHX&#bD13dsS`r# zx{Fgb4`&}#A_g)!?@r|eZPg+$$go1*>nSsplEth7*C5v(X6GxINVpC5(R#W=`7{2& z)5u$2B^%BaJ0EMsN3CA-_o%Ctlgf?S1!v4_>7eq5yIrQtZvW%4HJlAgX}TT#nL)ba zIl3pJ#bLR1Iq-<-k)>0^t1w4@ALK+1*tzA#8c6;{h7JTmj>XzZ2gS!Rd3Q%m$E%SbPE1P03m;{3)^50(hb}Ip{*s{l$-wiJVm0&lWj8n^=@oH zmmwIER*^1W!OHO%|#h$Dm1KM6{`^A6fC3j7T_2{_^5_vus5#Qzu?GXpwh zXtq0^t;%FFZo4g9xg!YrHIoxif88?SUG$b2I`U-7VJ&+R*?fM? zQY7`&6YjOo-g4X2x&YXvhI)Sux&q|yfbMVpZQN&Lt-7atD!QCQ&m9ex0D^YB0#%?m zclAs-IlM03os4%{wn%lPoM%hRk&_EgE5ap63HoLkq01FT1&cUeXgONw&u6*#RqVpK z8c6-trOPMx?yniF`mQzTdK*DFw@!v~g=e(hWYiMuC^|>1nTQ0}>z71Qml3 z@KPJu>RsF5EPR*uh11wnE(+zn)qefN{I@kQ%e^t}-ddJdrox(-1gO(dp3){>p+X!LHykM0EOHo|*kPG_d$j?M0+;rO5pJ@2&0U z1#(ouFPn69!p+&0Dp#qM1fnZcb!ZOHGPVpuC%i2F#s{nj-Lnly*jNw4Yy!^)g+@$< zGoMj)uuhmkor6S513lkvQZ{*gjncKdX%m}Z5cj;dd6hqZ73x4mJV5>`T$@y|qi=V+ zP%{HaJR$g+4=Men!yxI7ZcT8B$b zVme_0fpeUvi*8LRU@&(jSCd&2Jp@dsjhE_uuJ5`G*L7ti7w%?8-?)^m^Hs||4+Z@lAx#iybdKOi$6ALW*m4?j3KfTj=PfW{4 z!ryZJ{%|Uq?uFoBx(ts-tp{j1!J#29LQ9sMc>PE2wPhC3r?o4;&SBw)-9QJNn@>bp z50Fiz#8w|R|IB!$I{NFp!Oz{P{PSMDv+rb{b~-FXB|{;hERy--806#9xl1U$*dP&# zzec;8zEe<=;lgX#N2(m_a;RN`j79p1bd#^xrUwYQ&JEsutscGvwY~zAnt{QD8CuG_=)E@7+$mTZ+x?3q%YbPqWaF`Rn06z8>e0w783!UNwN*?`XL(~ZtjM(gg2&mR+c z$b&tfX-+%qR=z886AYsWsZ`i-o;G`=PvbV>m**8UK<-RvR{MuY_^#CNVEia^bf^%v z$abh_9T@htrSzKu`~~25!JH*-b!FuX*$j}^sp{V+z^LUh@Ineh*_yR$IkSb^pooEW zvYk7rko91AkVY`<9__sGM|#okgrB`+aRt0g8Omkm#xpn?K^&$zFxi8gZE+ zG;S<=-DN$qmQ~VDsy%{A?d){H$@o=x6U}~}jQ1#!iB1)C9BpBZksBX>lywxn5Qp>~ z{KV-uZ24H~p&8lx-~RXLfZEdanBKPNt?BWSr$LCAz&ux*GM;=|Fn=!rdow}lnQCU0 z6hgCTXWG~$8Zpc@JneK(L|kUE(qL&*e|wzsRh_S46Ia&Ca=mJZA`C2VwmK>@7@w=| zFUb_t@^zuwz{St!gU#ONll@l?LYV|d7Ag)Z>1RvrvN&R_ciw2}i4>VKOVm>b2Q#ur z8vdGsM=pP#xo`HRb!VKLX;RtJ;(QnL1=ix-@ahy%ToDnfeTk%CR(7J{efN-deO$-5 zEXw7gQuV@XS}M&}ac(B)z?Tv4keX3(Joi)4h6R_L0s28>jzQ#U&zbXV1>0q$?3{!$En|y83hHN#+;Mzy)LH zBodW)xnf#oI~F@hM?0Vym0r{v&6!?&_QvyJpLPPpl^b|wqS#FsqXP?O?~JJk)8WGB7ak>ablg^mO5L=#8!55j~^~V}p$C z#`J6aWs&&w(qu+{Bt`g$K;~5wiz&YC&)E*EWtdOpovubN7MWtKKO2F@R^{7}6&3F& zhb>b%3nr;F$4shPCx>PH&-LP)U*fvKqJpzSeXqaNij zTaqi1gL?z^L&=ya`ReL!Xn3zRO{hZe8Yr^5OQzg50X{0|m6{{7T>*2F#{9*moEe#Y z`YWC@3d2=$f{bj@`HQy`co!Zx>&dK>MfPAy#62$~BK8c~(P%3vSL&fiJIc5Aoi_PF z=EzmPCTCKgJnIxvz?E;4ilf+)D7EZ8a;}_Vl2dZ8@(5y;R0G^Q+rK-b`1i%{iPy5h zyO)4z5o-BLcrUr^QU$)~ygqR3vJ9pVg7rdzA$hCRX@2ik1AgvJRNRKhtX0q}*<`qO zfqkGYwK7pGZa%Qs8r7MTvlS;O`$Y0#Uyrbprans8r81CY;mtj0yF~|o!wlKkxuP!jO=`%KqlY_ z62|-L+O(2L-Oa2K;6%<2=7M78AAf7;Pp>naE=J97m8!^ohrResJ)`dvOv*3IMm$NO ztYLRuOcj~JOKRB@6CJsrHX=p*rz7|I$hSCYRHI85Es(F}dR@n6BA36pMuOLG8AY1*3Qxj( zjSuf*Jq|h&v}LHN?|o`_v+zz`jGx+Q^IXC#CF_%UD$eBMPOaIQW}92`^4MZnsw`#t z?T;55bVV=I+F>6~*WtVQvE4C%TZNYQ3;07f$0nAS%>uuiSJU`9gpvab8WrcpuPbkk zEMsL@#M-PTiNU?{Acx&qa@VRd3dfSlfNsH$p_GOBlNFv$CMt{W_0L*xyTVVb*!ilJ zj?eOCSBo4PSTc#2k?Z8sd&Z9JCQ+r9fbrQ0JLF}i#G3L1<6w8<6mw0SG(LGUpCP5$ zr8jb~$jKe{CiTS`{w>ic9L{Vxx}f~c;LgYHdO$mnWw_zget`t3$|REQr2gq$dgp_@ zgAAjcu9O=6g=E{HKQRKgfFDw6PV{1)CiUaWebDC1c}(9FuM?VI46EQAKJT1GGbGlB zJ-Njev;t2`{26|_vjZiEp9W&Yqb1wF+}JGU6D-f&izTi2mc6sXK%=lNO) z5J)29NZMm7bT^CrCGXzIOL+g#t0xk$IaL%yKWFjNWq;D{RLJ1a=kKzYW3<~WLu>hE z!6Uj;1a5wjmFuQo7JZZd5rhmN{T+vd86ojkIWT~j;1SEB=WL6azwXy%^b8dCyD+*n zA&H%d?na5M)+K0ZbIZIGr_^oT?VUTezte2rc=2BWL`+QE=$vB)=!{TqpP0SF5kKaI zo_?p;bN+L@n;l}c78(W_`F!oLRQk_?jBR0L0hAzy(NXx-FQ6^|cTy6|4{PZT9CMCi z74S92lhBl-uc>9g7TS%jIE;{xX)u2(i)!V=^7aJR@J<9Q=G2N$_a% zr5r9dg>6Y-ua)}&F3YsxZxrG2s{+2(Hx$32znf;%d zLqbdq7#H_HIxktpumu5bJg!>?|84grs~@JOnidP|e;SX*G`{%C6o4xMm2UX^UF6KUNj7RxEPDzKwLsV#I)2rsV0vTV;Vx!U=b znQok%%4qHHw4T_}c8>d@&_96aV)dMo)RvV4S83_ym7Kr-Wd90FFHUGcC9bYBZ%-P` ze6zCsOk#UP%C8xRS~$@;-D(rO$b{OkqG$E3K$$_P#QONTQB(KIhF|97NYKgzUueM< z5~T#Xdy^t-@FJjfX2aXtw-prmPd3udyS^w5>~?%Aakb*sdM+t*RnHRZU~(#!9-w^( zicTmrJm+*G*M9Rc2;`e;=GIlP_s283wdYE_IOo2l$dp9=D9mK$?S-q=0&yroZiVi#% zXx$E1pKv&02#P&%eGR$~&~BnjUOu>@MZvXAktTo7QQ+8(wLKJ?_n$0Z;o4fZweL_v z&(31d2x|P`d~w59y4>~eitVM$>AkR4y7gF2jf}KrI|{XH5jaGVQaCd&f@WFS_!)@4 z&Gvl3+dOl^k6g=XJa35DyKQFa>72Ml8Qx)JO*J|@V+-c;ii`K?*vQ9p|Kp+<@68>= z6~;5!9)G+1e@29tx!73r5bE4s_5YFU*O0?EPg6JWq56;OJ`5(p{Q%I1Jm&w;pnyfe zC4^D5;xpaS{2xv3hu^W@VMW0HKjsH9ipdS`Nn-z_`AZICACC(``9J0bsW6KF|LoW` Z|6*#?WF!7S1pxC?Q_^}_u3-N8e*r_BLwx`M literal 0 HcmV?d00001 diff --git a/docs/modules/localization/histogram_filter_localization/4.png b/docs/modules/localization/histogram_filter_localization/4.png new file mode 100644 index 0000000000000000000000000000000000000000..c7838cf26a75c8ba515381f1ec650cbd965d8173 GIT binary patch literal 51007 zcmeFYWmsI>vM$^-1PM-pyE~19;1=9HIE3KZXmDr}0t9zRa1XA*HMlzjCqQs_=T6pM zd++s}?|eV+zuR;_J$ueEYFLe`df!oeQBjgce@^rq1OlPU%1EezKwuaM1UHF{2;3>; z|7rvRq1jo9i>t_ri&LmLLCvjf%|IZTFY#JP+Ui=w!frH_lql3#aD>JXF;h%J%3@?N z=QDgt6q+!C7axO(SvAX*Bwo_%;#OGx0IO+8lvFX)?J`)a7EEU0Nvd8eBUfNU@L}Gv{w$Q7aol{Ysgj;(SfU_>cj#yy-t}>$dmWl&KlgO)*@{v*j_Sr!DV{~AQ0PC5Lt_xc*E77T-K$eTR_Va0#goqeW8Ylu+c zk4A^=_!-Bd=-7~USYr(@URe!{w8{*!RP_+lc?~*i935s_w-6`0@d{p~0aqY^QaP}Y zjwJ=*I{O!T);C8qR+)lHGg@E1Pr^JJx(nmFh2DLoz7sUOKz=)ui&Mg0q5rKX`P8pw z!%yBf?LBWGsYam;UVKI|`Nh%OgF#E$yf+KXePQA17euRY6{3r7Ae9gq?D*mfX~kJ#7O_~90t2S<UPW`8E2EGAeRL5i2p(!=c7$MwGr^UO@(6&)#Fnnr7{8?5GgR5Wpgm)T~ zpEl|TNd{wj%v0n)u_l2w*vK6}r+%0ye~wv~Kp%lsQ@j!r!q1mEUFCkLi)V+ZS=E00 zrEZw?{cC9c%eJn9jh?EUXUDQTg2$^QO9Ae#!dKQ<@Vpdgx9<0E(WqqN zDVSMeWOpShLos0z@^GzUp;zQ%9xB)D%YxtgkNu$JHNKVQnY2R*RWEYh>s;Hv{JUuVF)vrHv+1g> zDqJY~GR7M`t)FhB9Zqh}Zb+inrK*oU&F>4BD3MQp((Cmpfxw>v0|Rx1XR{jNco&dr zADfk5Bh}?^r-D+7R+vpcTN9TyVXd?VU@Ta5w~@5;k-QT+Xd^~|VPRp=!FZz(#@k$e znPKa1aage26BP{(p!7Se&AroX_&XhogY<(|ca!kb0f_|u`yU0-8@a76Eb5{oh$FdLxuhSr$pH}Y?^ z1^LB*840Rr*=qWmw&o8rs{~wO;TE$qCa5n-kYH zXMM7u%vkm>bugoB97+FsIo#Ydr$DE~6FEJ-dAWIIub3Kbujmi)7h?O)bC}i3YUc$? z8W^rjnqmgBi{f^W0oJPv2^)MU^OvsafR8#XZbh7%~14YEUXB8`tV6u+(%rw z<7Ed`hjoWZpn*b|RnI!-X;M*AP!dnlq14y#_mMaey26FN8k^sFq_V@`gat^MNg;)m z5;t?169y4)5|we-ziP4gn9TcCf%B_f<;WlqqWe%r>mAc?@Azk2 z^0#Rxe7T&fWVi}urK;4;n>Q3ru}(=&pP#O62;rfHQlM5ye(pjEUDgR?dCeTD*~LG! zQ}yacSfz&cLAh-$Np)qdTn$qN|2x-_Z}0bQQq2sE7tI$fOpLk4%+nN8hafekdPaKD z`-t;ZHPF4ieYO3T8k=e_YpChS4@gZ}RqL*(GxCR|KPqbuL(yAXyGgrsUB@9WcGmyU zI2C?q*bC$L0=9ZBuUi;p*fB9Rp*q(_9_rNReYGvM&6BqHZK5^Z)w!)3@8Y3fXB9Tx zX{5JfLj$ZMc8T+;jyG#`Va$Xxf(N;cu>#A@bNAnnhNyperR&mF-3Sw#^FhVdKxs6!Lb+Bs9|~bXm_2`Urj$fAB-B zLs&=LLv`n0@@;asD?N?`mw-L|1;C9TwZ#a<=07!jWc}pP&fShFUM!A4*(jb?PCCoC zcfYrpX`fj+N}UPieMq@ZnPz8U;Vfn;7Sb0H7Eb?yNuHN_G=(AqXE9mna+ZWpv)6{TabULn0 zcP)n2MyBIFuFL#DR z5@7c-_z=mUt--j1>)e^#331ADs`=B@7e25UD-f6X&5go{S%muWyM$2;GoR3exB1v0 zMnP4z#vJ#6-}H@+Po?FoJs(v%9h8Y3Mt+|75+kJSCFb)_&x=rz%<~6@^>egn7#m*o zSPh@>DTh#pw5EoR{28%Jw%~&vHzA$Qp1QG!;+e8p>RC2BZ2vrvj1IkE%VQZfxO4uZ z*Ebi_nvlb0WoTXFGBz%4BOWK{sC>v=C~2y^ zyMO)=g1Q`bo41pk8Lz`UujNrT*YK@QxALa@+X}bW%uWfb;jQIjrz<*caY$uI>-31W zU(0xv(>!87Vpm{kVNzjU_-kSy=AD4Tk;;;^1X4Ssq)NHKy$v0kG0L^*8@Gx zplQY(&kN;6zdw!Thu?M#cHBtbkuiuMV=!SnJot29@?c1kTMO)Y)jc51lfNc6CSkM@ zCE9p(#vKAQGX9M}LWy^7nq<^_U3!N6vRb=FgPcpSW{3CB)%cn?eTec|t(=~hvU$4q zGH;ex*W($qAUhI@sxug)TpcP=|Dw|ifl{Wo=oZ_`CQ+b`d&NgjrxCpNK>UeE4s zQtvPAqbK^X@faL8jxTVuthrk_Z1xoyYxy;FH-9+x+&hmT?&GmvO!2JRO<0+pnD?kP zx>LIvSV@(1Lvb58*j_4Xf_k=YX!RIjx_G#edSP9xjCXVfxse@{3*9O{%-A`mR3g&y_^^97^9kCI7>0Dwa_-}GVX)Ik|EX#@c1g>};coPf<7RC!^DdK;QMp^) z=lMI8v0@gG;Q<^h0TBeBHqW3wX(1L*v2$AV-2X9PYEv@a9bN?!+CSp1#0)~poD<6x z)AapG{~0vdVIsjzHFDyh<*fQ!Hkh6L)mc9pNR10bZYnPRNiQ%^c<*E15@LpH!VOyC zODaJw+e?isCG#<=qtD+*^3$iT{*W?osVF|q-y5YgMw9xM7|sItBf(5t)?85$!~|R; zgPy_RfZ%~EIN%QiM+AEI*EI+v2S@y$Yc)8AzsrC@pdc#{!rx_df$yhR6z~CR|NRXg z69_^Ae&GP0fDG`zOM_t<@c+Jsn*^SL#MH%QWr1&X6DKn>duL0i3*zEIA#el5K}N?J z1j3_z`oPJm(HsE)>X(&25=j?LH<`reGq-Ok}j4oJ|QAGowLb1|lHx3jf( z=64sO`l|##aQ$=}LPhac5f>XFDs4p-3UR2D8O3Whb~bh@;pY?-6oO8s=KN|BQh!$m zehE=oy0|#-Lm+N$ZftH`Y)~f)2nQb@AB3F~!pX@BlwfuCuy-+bXSH{x{+Ez{%aJg1 zHgU3YaIu2gQ#{Eveh+nZ5u&1cYUn?&fA!PM-Ri$B**pI|EMS0;rza2&Hg?GWR?WrA z{Qsxg)02Ny`)gePYEJM;7{7{@yP2)Fgq0mI)j-#TIXKy03;xy4|L4(vd-|`cn$BiU z;!r!Fri<`@7whlJ|9tpAEB@7{&VSqF<>mZmlmB?~kD5mXf8P7MyddOh z?f;<*|5CKS?gE-7{9F+7AFUOB&YBrW4g!gSWF^Ej+~M|`k&?_Lzdk-HZKjy>E4nGW zDJ#EAf|CfOMB|f*%IF0bCBf2#50w2Lv^WGyt+Wi_LmKiHaq-8V;djFNsY1BeJ5k!$ z`IPgwQ=HQtZ>O7~&NqY2i?z3D&TF-4`L`+R`8y?r%BgynUd*YI^t0F`$S}~q-=Ygx zGQr6)Ss4@{@PFQcAOs3B1S}BT-|t{9Fc!@5?QaIQe^&z`i-J}O|5E_u&r1!0Be1}Y zSpE1P(SVS&e@g&L{y!m4GxL9EPGpZ&mSX9ZmGISv@mY0W`3TL+QW%#Q7jIV0PI=)N zrfkqhT@jg=X6JFttJ+;XH)+kE@r>hjVpBSSp5u$`3f0#LpqKq#Z*dweCz2{Fk=_;h zVH{cZo4c57$|&-!-){Xvt)bos_knlB^wsp~^{>(Lmet#ni6bSF``OD)h*iH(G2B-)~Ygx>89C3Jv$j*qsx1t+qaEGS`q$%wLP^) z^QZ4y$wPMEov>>y)F0e3r*o&Jgz7PzzFV^)EAcql%r`z``0bqwZ9asA0lgnfOs(gg zUAw9*Gd|m59`wH3=%4Vml~nsBiMBO~#~Bz}Jo9h|a&zUAmZT zTUMf}p0TeH3cV6&ZY_&^TV|*jA0MB8))Z8ebC82K0al5gnwgp4p3xVtUGik6rKcCT zk)*}UKpxDNjvT)^-{qDi5tk4pTG2A{nerA54GE$6Dc)%i8%-`O;C7G`6NAIV%KFUj z*^7_a<%esK?*@$@#;!NhMOZtz45#0Q5YUe^lHBy zp8c?yA%ffLylmJowC($DtfUm-*|osIhL9o1LQPG*fuB5?5&W7y)f=V1Bg;=|F0iB? z1=+1cU1*pTl`@5jVx;x%3%p($OX;$cwRD6h+v}3es$An*XzK;8TPeHqV(natvUa#d_}Za<2cpwU z;-(Ya>o z=gP^s({6Tu%u5?>>)fB|M?Rcz&G>w=uz)sSSZLkDSCkoN|0YoI*a+D@Y>B_L9ceu| zwU9oP?jO?c`^!Ub_a~V!mREk~mu$m@x-GbBEr*O5|A&OC z$DJypTlo?DW#4_~C4J+K2IvpI^m3vRqMqgYK=gIXAI6x#hE4RfnxCi!c2C`?P3<1r zD-r+Bs*Twcy`8pYE@-%kVn=!__n`i!b%*by`%c-6J-JV=#rcG@(9OVz{^fnw3qQZ} zci}I>e2P+K_%QPXox4&`h5ZnV2TL~J3OmnM1fp-&mw6+uZZa!S{3-7NdQ?dnrg?U~ zR&ork$TvRcO;kk3NA0QGfeZWmT%1r8gz)#9LL2ZD?Kl$N|8O3hz%A9c#=ZY=9tiRv zFuV50V9fve991cb^-xillRSs#E|t05!``csItCPt|M5u_SU6xxTo~1QahCGu)Tt3e zYcG=e!+{Yp%$fg|0fAdk0yID&qr{}7xfK;0RmR0lKP6K{#PT013D=H}%2Ak!?ep^U zlb!G2|KXaFMEs)$;a*bG+t1h7(UjRnYZaNAn~!&3ir6j{q1~!zc^?JCG*!Pj<%4T(!4*0{ZjBTvjp>xok-wo z{Nu!L_t*GfT_mM3cIsG;rS|m(P+Wf$pSRJ~PyDTDX)=zFw%*<;F|o1RA5q!ZU0wHn zap>0Crxu9bzlkOWOxK35iFijfXwO3R>TE)J;&%Db*Lh?{q{5hnGE~G7FwPqcRv}e+ z#)5cP%KJ35w2Jc@t3%YU=7*-?{n+)vx%e)#KD=WWZ`{XWv{dc|rR0+g4ZK-wZ*0#f=_L61O*!p|9J| z#YXFJptl$M=3~JNv6y+t3ddz7CAr1LEL?{w9Y|hrkd}xD3>?+@U%v<@Fy+gO7lI+K zEF)TaddVCRk=HA4q(y}Xo~$AlMLPG9TVk_b*ms;10(Y9YSQ#@%I)$0fo z4`Ip*MMEXi4Z(K5%^@0IXh^4;}s9jL}zC}Hp+mT zyp7Fnb(_nidjNs6Cdiub59*tg3!Lw*A+@u@uOuZU&5vb_jVViXfAq7Ec&zv%F|e`@ znFKQT9i+LhqVT&PW$0K^k*i@N#dJqgONXTo%DeOzfUx1*w?--R2Y)KT5aL?BRT>)` zDcj)JH#FD*7kYSc@nL6o7ck&$b9)3j?RMJcp3i?=hL0BYcy5bcQtc4P=SY5$J9!51Zg{a0Kr-naX;$st$2dW5A0 z5+OYAPvFU~+8CWdUDH~vH=623@8y}4J6F7xZw(t(LzwftC{v47uFor=%fcqhvW?}q z1pa_eoam2dE@)~JEJsHE!vMFPYgA)P2zXsSYy55{+VY~B*t9vXU|%Qi6ie7+XKv*Y z!D=f_+Uj_$LV90s9;RV^$S`E!bfL#@2DvwqOee~H)+{k~y#2Rs7Q3LL=m)&$MX~8( z9j^V&^*+7jo9QI7DF@BD!t#lF@2u%AE6fyRddKNZ<8bPShVjdtqO#X-lzi?zrJN(kWNl>4x$IiZf(O61r_7Kd7aJj9`QkC^4{jksV5zq|;z~v;8v* z8?xEp?TmhHPY}891y<^LGyXO`BsIf2ZThZ*SZh@M&`1%}FiLd9Z;#~WCVqf-@}-Zn zx=?EO@3aL&fg!1V1+Ntv25`T6Ic@2Gvj-4hfoMPQZd{?Wsk zmJ9Bx&!K1Foq$<^;VGIoVc5CWss$J$itsGYtILANbaN8z3!a5CyM4vmaNd> z?-?U4yR0sIFYqVmA!RE|?Hmoi{b#nZ@xoUHMdHL`>}bGXRYi(4#1jL27}Lf<-5N&K z<+9&hk6%(3&WPYCn$J}SdEWBFMQz+~pQ;{+-?e;|j5ytNh+eC2GvAWivQM?&qc0a3 zBviEJI2;=FD|V{+y%71Z zN*my`;agCDi(e%)!pSu9kq^WyiDXQIeMc1UJCP@a#N5V?zfrmssSgpSK@s0qxY?~=gj8;MMg>D!j&p~y;Uo(oA#m^mCY3b zpPhp2Gq+aHPc^H*-F8=&^&3v6rCGt5_Sm;v6DV8LfkY zcX8PZ_+#|Y=h0qN4|!`{Zi|^`Ky<(%1xps7ez*zj*$!=;Rh$%2daSNUIq*!jh|gX~ zmv6LcWV94^y611$-J`O$AZ&f~nrVj=F z<)b{FEbp-y4sOt=&MKVcgWVafG8NNGj5nAW!YQ93reH!Kmg7*5XFx`ViB{u`7C=T? z#zaMC$K-Nzzn(oXzx}$3FriL=qP#lLzk+Er)C{{WI2(baW!NFu`XA+oK#ABIoTTe|SAg?*6+cm)U8%;hbeM%=trO zf*#Mbilzsh(2PLM4RjV@Oh?pJh1o-aNg zp8U~>>VopECNFqw2FG?eQ=Roc=iEL`EUzO;%X#!XAV7~)ey>L$jog8ZEI|$k+A88& zCjbOV0fLrK8og&e-9hI^iC{kN%MnAD{b$A6F_P(gWrI!D2bX%ggPd{iw20>?esTl-H+=yEh3(yl z9RQo+eH84XX1`!RC;ebMqcTLH;Y>mKFnzuY_n7fu&e@%yjv>6|!jqZQYKO!38^qb) z?`f|p0?;6@2>n0{crU?41vU#^ea1?>+!ssXA>pc;3(9_YmkLERi~f?682?S;(3=^8XnfhDrF^8f zWeOJ}-l#mnqmB%~BrG*R9%WZ}=aV`53bVg!sxAFQwpn8I`eYhnQO3e4Q?13O;jOV@ z;O@z&D$9Rw>PJs%z4y8=NG&X|ut^39=n@^Es9yygo;`uCQf!%(ORr!rb9zVv0ZD$V zpF9d{pOUldF23LAv9uPaC7g``bBn{534_cQBmBWh=Qd2NV5jo&Ta;y7sDYQ)UQi;gFy8(hvFPxfm{j&)I-j>txw7w7~5EkJo@rk($pA8z487dk|B$hC9Lsv)B+8xaGIt!4StJftOwpo^N z%w0lWAKK-j47-C5m4lVq9HueG5#cTY1JKZemjG;L(RU5_``XT!_jf9o@o{G3U#H~J z2=@umc<69FEXo*YbiavR?(b(L48tkcuw#%M?1@DUlFz1!157S5bw(&dM9Nm?Bj2?20F}d)R`fReQNtfWL4#aM|eyK+!CGBAn-vLjl0${;S6<-)V zo!p8%rsi(qKV$RV71iYoDXzx1&J;7#5q-_t4-&A9nMw~4M-QR~*758G@>h^XMPgJ` zo3ost-#Bk!D{1c4fDgJ?zhgq(2faGPCpWC}VwBHUI@xPGdd^UeO)0;M%J#f0^~=Rs zs$qSS7JUB1%!R9p-em^LMp;SCeA|;{b-|K(F8Nw>P*Fi)^kRR$prj;xd}6|?BM?0< zG0{RI!DL&KYi^aly3-|hVN`HT@yyH8iud^<2K5OP2atlIn}`$I~P@?%3}t-7pY#;M0u zBL3`2H6Ga_vYGkD*M#bVlZaJ$1Fd(cq=N2IZ%cF~AMZvU6>1lpP+j(>40q%Lg6$JT>u6tH6RJ`3`B`d&8#pCC++Z98mznWQL%B2p32BOsDNQHvKN3 z({SmeagNu2d$63*4EaXzwUg#d~YRby=*=lqZd9#VPZOIlJR*B$2;H5 zP(*J!BPH6BvyO>@Kot$cu-q%zr?Do?Y_vJC++J0fsoLqZcyn&`thMOs0=NE*A8MpN zGj4No5a2UI8NdN|U;5kxFUlnfVYL7QKtF2uR98>@@YpwQ8-=OfA9WMTB8wzu1llPg zM>~E1Cv$Uu=%>uHsPtsAo+3Xg^mo zPfkFP;d6U225@)qrFzUJHijje7cRw)cuw}U%~-_IFQo^l@64>F4Gaw0?zrvQ|5VH; z?eZs8)08f@ET%0bF12*HloN?JLdO>hPmK3J}T8&iVsb!-+mZO+_sz)nBk~0V`iY4 zK#W=z5T?9hpp5lXc~c48DOV%$X%#&z=ih72<~%38sz|woj65d2h>T8|W?~|E&#Ur^ zYKkuv-pz~r08XB2=B6_KI(Z7G4~GS}{(Q6aF7ffKCtxaJu7Z3j?PlOd+I(coftB~I z>YDET5Ph4T8<*|z=hjUVDQ|gw8*g-z+Oh|K5}!XaT7oF_O1pZ)pCA3K^78cZDyXTMuC`Od zzo@eok90ChnN#z-RsBip=vx&+x0SUfy{#Pn>8xThx4NMaCe=;H*TTX1seUer8MEqh z?84Bwhsy0kgtbuwk<`6;V}jRev90&DEWt7U(x*?KT-JNB3yX_$fYOQS>2PhAg~Qx=thQ@bCu+j{py+{Ee-_$&cJEH`-fpms`^T!g{N6fbGTMHqw~B_JiyN1t{?^4hoc~o zS761OILEm!y?a|*?3kGoHO5eT@Hhw`AAe#zSAG*C3@hRV797>8UXA%juh_P&Qs1l^ zY|mSCW=l!eKgm2Kf&;*rRbU`uVPT=u=uUE8j@0to2}#J_e%?U=3zLrS!-irCAsmBx zY++H61+sJo3Od|ZVY+m<+PO5~B<eRRBpTTV22UzSaN5!+ zwFq{~@;0ht*L$3rpEApDqU%a#2}K~wUJE(Jbmjcg$Yd0!ZOG3M8h%qsOWGHNtarLA zHa=69DlA+04g3_P66&W@-kdYZLJpI?40Kjlxm$Ha!z(u-(sC= zD&TCCy>=Y9OmUdI2#btN-ZZ+B*V{C`&9-WCeO5cd_~UFZjSe6_rs6s!k1j5GRpY+@ zpd4vA!l##}Z`I4flMCi79m%WaIiVlku94o+YSCIJC>nN!`;L2l9O;*`bR6L}YFE2x zKH2a}8&l{E%V!0ioc*T~$Of|fnV3h7>2gw5-+y^|8T$4?`0l7Wqay-#1UIV599=DjSX?%eV05_0CZbE=`ea`U$cF zi5rB~D50k9QtWZc;YADQ5%;?HpZL=HI$D6BKXU4FB3}UUdjrFK^^nq+*>@*+rFAEZ zG)f-xk-z)3nsSR4ey|nKD3v?RrM>WQ8V|JCo01LnwKZ^^(v;fkOKL#t=_i9>3SUw9 zJe;PdM;vcuM~>ra>5FwNNm3W?nSHFPLv?>)<#=^&#lG@{kOQzsYqo!6-(5tuIL>LO zLN7*QZTVRr^dSvA9r9QEw2uzDaIRArDn8DUyM0to!PY32g8?YyV}g-<<*HUdy6qa3 z?^7^PP*D*Lc;LJs*3!lU{+lj{uULU#fqDwYX+Oc^(+NxA>X({sksV#NSi8U24`VRZ zLyneh3ci1nW6I?tv50J9+3}uMp^(&=hWB=HoFwyh-K|nz92-rI@ROSMcjsupVjC){nIH4jr=MN zejC3&dUL|!8B+U+kM55Net7dYy0t5S2zZAapa7DyrUIL3Yduy6Det~H-2Fku-DJ3i z{1iq;%dPyN7JP*6(WEwebL1W$S-nD~O|^?n{3=&_A}DH2nrEVz<^h`%ASgJ8c>^eE zP>CW3>~K-M^4C$I1U=ly76kgp$tfnV<9?OMquTP07BjgrHgnwaLuJK};N}UYlP{dH zmJ{t5-`2tNer?jugwbwT!O{R~I@aE0;6jGMvJnIYB2QXI4B*d}gFG!4Pi%E{lT5~g zFVZ;opXqD$-4br(k0vybSs#+VHVfTYQj{hK5y1O1&;Z!&b9^8R5I#!a!Qpx|?luHB z^lSz0=+#)O&A8x2|JI#K55wZLQ!)-0GJAB z9g7a(iI9U^Mi4xG44%7{+KTryq)d*Mu+TdFi1MLgTr5w>hq>Q_i~!&lcMw<{ve(6e?bpctvTmv?EopAjjST&g83V;aaFkmK6wdI7I7GkqAI zaWd-Xy#NQmZx%pEv?h5kI$%{^Vvi!aXbC|>IeEnrSx530&P)&QS{ayRKsr+%u==lz z)tMn)a9%xDt$SX*7(y^OkOUT1Fgtk8S5mtsiu8%*0k&Xq2;H@&6@+Z{^3j}jOwPlA zs8M?#Gu8vfS?zNym$u2vDT(AEz9rkzEht*x%8M1u26SOe)2NsA$*^IKDy9+hBW*(! z1z&zkd}F~9I&|$9qW{@W(h)-y1&ZWc7vzZ~HDq@NW}+n#qu>V+zm&8PWg@Tu*ixd; zl*Q#CQ`~4{x7H^NBJ_*N1KN7vRmOx;_fk{1tBVtbxvo=CviqZWq`JpebLSItn)O8I zxSUfs|FxS%gM^0eS~F1^s`Fr+YB(lN59!nX{c}xWFZruJUc#?CwK}HMwi+W{=f^o9 z_-_G#pMdl{Kp)8XlA!Q^0?7yLBadq{*_x+2+Kv@$0WMo!YtNT39b7^pjs)8n+1x&s z;&8k?dcs!YPYrvbQ$8_%*wUhsqbR^1{aV5$b5n)VDj<*%b;>OKofj`wSIh64IHGW)%_- zgxi24LIcb*wlY9dt`;E^J~2r&;JJa?){5lsHesdf#-l&=4X32=lK^S@P!~SNG zUuCudSBaD00fPcN+C=?KmlZRpD)a^V-Yd0V@cvN%-;2iQL<4vPtP+HrOXWb1pl&*= z3DpC*LD@V_`R3clE~}ZDIVN8SyI<^HnF-n6su_WxZo2V0F#<4u88K}DeGNj`pjlD% zXojag>peCs)cz*i43h9d+iKy&Xkk427Oq>HQk4WNSPa-X9NGm8 zIDje$AXLXfA!VMqOB@Z=uR;N`Ug7=m%;_J(y`h1=44Xn{OL;pHSNBVJ!7pE72ZFHj z=U|K{(}zW;@MQX4!=*029VipYUUF{z;SQ21uMOiNT>|1n+gQQUx;O5(iK-3FuVNE$&A*z0tp*nQm1%yl4i040##xNT zhJTtIU4m8yc)+4nxO(A{ujsLG;J#BG9R2Qa0T`80NqhqdEq%vlc5~Hze#2K0-9=?( z`O4m_FX)y4L@Cd+?9DX=us7=}=TnEVXZ!^FG;O25>2=D6XTTqGGl66cZB*OHTUTI=#z`f!kQT zmLVT2c>j&PwRQg)0hy3z91}A$BQta86Mb?sH`5};v*_{ypu{9z%9tVomgNIV@Rj_# z3a)PFdyIiMNWy8YDM3QBv-50gg!GRR>wR}U62hh0{qyZdO}+S$?mPhzGmgi+1zsxvXwnL@ z<-N@zuz`D=TPpIez39EWnEV)*vH~P0yAB`k|8U^JXty<*esSIHGBybNpVDsGUOAi? z84L@-bY!a=TY>_m=ozTFt)%9+Y-OoCzNOaQ^K&{8HrAJ))T9ZhzW1AJN12a)-{A_! zfCUhM+s^5?B==j=BAlzxzjJU-1|a#$z9+FX&E7WC#lMYW)TOQ%Nw&GYPx|P$fm{eO zS2x$OcJZL^b#+Nksej%D4)@@3UMCF^p~5-^g}CJc=n@aU*xdvrMn#d;HV1N5FuyYR zr(m=ndvGi{hC?RpyDKjdy^4M#fhvB_pzrmLuqEfWl&s7b#UQ13#sqBnc99cy^WOd0 zwr>;uOzgy#7bUuyS1|dcDmTvhlh+;9e4WydD`EJ>0KdR*Dq9`M!;Q zm+yB&&&5(~W$FFJE9_Zru!1Ai14f0z%bBq;I%s>{4$&In& z$FCEwbK2uK0c{@}Lzz_Vb*|1)6UJ zJGsNMX@#rgkwtFn1F~}@RwFrfsGEuLXpxve&W_mvmuI0EL7{e6#c; za;&4rMed^N!*~Jqzd^1;b_mJ78(+BReuJk~ z)(=2e1zA}?7obom&+0oM(=G1nS1V5%i_QvjYq-sEkPKv#xvZ%Y_A3~N1@3x99^zzY zXIGwwxreBWFLFTy$J2aH8*Z zuvK5^_jlOorupNCwWPW0{%b4|9mwd&q~Mus&8wy~jD(yF5Ef+BQ|% zR6grV6Y`<}eR`Js?VGhiFH%?HDSfxg*4qvAkgM44gD|e)48QvsKiX~FyT;aAf&Sj! zBua4C^kwU#&l)|sQpHoo&W*_9=HsZQmVsG7#(Ia*x0aL55#_zm@3@YhD{XLGIr|Wn zyG2Th^Q*n85j7yqRfmNJ{o@PQT_t;yfkMH@FL!rPj{`m~R`DGQylXGvO_a$6A%)9* z@2{4&F#GydLH_2#sP1cz*rhTR0Xwhto_!2F^2!V)Pl=y@@~(7bHY_MB))9PsHec^# z3pVVXgvX`DNW>OnbijHwU-q|#=F|0IJ`Q+jpk-2IDsW`3WIASu=G!0F(RX!orCqQb(##0Ma$ z5gSIN9J#%{?P(n`zMGF3_N(SnVi>szhPvN}W&z&>v+dD%SpuKG`#O)JUW4FTp^MY+ zUha^bAa|(ecDwKopGIAhkx#dhgfeex4d2Ov4QT+i2$RqZ8*@gN2jkiNwAjsuWd=?B zTopAm<$>^*55K>k%E(OY*GTX3;PmfEk-a$?dl~$cemL|IgE3$*9*e$JzYEAvO3v2E zJI9Z+eWWV=@neeQe8A`N;oh8?AXVMcUiaY(`t^%;2Bk=Ay~qRxRDRd~;g2}dH0cN` z^uiT&t5#+uo1QMT?GA+J7dv})dz3rm`Qd+NHF`TzezO$i0cnSX*k%?vqprA3qzbnT zq|l2dd|o`G*!+d~TEpGQXXia*q~QK}>&3+MbKi_jrCF3$%?^Ri2B5+#&qJ?e`PQp0 z$QGbJ%{o|>UYGWsBVJ45n1V;3KkM$kijOxlt$FkIjp2w$Na(R$q4>$okERn_pO7%W zx$D)~WiI(bORBDze4km(f!ldnwk)FA z0|a|SIIE9;Lb+J^qS=c2HhFTxRK<(j#J9c%%*HxYc|pKioP_` zXsbLRY)s^QQr%_Ibw+V>1xO9UdrBXjm8eNMNv6sm7^xYCC=VW#?9Sa(S7i>2s z^W4g`60kPv_!mA`!j2*%#pY@5SgVd)c4j6fO=mr9{w(kr<`Vb3s1WBtEInCaglso& zo<5Huya$HfqyD}P9&n*42>ST2>7RWz3#Q}6#RPG`^=BuPQ|_EzPWj9riOBf*^^lqu z;hiU5dsQN@QVssU+(zehOR<xRXuHO7eCro( zv3m4*DK`5`?2eK0iHupG%Ge*gXt4JkLTf#&d6lf@PL^To1?J<5Z8(wn?E%Br0K(Ez z4*s!K9pv|(APdAETmZu*J>?(E>1Z}tby%~uE>+!p<#q0?3hMdmq>ESbT};pNBW&^oe0@}X1npoLzxP! z9ZOOl%OMR2vriR_pVCASk+)vOUkt;|Ilm9KFC5G)9()Du8%5eG3UM{f2Qt!@-lixu z>HuMEw z0$L%<@Ne`?WyspnIDq(P+D_?bjgfg-G(Sp+wLyUMW~U(my9zj$l^=<1 z2L456zr0;yFnHcm%B-wo;UK&b2XNl2l<4Pxdc|RliuFH1?PCJe#JiVFjH^ETD`2_| z@vYq=_q9F7Eb0Y#-q(G^Z@loQ5p0p+fN|>s|CzN#q)PxCI|s}CAEwSaEUGW=_QTLp zLrZr`NjFG02#C@x-Q6H9-94m)NC*hh2ue3dcO%`++%v!X-sisl>En@ecCo)}ug}_G zBjmYx2`NqioXl{{$_(EX`;dv%E?aHchGE2#Nq66p>U`mc2(hH^c=TLRXvkm=pt^G> z;Tnd^WW)%8TFnEeNjpYg4@kd|Df8I4#CsuH8?HkPWncI>dQh6UykT5^nL3Fk+)BURWRjX&A!+#lsO49W2) zftr7Bo7>coO!R2mCw}*Ig__Sne2oZjUm`8Rn~YNb1H8$E!IblpbFUQ^MI!c#{!}zb ztyuqZOxj0{Z2^a~_k7K`aOJih0qlN&#E%trV45)uJV4N>1*TfVWS0;y=9lmVIWQzq z7_E=$M3vNJ@JWUdX~fDVr!xA;r1FhNd-g-|-3y|T`9+4om=SCnpCnI_##@lbAVk26 z6y*kAJ`bRbC6iO)iL^0lsSGJgxM42O(Se6#l-6vcwg3 zT!_QV10==JVBqoJZa}w#z((NZr=Cl>O^{&|Z;Dbo7(yl~a^X#|Yc>8g8S`Fi2=ced z?;26&bFTVIdY1|}D6Sg<2#S%CYE6Ym)~F%=0A{QSPonLg)B zr)~Z9v1DkLX&$)LGZau&Q4_KthilmX`*lB}$Rb0k@CjaU{R*2%W$}MsNKI~GZp$C?8IwUDZ zknGQa4)yEKW+hXcnpw9$JpsVrg=FG{2%* zwX8Na1Qz_h7{bwStZ39kpN2EK2)w}kMG36+H12rq?rk|ME@z5LO5@^lcX~43KyR9$ z0silI!yfML8a_Tk@a>=b&9c{2JcWq$)BV-u;H#Q(;O};|`T^-=0wZ3H-N+{t^PV%VetDQoejb2niLb}ytX!M9fyOV+z zwBHl(to~tXsOrd&lj~!7B^JKup)Mwv41rGuB$+PY0J7P8BbsS=KOyMReDEWJ7l1M( zU7iL2-kws`9R9avW<@A@;*9k48i9f0hVB!xa`bAenVT{)WrBqHz7BCa=%!a^F5>!? zTdLA#x<_QK^?&Lai}@QYG3lWZSqIjt0OYoC>aiNAUUS9lvSpCFwfc`UaK_Ko!Hd+W zXCPp^z?3i6NIzl4yCV>kd0)GrDdO9(kmOd`dF5a2=PBZ5sPCXZw)=Vaprhut`qsz0^NQ#66 zRXvD5AiA9PH}qn%wbx zRWpT%BWm({_4ZZ}08OVnW)0tUpm&`9aukepfH>ilL9FkX;d61IZ$p{oRTFga!lcuxiD&i) zUkA_;-W|sep8+)Q{Zjb7?vei3Jaly|oqfrD5+E*vJN*C;P9qf`?$xXvRiEt2dS4HF zfK0o&`#_xm>);t$m)3Q8&JeWbK}SMtwm9MOCFjGFZuO6&399jXp;M~`PW?{You8&- zi}t_TO?iB1`WgP-UH)4a7M_@~LNbx!>gl=|2o(!*`*Y>BdQh{Z?(-MPxM|KXfx)AY61E=*m!M8t4>EK8|FQtS z3keDe2GK>~5+GE_n{s+^2@5NoZ+1twV6kes;ORnx?!W}k03`NyU{xyuX~FYn-l|rP zjIyhiwZD59a6U-un_}kRS2B|1SqG?A)8UQHN%v?<9Vsa(d*956<~N!4HKd6RTdFfl zZ%Ob9O#>z6ZFku3CasKx8MoT<6Ihles69fi`@n-=v;v+j9fBJk)Eb}6^ba&T-kZ%g zvw~D-Uk8<2mcP%9VyK)lRtNh>T(COtH~ZbLN2+obU?O|Ds;>!joMBDrGt<_Tm+uka zGULZdTvez~z_A*=cHbX&lAogt>OW!uHl}dEm_-gt9E>!2h6Y^EllDyP(460xdUHpRX-X_lyB4f#&)ZrOy)dqj0bn*x^v%IMn-g+-Rf zFAh_jRSKiLHQx()pGmD9)(z6FCO2Di%4sX2CvVwlT*nqK z0ap+M;P#$ZP3_q5a0vizXS0}jvg4|#{ho=yA}f{05B*M9;bKS_tVdE&0nPZTtR5%$ zl-M6BpZmi~7M`sLnn0I_Fn_dav))o~Ea_#Z=@pRuwD)PeXGA{FJqPSIf0_T)tg26{?=!hKTv!Qt|u z#odZIbVpz8qrV(|RVS1!dF3)^-S_v7w5N|30i9LR+T9D6W8it#qUJFo@&2lxdFSlg=>nKy&wBiedXWi zet3N}+p#f9__6vyC+7ma^6Z<-W1iidWV~6AZ69f0erFhN@8Eo( z#4GHr&y#N5tJzjU@1M;USFMIf`?67ko@cn+@+z?ahZ~Tdpr7EXegV^SAXe9g7V%{4 z)SfD@)eRF(*;?*2*L;Aljhn-BPDUdh#!|K`SMxW0Fx5&YD6$!BWPB8wRhj`~I7>Y7 zorkno#gbHar=L47h5uke`jX0p=~FC zr*tYt8tQ+pct30M89=J*ecqef>04XM_x^sSRxO{$)o1?mo5vZ;;ha|{L0VL2Q6dRN z-v7)yY*4hI%^RaW#xE>fo^Qu6Eu$f(WgX`%fu2Fev!0!jpFbv;cV1ieP?_hO2KbDw z3s60{Wq!V01dg@#|Kc;{h)bOJ(|x2|x!cWm+OdDylz1-oA&b()`+ig96fiVQhbN)C z=Q5*fm9^55>qW9MeTC}?9;?8czJOG@XZl6ny)!jM$rl7W-7!^71NYH$>=eT8@- zd4mydY}tzB0;!HJ06&b2CI7bN0XeOLqyQD#I!ARKb4)ehWAB8%EQw#C85~P)-Y5e7 zGQRB!30{QDda`>12W#Kd{^Z}LrKV;|v~#*44-F1py55(cq~>0C0R#l#4+;%dicMEL zezGGgwBxKS$W;kw-x9^7*=s}JJGu5>f%vK_5ToUGR1YlKqJy+lNw0X)S4L9@Xr*fJ(Hy1Ur+ zU%uGheZ}zz?CT||Azw-wWs1Rgs6s*F@ya1KK)UB+q}LzY;$($Ky|hQ}6amL5PB}*aPGq zO_PktB?y>(6##K3f9rkTg@9N0*D`+@%;TXCm5`aDd{+S?; zc)UOF05n(Xlr6)E2k zhJE`@56D}Y-*gCGAW5!igDDj!fOTQ45p(jsn^!L$t3dq^0ZRS`m=esPSeDO^si8cZ zI1qA;9YG_afQPj43D6-8w0T|tltO`+(gRuZO-)elDCcN4+6t^ZL!at{nA8K zELb^DLETu#mbQw0d;NAGrJ){*EG$y>KY(96Tv8-w!Gzm}ND;DNOc#R@fMG;mj1#1& zT*7AweS(!X*l|sAQ&`)07#c>XhC3?F1P5r|iJ5$9}dau8nY>Sp3 z7_hw`+l#b;C4mSmJlJX+K^)0sLwF*Rk)CTUWm27mto>5$UGVP3r`)FZE}SL@{S6?Q z<*-7jM2jUr7mCgKD);6Mbs##u_xl|F23MT5euBI{49VZ7l}Y{Hj23i`^ND^w=ru@c zMly@Gy5;p+E-y)%WjG|M8{u@PPCyYa@RRw$!U^BpOj4h9`d$SSmuXnS^>aTIhqulo zX5fXXCIg}!3;HvuL`u^9+!rn!iR5U%iGk5_`_(Cx2x%iRSbpaUC-x=6&+nos>04H$ z*fF*93Nm6il_jWLoZ-(i{4!X1&?nG@GTGaAVZ*;6z@sm}st_OpO(zlZbpE^=f-c-d zpQ3azsVZp?I?8`gvP`P9w2!vaf+!8!Y(MF;xBb+Eg(c#p% z+VcHM_HZz)>R!eMSn0kYwS6tB_lgSC9s}3%ngclkTls|Aw_`uboWk31>6x-T1+FL7 zPJa$$e(pKl#S;RAG#cQ&MLeRDfhG2qW_*H2<~JE;XOJ#G;kH$##+=!2oNu*0eme*{ zY@;P^FQ#lToaO?iMKEKr3VU=|6a*vS@9w-^Wc}Z}*USz)cBZ)N+3;I_Va&SwNZE`a zg)7~qPg7w7SQ~~Bx3CHq+c4g6=~2D@5f=Nu+Z=#4kG4f7=gfCtd5tQ&uo2A2%2RyE z6BC(K89iIkRazU>+8n`=$b?;kG5FyZpnMAg**fF8&|2Vk41@;BedU8b46S`(_#}NB zD`Ga?WeiVb7#5SLbeERZPi|B`#wEEMEchAO0aLSFpZ|A~&y=vZ)8RHKw=4(N1DXnO^w z4rDdYN913c00pvpiPv23eXej4w!NT2m%dGm+vHwRGF$c`NpWahh=9l?NVuP*R5JL# zw4XgY2Zt{})RtyIfS9U_6ZCe3VMqHB3lnp^5HPXS*Ygy3mzx69{g$CXg4>JygjPwd zz;daw|7XEE>2+@>Bsd&*xY*~`PPtW4am$f5_hTTd=_p$Fgz(L z%MZ-PCKojEJ%^KHlc6}`f_5}~&p_l1@xpg=RCdFbR3K2tDlRk!7-GlxQCpnmSypV- z9p=H5wmV{=jFO4EZnm33>hLvmZ$jU7v+9~;_xn|IFbc78i%FfY6iu?|qcT@N@8$r(-Xzz`zbGCyt>l^8NLcTM7ya z_oE-PlgG=g`xwTz;JEmBQnKe~o3R3H3jG>}cpGW*Obz=cCwmc-S>xulAXWs5o%-3c z3YzuJ7YHZ2e3Q31kIpMCEhy2XsQbql%FH};f2p1SU7Wla1I69j`q6)#kq-VyD?H~K z$guRT4evIql!k6=tY2mOTrpDW_Q83ZB-w!3>EU(JuU^R=e=!&kK18T4PnlOo9PJ6n zWtw}@(dhTjH=RyM`9@3(3=?olEE5RHxg!X^-+sb=jl*JNoMX#ABmUT` zL|j?l^t3k5a4sO57WLB-Fy$^})a^A>=GEemh2Z{A*pR%*YurI}a8kd-!~@A{&qM!2 zKfU3H`mj15L~9qdfag4uCJnNM(SGZwTqZ_FQmucT8m&nXb^YDLSb~MFtLx$CV)v+n zv)I8uxEFUbqW`Q@1Dk$>VG7DNa20RjtwcSbIHA4cCbYOHv@1ASGRr4)Ip zwcchoYMV>-@L#&cx)1`P}SmpELnogVh*R_ku`8IO-rLSX3EcHnsKj?fw}+ae$A3#f>4P=%E1Slpj$dsn>Ob%(fr6Gx8!~GA5ZRozG@GSDU`Yx(c__eFpqWkH`y$5 zuJV2FmLL@;J8x57r0X7wYm`4!e!8C`ndq{v7LAYreYEg4>fkWO(<%FGh%gi>5Bsg| zdp;_Bz^3=zEPP&Ej#a;7&yp;2WyJ`ub)mA{lVN4qYqct4$NTZt#rL>**Ban`>3e>u ziOes^`NBqpcFD_BdyGIx{7x$>+-2HCXurat!H<%FO(jcrp6Y)3sVuYW1SU4#8qUEn zRus3}nYM~>NWyqUMR$L!AaVv%}w?RNg{Z>HhZXndyOjE*Qd zRpsuz8ZM!)pEKMl6mWxmjk{4cr#t4}<@jRua%`ZeN&Yj;Jc!hWvLDn#elmm^pdoD6 zNbJytbOv%9WD7@UNABM%53v~jrjlU#h|n+fg4EQdgq%CWWohvm4ff$6B-yB==#W6T zhBwBj#;$NS;m4H6E*sA(RnjR*hNyKb9R)u3M%c9kFBL(+^OyD{2^YY8r`dVl{5i~O zg#9bv6*PJch8HF+i(H3OBp8@rfa9cKZWIBp!(!(5*V zIj)N)y4eAc*i?!WuqW-lo9Cs5A@7Gg;=vw0-;;^ScAEb;{mMUN2jYN$l-f#u<&W?Y zVo8bQA22Tq4jKscXRxo@My9SnZ>ZyqEICnc%urq{T+eh~BKlmP!B`3nsNm#SBT2iH z8RLKJ;D(dooyEIi3X46cuW37y*Alwjr9=pLzSGrU@+i0}2>eBv*GOz1m>Yj`FCLt| z?$x$Qv2(fNck<=EkxzKw<0jSAuK0~m3+(x!Z1)my+C62EC?zZAZCE5lVX`ZpnCj|g z2@O(y;>M}1tsQ^d;6^xu+xWMTzQq+^iEfd6r{7DGznk`rZ!@5ir-q2Z-A3nss5{d?$Ha^%sgl&d z;C4mMj$7LH%Sq)1m(AXNN4I_S)H^?60ye`IJRrK%=+~!DVCfG*;j%c6TW~7<9e4#A zBD?~+A3N%4$R)=8#yrZe=n4z2RP6aFf<&}?5%tyw<>}U&^Xf9e8}DqUUWBEa740`F zoXSEj{w(S9wAj>fRi)K$d-99DX-Vq5Of4et&whZ=^J3>y&IoLBm7Ia8e7E^h_!Z%Pa_TnCvOHD3JrfE#O zHs6h8h<}c?R&RiuIL$dIUxuRV7&1*#S!uM5*#79-bez{jZ8$r za#_IZNXc|np8KN8@9#&5EA8C$&nS%HijWXR#E651&9t?;rNlYI`2{Yuluv3|&}0HG z|1!Cf>jFhIU8Q&;8L-Df#?$!jye5O=aTPm(#h|O5ygMI8`NBCwqla9zFZSGxXFvO^ zz3=zx1mB0-BaXw5YRoU(FXLL>>`_0=aODI(w_J~C0a2h~X|F^}Od z8jX>mFmV>~u!=swR0pufo!_c-X$AeYG{|oov}!s$u_m_&Ab8JOM~MLciUPbuWZ)~P z(Y^Ur#!s1_j+rsKCf!+eH*`UtjytL6d=5AVAOr}8xW45{k*E($!>3MiU#;@}FbPn?`5%+om49Nm zPVODs5?!fEPxq2Z^#D75B)E(t7#Ib|(GZaEyd5(y5hybPHX@kzyR*SO=P{H;Xyv)o z_0-_N&xC=tX5cC|ON9Pay~TDisi8J?c$P^xP%9a{6!;AgX;Ba`>$xwA-2Q+$8z^S7 z+&~~WK2emG>=&*^R#VHTU4&A`$&P!+?5+*yS^=%+5>U>^KF9+{Sk(Mz?pIh-7*|j3 z$Yc1gE;v9F0b6FpVa$JQ=jU<+!k+CesQKKnNvZDdXy@+~~4=xZfT7HWt$Ky4tm16B_%PEdtjx-4>=ajqcXuoZN+a|}rtU>C zG^G$PrbPcK$dtFDlO!#o7g152_CBCq#D*W?h4E-2H<}C`FlDU2@ofQ9#snqAu&*_W zFu(nTt5^Mn0m+r}#7!Qa0t284mvI9zrA z(3_*NfdN19R=uAAXur7N>+>I;I1`<-uIi8z*!w!cp|DA0#75?yv990+j1OA9V!?MT z4L>>}Q6l?9J>r!T&KG2_rQuCD{X2>BKL>~VT+Nr1_ptK^Qwhy9RoNDhOxh+${ZdeM%4uYH-I}Ovs8{mHs2Hpm644q1wEWU=q`r0Kbhg@02 zgnkXfv|RR>UbGdb2LHQnXs`fC9E8R=jTA3R>X{H3n=iDBrf><4|55>--1QR7eWJXA z>i08507=b2#!AQZ*_cbTn4x+YQN=7gNR7b>ZKNCKL5Tw0G6!=$hrpLxxG8b%8(`6s zq?SV4d+Y?X@k9JLM41>ZV9Dmh42}r^8|5`ML#f-LNuKhH-;%8S z=+;jkElVcv-ihMW`o+fcp1XAc2;+C%UFI}+=+5%`i%Ot~F7BHE0L<2havK;$uVGGsZZ$xBS+dfLtE7kfD2 zv-1|ip*M2ZL4^~;Tx0-f>(JiQ(4N%v+^<;bkp@MkUUR@MN7L5BQ{%>1m(ME-oqu0lT(}jt(d{56^ySj$_fkf3_#% zBRNw|+oA05&CSg(fq>9BY)Vn<(J!bP-Nr#rSE+e<0ZMIJS`j#acFG1|^jqF;IPEi{ zGPC*V>fz0EFwXRUg5!02qFr^}_APC+G5mk8-@ZSAY+IGqqCXL#Pm^|sNIv2^x1(y1 z9X>w?`mR2#$itIE(lRop042cY?tB}bmihdPv2*V7hW!1f8-tC<%QA^C)zuuV92}*w zv6wBJ@gjSMC%(i3?OGdujGqdBQ$yY(HDsK4^WfZg#7}s5>yTDt6d3L7Cdx9!_Mv%At52j>r5zA?Y~ss z33)0$Gc_L0ZndS2KQa42TU7bxY*sa`C|O!sUJmn&jfTVsbpKp-OOVIGLGsiy}9z28xJX z&zZXe<(wP)+R^B7+3e;f)JtNaXXr->OAxn}MlR*M5C0~XFgNnGJU{hIEy)GAbqAw{ z%!E^J5~-kJIQ~aQ(2?1;`k915D^Ffubj)ab@4)^nqI3;zq!yE{(ao1O)vv``KFTEm z*knh?*f63thohz8(St}!8pok88najPq?;JZP(O>vuN^vqGwDf0K|Ucx&dx{ffPY%~ z+?JYMuijVl&gSLib?kz(P4i^oF(enWv$OL5u~m>$LIBI_Nhh3HTPxTnA^4t|ovnn3 zh`2+8JHdQ`#v~+>jcV6+2aS2!+OjZL-}r1uSbp&%{1k(Z`ign@NX9E&~&ThLI<$p?02XknoIhRhxuG;Eq`!5tD%(Mrx<%2@v7lp4-!`E-5(V zRTG%6{29=QzHqG4EmR9x@=P8AG}V`6qz!R1z z)8&*}R(PHdB$2aI%0)(z4Iu=N{83XrmEyM=LP5qp4XNZk{WqH~=@zb}V6rR8T)xl2iL9BUaShbAFG>(djPhy98Hr)?TeyD3@ z%5kA1qj;${-LRT3Hg_?vlzptf(P6P1;MRt*(t1DSE+p6Gbt@dlbk6EdO}JSW&Ejc~ zU9GtLi)WdRxmKB0-6eWI+Yg8ts~z==wX#>{=QZ&`C0aL}#ybD1J19W^b_nfCo)3pZ`x9Qw8-@GwoeZ12qKFKQnqon=w8~CblOp;)vx}Wo-SJ>_G@K0rgfH`fCpVvAWIB7hO_ zk{R0Q*A3H`gYc;5EhKVItpxHc&=Vn2iYl)eAlV4!nEY!iF>GE#b@a;VfB*Oedbw{+ ze6ZxrCQ-dJ^t)`(@4Nv@`J1Jke~mg=Ch{k_eXpMz>%5wlDAcp#aN@a+{)}D7Y=)$y zH_VB7DZ?^FF2)|3=YLHc&R@hIF1nGA#D^!CyPAC>SD9lU6K|Hay~j+Q+Evv$iYqHT z8Ch7$4qEZCy=mLD7+YKll~on+Hn+s^kI}f<)F01oGBRN6gy1-tyL>MetG6T1d)t}2 zPj9?qd|>bJ&p*ML-*N| zMxR4xUN1sm%SC!^m)}S>pIU|1hYx#UZ@kwxY|iTGjyFwFd%K+z^q1EB?=SaXS0Q6o zfUJ=zQ^ZUTHxIcDYbN+GLSw^z1vFTzp7Qt|n<^Iy0xZ?C%9?Bpkr2YT*u@=>?Q}W6 zm&#_OA_K4kaDXCjf(=K@F^*Ouhp5rFzN2}7diA|ipsb&Y}$c;ka z+5KpUSnvDR^BVc-{Ih=WLQcnEk+E6}+sh2Ppj9232W3`zC+(2Hwlj+TuLP*qOaB6Y z_6mSjv%R;dUbaJ9UAK)7o@QF)$6Po+^qvc32BN%j{B_Q>1un3;ghyugH!sA+SQ?Cb z=o=Yv0K0`6e*nNsc@v7#e95NYIP76%0BlXvzBUC0uswVl#0o5I-9PK2$^f$4W}1It z?B={NH0&v?q1e?GfXxjZA7$M52(%YpQ9^2GDdl(G;7FqEO=m{Ncb27;dUuXKvpXfa z_1>hU(yL2Pc4Kq>d%HjUk8-uYj}9YMh!=8y;2Ug}Fq|$hL!RW}$7=EUMQ|dj)UV&S z5BEoYM>!I0*w`W0x1j;Gcc_blSS+0xSu?$p7@2;zgRo{au zHOqJoEtNU0(2(J#WzU@H8C&86(%8zLpGDyq#DjTWD=b#SIlH|rkB3$gDR5)n{A<`U zGAt2<{+k@Zf9WkQ)$Cc&$TunJ?`bhUFH^W{GFGLxR_ zx1g@93;J<t1d^ES1d7+1jsAWJGb(VMBG$I6HcxWC?z7;;j5&rR~=Dqit??KpCPcdFb5W zV0}r7XHCOpo?4BOl|)ZUY zTs|}+OT5&+dubrSmLc%RmU0{7kw-!o&6nLz_$=2J9 zDc>(0PhAlJqePjS$H3nNrwG#<|!t;X{Wk_bO@zF`V0=qR8;fOPGGwrM!& zbj1bq-kX=(j=Kaem~`>nWCSS$BLTZdRZv54A#y{04J6V|^n(9m)0M)nF*2MnMe0&? z$zJJp=Z4ZZE9{dvzH&wJunT*b+#P3WeaB*S{Z7}C)! zazk3<2JL_fJGeA=dbz`o)Ann__Ou(_nkzfJWqECgL7kE&Pj*1tE!f^i+qH z$xqu*!}7TgX!6)xvDS2w2wV%Uv1be+g0v=jd4K;bJXJ3HUPM|Bjf;-m2X%;{xrBu) zI%EXPBMpx!rd0NA4gM4RTemy@)+(h3c>%dM$3-m|Y?4b1V$4UP%?h^h;3uZSt*}cM z+I(T)e)lF}%itjI=Nr0M*QB&;`rU*n$F)H@-N=YgQZ@orX)yhGItaO|QPf)&Ob;9! z+dmptIKr+ylWbiZ^qm&ao@y&!kC=qXq)h+FDrO7%hF| z%QyvE;3JYIDAQtkEe0g@pTmvaIn_k@z>K@9veGmXvd|fq z;6IU-OXjw5ad-*zYc!Gwi3}k~3P3WAzh=p@cVEud<+{+M#H$~cAFX8Mvyu+j!R&_Z z&AK+OeuXbW9&Ag{7E!;h%OtK05=4+yATfjFY)83_=z&yVt^q{hE)QAZXLa?D30JW& zb5!SC;#jq094wQ1C0~~4fbDNCE$jxN$5b`jsN3Z=)f9?ABRGEo8UdfpTkgL`_}1ze zr2B)d_g3O))NR?9R6@PaIZP&XBI*O!JhB3%Ht2I(<93wxfp9Vxn+R@>VeAJ^NC9XL zW1Iv&4t9|arQ2&tH2I0&4XB0-aZ~3nc6zAAslVxJ49MZ4f3HTB$)SuxnNfw>fLqv0 zN_6}wNP&73T>}(*0q)vLk)+3~9c{sJ7eKYSSNWJQIJGT?w~V?3l{IT4DO+JOdDUT2 z$~4q1b%erEk(TEtHuUQ<@bD!f9uQeg0HR~!e2I@ojlcjpqUwcF)Ho%pd;NXb&XK_PU)qVC*fznt??)9GEHNU(`+zgvFcjz~7efyz1{$;1x|ds*9>{h1 zmgCsu348W=|HT4ZG2?rvYZ0GNtQRMQi+ydcP#D|UIs4JZE{j}D=O7xLq06Wr7lkAm z-Wg`qTx#?HPWCOviz)qNF38|GH<9znRcx`d!j>z3fNTF5uhs!9kJF#bi8+#5H>o%O zvusHS7Aq_n^m@`L7QX=Wa+73uD@n2ew>IIXH3z5lc(sD=g5mA9xckA|$C$>Y!{ysj zdWL=# z2zlY-b@RH}TDuXGrQcQ&&qH7$w`o1T)h4+Qb09^Cj(hu#LVkNK>0i3FGquUji_mph zN`x1|Nf}JBxahyx5vI-^mZ~;?3?6JJqd(D$un*KfVr+N*WG4=xUmBb&SmG73)2>#q z4E3**jwCEEyd_3^+Y-$O^r$(zd=@2Mlo@z@VOoH1i0maSBZVGc&iW>gG_bZs?3czolxxSX4B}&jGLl(_M z)+u)|8fID$8&wE|i^hpOJ(MJy5!T$SqLk3+j_5{hLangR7=Z?i$--d^O$F*~;A!7Q zN5e;-RhPSXPuTU)`Z?!BZdp5p7a6Lct4ZTh$)@7AwhtMBzU>iJtnXPBEr2~z;<{hd~46q#i37*AzJmVh|>?&6! zpi=|Cp_Rlk0X&stc+??X=pUR6bl=5^w#v@hk!7-`$hq8QbVW~o!Q~n`H*nBUQ2OMr zq0K?qchF28i?H$95k8p~zgcxFQoEwf9b=Mx9WQR#X?z5ty-LhDjiFq`2VS&9)1TFKxhnZuDg~4SvKy9fj>}2sWvOZwZn? zkC{pKqpe@~p_svTCU1S(uR7c^_*k~-<(a34uprqdJ`1}K?H^MS$DT0VWwCJhYLCk( zamf0J>b;m;3(Pvti*9M$TCtsPlg}X2>~UOU9@CeTFaetqgI+VN20r&L9JUsB##<)< zi}eP&O@c-B5J<-y8rft&<|U;UUQ zp@wAB8a((RcZ7f5)}8ZOwefS+rEJIL5!Tfl{!~s1uqzVui4{h7&yoCqEQ#jamq3+q ze(nmSqPP=^9{;#GU#Eor>f%_^*49?g(n@Jvh2}VxL9u~O^-T-rgNe^qr%1$44@ks~ zCgCEA4t35wtXAS$ti6`$x)38VNMtb1%4Dka)KQ#xcFhof75O^#17kQ+3q6DgVLa>y zaHothK(x?HNEid8))sK-RZ?$nZwity{`2+m@+r{l@oJm<(cLi`cx4*E;8#_%vD4?)-OYWu!ld6m7A5!Y;_>0HDQW+ z;=tjuFDX<)6XHz=aYd*FLbuWF0F5H8epFZ)h~ba`vTUM(t+h(W^^cl?BH0*Wiw?J4 zH4;(p+HZ!fI_aFo9H)rSaU?u)07xiDQ!DN2F9}ccZwVTT9|&@sJ`0kbRA+IXPKxfRU>O$1U< z2HJcsYAyE^&BIkT(M(^{&=kJQF}cZWkw9~5wP77GmYIHNQ~m9OiwD-xiEX8j#(OCy z7A>iMOINcNn0Ne4gBm}?UWS#Jbl`n(?~MZ8AJ#27#;ev-+wGjk9@qm3Ywb9xq5V+(iyFO&0 zD|cc3#svlW&9?NcuB2_}c<`5ABN_|3WtPzUuIT!g*a$P49BL%^UNk*Wv;q@Xr`nZA zb1Onudh6-kfyLD*of=5R`mXU-y8koNZO>d&_~TRIteZ$L$yMB6AEd*6i5Vtjmm-`2&F@>(ahR##OWrBWX1Gqyd==#L(64Wukj7|C3K zuDNC)DXMGOoXjoBE}-1@gDiIIF(tyUwRxuww8jJ=-k^lF;s z=WYHTvK*^qpxe}fioexG?m>P#<*o{p3g1Uef|*&lHU{hiFdn3&LQ_NRRm1Z~ilFJG#;_r9`u^yuqdg@OhpNWC+^ z;Jg_(e)ir@!F%XG&+D_aRBSik6II0{eP#I&&rLD2KE^bc(EsNrVXgeUd_Y7?ReK9p zFD_E5sJ{c(1hYg%jml9zYmkHndqzN;>_=?njBJ#rnOoh*wmWGM4J^2h&P09~1LKdW=tn4;SL+?X2#Dy43jDK@T>Zy9G-~KU9jaEpDGU(9- zUPE5=E<#%igPczQJID`ZucbzZ9C$_U3V4g6{(OlGr!*oLbe80IT-tj)DSYov2|_@7 z3=a?IcHbKZ8B8gvqXVW4?Fbwyj$*mEe~s^laB2uE=4dfENa%L+d44P&Z!RMsod7{x z3IJoWSiX zqleAj*?5V-%$(ynhq1UOzZ19mgE8D=Vb{fpfLn~-UXs4!9S3=r3#_S|7CNuxb}H7O zREdKG$%Os117^dU96{nMh8>qzoxyPp8GL*{1=`mm|;OJp< zRnc)eh=(ZNuy5gY3Ao^w)a(gx52Y4U*E|wLRC&nZ^!xMz9iES8JxlI= zj((19%YOMehC%Vpvq_8b$34be*BSK^XIvs3ruRlU?NCbTZ7223zgd1Kf`0iA2fc^7 zS1nq^|EIOLev2yL)6g>pVYY>d5vXN-!z`J*p5X<;n!K!wWR4T9Yj6ry1zM# zmS6@g_+|o{`N)H!n=KZS>_~b4Ao8^oIH|}3o<*k~`$r|Jhdjn;v zt0aDn$f0Ah*;HV)QRK?cTd9SOTubX(nl;N+^wlEbGSW}y!qE5F{xK*p4aZlh^}s`Q zaDTdZ3ou%YyZyH_WSXQ)J0|kntm8O9Q`$_91n`3^E(xy;Pb+;di}e$Lq~HEhDx{oK z5|Zmz#=3ql4J8ahnF{h$&-P&`ElQZ>-n+6(`O5AWTX4_wgKD(DhZybvLD)FJ72b?` zaOglzhljP5N3R9OmSjsC28j^Wp!L_Vvg(Z>Py|)yQCc5S|5}>Z@1&g2Z$0Lhwa_fL zTki}GAn2Y+uzFfsP-sx+(Yb4{jFrX;^9JLuBciQsFPol^Mtx{-v}}zaiCx5U*w>>J zK{Tcdxe`h#S#B?g9FE^{Rq6LZj2gW7)Toe7blH23FVHX&UoB0(Nho?Enz5F@0r#7g zBdATSqpSyuHvH#4hZo!LQS?J`jxe&(BYvnA^90b-ynh3y9rU=2hA6q8YO)>=7n_l| zxeqo+u#h3wfs`~~&f2aG(Y^_bpB?JccF_nRJaK@ne?#x0@VCbXYEbilj20c&qYQJe zFW2^HViP3Vws#9`O@gt&hMD0G)EN1+s93V^c~~^J6$RNgsT_?*lY8F65#{;j!ro`$sK^X;oqj5N5tLv~nsVs0hl3*4OJcs<0 zWGDQz`ovju#)wt-JdRH9u8hB|#zLviO-Ga8d3=#;I9xhOL6Zjn?H#}7f(ms=yL;&9 zMVzQ0)^4%(J5jIaW2vL3Qkz)0ntL9qo~qe=m%bh{%qPnYn-r9t5^i@VXxk}ChI zxXp5Y`E`RH2Uqw|MtFS1@)x9ragKl<+Kmo(@TB{d3lOd(*(vPP86$W!`q}8V-{f?} zOHslRg|NDsX9A76{>))X?4{&_Mh=BPJ}m%r0Wl}CRQ@Zppmp@+wwlP1^9BB+C)FzZ zUIW=FFYcSxx{dx*S&(iEee~V{)bUB>2w?^oqLSJhgA{nFX|TfnPg_q8&ZJp7%hN&w zfw&iB-;1e8x*jqnNpq8a|J1lO6Y;z8x`;5U{9AT}k&4#PhTuEJ6&6*}CFl3wtAhaeNI+;xiaO8l)bI6lXn zDc?WMby{^HjA!wx?3Dia)W8lQa3si5`pb~Rj`fi|G(I1dTUFol2z_EsX6u%WButR$ zr|9iSgSo)d(OrB;DX`*GIHU?!KT28%p&c{9up1Jj^T!9y2`d8ocUf|O8ES*&wgYF@ z$Jit3tv_cC>@F();YFn_xL?n{r2hr(f)XVrVshh9vq9{%A=7`E?1(|(;(c}vVbk%S zK@rpGrj0V$Nl=3jmc&_i;}PGw%f$o^L|Ip@ShFLM`#)EX!~}v+cWnDEEEN|aRvz6} zKDnfz2}6{VvN|p}P4gDbGr_x;_Ww!H1Q}>ik&1|=L|$XzS!)*1Y^1D zv`6VmHjs4Q-H_lb%?k*`z>|WD6$S$5(`dF8tKizaO{(hK=^u7@)E(yi_7=<@_GuSL ze4T8FLy+sNK)uZCfFFV?j@%t{r%D0g8IN7GPpPs+owa{o&xr1aOL zFo+ZR_F8RFX=Zmb+Lys`B_fBJnVY#now8R{HaiU>Kk2qUY{*YQtx0<4?l)wDF?M)m z>nVLejp6Wu4(cSbic@1eLK4eX=_;S=mr57n9GK!n0MXQyBHuP;lz2$Y;kj$(%1LyW=mD^u4D zGyYS=ha|{Hy_{F_avx%>6hAX%m!bcA=<~{xazhZ~D|p#ZyE5?+U;j-U5G$e4uocr> zqu}q0irWPkUahxa3L*tm2G*&8JrAU(?Rkwjm9@ zlPb`LSXZwGXfB`$(yRJD3{cFsmUrG7%8|MZNodjfBLN6Ht2leW1i8OCEzH4}m8DGO zXmtXiLA!=V;vYx-MK~hLvlJVg_Cv!*I*!LQZLEALJ^h-#ys*eL`cVxjU3yR@2Jk+; z2otR;dRC6b&a1zue=yG*jeRHcJzR<4_<{3CHX595jJ0bDPDTYAo(xV(g_%$fj)^QV z(j>UVrYDorKXX!JM82G0<1)5UYQWafIT^=wD7G&94W99m!Bx|U+zr2-aGi0U4a0KJ;!yGf>5~=G(XMe-AR-P;V z!iY;Jf^*JZHVo8VuSCrusi~uq&F?2M zi^3_ijW^}LxYW>%lS5xYA;b#9eHkGx_ld5i0x{}z?P4IER_}&pfa>o!t*SmS#L{-C z;eq1p`dVQuSTIRKN`nT09*`~ z@^V;{pyc{`8Uy5TlrLyWDO4Prw@1_G6S!kn_E&n{OvJQ;MM%^k{I%TNe^bmdzXR!K zy2s7`6amMrST^I{emmcPL=8aSzXh;gVpCHW8qG^w$V|U{8GMP6lW}yc^uF6GU@m&H z?z90@H%76E&Xye^MK_PZn}S3z)a}}U|6L{>KhPPN_S7#<_>q}cH9@ksb{FfS<4KC+ z^xNv>-mCk!ny#=8{Q3RKeMj)*y_-+o<1q&82Q(n8yz}c;n*a`cUAUt#Ih{hQ*ESNM zp@}^2_Y&AbwE^YP9W=sjm?6hpx_4sPH4k2eI)S=ZK5a+7?-}FjWW3{g=wIi&pa3?=Ox|S}eB#7t+!HFj#}MVgA3n&!8S?TfHnsO9OJSqz zTBh;~rP%b7Z0QxuBb5cl&{j^jn2@-9KM1osr+Tf zVSN5&S2FtBnAP8%F(zQo?&r-LWjKsZLOmQLZ&tv<_}H9)%lVgC`A6*IC5bE%a|;i% z$`*Iw87&sfZ6IIp6}FTC9{6V@(NdjVmS{1ONT4AGE+m>tI;x&iJZ>)Wa77yNaz&{jaVyt$)}>|#1FELvD{bvA~#cu*O+7l z08~8NzS8FBm$njhrF&}23cc8yRNuFX8c+=siF+ALK&oR+bg13FA%dFWc%Icdq^+s1rAMO{NDGJaBxmjuvHrb`TvCi28 zxQQ;hy$uZwiukM9g#-86pyKp0x7Z3rU_2M-?4K?!8g6G3 zL@LZ&$D0Dk_PPD)y_#xHe>|GM1ItQh+pa76%VllTrj$zPD+$HYhr6i{{p?}f{PER7 zdG6^0}=?_8smsK2^5o@&OBq*I1)M;6}q`>hexmf&6ZV|k51SgNyIa# z-gc+T2Pgn(sHohDrnJSx4u}k2I`QSNZ;ueZwlCVXF>UlkCjn-C*SkIF%FaeJL`Z(S zD+`}J|Cp$y0lBoSvU zEafrNS!MA}qa?JmLM@sz#6t;9JLwd+{Bm=L-CVygXjbNa9OkOqoo^0^ZP@ry?H6RY zYK1z=g~j5k*-7xD%s~W*`VbY+B3wGejp2>KKjz(dw4ca13=Yk0j~aWl(%?BGW$&u& zC%ATP+FI-v+}lxr!B8C1h0WfSR<(6#$&4cWBLdGw{{g0x7%I#-~qOW}~2A^rO*_i%2=*G`3*6u(tfbD{5e-dH|HBg+YLt1h`6gQL1$}{ZwUJ$iRfnayh^J=gMYHE8~|Yz4zu_>(g2SD zgCCsVK;z1LoTKPZ?YjJ+|D8bC7yUibvw4vqk;3cOb5%<5t@!0kdPZp6|cAFBxbhL&p z7Rb4l7wtyX)!(oIK#g($$q-in*;$Zz_|Cg}SU9Dma|lbfvie#7g3o)V#;AdmiPU|3 za=WCs?JB}*INUI5@IE%5EjC?k_@#hPMd}3U`~k;l=?+H@Sr~Im&s^rY=Ur&IidwmH zR|Jlp4tTe*Q=rMkFL>#pF{)!)xQxu(H$eOEkA{XLezOj=l-BQ}&RFeUY$f_34;Mci zY+-jo<+cevrqlcuzmF1gCQ|r&`Dc)VR6!6y?~jK&C{-=@uH`MccRnAWQpO0q*aYEuHKs>r%1-cGqTH)c1;@Bx3cv2 zc%4W}0{s0w`61YVnkMsw=whA);yh;c)7PYK)5^y_A2Z6?ay`7@_o95?zzp>PHPhnnG~R{o&KO8P>)IfV4J2G z8T1q1s19~L&+Y0|FwUXdS7YG<&1P3Xihqn~H876;#Pnnk`fyHlbjKtU=hxz0^ppC^ zbk?rggkod<08+xpE5Ias+~im!^Ci~XZot;VXWABz$Mw~8vdWVR7K?`An+_N{8-D{jisV5>+7L*i637z?$({E}x$m*1 zB2Q;Kaya%xk2|u;w<$V~StdIH6f(R}vUZ{?q^peZ^8h>%x_QRqVnM@|SywjAuOvfW z0-U>$H$3oE{z%m0f8Ja!RgyTK2=q|yeLerjqLAd@U=d(z==vySkjeJplLY7leI=I- zzG^GM@6Q>GKl3WB+&YOz?ZhFjh?kVrvXXt9@&g>}c4a)267Cr~SKszV8+`yTYg+T$ z2&Ix9m+Usq>x*}{ov*SULuJ#b$Kl{m%VB(e+xEAYJ1$8vA+!y5DK3p4og2&q$!8G{ zVZ?T!vB0i={FApzjnM%~cU2OR7eH4XOv==tQC=n&xm!YNxFRO0IF8uKebXUpFeO87 zi8PlUt<949t}csTqiE1_E6wjo<+bXRy|T>IrjfN|JlMc`i|(@o*ca12T&Va|T}zem z`TDEUPmS68CRa;;@B43i$qxtBe)w(gU!H@+U~W=Y)h5_U+n0PDPFm@eWfzsFqe7*; zqS^_xnziAzwTgU}C(LZnE*aedrGGNTT9C*iq3SHx;C0r+d%Za=W{yzP0r=UG#KS4- zF;BnvCnMUnl$d@BgAKTQvw{H@TVBc7`@8|NS>o7dPuB!(?_~~-c|FaeU^;8az=?kP-JS5_I`j$X=pPOXpLa(}RMABn%gU*zLt@XkOOr zHEEsUobc}X_DSz{E8L0|GRr}=dKVr@Cg?-$uLfL-+MiB?AVz7xM$sBa7L}fAKRi97 zI|q6$=NQ~F6%2M8dXTP{n^t&Q#~JL)WV=C=^X-m<{LgzMIo`)&Z642tZ{{S;Hf$v? zRm$Uly?EmOk~<^A9AXCKDWS=y>Z?=lp3i2LHbqtznPL;^PgVrA6^TS(9KM?GWypsi z^8HPsW(aN0UC!TwS{?gV>xS%9kvJ8|SF{PS00}TMEQeCgPZp4*)z7!`=a=WV${u?m zcV?A|B&O2aEepzxX0rb@?L;*5elO$7MtJrfWNf3_+vGe-@3DSo(a2Yf?B6K0#)4Zu zk+C6YW$&2L?*0~IU4ijc`|0@?b7~AVaP5?whfB-D!3N`In{x>!uBV>kkTsv(9V^|# zUUqIp?^l0-pyH0SHgaFGb=hRJg70z0SOlHY>~w3X{p@=_Oy?+1XW76Os6!VcNeg+o zfk1Ctr~x1q7DctVikCL#x3P}CIm?J1wn;s7zNi@IRDfpl=8694($$vj!JT$3NE9@l zbX7SiJtU&SfsXcwzPik`db=U5>{xA@A^HY9PeD9JLvv$M0K)gqzxWRDJ3zf?>$w4J zQj9L4(cykoI#0EQ^0ep!@t1XD2@Ti?HLmx{HwV)tMr+h-NW2supR*@i*AFo(<%ukO z&L=m&E1?h6p!<*$UB~k&WLNb$_`l-o|2g5eWbj>~nddq{zib#5$z_t&h@%q_bJXSU=1NYO?Z6CmssE{alTCeH|U1 zfikyVFG}X#j2Z^qv#^Q@OehddnZ^`$CXUD$HFW)4sa)pan9+YGbvtoOwS``nK|yur zl+o5d$kiJHQKVgi2u`0XOu2xc9q+wwua+n%Ox^a_xTIZf@(2DfJ-D^ z)F}J)UKB(o`x=`4)Yng5!iey1bfLxZ`me(I+3^RGlO#&NCd*hIA-|FXELXV>`;4}g zG0t8Xq>UbR;IdJe=LdVc^6|re|o3?DBf61v~c>+^sCRp z!YROx#HF0RhQ1esv+GbQ_MHbxaZ(?r@TE4DB=?Cey|T+mpkbM)l(9ZV}oDR->ZtedH)O}W};pPpV2E^GGF zU3g~-$yG98EE4oel&XUY`kobz=m1{q^)rCyZa!Y#Z(g6^3>amsGeUhf51bH&o*UeM z$P-PE<#oH6lK*WLtqV)#o_Qs6;pS>2F)gIZ;EULZ9J1s5IjEr zQM749u zO*N4sr;cOadYCN>-~Jo)IiIOT<~-R-KWjKIt&$qJtqMWmglC<)<3oLr0JF)q69%}C zO>Bij^>%iD9Q(~0l0TmvGka`y!8f`ZeAN+VQ)*>*t50Y1s6ZVUGoQr&$%-E*NtOLR zSQlh%+si#my3ttmu=_*2xUaE&t+M<$Nk#(vTeKbO&EMKL1L`_3NbsKj&9B+?ucEo` zEPJVLKc@d_gOUMSX)m6+v=&-sn1)7-Vx5ctbXr%?xjE4i(8rjJw>+65 zz<`5GJh5b+3Y}$@ip7>b4zI?G*Ke2mHc1nHYpGDe8ExEqKvBu|vvj>(F~WLl&k3E z{!`J0*Xsf49{%4O8oB-1Dz_p#sBy)LM9ft+_jCn$UWg}%-nnatMLK8dLwTN!n^AbeUeS!WKcB7O)PCJG#ClP>N~;Xj z75r5GhORc)q%F7A^271gM5#t50omvA^X5Nn$E~a{uM;O}QRAUq=gwK~(dG2_qde{( zUW$S`h@dLW%$uCtfVV%-N$RDWjX5zlcAO7^Ki}LBJRh|sk*d54lR19P=cExbOq9X6 zgL{><4qs)e@eDBNWQ1kOgZwfZ5zKxqemtngN2|YFIzGc!g#ZMtMsV({yx+e+`2ulg zLx6P-6A(~XB?u@k9iMJ@h5$7m4Zr~skwxNMFRQQDkcuSS%3iVWLObuqR_X^#QlAHB z+n!w1HFCdkQxQ!-KB{S_wUx5DxGk%u4VGUvWVi6uAP4+>!?Nk3wC}=L|h^>y=klJyl5E3uV0U{%po}?6F(O zB+8Se(8VE|$*QTP;%xqu^9}!K{@&-6Fv?J-o9~6=@{`5R=q=|iM4SawG*ccOHUHuR zg#9#Arpq{)uMmew=KT@(od)?!`qgHi$df}_P|E4-)D-oLEN97mBl3J)0$tYAvvJAy z{>ZVHz^wmpzG^G}v*LshW|{yo_S`LElR}J8qo_A#Vhie12#Oc$74yx;=%KUA#m&;K z{=Zxy?bflwg(&+#C;aZ!d*Ndbk*=C@w)-z*nM5c$X(V3TKAdj0?@$jt*P3#L{?)Ed z@O3&FivJ3rIYHu;rn61wbwXFXb1Es5jhdd3i)5boGdE5zt+KZ0`b+DIq%g6|bQ;iB zNv-gzsd_?lr7T_2 z^f8vK3c3n;v(d*!ob7@SVtOGF#4!}c$n4bWHQ}-Yvaw~6e@d!NWaT>DAIdDHYW@WO z<}X9Bq9e8X8>7e>rd{-eJ?6g6^TOxA{}(#^_;})X62yn(S3e4{K*@kqMu5kW)KB8J zL=lL9c8;T_wC4il1xRy(02`Va?Gs0-!c?7vv0xDlkrBbn?i$D zHfcp>#%1oX=ir^r39HZ1t)ACnjZ@X+^u(c?E2qdp)yDlW08#UhWZVlM4Ex!Mcpu%~ zqaJ>aRY_Lf5a^wn9g8X>s^R72=90@r{-WS%{fDY-xq&q8%*r;_^3D0%sM(?K#+S-v zUXE(}mGAnjE()$)NlKG0-?*F?KK*Rg`>ECB@JZyyB5p7hm6#OTXv~<>VBA-D4%4|c z;*_F$pY4MWPac|uqeVSq++KCFa9e`OrZb(;9yYDN1mCK!YqLzqR)|lxj=V@#=F*8% z?}hj4UY~W+pu=*yd>lQ8ib=oH_uIR)*fh#OjyP(C;Gu{M96Dlgq(BA}Fm_9Am&^auc6@>$qfpHvb!DY+yYQhUTv+K^5@UG zz1kss;Y@yqq(R{HE~bcOyWcY#UHOmGm5xe*)V9L(Sz=WirVDx*?&IGd_9kdDD|UQl zz7v@t!qqh6*mPbr?oQdE^bfTzSLS*Ji7*ojSqSwFnbm4Vxt6+)XlV;%Hf8d5#G3gq z*1KL0x9AzK@YesRL2PzspdcsMzZ4)e(cOaETP@ckbp8d`c{VpuSwLuH{*_|9W5i4` zW-@oh$#=hHBXUG}d7QeBD0NH2r%Gl0SDWLqvQ3>D%u8h#`+73D{h!(-n0S^~K`};5 zi-H+Ho`$NIZs4@UWMG!S^R{7+y~r;lVmFDQaKUnPKt9ogrJ!`hBg0^%JPy_J1c@`p zyN;5z0rL&bl*Q(%m!{DwjsU{_B368S%@om*Dw(X-*u^A2a@*IpIGs}#T-Ri8ac0cB zYBjuAzI}+2_2_XZY_x4y1aR}2bqr5=JMlAu3BBu*QLsq4^2gBrVl~w zM9(%Gt5?XkghS#6GOt8oT_~SE=j!TNl3#Sp$pt{kS@FqsZH7rWVXOoTmng=^A+Jf^ zhU2lgK8b@axb5!&Y`Pz?Jjk#QLlv}NgJFv&G3&l1ARtgAKXt|4ZD8CeTK6~|$vyuA z=YzSTn-30%wriagj;4CTI^${R`V(L!AVRTHW6Ty-XoXhZqtp~4npogvICHETsr_Ag zW9Dx7a35{S>d`~D>subW!Y7bI?Y&GuPnWM|j^(ZXg&@j>$9SX^;&pO%(3?khhsEjbx+ZUnTbHlNl${jdBs%;8P64-P#rL@XmK0ZDz_c^vzcWi(D5)_}o*~!ayU!zE*|M)Ia^q$jF zNLope?#`Yb6B;-*UOEX8O5ibtXTTQ_i$VQ=&LrSRb_=x02I(+&3N+rJ)1W1M)}PKjh05jx)|8Nni*>;Afit8oR)!!8lg>is)72 z^g zm0J4qPP-MGW~OqswI9s2QZmdLET4Ae(tmz9sjm{@&5BtM{7~h;8`CAp^kP2fx=$cOug2;G->vsLO6 zdVR(QOo>m|p4EWeNM~8qafwG_p4fe@n4P7zx|hD7M5f5Sd|g%Gaw1s?k2#5ELE^%b zeffZplZ3+*W>l+4X^!b^hqBEx-C%{G#HDt2z~R?0cgp3!wwqBL9Gq_X%-T>&fKUpx zO>Tw@WY)0@oMA-OqsDI*q<#07zb@}!mNTp#@w1lJK5c+#{XZ@w?5gknHy|bjpBf_EIG)oS*l)EzfTO^YOPg=z$bk)Ua8scl0QoO7 z=&|EFg{E`^GgRA9E2LB*q_|UT<5v#oU?947OpSMRi1g7vYi9on_ojJF0Hu94^Tfr> z_Vy40SAF+x%%M6&x;PSdV8OVLeq$Rtd9~l|lb#Y@>*ldFXC8>6V}p;l(hzrptvU{c z@$Hj3i~U{dmG&BR9}mn86^4A&&*lL?7#=Q)KfUgg^=njb^R(3ISDdUS zoxeWiZceM~C&JY*3}QLdzRsGd|UttCF?UQ~(>nEAf51`%~9Y|Qx1 zRNvQs>3>H|L|+cmDo_hN(l7A8?Cb(+p2YlcmR1eswg<<$`#vBeo5SOz<$4pyf(Rr^ zGjpxz|Mz&k%Cfb!1&9{pTwpJ&9J@a zHGg28d8O3_SYQl8!?u|^7LXGkj(=1F{I5 z5DhU!>^6=@?}f+y`yF5qemX$+gYk*g@O3~M!BW>4YUa9`@wNRbncH@zG|*`O=i^`Y zA~t@n;{8f^b=T#hIrqNx*hAq(5cfZyaW1$qu($4FF4})q0oL`$f8p^+vBwVlcS~@7 z0G;h33Fim^*Z$|5i$=VV)2IjrO#XLQVqk3m2y!R)?dpFH*UJ%;LJD%hwYOuhqWOY> zc#>!CiA8s_(IT%<@o*%Y{&%F5$L}X#Skj6GnyJO(zFMb#KCQfFzVAm#d|cUz9uKS; z^S)8W%Am+8@k;XhNvW~5`tUkG>-z^jW{4;b&LOjrK!kfa$6Q>5e;ez-z(8z#{3f!A z(nIcII}%Lj97L<(L8Kx7cPJsj?-c#2>5V>hQ!}BP!K6AJ2@!8vzQ* ze4~rixE6&_q;_+C-%ul9Ytq*O%*zM~3AGqQ-3`an_JZ1VRaB_CxVV(n)uo>d2T_Z? zfFAhoekPDvCMzxuKFDG{lV+vAmyRZNc{sE2XT^HQq=FxZnINWl+vi#d@Di9=0(7r8 z7At-3UHu<0ifL_u9ZwcGX`b}?8IY3l%lZ0fap#Ih_^5jFXE|;vwpRv(gZgfo6mIhX zuu(SM9nX1T*;rUwT83h{{I3NksjA|QTS~vCR*VQIE!uqK0{^8 z-x`d`m@3#<%Ck*jiG;}C>OAWT8lcV$g@xx&fAY?Y^&dYx-Smm@N0M_!bf6X#oJB}p z8=&{{`fd=d#-!Oc%D!-Z3JXhJ#NFTJ^I=T}3DzH!HJJb$@0UJBru5uw9^FT=p;0=t zrUbwd{$Gkb;A^ny$ukb3d_Fyuz9tVku_|v-TLDadJM^wM$vm$Bn^qCo+vgo6UrK{-%tq}pcDB*C?DcA%0#`xD9F&vFLQjvR`IM6fQZP_cQ|s@{?jyklc{OMAezC+8 zQE-PE;J+{84r(WpcxT=z4RS$;vkhl)aZ!vdUq3wPNpFNV%wf-4dF5Sj!6ISOaH1& z(ABQ)b@mzjG3ym+5V!N)@d#NYDUql6(>f#3FR#-_F6^R4#P#l?uS9UHI4S0oG>yq@ zNOSV^o$PHM7Z|Kp^_`+?cXxMcoSUoPDBscDU!RDu)v7Vdoui|;;vqqz>sCCABiE## z);G{|HoDM7tg*>&>pC!FQLw9lBor;L>-LPprci-(U#?{*@x>L$$2D?L6seF_zGB88 zco&T>XlKQS{ns7}3d*7igaS2H?;Zn&;5wYl#%{kRdL5Kdfu4<_tF_GGbLY&1M4GBm ziH>>b+Wg9D7$bwzB6cHMk9-7lR+hHl(5u}+KHf>rUzQZqQ1Q*^_mfC=_93x^E)~38)YoHhaZEt1i_n0C;j({hmipJ`vpse-lYU{~p$wZLZpwh`ES9iS^9q znQbo9{K(eY{pO}V7D$+ae;Ps94&sTreqlkZj~nQ!o%!mq=Z`dS0l8Xb0~W|lmC*$ASGE`JUi?Qvpc^B^ zZ-D1hy<@bMbx-I~zctC9E5iH?_W@}j(bO@jRP+oDzpUz0fl?YSOv(8#I^0I2Zj10A zrZxLW&AIVLBNoS!PXB50;Y<x4?2?@NO3*R#*_8?k!bJ{$YiJUc)Xn5DybTcEiP;P z@Ii&#WS-|khmckSGb2k9aC46y**q;+l@DMm2~wCpEV-@v1e6x{i_|YI{u>EGE$O-e zAParwmJ8+E1CFt3vxMt__w9osS8Y;0&z&eNyke(-FTK6XM+=KWl!3!n40Fj>A-e5w zCM;h_4XG@v#kWT@7=agX;czO~P>uLYd|^`tLj?<~f;sfX`=#b48|u$mX*z`KhSrg8 z>>xh$bX2#RXi;?3jvJ1_`??6h8=yCxzvwNGTdr5e5lDAhC3a!ip*9t#@P6@+fOqsD z5SYZUljYZHm3~fwq$~EDe;e?#j?)J++>eDsNu0-ou7jAzd9UY#fNssL>Cx{RP~!qB zzDTFHLUO`fFu2peQ^bFOkDO*J;Po%CjvkDy&HngLyyr>kn9DYyU zd#i0C*K4TIzz zkc3E#2PMKjgUsuwJc-L%?<{9gf&hKZy8v2mNCl{+ZoO_MEyQof270#>Qmcj33^*{C z5g{Zg6uEqu`bJ=kVUV5Bc}zZI>A-VK_Y0B@?dZdhPCdnfAwW9GB1qIrG$?qM>?ICX z+LtgXI6aJ9kQNsB5gm2p}04#9!A7`^A+x~EDXp~>Jip!ECwaO~C=2hag!92|Z} zkO*-9S|6{fg^Xvv&j@HlM2J-23}QXT58!p}&e?nMEm+=|emf52d^O@`FFr{>Rz#C< zBZPLWsicl$RWLLA9*Pe&2(3o8Km&%7Slm)EBKkTwh-fD=wO3GH!ySrw0r{Xco*@Vf z5K(LlZL(8pb4ba-HQ=_y|jHGJs0{RwQ-Ru*L?&{_8EfU>04CaH%wgi`O#^QU1 zlEPz`DVJj*Yee6G8HZEs#N2vgLTb6IIMstX^URp%~r! z*eNScwOEbs2s_||g2Edl+C&~4NMIIRuWNq{#rb5`Q#BWivAkKCRz8^=V9DlaV}h5@ zfQNj+Bz6?sA^9Qi5&r=5g}I7nDHs}26@qa&!SVJJ*W*H@pXSP zoAJ`xHNa9^el_ZiWJ3yL@x_M^J}ysBCvE_80$<6U2?8-;%=X0v;zV&b7molTDz>>< zkZ1d3BU%JkUaD(Y1voow7+PYdW;QsD=Y}Vu#zUuMCE}pKyRcqA@DyNwT@$q?PlY!Iw$@e0ctRaz%ma1J4p!K~dPOB9W4Aqmnuwq57Di^I;1r{D-AcQ-asUQ7q zSxY3Zk50U$NqukDXHw=&$Qr>$WP+$dY)shh8-ZaoY#;H&u*32U-(`v8rQQ6ShoG1E zH~2n!(pgJv1W7jFG3(H;PPoB!UIT3rF>w`{-%s(hzmB?y*a+S>SZgnJ%&{TETf%4P zNBCWl;yCMUvJGLzoLTm6zFQVRY$($8Tic*7Q^PgW}I9|Bzv zM)C&i{GCw7B;dn)!q`Z^(N;sehq(9ClT<++5aKi(bB{L*$=yjOy%!ybWbt`&NrQkC z@PLrt?{-KZ5;w-m@J#^IrCi>gV)yvWvc@JDQ+vF*tSaVPwQ{eh0qXmnWO}caeHfh> z9W0M!d@D+Ug^UiDrOZrs=v*A5P zE&rNqG*lx4e6$J>v6qxTYuJFq`DWnW2gZ}NlNw(w!VjTub^!JQOUxgWgFj#sf_sUy zKZ?(F)#15#+uD|;#dCPyoQ^|?yIPe&hhp1W{uh@&fcEFgorE7e960_vZ|u7qY)jbj zUkDot6I|ls@jp{M`|FgNM$sXn;MXD?^=8W^uF-wt7#03)t*spB-d`cljZ{}iUpGL3 zV~dN@tNeYLzn6%XMcxW#{c$>VOqeNx!ec%4*y+-6aft3+v_LZ{O4N$nnosI%};4A z5xoCh29W}G-e76>+kX$yj~7Fz{~r(A=`-kUUsmM}`Q{b~_$Mo=_`XcsAmIN2x}!#= literal 0 HcmV?d00001 diff --git a/docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst b/docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst index afe689b9a5..891de94135 100644 --- a/docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst +++ b/docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst @@ -9,14 +9,106 @@ The red cross is true position, black points are RFID positions. The blue grid shows a position probability of histogram filter. -In this simulation, x,y are unknown, yaw is known. +In this simulation, we assume the robot's yaw orientation and RFID's positions are known, +but x,y positions are unknown. + +The filter uses speed input and range observations from RFID for localization. + +Initial position information is not needed. + +Filtering algorithm +~~~~~~~~~~~~~~~~~~~~ + +Histogram filter is a discrete Bayes filter in continuous space. + +It uses regular girds to manage probability of the robot existence. + +If a grid has higher probability, it means that the robot is likely to be there. + +In the simulation, we want to estimate x-y position, so we use 2D grid data. + +There are 4 steps for the histogram filter to estimate the probability distribution. + +Step1: Filter initialization +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Histogram filter does not need initial position information. + +In that case, we can initialize each grid probability as a same value. + +If we can use initial position information, we can set initial probabilities based on it. + +:ref:`gaussian_grid_map` might be useful when the initial position information is provided as gaussian distribution. + +Step2: Predict probability by motion +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +In histogram filter, when a robot move to a next grid, +all probability information of each grid are shifted towards the movement direction. + +This process represents the change in the probability distribution as the robot moves. + +After the robot has moved, the probability distribution needs reflect +the estimation error due to the movement. + +For example, the position probability is peaky with observations: + +.. image:: histogram_filter_localization/1.png + :width: 400px + +But, the probability is getting uncertain without observations: + +.. image:: histogram_filter_localization/2.png + :width: 400px + + +The `gaussian filter `_ +is used in the simulation for adding noize. + +Step3: Update probability by observation +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +In this step, all probabilities are updated by observations, +this is the update step of bayesian filter. + +The probability update formula is different by the used sensor model. + +This simulation uses range observation model. + +The probability of each grid is updated by this formula: + +.. math:: p_t=p_{t-1}*h(z) + +.. math:: h(z)=\frac{\exp \left(-(d - z)^{2} / 2\right)}{\sqrt{2 \pi}} + +- :math:`p_t` is the probability at the time `t`. + +- :math:`h(z)` is the observation probability with the observation `z`. + +- :math:`d` is the known distance from the RD-ID to the grid center. + +When the `d` is 3.0, the `h(z)` distribution is: + +.. image:: histogram_filter_localization/4.png + :width: 400px + +The observation probability distribution looks a circle when a RF-ID is observed: + +.. image:: histogram_filter_localization/3.png + :width: 400px + +Step4: Estimate position from probability +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +In each time step, we can calculate the final robot position from the current probability distribution. +There are two ways to calculate the final positions: + +1. Using the maximum probability grid position. + +2. Using the average of probability weighted grind position. -The filter integrates speed input and range observations from RFID for -localization. -Initial position is not needed. References: ~~~~~~~~~~~ -- `PROBABILISTIC ROBOTICS`_ +- `PROBABILISTIC ROBOTICS`_ +- `Robust Vehicle Localization in Urban Environments Using Probabilistic Maps `_ diff --git a/docs/modules/mapping/gaussian_grid_map/gaussian_grid_map.rst b/docs/modules/mapping/gaussian_grid_map/gaussian_grid_map.rst index f78f2c95d8..b0f112a871 100644 --- a/docs/modules/mapping/gaussian_grid_map/gaussian_grid_map.rst +++ b/docs/modules/mapping/gaussian_grid_map/gaussian_grid_map.rst @@ -1,3 +1,5 @@ +.. _gaussian_grid_map: + Gaussian grid map ----------------- From 040e12dbcb88ac5a3cfa7097ceca8a5e5562ee6d Mon Sep 17 00:00:00 2001 From: Trung Kien Date: Sat, 29 Jan 2022 14:16:34 +0700 Subject: [PATCH 468/940] Add inverted_pendulum_lqr_control (#635) * Add inverted_pendulum_lqr_control * reorganize document of inverted pendulum control module * Refactor inverted_pendulum_lqr_control.py * Add doccument for inverted pendulum control * Corrected inverted pedulum LQR control doccument * Refactor inverted pendulum control by mpc and lqr * Add unit test for inverted_pendulum_lqr_control.py --- .../inverted_pendulum_lqr_control.py | 192 ++++++++++++++++++ .../inverted_pendulum_mpc_control.py | 30 ++- docs/modules/control/control_main.rst | 3 +- .../inverted-pendulum.png | Bin 0 -> 6127 bytes .../inverted_pendulum_control.rst | 97 +++++++++ .../inverted_pendulum_mpc_control.rst | 6 - tests/test_inverted_pendulum_lqr_control.py | 11 + tests/test_inverted_pendulum_mpc_control.py | 12 +- 8 files changed, 328 insertions(+), 23 deletions(-) create mode 100644 Control/inverted_pendulum/inverted_pendulum_lqr_control.py rename Control/{InvertedPendulumMPCControl => inverted_pendulum}/inverted_pendulum_mpc_control.py (84%) create mode 100644 docs/modules/control/inverted_pendulum_control/inverted-pendulum.png create mode 100644 docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst delete mode 100644 docs/modules/control/inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst create mode 100644 tests/test_inverted_pendulum_lqr_control.py diff --git a/Control/inverted_pendulum/inverted_pendulum_lqr_control.py b/Control/inverted_pendulum/inverted_pendulum_lqr_control.py new file mode 100644 index 0000000000..fb68c91c45 --- /dev/null +++ b/Control/inverted_pendulum/inverted_pendulum_lqr_control.py @@ -0,0 +1,192 @@ +""" +Inverted Pendulum LQR control +author: Trung Kien - letrungkien.k53.hut@gmail.com +""" + +import math +import time + +import matplotlib.pyplot as plt +import numpy as np +from numpy.linalg import inv, eig + +# Model parameters + +l_bar = 2.0 # length of bar +M = 1.0 # [kg] +m = 0.3 # [kg] +g = 9.8 # [m/s^2] + +nx = 4 # number of state +nu = 1 # number of input +Q = np.diag([0.0, 1.0, 1.0, 0.0]) # state cost matrix +R = np.diag([0.01]) # input cost matrix + +delta_t = 0.1 # time tick [s] +sim_time = 5.0 # simulation time [s] + +show_animation = True + + +def main(): + x0 = np.array([ + [0.0], + [0.0], + [0.3], + [0.0] + ]) + + x = np.copy(x0) + time = 0.0 + + while sim_time > time: + time += delta_t + + # calc control input + u = lqr_control(x) + + # simulate inverted pendulum cart + x = simulation(x, u) + + if show_animation: + plt.clf() + px = float(x[0]) + theta = float(x[2]) + plot_cart(px, theta) + plt.xlim([-5.0, 2.0]) + plt.pause(0.001) + + print("Finish") + print(f"x={float(x[0]):.2f} [m] , theta={math.degrees(x[2]):.2f} [deg]") + if show_animation: + plt.show() + + +def simulation(x, u): + A, B = get_model_matrix() + x = A @ x + B @ u + + return x + + +def solve_DARE(A, B, Q, R, maxiter=150, eps=0.01): + """ + Solve a discrete time_Algebraic Riccati equation (DARE) + """ + P = Q + + for i in range(maxiter): + Pn = A.T @ P @ A - A.T @ P @ B @ \ + inv(R + B.T @ P @ B) @ B.T @ P @ A + Q + if (abs(Pn - P)).max() < eps: + break + P = Pn + + return Pn + + +def dlqr(A, B, Q, R): + """ + Solve the discrete time lqr controller. + x[k+1] = A x[k] + B u[k] + cost = sum x[k].T*Q*x[k] + u[k].T*R*u[k] + # ref Bertsekas, p.151 + """ + + # first, try to solve the ricatti equation + P = solve_DARE(A, B, Q, R) + + # compute the LQR gain + K = inv(B.T @ P @ B + R) @ (B.T @ P @ A) + + eigVals, eigVecs = eig(A - B @ K) + return K, P, eigVals + + +def lqr_control(x): + A, B = get_model_matrix() + start = time.time() + K, _, _ = dlqr(A, B, Q, R) + u = -K @ x + elapsed_time = time.time() - start + print(f"calc time:{elapsed_time:.6f} [sec]") + return u + + +def get_numpy_array_from_matrix(x): + """ + get build-in list from matrix + """ + return np.array(x).flatten() + + +def get_model_matrix(): + A = np.array([ + [0.0, 1.0, 0.0, 0.0], + [0.0, 0.0, m * g / M, 0.0], + [0.0, 0.0, 0.0, 1.0], + [0.0, 0.0, g * (M + m) / (l_bar * M), 0.0] + ]) + A = np.eye(nx) + delta_t * A + + B = np.array([ + [0.0], + [1.0 / M], + [0.0], + [1.0 / (l_bar * M)] + ]) + B = delta_t * B + + return A, B + + +def flatten(a): + return np.array(a).flatten() + + +def plot_cart(xt, theta): + cart_w = 1.0 + cart_h = 0.5 + radius = 0.1 + + cx = np.array([-cart_w / 2.0, cart_w / 2.0, cart_w / + 2.0, -cart_w / 2.0, -cart_w / 2.0]) + cy = np.array([0.0, 0.0, cart_h, cart_h, 0.0]) + cy += radius * 2.0 + + cx = cx + xt + + bx = np.array([0.0, l_bar * math.sin(-theta)]) + bx += xt + by = np.array([cart_h, l_bar * math.cos(-theta) + cart_h]) + by += radius * 2.0 + + angles = np.arange(0.0, math.pi * 2.0, math.radians(3.0)) + ox = np.array([radius * math.cos(a) for a in angles]) + oy = np.array([radius * math.sin(a) for a in angles]) + + rwx = np.copy(ox) + cart_w / 4.0 + xt + rwy = np.copy(oy) + radius + lwx = np.copy(ox) - cart_w / 4.0 + xt + lwy = np.copy(oy) + radius + + wx = np.copy(ox) + bx[-1] + wy = np.copy(oy) + by[-1] + + plt.plot(flatten(cx), flatten(cy), "-b") + plt.plot(flatten(bx), flatten(by), "-k") + plt.plot(flatten(rwx), flatten(rwy), "-k") + plt.plot(flatten(lwx), flatten(lwy), "-k") + plt.plot(flatten(wx), flatten(wy), "-k") + plt.title(f"x: {xt:.2f} , theta: {math.degrees(theta):.2f}") + + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) + + plt.axis("equal") + + +if __name__ == '__main__': + main() diff --git a/Control/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py b/Control/inverted_pendulum/inverted_pendulum_mpc_control.py similarity index 84% rename from Control/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py rename to Control/inverted_pendulum/inverted_pendulum_mpc_control.py index 3764f29558..6b966b13b4 100644 --- a/Control/InvertedPendulumMPCControl/inverted_pendulum_mpc_control.py +++ b/Control/inverted_pendulum/inverted_pendulum_mpc_control.py @@ -17,14 +17,16 @@ m = 0.3 # [kg] g = 9.8 # [m/s^2] -Q = np.diag([0.0, 1.0, 1.0, 0.0]) -R = np.diag([0.01]) nx = 4 # number of state nu = 1 # number of input +Q = np.diag([0.0, 1.0, 1.0, 0.0]) # state cost matrix +R = np.diag([0.01]) # input cost matrix + T = 30 # Horizon length delta_t = 0.1 # time tick +sim_time = 5.0 # simulation time [s] -animation = True +show_animation = True def main(): @@ -36,8 +38,10 @@ def main(): ]) x = np.copy(x0) + time = 0.0 - for i in range(50): + while sim_time > time: + time += delta_t # calc control input opt_x, opt_delta_x, opt_theta, opt_delta_theta, opt_input = \ @@ -49,7 +53,7 @@ def main(): # simulate inverted pendulum cart x = simulation(x, u) - if animation: + if show_animation: plt.clf() px = float(x[0]) theta = float(x[2]) @@ -57,10 +61,14 @@ def main(): plt.xlim([-5.0, 2.0]) plt.pause(0.001) + print("Finish") + print(f"x={float(x[0]):.2f} [m] , theta={math.degrees(x[2]):.2f} [deg]") + if show_animation: + plt.show() + def simulation(x, u): A, B = get_model_matrix() - x = np.dot(A, x) + np.dot(B, u) return x @@ -85,7 +93,7 @@ def mpc_control(x0): start = time.time() prob.solve(verbose=False) elapsed_time = time.time() - start - print("calc time:{0} [sec]".format(elapsed_time)) + print(f"calc time:{elapsed_time:.6f} [sec]") if prob.status == cvxpy.OPTIMAL: ox = get_numpy_array_from_matrix(x.value[0, :]) @@ -165,8 +173,12 @@ def plot_cart(xt, theta): plt.plot(flatten(rwx), flatten(rwy), "-k") plt.plot(flatten(lwx), flatten(lwy), "-k") plt.plot(flatten(wx), flatten(wy), "-k") - plt.title("x:" + str(round(xt, 2)) + ",theta:" + - str(round(math.degrees(theta), 2))) + plt.title(f"x: {xt:.2f} , theta: {math.degrees(theta):.2f}") + + # for stopping simulation with the esc key. + plt.gcf().canvas.mpl_connect( + 'key_release_event', + lambda event: [exit(0) if event.key == 'escape' else None]) plt.axis("equal") diff --git a/docs/modules/control/control_main.rst b/docs/modules/control/control_main.rst index 9eeba434d2..d6d36a726b 100644 --- a/docs/modules/control/control_main.rst +++ b/docs/modules/control/control_main.rst @@ -3,6 +3,7 @@ Control ================= -.. include:: inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst +.. include:: inverted_pendulum_control/inverted_pendulum_control.rst + .. include:: move_to_a_pose_control/move_to_a_pose_control.rst diff --git a/docs/modules/control/inverted_pendulum_control/inverted-pendulum.png b/docs/modules/control/inverted_pendulum_control/inverted-pendulum.png new file mode 100644 index 0000000000000000000000000000000000000000..841aed922078f2e72aeec6dab3779c177b011fd8 GIT binary patch literal 6127 zcmbVQcQ{<%+8rrEh$umb5+x=|5JVqBh(0=r8qq}=B0|)Nh!%_yy#zrddQ6njYog2O zqm2^1m(hLO@7{m!bMN!b^PD+n&Y8W>yZ2u2TI=1RT5zRnR~fHDAdqV+$_hH*JP(dh z5@PUeN~y04PNWFsr!OH8isti!=o2r+EeM1@Lq$PO&ogCp++VN%Rc+g*t<=T4A|yOy zCfZcGeUB~fJI>_Wi5(+l|CILLRWtEl3EfkMVw-A~l0I1S52lG=p5wGJ*|tM#6LBv) z@2V?~tKiVI9Cu7@p1xjt-?tJjEWy*sM~JHImT!-G`}Ux7!|xc?8MR*h$b5b~wTH0n z>%ZmzKJp|PDXjY#2wQWiiuil2*dSdJ#s79OF?l(p-U@A0>2n~Ykwh$tlT8nam}Ny0 zlLsqLPfwFvzfLem60Pw+HRi3(uxCtXmJTt{kzYuIkrN$WK-L$83=$1`uVrYOv1I)y z6=eMA_gySnMO^ViVwa72QC)Y4*u=9Nlmp$%J&<{*2D`LCR9=)!n3(|7VImq4MsYv6 z%jc&vvoK-BUMzN!VBsU(S9g4efsEcm&8b1Pk$Y7C>C@k#w7j0jy=+DAygH5^HrM)g zdQOv?$I4Ub2opUi$P6qNn^@2hbV*QziBBW`5Xb-7(C^p+e!DCMrm)yZTg?^ z>ZhM=M)uezJ=WHyQi^1<`SV4kGgXQn^;heKlIT(gPs^qIMbyim4s};EC za@aCl8pdOl@yc};tATF=)yG?JgoK3l7d8Fc|73Uk>M?JqaGkl!!_(-1KCIw*04D3Z zL)~do?Kr|@s3rV0IkdhjS zb{4U|x=#dd^?)NGQfPz$sSJR37n}JDX)2H7cnww$IY2CXIU(3IaAOYO@oerlP{H>lnS7{beDuKXnme z)04KEIPBV)5<2djTT+6Ij;54<^oW#<42Ar2WmYoRF22jga=hx5<4Eb{cMbLBlYYFD ztlj~ggXgH?!PU-e;G52$A<{=x1-*lVbcx`(sF;`-1DC8Vs0MZz{em8nn3!l~YkO3g zIq?W2nx28dV-*!rh(KNSL|w~{&^cIgvA<*Ps6n2TJilyjKXYQDz0QumQ7~F;anS>l zy1(yP`s0Up*ZA#k(IZBR30*eX9&i1gX<_UXN^^dL{^czEF6bWAH_Xye57`Wj@AuIG~i15sz6%LxCWPSc(I zbl#efeH83E4sNE-UViX>&#@*g4a_wEi)Ih!+$YglhF;hT( zem;NK{-~p93<{N3P+;8>M(a3SELZsAFfju36dAe4lfZ=v%~p%o*41sIH}{cqc6N>z z-5)8nCPSmq&24SMuh*DJb1rbETt!Hxu8f{U8p47Gi_CjgMt+P`xN@|#v~b?JNFnzWWfyUyG-9Q$+cc(=qAk>stukd{X6Z|2mGZniJr$ z92R84KY#YYo|G^q90-6%;iK2y#_GSa>$qO9o@e~CmMwLdmIJS+@c8lL59YYzeqlB? zB80!~$r@%|(uZ6F>v{6(wIB@*&C~rIU1qLoT2mkH?!uX$NlaVBvl z3JNCidNqNXemp^J9Z_uClV+e~0w7oGdvwl@Hp`I(?usw|HJjCEr$=VHl;JT#Efam1{pCxk6Hc_J zv!KszW#e_Lal8pN4UNg@1K#h3MXk>SA%b?jx2cJ*TRfSje0+p3epg^z{=6Kg0*BiS=09~)OK1eq_Ac+v z{{2f$Pd}fSP-0X7XnAXQXkNmH_?;gkbl$YIx%Y3fyI_1ft%SVj znDUQW-aJK6LjEomcT=$%$lSQ4T0Sb4=+ziakC#PR2MX~Jq z42{*E$V$RUZ!j{Bq66O>a;6Y~W!1_+yRcmYO z^Gr_*5ET)Lj*o|;RL7MKNVwT~c-og);WKunN?Lum&xdgE!!ySPfTCVw0^9;tGy%0An{IJM~52B z`p$8+$EuM;>NPFu?%P@RjNXK`%VWkod}h_dJ+z_SfHxi%4GFu=hENbF9n`iduG|uJ zj24Y2QvYeG6(nZ5Ju2B+@FH76Lc$UEQ)94~7<5gGM~H)LbcZev7F?`4{naSy^*Qrb|Smw$Z~?uXqD&)h;JyT=N0ZAkO9Lbl(z^ zqnXZ6MiCekBwRn@DB2Tu6(Uf*5tz+? zUlRO2(7rX-!OhLh1|TI+cdS$Rf|v>fsIBcfy1Yu!-q8UgqY!l(zWNkVY}3VA@z=mrK}08GOnrbD0xkj%`;z(>M@ zu9A_#jCnef9;gM5gaZstxl4Mj*ASeS+4PKzmKG7W$td2ilICWLXk?X@#R5o9&&)ji z>6lojMh#PM%=?OhYMz4{0<=m~UjBU9U>c2ixBtoYR_F4I8#`Fdqe^!Cb+7^pyXR(B z8Wt4E0s~!d^eM6a=F}3n6R&e4%RUMEr8HZ9or@!v9jG@EA@CxiDBZNmJ@nEKdX#bN z4G`GS%n8yB z;s2JO|E0K?5;2+l0&N6?g)A>E4VPMXFnd#%D>ZT}(65eT;>$z`Z`Q);1;Bke&Fj+( z3wDvrQmw#1Rm&8DK0H9LbR6c}$dc01n0HsMmp*H_P!H1?92|7poL1zcBeSruu(Gyx zJw3i$Bx~5n9hlVeyunHcjk)h?%mq&w&b)O7>`LCZZ(B^VJUmxx%%Xsy-rt;Il5h(W zoAf~eLIjGJDC)$M?z@*b^x)E}DYtyU5!W6tM94&8+nBhx)?Y}D1hB3}M)m#u{k^@t zQwJl?BDs>kiDuZBS1Psg{IrzJV~w@lP{bMx_W0zUf0Yj{}QqPmS7#3QuK&DR;6q)h61zEPR=ExN}Z6I>+R zH#i`F*3U?{OJ9;)yY?s-t8Hl5QCJ?HcQjc?H8@nSOZE~bX8GN2tl|dOSbSigonB6B zaj~EuX5AO4YCrqu(9qC`oA(1lX`oxbIDSZpy!pw+DH3sbct{sDUg4V6(!(E*0(R)R zplA7F2^dFr8mt4vM?`Qx9*z~!ghYK}{cBiMJMHCk7<47prH-0`A#bb@M}_w-!L4#~ zaS3^CSv`(o=>i4kulDw(4P}XE^^o=`7R#ynw@flV!@>-gdSxZUfHC<4mPx|Q)RcL? zCmkv&nFMfEX!Iy^ceg2q;elI_ zZD6bMvR_G>|5^D3ia6itgVQ{0WtOntvFC)(w#JHw6dsRnZfQXxk#erC_p`IJ^Gzya z+S^rGJg10?WQ`m10(N%X!QblM?9y(Tn|wqU#+8-|{lQ{^6L)%LpI|pxLtw(kcZ%HxG?d8DIot8=G(_ofb>$0!vIl{0LNjVbay+29-*8G)o>pCZiL zL3Ud=29ZwqJI}Y%*6wXYJk?7(2&6ZVzETf#OGU*ypyw2@x2dWs&wO_(X67XW1A~>7 zmHSdfsk|~();jY%gIoj5TM981fU`MOSZ4zgQRjE!>0rSR0geNI8letU=~x5)g7zHd z5th2*p0k%qTsOhEUaox?KIK>2M}mbn`M5S`B36VEh+cND!WCK%_V-tqzih%}o3n4I zh@Ujixt08#>&o}?dKuo99tDbyGzb2T52mpSQ5Kuq!3n!`JR`T_j^)tKdcE~4-|MjaDy%t9`)O*(Y2}Nb5O$$ zD`itWt$8n^X&h~AEt#6OwB!I!m24UACp~{uZpgnqFPoU~-~}BO)i_Rf@L32aH+P<~ zY*snxH>9w%G*edJ@FKyuz`&giZ>7=B$>#fHxZPh+=Pob4qvjgJ!x0rN%svt(4ZrHX&)y|NSL>_e3->PGU~sEz`LU7f?aE zWgX8;Jem14uup1zD(8JM9(7Hivc+Uoe+Hqi9(I`X3wmxm%Ymo17mlw_A;d?0HG!K3 zYqv6rCPV#h4vruC;V_^E({kE~)*rlT@94PFD|?&Nn!finfTK9u1ntc?=#JzG=S0Frs|2}?imlJS`#y)Pic4De2@0@ zxBAzUUHH9EQxX$@XO6X~x2Gs8C|m*+MnSF1>L^-0MI5=iJcLS5*904Jpg@FayJ>-K zOON-#!6l%!*xK56|?-`ozTBc zQeJdx>*En?bx&YnGlrJ$Gkz@XNZ6?OHd{^*Mq VGO#d4OR$3vQBi~|6v{sf{6G7W$mjq7 literal 0 HcmV?d00001 diff --git a/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst b/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst new file mode 100644 index 0000000000..5a447f7cd4 --- /dev/null +++ b/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst @@ -0,0 +1,97 @@ +Inverted Pendulum Control +----------------------------- + +An inverted pendulum on a cart consists of a mass :math:`m` at the top of a pole of length :math:`l` pivoted on a +horizontally moving base as shown in the adjacent. + +The objective of the control system is to balance the inverted pendulum by applying a force to the cart that the pendulum is attached to. + +Modeling +~~~~~~~~~~~~ + +.. image:: inverted_pendulum_control/inverted-pendulum.png + :align: center + +- :math:`M`: mass of the cart +- :math:`m`: mass of the load on the top of the rod +- :math:`l`: length of the rod +- :math:`u`: force applied to the cart +- :math:`x`: cart position coordinate +- :math:`\theta`: pendulum angle from vertical + +Using Lagrange's equations: + +.. math:: + & (M + m)\ddot{x} - ml\ddot{\theta}cos{\theta} + ml\dot{\theta^2}\sin{\theta} = u \\ + & l\ddot{\theta} - g\sin{\theta} = \ddot{x}\cos{\theta} + +See this `link `__ for more details. + +So + +.. math:: + & \ddot{x} = \frac{m(gcos{\theta} - \dot{\theta}^2l)sin{\theta} + u}{M + m - mcos^2{\theta}} \\ + & \ddot{\theta} = \frac{g(M + m)sin{\theta} - \dot{\theta}^2lmsin{\theta}cos{\theta} + ucos{\theta}}{l(M + m - mcos^2{\theta})} + + +Linearlied model when :math:`\theta` small, :math:`cos{\theta} \approx 1`, :math:`sin{\theta} \approx \theta`, :math:`\dot{\theta}^2 \approx 0`. + +.. math:: + & \ddot{x} = \frac{gm}{M}\theta + \frac{1}{M}u\\ + & \ddot{\theta} = \frac{g(M + m)}{Ml}\theta + \frac{1}{Ml}u + +State space: + +.. math:: + & \dot{x} = Ax + Bu \\ + & y = Cx + Du + +where + +.. math:: + & x = [x, \dot{x}, \theta,\dot{\theta}]\\ + & A = \begin{bmatrix} 0 & 1 & 0 & 0\\0 & 0 & \frac{gm}{M} & 0\\0 & 0 & 0 & 1\\0 & 0 & \frac{g(M + m)}{Ml} & 0 \end{bmatrix}\\ + & B = \begin{bmatrix} 0 \\ \frac{1}{M} \\ 0 \\ \frac{1}{Ml} \end{bmatrix} + +If control only \theta + +.. math:: + & C = \begin{bmatrix} 0 & 0 & 1 & 0 \end{bmatrix}\\ + & D = [0] + +If control x and \theta + +.. math:: + & C = \begin{bmatrix} 1 & 0 & 0 & 0\\0 & 0 & 1 & 0 \end{bmatrix}\\ + & D = \begin{bmatrix} 0 \\ 0 \end{bmatrix} + +LQR control +~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The LQR cotroller minimize this cost function defined as: + +.. math:: J = x^T Q x + u^T R u +the feedback control law that minimizes the value of the cost is: + +.. math:: u = -K x +where: + +.. math:: K = (B^T P B + R)^{-1} B^T P A +and :math:`P` is the unique positive definite solution to the discrete time `algebraic Riccati equation `__ (DARE): + +.. math:: P = A^T P A - A^T P B ( R + B^T P B )^{-1} B^T P A + Q + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation_lqr.gif + +MPC control +~~~~~~~~~~~~~~~~~~~~~~~~~~~ +The MPC cotroller minimize this cost function defined as: + +.. math:: J = x^T Q x + u^T R u + +subject to: + +- Linearlied Inverted Pendulum model +- Initial state + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation.gif diff --git a/docs/modules/control/inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst b/docs/modules/control/inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst deleted file mode 100644 index 328f9f6b24..0000000000 --- a/docs/modules/control/inverted_pendulum_mpc_control/inverted_pendulum_mpc_control.rst +++ /dev/null @@ -1,6 +0,0 @@ -Inverted Pendulum MPC Control ------------------------------ - -Bipedal Walking with modifying designated footsteps - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation.gif diff --git a/tests/test_inverted_pendulum_lqr_control.py b/tests/test_inverted_pendulum_lqr_control.py new file mode 100644 index 0000000000..cbbabb93b1 --- /dev/null +++ b/tests/test_inverted_pendulum_lqr_control.py @@ -0,0 +1,11 @@ +import conftest +from Control.inverted_pendulum import inverted_pendulum_lqr_control as m + + +def test_1(): + m.show_animation = False + m.main() + + +if __name__ == '__main__': + conftest.run_this_test(__file__) diff --git a/tests/test_inverted_pendulum_mpc_control.py b/tests/test_inverted_pendulum_mpc_control.py index 9519b45ec9..800aefd7d5 100644 --- a/tests/test_inverted_pendulum_mpc_control.py +++ b/tests/test_inverted_pendulum_mpc_control.py @@ -1,13 +1,11 @@ import conftest -import sys -if 'cvxpy' in sys.modules: # pragma: no cover - from Control.InvertedPendulumMPCControl \ - import inverted_pendulum_mpc_control as m +from Control.inverted_pendulum import inverted_pendulum_mpc_control as m - def test1(): - m.show_animation = False - m.main() + +def test1(): + m.show_animation = False + m.main() if __name__ == '__main__': From 1d8c252fef3798d502dc3187e0c9a360a26fa1df Mon Sep 17 00:00:00 2001 From: Daniel Ingram Date: Sun, 6 Feb 2022 08:18:54 -0500 Subject: [PATCH 469/940] Clothoidal path planner (#551) * Add clothoidal path planner * Code quality/style fixes * Open up possibilities a bit by allowing control over theta1 values * Get line length under 80 chars for code style checks --- .../ClothoidalPaths/clothoidal_paths.py | 144 ++++++++++++++++++ 1 file changed, 144 insertions(+) create mode 100644 PathPlanning/ClothoidalPaths/clothoidal_paths.py diff --git a/PathPlanning/ClothoidalPaths/clothoidal_paths.py b/PathPlanning/ClothoidalPaths/clothoidal_paths.py new file mode 100644 index 0000000000..6fbf46ed2a --- /dev/null +++ b/PathPlanning/ClothoidalPaths/clothoidal_paths.py @@ -0,0 +1,144 @@ +""" +Clothoidal Path Planner +Author: Daniel Ingram (daniel-s-ingram) +Reference paper: https://www.researchgate.net/publication/237062806 +""" + +import matplotlib.pyplot as plt +import numpy as np +import scipy.integrate as integrate +from collections import namedtuple +from scipy.optimize import fsolve +from math import atan2, cos, hypot, pi, sin +from matplotlib import animation + +Point = namedtuple("Point", ["x", "y"]) + + +def draw_clothoids( + theta1_vals, + theta2_vals, + num_clothoids=75, + num_steps=100, + save_animation=False +): + p1 = Point(0, 0) + p2 = Point(10, 0) + clothoids = [] + for theta1 in theta1_vals: + for theta2 in theta2_vals: + clothoid = get_clothoid_points(p1, p2, theta1, theta2, num_steps) + clothoids.append(clothoid) + + fig = plt.figure(figsize=(10, 10)) + x_min, x_max, y_min, y_max = get_axes_limits(clothoids) + axes = plt.axes(xlim=(x_min, x_max), ylim=(y_min, y_max)) + + axes.plot(p1.x, p1.y, 'ro') + axes.plot(p2.x, p2.y, 'ro') + lines = [axes.plot([], [], 'b-')[0] for _ in range(len(clothoids))] + + def animate(i): + for line, clothoid in zip(lines, clothoids): + x = [p.x for p in clothoid[:i]] + y = [p.y for p in clothoid[:i]] + line.set_data(x, y) + + return lines + + anim = animation.FuncAnimation( + fig, + animate, + frames=num_steps, + interval=25, + blit=True + ) + if save_animation: + anim.save('clothoid.gif', fps=30, writer="imagemagick") + plt.show() + + +def get_clothoid_points(p1, p2, theta1, theta2, num_steps=100): + dx = p2.x - p1.x + dy = p2.y - p1.y + r = hypot(dx, dy) + + phi = atan2(dy, dx) + phi1 = normalize_angle(theta1 - phi) + phi2 = normalize_angle(theta2 - phi) + delta = phi2 - phi1 + + try: + A = solve_for_root(phi1, phi2, delta) + L = compute_length(r, phi1, delta, A) + curv = compute_curvature(delta, A, L) + curv_rate = compute_curvature_rate(A, L) + except Exception as e: + print(f"Failed to generate clothoid points: {e}") + return None + + points = [] + for s in np.linspace(0, L, num_steps): + try: + x = p1.x + s*X(curv_rate*s**2, curv*s, theta1) + y = p1.y + s*Y(curv_rate*s**2, curv*s, theta1) + points.append(Point(x, y)) + except Exception as e: + print(f"Skipping failed clothoid point: {e}") + + return points + + +def X(a, b, c): + return integrate.quad(lambda t: cos((a/2)*t**2 + b*t + c), 0, 1)[0] + + +def Y(a, b, c): + return integrate.quad(lambda t: sin((a/2)*t**2 + b*t + c), 0, 1)[0] + + +def solve_for_root(theta1, theta2, delta): + initial_guess = 3*(theta1 + theta2) + return fsolve(lambda x: Y(2*x, delta - x, theta1), [initial_guess]) + + +def compute_length(r, theta1, delta, A): + return r / X(2*A, delta - A, theta1) + + +def compute_curvature(delta, A, L): + return (delta - A) / L + + +def compute_curvature_rate(A, L): + return 2 * A / (L**2) + + +def normalize_angle(angle_rad): + return (angle_rad + pi) % (2 * pi) - pi + + +def get_axes_limits(clothoids): + x_vals = [p.x for clothoid in clothoids for p in clothoid] + y_vals = [p.y for clothoid in clothoids for p in clothoid] + + x_min = min(x_vals) + x_max = max(x_vals) + y_min = min(y_vals) + y_max = max(y_vals) + + x_offset = 0.1*(x_max - x_min) + y_offset = 0.1*(y_max - y_min) + + x_min = x_min - x_offset + x_max = x_max + x_offset + y_min = y_min - y_offset + y_max = y_max + y_offset + + return x_min, x_max, y_min, y_max + + +if __name__ == "__main__": + theta1_vals = [0] + theta2_vals = np.linspace(-pi, pi, 75) + draw_clothoids(theta1_vals, theta2_vals, save_animation=False) From a5feb75dcefc71802abfc369f23e278dd0329202 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 8 Feb 2022 07:30:42 +0900 Subject: [PATCH 470/940] Bump numpy from 1.22.1 to 1.22.2 in /requirements (#639) Bumps [numpy](https://github.com/numpy/numpy) from 1.22.1 to 1.22.2. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/HOWTO_RELEASE.rst.txt) - [Commits](https://github.com/numpy/numpy/compare/v1.22.1...v1.22.2) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 90e98e4f5b..7d830a846d 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.22.1 +numpy == 1.22.2 scipy == 1.7.3 pandas == 1.4.0 matplotlib == 3.5.1 From 30fe42c7b43265eff12836122231d3283daf52a3 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 8 Feb 2022 07:31:49 +0900 Subject: [PATCH 471/940] Bump pytest from 6.2.5 to 7.0.0 in /requirements (#640) Bumps [pytest](https://github.com/pytest-dev/pytest) from 6.2.5 to 7.0.0. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/6.2.5...7.0.0) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 7d830a846d..b1b5e9c679 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,7 +3,7 @@ scipy == 1.7.3 pandas == 1.4.0 matplotlib == 3.5.1 cvxpy == 1.1.18 -pytest == 6.2.5 # For unit test +pytest == 7.0.0 # For unit test pytest-xdist == 2.5.0 # For unit test mypy == 0.931 # For unit test flake8 == 4.0.1 # For unit test From c7ee9337e9ce789741d163f548680249e3522fa1 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Feb 2022 07:25:28 +0900 Subject: [PATCH 472/940] Bump pytest from 7.0.0 to 7.0.1 in /requirements (#642) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.0.0 to 7.0.1. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.0.0...7.0.1) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b1b5e9c679..de00ea5370 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,7 +3,7 @@ scipy == 1.7.3 pandas == 1.4.0 matplotlib == 3.5.1 cvxpy == 1.1.18 -pytest == 7.0.0 # For unit test +pytest == 7.0.1 # For unit test pytest-xdist == 2.5.0 # For unit test mypy == 0.931 # For unit test flake8 == 4.0.1 # For unit test From e494ed6eaecb00fdf13fb361db947498c70d898c Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Feb 2022 07:25:48 +0900 Subject: [PATCH 473/940] Bump pandas from 1.4.0 to 1.4.1 in /requirements (#643) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.4.0 to 1.4.1. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/main/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.4.0...v1.4.1) --- updated-dependencies: - dependency-name: pandas dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index de00ea5370..fb62322132 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.22.2 scipy == 1.7.3 -pandas == 1.4.0 +pandas == 1.4.1 matplotlib == 3.5.1 cvxpy == 1.1.18 pytest == 7.0.1 # For unit test From 9da650e31bc7879ac2a5d59bf46415b0232377d6 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 21 Feb 2022 17:19:22 +0900 Subject: [PATCH 474/940] Update LICENSE --- LICENSE | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/LICENSE b/LICENSE index 2867142fc7..c0c52a4321 100644 --- a/LICENSE +++ b/LICENSE @@ -1,6 +1,7 @@ The MIT License (MIT) -Copyright (c) 2016 - 2021 Atsushi Sakai +Copyright (c) 2016 - 2022 Atsushi Sakai and other contributors: +https://github.com/AtsushiSakai/PythonRobotics/contributors Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal From b1885a056490ef0904cea80aa3389811903dbe76 Mon Sep 17 00:00:00 2001 From: i-aki-y Date: Tue, 1 Mar 2022 21:33:31 +0900 Subject: [PATCH 475/940] Fix the broken gif link in the "Lidar to grid map" (#645) The link for gif animation is broken now. I think this is the right URL. --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 9aff69ab72..8972bae5fa 100644 --- a/README.md +++ b/README.md @@ -217,7 +217,7 @@ This is a 2D ray casting grid mapping example. This example shows how to convert a 2D range measurement to a grid map. -![2](Mapping/lidar_to_grid_map/animation.gif) +![2](https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Mapping/lidar_to_grid_map/animation.gif) ## k-means object clustering From 5f4b62d87a0e9bed2d0279b32841d4bbe323fdf3 Mon Sep 17 00:00:00 2001 From: Hrushikesh Budhale Date: Sat, 12 Mar 2022 04:38:25 -0500 Subject: [PATCH 476/940] Fix missing 'delta t' in EKF documentation (#647) Reference issue typo What does this implement/fix? Update motion function in localization/EKF documentation. Add missing delta t. --- .../extended_kalman_filter_localization.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst b/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst index d2cd52cf12..a9c2939678 100644 --- a/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst +++ b/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst @@ -89,7 +89,7 @@ This is implemented at The motion function is that -:math:`\begin{equation*} \begin{bmatrix} x' \\ y' \\ w' \\ v' \end{bmatrix} = f(\textbf{x}, \textbf{u}) = \begin{bmatrix} x + v\cos(\phi)\Delta t \\ y + v\sin(\phi) \\ \phi + \omega \Delta t \\ v \end{bmatrix} \end{equation*}` +:math:`\begin{equation*} \begin{bmatrix} x' \\ y' \\ w' \\ v' \end{bmatrix} = f(\textbf{x}, \textbf{u}) = \begin{bmatrix} x + v\cos(\phi)\Delta t \\ y + v\sin(\phi)\Delta t \\ \phi + \omega \Delta t \\ v \end{bmatrix} \end{equation*}` Its Jacobian matrix is From 9c5f981bd90b5871a4ac3c596f729689ad029067 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Mar 2022 07:13:46 +0900 Subject: [PATCH 477/940] Bump mypy from 0.931 to 0.941 in /requirements (#651) Bumps [mypy](https://github.com/python/mypy) from 0.931 to 0.941. - [Release notes](https://github.com/python/mypy/releases) - [Commits](https://github.com/python/mypy/compare/v0.931...v0.941) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index fb62322132..42ef7586f1 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,5 +5,5 @@ matplotlib == 3.5.1 cvxpy == 1.1.18 pytest == 7.0.1 # For unit test pytest-xdist == 2.5.0 # For unit test -mypy == 0.931 # For unit test +mypy == 0.941 # For unit test flake8 == 4.0.1 # For unit test From a03a07296cab0669ac664042e31d420f55ebed4b Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Mar 2022 07:14:13 +0900 Subject: [PATCH 478/940] Bump numpy from 1.22.2 to 1.22.3 in /requirements (#650) Bumps [numpy](https://github.com/numpy/numpy) from 1.22.2 to 1.22.3. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/HOWTO_RELEASE.rst.txt) - [Commits](https://github.com/numpy/numpy/compare/v1.22.2...v1.22.3) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 42ef7586f1..b173a6fab5 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.22.2 +numpy == 1.22.3 scipy == 1.7.3 pandas == 1.4.1 matplotlib == 3.5.1 From 762d1a4d428fb60be68106359c6456b37c7cef20 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Mar 2022 07:51:50 +0900 Subject: [PATCH 479/940] Bump pytest from 7.0.1 to 7.1.0 in /requirements (#649) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.0.1 to 7.1.0. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.0.1...7.1.0) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b173a6fab5..2de832ce3e 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,7 +3,7 @@ scipy == 1.7.3 pandas == 1.4.1 matplotlib == 3.5.1 cvxpy == 1.1.18 -pytest == 7.0.1 # For unit test +pytest == 7.1.0 # For unit test pytest-xdist == 2.5.0 # For unit test mypy == 0.941 # For unit test flake8 == 4.0.1 # For unit test From a3753272043c0e9adb810c33f1386c26e1333719 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Mar 2022 08:21:29 +0900 Subject: [PATCH 480/940] Bump cvxpy from 1.1.18 to 1.2.0 in /requirements (#648) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.1.18 to 1.2.0. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.1.18...v1.2.0) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 2de832ce3e..6f6be66470 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.22.3 scipy == 1.7.3 pandas == 1.4.1 matplotlib == 3.5.1 -cvxpy == 1.1.18 +cvxpy == 1.2.0 pytest == 7.1.0 # For unit test pytest-xdist == 2.5.0 # For unit test mypy == 0.941 # For unit test From 62eee8162ef561234ef6d79943334b344daa0339 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Mar 2022 14:36:50 +0900 Subject: [PATCH 481/940] Bump scipy from 1.7.3 to 1.8.0 in /requirements (#641) Bumps [scipy](https://github.com/scipy/scipy) from 1.7.3 to 1.8.0. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.7.3...v1.8.0) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 6f6be66470..e8dfbcbba8 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.22.3 -scipy == 1.7.3 +scipy == 1.8.0 pandas == 1.4.1 matplotlib == 3.5.1 cvxpy == 1.2.0 From fb6965a34fc01633aaf441964ca174a4eff605c4 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 22 Mar 2022 07:21:11 +0900 Subject: [PATCH 482/940] Bump pytest from 7.1.0 to 7.1.1 in /requirements (#652) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.1.0 to 7.1.1. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.1.0...7.1.1) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e8dfbcbba8..f671321704 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,7 +3,7 @@ scipy == 1.8.0 pandas == 1.4.1 matplotlib == 3.5.1 cvxpy == 1.2.0 -pytest == 7.1.0 # For unit test +pytest == 7.1.1 # For unit test pytest-xdist == 2.5.0 # For unit test mypy == 0.941 # For unit test flake8 == 4.0.1 # For unit test From 840248e38e47bb669f32075d9794cdbdd0248e26 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 29 Mar 2022 07:21:50 +0900 Subject: [PATCH 483/940] Bump mypy from 0.941 to 0.942 in /requirements (#653) Bumps [mypy](https://github.com/python/mypy) from 0.941 to 0.942. - [Release notes](https://github.com/python/mypy/releases) - [Commits](https://github.com/python/mypy/compare/v0.941...v0.942) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index f671321704..bdf1571465 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,5 +5,5 @@ matplotlib == 3.5.1 cvxpy == 1.2.0 pytest == 7.1.1 # For unit test pytest-xdist == 2.5.0 # For unit test -mypy == 0.941 # For unit test +mypy == 0.942 # For unit test flake8 == 4.0.1 # For unit test From 7ac2a17d23a840cf530ed9962a5236d1b25d6033 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 5 Apr 2022 07:25:46 +0900 Subject: [PATCH 484/940] Bump pandas from 1.4.1 to 1.4.2 in /requirements (#654) Bumps [pandas](https://github.com/pandas-dev/pandas) from 1.4.1 to 1.4.2. - [Release notes](https://github.com/pandas-dev/pandas/releases) - [Changelog](https://github.com/pandas-dev/pandas/blob/main/RELEASE.md) - [Commits](https://github.com/pandas-dev/pandas/compare/v1.4.1...v1.4.2) --- updated-dependencies: - dependency-name: pandas dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index bdf1571465..050904a674 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.22.3 scipy == 1.8.0 -pandas == 1.4.1 +pandas == 1.4.2 matplotlib == 3.5.1 cvxpy == 1.2.0 pytest == 7.1.1 # For unit test From 38261ec67efd65256f44cd92b88dba58502fc2f7 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 10 Apr 2022 19:30:31 +0900 Subject: [PATCH 485/940] clean up clothoidal_paths.py (#638) * clean up clothoidal_paths.py * add unit tests for clothoid_paths * add unit tests for clothoid_paths * add unit tests for clothoid_paths * code clean up * code clean up * code clean up * code clean up * code clean up * code clean up * code clean up * code clean up --- .../ClothoidPath/clothoid_path_planner.py | 192 ++++++++++++++++++ .../ClothoidalPaths/clothoidal_paths.py | 144 ------------- .../inverted_pendulum_control.rst | 14 +- .../clothoid_path/clothoid_path.rst | 80 ++++++++ .../path_planning/path_planning_main.rst | 1 + tests/test_clothoidal_paths.py | 11 + 6 files changed, 293 insertions(+), 149 deletions(-) create mode 100644 PathPlanning/ClothoidPath/clothoid_path_planner.py delete mode 100644 PathPlanning/ClothoidalPaths/clothoidal_paths.py create mode 100644 docs/modules/path_planning/clothoid_path/clothoid_path.rst create mode 100644 tests/test_clothoidal_paths.py diff --git a/PathPlanning/ClothoidPath/clothoid_path_planner.py b/PathPlanning/ClothoidPath/clothoid_path_planner.py new file mode 100644 index 0000000000..5e5fc6e9a3 --- /dev/null +++ b/PathPlanning/ClothoidPath/clothoid_path_planner.py @@ -0,0 +1,192 @@ +""" +Clothoid Path Planner +Author: Daniel Ingram (daniel-s-ingram) + Atsushi Sakai (AtsushiSakai) +Reference paper: Fast and accurate G1 fitting of clothoid curves +https://www.researchgate.net/publication/237062806 +""" + +from collections import namedtuple +import matplotlib.pyplot as plt +import numpy as np +import scipy.integrate as integrate +from scipy.optimize import fsolve +from math import atan2, cos, hypot, pi, sin +from matplotlib import animation + +Point = namedtuple("Point", ["x", "y"]) + +show_animation = True + + +def generate_clothoid_paths(start_point, start_yaw_list, + goal_point, goal_yaw_list, + n_path_points): + """ + Generate clothoid path list. This function generate multiple clothoid paths + from multiple orientations(yaw) at start points to multiple orientations + (yaw) at goal point. + + :param start_point: Start point of the path + :param start_yaw_list: Orientation list at start point in radian + :param goal_point: Goal point of the path + :param goal_yaw_list: Orientation list at goal point in radian + :param n_path_points: number of path points + :return: clothoid path list + """ + clothoids = [] + for start_yaw in start_yaw_list: + for goal_yaw in goal_yaw_list: + clothoid = generate_clothoid_path(start_point, start_yaw, + goal_point, goal_yaw, + n_path_points) + clothoids.append(clothoid) + return clothoids + + +def generate_clothoid_path(start_point, start_yaw, + goal_point, goal_yaw, n_path_points): + """ + Generate a clothoid path list. + + :param start_point: Start point of the path + :param start_yaw: Orientation at start point in radian + :param goal_point: Goal point of the path + :param goal_yaw: Orientation at goal point in radian + :param n_path_points: number of path points + :return: a clothoid path + """ + dx = goal_point.x - start_point.x + dy = goal_point.y - start_point.y + r = hypot(dx, dy) + + phi = atan2(dy, dx) + phi1 = normalize_angle(start_yaw - phi) + phi2 = normalize_angle(goal_yaw - phi) + delta = phi2 - phi1 + + try: + # Step1: Solve g function + A = solve_g_for_root(phi1, phi2, delta) + + # Step2: Calculate path parameters + L = compute_path_length(r, phi1, delta, A) + curvature = compute_curvature(delta, A, L) + curvature_rate = compute_curvature_rate(A, L) + except Exception as e: + print(f"Failed to generate clothoid points: {e}") + return None + + # Step3: Construct a path with Fresnel integral + points = [] + for s in np.linspace(0, L, n_path_points): + try: + x = start_point.x + s * X(curvature_rate * s ** 2, curvature * s, + start_yaw) + y = start_point.y + s * Y(curvature_rate * s ** 2, curvature * s, + start_yaw) + points.append(Point(x, y)) + except Exception as e: + print(f"Skipping failed clothoid point: {e}") + + return points + + +def X(a, b, c): + return integrate.quad(lambda t: cos((a/2)*t**2 + b*t + c), 0, 1)[0] + + +def Y(a, b, c): + return integrate.quad(lambda t: sin((a/2)*t**2 + b*t + c), 0, 1)[0] + + +def solve_g_for_root(theta1, theta2, delta): + initial_guess = 3*(theta1 + theta2) + return fsolve(lambda A: Y(2*A, delta - A, theta1), [initial_guess]) + + +def compute_path_length(r, theta1, delta, A): + return r / X(2*A, delta - A, theta1) + + +def compute_curvature(delta, A, L): + return (delta - A) / L + + +def compute_curvature_rate(A, L): + return 2 * A / (L**2) + + +def normalize_angle(angle_rad): + return (angle_rad + pi) % (2 * pi) - pi + + +def get_axes_limits(clothoids): + x_vals = [p.x for clothoid in clothoids for p in clothoid] + y_vals = [p.y for clothoid in clothoids for p in clothoid] + + x_min = min(x_vals) + x_max = max(x_vals) + y_min = min(y_vals) + y_max = max(y_vals) + + x_offset = 0.1*(x_max - x_min) + y_offset = 0.1*(y_max - y_min) + + x_min = x_min - x_offset + x_max = x_max + x_offset + y_min = y_min - y_offset + y_max = y_max + y_offset + + return x_min, x_max, y_min, y_max + + +def draw_clothoids(start, goal, num_steps, clothoidal_paths, + save_animation=False): + + fig = plt.figure(figsize=(10, 10)) + x_min, x_max, y_min, y_max = get_axes_limits(clothoidal_paths) + axes = plt.axes(xlim=(x_min, x_max), ylim=(y_min, y_max)) + + axes.plot(start.x, start.y, 'ro') + axes.plot(goal.x, goal.y, 'ro') + lines = [axes.plot([], [], 'b-')[0] for _ in range(len(clothoidal_paths))] + + def animate(i): + for line, clothoid_path in zip(lines, clothoidal_paths): + x = [p.x for p in clothoid_path[:i]] + y = [p.y for p in clothoid_path[:i]] + line.set_data(x, y) + + return lines + + anim = animation.FuncAnimation( + fig, + animate, + frames=num_steps, + interval=25, + blit=True + ) + if save_animation: + anim.save('clothoid.gif', fps=30, writer="imagemagick") + plt.show() + + +def main(): + start_point = Point(0, 0) + start_orientation_list = [0.0] + goal_point = Point(10, 0) + goal_orientation_list = np.linspace(-pi, pi, 75) + num_path_points = 100 + clothoid_paths = generate_clothoid_paths( + start_point, start_orientation_list, + goal_point, goal_orientation_list, + num_path_points) + if show_animation: + draw_clothoids(start_point, goal_point, + num_path_points, clothoid_paths, + save_animation=False) + + +if __name__ == "__main__": + main() diff --git a/PathPlanning/ClothoidalPaths/clothoidal_paths.py b/PathPlanning/ClothoidalPaths/clothoidal_paths.py deleted file mode 100644 index 6fbf46ed2a..0000000000 --- a/PathPlanning/ClothoidalPaths/clothoidal_paths.py +++ /dev/null @@ -1,144 +0,0 @@ -""" -Clothoidal Path Planner -Author: Daniel Ingram (daniel-s-ingram) -Reference paper: https://www.researchgate.net/publication/237062806 -""" - -import matplotlib.pyplot as plt -import numpy as np -import scipy.integrate as integrate -from collections import namedtuple -from scipy.optimize import fsolve -from math import atan2, cos, hypot, pi, sin -from matplotlib import animation - -Point = namedtuple("Point", ["x", "y"]) - - -def draw_clothoids( - theta1_vals, - theta2_vals, - num_clothoids=75, - num_steps=100, - save_animation=False -): - p1 = Point(0, 0) - p2 = Point(10, 0) - clothoids = [] - for theta1 in theta1_vals: - for theta2 in theta2_vals: - clothoid = get_clothoid_points(p1, p2, theta1, theta2, num_steps) - clothoids.append(clothoid) - - fig = plt.figure(figsize=(10, 10)) - x_min, x_max, y_min, y_max = get_axes_limits(clothoids) - axes = plt.axes(xlim=(x_min, x_max), ylim=(y_min, y_max)) - - axes.plot(p1.x, p1.y, 'ro') - axes.plot(p2.x, p2.y, 'ro') - lines = [axes.plot([], [], 'b-')[0] for _ in range(len(clothoids))] - - def animate(i): - for line, clothoid in zip(lines, clothoids): - x = [p.x for p in clothoid[:i]] - y = [p.y for p in clothoid[:i]] - line.set_data(x, y) - - return lines - - anim = animation.FuncAnimation( - fig, - animate, - frames=num_steps, - interval=25, - blit=True - ) - if save_animation: - anim.save('clothoid.gif', fps=30, writer="imagemagick") - plt.show() - - -def get_clothoid_points(p1, p2, theta1, theta2, num_steps=100): - dx = p2.x - p1.x - dy = p2.y - p1.y - r = hypot(dx, dy) - - phi = atan2(dy, dx) - phi1 = normalize_angle(theta1 - phi) - phi2 = normalize_angle(theta2 - phi) - delta = phi2 - phi1 - - try: - A = solve_for_root(phi1, phi2, delta) - L = compute_length(r, phi1, delta, A) - curv = compute_curvature(delta, A, L) - curv_rate = compute_curvature_rate(A, L) - except Exception as e: - print(f"Failed to generate clothoid points: {e}") - return None - - points = [] - for s in np.linspace(0, L, num_steps): - try: - x = p1.x + s*X(curv_rate*s**2, curv*s, theta1) - y = p1.y + s*Y(curv_rate*s**2, curv*s, theta1) - points.append(Point(x, y)) - except Exception as e: - print(f"Skipping failed clothoid point: {e}") - - return points - - -def X(a, b, c): - return integrate.quad(lambda t: cos((a/2)*t**2 + b*t + c), 0, 1)[0] - - -def Y(a, b, c): - return integrate.quad(lambda t: sin((a/2)*t**2 + b*t + c), 0, 1)[0] - - -def solve_for_root(theta1, theta2, delta): - initial_guess = 3*(theta1 + theta2) - return fsolve(lambda x: Y(2*x, delta - x, theta1), [initial_guess]) - - -def compute_length(r, theta1, delta, A): - return r / X(2*A, delta - A, theta1) - - -def compute_curvature(delta, A, L): - return (delta - A) / L - - -def compute_curvature_rate(A, L): - return 2 * A / (L**2) - - -def normalize_angle(angle_rad): - return (angle_rad + pi) % (2 * pi) - pi - - -def get_axes_limits(clothoids): - x_vals = [p.x for clothoid in clothoids for p in clothoid] - y_vals = [p.y for clothoid in clothoids for p in clothoid] - - x_min = min(x_vals) - x_max = max(x_vals) - y_min = min(y_vals) - y_max = max(y_vals) - - x_offset = 0.1*(x_max - x_min) - y_offset = 0.1*(y_max - y_min) - - x_min = x_min - x_offset - x_max = x_max + x_offset - y_min = y_min - y_offset - y_max = y_max + y_offset - - return x_min, x_max, y_min, y_max - - -if __name__ == "__main__": - theta1_vals = [0] - theta2_vals = np.linspace(-pi, pi, 75) - draw_clothoids(theta1_vals, theta2_vals, save_animation=False) diff --git a/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst b/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst index 5a447f7cd4..4c1f672ba0 100644 --- a/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst +++ b/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst @@ -34,7 +34,7 @@ So & \ddot{\theta} = \frac{g(M + m)sin{\theta} - \dot{\theta}^2lmsin{\theta}cos{\theta} + ucos{\theta}}{l(M + m - mcos^2{\theta})} -Linearlied model when :math:`\theta` small, :math:`cos{\theta} \approx 1`, :math:`sin{\theta} \approx \theta`, :math:`\dot{\theta}^2 \approx 0`. +Linearized model when :math:`\theta` small, :math:`cos{\theta} \approx 1`, :math:`sin{\theta} \approx \theta`, :math:`\dot{\theta}^2 \approx 0`. .. math:: & \ddot{x} = \frac{gm}{M}\theta + \frac{1}{M}u\\ @@ -68,16 +68,20 @@ If control x and \theta LQR control ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -The LQR cotroller minimize this cost function defined as: +The LQR controller minimize this cost function defined as: .. math:: J = x^T Q x + u^T R u + the feedback control law that minimizes the value of the cost is: .. math:: u = -K x + where: .. math:: K = (B^T P B + R)^{-1} B^T P A -and :math:`P` is the unique positive definite solution to the discrete time `algebraic Riccati equation `__ (DARE): + +and :math:`P` is the unique positive definite solution to the discrete time +`algebraic Riccati equation `__ (DARE): .. math:: P = A^T P A - A^T P B ( R + B^T P B )^{-1} B^T P A + Q @@ -85,13 +89,13 @@ and :math:`P` is the unique positive definite solution to the discrete time `alg MPC control ~~~~~~~~~~~~~~~~~~~~~~~~~~~ -The MPC cotroller minimize this cost function defined as: +The MPC controller minimize this cost function defined as: .. math:: J = x^T Q x + u^T R u subject to: -- Linearlied Inverted Pendulum model +- Linearized Inverted Pendulum model - Initial state .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/Control/InvertedPendulumCart/animation.gif diff --git a/docs/modules/path_planning/clothoid_path/clothoid_path.rst b/docs/modules/path_planning/clothoid_path/clothoid_path.rst new file mode 100644 index 0000000000..1e8cee694a --- /dev/null +++ b/docs/modules/path_planning/clothoid_path/clothoid_path.rst @@ -0,0 +1,80 @@ +.. _clothoid-path-planning: + +Clothoid path planning +-------------------------- + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClothoidPath/animation1.gif +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClothoidPath/animation2.gif +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/ClothoidPath/animation3.gif + +This is a clothoid path planning sample code. + +This can interpolate two 2D pose (x, y, yaw) with a clothoid path, +which its curvature is linearly continuous. +In other words, this is G1 Hermite interpolation with a single clothoid segment. + +This path planning algorithm as follows: + +Step1: Solve g function +~~~~~~~~~~~~~~~~~~~~~~~ + +Solve the g(A) function with a nonlinear optimization solver. + +.. math:: + + g(A):=Y(2A, \delta-A, \phi_{s}) + +Where + +* :math:`\delta`: the orientation difference between start and goal pose. +* :math:`\phi_{s}`: the orientation of the start pose. +* :math:`Y`: :math:`Y(a, b, c)=\int_{0}^{1} \sin \left(\frac{a}{2} \tau^{2}+b \tau+c\right) d \tau` + + +Step2: Calculate path parameters +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +We can calculate these path parameters using :math:`A`, + +:math:`L`: path length + +.. math:: + + L=\frac{R}{X\left(2 A, \delta-A, \phi_{s}\right)} + +where + +* :math:`R`: the distance between start and goal pose +* :math:`X`: :math:`X(a, b, c)=\int_{0}^{1} \cos \left(\frac{a}{2} \tau^{2}+b \tau+c\right) d \tau` + + +- :math:`\kappa`: curvature + +.. math:: + + \kappa=(\delta-A) / L + + +- :math:`\kappa'`: curvature rate + +.. math:: + + \kappa^{\prime}=2 A / L^{2} + + +Step3: Construct a path with Fresnel integral +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +The final clothoid path can be calculated with the path parameters and Fresnel integrals. + +.. math:: + \begin{aligned} + &x(s)=x_{0}+\int_{0}^{s} \cos \left(\frac{1}{2} \kappa^{\prime} \tau^{2}+\kappa \tau+\vartheta_{0}\right) \mathrm{d} \tau \\ + &y(s)=y_{0}+\int_{0}^{s} \sin \left(\frac{1}{2} \kappa^{\prime} \tau^{2}+\kappa \tau+\vartheta_{0}\right) \mathrm{d} \tau + \end{aligned} + + +References +~~~~~~~~~~ + +- `Fast and accurate G1 fitting of clothoid curves `__ diff --git a/docs/modules/path_planning/path_planning_main.rst b/docs/modules/path_planning/path_planning_main.rst index c3c5c389ec..5c70592afc 100644 --- a/docs/modules/path_planning/path_planning_main.rst +++ b/docs/modules/path_planning/path_planning_main.rst @@ -14,6 +14,7 @@ Path Planning .. include:: rrt/rrt.rst .. include:: cubic_spline/cubic_spline.rst .. include:: bspline_path/bspline_path.rst +.. include:: clothoid_path/clothoid_path.rst .. include:: eta3_spline/eta3_spline.rst .. include:: bezier_path/bezier_path.rst .. include:: quintic_polynomials_planner/quintic_polynomials_planner.rst diff --git a/tests/test_clothoidal_paths.py b/tests/test_clothoidal_paths.py new file mode 100644 index 0000000000..0b038c0338 --- /dev/null +++ b/tests/test_clothoidal_paths.py @@ -0,0 +1,11 @@ +import conftest +from PathPlanning.ClothoidPath import clothoid_path_planner as m + + +def test_1(): + m.show_animation = False + m.main() + + +if __name__ == '__main__': + conftest.run_this_test(__file__) From af2061a1e784a6779bdc08976a43157ddae17884 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 11 Apr 2022 23:06:13 +0900 Subject: [PATCH 486/940] fix doc artifact link in CI (#660) --- PathPlanning/HybridAStar/car.py | 14 +++++++------- PathPlanning/HybridAStar/hybrid_a_star.py | 6 +++--- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/PathPlanning/HybridAStar/car.py b/PathPlanning/HybridAStar/car.py index cc7529b9c7..b378447fcd 100644 --- a/PathPlanning/HybridAStar/car.py +++ b/PathPlanning/HybridAStar/car.py @@ -12,14 +12,14 @@ import numpy as np from scipy.spatial.transform import Rotation as Rot -WB = 3. # rear to front wheel -W = 2. # width of car +WB = 3.0 # rear to front wheel +W = 2.0 # width of car LF = 3.3 # distance from rear to vehicle front end LB = 1.0 # distance from rear to vehicle back end MAX_STEER = 0.6 # [rad] maximum steering angle -W_BUBBLE_DIST = (LF - LB) / 2.0 -W_BUBBLE_R = sqrt(((LF + LB) / 2.0) ** 2 + 1) +BUBBLE_DIST = (LF - LB) / 2.0 # distance from rear to center of vehicle. +BUBBLE_R = np.hypot((LF + LB) / 2.0, W / 2.0) # bubble radius # vehicle rectangle vertices VRX = [LF, LF, -LB, -LB, LF] @@ -28,10 +28,10 @@ def check_car_collision(x_list, y_list, yaw_list, ox, oy, kd_tree): for i_x, i_y, i_yaw in zip(x_list, y_list, yaw_list): - cx = i_x + W_BUBBLE_DIST * cos(i_yaw) - cy = i_y + W_BUBBLE_DIST * sin(i_yaw) + cx = i_x + BUBBLE_DIST * cos(i_yaw) + cy = i_y + BUBBLE_DIST * sin(i_yaw) - ids = kd_tree.query_ball_point([cx, cy], W_BUBBLE_R) + ids = kd_tree.query_ball_point([cx, cy], BUBBLE_R) if not ids: continue diff --git a/PathPlanning/HybridAStar/hybrid_a_star.py b/PathPlanning/HybridAStar/hybrid_a_star.py index 9679e3979b..4ef0c1dd21 100644 --- a/PathPlanning/HybridAStar/hybrid_a_star.py +++ b/PathPlanning/HybridAStar/hybrid_a_star.py @@ -20,7 +20,8 @@ try: from dynamic_programming_heuristic import calc_distance_heuristic import reeds_shepp_path_planning as rs - from car import move, check_car_collision, MAX_STEER, WB, plot_car + from car import move, check_car_collision, MAX_STEER, WB, plot_car,\ + BUBBLE_R except Exception: raise @@ -28,7 +29,6 @@ YAW_GRID_RESOLUTION = np.deg2rad(15.0) # [rad] MOTION_RESOLUTION = 0.1 # [m] path interpolate resolution N_STEER = 20 # number of steer command -VR = 1.0 # robot radius SB_COST = 100.0 # switch back penalty cost BACK_COST = 5.0 # backward penalty cost @@ -276,7 +276,7 @@ def hybrid_a_star_planning(start, goal, ox, oy, xy_resolution, yaw_resolution): h_dp = calc_distance_heuristic( goal_node.x_list[-1], goal_node.y_list[-1], - ox, oy, xy_resolution, VR) + ox, oy, xy_resolution, BUBBLE_R) pq = [] openList[calc_index(start_node, config)] = start_node From b53fdf75f66ccb63b5cfaadaa81253d43f01805a Mon Sep 17 00:00:00 2001 From: Chris Mower Date: Tue, 19 Apr 2022 04:53:24 +0100 Subject: [PATCH 487/940] Add optional robot radius to RRT/RRTStar path planners (#655) * Add optional robot radius to RRT/RRTStar path planners. * update __init__ and check_collision to include radius * during animation, if a robot radius is given then it is drawn * Add test for robot radius * Correct import error * Correct missing robot_radius errors * Address "expected 2 blank lines, found 1" error * Address "line too long" errors * Add missing argument description. * Remove collision_check_with_xy and replace with check_collision * Fix "missing whitespace after ','" error * Update PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py Co-authored-by: Atsushi Sakai Co-authored-by: Atsushi Sakai --- .../closed_loop_rrt_star_car.py | 23 +++++++------------ PathPlanning/LQRRRTStar/lqr_rrt_star.py | 8 +++++-- PathPlanning/RRT/rrt.py | 18 +++++++++++---- PathPlanning/RRT/rrt_with_sobol_sampler.py | 20 +++++++++++----- PathPlanning/RRTDubins/rrt_dubins.py | 6 ++++- PathPlanning/RRTStar/rrt_star.py | 21 +++++++++++------ PathPlanning/RRTStarDubins/rrt_star_dubins.py | 8 +++++-- .../RRTStarReedsShepp/rrt_star_reeds_shepp.py | 11 ++++++--- tests/test_rrt_star.py | 13 +++++++++++ tests/test_rrt_star_reeds_shepp.py | 2 +- 10 files changed, 88 insertions(+), 42 deletions(-) diff --git a/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py b/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py index c0c8c356e8..dc9a575694 100644 --- a/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py +++ b/PathPlanning/ClosedLoopRRTStar/closed_loop_rrt_star_car.py @@ -37,11 +37,13 @@ class ClosedLoopRRTStar(RRTStarReedsShepp): def __init__(self, start, goal, obstacle_list, rand_area, max_iter=200, - connect_circle_dist=50.0 + connect_circle_dist=50.0, + robot_radius=0.0 ): super().__init__(start, goal, obstacle_list, rand_area, max_iter=max_iter, connect_circle_dist=connect_circle_dist, + robot_radius=robot_radius ) self.target_speed = 10.0 / 3.6 @@ -127,7 +129,11 @@ def check_tracking_path_is_feasible(self, path): print("path is too long") find_goal = False - if not self.collision_check_with_xy(x, y, self.obstacle_list): + tmp_node = self.Node(x, y, 0) + tmp_node.path_x = x + tmp_node.path_y = y + if not self.check_collision( + tmp_node, self.obstacle_list, self.robot_radius): print("This path is collision") find_goal = False @@ -151,19 +157,6 @@ def get_goal_indexes(self): return fgoalinds - @staticmethod - def collision_check_with_xy(x, y, obstacle_list): - - for (ox, oy, size) in obstacle_list: - for (ix, iy) in zip(x, y): - dx = ox - ix - dy = oy - iy - d = dx * dx + dy * dy - if d <= size ** 2: - return False # collision - - return True # safe - def main(gx=6.0, gy=7.0, gyaw=np.deg2rad(90.0), max_iter=100): print("Start" + __file__) diff --git a/PathPlanning/LQRRRTStar/lqr_rrt_star.py b/PathPlanning/LQRRRTStar/lqr_rrt_star.py index 177131ac96..28d332aa00 100644 --- a/PathPlanning/LQRRRTStar/lqr_rrt_star.py +++ b/PathPlanning/LQRRRTStar/lqr_rrt_star.py @@ -35,7 +35,8 @@ def __init__(self, start, goal, obstacle_list, rand_area, goal_sample_rate=10, max_iter=200, connect_circle_dist=50.0, - step_size=0.2 + step_size=0.2, + robot_radius=0.0, ): """ Setting Parameter @@ -44,6 +45,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, goal:Goal Position [x,y] obstacleList:obstacle Positions [[x,y,size],...] randArea:Random Sampling Area [min,max] + robot_radius: robot body modeled as circle with given radius """ self.start = self.Node(start[0], start[1]) @@ -58,6 +60,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, self.curvature = 1.0 self.goal_xy_th = 0.5 self.step_size = step_size + self.robot_radius = robot_radius self.lqr_planner = LQRPlanner() @@ -75,7 +78,8 @@ def planning(self, animation=True, search_until_max_iter=True): nearest_ind = self.get_nearest_node_index(self.node_list, rnd) new_node = self.steer(self.node_list[nearest_ind], rnd) - if self.check_collision(new_node, self.obstacle_list): + if self.check_collision( + new_node, self.obstacle_list, self.robot_radius): near_indexes = self.find_near_nodes(new_node) new_node = self.choose_parent(new_node, near_indexes) if new_node: diff --git a/PathPlanning/RRT/rrt.py b/PathPlanning/RRT/rrt.py index dfbd4b1b7f..55092e6e00 100644 --- a/PathPlanning/RRT/rrt.py +++ b/PathPlanning/RRT/rrt.py @@ -50,7 +50,8 @@ def __init__(self, path_resolution=0.5, goal_sample_rate=5, max_iter=500, - play_area=None + play_area=None, + robot_radius=0.0, ): """ Setting Parameter @@ -60,6 +61,7 @@ def __init__(self, obstacleList:obstacle Positions [[x,y,size],...] randArea:Random Sampling Area [min,max] play_area:stay inside this area [xmin,xmax,ymin,ymax] + robot_radius: robot body modeled as circle with given radius """ self.start = self.Node(start[0], start[1]) @@ -76,6 +78,7 @@ def __init__(self, self.max_iter = max_iter self.obstacle_list = obstacle_list self.node_list = [] + self.robot_radius = robot_radius def planning(self, animation=True): """ @@ -93,7 +96,8 @@ def planning(self, animation=True): new_node = self.steer(nearest_node, rnd_node, self.expand_dis) if self.check_if_outside_play_area(new_node, self.play_area) and \ - self.check_collision(new_node, self.obstacle_list): + self.check_collision( + new_node, self.obstacle_list, self.robot_radius): self.node_list.append(new_node) if animation and i % 5 == 0: @@ -103,7 +107,8 @@ def planning(self, animation=True): self.node_list[-1].y) <= self.expand_dis: final_node = self.steer(self.node_list[-1], self.end, self.expand_dis) - if self.check_collision(final_node, self.obstacle_list): + if self.check_collision( + final_node, self.obstacle_list, self.robot_radius): return self.generate_final_course(len(self.node_list) - 1) if animation and i % 5: @@ -173,6 +178,8 @@ def draw_graph(self, rnd=None): lambda event: [exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") + if self.robot_radius > 0.0: + self.plot_circle(rnd.x, rnd.y, self.robot_radius, '-r') for node in self.node_list: if node.parent: plt.plot(node.path_x, node.path_y, "-g") @@ -225,7 +232,7 @@ def check_if_outside_play_area(node, play_area): return True # inside - ok @staticmethod - def check_collision(node, obstacleList): + def check_collision(node, obstacleList, robot_radius): if node is None: return False @@ -235,7 +242,7 @@ def check_collision(node, obstacleList): dy_list = [oy - y for y in node.path_y] d_list = [dx * dx + dy * dy for (dx, dy) in zip(dx_list, dy_list)] - if min(d_list) <= size**2: + if min(d_list) <= (size+robot_radius)**2: return False # collision return True # safe @@ -262,6 +269,7 @@ def main(gx=6.0, gy=10.0): rand_area=[-2, 15], obstacle_list=obstacleList, # play_area=[0, 10, 0, 14] + robot_radius=0.8 ) path = rrt.planning(animation=show_animation) diff --git a/PathPlanning/RRT/rrt_with_sobol_sampler.py b/PathPlanning/RRT/rrt_with_sobol_sampler.py index b88e51c680..8045d8f764 100644 --- a/PathPlanning/RRT/rrt_with_sobol_sampler.py +++ b/PathPlanning/RRT/rrt_with_sobol_sampler.py @@ -62,7 +62,8 @@ def __init__(self, expand_dis=3.0, path_resolution=0.5, goal_sample_rate=5, - max_iter=500): + max_iter=500, + robot_radius=0.0): """ Setting Parameter @@ -70,6 +71,7 @@ def __init__(self, goal:Goal Position [x,y] obstacle_list:obstacle Positions [[x,y,size],...] randArea:Random Sampling Area [min,max] + robot_radius: robot body modeled as circle with given radius """ self.start = self.Node(start[0], start[1]) @@ -83,6 +85,7 @@ def __init__(self, self.obstacle_list = obstacle_list self.node_list = [] self.sobol_inter_ = 0 + self.robot_radius = robot_radius def planning(self, animation=True): """ @@ -99,7 +102,8 @@ def planning(self, animation=True): new_node = self.steer(nearest_node, rnd_node, self.expand_dis) - if self.check_collision(new_node, self.obstacle_list): + if self.check_collision( + new_node, self.obstacle_list, self.robot_radius): self.node_list.append(new_node) if animation and i % 5 == 0: @@ -109,7 +113,8 @@ def planning(self, animation=True): self.node_list[-1].y) <= self.expand_dis: final_node = self.steer(self.node_list[-1], self.end, self.expand_dis) - if self.check_collision(final_node, self.obstacle_list): + if self.check_collision( + final_node, self.obstacle_list, self.robot_radius): return self.generate_final_course(len(self.node_list) - 1) if animation and i % 5: @@ -183,6 +188,8 @@ def draw_graph(self, rnd=None): lambda event: [sys.exit(0) if event.key == 'escape' else None]) if rnd is not None: plt.plot(rnd.x, rnd.y, "^k") + if self.robot_radius >= 0.0: + self.plot_circle(rnd.x, rnd.y, self.robot_radius, '-r') for node in self.node_list: if node.parent: plt.plot(node.path_x, node.path_y, "-g") @@ -214,7 +221,7 @@ def get_nearest_node_index(node_list, rnd_node): return minind @staticmethod - def check_collision(node, obstacle_list): + def check_collision(node, obstacle_list, robot_radius): if node is None: return False @@ -224,7 +231,7 @@ def check_collision(node, obstacle_list): dy_list = [oy - y for y in node.path_y] d_list = [dx * dx + dy * dy for (dx, dy) in zip(dx_list, dy_list)] - if min(d_list) <= size**2: + if min(d_list) <= (size+robot_radius)**2: return False # collision return True # safe @@ -249,7 +256,8 @@ def main(gx=6.0, gy=10.0): start=[0, 0], goal=[gx, gy], rand_area=[-2, 15], - obstacle_list=obstacle_list) + obstacle_list=obstacle_list, + robot_radius=0.8) path = rrt.planning(animation=show_animation) if path is None: diff --git a/PathPlanning/RRTDubins/rrt_dubins.py b/PathPlanning/RRTDubins/rrt_dubins.py index 8ab06c7323..a43362b340 100644 --- a/PathPlanning/RRTDubins/rrt_dubins.py +++ b/PathPlanning/RRTDubins/rrt_dubins.py @@ -46,6 +46,7 @@ def __init__(self, x, y, yaw): def __init__(self, start, goal, obstacle_list, rand_area, goal_sample_rate=10, max_iter=200, + robot_radius=0.0 ): """ Setting Parameter @@ -54,6 +55,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, goal:Goal Position [x,y] obstacleList:obstacle Positions [[x,y,size],...] randArea:Random Sampling Area [min,max] + robot_radius: robot body modeled as circle with given radius """ self.start = self.Node(start[0], start[1], start[2]) @@ -67,6 +69,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, self.curvature = 1.0 # for dubins path self.goal_yaw_th = np.deg2rad(1.0) self.goal_xy_th = 0.5 + self.robot_radius = robot_radius def planning(self, animation=True, search_until_max_iter=True): """ @@ -82,7 +85,8 @@ def planning(self, animation=True, search_until_max_iter=True): nearest_ind = self.get_nearest_node_index(self.node_list, rnd) new_node = self.steer(self.node_list[nearest_ind], rnd) - if self.check_collision(new_node, self.obstacle_list): + if self.check_collision( + new_node, self.obstacle_list, self.robot_radius): self.node_list.append(new_node) if animation and i % 5 == 0: diff --git a/PathPlanning/RRTStar/rrt_star.py b/PathPlanning/RRTStar/rrt_star.py index bef0086095..e2c05456de 100644 --- a/PathPlanning/RRTStar/rrt_star.py +++ b/PathPlanning/RRTStar/rrt_star.py @@ -42,7 +42,8 @@ def __init__(self, goal_sample_rate=20, max_iter=300, connect_circle_dist=50.0, - search_until_max_iter=False): + search_until_max_iter=False, + robot_radius=0.0): """ Setting Parameter @@ -53,7 +54,8 @@ def __init__(self, """ super().__init__(start, goal, obstacle_list, rand_area, expand_dis, - path_resolution, goal_sample_rate, max_iter) + path_resolution, goal_sample_rate, max_iter, + robot_radius=robot_radius) self.connect_circle_dist = connect_circle_dist self.goal_node = self.Node(goal[0], goal[1]) self.search_until_max_iter = search_until_max_iter @@ -77,7 +79,8 @@ def planning(self, animation=True): math.hypot(new_node.x-near_node.x, new_node.y-near_node.y) - if self.check_collision(new_node, self.obstacle_list): + if self.check_collision( + new_node, self.obstacle_list, self.robot_radius): near_inds = self.find_near_nodes(new_node) node_with_updated_parent = self.choose_parent( new_node, near_inds) @@ -128,7 +131,8 @@ def choose_parent(self, new_node, near_inds): for i in near_inds: near_node = self.node_list[i] t_node = self.steer(near_node, new_node) - if t_node and self.check_collision(t_node, self.obstacle_list): + if t_node and self.check_collision( + t_node, self.obstacle_list, self.robot_radius): costs.append(self.calc_new_cost(near_node, new_node)) else: costs.append(float("inf")) # the cost of collision node @@ -156,7 +160,8 @@ def search_best_goal_node(self): safe_goal_inds = [] for goal_ind in goal_inds: t_node = self.steer(self.node_list[goal_ind], self.goal_node) - if self.check_collision(t_node, self.obstacle_list): + if self.check_collision( + t_node, self.obstacle_list, self.robot_radius): safe_goal_inds.append(goal_ind) if not safe_goal_inds: @@ -219,7 +224,8 @@ def rewire(self, new_node, near_inds): continue edge_node.cost = self.calc_new_cost(new_node, near_node) - no_collision = self.check_collision(edge_node, self.obstacle_list) + no_collision = self.check_collision( + edge_node, self.obstacle_list, self.robot_radius) improved_cost = near_node.cost > edge_node.cost if no_collision and improved_cost: @@ -264,7 +270,8 @@ def main(): goal=[6, 10], rand_area=[-2, 15], obstacle_list=obstacle_list, - expand_dis=1) + expand_dis=1, + robot_radius=0.8) path = rrt_star.planning(animation=show_animation) if path is None: diff --git a/PathPlanning/RRTStarDubins/rrt_star_dubins.py b/PathPlanning/RRTStarDubins/rrt_star_dubins.py index 26367eecea..21cc9b2bc5 100644 --- a/PathPlanning/RRTStarDubins/rrt_star_dubins.py +++ b/PathPlanning/RRTStarDubins/rrt_star_dubins.py @@ -46,7 +46,8 @@ def __init__(self, x, y, yaw): def __init__(self, start, goal, obstacle_list, rand_area, goal_sample_rate=10, max_iter=200, - connect_circle_dist=50.0 + connect_circle_dist=50.0, + robot_radius=0.0, ): """ Setting Parameter @@ -55,6 +56,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, goal:Goal Position [x,y] obstacleList:obstacle Positions [[x,y,size],...] randArea:Random Sampling Area [min,max] + robot_radius: robot body modeled as circle with given radius """ self.start = self.Node(start[0], start[1], start[2]) @@ -69,6 +71,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, self.curvature = 1.0 # for dubins path self.goal_yaw_th = np.deg2rad(1.0) self.goal_xy_th = 0.5 + self.robot_radius = robot_radius def planning(self, animation=True, search_until_max_iter=True): """ @@ -84,7 +87,8 @@ def planning(self, animation=True, search_until_max_iter=True): nearest_ind = self.get_nearest_node_index(self.node_list, rnd) new_node = self.steer(self.node_list[nearest_ind], rnd) - if self.check_collision(new_node, self.obstacle_list): + if self.check_collision( + new_node, self.obstacle_list, self.robot_radius): near_indexes = self.find_near_nodes(new_node) new_node = self.choose_parent(new_node, near_indexes) if new_node: diff --git a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py index 6ea66dc729..323bc76be2 100644 --- a/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py +++ b/PathPlanning/RRTStarReedsShepp/rrt_star_reeds_shepp.py @@ -45,7 +45,8 @@ def __init__(self, x, y, yaw): def __init__(self, start, goal, obstacle_list, rand_area, max_iter=200, - connect_circle_dist=50.0 + connect_circle_dist=50.0, + robot_radius=0.0 ): """ Setting Parameter @@ -54,6 +55,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, goal:Goal Position [x,y] obstacleList:obstacle Positions [[x,y,size],...] randArea:Random Sampling Area [min,max] + robot_radius: robot body modeled as circle with given radius """ self.start = self.Node(start[0], start[1], start[2]) @@ -63,6 +65,7 @@ def __init__(self, start, goal, obstacle_list, rand_area, self.max_iter = max_iter self.obstacle_list = obstacle_list self.connect_circle_dist = connect_circle_dist + self.robot_radius = robot_radius self.curvature = 1.0 self.goal_yaw_th = np.deg2rad(1.0) @@ -82,7 +85,8 @@ def planning(self, animation=True, search_until_max_iter=True): nearest_ind = self.get_nearest_node_index(self.node_list, rnd) new_node = self.steer(self.node_list[nearest_ind], rnd) - if self.check_collision(new_node, self.obstacle_list): + if self.check_collision( + new_node, self.obstacle_list, self.robot_radius): near_indexes = self.find_near_nodes(new_node) new_node = self.choose_parent(new_node, near_indexes) if new_node: @@ -117,7 +121,8 @@ def try_goal_path(self, node): if new_node is None: return - if self.check_collision(new_node, self.obstacle_list): + if self.check_collision( + new_node, self.obstacle_list, self.robot_radius): self.node_list.append(new_node) def draw_graph(self, rnd=None): diff --git a/tests/test_rrt_star.py b/tests/test_rrt_star.py index 5327f4ca20..232995ecb4 100644 --- a/tests/test_rrt_star.py +++ b/tests/test_rrt_star.py @@ -19,5 +19,18 @@ def test_no_obstacle(): assert path is not None +def test_no_obstacle_and_robot_radius(): + obstacle_list = [] + + # Set Initial parameters + rrt_star = m.RRTStar(start=[0, 0], + goal=[6, 10], + rand_area=[-2, 15], + obstacle_list=obstacle_list, + robot_radius=0.8) + path = rrt_star.planning(animation=False) + assert path is not None + + if __name__ == '__main__': conftest.run_this_test(__file__) diff --git a/tests/test_rrt_star_reeds_shepp.py b/tests/test_rrt_star_reeds_shepp.py index 0a4663056a..cb6b586b33 100644 --- a/tests/test_rrt_star_reeds_shepp.py +++ b/tests/test_rrt_star_reeds_shepp.py @@ -1,5 +1,5 @@ import conftest # Add root path to sys.path -import rrt_star_reeds_shepp as m +from PathPlanning.RRTStarReedsShepp import rrt_star_reeds_shepp as m def test1(): From 4f8c923589af8738b97fe821938ea5f51d55b096 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 26 Apr 2022 07:15:19 +0900 Subject: [PATCH 488/940] Bump pytest from 7.1.1 to 7.1.2 in /requirements (#661) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.1.1 to 7.1.2. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.1.1...7.1.2) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 050904a674..25d15e780c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,7 +3,7 @@ scipy == 1.8.0 pandas == 1.4.2 matplotlib == 3.5.1 cvxpy == 1.2.0 -pytest == 7.1.1 # For unit test +pytest == 7.1.2 # For unit test pytest-xdist == 2.5.0 # For unit test mypy == 0.942 # For unit test flake8 == 4.0.1 # For unit test From 28d95730448ff25bbe7ec6d2e7d9240800e2ac4a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 2 May 2022 21:01:46 +0900 Subject: [PATCH 489/940] fix doc artifact link in CI (#659) * fix doc artifact link in CI * fix doc artifact link in CI * fix doc artifact link in CI * fix doc artifact link in CI --- .circleci/artifact_path | 1 - .circleci/config.yml | 2 +- .github/workflows/circle_artifacts.yml | 13 +++++++++++++ .github/workflows/circleci-artifacts-redirector.yml | 2 +- 4 files changed, 15 insertions(+), 3 deletions(-) delete mode 100644 .circleci/artifact_path create mode 100644 .github/workflows/circle_artifacts.yml diff --git a/.circleci/artifact_path b/.circleci/artifact_path deleted file mode 100644 index d2c64880b1..0000000000 --- a/.circleci/artifact_path +++ /dev/null @@ -1 +0,0 @@ -0/html/index.html diff --git a/.circleci/config.yml b/.circleci/config.yml index 0a1962ad0b..8df4fab9e4 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -6,7 +6,7 @@ orbs: jobs: build_doc: docker: - - image: circleci/python:3.9 + - image: cimg/python:3.9 steps: - checkout - run: diff --git a/.github/workflows/circle_artifacts.yml b/.github/workflows/circle_artifacts.yml new file mode 100644 index 0000000000..56ac78ed15 --- /dev/null +++ b/.github/workflows/circle_artifacts.yml @@ -0,0 +1,13 @@ +on: [status] +jobs: + circleci_artifacts_redirector_job: + runs-on: ubuntu-20.04 + name: Run CircleCI artifacts redirector + steps: + - name: GitHub Action step + uses: larsoner/circleci-artifacts-redirector-action@master + with: + repo-token: ${{ secrets.GITHUB_TOKEN }} + artifact-path: 0/html-scipyorg/index.html + circleci-jobs: build_docs + job-title: build_doc artifact \ No newline at end of file diff --git a/.github/workflows/circleci-artifacts-redirector.yml b/.github/workflows/circleci-artifacts-redirector.yml index 951e3a5947..d988d2c38e 100644 --- a/.github/workflows/circleci-artifacts-redirector.yml +++ b/.github/workflows/circleci-artifacts-redirector.yml @@ -6,7 +6,7 @@ jobs: name: Run CircleCI artifacts redirector steps: - name: run-circleci-artifacts-redirector - uses: larsoner/circleci-artifacts-redirector-action@0.2.0 + uses: larsoner/circleci-artifacts-redirector-action@0.3.1 with: repo-token: ${{ secrets.GITHUB_TOKEN }} artifact-path: 0/html/index.html From 163cc5ea58d68ee994f1546d118333dc01217552 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 2 May 2022 21:06:33 +0900 Subject: [PATCH 490/940] Update dubins_path.rst (#663) * Update dubins_path.rst * Update dubins_path.rst --- .../path_planning/dubins_path/dubins_path.rst | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/docs/modules/path_planning/dubins_path/dubins_path.rst b/docs/modules/path_planning/dubins_path/dubins_path.rst index 5e14820f8f..6765a84617 100644 --- a/docs/modules/path_planning/dubins_path/dubins_path.rst +++ b/docs/modules/path_planning/dubins_path/dubins_path.rst @@ -5,7 +5,18 @@ A sample code for Dubins path planning. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathPlanning/DubinsPath/animation.gif?raw=True -Ref: +Dubins path +~~~~~~~~~~~~ +Dubims path is a analyrical path planning algorithm for a simple car model. -- `Dubins path - - Wikipedia `__ +It can generates a shortest path between 2D poses (x, y, yaw) with maximum curvture comstraint and tangent(yaw angle) constraint. + + + + + +Reference +~~~~~~~~~~~~~~~~~~~~ + +- `Dubins path - Wikipedia `__ +- `15.3.1 Dubins Curves `__ From 462a8cd6c0fd48434af126204bf5b1eca7ac7357 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 3 May 2022 07:23:49 +0900 Subject: [PATCH 491/940] Bump mypy from 0.942 to 0.950 in /requirements (#665) Bumps [mypy](https://github.com/python/mypy) from 0.942 to 0.950. - [Release notes](https://github.com/python/mypy/releases) - [Commits](https://github.com/python/mypy/compare/v0.942...v0.950) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 25d15e780c..46f56702ea 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -5,5 +5,5 @@ matplotlib == 3.5.1 cvxpy == 1.2.0 pytest == 7.1.2 # For unit test pytest-xdist == 2.5.0 # For unit test -mypy == 0.942 # For unit test +mypy == 0.950 # For unit test flake8 == 4.0.1 # For unit test From 32b545fe7c35b57f280cd9d570f62839886f2e4b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 7 May 2022 13:19:30 +0900 Subject: [PATCH 492/940] Enhance dubins path docs (#664) * Engance dubins path docs * Update dubins_path.rst * fix doc artifact link in CI * wip * wip * wip * Update dubins_path.rst * wip * wip * wip * wip * wip --- .circleci/config.yml | 1 + ...ath_planning.py => dubins_path_planner.py} | 150 ++++++++++-------- PathPlanning/HybridAStar/car.py | 2 +- PathPlanning/RRTDubins/rrt_dubins.py | 10 +- PathPlanning/RRTStarDubins/rrt_star_dubins.py | 10 +- docs/conf.py | 5 +- docs/doc_requirements.txt | 1 + .../modules/path_planning/dubins_path/RLR.jpg | Bin 0 -> 10220 bytes .../modules/path_planning/dubins_path/RSR.jpg | Bin 0 -> 10245 bytes .../path_planning/dubins_path/dubins_path.rst | 28 +++- tests/test_diff_codestyle.py | 4 +- tests/test_dubins_path_planning.py | 12 +- tests/test_utils.py | 21 +++ utils/__init__.py | 0 utils/angle.py | 77 +++++++++ 15 files changed, 235 insertions(+), 86 deletions(-) rename PathPlanning/DubinsPath/{dubins_path_planning.py => dubins_path_planner.py} (72%) create mode 100644 docs/modules/path_planning/dubins_path/RLR.jpg create mode 100644 docs/modules/path_planning/dubins_path/RSR.jpg create mode 100644 tests/test_utils.py create mode 100644 utils/__init__.py create mode 100644 utils/angle.py diff --git a/.circleci/config.yml b/.circleci/config.yml index 8df4fab9e4..275ad3bc7a 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -14,6 +14,7 @@ jobs: command: | python -m venv venv . venv/bin/activate + pip install -r requirements/requirements.txt pip install -r docs/doc_requirements.txt cd docs;make html - store_artifacts: diff --git a/PathPlanning/DubinsPath/dubins_path_planning.py b/PathPlanning/DubinsPath/dubins_path_planner.py similarity index 72% rename from PathPlanning/DubinsPath/dubins_path_planning.py rename to PathPlanning/DubinsPath/dubins_path_planner.py index f8e6d7b1c1..69c213ddf4 100644 --- a/PathPlanning/DubinsPath/dubins_path_planning.py +++ b/PathPlanning/DubinsPath/dubins_path_planner.py @@ -5,64 +5,82 @@ author Atsushi Sakai(@Atsushi_twi) """ -import math +import sys +import os +sys.path.append(os.path.dirname(os.path.abspath(__file__)) + "/../utils/") -import matplotlib.pyplot as plt +import math import numpy as np -from scipy.spatial.transform import Rotation as Rot +from utils.angle import angle_mod, create_2d_rotation_matrix show_animation = True -def dubins_path_planning(s_x, s_y, s_yaw, g_x, g_y, g_yaw, curvature, - step_size=0.1): +def plan_dubins_path(s_x, s_y, s_yaw, + g_x, g_y, g_yaw, + curvature, + step_size=0.1): """ - Dubins path planner - - :param s_x: x position of start point [m] - :param s_y: y position of start point [m] - :param s_yaw: yaw angle of start point [rad] - :param g_x: x position of end point [m] - :param g_y: y position of end point [m] - :param g_yaw: yaw angle of end point [rad] - :param curvature: curvature for curve [1/m] - :param step_size: (optional) step size between two path points [m] - :return: - x_list: x positions of a path - y_list: y positions of a path - yaw_list: yaw angles of a path - modes: mode list of a path - lengths: length of path segments. - """ - - g_x -= s_x - g_y -= s_y + Path dubins path + + Parameters + ---------- + s_x : float + x position of the start point [m] + s_y : float + y position of the start point [m] + s_yaw : float + yaw angle of the start point [rad] + g_x : float + x position of the goal point [m] + g_y : float + y position of the end point [m] + g_yaw : float + yaw angle of the end point [rad] + curvature : float + curvature for curve [1/m] + step_size : float (optional) + step size between two path points [m]. Default is 0.1 + + Returns + ------- + x_list: array + x positions of the path + y_list: array + y positions of the path + yaw_list: array + yaw angles of the path + modes: array + mode list of the path + lengths: array + length list of the path segments. - l_rot = Rot.from_euler('z', s_yaw).as_matrix()[0:2, 0:2] - le_xy = np.stack([g_x, g_y]).T @ l_rot - le_yaw = g_yaw - s_yaw + """ + # calculate local goal x, y, yaw + l_rot = create_2d_rotation_matrix(s_yaw) + le_xy = np.stack([g_x - s_x, g_y - s_y]).T @ l_rot + local_goal_x = le_xy[0] + local_goal_y = le_xy[1] + local_goal_yaw = g_yaw - s_yaw lp_x, lp_y, lp_yaw, modes, lengths = dubins_path_planning_from_origin( - le_xy[0], le_xy[1], le_yaw, curvature, step_size) + local_goal_x, local_goal_y, local_goal_yaw, curvature, step_size) - rot = Rot.from_euler('z', -s_yaw).as_matrix()[0:2, 0:2] + # Convert a local coordinate path to the global coordinate + rot = create_2d_rotation_matrix(-s_yaw) converted_xy = np.stack([lp_x, lp_y]).T @ rot x_list = converted_xy[:, 0] + s_x y_list = converted_xy[:, 1] + s_y - yaw_list = [pi_2_pi(i_yaw + s_yaw) for i_yaw in lp_yaw] + yaw_list = angle_mod(np.array(lp_yaw) + s_yaw) return x_list, y_list, yaw_list, modes, lengths -def mod2pi(theta): - return theta - 2.0 * math.pi * math.floor(theta / 2.0 / math.pi) - - -def pi_2_pi(angle): - return (angle + math.pi) % (2 * math.pi) - math.pi +def _mod2pi(theta): + return angle_mod(theta, zero_2_2pi=True) -def left_straight_left(alpha, beta, d): +def _LSL(alpha, beta, d): sa = math.sin(alpha) sb = math.sin(beta) ca = math.cos(alpha) @@ -76,9 +94,9 @@ def left_straight_left(alpha, beta, d): if p_squared < 0: return None, None, None, mode tmp1 = math.atan2((cb - ca), tmp0) - t = mod2pi(-alpha + tmp1) + t = _mod2pi(-alpha + tmp1) p = math.sqrt(p_squared) - q = mod2pi(beta - tmp1) + q = _mod2pi(beta - tmp1) return t, p, q, mode @@ -96,9 +114,9 @@ def right_straight_right(alpha, beta, d): if p_squared < 0: return None, None, None, mode tmp1 = math.atan2((ca - cb), tmp0) - t = mod2pi(alpha - tmp1) + t = angle_mod(alpha - tmp1, zero_2_2pi=True) p = math.sqrt(p_squared) - q = mod2pi(-beta + tmp1) + q = _mod2pi(-beta + tmp1) return t, p, q, mode @@ -116,8 +134,8 @@ def left_straight_right(alpha, beta, d): return None, None, None, mode p = math.sqrt(p_squared) tmp2 = math.atan2((-ca - cb), (d + sa + sb)) - math.atan2(-2.0, p) - t = mod2pi(-alpha + tmp2) - q = mod2pi(-mod2pi(beta) + tmp2) + t = _mod2pi(-alpha + tmp2) + q = _mod2pi(-_mod2pi(beta) + tmp2) return t, p, q, mode @@ -135,8 +153,8 @@ def right_straight_left(alpha, beta, d): return None, None, None, mode p = math.sqrt(p_squared) tmp2 = math.atan2((ca + cb), (d - sa - sb)) - math.atan2(2.0, p) - t = mod2pi(alpha - tmp2) - q = mod2pi(beta - tmp2) + t = _mod2pi(alpha - tmp2) + q = _mod2pi(beta - tmp2) return t, p, q, mode @@ -153,13 +171,13 @@ def right_left_right(alpha, beta, d): if abs(tmp_rlr) > 1.0: return None, None, None, mode - p = mod2pi(2 * math.pi - math.acos(tmp_rlr)) - t = mod2pi(alpha - math.atan2(ca - cb, d - sa + sb) + mod2pi(p / 2.0)) - q = mod2pi(alpha - beta - t + mod2pi(p)) + p = _mod2pi(2 * math.pi - math.acos(tmp_rlr)) + t = _mod2pi(alpha - math.atan2(ca - cb, d - sa + sb) + _mod2pi(p / 2.0)) + q = _mod2pi(alpha - beta - t + _mod2pi(p)) return t, p, q, mode -def left_right_left(alpha, beta, d): +def _LRL(alpha, beta, d): sa = math.sin(alpha) sb = math.sin(beta) ca = math.cos(alpha) @@ -170,9 +188,9 @@ def left_right_left(alpha, beta, d): tmp_lrl = (6.0 - d * d + 2.0 * c_ab + 2.0 * d * (- sa + sb)) / 8.0 if abs(tmp_lrl) > 1: return None, None, None, mode - p = mod2pi(2 * math.pi - math.acos(tmp_lrl)) - t = mod2pi(-alpha - math.atan2(ca - cb, d + sa - sb) + p / 2.0) - q = mod2pi(mod2pi(beta) - alpha - t + mod2pi(p)) + p = _mod2pi(2 * math.pi - math.acos(tmp_lrl)) + t = _mod2pi(-alpha - math.atan2(ca - cb, d + sa - sb) + p / 2.0) + q = _mod2pi(_mod2pi(beta) - alpha - t + _mod2pi(p)) return t, p, q, mode @@ -184,13 +202,13 @@ def dubins_path_planning_from_origin(end_x, end_y, end_yaw, curvature, D = math.hypot(dx, dy) d = D * curvature - theta = mod2pi(math.atan2(dy, dx)) - alpha = mod2pi(- theta) - beta = mod2pi(end_yaw - theta) + theta = _mod2pi(math.atan2(dy, dx)) + alpha = _mod2pi(- theta) + beta = _mod2pi(end_yaw - theta) - planning_funcs = [left_straight_left, right_straight_right, + planning_funcs = [_LSL, right_straight_right, left_straight_right, right_straight_left, - right_left_right, left_right_left] + right_left_right, _LRL] best_cost = float("inf") bt, bp, bq, best_mode = None, None, None, None @@ -319,6 +337,7 @@ def generate_local_course(total_length, lengths, modes, max_curvature, def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", ec="k"): # pragma: no cover + import matplotlib.pyplot as plt if not isinstance(x, float): for (i_x, i_y, i_yaw) in zip(x, y, yaw): plot_arrow(i_x, i_y, i_yaw) @@ -330,6 +349,7 @@ def plot_arrow(x, y, yaw, length=1.0, width=0.5, fc="r", def main(): print("Dubins path planner sample start!!") + import matplotlib.pyplot as plt start_x = 1.0 # [m] start_y = 1.0 # [m] @@ -341,13 +361,13 @@ def main(): curvature = 1.0 - path_x, path_y, path_yaw, mode, lengths = dubins_path_planning(start_x, - start_y, - start_yaw, - end_x, - end_y, - end_yaw, - curvature) + path_x, path_y, path_yaw, mode, lengths = plan_dubins_path(start_x, + start_y, + start_yaw, + end_x, + end_y, + end_yaw, + curvature) if show_animation: plt.plot(path_x, path_y, label="final course " + "".join(mode)) diff --git a/PathPlanning/HybridAStar/car.py b/PathPlanning/HybridAStar/car.py index b378447fcd..14b7f956b7 100644 --- a/PathPlanning/HybridAStar/car.py +++ b/PathPlanning/HybridAStar/car.py @@ -6,7 +6,7 @@ """ -from math import sqrt, cos, sin, tan, pi +from math import cos, sin, tan, pi import matplotlib.pyplot as plt import numpy as np diff --git a/PathPlanning/RRTDubins/rrt_dubins.py b/PathPlanning/RRTDubins/rrt_dubins.py index a43362b340..f1bd03ca02 100644 --- a/PathPlanning/RRTDubins/rrt_dubins.py +++ b/PathPlanning/RRTDubins/rrt_dubins.py @@ -20,7 +20,7 @@ try: from rrt import RRT - import dubins_path_planning + import dubins_path_planner except ImportError: raise @@ -130,15 +130,15 @@ def draw_graph(self, rnd=None): # pragma: no cover plt.pause(0.01) def plot_start_goal_arrow(self): # pragma: no cover - dubins_path_planning.plot_arrow( + dubins_path_planner.plot_arrow( self.start.x, self.start.y, self.start.yaw) - dubins_path_planning.plot_arrow( + dubins_path_planner.plot_arrow( self.end.x, self.end.y, self.end.yaw) def steer(self, from_node, to_node): px, py, pyaw, mode, course_lengths = \ - dubins_path_planning.dubins_path_planning( + dubins_path_planner.plan_dubins_path( from_node.x, from_node.y, from_node.yaw, to_node.x, to_node.y, to_node.yaw, self.curvature) @@ -160,7 +160,7 @@ def steer(self, from_node, to_node): def calc_new_cost(self, from_node, to_node): - _, _, _, _, course_length = dubins_path_planning.dubins_path_planning( + _, _, _, _, course_length = dubins_path_planner.plan_dubins_path( from_node.x, from_node.y, from_node.yaw, to_node.x, to_node.y, to_node.yaw, self.curvature) diff --git a/PathPlanning/RRTStarDubins/rrt_star_dubins.py b/PathPlanning/RRTStarDubins/rrt_star_dubins.py index 21cc9b2bc5..e2a456d75f 100644 --- a/PathPlanning/RRTStarDubins/rrt_star_dubins.py +++ b/PathPlanning/RRTStarDubins/rrt_star_dubins.py @@ -20,7 +20,7 @@ "/../RRTStar/") try: - import dubins_path_planning + import dubins_path_planner from rrt_star import RRTStar except ImportError: raise @@ -136,15 +136,15 @@ def draw_graph(self, rnd=None): plt.pause(0.01) def plot_start_goal_arrow(self): - dubins_path_planning.plot_arrow( + dubins_path_planner.plot_arrow( self.start.x, self.start.y, self.start.yaw) - dubins_path_planning.plot_arrow( + dubins_path_planner.plot_arrow( self.end.x, self.end.y, self.end.yaw) def steer(self, from_node, to_node): px, py, pyaw, mode, course_lengths = \ - dubins_path_planning.dubins_path_planning( + dubins_path_planner.plan_dubins_path( from_node.x, from_node.y, from_node.yaw, to_node.x, to_node.y, to_node.yaw, self.curvature) @@ -166,7 +166,7 @@ def steer(self, from_node, to_node): def calc_new_cost(self, from_node, to_node): - _, _, _, _, course_lengths = dubins_path_planning.dubins_path_planning( + _, _, _, _, course_lengths = dubins_path_planner.plan_dubins_path( from_node.x, from_node.y, from_node.yaw, to_node.x, to_node.y, to_node.yaw, self.curvature) diff --git a/docs/conf.py b/docs/conf.py index de28ce4752..892e2863be 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -13,8 +13,8 @@ # documentation root, use os.path.abspath to make it absolute, like shown here. # import os -# import sys -# sys.path.insert(0, os.path.abspath('.')) +import sys +sys.path.insert(0, os.path.abspath('../')) # -- Project information ----------------------------------------------------- @@ -42,6 +42,7 @@ 'sphinx.ext.autodoc', 'sphinx.ext.mathjax', 'sphinx.ext.viewcode', + 'sphinx.ext.napoleon', 'IPython.sphinxext.ipython_console_highlighting', ] diff --git a/docs/doc_requirements.txt b/docs/doc_requirements.txt index 65670d346e..b8702ee750 100644 --- a/docs/doc_requirements.txt +++ b/docs/doc_requirements.txt @@ -1,3 +1,4 @@ sphinx == 4.3.2 # For sphinx documentation sphinx_rtd_theme == 1.0.0 IPython == 7.31.1 # For sphinx documentation +sphinxcontrib-napoleon == 0.7 # For auto doc diff --git a/docs/modules/path_planning/dubins_path/RLR.jpg b/docs/modules/path_planning/dubins_path/RLR.jpg new file mode 100644 index 0000000000000000000000000000000000000000..ff961e5e2dc4ea3d624963f01b3ff549d63a8077 GIT binary patch literal 10220 zcmb_?2UJtfw)de)lPX2&3J9S}?;s#Tf(VA*rI!#&=psb~5tJ4}5tJecy%Pu^h#(yW zqzQ!Hiy*y-z{C5$_xs=Xz4z8z-&)^3>zw(WJu`duWY3<=J~J0%7qb8@80Gm(Ld4wU`Y7C$^YM29xAR2&!IPI*5$@*ur>#HqN8_sw?uPo8smbNd26zKd zKod~A#Q$IE@88qoJpjla002?K-#ptl0Dy}Gfa?=~^LVlWfF=R}YWqEH5H|l%hWPSH z=;#OlyZHb>WeNb-1^|G<{9lUxUH5NW{11KQx~#)?*-wwl%L#A;8~`o=47dY!fXF2h z2kro3fb<0(PzQ(z|InW&(IpXIA^t;TSFVs;At$4tASWXyr?^UUm4cF*lAN51j*6Ow zmX?l|;wt?$dfIE3nD&nlfEaVWM+Qs+!$btP075zfB07SL zHh|;Oe3xnw{2AK+BvP^~#9;fcsfb$vTT)ujNIOUak=|0VoSN=!m@h4hbb zMLK|xfRK=s_zKw-qQ6S~kxoK)h5n|P>LZ(L;$F`fZgHz6=8!TnL2VJ0Ej$vE>UQ74 zk<}Lyz|~8sgmgr7fC@124g?{9K*OM@Yz7QJ$-ljLetknfMRgi+BCPp}5u>=*SHMeE zn*c$*e+mFRNypi8g$7CX`19!cSkK`zxq9J(9oDqsJX(gZ$R<~3-c(lOO2H-m#FoYL zvv0r5*(@9W`&Rx_lmB=zz|9Aj$T>uT=Qb|@@TRdsUtm!Wf{<$>&3re}Rg+V)B7*R) zca`a`EXX`RE3Yism(Ha|#>ek?s_K@z?wyxqU#_B+YxOW7;le%z1`^?WJedTKRJ`wo z_)2QBPl~*9t@&(N5v$VprQR8HkcW6-gWLEW6Eowo`tz5@JxOdO2ve$vrVi9wQaq3J zIa28KRk>2J&cS;JQoX2mqwceJr*cL#1-afSND);K6iG-^1Lcfj{yp?l{XCodd?B!S z%?&$IlBlfq)h(J(reI_payjB6!~5^>8{@zM32HisnGl*-Y9-% zaXvk{xE98^d|fRo?ARB|3PCa;&DALCKwQr|6I2<0I)9v%jPk72exaFLA1*EkFY@?t zf}o>#;5iu=ZGD#$PGSui4AkQ8Z&njWR$-QT}{=XW8pY-#qbC;u>3qX(V0`O`axd4g?w&yQ^^x)OdVdBt94=I@B z2gHPSiG1YSwM_DaSCK0~%1hjx2u^SxR6#gj1u~c#d_Q?5A#Y?0iM(5uk$D`pG**@e z!Ml%P(>K%CpWmzDMPw_!tN`CN_Ni4f*d_oQ7eH1YS#ubL7ewen;vm$TPJ6340pPfKdpy+z2(n=;%yBT$S!+bVd|Op-i# zZ%j(Q+Y^^(V`3)s><82FPBq63rQ>aL>VeP1)h|vaL#Q zoM$jEnU{(!5^&5oRC z*l64Vn_TLu@)#8k{!NjSkvQ|95vQ*2GxVCssA5cxcXx>M##ig`G`%f;op$7^dTgVW z3(cLV7^QnWvT>hVlysUWnMnLcgem*?=UZ-Go!qrR%(+G2m`6B1lnC=vs@NyflK;MD zUDk-+6S7%gMN2P!k4_hRPh@by9?sF;$bf)BZMs@+NI3`x9H|j{F#K^pp9kE z0vg}rQO(3DNzj)kEr^C&-->I4l3VoV>yD$SXjd=@4t~-h7XdQ@vpOvSExxY8-G9!G zRHmC#@@N&+kV^+Hl7SC%+ znWN(#LO6TNF*1so&en(@?KD&*!2<(Inu~|VJBGf;K8w=M_^xRV{@;tYHod;g)M>ni zmi1}I`qoSDh3$MIHz=454?LS)$fRLr_A+jA?2ydcM6D{7_51g@H96&tc*iXi)@yhm zfBQ8_VZZ^o$ma)y=!l&I1b|#K41y~Z_2O)@db@pQ*y3T|P8o|7t~pKJk~>ukJ{cWc zNVF>ux+&aw>7`71Wj#dYAQL^TBq0g|U_f^TJG-miY7)bnis&%g8PlFG%?oiSw7ghgHrZ}J3hiBd^1Gq z1L9$zRZ=G7?#h-?g^Z+hoO7q2Afi3m4)P)1@VgZtTONzgoE6{!N^vVtRf83F97ncGr6lmCe|B>t2A@ zRI2ddm`wzz)6z?oUkz9+ymt%`bl=Xk^q-`r$~Nh4T-;T*T>{}$946AOX>@$KKdn4p z!}Sw9q*V(%d^C5v2#?M6VeNf8tx=4_ZNH^^$h%rw(KB(NCkN7h1SWC10Qyc=HkJs$ zzchUNxLFJpD8#-Oc6)B{)r)4Sd$&l+W6ttN$KE->oH8xZL+)^oSbkA6bo~;_XmYWN zZ&PD>c?Nqr8uPl)l)VLs{*6g&PGgT6Yt(|xY*&RQ-xE9MKGOaYDHXFh{nPKRBH`4O zhSM($opI-RjU9H#{fQigX_RYzOs5H9O4QWjO_nINL^H2n#1^ibd2NLI2MO3Ps-mqJ z{?36qF)mat^nJ_x1Y?wPAD+6pL67!nhEYF+9UU0*xCXD-AOKivg3 zk5)Y|yEC9N8PmO^@{(h!$~24DtA4t&ou5m3X>>A}x6u0Yc%=Nb&MEEnERF;F^*h6G ztaC`A^slN?rJCP+zmpK*1JM%AY$VL->zJJ_!c)FoDkV;OOf4ho7ewyq!g+*OFh%pB zzX@F1_o!gh8+Oj9-+$iQl~D4%SX#p^{z>Q7K$+hfSkTr&W?)YQO)sZ505Omw4p4F3 z8WC*R#F-ve@5yzH@2;INV(ZxI7bF%i-+5{?1N6vd6|-qL@2Y35t?Unv_=368fl(ud#n>l;|2rkSuM!$Bp z%XJX4BQ7f|z19N-clh8Zi-v;i2Eld8L5SNiFZ|<+#zS6iW+;tZrC{N){*iL{MP!o{ z+By|ntGz_p`W)>0a63?U>vy;uqlB^5f;(<%a~Ce-EVkT|-m}mhdlOwZv?W+PgN^a&Vj)P+5J}-e6 zepk_ec-Tj_wCP9LE&#~Zb&(i*Bey4ep=QE+9x}|CYMX~Ea`f!4Q!*Y|#AQJUgrAKS zH$XHD&$6BU5?uUt4xWt1Jx&?Bwh7iBH7pd+PqUEMYaCa7Wy@;W>K-uA#xBlq8?!`loexcDpq#Vu?GOqJV zUmRX-F{hM2cn9R2YE!2byb&Q3$HvH8xI@bdCx>LJ>BYp?&MsRz4F_Ls zHvKu8CN7~>t`Oq;q}a3D!BK34z+L{d_UP7&1^J;u>LW-3>rEZ{!1-F~yLuo!VoqX~ zR?jKgZ%qo#4|_a?1>1J;?Oh=86}<4(`@zEnhfv5sLVy5}_(N;)q>w}`<8n&)YpG3i zBe`$_Mxi~Bx6UNNanGM&s8qo(F0vMz$&k!bo}fxh8(e56GW3qP>qtySW(1~q58}9x zW)bt&m@ipY@8mRulk{{jY^KRT>5JR6^pcDv<|M_G09Wz){#V|OL8h^J?*e3GM}+Rq zO;__6lS4AKPOiEnqg~V$oZnBxy9)T+v@{0Q7sz5+L{IXagb_M&@uXS9TYzGtGrz$%DjGYu5nkA@+cQf-FCh zYvH9VPPMo**M?KKogox_^u8S~RMD$NrmlnbL}9o;T}ECUpNysKtEwZDm9#cJU>-qF z&ADBqkrr!GKhdKQhWQ$op?JhwWvD&eQ=6L^n16uyW8Vp6>c%`}S%3AFW03XhjgPUL z8EgDam2a)O)nMMQQ#u+)b#800!oJI<@8#3&8s}D0oRT;)u2bGSu!V$1-?Y|K>l{u9 zTtH?TK*7oD3CkXp*rqwWct8wYMH7_b!C}yq37f%n=w9Ze=TMyV+QPUVSWhi{LI&eVd)2by*hKB zwJ5&sRGMvB!ss-kCs+!cS2SWjAaG=nV5M!@}ytM6H*BpoqW?-2FU@D))@1 z3mokTlXecZ^iCjJv6X}WfHq-Xfrj`%hE!JcOaSLvwpt@W z(cnteNj+e_bL9rcYw%q2Nk+o$i66*Y(V}@oB#}{{g+aU!=m5jVE?pjk(+}GVfJUgJ zR8FTJhmQ^nZ*PfEj*H{PnL`Gdva0Iz7K396*8VYVz*40~9?U#pUF*aKX^HoK&3z~t zZd>+-ce!8A>vgwqW*M)jWZ)cRS)No`Ez7zhTbjzf-RqTXg7EdFGP0DDB<`i0+V3Sh z1ibABL{%>#nszG@&kiw9{+f|s{$A4K_$$-wS-!_u<|NES7S}{|ftR^}yAY1X_aiM0 z`><+4e7zYD-zQIsamL3DbGgTPO>0&f=#vbk((lJHj}>Vd7L7ZHhhLnWOOMi5o`7bL zZ-;fQEcso(j(R=ke`UI=11Ivs;Z8PIM8Hhs*Gul!XLlF9ei{bN?WQ8|j=3AW!$f{P z2>%dQvWD&-Wyd3b-*+ztCslWp2vV!1rN$4V%4`%_W+`4ByZbgKipH_rL3 zI@`u$U|*27?!~W>0%&NmK(g5$%5Gc87X+!5JHA{3gDyjKD2l}P`1xAralblaQkz4r z0!{kV=Socx0q(4ZU~E>!5?nSkNlM(=-H==QTcaT89SGrQA>=ukw%as`WPw;2A9;#2 zzU#w8!hh=BizLoHB(5UAjHgxCRgSz&4!f6&LdNd+k8GtlN}Oe+|02Brz8bXq1r%#f zzwqb~@7;G&D;3oqU_lht3^aJfYmHz^zQ3qZ{N3GJxV7%L^VYGZ055PJxuujKekE0~7;De}0m1-vmwT4`=p)O4qhwg(a)! zD!#d?A<1x5(nE=e6wgA^>4@*wn_~i{lE4XWRFAP93h*0!>0|jVRqIqguh*GPV=o;| zb&vWEnzy5;u`rT9KWQxKS(H=sts#ZZzCi$K9F| z5H~s%1)#qy^tJf4E#uKOCEFLnb&X* z0(~Ty7nrLh=9oBB#?3%zl9h- z7b0*{$el4W)Pi=eNyS~)6N@{}46o{B0ngJ#Z=FCYGQZih2r=B6aSaI!#fhZ{e=iJIUL(FDtSde)D@n zWtm(1`Mk&s-Z#hZWtXE}IJ--8^X{{DO@)>TksSA8?hd!Fu;l)0LuucpZcriVs_3QB8pLkF2+R$C?8b_1Ej9cFzGf5Hl4T;G)^gRn*OOPv~_RDy{=3k8e*yMVge;U zgJ(k2hI$|g73AwM5Z3m3nTp?snUa8|T9RI_z?o4`SNJs;EP_7xTlz8)Q;x{Sb-?CEY>{~*c z4Z0EQPGhqQiDpZf;PenmBq66;{G7grVx;#Xzsljp!GqIJ$U8A>2Ws!Cx%UwUBQ_vFaq(sj|~W@7rl36PDH2 z34-SMlFJV(bn0|-Kz5BOfgtIyzk5u3|2SWc6gHmz#y>Zn>?&VBdw9MkCFiMv5#vk9 zXz8`F*%*v?8&n79t}aru0`J$Wa&ZTV`?wb}$m&9hO8d!wOLFIQz7e&wtGs94YXQdg+(qOO3y$YAgHxB+r4 zQR}cBdp0n2U^Y~LHnw3nX1@(x->fUG-xrXS&V&pu&;XSDs*pP2Dw?rW1sdk}sA9V; zieog!h2KmKnbSgyAS=gaa|J&bR}OPkvqZjrB>T0y)o`ztx-!rh86?r-V3E`l|FH8+ zJ;`ulGk5%cf0azt#*4HCv*IuzY0f(Bs!qh3n+qGSQYJrifIbsgOsNAxevE#C#Tb}W zzi+zY3L$b??K!n8~ze*kMmDZl!oese| z^_jr~V$o*zIpOcP7vXfd_a8*-PsesqH=YRU+ha8NNeCcZzBMeHIVK~(<6NtG);h907Ah4xpXOt7AZb>KuyX{7R)HqwyLcDis}oc z$Mtjks4uYFdU&@&AslbjH>lPAu>&=)3xOh`tiU35ZH9+(|GUMp;FPo6C(mA(OEK0c zyqpnzWcM`r%M;})+V{P^`jlQ}MiC{{p8^!O1=^9oVkS`PzS?Gy%Q6DLQwa~pm)DI{ z`b#Hf+PrxShIN!kx8>Z|c54#mRBzFIaVEn!6OqNyY41a9_#U72P3P0(uDNu|ve1;{ ze3Bvc9J@|oDj8|KCANe_7+Ka$P0$HaN&Hf5@Z9R~S}IkGiN73nvQ?TURjUDu2q=p` z20f_5MlJCYwW9RL8oGa3s_5}s^ZLUD^dFEwd_Q(+iU?6hFVgUZ>k^%2sz{RZ{ zq*M?{vd7TkF)ktztCV0_nsT(*T7%uYtkr_+gC;Frw*L0zR%Zt zbbDCi#M^nUkBt<%AZ(*o3VqH~=mUl{%?M=aO(;7_X!Z-Fohy=k;FwpKH(W@R%%QF2i5*)f)J%AcP4%6IOqb5 zji2*JXpJEidTCJdgK;$+GsD;LJ4h&h#jdPd4{~>nPiG|sKK!B=ghSpFa0K~DS2@a ze=4_Ob|snHrpX@Nt*Cu1i0@6;)inVEG66;LUtrL7mZH%o5QNAY$G-AgUEEak{?O+0 zo|*%*gecLnZZjIvxIizlK+gVl%T4KqWtp$a9Y0wvyKmcb+iXGUNv&i>?fgSw^v6L4 zh6*V27)_y->~8P|4~BruMA{AqyHYh%vv!@>ZD4qKz5~O+BVX$Cs-UsB8;C zuJQ(yTG%Yv(Y!vphqFdo`R{4vUnHhpjvuU+||XyTWp?Sga6+ReKM-a`a!94gU*6yVAgj* zDAX*5{VPlI0ZYnvL;jJU_jMGHmNRr!#30b7M2){3&QSe0sqYn$cI6Fz@1eTtBqsw8dyIIdK8AMa+=4O7HI(75BU%ul`j5 z5mBB-b1*yUYNbj|t*_FU9K-@;M-I{1?^YT3;DZquTWS64TmD~x%-{d`6zvBp6n2mH zH+Wijn37HrVA)WbPa$q z5n8=oUHBl9eeGLY(jr22krtx$sIaw29yDh7Q-5kyk@LriME2UjJ4J}kepO2lWmC2G zsqbzdnp0@nJ1%&&DdTk!3S+@G`%iz+XP3(yUBu=441e%0NQ`lLD|Uq_=U&c{0lPX( zcNaQx^HV5Q?sPT#&kf)2lzCcWtwXe{a7Og z-Kzdtyz2dg4s)k+t;@yu6xr--HKj>G2tks*Pp0vaPM}rX)-sD?KQ4krtsN!c;t?6p z)c6maQzz_#q*3EK?B%b%k6Z1E#FBJY2MHSXhQr2NcHDK`?tO+p%O1M^7lT1j|FoX3 z$Y_ScukRw=Pr}+Zo*pu@7&r|u;lBzo6jFeS+X#NoNk_Y zsz3HMNz*5#mIyTXmeJg`UI2@kN;hxl@R}hnHxtcs>HMWzE^l4R)YjKhWyFc3XE>|h zWqHGPvRxaWsmNKVh~Ak^PjIb)Id)1OJzBn+PnceE?Ka%u=Np_!0M-@r915R?K#(d~)3=%$Y7X2B zA0+ z`)MHqf#&xtGymg3aN#V4tOkd)t1Zx0^9DRm8{Cz_-Cn$=QdwRE=z2m=Kx4KTVj zH5exyD7yA3ejYzRUT9Z$aF{sV^XuHS8;#WF?-2Yz*6#M&7RS3#Q`-)LBJ444ELeYXI!RdWRc#hcFZV zNv;|v)FLylCLAo$wcj_qu1e-pTsvR#oedQiw8p1?ISPFXH~U`DkO~`0xzjkh5wB~Q zIs64X`NQj7T}KGZ=xH3&jKEy&l$M&7es+EsS+=weq|hAI1ltnk)UScAmBU>`Sfg6) zZM@Q-!&5T$(d`Fp2IZC_^6wYJ?P@;O_E zhI#6x1XF0`!3;rNWd%N*P5&fC-igTgQT^Lh_;dKtk5`a|g|VPRv{aD0#h%D1J@Jdz zj#F+`Iqa%=t)tl%0$yky&t#D8(O_6XecAIZ+n;qA(^a8S*eGe7hB=iDo%n~PZXz}t zDzt2^ofNrSo_bk$jUr@J76Q#qY&U!D63Ci%RudQz1Y>U3aGNx%ZCt3N<108I67=FX Z%b-{(ghI6z5(EeTu}l1yg-I{Q{{yFSmw5mH literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/dubins_path/RSR.jpg b/docs/modules/path_planning/dubins_path/RSR.jpg new file mode 100644 index 0000000000000000000000000000000000000000..0af2692790d7bfb1951988e11bb63ca92fe18477 GIT binary patch literal 10245 zcmeHtcU%+O*67fC6OmpN5CIW^08#>SXd;A&^y*PMp?8RY!VwTKG^q+o?;s^e7eok1 zi4a2#MS4ppQkC+>d+s@&_wN1fyZ8OxfA3rKn>}mxUS-ePv)Amk_MDBK%>vA~wRE%q z5)uF)As)cl9O)Gub@h99?n1S6^fdq0K*|9Sf&4lExVig!-_`y_z|7o2;78pbaNpL) z^AG%=T#0h`M}9~L0F1;xY5zY}(b(Dh*b<4hh^MbNQ8}@*c0~NV)iKzvB28{J~%F0AEjEB2CW^dRtHLA2^PPE4#V+{m}ITe)O2$-rd-ccr_!Q zJb({y7tjWNA>#i};io-4aslAR9srOf{H%MB0RV5G0076t&pM&k0KoJc0Mw&B?|a|> zTW83LC8>i00PGY20E0OIuzmsnTFXB=`jhwPSo}B7DnR7nAwH)E@o)rO0ee6I&;i^5 zTi_ZIlLoE>Qh?mqB%ltEk^X=mB^eRODan5TH6F0PqrrkJzmrZ}uNRNlisVMovNcqZ!N${7_6nMn_6PR8J%!k`o&#si;}bv0gN# zInT~GB9z$W<1{l_wQy}}cdaxSPpC$e)B<^He20dfiwGD<2^Vxv3@aV`;s z(U6gnQ~j>|$1Md5_R67>e&Btc?U(S5&f&8OfS!yfm4%E2 zPz5G3F9}?_MEY+OSGo&a+-dR-txe#w)=%tSQ8_v8;rLYU}o($2Mq~a-Qjak zfX%A>`^RdR>=oa4`o4Kr%T6i0kqc~`nuYTZG9ycB)S=|h@3I)v3B#y;3o7Gwo5N{@ zTY&oLvQX7FW!e+}Zimp9%k?-(P%C{H?*PngOB&-<@h~32{OPg`il_2EORo@w@!)`Q z&yJaeg@ollDjw=y_0%{j2+$RD_KDx13R2sT0T)d?j&{lBhJB`|-I=UZ4UR^un~m8; z>$T4f2MfV$z=aI~j|q3rlWW}6(D-i)HtmmWY;LtI!+7oTIwNbTt7Lb}$N9|3uPeHD zkFvXrVpZhAZF*uS=BAliSaCEQr+Zb3qGgl#VZCIiq*2XhsDtW-(5G!!uQ`K zusykHRK@qs-O+n*qN+F;URmDZdc#E9r%Ni%TbxbU8vOn?KwgUzPARm>z!9?3aTsp+ zyJ1QI{sy7AD;8fQYUL+_u=6Rs&c* zHfD;On|ckkFn;kY%`7Y};zSN8e^qYNvGcoXkM@a&ztj;*p4Ks2=bbEIeC0a)r5>K0 zbMwl4Ct>VF3j(GNzam%?L2V_Dp=^a8@-xB(5?+a ze8QE!WaEeM%8nX!fed)}Mope$_{-P9iQ=6?iJja_nOZe+pvFP3SrAi@$n5!RRaPL2 za6^jFsxP47x-D}#wOc5rEjwevD`zfLIdhjEF12ymYU1^{J<7G9yr^jTU0&G+VR7$P0GV8j&s+hgErQ$xxoTY-X-%m#_!~u0WqlQRiuMx{Cb(rqMrWC zDgGnAp2Zpc`x&GD4eN2>thEQBSX}A!!TR~t1BWG;TzpS=FJIXgv~9bO)g)e&oZpM8 zA|%*$Sd#7f8IXPVWQ~*YQ~f5C-gj$tQ_l+|6>*64nk8xHUl+qP%!m|LOjohf=ead? zy1g0x*fXFa?q84G(pajl2ynF6zM9_>P7rb?85B^cn3Z?mxBZfrWz!=Cv#ncge!7c) z7@NErf2+l)^E62Jpr{ahY1@$LXi;*yEOKPO$l9_H61uYc9;K7kX$h7whcy~MmXP5c z?p?TA>T8cyPT=4m3x@I}QQq6TH8~S?2AEVH_qL`VIxU;lDoZ^3>SdEvm3Vy@m2V?< z{|rzr_>RHwB?gv69q*)V-Z=w|p0yr^?YV6BXP0opx6Xhy>`aDyEk6U#+Wrko?xnd_ zrF)m||I^;(oc`nh-<3P~at2__-bs5nsBkG@H$3a*2fBj&+cY|Vs)OnUYt9w&fBkr` zRsG~AM{vH|X6G4DW*TZY-Tx5eQ#SU+)#F7B(JoJ;ei|b?eK)pCPj&hEyWpsAKRN#4 zp{w7I&B(K@P8_i^{Zt2*T4j$(4?~NF?lJv^V=eLRJEqeL>!W12)Yi~omF<)2Hg|Ch za_2JNPi=pF2l#(-UbWCB;&;5?1C5w;045aU5AF& zWN*D*8J_PhvK%VBqE8O9^xl@ved}oqOs-qcs0vc)I43Q|2|S)w@cG|7!8O&NF6bRt zdgTnTe6U*)<@av)?IB+B+8OY8bh>&(y=ID`RW74`(r^0xuL*71mITS5mtH9K;|1Mz zzB9lv{|xZ!GN?XjH8rS7T7HIu@p3NK>iA|=EuTiozWZjDS$hQ$L-g3E_xv|Dtc^8H z;cP53ok-RFTFqA?-8JX7f9-KgQ|YHt?O&UJkKD!#b-(0&V&mQL^tekQVr})50K)yC1CjFL^ z5VdX|9~ykGz~yBpThwZoS=RJ7$6y6tC|-1bU;EOa%F9?#p*z~Rc^8tAL5SI_#P#oM zV4>dompYp`o4^XAGQx!;M;qh9;#Mx@0gT*trjtA49H#`eQ3&e8x~m_`T^~q1D2`2a z84+phT58l%66`V#?{|YVKi}&z_-I@60Df8a=|&>Ug+Z8G`ZfIp;%Jv@OrggH-uf!#5aiAF0+izx__gU$PLaYH%BjGTWV7b9tSee5pK_ z%{R`IH=i>57LJa`j8LCo%`>FXw#@cck?TgquIHWhqZwXhx2K5gfPssECtZF*TFWWH zOXz#ASmcpbU9C9gY98B6b}XhbL;n?&Ug0W>H@7E}-IwYXmx2VzW~BP&MgdjAB?_w$ zeyo+DWgVIit1MOyb?$K*H)dW=`{fM42uYs2;(5H`c?S60rb(Kus>(rr`fNq;OSo$= ztZ}p^CX%4dBXyl!VbiC9!3ju$dXo5*K54u9RqUgC!}Ms~g#18IKR>S~x>mLDMftv0 z147r#3e|gY*0U$7wbIkTtD(4K{6#Gn+DQ8$T0?uu^t(&~ZbJEE90Qx?`CY8F4_33u zHn?dS50R2N$Pz>@Snar?LV{i%`mcp;TE_SXn*vP zZ3R^OT@6tF!6^Q~QzwF^OZObzKiV-n1^Ogug3P%2f?*G{f3L+AUt?A|{GT-ErGiWmQGF>EE1(1@oh0y1JvI9~DzB$>#Z5O5&9E@&p>N zj+u1nMwq)MlP{YEjcl=^`Gh=hvrVw$b_z9ekm`uc$EL~l@my*-1QQX|4CTY-`1AYx14 zks3KO^+h;cx!v1|*`gxJqWq{-!<&Pa+(8G@a*SWl0VH|H*FOF`vF*?BH^v5O2=&74 zcNVhu*Gy?9FMP(z`j@$4DEo|gC?1~(9EZHKgX1_wpkT&1sDb$FqE!D5p>8>axf|{4 zL1fvfJ2w};M+u3s*Hut|9=_c3rhb%iCk~+(~*LSNs z8_~WsWYe^CvDr=|DQizAIzm1x)1nhi=DxNS4hg?c*Aul1BpGB->3gROWh5sZNt`Az z6aaWg+UfRw4}49Z4d7iE44-A3zA%alFmMxs>fVEhmkfB^B0Sr<9^Ol}tGmfJKh@#! z3dw-B+T$vGtK;V_1^aAC^Uwp~q(M2?^F9A!R!8ldaGQ2O0_@5|6>08g`ZgoKR?Rue z%fgFlYh#`+RdIZ+BuaN}WqhN#j%+Vgeh%J$AFqr63cJl-viTr7wWpilVu&+}#pZ!U#?Q(0oqKo)G<%3Bz9VTfLT%$3Z0 zLh+t3vrh^_$vA+Y?c6X#r)F(Bd%U(!s5+fsg!kR5{?eWK8W4VhW9@)7@}2>VOkIJK z&%0|L_IX$&KmFpGq>GNqV8YG%M(v8`=CX&xT^>JeAqx%rskm85kPIPsk zhAxG&C*4 z;n_}OLSxdcOSa!QW}#sMh7c>9`)^B@Y?xO5?kt{+icBjTL^FR(xPbuzYhY}sZYpup zhw8yJrjq%U4L0)Gk*>1%($V}$c=-C zOm?E$f(Ky)Q&Y77^UHJlx@k*<@~?X9=eylgk0UQ22DWhba})cEVIg?eM{;UgjO$J( z6!1`e7&qP$o;o+H?h(Y`<`Z-nStI5{G>~^`wNy8190@k+GCsAvZJS!N>1|OYF|Lf_ z*VYUuLq zdaBEPBFZ58Y$?dGpQQBihf}bgu&}V;aw=Xa z$t@~+l9SlQO2*MmoKxDKWc$<#2LDN(EKq*qfU>K~#L7dY-!(P1UPmZlyckwC7Y=_O zca_OriEnn*iav2?gfygjYPxl?59!?UQ2I*FazZZ!M6W80zwyH1 z8L-7)GZyoQ7rutO7*I1Iu?0;!+tk%DZkQo45HfB{# zqc`&Pgi7e0e}e)oaN5}dzQ4hnqBoVpd{YsKpxol@R8HYX$>-yLy>?#}FVYhBq(5eS zdG60o27|f#SB@rExTk6BgAby1@w$FG8pf|Y4uNR+(f=kLILEuwB*Xe*c-s2IhetO9*f2e-PZ!cv zmXJ*B10|IWQ~R+@9v%qX%3?vWXNa-*hhc32iYL!}07f9uu!pdy{ZdvYI!>!qiWNGk zlm6<^awzLwo@mwODFm;nXmgeRt}#T`kW0VGS;}agmDh_)&mVuna{kH9zpomvt9+N9 zDCc*wC`$Nb(x-iQlK#0Tn*K@rvpq?BC0#3}jwOQ*-s38n-r2r+f5$?@1wU*`%APNq zaShZ|rXW>oz*4z74g4W_1Ki>rf}?m*`;eRIbGgMkYP8n`H$HM{M6Pnik~xVpf^VF& z5872_YsJ)ZAzbPG@`r7!Fv@PXKz9*X%%nrju%^124vTPt8n?PxyOoXrKqZtEG4d}m zw*Q#Q)x7<%#MJr@1~2j6uTQTAh9!H$Q-i2nRoA%(0{PXU;k^7=?@^Tc-JjLm~^hJlU8UI-u?Pv+}4Yq)M6`8ZR5}U`cbOcmuFug zg0={`G%!J#^6{q7F)0hz?k~@Al__a6qFtp)H)8WpZi590@vF~9p4u;*0i#A#N3Pwpt^vEM{zgOfD_O*?=aIRyRCpZd9DVb+kT2G)es=9HSI6q`l_ni+p zJYb#4g_0J%=0|@{E}U9Pbx9#np-`K>uA5+CiH4dsH>pCf-;7P4u23rRx*?ZNs)`X24L|fM}%nR!H3Q9 zc0P-+MQ!KZ7myOaOJ$~CIwfpD6}k3Ju<@wUVvNibhu4W9f@F0zfs09iQT8bJ(74Ql z>sii_3u0!rlaOMZFkcV3g*i?VD+@I@G}bp8BN**m*IQYd)%{G23w(6dZ*fb4=MjOY zE2;*t+j*+Eu;gX$J>TF&^W-)EIG3!0y4)t!%9?sajUy%U5fer!2nJ{AylhLBM>62U zSyP5ZLVx?*w^oeF5I}i>`>U^}$NY1G& z_p*%TqZ>XDHZc)%`mN&`T%@+75q2YW45$Fc5blB0dawmYW(>>t-{(82`0-tcsZ{cun+ZB~w~$ zb~iygkepeKoRr;>r+b4VBr=M<%k{JW3(Xqhe#obx_hUKXml4EI-y?u-*tjT^OQIsP zv7nBf7x+xq8g;$1@@m_i$r5o2kbD5Dg9SX*S?A1au$SH6oZ7(ndY>Xy)7)RQsU^yX zE6k_xGyS#2ct;LvLpKFh;hZE|=hB-edTV60$<32brZF^UfHUpD?^|bL)omex-{7c~A1uOP2wf`8x0i`Io|rQMe1bMVVnS&XKQ{XF4j) zh3)p(8zit(DPid!+67@vOqLfDHv>ePt7=vk5O2y%lNb?uS?(6|hDk%%dll(>;jou} zY&C5rcTD}OHOU_}B-mK2Mp%SOtn+S%U$U*Re)qu5JnM4sWq96OXj_(klzlDzJJA7& z`C4%w@7Q20M5-{wl%;~jB*--vfS&u+rLaVG8IV7dckbI2^>7lcc}ItT@t5o&YpzUr-4h?rEak2Q7a=`y~jvoWy@ z9`Jygk|SQF$bo2b!$?@m(91*a}=IHOzKgb$C!T;G$-@0t|dGbY`Q z71`MiRNY%VWKj~H%FNWuEu?SU%6h-nDuH#^MR)1=i&M3mw42&)$4nQo_6k7-QLT$sgtIuyt%Q)pDCo0}ZXCh*fE_5*{LwIE4Yy%mbc-t8l&PQ1Khcvm3tV0Oca;{EB zrChnb2wtbUF|^)+qI>q6dmKVETvoQe$?R~5aN=%4rB=pjJ#RjT#4E@ao$1y(LkyFA zUJ>3}Fmqb>rPV>wvcjOxOC6ORqpbgE_w{#TPs2My1}Z^UR%Rb#?`ACf8boH;NieJj z@R#6Z^O9#eZyt)}G`UT|A}5fSGjkb`);lNSr~EYK?<@;0JC*k3OS6neMM_m{pjc(I z^clb4m?8BV93HNgWf+FBFMExlnc6``_LVu$(`a=I*li`02OaNt80zLFH@_PTnr}`} z;OX}hG2czob}kXyGrTK>Ge~2^^mmPXVN+UbR>{WH*hc$ifnC>DsSx#FQ5SFFIrdfK zX>)$9p2X)iy~Y{`WyxH`FH0~;tG;F|N=4=s?*uyWQ&5apH>_07PC7VL|N6-;4mATx zU4obz(B1dV30KFQk7HWULSxZ90badoOV0Xu|Mg1F5F4rj#T<{G&F3I!0~!K>-uWat zv9GoKl%Lx+fH5&5vf&jh`^Kgj_eYu**mUYA%Q__wcJv%qU$TiNgtu+#7xA?#C3dhV zWgiR=LHNldB&sOw!Xt~t=sm}~bwv&CpjNyJUtezr_ywWVlIQXGX}V8|n&53eFGs zDg-9XdbV@qIrBj*Lt;vc%;kff_n7W%_CHLvbRT4=Rb<2#RN~{ZAf>PJw?7Bjs=huq z(o^aFYPB$J6-=H!oq6AEUjm}kGH0P{eBP+Fwsk766OdG8Eb^Jc6~v?kX}#d198equ zgGy2v+-mMUsQa=DdR|$Qb}`(i%ec+SOg;aR*0SoWRiU~I89{1386au!HcFgl1yp;I3I|4WC<) z-i^4eSw7VaNpdYRHTdh)sXMr^6ge00_0HxHm0@vBS#B8^`i`u;V&y=g*-hvDh;05L z>irueJ4wMDax!^}B83xV;X}?#Y4Zsa6-JNP8{mf6fp*61An?vDf)XxdsvYK7M+`a!NPoAdNpst2acsv zshQfIQSRGbyeih=ci=H2d%7Q(h}YJYj-~W?;o<-- z3X&6>#7Z!f;-vdO=3Q(v?jT7ags4v$fbMAVim-H}*aLd30xz0B|5rbP{9{=0uVWC4 zoGHd`d3Z}}pPfa7p;PUg*)vdF?flmng6o>xgtvu|9ca#+dqTPIy6fYpj6ks96mmhW z5>K+DKIAOBpM1TApbZNDs&BF71zbJ$4BD8IiK|SELTnFDYX{KXzc3*`xgxq^S6Nc- jrwobvY}8n29?0XTTnAW%3IWYm{-br-|2?tl+4z3};nk7? literal 0 HcmV?d00001 diff --git a/docs/modules/path_planning/dubins_path/dubins_path.rst b/docs/modules/path_planning/dubins_path/dubins_path.rst index 6765a84617..b612a82ef2 100644 --- a/docs/modules/path_planning/dubins_path/dubins_path.rst +++ b/docs/modules/path_planning/dubins_path/dubins_path.rst @@ -7,12 +7,37 @@ A sample code for Dubins path planning. Dubins path ~~~~~~~~~~~~ -Dubims path is a analyrical path planning algorithm for a simple car model. +Dubins path is a analytical path planning algorithm for a simple car model. It can generates a shortest path between 2D poses (x, y, yaw) with maximum curvture comstraint and tangent(yaw angle) constraint. +The path consist of 3 segments of maximum curvature curves or a straight line segment. +Each segment type can is categorized by 3 type: 'Right turn (R)' , 'Left turn (L)', and 'Straight (S).' +Possible path will be at least one of these six types: RSR, RSL, LSR, LSL, RLR, LRL. + +For example, one of RSR Dubins paths is: + +.. image:: dubins_path/RSR.jpg + :width: 400px + +one of RLR Dubins paths is: + +.. image:: dubins_path/RLR.jpg + :width: 200px + +Dubins path planner can output three types and distances of each course segment. + +You can generate a path from these information and the maximum curvature information. + +In the example code, a path which is minimum course length one among 6 course type is selected and then a path is constructed. + +Code +~~~~~~~~~~~~~~~~~~~~ + +.. automodule:: PathPlanning.DubinsPath.dubins_path_planner + :members: Reference @@ -20,3 +45,4 @@ Reference - `Dubins path - Wikipedia `__ - `15.3.1 Dubins Curves `__ +- `A Comprehensive, Step-by-Step Tutorial to Computing Dubin’s Paths `__ diff --git a/tests/test_diff_codestyle.py b/tests/test_diff_codestyle.py index 3dbe11a11a..89c228e285 100644 --- a/tests/test_diff_codestyle.py +++ b/tests/test_diff_codestyle.py @@ -92,7 +92,9 @@ def find_diff(sha): def run_flake8(diff): """Run flake8 on the given diff.""" res = subprocess.run( - ['flake8', '--diff'], + ['flake8', '--diff', '--ignore', + 'E402' # top level import for sys.path.append + ], input=diff, stdout=subprocess.PIPE, encoding='utf-8', diff --git a/tests/test_dubins_path_planning.py b/tests/test_dubins_path_planning.py index 18492ccc59..99c266bc6f 100644 --- a/tests/test_dubins_path_planning.py +++ b/tests/test_dubins_path_planning.py @@ -1,7 +1,7 @@ import numpy as np import conftest -from PathPlanning.DubinsPath import dubins_path_planning +from PathPlanning.DubinsPath import dubins_path_planner np.random.seed(12345) @@ -33,7 +33,7 @@ def test_1(): curvature = 1.0 - px, py, pyaw, mode, lengths = dubins_path_planning.dubins_path_planning( + px, py, pyaw, mode, lengths = dubins_path_planner.plan_dubins_path( start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature) check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x, @@ -42,8 +42,8 @@ def test_1(): def test_2(): - dubins_path_planning.show_animation = False - dubins_path_planning.main() + dubins_path_planner.show_animation = False + dubins_path_planner.main() def test_3(): @@ -61,8 +61,8 @@ def test_3(): curvature = 1.0 / (np.random.rand() * 5.0) px, py, pyaw, mode, lengths = \ - dubins_path_planning.dubins_path_planning( - start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature) + dubins_path_planner.plan_dubins_path( + start_x, start_y, start_yaw, end_x, end_y, end_yaw, curvature) check_edge_condition(px, py, pyaw, start_x, start_y, start_yaw, end_x, end_y, end_yaw) diff --git a/tests/test_utils.py b/tests/test_utils.py new file mode 100644 index 0000000000..b397479809 --- /dev/null +++ b/tests/test_utils.py @@ -0,0 +1,21 @@ +import conftest # Add root path to sys.path +from utils import angle +from numpy.testing import assert_allclose +import numpy as np + + +def test_angle_mod(): + assert_allclose(angle.angle_mod(-4.0), 2.28318531) + assert(isinstance(angle.angle_mod(-4.0), float)) + assert_allclose(angle.angle_mod([-4.0]), [2.28318531]) + assert(isinstance(angle.angle_mod([-4.0]), np.ndarray)) + + assert_allclose(angle.angle_mod([-150.0, 190.0, 350], degree=True), + [-150., -170., -10.]) + + assert_allclose(angle.angle_mod(-60.0, zero_2_2pi=True, degree=True), + [300.]) + + +if __name__ == '__main__': + conftest.run_this_test(__file__) diff --git a/utils/__init__.py b/utils/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/utils/angle.py b/utils/angle.py new file mode 100644 index 0000000000..741304f00e --- /dev/null +++ b/utils/angle.py @@ -0,0 +1,77 @@ +import numpy as np +from scipy.spatial.transform import Rotation as Rot + + +def create_2d_rotation_matrix(angle): + """ + Create 2D totation matrix from an angle + + Parameters + ---------- + angle : + + Returns + ------- + + """ + return Rot.from_euler('z', angle).as_matrix()[0:2, 0:2] + + +def angle_mod(x, zero_2_2pi=False, degree=False): + """ + Angle modulo operation + Default angle modulo range is [-pi, pi) + + Parameters + ---------- + x : float or array_like + A angle or an array of angles. This array is flattened for + the calculation. When an angle is provided, a float angle is returned. + zero_2_2pi : bool, optional + Change angle modulo range to [0, 2pi) + Default is False. + degree : bool, optional + If True, then the given angles are assumed to be in degrees. + Default is False. + + Returns + ------- + ret : float or ndarray + an angle or an array of modulated angle. + + Examples + -------- + >>> angle_mod(-4.0) + 2.28318531 + + >>> angle_mod([-4.0]) + np.array(2.28318531) + + >>> angle_mod([-150.0, 190.0, 350], degree=True) + array([-150., -170., -10.]) + + >>> angle_mod(-60.0, zero_2_2pi=True, degree=True) + array([300.]) + + """ + if isinstance(x, float): + is_float = True + else: + is_float = False + + x = np.asarray(x).flatten() + if degree: + x = np.deg2rad(x) + + if zero_2_2pi: + mod_angle = x % (2 * np.pi) + else: + mod_angle = (x + np.pi) % (2 * np.pi) - np.pi + + if degree: + mod_angle = np.rad2deg(mod_angle) + + if is_float: + return mod_angle.item() + else: + return mod_angle From d74a91e062732ed9bc9e85fe708cd615bfc0bc7a Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 7 May 2022 15:21:03 +0900 Subject: [PATCH 493/940] Re-architecture document structure (#669) * Rearchitecture document structure * Rearchitecture document structure * Rearchitecture document structure * Rearchitecture document structure * Rearchitecture document structure * Rearchitecture document structure * Rearchitecture document structure --- docs/index_main.rst | 2 +- .../aerial_navigation_main.rst | 8 ++- ...=> drone_3d_trajectory_following_main.rst} | 0 ...ng.rst => rocket_powered_landing_main.rst} | 0 ...s_2.rst => Kalmanfilter_basics_2_main.rst} | 0 ...asics.rst => Kalmanfilter_basics_main.rst} | 0 docs/modules/appendix/appendix_main.rst | 7 ++- .../arm_navigation/arm_navigation_main.rst | 28 +++-------- .../n_joint_arm_to_point_control_main.rst | 13 +++++ ...obstacle_avoidance_arm_navigation_main.rst | 6 +++ ...ink_ik.rst => planar_two_link_ik_main.rst} | 0 docs/modules/bipedal/bipedal_main.rst | 6 ++- ...l_planner.rst => bipedal_planner_main.rst} | 0 docs/modules/control/control_main.rst | 7 ++- ...rst => inverted_pendulum_control_main.rst} | 2 +- ...ol.rst => move_to_a_pose_control_main.rst} | 0 ...amble_kalman_filter_localization_main.rst} | 0 ...ended_kalman_filter_localization_main.rst} | 2 +- ...=> histogram_filter_localization_main.rst} | 10 ++-- .../localization/localization_main.rst | 15 +++--- ... => particle_filter_localization_main.rst} | 2 +- ...ented_kalman_filter_localization_main.rst} | 0 ...le_fitting.rst => circle_fitting_main.rst} | 0 ...rid_map.rst => gaussian_grid_map_main.rst} | 0 ...rst => k_means_object_clustering_main.rst} | 0 ...st => lidar_to_grid_map_tutorial_main.rst} | 12 ++--- docs/modules/mapping/mapping_main.rst | 15 +++--- ..._map.rst => ray_casting_grid_map_main.rst} | 0 ...fitting.rst => rectangle_fitting_main.rst} | 0 .../{bezier_path.rst => bezier_path_main.rst} | 4 +- ...bspline_path.rst => bspline_path_main.rst} | 2 +- .../{bugplanner.rst => bugplanner_main.rst} | 0 ...othoid_path.rst => clothoid_path_main.rst} | 0 ...verage_path.rst => coverage_path_main.rst} | 0 ...cubic_spline.rst => cubic_spline_main.rst} | 6 +-- .../{dubins_path.rst => dubins_path_main.rst} | 4 +- ...h.rst => dynamic_window_approach_main.rst} | 2 + .../{eta3_spline.rst => eta3_spline_main.rst} | 0 ...me_path.rst => frenet_frame_path_main.rst} | 0 ...e_search.rst => grid_base_search_main.rst} | 0 .../{hybridastar.rst => hybridastar_main.rst} | 0 .../{lqr_path.rst => lqr_path_main.rst} | 0 ..._predictive_trajectory_generator_main.rst} | 2 +- .../path_planning/path_planning_main.rst | 46 ++++++++++-------- .../{prm_planner.rst => prm_planner_main.rst} | 0 ...t => quintic_polynomials_planner_main.rst} | 0 ...epp_path.rst => reeds_shepp_path_main.rst} | 0 .../rrt/{rrt.rst => rrt_main.rst} | 2 +- docs/modules/path_planning/rrt/rrt_star.rst | 2 +- ...ner.rst => state_lattice_planner_main.rst} | 0 ...t => visibility_road_map_planner_main.rst} | 8 +-- .../{vrm_planner.rst => vrm_planner_main.rst} | 0 .../{cgmres_nmpc.rst => cgmres_nmpc_main.rst} | 8 +-- ...> lqr_speed_and_steering_control_main.rst} | 0 ...trol.rst => lqr_steering_control_main.rst} | 0 ...ctive_speed_and_steering_control_main.rst} | 0 .../path_tracking/path_tracking_main.rst | 17 ++++--- ...ing.rst => pure_pursuit_tracking_main.rst} | 0 ...t => rear_wheel_feedback_control_main.rst} | 0 ...y_control.rst => stanley_control_main.rst} | 0 .../{FastSLAM1.rst => FastSLAM1_main.rst} | 12 ++--- .../{FastSLAM2.rst => FastSLAM2_main.rst} | 0 .../{ekf_slam.rst => ekf_slam_main.rst} | 2 +- .../slam/graph_slam/graphSLAM_SE2_example.rst | 14 +++--- .../Graph_SLAM_optimization.gif | Bin 0 -> 114966 bytes .../modules/slam/graph_slam/graphSLAM_doc.rst | 12 ++--- .../graphSLAM_doc_11_1.png | Bin 0 -> 3931 bytes .../graphSLAM_doc_11_2.png | Bin 0 -> 3931 bytes .../graphSLAM_doc_files/graphSLAM_doc_2_0.png | Bin 0 -> 7764 bytes .../graphSLAM_doc_files/graphSLAM_doc_2_2.png | Bin 0 -> 7924 bytes .../graphSLAM_doc_files/graphSLAM_doc_4_0.png | Bin 0 -> 9308 bytes .../graphSLAM_doc_files/graphSLAM_doc_9_1.png | Bin 0 -> 8521 bytes .../slam/graph_slam/graphSLAM_formulation.rst | 2 +- .../{graph_slam.rst => graph_slam_main.rst} | 6 +-- ...iterative_closest_point_matching_main.rst} | 0 docs/modules/slam/slam_main.rst | 13 +++-- 76 files changed, 167 insertions(+), 132 deletions(-) rename docs/modules/aerial_navigation/drone_3d_trajectory_following/{drone_3d_trajectory_following.rst => drone_3d_trajectory_following_main.rst} (100%) rename docs/modules/aerial_navigation/rocket_powered_landing/{rocket_powered_landing.rst => rocket_powered_landing_main.rst} (100%) rename docs/modules/appendix/{Kalmanfilter_basics_2.rst => Kalmanfilter_basics_2_main.rst} (100%) rename docs/modules/appendix/{Kalmanfilter_basics.rst => Kalmanfilter_basics_main.rst} (100%) create mode 100644 docs/modules/arm_navigation/n_joint_arm_to_point_control_main.rst create mode 100644 docs/modules/arm_navigation/obstacle_avoidance_arm_navigation_main.rst rename docs/modules/arm_navigation/{planar_two_link_ik.rst => planar_two_link_ik_main.rst} (100%) rename docs/modules/bipedal/bipedal_planner/{bipedal_planner.rst => bipedal_planner_main.rst} (100%) rename docs/modules/control/inverted_pendulum_control/{inverted_pendulum_control.rst => inverted_pendulum_control_main.rst} (98%) rename docs/modules/control/move_to_a_pose_control/{move_to_a_pose_control.rst => move_to_a_pose_control_main.rst} (100%) rename docs/modules/localization/ensamble_kalman_filter_localization_files/{ensamble_kalman_filter_localization.rst => ensamble_kalman_filter_localization_main.rst} (100%) rename docs/modules/localization/extended_kalman_filter_localization_files/{extended_kalman_filter_localization.rst => extended_kalman_filter_localization_main.rst} (98%) rename docs/modules/localization/histogram_filter_localization/{histogram_filter_localization.rst => histogram_filter_localization_main.rst} (94%) rename docs/modules/localization/particle_filter_localization/{particle_filter_localization.rst => particle_filter_localization_main.rst} (94%) rename docs/modules/localization/unscented_kalman_filter_localization/{unscented_kalman_filter_localization.rst => unscented_kalman_filter_localization_main.rst} (100%) rename docs/modules/mapping/circle_fitting/{circle_fitting.rst => circle_fitting_main.rst} (100%) rename docs/modules/mapping/gaussian_grid_map/{gaussian_grid_map.rst => gaussian_grid_map_main.rst} (100%) rename docs/modules/mapping/k_means_object_clustering/{k_means_object_clustering.rst => k_means_object_clustering_main.rst} (100%) rename docs/modules/mapping/lidar_to_grid_map_tutorial/{lidar_to_grid_map_tutorial.rst => lidar_to_grid_map_tutorial_main.rst} (92%) rename docs/modules/mapping/ray_casting_grid_map/{ray_casting_grid_map.rst => ray_casting_grid_map_main.rst} (100%) rename docs/modules/mapping/rectangle_fitting/{rectangle_fitting.rst => rectangle_fitting_main.rst} (100%) rename docs/modules/path_planning/bezier_path/{bezier_path.rst => bezier_path_main.rst} (85%) rename docs/modules/path_planning/bspline_path/{bspline_path.rst => bspline_path_main.rst} (88%) rename docs/modules/path_planning/bugplanner/{bugplanner.rst => bugplanner_main.rst} (100%) rename docs/modules/path_planning/clothoid_path/{clothoid_path.rst => clothoid_path_main.rst} (100%) rename docs/modules/path_planning/coverage_path/{coverage_path.rst => coverage_path_main.rst} (100%) rename docs/modules/path_planning/cubic_spline/{cubic_spline.rst => cubic_spline_main.rst} (68%) rename docs/modules/path_planning/dubins_path/{dubins_path.rst => dubins_path_main.rst} (96%) rename docs/modules/path_planning/dynamic_window_approach/{dynamic_window_approach.rst => dynamic_window_approach_main.rst} (92%) rename docs/modules/path_planning/eta3_spline/{eta3_spline.rst => eta3_spline_main.rst} (100%) rename docs/modules/path_planning/frenet_frame_path/{frenet_frame_path.rst => frenet_frame_path_main.rst} (100%) rename docs/modules/path_planning/grid_base_search/{grid_base_search.rst => grid_base_search_main.rst} (100%) rename docs/modules/path_planning/hybridastar/{hybridastar.rst => hybridastar_main.rst} (100%) rename docs/modules/path_planning/lqr_path/{lqr_path.rst => lqr_path_main.rst} (100%) rename docs/modules/path_planning/model_predictive_trajectory_generator/{model_predictive_trajectory_generator.rst => model_predictive_trajectory_generator_main.rst} (90%) rename docs/modules/path_planning/prm_planner/{prm_planner.rst => prm_planner_main.rst} (100%) rename docs/modules/path_planning/quintic_polynomials_planner/{quintic_polynomials_planner.rst => quintic_polynomials_planner_main.rst} (100%) rename docs/modules/path_planning/reeds_shepp_path/{reeds_shepp_path.rst => reeds_shepp_path_main.rst} (100%) rename docs/modules/path_planning/rrt/{rrt.rst => rrt_main.rst} (99%) rename docs/modules/path_planning/state_lattice_planner/{state_lattice_planner.rst => state_lattice_planner_main.rst} (100%) rename docs/modules/path_planning/visibility_road_map_planner/{visibility_road_map_planner.rst => visibility_road_map_planner_main.rst} (91%) rename docs/modules/path_planning/vrm_planner/{vrm_planner.rst => vrm_planner_main.rst} (100%) rename docs/modules/path_tracking/cgmres_nmpc/{cgmres_nmpc.rst => cgmres_nmpc_main.rst} (92%) rename docs/modules/path_tracking/lqr_speed_and_steering_control/{lqr_speed_and_steering_control.rst => lqr_speed_and_steering_control_main.rst} (100%) rename docs/modules/path_tracking/lqr_steering_control/{lqr_steering_control.rst => lqr_steering_control_main.rst} (100%) rename docs/modules/path_tracking/model_predictive_speed_and_steering_control/{model_predictive_speed_and_steering_control.rst => model_predictive_speed_and_steering_control_main.rst} (100%) rename docs/modules/path_tracking/pure_pursuit_tracking/{pure_pursuit_tracking.rst => pure_pursuit_tracking_main.rst} (100%) rename docs/modules/path_tracking/rear_wheel_feedback_control/{rear_wheel_feedback_control.rst => rear_wheel_feedback_control_main.rst} (100%) rename docs/modules/path_tracking/stanley_control/{stanley_control.rst => stanley_control_main.rst} (100%) rename docs/modules/slam/FastSLAM1/{FastSLAM1.rst => FastSLAM1_main.rst} (98%) rename docs/modules/slam/FastSLAM2/{FastSLAM2.rst => FastSLAM2_main.rst} (100%) rename docs/modules/slam/ekf_slam/{ekf_slam.rst => ekf_slam_main.rst} (99%) create mode 100644 docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif create mode 100644 docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png create mode 100644 docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png create mode 100644 docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png create mode 100644 docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png create mode 100644 docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png create mode 100644 docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png rename docs/modules/slam/graph_slam/{graph_slam.rst => graph_slam_main.rst} (78%) rename docs/modules/slam/iterative_closest_point_matching/{iterative_closest_point_matching.rst => iterative_closest_point_matching_main.rst} (100%) diff --git a/docs/index_main.rst b/docs/index_main.rst index 79980c2bd9..151759284d 100644 --- a/docs/index_main.rst +++ b/docs/index_main.rst @@ -31,7 +31,7 @@ See this paper for more details: .. toctree:: :maxdepth: 2 - :caption: Guide + :caption: Contents getting_started modules/introduction diff --git a/docs/modules/aerial_navigation/aerial_navigation_main.rst b/docs/modules/aerial_navigation/aerial_navigation_main.rst index ea6c4c8e30..b2ccb071af 100644 --- a/docs/modules/aerial_navigation/aerial_navigation_main.rst +++ b/docs/modules/aerial_navigation/aerial_navigation_main.rst @@ -3,6 +3,10 @@ Aerial Navigation ================= -.. include:: drone_3d_trajectory_following/drone_3d_trajectory_following.rst -.. include:: rocket_powered_landing/rocket_powered_landing.rst +.. toctree:: + :maxdepth: 2 + :caption: Contents + + drone_3d_trajectory_following/drone_3d_trajectory_following + rocket_powered_landing/rocket_powered_landing diff --git a/docs/modules/aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following.rst b/docs/modules/aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst similarity index 100% rename from docs/modules/aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following.rst rename to docs/modules/aerial_navigation/drone_3d_trajectory_following/drone_3d_trajectory_following_main.rst diff --git a/docs/modules/aerial_navigation/rocket_powered_landing/rocket_powered_landing.rst b/docs/modules/aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst similarity index 100% rename from docs/modules/aerial_navigation/rocket_powered_landing/rocket_powered_landing.rst rename to docs/modules/aerial_navigation/rocket_powered_landing/rocket_powered_landing_main.rst diff --git a/docs/modules/appendix/Kalmanfilter_basics_2.rst b/docs/modules/appendix/Kalmanfilter_basics_2_main.rst similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics_2.rst rename to docs/modules/appendix/Kalmanfilter_basics_2_main.rst diff --git a/docs/modules/appendix/Kalmanfilter_basics.rst b/docs/modules/appendix/Kalmanfilter_basics_main.rst similarity index 100% rename from docs/modules/appendix/Kalmanfilter_basics.rst rename to docs/modules/appendix/Kalmanfilter_basics_main.rst diff --git a/docs/modules/appendix/appendix_main.rst b/docs/modules/appendix/appendix_main.rst index 8840603bca..8a29d84676 100644 --- a/docs/modules/appendix/appendix_main.rst +++ b/docs/modules/appendix/appendix_main.rst @@ -3,7 +3,10 @@ Appendix ============== -.. include:: Kalmanfilter_basics.rst +.. toctree:: + :maxdepth: 2 + :caption: Contents -.. include:: Kalmanfilter_basics_2.rst + Kalmanfilter_basics + Kalmanfilter_basics_2 diff --git a/docs/modules/arm_navigation/arm_navigation_main.rst b/docs/modules/arm_navigation/arm_navigation_main.rst index 4399ae13e3..bbbc872c58 100644 --- a/docs/modules/arm_navigation/arm_navigation_main.rst +++ b/docs/modules/arm_navigation/arm_navigation_main.rst @@ -3,26 +3,10 @@ Arm Navigation ============== -.. include:: planar_two_link_ik.rst +.. toctree:: + :maxdepth: 2 + :caption: Contents - -N joint arm to point control ----------------------------- - -N joint arm to a point control simulation. - -This is a interactive simulation. - -You can set the goal position of the end effector with left-click on the -plotting area. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/n_joint_arm_to_point_control/animation.gif - -In this simulation N = 10, however, you can change it. - -Arm navigation with obstacle avoidance --------------------------------------- - -Arm navigation with obstacle avoidance simulation. - -.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/arm_obstacle_navigation/animation.gif + planar_two_link_ik + n_joint_arm_to_point_control + obstacle_avoidance_arm_navigation diff --git a/docs/modules/arm_navigation/n_joint_arm_to_point_control_main.rst b/docs/modules/arm_navigation/n_joint_arm_to_point_control_main.rst new file mode 100644 index 0000000000..cc6279f681 --- /dev/null +++ b/docs/modules/arm_navigation/n_joint_arm_to_point_control_main.rst @@ -0,0 +1,13 @@ +N joint arm to point control +---------------------------- + +N joint arm to a point control simulation. + +This is a interactive simulation. + +You can set the goal position of the end effector with left-click on the +plotting area. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/n_joint_arm_to_point_control/animation.gif + +In this simulation N = 10, however, you can change it. diff --git a/docs/modules/arm_navigation/obstacle_avoidance_arm_navigation_main.rst b/docs/modules/arm_navigation/obstacle_avoidance_arm_navigation_main.rst new file mode 100644 index 0000000000..899a64a5cd --- /dev/null +++ b/docs/modules/arm_navigation/obstacle_avoidance_arm_navigation_main.rst @@ -0,0 +1,6 @@ +Arm navigation with obstacle avoidance +-------------------------------------- + +Arm navigation with obstacle avoidance simulation. + +.. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/ArmNavigation/arm_obstacle_navigation/animation.gif \ No newline at end of file diff --git a/docs/modules/arm_navigation/planar_two_link_ik.rst b/docs/modules/arm_navigation/planar_two_link_ik_main.rst similarity index 100% rename from docs/modules/arm_navigation/planar_two_link_ik.rst rename to docs/modules/arm_navigation/planar_two_link_ik_main.rst diff --git a/docs/modules/bipedal/bipedal_main.rst b/docs/modules/bipedal/bipedal_main.rst index bab316b0d9..fc5b933055 100644 --- a/docs/modules/bipedal/bipedal_main.rst +++ b/docs/modules/bipedal/bipedal_main.rst @@ -3,5 +3,9 @@ Bipedal ================= -.. include:: bipedal_planner/bipedal_planner.rst +.. toctree:: + :maxdepth: 2 + :caption: Contents + + bipedal_planner/bipedal_planner diff --git a/docs/modules/bipedal/bipedal_planner/bipedal_planner.rst b/docs/modules/bipedal/bipedal_planner/bipedal_planner_main.rst similarity index 100% rename from docs/modules/bipedal/bipedal_planner/bipedal_planner.rst rename to docs/modules/bipedal/bipedal_planner/bipedal_planner_main.rst diff --git a/docs/modules/control/control_main.rst b/docs/modules/control/control_main.rst index d6d36a726b..cee2aa9e8e 100644 --- a/docs/modules/control/control_main.rst +++ b/docs/modules/control/control_main.rst @@ -3,7 +3,10 @@ Control ================= -.. include:: inverted_pendulum_control/inverted_pendulum_control.rst +.. toctree:: + :maxdepth: 2 + :caption: Contents -.. include:: move_to_a_pose_control/move_to_a_pose_control.rst + inverted_pendulum_control/inverted_pendulum_control + move_to_a_pose_control/move_to_a_pose_control diff --git a/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst b/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control_main.rst similarity index 98% rename from docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst rename to docs/modules/control/inverted_pendulum_control/inverted_pendulum_control_main.rst index 4c1f672ba0..e41729fd61 100644 --- a/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control.rst +++ b/docs/modules/control/inverted_pendulum_control/inverted_pendulum_control_main.rst @@ -9,7 +9,7 @@ The objective of the control system is to balance the inverted pendulum by apply Modeling ~~~~~~~~~~~~ -.. image:: inverted_pendulum_control/inverted-pendulum.png +.. image:: inverted-pendulum.png :align: center - :math:`M`: mass of the cart diff --git a/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst b/docs/modules/control/move_to_a_pose_control/move_to_a_pose_control_main.rst similarity index 100% rename from docs/modules/control/move_to_a_pose_control/move_to_a_pose_control.rst rename to docs/modules/control/move_to_a_pose_control/move_to_a_pose_control_main.rst diff --git a/docs/modules/localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization.rst b/docs/modules/localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst similarity index 100% rename from docs/modules/localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization.rst rename to docs/modules/localization/ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization_main.rst diff --git a/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst b/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst similarity index 98% rename from docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst rename to docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst index a9c2939678..0ec920c9df 100644 --- a/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst +++ b/docs/modules/localization/extended_kalman_filter_localization_files/extended_kalman_filter_localization_main.rst @@ -2,7 +2,7 @@ Extended Kalman Filter Localization ----------------------------------- -.. image:: extended_kalman_filter_localization_files/extended_kalman_filter_localization_1_0.png +.. image:: extended_kalman_filter_localization_1_0.png :width: 600px diff --git a/docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst b/docs/modules/localization/histogram_filter_localization/histogram_filter_localization_main.rst similarity index 94% rename from docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst rename to docs/modules/localization/histogram_filter_localization/histogram_filter_localization_main.rst index 891de94135..fafd578333 100644 --- a/docs/modules/localization/histogram_filter_localization/histogram_filter_localization.rst +++ b/docs/modules/localization/histogram_filter_localization/histogram_filter_localization_main.rst @@ -53,12 +53,12 @@ the estimation error due to the movement. For example, the position probability is peaky with observations: -.. image:: histogram_filter_localization/1.png +.. image:: 1.png :width: 400px But, the probability is getting uncertain without observations: -.. image:: histogram_filter_localization/2.png +.. image:: 2.png :width: 400px @@ -88,12 +88,12 @@ The probability of each grid is updated by this formula: When the `d` is 3.0, the `h(z)` distribution is: -.. image:: histogram_filter_localization/4.png +.. image:: 4.png :width: 400px The observation probability distribution looks a circle when a RF-ID is observed: -.. image:: histogram_filter_localization/3.png +.. image:: 3.png :width: 400px Step4: Estimate position from probability @@ -110,5 +110,5 @@ There are two ways to calculate the final positions: References: ~~~~~~~~~~~ -- `PROBABILISTIC ROBOTICS`_ +- `_PROBABILISTIC ROBOTICS: `_ - `Robust Vehicle Localization in Urban Environments Using Probabilistic Maps `_ diff --git a/docs/modules/localization/localization_main.rst b/docs/modules/localization/localization_main.rst index b1769df163..db6651f6b8 100644 --- a/docs/modules/localization/localization_main.rst +++ b/docs/modules/localization/localization_main.rst @@ -3,11 +3,14 @@ Localization ============ -.. include:: extended_kalman_filter_localization_files/extended_kalman_filter_localization.rst -.. include:: ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization.rst -.. include:: unscented_kalman_filter_localization/unscented_kalman_filter_localization.rst -.. include:: histogram_filter_localization/histogram_filter_localization.rst -.. include:: particle_filter_localization/particle_filter_localization.rst +.. toctree:: + :maxdepth: 2 + :caption: Contents + + extended_kalman_filter_localization_files/extended_kalman_filter_localization + ensamble_kalman_filter_localization_files/ensamble_kalman_filter_localization + unscented_kalman_filter_localization/unscented_kalman_filter_localization + histogram_filter_localization/histogram_filter_localization + particle_filter_localization/particle_filter_localization -.. _PROBABILISTIC ROBOTICS: http://www.probabilistic-robotics.org/ diff --git a/docs/modules/localization/particle_filter_localization/particle_filter_localization.rst b/docs/modules/localization/particle_filter_localization/particle_filter_localization_main.rst similarity index 94% rename from docs/modules/localization/particle_filter_localization/particle_filter_localization.rst rename to docs/modules/localization/particle_filter_localization/particle_filter_localization_main.rst index 55b44e166b..c8652ce8a7 100644 --- a/docs/modules/localization/particle_filter_localization/particle_filter_localization.rst +++ b/docs/modules/localization/particle_filter_localization/particle_filter_localization_main.rst @@ -33,5 +33,5 @@ The covariance matrix :math:`\Xi` from particle information is calculated by the References: ~~~~~~~~~~~ -- `PROBABILISTIC ROBOTICS`_ +- `_PROBABILISTIC ROBOTICS: `_ - `Improving the particle filter in high dimensions using conjugate artificial process noise `_ diff --git a/docs/modules/localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization.rst b/docs/modules/localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst similarity index 100% rename from docs/modules/localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization.rst rename to docs/modules/localization/unscented_kalman_filter_localization/unscented_kalman_filter_localization_main.rst diff --git a/docs/modules/mapping/circle_fitting/circle_fitting.rst b/docs/modules/mapping/circle_fitting/circle_fitting_main.rst similarity index 100% rename from docs/modules/mapping/circle_fitting/circle_fitting.rst rename to docs/modules/mapping/circle_fitting/circle_fitting_main.rst diff --git a/docs/modules/mapping/gaussian_grid_map/gaussian_grid_map.rst b/docs/modules/mapping/gaussian_grid_map/gaussian_grid_map_main.rst similarity index 100% rename from docs/modules/mapping/gaussian_grid_map/gaussian_grid_map.rst rename to docs/modules/mapping/gaussian_grid_map/gaussian_grid_map_main.rst diff --git a/docs/modules/mapping/k_means_object_clustering/k_means_object_clustering.rst b/docs/modules/mapping/k_means_object_clustering/k_means_object_clustering_main.rst similarity index 100% rename from docs/modules/mapping/k_means_object_clustering/k_means_object_clustering.rst rename to docs/modules/mapping/k_means_object_clustering/k_means_object_clustering_main.rst diff --git a/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial.rst b/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst similarity index 92% rename from docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial.rst rename to docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst index 2e9470ff6c..1f62179efd 100644 --- a/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial.rst +++ b/docs/modules/mapping/lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_main.rst @@ -16,7 +16,7 @@ a ``numpy array``, and numbers close to 1 means the cell is occupied free (*marked with green*). The grid has the ability to represent unknown (unobserved) areas, which are close to 0.5. -.. figure:: lidar_to_grid_map_tutorial/grid_map_example.png +.. figure:: grid_map_example.png In order to construct the grid map from the measurement we need to discretise the values. But, first let’s need to ``import`` some @@ -68,7 +68,7 @@ From the distances and the angles it is easy to determine the ``x`` and -.. image:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_5_0.png +.. image:: lidar_to_grid_map_tutorial_5_0.png The ``lidar_to_grid_map.py`` contains handy functions which can used to @@ -89,7 +89,7 @@ map. Let’s see how this works. -.. image:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_7_0.png +.. image:: lidar_to_grid_map_tutorial_7_0.png .. code:: ipython3 @@ -106,7 +106,7 @@ map. Let’s see how this works. -.. image:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_8_0.png +.. image:: lidar_to_grid_map_tutorial_8_0.png To fill empty areas, a queue-based algorithm can be used that can be @@ -163,7 +163,7 @@ from a center point (e.g. (10, 20)) with zeros: -.. image:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_12_0.png +.. image:: lidar_to_grid_map_tutorial_12_0.png Let’s use this flood fill on real data: @@ -194,5 +194,5 @@ Let’s use this flood fill on real data: -.. image:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial_14_1.png +.. image:: lidar_to_grid_map_tutorial_14_1.png diff --git a/docs/modules/mapping/mapping_main.rst b/docs/modules/mapping/mapping_main.rst index 7d2c4cfe67..0f7ec549dc 100644 --- a/docs/modules/mapping/mapping_main.rst +++ b/docs/modules/mapping/mapping_main.rst @@ -2,11 +2,14 @@ Mapping ======= +.. toctree:: + :maxdepth: 2 + :caption: Contents -.. include:: gaussian_grid_map/gaussian_grid_map.rst -.. include:: ray_casting_grid_map/ray_casting_grid_map.rst -.. include:: lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial.rst -.. include:: k_means_object_clustering/k_means_object_clustering.rst -.. include:: circle_fitting/circle_fitting.rst -.. include:: rectangle_fitting/rectangle_fitting.rst + gaussian_grid_map/gaussian_grid_map + ray_casting_grid_map/ray_casting_grid_map + lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial + k_means_object_clustering/k_means_object_clustering + circle_fitting/circle_fitting + rectangle_fitting/rectangle_fitting diff --git a/docs/modules/mapping/ray_casting_grid_map/ray_casting_grid_map.rst b/docs/modules/mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst similarity index 100% rename from docs/modules/mapping/ray_casting_grid_map/ray_casting_grid_map.rst rename to docs/modules/mapping/ray_casting_grid_map/ray_casting_grid_map_main.rst diff --git a/docs/modules/mapping/rectangle_fitting/rectangle_fitting.rst b/docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst similarity index 100% rename from docs/modules/mapping/rectangle_fitting/rectangle_fitting.rst rename to docs/modules/mapping/rectangle_fitting/rectangle_fitting_main.rst diff --git a/docs/modules/path_planning/bezier_path/bezier_path.rst b/docs/modules/path_planning/bezier_path/bezier_path_main.rst similarity index 85% rename from docs/modules/path_planning/bezier_path/bezier_path.rst rename to docs/modules/path_planning/bezier_path/bezier_path_main.rst index c630d54345..fbba6a4496 100644 --- a/docs/modules/path_planning/bezier_path/bezier_path.rst +++ b/docs/modules/path_planning/bezier_path/bezier_path_main.rst @@ -5,13 +5,13 @@ A sample code of Bezier path planning. It is based on 4 control points Beizer path. -.. image:: Bezier_path/Figure_1.png +.. image:: Figure_1.png If you change the offset distance from start and end point, You can get different Beizer course: -.. image:: Bezier_path/Figure_2.png +.. image:: Figure_2.png Ref: diff --git a/docs/modules/path_planning/bspline_path/bspline_path.rst b/docs/modules/path_planning/bspline_path/bspline_path_main.rst similarity index 88% rename from docs/modules/path_planning/bspline_path/bspline_path.rst rename to docs/modules/path_planning/bspline_path/bspline_path_main.rst index a8043122fa..d3523a1918 100644 --- a/docs/modules/path_planning/bspline_path/bspline_path.rst +++ b/docs/modules/path_planning/bspline_path/bspline_path_main.rst @@ -1,7 +1,7 @@ B-Spline planning ----------------- -.. image:: bspline_path/Figure_1.png +.. image:: Figure_1.png This is a path planning with B-Spline curse. diff --git a/docs/modules/path_planning/bugplanner/bugplanner.rst b/docs/modules/path_planning/bugplanner/bugplanner_main.rst similarity index 100% rename from docs/modules/path_planning/bugplanner/bugplanner.rst rename to docs/modules/path_planning/bugplanner/bugplanner_main.rst diff --git a/docs/modules/path_planning/clothoid_path/clothoid_path.rst b/docs/modules/path_planning/clothoid_path/clothoid_path_main.rst similarity index 100% rename from docs/modules/path_planning/clothoid_path/clothoid_path.rst rename to docs/modules/path_planning/clothoid_path/clothoid_path_main.rst diff --git a/docs/modules/path_planning/coverage_path/coverage_path.rst b/docs/modules/path_planning/coverage_path/coverage_path_main.rst similarity index 100% rename from docs/modules/path_planning/coverage_path/coverage_path.rst rename to docs/modules/path_planning/coverage_path/coverage_path_main.rst diff --git a/docs/modules/path_planning/cubic_spline/cubic_spline.rst b/docs/modules/path_planning/cubic_spline/cubic_spline_main.rst similarity index 68% rename from docs/modules/path_planning/cubic_spline/cubic_spline.rst rename to docs/modules/path_planning/cubic_spline/cubic_spline_main.rst index b1973856e8..6de0297a05 100644 --- a/docs/modules/path_planning/cubic_spline/cubic_spline.rst +++ b/docs/modules/path_planning/cubic_spline/cubic_spline_main.rst @@ -8,6 +8,6 @@ with cubic spline. Heading angle of each point can be also calculated analytically. -.. image:: cubic_spline/Figure_1.png -.. image:: cubic_spline/Figure_2.png -.. image:: cubic_spline/Figure_3.png +.. image:: Figure_1.png +.. image:: Figure_2.png +.. image:: Figure_3.png diff --git a/docs/modules/path_planning/dubins_path/dubins_path.rst b/docs/modules/path_planning/dubins_path/dubins_path_main.rst similarity index 96% rename from docs/modules/path_planning/dubins_path/dubins_path.rst rename to docs/modules/path_planning/dubins_path/dubins_path_main.rst index b612a82ef2..0b8c8fb603 100644 --- a/docs/modules/path_planning/dubins_path/dubins_path.rst +++ b/docs/modules/path_planning/dubins_path/dubins_path_main.rst @@ -19,12 +19,12 @@ Possible path will be at least one of these six types: RSR, RSL, LSR, LSL, RLR, For example, one of RSR Dubins paths is: -.. image:: dubins_path/RSR.jpg +.. image:: RSR.jpg :width: 400px one of RLR Dubins paths is: -.. image:: dubins_path/RLR.jpg +.. image:: RLR.jpg :width: 200px Dubins path planner can output three types and distances of each course segment. diff --git a/docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach.rst b/docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach_main.rst similarity index 92% rename from docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach.rst rename to docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach_main.rst index 0ece6e0054..d645838597 100644 --- a/docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach.rst +++ b/docs/modules/path_planning/dynamic_window_approach/dynamic_window_approach_main.rst @@ -1,3 +1,5 @@ +.. _dynamic_window_approach: + Dynamic Window Approach ----------------------- diff --git a/docs/modules/path_planning/eta3_spline/eta3_spline.rst b/docs/modules/path_planning/eta3_spline/eta3_spline_main.rst similarity index 100% rename from docs/modules/path_planning/eta3_spline/eta3_spline.rst rename to docs/modules/path_planning/eta3_spline/eta3_spline_main.rst diff --git a/docs/modules/path_planning/frenet_frame_path/frenet_frame_path.rst b/docs/modules/path_planning/frenet_frame_path/frenet_frame_path_main.rst similarity index 100% rename from docs/modules/path_planning/frenet_frame_path/frenet_frame_path.rst rename to docs/modules/path_planning/frenet_frame_path/frenet_frame_path_main.rst diff --git a/docs/modules/path_planning/grid_base_search/grid_base_search.rst b/docs/modules/path_planning/grid_base_search/grid_base_search_main.rst similarity index 100% rename from docs/modules/path_planning/grid_base_search/grid_base_search.rst rename to docs/modules/path_planning/grid_base_search/grid_base_search_main.rst diff --git a/docs/modules/path_planning/hybridastar/hybridastar.rst b/docs/modules/path_planning/hybridastar/hybridastar_main.rst similarity index 100% rename from docs/modules/path_planning/hybridastar/hybridastar.rst rename to docs/modules/path_planning/hybridastar/hybridastar_main.rst diff --git a/docs/modules/path_planning/lqr_path/lqr_path.rst b/docs/modules/path_planning/lqr_path/lqr_path_main.rst similarity index 100% rename from docs/modules/path_planning/lqr_path/lqr_path.rst rename to docs/modules/path_planning/lqr_path/lqr_path_main.rst diff --git a/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator.rst b/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst similarity index 90% rename from docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator.rst rename to docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst index 07a7ee9b59..0fc997898e 100644 --- a/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator.rst +++ b/docs/modules/path_planning/model_predictive_trajectory_generator/model_predictive_trajectory_generator_main.rst @@ -14,7 +14,7 @@ Path optimization sample Lookup table generation sample ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -.. image:: model_predictive_trajectory_generator/lookup_table.png +.. image:: lookup_table.png Ref: diff --git a/docs/modules/path_planning/path_planning_main.rst b/docs/modules/path_planning/path_planning_main.rst index 5c70592afc..a3237f16f1 100644 --- a/docs/modules/path_planning/path_planning_main.rst +++ b/docs/modules/path_planning/path_planning_main.rst @@ -3,24 +3,28 @@ Path Planning ============= -.. include:: dynamic_window_approach/dynamic_window_approach.rst -.. include:: bugplanner/bugplanner.rst -.. include:: grid_base_search/grid_base_search.rst -.. include:: model_predictive_trajectory_generator/model_predictive_trajectory_generator.rst -.. include:: state_lattice_planner/state_lattice_planner.rst -.. include:: prm_planner/prm_planner.rst -.. include:: visibility_road_map_planner/visibility_road_map_planner.rst -.. include:: vrm_planner/vrm_planner.rst -.. include:: rrt/rrt.rst -.. include:: cubic_spline/cubic_spline.rst -.. include:: bspline_path/bspline_path.rst -.. include:: clothoid_path/clothoid_path.rst -.. include:: eta3_spline/eta3_spline.rst -.. include:: bezier_path/bezier_path.rst -.. include:: quintic_polynomials_planner/quintic_polynomials_planner.rst -.. include:: dubins_path/dubins_path.rst -.. include:: reeds_shepp_path/reeds_shepp_path.rst -.. include:: lqr_path/lqr_path.rst -.. include:: hybridastar/hybridastar.rst -.. include:: frenet_frame_path/frenet_frame_path.rst -.. include:: coverage_path/coverage_path.rst +.. toctree:: + :maxdepth: 2 + :caption: Contents + + dynamic_window_approach/dynamic_window_approach + bugplanner/bugplanner + grid_base_search/grid_base_search + model_predictive_trajectory_generator/model_predictive_trajectory_generator + state_lattice_planner/state_lattice_planner + prm_planner/prm_planner + visibility_road_map_planner/visibility_road_map_planner + vrm_planner/vrm_planner + rrt/rrt + cubic_spline/cubic_spline + bspline_path/bspline_path + clothoid_path/clothoid_path + eta3_spline/eta3_spline + bezier_path/bezier_path + quintic_polynomials_planner/quintic_polynomials_planner + dubins_path/dubins_path + reeds_shepp_path/reeds_shepp_path + lqr_path/lqr_path + hybridastar/hybridastar + frenet_frame_path/frenet_frame_path + coverage_path/coverage_path diff --git a/docs/modules/path_planning/prm_planner/prm_planner.rst b/docs/modules/path_planning/prm_planner/prm_planner_main.rst similarity index 100% rename from docs/modules/path_planning/prm_planner/prm_planner.rst rename to docs/modules/path_planning/prm_planner/prm_planner_main.rst diff --git a/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner.rst b/docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst similarity index 100% rename from docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner.rst rename to docs/modules/path_planning/quintic_polynomials_planner/quintic_polynomials_planner_main.rst diff --git a/docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path.rst b/docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path_main.rst similarity index 100% rename from docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path.rst rename to docs/modules/path_planning/reeds_shepp_path/reeds_shepp_path_main.rst diff --git a/docs/modules/path_planning/rrt/rrt.rst b/docs/modules/path_planning/rrt/rrt_main.rst similarity index 99% rename from docs/modules/path_planning/rrt/rrt.rst rename to docs/modules/path_planning/rrt/rrt_main.rst index 1afa17b144..5a3a30dcff 100644 --- a/docs/modules/path_planning/rrt/rrt.rst +++ b/docs/modules/path_planning/rrt/rrt_main.rst @@ -14,7 +14,7 @@ This is a simple path planning code with Rapidly-Exploring Random Trees Black circles are obstacles, green line is a searched tree, red crosses are start and goal positions. -.. include:: rrt/rrt_star.rst +.. include:: rrt_star.rst RRT with dubins path diff --git a/docs/modules/path_planning/rrt/rrt_star.rst b/docs/modules/path_planning/rrt/rrt_star.rst index 546e9bf6dd..d36eaac70e 100644 --- a/docs/modules/path_planning/rrt/rrt_star.rst +++ b/docs/modules/path_planning/rrt/rrt_star.rst @@ -10,7 +10,7 @@ Black circles are obstacles, green line is a searched tree, red crosses are star Simulation ^^^^^^^^^^ -.. image:: rrt/rrt_star/rrt_star_1_0.png +.. image:: rrt_star/rrt_star_1_0.png :width: 600px diff --git a/docs/modules/path_planning/state_lattice_planner/state_lattice_planner.rst b/docs/modules/path_planning/state_lattice_planner/state_lattice_planner_main.rst similarity index 100% rename from docs/modules/path_planning/state_lattice_planner/state_lattice_planner.rst rename to docs/modules/path_planning/state_lattice_planner/state_lattice_planner_main.rst diff --git a/docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner.rst b/docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst similarity index 91% rename from docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner.rst rename to docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst index 97e083389e..3c9b7c008c 100644 --- a/docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner.rst +++ b/docs/modules/path_planning/visibility_road_map_planner/visibility_road_map_planner_main.rst @@ -24,7 +24,7 @@ We assume this planner can be provided these information in the below figure. - 2. Goal point (Blue point) - 3. Obstacle polygons (Black lines) -.. image:: visibility_road_map_planner/step0.png +.. image:: step0.png :width: 400px @@ -33,7 +33,7 @@ Step1: Generate visibility nodes based on polygon obstacles The nodes are generated by expanded these polygons vertexes like the below figure: -.. image:: visibility_road_map_planner/step1.png +.. image:: step1.png :width: 400px Each polygon vertex is expanded outward from the vector of adjacent vertices. @@ -49,7 +49,7 @@ If the arc is collided, the graph is removed. The blue lines are generated visibility graphs in the figure: -.. image:: visibility_road_map_planner/step2.png +.. image:: step2.png :width: 400px @@ -58,7 +58,7 @@ Step3: Search the shortest path in the graphs using Dijkstra algorithm The red line is searched path in the figure: -.. image:: visibility_road_map_planner/step3.png +.. image:: step3.png :width: 400px You can find the details of Dijkstra algorithm in :ref:`dijkstra`. diff --git a/docs/modules/path_planning/vrm_planner/vrm_planner.rst b/docs/modules/path_planning/vrm_planner/vrm_planner_main.rst similarity index 100% rename from docs/modules/path_planning/vrm_planner/vrm_planner.rst rename to docs/modules/path_planning/vrm_planner/vrm_planner_main.rst diff --git a/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc.rst b/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst similarity index 92% rename from docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc.rst rename to docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst index 5092fa8e2f..a1980ba17e 100644 --- a/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc.rst +++ b/docs/modules/path_tracking/cgmres_nmpc/cgmres_nmpc_main.rst @@ -2,16 +2,16 @@ Nonlinear Model Predictive Control with C-GMRES ----------------------------------------------- -.. image:: cgmres_nmpc/cgmres_nmpc_1_0.png +.. image:: cgmres_nmpc_1_0.png :width: 600px -.. image:: cgmres_nmpc/cgmres_nmpc_2_0.png +.. image:: cgmres_nmpc_2_0.png :width: 600px -.. image:: cgmres_nmpc/cgmres_nmpc_3_0.png +.. image:: cgmres_nmpc_3_0.png :width: 600px -.. image:: cgmres_nmpc/cgmres_nmpc_4_0.png +.. image:: cgmres_nmpc_4_0.png :width: 600px .. figure:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/PathTracking/cgmres_nmpc/animation.gif diff --git a/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control.rst b/docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst similarity index 100% rename from docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control.rst rename to docs/modules/path_tracking/lqr_speed_and_steering_control/lqr_speed_and_steering_control_main.rst diff --git a/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control.rst b/docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst similarity index 100% rename from docs/modules/path_tracking/lqr_steering_control/lqr_steering_control.rst rename to docs/modules/path_tracking/lqr_steering_control/lqr_steering_control_main.rst diff --git a/docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control.rst b/docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst similarity index 100% rename from docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control.rst rename to docs/modules/path_tracking/model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control_main.rst diff --git a/docs/modules/path_tracking/path_tracking_main.rst b/docs/modules/path_tracking/path_tracking_main.rst index 2a572ef6df..504ba08795 100644 --- a/docs/modules/path_tracking/path_tracking_main.rst +++ b/docs/modules/path_tracking/path_tracking_main.rst @@ -3,11 +3,14 @@ Path Tracking ============= -.. include:: pure_pursuit_tracking/pure_pursuit_tracking.rst -.. include:: stanley_control/stanley_control.rst -.. include:: rear_wheel_feedback_control/rear_wheel_feedback_control.rst -.. include:: lqr_steering_control/lqr_steering_control.rst -.. include:: lqr_speed_and_steering_control/lqr_speed_and_steering_control.rst -.. include:: model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control.rst -.. include:: cgmres_nmpc/cgmres_nmpc.rst +.. toctree:: + :maxdepth: 2 + :caption: Contents + pure_pursuit_tracking/pure_pursuit_tracking + stanley_control/stanley_control + rear_wheel_feedback_control/rear_wheel_feedback_control + lqr_steering_control/lqr_steering_control + lqr_speed_and_steering_control/lqr_speed_and_steering_control + model_predictive_speed_and_steering_control/model_predictive_speed_and_steering_control + cgmres_nmpc/cgmres_nmpc diff --git a/docs/modules/path_tracking/pure_pursuit_tracking/pure_pursuit_tracking.rst b/docs/modules/path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst similarity index 100% rename from docs/modules/path_tracking/pure_pursuit_tracking/pure_pursuit_tracking.rst rename to docs/modules/path_tracking/pure_pursuit_tracking/pure_pursuit_tracking_main.rst diff --git a/docs/modules/path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control.rst b/docs/modules/path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst similarity index 100% rename from docs/modules/path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control.rst rename to docs/modules/path_tracking/rear_wheel_feedback_control/rear_wheel_feedback_control_main.rst diff --git a/docs/modules/path_tracking/stanley_control/stanley_control.rst b/docs/modules/path_tracking/stanley_control/stanley_control_main.rst similarity index 100% rename from docs/modules/path_tracking/stanley_control/stanley_control.rst rename to docs/modules/path_tracking/stanley_control/stanley_control_main.rst diff --git a/docs/modules/slam/FastSLAM1/FastSLAM1.rst b/docs/modules/slam/FastSLAM1/FastSLAM1_main.rst similarity index 98% rename from docs/modules/slam/FastSLAM1/FastSLAM1.rst rename to docs/modules/slam/FastSLAM1/FastSLAM1_main.rst index f1e9dfd8aa..f09125dff0 100644 --- a/docs/modules/slam/FastSLAM1/FastSLAM1.rst +++ b/docs/modules/slam/FastSLAM1/FastSLAM1_main.rst @@ -11,7 +11,7 @@ Simulation This is a feature based SLAM example using FastSLAM 1.0. -.. image:: FastSLAM1/FastSLAM1_1_0.png +.. image:: FastSLAM1_1_0.png :width: 600px The blue line is ground truth, the black line is dead reckoning, the red @@ -46,8 +46,8 @@ an array of landmark locations I.e. Each particle maintains a deterministic pose and n-EKFs for each landmark and update it with each measurement. -Algorithm walkthrough -~~~~~~~~~~~~~~~~~~~~~ +Algorithm walk through +~~~~~~~~~~~~~~~~~~~~~~~ The particles are initially drawn from a uniform distribution the represent the initial uncertainty. At each time step we do: @@ -75,7 +75,7 @@ which are the linear and angular velocity repsectively. :math:`\begin{equation*} \begin{bmatrix} x_{t+1} \\ y_{t+1} \\ \theta_{t+1} \end{bmatrix}= \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix}\begin{bmatrix} x_{t} \\ y_{t} \\ \theta_{t} \end{bmatrix}+ \begin{bmatrix} \Delta t cos(\theta) & 0\\ \Delta t sin(\theta) & 0\\ 0 & \Delta t \end{bmatrix} \begin{bmatrix} v_{t} + \sigma_v\\ w_{t} + \sigma_w\\ \end{bmatrix} \end{equation*}` -The following snippets playsback the recorded trajectory of each +The following snippets playback the recorded trajectory of each particle. To get the insight of the motion model change the value of :math:`R` and @@ -527,8 +527,8 @@ indices -.. image:: FastSLAM1/FastSLAM1_12_0.png -.. image:: FastSLAM1/FastSLAM1_12_1.png +.. image:: FastSLAM1_12_0.png +.. image:: FastSLAM1_12_1.png References diff --git a/docs/modules/slam/FastSLAM2/FastSLAM2.rst b/docs/modules/slam/FastSLAM2/FastSLAM2_main.rst similarity index 100% rename from docs/modules/slam/FastSLAM2/FastSLAM2.rst rename to docs/modules/slam/FastSLAM2/FastSLAM2_main.rst diff --git a/docs/modules/slam/ekf_slam/ekf_slam.rst b/docs/modules/slam/ekf_slam/ekf_slam_main.rst similarity index 99% rename from docs/modules/slam/ekf_slam/ekf_slam.rst rename to docs/modules/slam/ekf_slam/ekf_slam_main.rst index a79c2737ae..5a23b4c887 100644 --- a/docs/modules/slam/ekf_slam/ekf_slam.rst +++ b/docs/modules/slam/ekf_slam/ekf_slam_main.rst @@ -581,7 +581,7 @@ reckoning and control functions are passed along here as well. New LM New LM -.. image:: ekf_slam/ekf_slam_1_0.png +.. image:: ekf_slam_1_0.png References: ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ diff --git a/docs/modules/slam/graph_slam/graphSLAM_SE2_example.rst b/docs/modules/slam/graph_slam/graphSLAM_SE2_example.rst index ef5d05bf22..491320512b 100644 --- a/docs/modules/slam/graph_slam/graphSLAM_SE2_example.rst +++ b/docs/modules/slam/graph_slam/graphSLAM_SE2_example.rst @@ -44,7 +44,7 @@ The Dataset -.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_4_0.png Each edge in this dataset is a constraint that compares the measured @@ -122,7 +122,7 @@ dataset and plot them. -.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_8_0.png .. code:: ipython3 @@ -131,7 +131,7 @@ dataset and plot them. -.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_9_0.png Optimization @@ -165,7 +165,7 @@ different data sources into a single optimization problem. 6 215.8405 -0.000000 -.. figure:: graph_slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif +.. figure:: graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif .. code:: ipython3 @@ -173,7 +173,7 @@ different data sources into a single optimization problem. -.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_13_0.png .. code:: ipython3 @@ -195,7 +195,7 @@ different data sources into a single optimization problem. -.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_15_0.png .. code:: ipython3 @@ -204,5 +204,5 @@ different data sources into a single optimization problem. -.. image:: graph_slam/graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png +.. image:: graphSLAM_SE2_example_files/graphSLAM_SE2_example_16_0.png diff --git a/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif b/docs/modules/slam/graph_slam/graphSLAM_SE2_example_files/Graph_SLAM_optimization.gif new file mode 100644 index 0000000000000000000000000000000000000000..2fabeaafc9cd4ad4b71bbf451637bf2560f1be5e GIT binary patch literal 114966 zcmdp-`#;nF|NnP*ZgxOBI83Nv=FCW<)O(xb80HXiYD6ij5v5XXvyC~_oX?t5A!fU?vKay;lXfsbc#*~tAc-m zKoAH-RaI3(Lu1{#btDqW($aFnh7Hcn&aSSmUS3|2k&%IcfxC9?N=QgZPft%xP3;41 z`w3F{1A=@9A^(LTSCPmCi1s(M#tIIonzzYkNL6_g!@K8sD^U#m#*+Jp7M;;78ApY0rc2g7&V)$Nv`_zjFBSr})E1!J=4D zc>=sVS*<(`U+x4R0)to4=v6#^RabYFL|V19T(!4fb#`8LMGv{4hM4%Fz_ml$^@buz zL$MbB=ZPDJQk;iUorlt0hFn}$natIopw)^A#*4zP`1!wWFis`t|FpBGGDj`LCk#51Hk?8ABNvt2sHVMMbMsRjc*&tF5i8 z9UZHGM-Ai*jTa70Rt-IE7@EH@^s;4W@ygJ*>;LBi0|R4YV^5zxefaR<>d@cj>iGET zg9ocmo~*ul^=ff(@#V|a#l_Wc|7WXz4fOx18T!4P;T60zfl|emZ25K%wR_rFshXz%c>1&g$IkPj~Dv$K#;Y=hECKE@=$22 zc~B}bsoXXSyV2#325=+mbOzpYLJ4P-{Zkgr|h(m zSwR-T5UA+jt4GsavxabVf6r0 zvG37jY&pWa3Z!J-IobGmtOrKv*~s<>gYJ%bsma(pDDTGPktqn@tl*!x8(0C?2#RG< zk6Zv`URKCu<9s8i<-B}1R$U-J1>N7I1b@|Z1(6_IL3&~ptLbMsrZoO~8p_py3yyeN z5Nrjt4;V87am%z$IF1HT#b;7}dV-!BJ4!&!sw6$5s|00<5k!vz%7EsJrb>}|DWEK* zIL$i~Vu0D5RcQclc~E;I!D#znfII|bNvBqcHZFm3xdnn~+8QEtr}-%A9^L$Y@O zoaQ5I!#TXaon3)&tANsUYH-j z#EA{gnbQE`=9V(8_s5i=h;0GXHvUoO&fDwH@3p;Q8bZ?D->J#o-XZ?7P@hYLH$q9tDg+wRS;#fI!X{%hvRNi<1{xQwiL%LPH4^Rotfu+Vw)#CAiF#=3c{HI6yl zCUwHe?pa{+J{Oe!@dW58Iwb@RO&K#|CB$W(EC5IB8z?#O!i-YmakabE|NZqH8l?*z zrv#{wT*@#1+Ah-q>f%)uo8MNsj^WK8-aV~Dfgh`X`u$buVe{wP!;pi2zO#^Q`Hz_+ zpZ@%u&9qrro-aMP@@wJzrImjdyFRV_w{+X4Zy6#Bviz}}k$TGOzc-&&1OMngU4DjM-Uyz|`z`eUW1cNEDQo%J*G0tUF ziIl!QJ1rcUxhF?Af~z9y<^hLI!MG|qaivuPScE!i;JxOtQ%Qooh?oKDTTZ6gtic)+ ziqL{d6xPYyFqxjNHTGCTPv<+h4ZA?@Fh8hsFIVH}vS{NX1>!RmJ%s*sw7a94xDYm@x4sLmz*h*0}=`lfmCyr}FYv?TMvVA&q|H(?icN)VI`VjIpCPz7 zXq<1X#zPzk0BKxY;R;Q|ni zeEu4jnHQvF3X-cXkZRJ*8Rm0idcAg~dE>?~h{1!MCA$jo*SJ(RXy%|Z zpy~;Nu4u$~{BKlX+Z{t(w;!fcz(I$XZ8*(9xWazC^Yjd!)oA3-Z{0WtH;YO-=h9^E znkV-$yQpmPs`iX^QJ{8eO%naSL$&u+j9Rh_A@$R@bl-qf*45D3tE#zc)yHnRl47bo zJy#(3ZdPW%G{0Er2{9x^XOU!=yVl=$t#^Oa&Ho`7<1@Rs_J|qmKrl$-a9X`tvzhN! zUkAgfKUuURrbtn@;WcLWZhg@LiaOAaF2N-34D5dP#=I!=L2*os*^UR5hS7~~G7=6F zeUEO+D{YUY8wwUs%=Bnv;vWb(f|s?iW)8L9jjm%k=hf#+mj&n@uoIU(%}nVwDvq%`)-kr6u*or_t$|YFHQ``3@hsY9<Nh7WXuJO^TKbZg6l$9}QiXS3l3j=Rzf@m?zTNij%grCE`z&^1 z;l?B|swxyg=A(s_VTbOhvO$Z2EwctE!N@e_RpWvsR0JJ&9xFSz#h42(S4;o_z!mF8 z>D_RXezZUiRoh1u%w8-)xC|?5wk*$y9v(M3=6Gn`%kYdu4>{(bbiOl_C3Ff?Xf{e* z%_1zrnaUT$&ZX}jSZ7f%@UyH{b)i6NU|i4K=> z0g2!>*L`*-evu$Nvoeg+%sxgs(D2`OfAzqk7^nL}w1$s_i~u=eI*D8_ZX5#xUl(_1@>^0T<**m~RJ81HzZ)!#ir790v10rE zDyG-`@MkY^e&PAb27JB=vKj>2zVRr)i~IT$V-<=5cez+eclu#qx`)vf5<&8j#AxZh z^XHK=(BbvPryz5vl}nr8-ZDUa8EBKh16;wLRQO5=H*q7nYZm6c1nW=Dl%xbcehqDv z|4rb~6CeccP1drDXhRX+z#Uw-33ksU1{R(4AOzbT%djS<9@0RyYM|ci-t$8Rw#Ea^ zAi}+gNuo4#`xGGKpvQh3$DIeH++CU&SpOvOU>bE%3iwdb|Czw6X1R436}u20FDlF- zHE`xONA1YgR!=X-e1y9Q_N~n8f2>GI^x^e`NrVX$NCZrYVA+GowM17JHbZ~u@>kpz|&7k8A|DYgDN!P`m1T0Nyl(Ukhc+VFDkk_)^8itXC27TLfZp9yf=(;!tN-hl5!%2=oY3E z6~)0Agd{fIKI1)$Z0L5`Ms%&ua^ErlzNsDI#eryGApa6JA30j8){n~Ej_fY?au31$ z?&cG06K_8Pd}OCq95I!WL+?|)TuNf`Y}l8SglL(cy#wYzCh#!UCw4^&_<_oRq?mpo z(r*@~Ws=0loJfBgw`BlYz68^Ko1jm0yTWj|T8=+S39~Uhir@(jreVJvi5uB|n87Mn zdUBx#L9SO%;5mprQr>R%-ku^Dm*UaDVKy!Sx-xex3vj`}o`=RfdYpOt5z+@#YR&~a zEcsK;705b0@p88-O5`pjY}(9i4;y*3%Y}onGKCs`Od7}v#L;=j?;H|Pu;t0UPxVUnd+m6og83u-UQ?Z=eOHa6(t8l(Xj3X9%_8TYJ$FKXW;QhcUOs z(S*{7^{_yu9NPJ72}#Gt-w*dd0#Hr_XqU=P+B&|s96$xGATa#x*G1E z|9)-wP6_9o8JH$xl*@qLSXelGg&`(k63XdLL~on!3kQRmEZ3^7FWmmve zh;sv&C0Fdo}?4bXoK z_z^J)rH5g>Vb1>tRqsbpG2)zSE(ck?O>bbk zB*+@B_(6xu5Icebqsx`B zCO6=4&drNKDlbI4V_Fr~Nj*3voOl(eecy3YE2=pJORDO{U*`^W=62|%J1!r8Gc@L! z*3_hu-{qm$#lDMacb6w(lHIa=D2TJukn^1`2{O6UmcSx;7sYPK#z5s^k;-kYP6#$R z*EDH#3%1iVseB1&J`xj4J+57Os+xUD8jdMvpVB^pe1<#{?hXH_hfN5I>{PBGqnD0F za*^-RFi+5h9+JxbM+cZ3WTmdFiF51bcjHz`7oF!-<|8JcU^rsvT$UGh*9b7OvAu$w z6rfui9TL*_7?|8Maq~@rEhE2t>6jPj{@TwsG%1)Xl<{yhyh4VIVYN!KLfvP}F1>+O zu{w}X9+V~Gf5Feq{Pd5Mj6$$UCmav|9>)x&B_@XTUXee1oNzdDiF1*vU{h~gVT)-q zz~z}3To*9;5B6j#`XUwn%^6<7Me=|9?_?i$y8wT-+sBs(AK4yTtg7T4pR#YS#LZsc zFo@FFBt2XbH#Z5p8GK*WfP3S1Y8eRTCEL>>OM=)Y;!1~H7i6@R-`6Z1;N>?Sugkx0 zvGqhL7a1+f?^A(qbwVx;!1s$%{XL<263F{l8A;fMJMpd^I&J{(VBbcIisrqZu#Xf~v9%r}PZ(@!-qCfs3*M zCg>@14Ef|wLNo?0SjY=R!mHS?%icg8wZMs-I9r)}s$<|i5|8|z?o*#=?VEz7+`RfcR1m)heewK!`hLuPtGwH$q8j3`k9>jGjEtfbM`7UC zF3$UL*_s#cVv>3^WILD`Xuvsd8)^AA%%~ry_senYIw;8B5Cc!vLbSgqi;F#|0kinw zzim39%Ja>g1Fg9BfzlBm^fhWO5xv_ZKGNMm%9BK&U`j`rEZD@{!`y^V_sNuc9t+L2qxOtgkrB51~IsVd`Wf z8#ao&BoWn|&u9Op<@HgDJWQ^|sm9;_mF)KA%=t7C`^XB4l(>*%jj5z6{AQQ%wNEd- z0isx3FC{Dn1SeejOrYI7KY;3Bzw)7=8)fOApP+7(#FbONgU5vOw7M;Nd|NS# zJGg@kFOxm$`w5G?i+%FbozFoVbbVLranV&mG1?PzR%8FxV~^Ni)a1shp!H?#TX&Q2 zn;Zg9H_zV+u9Dvs&x&8FtxPPY*ED$CnZC%53r$R9N%slL=c7RA4h~Ws0qb6m#XQe! z-}ZK=6j?=qU&{QqEDDS8Wc2S&4C5C30HX6xU}zGs{cM8oEC-b2Jxk@o)YiF{vF7L^ zgql4mODZ1_p8?i+8q0V_JXOne=?MRM&x}^GrI%M{kP0fpKBE21K&yg-nY;U7y zJ{4%v3toY5P**0KA)8bTr;`p$Ol0{J|~c zVMh(WJ?OBnk4GAW@%G4PP1_+44vxo_2cW zB7^;C#vz3^6$##AYdfABF=Uvv9Uly<5*FI_E?|d@tI}Q|O`1a2O!XLg){Y>;92sMz zPFIMyI4dh3X(C;MsM_8nzDE+jnlIY$LVwMv1d~4(gcZ~km+YxVuEY%9GfLmjKx#(v zr_K7~`Az8Fuq5%d)Z5h2TbMmh_g}EiqQ5)O)jbBo+g*PYr0O@jwyf1!RsEorpY<<= zC1GN}0%`JE6D7uR+NNWyXrg>XoeiLe)DDYBinTDMF~&x93)e?bCq=`1_E?>-lAyj4 z9vk--E_I?sh123%*A3TRxg~84L7_mkqNLG^ySSI{h0dQ3d~dLC-@3ng`gCqda8a+W zdqvnTL*>gV_O7kykJm%_NM=^=MX!jxgN4416S2d!FPhK-9cLL;WSFiw)A7xCx|^YG zc`oORh~igxvie@r1ra;%)Lt`k)>^0wd+t)W5|U8k%}-o8Fo$npHYRi=Xwl=_#U~;c zkb4b=Erw@->ev@-BWw*>fw6cw@;<)(xI&vUhYX%mJxOX(U?g(DqICe0TAuMio~&yT zBs~^sM=RuqYU|mLs0_ZlKR@4v`A@%De1G4%|5%jn78VS3$6&Nv<3$HI`kmwHy@PKC zu4>L_8Svpq-SS6`)ob=iG8(>0Jq2Az+Z0;vbteN7OOU}jDaj)FJ6A*8kV?Dk<^63{Nn(NB`RXM4Di(p^z6@>s)yjn}Rq?FK$@>Ax0w zq!_qQnxX<7EgVn$EJihg8o6^QH~zEV3#QPX?PuGqkS zp`O~Fp>HlyS=pi#Leem>qc;b#Q9yE`%0yt{Yi~>#C+3Py6odITVf4Y;$uOLRcWip9 z03F>{YCTa$yXdLqVMa?uG-%`Pz}le^bvL|i-_R5gQD?m4^%;Ho;3yZ4*^_{nuI3t8 z(!i+2?%O9zQ)2rcuYW=* z;YYS_BG%ombp3JehQ1%AyiPsBaTZr2v7@BX4qQy(Yb&VmvnkogD&oj~5j9HJqlftK zew~=zqO}#Yu-O5-Yc^zkXl$@ zT=A2$7*doy?@Z8xbw(DBr8b<4(`%oxY`0atm_B7aXhG+xusAXJ3OPU?riduqIdmjf zfxlSj!MmrHu=*cF$G%_OdxVakoO8;pP{Js=2Kbt4p;ei(MCYLp`lDp8Nx_y2YE{RD zvf+Us1?PTvDEe9LYIbA2$-{k{d&)qTY|R5s8)`#yEe?^+Vm2u94b%^{S|Ll8&0Af^ z9NqtOsMke?PdA3hYd$;{Fy#VoBGeWHHI2U%-?HtPIKSuG>B)?Ze`<4nqC4pEr7ssC zwx-Q-mthC}A$Daw<<}gEOH@$R*`t-`A&Z~_2H%^AZAemooUp=gPUG*8HXBIzgCK`< zF=rCRP?z@`+#Yl%c+-C+!StI^wiH@tnD#A~wVLTh*RP!ho)lY)K?Tte8v@j4!6=^# zYh?3Nu3uXR+G?yyCF?bsd?kp!=xNNYHw}dtQosaag*w{d!7Smet&94+qnmTqj@hE8 z%aCU}H8yfx(`i9S)(u;Xby%A4`=JUGiFE``?UX@=Z+x#HUO33%TjCK3BRqQzw+xKj z&C=@76RpQNEiYN;t#$a0yVj`dLRg5wT_mwgZr^wf8>Y+)`KO|vn5B&@wTt*}+dllMQ)4+u#ep=%Bb?-_0BNP+iLpLW1-mhT(2XDx>dds!`r7L#f8#@X&P$6|} z$O+ZFjrQtfQ1*2v?Z1Uc^?i+PC{&L(B-Ko?zQQJa31D*bo-RP_*tH@#@MjAlxXk_+ z-;*3OV0_GOD@T1}og(Bv!j}bILiZKb9E(D|>Q& zh-*P_23P2V$dDyN3NCwONQF;Wd~Ys#tC(9y_mVU*ejyY*-_Py+T@pIAxd6)VU!iPhm;zQuCw?p$P{zZ0{`A;h!qugI>WGQvdf6>Qeg4zZpK(m2EC zo*oi%JfRKb|z-fX6@ee(W=lH(4e;mF(8ijC$E^n3`CCG`)I% zCXdYJ+h8)h9s7dQgn1y|*0?WJQ|v{Gq|aH`!~1Bd`HOEJ)g zSQNS*tt?Zr!2K(mC}qM&rgq8^fklEk`E5a2*sb;*6BLTmtLANm27MIFgU8-Oo4ahSg#2nW{;ulw0m&udU|No3bqn~{KQ&&^Fzjk`DI7N8a`PQJdUnUw*VVPUH40EVS}?7 z!LWROJRlCSUtbJqKyS;UBR1wa=e4c<9ArXlD8t+hKcT91O~4IwZf!vlC;j@oqVLYdPyed0Cj5E+MWRTwuJy!D4VJHi5lful$5P|^$%NO(GWI~wUJ zY*9ZJd+*V%DUd&Eo&P$A{|Grdpg)thRe$*#Y;Krzp)WCGa$2nrJUsL718e1ug~~Dm z_V$IfPPTI3-a9ve68!g0rbaw{R*cCj=lzU6>pXZ19;V&ae_5h-=3~=86$^pUZP#MU z^=;)f%xSMv$u1#W)bAWq({8|z3k#WF_bTCL+cgDR%-X=|Zwd9cn+E}o6Hw8u+w^k}0=R(*Jy(1+dC_rz$W z5Qlp?U47RG5$GoS34=dSF2zGa8|@?P+x z>yl0XpgS}{=B&4*mXk8tFt@aHolXu{To-m^PIc8ZQNac z?VYGS_{Vbg+e&_GnabovhAM>(u{0|y^@g99USqqnZm!I z$y$H@bH{5hsXDb*&AzjyOCPS;E@xP`^IQ{5IQ5r&g1zha{m=4;&5-8*jMIcoEvGN! z&>y`bju}6^+T@~&GgXg)tU*?P5B$5wsV{#hAZ?2cSr9OZ83ilo-OXN%!SG;F*~8ma zr3p{*6gYLS`_O&!I^D$rLqbtA%q&lUd`an^4M0(p(QX|uUl4Q>L=eefXQ#J^Ei~F9 zvgw8>W@tOPmKz}5b6hLXsmNT@N9WpgK~Lr5cO1SA2>RxU)4o(lq)!d-ATCjJu;Dle zV#Z66I{zGR*Cm9l~ww{9b&NK|M{@fz`6-OVi{c8Q+L9Jm3VimR|3{C;D`6 zQG66ormp|h>0OrXS1UXfmP=DBG+yRMJl$?fcz2;n_{l9;Gi;=LLEx*CeNUKGdkZ|J z^^z|^WSfGvjO03AgJJt%XJ+TgiRL82r$e`RRvNnI zY*6tT8=G=A5-04apY$%df7<+sja>*iIQjV2`|x|Zmi?Ob|LxfxQM!05`%T_~8XPhh z#CKJ_(YQ+hl_lPpRlV1}=&o9VY06P6%P3jetue`v`}4ahw!Z#iy;uignF?Juz|L22 zO)&zRx85gnC;6yR6)ZeS8IS*z*?R&_OPv-^aAr&V==>UM4Z&uj zFtGv9B|==XGTiPDSRkN|gpiLFkS|iM1bf_jK|qz%lDQMCS!lpg6e%skER^s2eCH3I z0(X>u_KAQR@icf?pzq2keagugUa;6T_|>h`|5ZnW5f@yR1!uq8eDs&`z8-{35RQPT z6HI#I!7F=iSw)=H?c21@L#sOk*S82A2z)Dm;s9Yr@oP@3ojiyapItu?ccnea{MJRA zIjA1JouaDM@nGOng=0=Lk9D%YXv6<-Exi>(7@Vpe`jH>N|haZWm5u zf&SMGYx*TvSD#cAkNgCjApGK6{A>C?t7n>5wqX}PKaBd9)afvPa?k(;>k~c!VNO61 z#(omj_JZah7*f+csT{+DSOjYtGKr>hFC-)vYcIlOtWg0HXUfrgoUv<&WWL=z`f_X> z&X`h2;Xz*CKNo!Ez>R-M@N8zWpCUFn?!DIihORJP{$t>QZ=>gq{9I*5@x#`zuH+9Z zJ(JuiSxnz)tAxY*=*YqYd5oBx?d4i};T_Q%zkVDqP1|!g`tqiQNaJJ0j(h7iiSaf& zd#O(8T_fbi&WN~okSj=n9bE)1 z7W-7&W1n^W)GpF^`v*mhSpS3E2so0?zejEE#2z7L%a6bn@bt87pNWEL#h39ct^#hSU*FLwf2?ip9$8rzi)en1#^|Gg94 zt^cdutL*hZqZXx!Gl%fN#|1ZSUq^VLw~yoJZ$no8zmf>PP2b#1&P&g;t}WJFy*L%d z)Bh1%L(G4s<)ciV*6yP6gd|-KX_Na}@SBN)`X@Aa9;U+iPtP@B)>&E}aA%rUFs8~V zU(a6vXb7ikg*>KYVw4=49(|S1%Hmm)ZLIE8F}<@Uyn;t3?7Z*U8-v|Ux)yo3{h|$- z2KXp$^jo%N+~$4ENcR2FcWtpaQIT&!*snbt&bJllcdu3ah^aoq-i9 zAh)GXagMV=sP}Q_nG1J-R!le7pNRE94(c@#TUR6I)K22X0E;Tv#G*yhFVppKpRAzu*k_dVFF-<6q?GFqGh!3WFp z4@uZ?i?AeA@P=v4KDoHQS5cPxuWs*B5bj%2ASVYsqfsX9J5bP`6Sz$7Z;(J%z{tW| z5$p%lUpjvTG}RaxM#nlyY%AzTk51qSlzwDLH(g^pm_D`mZCH>DD~UQ3Kdm5M-ZuOx zbt40!Gb9y+FW^vK2CQtRshJ6}Q4^OpviGL6_q5gSMoVyp$*2JNnP`qW`ttd+*XO%_ zg3qf(b6&d5&Tjj+|I>=+*O%cx77pj@nHi|*UCSUlBst&xWxcmH_Vj(Wu#}wDkGDu> z<7%iP-!v18&IP1SFQ~Un^%cgxJL}l}jmXon(#+OzlCSB9BZe3FG zr-PcFt_DiR-PEW7K>Y6-Y>D)&P1YPPMy}3uF17Wy%0q_!Pyxji~07m=aH0J~B%xChex%mo3-C+2w0^s|DLD4bNRE z!aN9{u0yVj#ElRJsJD*T?Q!?49V7>tTWVvX5n)V-0Vz7$mkajyW;YNzxXf~Zfn*U} z_1(c}Q%nQOHqz8`b99yi6D(nP_QL}xg>%c^4e&1%!eMQVm&srFezOt9dN1dW8y=)v zBBdsh=3tzE!^P;F;M{T2Xz~owV`nFd}%pqhbaZpR+5t>)T5tpPID!rB=Kb`m3 z!BXeY$9RyIj{C^0$7y6&JFw;+Loc?Ica7x)y39UR$CRBwkC_Duu71h|#&`VN2 zhEl3EAC!M+z@Pt|bKrS7*>?}ZJX7sfMlb}%l(uNf6Vx+$mI_Sf0lZx82xmjWBcElY zZFKkDm{n@qXgHCVcaIEWzrG7KYV>IdLRtJ^Bkf}QIn6~}bk>P{ z-SO{+h3r9u^_R%lGa-*t%rAkh^1Dz>-lh7>xxlUhjdIgy6J~@j3lzv}HQ4ZKCPq#Avji1l-!7zEaa{SZ2=Ts3&xl z4U$2&BRL)1y%$l?FD+LC$SDSAqgmhcngx29_kaymS*Y#qUy>)Q_#}-odi(OpeUv}!^nV&&CTQ6HZ!9Q*F0&EmqZSz#75;y`1_(^3;m3@X0r>A zAyBDfa3W>1IP2k@F&17Vf0__TmV5f5?u2XHISw{gVsJt^RF4&PhThdc)p zawp>?G~gO!yN-7C+d+IcpWLd+Ues(gfIaIE$0vbQgVu&x@w6qh<);u6jVjS1$O8oS z*rA4}j6_C6`;XIA^LW~hYt_Fqq5GLbI@&MqxTN7BoLbxnuD!#b+Ws^-Jz6U`SZW1+ zq&G+&1|)w%MZJ6zfd+mUq|yL7?Z_jL6#7|o3&g0KoO?Q5ojg-fn74hS7!Ibd2}o2l zIrcZl(>tEJiR0<#`sw7f{)JHQB1hiJ7m8NYc%_A$Zo#3G1#ms5yAIKE-JACp^4DFD zUmY0-zL%03CU~tX= z%ynYTZ|XHiHi0x)EK}qY>08L)Q%yj5gio+Q!^GYVKLbHPM3+nva^xU04csEKE91^fAvR8debpDgJAJKZJ?WduodH1nzN?pn>(eq?O@K2N$jo2xDh2NFH>U znC|{fTMzWBVfw}2!8ih6<8+QGanL(A&H|xNF$Q~+g;?9#Ef>|~k&p)wC57o=%W1{< zQn8h#KA~Gd`l!oG@84thvM|O>1+&45oZ!@4O-&Vrw|NPw0XAZ_TOcguA zf&dzW1qu>f=!TeEY{jWn$;TSq)`7qmPd@VVa=&o*e&s9EO4x{T8c9_EHdu>|At8Ex z!E`i&vpMI7?+(13J#R8JKv2?2`uLY16%@uJV`HfK=M|rt5&%U6Ux|chH|cSDLAX%$ zf~%12d9)onUU>@meYLEXb;5EfgAnv`tY)xdohS;!D|t1{&GlG=XaQ!yO8AF`ybB?Y z><{e_Jz{@2bKriI0G2p7w#-;tz%Po(8b0x^Eo2==h?EzC{Igxs;U_9qN;knhdos|fQx~}epAdi#DyEW zmV`zHJ`CFPI_6l!CoKwhj8H z@#8TJ+;Ny?L}U)}PL)-n`9YWkMpZv$;aG3Ad?>e419F<6e@-bnI3O~X^WQfQ9F}U(_D${y>c?@wVKru8>#Z=xz>q=(5m6zh?~86)t~-51c7XK+g5q7FC-0l6)7+t~hO@Xlk6 z%9Y#e#<`U#^+nM_@W0+KHR95QDHcyBwatamIwrc`EMd+AFA*`ph-%B~HLksUuc}Xs z$9KA=;8UUQEN=gJ)=)J>Pg-^cZ6i}jX)>k!g~h+3GhD46xa%g;n26`WDT=<0zAE!C zar(9#!P+P;kCx|6HnL3bP%y=mf1*pxmN#^l4ALJf3ig|MP_dq$lD~aR4tO|cCFd*l z2d<%@4x7PlbmS#ZKkQ}?7NrF#eZ-1X`N_Nw+795y`mZ=F?@jIW zV)OJhcxRSX+rK3^;`5fN6%PrDbMjW@QG5iZjkbR%mKY8Jd<>7EU=d*=)0#mCe|;whfye z_dPuK^Stlp_tVR@;1d?bQQ|-psncU|E_{E0Yc)K?B4U| z@Ph+Nd+s5lH+gLXR!k}nQhmjVeU|8)jzbHr;cb-M?2eh)@U-Q_JIntoEG403FKFx4-jFH!W~)ybmnrl+*F% zG`9toc799%Nj)HcFvNVAgfd1@%L(_PnD)?hU4u3~9uzvvRQ%m;1mZ0mPr`4;NO^iS z5Zv@wCSgF2;}N_2hr@07078K2KJDBpyzmm%7%@?kPxKX*jq8jiiJ;w^E^MRkuI6Y~ z7W1COr0I0$&jdhTLu!w1Mftk7nLXvdH|~D<6r3&{SzH`_v~ueFw+D3EYxJW5=9qR* z;xhmW-?p%b2_Nu%$5T2FWU)_flgminG)*4tl&#S7^k==@?M#faV~S5r#?Ey!}^^4waXr=YQrHmoBRpAn_Wv* z*Txn=O|Mln953PIL^3*OF}YeNyGtDQo3#nC$-x|t@?9Zkw+&?B% zB^W&5pyjTL4j*4e_{dzDdu!3D3+x~Q1!xEiVGR5HQ_|pF5-P2-*c+7n_Tg%a-8Y|< z1;k*izyrY|ROF2Kc$~(&S}~jfWYTSX_fF}?loXlo3cf*FjB* zYD#%#r;Dl*__;=n@J*lr%?$dAp+HMJY z+nxurQ=$QdB^^v~c@624uV~97N5i5(S$HW=uq2qu5oIxFnlByWa(AkYkuEisDI1ID zDtyhJM3bIh6Ac=YSkgkt8q^_mY_P^x086@sXsBPEBK`s|z_( z45zT*uL7fB&Tpc)O-vma$?S-&%QT&6=a-Oc5uc5$DO^`<#go9CMk*Eg7r4n@(Phkx zEPg#!9<$rq5452=n3CSW4&SsDkaENXgXlwzTf|j~+%Pa@`9HkPP;G3Zw_VA&7Sn`( zcJlCoaksOIGKF^rV9g--z0urZh?26bvel{V^PJOnQtr-#kS|90Q0j|A zOgnuNjI8=EZ%5bMEO#t^_qb`W_Y=tWdp83o(u^nqA|{t7dVXM#rnL#<{|RZ*068MS zkbJrMr=z-Jo*Ab_kLRo$HmS;eSHN4G2|L2|=Q;oL4$pr-0X;p~dps7hk5dh=kNzq& zS%mI!9g|HZKvgXk>f+b$g^sM8ExX+9ii)8L_DlD5*hTL$JVseTq;b~>K0=m<-Uc3q zlb~wPW^tzDFWjp_im5%`q;7&+l2$bO&2qzY?GFV^5$<0?vaLgH=g_B8X9ad2hgCTD zgEJn=Gp#Z1`+*iH{qrc!ugo2cG!t+TUr!+M;vz1eur+X?*uz4$5rLRo^+yM*#x{Y4 zN`}-aP<+;z9b^UtP@f-0@5!+g;`og7W|MB9eKg`=qMH_13;OfZuyTi_PAlHu&YMam zW9md`8|fNlhcV1*tyP<3`&Gk|-+~)ehZ3_Ml2^x*4&nH)XCdnSr6WsrQ<@<43+goE|~D1Qsz`!(Lal)j^pJQ z0K|l4;`qG~(pYIegQlJ}&sS)CN5DB6nFOHm(5fcxTH%k&WPxH|++$mOY| zbY-iFZevbg9CGW3Q>~cyFwV(km}WslVPYtFKng4LkwRDcWMY4RxQWjk#OwWpWzM_0wN7W6_FhZ7daPA6{ zi&_;`d|kJ5I8*y*HEVPoMrWk>T40gUChDTWazXoGsQQ8|WmsQ1hzylycC87qT?ZB`cV4ZaWNN0F@R6cyGfzVV$W-{~ zEzU&V!YvJu(jhCqzB{PuPUWMgCvwNX*=p6=1C6byjk`lfZ`dA#HR>ec+%CInH7KdA z%%=htWo*Og!|JZ|&1)(~Xm!aIv~|XlN)D)K!(Fkcw7U*Cldd_{gLT~E_ey!XiJWqb zjtk0Fl9BSFfIw!?qmbyAYq9d1$Ped3*!*oNib4}hh!LuH5P70uI^3DFEBxtul?6+! zQe?Gjh2C9>o&9?cYsb=U2w1jh(bsT|z6o^l;D@Y_b3o_%N9!zQrA{jT?dx?-q~F^8 zc8^9+IUgJ`rw+dU5uaqDwUiKcF6N4|2SmBU<=*)Zmp<*uZjAp{<34CiQ+yiSdD$X5m6QylfR}m5S%jtbL#Amh07c_{zItC!y_eTeV>=3Qg~^ZL{)2UDp&GSJ=LZ zhol(O&lz))7Yv~8TH=9f@noVPnK0$1?LC^e!J&10$0?V52GTJim2u(tMr(hk$ zb|ny`(~ObrEZ&AsltJ)RzG)3d-5lnK9LA6Fh@^Uumtk(^bvwGv3|4HiU2Nu9L`XuR zKV+yZWaxb{rc!vY2?mTV!!jdZ4cC)w(CX+{=IxVS9WCZIsz#V0qu-}7F|HJz(ASx( zM&++8Rnd4ySuGG4+s$cMvouUwG@y4^eagjsCtPf9Hy^y|NM+s}^aTbt=^akI*}kB6 zROZ2wz0|0~>G|C3734C_k1~runLxjMLcyK23K*ns=dY>Z5Mqe<5LZwL5S{9*+u;YR zIH7)t_(M@3mET$>(pHp0x;_qTRJ&gAYfQ6wXP$7&gCg5YxqDNq(+pZ@!W=+@gVREk zmTi%lEqpUEkC@wO&J>u6@0wp60;`AcSs9?d=TyB={jt#3ekSC7^BO_4mrbM9x=4I_ zlWMLB`O7dKVpGGe(@gd&vfHD3&=qJ6Sm+4Qvy7aja#Zd!cuc-cnkdHAWwD8C+$4y@ zyfU}>fHQX`w{Y#pzTyj+;H@OHW|8p;f-%KajZ}uhH$&Fb7TFK90!|hEsM2U7{bi?!Swezv!TEAOdK0GJ6k0= zuk5C=p(?3F6&k~g(;(ou<@NIIq42@3xCbnWP19-8dq=EGp}TN$&Qu*Dj^e&I^AX;;bm$w>Uu&q zm(jC!dr4R8*GVMMp+Ri00KBNiIJ97HXXtQ+)>l7{cZ@^^&8k)rd+ZaE$~bDU$*u8G z8;{-7Xr2zYSo9;7bd}uaHSfFmvty3b>2NBLhm2HD;i@BD+*db)D0lL#4_QNzxtcNy zT;*cdcN(RCFz2|$)=Ge5)3{g{-=INoYNTU(9l3&|7SA{si1DL%XbR4-Xzv&*Yb}V~ zR_Xhl+fV6!BCW@{s&@!bwUSM4YxcPt-zAT#$^yaZV)McY?NPVbL79G$324jjm~XKIO7OtqbB~oqk2j+E%U$S?I%%OZaW+^69~B!cOV&i5%D=nceU# zPP99cRlg9VIdh396-EPT=t( zG%JbPe@k}$9iedwY=@|{G{hUrU_V>6de3h#cct~unTijX#q)hG%W}#P_RSO{<^@xm zN8R=3H+Q*ztXgwG_OCu1WwU*d*#Tre+WlI)@E8V{=ZEI3D|99zN@V@whu=)gHtVy_F1 zy?3zJ>Par%0-BG(y`@ODuDj$*;Kl)3B<@1kTpse434lnXGga zw!)l%=7zu`AjyZ=q9D@FWghl9kewvHzpE}k+a081_L0)h&ryy(SFIiw;$*#+Co37|?^ zcC{0gT`(7KJCf=Su09{u&(Y*&Z>|h|X0^p8+Yw!vd}b&mWc(sQf6$RK!!xlucXRDyjHtSCROD?-U*BcX}h@4sXEn0*pXO;cjSzbul7%b6CJxfys za=Rns@bAFGy^Yvb1Cr8L&UQ1Jk{+<#VHVp^&3i_%s;;L z)=l$9g5j?{3dB6^lRZfNE`tN#@aG#2Ke*{=#y3frbc`UV&2x&&LN6bX_Wl$0dw!b! z0l?e(!pKRth=iD^*=>7|8M(jPbSmjK?+JWj9Z+H|yBa1P3>z96JY`G+y3c5)Taw>P zTr|4PWKk%U@GGYRpUI50mb}egJ{}5t=!ajnBHvqLvh#P>5;gNoY8*Ay;?4bL)Wg*o zrw4act@*09LbPW_7yLcC@Xe14g(7HpOqa!LyEh7WEcKxDfZS8)22&xT6a#| zy}ega>AaG^NqKr3>p@gSk$gx2k~9{D5cqPjggOZg`n<=?pymW^04|+4GxcUX81sV1ZX={xB!*WTxDNU2+3v zRaRcMR-Aov_^q52c1w6?ox*(Z($HIj;XA+m$WV9p^tpwtueP2j+P->^bp7L~m9Eg= zZxkPl>Tdn5XBhImB&hPvGj%iuhS*>{A z^P=)}`iK4#ANDCej9iJhl>YH%MA~)5#|O^w_tHN-R~#Nve0m)*5BG*>y!pJ~{N-Ev z@&#E^e1UG1qdn!|Rk_MbIr`|Af1DR||9sZIy0GHUg5jzK#yjZ2wFmvUD1tg3@R2z#~o5CjB+5N*3V_~V;0rs^pAXUn#`u6wj-5UqK9H1s-} zb{)4}@$1s6pK)6wxib*OwVzi{LIziD>$nU-NYDu`Xz8|}1&49LGZ4gf98!XZ5b^vl zKvmC4M4fR_$5G*ovz*}c3KGN6*1V0viU+L&H^L8mEA*ZhHH zPTNXbryrQ88`VH?-wn{VnN_3`U1M=j71~;-dDP~J2nluZpr3Tsm)&V~3$g%*FB-GV zT|0o|xxQ6|k`SrVZ9Sh|56?X7L*&~fx{C)+^;v>i9C6TRBW1u~?ewn6vrtdb_zMgR z_4OIs0;j&Tg5A*y?IFEH$`0(aR7r;#Ie$XC@E^4O{lbhXPl$Nr6Lii>KEKOb0Z&uW zcFzB4{4P7nbU%WxaAy@Hpp&m}1; zsGyTP7pkfTkwNmu1k2xuCO<4@*mOlfH%w$AA#J)4hJ~;5yWk4A4hupGiul2;+1W9^ z{aC^ka7S&@Eyj-HDKBz%oH+D(e8Eot*ye@dC}JSGsXVte{jzi z|ATvOfQ9vGZ2nK^d0BbRQ%b49q?}TVZN*xDQn33>qbKI|(*k$qgPfE(C?f=6)r=b5Y>sep_kCD+IbMybPo;}pAd1L;y zo`Vgpg&X}h^t}H6f}S^TUY4c*L`D4zJ@4E1=kVcwq3101tbFYMD9;tv|0>U|Hd)g3 zxy!h75372_C+o)MtOwy)LtCq#MQ2UKR8Q^u*LQxkGwW0Gzr^#mw5*x5e~IV3fNSO9 z|KiRKyZ-f^mvQHw|HhqbYHF5o=Z1!cwzjr&=guwT&Wfz8uld#g={vs@{_8sng@5w% z|CE;g>pM3z{6Br?`^Wwzo}Zoimv~;j{*!qA-v3|3^Rn-}tUNCh&qG8163@%p^Rs9F zMLf^V{r`e^URIp{&(AXE9P|Gf=FC{eoFT0b+SoB&n0bi*!?T=9JWJ~?zb;era+Ytb z2-D1khrKu6TAn$w@}UYNTcqcCI+6P8@rP|txw1cQsoYydGHpmqEp?@ae! zYe^%~o_m8SRKN6nzD0(4$H4dRG++NXhlYUu=k1|2RK)dK)qJ5ycG& z=nLYm%(D}cwys-lJFdWptCilMyPI4D8jCcg3?0cGN(DwpOYA@fB48>w^E^X=dIOzz z-Y-{dx(09ikrp{of`E)oxSBUl=bCk-LbU8^PV^ZB$YLRcYpq1l(nL_=h38DM(p`=F zO*D~Hm4T<4zP&+x7sU*9N=4T~br7&7ob33aXG=eK785@Qg%PB*#N%12t(6fIHb|)Q zbNoC7rpsfG)tjld(JrWC7L?gpw|GY+Iv+w#}`(xVs$|;X_U#yi@nrb@V69dVi~b;{c(V zYj-A%DYi|Xxh8||+q1)+dvZ`?cCQ$ z*5i^E8|`XHSx=H-RGhQq*XJ(6>~ zvz^fNuo))kp(!2!15-5Se%#`Y(Wdx%tvHNFVc_0egu@8Y&jn?fw3iU^aTeb>FE+nb zl&`rkjCU~1_G{o`wU)ILf3P|U{(nUg&g38~RjxLCgG$iVN6@l*4 z#YwgT)NcyZP=5wdx_HXiS{J%ZAD32_(R7K$Io4JsgzY!zW*PIj&H*JQiIeX7=94)= z?JzBzmCS;|qPiNIphQ7JbaC5dx@{aH*YP8?^z6rI>XA4m z-|615=Zi50`H6rHD*!QJOR~isWKyk4HBUguMkjc;EIGqCx`Ms~?mVN+%pFiYig=4Y z9f}q>veXr6BWo@tGDz*S#7?>ZJq$r^ds6}nO&zpxSnwt2B@5(%6HZgw)RKsSS8&z3Utjcpv6Cz!-s1ZCdF9_P2|)t#oq)7J?G0y}-tZ#@}>5u|t*r@dtMRZWK7(wFieV6DKmr zKro?<{f=aT$?{H_X}PG?qjThdO0elBPE!Re)I32{U@~MqHlFv$e#j4KNJL1@&j;KnvC%zN45Gm?gBvSF)9iy+Q;3 z7UZ2aBg%r=h8xw_EodE-2x6?)qo1$j%aj=K9YxYi*!pOkH+io+K0MQ#In#9WpE5rs z(FuO+1YyOk+orQRe4nW$!z%Vy1)5?lW|!f>mMW3?p~DYNi|*h`?T50@;RDz@GV^T_ zhAv3-K!EOoMtZv}aLrewReLhX#ElsTKY^R9nZtQco$>Hn7z5=qH-3Pou$4_w&~G~B zUdbcn%MQ4Av#uKdlX*axS}|L#yiwaBQzu{S_a^JZDb?7T3s$v}f#;Gy`V%#(x_y{fQ8n?rm~SE{x4?!0b%uqD9Wc86b3m9UqF)3@;TgALQQSWg108HAB9c|O;e7FnVD_n2A9rMrVj z(#!J&W8Is=i|2@u=)N+DK6hoJ%86Nx0N$ErH)2ltO6ZfCt#RXq0XgMe2Z?RH4Y;JZ zfQ=R_ENr}dA$PXq#4DxIgbZXdwXrk6W!U`DB!(*zZNTENjoz`Sw!Ua|jt3yFA*d_+E=)|uhO z*{Z=m;6;d0sspe02)z6SwtJC=a%Q@%%8pTi@rZv^Hxls{_#BL_m^{)S6V^GI6yhZW zBcnOIJ?b72kOCY+h?)tz{ygAy z$rBY$Qz(}5=I?-KWlR8v#q+q6WnG+=n3`=i1MZ*#_Up1DQTz}SFslkvE(Yk3LtjJo z)5|jvor%qFQHMuE8%KRlQv-O9w8{|JA~|!F9O^KQh}Kr|M_>ff@B(VSQYUisQRqu! ztjYnv7saP@z_!UuwO&*!LWDkz>XZW1OyH?KYLyAp@Pby~JZ29Y>L3l;B2?Cu?KCz7 zpOMiAWA}&2a;;pJ*Arm>X?Pn?bkt)P0=MM(-#N%rO;ulEA5oa|roTj@DKOi+2( zbkDTV0l(wrJ!=Mi~v30la-ryIu6kp>P-gK zIuEElI0~Rs%&N2EIhB646_zvLS@&Z24CpnFu9FmpKztH@pw2={f=A&?shCdb0VYJu zpn-cw0nO^@Ci-sGI|bh2xCg-~v<^}`2Jn%UyWS}^xPw@iSb^Zj=HL%wAEQTN>0SrX ztsE{)tm3e2R$-LK< zIFxG339FP)v>2{$SadwOn6i+$uMa4h%r-)+HZ}sq@||0!fSWl-%^##9(WQqgfssc^ zbV%A+9{hri*2NZd41=L9Mpa8-PEx@Z0O2WBt`3bzO@w>#;8o+8v&${FZ-EL)mG0gn zUUE2X6kvivIG6zj$ zZBj2*Dl1cRm_c$NxjYIedxBm!1$>(d-Pr^;I+)QPl)=eNyY&#@wYXPyO$maA#Xwh78FS0tc8*!WmY)({3=tELbElzy!x;>{HatgZ_T=V#_ z{S@ma9i{mwOnnE+x*EC06xEqnzNS@djDv%_PUsr8!6G~6cg7o`8^yUfFBX|W6DTpY z4!IY(N3H-^;`$9})lzCDhuKP4$oAzS_hz?;p?Hmr*^uoh=iCE#n&8hz19!Ei(GDGU zuFC4RV8&zb)~O?%IjBwosF~7bgAUMN(X6w*?SffQGNkM@PidKY&HIVk zV-Jlbux^(jqr|aae`2XwiAP^=Ae0IST&29Y^NH6=eFCVa0>Mao0v&|e(^WlsW}nx}P^0P@FD%M`Mc z+I2;A8VKy#e|!76E>y&!W+3QsP;ny1OMZlr80g0XEHf*jcK}}xU~x6*0$R_x`-qqC zz3`GAof#!RHk^TCrn^JyQ0F%mBO_SneZJQl_?Lu9k&AEpErQbGnt(2juA4 zNjO7((Mxt}nuJuX1o*PkCjM7-tc#0SC&|-7!3S<01X&Boww{I`m=hjr(<<9?K>anG zdkAf$a-n51Gx#*{9PBjAFIQTApq><5(cV&smwZ`~7M$27OwJdb72nh1BLgK}=FcYK)``Vsed#2XHrlb4n2Bu- zDwV0w0y(lZ5fsRjL!^M`Bm+wYu4}=A#L9-b967T^pD;n7u`b^>`Gu`D~* z3C|k*@VLF``_T-lM`O^Wh?6M9^%wxZ6}le+CQPbqU7jVf;Cf5ovD0)d3Fx?lY~g?< za(EbRG~JTxGYK!JPI)O7kZZgL&Wwyj(VJR0(ZQp@UVJO(Vs4l8z{}BnDi2fXtjE|p zyKwL)pZmLJ~xZ<~hi*C;NtM*@n2V9l)zHxLLf1`td9(!GGR;fGGp~WN?@PSjqt_Su@DB-ZWHDA|2|k z94$^vWAdit9~e#qM6u+Vuk0Cfa(Ov`7qh@h>6dHNtmg zJOC7}^7JD&-)4_RquJmabJdRd*vRRNE@{C^^fO>R6!l!6}Cq9vdKKySG29;LSwH-z(nyQBE< z!n|}jIHH2~mRdK_-w&j;SF61SG-IUZ#tQ?lfplDH`9IseB*qC(bc6l#4!l6%tU6Jg6fT%{}rt@(MgEVeZQd_*U9t zoyJ>cq8vPlJxc>=X_8;>P&-wtI;LC9jlr#t0H?~hN^t=v_tO)r&f{>;Bn~k2?UR|m z`yL8(Um}>*j_ja)L8BW#uq#G~J+9%PX4D%@3DD;7m-)!UVj--o4CW{Q@-^Xa%nY(6 z5$sO*0KW=E-2P(z`O(@hi^xrww#0i0dOyP;w^a=;LV%cB3VY7<(HgiDtX95ETw$fmvS#?o+1V5BzYK2<&?=o zJEh3T)o;A1OLYyfFY{iykheAm=LU-2l<}4~s%4LkPJ>sz=+pn=7YzVk`k4|q;^mK( zd%+*)qsF!nAZdmxprc~@F)silUN06DHrz6Ihk&b1u8 z)lL#!M2LK;Qw;)4q)>zhezuR)&x0n=qH#$$7T4K?dH1f6F%%_}qWah5W z{2t%?DJFOp$Zrg?Hdvp&HV2#$GG)!&KIBZr==`SpE{157MAfbL06vX8_V`_$M! z9$ZfIbGEasT^p8>(%#?v8|K_f%1QaDI%BhU@U^!Nvnue;oB8rUt7?+k>hm1#m7h~d zbZc*!+2_tcQi-MEP?e~`x}2=rjL9G*dACrtxX=v-+@ZO~A0<;n<1SJaqzti7DdF0S zoq?u!qbd9GYi07@T-Y-^$3_jKR?3jbiZw7?vYNb}*lE>EY0WV%BfvH+`i*@)^SNe{ zn`d=-YV~q0s-?lq%`J+7aB{Se+X>Ve zY1#UyG9wraoJrv{>~5fP7$S#`an#)4kBI`yktY5vbfa#_B&$3z5JwL7cg!S}Zh76@ zRC4H9bFs!my-Z|Dcs_<>klh4%-u6ginB_Z36cA%7SIS@AWIMt9flrPFe>dH&f4cK* zpf~H&<>4aLi-RJ7BCBDso(;=-qss$VopKSZ5EMk`e6sKnsd~RDkGV%GEQoPGZ)b__ z_h5xHwh3(mTS|m}EZL8Sgok=KoTydZ*<4?E(PnZ8xq==Z|7BPG&W0z)pX4ml zmAyu&8y72$0xzw7pOq3=XG@|9|1kL2@~mZAgK-~B9$Oi>r(|U+cm6+4Qcl zm;cnqnj-{BoYP7$%-858llIC#El&)HixUSu+jma@~M{Iw`3l$~;3VoLx1H%H0=l!+p z85bl&qI;&E-b=Z=dU+h*C6pvy-a->pdJp+0zaMecYnJ7%%y|vxO}0MkAFOmUdSWJ4 zoXVYRa5eE698Tiw$g%z5j-mNSt!TM#X(F23slVJR^Pa6UG2OX2J-SXcSSld0tdLx) z>+h1#Vyeg(|9OQVROdjsAql{xei#cdTR8r#od^c>4q5KDWxgZ{Ab`&BwTjqMvs=yR zd27ZvV3t=h&f#zQNgE+yuwIJ`W|z{q^f;VqNJBkF`L3&AcF}hcg06+kLC``}=IY)e zuw{yFeB(elj!A=qp@N@Qrg@%MW)a1c>Lw_Y2@{M=tBXQ2O?g$tLdcohzT_BZ(IyTvYQ;nN{kO9-9Y zttG?_q*kNL^{R|{b?iCW_$(@Lorojz)VKpF)EZpQKj1}i_qRP7Y*nej!kKejC7Wvp z5S|ooc=F>2w~-1=u{{b~CUF|9l^&zLcGWRkST!n~w%Ev8{Vo0av&sY+&xa$hXe9`V zGDBpz+;?1&2>j@oxYP$dn>zk9wD5V>)t*QW-sc)xvFs-q*DOaJIn_PT9u;m-suz+T zuATmw=oNNtvnUpEPiW;%jCi)8>;z?jL`q#WlUN3gSkWRAH6oW^Bm#6aZ>7r(k!^a_ z0_{t7=*^__MyJBRv>)~VPiFk1Z9h3 z-?UOwVQS&=Vk7#X(OL-&%%|~@V-5`pV_R*-+{5#PNYHOy@Lq60LYA3=tF+WMmr3Ez zzdkgAm7Ecm-;CYsFhCCJll{YdhzL?t=xvCB52}QFKi+y<^q|O^;)>J5(hx45yw3>2 z4OhNH;0>G?Wz3W7pRp)k-X!Cav;!tSZeQ)9dgp|@vBlnZPq;|XM}jP`<(ZP>T?Se> zn%m6onB=r2TPing!d&6$=AJMH>dK{;ZYDtkZin^bL^5Ea{f)y=bzP6$huZ-Jb3e8X zI}AcRykxL zicA;0G1w~&CH#I;;s8@}+;}~1-)0+g{Q5YF}XX&*j&Zi<)rrReX!Lm=~SnXicr%D+!*@{#*hfTB?f0pg-VZI zG9k{F=x}dP>B$Pk6)Fw>IT!9jlNm{EK$){!A7IIYEQ+C4Jc1SW@-sS|EI;>iZ@wnU zag-`pi*O5KwB0xAwn7=`^qtkewAye?pV7ME&pB0})DvZdmiyR2sE4*C4>bMWi`*a zd7v_N<5jt!co*``3?4mLc3x`#oGXPaT)ete+C=vdN+gIe1dD?zS%dvcd zUd7|W+oIFw*q#+j>(wNb;yB>ga>x%-a%>0@p(g3SuKwX?{%R3?MxOE6)pL}6`PrD; z&0P-L_aVMClXrnyBx&KNr=|xTl}xFEb<(O8mxcP#F#Ej-$0R)?w=R!60`FSeLi_&v zVH?b!X^>xOI^8*b=(1NbX&rg0<^{&eN9tAUbcxJXU3luS<;VJsxebu7LZ%#c5o(f~ z4+btTt5b%Bv=Tv?+wkVq$EbEiOP%+l9Ae#V6ReR?@9}R>FDCr1R!`+$nXM&LVKI+A z0me8JaQFwc(kc<#B)QrE;GvxWWS2)1rO&8axIa86P%NCZS9{YrXe<{nCEW@)MkZrk zurIneIc}nfV+tZXS1g!ExM*Uf;tD5z$mQI=@Eo=XXoo7bgrCi-xl)*{=ECByoCYr0 zZY;^qdwz`ka$nw#dl#8BcgilOc7%jTgKa!UO1)9Edb!A1Yv99fyU}n7XamYtFdwL@ z?aDac;Nx4->k?eM{xJl5uQ}g}=3Bo2r%prg8i*FPzy{lebRTq{K5mX>odY1f0U z7p#ZWOU}WP+BU?VEB%y4G@EZ}lR`~WbGgS>`t^E%RT)cbn2+QFhREQX1@os`|9aE1 z(W(IW2Ej?KT!UH>qj!A<4bG4tE*#5yVx#uxsSEU8Vcu7V*QZY84iK;Y9MrZ~wRb9` zvQWnNV6V(^b~*y5-XZ7LW6>7p&)F+k+27aOz1m>1Bs5a#TysWg4fNa?&yd$<peXS+h8Y;rlwkIQ=)p&r&GM@B19Rh^lNrN+&R&4YU5owyX zy^NK=1D!gHeuKeHVDyAyFS4-ncv-#^j_iXhWv zIp>b#Z~vOb1ZBm+=)@acVaj}fDHd=S(n zSIc+&cX8X?s%0~cu%35{pp7;H@3~wOLMccNdn^JV5g>)0K}`;RxkNKVZoO(5N}Y5W zPBb@`2=ZWlWPu>BKZAe{zNj^`uUp(ZHaaqvm(nj@%^GCNAM;0~1CtWcvGA6Uh>$Vu z$FZTtrPn+_C5C;srZ3{<;whxgt7!M4m2#1Z20_0HmKh7vPJcc-Y=(-+S?zocad2C~ zH}w$KCh1U3Su||tall>QKa*eXu_PR)o!czM)omXB)Dz`d_-uj}sT`Qen1;cveQk4u z)&JO|xmv{T$4(o{ysM^sj=jiDjW(99*WIq_u@k9P#XJA4Z54g?#dNFPb}K8!2$h|S z3c>-~!61dz^sMyl^v3|k*dsTkEA(Df_s@u*YxBZ!6Xp>8!S#ZTY$1!VT^ZVUznLuy)Y^^QDydL{sl6&|+`UBn|gBqi$l_H{|VyUTFS%IR0 zBhEPEn3k5BV`Ty2JcRR*6`HeFR;FgQHxQbom6@8h8?sL*W$zd`CRYobve8Fqg{NU8%$gwrbOK1*BhHlsPT%Y1sr#6*d$0(Oz-hUEX_7 z_%0vP$JK699e&A)fAkuDanQCf5YPsB`MU}5wxM|qAY;&@_wa+DOsHXEX zW0T4XQd7@=)-@FIeg;bzX!a3>IOpeZb`=$QI-c*tFer);HndbjnC&I>*&FRYqjA={ zh`bm2*V13NHM333aAr%lAWsBLT26&kf$7laXQkyw6V$3gi(VtbHfe_GxNpi93BS)H zw@NykiPbh?XeV39r_7w%L#G2VnyWMA{&!XP9`4vHg8DAK_+_N8#YLhcQ+WU&u8ygQX0IFUCuvWQ)J@8 z_E;*xHmQEr)I9xcFF9T7K7|F}7F+DhSzgN0()NL)E1=l{D0KL_Qi)Ix*7RD^<#^oR>f_Gd#7Tq-JRq7K4Ux6O+^;|T#u-o|-6F2S2es}dV7~7I*pP3mD%d?+_!)U_a{>FT6O({Xt z>2Q-kO?)e{;IZSw2T;iM=Im`mC6UZsOGg`poGGf;n%6QPHB>lEGRGub5}D5i?luP~yf-J; zWi>g!Z}=&#S^vE2(ie-$EQ8J2zah11KzL52r-wsnZ1fk3_)jarn8pfrR?ToWKxQ82 zIwv@}0QU!FUkRvWO3uuj)NuyEO`Tv^Do2FCX1i9ZFv$xU>;mI$%~*>?&Stj{BzsnM`?{B!#oNdk z$aAr7FTaKNN1mF-`o-^@e6{t^Y40#UQ>4`nH-H&kWegg_gByP5UmEWf+&=i49vM>D z-11VSy8S2jXmmwhd_}A=_P8AZ*ka^!-o?KI=^9B6^Lm)_>eUqo=UhGgDZzp1P$i@A zI{G33pKI^r8pXzyAu5IH%yt1X%6Zfd!DvCmdXgR6(PvpE`IB(?LV;a@!~0i#qb$OJ z`gF2HmqY_Wh$1|A9UwO~6dJ#`mKsD}z8y^MV!s>~Adk{noSo)^87SEoBy_=PTxM*n zk;_P|^if$05W1#;(l5jG=IC2pNY;sV^&yR!z_l+!v$R-vF&)4*J0#!CRrC{pkx&;L`QpSg<^XAfG6#qXCU3{ z08XW@q8+Sf`}QJXmOV*I@9;vDV@(lehe~SkvZB2wj9V@irC_1H`;J?b=@e~l@TOJ- zyI?fFOgB5}1IxeZBR=iN1v3SAuOMH@XV8bbcUq}!pmPG-Ee!* zcCE@G6B}!Ym*x6Oo{-7YS8N&ejs&+5&6zDX?L>`N*crfY_TL!R`4~BQ{X=xzE#t0d zH@-S{K4VN@c*!~5<8ss45q7{_Ut|BTJ{LTBt6$ZL6u>~6ejQto>*_jb?RI+O6g0Mr z_hH!hvqgP#hipIW6GQ{v)VP(=inyegPnJysK4h{=M~|D+6W_9jK0>SttGt`mcCmD- zi+E={Lei{*4ePViLDe(^z%Cx#zw7*ty9N#CpeKJkFBB%8ACXKAXUc5?T4fga7T z;_}J@JV0WvC(zGvZ!b2OLa?#FarY|XSv2OVAZ*4`w5|Ikp*$miNx^j7=0@;Dd@cmH zSi9BL4b{~S->5jW*B`PYl+k4$HS7xLAyK5TrTptKEUb#N-bC!(l#d~D`RbLhFvkqA z95#JT50AiAuG(+xwbEN{0^4v@I|`c;>z(!t(;#=lhVw2Z(s z5bJ=8HCIQtYR4_(^ynfG>~~8Oa#&)Hac*m)srY4})}V^93ZCdXwbcVszTrlw6rJi8 zV}1g1OZk*pf#ceKqSry@>MrcX?H7`W7>jUL=jXx{H~BW}BnM-vZo#(raD;{HYiwwa zbAuu~>fcT(j?e7Z6BMXAR<=t7Ry)iJ5P9SPhJJaaX{7d}5*A$P@sk!;|6n^J6BNv( zdTuu$x}nm%CIq5+q(3^AUQsZfOVd%XumiKk0>^3c<9 z`6@Z=^35rL1Edk~i)ci8>~@q3H!bc)bqPt2~%-nGRYCTiu}lt z?M#ZR11W-%8xKqAsC|PmGq1y3Y%*_g5p1NT3s)M5P=n=HMh)z;jy`2^6)0OB2Hf;= zq^le`h78S#aM69XAGNV$t2^YfbA53O&Lsn~X&nvK)o3)SBNpm20yX}eHb9ioh9?@h z2$c{6Go?=gurjuwN&ho^JupA#&|gzRrse@Q6Yg@a9<6>ve}Pmca<~C#Vog*2f^(rP zT=9O*yIA15lIEQQBpP^+C>`+z_l~SFuzN9~rfT*~*E35C=uX>>H$IN(x)Z~VOibxj z(uN==;)>8YzOx8lz|api9`q#}U7x)ow=y|sE|9Cmv5MYbkD>=m_*ki&uHT>Fy7{7z zDMN_gC;GE+7op}tH`v#0bnBi=@OJS?gFvWtR*_Af=j3JNTz+P`fJ4si9GnT#aSH|K zl4GmL2WGum7P&a*A=fzaaW+}IOUN98NEnaU8i(q8YqF#z6%yPu#lq^0=G*kZ!423$ z21PGSDcG)cQT)K#fMI|y2X$Iy`@5(4wy)~|h<^Co^i0laP@O`mOa>Tj}E zE7S`dJ^KaQjKsHtpv4lX=hW8?zT`(^_(x?f#g2*^{v}*K6*aZcMsj85^t=y1C#P!c z`}^kjmbjyU;b_F!3ihxd%DV30H4}mg-3}M*c{j>}e{^H-JtvrK;Uup4p`z;p6S0%O zp)nek3_5g*;i<1j)>ReZCPP4H_SBiU_RQQ|b4#2n^G(zxoqk>^YIV%f{z=3Kh@FY8 zM(=JJFQASs3&t50u9H4w>{7C;A{YK>E`eDFB;{PiTKG8xn(F2jI^3Wc7HlQcTUhAz zKS4T^WE)j8Dyq}4;om6W3O$10OT3hsU!oqjEeRtAWotN-@;DitkUJx)_nxU|MxV3O za}kpkP7RnKe}d54{*&j-k6v95I_HDu2Y7rboWEd2+;$sTcZk3 zepD{d)J1K*u03A2{X6f%i-dO2>pzoDAT>pD=R-(j4T+ey@0;-UX?B3fRJzBCKXm6& z-@M=SLw`PAh!bmJ$pzBG%ZeaTGdqEBa810eTs8W3#S!$*syw`&>D`CQ`$IxBr!NzdnDYWz15<=r2#SS{-EW?NzZ3@O+UeMn|XASVN9Nq8w>Tay3N*Lv5G7`q+ z&b4EdmcWl&_$o5VkX-NVqMGLbWaIpLFk0G6s*}*6n$~2z{bB3Tg}1c`ctd^75k!h~M0IYI}x3oRVR#>(`~2yLNi9 zo6yHW==_Hj33p8Z^1I_wT*C{_@#1AwA+86ny|d8NqHsnu5=!P*18(PjmSKIK4u=b! zEq$POWKrXcn?82uIQdkv?~U;yV-@&ijhQJ$3r0yUrjo|`2Fk(?n*ea9t)5jr(x=1I z$#&0=BtLGm@i_2ubM1ODjnxBs$0+KZ_2XY$bSim4T|kjJtpZE*dryPo@h)^V#>Ow6 z70cRK%cok36=_cG#9f9{&s{hEbSMLvN~D`VmmjytKe-dU*ZGbi@X~kntV3|+CW@|O zbnJKnCA~w1X(l!NGW}ih)aWVSpqI{S&jn(6gVHp7%varo}Smn0`wTMFWl*UEj8HUS=8Sat@H!ehfeOB#^U5lLdYk1gYg{FFibs{CA{&R=Er?AkOr{N>t*w7rw zU~HT}vpy5gH<8P-#QOyzCw&S(ZVvS|<%fWUYjq!&_(=8*=lU6YLX<5Ox`v^fAr;oR3MHK|-)2BM@U zl5(mh9ly#`wS92T#?5yN1(rL);L*>CF&hWwqS+fhVq75q#@LtTT~|Tlh(N`Nw>$fM zRKXi;C3p@5wJbFmqk{LkOSFUiQ@%$3epjGm14_d4sI@ZCw|Bp%F$_g+p|Eka4@EFJ zV`K2r_(0k1XHqf}jOT#=YTylDDb30+QvU`W?0NHX$Q9{FXi@=2X76O5SzmGH#%)A5 z(QHso=wXn9{Pev7jGWh(%HT5d#tywgn% zlpdASI!L)9o24VLFDr}GT7Kh5#Sg$W;nhrtcVs$3w>qRsM1!sU5sPN zb>a(kYoQ6_F4jk0vX|pIe}+EFb+_goVzj%Czq@up2eSV3Ao%!dspUmTiu|uM;TJpq zwN8d%J5ROQ*pDj{pj#+C?MRiFy<1caDjn%1o}s;knIfIfv&P?VHa_4u#@>;MV&Ms8Tc_HjtlvCnHm@}?4-uHp&?bhB*da0`*Mn^oDU_d%fJ#lFKQ0e z5{hi=p%#Ztt&Qpj1Hbi3Z*#G%RY{vG0=~!#kpvrv=$Tb~m0Ag!!v6wQU9P_f2;1`7 zc^IZlD`4biCIe!m;rl57Wz-b`tmSVyoHuPl{_O6P!tx&Q=OlGTumrMvbNvRTY1!3cZSn zU|B+LTJgu>G6EL(jRx*dJu{L}s2WkyJyn$83mp2oys1UTBT4nC3`i#5Jme`5Uc^tK zKUiLI_TkXQb{g&I?oRpYP%?W32IUDh|E&*JktlDM{HB&*zW>s5HovvcNgvOLPMt$n z0MKzMcMYtg5{UV7PUXJjz_=uOw)JXSm@D~#IG{Us>GR+odC5u4$J!=0tDdQ@^Qmk;&^RT%REb`s_BXbLThzGfIkuU>V>NmU0~# zoZmP+J1Rz#wOQlqlG$$(9Vbkn3Vn%+Qm$uH>x9czu)W8G*Uh9k^>uWK6J6?ZBbL!R zGZsrsby5*!5lrYqEJ#9%JEsl{0y}^4eZTVA&Byz5YfnwYOaCswP$jUlPbIU*GBBUQ z`XbT!<8JWnJ`uhb)&L-*J`XMz+%CB{du6|B=}1@?<77C>_)EjZt@N8fSX)R{kwE>jif64gRj!=Nc zAOBL)@NMIWr3}gip~sWbPRF^Ev4r*!n2J;=LwIS)_aMOs|8jPncvX9-OrF~6B!6>D zmrjcd)_F-`cmJB-aw%(^wh!#Hst;h_2sF%b(}_a#wR6xAhE1 zL$2dd?(@&xxxrT$+BBJVaN})L+16)&w;kVfLFskC<_M?mOqLmiHA-aJx~@xmXsCj} z56U4#ai7>DXkzQJEcoG22$LcHW@UlHHT_>53fmcBkg93Tl+#z&FX|2eI^wO|0e&)@U8e6?DcM zq%{DXsjAVil^Pf45NPzXPbAP@o}is^gU#PCrSlt;)faRpu-%n9`+4x=1-IBWqgMH$ zs1KNL^nVPb+U?^Phk#3C*T-(8Z7Eti8f5DNxDeqU_ePazI_uk_cS=nfAled8Y1YsH z)h44-p64&on_Ug65hA#U6n2>w^+9Q)MDnPaI)uhI$T#uqLY9XxKVNh1YBepbH2XL# z>qgG}d~GBI!Gxd_kE~jTu3z;YDk|I46(+@eq5qRBteJCbKD=_V;pM3W=jP2m2kuK* z#dJ!$iXyd8DLirZ?>+P90N58gCYE>56XtMlyKUt@!)&aYL`~uCoPkxgEa6 zIZKyDprV`0%ERCOm^8LM{ZG_}rGbA-%H$gwf_zYO_kvHJev;$3dKuu+{`SY{v`c1t z(KO3?Vz`|mNNUVvxA#DVIVgHVx&FH`OcAp(wr*hE6H!yZE$x0{lf2j=#GJ6Su#x7Q z1SneSNjr~3wQ9n2_BLOy*za*}U%D1(SLG6;(V@)1Vesx9j4o1->h)uL6}G6#I=3*q zN5BZUSk1xjUSrmBuDCzsXh?JA{=ud3h}22s9cQO<4Gc+ts>!?ki&lZ)O=W2Vj=H$A z3-gG>a@tzrlPWCl=CEwnZKIV8r?%t#0~!>wQ-Y0l>iE?T)?a%#({<{%YPY{CU(|Kh zb9_jY1;FG|%;D|~#@Jjz6U^`10^v1=9Cb>A|Iq$r2OpK`>PqmNls^%ag05UZoz$41$%UZuFVxQBwkJPnkOF2z$AvNntxRU# zJY~hG4|#GBeQRckJ8BZZ4!7IkG86=q>nZwh`+Uk1OXVeux^Uf&2u-y?y$*tK|yt_pxt}Gf+E;p zdbF&MZy>RAD0c@p3J^QGA6e}-l~-7~Y5$yOGHd-wp1Tn z*hVg9)1i7zkE&a?L&$KL)5S=>>ZQG9*%dCthkm-qV&){`Pb%i!SP3QbfUd>;w33KpF{|?+!ZRp$?~`pJRdW|d*A$V?v-!4{d+ff#-FE%; z_LZV|C2$F-x5;QOjartyZ{C_Q`e#8inuIn>-u>jmt$@8x6PH+|e{?O#%O;5ulP7lg z)0t1c!?zxFbWtOyckxpkIY1ZA#9V+QH5LfP#Yc0p6w(!k^hBW+&wKCYG^iLU8SA zqZezJ-AZt}(7UlQQa>~QStuXaHZFImxihY5lE~MNlJ3mXSWsQoxQ&BVP$ml{FWVCV z%4`q$gJ6+qW`2F>;RwtyBOh5F3DdO=XU=5iZ!WL2K?vuwGHM?%LoWm5&2A9SQB?wB zwuL+-!(F1X-doGg#T_E6cP?(&P-fTaxCXXyCmZxGa@vI2_>&35>~&1#M2-e^Q8n?d z(zZMM>r6RvR30E(S39CO$&wy$nb(>lnE|>QQdHY2dpqB%yu{IP=h6K88jxHd*s67R z^h8 z-ht1nHP*`JF`T49EGVKcRG}!`YsR(O^FzvptSNG%;yS*}ZVdv1zPg`_+SOh~U zAPC3242Bkin&g1gs zp*RD&fC;v`hY#L-haq5<#jl=V>AsY+Q(liY{Rk_K#$0frfcSHA$&Ax#!~`ul z`h{1Kd)ja_z56|QV$oBKp}KGW0)r5dt+OZ@srW9t---x1ORXW7?BsfeUVgae=jW$O zYNbXuZZ^#xha7OJq_2kQo{)fNTc16qNCpv{ zztV2}u{M6S)w)zv4&|A@m*tztC-$0ixj#(7B-iS%?zMM9dTO)8 zPg|0|t4#jsB-^pBv**RDh}M0}{uzS%Y{>{&`V#ZxFxdvS$|R}RigPJE{d`G?tuEg0 zZZV975H;IW$`I9D!+P1*&{K%<_v=k<>$Vd!>U>Ppd@Y%$)Wr0xU9>%Fw`@K7n>xRy z)DhlbD0>-WpsmEJK1?xCN@!?5SIQfkc&S=mfFSZ;*-Z#nwjunpBmH2LP!y^a|cmMAkyI%B_&g_*g_!@##re-g)mxt z9%#Se6Z;QZIH3L#AV)(W{5=dcwK$UcEXYs}a`J=VL2Ww)B66<%$9$4{R2=EJcn-F{ z4K>K!P->JedIkN&{;RqNUm+`4bvjjlkJQOCiQm6+bX0Y*)NN+?>6BtlhM{G-1X*Qw zE{cxti^Vm0Kt{O;M^DIeE}>VIaQY+uj3?kBg>EW9{*b_SfsBP>#JBmVU5&VPCK^V9 zus=fmn&1?W?hu4rJ1?LX`wgiYgYUWymyWhWkveKf*6%xO;=4|Ml zkL`)`I$)1$poNoY@Md@2&yoUzKj9ORh(iS*X>LZAbod&P>I&0&kH-A^)baB&nf1UL z%hZjbp(oh|>N40bz7Bt`0Ymfvzu zHVRVu(BQ86dS1EuR<8l?$XiDRdTeOORa?*BS1Ga4R&c32dCDdx8tI=E8rJfa;?3ZaAiUIrIpVaWWoqmW-lEaU!S1C`9tncYKf|+rNNtRXoJbZk96*n8@ zysHemi~p(~w|8M_Po97VwbXetzspwqBR0Y!ce_R;Ws*!&m5DX#ywx}KnkHf&Z4$WljxPY=mcW%fz;Y1;wEufoXj7?iOt{y4}mF#+;~3z>Q- zhEzIkaCXd+G2`$jcj>BBigS1AZK^xKEU26k`Fv?ju~)gPmP}F>tvWAXa?X~y)IdKB z+BpyR-jjTJeIM_!vZVId(s9QZw^w*a(<5k*{M&4j&Iy-vny_t9qT&fpz$`nJFZ(dJ*9wnV-l4fE`yy&UB9wj{MHo>UO-?FHh zw)XXKBDvXr^|h+Ba{gaFCl|!wgVA8GTX?^$RHMd6o;WbrbvzM5n-N(BRHX*gT~pja z4OW3IR)LMFffv38c6|-JHXU#^HRz^Qz>Tj#zgqm~6F^D} zFz^d7_Vd`P?qMgw%In0#OLD_wXbNZpkWGK)fwrs+NPQ-7Ie5Ax->jI+&w zglH-HZZZ2`zXOIcu+L1wg5M#NX1p`sJDQ&Km%2TCeg!GUuSDUQy04?8;O;cEPoEt} zdV|XcIZKa3gHt-3z=zhJb*FjzTG?oe5Baa9Vu)$k_F$&e^Fguyjwm#vJ3VfzS4|q& z>v3Ar4jZ-kX&5-uBnm&%m-z{JZO{a|Qbf?`cjx%uyK8;y;d`(OH}hHQYsFdd^&;@z zZt!UO`fGt6#>{uxhmdRp#CW?sf7!o3S`R$onq}B@+?;XzcK^xr)VMKMbv3$tMR+t? z7i2Bqzmwwukort2X)`Bas>BD^2x7#iE6t9>GK{xoJVQ%gZx)Y#^H*1&&#oc~FQ72) zzUp38&pFvSsQGMPfA3d2jAAo*%DV4&&7P#!`c$NmK;MM?3~RMUUPZ>yo&5sCZ--U6 z{^!0GKn=lx{jZxhrs>$czVa>2D9Z2PSHB>7#&!S0k)_22{?-wyi8pLA_bc)K_?GFi zlJQAMu&FtAx!)ZvKJ;n!SkMUinH`lOhU%it7TOEg+sf$Vq>uX^8H z)_20tE}8JXB<%emRGppiMs*d?5nSyNPybZ&C@^~9$i5vZ8Lk zG^p+%tS%kI=s#q$ z_t;2Z)<|w{Zc$Ou|8h3FySvYyKmWg+&0h*aQC&e#whQ?p2N`oXy8)N1ip0D3Hxp-T&ikejOSa9UYyXp8h|P&9Sln z3)y`4?%n@KkWGcEdHDY|RnvRR|6kP{=}aA?pYP`0+G+|iT2yjG=^Q7Vp5PhxC7P;H zcKaU+C`Q2m%IcDs3J%6yv_O}Yfk7&;nFt#9a2OvB0^l@aBNeKcI)EK8rh~wW9T}RI zSr!ciS)wYdh+ks_T@WgIw*A13;m#>dPxX<6mQ}ymD4s<(h;m!G~^P7O-t?MrMp0e z9KP^UUx|w%??*RP0d~pH1TZ< zNu_c$eqE`Tg$_e~9*H!Ds7y7}fT7oVcJQA}G-&zRXPQz0I`?7w+P}5Vrq_6LPn#|v zdq=@!h6V`KdT+PC-rcmS zhQs4;>p`u+otduRUfzPX)qdT5oLxPTIaRaL$_n;SPH)f0{x?qZ?IO*EWR&5Z{SSX2dRp#-;W(GSg z?GR+Q#S+#oA_~N}^5W4|gfZyyerh85azIdn=1|xR0k7NSAOD(relgvl$86dtPuEG` zp4+A07fspG>h?o6e>GLvOtYjbHY6a>&wpP_GL-b)d#LHGptXgMnQbpYz!mG$)Y3$U z;4oC8`?Wj>P14{!u-WBP$r{%-TL!`d)~s+njofOW6FoBF@0n%NLD z9@2kQrariuV^-X#vY&ZN>&a@a&3L0)`sgj~AFB#gQzb&>$hGnlXIAr*%t_9b`ErAp zoB{)W6RvFuZ&WTX^cg34^-!=|4}2=J`$S^O;UgBGg~i(R^O}!iaaPtn1@u)K8YwGe z_Q;6cqf%u9sbj-HlHN%bE}Bf_!@m%5brL|AMC2n>UScD7%|tkhxp(cd0e_rna3me< zTnIvlH$(LEKzG?*UJ#oBvO&O=I|F=PIZ+HXjpr946+~zHX1Ixa9Lx7^bCo){buf)J z8jNf%9hqv;KDIno3$GwOU??IUiP=%sILgCHrge+F5Wy5fW`<%s`Vg4pABNbXTE%mwFMlagCLJ&oOQY7_Bq!hP}Uv=y9Pv{ z%!yJ&GdBt-WedHrSX59xReea4Pfd}c!oJBixwH6oQFge~OAJF5dY-2wLjCH{u-9_C ze@LHSL+tQ+oJT%u^w?dYy5i_%W4yVtb3GVdTE)|BSQQ#J(3@joA-L)u0BciS*`jh# z?-cr3yL%(TEm45Gi1wv1EO6C{Mhca*;By}Yl}O1k-L(vUtd=Ice68GL?>whmCMUSi zWCpPq7^!y}zSWehd-KP$q1R^#m$!d0v8Ft{NSqH#(|!k?d)Wg z7QDW0V-c|IE`e0`f;Rq~cSCYyxQjffsn0)w=n;S7j-pN4^kT{i=}K`we|IBgeEf?v3GEl_8=v z>XZ`%Ww_Lb$onccWh~s=rUQoV5q~f}vGUGzT%dp9o1pfz2oab8M!2;Lw#4oB((?Fz z7t%OvvO;6o9G9XtTPxMO)B(nfDs(;X6E)`FrPld5LmTm;a_A&NpDcasGApMIB?@=; zG~xYQK3qK`7P^w@h%+>VsRek2e7unWxej1eOmg{ht|a?H|ABRB!mGpOGTdniLt}2zu?9w!mZ5Pyh6<7w!RLi9_raC=!ob)-t^iR3%dSAYEIetr7s2>ws(TQfUep8G zkevacRDo99YMOA#Hqjdn{9AGCuSMm`pJ12Zqyyv>usV!xs5^ZfFjiTBe^2;g8rvu| zgv)W??=hTgA41uCb>G42phxyU6`I23>R#xBRrK`;l>2er-}7!V3>l|{rud(wXSoN* zEgW7gXsc`9?P`ba7E>L_6^!G|HiQjY(T5 z=rA#GwGSG}4%%*}gx0|Hh!DXbXO;w7zZwsOqaKey3-frjAm{G{SYKks7LHSsC<~Lw z-P@SGQ;JNA4kLx5_&xawh$@+@L>h+GeT7smLJD7Tw)a4XTMo6v0HxFWRXlUMI42r- zIS45t*a_`20qyTe&0)v$D44!^L^vpurVcyHErozl5`zR?%2^5#%r$VVmfTNkr;z1b6cgR7oTXjH=03 zRO4awv+L-pzX9*Rk;<{Cu3RJ~QR(yJgsOH#ILuj~UZMODvEdD(hjz4v7}He?g!S{8 zJ?YRHrap%ui?Ju#>YMA&by%fluR#{M%Sr zWHnN_L-892oZ0(%;-IojoID?Q939M%0R9qKb`RpB8LCCB%vlSJdV_3w3}F1z^z(eL zP9W>wa5hRHg$^OGo#8(f{h(Od3_?pe{#9neOddK{F{{|d-9HYOiuO0H0h{JQoVXEF*ZdBy zLBq}9FQLdwW`~=5V3Hl8sJ7F$@!T_xEDQ}03wcm5ikVydxF50j78ybGGCojfhG-5wL03@rHTm%S^;H0&`|g&_9n@$5SGk9`pCXinemjBQRb!YK|Of z!|e%B8fP*U-k_%gQ2T^g|Ad*41F8H1iKewwHbY{>P(HWzQp*`SnyciOf6y%2o()8c zT>8X_#W&Dl7G`M)s@$05DgpYq$SkLji!;nX+6m`*sF4lkq~D2Nkm&3(*Hr`rWfUE2 zOLA#Lr^Df*CwaTVv$1R?eQ~o8fP{`9+r`RzX{>}*<%2!dIY5i}ZF40d1IGp`3Aq>% z1pkD|F@x@3RX!|XZhei&qOoixNMH6P?7R}WBk*M^kS$V9FH}tHMjl&2SG@s_e+RCQ zLVX8e7bg%-v5nh0P7)p-+_ZlkWnT?Q{6ZD9nenkAhVm7rS$(eod{aNJB@Wlf?Rm^( zX062rTRrQC5(N69Bk%BXGz{8HD1z42p zDw^jA-xTDh`w4DW~iejSeRDalsZp|4{(5Ps=9%9#<9;_V9_O2o}jv6)RP z&QnA2_?3=AQ4NWRAoj79*T8{{E#bg^tOPUX z!+bOYQ`m>N^UxqJ?7UEdq2)VshwwCb828j+hmhEvT%u%<*Pam~zN$<|bt#4v)d4j< z(PLFXgR$sv5pb3gb7l$M_Psp;z;>)!Zm_%lxeE8)k*UjuTuX(A_dt)t_Pee^Popau z%{m!0R=Nb?W>)C@cba`Yx{9V$ZX?AKA)09Lb<}MV(a(hKe4yvLHw)YjLaqPCVnuUf zOr0V?g@E4*r(F!&PK@qPEPDNqg7eMff--}}1zqq=jRWX|#%LE&P|y+@N(BLD- z%5a;NgT;Uo=ynk&pLC70-2^(rVQ!^{V7ZNx(JfnpTbi4}($s64GnFq%;@egSVC}&5 zVLrn_JG;H)p z{%{T8uf|+7LmvIAh|3# z01S0su~};C>M;*dAVLatOGE`p4!9@sgJ!rrAk?K*?u7~DSuXU`tdEYa&1aY2PgLM4 zk4p8?%Jys|G8~yOf9Zx(TAv7r?U~bDU*RM^OZE}N>|L0fxIJw)X%~Et?09_J3_Zy7 zd*pKf_*M@MP7I(rF%?~#@ovnYJNv+$53y`uJZA(e0;_8cZOF^Vtttx=m3FKuziAB* zmW2QM=kVFgI2W_4MKS%@y$jJ@@}Yk*r)VI1-wDq3eAqvTJeqQ=S!#Ep66|0t5*%Ou zuh&)3XgV<;&jpgEU*N_Yb;5f&U9j^9A`VDkLJ2}lJbh_*6~T-tltX^sk(Xc?v*yNR zh!iIoQ0GI}rm0YAVTk-Iu>IY^;B_c>^;I|#R+fUORVPLQzIu7nq_`>LENcgbtBYmWF!Ync^=#SNiHVgUf+^JY|LP+7=Vx zD~2X;;rZ;qtBJ_3noe{s>S7|IDLww@u8h;Gr+ug}j#rhwpJ@=!|(TRwz-RM#{ zj5VLCx^QL927+TNbrNcRGxjb!`e*ugF~a;QmY5H51m`_3zUbWeRcr43Oa$Ky-sW>R z>qOR>d1%HTOmB9?^a^KT3(kIh>Do1zIBQh=T#Dn+J zA+Yf>4m;}lA`mPAf_WE^;i%ISwM-E7FH>-32Eu6`mT=bb?>Y=Ngy~PXJh~NK#9$_| zAv#>Z(QF-3IWb5eUg}SAp-GUfW;gN@5hgpFqpBea{xnFj<6cA5_7t9fr(DfGcX1w8 zDFnAMPHqqHCFhBRmdbS?RsxL`HxIZH%k+vR*L<0ZQ5)@CR2Kz$@c@|3hHMhU`a~%h z32eYWi^)T*9p|4lD^=KoKm9))_F37C$$4-Mpx7cAf5$42i+zc;(so#A+AM|*}mgdbKKvCjbB0wXM7yNjq{2G5rP!oF>_FgO>BAU z%G`m57Wx9YXs&|@2sDHF@&NX2C~N`g=d=*z$UL};RE<+M`}A4^^Ja6VOVYXoX6)hY zD(=Pep5}#uAFPiMR!6X_Le7Q2z4H*NnNoe0N8Fo3`YXy2_hJ6qvY))+oPB{M?fBIj z$4%AYR<0)V?$@L;Ti7bnD84ZDNB6>z9 zLhznt9IO9SP3LOUkmnYwUawv2%;TOj>arsX^z8FBifMF86a8Q)yx2?*IBmj^eU{91 zWkM3ns6mdnyDTA=?ac}xB^BxJ;T*pFgwyC_;ub!cDEvq1P4Hmq`-@T077u7TaqM^p z^M!d#;btev7LLJ`$o{H?(LnjcB1&;rg0X+?cdIgr6cg8Xk~ntfj07gNH%~u_IWXNF za^+?ITY{mDlBdc}Y@i*`Mu?D9S-f&mm13eM?iL+2=r&K>&v2cL#$Bks z_}R_24_B`-M|zteE#Ga*@+F9OnEp$yHp$pgdze~*tvRA%J2S6GlT!ZiZD4}rG}2O3 zrE|gzb)k)&l+(u#*7!637R(|XuHL7`+*$9ec^>|MaCe_UO*L-2=u=iIplLv;h88*k z(iGGrw9rGZLO?)3)F53^lMo;jF%*$*fPko|hzKaCNd!btpP;Cys6kP&Jc=C~?)=~L z&faIwoH^h2m%Sz*^C8J()|z#%`}$qefZ4Nh|MWJcVU8K&tifs(o{a|r)-J9+=j(mF zE=%;)O^)r43LSkOt@*iNpunCr`*B6$(%F^;x0RVO8U z_SQb*t7PsCm&Usd0VAf!)oIL?Lwvm`VcVf$=GM=KFb#`!GO$5@4LN!PxC8aL*oAvl zLcVdc(D6B(JSucFVk9e|hSA0`(DA+*enW7x#cjBfY-%NLNKe&At#Og*ZN0x= zPLC|v6?+|r1QKTLqo1v??!Szl{{$*L^!0IWVp@Z$Nwt1Till${jt7uZ|IvO<$Lqrie*2YO@tSiVMp{Xg z8@nR7Y6OHb@vM?y)8M~RPi4$Pt%&KZLaar@Yb8T#({p&)yV;++qW$WGA0!4pprvFB z4Vp^BzX?T$oWfL1cBE+4#mwa7Zgnrm!ghHn8;+XPsIDs`c4XbzUS$5oM4ofGGq^`{ zqHqmsi1Ph$&Hl@JU5_bT_z|4pPm8#kL`5oIzPC$SDFM9y_m; zKI@I#^a5q*63>b2@ZhKZUZEvTqo%#7*K zB6V|4--d@8LVT1d<(Nm1WdRbl_c&q*mZ% ztF5BqXf;tEb@1Uq!bmSFIGqRaOriBGwNw2yZFVnh)hy9xYeqZip-y4$nhRdHGwW)s zsF>SWt|8|A+%v*{q1doF&JS3I*VFFE3*?fPz$hR`D>p)L>{)m5QoMiF)5!0 zkV|Xpbc`rqB1!46#ea}WF*I8rqv?C*q_JYuC1#j!MixUZm7WMW$6pC8y}QfVEFt^9IgDtAW`QzOL|2DCyApha5%QM?uoFRA*y+S;wjLad@VqZPGQ%m}$ zR>lBrkL)OXU!-ILy?zkAA5^Ax&%t9Ok*^|Pn!fnZhghbZRG|#`fkux&9)Q$t49gb;(!h;!o;IAT$PFZ@l{LL0S2ENj zv3Kl0;rVYCrRY$J(Ip)5szrAZvbru;vj5zeu~{KxWhfD37nGm8->@3^Y0W|T3Ai(E zV{OMpOd6>`hAP2=}Eh>ovH_aYiXU_@f>Ww};!M+&7_%FC3reZ z3TYUF*9zm|s#nG=nq@S@W!!^*tcJ4x$-!tU8G8M!5o6dp!B2Rf4n+jvbexXp`CIWv7_-5aO||G5rzQrXG9-cZOfQ1pkb%WciD zu`I@f(XWb+Y^pi8^~1kiY?yAHli=FpguZCGfoZ8V+;mpI*W|SuPI2RHBq~q}?fv?F z_x_VGKYd&c$R?*s$Q$=sp#YJKT=is@!`apJm@P%OpB#tnL5cQ0ZrO~lYmEIxnwUqT z?Sc!-J{Lc2aNp-&4^ywUp40JB5a?U^&DDm9NH64!>JduN~D~ zzcG-(#R)NMbieO$G@hNDu02Khnv_tr<=vVuSNeZldD8CQ`0|R;?cs*SwquM9ANP`c zoV0#3xVA*3W6C;;9I4DdI1Db_?n4rvwQXLf-Zxyi%ci_uv;N#8F-Q~opw#4|tGKDH zup9;RU4#raf-EP1*hb!|Aq>YFdhjBwE)eo2LUd2d`A<1EI)bCL$i^*!XYxiim~eD^ zLEx;W;SDMwvnv->zciI=@#_^~!g{DBvV8gx_fh;|4x4-O0xZeZHJS}^BvQCbS&g}=Bbs>mwJCegeB zTWryR3_LDEHFi#gr8HVAH!IF}NnU7t)Lyl1y2=`P)q+)vOwqY7G0nXw{rz@)ZT=@(b37~6fg1GgQ{AL2k9^I{_y$aS)S{9 z$nDar`zx?rsdyFZB0n}{t@AHR_i{Lc!M!J+o~t&^tPK>k4C}YjXVD3O4@zno=0sRa zhg2+a@foEcLbYE$dQI;^d&*d+$mhU9Q!z_%If80dK@FLZ*gf9*GSCWA2;PRT$?m6p z-*6-IY-gp6J01eTf3&J4NjOetLFU&UcXI`zbv5Y*|1#7pSYBZ)SouQ}GuE1hbb76v zSM_^xHnG%M3nG}}`N?_yOS~{v5qj79{if2wcdsn}#TyX&jQ^#5IgCMo~B=Cg30b00r zNx{H+OP#pe8`x$;5dY&4BT5}~%Vv&{_xE+Bhsg>EM2FSV0SJk`zxp&0tE*-tI!@so z1{J9gkvziT_34KrOF>uD1BvVVEJf=7%0NUStP@h`Kq<2U9VCNQD#fe+NFct%PT27- z{UBH7~T78-FXlmt4$|EF=Gp=SBKBOfqJfgDD{Jmc@Y7Zgfe%J*--b7!6}9WIZ6 z`iDnwjghpmW|)6(H+dN{$+MHmG2M?0FETrzj2SmNub4h#nZ0qQly~1n1=xTs`>i^( zJb5v}kV>BnJb&2nrp}%W!bbb!zD|%6>3m<|p%K)ks61FeH&nBYYbZOa*9*~XE8P+r z0%!4xnQRY}ljpq6;bmSfJ2azL=vT%oDqZE6`d>IB8P{i;yQ*5zWgq;Ztz2va<9b8L zrbYDz-Ik2AN0zFe?m6;K5O9&yBQ*ouh`a3DhG780UEW*>1G{4E#;R2l?INrBG&QNZlWt4T<|? z2s-XMDMv#C7+lMV!Q_uE{>}sbu!mRjEn9Z**HNmCQ%s%r4tM>#s(J^~<5E%RP!O;S{#Cf%$6xT#XzThJf7XRm>3yv>HMi}vdbJA$g2MV)YNDr zRh>A>d3|!))ne<`@Wp`L=8A{693!_<8j*XWf6L~CI&EPi{lVaqKMdz{Xj@gJF4A)A zM~Hb_ks(9>uQG|F6g__GNpaOCJxs^?=dsVeR604~&i*SI3WC&nyDshX49p){54!vP zW_wl@TZ4r|v*H5ZK5=qa*3X03fR2S@IxKswzt+;IHZZ+&MXx!2(EUO(p07%Wm=L)e zx*xB4bmIfbmp=v4B=Q=xE?LQVKJv3ZONBkkm%*=rH!kH4PTcBlf2{w(o@pv&`N6Am zaXA_*M>sAjQF5SHz$f>1o96kiy!4rJtBJ}4aji*I3YpXaMnH9$EB!U4q-hgv^F+PN3(8R18h_WfcmC!irFs9&Lk4nw z&TYR+87TU(ikn=fx=AU`9u=s%@bNiDf$zG>64jCuh^bYM#2^9^IB*UY1!8)s9c`g- z(U%w|bl)r&e00i~*F~6VM4{`-!UYpvnj&4Fr)%f2@V*x|W5F@av-AF4h##V49QZh%DuU4xhM$;!MpNS-sAr7U{{D zC^jeP^r+gmO22(*EfUv-bPX-$8s9I%hS77`?m>MK2WiR>nWS*ZQp~XC9-+ zUUS&LG*F30khQI{dc2XrjdVkK5&2q6p4+6t*%NFhBG&}E{mS~GB$wxiE}i2xvd1R8 z8du%gUSCcpe|-70>K3i>C7bQFq&^oD-=r89ODEHn&dCiS>!(5JjW0Xj z70*ZOBi|e!Z@8hWN^GkLJL_%F;t(h>?n8h~Z;s}7<7%tuEDO2+zi0pWp%%-EimwK* ztRjoKK7lbJCz#Eru!@x(_g8R4;mcYE}|BmGk)UFC7>c+pO_f6;-cAx>n9M(0DI zGFW=1mWOXje_x5!6N8?}1=;ze*<#fFjw!uB z>CER1-&c{cSM}7gZ85hJ-&eY-+#B9<>V+=m!gw7_#1EY&|De<?a#o4W%6^0tepgK7}gnU9?pE*VJ zj+>!GcNZmntMn3sy@vo3Yn=DcfFA~GQ>OeKgIrzDTXo7&Z4V@}#BMDTx;C%;3XEE| zRtoQA5g79|CgSfO0h=i9p)*e}v_#d4zaO?zwL1u+4#T3Bpqt#e_nu^oSeI62K}Z$6 zAWX;FUd6LS(3&BT^eu;Ava72E>pDSIi<>yyy~j{dBLT|4nR&1#*J{M*WZp|>?d2a8 zuNkrT3Imq_|9WVpfXmObTlqoxWw;$>oW?D8M@92bl4rMSS6$wl&oy!?xO@y1dF1?5 zsAEHF(TPB=Pu?HBh0iztor@OS-iO{&y1(>6qAGeBx^@Ec?SGH=r~OsU)MK)=%51c}LA|Q(sj|`<_D`z~6wX{RLv`XRGUJ8taFSQGoARk>{W#M| zTOY&8+QF0zs`Q1(yDGYFw(LKuX7h&JPw!rTHkJvU9;MV`IMUT&rWu60^^ogWRb|tH z_7`PSReFUqG;AeJXdY1;mm8ZBl|i3IMXvask_lAJwM-1%gWjA#&DeFc#<&I149d!* z1tyY2rF%G|GwJ?P8&ne6(8uM$7akBid!x}Y^ZoCdy9aT~bXhN@}Iu$C($;;0LvS#-=qy zoW1F-xzXg(SM;v>MzcYaz@xu5{$BnVd9ac#MP5a}2oCFG)N)NSMcJcir>HOBTYlva zG!@v`@PjeBKpW0HyKS^AT9vdLMNB2;RS|k_7LVc!lZ04=55?Y%)NH61X{;($^)lL- zcnk|$!9PiuQl~qC%e_yLGQ0{E8S}(|f%?E1WyKE5yk&1XZd`3`dlF`qcf1KWsHBIN#GtCH8?Fj{;jT@ObzE)KFJb(|hPCV)!4jI>k zbV^l=o|r=}_?b)Og9wkXJ-Z#8%I z|7khY8cBl_j*1u%L~d+95ARptO(eKtY5nnr83X4`Vz{?rH*G;O7{%(2hnfxc3|Pg z6t2zpC)U2U0JE)aMUzUQ+jRy ze-m(nw0pT0zk#Y0z?3SL7NXIyGX475WL(ED-Q~-w7Y#~%A!?X8z*mU1FVIuw$f^4mhL>EDe)u?Pc*%s;N@-i%XR2S@XD~{Dwa(gAy3_jH4Fy zXkf@X$iWJ+L7z03Lngt(HAMRRj&rqERTb$mz^FgNdYbdkiy(m{^kTUf{ZsXd{+{;Y zDj7YsmbmH4B?v}S1F(ny1H>7h0JseYPNqPjzOI0<3VV^7Oo9<8>5Ky#Xu99-blL63 zne?y=-GM-LH)Rg2uYrrJWn63G(?W;~k8snYjzJS`Xf-WA-Q0fZ+a8d;<`UkWFYdYL zCp_YD7UT(RJKAU}K?hgynsV-6PYp`ZSEW8Mi3skdXF*U6;!-sRh!-y1eQ3VXT`h4d zGB}Y=?eCUi6lq@9o9D7Ura{e(Qb>OwuNtmF4MS%GX9Ago_YVy1cXcBUR!|MMPrL$@ zGn7(LAJn>8FI2W(*EqPdSar|R)pyE4ni`=ggy23d-=Ep7#Sk*4Dz*gMf+XQBmihPy z`tF%dz<5ML@^VX|ZAmUS=hIg(J-vlCMi?HQ2}ZT{R*=(gyIQ@teL(x}jnJ#R-O51R z78Nkf#6b^kIb(rJlJU`ujx{&!7gmP|!avP?FAMVxg}6pYRl8C!`FBf_c|j^6=G->ReD#BXnYvpVb9sYF<}sU~zk1THjOujY4g+N9v}Z z?L@mtkWRPn-WDb*1%MKiJ((OB2~=dvY{#9stq`}VCj%1ONqhgjb5x{iZiZV7EtI(# z$5PR$XEPrNs-aqbgLJy2-he^8M=L?Ro}gvY@Z?;!c<$k%aB;#mwJVZ)bsyV zkjooT=o^?H~$wttXG$c0ro)r!Wz1y)TGq~-P(aB8=meloibj@9I{YCwc0O8!D z8ns6f|2GL-b*W<2@{5z?UO!)HMl~MwyEFUjZqu74)m(#-BR*+MT=mOKh$xK&d<(^m zys?=PjroG1BgZs-f7I2dKv4HhKUn&60_~FRE%y1BVytA)0i=^i{}Sv_wt|diwNF~T zzg|bSMz0}^p+9KW>bYc8ue;7yYZTK0odd%ywNfVcoZlAsY5AI)A& zk5^py3bK5~Oj~mIHjK#&-6|gB6J-wt9s zzPBExf7|+uDG!{)Rcv-{pelylYyy8p;)c9it7kZ`tgK4ty0M#w(J%yPtj2R!?>@Ud z6RC8j-R*XG^^nmV_fd)e^P|JnU!&O|ds^{7VIPI`pc(l&gG7%Hl6!YjnLm46_s;p7H;L}xQ)g)wi?{fY1Kd|j03cwh^|Pm zK@{Fb^EMdLN@(z-mli^ky*sBc+cC{gjC)?;%$f5jYmFB(F54j98D4rRw0{b?IwoaAHt-XF_L52oQ^-94}IOg>6DU`C3B@b@(R8DkG6+-w+^v8 zVl0N&GZL|<2xiFVL0!a_-8Arw)C|M^5gJ~;QTg-_o@R>MpX{+eHcwat8Zl2&a9$^5 zv_gHOo;yK89Kv3j*9xfss}+FB>0EODVtT&^}mH9@L!GzlkK>WIhwv9mrkOX%>l36(fjP&pwHGYWNeQZr2^K&_rk}f zH@N1r97U}VnaAnrk*F7dAK4edEA-sy9DE8`n?y5bhlh28F#@k^Gmo^AIK)J*-U8Un z*#0+;vHwBO= z;N}IdoDLFP-yzMwQU6(qDj1OkYN%MK#845wx=%?2bC-MWE)ol(*GB`;Tb@Wk%QkWqICN2&;bHw9kv_k5IlkB0m&LDWIlh%^jPYvR-2Q+C*RX$USSC*vAQr$DEOU--}0wLIB5A6z& zkwwCqRfou$Jf(?Z0%QD;{xr6>0(*mvk%5l`9V9-VVDchXn6B>C#JEP8{_HY0b48G4Gp_9Q`zZHdmjP45VJgz;tkik`NZCOj~=jbFC|dBxzVr5uI;fZB`F5m zW|<`|_k9qoNC(-&U?I{|ZZuOO1i=&F1TV*m%g5i3-tm97FKHaH(5Yg%MXSO~H(T1S zxZ@g?Rd~$k*-hZN8wmEoOK&$NWb6nXES@9QUmjhaWf~&1*SWH>siTwe#c(%f&`~|0uqe=5w$| zZ*f8N`}Cn03C6-am43pc!sFX(3amg}@ou{-a~Jr@`} z@r9fc+#xRn5DhsV9yC4Dhr#|cxB|(g2Nb^?rN4n7WpsC)(?LWC1vyg^h?xYI!XM@P zHC{&icryOOW66KCojOCQcnDYs5o&xx?Uk4%(FpCC`~#8z#w~NSFdSVW1XuCklIA?i zm#bUw#wU=XEe5|Ox@qvJ#@%(x`)>_;TVvwrZQazghdj%rMKz)XnaN#4$oTYamAmZ{ zAw+WKuGQuC$BNm#M&g4&me;Gv@_ieu-@!A0nv<|u%6uBPGi=oG0b4Z}PNsXT%vDpx zZ2b0d@<&O%5OgU-a_S&wjf`Wsz((Xzus@eXF4h|639?gb0(v^BV!xM{GPdP z)(llEQIcw3WXLTtD<4}iTWf1B6L~n<253t$0`9KYeak%R?}{CP4BPTB{YwqD^(#v@ zO>2jLcrZYbt1IA+=PJtU!-9XW9qRvtVBRGj$V~Vn-&ZW%@Kk30F8-69^^klL^j5q) ze$M6Us~I>9cI2(f$Ct-dK0B(PqdR?}Ohv3d2~?y3$gH3?2F1_fG#AH6BJbYeqClfjf7p$F_E%5ApUNg=HB;U)G_ z$Lwu#Js>g9%_u8h!P@PP+zzJ`=eIol8hOOfyDM?oh)th?EO$ylqn&<8kdv-Mg7H9t z!8ee_z}C$UiJk+Ajta_QASupa%hrM9T>}Zh4%-emB=2=dIh2!F{!Jk^B##)yA9IVj z=IQzBd_LrS`qf!cZ?c7uxBWC1G}IMwCnx=v!^e>Ue~R56O$xYYn?bV(Tzho;uXvWT zqdhIxZLL%#a8M=k`(NhZ-xSA>EXUXbj(H`6d50YHj|}D?{qAe*2%0!gs$7#fd;==l z1|Aula*;0Ie6ch!$m$q{ASvNbxfUc4m;~BY;&b3{Zh^XZw`aduH*Nb7FNC13OSjVMlJsRAspv zNH|*e)``3BLd~_)UhmI)YhG}$Vtac`)^{Wt484T9U6`U=pj$u=ul{Gp6b;;)JC*pu zGV6z>aNtP!=#Fjn&8xG@pE_-MlP~=2chKPCU(EWaOY6bQL;Mfx1?9j|&o6~nyLiJl zgys;RPdAIU4V8cQvm8ybB!a^B{ygAJDLUfx6#2tad4mD(r=z131Y(0`^Y#uKKeZ5h zk;Oj3&jD5|fk4pJ)%~AB!p4moJv=-V zHbQW4@c+Xj?Ay05J3IRdXww{M&36#u4+#7fg!&0X{Y9Z(K{WoT5tpE=AAt<+fK2C* zrvK$6tiQY3=`F$duc6@|Q}Y#j`<0EG{xx<~I0?hh|2PREX!Lnx;2!x5W?4zuDOyW&&M2QRr5_xk)dm2fAjSh}TQZfo&$dc(W_LK2>5 zR49am|H&gXC5(%moBuZ(;cD4`+X(ks#^*Zz10%dVHU745{LAq8@|E$W!ST`2(W$Aa|9>Ij?c2X! zzkdDl<*(uZ{au+C3J#Eji^3l8dBV6Y#^%G5%Md)$$;DcY3xW_0V-iUeE(ZYuW_<)$&ZX|1 zHht*9{;A>IfA3xDHtRJ5A6F(v2^se|q1foBLH49?JMUkD>C+iLVc>p*#`*+Sq#Qg7 ztbrXGJ6{Ki>^gT+)C6L`bQ?@qF~wMeez4tOpgEdoP<;RW(_N24vq|hO#9+`9 zt~f!kqnJWf&I_j;a8*mC94N!6Pwi8W>TUxCorZ(-0k?Z=psOlUj?ugC7EOYndb=Nh zXipNv;l_>2NCk3GOMwEL7TJxkjh{qR(2x-Ws%%Gz@aXo{Y$<~rPhjV2=r2%;j{{xE zL-QJ_1+ao}`n1^6zo+&Xr6Q&HMO~3uP-NA<2lQ}*rpdJUG$MHvv>PxjeY>qLxgT^6 z>Srzk1x&V6db(&o^`iPfOC*D)+mUZCXg=PfWCjpxqbxu?a!Op$?V|4XiYIxg$6=PF zNGj50=uwmM#(@WtXx)V~RHc$~Lj#yeZ4VX6HhwyUjn*)^sJ%HWyacK$;BPcMwGt!$>El0>s|9U_2{r#^GV#M0tOHNyMia$;mpZWdihU16d zpJkqF|9qJV-}UF~?6zGL@Wb2>f4>_ z-oUQX-{tFNm^LxK?k5A1o!;T|%mllsH4$MyCke1(d14ihnj9*QuF>n8sHSr(H)}|A z^2K<v4YCU_|~qlzBk}c-@+{J+;k0 zqRKtt8&A!T?ds!0LZ@rm)&KqCWgLcq9)2>a>}x%0ZOZ1kEccf?K1R`uFoo+_&y1a0 zB!Q{6O5_R&&PVRL#@d=wg`RHTh@z=%6$4~Du<~J6k$*&EP^*B0I=9T#i~yI`1EW=abd2yn{><}1BSoFQfdn#_0`;5NZ-Ysa88yZT{lY5bz+{8FB^g-?aDV` zKe1rzDaTFd!{8aEzA0Q>4yMQwc{`@8!d9>WRftc?P}X#IO5eaqn9s`rO$WXi587#K6Y!xIB_ z5<*)s=?M5OF>4n$~r9PnKNI$of`5tt6fcH&2L9SGj`6_)ubwSOSn zo(Fbw%rISmJ249PAma~`OB@HXJ?Ok#JFu4+Ldo%5!3uWkzl3K{kPULwUNKrEPRq(p zo>W(BHrxxL?j?8P8$JD7$jI?)m@`7SQWv&gfHJ7xA0-dTS=zT&T zh5sKprxt|TPX<$Em>w1)gbB;cJ*Y8{K5Pw33We?FCo0naK}<~6T_}m|wPj#etb#S_ zjY)i&;?)ajdX;j}0sP!Pu`~siB6r0LfkJqqqtl_{98WkZem%2Pzt0=k#(JEB?_|Rx zNf<6Ol}d>`R1_;B?b59(+sashd9bQB86uLthUiYmbqGpKM|qakzF0Y`1B9vq3A&G^ zU(2agm4g{!u-Aitt#yT$kX4LGYyqKZy^$+cI1VR1C1c`^Z+=D5%Y1j z!d?WgUtyv}8rYsCuze!EDSsQWs{Bz-tds~YlA~R(R}ErN`pkVfvY-c{m{)X|zZhke zj|*o4=}e$ao}aLU8#0aKQQ%BQyp{USmv>{CB=~+%t@$93!U9$^T&*y$Bq8d?eZV!x zlOTYR-2KnwV@}CopCj6hBn>COG?)VZPZcP99bo?jJfIfjo{adKh<@h|7Gdy=^&ty~ zId+^T=nIqrjH#CwnF5Gl5G)mw`L!h0M-I`TK#wqx`SQ$NV?bGP;%cE{1Pkmj1?Q5m z17cLXbtVRm06XF>-WSFH&WqN|SjIR3couzg$f?mLfff)OOUim!8T04)LP6iT5 z{-?WY#|A2eVpOA8Wc9t);Dlfy2}ULJAnssKR-unItVPxWiC1du?V5ktHXQ~IkpV@N z6UNwMCfNG>_tUuy=q3VWPyk~ocEM%rl?bGt@c3j``x@|(=ij>Au)Au9Dyzk@SjOSk z+4;C$$n`~6^+uXC1@>yJ^7vxGd>w2DE9ppYOow%oO=-vY8?0h9=w@2KNd!H1Jl)1R zu)8ES##-suaYfgu|Fai}sIxKJ_Q2k-7$@(Y+23;?CFcNb%}d0c3>N$VyCV(+|E{*v z!Z>cb5VdytwEaA4H4|(l1~M3~>tv^1&DPm{1mZv|sI1=ncSzM^FW`)PQKIaq`L+_g ztk5(Bif~5elaTT1I|Jl^1)}(y8a!Eu>R=sC+4E zVZim&&RKxb9xP;|Y&IyiX-sxI^~m_O_OkR3S;R4saug}}k{XDlRP2Fb9xmx!c1)kC5_w4^|CtYX1F zZ`l*{{Cf8f1C#_x)&a@LOGTCR?;0 ze6KY;*$D2#3~6Ft8f3tIL9pvesxA$U_-T0VmzdlTpWaE#v89Y3uPz}9E)=L1hD{z? zYonw&2W+D#ZDGTsL*OBx9>_HMgVq(F`G6}6af|L?!zFl)SG$HD@^d%M{Grrb5~#xj zYt|K5Q0<$2`zW;TU5l$2dM!t(j@h5U*arOw6NDlS_a>%Bk891L zeKUM}HbvecZ8tn-#7NVMEsNAKF-=RLuAeav(QL_bq z)a!=kM|6ZhP$fo8*t&O$+ceQq!Ty(X9iOos`=N_iU!JQCHr$TCOZ1cEGNGbGq(Q z{AlocES|BymYEtyg4&b(>wzPftbL@fDf#GS&8+s_iSO?&| zn-W6~3=}-N?16udL`*I|wVFnQRxpR$9{^Ty`w{U9AwtLZ*@J`lqvl{w5EA14#QE%O zsI?3uLHP*NF1m)N%U$ISG-L5u^%=Q=B+!GRe)ybidC+_LiRU#v(_3D) zLITm7*)3)Jl|-y##Y~h@x%aESm@_O?0vjfKc;e)CSdc8^wqe|zR_v)PGUv(bO`~(& zp*W>?u4`o_kwSnhPO%?a+{;8J$N_^lE3UQ{`bSxVx2(WBtl`_(s1{jtofufHfGv;1 zcY@}~ZC=cC$kxor^%*bpyQEL8aF55tdk5Y<%>@q%%8rJHT`NMhi{JdJSLOBJ`i4Ta z$qM{sySFpphv<`2*NWpQXwR3B6KcqaTXNkh(7Qqq6JKo?uTYja`>%`}9ENHxAgeXZy7#jW__EB&x;jIZj{<5D-QZoe+pTn^qWTZ%J$0nhkiyao&USi%LkP@@oLw$D7RSVdV`CDPm9ib*V61&CWDhKj3!wEb zTrT?MaJ!PO6nV2b`pEp2usx(0448{N=^R$y+yI-ZX$d&xwBw-&Fo6*q^u}KNBxHKs z+(i|yh$Kf|*Ya7Yg?Z}ZD z!L?|s->bd5(#j}@j_5D)45MtZR|oXsZRZ`MW2Z%<_?C46Wj43OqOo#%19U_EbbGkzAPP-PQYI?c}^y5WV|hE3MDhBkjQH)Wvs_5Bg@%M@2+ z;f5@J4XME?;S{Q%S$J2+Qgu~y*M>-?wzcHU@*3OZO9wlwH^lb|@OF#$9`czF7OEqz zzd)jzBKY7E(p+{5qKszkz#NK*EQgRi8{I3pVb+{>Tpwonx_4pWC<&V8WYXRD-Vd#|^?~3*(CD@$dPnqLnQPrOsKEyA$LQ zr8^-)vS7d&r5|AqnVG#P>H6>t7Y5N4K7)4Yq`@DFj?N}^)P#@QdFF9LKy4Z04hvD+x zJMQd>B2`D!z=5Hi*KTj$y{VI1YJHU;5W-I~a#@>6nnRu&t&8&4N~s$0JeTB3Z=0JR zODe>V^$Z0gUUmBI|0o38M-3UOB=Ec0eKg}CJ0j!3|1<(RMYu+?7PG|&mWhPg>lIe}Jt!V@`1(AEcTnmypU zRmfXk%W>Lvl>t3T@%r&`7ulK~Z>tbDB=>zcAD+SVXHtf4nFRHw#-UPMzlbAtZ0F)K z=^V$bp)^pC7~F@_-Brqf)t)`0MvQ}7`V8(H#Up_6_i}95@&6$9!1T143EPKv;7+5s zmN5&en+wK@Ev|s&gYY~^BoJEwC|y*@1!awe`S#7Ktc5l3XCAwyH>!&|g2acD6y}Nz z`GhDJ7X%Fj*0@8-^-YMUZ|?wmkm#&d^e`$x!eUQc**<1I0FRx0{`XCi&dlRP<(i}s zt=e6~@3g%^{jzS7&pKMqTRf)uV;)3f~$|L?@7l|sNN|i zOoc^QDsl$l8?AZnzS#ZHpOk#;47nJ0PJA5I0>N4gprZ9hRjY9@C_pFMTqOr;_a-Ui z^7J}5@2k+Tn(h9O*6FniuEU8|jQ;vHw@G4eiPhpY|M-y=M=gK{()RuA*v|^T zJd(whqv;M-#wB)%xE5{%9rMis6W{*COJSAx{`&sXmU7b=oyM%G`0;}NNyXi|tFxC@ zs6{$^Xs(79R8>zE0HB2m(}j^4+uakcwx^l9z#LlI6>&HC?av_}O{D(XHDG+?n9Qh< zos#CE+DZbPJWzuG&%~=jRu0U&BCrqlkM0b2BBmEp{9RNERL?gjyV8P8*XKb=S78#O zE~*9v5rTC8j1_WQSzAM}qzJxqDBob3j-UD5wT?lSS3xAIe7P$pHXB zJXzk zvB8Up=;?!R=e5<9PVFy6^_x%)(q`Y<9XS5w6LRm0t;>Q?+v-KtR=Gd>ho=-uA3wY! zdcL2e{|_VE+w3mNZ_Q0MK1$yBz+pau>pwQxBS!Ry<+d|YwS+M#{=XIC{N#_X$C3&ztIBw~yYWULl&)E@ZKE zR5lvy++y+VxI1fDetFsNsMFolG|p5--pYcPXuoNpHA~aN9e;bsOr#=Qyr-5w98jJa2 z=U&F@n7CfVHE3q5iMjW+Z3>^_+SEj+lan6M*(4mwPbr zAC%b-P@Uq0^Ck!?4(_TzgfItgTQovUU5#wun#*L(pi+^LQm1tK7U z!eRk9z7j~_EZBRU0eP@@m~y-~{b{i;6{Jxs<4;GUz1oasA#sa&zxp(=|`tQD_ABYU`^IKT^qE?zD~S;A11Ff_EgO9%sL zeY))2wrwc3Ew9a16YMGihx8QJ+uW6spn4Qm>)W<*m1_MMTyjMLMR2?5iO=&Gn6sYe zvy=((ylI}0UWvsLC(0TDM?a8>| zv0TlqW8g|D^PvXGbecFH!<7yXkqeX%R3OhKcVjaE%~PyIaSU&g9KF1q7u8kSJu0KO?W-i4q!4Z1pLvo#>hq?9L!=^(0bN5y3%{qg$PmCL5|D%*NT!PZeS4m_ zG^8Hq>BF@7h3DGLf?OE6+Je?nZ3{}Kk(1(pms7Q^gtd)a5#9_T(v^r5Wh=_26czX+ zadU{jvo1=Z<4x^#6f|HA;tPZPsd3LEc{usI9rf85-h+Iu>lCx0Fu4L?Dh}#i0nN?A zt-XZ)fQRsxmrBR-m7WcAXA9vlP;k;luXPfXy3BD{fsBno+yn*Na9|=IWCqYITyYT2 zY3<7bKdD!uZslRun9+W>sv^~uW(^5=u>Y)LbPp#oleOX3^c{TehBLCknPI~~P{J3S z9+77wswa|BhmS#{$eQdRFBT05W8}gZK(*!ar3zFujYY<>7}!VC6$^)UbYrdgz zhR68z(fp))XGXNxqVO#QoDY%XyzN2?ViatbRz3=S@f7WI+8%U`wI;Uu=jg z5j5E!-3;Tp#sJkN43v-^FajBxiTzHMfrtoc7MS zqno@JV1zZ6y@c)D1FXY=Hh2NONiVMP*zIH`B5zD&AC}!SSXXw(bRHDd46F?e7LYuU zghGC5T;c3}$Ie>CJf-x0TDBOZSfG?hSUx_99M&i$Ho z#62HaG(M~wMztokYM|K0IMdq2QLTWy+fl5Hm-i}x@wq@P_%4D>dJ{4b^dcEV_5#;c z!lTS%e`RnD8C&IDYsy6r+C_1jpM#cdK})}P!G=c}^N?dYu$1_h7o(Xblrl=s&Qc+i zkim-VLAp@d_7`x9u3Tf(BRB8PbCJxu+ATh7sF?qTOYS8EE|0zgvJFvBxiGLHotwSJ zwxP$ewI|B-UzYw;)KQ`T*O$Z+0@#o|%xzxu-OVHNKtU(-%_Q@&->0+8%T1HmCe&?T z&0t?_;eMv<96C307t9z2PI{GRC+^5oYoKINc*HB@&v_=F$I*rj zE=vIN^8hs}a8<}iIK*6F08Cq3+;b=4Fpi&;vmQZ!-gMsRMdU_`jrYePeP$sO285~Z ztqpw-s^wm>*&J6oXmua#V*|%i#|I{fn_@DqmNOhHWApg)xDkR817yx)YD$1EJrF+$ zB!CX33ZT8`awBDmP$F33*zLaRu=L>lpBl~sV(f7?*Bbxo)v?!4_9J%X11td0$(DB! zc&fb5J0&^_&A$$|0IE8tj8ypyba5H6P@1NMLjmR8;>S%@w_%u8Z}P@R=NxbZf1E- z-W$LIqX^uyK(01^gWRL)6DjL++WrUo?IQ#$8mR^*`b5Nr6^P%*@Yfw-Y!TCiDA~F{ zXjZ9eqD#?;Z>aLezy|T&=qYe3zw!PVz!tt?g#nC2V*BwIUt>;(Q(3mOE73%@euepB zOG@0XR3siWsUws1a2+YZp3_V(<^9_~RF~Jgrydk00TDQXf};ee-5gp)wmWzNi1lJU zB6XXg*ggbE<&Jh3wOmqgq6;n;^l(O3RWM^5Z0I=UbGYFvOq#jd(P_QpoTg z13S4F8f`jkez;OU@UD0JQBW^XD+4&53#binYRs%0-<^-~O36Gx00%su6R}v9kne&= zJOS5-*K9@ShV#dX!p^1Ww5-F+^|Ww25lq?!GFo%*R5`>GL2+kCdE!<$Ju#{|kvR5j zN(mmP#R{Qw9V93h68QN9&_~Ky(+YFubMk`&^2Qj8EAPNf<=*!ZhfZlS9AIPsczv_E zU|SC)f^Hqs39;^p{LD~0x*O)75kVaLSA|>6@VZW)qJ1XFi>#r|+?2V?>zYBA_!^3o zAKDaNTTwnmpq8i(_n|TIB9O%xc!=7TTK~X%y-m;*rXyfh=N!b{Lr_mpqY))5_y9AE#G@nFs{hLEk^!x|{I5~@D4S-Rv?T_6%xL9zJd1*qw zSjrz0^Dsui?MbV;qXlTiq?xrOAz1!esA_Xpp4g*sg9D4cEMedFGTjqwbCm^#S8Rwg zZ*kkh;=pT?Fx6uSjA`!n(!DV+gF#SqacWnm%FC7^4HZ#%^Ex2xzP9=Hn7#DgcsL~o zTTaw?M;tG+I&jdd)#Metv_E(v0mDtF)i^x{ z1lmWtJKo*b$1GFL$$DKJ4v!(|D}n0K(=V60H2Z6QGARj%NVDW;m9wlbHam zAGq2W#Ix|AF!yab3FE5GLK{ZRd~~{owd-e@s-f%KiOg_H>MCg<(xI^{e1}EBEq8dJ zOVeD`wpQ-b5HxaLe`8$q>zKN=DS)^-tN}u6&Q(+yA7q$; zby%?E#<0-$qM->X>cWZV9UQ#b9e(`PO8=+GsSOxhs(f%N~$NkIY`a-eIwgb>G$N8a< zf1J+@hL{|m&uVn=6sg{(|Ly#K{nqr?yv**fvXFBO@X(i?9yh;%r#yz$LTDhvR698f z;XI-Kx;D0vF4qq*_57>KBfWeDS`R4Pay|G0IZLL?(KjGkR-A><0ogVM{;2Xbw{|sK zsC5!ZdtOD!m!PNX2SwQjJ2Yey#cWmDXq4H4xVnkcy+AqGe!E z>8deMb&v)RTx5iJ(pfk}hrGuxPd@VV65fF21;<(Ca*&PvZ$*$mSWTu{g+5kE#{wZ5 zfThNfl}XpSRlx-00)b-^u8$i`WW-T7Z6!)UP0YfTX}_b|(#R49()!je}<7_jfH4(*uYOGOuXu$w-^an1<_HB@HQ-&y(FmK%iw2_C+CD<9l#4YzA)fIDM< zMnyAehGuKY`;wWgG-zm>NrH~A?8&R3YlLDHP}zB|Qxxyfp*i2W|7`w!fkng>?#tA~ z9|q4pD!F624vxWg59;K6?Y{o*jCrOtc*os4k52XGUrwDhj%EGK?_d99KsdS7_7s5a zAu#3!GLA`fKEJZN4lSHxY%+^`%)3T7+}V00a4T!ox#yI$bT>jkQm>Vj_^&-HCz zP`#3&hu&{lu*+=M>3ZCt^-asdw3wHL?@70u*H`nIutgo&aLwu7SaE*)qQS982fTM% zmDQ!b9E1bh!f#rYUuj=b*w=e|$GVlE%aK7W?Y)z@@k+&X`);$k%)9&T4pqG{+e5td z_%;Z?T6($fq2u(?`zMyZ;DP_dZA%H0X#8!>S3Di>3J#mJPWxKNZ0B_aM75ofd)uH> zne6Y|JAHoLrrFK>ZBS|7Orx5u9syYpadC3TO3pqWhWAGmQhtgH&q(c{roh08zkNb44ie}p5a+hnL) zyB`U=_6Ntj7Hz`3s)!@qA(;T(sWb@d_lsAJy#>nWKSkfss=ym9+&HTgbo5mJi$6*v zw7he1({0j{e(#7kEBULtK3*{Q@%uG)WPa4sS~a=mINQnFCq7D=9X^6J{;rC@!vo5y zx@$^z+t?L=>pJ4)?$K{IAC;x(8ZthCDI8I*)8|2B@oFCKI8cSQ7INt3m-Bxdm)$o1 znk>EfwQ-x%+mOq@9$dNk?b0cy_q#U#{rHD1{{MoIfx%z}1%>|;A(KUReSCZ(BO_%9 zS!!zP$&)Al6Cr!{FG42w-x0D`K-{`IZdDFF2h^Vim^_A<$PlvIK$~HR^8*Fj_iF!> zBKtSEOR)PNwcUD9beBA(Pd!>jkyV0|F2Mf{?w*DoIjj6{aJLnkbXhyK+i?GwiuVHo z<(-|^ZQJB^PtPA@&oyt#e+GAdghjt|kC<~$n)W;LE;Q+Vc=Er^-K3-+w13OHANTw> zoJ^r2OZ9)^WLWGUZEYFd_P@t>eKG&CWZ@hB#mRP={1;1h%XO{Ygpr zlb-%ZR^DYJvSs)GEbpGt{;%?Gu71T?s|s0mx6vxE-#xp-uR>Pa9SzQx)pnm8uDG+O zVktHIKS8o@$FpCa{I|AS81`>!_e{*_f3jq<&TiN7e_68Z|F^SST3Y&l1<5}A2S~=@ z{Q2*Z-L|$rSFip@WVc{c*4e#N`oDB`U$%~ZxcXl#+5ZNT4G;ghbLY?W^q;3s|12#n z$x^#7U;cUj{?FHcZ~y-U$z%xGq5rQUyA*><{{tbbKWuuIy*+9u&m#&S>?MC%&5oWv z1!(J_*C-Jk9>vF=ZU<3qy;8`JI9C+h704t2Kn|p;AUjK&6oUaUENYqH^7OXfI}9;; zb-yPhOxYqzxbl#B4SN78EvP)h2m>jT3^RPiW_Nmu_J;%TpKD{TU|=}D-6Mtv6tEcV zF0)^B_n*+(a{Db{mlwE5UGn!?+LGKcR3DpV7JSO?i$SDL7#iS z$X|T-n9Pp3h+EDJuE&T-2egX?X{7T!K}C$1mGgBexjhaeJYHVoOLFVpZ>~5KM~OH zB}hE))L9)@xUW1`zo^W(iG1|17s_-?_M3S!KDZkvP%}OVa7C(YM}bBxrQ~Yi^LmZq zQq}YbQ(&{Mgg33Ixm30ucJSd6IUhpQj>}d`e?e{stjxK>RKjr}Ios?vMOA9oQkw5f zgsQiJR7GA9?cyU5mk(Hi7`r6hJ`6Uh_Q<1loqO?@z;H>tBnfN}VD#ZyFyy0G9j8<| zvy+(dD)g)1xqWx#-j@jZX5Z(`5dCAjGT++^>%iYswZ#VxhaHvW5-ff!lk+|=MN|PZ zc29yfPQ_Orx-uEhxQKimTp=djdiwDy)TUNkV%lr)PF!`ErbcJpsDp%E7+3*{0netQ^m^uxDDv>fyAvk7PSeSe(Pbn*L>)N3EU&(Tkr zC*BKxbo#-RwjzbR4$OExb?q5L@7qyNu=ton$~3Z2Sx`sQdRz)jE$jn}kCxlsYYVva zlX4~`y^7n481{PTxqp9FV0FYVQsxFYxQ|qw->BJZ7p}rQ$VXQ)-W1Y5jGS)s70I8qxHWQLz;o)Lg*2{1@ ze!TC3qh+QUYRG`b%-6EAI_s$6rjoGA+3Gh~F{Q6*E8lr9FD3+J-waX_%9b27T{Y4= zP|xJhX9OW;0qe8I(Kqw*F!wxYROh9K**5^Uro^2O#=9A=R5;kPLX6`1Ad_?UaPW@M zy&t~L1wsZ`+PomOD#DP;D{rWEYONY^U<5PPESnnYU@>Lxx>PbJUCF#&=L}49dj=Z; z&{69^d2IC4$#2YB!0ez5Vuh06fOD=GyL4zcvNr639Y>|wZ->fZ7SfagRKG-S(vd{k z3V+o@o|ZD8<>CpLkO2*eZGadO!wAcVK~y12^`>|N4%1aUOLA8-^J0c5)VE>Ly1HqD za6+oCdOghr;2$j69aKI}9y!o~h#8Lpz>Cfd!%T>*i-Yc1igeg?89(Poz$gV0!AbHhSXCdX z+|#OI2V(%j4+ervTw$u5r-9xW1{OZqun#iW+7Fj>T}_rXh&yHTMgKnPNAt#U*t z=qd`vh7AXaIU(sGc=1Tb2}@SKG45>l>Cgif6ZSAd{XlQcjayZ7W}w(rE$P{6 zRxTWADhfrMyfL&swRMn824clXxIS#f+~PTaQF zDQNR$>V~q4XKn+&IiHKwNXobzYxlu1G9^07C=edR1MQvs9kID!K!HuOFg}iqiAiuh zPvNsJw5>o5%7{&g43;5T69cMm0hCQ>2ae_D9BrM%cS#|d!~Eo|Jm6^a#adHg%wXtK z7p1)!t}0^;m^Xoxx$%-Yikt?6?98|`QzeUp<*=|Jm%*P42mQ|6;uvvyuljji0lqk% zZ8I~^qc;z#IBGE;uiK&`#?n>SYfTRLg}P?y(l$rm;=gFlq^J%@6|(m~Ds>|;RT`W3 zDSzLS-&7da@b&7ThMh}LpnDur)hlbOQ=FVI-vt|S7-}S5p~Lxust|*HkVO&@d-Nwf zke8xqsc^)A)E-KBp*0js{&DlXgm@2o4vN}jeETj{(=U6HNSwMEJMCKFYwHq zK#_IUj-}bwA?*+r_&EmN&Nkq zI!J+ZPoP+i13>oDd}Kw+K-7VgVe)4Hr&P%x_CxT5H9YEprz#Qty2;VMJT^)SwGziC z9XVzujW83&qUed^*yD#IsB7OL!6K*)EojH#Ef0?Ddu$lI)dk^0lm8wbZG-o3Ain7QoUhazxG#(eBK}-puXT9S>w(|X8z{prz_#xim@hcz;z>&iq$BuPDg1OY*0=o&em^$^`Hf-mUjj=O;?452FD(Dvact{sWm)E!+f-tqqM$>()BGhYA!_%MnT zG_eari(qxi$4^+pa_H^}1d?|nIz%6GN}MP23ajGbc0b~VY*8Ju@r{164ii~Uck#vt z2H{yoH97hT$ZC4pHM_uQaZHWuytaE!MzeepF^fDJ5lV;KQdnJwBTB|V*S0|LOt31& z8<2ilBh4em?#QxjQdV}3t2pNMu+y>tS&f25NrN6_ppTGGPpU!B3o-VFMRlTec(Qos z4;(ZcAlG*WCIbd80}z=E#54Vqu|f!oaG?HL(9=?2Q(_ra?4(RN8jq(KWuk<_y;`Bz z``^&&w7BS75kCcv_H)f}HE-j*WbS zma}uMwXej87RG_`+K#SQh zYf|>Gz%gY71Xn|t5g}Z9lsg3ZYAwvx$`tksV0Y0CONI!z85MV6nae_#dSOfS$70B+!W8=1g=Hw`QlDrIK z0_F}&`n^y%76mN)iue{uAu`J_G+%*b zXyajMJ^f@o5w=efF#@k1=R)ZKxf4Etyxx@k8BiHi^|U@m_mvR7Tyr%F>lF#i1crajC&RN8$k?X_g+lx=@`$_%1-w z`{Z+otW!(h)2i{vuURNe8P@?1nqXhjt+|vj9>nEBdx+rD2biiAN`$m(d>ULqt2ql* zr_Eee(m{gr{L_}!K{9rsY010TqfWl%sGduQ6rS?J5sJ)xA&UOdum zEwYCW43?xyoHXt3hIJ`KG0AEIdKak zVq}L1;g2eiT-0tXAV7o<+)e3?h(q*nDwx9PP7<(?i{_|B1YSqSnmTQF2dC0#n*p+J zI5L5s>N6466$Yy3An$rZFAG)cg+MC@^b!^r)9UE90@*34Q4T7cmG9Xz6jN z4Bdp^UL%A)F-TC9(Rjq_@gcciS%VMru`T(sbVE?|*}rtqv30hcLRE2L}-k=d`pf$M?Bg~LmZYszm_#&$q0+I8|#aQT$+VYGgSBs0>)B1 z!iXPRrwU8rQ|~~_R+kV}v>mcMZ`(0X_H}d?K@dwLqs5S`zJ≻MieUHv{SR=GG|% zu~~87I5@lOO!;PoA$Tgg$7Xb@L9U{)b;6T+Istx^PxIC(a^ZwkGoXD-d*cmI%?uef zlf_#*eM%jAXl^1{8+!y5&ayu@&IWgx4SwG}^!;Jhj8|fln3}_v+f9_?Wt;;0dOLtS zF(}Bz1en+nNaMrL?Yj~hv#}hsUV$V^p!QMlUOhOx%u$yg)|+{79GV=el1 zZuaZF$eFOoa<~<6>_=}wtO!maHh%gW<4RixZsZ5>!@P9(Tb&g zOW@Q8_FfeUG@9;XyL!T?8l|gpkB+Xyh)>yZWLW_@X~kWl3u2%NVmeo0Q!|OOyj3z` zqgd@YT;=E}3R?@4qrRCK?4zp)WwbDR*tQ{va4EFUx|Dci6DmRofX0h&ZXTHa5EAVx zoeZFXj?l0oX#@&^?mGngMitNV3y$ zq4SX*G5wb47W5lb#D)^b_35x0v6C?!v{~3Tc;fM^4nUC}b4!qy9|M`4bV7{_X99+=Y?0SRQG-#r*D`E%T+E0F^=y!Z0>%pk zS~+~}Fn{QYEfD+@5<-U_KMvO7g9|s9I3f|rsDsV6@(0CEkJ88XY`_fZ&4oJNwih1t zGDpdUgK8=r9K@-d9@@XrlFhXz_A5vf=pD0V`wmK?rB*t=)9ent4vjf=jm|zJ6 zU<7ocxnNN*C122hD=@9PeWaR>Zz-pyV$u20QM8;me}3Gn_Y%^PlQn#~cyR>=1p=|l zI=?sVr9syd7;-su`FhD73grq$I+!kooD?oCd_f~bTiy&VkR~B(jnDx6kz>E`} z*T!PhA|4J=SSu}G^wWh>`JL5^&E687<+iJ(~-5>acfd zA(C_VKSQrQ0M3-Ynz)jz9txlIaXQFI4WjRV8i7(Qd>b_x)E|QErXx<$5obhTZ%N}0 zKDglP)Eys`Hxjx_czGuv^Hb<6SuWyMs`#rmaGxpAK)BR^54&*Au?&T*BExL);LH)e zuUL+T3cHpAdVCaqneteG9zu~{U%VOLdJLtf1qEz?&4fUH?t6UQ0{u_jJ4L4K;rgeu zO6c*ez-E4~pT+(NK+?K;eES`${)dal%v}yBOI&qfp!M+`~thG@U~h_>`dEJRjQnodQ5H=Nh9JP!QKTeLgQR&_#E@>8xwqUr#%fs|{y zI~%-Sp!Tc-)zj+JByyXQpKHhvGRHy@1HQO>|Btf1EWCA(U(Y)A#*4QI;}gKGQmG?S zF6%^=uTn)f1z8vkFDdj5R{r#9Kf2~8Xa|28>(XLD{tH6~#WCRLr7K5o%UgJ4j^s~F3`^vS5C^9re6q6#?n)xX4ZrAjI7brD&;D+_TP(1*zf^&`s z@%%8FoZ!|kdEo7ErENV@coHKum?F115%qEILD-kMPE}|q|I1+p-17TES|Tt&^eyD~ zYDm!%UK^MxMPW<=0ILZygbZrnHIdjBQfV11B=Fn;eahSALbY`<}bM*-PWH98I-lhs;6_yv{;%)r&uRubfmpWwR2x zceFWVXWwVGfzo|=ppy6Ayw72prpkAZ=*UKUF6D&8eXfTR^;L}Hr|7NRN!8%m6r=?+ zc*)Nw+NM}!i+T7qe)RN)I)$OpFoc4$o!!W{JW7>O`t8*9tsVm}<aE0moZc;@W3|(8{>f^eE8Cd|jAo5~IrxF?`o*E}uocQcZ$u3d1TTGfrITY-o z-*)4ayfW5L%jatBlP95uN3qz=G_38W^Ig9M7lYdLNwqmo@Fx^b1TEweuEHn^0rWHj z5F*c4BAiZ|Fe|lcW`Lk<-L-|12zsVZ4$ED**&TgxYP?Q9j@7_t8d4WHEGlKN2OZma zU{rI%A#PK>+~@oeCP7rEbLa=4O?lwyp30K%o9Vp9_CpX!|Ttj?{(-Nz52!np5ELUxGjjO$Q|B$(BO6# zfgcA~JLx_WSa7did1~Zf3>@XwF(VTkm39K|R~k;<4{=qjoem0dJHC{Q|9EvAqvp&w z6vUqCsV8nXP*jeL&L^hyzRy3m)@~!iZQ=eyI0^$bPXrC~C{(#D%ObmLf0pjFKKgaKlC()L3$5nUQ89 zA`U1vefWt52>7c${3Khx{z{AUq^CU#ZD^cPu4~`(Y8DfNfId z6IAy&H9BtHf~+-e?TJ^gx<`Il;%E0}QPmkyvgo5k5iyMr2n}}rXbok-!_*M7v}+V_ z;d!98$?UvpfKr89p{fJB7R>hKf6r#Er8@mn;A-qu6d=29m)b~(yA&+jg|2zMcQji~ z&BM)Pl74_Qfy5;3Y#zj}XK|o4;!&kVpVQ0DSJ^Cqct5lSh;Sy?KkzVB+7P-Ec6U1} ze|}J{gTXZ-4M4PJfr`<~B?{&0*Udx&NZnjlMMS6Et8cQY0BJ~vM)hH-3z5Y0=Z!nlKXVeQr zp+emOzoGN4vRJSUt<~RJ>o$K7>E~n}Wrx>7J3j|dT|)?_Rp z!qgxYCo~N*NUIRFF)5UpJ_8$2^Uqq)w<^zYWk~q>VQE-B-SH=(yN#J2$MmZM?VFF1 zR}EPzGeOBZJmt6cL9VL=5L!T%IS1~?)B_QfGzE;SRPu{BiiQHjCKk0Y5DJeWdN1$& z-h-JrArFC$>v|mC+pzm!JY1Xn)MG0UYE3GzY^RL?Lo1QtDpIwJcz|E-!$53>3H<5f zZt?%f~NKG*Et*beM^=>q2iuH&NbW-($TmSt=F$U=E z-B;d`vM z1@CDk2UX)JH?@%&wOvEj3_xs3AijU>0i_>q%haW3TLAmo}w1#aCjFK zIoROx!N_8aCTHHkGV;za3DpYS^><5K`v+)_A%qFNAh311z7iQBbtO#xTs;SL+**_* zeYmQ6mnG7FpKyQd48{whA`qi_oS;0dTUB+UF){~&nf6^~3 zMl(~-&OQ5TSqV8W%syWA==Qd`(5r8DMfb*! zl?UdUNFgM$BTQu%O@%`XIesa_pzUTXfkni8Q#uU`91$i_vYWvojx;%ZV&hQ z{<(gE(Kybc30J>p{N0lG?gxL!bLZKj-y!a4&8o}mPOC5GNdeN2#o-aj%0`kQ>D`A6YvI#DgJ_ucrl(zOu~5pwI&i32aRm29Ka`D-KOC2VFpYQA5-T2}^Hh2l(Vh|V`nQY>P&_8r!bK1>+ ztoNcdGgPl!;ra7z0!U6gU=NDakT0z&5N~6P`kd_{KKWgL>duqHV50MiGz(p$nUpIKn3c-YwYpl^w>SLUr z#03b<<(7LsNlKfd&m&8!3O<*8g#te`jYOv0ywP7z88w)Hbq9BKBP}f_DLaIWdNU67=YfoqE}nL{+)xSC zcLemrZ$4l>a+>F|tHPyn4LCb#+ZU&0Do`{_E;~Eh9Q(z6TV|twByy7u!l4HoB7r$C zgK9NhW`=UXf{Ur`7h`%ZMhm$yR4%XwI?-u%r&T>PiK!$4C^7&@JX5m{?)s#rFH_k< z#5z`{!=kWWKZcMcK;!imSsa+b!e7|+zSMnI#j{SZF^;8L3^rJ1;T5W1yXMZh!lhSo zA57O*)0pPXxy%yA?ow{WUa(%i60rwlNHb)KwFnu?_EuviaP}DmP25+wk9fq+zWkCD z=Q9rJ&fW! z?*l`FjVQI~{&7QHSfsJJ9MFej)dIuhgTX zAXa!%cT%%Rr8uDspu}f)&mg_=Tt67ZF3GvzAhVvYikM|%ngO{7Z?Ee0CAQ<;B(|Dm z@b#O;E@*dlBHSt`B)d_L_(gHIyHm z3Nqk<&qgcWPSby9Wjz~n+KQn$(hLnCu{$$(COB~KSd~Ai?KUwmMxRHqx;Bk%c?(f{ zDR67YLjz^4TomV1@fNn2u_+lOiyfK7Y46eqcxU5gz|iz&K;bp05-+xY4+K%nvKCed zL>_D$Wf*%mUzS2dfr6LWAq1#14!WwF=ROAU>w&nC$~KEH{P|guBe69g+w`^o>;y6v z4*bMdV1%prrbl`CyO_menBg?6#1QIOffWvJD&g#{hex28_siB11@(wZF~I-veOB%n zbvS>cF3%3dwi1B<8e>z*s7vH377yqY%HKT8x?hF%rGOk5)0@62IlTd>Ewgf)p-LTG zzh)4RPiblUOTga_7X$9b6es>>5y!fn=svABf!+XU-sG)zGoCtyCGFQkzv;s<{2USs zI^6{M8BhZ*$nfx#>pz1Pd>8!{nK}yUQ){wC$U45)S*CcjV6e$}PAZm5ZRVC~RRw#w z>6|Wvqh$CAhk|42CFO=)2b_&m*tTXK^sO+2q3Qf{ntU2$&G%Y09XQLs_v82N_(@D8 z%4#bPY$^Z+<}vKDct>?*?Pk^wJ>GyGPi>vTiZRDomXd??M}8FKQl*e=0ccu>oO+^w zp$Bs!vJLi4Wz|e=cR9WGHMiwXH)R&$-@~z#@e_FP-Ggovzq~{Uc9zE`I zD#$kw75YkQ_U)Sen+QW?u%E#qvRY>Ir9FPb)Y@4VRSNX1_x3b{8AxoIdR;6O-#CLU z`(QV`89sLyF>1-P7~_PUDHnFZI=H!~aWX6uWSFaImI=OZD$o=H&Wiy~Jz$41I~N#) zodh-^`JFfp^F2{?ZtBVC7zb>t)oBo2!GjtTh4oT~5e-aX$lyG%8sPleZ=8d1A(b*4 zJH+*&HVhmtFeLu9ep6d>*r1XsVX*`Ntbm~eC{?2abhTTQ9l9*2didE}(VHAxh)J6)?o|mu5dQTw4Ip#_bqg_F3Edbm8gsPnl1+ zhx6W!z+wc?3&>!??2b_e^JvhyMT5#Q5lM48xC`gmglnyR+xVL)v}|U5@5&1%#5xq* zOlvs1DmEfTvJ7OzCKY4?m=o}2@2Bl0k9Vb(HGq-UuJYPt?a6Q55D*YC zQ~^;#Q@{o&f;}oK)*B0ow~8nC^Souhdp~=hebzer%UNfweB={rW|En?e%Ie#HAoD% zWPxU6#1}&o|8ig%!;lLU#O@Q^ii24?aDBz*35MZOBPSP*Gwg2)tMWJDzA8sIw4(sX z<|x7tshVHLtGrLZlmW^DWx`z1oRp=O&88X&6a^ehG0fo}S6=xfNjblENNGt4O}(t= z`{NN`>D~^!0R1Q5Iv{*fq;ubG_|@M3FEDT( zrC$Wmu$y``z4Z294nA7B=CRblg?(U`%H{o_xkysDNqfsF9PeC*j48C@S_}tNXS0kC&4#uTP;g z5Pr=5z>z>j?bG=Vd;^Er{aLo*4sfgH6(_72t?=YO%MjWUZXxlWLpm~s%UwN=NWZ%_ z&bxGF2H%x+?jo_qp%=CcfZ<63Z7JN1$or5KX##gg0tL+lfZ7OXAy8HaRLm1Nb~7AH z)-pXQtD*Mp>U_R!IPD>;gB4;F|L< z3c8h4`(mO<-0B8aY^%5EXr;QK7==w)@<(s=-$FhjgSFjx!EA#3=5OZIV*JZY9bTsT z)C=hv9QkgjgA)1*a@vsbOodExtV+G*efg$)10*l_^+WwPT3EV*ke*S%{rHM~Nw13i zQ#n$W_RMitBu9_T52xtSkf1(E{x&C8ey_&iY#FBTBX@2e7QH?{$}`VKntO5iLXNKt ztD-z=_U3J)7l<8UryPwm1K#b)+g>i=+w-23jTax4@)zpBxk_Q1lA6ZDv@`oJTgk7x zM_CjNUfvaaeCdkQhlf$DRWRfHZNyiE$b zlfKI25_%>a^c8t*=?ga?!p!btnvD`1rv>TTP}3dT)Q_>07&RS)cN}&vhnB3-x@rIQ z(|;TW>>EIH)@ogRnq4=z+AA^i8Nxy}nyR z?^Y%idAa%H8uBo3|HU;g_;OHSLknvL2YH4$v)7=r6$Z;Y~&ma|xdc|3}oq-UwI*Z*3s zdiTD)?5{{s)KRYE41B#;BnJy~E`zT-%%Mnn4k7u7c&^>-$~W_ZXdmwH_~SeuU}WrU zw8$c}&*BbqK~RA+t3s`x$HWFz{YcC(UA!0VrLuwe5!egH-bN-(DsaZDrbVj;8t59*OIt4-4RPD3CtRR zb46@ZMwXGr)~v(RX1duEk4roX`2s%2n(@;+xnOJ{vn$g)Vkl>?&+VlHllJ4Fe>Qm1 zVnyLP!muZ$Km_l4aK3gX0X>&z)38JSO}3f@4b}T>Ojez)1*kG+4QZ#Pf5eeF=^PVA z>sZUlk{|O2W|Ne>NUT$St3pl=(^BWl(YL2A)yfy`07z0rCT^#liz{S+SJNuA z9Tnihdg4<8i-v=(qAPnz6Pcr-F5Y<5%S@x9#L;4e$!kjHWC)*6bxj#-rMc!B(Zm)# zJ=ozQ=fovN{#i}IebkNx?3uYnk@bfSAm&jrYOaY;aBLbsMp)Fgc z+g^;lO6C_v#{|xsHd;RJGsNlC5^c9>k^HT3B|C2mo^%Jn-Edrtdc7&f&V4Fpsy4bT zJ#cs|_{(5LO^xT1pM_^`mzww>r`q0WrQV<3lW?u&?Cv`*sNxx|T=QxB^yuI|?F>E7 zI!#ijSZun7EI)KFC)x4a8r3RDw3eM<%U#vOmAmbpR8ddZ?nSB93UKtWfnuB1zH9aV zE5H8w8NSXrBk=jR(AoWx$^&hhH9Xz@qx@?cfdw#k%^vNVA=938*um&y?-KbYNlZ@# z3n)HGgdh~yj{18Mh7?uOc;{(;ue}+A8ZlK88e++Zx!GOMOxRtze?twSR`ks%9##Mx z4(HJb*l@$B(_f5qeY(SO?wJW`pAajHonHA^UUP}d)u2%`JW^?)d;xyrNRURs?iXM_ zf!_Ce5Lz!FSp?sun!~0VDGXva?O5c=&nlh`WV&?NgMTF`9YR z-^2;WSLgePhXT$VSo^weLuizF>6;chu`+CC5yJMvDSv( zt&*KiEQ&xx~Xx|o#TiYrO0DK zeV^th6Xd9cyRLe(?&_`^2bv=gu>q+eCJ&q^IJ6I(2HOzB0Fk)5_UGD_`-`4^8q*%# zo8jTV#?(63xRVkcHTmtuvMzd7T9suf<6CHdK0ZCN)R6P6)gUB zDw#mg_aJQiX~9+xn%~*FH793t?{mYojmL&D-ZwJd5{9Z}p_>SiP0xdIHvPBcJK1|g zgU_DbbG3RmyC+a%`k>{Teb<_o!cc1p0sA|6me>X5o^Bqpa?Ml8#peeemdHoh4n{Vc zcMoxznc1sPu8TVRwtgB~6GQA~x+|8gFq#i@f9Cq-o8|H0IpeV$|IZI!ZD==)L70t1|Zh!#V==<3>w-5u4-7khdK9*Yw(qfSYIBivblZ8 zBD2u^Q35imIlN!&zR%b;=k;}F&<;5ZGPW1)xe-EvW&{Ga;DtF3WxPFmQIn z9Txu70W2$7+TIlI?xQ0Lba!ASc>2E%SZ8{>b>3DTN#j$`pzTA53=7Q{4}iR}^P#mR zK>G+}nK@?NhBs`gqDuWV=aC!>Db6Q&C`^qQn&%h~L+s&&FM0q+->4*~-Ed!n!UKb@ zcIR^34M3@W#D$mfO+6y>7}Na55uYyLFsTXt6Wx9Z&%?2y2N5ZOK(pCM(1yZxyb3M5QPaHnI6pF}GN@?&YvIweDOTxuksJ$G7~``k zjgRh%dZ@2{o@qLx{1!N2Q`(AfOtotA_4ZT(0C3(i;yP##v5a7Id`-hK{KLCGS(lv% z!7KnE10I5s+9PL6!TakNf2m0?A@`Gc1{P0I!QBIDm&m!Ro1ZS*(LJcUL>9PNJi`@t z4;e27QhYqMHUYVlP>2e~Jnwt6_m8pM4gfxHS@xNB+d{V^!w@PRfT=O>( zQYHNznj)FWLsN1h^vTrj@6Z(Z@1d#xfe6V%Q)Sq!ntu=>iB9STBW9af)~Jg2lv&Vw zd(Uh3De}tHxBnnQ^r#P1x||5z@ymMd&y*{n&(X{u|0quV?-L{}I3@r54Tbjq_e!Xy zrl!5U{lbL{zjJf{nVXU;p$nWV|5QTq+*D=d@7mhm|5QSKeZPkau3Rhnn+Q!+{hgbd zJ#$4)gxp~1m_O@#ix+M1I4pk4pxd{CQBI^&;-san48F|OA?d=NwK zgN~@JW$m1#{HG5pKmrIPMaHm%#i;bI#TNFn00qNk`w{{9tydv(KBf*+G}T>p?CwS1 z!uDbKVS;_U7(2~AzdXY+z0NlXxLayuo$Zu935<0xUk?~jcE5b$f$|FiDBBHUI@IJ) zD0G_T0ReOIJG+6XXIG9_Zrw$sz=pw-OX^4oah@`c#<8Z{#jFpZu*dr3sEM^MinX^6 zS~ci)|E{i_IGqnuo_m&;{;p?Q)v(tc&)QZsL;OX%J169A}9DR%)S z`l6I-RZ5(p-q$rWFb5?G15n!3YkasPrIG^Jy0U;}h`UnwZ`JR?EU;ByN-1!%XB|ZB zKmCZZ<7`_k1w)v7xOe&N8mxKe+%x211dLS?w#nceLa{=WZih0$o-)rlHbfx@_v7|vSHdOQHr4pZO#xHY6DtoLp_ zAjbW$ql7ghWcR2oa|^HbDigx0j`rFD@uJe0-1(bMIh|W!M@ZvueYP#6eYv@uDBn`= zvr_JZj7&%Gvk$p$U6=~r{O>+U8^w_R4?gIs<+q1Br?-B4l>O@L`K9||O?0~%mfON^ zPdI@lm4SM?i_g4GTPA>Sy0Z??OP1R?dLXFV#$S}~eys8;>yY!-XD5zr+vC+c5hNAF zA9iNFmi$Jn^(fE|8-LgO>I41*{?~=5_)2y60fZX8CTF_Ob2jg(nNL6oN`<TnKU&` z$5MYe!@zIv)~Ngn8Dg33;Ungzi&v(d%R%r^poxu3iDcv6k~tyNwV8d=P;akccr;{S z<62B2?^Oe20l6m5$WOD}NsOM%XA!GaL{+u)g5l}i#ozrYxl7JC*mrRAU@pPh@LU7s zOLn)4uUI5p%Z~fvK^a@PEPgWSvTqnR4K%2356$@dZSK^o$Sa2Zfxyt^cE321g z)gr|SI?MNTIv5WXYnwhtSo9P-ryVJ_^M(_gupScjQalsdj?mrV6a(+oacsSATrEZjVi_X|3xKAMM8Juik4< zVr!svtQt#)I0ZAH1ig8VXUQnS82e?Khy@&D(o;_#iyFwI`}9QkTCt_oIOr&)U=#H) zL9(ZWb_w5-QYc&{?=%E9fLcy$w9ov!YO*CVvb0weB$+I5>H$@ET6@MB51iPPU>0ly zI)92`p(^}bFw&-LC>qcl$O3gtC494Jm{PtGPs^qs*#BKUw+#}(r&h>^%lH*#_9%-iT8Gz61{dT6JKv#wE_Ud$t7-E&4KqQjkpXy|1 zrq3Fz{7ano;*x9o&POkxB2k2oND3M$YRllt zp{^xrQl7CAj*}GNg6Usq5yY9Z&-)w!UzbYdWAuCrNj1t;^jM`y#-IPxhAkf-GG1#f za1?WngZ8`~YuBHy@fi>+G!8Ai z2nXJ7VY?thYKVmhm@(p-?)uI?q`#NZPN|}8vDzhsFiOrNmigK5-=&_h!wOscgr0S#3tH;mYB%5 zVSrfm!@7CDG}Hx@6ZS4 zIk7JOV#H?NYqUiQ=hH5oP}yv%|LH)j(y;H zM6$C)${2lnHRe?4;^xP(Xxno5I++V0l*Q5g;5%E#sr?9MAZBxxT8gJXXXf-9yBSle zqj@`39;p`cwQBZ5)HLkp1X|j_ZC{v{^y{TW554bx*OOOll%DU|9p3gLU4K`FhsFI>aIou^NoEzNfSl@F{0s4fybzijQrZd*~Na$17OqM#OPz3f;%O%z2M85y*jFAs`TvY^~h@@}MfW*O$KuntZnLX{fM zcEFZkGRDi0v0p0m6~(GbkagG{)+W1h2w4x{u#NM(t%%MhtgOy@u;;Ybix6bqd~keg zOlF6(8>`^iEN93Kwc%K7uqU={T;VJoe_n!okp%OZ-xwt2nBcNZcVbS?XH2MUjwa^U z&_WlUA54Y>IikH;q(4*vC`5#^pN}+47g$P!DyGiv0Di5!sY9m(ci|Y+^$8}hJ>!b` z9*HamM2>y#ix3V7LkEeV)UqYK+dMT1OOuEwV5pxO16DhZ+QMS|(x8Q675X}mCjhj3 zkae##v6qM`mqCMzA>v%9)oc9ah`WKSxufF`!z-qXyL!3>{St(DF>yJDTpQmY`B73aPSG*6#3N z8nlU+AH_K6GXt6toh@jJr$iWmI^@3?87G0v?)t{PMtxLF{e!Bq`5rEa>Lk&uRFNvc zkkKZ|P9YI6|Maa2)o2VIwlIuOF+>1KI~;LLVIu4_5hD>RP6jJ7X$l##vLh&nEQL8r zHrFkQ6=0?1=U%{QtG4sEN<#BcU`%B;>bA-fX@b_ zYQ{loIu7Rz^ zdNdI8?aFFQV2b8lr>L!=R8?nJiGr8I=0H(Ch2*?pEmk5{Xi}ufdq+!LN%$rj^dY(Y zqMGwg+KD)Hy}dQs6f6G$pV7udUH*=4l^$+XRjC(yH#w+HBA_rDIw%aylPUCF5u96q zO_f3!SOuXL?WlK}HXqt7MZG0tVS1|Ziw&gKFic@3ua4O(hHCl9KjZMO{JUI+4Li?m7MHb3?QK2_y06$Cpl>8VaspF_UEbRb+4pBRB=Ct_Zba ztT8w=pLh?=lC!KcAJega_cQ#z8}+h!Bm^!hujPmDFdxd5#usk@agqxD0zFfewnp+;yK)D9?lNOXI<;b`AT0W zfqBz9IgA-C=tBB6_B1{j>Okg zqPTS3D6fZHMhDQkD+r2quoZBveJ{6TP+3ofgp8J7y7Bj)Mv zp|D;tdN&2xq%KsWpiZLD_}Wp6IK}OqB1+?B3$xq+i`*T8ZHpS{DiMk)xiu)iBn!zm zy-%m*BSlH!aZ*(6`CQwp0}IVpOwV}P0#Fhl!Q6rG+=pW>RNUiLrOqu~oP^)3&+K}P z;#XCqe68F1E$aH$W_$_{jGd3Lk=`QrD{7C!EPl20%91q6cP#x;jp;p;28zKJ*c2>O zE-louTpu3_+a!Uy=qj()^eb9#h&@C;=Lj>E_&V8^F~?7Y=&01CC;QH~Z=tGeqtUT0 z?WBjRl?|Qmt#Ec0g(8v_468;{Zv@v|36IXdV_JxbZKB6GPi8z#B2w0C8q?U8GlfG} zDuxgbzamT+iuN#!(7gzofe9ibogS_}M^W^XOphIeO1IwAehS1J7?mcgsMBG-08<>P zQi&DgKJFNLXty5`MPv=rAK{c4>rR%a#40HEiag?u<8_uCq$s@|^5^K2J5UaBZk=#X z$3l;7V$9&9#?`pnsxnsyGrfDOZK@G^_LThjH2lgI75iC$KL}Ku+IZd4*$+roR)3`M zKsdpLZ($*Gz9!sj!r0xF9(GpiA)=>-|5!yv_w9QqPbOVYa8PKyyk`t#KI12 z>3Yx(PxC-5YrzB&z%l^cmX7w6CPii;a%hTsl%gILqyIdO+`>}0J?df>YnfV#X_cVj zXfgU`e~4Zq&WB!7lN|Lwv0>%Y6^F#DAMRFJ`l{}1&qx4taVb5LW;0kvee7d*cehZq z?Nr^835Z<%@Iw8GiFSoBnnH>gnN36U)S%^>&Yq(C{*0mI?>IEW0VR3@&zQwLMVNO% z8!1O;FXDQ}Z_AG5kjUBRhT+T>RHC?*PE)9)pi4y4Dzuls18;6ghuS+8!dVJ=^LI@9 z2G-Mau>p@PR_{+frnzM0Pn9TS>Wi;|zu?arR>Msp&TB z=uw`0z~-}(4-n>*Gfv)__Fz6nZDuuCZgh&@XO?B*Z0)~Zm8g)=GXDDRxjl9&l~5AtdsIR&Fu zl)&zx1^c=~-O^#2Qn=|7nuS$3b3S;C+q zYwEmCvRMDhOQ7qViERj>DO@`;_{0LcG4flu2*rKdC%O9rsP>gnIM6a(Y8mYxi7De+ zTbE};Lf_hO;p*1I#{QLAw5sfi*$Nnc0~tvC19$uW&z{XUFCU0vGKbjR=Z z*zDM9YsOdav~FB)PWf7YPt6)9}xhyI+|L z$g?=giZ2Mr+{2fKQ7f4}Rd)xk!}AP@RP&?RWlRKm_bko~ZAeK4)m8Fdh|ZH3AYT|6 zUL)02Y@5GK8qRBMF(@ZaoGpLX?MBcsb_G52s`fP~=82HLokFucZ8vnSt0*0P8l0te zzM7#(N+!J|wqG^<@nf|`FQv%Z78O}G=c)F#f_39qY&rAhF` z#u8b-W|^0A3!Qvca)Z*}WE13aphkcU*Q}f4tY5ho5(W%%cKXx*C|#yT;!$o@(;|WX z`dPIkw?k1@F(F;dl~bKXLp4p*vtg2DHbEl8;V<~*4#fUI#;qyyz7dKJUN6Gl)F5BM zbdgzu9+Ue{>M>h3ddFa&+<@~;0tEKGm`(ep0 zZh3!t)XzV;RPy+v8Y$F4WyW_Ozh}$FBeibg=(H=2=;M1n_^C%>>r36;DZ)A|{;G82 zSkb1?#ED$?R4qzdyKC*AyhM=z?CM?G`-HnKjuV;}DR8}pst|zr8^NPrw-!GFe4g5$ zba265T(gl>>V8aIQ{cZhxxt~^EG435`OyN-vOLyp{J>0^aemfIPys@VL+jI*H#sWC z5}nnco7Scc5-{KTx`V+XIUE{N3IB_U3s@c`b*V=y>v1u8M+NahqjL`2;y|X_wXa_u z+^Gh2W)7Rc?TWxi{th9 z))ap7*(NE@RA0~P#9LJd8RZ3e;h8yvt%1^( zE(pKv)7zvIELTi2z>Vwj&ONktv#XBl3O@>)nlcWx8rp1Rvl_Nqc)vs}7GK+T!kl0c zKjHDn7NPcwQf;yjST#>&7g@Llv;?{l9Q2MF3MjSc2_r)^0E8;>a0sH*5I=Bj1`8v} z-UK3zKY5hccM?m`c~(ySyybH&o0Eb8&FtE1p&icvXSwb|voK*;M#HLN=73cl@0Y{W zS@1gndaTb5nsX&&S&Uj(;g{^sAA(?vB!mHi!wMnt8YC`5fj3N7L`jL@n*FK4@6$nJ zCm7^M;#z&7;CyBW(81)m$&pVXY+E88i~|hO&ya8p2C%9a?&T^8zelWr?8RFX*Mu2i zv^>;mrRF2+pKdJH76VtETMQAdkuhazolSh@p}kPiLom&+cdHrQNP<``Z`SFK^qU8i z3lF#Pde}N?ai@Ne8$71`OWL%vrkO{bgdSjwz!flRJ4h1s`%{xz!bi7+4pyWQmYF@T ztIwx@*9|5_L=LDGcqrzj!%hy#?+5>mEE!UW8q$qNwVW$EuTC{P+(85NLY+M&TvIsDxJNQrUx01+my3C zyRqpM<)9fVf&4PoYQrnZ>xxq09$sG1p@>_1^G{Lbf$pK!@0a-p@OQFK%c$J%6QQRF zIt6Ou1T6dJUdJzL6Gljnz%Tx0KfWwe-D;92!3o`D#@c`zXiPX{YSqV5 zFzRu&+$Cs?URQgMaZeO4e63)Dt%hnezG_{Tfe&BSnB;%jxyd`X<+TqFe%08x`GEd~ zw51&Z*Yj!m_q27YH-GyaUEAP$;`i;x>E|mi5+dM-i~w+d{@ojweaxFr60V}Dx1W6I zQYYLM&-<>_4)J8rFPFP166hTJfddXlGF?Jert6^v6v>rkhf;J)FH~*a%U7T*@Ell9 zvxH~dNY)O4TCJ?^da~n@igdQHR;Fx!lFnr9``lETgW5#CiS7vhn31E>udA`#+C|l{ zboE95^dgpnAFEq*LRXD7O+YJ4O5h?y+?d{@{Fy!}&7 zg3J64ag=rlb!E=AFt^1^Zc5Kzo)Dk`_Ll|C*nT1m_9DU+6_<7Kg4X zKmB>UoijDCccJqFgE*>^JR#Wn>?ue<+$X3uK9W?S_m-x+hzU%Ou zIx^_(8n7elr_`+eA+ZD_iqq@(Q;|Z~B;+};?{}9_DJ69mHqgEChrHEX-y%%QI051d z)3QrpSlA{lLEJmcpm966T95Z+E>w&vk+i^$uWlfxLq_lM0^aLImhGae8!qO~QTIPdV=juxK zh-*C8ep#=NU_CQn&E=mVuHwS;TjH(4NI*{hq0HMbvtp!mH^-h_HF6ss_nZ>#g6V({ zF3ocY#7n|w)izA+ei)%`@eC<#aQ4D+rH+!&jFQlvK~=hZ@R@~^8qlOXMNKGbuE5zA zxqhCdO1ikgNw^Y@UOxw?Q*d7<_{b{xrl|80hE-(Q0GxJi0lhkW=%_BC{y~(WpaPK5 z?A5*UOeLH*P^h=KS~O3}(jK%Nh>Vz|Bp$P#_zOB`e3Ii`W7CIb%=uY`?2QDie=I=rg7 z)o}N^LQyYOn8Mt9aExg&OmC>@}4itt3PAiQb6rOHj z!byu{fAqKbQanl{tr5Vm467|vF}=!x(ZZ_x zWEcgA8E*v1zzZ|-PIk?y8hH6LNTNdh_6!WU~fk@u~x z5*r*of~#g+M=Ay1kvAOf1?Sx3hVDc6HEV99!EMAG*WPuzUZ{S40FPY=(Ws^GeT#uT z3hSOcAzx${Fv4>v6*!RK+P2zr%@_n99A?99NN`&Xgw_n(MR2Q@0cwlj{v!dtvop1o z0xXLwDi7O<3g(FVfra4#85l)Y8T>fvqhyq1ekC$rh2)@Ht^>OJ-Y@lnMDv_Y`^y{n z_{`wTrebhhT#9CK66w`qye*>#j!{7NkpE5S8&n1d&Q`lU;O0K+cAElquCWzj0uTQyT5G2U$wZ9ZwXYZ zh=J?N8q^ymO=-O1&KqG3CT0}K5Xj3_Z?%0b#Vg!bT1~))5*E&POK1qdpi3q9qL+l2)PWlUxCNmF<(g!-V@} z$G0j5D2LKgso7aGK~w{1MxokBIDaLff|-woYNr{_$AFZEo_Nq$#!_Z*%*0Q4axT;j zYW$R8bp>?{hQphq9Pa(k%i6D20{(-3A`XZ@Ac*b;$9<3+N6gN;)TyjT`MieRWXH_J zAb&Mc@r{n`{@ACH0$b6NsagSu{_^yo27icKuIF(qdLCgB{sdJ93qCFwFJWm&I5tGY zTM{InRV+ewtga1@A#zD9NXKfzG#P2ljM2NNZLw4uR0hX2fmCe$R<_(A0zq1bOpB01 zn$>Riz*pWp1ozAknPHaxOu6g%vXT|Z!!qM{g;C_9@{!&KFAfJM@S&M`^spYpln^Av znkj4z;%#{r+f>HUk`UJe{Eb)~{2}Gt!qbj1)~mBx>th{!ybzJ`Pc|t$)_QT@h2FR> zZARFA5217+AIVk3@%Qg}-hKnp@YpD`P9CmAk%>^}OlbrXa(VNtE~dl@hFVu0Ask8A zd$f|UM42jaoEqB0Rt!XJ6hL?8UUniNOaEYJwRkn2T_DWH##XFZc9G7f0;&H>qwXb!uw`vfD5i;giSDK3$dJa z6rL+_Qwu+!;t(M30=AU^>SD2b2D=h!G-hxu7bn!FfEL>@(_+Yuk|z^@f0iRxvO>~J zWYZ&j-vRIX^;|zG;z?b&zo@%V#MLAw8y$eO3w((epw;7e3H zh~#EUgTvnU&*{cs=3$*!pFHBJZ2QYWdL=%65zoh2I;<0JSdN?sMJ!g+NPh-*^M#gd zrJ05^S%>Jzm}%Ar!<;bncOiCwrYUnn4DhPoIBnwrl#yJ?j3jSq0f$ad8QTO=61Sf( z@(|Y`lNQdqACK$;#(XGXoEC^EW^tXb$#s^SjM>eM9gN^C@Y&CEkGs319y%^Ra-%Cn z@_4H6pu~iCT)0XKTCmo3Yar}qc4`raObh*)GbQc@)2MS3`w3O#RP7ZPqkbF1VBs8FPy_Htn(eQdHT;ex?K;%sJ zWkd)Y%x@~;Nex*lBygQZDvH68pO(wJ0o865VfqWrLO>&&u*YNPK@JW#f)f{=LVw5kB6#3LMWCP~)+(5#+RI82Y3VxbRF*L)_~lcDtPuNghPwvDxg0Ru{^cqw$I+VHybZ5!jve1obw%RqA9e9YbV(y zWpGWHY%Ofmk|_Y)w7vTo$g>yBvz@=#OEr^D$=MNipbF3?a>-(WrkJy36Ij~v>iwJe z{as&gx8w)wX=(oW+4t1Q(}A_?;qLx7-(m>C{DIr)M}yXkfB`J9Hf`-&QSr^w?i>;K z!goU4C-gc#=lV0tR(E)?!@YA(Nnd3Cm~fu_8a%nQO+@P-Plr_;FOC{PRP}&X7voz2 zq&LKTZ8p;cScM_bHfc<;-q61#rk=z#meM(B~+p5w{+j~PYTJThC%EApiAHEu|DK>v?=c^%pX4GG2qdYPXaFJ%0}RHt{amjw=E>{*)&ImGno>P>kT{Rj7jz6kOlBvRu%tjua^^3|6z!s~<)q0;zV zLSRXpUS4;dT8I(C_$hs5Ku0w^Nom`VtL7%LBoOjNq`2#`3&IWEG;2u4WtEor{@tb* zGkG4WRpBq)8)k-rlA#xwe8Stpk0`=kdi-tku7|3_nl?V{D;DXl9V2*}VN?F@@?jfD zRk+0JUycrS_Du{y!mQ1RP-bvfi6=jK;q%$=KE*6CzH`x;wah5RU zBHJu`6f{gYyQfggcQ?XuI3}1pWljyIJk9m~SeQ6jTk3&06C6`&i_x_>4!9FGVY?^r z$r&(abLS-btWV1Rh>5d12Ubj2M%I3%?!}I}LaJ3386TDqDjuy#Tff=Yjuf_0S`oC8 z^>1*^ijk~5la!%}BB*R12dQk)Qz*1}nETC&MKX^LG_ov|9aBnaQF@|HE79j+^5}$o zLMSxzyS8Ckqn-u|cIXn%`4L)2993ajG^V-wPzF4^WuUOrRwU0pV{H?rL`Yu)?N9NV5v z#uEC#^}7Kgm?H7#ERJaLntblz`|TYrD&x~zKAQK8;6Fq?G9UXj#yNjnn#eNJEGyql zf^TSIUd2Bi^be49NR?f-uCbWVO$53xDn?QdKxjXFcw23$DRQ+*kBh`%1WWIJkr`8* z|8Coj@~&{q~DT; z2u{;q_WR(l<$7aPG!=zy33oF;d?a5Z^O)vsLDA@(p^-ka27NGlyYQ#I5_vFDmLYH2%ySU7OrieB$S< zAqF)TSQJ!LNgXxyZ5#{f^38AFXJp}6=Hq&$?PyokJ&PmRavwBVnvQ3|IREB@v|0b~ zK{oB>BWcFAr%Z1!*6*me+h=TjMtEbZPjKbKpD%4LHu}MsHhX&LRo`y*xZG-NPkrxK z<9J(hV^-6r!9ZI;xfTlc=jvLJ(l7 zDtY_CG}>(xf!lyq$c&-FAhHKn5B%yt!VxqU=MD%%P$-rkN+(O-aByY|Op~aIJa{-= zUD12Q)&9QxZ>3ABy(EfxuRW_wYpZIr_%+;POrZGiTBFM@Da~^4Nb`|DKAAoa5zhU0TJiZO>gZR<`DNl{e@ zixIUGVKfW56a)r;h8#kYl#&;k^3T2*Xvv;RE4RwO2U0l1-gFiisy4%MsF8RWAT81I z0e#D^)`F1mw1`NNBC@M^r{$Tj&Fk8SLra_O-ZwpztZjezCjM+M(>zhn^`T$pS7I-1 zBoi|!xYN?y;OYP7dO8~uBYOs{yr{n8RAg{d&9VCWtwZ2i6iWUN0j~I8k58^=4H!y0 z+|k9nc#&_^b+kq-1`7ZPnc(Q9j<&qD=^UNbP4F*kYW^oaXuWk_@ZX84?qO9F^8XwZ z()gc2p}WiEQ0N~mp?`-$A4&fYpisLuvsNdo@87M^9n+xqYrOs!R%rIWTA_bY6k7IQ zib4d!e-?%QTP`Fo3ei{m{rS5nWd3hOq5l;Z!sN1%|5gZiOD~ zD!;M0TyBMCQ~y_1=+u_~_o2|E+W#9U^dBvuN00tXOX&ZHLf&n)qs64)rs&bOx@*VC z31d~>?e#Y*9d^8VINE;t)=3H%t>e?tFmcMO*eqtOqw)4>n$iCR3XRA^LjM&CJt`kj1BJZd;je4luQ3c1&>1?}Kd{H(VZDZsJUvrnsBlD)qvju} zZUw7bjalQvC<5i=u(qy~B4v4kinfzy@+Y2xX-7;pMxCEx0}x@!^Q11rMaEXtHgy6* z)!ATO6qKDWO>=*T&=Gr_yF}!C9fUOQB!7J!&w}@MyRzc{%m|4}DMZk;Ht)hokygdm z)sDkD?gUZ(fWxFn7~D4fF$EO7jN02vkP55{k?GPu5Jp%E06x@^m%S%IAQf~JRZ{ee zm^GATPDEMJ1{`VJ46ZbU+yZBL(XxAK4yY3OA``~Z_s)`&l=Ycj*I=9QU!GHxZDlN& zmfkqU#Z{SZoWfLaG%Vitj2?aTt4opg;dS6zTI?E7{P^UAKOR-(@?m$_arjhC14Tsf zq2<9{GBreMmQsV`Zjtw6>%GkGy=t-#VLmZiLTKzfW)Az3B;Fg@B3Dc3eU7hBFybRw zF1BcS!6?O&N2ytRcLxWmc5b08M#S z6tzx0<_jD-H|aI$vF5$4PcsszsfRDD>&>%~nZOFGoL7d{MHVg% zw_4Wu_4wM#=fE}Z6iJJ)I%HGe+Q4621#Lh^XE)l zfK9)dc#6<=-tezek72t(-k<#KZ0kKls%?1DV&DWWuFR|eL2*>Lx8clH;>wW~nx?6hnwpiBHm$3xsH=UI z?+?8{=X<{2pT7S9KX7=R^E@w}x5wS_+*lI`^DAG2X6{(O&dXAxsQzG;u-|HoYf0Au z;HQ0AZ_h~6J=weEuWn&?dhrV!*U!uSmXnbe7hmXOw|=~Dw>{r(5As>wlw)EFF%;Q|k zTaKzV)(N$bW4Isci?uE<#C#F0&6bV%sILAuk|` zKd_c!D0Ff?U$2eMl@GxqQ%P+rr-IQb5$Y8N+76mg#f9~bbaDIvEE}i7vGSj&eYTxe zVD=ugipwW6MkB;?JOM{6`|cQkoeo9&KoK2VEHe~)sb>!VTYh5X%lk9TO90*VJyYN z4qL|4)R0?bslDhwXn3Z>(M`ugiAI9=iC>F;r4jH!EB8$!Ldnq>5G6WRlU`JG?Clv+O6j;6)yax`(NV6Q6s zM6C^`96b`ck~l$XrGwtOl7>V1K)k+yOI-)`B!_c%9SA86qXAKw9KGNnK=APU`5x;x z<4MzxAXBIAit9mfG`|hdM4&gwi1PlMFD2srlir=DDA2S6AA`pZe*(FS^fbscAja{V zMqL$4ixw&I+$<7XU6&)XED9+M>CLhv9ngq62=qv3LaWf?WQQs1A8Rr%W2zFrXm3Oy z^eRxH^cz@T%2n+!pyb|P5m3qE{P_$PI-TTX1zkFzy63y=)v3#&5t{+sf09H!Lc2N(DnqPS&Jn{J7t0;aZNQTmLbXV7-jU8!2p6wu6hE04} z;ihDQIpng1W!q#mmxS{Ux&;TF-DbZ;I@3{*7HNB#tqSh1u1nT$rjShC-@0G{sP;vl66u`W!f>mDS$y z4MJ!?UhIuCkRgy@rh?5KE45&`?QT+%0jUBV0vH^ebBB6{HHjbg#E2j9Flf-SS{F@G zEyDj!gLab`3OSuUO&5kSzDQarCCDuc5$v}h8UHO7yd#kpmTfPU-@sBZFAfaIjFOZ; zPa+f?kCI1)Aq^M4Kw4-|J^+1dFtiicCIJZjVzt-e<_)cwNTjwKA002|nIV*jvF9~^ zGtV^cPN827qx_5g0!FBR#pYWeUZlggO43&!1-P>|yxRZpL-W?*I zgjmZVPi%ZBKC^vu;?{vDpN603|NT4+Y8>+nd)JAq^8Ju>upshtFnMxW)+cvba~-kk z!g$h;&^TO^_f+!DL(6Jm!fEQDmilSqs`l09K>p@p{6 zvbMH^J!y#+TcIRDXtkNN7(3)@LXR-uy?hjl7^;JZCiAGr7|6&NpoTDEKgFh87pWv~r zw*g8DqE1Xly^M{(EI{vnfjw1&MG+-}bECZYi83NKcr9ba80@eRn*)6OHIKnM!>#y$uKru!b-_8{0n{0EZ#04N=w zn3(uKP$+4E25^N^iLmA7q6QH{fJUBJ2>wuope;bWgeiUTgi<{sAAtIAvW5^Fw9taEgj68-HeD$*yxEn2Rzi-eNZ19HF^O$gv$dLqZ%lu z1z(-_9E?;t>NN4WMqmLvOkqq8M%{8KmlZ({Q=B?P$A3;?luaPu6@+72Ou_#uA%Vn7 zs>C5WEOmn>`6I&@0N%w1&)tN9x6`YcFM)%yDPG^uBMXS-uZhf7i7tevN-sn~kaGme zrsK{mKZgRD?luz(yVSJ{4z)N@+EczhI)MG)=mNkGF+-> zpnfEn)(AS4+5jm}IIwWKs2tiXDt~LyL|8oV1(rAX*+yL$e^Pj=hcDr~05x!`*`-pv z>?h%_l3;0>Ucm<%1X6hc*%Pg9M%p!XX=nm28JwQ~s|_*2M>2@WLW)E*4f^%+#J;cjE{h7a!BS#x&N{;Bw5H#GlMozZK^XR+9gm)=o4TLG!eiW zmV*Ut94>p1xV;=Lv3aXTY$}?0AQd4{_E=%1=y(qr^-xOSD zMSOryt2whae=uQG2<<3``-#)m zA%7sxRV`pTBTL)>T5g6rYyQDOguEh8Q8tlLbak2vb`m2Ss3|o`h5>KDqvmyJJ#-Wo z5Ui$+CNY2{5+=kAt2`hPgz%?{GGgeclgBYbLa~p6KK+Mht{@+2;*J#KAR3Gxcs@_Q zvG2{{uP#8g2$3D!CiX#o@wqlc&JA4`#YCtcP}C-SW%tH;tn_}&HlS@K8sdwG;U1xXyV~qu0F!834a1?( z+4!M$u#y1ckcjD{qz2&m62)gXspx)EavbjzMLOgJDn!*0xJtI!C-yTSL0BhH-?-`d+q+6%qlf7!t1$c(mFk*ZQ;Un$d*K(zdj*P&2W+{w+ z`i{<+qz3Vjk5QN%zcAbdNH!pGS_8_$k4UP7E~|l$(-6t6rKuYbec@%e3Mw}j_OrHm z3p@#CA}utL;rxi}5751QSTf!-c_D8k_5I z1fj%YdEp4UDo}*@ts}F2*aWz1(=G$huTO(N4n-aVz#vYrUB{3P&#&w?4DZ~4l42@V zRVJC7IIWDNTQ}od011nVs35#x8A~HeJ6G0959&Z^8^^qbry#|w;{3z{I%-H%)*`~} zTgUve0w%*J)O-*)y0tqcPEK^_m`TJ@V#=g5CF!^eSBS6>*~Fk^VuofFKL(x`K<8wI zTHUBlz61w-f_33+JpwtVc55$FLYY)g3cjuhWV=YxGjU`qg+DUr5c)19-&VQ9c;3~< z3GXS(gO_s>qXmfWed(Q)RQ0ht(POO~C$KLa_5(?_72fRjKwNs@VwL5w_E(OxLxzm7 ze)--u=yg)ZVgYQu!tUKVMwtzwkwT2{ca0YR_@MhmmqziS3JdqTCIUOqQBNHtJgm`) zL})b;d$n$VbRaNt;g1jcD}G$k&ULqv{3Qz@T-%|B2$gxYZ1@<{D$4d0_A^bebH?V_AQjd+s*23xSASnAxsdSS9}^x%^Pw<$x2d^z;?UZekx4#N;4ChVEy3Hck3b zz3_Y=Iw7n z(!UDQ`-kQt9LkwckdMcz@}exDQc!3yN4lL`aD$D=MVm|xl;*%XO*%h1hIq$(sUi3eNEw^hBQf217MCqP8=!^h2g zsc`6J*tMX;FBBW?#~0z1n@o$w)8hZozyB@%sszbez-`$v_x^Gx=Rl-IY%9nds45_K zY#ci?7@5POwKRAf^=_HmSpoXKN(LW{>i&6W2 z+g$%w<2KZs}{AyRFC;Rg64P-K!YWaS<#gb%Cbtke)Eq+4=Pwi_L1 zFq2o&p|uw??!01FU%ol?`s5CW9Qs9rg zCIm0ZEHApDzjdXb)P_w20edH(FGZ|Mf1KWFxL^}%qe3cplmy{wz;5~@M$o82A=q>S zTCPw|TY!oeM8!7fx<1~1H}LE9HX~UC?WneuP?_-OkAdvqPfHC}_2VZHFD z*bMUnmt)&b(jl+v7kq$;oMWG39zMId;@7d|2aFNC1SDTir^2H2(ErJF$!8!gv70izUQ~UC=?l`I+Jz7b5yOsMjX8pPJW(^S!tKAV|@fEaD2achi zQaKu@+_;AH^5=K)rE0F#0#%{&71sA02oWOS`u-JoDg5fGlTMK=PFJ+-N}1|q5TVF5 z#Y>Q3}RlMQE|5`Xev;Oj-6HYH^fz9)g|k?dgC?u1wDL2w}46w z%-%iN?KIz)l3Jl!m6F{&^}ixkFNUAi_~%tQQi@a-cN>b7-c9i9LtU?I@-aahbtqtt<26Uq@tsz{TtO45a`8<(vg!*bth+It))Xv@{7UVdbibe zrNjEd{&Q-3^ro=a@zN)wzE-SBCmLCRrQz=MPOJWPq~(?BWP<%_cMXHRCqfZ~cA7^Q z6zJFRn#52Dk=Pv+@xw#w;vM(9IV^SU7@eLh{C}a4PnS$%EnwtajGdz%vW~>$e}lb~ zZqd|T{veA-87(0&_i7j*>(B65308@)7q98_sgbY#*76MBts$o0Q}QTFq$U}fux$sb zXyG-TH9SASo3QJ3 z?bKUzk~3kuMa$VfdROUbQWEBWpSUO8{M9HiyHQZ2b8QW2Vs2PnrVzR9q%Vd-J~;)1 z1zziPS$OE^bZ86lyL-xBAHTS+D{epcQQs4GR(DmVuHP#dRQtZu_ zw7qcbBX?chrl`7i)+S#RvupV*w}^~)V2uk2&HN{VZvLYloeQXM_qU-=1$9Xmc;`Cz zYc(|6#01Sp=n58^ij0@2YT{ArACR*BXKyUz$fV%AK#ud@oA{b-3HG=2mNsH!Y6&hQ zx0Up^R4Tk>I&yZXov58iXOZzi5-hxa1i;V;$r1r&8aCLP+vr}HiMZzzJj{|Us<77c zVW2+DE{%mSt`i(1@iI8DT#HBnnPzwN#(2(~l>67TuD*j5s?A9G0ziAE_6DU08Ucl` zuQUCp)kcP=^rDWEv}fX_4)C#3la*rx`lb|38!X#S2eSs4*+Iny!iz%P=a9`ypLKKQ9mx$f;*MuLaeowBa4?eMd}NkHc?t5MO5k2pYPN_=iZd3i9U zjaVZ){1_;!)dRYm4okvnh>WFKq$T zQJC-ATV=0M64me5>Xi>IMiX~^E!a&5q&9*k4J&_)#DRFay*?aIvO4OxC#@7W!jZki z(<`%fH|^n)&A-H&dXpQW#*FbE^{E?(?v(nSf0L7lDp1VTr6BOgYo}T9=JrBsHFoCi zUJ0FkO7<&bl`}HZwqOYNa+*4!59_Yi$IXvrOZja;A}a8pvQv)7c-jB}l_~9vW&lb> zT=j52Nb*IW{VI64Qn+QnS@T(^2Kt0VhM>mVLq*DSDO@+?D5LRhlPpxo(S`H;yTU)y zN}@og+AV_^n`{j|0>{9yciW|Ko`no6`yyY~ce>jRI__T3 zRJQ?C8fz-AMr(yPB~mAKR!5EcI}24`w$G;@tM?u4ioPaJic03~^dmaZ+~;bx8cZ)H zhIh|9FXBxP2Q_|8@6f)q4B1Ow+yVUv+F$ywEcwr@CRyktKCNB8`3@Zuiqo<{gYxWg zXRkKfq2MYq+s4`{_|ufYtn^kS>b$OYqfTZ(N z&yDgx*ldg2=XJy2<|GN7q$s3f>4&=Ub-|%mlXrjHaW1fbz4nev2Kf@-!}sid1++?n z9*OKrG-~y5JH6zS!E3Vfqp&H)o{PnblU+t`v4_h?mx3%f¨k!z_aNFW=6G#yxJ? z-Vp=8czN*BHE|}Hs*bwyF0wsae<>w-t2a5zX?GKmEyq=TFejOV%BV%v4z$nL+deQ? zn_$LmyS#NV?|3|vo*C!l5sC7dGaem(OFVCpb?tT8F@Vwv%+p;sclA_y?RrR}S!^e0 zRWcLMUu#L2^r}a^zB_QGi5*mLWuHm1)3}MRwD&$X@~rjq)46mPz+~I{BVmy888&>{Bd>iD`zr zX+rc~ukIWB1Q`b#U2x3$@*I)wxfxtt-tW8QP8!ek9w&H#)m**bcahY? z7~Q=9+U-{FD1uPUp-JNvLB)XWe<}<8#>tCdJ42A>El%wy>ul5hQGib4=(d;)0bU&f zbcgP6AzX2c5(G6eRvs1TxKB`2a)|TBR0i_%(!L&a*H#J#^nLIpV^m4lhrs9P5u5u) z#%zX1W-3LKs- zORCB$;O^srNC0KL0Dz%Nx%Y8Hg?*DgM&jSaQ(Oge2GF4B_8-3+-QOz@KCoy_+t~}a z^w4#RI8nIcUm|1y$`@ybs4kJ}@;Xa$)(bc7-@)x1=cwAP%wdQZ30$blecLtnLg>7c zpMze9w`z-%ub0D9bNwm1ao}-Yq+lw?+Fnq>S((PsY^`bSx7s+}5cZFgr6k^Gq7VufR za4AZmb^^#g6SLeg^JV>95FISjEVe@I3-Dqi8rXY=&F6zm$u&<+y#97XY&~}?=5{gh zEMEY`p9tNLhx#z~IfCn zrC1HJK2EtI?qZN)M$>#p& zxt$oW5o5>}?LM&X?Iwg&C~!3s=9mnoX2NY|yE-ybx`GE>^6-CWDZ?A*8kpAT3B5nw z@ZSt$)jt{uB60T9yUYckf{@$#fE)`v+kr9U!{dZ*<#Z7_*6Q%&^;P=?wilYCDxO%| zDw0IkjG`g$M_2BXpfWjSp=%H~{l#L)D)=+^9}mRuZg}T5X|7NJ)$0Nq&xpGhmp@7u zuodA%Kn`&?yg7U4;WWwpPExiaaL9a6a5cw^3O1&$vP8GjPj&=sf=#wo4(Q9vrI)PY z7ouJkzDIDpHrO8gd(5gF;|;t0MN>l*inYQH3o#cWgYEf1WjtH23a>Q-v|M0|9Q}E% zC>MlymaEc)f4}slSGUUT^4plbRUD&_4$Utn{W+K2!EVz$kdA;=tHIix@^F;Q;R3*= zX0K$rHh;M*T^QxFaX7V`0b_Q&{)nJcjvlw8#4G%vI(mxs9aVT_b z4I=e&*A-dW>SB%#gEb@qi0eg^D%Q4r71-<|JZhjiX}mx?S-Nlr+PPRU`xvE-D{D)~ z-Clt{Rzd`Cv65|oNO1)wi>Y^!oJUfaXVT9p1db)KQJ3_DOO@W@ zGo;9^EIP=%o)I^RLC{@IXCTuBW@wK&_{1~p`)G!RjMS42LQz?$c8T5_%T_9jIl^^g zbOwz8Hj|5G_}Fh;rg1$0&Ij#n2X4FtQ@=x`BS~I6UY?BXk9gr)WbD>e=+l;vcPL_fUE@lF(IT#g)@F+ifhzH1{P)f|f8X&-_K z+m1whYcK5szF@9xvdF-IWVe}emOLQLNyMgVpGk4P^H&wfOe!Y*=JI`>|2~RlK!PL^ z0B&YpwnB4~ZvkYvbNKw12so2oU+Fl*&PtI@o`2BC1acc<0s;cmKCbRj=gdDxg#=6a zo3lEvNKr2LQ7JivOhsbctMpd|ZfihmVohy1xSes?f|Bz&^1|pUSzAAJFCJSI7)92+|?4V`oF&1&@_+6EtvG{&oH?$yJ{J@ z@9ULYAcAk-!KFu>+a<&WkUnozj{q@SU^|fx-!ePr1=ubo2w5InPHhd#bmKzM@Z&uU zwa3Q+ATfj+o|O)rms=ss2;*J|*j%v^O5oYgD~bo%j;gzqPgU&6Y>s~*=h^*FWI=o( z@lKug6}dfJDMk*9TxV=%l~3OpU@BMe>D4|VOOIr-PkTvciDj~O$Z_y&4fUMqe~A#p z4t%eg;}#!kcN5jJ#E}r6r<)uGpG}OSfdu1sMHIH2h+%7$zi!FWCYD?(IXn(SG6c)aB~O9 zG@&+Z3(`*8bw2Zsdb+I=OWl}Jxm1l(EdCX{B536&9 z1CfEq+_fRlS@p67$cKDF!d#%KcAM^JCe2-^`meJC#|da(Q=1Z%lOW6{D0hY7li=9% zEc$M+B7|n3ALJs9GJNBE@qCW~@hJ)~1jxQ5U0V`yfw#=K={~7B+F}`G9;zdVx`yBB zzxA4#nPY20-A*_GhA_>nNaFj5^N1OsF)oM2XX<8t)np_fw&F#W&k?u;X!$`FK(@(H z(HH=&pGJv&(D9aUH~PNOJRamd^sAnfG2a4t@jxBfmV=qR{(4aOB;0bQ*2BWNdq!rQ zlvBny+aE4&X1+hQB0fQ(o)0jbM6+tHe~S#b@YBdPIrz=s1}77X!BO~toSY&!ng{Xu@MN+;>E{Tp zgNA8r6OG?A&U!@IR<3Z|%$?=U&XV=4;4#rRy8Be`30vQ0;Ml ztDq*%JlvSb+4|}4Tu|$9Il=foXL#i1>xByr>R*o9x0YxrHMcdG-Tg;T&HLF!C7RN#5TFrn1Ks4^`~@oL8BK zeHE*cJLURuLh7+=3?BX@0loq>H=9+K9G+Xf*_HP!K-#UWda}M7y<%7s zM^H_hlMQHxIeQQ|0Z=(zrSe4k05UL->|m=|*ivL08{tdkn7Av;*W;&TXpuk&%CM=*2>3_ z5c5hZfk|i(7)rRw(LTAVT7=2CX!Z>}d^(D)NTNHI^BqAEW>kOm*`8$;CxXK;pX}I6 zVLGYq@!{E{Hr`I}nQipcjFumzppHhV?V^I^`8R{@aD2_AzEP*=D^*Ua^NQHoPoplt z^R-T&5waoVO;D%rul6r~vSbo)k8P#z-)Wa$f@YPTuo_`OffeKV`f8yWeaE;r>e0$^ z&tA4){ABsI#i`h8649;|2AO##*|EgNDu*sR%VMI;X;5yN9Y^Lrxjr1K?!C6}X#;z0 zW1x|hF}IvXjpwY$X?)#cT+`2oKkT>^q9Qb$dSZL@_{guLi>Sy!FS)t$2T#_&hB#cS zM97z;`(qU70G5{`FlBMaheJx-An&SETa!I6RNaRTDK(gW!UE4djxeGZOY-M^hMQ*6 z^%k!`{Dq3^OHn**P;zxD?MMcy4E{@Js8SJ!@ok<0~7TYcVjhBhtJW`QDqmJzgpHP&tKySaq0W)0p$dC3T%# z?!#tPIc#&m;%;wMQdJYWRr{Kr?-nP<`nlt3P-zL5pC|uo69VTtmrxfusbkTSx1BLN zEbnk_w(!c$(Kkt$CAwO$JYw=E_k-ET%%V*KefaC%0`O1c%Fio^S@9CtgUJE zCnRL_Pt~80P&2|K-mSl8b+@KzPsi|P_ORRd`3l{QucXVq~>NEUb zYZt%1qtlSm&`=g{eK+6R&k}U}_q+A|z_)jq@B73dq5lho(*JiQ2_Hj*5{t%nZ&VgG zC1FlRLe|X=-7O}P08n$XzW5F~WSJGNVbft?5&{6z%1SOKOaZk!QB3qCULhH>4&OkA z%kZ~lLw1qe3oj!Bg`a`=*h%o(pnsJmpuKUvgGTB^LAsw^2nmIP`m&Z=V;6(#q{St-LQvWYEkC?F>gC|W9QIcr z<918f)ac4;lU}c{RF?s+F<^Lng*G4}gsjZ2hW+@8zul@H2W={3@%0AI;4Y4{-Ta%I zB;|+2w}p04{4z9FJI2rGT#4&K{bhhJ<>AB(2(Ugb1B*p|cL&+)?sY}S4U;alcAu^u n1bp8i9={4d81rZV00i)b-%LrT_UQcoLPCF_P*NiU0I>QW)2;|X literal 0 HcmV?d00001 diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc.rst b/docs/modules/slam/graph_slam/graphSLAM_doc.rst index 4367f770c3..5297604809 100644 --- a/docs/modules/slam/graph_slam/graphSLAM_doc.rst +++ b/docs/modules/slam/graph_slam/graphSLAM_doc.rst @@ -142,7 +142,7 @@ created based on the information of the motion and the observation. -.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_0.png +.. image:: graphSLAM_doc_files/graphSLAM_doc_2_0.png .. parsed-literal:: @@ -157,7 +157,7 @@ created based on the information of the motion and the observation. -.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png +.. image:: graphSLAM_doc_files/graphSLAM_doc_2_2.png In particular, the tasks are split into 2 parts, graph construction, and @@ -289,7 +289,7 @@ robot with 3DoF, namely, :math:`[x, y, \theta]^T` -.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png +.. image:: graphSLAM_doc_files/graphSLAM_doc_4_0.png .. code:: ipython3 @@ -420,7 +420,7 @@ zero since :math:`x_j + d_j cos(\psi_j + \theta_j)` should equal -.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_9_1.png +.. image:: graphSLAM_doc_files/graphSLAM_doc_9_1.png Since the constraints equations derived before are non-linear, @@ -494,9 +494,9 @@ Similarly, :math:`B = \frac{\partial e_{ij}}{\partial \boldsymbol{x}_j}` -.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png +.. image:: graphSLAM_doc_files/graphSLAM_doc_11_1.png -.. image:: graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_2.png +.. image:: graphSLAM_doc_files/graphSLAM_doc_11_2.png .. code:: ipython3 diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png b/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_11_1.png new file mode 100644 index 0000000000000000000000000000000000000000..a9859333465a59a0c4034f9d007e8dac510a9240 GIT binary patch literal 3931 zcmbtX2~<!AI4~r{fFKB>fDocaQNSP&0SQ7FB@8AqbgK|W0mBdm z1#CkYL{I`@5^w<1d?pFV6b3<20!A8*5eUH-?BDP8d;Q*DfBk>gy7yMqty`<=oU`}Y z=i2dOb}H+(tOEc*1!HgH2mo?uS$k=%g6yev%Q{i^S{-%>b84;Zy0rEjP1aWovB!r2 zfYOGQTaGspvm_fdCEK1RpA06FBRwzp0D+$5kbq!vfS=d42%igKe!)R#1PX!D-*%o% z4lzR_|M49We8CsFo(SFy0IIbZn}esKZVN|Z&%1xU$erurW=y^V@9j<6++UF%brZYx z9A;$iQysFRcIOteO`er6pHyhF4Zf7xc=V}Opr+2IusHah6RCvDW(H3K4=a*5yd9am zKGJPUj(7dNFLZ|>xB3o;4XA*C0}^YO;tvCLcAuoV_awt#m9B&r=tSo||FSSe{a8Ep z*%Z1OXb3vkvj(s-Sx*EUx3vRIt4uljpA6+wR(UFHTk}kLN}j_Q8ugK+2rqMjgX&m8 zTIcHkplSdi7^Kzoi1V4)97GYnJ%{+yZ~*dFC64#%)_j~VQQ>W5I`a+v$Li{K*Xcs0CjEw0@f8eZhHMi^5J-cv<*RwkuZ=wRsmwJaei*<#7r~$zY5yfVI zNTbl@0bX4`HUjs+xby9=oCjv8y?v16NAUp5}hlxwwZK7sM( z^mCfXIZSz#j8m)2v*e_nsmwb6QDSJ6OTzsP~vR>6KA)6JOm1{ln|~ zhExX3G)~0iZ;9V@I>ncew6s)o40ohv$^PO%44$V&KZZ5a0L^4SD3X+18H{6U!2_?; zEI8HJ#Wdy*tl*6xbC@uN=|t*l{^dYzA-^iO#dxcc&iyk(W)aMJQ%m#J{AodeAYn-oaB7B!LxBpRS(*gF>0oSri|KrQ|V3 zdKzQ+Ln36BSHq znJYiWKOby#!s6Q2>?B2b`46axa!Wk>9P?TZC$rMOY&Nh3B=HZ&Ee{k)X$y-^APe_;Jz zBR$UYEcLDsG8DrSxH@cak6V6-=RIX5?z(0uPiHqc@)BScJhA~?qdsqQ+(qvkrUdRD zdRK)t_KdXf$%itX9oc)z)%Q%skL8uxGAk1$su(WRt6Zq&cD`Ov{hKSbqoiiCPH5~j zU~!wcs`ddxG#&v-F1N3HC1zwB6e~Ydw%3PRYJ>E2yiW7%VA1AK%f1l2?Fvj^8>91a zHqD>uxxqCzyfU+Xr>sMhhBFD1>j6rC0FfwQSOZh;=?LJ+8P&N+`p5g9&?n|sbCQm| zd1Pg_^aDZPveOv1{{796n_uowXuip6!RsZ`5cfB(QV-ke1)lvwDP$8`j->8spzBsw5>_Xw7 zIz8wn%_I;>7isgyXtY^ynTl1Us0B5QYKKB$4TCW?MN$y@TguxWusi>T!l-_1{D;WC zo_rHcO~|1N^7N;yJWkMjt8cKb<%??%ij$sBydx`r%`egJ06Prn2~6M?TS3%LcE{k+ zI2Uk`>6ylT)hl6ruIAF4;URH>D9kano24{$@J`ZrSn?Qh|F^SJTaPEpgrMR|_X5L2 zS`R&@P3(xl@f#6PaUQ#)JO>~&?BFywauh?fVbL0$SdS1*nIuWtka2Y=_jZF4!yVyB;V)&(FfZ9#T+lS7;Z5QMXy&qPBS!jT|(hQWWz+YNWZj=7+Vjb%4#=8O=Un04NdcgnE_J7Kw z|LmNi3;Yk;`CWsSFN3z#)h2z<3&VRQY0Pd~RJT}zE*@GY+HBqBrUjhp3nglT$`3au z3cJQq$j2R%6m9^#qF$4*>q5_?qu9q`>aTenVWjh2HC`ddzm~b;FWo+UI>vX}f7Mpw z$Ls0~;&Y3qEYhF1izn%gx_&UI$APaBUt^H_No)1jTb>1+3&-Xi5V0rT+^&1P)Okb3 z_A|IPlL(9G)~pF{;QdL#Y?075Te;#6Xs)UPF8AbvQ*E{%CfUJk6DUuQumNcINY5Ii zU?MRx)HaH_vl?Ye0I|S9{q?N<1l$GqyyZ{EqR%kk*VvRE{kYs-Fm^*$mR#$XHo6Uw zXa%W#NpEH|bP)Z7GDOpj@{;cBi4JRJ7;mqH&6Q5lT*|M-nx2XgoT-*kwCJap({y`T z#$WmQnewmY$PC!0?9C}|P5PK~#P6!*pRK(jYmOKE@Wh*wJUB|QI|vwporpx7{m}6m zRiI{<69xDXR9;z*faPU-+iDn?;+HMrR7q3lF$2p^oF(<-9EwSyxLRK1g0Cmfam|x7 zAo2}`Bt2lXuX|~_q8fW4O^vMwM)Dw*QPjE6W0eR!%NHwDUbacsvh&;W*XR~*%3;zb z`34rrGvcFx4F`gtD%~<85@Q=V1+mMC!5blkGB%HXkWQJJKRp+kdntG!YjcRDTgU3} z;J>OH+%aFloW;13sKa7z8)FT?J}HYyyO~|90fa(f*1uJ5f3?A%q#djudGy*^^tPs* zy+3?!)Y1kF1XZk=T{mUg?@&Sf4vvZa5W?>+(+)Z@o9MhI-}!xn3-xR(Jzj6Is@r9! zZeTyEJph>|ddO6B*uoIW^9ji`d9c%VStg)FR*l~sk1B~TJ2xWBIG>~GFHXGo_Y=`!R z&qSKQ+hXh#a6iky5yyQamMH}ABO0FKCARl+}o%@Sz@G$u126c)-xy zX_1&)A;n<6m9$n9_iKWX;q#BQM|K7M_-h4ZgXHJ8W*z|Wl0f;g3iu?rkj(|0D)`j6Ij9Tr-cJ5tHkg zBzSbMxN2lkYHSYoGlG_-lT(>gN)!R+$7WtW3hrLRhg)cYW;4hQ7e1)hF>}ytqqbb= z#4B3VBk6)x_Wtv(9nQuk92bYh6sBEv*`(Ki2UMUbgQ=ss`c zG3UqXt6}Tv$0>%%4{s|z!JqD24X8l>TH5@N0QtT4!J8F!T#>0AY~McN&ns{-y3<4C zRhf6J%B=3}-zSvzm^^Ga!FwTou3kQsE;WAT+%nXeBU30a+h$daIjmKz1bS39P9OD> zT-D{vxa%#WBy8yFdZJZ~-^$WGN4C}OBOl|R!1<&*l_Y#TB9k^o>VMx@a2BpDH{bwK zk|}hUy{OX;*k?1^a&uEE?@qsvRV}+e`wyP9`H&%UeI-;x11CGHKNP<@ZooeLdkJS) zP{^!AI4~r{fFKB>fDocaQNSP&0SQ7FB@8AqbgK|W0mBdm z1#CkYL{I`@5^w<1d?pFV6b3<20!A8*5eUH-?BDP8d;Q*DfBk>gy7yMqty`<=oU`}Y z=i2dOb}H+(tOEc*1!HgH2mo?uS$k=%g6yev%Q{i^S{-%>b84;Zy0rEjP1aWovB!r2 zfYOGQTaGspvm_fdCEK1RpA06FBRwzp0D+$5kbq!vfS=d42%igKe!)R#1PX!D-*%o% z4lzR_|M49We8CsFo(SFy0IIbZn}esKZVN|Z&%1xU$erurW=y^V@9j<6++UF%brZYx z9A;$iQysFRcIOteO`er6pHyhF4Zf7xc=V}Opr+2IusHah6RCvDW(H3K4=a*5yd9am zKGJPUj(7dNFLZ|>xB3o;4XA*C0}^YO;tvCLcAuoV_awt#m9B&r=tSo||FSSe{a8Ep z*%Z1OXb3vkvj(s-Sx*EUx3vRIt4uljpA6+wR(UFHTk}kLN}j_Q8ugK+2rqMjgX&m8 zTIcHkplSdi7^Kzoi1V4)97GYnJ%{+yZ~*dFC64#%)_j~VQQ>W5I`a+v$Li{K*Xcs0CjEw0@f8eZhHMi^5J-cv<*RwkuZ=wRsmwJaei*<#7r~$zY5yfVI zNTbl@0bX4`HUjs+xby9=oCjv8y?v16NAUp5}hlxwwZK7sM( z^mCfXIZSz#j8m)2v*e_nsmwb6QDSJ6OTzsP~vR>6KA)6JOm1{ln|~ zhExX3G)~0iZ;9V@I>ncew6s)o40ohv$^PO%44$V&KZZ5a0L^4SD3X+18H{6U!2_?; zEI8HJ#Wdy*tl*6xbC@uN=|t*l{^dYzA-^iO#dxcc&iyk(W)aMJQ%m#J{AodeAYn-oaB7B!LxBpRS(*gF>0oSri|KrQ|V3 zdKzQ+Ln36BSHq znJYiWKOby#!s6Q2>?B2b`46axa!Wk>9P?TZC$rMOY&Nh3B=HZ&Ee{k)X$y-^APe_;Jz zBR$UYEcLDsG8DrSxH@cak6V6-=RIX5?z(0uPiHqc@)BScJhA~?qdsqQ+(qvkrUdRD zdRK)t_KdXf$%itX9oc)z)%Q%skL8uxGAk1$su(WRt6Zq&cD`Ov{hKSbqoiiCPH5~j zU~!wcs`ddxG#&v-F1N3HC1zwB6e~Ydw%3PRYJ>E2yiW7%VA1AK%f1l2?Fvj^8>91a zHqD>uxxqCzyfU+Xr>sMhhBFD1>j6rC0FfwQSOZh;=?LJ+8P&N+`p5g9&?n|sbCQm| zd1Pg_^aDZPveOv1{{796n_uowXuip6!RsZ`5cfB(QV-ke1)lvwDP$8`j->8spzBsw5>_Xw7 zIz8wn%_I;>7isgyXtY^ynTl1Us0B5QYKKB$4TCW?MN$y@TguxWusi>T!l-_1{D;WC zo_rHcO~|1N^7N;yJWkMjt8cKb<%??%ij$sBydx`r%`egJ06Prn2~6M?TS3%LcE{k+ zI2Uk`>6ylT)hl6ruIAF4;URH>D9kano24{$@J`ZrSn?Qh|F^SJTaPEpgrMR|_X5L2 zS`R&@P3(xl@f#6PaUQ#)JO>~&?BFywauh?fVbL0$SdS1*nIuWtka2Y=_jZF4!yVyB;V)&(FfZ9#T+lS7;Z5QMXy&qPBS!jT|(hQWWz+YNWZj=7+Vjb%4#=8O=Un04NdcgnE_J7Kw z|LmNi3;Yk;`CWsSFN3z#)h2z<3&VRQY0Pd~RJT}zE*@GY+HBqBrUjhp3nglT$`3au z3cJQq$j2R%6m9^#qF$4*>q5_?qu9q`>aTenVWjh2HC`ddzm~b;FWo+UI>vX}f7Mpw z$Ls0~;&Y3qEYhF1izn%gx_&UI$APaBUt^H_No)1jTb>1+3&-Xi5V0rT+^&1P)Okb3 z_A|IPlL(9G)~pF{;QdL#Y?075Te;#6Xs)UPF8AbvQ*E{%CfUJk6DUuQumNcINY5Ii zU?MRx)HaH_vl?Ye0I|S9{q?N<1l$GqyyZ{EqR%kk*VvRE{kYs-Fm^*$mR#$XHo6Uw zXa%W#NpEH|bP)Z7GDOpj@{;cBi4JRJ7;mqH&6Q5lT*|M-nx2XgoT-*kwCJap({y`T z#$WmQnewmY$PC!0?9C}|P5PK~#P6!*pRK(jYmOKE@Wh*wJUB|QI|vwporpx7{m}6m zRiI{<69xDXR9;z*faPU-+iDn?;+HMrR7q3lF$2p^oF(<-9EwSyxLRK1g0Cmfam|x7 zAo2}`Bt2lXuX|~_q8fW4O^vMwM)Dw*QPjE6W0eR!%NHwDUbacsvh&;W*XR~*%3;zb z`34rrGvcFx4F`gtD%~<85@Q=V1+mMC!5blkGB%HXkWQJJKRp+kdntG!YjcRDTgU3} z;J>OH+%aFloW;13sKa7z8)FT?J}HYyyO~|90fa(f*1uJ5f3?A%q#djudGy*^^tPs* zy+3?!)Y1kF1XZk=T{mUg?@&Sf4vvZa5W?>+(+)Z@o9MhI-}!xn3-xR(Jzj6Is@r9! zZeTyEJph>|ddO6B*uoIW^9ji`d9c%VStg)FR*l~sk1B~TJ2xWBIG>~GFHXGo_Y=`!R z&qSKQ+hXh#a6iky5yyQamMH}ABO0FKCARl+}o%@Sz@G$u126c)-xy zX_1&)A;n<6m9$n9_iKWX;q#BQM|K7M_-h4ZgXHJ8W*z|Wl0f;g3iu?rkj(|0D)`j6Ij9Tr-cJ5tHkg zBzSbMxN2lkYHSYoGlG_-lT(>gN)!R+$7WtW3hrLRhg)cYW;4hQ7e1)hF>}ytqqbb= z#4B3VBk6)x_Wtv(9nQuk92bYh6sBEv*`(Ki2UMUbgQ=ss`c zG3UqXt6}Tv$0>%%4{s|z!JqD24X8l>TH5@N0QtT4!J8F!T#>0AY~McN&ns{-y3<4C zRhf6J%B=3}-zSvzm^^Ga!FwTou3kQsE;WAT+%nXeBU30a+h$daIjmKz1bS39P9OD> zT-D{vxa%#WBy8yFdZJZ~-^$WGN4C}OBOl|R!1<&*l_Y#TB9k^o>VMx@a2BpDH{bwK zk|}hUy{OX;*k?1^a&uEE?@qsvRV}+e`wyP9`H&%UeI-;x11CGHKNP<@ZooeLdkJS) zP{^e-+9mZpa1`N{&VL3-uHdo%lE#n>+`+VCsr0F+#Dht z3=9n1rdN!t85kJjf#aQHtibp~{YMtCV-Eh)^u{sZ7j?`d5jbZLxZ)Vhz`%LpXk+|N zjNS)`S|P>`AvQ2*2>f=CCxhSZkN{s;i0?gj$uQ5L;CnECu#&2hs)FR*kdOdvW##|6 zt^^D6Qs#vU2{SN=SDP9c+_?W{nHYKhW@yXG8WpZ)Iw9?sb?f0(_S=S)7ue46Sk)(8 za0`UZx(5n{RRwJt^j~U7dHvbO4dTpKM@tmbJpJgixMr<`l0XfUpRARD#wY(I;@A8a z@#%Gf&R1afP#!OLvmwrVq$yNwgVvnwmEGsGR1a<4-5T3MZaK@_1jCJt&fTnX z7m}2c>d2SmL!I4tr3vKEOy6nPc_FdiAs7KgND&;)sbz;RD;zR)(P zD{~!&R)u|z-J;hW%70WKIT;ywOta2BoAz*P!LgQ8y>$m1;E^-eJ=k=^PXp;F zRs@;?Sup;}#8cy{{`iiYAkqsAip-3Rs#Q)Id=$xahnfrpV{yXmj$xE)_j z$LOpM(z$VDk$2{2B&Dn!0G=^$Bz_Ld@s6p1Ky=kW`@})vt{jsr`@^_VQ2FM=M~R7C zpwW%?<{I^j7sG>tgR6RY`DA6Gb)7`iUZwJOhdUpitlGaNG?|MH{J8 zk&$D|Q!S{+k6B+SIKB*nz`fezS)NHive#z1&~EKalP$dGdw9D;70R4ylZGrIZ=0I5 zfhRewey_gtX(I-F=8l>MNw{q;42mH(2Pc8^M;Gj?e^Aa-wSIp{)0OCXtxRPy_pW3&>o$&3c7l671cb z+ie;0_N=1JltwBc+LgX&Pham*mdIT^C%|F=DK9UN-uaP0+gY2TQ!p!i8$+75QxTSPj^e1+ig|a5>cb4{dH_xh|@zCuoWVt3<-p035 z15L|Y?ngP^sX4d?cD@6RNj%v9;x?T2d~YuzS%;#vO(FKM2;F>9g>ZHj4Gj%#=>dkC z+S;uT#pyM1$t=H9E!$jzdoP|#GgWHY{C=jyf>mloQU%R14W0INlMYBl_L9fQPqATe zh+qR>gTB+DQa~~$hBuREU!4?DU3+&>YARw$u}^D;OHjc9n8wdf5fiq&=rUF7BUD>k zn~Ar2CCj2RP$j7sv|Nw!Z+h~GQ)qo5FU8u$Mem`&)luuW(pz8))=4|%*O!l=U5fbL&Ek2R-H zG&5hLp!Zo-&U7s4ruIhu5@i;;b^m?LZ!_0Lm)4nNov4YLds96ZzE?l=hHEO^hCRDETi+3ehcz{b?Q(b*_l8*n<9CxLNtON$_d;YZQ$--v(zwUo*v8@zV~G;Djv@ip>^@uO0>vMi z7FQT+Mx>L_;r#^#(lCGjzEXd_)PYRA2pqQ97Og@NapJzFiq7jTIpq~ zKhO2E_yTh$QwozkRFp|dO08l2I1_w@NvUu?ezg<}q8wBsU3{Q9PqK(C&ot3nSj|{^ zedev>Vw_PuxY5fg)H!FHiX)JE`}pugY|?Eb*dKKM=|2q1mt84-?>+#yv9DO}IbfHV zuJZrf)?N7+wmi}C=2Gx@OC-F?OjZtNL)+D|C)z4%?Jx?rxw!JoB$Rp60`%@MrIZhbtXw%(fs`Q_* z=uOnhSc{|I%~(4Huo@mZ6m~H8Ug)a3WKa9iJDf;*JJSzBLbry;M@Bkco;ORnd3`P2 znD-oUckND$+YrWY_*oHd_frP)Iym>G`AQw&WDfqQW-jdgvjE_4V2@H>KjjV>cDAy} z`M2=#kGBm|<>V@=kHr_d;y;z5!e%eVQVEb3uK1d_g|0-kD*{)~+!dRxnA}ssk92H@ zE{!)qxd~(CXYrxa`0nrdW;_#JxSf&8XxpL_JTHo;t`RnD*Wui?wK5Kygja@rcaEnc zRddz)a!EA--(AfWignKXnGbwO&>|*TT<1RB3o=t{{Pc?S2?t}ADWZ8ekzd~)>gO8EEF^A(5L<5tHGi0w+_*A z*y;lkJ=R!RDYqQ`e4@nZmpCK^*0(3!^-QP0Ez|>iJjk{z(5k3a@pUWa{3qCB z-vC<@x*y(u_FRO!MaOY3_vaJqtED=tNp0q`k3G*Q_&9d1)t~Nvt326F z=_6|O0mJ0(r?+A;OKZS2yBFHk!fd-2I<+p`AiXjpg_6hH8!=(3(x)wjnHX%VPTlz# z*cv)~{YC-Osau-4q_i~rkVfieanOJkxw3Y| zTUWC9r7@-l{LD}d0`3+Vy#)>POj;g+hQ-v-!@)je^m55vx({@_IIbB6SO=Z$5bKOz zl*eyfP>xf3mLcIfeQ_~s7D6slee0t!?p|ZR(rNY`cYH}h-P?M_hq-@lUtSW$g$Epu zJQ-w?D-V=V{h9D~TnPLgXPQne&E9^Cc3 z=QqOJ+k0ocOTSaTviTDmWT*YjEl|Xwc}=ZBE8}mAc?z+)^?u+j~TzJ6{1-d&+|%em&lvdq#!iMuK^MYQXWn4hU< zO@c;j?W+K*wz#;+dh4#oyDex`OLB6y&oLtLQd_6nO$B{nhZPEpDH9I_{8)Je5c1zV z3i&5J^v4F6E8UTr^(F|rp!n*A4r4Zi)3S2vwbdb^m~ZAet@p0@bgLiVqmdC1_w~+K z&z6%e9&une2uIMkAGfZARk-Ga?VWquAZ%i1zY!+LHgjLs!rYvjM{koiXXlGdkRsY% zX$$(2O!n|HNNC zqeC8k(0RhRZ^&-!>=l-?TJ85b<=Tv!3V)Coe>JS<{mO~RZ8y+<^1E{?YEKcDpNn)n z69(V^o&TEkJhNnd1h^`R1Gr@1KBh?u22E1X+Zsc$E#ULQ%(9#z(?_MCBk0b0IZ65FhIGtl9 z_k8Rxx}Mjt^Ydxr?k`kvNy)doPoOz#m^5J3Jk8DfXgr;yKIprZmfLB0p|XU`zfz{2 zAX1HVvarEEFUWVI2>p@E(d!FRd$FvBFe9KUJ^K7>-3K?EPW0)FDnpXLgK+8W%Nb?i zbtl02wOf4+wEEhrn9y3Pv+dxX0m5uu{L$BGc#ZS9*rk^%F^9Ctz%KCzB1|uwTaaH$ zN{Ucw=c#nI_m4-g{9v64T**S?4&m_EL_T(ZVOMNgcBL`LS5`%{sdVA48^@{yzI842 zr1x)&hzaK*i=ww?kHoc)$tm=)*T%dKLScs9hKNXW(F-T6H+mgOAF8E3x0mF;tjyWl zI#YRmNb9Tp`!0hsv^udpCBYQ1-;}OgNh#W!guGUrTbp4>{{p?-CFz1&hW!QXMel-M zl!-#h?}FwBl35#VVh)VW9JV{<9@92ON-`Ny=j`IOIGLPayVw8yz*Q zBVgdlnp5{@Ua)x7Z9zRQk1PycYgx!`z6G`FV<*y8;W>+xt_B)BFO(ES%^%zdgSQP3 zQ$neLZMn_wNAs^Cslz1(VBML*Ir>#UUI^tTiv-FAlc+E;`{3iYcA!(XcAo<;&Z|%n zhn?5YT9{*CxjNl=8I5%EVXOLZUv`j&a`c?BlFo0n&KoIbpsK+5qdHA#rlYd?E8eD0 z>54f1*@GzlJ7WALu%7%Cz=O^`d&DWM8m(KUo>QZfW*Qb68o2zJn`{a_2!{h+0Nk$& z9?xgOkBF9*F@qI))ve2#viN4Yf;&Gw3XkbE>W=9!0z$LO!&!Vbr}cv!Gu0;*=S<=L z&6}S+Y2x5HqZvu~+%Q~RCv0`^XNMkj1Rk~>t=XTQeEgL^{u3ZG(4UfmPp`YUn46fe zbw~ejgT8@Jg&Xc2@_#7Rw6pD~3E#N8k81l-ZX#ihK`a^zabIBmj_5GzW@E&{Ztb3g zgs)%pzWjx4E-e8wG@3o#79FHr*c%lyRVnl6C|nC#!g#aV#s)Nru3Piv42h0vUo0;xe((P+9rSA-?ALGS z7(F%+E%8?MiEvt1b)jA=^-VSgU8vWN>)whA>HJ_&V#Q%_#Ox>>up^6wmh%Xiw_gnV zb%U`6V8N%VL9+O2fNt=O)r9w-{ zf@IFU$kuN^pD`S)x5>|KNcfN?uxT>GL0c>m?l(fa_p=@u9mUDXhVa3I&~`RR1qF^7-gSxIv6(aSn# zBerYcsi&r0cmcinEwe+fRY(Ye9D?$WWJksn=0s-!y4%cVxf!`!3slPrxfo+*Z3+e^ zC!?_V_U&at0y%dr;JStvGwnPvd~ZZiVb7fN3FTadfNIIls`PslN=VrGNJ6iU9|s^i z*%{4K-&PC%j_x>>8e$V9qBBog>Z&d~{-I6lKR#OF(z83C<0^RAh;VdOu*fghYez3l z-NvtwptNiYIrq!<@O~FA)xU#&3xv6VSI#&#p-|#h9sJS5Ye(WAfCHK688o!_r;jUb zf-(3Izeu6{N`UO2>DQx*@#ybN^WJc9XlH4Uru1#=i8s^zMG0Yb)aW3jgJ%3=_S)gG z8?QSibHuVb4JgC#xw9_3{4pnBiAdoYZxfXYJCYFpQDRZN^34^0Q$dg~b@IYdrLpjT zDnI^TCe8@}AygmEF3Ztu(+iOmwvnfy2-Sc%X@0|cvG zlqa@~5bHtmad=AW7}1`wAyQ_QN##;MP<8Z(UFVMfJc%&d+!vqz$nTfTpt0>Z#b3VU z3B3~+yl|_tAXp?`}eos z!GPKCd2lhoA!msiU>X`}9z+E=Vjs`S#Y3lO5U*rFZ4`8r&cII!1ZUN?eBC)KD~nZ3 zOG@gc6HwYPi`yOC*u^T_)HpJ}@q}&-8vjJ+hGya+piu1CdYPe-Q4qjd6pz*r&M6k0 z>xnDt#!;99sCLuZZlRkEqeSOkUp2iUGjN;`&bJ(iko}uOT+1fZ5tyjCv9WR76UdGFW14^fea0yU0Ic0i3a4wIAWk3!P%IO#^3 zAQ;8$Yd+`;UR~4gNsDs@p<|`Nk@6)o28t;0Ckl9BDhSen;W zJE+aaC(H`qp@4w;{|^sHj1cBABN*+6eJlpgVQAJ#oa4&3E)lp|I`z+El#kvwqRh6d z<4c1VJYb(NYJvM$>hpiT6kcntz-uZxZWb~O- zMmZ&L!w(e)A`+$NnK)azg0T)@)Q!x=&^BXZJ3O3er)Y<)1GP zyZQ~fdu}eo6yiQ=Nqaahy^|Z0)M6SR_X;JnE5^E<#IpxCN9aM{WTIF*r5b%yX*ARC_Sp#)BmMUc>sC2GxuVSkxvKc P05g~xTNqXR=@$PV+Clmn literal 0 HcmV?d00001 diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png b/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_2_2.png new file mode 100644 index 0000000000000000000000000000000000000000..2074d3de17307b822b1853288e1e1ae715938693 GIT binary patch literal 7924 zcmdUUc|4T=`|jAc!svr6Axl#BDP)gPBzxJHY$MsmIx@zLr1VJ%g&|Zbkt~gUW*B=i zNcLr{WjB;%>~kJ{f3M%~b6)3r&iV8Fj@OI1J@c&h`?~Mzy6)$ZrTNw4oWh(S5a_sx zG1M9aVn_huZFW}R@0LKY4e-GnYG87M9r%f6_d5EL18(dP3IcKQ9sM$Vr^M_78#Tg= z?89t=U||UN5N}X`dl=k5D9qp2Ln6XEB-A%35TdA}s3I?MJ1h*YsigE@-zx@%_$cwh z1cg8#F>4d(p z_jdWacW)vV%5=ir1A4*>D?3IMry>mtEWZ|npO$!)bCq4ik&!dw9!J!(#~2Q%YCCPm z^TCDtW~%NF+E>;c&!5N94m)#JmGm;YmzOf|Qj(I^PL7^}5|WZ;sf-3tD5IPN6e|7f zze39oWn3CUb1y@m(iZzamUZxgeQnkJhf3QhT5Y3s4y@1;SK^nB4!>npC^VBFGTQTO zYotY5QZn{0UP(zlV}{c}nE6wM9qj9P?%cVva&oT;1VWi9SVBrFE|5|S=6-m>F$uUF zpRKjELEF<)3;iDjVFN=y%kNOT#)(Kd-~hzxIL9YbdbOeGn)>$Pn(oGOUtL*8 zs&F~WX-PTU;*8SC^=3y`SG(&AgJ99K2bzr?OMeRin`}}0EhZ(%!D5%O==IKxh2Dp+ z4IhT={7lD1{+j;5FP`s8j4Jc#&Y79j`~5{qwxUkPG_BOP_x<8Rveec0%LeW&_Y>YW zKP7sTBXx6|_+LN^pB}vVZ2Tg$`b~;Z_Z-eM$RTcUg_O=?BMz3}CP`;;0QU2uY*<++8a1Az>KCV)j;; zQKoY*FNJDEZ!5>K9`{)6EAXGF%Z@qNRS6imz{)LZ92~52N;B+3VEyeL$@dnyUHH|y zj_>bGu{uaK;DG5=3tfiEemghsp;C9}$f@`u7kp&{x+D?+oU}|Dfj%7U#9d)j__Aen z)qky)i;GK0)yp_L;P?8vL-}p+N4t{Qib2=BSFbQUy4x7_iRjc}oX`5sT<+kWCV)=v zot>Sr@IjaT-NAa+$*G6pvxOgv-;|a<<2Z3VHTO-Gh~-h^z#X&=`{W)cjRw_snyFKuQBj&MwPEhf z3E(2P`nvH=^OqW63;?IksJ#f#K#@a}Le&@}2~of2(xtgnRDEX|Siy9c2nWO3n?9%V z?*ZVpeuEm_HqZ2*ct0g;$9+;6v%kN;xR9R{^*8@{+frbW(4VSM2R_E}2CqGzvh~%a zy$Tqu1ij7AmyMRsi_p1fVfJZN_<`4emEa#(ZZ}LwJh!Fo?7Y6<**Li_LZDjZU9oa? z?OKhY;TP{dw&I5a)Rw#eRU z)z1yJ*-zM>eheZU?k+_GH4?khIHkU7@x1ETF^MTMbOPT2!B%?-H*|kXG6Qe=ke2vq!+#YUL z7nskPN5?~^BH)8svK2BtuMOF*nVQbr(L(Kpg@lBp9L^E}5ChRrb+D)PAW}7x9L@_< zYbEQd;R0Z4vbXL!L7YxH9p+#+3o8f@u`e=*EmEwK5-wa`)#Z30Ti4Ib>vE`PA+zZ{ zN5&cgchmm$>$I%ij>)7#c|OoT-WWZ`%m)xx@vFM5$AzI05o$*@4sSZ{3~ylBKcv;O zy(%w%4y>=;#O|IFddGCr5B0lU_L%U61fVtGfO})*PR!|Y0^80<%Hs_806TCP1*QN}%sX@Yo-Mon^cpr*JX#?6+$8^i%o%y^Z zWysd*L^swar+ui*b7|}zfJQbJ7MA__t9l;08w-T>F0JS3=@9s&K9#U;uBxhPPl!~> z&yCSUZY@uJ?ojkx9x4MCFa3##y0xVx2u{wn&5c@=BPXKwXT+m7dagR74>tXWKeJ%& z-D4a_(@`Up0jBja2i0>q$a#Q0I9KL`sFh zs8pDm*tYDqwUT7MI+Zdl= zu_nI0a;LN+-U0+u9x$4Aut)2yLm{d4^cbM<3>_VXwGdPL*W%HfoN?~TvGJt+agM<8Qj<6g^NjegiBj(!Qy56F05V1$iZbaE`T zTSk-{cc=ec#PX2UYScp>ao2-@5T{E2sa^}ccW(7DvMz?_q@^Sx7%x`E*S5^ERI1>3 z;jE>C+X8FnA*0;;ywwwA*qPU7z`l2YqF&f!hDM!KtlxWUi{3cd+>?7LbaoBk%;eNm zLt9$`JC|_&_1R7)zWVsBz5<)}jt(gZB$b6r0N!IH$ndSeMz)yn`x?N-UjQ0Oy4wXL z=0jnjB(RT25Fr`B1T{n9;rp{wz0RIN+fJAsXxuFwI1Vp3a644}*#Z^O%57~CMr*Ga zSYOpIz|(8%2K#)ACCy9;ReP|dkVtRG4gYtUY(>3|J@5us%{kYFqUP*no+_mw&$>34tg2td%i(P{h&GnOrqxi(r0-WkObcHcPzm{A3^a}=0M8=MZlUjvRH40X z`Es?w!x2d_cZZ(OtR;9r^#BS(46?e>Ymt97No;>sz5cZeKEi*TfPE+)lW|-`4b&5a z#M8!+4mBY%KtlqwNe&=lL6)|*tskuN&dSRl75DzKkDlkw@1OFngbX(E=+cJGi*^7t znLIKKN2NL+_vUXWuG4`BYdO*|`T#y192`JLrvhZ~_nJ^2gV($^`R3l8nHNFjfIQyq zD#2p0i6>R=!8NYKV6!R{zrKC{qyB(JZRsyYRioktDfMXjqC#9Ax0v=9pb=g>+qaf_ zv1v*f#wv>JSk0^23sm@{9xkCm*c~WA1E;wFIMgX^7Wi(=_lRnSC9rV4X;T7(%g(PP zG#SwDLJ-(7rMhiNkcfKVk0u^H=39W2DRL!d>L9l)9UR&L-3Ev=DdGJQ1?-X9lB_~2 zzTSvpl+JmlOd$tO3N&-L(d`k4ZPf zRz_YNiOkN6gYYA%5;kwy`a}d_jq)o9!|8%e>(Y_jk!`1BxfKvuHzEAZdl6=aFZLZe9-JA$OFd0$HzhzVQ7!N0i85(6s$sP-Rh zP_^O1Oxkd)qKDt&k*6`~5k=Tl-Dnr)0n-z(Ik_s?zO8Zt8#aga5FG|EEw!MuP00 zh(-CsM#=u>q~DdWO6AIZ9mo=Y7CIXnpo~K|$0S|5q9ZApQhlGPk^DV29}~oM5Sv9V zLVto)F}T(4smHd(UiDn3fhIy}*ChnEOQ1_&aPkl1R)J>aTUmI)nmzEO_p2>+bQ05S zo0t;gl`L${-X8VP!9V6SJQG`CW?%-K{goGU^NxP-lZBKa0!fW3#=s5AzEiQIE-^u= zH~-fjXMUjo-GZ49%wJl%9m)o0(@zr9vA%&#FkX6*sF0AYPZRE?9FbFo1G@&(kVqDl zRi5>I&7Q1m6c~YSrQj$!_|Um7le11x=weDD#-3;6B5oWuz?#7*|EV7)*Aw>*l!|!) zaBakywF#0a0xio?0d%<(X;I#P+c}vvvBPS&1mGJthOi{{Shmh0iLKDUHy0lz7*CTa zBKQZa9bH{pfRAofG=#o&P{AFi=9~&bx|k^Z&%XN~7W}_MXz;{E|6GxhbHhF&rhRu! zkvl6mQ!Cvz>@@8wTXh&|zE#m;`rk`kj_9v|o!)m30Gp1}6F-+ol?RD<>`w-*9ZaF- zhYL`DYdv#pVS9|N_towAJ1zLbH1A5|%9n*y!$7)oZSFX+tivzER(tEorKhvh{0$cK z_~m8)?v9SfA6M?x>of)-h{nwl9=1AqKg_>O!phMt;%mHWy4g*TTq~Ke-TnpvCh}2(U3Zb>8fQ8(Qi&b&LxtWc;ud zQ3A=0A79LBoi8*G89xWkG}3TyNNb%I%pP3(zIm7X%oNl+p~ z&eKmya;H!Za8V7p7K59JgCMC;n3|wG0)>msV3M zeS*J=Vbagn$mPOdDekblu(T?`a#wR|Ia_FmhM(<<_-_34xmvZ$@L)K-tuPQFT^G^W z{`zmj;EMAfZ;#;ZF}6BK8O-YREv6nO;(hSQh`FxpnW!$`U@=V4;4z-Qs&fIF7ph(M zDt~3a8mu$x&`K_GsdjN*8F`r1fYtsKxt!IgapsSL?5gq8w4ZZIS!m7spkPy%RdY$`)9v=Jy|*8S{rT zW&e?6=H{qZCD=_hoEnrzQ|YK>JrhA{bJ#ERtox-i+IaX}+GO2jTuQM#0jjan)&G$5 zB<@*L`FU~U0n@Jq@D}p?LSncHPt#9?oka{fQoL~?oW9PTpC7!pHs1cB)TDhS*Yqqg zM?GzWw|Cd#ABmpAB%HFz;2<#gv$_V;3?O?o*e6de?n!-XCs#7yFqg{a1Q<&|S(thz z1Rm-A=HjXF1x(La?@yR&;eNHkqi0$|H@kFP0tZ?`%qYXCH*>WQM^DjxRTV_D_3k#P z2wp#O*ZDz0jlNSGGrDFEz9;rJE@-1Vp25N!ZV-UJkPQ@MGWe?o^~CKj24447Gt@m? z*Q@P||AjpP^lMRQ$wPZye9G=Kp%oAOi}wrH7H7TPtTw`0c?1WlGq+mj^V>9w-=hE= zJM15te|-wQJ#nV_e#2ZS@aSfT$0eNzB zDX*?pl8rs6!lJxj@h~;@WJh3vT*F7Xm%&s7r`3`E9@%QtdP6|Ox%u(GKJ7QI+F<&Tl4ApyJ3Gw-~ zTSsa^`VlKs5JA`8+D6AJG6Zz7{q1)>y?OQ~1P6&-1yeWyiEu{Zh8q(Ec|t?!Ru9uf z*)d8dS;P^8jmM;8=wY-snj;j3F@|q>SCbypB_vu;DCq z?6)gVoOJN46J6ZLWR%txLh}l9UGc)o>XE87zY)r z<8U5q`6Wr6P2@u+4W@1Pd*MeUFC)ww8oNaHKMxP^7lw4G;d~gzP~vM`w@}M-bJV(S zaxIu*)-V1=9mfd4>oi0G$ul7ncUC^N|NqGG|IitHoa_*-QF2<=@W9Y2&itFA`T*=B z_9v^n+Z~w5i2@@iH06AcLc%2yCt{VWD8Wp;iQL61##qO4j7h9eNE)UFK5JIW4Z!2` z{}vt~*Z@NY%l_5>%(Tnc!TQh)ou!t!{F3=rk`-VND zdN^{5>YSGo+&0zEQpYTHE*A|oEG)&Uj~yVWhsP1CEY2+cRvG{fPd#F7cAnIPjB+}Q zWVMn%cP=}C5EEB7?3;Fny1PBs0e8#+q0Lrl>1k<=uK)fmj6ViWhP9B@s*w?dm2eqA zQZoO;J^#N5LuswWuN%nz>ZLQ%xiQ?OvX6dVko{D%`mJ_vB6E-X6P|u?Z@d?HbF|kC z6XJaYEC-@Ha9LB>(2uHBPCcxetutJrq9sv-if8_F0{TfsBFA@`QP}FA`_N5j#Qsxp zz=U+Wyj1}hmp+OE%o~)kVhE#*Q-N)jVFMtzOAH;OnZu1kziH$myTy;%7pLdzyn6< z^nZa3P{jcpby+_vO?&ItM*Y;xDpi5XX3VC`unP*n@L&!rM#!KTailhj{m@W&e(7p& ztgHxrz^0G>G4?bGxCotlP4gDXn}mGg63V%!%V$3@6rS^@4#D!ESq#Bk$-IvbYWEbk zpo?f9Dui=+oGk66JRUn>UsF{sw#^DA?H>*8ZbNW?4MY|;_tFG9D1)HA#oMaf_LEk0 z9*tgd?fdt&Hs_z#RoMew3_sTj? zvbk2MRWZGwMXGO6!wF&?XnoHIq?`9>z6FZvI3DtHI7H;zP|HisGD=HaEbWfM9ez)@ ztMu2gGZWTK28&yEuhQ{83>`azY0u03cc7~+p&V;Yw@jo4Q^SDT+=i?fBJ_raHs3nx z90aXxSM_0rIQsT)j42#RE1)AoFhscmYF}a1Dzy&q{!h(xxsI7x1(;pdrmHzhBlPB} z@5HY%9GMkEWl8yTS;*mQFTs(&s*%lP7-JBx&c`{6KNBvt-(x7b9=%yK zVAS5QZN0zX+R}c)XM$dWeZnFM-P0xZaGI+^kdNkvh37IHIM#T1S>dz^CbU$PT8G*s zFWhhDMrL&I28s`!jy1wGk)8|ue$764ZITY6E934B5%yxmzWr{?+1{O){5AMV4d4Vz kQ_9h6RgV8_S?|&XUzBf8g5MkfZ>T{gM&{6BgIo9h2lAoP?f?J) literal 0 HcmV?d00001 diff --git a/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png b/docs/modules/slam/graph_slam/graphSLAM_doc_files/graphSLAM_doc_4_0.png new file mode 100644 index 0000000000000000000000000000000000000000..4b8cfb25d1e23ab14a29c3fbf5992236ccb4827c GIT binary patch literal 9308 zcmb_?2RNH=|F2PP?b51E8?9ApgxFLYt2V7sdqvfV9clzcqgIWUm{qN|lu~NNNU0t4 zhaw0{Q7bV@%s7wtyyt&@|NnKa_x+!9om|(GC(nH+&vW13{rP;8U}B`h%)rAyMMcG| zrwcWsqM{B5KJT4B3%rx6>?(oNnSk4R_s#>a@bj)H;F{i7*E)cTijn>FpdKPb9sz@j zfm&99=5Sab!pYx_%G)W>*9#u#<>7oK*v&t{1MUO9DRWas;>yFoKwo7kssBBH6YlRW zbpgi7O+|HuN)M`eFC=fB5SDrGNB-_6>C?@KA~;CS-&@n8m?q|XI+qJn^LpoX8DWVe z*lWLd1*2}Rel1yLw4TMZgm6oOtFwi$QRiRRp1E{Ce}7fzeDSs7vpn&!xv>H+ujt-t z7A=R}A0r(Xm$6lqO5M9ZGq7!4#u+q#58721UR@qOTx(8kPyvBt|HK_&s6n71g-d%N z5Ooojla2m7T?W?aF{=JJL zMsFG$8(VX)f}SK{%n=`7P^zrn3R@15&%DcH2pAYMmd0Hod@Xet~)TvhhZ_yZs{G4!)7R`pz^@qejT@ zp+i23Nvz5$X=365@S=M7?7G$N5$~D`PqE^l?zj1xZ()c5)x4}nEdHxccextS7K zQobhA(a|LdY7{)IS+X-@2xsG#d*taUCMM~ovRVS40>=YaGsOIY1VgI*|M(=vv z%zzYfUw>k9(z+=`hCCI(N+uv2j3zP+8{0{=39;LMNaTQaR{PnoRZqoH_IKAbZktBN z4#zL}JvLQ;$J|#es?ioB*}C|<(u^`NxEL?kgdJ|3F$NXYr6&ZIDvjS7mvGk?%I5z0 z+%%x_r(M_RCkJCqP3pSo$2X{c`eq-JS__{FJVtePYG0Oo@GW#HziVgA!8jmbdy`ad zRTbkgTp|;+a*x<@NSr@ROibJ#%4+$RDQ2Fn02km@@Npf;Q_2e(wN~B#m0{fqp^Hp8 zwb0ds^6*tOA+}%iMv~d{MNM;$cD9?8c6f--?vG0^FR?-9Z3dfgfF->x`jYh|Q7iua zz!yJ%vC#s@lQcwX6u!#kTs5r!aaYUGkeRr+_}*?^Yk#Fv`}h}6PKU#ZvGJzR0G%*0 zX^Ds-!Hy4hyagO1O*TyyV^ytacVN#xB6>dLD?}zV{IrJX{ ziERYDFOnZf@2ahIBiR5Z*cgEg+%IuQ)pl8Lw|GXUw0s*Va@H4^eEpp>dYG)|7@5ybqJ)m1zOA(f^}Dinhj!`<(QUIJ-ooa`-y zs2(bWSks4t!@6-SIrv?y>dE z>hIxYt=TI*Q1Vdm+xRfU^cN&?szFX(esf;%gez)yH@IaZPRh4WvQ8RF2^R=klcB1G z&kP7sHqKGO1`GPP2Q>zZ?mT@6hr4$?_G+vWm=(oQtSYCHFOT~akDA-%^6 z(;-5@F^}0*kZV$7|1C)QDL5q1_p)WJy>%QH35T^ps>PNW(0FHX8KimzNGs}I_Q8Jw z&2&BHL<1g-Zg;qxbl2JM@iI*2D9L#;y-g^#i~NMqy9&CKkM^5iV|Xy%!2JP;>Xi?J zJD!INSvb&9F3%bu3R%Kg_p};gh?G|t%Z9M~p`pEFvMdktGj2CB96j4B3$Ohd7GAj? zItNws4&Y}lzN@&D#G^jBp(Z}}spOcL0O&ksrBtjqRqDxe!~8yZAS(r0462y?(VNAD zHDeU6X?!~S8V30+wLi>CX zG`hivyNP=~CR*JaCjnDqw1 z?IU)6%!A?Q80aEj1{pEvDQJi2PfIvM#r~9Jb}=?5aGBO>yO*d=6W&}%yK>`3(&twp zoFujCSp5=%xz~E_Xh=oU2baEV;FKuLyp%4M5dzneVZ0kmek?Z-OMkKccz4peF;I+3 zKkKI3=3IwCp5msR8;0S?_G8BIMTR4ZRUb3mi1$f4PYDJiE=jt4pcU^~qmjw;-yB0FJ>Acm+}!? zL;6xx;rsrPhm$i~9a51pZVhksv$lZ96weKY`JNn;w>R2Z0|-H5ejOZ^(g>n$K^Re~ zqIq}yOZ7_$>$Y}Q4JPbje{KVi7qWp!b($2;vADW3OVUNM1S*KR!d*c#QWU|9Y+hd~vvt zA_r6*gJNHHTpvHor3FGs%MQ-x_0N%v%9T5AUfr#E%==m7-+8AK;X4g?g3VC67MC(_ zH*vhSWAZ}PX=<*tz7CrkYo*A$bS60+?ylR0F1%2qOuw+S?^%9VIPHceU=XeIP3!CH zN!%Iv4b%)rd=0P(t^&f2_SS-knhi)P|CPb%)_Thv4+pO*Ln6>63O{2~3x}5Ld(2=<1o6$6FE502QYw82%2dbF_be zCy*Z(y{iqG+si+uEzDN>B@%~n)%r`f{-_|uC%^dc>L^XY?>+KwO3HE8%&=)i7G=SK z68G%cvw4Cf@^}o{Utxza+wF1i{Yn?x?o?u2IB-m!IjNYxC~V;Pvn|dbU-?BGBd7n* zI8GY=PinS+)(|rh3d8S=-8+-Gn>N}Qn|(aRAmt5a|EJDp!-;b-DwV0yD=4Vo`Q(zdYJdJm_K57$(G>fj%0As zxbXIXhL4CCKhZ59nRZDli|&;s3O~*V)YX=%Enb=Xp<3;LWV>1-{ysm#Q8H z(^(pFm!GQvy(@iq&9<^~UWbYCk&J z3myAB?ozV4UX!)S#*teYr17l6!a-6b858-)^fALxq$4azT+H!a!e~3&vLr&#L;*Tn zV(79uS{`9f`ViQ)T2zi=;sLMMr8P>mSQYtnx+s>vaH9@8;VcotG74#+0vp+W)o3optaK;htJXca@Fe| zDY@w54D^p|ydX|u$C(5IrGxQ}?MSZdnT}0X>K8qQ9az@S_dcOee@rZBW(W#Y@L*F{ z>J1mt2D@(#+5@k{mZm;p8L>AX6(Qm^CQNQlL`y=dAA!q8zu#a>TjTa+^(Gu^B0l+( zOSiVRC_X8u?&p75MxXFV|BPMV?1=zCtj>Y>M&TI>Na?{+1lANWIA9a11%0FQS$237 zXF(MZl?Jn5JW{(r=SxPOwV)lNlD~D)*AueB!IoCgcXt+Zm`vb9%vR&y>qDVN{ZU~L zZ-77z{}mG7j+O$kUjQ)PKSdA=Ag^mz{*UPSUwk#~1y-SYA67ewdxZ1ycs5^`ZJm$y zHl!T6{c|~c98Y1F&$h7I(vQ&O;@0#KGofaGAra*3=ur_6=$$YxVy`-y2Z8J$Oh$D@ z(^)G5f^{{8&>;CLNwMn_zgjW~jxeNj^$Qr}DxnAGRfWEvYaL`~XLmUV`2BYTt9K!d zaN{8z_Q7mgAl=^ttNy3})%`sy8H;3A+)RlG_n+}2MvfC~GIBL&U~WbBY;4PMUS}x6 zuZD2KXlsGW^C4T`Xkd`V*#6ZhJL~tBQ0U{U^QOu~0fp-8Snw^bkZuAZ8$TBP2!UkZ z;{{__P_%HGI@brMhLF+_hOE0cf==+h0#B0-!6RS^_1@V5J(B0;VZh6j3Hil&*2WX6o$=S#|o_S%G-Yx)k zzogxs$)SyrfWxM?){I5HOP8JsTDR@WV?uWqo`laIcwAay?L9dI0yRT^3rs+2I<2?H zFW0U`Bo4)#4^1OVIUVsL7bloC-1|GmKEvl4{>cHnRIQDR9}N+#c>sNL!d!|qzIOV+ z`4^36?=rp?!@$iNynoQvEOKlNvz~B#_v>v{|(09(6dRJ7x#2>T_happ0+)# z?{X6KN!`vW6PW$7wW)gim3KO53MZPReOhJld8fExdO#rB-dCZ{4Y00NfUmJreX z-@=64vSCBM7=(nUvev2@=bhKdy{i~-EU07_s+@JNNmuLWN6k!sVr)qGy#3j&K1V22 z_QikkuYK4qsb{_wT%FLYgd|j1uqf2NWj-4EX6p0kKujjlUr{bSd%<*nEx65l-Rp3} z%ehGPbOyi}Vy%UO^nUM)k{jbkGrP2)@i9rXGq^S^IhvJviB=&8zc0dpVGijdh|rR0 zPsVeVAF)6#K=daO8r9xlQ)jtJX{x&{d`@j88dc3Q}aZO`rXjmAyn==0Vksr3@Vy$P!q1j76vZC)L zuCx_bSnW8jwEtscMFq?3-h|@vrBERmWr1Gp2hOqV0|htUu}k4p?1i;6ou;#Q`RK_v zkskn;45szTOu=ZJS3PfX|Na8iU%n_4PUHo-2W+O!-@1kDv%5%_9auz;BT?+dJCCN=A_X>~-qGK<%q~LyZY((To}Y2}h{r%(7keIZN&`i!Ha)~tv^yC@yuO99D_wU==*)d}WOUawfJMx5q zntZm&wzXPArfuzd&zcTZ4n`mL7jb6Y2cjTZUm#Yn z#wEdRHIl1)6Tu9}1C<(OP1(S;A*q%l?H1R)XjYRv!JpB_I9C8=t=P=fyyb4lFtSng zI~t$>qa!NbTGyn{+Rfh4`Hgh{$pnC^GknEw6I+1iT^}`y2uO-macDWPZK?K+ zZ?lKexP2G47j?B&iIDj3mPPEkPaqpAFF3UKLw=l5hj^+6F_(|#1+$`5&!Ed6ZN z((J9dBY{>PQ>d#b&!6a-9vs(wGwgfz@~1+e^xju%?VJG5Y<^m%{M#JOP1l0X_knr# zdl_%d{PgJkl8YbxHP}PK0HuNY^JRXDnPWc2l4e!+q+$YwC`>zQxM|4E#@170K#Qc_ z(B0Y=!s^JX7NStUbW5U<@fbnf$Vh%gA;SimQ!XP5_p#4`0amMMT?=^L&Gy9vlG8n`g|Q*Frk`=4x4xi{1@@#I(U=V{PbXXSMY7iMoo&8cz4JhlB0PFovU4nm6=ltJRPpBlC8JxNgOa&+51iNpS znG1(u`agE!Uc$`Yp-_1_2BeKTT0uIw_Pu}dYcW)~ zk7dsPsEw{$@A^4Xzv4s#iM*)gce~)ZH5Dfeq(SOB*v1R?17=}oX_>X%nSeT@RfpJv z?Mg^1cNB$99cSTvp8rR@!>hNVbWMVI_lW9J?aKDF!g-Zy>J7$F=z)nt;Ih}>V$|U) zK(p!q71}p4rX}E_a<^QYu^8Zn;fA8rGBPJrJaKYKuZMf1#QF1BT8(duuv&h%W z2Z8(_$v%E3S;@aAy3sC>**ryHb+ZD@I`6fCgL4Zb7Wa9W2QYhd%St=KF&XU*sqV1j zkgM*1S$M;K1O){}jHm*k|I?%jK&oEm%AfnLMx^u!jBZmSko`Dqpx?0OhM0L?`szQV ztESqDLIoC2ViDv}w8b0|FlDueu(BxptzMuNl{VEKnw5g)KwIlAxzCC#3+z5a=?eA+ zS}pDXmAoy}Q7^7Qk0|H~E6eB@po;W_wVs2}wEB}zaBoh{y!me;7T(|IaC|JhgF@*p z$_-omKa}jJrp!&n!^2}$?|T*CRF%r^08l`d>Z46vO5yRE`$vaXb@!mtw%OUJ`(+l* z^E0-m80ilfu>?T+v$G%G6||`-NFAO=q(9a9Du|(>A(~qO0boq8AUWZikfNgS4Rr{o$Sz#&){q`6i;i_;^T_yUb zAXkb=p3AwEDk45;>Ts{QiG0$M)s_%P5=FK%E99A}$gU4rGa3Yu8KX349F!WO&~ecu zT0xqDb3Ss_+u)CuK%PD&PQWnStM~7J+jW85*tBo*CDf^G9w-VR*bA`pJ?p{lI71gy zrk1F<_*@&Klq>$T+q;nzz|9F`^V8Z$No@J zvFPb=$P*VA7keA71Mm6BF5!Ib!9}sw+=qr2p2c!)wy=dCuR6SIY|QEH?KOX-13BE# zU_J_acKkmvBn`=68noHtzu3)JKw5HpMW z+F|A@@9MCJ4y*w^yll_rzH>#Ns0$6~&%cti?Oq$iEmovXy)fl%Y;ISmcJKEJdsav% zlG$($MVks6;lUCF1IgluPvTO815X&((xP8)`<&cx*k=Hsb}Yl4ya+Bzu&25uG4(ms zH15e6-yalFhe_);ov!{@YC{En1j6)B%wbbSN-ka!`vq%jtY$MS@7P8^IiGO|h0=)e zv4DYo5&(Kd!)|`ym5%6m?09>IkY^uB+Ek!%l5N4j^ zoEvo)oa+h;#e!yg{vp$~(;h*UOIP;38E>dh%^QFYj19oKgxKVfJ*)#1bUA<y2rhpBb*i&o>XHfmk=$o%w4pT2r~$pT^ES=y-r{Sjn>PEe4%J96%#mAybhXD1?4 z3@})LzI1!E;3^@NntlVrCyf_+Sr(L4T~u1yTUJ(fh~Wl-lzuctoP&pN=Z4tu7NxUG z@N~Gyuy>_6g@)#B)*%u)d<-Dpb+q$W@r=JWOZ#{F`8AFQ+)Itq^o6TpI}>Q>ces|g3B`&3$|xO<*Lt1GmXy-uJg}fGYL2^knhzE48>b-K=ND*)3pQ4)d*L1lXFKlpLthx zU=|}Y$-Nv1B=a5;Yd=fnJ3<)y11~$kaT6o2?C%H7CV3Tvzo(0IL|e;j1k7#|?Pq4z zdpN+D%Zk5=xrZ3Z2vHi`naEipCrz^JzVUJNH9WjID#antB^m_AG$3t$kegg^;TB!} ztX}|DC)>Aeckfrr)qdRTz}VwrB1Q0+P{4;dQ$K*Se_Px~WB?y}oIu2u9z{PukdFGi zuk*K3#g~R+3#Xa~2rgJ86^XP2*?FOW^J2QSHS+|ox^KdGWO(Z>+EBJyRaxMVDt^$r zR}2hRJ_trM93l=dY7L7-2S4&AQ9Ui?Bw`G6_`KyXfIJo*0oyJ3RndSQi1ae6Sf`tI zhqb4loD}q3h}4Zp7l}5$u7PCObAuSGznS(}CHjGFXjJcXWgI^R0+EKojj@~5>hxYf z<pJOJw6299g7?aF3!} z&%LBJ&c=HON-(!dmjylYpkqsOqIYPuw#KLt>4@6YY}ITLwYS)#3$=<4v6a%QO|1}VRa+#q zQCn*7h}4RT@c!J-bKlSXy#N36zOT>6I_G!J@0{yg*Z2Fqu9Jl8#yXrFCpj1x7&!HG z;bsgBj1j=!J8VaQpKCRC)xa<2fGc_yY`|9pn{zzyKfAB4bpQjyQQpIEMglQv4`{p? zsC_fg+y@beyzTG8;B`CD*V8A^)9udbU>E-YHy>|^oT8kf%;~#nRXiwfq&Q1?=G2=~m-!v2&CT*2xV)q_9H+=aD|iJuU8X4M(bfk=EVV*`1nA^~_h4ipBpNe0?%8{=ow#2e^d9@f|Su_d=`y4?Fum-!oQJns-k!-!O>Cq@UIl}qsl)9-=mXLCg=}R&k_eD3+w=;#hvtXh%wR#Z5Ep9UKRa{bhz$H;v zvJmS7`u5tq)dglSxcah1Mc*pyfw%Qi=7^e?tEX+pH#uS`_JDbRRaGWa>8V?hyacaW zV@15K!QEr9E~zqi>!$Uq`%BMqi&5XiCGV4x>aTTR!aI3B`9viiNVVqWc-!egX7cSv z-hX%|W@c)ceQ#O27-BjpX{v20yOBTgQG@yh z)wmCx;~#gZe|Xn|J69lWkX?d;_k4&FQL0PLx_Q6?(QrqIeZuU^#Yc_RP0P|oZiY!< zs#)deA;JP{2O=JyO<=CXrLPmfi-Fz@)5`b%O{z3r)UMAl#>*=??RMI$tz>8wdG+?xWqI;oM7Jn?PG)b z{dYFp*X@L%YngO6wP%v3rk~0`PO2t!m&+M7^cbcBT`sGGpv%vsz`qloJMGNiJu^@h zigl(&$`|TF5mt8)XXfVSyl&bnjOV(lK27I$9R?YWH>Kn(nb{O z5_R$#y@2EIlPWu3^;*B!kcYicg*^fZnxc$}#3AHxm!)1J6xXn5hv#VFxOBt*J+UjSd&u!ye6%@dZik2E38 z#J2z9s!G|7AFYp@*+q?dE)*uK&8~L4d!fLD6wWnhPWaI^&IoiYGX@1c8o{{efpEc2 zfP@&x`{I*lCygO*S&SJQLnK8WXhBttZO51F2eLCpLcf=+#<%k!)#u_Q!Fv3U$-(tcUg_5Z@%KznEP(>p}w) zLeEn`&xd3awVF{D1D~R&8_txu7j5G467n}BJ++Hnj_)u+Al|a4p4MZlDwF*UrV5(m zX~%igjAHYdGjz5zAe>j87@G_!gj%#;YLo^~6<|&7iK+=5#+LPS(yVN=xwEL(0(BWn8dHVwxQE$ci`POh|cz5+qeugz#e|f zBsSl<*?LJ+ljcuu-Zy(mKBZxK)dk{2BOALIiF`I5_$_E5ZzXPnLh9k)2B#~$(iM(} zCoMVAAbvMR50R*u^HqeEsnM;Euak+zL9@=vfRil0G@ckY^ge&;8O?4p!pPyO2EfA3>IxcL&k%0mqd!qGMF93JL#?3(g)v zK!gS0?O-r(dqD~%n#s@&LAP+cOY#t<_%LosgTa0r5)>lcXp$SRgks$LzS0KTRDu}M z&VdP!M%|AcfE|7AQ(bCY78L##q-Htsx`OrSj0Q3WM?5;-c3NIueqatDi<4gbJG7Ws z&L7+8c8;B%;Q{ps`&Vi z@=vfxs!dKGmxKfTM(leTkaFa9dT03-^+Fh6BnLybrwCxWf|^P6dVa2l}BLH233_TPqA z$>HN|CquY0d9cCSaEVKonfJA^KaQ;R-0A5JE<$;!)GgpW9nFOy|1u@xQ%NxRYp|r3 z1Je;SO>ok3va94|3+)0@-j{l>wY616$^>4#aTH9UGIFL4vwnP@J4KEgZIneLnJSwT^IV862S69}Pk{~=-<%xu zhGOf4_0hTALv_t2o0^c@=9jL!4Q(htT2J3B4iZgDNmKt=7_2~ub#nfvqdH#MTv!&$jY!-J0q8*oDoP{|e+0}Yo4 zz~DDSg-o!ML1g*S4|(exEv~Lg>Jj~!RRXfFq#)S`JL{@3yW;!g5h2p~s>%JAvhboj zT&*^I^dT4jPN&UwUCpL$;)nh23Lo?8Rgt`Ge+?bx_Eyx+n(ce+&XCbnX`qsW_(Tkpw?RepmS!s+IU?w;Wkq= zz`zzm*Je)E!B%^G_R|?z4MHOZ9n7?9BYT{7^_6gZXNEZ%^@t7dU*5y%BVZ#lm^ zO+t&oa1{r?nAcL99;c_xWP4?!M5h1*Z1RwCfU8#lG5}YSIbsYM^FmOSYqffCQ73E; zDp8!?UE4i>v9U*IPuCmu&Kbx;KDBqWe3LET(!$){bih-CCoM&03J5`^NkvB~1>U9s z+_k&`(hBxAvYk1EdB@&h_YgCc>Y6^2S=Yw!vlFc!mlNvFt*Gv_uHuvG<7;S++6LXc zJWJQ_HLbkKBsIq))fJbsg|M)X_AqW4Wyr?G&)1FnlKBLXCn}?#+#lL@UCe*B z{`FhH{^VT?FQx97X}Kra{0^|oY6|Fm8XtGPS38&xwI$4HF2ITzIsGV5j%iyZ#NmX^ z;9X&46-x?Jpvumj-(xJx_+NnD*KWaF@A``6$K~+1of>&oG=krwu zquXa18dh(>uSmv=??qysc~2 z%O+56zugNAYkAaFw9C?B$CI{Q(!m^+nse-g;mPhdSuNO4>%?4h<#!PQgs&S~Z~)Yb zRup2n6}&bdCJBGfaC)Z99*02(l-E82_+AlcWwZq7D=O$UHWi-4>Y6ei5ZcWCaDS=# zz}8+4kPQ{CV~=&u1-{0ze!=UzF5UQ~2&fA{WHf{rwzsH+&3}mk+LllaVBV7=a+E@? zO|iU4HL7j&c~fLcZdqY1swNUyT3eFhRO%kz641BR5gM{R#}UrM{){U-BrRSs(lh!j zSC11AYnqLPPXWoPmnitologqhQ+^gWc)RaQ+1XvP5AOq8&o}-GEG1|d3#-sEKB6jc zY_>$2^}4-jCm=+f_tjaEJM%#uixZG+gY|%}9y}pv8_er2qD3)*Kmc8kF(I36atDcv z!c<6J;p1`ptUfD<0dl*X|B!?IJB$O#AHKX1)#i>s-z;va#$aN(MjsNQ~AEtebl8i>9l(*Q*5{Z%d zs7S65Jg%XM7Ogt?_0K@L7aCF#AD;sQ6iQ3UAZla{Pr8Df@IeSLv1Si{!VFWPh;0Wf z|D_^86@a_a7N7J=O*Ra#jKv7_c{?K7a5B={E%Lsc)w1sosqi7N%1-PHoTq@V9SMrC zazvzl9!+A<$9eKm)T@Vy{6Ny`B~!>+&_w&)(M-I@Af~xysGaeeBq23EUcwkT`uIPm zxBqV1|4ncFE#v;NIjB2*KBf<^q zgtc&#@O_I)Hmr64j;auz?}iq^;<7xf*hs-tXiY;OBZL9^#TH)7dFJ?zUklst*kq)T zucdi1-cwY8+wp6`<*o`t^`xw>B<1At=( zM*2zXEjwhi;^MvWNTKRu1qB7z`#&&&hAu8Hfh&W_@9(qbugP~`_d{}tsKc$Tg|0q2 zrWd3}=*?9tTMl5HQfg6cyf!~3aE}3baw3zvmC2LUs)aWA zvHJv|TJ+BWsPl!$+7$jA?J!9m`use4ncRP}UOJe1o4hYc-jC*!y;a<{von+0Oseg< zwN1^DlV!8RDhAqH~w} zOCgcFn^sgPl588bzmdODBu0vmurTSMxPP(`#!lFi1&B@s?SBFp8DujZ5H@T>o%X-gkXg&p7AeWm8igK1pNdg8KTW zjT2GAF|K)`k6`qE*sGT>?-l8!Uho=K5)GZ@QSlo6zKmIGquOJ32dZlCegk8ECi^hg z!g!5O5_l3in*3&(=-XrGWn`F_(5WZt<)dkd%HvJ zXJuuR9rmULG=F~N8~6Jx;?=N52+a(q5Rbws6akV7&+X>JU$zxfs~WS?0^BUa;r}U zUQ!^j``gAU83TEJ2R{1N*)Y}i)~)Vx>$;HTH>H9qo;NchJ;I#X^=*=;G^z)2r*@D? zhe3<0kZe{QNKonSb>U}{gjQfwE8r9WBz?3)5?L+*G3eUI^%hu(?n18U2ri0c)5CcH zNu+n)%sybk5OIS0+GI>0Zawx!Y1?5~RL`kqe$5-F9Z*C(?_3?b5>Payg15$T#a zI==kkAc@Jb4dun8!XS^PMV}=AS#G`U6-h5*8{0W|=U=7R`r#EQb{M|P!;|*WZCwc{ z#{S775{wDJj+{PoeM%KGv9cOe<9nMRasR9dpI+LJw(yO`qSV76DsDM`SZocv$SN8Z zU$*+*I5kK4&PDqEw$DFK`PZ*svkMCw>pk+SBMXoDrH5NXAqLN77$-l&_7wpypGngZ z)pJIkDF!OKym62E#oK`h+1vRHo4?Pk#o)Nmn>!vfWal}7$t4rf8y#Z%Pp-ysnOazU z9IUVz0p_AkL`T2f&4q@m$hU3sDl02997YEKF_P8vbl-10z{(ahcugKT8>f!vjE~!5 zb~@#20d%;QBzW1#h!co!F3)xe+rS6%=>_l-os`ex%>loAC&IGE?TjP-{Gud&4+Z8V_X z+n0xr6N}QVvTsYrR2|l|w5RKRr>>lkv)$3@Il?W9OA%SHSNskjw~FWRSJF1%yhDrk zdxYzv=wW0Gjl7fijH?uYA+><{>N}kr{s93Qgt$k6@X;D^ofHMnVFiDG|4bz}v$CEv ziCc}{BCvyBeW9!GhSCS)QYhM^HF?nR^|6V4l>rxB;d4?_>Kk+bY<2a;)ISLD=qVyy zx0VMOS~m#>Ics_kDqaDFbG;g`u?ACXYj*4#^U`5VWVqR`DNtW8zUk+u`0m|126&O_ zR7?_uX0h{~l?V)YUhkv&BSaiAI6DMH=fP`wiBWczSM*G> zYC~BH955XJP6~P`YlIrJ#z0j8N)3l<SH`|I6B@o< z?J*<=;Jsh(?((ubL#5zw{u?K`S2tdq;>y?T%))E@a$GBQ9SvF?eRjL!QBBCtX{&*> zMTpmsN(hb1*IXRW5lgIb9lL`#)Hy7e`feNP=pNT_X(l3KBDUEu2UHOrAEnO)%Eh*50hY%X9RE%xPXX;-ujdr=5Tp2s}H|5?Bj zhnK74E~ZfMq#KvouUSP75gn4={gS(WRFk-@f9FsARbVMlgh&?5yDLOU$z218JY5aC zzEaiRyFS-r-5y0(TTz1gF9ht~js7{^skt+G-&O82Y2Zxhw{2+4>~*ts_bZp9M?*mq z#3~Q(HWZP|ko9cn4Du)mbVMZtcDg~v%}mju<-v`Be(@@s#*~Hp=)6}3FI2*M_Wp_1 z9)snDCiz;)-qGaoX3fp7SC5Hl+4hSgdEMOHY=cK!oDqmT_Pq{C6Ti^?XGu#zvUUV? zK<&0*Hh25`QjF@8>bQ?p1QgRaXnc|^nSFO#RN*`BQKt1--=o!1X;Ipvw=R_E$jQpO z43=AKZhbdDCOo+5Ae$xH902Hs>7Ac5u0QfGj=t!l=3W^}63rB{gM?9jVa&hii=Dig zpJ4y0?)Vob`(%;1)*14_7;YDoil)^M^J^YvwMvc;(LP4i4rwaDy3zz>Z+$Gh8rQT^ ziDu9>F)1xBF8;Q!44BS8OzPpI``|{~V8~J$4(9$sw9DCcey)k87OmIt=!{42qtnNa z9}h7<00o}#sVL7El;)oyh;(hQjtME=ftU5@q5zo`0EjkKH7CR{EI$RYGFWl^#0md( zXF68*g`C~6Ry1eYwJXqNQz`Err`a!QeqLj^A4uxGPlHRwW5=^EhG%}T&njL@(mWKZ%EeB3BHT&H<&4hGc4K?4Z@c=37hFY9ZdggW){B%&f(M0HS4_Ht+rasGb&t{qAxC5C^Q>)sd(Ks&0-yr6zL!ta-H$n_KbWACk%#(U zD{`0Ff4!{E_fY?T{5kU(P$0Sh1O^v0D@JfG>BcEIVi|xO<12A!p}V&ifsJ8&BX?CD z2--k4At534d;EG&KK-{V$h$)~mNKo?D0n7Ml7?J)RuWO>VZgxi4=n% zb^M6nuQ)CD>c28=P-KZqDM!Q~<>V43@mL$Y3})e8knKBc<9MWmuQKJv@58P!K1^fg zc5vZcfk_xK@}k0XQT3C(Sg979oW7T3mkRcDBea$ag8a9&-%p@-gCdpVd ziW4>BILR?d{BD&VXb=+~v-s;|Fz?kE|H*`5g~1ubpz?tBnMCv&D2m}J6D_ugj8S=K z`408ZGQsIg9lOrJ1}wKMq=zMnQO1|*^rlkM8t19*`;|Ch5+v(&PDGG(FB|Q^m~(m( zwl$V9+_ZIUIr`fcYfIM1keQ9;*v78MJgChZQ^&He<>+{y3cAyyt_ELi?V-X#H$DE4_PJjM8#ym`vs_ZOL;EpsqF17?5Iy^yrD9@iucY zdNYmDu?l5((ng7W`1yzQ^orw6qqvrj`;jIu`SOdkdJbz7QORqzz~>3F4?hcVSf{u@ z9#R_ivG9;nBPRKm`$$zlh5o#p^hhP+KGX0W;6nE~y#g&zT78!NhXcsuGnex=1G2a& zuh@@@#FIiD#kX!0MqZN4x$_>E$AV$lRIa-)xfa`r)rZj3x6C{Gxav)eDo%rWxpKXL p^a7q$@b^3UzhxGG%FT}lAZ8I3v?i+?5m+XJp0+W(@`~fV{{miSrxE}F literal 0 HcmV?d00001 diff --git a/docs/modules/slam/graph_slam/graphSLAM_formulation.rst b/docs/modules/slam/graph_slam/graphSLAM_formulation.rst index 43f007e7bf..4978596c10 100644 --- a/docs/modules/slam/graph_slam/graphSLAM_formulation.rst +++ b/docs/modules/slam/graph_slam/graphSLAM_formulation.rst @@ -70,7 +70,7 @@ Using Bayes’ rule, we can write this probability as since :math:`p(\mathcal{Z})` is a constant (albeit, an unknown constant) and we assume that :math:`p(\mathbf{p}_1, \ldots, \mathbf{p}_N)` is -uniformly distributed `PROBABILISTIC ROBOTICS`_. Therefore, we +uniformly distributed. Therefore, we can use Eq. :eq:`infomat` and and Eq. :eq:`bayes` to simplify the Graph SLAM optimization as follows: diff --git a/docs/modules/slam/graph_slam/graph_slam.rst b/docs/modules/slam/graph_slam/graph_slam_main.rst similarity index 78% rename from docs/modules/slam/graph_slam/graph_slam.rst rename to docs/modules/slam/graph_slam/graph_slam_main.rst index a1248a01cc..987eed385c 100644 --- a/docs/modules/slam/graph_slam/graph_slam.rst +++ b/docs/modules/slam/graph_slam/graph_slam_main.rst @@ -13,9 +13,9 @@ The black stars are landmarks for graph edge generation. .. image:: https://github.com/AtsushiSakai/PythonRoboticsGifs/raw/master/SLAM/GraphBasedSLAM/animation.gif -.. include:: graph_slam/graphSLAM_doc.rst -.. include:: graph_slam/graphSLAM_formulation.rst -.. include:: graph_slam/graphSLAM_SE2_example.rst +.. include:: graphSLAM_doc.rst +.. include:: graphSLAM_formulation.rst +.. include:: graphSLAM_SE2_example.rst References: ~~~~~~~~~~~ diff --git a/docs/modules/slam/iterative_closest_point_matching/iterative_closest_point_matching.rst b/docs/modules/slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst similarity index 100% rename from docs/modules/slam/iterative_closest_point_matching/iterative_closest_point_matching.rst rename to docs/modules/slam/iterative_closest_point_matching/iterative_closest_point_matching_main.rst diff --git a/docs/modules/slam/slam_main.rst b/docs/modules/slam/slam_main.rst index f4d10feb9a..86befa6e35 100644 --- a/docs/modules/slam/slam_main.rst +++ b/docs/modules/slam/slam_main.rst @@ -5,9 +5,12 @@ SLAM Simultaneous Localization and Mapping(SLAM) examples -.. include:: iterative_closest_point_matching/iterative_closest_point_matching.rst -.. include:: ekf_slam/ekf_slam.rst -.. include:: FastSLAM1/FastSLAM1.rst -.. include:: FastSLAM2/FastSLAM2.rst -.. include:: graph_slam/graph_slam.rst +.. toctree:: + :maxdepth: 2 + :caption: Contents + iterative_closest_point_matching/iterative_closest_point_matching + ekf_slam/ekf_slam + FastSLAM1/FastSLAM1 + FastSLAM2/FastSLAM2 + graph_slam/graph_slam From b9345da036bb9655c84b8081199f99d17b25afd6 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 7 May 2022 16:04:39 +0900 Subject: [PATCH 494/940] try to use python3.10 (#561) * try to use python3.10 * try python3.10 * try python3.10 --- .circleci/config.yml | 3 ++- .github/workflows/Linux_CI.yml | 3 ++- .github/workflows/MacOS_CI.yml | 4 ++-- README.md | 2 +- appveyor.yml | 2 +- docs/getting_started_main.rst | 4 ++-- requirements/environment.yml | 2 +- 7 files changed, 11 insertions(+), 9 deletions(-) diff --git a/.circleci/config.yml b/.circleci/config.yml index 275ad3bc7a..075a613be0 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -6,12 +6,13 @@ orbs: jobs: build_doc: docker: - - image: cimg/python:3.9 + - image: cimg/python:3.10 steps: - checkout - run: name: doc_build command: | + python --version python -m venv venv . venv/bin/activate pip install -r requirements/requirements.txt diff --git a/.github/workflows/Linux_CI.yml b/.github/workflows/Linux_CI.yml index c706a50ed6..73f8aa5c0d 100644 --- a/.github/workflows/Linux_CI.yml +++ b/.github/workflows/Linux_CI.yml @@ -12,7 +12,7 @@ jobs: runs-on: ubuntu-latest strategy: matrix: - python-version: ['3.9'] + python-version: ['3.10'] name: Python ${{ matrix.python-version }} CI @@ -26,6 +26,7 @@ jobs: python-version: ${{ matrix.python-version }} - name: Install dependencies run: | + python --version python -m pip install --upgrade pip python -m pip install -r requirements/requirements.txt - name: do all unit tests diff --git a/.github/workflows/MacOS_CI.yml b/.github/workflows/MacOS_CI.yml index 4088c4900f..5c796120a5 100644 --- a/.github/workflows/MacOS_CI.yml +++ b/.github/workflows/MacOS_CI.yml @@ -16,7 +16,7 @@ jobs: runs-on: macos-latest strategy: matrix: - python-version: [ '3.9' ] + python-version: [ '3.10' ] name: Python ${{ matrix.python-version }} CI steps: - uses: actions/checkout@v2 @@ -32,8 +32,8 @@ jobs: - name: Install dependencies run: | + python --version python -m pip install --upgrade pip - #pip install numpy # cvxpy install workaround pip install -r requirements/requirements.txt - name: do all unit tests run: bash runtests.sh \ No newline at end of file diff --git a/README.md b/README.md index 8972bae5fa..f54b880dc0 100644 --- a/README.md +++ b/README.md @@ -96,7 +96,7 @@ See this paper for more details: For running each sample code: -- [Python 3.9.x](https://www.python.org/) +- [Python 3.10.x](https://www.python.org/) - [NumPy](https://numpy.org/) diff --git a/appveyor.yml b/appveyor.yml index c35e76ae4a..4964bab3da 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -8,7 +8,7 @@ environment: CMD_IN_ENV: "cmd /E:ON /V:ON /C .\\appveyor\\run_with_env.cmd" matrix: - - PYTHON_DIR: C:\Python39-x64 + - PYTHON_DIR: C:\Python310-x64 branches: only: diff --git a/docs/getting_started_main.rst b/docs/getting_started_main.rst index a7b9ff3607..4a19126686 100644 --- a/docs/getting_started_main.rst +++ b/docs/getting_started_main.rst @@ -26,7 +26,7 @@ See this paper for more details: Requirements ------------- -- `Python 3.9.x`_ +- `Python 3.10.x`_ - `NumPy`_ - `SciPy`_ - `Matplotlib`_ @@ -41,7 +41,7 @@ For development: - sphinx (for document generation) - pycodestyle (for code style check) -.. _`Python 3.9.x`: https://www.python.org/ +.. _`Python 3.10.x`: https://www.python.org/ .. _`NumPy`: https://numpy.org/ .. _`SciPy`: https://scipy.org/ .. _`Matplotlib`: https://matplotlib.org/ diff --git a/requirements/environment.yml b/requirements/environment.yml index 1441b79080..109fc57789 100644 --- a/requirements/environment.yml +++ b/requirements/environment.yml @@ -2,7 +2,7 @@ name: python_robotics channels: - conda-forge dependencies: - - python=3.9 + - python=3.10 - pip - scipy - numpy From e18799cbb745d3cc3ff5cad707f401ee1f218834 Mon Sep 17 00:00:00 2001 From: Drake <1024507980@qq.com> Date: Sat, 7 May 2022 16:20:20 +0800 Subject: [PATCH 495/940] modify end node's state (#656) --- PathPlanning/DStar/dstar.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/PathPlanning/DStar/dstar.py b/PathPlanning/DStar/dstar.py index e01508b3df..f8954d776c 100644 --- a/PathPlanning/DStar/dstar.py +++ b/PathPlanning/DStar/dstar.py @@ -160,7 +160,7 @@ def run(self, start, end): rx = [] ry = [] - self.open_list.add(end) + self.insert(end, 0.0) while True: self.process_state() From a3fd04f68f3b1bada4c6393e5b9dda3704eb36bd Mon Sep 17 00:00:00 2001 From: jsbyysheng Date: Sat, 7 May 2022 17:15:01 +0800 Subject: [PATCH 496/940] fix error: 'numpy.ndarray' object has no attribute 'append' (#662) * Update grid_map_lib.py fix error: 'numpy.ndarray' object has no attribute 'append' * Update test_grid_map_lib.py * Update test_grid_map_lib.py Co-authored-by: Atsushi Sakai --- Mapping/grid_map_lib/grid_map_lib.py | 4 ++-- tests/test_grid_map_lib.py | 3 +++ 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/Mapping/grid_map_lib/grid_map_lib.py b/Mapping/grid_map_lib/grid_map_lib.py index 10651cc673..a93ea309d8 100644 --- a/Mapping/grid_map_lib/grid_map_lib.py +++ b/Mapping/grid_map_lib/grid_map_lib.py @@ -120,8 +120,8 @@ def set_value_from_polygon(self, pol_x, pol_y, val, inside=True): # making ring polygon if (pol_x[0] != pol_x[-1]) or (pol_y[0] != pol_y[-1]): - pol_x.append(pol_x[0]) - pol_y.append(pol_y[0]) + np.append(pol_x, pol_x[0]) + np.append(pol_y, pol_y[0]) # setting value for all grid for x_ind in range(self.width): diff --git a/tests/test_grid_map_lib.py b/tests/test_grid_map_lib.py index ffdb72b1ae..ed4303d4dc 100644 --- a/tests/test_grid_map_lib.py +++ b/tests/test_grid_map_lib.py @@ -1,4 +1,5 @@ from Mapping.grid_map_lib.grid_map_lib import GridMap +import numpy as np def test_position_set(): @@ -19,6 +20,8 @@ def test_polygon_set(): grid_map = GridMap(600, 290, 0.7, 60.0, 30.5) grid_map.set_value_from_polygon(ox, oy, 1.0, inside=False) + grid_map.set_value_from_polygon(np.array(ox), np.array(oy), + 1.0, inside=False) if __name__ == '__main__': From 3d209faefc5d0cedf9ba347d189e99caf0e5265b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sat, 7 May 2022 22:43:31 +0900 Subject: [PATCH 497/940] add gh-pages action (#671) --- .github/workflows/gh-pages.yml | 29 +++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) create mode 100644 .github/workflows/gh-pages.yml diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml new file mode 100644 index 0000000000..e51197cb37 --- /dev/null +++ b/.github/workflows/gh-pages.yml @@ -0,0 +1,29 @@ +name: Pages +on: + push: + branches: + - master +jobs: + build: + runs-on: ubuntu-latest + steps: + - name: Setup python + uses: actions/setup-python@v2 + - name: Checkout + uses: actions/checkout@master + with: + fetch-depth: 0 # otherwise, you will fail to push refs to dest repo + - name: Install dependencies + run: | + python --version + python -m pip install --upgrade pip + python -m pip install -r requirements/requirements.txt + - name: Build and Commit + uses: sphinx-notes/pages@v2 + with: + requirements_path: ./docs/doc_requirements.txt + - name: Push changes + uses: ad-m/github-push-action@master + with: + github_token: ${{ secrets.GITHUB_TOKEN }} + branch: gh-pages \ No newline at end of file From f74f0c1da2030794cede57709df076713be04269 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 May 2022 14:11:21 +0900 Subject: [PATCH 498/940] enhance_github pages doc (#672) * enhance_github pages doc * enhance_github pages doc --- docs/_templates/layout.html | 8 ++++++++ 1 file changed, 8 insertions(+) create mode 100644 docs/_templates/layout.html diff --git a/docs/_templates/layout.html b/docs/_templates/layout.html new file mode 100644 index 0000000000..7cd969e52f --- /dev/null +++ b/docs/_templates/layout.html @@ -0,0 +1,8 @@ +{% extends "!layout.html" %} + +{%- block extrahead %} +{{ super() }} + +{% endblock %} From 785e62175fe71c277d8501018347554c5edda836 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 May 2022 14:23:11 +0900 Subject: [PATCH 499/940] enhance_github pages doc (#673) --- docs/_templates/layout.html | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/docs/_templates/layout.html b/docs/_templates/layout.html index 7cd969e52f..89c38a39f9 100644 --- a/docs/_templates/layout.html +++ b/docs/_templates/layout.html @@ -6,3 +6,19 @@ src="https://pagead2.googlesyndication.com/pagead/js/adsbygoogle.js?client=ca-pub-9612347954373886" crossOrigin="anonymous"> {% endblock %} + +{% block sidebarsearch %} +{{ super() }} + + + + +{% endblock %} From 20220fdfd27b277d8ff5fac22680b47ef3ce7149 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 May 2022 14:29:48 +0900 Subject: [PATCH 500/940] enhance_github pages doc (#674) --- docs/_templates/layout.html | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/_templates/layout.html b/docs/_templates/layout.html index 89c38a39f9..6593bd00c0 100644 --- a/docs/_templates/layout.html +++ b/docs/_templates/layout.html @@ -7,7 +7,7 @@ crossOrigin="anonymous"> {% endblock %} -{% block sidebarsearch %} +{% block footer %} {{ super() }} From ec19f6373d1aeae40ace9bf6100f49da4b09a6cd Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 May 2022 14:39:01 +0900 Subject: [PATCH 501/940] enhance_github pages doc (#675) --- docs/_templates/layout.html | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/_templates/layout.html b/docs/_templates/layout.html index 6593bd00c0..c0cedb2330 100644 --- a/docs/_templates/layout.html +++ b/docs/_templates/layout.html @@ -7,7 +7,7 @@ crossOrigin="anonymous"> {% endblock %} -{% block footer %} +{% block content %} {{ super() }} From b01128a8f65605d75016ef980009711e1f49c917 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 May 2022 14:49:20 +0900 Subject: [PATCH 502/940] enhance_github pages doc (#676) --- docs/_templates/layout.html | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/docs/_templates/layout.html b/docs/_templates/layout.html index c0cedb2330..4b5b278932 100644 --- a/docs/_templates/layout.html +++ b/docs/_templates/layout.html @@ -1,13 +1,6 @@ {% extends "!layout.html" %} -{%- block extrahead %} -{{ super() }} - -{% endblock %} - -{% block content %} +{% block sidebartitle %} {{ super() }} From f5d80ecb1cf17193b9061627215ee18348e3b6dc Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Sun, 8 May 2022 15:56:51 +0900 Subject: [PATCH 503/940] remove old doc links (#677) * remove old doc links * add github link * add github link * add github link --- .github/pull_request_template.md | 2 +- README.md | 5 ++--- docs/conf.py | 11 +++++++++++ docs/how_to_contribute_main.rst | 2 +- users_comments.md | 2 +- 5 files changed, 16 insertions(+), 6 deletions(-) diff --git a/.github/pull_request_template.md b/.github/pull_request_template.md index c541063156..c8790ad9ec 100644 --- a/.github/pull_request_template.md +++ b/.github/pull_request_template.md @@ -1,7 +1,7 @@ #### CheckList --[] Did you add an unittest for your new example or defect fix? --[] Did you add documents for your new example? --[] All CIs are green? (You can check it after submitting) +- [ ] Did you add an unittest for your new example or defect fix? +- [ ] Did you add documents for your new example? +- [ ] All CIs are green? (You can check it after submitting) From ebdc2d45003c9ce86eaebb1ebfd09d527c7e2eaa Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 11 Oct 2022 06:46:55 +0900 Subject: [PATCH 538/940] Bump matplotlib from 3.6.0 to 3.6.1 in /requirements (#736) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.6.0 to 3.6.1. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.6.0...v3.6.1) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index a85aa121e6..67637bb3e5 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.23.3 scipy == 1.9.1 -matplotlib == 3.6.0 +matplotlib == 3.6.1 cvxpy == 1.2.1 pytest == 7.1.3 # For unit test pytest-xdist == 2.5.0 # For unit test From 001efc5935c4c5a3d25c2d5441db838817fa44b3 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 13 Oct 2022 20:13:00 +0900 Subject: [PATCH 539/940] Bump scipy from 1.9.1 to 1.9.2 in /requirements (#737) Bumps [scipy](https://github.com/scipy/scipy) from 1.9.1 to 1.9.2. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.9.1...v1.9.2) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 67637bb3e5..e2fa5d7546 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.23.3 -scipy == 1.9.1 +scipy == 1.9.2 matplotlib == 3.6.1 cvxpy == 1.2.1 pytest == 7.1.3 # For unit test From bc88e70f7ed53226d9c200a2087ab361a2d8bf6b Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 18 Oct 2022 07:02:25 +0900 Subject: [PATCH 540/940] Bump numpy from 1.23.3 to 1.23.4 in /requirements (#738) Bumps [numpy](https://github.com/numpy/numpy) from 1.23.3 to 1.23.4. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.23.3...v1.23.4) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index e2fa5d7546..160c043818 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.23.3 +numpy == 1.23.4 scipy == 1.9.2 matplotlib == 3.6.1 cvxpy == 1.2.1 From 381634821511054f50dad6743ae0700d75525c72 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 25 Oct 2022 07:59:09 +0900 Subject: [PATCH 541/940] Bump scipy from 1.9.2 to 1.9.3 in /requirements (#739) Bumps [scipy](https://github.com/scipy/scipy) from 1.9.2 to 1.9.3. - [Release notes](https://github.com/scipy/scipy/releases) - [Commits](https://github.com/scipy/scipy/compare/v1.9.2...v1.9.3) --- updated-dependencies: - dependency-name: scipy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 160c043818..1170b24088 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,5 +1,5 @@ numpy == 1.23.4 -scipy == 1.9.2 +scipy == 1.9.3 matplotlib == 3.6.1 cvxpy == 1.2.1 pytest == 7.1.3 # For unit test From 39472e66d217b6980d8ec18431302219b5fe2412 Mon Sep 17 00:00:00 2001 From: Abinash Satapathy Date: Sun, 30 Oct 2022 06:28:58 +0100 Subject: [PATCH 542/940] Update README.md (#732) * Update README.md Updated the sponsors correctly * Update README.md Remove the tag. * Update README.md Updated development references and styled the single line codes in "How to use" section * Update README.md Styled single-line comments using syntax highlighting for markdown --- README.md | 35 +++++++++++++++++++++-------------- 1 file changed, 21 insertions(+), 14 deletions(-) diff --git a/README.md b/README.md index 97a7742dca..b46195f35e 100644 --- a/README.md +++ b/README.md @@ -70,8 +70,9 @@ Python codes for robotics algorithm. * [Contribution](#contribution) * [Citing](#citing) * [Support](#support) - * [Sponsors](#Sponsors) + * [Sponsors](#sponsors) * [JetBrains](#JetBrains) + * [1Password](#1password) * [Authors](#authors) # What is this? @@ -107,15 +108,15 @@ For running each sample code: For development: -- pytest (for unit tests) +- [pytest](https://pytest.org/) (for unit tests) -- pytest-xdist (for parallel unit tests) +- [pytest-xdist](https://pypi.org/project/pytest-xdist/) (for parallel unit tests) -- mypy (for type check) +- [mypy](http://mypy-lang.org/) (for type check) -- sphinx (for document generation) +- [sphinx](https://www.sphinx-doc.org/) (for document generation) -- pycodestyle (for code style check) +- [pycodestyle](https://pypi.org/project/pycodestyle/) (for code style check) # Documentation @@ -131,18 +132,24 @@ All animation gifs are stored here: [AtsushiSakai/PythonRoboticsGifs: Animation 1. Clone this repo. -> git clone https://github.com/AtsushiSakai/PythonRobotics.git + ```terminal + git clone https://github.com/AtsushiSakai/PythonRobotics.git + ``` 2. Install the required libraries. -using conda : +- using conda : -> conda env create -f requirements/environment.yml + ```terminal + conda env create -f requirements/environment.yml + ``` -using pip : +- using pip : -> pip install -r requirements/requirements.txt + ```terminal + pip install -r requirements/requirements.txt + ``` 3. Execute python script in each directory. @@ -614,7 +621,7 @@ If you use this project's code for your academic work, we encourage you to cite If you use this project's code in industry, we'd love to hear from you as well; feel free to reach out to the developers directly. -# Supporting this project +# Supporting this project If you or your company would like to support this project, please consider: @@ -626,9 +633,9 @@ If you or your company would like to support this project, please consider: If you would like to support us in some other way, please contact with creating an issue. -## Sponsors +## Sponsors -### [JetBrains](https://www.jetbrains.com/) +### [JetBrains](https://www.jetbrains.com/) They are providing a free license of their IDEs for this OSS development. From 2b877369a4a9335e5b28e2b8cabfe03c8cbb7405 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 1 Nov 2022 06:15:31 +0900 Subject: [PATCH 543/940] Bump pytest-xdist from 2.5.0 to 3.0.2 in /requirements (#743) Bumps [pytest-xdist](https://github.com/pytest-dev/pytest-xdist) from 2.5.0 to 3.0.2. - [Release notes](https://github.com/pytest-dev/pytest-xdist/releases) - [Changelog](https://github.com/pytest-dev/pytest-xdist/blob/master/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest-xdist/compare/v2.5.0...v3.0.2) --- updated-dependencies: - dependency-name: pytest-xdist dependency-type: direct:production update-type: version-update:semver-major ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 1170b24088..82598ddd69 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,6 +3,6 @@ scipy == 1.9.3 matplotlib == 3.6.1 cvxpy == 1.2.1 pytest == 7.1.3 # For unit test -pytest-xdist == 2.5.0 # For unit test +pytest-xdist == 3.0.2 # For unit test mypy == 0.982 # For unit test flake8 == 5.0.4 # For unit test From 2d0fa60fd40398244317491655f6a51462cb73c6 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Wed, 2 Nov 2022 23:23:52 +0900 Subject: [PATCH 544/940] Bump pytest from 7.1.3 to 7.2.0 in /requirements (#742) Bumps [pytest](https://github.com/pytest-dev/pytest) from 7.1.3 to 7.2.0. - [Release notes](https://github.com/pytest-dev/pytest/releases) - [Changelog](https://github.com/pytest-dev/pytest/blob/main/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest/compare/7.1.3...7.2.0) --- updated-dependencies: - dependency-name: pytest dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 82598ddd69..c8660ebd16 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -2,7 +2,7 @@ numpy == 1.23.4 scipy == 1.9.3 matplotlib == 3.6.1 cvxpy == 1.2.1 -pytest == 7.1.3 # For unit test +pytest == 7.2.0 # For unit test pytest-xdist == 3.0.2 # For unit test mypy == 0.982 # For unit test flake8 == 5.0.4 # For unit test From 768df6ffabddc030fdaef3c1668c06ab30d25ba0 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 8 Nov 2022 07:27:05 +0900 Subject: [PATCH 545/940] Bump matplotlib from 3.6.1 to 3.6.2 in /requirements (#745) Bumps [matplotlib](https://github.com/matplotlib/matplotlib) from 3.6.1 to 3.6.2. - [Release notes](https://github.com/matplotlib/matplotlib/releases) - [Commits](https://github.com/matplotlib/matplotlib/compare/v3.6.1...v3.6.2) --- updated-dependencies: - dependency-name: matplotlib dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index c8660ebd16..ffaef30d19 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,6 +1,6 @@ numpy == 1.23.4 scipy == 1.9.3 -matplotlib == 3.6.1 +matplotlib == 3.6.2 cvxpy == 1.2.1 pytest == 7.2.0 # For unit test pytest-xdist == 3.0.2 # For unit test From 8cd5b05fb43aea4f91faf2007b039667b68681a6 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 8 Nov 2022 08:04:42 +0900 Subject: [PATCH 546/940] Bump cvxpy from 1.2.1 to 1.2.2 in /requirements (#746) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.2.1 to 1.2.2. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.2.1...v1.2.2) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index ffaef30d19..cc6ca162c2 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.23.4 scipy == 1.9.3 matplotlib == 3.6.2 -cvxpy == 1.2.1 +cvxpy == 1.2.2 pytest == 7.2.0 # For unit test pytest-xdist == 3.0.2 # For unit test mypy == 0.982 # For unit test From 85e00de888e8bc51ce2af0a0370e4a77d53a56b9 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Thu, 10 Nov 2022 21:04:55 +0900 Subject: [PATCH 547/940] Bump mypy from 0.982 to 0.990 in /requirements (#744) Bumps [mypy](https://github.com/python/mypy) from 0.982 to 0.990. - [Release notes](https://github.com/python/mypy/releases) - [Commits](https://github.com/python/mypy/compare/v0.982...v0.990) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index cc6ca162c2..889d182f78 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.6.2 cvxpy == 1.2.2 pytest == 7.2.0 # For unit test pytest-xdist == 3.0.2 # For unit test -mypy == 0.982 # For unit test +mypy == 0.990 # For unit test flake8 == 5.0.4 # For unit test From b50a1180d819b0d45d9c565326ba18cbd12c3e5d Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Thu, 10 Nov 2022 21:29:11 +0900 Subject: [PATCH 548/940] fic mypy ci (#747) --- Mapping/rectangle_fitting/simulator.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Mapping/rectangle_fitting/simulator.py b/Mapping/rectangle_fitting/simulator.py index faca2cb79e..aa32ae1b1f 100644 --- a/Mapping/rectangle_fitting/simulator.py +++ b/Mapping/rectangle_fitting/simulator.py @@ -138,7 +138,3 @@ def ray_casting_filter(theta_l, range_l, angle_resolution): ry.append(range_db[i] * np.sin(t)) return rx, ry - - -if __name__ == '__main__': - main() From 8f14488ec2f243e48222bc87923604a7d46c45af Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 15 Nov 2022 07:25:44 +0900 Subject: [PATCH 549/940] Bump mypy from 0.990 to 0.991 in /requirements (#751) Bumps [mypy](https://github.com/python/mypy) from 0.990 to 0.991. - [Release notes](https://github.com/python/mypy/releases) - [Commits](https://github.com/python/mypy/compare/v0.990...v0.991) --- updated-dependencies: - dependency-name: mypy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 889d182f78..fa20768c46 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -4,5 +4,5 @@ matplotlib == 3.6.2 cvxpy == 1.2.2 pytest == 7.2.0 # For unit test pytest-xdist == 3.0.2 # For unit test -mypy == 0.990 # For unit test +mypy == 0.991 # For unit test flake8 == 5.0.4 # For unit test From bcb2c863eb45ec8c11c1dcfdadcef98ef9e85b6b Mon Sep 17 00:00:00 2001 From: KohMat Date: Sun, 20 Nov 2022 13:19:42 +0900 Subject: [PATCH 550/940] Fix the start state to use the current accel in frent planner(#755) (#756) The robot didn't reach the target velocity when running frenet_optimal_trajectory.py. To fix this, I changed the constraints for determining polynomials that generate longitudinal trajectories. Expressly, I set the initial acceleration to the current acceleration. --- .../frenet_optimal_trajectory.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py index b7d1b8e642..331df36309 100644 --- a/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py +++ b/PathPlanning/FrenetOptimalTrajectory/frenet_optimal_trajectory.py @@ -116,7 +116,7 @@ def __init__(self): self.c = [] -def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): +def calc_frenet_paths(c_speed, c_accel, c_d, c_d_d, c_d_dd, s0): frenet_paths = [] # generate path to each offset goal @@ -139,7 +139,7 @@ def calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0): for tv in np.arange(TARGET_SPEED - D_T_S * N_S_SAMPLE, TARGET_SPEED + D_T_S * N_S_SAMPLE, D_T_S): tfp = copy.deepcopy(fp) - lon_qp = QuarticPolynomial(s0, c_speed, 0.0, tv, 0.0, Ti) + lon_qp = QuarticPolynomial(s0, c_speed, c_accel, tv, 0.0, Ti) tfp.s = [lon_qp.calc_point(t) for t in fp.t] tfp.s_d = [lon_qp.calc_first_derivative(t) for t in fp.t] @@ -225,8 +225,8 @@ def check_paths(fplist, ob): return [fplist[i] for i in ok_ind] -def frenet_optimal_planning(csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob): - fplist = calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0) +def frenet_optimal_planning(csp, s0, c_speed, c_accel, c_d, c_d_d, c_d_dd, ob): + fplist = calc_frenet_paths(c_speed, c_accel, c_d, c_d_d, c_d_dd, s0) fplist = calc_global_paths(fplist, csp) fplist = check_paths(fplist, ob) @@ -274,6 +274,7 @@ def main(): # initial state c_speed = 10.0 / 3.6 # current speed [m/s] + c_accel = 0.0 # current acceleration [m/ss] c_d = 2.0 # current lateral position [m] c_d_d = 0.0 # current lateral speed [m/s] c_d_dd = 0.0 # current lateral acceleration [m/s] @@ -283,13 +284,14 @@ def main(): for i in range(SIM_LOOP): path = frenet_optimal_planning( - csp, s0, c_speed, c_d, c_d_d, c_d_dd, ob) + csp, s0, c_speed, c_accel, c_d, c_d_d, c_d_dd, ob) s0 = path.s[1] c_d = path.d[1] c_d_d = path.d_d[1] c_d_dd = path.d_dd[1] c_speed = path.s_d[1] + c_accel = path.s_dd[1] if np.hypot(path.x[1] - tx[-1], path.y[1] - ty[-1]) <= 1.0: print("Goal") From 644ce8a5fda39cf8a7fcff4537fe10b3f4bad538 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 22 Nov 2022 10:46:42 +0900 Subject: [PATCH 551/940] Bump numpy from 1.23.4 to 1.23.5 in /requirements (#757) Bumps [numpy](https://github.com/numpy/numpy) from 1.23.4 to 1.23.5. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.23.4...v1.23.5) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index fa20768c46..5e3b4d8caf 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.23.4 +numpy == 1.23.5 scipy == 1.9.3 matplotlib == 3.6.2 cvxpy == 1.2.2 From 405f3e79341356c4fa3f78dbe37bcd87f12d155b Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Mon, 28 Nov 2022 21:27:22 +0900 Subject: [PATCH 552/940] Update gh-pages.yml (#758) --- .github/workflows/gh-pages.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index e51197cb37..bf46598633 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -8,7 +8,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Setup python - uses: actions/setup-python@v2 + uses: actions/setup-python@v3 - name: Checkout uses: actions/checkout@master with: @@ -26,4 +26,4 @@ jobs: uses: ad-m/github-push-action@master with: github_token: ${{ secrets.GITHUB_TOKEN }} - branch: gh-pages \ No newline at end of file + branch: gh-pages From 727f32cb8b1a144ae1b6b167f2c2d2ebee61851b Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 6 Dec 2022 07:29:38 +0900 Subject: [PATCH 553/940] Bump pytest-xdist from 3.0.2 to 3.1.0 in /requirements (#760) Bumps [pytest-xdist](https://github.com/pytest-dev/pytest-xdist) from 3.0.2 to 3.1.0. - [Release notes](https://github.com/pytest-dev/pytest-xdist/releases) - [Changelog](https://github.com/pytest-dev/pytest-xdist/blob/master/CHANGELOG.rst) - [Commits](https://github.com/pytest-dev/pytest-xdist/compare/v3.0.2...v3.1.0) --- updated-dependencies: - dependency-name: pytest-xdist dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 5e3b4d8caf..b5e9d37b81 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -3,6 +3,6 @@ scipy == 1.9.3 matplotlib == 3.6.2 cvxpy == 1.2.2 pytest == 7.2.0 # For unit test -pytest-xdist == 3.0.2 # For unit test +pytest-xdist == 3.1.0 # For unit test mypy == 0.991 # For unit test flake8 == 5.0.4 # For unit test From 5ac66d71dd3e4cf06d7b32782af9d2e911633a07 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 20 Dec 2022 07:30:26 +0900 Subject: [PATCH 554/940] Bump numpy from 1.23.5 to 1.24.0 in /requirements (#763) Bumps [numpy](https://github.com/numpy/numpy) from 1.23.5 to 1.24.0. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.23.5...v1.24.0) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-minor ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index b5e9d37b81..47d9eefab5 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.23.5 +numpy == 1.24.0 scipy == 1.9.3 matplotlib == 3.6.2 cvxpy == 1.2.2 From 6d27738e3d243cf758d6eaa16844504bb6eae2ee Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 27 Dec 2022 08:02:56 +0900 Subject: [PATCH 555/940] Bump numpy from 1.24.0 to 1.24.1 in /requirements (#765) Bumps [numpy](https://github.com/numpy/numpy) from 1.24.0 to 1.24.1. - [Release notes](https://github.com/numpy/numpy/releases) - [Changelog](https://github.com/numpy/numpy/blob/main/doc/RELEASE_WALKTHROUGH.rst) - [Commits](https://github.com/numpy/numpy/compare/v1.24.0...v1.24.1) --- updated-dependencies: - dependency-name: numpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 47d9eefab5..3f68d9ab4c 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,4 +1,4 @@ -numpy == 1.24.0 +numpy == 1.24.1 scipy == 1.9.3 matplotlib == 3.6.2 cvxpy == 1.2.2 From af39afe05cfec0ef202cc1542dfe0103c130ed3b Mon Sep 17 00:00:00 2001 From: Lingkang Zhang <36938500+zlingkang@users.noreply.github.com> Date: Fri, 30 Dec 2022 15:38:43 -0800 Subject: [PATCH 556/940] add axes3d to figure (#766) --- Bipedal/bipedal_planner/bipedal_planner.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Bipedal/bipedal_planner/bipedal_planner.py b/Bipedal/bipedal_planner/bipedal_planner.py index 9757fc42d6..8ca5ffcf78 100644 --- a/Bipedal/bipedal_planner/bipedal_planner.py +++ b/Bipedal/bipedal_planner/bipedal_planner.py @@ -51,6 +51,7 @@ def walk(self, t_sup=0.8, z_c=0.8, a=10, b=1, plot=False): if plot: fig = plt.figure() ax = Axes3D(fig) + fig.add_axes(ax) com_trajectory_for_plot = [] px, py = 0.0, 0.0 # reference footstep position From 1d683435c6d7c9eea2895b3f1441f00772f5ab32 Mon Sep 17 00:00:00 2001 From: Christian Clauss Date: Sat, 31 Dec 2022 07:51:17 +0100 Subject: [PATCH 557/940] Undefined name: import sys for line 188 (#764) --- PathPlanning/RRT/rrt_with_sobol_sampler.py | 1 + 1 file changed, 1 insertion(+) diff --git a/PathPlanning/RRT/rrt_with_sobol_sampler.py b/PathPlanning/RRT/rrt_with_sobol_sampler.py index 73488210a7..06e0c04c68 100644 --- a/PathPlanning/RRT/rrt_with_sobol_sampler.py +++ b/PathPlanning/RRT/rrt_with_sobol_sampler.py @@ -28,6 +28,7 @@ import math import random +import sys import matplotlib.pyplot as plt import numpy as np From 2916273e6239c70a12b1e46845a26bd49a727133 Mon Sep 17 00:00:00 2001 From: Andrey Bozhko Date: Sun, 1 Jan 2023 05:44:34 -0600 Subject: [PATCH 558/940] Update loop conditions to be more idiomatic; fix missing imports (#768) * missing import * use while true --- Mapping/rectangle_fitting/rectangle_fitting.py | 2 +- PathPlanning/AStar/a_star.py | 2 +- PathPlanning/BidirectionalAStar/bidirectional_a_star.py | 2 +- .../bidirectional_breadth_first_search.py | 2 +- PathPlanning/BreadthFirstSearch/breadth_first_search.py | 2 +- PathPlanning/DepthFirstSearch/depth_first_search.py | 2 +- PathPlanning/Dijkstra/dijkstra.py | 2 +- PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py | 2 +- PathPlanning/HybridAStar/dynamic_programming_heuristic.py | 2 +- tests/test_grid_map_lib.py | 1 + 10 files changed, 10 insertions(+), 9 deletions(-) diff --git a/Mapping/rectangle_fitting/rectangle_fitting.py b/Mapping/rectangle_fitting/rectangle_fitting.py index 124e48fe76..f54ada1e3a 100644 --- a/Mapping/rectangle_fitting/rectangle_fitting.py +++ b/Mapping/rectangle_fitting/rectangle_fitting.py @@ -162,7 +162,7 @@ def _adoptive_range_segmentation(self, ox, oy): S.append(C) # Merge cluster - while 1: + while True: no_change = True for (c1, c2) in list(itertools.permutations(range(len(S)), 2)): if S[c1] & S[c2]: diff --git a/PathPlanning/AStar/a_star.py b/PathPlanning/AStar/a_star.py index eb2672a9ce..6d20350432 100644 --- a/PathPlanning/AStar/a_star.py +++ b/PathPlanning/AStar/a_star.py @@ -71,7 +71,7 @@ def planning(self, sx, sy, gx, gy): open_set, closed_set = dict(), dict() open_set[self.calc_grid_index(start_node)] = start_node - while 1: + while True: if len(open_set) == 0: print("Open set is empty..") break diff --git a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py index ecb875f410..5387cca1ad 100644 --- a/PathPlanning/BidirectionalAStar/bidirectional_a_star.py +++ b/PathPlanning/BidirectionalAStar/bidirectional_a_star.py @@ -75,7 +75,7 @@ def planning(self, sx, sy, gx, gy): current_B = goal_node meet_point_A, meet_point_B = None, None - while 1: + while True: if len(open_set_A) == 0: print("Open set A is empty..") break diff --git a/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py b/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py index dd4282573e..60a8c5e170 100644 --- a/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py +++ b/PathPlanning/BidirectionalBreadthFirstSearch/bidirectional_breadth_first_search.py @@ -76,7 +76,7 @@ def planning(self, sx, sy, gx, gy): meet_point_A, meet_point_B = None, None - while 1: + while True: if len(open_set_A) == 0: print("Open set A is empty..") break diff --git a/PathPlanning/BreadthFirstSearch/breadth_first_search.py b/PathPlanning/BreadthFirstSearch/breadth_first_search.py index 406e5eb51f..ff662170e7 100644 --- a/PathPlanning/BreadthFirstSearch/breadth_first_search.py +++ b/PathPlanning/BreadthFirstSearch/breadth_first_search.py @@ -67,7 +67,7 @@ def planning(self, sx, sy, gx, gy): open_set, closed_set = dict(), dict() open_set[self.calc_grid_index(nstart)] = nstart - while 1: + while True: if len(open_set) == 0: print("Open set is empty..") break diff --git a/PathPlanning/DepthFirstSearch/depth_first_search.py b/PathPlanning/DepthFirstSearch/depth_first_search.py index 523225ee42..6922b8cbad 100644 --- a/PathPlanning/DepthFirstSearch/depth_first_search.py +++ b/PathPlanning/DepthFirstSearch/depth_first_search.py @@ -67,7 +67,7 @@ def planning(self, sx, sy, gx, gy): open_set, closed_set = dict(), dict() open_set[self.calc_grid_index(nstart)] = nstart - while 1: + while True: if len(open_set) == 0: print("Open set is empty..") break diff --git a/PathPlanning/Dijkstra/dijkstra.py b/PathPlanning/Dijkstra/dijkstra.py index 9956dff326..004e49f15a 100644 --- a/PathPlanning/Dijkstra/dijkstra.py +++ b/PathPlanning/Dijkstra/dijkstra.py @@ -71,7 +71,7 @@ def planning(self, sx, sy, gx, gy): open_set, closed_set = dict(), dict() open_set[self.calc_index(start_node)] = start_node - while 1: + while True: c_id = min(open_set, key=lambda o: open_set[o].cost) current = open_set[c_id] diff --git a/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py b/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py index f2416fba98..b259beb870 100644 --- a/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py +++ b/PathPlanning/GreedyBestFirstSearch/greedy_best_first_search.py @@ -67,7 +67,7 @@ def planning(self, sx, sy, gx, gy): open_set, closed_set = dict(), dict() open_set[self.calc_grid_index(nstart)] = nstart - while 1: + while True: if len(open_set) == 0: print("Open set is empty..") break diff --git a/PathPlanning/HybridAStar/dynamic_programming_heuristic.py b/PathPlanning/HybridAStar/dynamic_programming_heuristic.py index cc635260d6..8a78b15d5f 100644 --- a/PathPlanning/HybridAStar/dynamic_programming_heuristic.py +++ b/PathPlanning/HybridAStar/dynamic_programming_heuristic.py @@ -65,7 +65,7 @@ def calc_distance_heuristic(gx, gy, ox, oy, resolution, rr): open_set[calc_index(goal_node, x_w, min_x, min_y)] = goal_node priority_queue = [(0, calc_index(goal_node, x_w, min_x, min_y))] - while 1: + while True: if not priority_queue: break cost, c_id = heapq.heappop(priority_queue) diff --git a/tests/test_grid_map_lib.py b/tests/test_grid_map_lib.py index 8ae142b003..92ca67e297 100644 --- a/tests/test_grid_map_lib.py +++ b/tests/test_grid_map_lib.py @@ -1,4 +1,5 @@ from Mapping.grid_map_lib.grid_map_lib import GridMap +import conftest import numpy as np From e7710546c18f8f4cd076c030939e77afc86d43c9 Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 3 Jan 2023 07:52:07 +0900 Subject: [PATCH 559/940] Bump cvxpy from 1.2.2 to 1.2.3 in /requirements (#771) Bumps [cvxpy](https://github.com/cvxpy/cvxpy) from 1.2.2 to 1.2.3. - [Release notes](https://github.com/cvxpy/cvxpy/releases) - [Commits](https://github.com/cvxpy/cvxpy/compare/v1.2.2...v1.2.3) --- updated-dependencies: - dependency-name: cvxpy dependency-type: direct:production update-type: version-update:semver-patch ... Signed-off-by: dependabot[bot] Signed-off-by: dependabot[bot] Co-authored-by: dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com> --- requirements/requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements/requirements.txt b/requirements/requirements.txt index 3f68d9ab4c..9a990856f1 100644 --- a/requirements/requirements.txt +++ b/requirements/requirements.txt @@ -1,7 +1,7 @@ numpy == 1.24.1 scipy == 1.9.3 matplotlib == 3.6.2 -cvxpy == 1.2.2 +cvxpy == 1.2.3 pytest == 7.2.0 # For unit test pytest-xdist == 3.1.0 # For unit test mypy == 0.991 # For unit test From 3dc96997da60116ae5bc825d2e67adefe5ff7dc8 Mon Sep 17 00:00:00 2001 From: Atsushi Sakai Date: Tue, 3 Jan 2023 22:27:55 +0900 Subject: [PATCH 560/940] Adding point cloud sampling examples (#770) --- .../point_cloud_sampling.py | 168 ++++++++++++++++++ docs/modules/mapping/mapping_main.rst | 1 + .../farthest_point_sampling.png | Bin 0 -> 253175 bytes .../point_cloud_sampling_main.rst | 70 ++++++++ .../poisson_disk_sampling.png | Bin 0 -> 265198 bytes .../voxel_point_sampling.png | Bin 0 -> 250443 bytes tests/test_point_cloud_sampling.py | 15 ++ 7 files changed, 254 insertions(+) create mode 100644 Mapping/point_cloud_sampling/point_cloud_sampling.py create mode 100644 docs/modules/mapping/point_cloud_sampling/farthest_point_sampling.png create mode 100644 docs/modules/mapping/point_cloud_sampling/point_cloud_sampling_main.rst create mode 100644 docs/modules/mapping/point_cloud_sampling/poisson_disk_sampling.png create mode 100644 docs/modules/mapping/point_cloud_sampling/voxel_point_sampling.png create mode 100644 tests/test_point_cloud_sampling.py diff --git a/Mapping/point_cloud_sampling/point_cloud_sampling.py b/Mapping/point_cloud_sampling/point_cloud_sampling.py new file mode 100644 index 0000000000..df7cde41c0 --- /dev/null +++ b/Mapping/point_cloud_sampling/point_cloud_sampling.py @@ -0,0 +1,168 @@ +""" +Point cloud sampling example codes. This code supports +- Voxel point sampling +- Farthest point sampling +- Poisson disk sampling + +""" +import matplotlib.pyplot as plt +import numpy as np +import numpy.typing as npt +from collections import defaultdict + +do_plot = True + + +def voxel_point_sampling(original_points: npt.NDArray, voxel_size: float): + """ + Voxel Point Sampling function. + This function sample N-dimensional points with voxel grid. + Points in a same voxel grid will be merged by mean operation for sampling. + + Parameters + ---------- + original_points : (M, N) N-dimensional points for sampling. + The number of points is M. + voxel_size : voxel grid size + + Returns + ------- + sampled points (M', N) + """ + voxel_dict = defaultdict(list) + for i in range(original_points.shape[0]): + xyz = original_points[i, :] + xyz_index = tuple(xyz // voxel_size) + voxel_dict[xyz_index].append(xyz) + points = np.vstack([np.mean(v, axis=0) for v in voxel_dict.values()]) + return points + + +def farthest_point_sampling(orig_points: npt.NDArray, + n_points: int, seed: int): + """ + Farthest point sampling function + This function sample N-dimensional points with the farthest point policy. + + Parameters + ---------- + orig_points : (M, N) N-dimensional points for sampling. + The number of points is M. + n_points : number of points for sampling + seed : random seed number + + Returns + ------- + sampled points (n_points, N) + + """ + rng = np.random.default_rng(seed) + n_orig_points = orig_points.shape[0] + first_point_id = rng.choice(range(n_orig_points)) + min_distances = np.ones(n_orig_points) * float("inf") + selected_ids = [first_point_id] + while len(selected_ids) < n_points: + base_point = orig_points[selected_ids[-1], :] + distances = np.linalg.norm(orig_points[np.newaxis, :] - base_point, + axis=2).flatten() + min_distances = np.minimum(min_distances, distances) + distances_rank = np.argsort(-min_distances) # Farthest order + for i in distances_rank: # From the farthest point + if i not in selected_ids: # if not selected yes, select it + selected_ids.append(i) + break + return orig_points[selected_ids, :] + + +def poisson_disk_sampling(orig_points: npt.NDArray, n_points: int, + min_distance: float, seed: int, MAX_ITER=1000): + """ + Poisson disk sampling function + This function sample N-dimensional points randomly until the number of + points keeping minimum distance between selected points. + + Parameters + ---------- + orig_points : (M, N) N-dimensional points for sampling. + The number of points is M. + n_points : number of points for sampling + min_distance : minimum distance between selected points. + seed : random seed number + MAX_ITER : Maximum number of iteration. Default is 1000. + + Returns + ------- + sampled points (n_points or less, N) + """ + rng = np.random.default_rng(seed) + selected_id = rng.choice(range(orig_points.shape[0])) + selected_ids = [selected_id] + loop = 0 + while len(selected_ids) < n_points and loop <= MAX_ITER: + selected_id = rng.choice(range(orig_points.shape[0])) + base_point = orig_points[selected_id, :] + distances = np.linalg.norm( + orig_points[np.newaxis, selected_ids] - base_point, + axis=2).flatten() + if min(distances) >= min_distance: + selected_ids.append(selected_id) + loop += 1 + if len(selected_ids) != n_points: + print("Could not find the specified number of points...") + + return orig_points[selected_ids, :] + + +def plot_sampled_points(original_points, sampled_points, method_name): + fig = plt.figure() + ax = fig.add_subplot(projection='3d') + ax.scatter(original_points[:, 0], original_points[:, 1], + original_points[:, 2], marker=".", label="Original points") + ax.scatter(sampled_points[:, 0], sampled_points[:, 1], + sampled_points[:, 2], marker="o", + label="Filtered points") + plt.legend() + plt.title(method_name) + plt.axis("equal") + + +def main(): + n_points = 1000 + seed = 1234 + rng = np.random.default_rng(seed) + + x = rng.normal(0.0, 10.0, n_points) + y = rng.normal(0.0, 1.0, n_points) + z = rng.normal(0.0, 10.0, n_points) + original_points = np.vstack((x, y, z)).T + print(f"{original_points.shape=}") + print("Voxel point sampling") + voxel_size = 20.0 + voxel_sampling_points = voxel_point_sampling(original_points, voxel_size) + print(f"{voxel_sampling_points.shape=}") + + print("Farthest point sampling") + n_points = 20 + farthest_sampling_points = farthest_point_sampling(original_points, + n_points, seed) + print(f"{farthest_sampling_points.shape=}") + + print("Poisson disk sampling") + n_points = 20 + min_distance = 10.0 + poisson_disk_points = poisson_disk_sampling(original_points, n_points, + min_distance, seed) + print(f"{poisson_disk_points.shape=}") + + if do_plot: + plot_sampled_points(original_points, voxel_sampling_points, + "Voxel point sampling") + plot_sampled_points(original_points, farthest_sampling_points, + "Farthest point sampling") + plot_sampled_points(original_points, poisson_disk_points, + "poisson disk sampling") + plt.show() + + +if __name__ == '__main__': + main() diff --git a/docs/modules/mapping/mapping_main.rst b/docs/modules/mapping/mapping_main.rst index 0f7ec549dc..14a7cce70d 100644 --- a/docs/modules/mapping/mapping_main.rst +++ b/docs/modules/mapping/mapping_main.rst @@ -9,6 +9,7 @@ Mapping gaussian_grid_map/gaussian_grid_map ray_casting_grid_map/ray_casting_grid_map lidar_to_grid_map_tutorial/lidar_to_grid_map_tutorial + point_cloud_sampling/point_cloud_sampling k_means_object_clustering/k_means_object_clustering circle_fitting/circle_fitting rectangle_fitting/rectangle_fitting diff --git a/docs/modules/mapping/point_cloud_sampling/farthest_point_sampling.png b/docs/modules/mapping/point_cloud_sampling/farthest_point_sampling.png new file mode 100644 index 0000000000000000000000000000000000000000..6024a5f2d5a274177104590ff2b689231b57323d GIT binary patch literal 253175 zcmeFZWmsHImoD7hxNDGL9V9^T5Zv8@CqQr~1b6pfK|^p)Ac5cs-nhHFySqD_P4b?Z zXU;p{ukY76*KqYt@9wVJRkf;W$$hU%sFH#d2I^B(5D0`JBQ3510>MFniw+qP_=bz> zBLWD7nr|*9rX(XK234}RF*Ua|0fD4L;}VeGsBYoO5(vv8GvSNy zhR8}oKH?fmWB;NGW2hn!7jFzI`b1YnAWZNCr>%lcqY)-TfMcS=IH}}D$PMqZ;C7J4 zwb7fz^5tqH<7(jUAPEihE{O`)q_G=hj7qa?>to|?sm)Kug$xD3Q7Xavw)7FOwKV&K zDM!u^j_=8FBRZ{mLbV_6AAFuXAs0$P1K|hR;)A>eqJVPiLKgIYioa^w zLso5*_CvlzN`l-l=^ZJ3w8Y*_RTe4H!WSxN$NO4i7D<&B;@bw zf(TXcM|~vY>ASUD2r(xx3+%a&B`8fC>BSk?Wsr}Gxlz5cbi1z|?MyW9#}OY$S>HVk z$xI@OpJj;;>e<;qyQ?!hKl^f#o^+?v0IBdSq~>@jJkMwL!@EA3=LAVfz)NIRqXm>ZH}1@qAPuIGa(q6aOl4DCGgITC{dWRN$P=!M^l zOfMyjQ#40J7)U1&mU*K@@e01qPq2k95nk26YLciTh?o@*)1PW7&=$28zCQqMQQnqE z8-pT{WD)Jq>5`c-K(9HA&R0cvNXeZ}4j-;fH1ON9au*%jhbMW+Z-eqA$G#>jljY9P z5q}^$Ly3@39dsN!xHen4|--)#!5h>j!uFX zCey^&hHu!-io}+~mcZ)52A6oD!5AOJ(Zp*6S7JB$YS(^Oa+ldspyJ6);9f`MvMo18 zDndUQ;ir{F>MGG$g<0iUH*GF!&;?Gh??l_o(%s>a>oY+Ly&xffq2PmdtmO{mZg?tx zhG(&jRE$)X&q<-L@T_qWk&VQkd_x&ZBa(SdRYVhyw-b^O5*1?e1RwwOi8lT^12XwRo3Z>Rf^sSX3b{t z=ZPx+dW-V5>&;ZIz4%&Qx5L}iykB|6FBHp#of@_!#=KEK844RHSH(KT!o|wPf?vdc z5H(R9$!!}o8dca1NzO|S&@9s|()>RCj)NFOg8j!YbKqy4#*-lxOZ|HQN~+n@{VXZavlFc*;R;@r|R8W5a@ZY_`x%#=(`-sba=* zfA`xIt*OwUe|c|tb9ubQ-URF`M_yspUNO_~{7)}s4~^g-E8oBTP|b5tFq2OBw)2%? zkZDYy_{P6T(rlQ0bM4gmIwU<_*Eju*O@?mHd}4j5cdU24cip`a+&6FwbSiT+vroTO zX@a%YHqfAO369Dir-g3peXw%y5Rwtz3en10dqn$y{HXlobGPT^&!b*<{Yd{I_c~wx zAkmDWj%8J=X%^a7n433Et+2&b662iA`i2}M~A$PQ;itLqf=G)!~~%oC8)sH?onXv9?`Pm1|9b zv$@^X>h|gjJAtL^gp}`Euo;}n4F~!4;|=n}nS-K(e!GPY=95ehYWLlhqlQh6f|_6dFYZaRq7=u~7|*pA~b8^K4>m0uS(nyc+Nu zG#hYyq#oAp3&DxLnZAW!0ZS{+1f3Rg6h};L;z@FG)KAEH$nH-q$r&-NG5y3KVike> z$!4z3spC$rNXdL`C2Oq7urL-ek|X}5cF$1d5kuYFd} z*YHs&aW`E%=9a%rz(lKCDbMV~yX_KRnq2H!1vKfIFXzt$Ufn5OyGp*6^m;DH&UO;6 z^fr;%a$vZtyKfu!T?negZ<->x3Kn74-`#78)1LR-$UgmE~ELH*Ncm!CBl+ zkm|~5r_`TUdZygQ+`8--j&l&cCoG`fd}w+Io)&ErwKEuSuRQbc7Js0-{N)gE7nDX) z|K#XX(UTecgeN{zopY{xv@;pqK2H~7YkxYFj;zmVm1up`+P6BJb*~ctPFgdp~A4Q=B_@jZvNIP_qrskGT)>nPoyuP4XJ?~mpq0HQ)pIq zMO)QDe5Z3=vr0{q&+*mLW}%T_NAfn~&iUBLc34!v%J2${x6JL@d}t<~6)iFCjskI7 z9^tXI9SENVUP1Q#yZW~fs z5``^d@ zNOF7}ZucB>RLxrCH&Wy)wXHc^`u2Dy_NKg+DhBp?Tqa$L7SdcQcXUVV=F>ltzhf!B zxVj6!DW+KEC-SIT$5~e%GFs~}Q7lV;^I(1MQP(TuTrrSy&^{89gLPAV$MVp5ztSVz z#C}}*TV$>&dBb@?E9f@Jx=!QJaPj-*+NAAL#tR>{x|d!~+bqQm*5R#@=(Pk5H_Es{5_sx-|UxVcwsWb=k1hg44@7i z4$0W?%~omrEd+fJk7|X1`Y#UGAN4=8#Mfcsjmr1vz}-JnWxsWCdKmE!E%?&&VETYC z5rMQSt)c4=Yz~6| zR~ZH1{qZjvxE|~LeTRz)0wDpPaDmG;6Y{@H!$C9Q{^Onw_zfhYDkdWXysH}7o0wQT zyti@mXv@pO;^N}M?844$V{gX7#>2zI!upcs; zVF3eVdHjWijhU6@Kb{R#<$wH^SIOMf#PXfExfLKYpbbH8R&M@3<^S!M|7`IeH8uWO zll7l9|MAQJS@W%fiM^PO70{%k;D1inzbgOp$A4AiXL%g?KP2&2%zwTGN zGc8mdB}wABnyZWfKO1f?#h8>7S}v}xyVQvtx8MDq8MCW5UGFd=oj*mwOZ)zpmkM-H z7#ssJc`gE>7XHUeA6d!wP!bBp{pU+M0)!y_AvXydB^vb47XtFZe=P|08wKiT2PLC? z{x1blfQOR*^NGOy|2*`6Wcq*Cl6n=Ro(fY+m)$NVzfkre-~D z({SgUEW=*-5k>rpX^EKn;_2z8l=dDu#9zzL=Ar;PHxI!Lj!ICUkFuD83|HFdaoEiB2PmOo2O7aVaYK%^3<(Q7 z$C(`DA#TqB^|CRY-%>jxc^OEko68K_{HCoEVuU;{+NqV1Kija-SrAJ0116E1x{sE#_(D_YGtwaYIBR6iol!3}X&V?=KAh-p35kIB6VG7Dp>u+^-vG%pf*xIKv!s8Vl6u%Z#{3ej;!R|>k>%!*1~xLxP! z@8>(%b=(>6Gava8F;c82wDA#7!B*G%%4CIhyCH&vi}&Grq5+*yK(~Es@>kXf%*n#+ zq>sx5lW&(*>H^PYyikjf9yX!pGsknYTblNnN-EjY54^lRloeb$qQFPo9&)e}CBz(B zOz$a6iOSQM`N1Iav{gQlwdrcSvVQIKU}3>_cfPKsbVApI2e=AL-OoN85t!d}GZb?R zU3Dq;-UYgwkLAUcPMN0gEVqUAv5Q{*2K5vZ`58Q+?% zF3swA&6A+({f7UiP~$_omC|vmsGOv$eSGh$LdHOS+ZAuv#&L-Bu-9^x!Z6)ZGnmYjK|F83jtJ7=&lUT zs869~UW&)2YAJ|LBb89kbBL(N*|ot7xlCQpi{q7oZAkYeuxgk?dpMbIhbsr#e)>?G zl1xiuNe*|>W{`H`m|Fuw?e9%umpk5e0r@#!Z{;K~3BiNmH4@QYUhcBa{}vX%UnXp@ z1;k9CK~6O2u-^MCi|xi)n{y-ct_lJV*<{eWlGVSj-I{Y)5^jBE}UpGZhhoBv|g0e9AI(GMwn@MK*t@<=OSD48AqGkbOHQ?omV_bJ&y-bvyjH&MN%!cVZ-QRx-5)2ck79Wr!kq!@Lw$=S>$%|Fnf6w~ z_hH0@&=sMFtElUXhKEAO{J>#7j4=|MT7%}j$^~y(ADZ$kjvKw};RO8q)+v(-y|pp7 zjWo06{i)KNVLj5g`{AN_w+*thNu#KrZ}ZiX^ru~wzdV;$soASY5g&Pfv-(9b576#C zAGU_SuP5Jk=d-pDnPRlm-**?3O)A5lG-^*UNyz%V<=n0PZ0?uS&%J_vQFf1NIXtfS z5XVUnXMM!FHqJ!-p(O}I77g2}gUqGszP#y4N)(Aq5?QPi$x=Jv_Qqigmb$u*QydRD zuVb!g+D=FHFk7E_s%n@M<7 zhBnRke9uSoO>V=(-NAbOaI?k|Rs(pp^fJP{skm&=K47uZ@!{@*UyHxbZO$NNBO&>hDr@n3-PTN7gBX zE&WEraX*l99BF|ByS77ZT!X%*y6S%Twg23%^I32%&|jbZUoIPcTnletV=X1|7F9yZ z%V^&(#U`+JeO5>oYy~eD17cXGCpq;FR*hqeW0ut`oTrAyz=i1Q+IA9I z*2JLL-`Bfqk#L*{_MXt-F}_h~y;I@tGF39WU0?TgK9R z7}^sbmQat)WG33=4YIb?M2~NMhGcgsJ!!9XBPRqKg*I$HKLeHx7iu2D_pNa%6W-0t zfTvfV@#w-XThzklB;6f{G&Q+|TS+#MQ;NK3oBE9cr?fbJir~ z2K27OU9erkbvwaXD07@<=FCu%m(32Xca%s2M~(L4+J>#}aFCCX*+Nt^l1|g$+_3Ze zz>((Z2&^N2zl?wduk)#nv#^D)dKc=BC(RD17hF}+x^@qbj?L;9P>udt>HIe5LMe55!zRD`JQ`uvbjjgI&jM~l@ffmA62w0|wu6WuX|>>Rcyp5Rz(2?$ z?iVXoA<`~D=@*Ub1CxNV>K;*P9oY0@hS*6`!Y@)#sNbgQ6lLaFbeuhp7&r7SW$y3lDYN1v>z^-&7428NWtL^n zR9_yQtB}2I2}!WfyW3WmD|+jW9jrL|sur@EXcS3L^2TMvz9;AiUN@L!LFHVYYi_j3 zcbYYr0QD%Ua6fXQ(}NW3PwQiS&$6|`;HHTwDKs2Ng!Qxv5XI#* zIp+~*Tiu&4MBRlDl?heTA$!(fwhgO-s8gpu&22r&x)zr5z1XEjTLv}SW52qCOMoYI zoQWQ*-T#tDE1T45RM}fswm*W5Z#)9ePSrPdaS4pF`U!}1i}J#f$|G#us^ex5QLuZ1 zoDS+PlHY~0%0-a3C=Vwa`g|YvTJ~C+frv*@9GTxro8?Mcs&)6Kahd#E$ zt|3G2U)AGe8GyJjvz1ws`%z@acLCkZxjF_H`d%4z`3d5|ssHl}mRA7FNoo2=s%Dn7(m4%6;Z$ONpL%`$8Cc z{jF-g&ZA}v(MhoYkjbm^^Sgjwc%qsd^tLh1P(`FGN%-aI;c&$F)6A@`;x7xA2qxaw*3Wl!b8t0oizmOqZ#$zBCj7_nn!#Dsq&orF+t_7v#Z5=;61Ug{~`)4!EVxq{ zKrQdXQl<4%f}G1yAUf0ZlY_#T;Y9+JX%sws&6G6P!aYNKY9fG;w`I~qQPfx8$-(V2 zk`vp>`qvmE^yM)NB<{p^q5$7tzhT+5TF6g?2!o^a_`NqQ!7AAV*hE!;t`+0{ltE`6 zcM=fSel$kD!s)!=bs^~w-`rm;mr@5J{~>v<5Vs>gkuDC+eUdrsQ8c_@g#Y8XrjfIU z2}(++@3B|ix1V!6fRL*3cn* zk23=s7T@d0T>P@1^)E6SeDPzh)fJBoTGFO&QJgGJNzh5^WsRq5QT4G z{-^aGU>Ek8T2oGmqWMv=ml(7>@qLAbU0yCl6tB#`YdfX7LhP$wV`v7~G+OqU4R32^$PlDa$jPIHivUz{ zH4m0J^#d8ZrnqdOEQeFa(WiuvL{8Ipb1Y;o!6sV7cmoMA-e2B>MJU|aK*=!cV6I|= zj`zgB2xV&*{n4JfMYZH8Q-f(O!T!gJiLB2WHwbgsB7T*;;6fXZ^0{4MfduUujK2zH z4}Dh>gAa9&v*5BRXFWdMo}@74EWrSc>P+DAdDsG?~&u|jM5W5pEw|~u4)>P z%W?pQhz(5)l)N5V$){BNsn9buH#3O4;$(N}x`NDmjvAfGQt#~QQRi>Jesi@&Mqg)M&xT8uN=oU8J*zp86SR+XITPam$BO*rXcX_$>b zI$D$P4JQ|vX8wI3NKlI}XnP;TPVd$-J}_0-yKvR-a$6gl+H%_IoQe;nadj1j zR8uZKyy<+4lQ`v0sZX*LM|7+I@u$n$THsHi0MZ}YZKs*bgfp3Cwz{_nS4VP4`NHZ? z`bila#9U0X63+ULXFnpz@7v7~e&6>6F3p~>nR(e$@|4k%_Wa3U5M^}?Cj{U!@f1j8Y6H{8q}q(WOjb0*mRoSS#og&j*q z8#I;+1khm)Bps1k0_xg_`x`ma6W&E%I7k*bmvyREPOcU*gH4@bP)Pum;N)2_K`!(N zuWhlkCng*8i||)COxgrWv;#Q6YM1SAs)&5|H%in(>Xtd4vm8c(c@An%w1X0*K_eC( zWa423ZiWx>CzQe^!@L9$rxo{^sTv0@_tO6F8f!0-4?BN@nurKIUTX{q*5c|-!UAAUK;sBD_0khH1R!GAV-OOBVv}sDz_lRnya}Oe zWPC@I$kZWXF2QzucO2lob^d9T=#57+3T>j(%YNP+MkF5%mKJAV2jD_OC;}Sy>L=;g ze{{9I`ngGtV074{cmMklW=lZ2y+pxY3S>gW%^E{lYhFmGKczux|F*XQU@R43oBJJ0 zD~QacD;(3m?5kH%&M*V^fJmQ1wWiz6^4aKme;Nr9pQcY^7iPduk0CF#Qce+9*NIFN zt;3>t2z;2-^coS5efGOID*N)5YzkQ_W+W}|-TaprJqHnx3PmdXLisP9lw04_oWGbp z3})5}S$TANfAaOl1Ujgs1M2S)%d$>K!X$m)9kj5_T(i5JE|oNR%xTmf-k4XCgcL`% z5r}nrQ%!e~#g*C`Y85TU5GT;aaoc@>?bd|!G!#jvA6mBNI$!H1GIY!jK&I^|@Ip^s zrrVho3!+R)x<=C>Q?Wa&zwSsEk_PC!`P5%^V3)7^27sVOonlyr%7__HoB3pE^9|8HA&eY!>YKiYKLd z26u`Z_9OC!j$lqZsT8-1NI$d^xG-;sEVAK=18~jp0|vARP)I7uF{(;fIv4KGE5#0i z=`J$4DD;gSkY}VO=!K4+*?oJ`$dFoh#}P1S(AixM-B-Sqo}N^Dw8=WhAxxyt z-y`41e+}%Yc^-lC{w_?VND~#?_{qvZEd{qF!DL4V_O06Yw`d#wnnMN44hg_I%L3Nf zOHH=kcp>o3_XCc>JF!=SVfWVwI?hSvN4}o}iicS-56j8t$c(|Ptt>1}nPuND%~Jzd z`WsyvC*GCyW~PK#S-Ost^^mt+hJE28a!PDN8HqpNof_#S{}}(2@jkG4M57q26Q}?F zhR2Z&wpTGj>bTUzjnwMLGJV-XXc1E5(9hG+Bx5k6-h`$k`Mk#`wx9Yx>>yU zg(BX?)$31lW?#$Am$3!DK%8EYV_p_fX9?kS6lz{h*ff39Kc?xM>Cv0!GH>opnCs(F z3-%^d-WO?jX}AkXBnJYPAgpmGVf9z7QSp^rK_DBJaB7oOpb9ZIp-aTzpF<491N-kC9_mhG``qWot#oSzBRXHRc1XWD*U)Axz~Nv;*8_ zo`^3b`{^5EGhASn{pq)hzI*_1vo|ob!lP_L<~Qz!!Hb|;Q6Mfc2OgYML~i;BF+SeQ z;F);J;N+@fRRcdj ziAG}qRj+bs*JFUkJOl1g{ET0P;sKALTpP#3r4vZ|J#3LmCtw#i{Dp%~K)!0Y6c<)- z*7{7gm@GR8op?EY1ryks_m6%{aetx_fFC~x94~VSKVsnvFk9M zr;ZD<1I&c$5fi{b?S*|I)JSoyj4>b-YAN8JCqA719i-x!t|CNSv8V7JKmh0jFsg>b z(30b$02)eT>!)j6dcD>jY^O+8@k`O^w_ma>`bmtA?UI0-iU;(aqp4q9=AZO$rXWDb zj+)h#j{Xegy_T`mRFG-;N-SGMnkd;B4n23*#?Y!u4< z3HzDyRXily-W2_B>OnNruiRoHkH=xXiVaX3s!sc}@4nW+{n0YUfuL3-Sg`l)QOAd? zS^v2z((y{BaohOKCSft#nSMWqskIM9oA1FiT=&Oov zt64|%-z|xPy(q^I4hi=M^p6w7)45Gb0gRhLCI)B)paQk9FUt`;^d%~wS4L3|r=C#o zAV_;UqyHURGzeVZis#!&2aHCAw$V)8a}^(YG{r{!CwD^_0)L6C2%^k-%)v-|Z1}V4 zzcPWtv z_r9?jtF&2YT~^?uv?XUZ4VO7T>Yz~14fw_@ShGCA`0t&Z{74ti`0m?&)e7br;B4mt zJf*xBfKTR`^u&J{k>`3_v->;jx?8>eTm4al4K?hg0D`o6pt5i5ac2(>(07YZ5Nbib zAnLyY_66xJqX>r+w?%Nx=K}OA|JjffMPPf$-T6#D;I`=Ql~3q?z5k}04Wg%!0IPIU zb>nD;uJ@(nMDp!(BY2nF0)o!@Zv@>AcuzuCp|Iso46mgNnvM%?yn4!d}9hv3BQ6@qA4KW`55cmT}w88F#+^-ti)(19D+0z zbv3UDI3|DF(DYHKXSxFRaJW#_QESS1#%gSPEdOnd^WLb#fIto+##8*{P`-m&Rj&=c z1vYO)Eb;>LsPBE0E+XE40E6P0h)lv{jfBEN#_hD z)vld5lJi~fLY3VLC9NwkGc`;1HwzD(s5xfIFDHHlig|6T5tso>zg!*V(WdFB9$DU#DZ?ZE56qu(C^Z8tOGTn`}5HwLM`FR0>%a7d- za*qObx8qewgI&C}Zi5?)=?R?;bTonI&8|tDR>@g4V?40Ho*^c6(|j`$2VI}LvrIbK z{;bFbpbIr?ThrzFr9gzn^Y}3hSaWfgegxc3p>$5qr}H(7XSszO{i__m(@Yc zlVbThbmXThtr-9bJ3G1vIn3QCZok={vjJG}k2($Bb#U#u6r+Xd#!Ziu{?81ri@AyF z(_y(ZfarZ&D>Z*S^@R8>RaD*(ar$3zL;dhk4r$WKcOUZsSg8%lMDRTUef=5FXY*^Y zcFVDa-i>CKts#-&O~%7*haY&K15<+flK5dB*@+>HjiAo1^9bmlWwW%anx&~aAC~|>t>GO6!qnSm52XC!bidB75Iid!8_`uSE8OZ8-ijDJW6*-qe zD2Z0c=bD518BERJ4Ijo{Ae~tRAMIc4&&{~qUv0=Wclq^YrGng6BDlgkPuf{JuuF7l zonCm~Rvc1c8lw2O4`g^@8s@8Xn5lnntv^%*A0wdc|IGj!ecX~;A{`0tY_LO)D%{}W z&fyqv!0b*d>*$UL_ufpU%i;!C!&L;k`7pIq6p39?-MQvQ3zpEUrrP!fE@sas!Jir2 z1lALcQjsV;2b0*0f*gSS6ds_nHPxKoF-KP3Ue*F;W+)WoT}i6q!??bHQ^ff!n%zji7<98=Vz737NGg=^}F>@E0A8esF1+WW3w}6Fq>zHCmjW)K@kxP2M=zVgwtEjlt$MFM2 zow-llvO(q_KhgrK9e52>Hzv5cmkkw4px2bJ9E*o9Uhj{`-1m^<*E5JCGqk>)roW6g_Apo^r8(1gD_ zUhr;()V2})95V!db#A9oxO-V0v)HG>2nQO1bQ4Cv^kG$g;Qe|<_$G($QysvmzM1pf z1=w}W<9#QtS=)deB*V6yZ>ZR-cyooiZfj3$@FU3yO<}W5QM$oDhMZEPk7X0s^%SpH z3A8K?ji4Nr)EY2X<&K|?PLbKF`k&?5BA5OtK+WzEzkZPv%;F1l-YxOiAC zJ2*e^d8i>lf)z|Xc3qwM^-Jv4#{`aQ^UHEpi6>Ak>+0{JNOJ{h1sXW9+65=?0OR;V z8Uq4&LLlBRe=Y8%zwo&3GB$DW-NHz}+Q#g{Cf3FYqv-H^@Dz~YQ=dEQTgM9ax5GDt zdPqca@oFh?Nci3YH0q(Gjy>a?s{;4Z$CwlQ5+I!j$p|F~lWhAHkUG@Y5Zf|;-NzrF z4QeV-Fu)Xrqr`FJ-OkO@E_Pp%;aX_89xI+b@#b@<@t8Om@IEiaWl=^5S>UGRqeSLd zTAz4|_tsZGh$$4QG}l0%&s6zlF#v0K)o{;jZ|X@tHV3LWScU5FH2_TkduWjz^3EeP z>wAl$XJ>UjZEv^L*mpKWgMWPr()MeYNwu-P9!i}$bBpcX84jy1Ty zmMYuMYI(zFu;F$y12FS)iHP`_bR2K%b>#>d8;%I(KYpSXhE_G=BQm4w6wvrPiRowe zWS(P?a8}I%nI57nk>UuQl?``$l1Cnjv3O7*qpXfgy2~ydKE#+*XPI?|0A?tI7JW;= zYC-ZNvS`#~Z|bf2y~S1rBs=~ziSv)s==-jOSq=@yus1m4Fxmm`^sE+^Jr3r%J!~O) zCN1kbS@_i4si}G5oR#pjoGk1*6vqRw8%UCVNxxh5$`Pb>Vfx?4Aj|6XL|GrVzOWUR zI3~5=kIaM5ybbmo@S&U$-RJbeFIFTL{^k7QbxzCGb}~V8c|AU9p`S)0{r8`B;jfAdl{0N*Fh^^3XdkOazHr#~sdFL7S^q@c>55aSuE zN)ES>m+LgSq}&gHcLU?M6d@pxECMEh=Bm3T9zu;(-pc>z^$Yu<81K>OuD&Z-01&W1-`ZZE5f5o$P-W&P32xxGZ#+`ZF$4F3=#sSWlY zE2D{2Rp4n$spYBPhwW$!9i{|<9(mu!4+X=RL%yEjL~P%bz4roHjb3G1j*}6J?!w0y8q`MXKQLKf$k^ zpFy|K3^_v2ItB1hyZfUkAMVQ+f`HLS3VN>ALLl^>qv;GvXu9js63c#Xz}+ouo*h*y za5^Z4iSCU|iB8>qrQFXhM-sK!%f2j`&p>9)kd02dW|jBwnuj?y)(|-9aSWE zbKi~v-`=YJ`m0zZqvs0zN8&D=^p0nmRkmMA6r6{X5zvgRKk}I>1cXRhkl$15sdQi) zo29$`sCH4Zjzv0iJno|9>r3WfKk}XUZPJrX^tl31mlEBsi2TaF#+kT@2!DcLGl*yC zMA7-fWrt95+>f?swCO*IeP0v>iIay|jTT6h(8aO|N3THvxTRJIYg?BqQCyTVMK@kY zSUsw-{L=LS@W@4363Af>GJ>@;&%}ZfoBHhQry=l^TkRw^j#|9bI#b`CFzf>9K#h-? zVQ7q4%Ug3bF8XpBnm{2qO6hJB8|4FAXR?`zx|sDc@G009&vewvK4op;3B!iz1PiR#u21E!y*=9 z8ge4QfUbOid|CPY-f=CPy^4L`Qe^BhrLPiL7R8xzQ=BuFD~|iKQz7iLazOfQ)Rup_ zaaW8zw`cLm)LIzLa2Mj`aGV6d~YIG$zJyr#2Sd@;u)ZZ1~(+)e-66}9cK3@!cK z+t*eA1|W--+;8>_x4V4bG`kF21%@C#=e|>j($@XH85xMbC24P;B1m&n=>CoLb6)}x zcs_bn=FkoS)_0`A{I)Pc27z(Wts{B_Ci5~wfIMG`&1L~&;*o4n=s@JNze2}_0z!vi zqY<^G@;JPCxW9|jHKOM=P9eaDl-a^RQB<_a->GciDV`-m~=$E&Mn|86aW112d( z^}oS&3ZS28(_KX)h}oapBeTWQ3sX{|ooY~L)k&M66qLLqyxe^ON4NSCK^mDvnltXrDzAt8_l)>9d z>EGe7C*lTZ(SW~vvkmwj7#MX|>nZvDX?(%gO>Oo%C3M2EvOVuvwBGR?1B^vhcOEn! zANr*6oBH1!xeA~+)B~>=CAECDU6%s4zlAZQo{(Pw3d8LUK6H)P%}dGGH57j(5t2=G z)~N!l<7i=PpiZ`y6Fzk7xI#4x^vhg)23WW4^e*+J{|8b7xT?v2pc?-B%auq@wcZSC zaA;~KdH8qgM(VJ z?%w4Z1EXMrMYHPh17Ntg7w-05$mZJm%;#X`Bl+qqEoR57UEWP3X&ylSZ|Z^P1|Q}& z#uA^?_9{As;4BZ28<~bBc$xXxhex@Hv8pl~6Weqw?`^-0&y5xm|8%8|&As!K3E{@H zMX?ibih_0srd6FmjoDCmp)0odn3UHK1Sjjj@rI6B7HKr6s>cHok3o9cPt_cl`75Vj zK#9P=z0Ld=o+=EHr;Xl9xJ-T$S-R`h(NqCtW`V2%vf$z|G{b_2j_ z9E!tOKj14T;Z=aHfC!ziGZ%p1`T@K7glGo9B2t0V9({dLu_N=M;o%fQ^IVuIzx3W& zf{*7t4v3YFI;;*JO@nhZ#mr+W+&%R5p6lKDGt)2jN#4#hZ#!SKiGfvUO2YpJJkY0p zy>+eXEDot#Tzvgb9=!d5WDS=sZ2c?lkvh|m)xyeo`^PgXIW7nD?cA*s=A<(|hekDz z`Q3mgMihN_bKz1{do25SKF0nrA7Uit=sSy77so3ghlXNCq_5tJ6pM^^^fHk963A=Y z298FxB(WO!I{@Kr_0pkX}H9ql(@g z2C&?11{w3sa0g{P9$cELvdh|QoAUwApy(KpNS0;@d8SEm(X<9K3sCsn{vsjg1I{@$ z^dK&G7RwC*#}(uzu$GV5r{yRyxUs?h+=HTi`(e5lz*(RwN_d^m<3&1J%WK~gbYIS5 zBf(O<0DqQd!tM}=oMGP3+}eKAU3CI2U*X=x`V&}`;C1Je;qqq}ZO(Qih+R-|?{!q-8Uc(ErAdLVmrqt3O62YIb2~$CmTtl<8-d4wB;ZXbzd?0o1 z=!StlGjrvn+RJ8nw0SI(EL;Y$@t$?>(hzqfB%#dq7tSn z2`-kIsqnjQLo{s1YE*k{shIYY0ilJ?l-SBt5C9^2z2?`lsdJ)BkVJX4B>p^IN50dC zDF6s|V+2Q@|1pxRrFvtY1dQQ(*apg7&eu%U`661rlT4&*s1PbubP1vi-2`z$MxqnI zX4sB=KJB(*i*IzUutU!h>fAE7V^BbIYqHc_X2lda4jxZo%~3yfzPl#gGcZ_7CR!yT zQSCRdL^=*)BU&EJqrQ^ZQA`w@U?N7dA61r$b1nZXd1A`K0oW1TZ=P>_RkJn7!j`k4Y2M~ zy-Iout+T3}8yATB89{@!dH<&0KvVBh2sq6lS3CVj%+WEv>2NpRt@RT!ZdU8MLiXWB zuHF#mMqe-{%&#wrU8?r^@4nVjhR-qC6ext0qYW?q8f?F5oZKtXj~41LoTf~Vz_*s4 zRSG#nDFoM|?SN9HsPuPlr&iTSGGvSSlw(e))kG&o%3ste1c$0e2`LF(4@JoiBl8Zj zbNmzuK&(#4V!q7j5TX-ki9@*v)4LVjGS{BtZgxIBZIrEKCSq|WeMEV9uU5an1#FMw zesA-wE{bqQFpcAVmxy&W&aM}T7)-H>WnO=Oz0+RYcM167sxXVU?@4p9J`O>|xBRw> z7VN`WV4IZRk>*JrrfZ#A++22Vl!23;$5RU3`3NEY3-;DP4wCGE_7BINPxLq4an~1j z)gy)fi@3Lpit=rvM`!4gZV`qCsR0B*!l9(4q`MnI0SSSjQ@TM(mG16t5KvlaK>ZNXy`6++2A=%C|4!9G1}; z&DWv#RJX3)P$+5^6CeF1=|>O+)|U>3tVOhSRczxSHr32cJ4Q#!6j@_SBZ3cGsy#E; z3n{XU4&>OaW-~bAN&o4{E@BYlrt5lElWKah5^1$^c+SCms?ea67ITP2nL>JRm)%8e z>z&Zc^Hxd#9**G-;KL-IQ!#gX-Ar^VJYQ-kk1Y5KU?qdly2I@`=V3no1JR#}7&1Ob z>;224`_&RS#*HIQ+tp+q#4X?C$~l84l}XR(=FbaqAX7ZBFx_Ncy>~^*gw@h5Rp%3# zI_uRz!I_U+?+-c7UZoB&{U0xYHcg~e`IB^pe^`MaDyqCBP*`Xs#Hyusg&(#P_MpwR zZ}9gqU|?1R>>92lYIPWX;~7%LjwTv#)4;@8M0Tcue@6#dMTX#M4PljDpeH)` zgVp_@O(u-MZFKe-H0XB~!ZN;=O1BOCC*`(<&xaNtN@3V*LGFih$@X5s>w}js&@g(4 zf6CLGkfu%~vMPVA@xs*CYpQb0@bV0`hWE|^qLq>880|l-3_Vb#txptRXTh+%7!5<~ zdry3y!>akyxQFoQo9;^bfK@Y%c6hiP#Ps!1KPg`d4l(!0T$}gHq(-2{lXRbDsZ0Or zHhAyN^)=AydAu>K3+l?5GY0aa3Wnr6;u|9NP$@d&7I*tP9Om_q_{7wEaM?NGr3HKv z!n?v_fo}UAM31klM&B0$vDZdJ+$hj%*o4*q9)Y0y+tj7!of7U)Y2TI=4lUj#Z-T{7 z;9hdPq(wb_Bk0{^marL6{73-6Iv%S)XF687Qj+&RU*O@}JC44boF z0ZpxP6`Ql*(Vl}Qt^*b5Ks@&{1pbq<+2S+Oy!yHF9w&|dslC(j024>{36Sd=TWZE= zIobys3{1HsusuNo{Z0XXxZm%I&P23!Ig9qQjr3lwHJ@lOYK>zTYhhcpl z^_5`>7nuMKCn$d`<&BkAl`=iWx`*nh#`unL8G}=aAM3`tX`)#z)L2(cl6%(Fw_Xi5 zSMiLXOC=_cg4A1#_MRG)6;V|g zLJHurhmJ}=IA7h9=&w8hbLwy1j~L8L<17(>0DHi(C1Xw5H=OWZHkj3C=|qA-wW!;P z^)^LWmuh-mD@6-uH+8s(v@Yu=1rJ1nj`FV<&_%xmUBPsWIcg+4EQsY`3GSXh{i~)^Bg-W1~*!&vjIM^%EJ;TS7RlkaSef<&a zk1k4o145~~7+OY_a=`eD_a?XDnu0DmJMC$mfUp~(DV9_8g}7ZucK6IQdz&7&P$75P zgI{yZ;2Ud7v#oBd0}_ozKBd3xAF51(YxRdURt|5@L26nFKbDS1Sg-FY#QIMRAj^2} zhp0SmtqC4}$W9LH(DV8)w!;IkosV*vKgk18|HdH!bW0vm|F@L5bJ{oz`h zam~BJPU@hnQb)%oRFSw5XIDUZCRi^2BX&SAmVI`4>TSkp0bwH-kU0v0xLXIQS&aie zz8o854GKk@1D*jhodJKDs2(2GXdqc)lS%$V5PBxP`t8+5?CW)b7-iposac_r7UMN<>(-}l9~A@P*3!o&2Gn7~Q1~s4CdXXm zw(+Fi^Or%r|BcVd4Aubst!#{0PAnLABYj`oUSF~@v5f!zPxbvwDOWy@zQnN6W$Q-Y ze%|L?4XSzY3NmV{i*fiJE5DZ#b}_O?K}XEgz;U#69#+g1&+Vj*vwCY(Z4nAA95P6l zE*2I3-6wrUv--n>cezd$nhHsr82Y=zt|4461f7$#noVo6T34MR+#1)aFgFJ5hJ zZvTaeQ1TcQN?vY~g-TW$I#tW%>Ls``+4O|qUH35j4{6e8$B~EqR%^53y z@|_7@%gK&=Pp%{M5_l#oP1lp*U;lFrz-#9s~YM zW<6~pCCuOZw;22PUST_iwav^vMsZiCgAHneH8|zK)^`e4(h14uR}T{o8UE!Q6gsC5 zKC(5*6gsX|9E8Bh&`V(yo4|rUzW0SQK5?f9BB&<{@)J03&^~gvi*L+)M|EWWJov2J zb>~YlTc_B5Q$fbuJ!~f7>$5l8pZ+ei^`8Cu-zy08VF#2!)CtbvLW38|iJNt5t}%wD z05za469S+S1t_{&4L71N#@vvEB|Yro=f@mj6Cidor%X$9oFD1v!%Touv8ngP-D6Y9 zt{P2?U;hvAlWPKk?H6U$+U#aFhzzv_dXJPWc7p}ZsIUWL)_nwE^M3$X6Qxk|*q>mC zFKEM5Z#{v;xe-%VfE%rkl6l$hf+Ap^3TiPI`D*2i{c2s_pbEUFQICs{C^s8aWDy6H zvf-D%_zyg!Akw}2F02C;)P?gpJL`DyjmtjD<8Q@uXQCmIJ=#0W3hDE6zb*=IU3r~W z?mm%?bRwBuj(hod-rhCm-&`IrzEuI^dohIOF>W6Vq<4mre)`z_ZWe!mXRDj`BBnBi z0;ol14%d1&*m5#li7m+3pFX$*ejmoqKyofgd{~Kd6h(31F&q+s`#8|Tld0l_i7}4f)VBPYbCgk-TZ$M z@DjYC#Lh>Su`g9XXtBxZ>7ZL0NTJr_(yefxE20K$RT`D-XH#<5&mQ5=USFP2=*R#- zuY|3HOf8u*o<)oDi1GZvI-wZ5{it8uMwQAkfV|(@<{Rpz&QO5`62K6IvnLL00m?{B1L?lU1TEHf21t8t9)=_VM%Oj)@xOUSb zsQZD?qv(FmgUE*`U42`|`n7a4e1H~oeRIC@u(taY3`*X{OZh)uhKoFpChhbSBRK!> ztQPfP^o}2%eZ(-^!+vveDEJP8?892hz7)!m%6X|FMOk%O=^a4AZ3!OnACJhjfxIr{ zd*)PYf`vNGU_xDq6)ZapEL(~ILDEBz23@DT@$J{nvxDJQqQC2EXZ>+GA_85gbrz&FLB3EBK%4P$_0CH9d@mf3VXRwk#*ot@eCJH%t@>d!|gkmIHA= z|82)McLVZ4N)KT3<)V0Df;7EAz-OP|dw?6@y6h)v%ju^#P5`esuqw zsvx+ss2_bx;g^VDL4${wtrqwuQOk)?2Fo{mXELm{d9x&82WXi(z*T~aiskt9177^u zuO+Sn-5*1dwqqLrGqriq$E!zEO0DMU1g!y}zjuYOWL+q3#mMui=PQKHel(vKl) z|H5;W61ZJOLZdI4=oYSKhQ+-XG4c$4Uob{9AySTG0A%Ij(PX=c9x8wg zTb(v#^gw!6F~GwXu+j2;e_VPTrF%t#nVzhfDuTA4E|ou_1x zy7GMVFS`eFlYrcy=?v#QgMD%_;Pa`q18b!L#NYvA+yo`d(BoMCg}yJvTB>gFdZ71rm%1({dT4IG8$Yk%puISAsSY ze$qNVw^TB=GY_#C@mksV)%oSL-TwwMg&+_LNXcpBjfsg1?io^}^L1X=NT(G_`u!;a zW3yIMwxl3)eBwG`7Ey%3h^9RiHwjEH2_wG{<)a_0x#AJ&)jYV3!cmUd8&0Ha-0GT6MX~6D9*u7xU*UC5dM*ikGn1(t`WQ&#n*~=CU=clJe=ljakPVM=?B4*ny z79}g|1V!($;j1xk3Y;!@8pW90YZ#3;bdgWOy*u;a^LK!QpVl*X;vhmGEiZ|hLxu+K zqXLDjP62NsBtyh4-~MM%gi4~DrUwN(J&Cs5PLTF9XbljZyrL`vb3wy;rv-thDYi^8 zJeu)&pc*OFHSzApA&#LrF-cPyJ)syhzgjoFUI=2bTOsTPcRFwnrRjfa3}+W&K~fd0 zh!C|AeDB{Hr{CJo0gh{nU{o_sOS-(PNM}iF;*Q??I~!meYD`LG*cdpsRf|4gEIzLM zSZR|9F{z4S>KMHW9!~?f(?mT$zdJ;wi1a#O86%GvegrFlRjjr#VGN#$`mV&PN#2Iw zk{>az^;L@Zy6t@nH+?RG`-uls$ETpsd=|%JIRS;X?ez?JhqR{yT}<&mbqMGOLbdBk z*JP1k@+^J&V~V+&1<0Zw2QyWx%y2N_#nT2>!u9nrYV81)=&hC|JU%&(8e%v~h1v=1 z8o#4*lhm7+F8ta7iQg7#kh(hLnzJ&!_U(_%PAf0$Mg96`5VRk>Wwab(gtko<-X(2# z!Ocgz5Juq)@Z}va-4y77pykmLa^)3RW1(S7vvX4EB6F4d!5s0~v7BJB_{@EJ5FZmN zxsCDSN4%`N8|%__N=I$LEnILL?{GP($~iE<@=S-hS>(tYxr3`P1s+#+L)H|N39=!! zBNA6-@#&q!5CNtiEawkfcpY*mqF>YN?3l-&{lmEZF3Qn69=d|Aqx#S{xA zflgN#i-qd1MXjgu7=8d8bC)PVhc6tTS!+0~M|%n>Oi0!#*p_#DB>#I6{{?~d97EC~ zTM*k$jjlX&JlpK<-`ge$`++jFy6Ek)CLpa01Hjzin8+OhwgJ7QLZh#g@nCeP(0;KV z{UHknQ$e#n;kCFNIZW>*_BZ-yZp4!~`d?4wvaXF2{A0ZJTl=}B_bfa87$c8(sO9H6 zflbGTT)b-n92lUGaMYx{JdE~xM9LumvI)~1@2CyVDyBu;Nj$IaaaG(^?%?l4JIwCi zP3dfnw1lPZmHM>O`*4T&!R50knnwz6K%)d@N*&x3;7OBQJaZPJxEG9d|(=s-qN z3dh%3eybZ}235p~M@?hg`|B&0toy~DEDM5nPYo(-*E8?Pf7S00KKKLLzL1~j^F!MR z%;Z9W2CqX?96H!*ie#NjD~$jmnzyMx1G zWZwVg&%b#V(K?IZeY8TLMRbUhI8zXC0Ll;Z;B;C*wOxFDGXCvE^_vtv4go{ow-2g! zLnRl}7nDr&q>iE?fsbF8^8{JqD@Zz27Y&r*#53J|*o;klv^$w6GsCtMU*}Lwk@xuZ zg{vTC6{R=vQDAv{TpNHi#215@P~{PR0F%0vV@~Zxb+20v#x=Og7aD8LUx~ZWby~>G zxdzjVaih&ne=W@s5SKj(-1?MLY2y1!C^T&s6s`JiSjb~6%aXGJ0X!Pdzy&V%;n$&b zAa!^4%|(*m!a5zLsti7kkw(X?Ic)pw4y1y<098a95>u9INp|v2%IE3%~dJr<;FZ8wSBb%m<3*c{N~GWa11wTdO~JMfKU8BGR}-aKZ!8u`??-RwIj9 z_`mVleC?TS`?IWxx#xEuA{yV!wgfCRnK_qdT@3C*kKp? z3}Bl&n{N3}fIPF=hPKOj<(0dzA$}baeu%)w*~$%{BHU=FeTsqeA-!xi|Me&FlbD_d zZ;3UCwNf78#G>q6-Q{KU#4oOXZvF0PvBtU5z{(32!(fobjbVK~71G|Uv#!fF^o*;eulj|$X#%!q+#|r%@8@d7L@82{O58pqhw(vf(bydTVEb;) zYM9jv5?~=5TLR0a;CX-$-MaiE>MrAQA%0n8E-qa@V@a@CS2Tlh#U|rQfjp5QJrnPj8{rn%C)# zgao<~Shj&g|I6Yn5(SUe86_*DzlNV-ek+Hetxig#LoJD_u+**rX=?JG6NcUq z0XYt%q^jf~sb(@PwoFpU2uQbB;8JR{kdxI^2Xs9ts~V4vq77WQA%mn9!d17FwO&Uk zG7e^k`4eafdsH;!UU;RNClZTr%SIE4$-S(nw~Bj3E}0#83S7-*pxAWk5BfZeL5a~) zal1!JPelJb8k<0iI*CcL=SAFt*rYXj^tm}nr-Migf43ePb=OR0B4sdS>Y5H5%c@5< z-=!aNid50U&5-t@M|h#Y+SOhK6iI!i#Ss3$k!!L9CJWgHlPS$&1riM=L&G|=5gQzS z_ZgYS8m1}VjgB(EKl~l|4wjA*L-Y&` zj3#S`Dy2GV!AvuT??$Adi60kBg4@>fs64XesR^mq;d*c_t$LH!ObCN|2km-Jd*Gg2 z0#_!S75KT*+4(%-$OC6XK;49Y%v?dHF4s3bM_C%V>gddal~fSpb?GY?8A0LXW~_IS zvT{Jzhx^A(CVL)DE_SrO@Sd?OwmR`LVxQ$~}jBL1ru;rit~1di z25bC0P9Bb$`cS+ITe-q6SHwMAKffT3ul;d#NOI>VtR%3efD)m%jc^rTE`}$QZ$20p zn}6m_D#YHPe!@>T8`x8utH6sNyf<~D_aSGnwZU#9BFeq9j}sqLfzE*-i33VPKOc30 zKx2ATRsO}CpwH;rIkl-;$>}61G)M;t;G)iH?kC4_N0iisQ9rSNapD}Ag$+rcbBk<3 z=lIR|qDZnsAl-8Y5tVI^;7A3OrgCB3B#?vyP0m2`K4(r{>IE)&w#>EL{bhs3MPH%u)DwL;^u*0Kf zod+4#a;D&}ghR3fCYTAZ4KU$XcvvR7j(_A|H}_pYV=9YgS4Bu*b~gwv90D8fV&zNz zNqXbD`cT;J$Y{-t~G7GAYiuMlk#| z<8_bO?vkO-hZ25H=&>6hPfK}J9Q*+%-YDSIu=9yfz+cvxs$=HUfwBdM$lA!A_Rrl8 zwab3@14#3aSh=fl8i!t3dH<(|TC1m{E&*0cIU%^wGdLdargINc<>E zbRsBq`$c~C7ZD=0->l*AFZ>WvOU5dNXF_x>Px3<1!d9iQ?>&3NqJocaU~s5y)KS-a zAsdZ7D}pO1-77$@i=4lCcfx^yi5RrqKA*9e=q)iHe-UigANBoDhx@Z=-mKCs8A9FN z#>*N_o*V3gaQ-{3VOPssO0G^h(af4b2AVJg0-k}%HjXgvndC~8 z(bbF5>eUm!Of*hD7P3}47Kc~moYvEB1YKb}mUWq%ujP+vricGgV~#@=t`#Q_%y8C- zdeG5Jj^r4y>ZvE;`5Uy;Qg)1zFll&bj(Atl^?*cN%}{b3fDv84+M)HXjf(!Ew&Wr- zMNSgj@mF;Nje|jZ@_K6Pf_$y^?x24jt&U$||Dfi{N8vKTd@mUp{P&BV8siUtmI-_A zf1KTWRsBNvC;h`>y|u~vKPXrm5Z!*r6?Im^bKDQucS!G3izWYlUYU5Uy`F|vNNTWf z813c&r<` z8AY6PxHI&837rw}KYUOAb2TtjF27_AE>SUt6G|ChID%$l=Q2PbV1^yOPxC_w%SEvX z#P=ug0hO+q5`D?1mv>V;3KqrP!yNRg^@I%1DoiYN`TFKd+6|T_4ayB$pVTil8T=Gx zo0-h7U!2d2Tb%bm8u%Tiw6L-mzPyT7kdi>1!AjY}+$-3AIV>>9QJ;hp2tDDG=0ye3 ztnVV_Uf3;2;S*LAN9<s_0{26EIWw(suKBK z;usQfr!`{s`MmGU!@LBVk5giyfq90z{@v!+K^1x53oe5cOBNDCN9>n1d0b{yd5jA@ zA_@pru)Y_$IMdB|6qxjBG!8lMHH8{H{LNACa^WVWVRI&qfum#h z)f-KmkZ@vLviroGGoBZ!8$=8gB|^2v^`om)k6SqMN^xUK9VAMxr&Twyafnrt13e<6 zHV>gYU^C^zo&p2>so6wb%9ivsd(Y5FHZAzJbQ!kCmKif$i918+wTrVPt8#1Eqmi73mdVlG?P;Z4?;MGCV4YNY?NL9gr9D z5Ka#zp@kb1)}tFzPoFV-nCZMZ?u z-7);UV)=Omk%92@4}a2o68I$K)@0#e~z@Yw69Mr`-5zMjh1L;lny-W2byrN*Ve`YVbtr2kP zwjOl*#U7bsWEu}8x%4Y^6=OY~aP6e2>FGR~@RITJI5vl$vCoPjfq~%*<*>xbKTvFR zf}6r>82x;=IWc{Uote-)%g1VR^xA1&y#|QXs|4}i!_KE)Dz&2@GH8zf7Kx8DJk??N z$$#Vc@P~e7-Kt%MXx0@~xkt;r!W2qa`%;;9R@sfZ^WL;+`L~}e_5OzsRgE`)nrdMx zB-gCdM@=V^$`?j(REOfVu&<*(nQAek07bQa+&0}iQ@z0=1;TUYcb|x7XI`hxMCpT1 zzTf%R9~gH z7{5ouxaIGF5Slt3%?R&Soc2X)pNPh#cW*}U}u=`4R_rkAa_eR?9Er( z{4u_Mdi=Zf%yQ)AdjLx)c^`71LHSMOyjH2PLU4#=*VrY2eNBGu3O7NRgYd4BZY5Yl zf>4OyrP?qRv6Han)m_E~l5`!Tr&LtjQ%hjc1fmNoToLya!yj)x+3xUQb&w z@}U*Zd~rNoWcWLUKDk{?QSMtJS8Ct@Olv7NBx%23)vf+qem?%&UzrE1(VT828M0sA8 zYq};WFY|a&g8L#kgn&Y#^vfL8>sHeNu0#4fX z*|qR1iqDz_)@0{&vngHAhbcMc!#j%zndJH+03OeJCm7qhCsXbRuR*z-R)K)xVh&C` zfXy-~mkT#4tzXNTAV`gBVO1!Tj?-X<>#n+Y=Go6^I|mJxwN6uoF%{ZpyvC0I;1bDF zXnQHtcmc0~yC%0+zZ!G0pT3T6K0P`PHix>Y-wCh2i{ch&VB-?Ukag>kt1RGzvst~y z?ZX!x=_UU*WR}~t3T6-Kk<5_+071`(QnB(KVoxzyPeg+bfx&rSLQ!ZApG273v=BT0 zmDWL-eW{^@WESSGV8IOkx5@^)b|WFvRuv+|il+0AhX&;|9?&R2lz0FQ!b9vbvZZyg z-0|6NJ!L4VI3lj+}9c~F!&4kCPqbC>hA+`)H z>FbpW6+^p?x$nRMaA`Yw;xVglo5A^G>RWknXFb!m067lOPLMcMM_G4`(muJ5fpcb! zzZMt{ZAcM$uxoL|M!k+r=ZavJ;yTWHqRU795dM30awKS$(#=l4i^>qVNe5#yp}kz| zjfmWVnGnlYnzVlbY>Wadu3aMUpme(^REP1pemvOmcDA78v~X0rccj0>{FL3na@5no zTgJEE!jh|!vA4>JrhLYG5>m7a1DR!;Ntxs29 zfSHtE#1%c0Y)GV&T&`JkrxKlP1P<8&g%6ZkW@nkb!(lvLw=*PdKAg8QL)=;6G~da_lHa}`@ni2>AQv6UVApr6B* zb^or2M0$@>J)ir0bgL~?re7jA^sz;BTTtdiP~#4fv$o9DzS2*M>A5}c*u}|4pV~U@ z7eswWTxb~iLKA*e?BfpMiqc5gVdnjC4jxX8^&kdu_Fe-`xWe5|w=(?)7JU&#Q(HX@ z2Ce*l_u1xulp6X)Z$^px((G{Je{bC>Dg6SrEZMQycI9`vImI%4dnv~SzVDPnUF3I? zJm}g{hWT0OVON~#?K)d<@y!R-ESq&vupeUmiI%Vtt#P|qp*ZlbV&hB4#4N|PtL{R3 z>YDzJL`%&AZ=^|e@S-P7YBxRe;qXk3#wRxe1h8G%XS#66VxO}(lQD?+`hiyGC$HPC zZgJS1-7gM2EOVt>1_5=tJT1G$uU=htEH*7X^}erD&_=0`bU#>@m^xB_vnnSNxDr^G zYPLI<$ix6+lC^DHU5Hvq`u2TvIXq%G3mR5A>qVcx#EF$pHB8}s4Edr(Ir0!}i1GOO zJ}pz~HvO9A`FTLX{<%YPD9Rb~B`v#22|Qme1nk1iXO3ie{0AN7-qVKw86x(l!vzq2k7|w4 zH<(G<(amIUh%eO}M|iYwVk}^Mgid0@?%j-=Y3ONBq89wUbP4F>rMyq}Cs~P;FcloNmq&xI zwUCeNin3)q&(Msdbs{fD zpJN3G7;`H+{y2C58?aK)d8tpnG$aOh3A1=eq@S3XoKNcYc%al98XI_($OPns!@Fy) z3J9wPy!v6ki^85KH#t8Rn8h$fFP)mfHy)n+h8IoJ131&OCtW`G6#WDH^hl{WE_Sju z2}Cu|r`NR=B@`M3>xNiZ>-JideLEve?Ku(C9ntF_!zrI$W0oJrZrAE2&wuNHJv$VO z-8pm$C$5%@)Gb=|PVIY1@Xh%shVFq~ygfy1=AigRR%z?N`a+DYSz`HTeNNxzD}gt! z0fgVY16(t;OfN@tzW}^B>q(*tvmAIJ&YlS+O}ONg1cXo6$t?!+6kg7)v-ET^qG9w6 z-#FL>B=8aCTW{I4G?%p4*y^*ktEfrH=Ub;_7Dl{eju7rMoF?2wU*)>H{`AEgBuIzu z-O^ro@r90J%@E4Z!T$FCImz*+r z0uvfW?ccR_O_nrF^!7~gq$a+s%ucX%N$VRJ>7t5Ob--wUrBz^g5rbk^=!HHL6O-By zhv8LK(PQ8Y@I4z{bDRfCHs}07=@4o?{X5|qx^PDcMzSgu4kl?2&*pd&X6bw=LmVF6O?}@`!axd!>$;Z0_Xz1?{X@6rCoxpVKVuo z!wv z-i{yU#&Lk8G@pG}^o5o7tRZqWa4od5K<|Q&lM2|v%&w>GL@qFJI`Px_BH~oP6a{{J z*6EU!zWIIEM*~BF#C9j)(f#QMZJ_17cvH|RAt`XdQ57&%rOS_elqAeMzGg^DJut`{PP9R0i~Az;O`@$$2tu zVYmK1(690^zH$jrH|Rs5UuLp-`A2rv6kQc9%5X8TKXmsecet9(=zg+}<7EB*9v6yM zL5w}4_Z(`v04KyK=OGqV6m8}+b2T#^K#F&oMgG}7iT-jdboUE8*W;|bkB+UWCB~&& zJ3}PxGn10{w5MVW!I9c8*%@HQBC!dPQFhiadPkry&Lvwo|E*QFXh^ipHvf^hG63U6 zD650Y#dGopGQu9)GjbS2XIJ(5Vrw1E9-n&x^-VDlwy*4f{ahLWe?I51IDVxJ0g#f^ z{b@sjHjYD5gbtUbcpd)EQ!(B0PvntNyBZ88L@USlDft_ z!=#B0-LOy`NWpDN%#-g(_fpqxWVpBpn_1=;yh}M< z9x5|e3QR9d-}?XgiIS-m%TcD=P=GnkGZL5b{DI(`zqRM|kQd4Fe_lCH06Dv73M&i3 z3YUP%whFp|e${(Ha1ns96w=E!zgqhy(v|^>i~zfVXer%FKp`T#0P;P%-axU`xLo*S zrT@W>u|dJ`X9+P{wQdJZwezLt=k9Y_+Ml$9YsO!?;G{oZH6O$=MO(&rFE=wYbLKq9 z@OHZX!2z?-L8x4>komhIPuDe8t>Ew9ztgNrkw;vf)GyT9-nFF*z3)=vl7$IVka(IS z`K^A&5Mlwn|L`DAXKpm`_-!D7`6;`9UPMTUHwaTLDTZR@5H800PE(RU%s$CPF;>t5;=a z^rNocAi}GN4LT*Av@IlY$lHOZ0Gsn6?ckT;g zsSvY(hh0LpxLn};z@<$N;E6p~L!>#1(QHM5xvLg>hZclo40rcqe^0?LseA%sQJiNe!&or*k8L^q!y6LcXVH@2Nn zeTK^7G5|U-RYlwon=eW3+9GCGH4Rw+ zgjF*>NWij41rNqbB7osS&$Z$K3?4o`!^n+NWJvP@+SxubwFiE^sQ#gOE$r^PM97yj z@ppmbkRz|4b|Z<$>Rn+x1=W>r-|OVjQHV+ItZMi&;q86z53AN}2+`2o)Mj^fkrgqY zCy}Q!S1KNhe)|`$TbQO;@G`iE1Dkn%#3!ueY@pvoFjuCb~25&}Cue*LC zh&%uidVZ1py+;UvH;P`-^j!VJ=4Qd6cT+~PYa`9U_l}Eod_c^Oj-eCP9EiPl_h3Bh zQUb`jFf)EX3x^Jp z%bKm}uuUO7EuDIu#`HJt1rHiMl#E|~e6m=-qWG@FjFWvc8$FDcK7yz8@P5h9S=7$W zh?;Et>?@PwoSu6`qxBx1quOe`@ptYx*C;|6AsAdk!^u)|3okY=@GiT}3&wnJZxx}$ z0kw(g2drFG77Z(}PgGy#D7kk~pKEl5@FA)zn+KK<+D*0z7`!&+4z zrdl5Uvl7fH3{|vGCp8c(SI=xZpWVaU=qW7GA}(y(1ugD{DamI zvIhIlY#SlIsv^Fik{=^(-+9|T5^0z4wu^h=?K$__=hwM^C+VVNh#rR75y;17kw4VS zH*>iw5K-6@SyRp6q7Q@g{L$$0d8z-Fdu5u%{tts6f{?+GmwDuPY>NkSq&ug2R+#r* zW+eHsKo!Se`I=A5J6Q}^CEvpR^Y+>SI(&p#=!ES@oBW3R3?DhDh!dGRAN%qNe!692 z$3$F@D_L};jX^enfiOHURu&t!mQC~3@ofhAh^Ku`ggWk5(kw+>TVw9to5fULeY5qe zq3s(?%|BNyLlRLi*6tpZ!R8C_Tw!AM#oy23X%wLG5}OG9@Ps0vPdtaK>sHZ?p_G;_ta?=`0N3B4%eAhb(huaja!#OOjSEndEmT)vuh$f$R%Eh~MVV*b84F)hVh@&jF|My=L^(6;L$2T|8&#V3w_pOR>h zzdv%@tzfiXuw)F64SUfq${bY6Mqbs7r;60FPi!O8UEf^!7O6z(!rpf(Yce%sM;%GQ61|K@+uH=@!U! zeFd|CMx@MQG+m#~q#3a5vvOt{$Ev{<@8z5WIm3J_sVK7K3(3a78rQQ=xSFp8InIR6B~qjNR!!6^RJ;WO zhrRA@-|4`y9zxMyvjc7~kLaZxeCa=-5`}nob=f=ol-jRR3@lr0hgBN|W8rpUPajOw zrES%_^H{zrF4 zz3KwW22%~>XoqoZ35efDK2U!mE1HnD_1>N5B=iNj5mDFOCs-Kj-$U0aU*ptpS)mV= zG&v{tlh~i&A;qtkX+I-fIaj5$Q=%SB$0n6_RH)Dy*$qv6e0oz7NPV@90pkd``TbLF zMB7f=U%FLg`oOA4Q|n{m2Pzi_fsmj4=y;n{A7ftmIv5$|q{YhC1u#3KPp?7zdF!qhVTQ7Wn1MmvqMiuo%2R!kTp77elm+ z7{@QMt?Bk``{~k{eL$qHUc3b~k_^zN&*-Tq#DUiG{I1m{R1|~t61{6OVHy8#@5)8f z+}ZKS|M3Dy6Kuo@L0LMz*vhc|W5|8FOpkh9i3sdZPu@3I9ol|(AbRuz)~kJZ9R5j_ zc<^n6aMV+i%#;cbL(wRFwx>}%jWt(Y*C}afOKBC7nz6FU5l%=ddj~o)IxF5=d3x_c zN6T#^$AcfqjyWbpt9kmPA0L73pzZ9GU-shj?zbvqZG0U3b-()pm<(kQkXc{`|9;)P zGaSmMsn+-#HyCf6TK_Sm@ByDzNphv@$4xAT zKw)Ar+S0_nuzfbA8sBq?ewf#@3dHm&z`ydn>BscMI-t;(!g+L@_1+n(&m7cnsDg4R zk}rIA2~0Fc00n~2DpQZj@5O3=k4N6$;m#oN^JsL|*+TwKMmSy*3{-^5`DdCuBm0u4 zGo{aFf+K{%N|-lUq*QW^$pv~;8-x0T5CV&qYjcgAWAisUnJSO&DMp!;lmuR1BCbTz zw=3!c&tn|%U@KgQ_Z$dZ0^XI;#NY0V{5o^1*?oydOve@SIC1z-7W3My(fX_T7~Hrs z(R2D(#tahrULmVrP^Mc*6y|*^O=+5?K2CQ0VApY=!l&Bddgm7lA^1L7U`p9|6Z7ECX5Ird2eVHrxHA1x-jHLtF*sT_cDH=P$>w5HeM)kn=Y8++X|5 zn9X1-`bjXm@&5bf_jLW){5H=7AWqa1l(GB|TY-aBhWDwabF>pg1Fpp077;X+g(*bJ z#Ph)V#pm?eEK>uf=!d`Jg_IET&c(8Vl!o=2wpy00G57RfpTnp|L&Nu#5Ot6cKej*U zrfbg`D$`CEYl8&19bFZM^0NbmTs^X*e=Xsjr~iPkWa27Ab3QS? z)bFc?t!~B>4t;pvS};>kQ1}aSPV7asV}}d!BBC&vpXQ=b5d}o}a-O?#86h}VRH#Jb z*J7rc31qK0cY7!5&2v~4_w=2-_?P^>eLmxsFV|f^(4Mw@RjwV; zs3vYy)F&m83&h*7z%qYBDqvVb8F$%BBfp;JtW~+wpbwGm`+>4a^*GHAc+T^UTWzA8 z|3#(8qGb;)o{p7Z$3wpm&heUqlZ$R_hV(j-E0rj^`0G!6!o%Q5hG6;VVB$X=<|o4* zQZx`qE_%|uU}|#tOwzDZM&Jd$_4Oh2xSs#JfVG{*ig$96C6RCiXo-dmN(9{c{)B5&WGsOq zx03jnQczK4x$L2gm58ZBZHF07#+i?QAHhdDhg`a3pyHRb_cl0trFR(6y{?kRw_jf5 zk5Twjb`t#=((BEU`jxmxd;a=$_U#Yp=Yt!kmLOe9^h)k-hevG;GJwjd%f4Z?*PoT% zLBrE9zTuKNxNE#eIXbjyoG6)r6@p>8?0OA!;LiS46K;c+x2^+>!)|021TJ^46wCRk z+EIR4Gczv<6PNw3Yu_9nW&R36(=n7!+bqV@X-K`I6SGIsiB-R7bY8q$i3#%z)HWD7 zo!Y^&x6^*l=A11bhqu%=$xC)1@5O2AGS92(Y%E~K{;~fByMc#k0@3XYkMai(8kK!? z8j>ltvTh#xNQb`GN@?Xze{E^!M`~(#p(ik-RwD<`B`Q;qf_N`4omCizmz#1^XoBCWbbCY* zREb}P%QlrTuGY#eCI#FoO>n11q^_;je2!9}*we{w08G3q4320qEt+E=G-A2dQimbC zqxa^=QmQ}lJS6!GYreI@SREX>2u(_FXyIi`G*(pkbNcDQJ zQMFT%>7OT7egq{+N}*Dw{uegomh_%Ds)VG$&bvFY$(7xqyN#;h2!PtI^rJaW;)b!E z^%Mm2n+YQbf&cR)G-;TRqA#%VT6@%sjI4Dts>BM`;W^T=OL>_@r|yH=J4*5QVbOl z^{u1n89)|21-!3r?Goz&J-)STxk$rIg5gTHv!?~CkzOo-#3-&40?7tm#|M5!sG%sX zCr46D-Xwy5v%)3aUbdgr0COI1@(Kf=s5Q|%<2G{L`Uc2}!~R4Ns^;HY1=;W=hGNQp zhYUbJ{u`1@)cT34?VNm$A$1%6517*xbR0AQX9HWJn)k4s__#Fm6;uFXq6P4ChGARN z$oN8JY+D;*uNVmg=a|s27Z=o+Hp9}i#&;0upYD}(24|TSyq~$!nwe}!n!qUH3H)|d zEQbx?7|=3|loyG55v%D{{Ak=c7LNm%8fcp+^?VyP{3(RiqSi5)MU~A}_cWzkZBvkV zKYG&rZraNFJ!pbwEr}%T(lD~x%;)s^_{X$n;P0;xOAW1ym2Mp_5i3c zgIfFmz*`D=tM$;|m0RJvT-fKu$U&(Z2nRx6y4R%4$?_e$In)wc78D@Gcp1p zG0AxqM8HPBR6gQhochzqj-(ghkx8e|t)vyx!y~#9{MoAmai)0<-Mij_^(?J~unIu% zM0YKjBev|Z)D}WrEJ(uI>~-!J_6364zJT`RE9n8E5(ZvL>0-(Yg^Z;43_}t#h8pSd z!=aDEp;?o3froEI5UI>D&(N1CKf+e-_>&aE|9!J$N!7fkjq8Jm-{#K?xAD~09tRIN zHO9U=WBe(5?{#Z~h?K{ZKm97|g+eeh8Li2diUy1QyWFLCFrR@l4hjBCE?;tL6^_esA+qa^3!bW$YU8jG)mTRar1JS#*NnhnOIab}daSLrx*k zKa3jK1gwou%}3;^*hD@(EuKZJT2N$LUK%Bk+v11v~nXCHKbDeuWHLA zR)I0UU+9$^g8lleTq-s=t0z=$KJsr#Ls>Z?{-`iBCI;&%E#xl8ki_(ua4kC zf87zi6{8SC^LyPU?9A(l7e7Dtci~EEsl06UQmY5l;RF{tmzi$?>#z+jVeg7BCpFg zHlA9$JB}xiPif5uaE%-$em)(*1XpV-lF1Lj)dBvv)h)+OO{+kKKQ#t@LtZSDs-R%t z9x$#jN)N{-)xKsFK&~v>*gQ+)v<~pDTH$y6RJ*Lxuw%p_lb6EIGJ;aHd~0(QIWxb= zl8rq>f0-tM6qJlLoiv^W5PI<*xs~i6ZX^DQ2)5p}R)SIJ5i??MWl2rty0vH05=m3) zg~pGou=N!URy0AcaE@9zDUf28IY91We3njZgs;ZhC;#ahZCcW;Fo<%otbE1IP`^aU zONv|YTi$}6`9JhM?(puwrCvHHaF9g?C~=si!4Dy4JqR7v>TK{{1Ed0=94~;seu_q0 z%TKy)87+S=N?rfaOfo|Wk(Q#aoXr>UwBf43zB3!mUAGz4$fRWkzpoweWymFP99gwV zp8BI`IfOIl{{=gZi{Ci03ZQgTqZn>+B#IkY)<$H14hl*X4HrAcKBZH zSvdxNi`RXYs~7#HChVfy&Zy?JYL3g%m*BBj9^%@%~NL8efvPSee-;M7RYbY|$QTKiIs(IX+O(>@llU8@n zp2`GgrB03FH0^W}52=2VoOg0f3$zX9xp2&3QM&nBT&jFc2jXhrTIFa}-Gh7n$3*_V zV)jF$Nhf16?h}=v(fcNTvN3WB2cY|lIGXgP(Qu2HN%=q*pIQULj zrNN@Z(`m$!G9=mS@QG%hx=!MgI66}$^5QwD=|E6devAmn!8-|6=<3o3zOrktA|Wlj0(aYj&G_CY^>pMRno(h~P*==d?NCZEvJZ zW8U0{p>8^G8J?c?oz!P2?u5-%4?62Lwou14F&5u()8yx1!BS<=_H(S4%HNl&%?p;n zlD~Upzbjx+!rMRQ48-xJYie%(&lXDdaOC*a^hqg+7Dqr*#QScrq3 zfr{VVEj-Wn)NR}}9nB=+E`DvZ*Xp9v{B*uvUx*gn(OQGR~Gxfb$S zMh?7`9{U>Qyy9jdTc@#1w1LeIX%ZR_wq^tB(hoi&e}2uGxov}{5Nm@-eAp>5pZakD zs_N@~6pmhd?#HDHJg}zDua+{u9``%9op`S>wZ9~{@&X0Mn`aXtozfP$2t+r`An%BnD(#eVfYnI$FCgt2x_ znbLt@C5hcW3Eue%$y=Q+`<_(U+%kGjIiFGz6;H!Xr=zjdo+t<<9#jMaPZ<7YCVM65 z_Tnb*LXvt5h%Czm{F)>b_uX+V*#F>y(%)QWFm+r^-H2G61ox^sAtyFVyj{7s^+j96 zBdB4{61epx-SODiS-vvNvC&5RTK^a$o1o&3^9bqv%ELTm5pz5d7yp}%`<}cpTr^rE z+@rsep5i(mRtR6)k&xu3X$(vwE|YLB4xIRO|v&Q<;cR>1^D23l5OErWPY6 z=2*_#QG(Wu@bd@d(u?Ro$!vUPkB$WiL}zZfZa|||s?NYtu#XM^d?Rx9kcdVJeD88D z{^;Ta&u!C#!62AzL0pB4iOaxGz)o{=P402LyEEhF3Dk+|Wzr-fAsp#SHKqT4IwRuf zFiW8QUU{45Y*0gscVuaUzmjC|i++`>Q%1R_^H2qf(->Q(mO%MPP6Ru@!~3cr&ovo- zZ$CT!w|z)WA>d$gG77E(kNhySDWZD!dJ!a8>OHN$!!(|e*_x$lUKC`PA`Cw%@=yUX zvS#joX-830rsb03?eyf1Qy=0`6jYypxzDQerS$3pns>sIettYQb@J>rEt~BLyiVRn z@F6E2z-&Zy-GL@OLpiTHV3BCpA-od=kerz*(^ViL*xCJtgASYPyQFQ`$5!NTD(muS z5-fbEg?*OyEI@m}8=yP3B)9HKv5}9g>*|xTlB`qbc2K&URDG@X@mz%Z8u5Hw(34*; zWX1-__|QowII#I3L~1aWOjDxsQxt>Kokl&nA(w<%Fqbj@y2YtVi#Kh) zR%ai^4QaKSNSQ6yf;f%KesTm5+^4yjpTh+cTgUT$E3ry%bX-uog&3ycoqyZe*Qp@4 z@vJ%LnN!-lK?@I221V&XcA#am7?kWbxu6YS@*1?iyl0$C?m;vmve$YprxEQom^bKsdXVT!S1M*kl0HHZg1 ziFXV{7xFYep85o%3&etBOKN+~&Uy&X7N&t?BM1m$ZDfrng5*0Gq7U0lYh8gznASac znXnJ0@Y@8-Cl*~tq2p<(SZ&E0L?g)vV# z;en_!JjjhjqD8u&@fP@hVM)|hX-s?qTIPx4Gtwp((dQSb99^OP;^6XEaPy&kyX>AD zj6HukahLB_fa0Y6jj=d_@J!JjXC}kY2t}-3+N1B)5Szmv<)aW4>Ip!9HO%N~0!M}n&3^7N}+|H%7q~jEyBqt~zqFAT^ z3^6ln{H-9mEWX}7uEM_!hyPjxIS|?9BGC7buG4E2g2+>t1O41T>k+!nyI&0LoXm9z-scM$)R%Y`__i;A`MBei}WGY{Y6S)LRlEieM8 zaki&E(Kr=dfs|y3Y74KAo^}1+5mX7EOO9CI$aoK+3VS7Nv}#ddgwl}bBi82UX6I%O zI;G?XD_blWbOj63cI+|S#JCd=58&CDko9nyovgBSXiza%l$cX`Mnf}d8H_`IQ3b0n zZ1M4Z(^b57N^hw*(2bY|32AoXbqM};@Vy)R+l#hrva~bKl56d*QSyA;3DyI3s)zZm zF0L9Lld#1#jY|9WxEg^Cx9h)T~{n$b*!hx*NvUvNQ*x&D*A_* z*PZJbUtO#^qH`F@sd{J-4_Xuo4Y0Y~QJJ)y9BK1;9SOuGsFI13Z9^EKvx0=hPwpgF z{LBp|h)CB>Vp}woYgf@C|B^e7`6VUo?Zb5aZ0c+0KdM6bA9{=kxMx)-(+i3%XS`$@ zbV;^32}9-oNTz(Ke=^6(l^1U(?~{H%W1ji10uo-4te%0neul93HJb+Pmz6uk&Ky0X z(xVn2U=4cVnGsKWN>Zu+3=@QO9@i*eDUU6{6Ts-aamZONfzx`9v`-;F@9kHZ1ELlM zY$COD^8f%39eKVyB1r>fx}BWhx|F7JYn`PgW8=7L zYk%90bD4lr1(n~I!(m|>SRns`YomQ*9*L#9E;S_O;Y&JItuwdKn$;tT1|+Bp)un&r z8Vg=nAMWSol~K4OlEwM5O@0{hg#PaD=QG;SaF-B*Io{9@;rqg}g())CtB_nsy@Zlz zsS%v|i^sv7jK^-vsen2X#=-4+Rma=&EabvpId8t(RsSxg|G1mR)bi-~{vJ=Hrjs)O zP>iigK_!{mk|BC!3sL%_>2O29ohh$SRfyY5Lh%cXMsE zX&HznG;!y&zZ0wddC}_(9!{2cP8?wjK3g% z`G>Y&9NolspAaI4SE}FnI0ylBc?;q3V`61%&xeTqtT$yQL5f(SET-uen*x74M!9!| z2W`205hjTB!w|NtEoTL3%XCwCCwiur#v(`gVJIQ}rmjt&wY?2hBMK8@$$_05U zs*wx8>vk4OzrBT)CM2o(FBq^x_mc1Sw=^(L&>_1l7e(SOx{T>{>T{bbT-kbaTtCMh zOFh>mXUwkN?&k&Byqj%g1xAeF0DfZW^{@q_V+Cpz{phvE?hV)a_`8%`V zEYTNo3SuBbce%;^ui?bAZ%dVHUB}r9OFO-w_0V{oRSf3fkVr=_YQPt9`?NS#Z`i{~(+Fm=*TTw+Q*oU*RMPq9E`@>#AU{>0l~Yi&Uu=o5N7 zNVi=f^;Csb{9D~Pbi8IZ6w4M@FR*q-x>jmyRo;H_<@x00{^57`4Z@gdftW0M4nZ?R z!hmmLyqp6*=C-B52Vet%d2Xh_d{%SudsSdkT|#}J{_56>fuMuh^~32aw;!>ZAI3~t zQ`6iZp9qK91~!NHA&7lMf=|@9@UV$WUuu(|BGhC6P6PV<4y)H_@?DPBX><;6+0ldA zCa|a$98XD-_vCjOMPZ60Jke|7&ui{k8N<~K?ID-Af3%kHd*c;kbLxJs%`#0t9%oz3 zY>u%|h+613NT*HL?py?9^O-{W8kB`g{p(30aRkQh8eo`q37V$s+p6~b#aLgOHIEVK{fg{QS=qtUOd)a9tJ2pw-ktyjz3vnb29iE-#Q zzB>)`kcPfv$0(H(p;uMFw(D|}9x7m~t7x~d#cN1*V!r`Iu)@Hm!uMTTQJEL^Ni^2d z;go;2CIf2U75C|mVW04{0|JF&ibbLgjSS&G8{hqF3(I*MM2}N@avP=Uz zUWz*ZQJTpUd)I5nB}nsg1N~LCEK!uMti^wR$dy2igLm|1#^$pEU^@Fkck6f2-;oJ8 zi>T)_iToJCBoly0_Y*GHro@#`KNlNA3maV1jYfT;_eVX8Gn?vYUdFKEEX{+ZS$WQ7 zz1EsxH+SD1(u@iNk`De5(-BNr+wT+KK-CM}BBOUz@(dcr>*j|J^3j}{xHgRktA z{P-C!lb{Xh^+?2JSKD2iIavEAGktD}YJ#Kf$kJYei>}YcO;W!q9WqCt3dIpu2~uhc zP`Ur@vvoZr%7@w5|3v%AC7DN)q{9An1~PQ`zj3Oz=vCbTEck=hI!-R5|5@dtwl$ii z+KEyk!k)=J9dc8~`}?Q?U*9tkOh%@OPsP&W8yUhknkTq5CB_rG1z8ufy+l}EhsTTj zuw=SVii}4Bx~&38ikuK2GxYYbTZRw*)}=2L6`9N-VSxKp^Kf?R_sgfBsc2Gk;N2xs zS}OEr+p}$48SzOkZ1z;Us}Z7ME7G6KTmG_P^KlizM# z@F--9?3<;Q0V??{?zk4SJGqZ~9#&XVzk;v^HF8T?nUva8z6yF@qLYvd z8$nVJUDyv-Z1R>1B4lQIUp~!zJ@GH{;jErySZw$+?=bgc@8$b7q6@*zf&uUmfGmqS zZEXB>uqsIpP#BN+ElF=?2ixyJqMv{F5e$3?!_8tIUklO9{Dp7YChzvaY_+WSmwTUl z9p<16o*He>$#U!qDhRLs;*jiNfiCL%D|*!DDTKWb*}UuC%Bjk^Qvl^f2kWqs*uCli6rBOB*c<^q(-f zuah0GKRE(XGeXZ7Gid#NVpTb6BCBBdOhVEsq!R&3nf1D7C}AJtl@(+%9^GtOgPaeK zt#$WJGF4V*UsiMP_70Mb*)xUEKry6yFGF4sn;vTs37y})3SD-YYQ9FTEkPHcr+$eK z0W}d@82ZMyzgSHEONvTB;LLkfamWPgNmS)h>rh9z0pCrnd4hC2Y@b-S`JQIy^4>`J zQA>OBiF~=wQ#WwQ7A&mGpBhyfoS`jjrI0T>NTbcOWBG_VZf}AIW%0;e6&S9 zhT?kGA#fOqeYjcYoFk2PIHxmeyjP>-I#gFa=+7*Gm{{!tjnxdJMI~xsm#JVp)0mFL z=;~BY%rlR<#q#F4;Y`PVIPiNs#!uE=;z)T-5#vUuSfeR8-AJ3;%IN4Q8kSr`{44(d z;=A<-FYd`j1n7MVg5ddEU;SqBW*a_CRojA1XIc5Hoxg%f{!71eh8WY%)g;c%`mhPCcK=!9=|n2roX&xzqrzG@^Ean5uQoV9rH%n zsRTD@deA~@s7?puK!6?f5+XIA&{7(CWTCd-D;nTQC-|&TVPFUVI zZVkFwuw{>O^9VOn2ksuolIsW~g=bkm+xxv`hB}Qgvv6qej7xaL;mwKO=3NPTOPehO zT7K=6rm$g%2mQ|WXUo6*SwOHEG}_eS)#}#RLhIWl^wkqCtiHP&1<%ZyxL9s2|Bo-V zez_!wPfJ(XHbEtAgJQX?n&bRgpeHaT>xD>#wRocSmHqiUZqI3fk(~}j-lZI@>GIOz z;p&A;fP;O8X0;btQu_Stapp1h3A3d0t9&ln#bq$RZHeS9_j7w<;Q4bZ;cGsWj@9eZ zn49M>$O`!J2#K0T0iyBW&sDOu2RJ6JgF@i4lyWW}G43y}JU(%xyCfH@Wn`319dtS{ zkz^Wr?B%7>VGJ|fC15RZZ^Rw4MMx&Dl7M!PL_+LY7wtpo>(bq(&3G4IbZNE1u5j?lL% z-6~Dy#C-y9dK_cn9GzSq?twjWagEMvNmeI%#5=pOm%^q$5Go~vg4`%q@~3dzs9S+H zBs5?99@Q6p0xfEe=f??X$KPXVHFA3yL(xKZ%eAX}_)VMi4`gDCM&y`|qc~g?p`~B& zTIjx6Zis#xhcZ&U9g}~@2Zv1dnnt5nv^Bktb+3MPvr^P~H*tG@sf=ixQhy_dl=193 zW+Mk^K=Bl1t}vrA&A`oU+c#8(m%3i^yxQs$4C>zBv2HSwp*bG{@3YxDF4XFL%D~OA z_8w8#S^|4{dmt0kSEVC$S_(3c<-KJ6FH7!fy6|nJp5Z}lcy%pBbKFmLcOtFyMAx@) z3gxq-0zWc=ZRSn3fbB8*!JmBCZ9_t!B+I%RUeC1z@(~SDxAIv5VuJM?VT469=DK=D zG{dQ2Nw-_3?ZiaE2@l^HYa+1#G@Be6Pkx+J$UE~O&)o&meCiMPM~I%s++qz79Y9#) zG0KDIF`#R!uB#N6mCYx?G}aV zkC&%`j(Q=jiv-E;o(VU+*S6LP96G?Q{KE9J(r~;EZJf0{|%UkO&LKplXY7jHXY*$a<<} z^*k;n4K%3$_{E|;a_!_U^v+bsF7{o?dCVGvpYq(j1E-#mcl_IGa$ zU2=GWg{mgpXOW9!rdZ=peMl~HN9-)RYIP$QEX~m@#%!2tIwM?uluV}zH($Fnvhw16 zdH6-bAGkrPyJ=7azz2M94T{TvAeFAq1=*^1QFj`8AQ3>vl5_r`(g!Pr#X2s;Lo#fy zx9ye$63=0=+C#I#_&ic79~FanPG)#&N2JDATph7Z1hEj?RgwK!@A+w2@ ztfBUW*P80RYfb<~<&%SAVmAHV!R@A0IHPDLY5O|8qK3=Y;q6C$*#6@o=~tNi^3Wg7H13o`%gjyVQp;cLHb8yT{ezYe~%D>T!e60`ZDOiqVWD^Wn+ z%>BHL98GQ*(FJ6y;n9)kATQKQ%`4>)JtG=_bt>=zo#oOpK(RK2{AIQDO6Y7@Poz7c zxKrnEEJoj5MQ!)q3#crEN=S(C>4;6YzE5)hnVNuGXWZtpd#a?>#H7$GPcbx@GHSdLfO$0KchVYI+Yu z4;Pw=;MF3nD2fV_v|9nY$;LF!x@D5HxN5**n;$a@Qc^fh`@(pbTM+23DGJ4j%IeeK ztfiBvfKsl{9i_c!6ZA*zh;0#0h*x#xw)d$gt zYy&x)Gsh?JaSuacvA$c3%5~dfCuUKi0a{osKPq5LJHd4L0R(e(^?`@PM!jV!#({bi zY!b5sSEJs?=nk)*bGC+$k!9N)yh1WEu-^2YG7sT%r5hvSmEvstk!J0m-|4mR7iv-P zUR*VE>Cwa<8gFS)zF7!FA(FnFbUeC=Nd=nzcm7Q$F*+UZhoHSYM_tak%`E;ex8IG%G|~|0*th0 zR?^soyNzpDz<*Q^4a2^9Dgea&go)$Cc1jtz(S!614WqlVKUyTBe{&1cKG-sbaAjbM zBRA}(K3F&T_}flE4=CP3(V5M@+{DbTkdg0eiD&{Dh z*Ku)`h7zJ#h@BNKKwLG0lh6qb_!1WRh7QQkyB)%>8%7*ToqS_32a|%k%n{Wp5(ifd z&?Bgq3D&8|sZWX-BmU9xf`4zGSPcL~@d6uNb@IVaGZDsjv&$n#m9AvJOjC=yodl9j z#i}v3M^m;qw!21-Fu}PbL8cFfAJW2?idNz*%S2ME@B~(ph0vI`&`F_vM^bu;u>!)| zg}i+{{~bWJ3fnT{=?Isq#!VkwliovcW{{XyMx^T z9)LnnnbEmxNo&a`k1XIxb#=9Rl_7s6z7ZgzA9Z0B{8fIP(C=+#>=gS-O|VrD>JQA- z0g)BNbVJXIUca}TBXPVwp zmC1bi8FNYt>@XfmqOlr53x=o0@eRinu=lQi>?OYGt2=Kr$JFK#uzGCUJD|F&B41ODr$iN^faZ0mnbJssnMcGTv1EITZp$}@*O z^0ji_;_0&gSu5)waVH`h++@Ba*aQa^f{=T26um; zkUIdKX$?104`@7KVM$8-L;zU8Q`%P7bSe6<5HaXD;XW8ob2 z_XnbU&SN@U-*atzhcKr-{fe%#RS`f@L6MH>z7w5sp<`+2GJi-UqZpi&d>Dh;bgFo5 zZN{P;ru%+!l@=`UFa6t@nF8buhj`-k98V7*{7k069k8jM(Q_PH+)jyxS<_b$jb@V$ z9gukuO^xUFsXGcdbo|{d;U+~@5dJ?Lnt zbhU$=09o{?z7OL=Q@+g9Rx1}mf|SVoe}3N38gPLlI7H0=)Zo-dU^_XJd2A z&8AQ9&ETTZSHCK4Q@x`F$U&C@1VGGZr`~F-r{h+LG4g^_4&lrTN{Q}$)V&aeZZ_|* zM)jq9!NQu~Vc;}?pjQn)wsw*>^)jO_Ac9S_yhJF^x0zt7?PKimw6_14Efi3olMhxHbk`(MdcE6L!h%9H;7vbP)1Fo#*dyCp$_|w zpb~x9c1;r5C5J14Br4`G)(3tPGnvSIAgf*BGbF_FJQ+kjMdec4xdigD$ z@~wFAi$VtjtCkITUFYq#+OKi#$GOro>b-QEC?%v^&ZTvQc2>x6q-Cwkp;6lC z^0PvrdH8Tqe?-+0DF&q!P$lnNH=Ta6^C?$DNO}?FwPWMW)Ccc=4AdRzFY8w~T0&Vf z6+SF9w)Tq}}NZ&(50c~8T>^Lrs)S(12% z#CSj!73iF~*Pb%$Dor7b^Xy^4aKzwgRaF1{K$}3JS*)L&`P8%Z>zZWFf9`|kzic92 zZoNuUM#c>jj7MtPs=gB~;>0`vJk&@reoUL5rdLIxzO8*9<#qT{6`?EVSpjmI(N{@9 zPC@!4B6`i(;bfyP4Ip;v`5Ht@42ZQJqzzd>PM$7N%I#Na)Ib|42FhUf4ZDpA$8GYK z5UG*wATaiVeXgozkJi9J3M)pQG)z@h^Kmu)8=&O`rk;oEU)}<`K8=sQY%+aYiDDni zKmOk@nq5=;>cm`ls#&gSL=UJqOc&Z6EOw|A@&ou_s&41?Nye_ipL&AnulEv_Yqw>_ zmZI{P0+vvoNcc%iP02)NhM_Qsb;$6uANXCED!m2gs;Jiffq>UCXdgLh${l^H1w$Y<+oK@PMn%?<0C#p_CxqK(9 zHnuwJo?1p({pApPMuI&Npw@O6ASJnj1=A} z!w5QF2O4saIAe4=FY4!cccxPHxTc(qK@`rHERvzqr13+(a>TEIC+aQQ3x}|De`aP_ zN}QlaJdnnK4S*5V!K#t;wa_cMp}Kk|g!pY#&A)sbiqIZO_<%@%%BrnjY|!5@%bfq% z`A#m949nc7kqOka5yMA^0}bZJ)qj4Q;JW=*8%=QQH-VUZl^(5u9;oZl%e?MiaLMjj z5d^KY_vn}J-2e!FGv?Fzk%1Xp#QlS$@z5`B*8@lPwI{F=B`lOax9c>sW>TB~;w-8u zJxJ{Qbv{;6v(w{UcWz{rolZ)YbBHV4xs%(Ld%SU%b44!J{v-Y-`9NoDY!C&@CTysp zuW}kaz`HY1GwoLnuu^(LY_G;j*#KTIY(N#J2qR6v_VhNXeF*BT(E6Rfu;rSY$K+)N z7Z10R8-yKk7>-J2&WM=8eQQ$Yw)Y#3fQLOc)k=Py?LDSqw3?7=KO_% z2ml%$*D<92-zz6!6NFl`<_szhKIyqB@TXJC&wa;s!F^}xe*o-=A*jQ$NoGLeVWXNp z`okIbwwd_2eG`d1KZq27xy&pVb`h~rs(WAqe|~~^pH~wN!K(vwXsMCLy{5#F;Y1Y_ z>+Z1}hKoA%^OkB`+JYW6y8Mf=0s5gFGdiV*UOSHR$w*%TKR8OKf=+~adDBR$sXuv2 z$k4dO=VF3hRJj!>8$4PJ>BNS*Pafg(i`deycCof?2gGN`0toa$oiPxUX7~?p6ozdylh95B#5nDj%AwI zox=n<-PlGCQW<_Oo=0Ec3HA4j3`tKi)UTCqz3AK!K4SzCHPNy7XY=bM{pHo7;f;** z+&P;R$~nZ`vC-({j(?9VA#3;k)}kU_ccGB@d6H)CHkj`RZg)&U z&DA89X2gNtTewI|lcKzRU(Yn>IBL7`dtKaVt@lq5T6DNS>Z3?LI`!1UnlVeO*pm8% zw5Ws?u+FNr>W`o^rSD9-*@KX_W~Ap9y0C4W%gr6HFcynNp1|*{&!!?q-;Bx=9f68^ z*k7!XF#mQOK}cjP+$c8^KyW&=+HqCY=!G|$H#j^$?xGLz913Te%D!bRz+}hM`@1Tq zh-#0F@$?%&2&E+&k^pP`MV+`2dO zk(OKdFDyBLea?K9W#+Zf`G*OWCN{^WQtwt+c3RwyiBgmW$9Z{%*`GS1?$H)320-|d zK)D_ruAiu)0F^MCU+3ktzm0htn-;nYj#U}>^AqZO8i^v=5VzlzUvyt!Ip`f`aKE~0 zA4>qu1dH+m`IorVrt)i-syPuZ6<0{yYcG4^ucy|22i@6a)BPDFRMbaLP5uB zyg6LR`;; zLWof{uudh;p-dhKpU2Sux8OPe<_Hx$gA=*|hwtX;PN+s$xJ^Q(&Y@AWYB2mni6M=c zICOf(yxLeZ)3Y<9=1x5N3deo-Y3OZ`*}; z7YYs{u;JBo1I~PVrjA?4bb=VB=SnO2sHW8Zr>*%DdTx4`A+%K@IJ%%cabLJ#z~N6t z6yVD0u9}8k!$JOjy9)y!zmon6Uw0rvW^ntV1xfa8@LH{T-jb zAxX1QR2Xlb4bx>JaA5+ga>~xUcmm1D^n~h7-a;K&%K7cv<;N40J%QcJ{8Ao+y8iK@l1q^_=^0t+bRy^c@oAibO5iILd zrd{^C?3sKg7OA8KE+oK@Z0@gr8#e)^rB$$m`GTA-8I>vTD1a7fz6Z@MYA5HxHW?*s znfP_|@sGoXmWZ)Ii(fM4=zwWxh@)+$d;dneG^Ui1Ki2bgLhu0LOD@rmZ{K{#qbX@o z@UE(=rM=fH|2!1`eu@r!v_+hHe+QmV0B`988Zjxzdvo)xHr6?|a7L_824%Vg| z%1cdY->h`FgOlY3h?Q`@Sd}s)RAisj>hryM2iu!Xzd@N~$&x7uRqo*7Z0)d&waHxX za>MgZ_6J$@j}M;j z|0P)9K8bMZ2ma{{8K$6X-eh_xf#k+!4G-5E)(abp$SiRVnjpUUwDI{vp6v&%3*dQ=40K)v;~Y-K1d0?tt<>XiklcAiP~4Lp6H4*2WhgKsy%ChEU$v52WW;@b^wo^e zTlSmhWsXhr^W%W%Z04t@_a<`bqY*KHm7HgO9O-sRe;6q4=9z&%T&7du4TsLwxAEY9 z4-gldd#~adr|H)7E-G^`fMtd2vs7!h+i>#UsQZ(e!6)8bNg|jdZz2f*wM=tjInz9V zor6T1cL-u!(e=MQI#!|Y$|(Cv%_7lF7?$vHk38zN5H$+_D_~!SBjBcgHQCBL#Qt7x z2||Ry`&V+1n;XZs0GS)^1EVHWV6>3G=7QzLuzdLsLyWR&TiVLESF41-bAGs3Gb-)8 z*_M>Dg66p299!BiDfqhxk1h$zJ;Gn`9SARfl04D!rW(TiN~4Lon5&;d2sq4|*j26W zE8pU&(p+YPNSJ_wkAYRr2SNb(J{#4vOBuqT23@n%U+jUl^^l40MLM~X?;Nh5+z|^y zIDWfwHB{XjAN>JfxH{p(x+tbS8U34ysCqQbX&Ml0uIO3meQ5>HW67(I5HEVL^d6?U~ zNz6jQy&7b|W?Nj%ILXE*qskg7eT_n~f`dmx;c+W;Pj-^aYed9&anXu_J|Rxjt_*is zW>*m7_@>`$awA4D-#QPb%kcW|Er07#HMuoGI3r3w(tCOP*QzU;nQ}OeE$`TM4`xTe zKaqq-B&!8U>yfr6g7*X#zf|i%|5DyqyjVT~uuG#uy}+#u@WF)aZWG zR>O$|RGDyVF6tkwZ7ktGe$WW9=ABKY|L0xLAZZ7`+WcK4V@mn{X@*wSk{|CajmB`)Bo))YAwb;^NaBl+$U(JHS=n}%$1aWgdyB*1VyRkvvoAWM*Q1QlC~ zxSkfDOEtko46b{cH_<_lC~K`K#jrT(RUv+h>7LP!Mt{eb3(@2Ddzz@j1j<>8*{F}d zyjPHu{e;OQ-JZWc8gESrw_T15Ez*R4_RWS@(i40(7_zb^0r)Zi}fR+gRzyEaT8pB$m1t}8Ls ziFvWImZ@}5D)0L2%cJ-KLp2R69^UW#Oa{day;}?5hJUxSyRE>VA8p1~g>reZu}%Nc z?Vq9=Ki-J~kK!lQrs@XG{Tjojeo5B98(8a2*HGO3rnLTx&%7T)!Wh;KyTOiaG-|BIwryLDlcup6+eVYdwr!mKe%E!*`3-BXIUkI1kGuZI=%+vTy%n}u zspY9zVfxB|+WcbMlDO17B54GZO#FKi%_Iu|NvDEC*Lv;GH|K&;9h(`?t$G09$2T;< zL%KZTtD>`bJzKBzd%#?Ds+LkWI%q{Xm1}53VAdk^U3B#9frGrAd!`#I4~=~wfa9e- zp$>S}^KIEet8VQjcIFg3&alpRRh$4kZuvVboj0-00;S7;9Pr5Y3_)OyX*g2CvpQbx zwAt5`6f6!N0#LKLz*8Kz+=A+F+cq>=W=WZweLkep!Eh*18KyNmw$13l=j8A)0J*Uw z`~MXjCipBjoH$m52C@;AvjHfFJPDXJ-}ml}6AThyaq3!vRJ8`gi-E9C8G;mY*noWN z6i^4@&K?#ib*G~T%`+!DKGnTdQ##ZQRDR_)sUW-;`_NlgoR9++Q?1 z%|jjdy_F?Y6TK8ukwLt69hNt58*+oTtK zCoq#(k$#q^9+L~T7`cn=Z(_7+`Eg>A{^c;yvFEbK5f)cvtkF&Pw~d`mvIspLQhX2+ zv|j2p0*s}uc9u{Q0GfAK-{tZ*qIW|p-LwAq6s_qt?&G#G zOvaf8sM;uc?2u;+>ThGv9HQyRe2=FDkN!3T(7a(+#;ncIGX(?I2{$6d?WB!KGhp_u zrMhDhd_clNvna)XdS6oNB*r1G6mMJ<#(&I=%GiTJ*cZODrYb(bDBp7pY^uy>CPJDE zK0?Gdz@Mzm`VEIzRc8XIK^$_7avg%1+sCiVCLR&f*j7&`v0IC4 zKuNQ(T;lSdk?4nGP`$~lyD(b4 z-YmAFlWi7|R4(;}gnX0Fvi$hz+}>}^E1vevb()#G1ms$g!X=|oUm5j}+!jh2Lv*9v z+_=ir_a)!dMn9j~Bdb!8gv_-n;oMsuPkm@=!YH1bxbj4w!9~J=xqt7=cZ-oBLMA~% z9croAnuHpLe`Gphxu*x(;|k3%W|iA3SVX}Mb?U986n9*61Hy|j;w_S+3)w3kiTZRY z8f5F<(yqUNvfW;ezkDjjOc-3&0VtSVBafE#!vLm(KzZn9FyPVdtVQSS=I3 zkDK+GwQMk2lczoMH4mE9^sL{Nv~^M0E9TbvGiNL0u@Kz-fs8rm1#XD_v5TeHlR4i8 zWlCom1A9$5#{4qf!EIB_pKaLXgVdBa)zrlQ|AAkfS|-1f>L_uDGzU5c?iId+Bh~ON zGVXj@h$bnPO1@*~f-?~lANRwy&Bo?OZTaqI!~~;XB*^i5>Juh_nYaTo%v}Ws0>n}J zcJ~&~We>n-`SF?qdmBzgD)u^BqLQ+E%O47LghI`FC`4*q<9xk{{5kVw!BVD99NzpT zb*&44_8$wW?A7(kUEU*C>s^Nr1m%jpwNBZLDm@~_KZOYHI+d+L$-vmt+2`HiblE9u z9$Bw`E1AtUbuX~{k;#Rb3G2|v4; zmP7%WZjro1DJ6apfxy1;1kP@;9uh?~055m0G*~iq6ioR;vA(~wx=fQ2S}_DnpzJrA z(&v}@*l7L83(BB>)(hMgw69`&R|fE<==WZ#oXuyC&a$O2c;vV4iXnh-!JcH`+i)3y zhOKon(B?|G9+Q>zUpkQr)x2cLh2w7f#a9Dex(3XpgzFg%yaYLJ@o%<6E_3>+PS@KS zT?VV?u3(K@b!hWH3=!&@Ahvb|bHa@+FIgFTN&sb!5gOqQG*wrPEr9Ot3xEVW;wcE@ zb;STX)SGJo!W6cn5*v=ouSQ6UGR%qpEnsX+wuT$Sp%Wm$9)v5R0ulJX(6fI*P9P*Hqs!TRHqp1c1fiSXB!`B&T#pDQ~$F5j~_16^;6b17U}oP$iQ&@4CuB z(az!hVAJ6BmnkO)f#=ULCNf;H@*tl{k+#k1l(4UI-;a@fSIro<UGp8^huY~xOJ;1WW4hZ_IVIE^~4HHwsW;b+F5Ol zCZ5^_$9wN21_Vvn0u0?UUIxlu;@_^=bjT$*1rxRfz)S#mG`v`+*tW08UBkIG*8g0f zMJh39xDAMQ16LGs%suaZfqdz0rDFFwe18{n*`_rP-6t)s%(Q2@q_&-3uy-Wbu0z+C zS_d@ZASFsUby4Z+%okS+sH{TJa}2L!2Z!cOcVy$ClqY9(&!R% z24w<;M95mN-c@&LXe+v`t7zVR=`-+yrXT1JQ7y;PqD-UzZG`P>ahrTs+18iTUs71S zGZZ17jQ~oqS?w?gY|Kh6?i?W&8xrytZ-fV%MdO#F`r6{4T$4Z3$6uZIF%UJXDvOj- zkwpFKq5vt@H5p%1)I{B=Q|@`#xc@#CJ_}?5;ebpY9-38bSx~SY-ENR~@y5-hjQ`Nfv_@N|eo))9x*NaRO z%aOZw?%3<-Cr`A4zmKjZws?xv}1Dr(C}a#?q>E(zyPZ6#FQ9 zrg6HPWlemu)eXZuIK&&y^P?>n3bii(3f!}lgZ}ze3U9`5`T5CjzDLn zw6ryd-7pVbDD|1xY|fjxXJv_Y^(S+H)Jq@CY?m1?9Eqr1BXZV6xaq0V z(GTCZu&BVakIT&d`Li5Z5)0}foNdEwsjYYZsezG;$ZQ=BFvML+|bOih>56gnVbo^E=n3nvh_<( zFcSC%C=*#c*cl1!Ipw4@DcnHMhupdz%Lq<4@LR6T%dWQN-FtX|pi_4gp;#3Qg9=_! zYSraDF}_Z~3>!uVdzud3E_gJv(DN5`@Ixq~keJ34QjlgF`gq@7FRMLn3S~EM9!FQs z5%|=1H02`+E?UBdU767n25kYh2w5O+<%&7Ed*Ha#JqHO zb|~h}!FV%Hli-Dbope-;hZ*3J$Vr=RvY>O%9f_A3=Z}Z5{UEMuxz%P>_HUg9V_FQZ zTL@w7&Ss8}%APH5IX=qY44YHaXPLh0tdw-pd>{J4teNCdpjWl8($y`|Zo4_WOh5QK zfs-xokH}7FihQJpa@{F1Ji7LqHg!}#0U+wfEj7AsN-t??4q+%ltzI47B`WLNx}`1CK$h6{!9 z4Ji9-1oi4W;X$Ml$(uw}w9yXX-(uI?>?WfPj-wZLb zSeaQbrJBdbCn-^HNO=0%%s9mSeWnq8%fxRn!qy}x0N6OL9Qcn6a&`p__3Nl4wuf*V zxE@FVyE!P&Njoc+kZH?C+>=?&YHUY2>*Wt*7~YKJ4=e!kv(Z>NKrg4A0aF}etYWOm z`#sV`0X~a}h4kn%&tD9G#mjV4W>mVumOyELnP5rwMTc~%c7-C9 z7#jyaKfe|Og{OUGjXizXzzpke?3t4nsF=mZJ@Cpo)BTf$tUTat&!cNcJ*}QWrL37h z*YLn4-~C@T1&0LsV2^We_S_=xzOMgNKT?q-=A4P%>@=LrqB!gPU8Z;~iAnEp=EaBG zc=@vXO%H-A2ecp+1eoJ>xgsb;&>>ap#xG?F8N9j3v^^zRoEyW+V>3JM2jg>WmJ#<2 z+wd1HAY5i>SxN*7pw~0x6WGeD8+-!GAZ%F59gK*1->qJvk7MPM`+ShM3K)PLre@TK6^ zbU$M#QH&HQ<)gxkLA2#I<7y3^raaR`j7_IInRoWD-esQX7T1WJPh z^scd*#{mzKR677-LvNcFirmA<3H@Ep@<4-_*lWmyqd?K{TW5;147)?J8593UYBLNzvW?Vz@j#y~P>g2nO|r>wc|+C@LM>AR z9D1W{+KyC@P{ew1kkt%&j4Ss2=q06SIu@ zafwJ0P3X%UT)P8LTNMD_gi+}HIaXHPUQ{YG{u0T~)6KGY)^|CfSwGf46Z&@bCIMCG zf@x=n`OpB-$OYd+c`jsEg5KOVtgw0(dV+vpX9Fo0VGMULSoX`!< z8xh9ib;v)>?jxhjhRm;*Y=$H~q%J^4r+W?ZT$qOvCAMN;8|Yt{|MN1k;QhbApBWFKI!*a$tCnR=vYmmULf z?(sGiak!)Fu7?3ZxEl%prX5~fk4oKPFB>Mh`lI#&R7!Nvx#vc93S}4CoCO`Ex(cYA zQyQK*`~e}YU6Ko}fGt1#n)RV=HS^Ef>NJc64j%(Yodaiet^OplYTYbV{s-pvM>yQa81p2ljwwyTt zy~cM}ND_MxUfD-PmeMbt<9};CzW6na7hT-#UuAhomwu1!VewH~@(2Nx;~GZ)-ocW< z?}rq7zm>taqN8kPLPHbGG+;Q9#J%`H6Qj+c8SyjNMnOgHcc%M1o4%Ale*)Bwg#gj1!>D zes2KYw{Jm0eAPy5&aN`EpFlP#A&hZ^5Ltq8j%UNhCsQqS>nTTXJ#LJ2`dqc%gT|uX zdheyjHjKP=_&zchqiTl`i)~TvQ=@ARgzGk|f#zGocP_sN^LqNIXV)l1ZHu~vXdFZV zaT84cs!i*~S9q#-pNMkg9;R_>#gilgzx-g}e#!+q%J2+rL}YojQ?%mm{~t6)nF55# z$cug2-1jU51pTFb4o?2zndyU*e|OdYCA=Z4%S_+rTB7yy<8{)j+%CXfZZkQWxlLLT zj7{v?PkNUD_i!E|za9^V6>PcoIIMXo0#JIwQ(a5Cp?Su&)G0~zlZN6-U_*#Z%BB2{ zXpPwH3LW*ca;10{I^P^^&xAZAP!IbqT$M1u2)F=8p;og*0BZAczIJRnwoRIn=3m+M zX0K6I0K187)3)afr9&${*>;a;TB%JqW55R^(lpdBeZYv(NrGs-8~^kb9)k(2Sw*W^*112GsYDv~60yMI!r(%aUVI@s=p9z!dJP_r-an%hK(@hpLX^ecb*| z5c*3E%eoZ+Vtm(BiAlpQ>;bV30EIG4Kwr>ap*R|!g_p(NICEt(V!ZY~M1TAJi4eCZ zT$K@kzAwf5!h1Qg58;%RYSI7t1A$)FMGtv}H}QRN^pWfPfT?xH^*G>M_sn|ShDX-=k0u^6*L&zd@R4adCu$dpr!B7A;Hb%7;vWLui zu&y*EiV=R-LO7gmCf|PaIXq_Od70k5yLH7u#-$$lGn5Uo3&E9nByY|2Atjvo2Jb_q&{Oi6P=gnTboV*6EQo$PH_h+7UzA9$-N9?0dj3Xfp$ zcng2&M?=8c+mQnbUCxm}X41P<8dS>C`{eleL>qFAxS-{pF`3*hEk-O&bbv`LBjbs_ z6m2i@6{p2Dc9E<`O?|tmE$zbCnO!>FbF9-P(HB#Ke z!H}C6+@BKJ6a_5$>#UeBAb6Ub7*YG=PR9Nw?WU%ZFXGoZ_w_lc*f0*-MIkYDMNr)O zz4M&5xSpeEMVR?jYJLjAqo|3o5V)+&vUPsE4PJjdZ=gy2z5H_pYN*t%G`8XrN=V7( z3vLG~@KA^1W$}<{{?H3UXPU&^u);lzoNhc%c1~OuGoIeiU}qq~0Va};fpJ&DC?smk z!hew>vYX2wP~*5VISz)t;Z4AUXt!fDW2YxQ-K@VySU4!{b?tNc&sKqJyFAlXo(pI& zqmQkjWE@J#^JhK-DYYJCh!$uEQQ3otJ~}Aa?|DBx+YoXADH00An~sKB|M)Hq7~%S- zNAVwOK2wqsoH6{^y>+umaA024Ij*Dk|&Q-`B?pcI5?Q~E)U)Qi2iH2|fDgi0277SGN@e67V$C#dDy z8xo<#@0bG(H3_(Q0&bg>iygAL6b?|)5z$a&PNB;CXmE5)Fz)1=1R^NIdJ4mi6`;{p zEL@@ZHI6~WS&nj;t!jD0Zsc#7JRaq+JR#~N>$~4!Rv8YSMV2jUCyi|U?&dE%TtW{$ zuZXqel+Wwj;4r)(-h8uQH;m2VO)@#ro_KwH$i_3FnlgzlE;x7uP4Tn(=fixX>oHOL||{c@uJ!1 zH8knSvk>@fn7Tg+!B`p^u=Y&2Hx=#1> z{qb_Dke^O!><^hhVAs-{BCSFl8gxuwg>96h)dC2SM~RKglme4#L5d4stD)7cwr+tl zSJoXU{MkfD!~S4NP~YgE3iX_ja*m}HS-8qIT)JI{`KN175zqsV)=+ zhCc4_&lO+UjWf3VxFi$9rn~2Y;T2x?zl6NNh;Is5hx7o?hiLpC6SQfSLFl^^TOH_$ z#AQ}WWtSYqELp@>9aGa{K-3)h9P`4PDfv7WK%Mx_{fVB~#L)Hd@F1|Lm3ZpKpO|Av zeCqsR+gdp)B-x4s_|V`$Z0~K>ns`wnFB|NBLfijU1&fA=!%VFb1B(v-bUpv32eswr zqIqDse_}x(K~OK*a!G-_3thcdQ1qz1z<{H~GMh6P!awx7fG|`CN1MC_!?S{(TRIS>=!y|!l z3wyV>ZOOy}Iz2D@1eGChMl^C21TBEtWxr^5H05~*O`4LsULNx7B}fg5(}$ar3p(@$ z<31D&+{J_^QBLt!N&Y4 z+QR# z^Xa=zNkBjnOa2>IouiSq*zy4yW>cdWag1=5bP8=K_nOxh^H(TM>Fad=iN_nW`#DbRzQL9*Wz9Xzs={E+)?I81R#Y%j&2Rc z)+Vn+Nm5y`C`6e9XO2!O%__+e9McNXHUQe2?}xI$6rJdftqDlN2*0fa>@hqE7GQ*t zp5wtND!0VKOpOMaXaM2EXP%z<9p{i+5PQ_KbB=mj04xBa&%r9h1FY9&IrZ>+k2EWt zG+JXLrr1rj)kz+<!|)en`~5 zhF{p+#W0X4L~DMQ^1abh{z4C7x|DVIQ>6m#cePzZ!^4Rd2ZS3RxRYI*E>?9UNg+S+ zNIn={n7_F+-NBnW2eAj~5;>k_$5xB~1>mD8&Q}wyGO1!ik?I*5Xf^jwqOE@AC2f>#u;Mv@#&>L9oD@}lW3zbySa*UFg`7BQN(>g;Ez*mvH~lgZ?W(@ zw=5I5M)^C#(^YOq*0g7E9uSQ)F!aB6pOWcLrP5=0X#T~2=LCod#D9eD#03yNgctk~ zX%W^x_POlvsI+CcQ8<%QrJnv)g)?_4NiMz&VWR*u6EUF2ocI!6D&Av$##H=qoCpDW zV$$=v{F;^nIMGl7qQr6KWAGCV$M@wv8u(XAz^P{1D*9rs+ADkkvCql~tKLgT68cg< zp)P|DP_MTN`6K6?SZExf2N;ugbh{zLxE*1#1lel+C1R2oHPjl z#=|cq-?8@tp6>;nb6D;>oil^up2vXCZvY3K2UK1G-ho)kbm}}f|EK|-) zlHw45k-SRry)s~0$af$PZz~(75S+iIJ%=I^@z4b5Sq~xSHnUmxOu$Q)GC!qMscdMm z*!aTO$~1B#jY|?3Z{VcaIwS5GzGNPMjODu=EOositooi$*R-bUGJF?v>&oVS@I8!k zZIdDVzSbW7I@SuS*&ny@?auoPD9x7HU5Rnce2Nu?9>TPS!w8!=3Rxwgt}srIG)l$M zC>V%3m26ps`rg}X&P_tbhnLz>fZ-|TmAFqI62YNZ@O5ByZOdUyix}~r)((k+n+IDJHb8`p|TU+B6>c~hE8h2+L){Zgd=v_FzT3=So|j^rfP$y3Q+x*cd}lwPz!H(G#1X^lbJkP=8~@OCjPK@M zk9TPS83k?|P8`wcJWqX&i1+Ju$+jL2-O}*o&rQMEss07r_*?(yQi(ZUg9r}~3Vt|% zWclY_S^TsmAZb)3hyohv^_Dr)BI#rc_G%Tyo19(0eMax?%tF}tFxNdV8|>Kgi)M3_ zF%5|12w4m7OM)f^Gec9_pLU|Fe%+nk{`~Y=GrxVu>AHe`%?pYFLt%~9%;N7@_yN)k zQm7U1iY&8VCM@g&C?a{w1))ThzjNCx8Dg@qONRc~D>6R_w(J8(mJuCP+Z+UC#x&0% zQcUdN&Tu1LU;0L5W{U#D$Go@yjetZqT2H5XqPbKtuL2*)d8eCU;x-Nr1`B&)#U(=i#sgV zpxdb1c#|O^X@lrzeoWr8;=i3%H-N}?wSQWPY^UE&7*xKjhV!TWet%Fkt`17$|F&F= zPwbj_vMFxiP>+WQW{G?NeuzsKtyWG0;Bkk6UnP4E$4n%8WkoHO-Z73WEyc^z;$}J( zr>u_^C8Y2CYF+4sJ6v+ilwO+1rNq4>l7LVVDfif0K@TBYt7>DFY+eyCr15Y)%Dkw` zuo>hE%=kG9b2Wf9)Tz&O7kGWb^FJ6q2X7twEQrVhY|H>LqyUM#m>6SABfpCC5F;rB zfRRA;N54SP25@8c#i5#G!;~bL-n|jQ=0h@d2ki%iwE^Pa!qNt{9xQap?VM+bng%Uok*G;CbtnGCF}sy>!%3|A(M08y+o-saF7MwpYwR3 zm-2RS@Wq+;A_aNUuSFopm{8lJb*8Fge*8-!D=u_uKJ7JMjbmOvx9T{$TQMo>FaLf{ z@p}j1R`@*UDL$i%v3eWUd5Dawg3&D$$GGRj{_DF$8gs!&ejpSEmr^|cb_j-EjeaNk zccx$aEA)zZ_9oHX8W}Au7W!&F^Cw)(3wj2u@H z#V&5PQ}W^X3_D%Lp}MDD_WRemY#?fYRpBT?gv%PAa|z!k@0GH$Lzo?pM)P6Pnp0;ZjB5V2B6tn3_o5gXRyU`qBE zdUlQ|Y+wz_@eZyqJhz^Z)S-ZE{3@sj)b(dtB@a@N<}ITwPoyxzmDeOZ8rfzDOs8CJE51ngZF!u6HZ-Q5Dh4b$LRjTjvM${XTeNJwNhsx*&t zq~yB`i_T!mHQdR@VqAPAmDH2*?mNu^(chlU6o5o)I z`q(zFRsuHdevpK@+B%j%kl&PjZvsV7Z-2*mzh|;^TzxQY4Gd+nGmR&7_mjzswBS=h z&2aL0GZ279ki`zNIa12r18{hEE8{*Wg*&r~B_?r_z3=KzCa;`!T5g`^wA$7N} z7rB5D$-Y&)i@9s)&5ym%zDdW#gBtB=|7f{8o2AJqrk#p6z|pH0jY|=lEIXSD+N&cJIkI z;Ft5pZ7i5<6OhsaNRX8X#+7&(_LRmv{7QmrBKo3rN_=KP96$)KNFsyQ_3&5{rCL!P ztIS9mVo9(mMI_d zb^X2jym@sEoLhMbj+4fJ1Peq;y>DSVJ57Njx$YasUC)#DD}L8F<`Wrce~?p9t}s0o zDTo|PbzlLriTh!3fb0oKQ_~*l{V|)b07}a)T0QR{AWMt@xI=F+jjp$}_?;`Rd-@X@ z5P8U3VlrHJlIDwINW%~67u{FvKnig%Xj<>BeV4*C+B!+*(jNr+7ThST$ zn&@~+PKQL0fTG#DrZ3O7n`IvZ<^{S8EG&Mxr0TnRb4`_SqOU0ZTf_d>q!xX;x!juk z68XA0*%kF1z`7oc_9u1{Dw=B7tuaMQ?*DQYAoq$RZj@k)Vx}Jdofm(oA zAfXrW;TfLjh88NaIwN&g2tBqo_#j|tOn_VH2%v})00B?1UD!e7_aHldvy6M1`n%V7 zb(-$O5?4tPiXD+a&dj?KmGoZ`LQbBmFXISE^SsBsNT6j0|#2sy&_n2yjc~Ti%Yk6C!YqJQR?n4YtdB|1d>Ml zPzKrS>Is|OzvdIYKTrEBwhT#n|6$Pv%%K4zeM3H`AyGxQ#PPNSjd@9De#^?r8i)0F z(&hvOPn?C={%r*TrWp|jt@}95hkP|7!7&j$=AZLT{*BZVjjU73%OiK-5U5&i$?sT0 z=@n_u!q>(N`z_vM*2D6H{n@py+ZPQb;llbh{gh@E5lrv4hqA%0T(a*a-o&L=WLd@fZreU~6lCti_v>la0Q zRBgHwwD3#fA5^H;kmWXM22*S%h`8m|*2;ImvZuV)+D=atslVJ8{;q;IIhG6#Gm(B< z#SO%Xfg83?&S*zT?LxfQh5lVi54wRh}xCxX`NE8YanP*95}l5AP6|-H?3^9zhHI_h~%Ah zoqsC7Uf1aLRgU+G4q9{kDEDnr30jSO#GiSqKQa{01c+Kl!%g!Ml$sTadDC*BgnCvk zHOHeXH}ZIqvz+;cclv(58qd)&TG=o8M*Q)uK3DF})#(@%eSZV+$}iHz0cqqVH4YAGTmB~# z1)dkCt<2vRyjj@3>%YN~+?-z!xo+jr1fE`bD|RtE^S9PWHfc5X&-pP5U+*3G3k=Y( zo_hv>*jVHULkffi-t5>!8bRct7o{yNOWX~TT&#YdV>%K7l%RBGh!>1F-cXbUn`nMg zr?NDdCgvw*o#K(pa5k7VfnO_x_Nkg}^cvRT`XyB@eP`zXC~5|CIdET+oaM$F*3?cL z*6oZGp4TLu$q57dyUVn{u?oTE~ zOh5cSEG*9OeQ@Ds0@?97mGzpNMD!5K*#+}YM`L+@C5N9MTm>#u-+s1bWbzlvs%H#7 zF#(n~wcF?4O=h{B^BqSVd%ljMSuEzIG|x&xQEFxlnMLK0c2Uh^x$^Citj2uB%vC|J zSHjafnj)SZ>;cE#UnJCiZ*q0x%-Vpk&~M+6idI!|_(nMcL5TJ`igjEgo|rNZ#v*$j zK6244OtxOcDj?e}FfT|f*9{jE-vwI2lLjvPt!Pk|vqhqOZ_Aw|)S*Fx~R_v@ROhhuHirEL^k5Fi;DF}V=83O`YpB4DS)nQ`UBH{1a~S$4J?RH&jr@gX#2F3F(Bb*oKk;E>}xU4VyS2sGek;{p58 zT!QCMb;kxdM+_BdJ4W}aAJ=v z=DC?FD+Uk_Ll-yEweUXE^hrv&pj9d4+>!D znb=1lqljl87jkVcb@ulINx3$|fjV)!Ajv(Gv=g5#s9ny3@l&b=`l&M&*+D)H6d``t zI{=)wBf{{Q=Y>YbA#rZ|XwFvbs+%mU{;`)EodbpxvNMU0Uj*O3-ghVi$Vxt?%+bCG zQ{Y))kt}flDwR>1Z=DOaDd)`((csjk;MMp;&UY2j=Rg0>n_cQA{)+jEHh^BVj`;c| z@Lqej_3vp>jgm#8Y_zbVGDfEVjL7kTJ0$5d6skz);$&;5qBgG9$WHPm1|MCw z3d)Iz`^3ucbFuBY=yQltvI|JViY0@whtR@B z2enYqj_9vo4VP5whI=Gk1p^pWJMmc|0p+t6#W_uusDJ4sw6%WPihYB0sb&1(?`_4` z{OAlsO|u_I9m7Btsr)iRcDkr3F#;%C6gvOu2QdBfTOSd0+CPl!G+)$+lk>=8lj2rd z`dhcG7wEytZB;H|8{*E0F69j%#WXLD9mQX*Qe7>_z)*mPQU|utapPU;$(s9T!hv=I zpG}AM9lmp`xuU-c&B@uu$PB-N38USe*)s

    Z6Q zNlR+ObV1!d0B8n3Cz`NuLG5HXT~@ZPWeI|Z~V%5$0H*;0M@$&`u0=x9F zV3IU`*W`Rpnj}I%eV4wWmxu?j&O}FdsoanP6$c?SKRPpl#$lAn>`6yUMxDMl{;Y&$ z!FQZ9v*rzR@ue!2<9lfvk+@@>&qj_q5znjAZ!C=hMu!KX=-@j(0BhF_HgjIauJege z6rKVHd^}T8B#qm2QWWuc&cqIuqwIntcxA*w(k!p%*BU%mhAK{>D&6A?)u-diJUxqU ztJLVWcv>qV=hmh+qf~VN*&9D;J?{0EnI$aq1;ejE_mT8Ip?E1P8LS!<9Pw|Bn$Q5n z+}lyc^bnubctxs#-P1eYRE&n*FfRMEI!!eZJ0WkM%RP+azPc~Dr3}034d0MoQQ-dk zLG%v(@}lr6*?l6jcd%cc=C3`l5%-Vki^pQV;pLxSxfL#v9Nmt(^e~6Gso}a?i95&& z*}au*F&?NaY$HUk(Bo(C_8yh}mAJMGkx%EQ!36Uq#sL$11$TRbCuxZCVE)8vX_eRF z&wT<+r4+Z;gCjhe`wY8~!4nR-wiwVYjJOT=9QsOT5U%v`^#tvAa>x9llUiD%%NP}A zAr858KUNC7e}6q@sqlcc^;G<0CI>ILg<_RrcJYe$pr03_HnJck(Vk*W>e+McPy7nT z;d7~#f=hEaTtGH(4=;X4NI>&#e58co^Vd^X?OAoms5P%!KY3WUp4l%9At`2J0b_-7 z#Q;#!#%lzH%0C;M@u?4{)MxL?-_08JCZZv&4XI9Nu602MA=EW@0dwB3+NG^UxNv+E zx58v$Wu5iM!*u80f^BMr>WnZe+q`_loWoQ{W}QN~Qs!=En54A4QE`;{O;{>7qI{_z zwRj0KB&HVlyrgnnP3N&NeM9L*CQLq`jglwGP}?)DFJ`a>#HNN?r>rZZU4|G7%II^0^<1fY`=hwZEUh{sIrhS^-nwY@C!VyNO z2}Uj=H*V_QO3f@Ad+6t=z^UaS9iWNA%jZe0qm0RFNPf{Wn_XS5#;$sH?c7&z$U3{l zRNECix7U4LTX=^pwkFP$Wy*nky%(yg)M5S# zzJHD@U4$MEGn9SCRaOFnmRC_Y7pVkl{oAXPlI$FMT(}XG{)**Ztv$yC)p6o%LAFPv zt@zqi0+xA?+4p#D5oJ}Xl<4q^fq`P~_=0eYGE3~)UPu4%fxJR;x<^Mii=5}~DR2y7 z0%yq=vhj23_Vs=2*xna6*uR=IvcT3rV*%T&qe&BCRBE??B@YF&yWBBLwOS7?)~*X0 z=l0r?8qRWGzA|VKufRiCn{KPs#gN?JkBmdeWROAXMJ6G>;)CTg2e(uG)YS|vhH!g} z2_6e%yyiLh+VGSLI4-~SbdZ5h4az(fN*4f&0W&kZVw>)s%yo>F~%Z6#QNnnLbHh!hR^;W;5GrC2f>w+I+S6{dBoUo z1dLSHt19e(c>+ISvuumvIo~$-z!JJo2w@hLqo`-HQFb_oFEFbMnYZx6oTgeRSj!f$ zqRCj^9n)_@dvXkTEIsZ-V+anCCa;glPLM;<3dY0O=vE#?V=TH_vsRh5Sb4 zHxFPIv!yK*e}maCfUm=3{`iR{&GSI3Y>{=;6cCo?k>Kp8eAFZ~x#~is$k8X3S$2jQ zxOyloo%z5a==Jz6P1?YWei2sN)maMe08y86kL*?4zy>~L-|kL$D}}u>H|L|Yb832~ zsl#iU(Lh9J*}x9m!md=N&j+W&FoPjAks*8QYqIV0AsXa~E9%_gTODpj>zzd$4w*Dr zR1vi=;aTiNUEXeW6Ve0&k02onR&lkeR$5CI?C%B1O zkX$2IuYUT-pT~|VSd#fasL^9?dw^hymkM#sH&n2OvuR$)XzkhVuX$M$8IBr$5GP9y zs}0F@>&fgCP}^I#rZ4@URAlXKJ;>x_A0fhT((yPI!9@!NUWysI>^=7%t0$zhkJ&~h z2F0_jufpSbZ#iM9wY5f5W>p0Zgq*Wh8K)>iMt4w;w@PviUrDp(kdBbw6-=3j^Uz1l zmFZ=v7_ZSGg)$b%Oj&e2c;^^`tuUA2+w;~hF(2RIYYv1SPmw$!KD2^hKnLU2BGznR z^}=^-yrqL=X;~!ry}=;aNTiOU2`0E2^xju^nW?}E`w_;hE$s*BGG;qh_JSO|4eL4*7CX?UP0AXq7vv4P};*pACY<;o@+s`Ui#+Dg)j(J^#7ITZnrQ}YROOoLOpoO&a$tVz<$=wJAX97N6s zCvOH`x=*>}Rm2SWv#25na(p=|T}b+t_|=x;jb85%+X)NmH5A>hIl-Rqw{$JjVOp#S!|Izx}z`!nWifu=t?V z%NaK=#+(HBQSTAukIGlzv{RDh*L2h>8|v2T_$329&_hie5 zViS&=JKSmD={sr2{*md^fj7TGhfvP`?QWPREx(|Po~hJ`EH*GM@?bH@Y(_Sj8tOL+ zwy7a9r#P$v{SICH+3heTu|qmIqF5yQ3p&y{Bs|?kVPkI>c%Jyy4uSW?ZF%`X(C5(( zC9{xEz8~&4uMps8$t{&x8+=zNIs{J3bv>q5-7Eaaf$Rf^8cf%-363C`x#Lo|b_*f( zo^W(ma;?cJaB1|-C-sW!lj5XP6g8L+7;Lt?mZL6cObV1xMk+3QK6( z0+(nUv$)%BRniI%E!ePPXp=%l>qeu3UH{$Bo%K528N>8CQxx?Pjw>+3gdsgVqGkca zjUGeBl!t}jQjJe^crcQrz+itY@`-I}y&=Ypq>rl{DbHXs^CNA$=$Rv$n>SJX)=BL3 z`@2nD_h=JdLW5oTuX;BGbj|Q!JE)DMX_{}P`jHVLPT{82QKa;y!_(g|o?2G-&&}F| zF>syYl~1db3Q9g=X2lL|Q2s@yU3E!nVjz=cVB1#ROiuLfH&DOP&lbgDiFq!bf0;z7 zEB)W%#*I3)CA8RPMO9aP8yZ)0k+PaKOr-bJ{JPNNDaI@+%`~e48JmTws599hhghO+ z%Fs6-e1m8K=*}m52E6`iQeO?CVUo6nxuTuUX3oTkX2yl96c{}7$O0Uh4H;K@&p!sf z&1nr<{&gM(6&&4Vaa?dd27B+|AxE_=UA67Ss{I~zkdq!7>?daP3$VrJMOfk&=)ApK zCDV{a+$6oLWJB2ki;uPUW<}89#_K5h7enV&aX(ETxfY!KO3bG#9>KqT6JVJ&DsECJfY$x`gF-cPo5N z`?UUBVI)qd*OY^g42C~1%K}w2Xy(s^Eco8#DK#B^1=42>7EKD7--n?eh1woj)E)_L z4|E!vOTj6w_D|{WOCP{8jyjHGKyq-Mp8@;D%Jimlh)Sq(K+UnPG`kER^=DA4X-3eS zsGuw?s-?!4G;+jB7J61V<+O*+ zA~wrt`A9CA5e=mNhEH#iKeCK#Gos=M=%8gN>t-E%x{=$Ri9pj{RDHOZHs|$W-N`e= z#=H@Lej(xh{;xAacj<5g4e_FAh;c==0)mzWw<`>~Syn;c*`}nQSx^~d@-kk&TxNgj z!Z2li3mFzCgNqvuaeJ;3y?oWHxf!614?m?Q@z-Ww4lw)6L)RcRN|PXRJ@f5Qte$eH z;|k~uW)5YfL_CyNpoi9xG6eL6v3ba zRnNkPkSL>+*x5MG5Jq|NgLoM@t8MHtMqAJT8W*4}lWxLj*O}a7n!pZ-rOdhdf5r=L zxSPgT4AHs@T+(Y!R(N+%T!GF+jD=XNO)V^7W+$v^FGvMJIFjzfAA64U4YV=)68f!o zFQ2Ma<_TaF|DJID5TAvj`whUYjqsr$?J)HN|1T9D~OLdb}E##Xv~)w##| z6IHt>c9-3UzFA2Z2KauuCu`!#4SrlE9L|m)T-U*%wuPMYEB#hn{5Z~?iR;2rMw1|R zt6SZ5o+v}@IGr&+#qaSRJeA&VSf@kN9hWcj$ksUJaW z7rx4GxO4gLXS8qZ*jSVVyOv8Zc_?r(REVauEsR+C+p*krq)XQZ+KUvJYv7EQj5qxJ zQ|SU$$zCmg*}lz2W@TX^zfd(vTZoPePGXl-RpA_z|NR!vv6g0AeLWS6wN{Wc^t$xT zh;SnNTc7nkedMvZM7BJzW8|rTEZKdc9;3U2!)tAa1A?qsg}0_)eUX6^vhGtnJX~vy z8rSfd22x&1N>Z0Zl`u|jiBo7i<<---OGe)gtsJA|6l}@FRMJd`>W5erG z&sv>it>8Tpv=emF-}^_bwb?~ zQ~0ZG`f{TdRbw9eSkIb{?oj!Th&=3zrs+v8iAE}aQa!OPIS%V%zdaSWC&-zrI zPn?Zj>qc4__abe;hq3&)9R$oiwW=5`CHyZ0xN6?5NweGtClX*5pimJ(ux;DI5_5zIr`ou`y}wtIx>|=%k+Y=KTFd!m&-GNK zCwQrb{`jx6>=uXy9hB(5!jfTq?=!Cl>DO{0iJ~;A&^B( zTf>C!f_rm06l4oZ8c~!CXZ|EjmfLN|kDGgGp6>1X9FPLl&qX5<<>tiULm+e2g+7=Y z_p?QK`s|;!P5l+xIwiwXv~RuX6h66nzAp`ladjsUM-YjZPB@gM&r+j1*6OjKWWr9~yjW(J@nJLaSt(FRSEf~QcZ zrI(OBy_98i(_8IlPDi*U{Wj9gkjjP4#$rR=kAqCnT;`r$j$dHZxRG?_tn*AyM3uXO zcY~$CyNlD<6_=NpR`JSd1755(@_F+Nkrg!XB-{Qs>IL6=VFEk0O?c@2=?W!2wPVsp3Gcy zY?DYZ0kO1ll2j?}na8;xaJPpP6OddeOiAsmGbXEFU3yq43=S61E`@}wD3ctAbgdps z7`j*|!LKSO7G+ok#PXGT;8}qn|0tZ7SR7#L0_BV7{rH`CA8g~s22qXL*!;+w*wG6U!g+rxKA5;{COtdKa&SCW_ zVcAd6f>IS)@Pe1e`&v4eZ_c?10P{@-hWHNi18oWZwW`NRTE>(p z<kO)Frs@1B8LR4J7NnO-tFg2f;HiIB&h^w>*UDEA#`zAlp z;;awvnAA2^Lal@_&iBVK7Ij&6ITTPBYw_A|6lQQW(MZ} z7e8lZ;rPF%!~frH$i~9T^gqU}x&Ct-UazojSNMzb`a8Q3ZRaF1_5l#l3qivKI!j1K zgf~Gf;84aCJEu8^Ej-733%#w)GJj0wdLjXqqoldBY&%jy7Vc@rLuY%d%`Xv_h$^Z zwsLcGweiW=Xwxfmkg34;{se3Scj&X#Rf4a9y|K{e|8WHR&4`8yLzrs~Yx};x?6=;} z#aE;Ew`Uiu>X&B|4&_<`yMn}r1%Far0;Dmce}Ys0hVuu0yR-$+rQPvM`=t6*BY=2v zV;tMSJUN06^c2c>^`{v^fHtT2>(t-9hYbK>`3ME!=p01wAb^V>PBaDy__oafA)h=C z$R7^)i#a>JfpP%tcIX(y{)3tDsfIB`L&a}%q%SM0Pre0ns^<3quU5x$u+iQAYrXQn z7(0jNOt@%m$9B@OZQHifv2EM7Ivw+gZQHhO+ve%7zR4N9gEQHGVAZbLd)>HzVID%> zzfD(#bJ?4F!fGAekJ$r+bvFB`@BM|4=(Bo!-3&MhM@fh$8Tvs3bb)G9oA_R8?%%hk zcXx!g_3Z}1zPqOx&3nVo)_megNZs-w!~wQRq)k`|cZ$D!3IasE6mbOLS|ozw6~42C&9A z3M9?#j8O(7m~|h}#11LP0rFv;xX;};pzNFH=x5|sU-g^g?~l7k)OB23&j4-D!H)vw zA(-RiH*5f56%Q^E5Im+Z#OzNPcHmEh8mJAZqx<_!DGY81QV`rCf{>ZK9xy$ApnzXQ zCh;JwO#ytM_Qp@%BtcIfLm8KFu7PbD&f!W2c*4-YgFaJ8cO@Ru4I&2^!%v8y9aLSP zf6ZMgy!hxDz?V|6%8zBXqz))iG)_DHx+|O5vO*=-VAh8M-dY@0ff-( z8PdkEnzLt_mKMap`rGNN*~2pg=-T|p5C(J;p=Zh;*Xru}JnHnELmdh4YvQ}ghjA6w zCYFT{xB(r}Qw?k0M~`0QZ0ujpZlK>Ex9^a6XT}*2*zGdLdlxPxhKH$`b;zMJ1U<26 za{!yE?(`15?Dws1ReseoI_FWL>Skj>Qxu?;M+{%)p06MuKv*d;&Muu$giPadB|2Xm zNB$o4wK`m_5}z;|-&XHSJ(d`G*p**vWzle4!f>< zevO9FiDHbNUjCM$C%3-1zE5s~Vr%G$3Kp$2cBXps_Au_Gkb^2w)E<&25gQil-onmr)HaP4U&V=! zEme)lcabDJ`HK^bDSLav&+=EV`YUzM#i#afM{n;~*?JnXixslH3Ys2da~2XuE`h3| zcwT;i0InHnyh-WHH|Q;O+CK4c&-l0FarJx>V#1<~PYF>ad5SJ2lGls%uJmDM0#Vh; zXC+W&6#M-#Kz;#p76LnOPyaNZ-`G%y_NE@fHkrZ&nk9v2MEXZV9|=LBQvrsitTn^& zO=#47twx`m(Clla=i!5um7)J*9o2M7y>T*69pG<<7KNJ7ekxdaWh^9yMX{_XXzJ z5QN?_ELHq6&rmA4qEhQGSGFo=d{U9wgnX&uY4hfKgN?3QmCD~*td>1{yAum9j-Vy) z!JJ7`^;mUG3n4~eCOc@)xKv@}6JF)}!;9b!4wF}SPYOc{b?8vOHVe9H(_LdS)%QiB zw+|kXJFdfN^~)TI$rTG+M)OHCpOYGeNkpuz3G|4n1es~yW<=WyPD3}bX~h+1$* z#m;&^81LMn@b@>FE3~T+YOrcBXNc44%VBT@V@+WhZ!&`KtoKb{js*Aj+Z zN5)D1h_ZuT0})qvv4)Q92@o8^$+$#}K9?dfHJAdkYm09BdLNy9qIth{N#l#fz9M48 z`p{o3-s(j-6GG5t8`wEg+*RAj)l(C;1tpr|4si?T(MCr6?%_k|%9rM<%dV3cMtl8C zc*iq{j?Oe(jxd`)SV()GwZDifbT6Z^FOgl!9?&;|n;$8c(796&mU#AcuIhVjCNdgg zt4O1fc)5NZ(tO^q*n*0D;~Wz9AvRjzW=Xih;_b(BB*ot!9GP)%Fl;bCv{ zO}K)=gqKTAI6Wo)<4ujpGWIxS`|(GRvocgjl&0m4q_tDAvj13Wh=9;@!U=jF=`X`( z5+yBPIN3tfNs<+Q+SuoSQ>&p$U(2#mo~w!dmkh(pAm<-j8v1B(yCCLMss8Qg-DJ5u ztv~D6#7#!>RmW;LZDc*ZdC8o$6%Wk?xn3QKkY|O{jnPWeqP+JG9lNFcn=D8qNe9^> zs9w_&YVNW;H-ws9cAtl3E0XkO7DgS2&(aG`(th%%5l)(BWQ_DLd}dKFCer$9m_KHF zd7B~Bm8Pafm$ic1+G8seWyYHX6P&JvCzE+nX*+F?!wVm?HK(#kr&JQfzG*)m>;q?z zVfY1ndk+g6Pt@@R7edEH!=5dX*elJu#rb1A(;Ee_6Cq|%NIiPPFirx}^O?_+o09B? z!>J0Y?^p4XxpWh>)53J(`~qT?s9MipoZO>;KxU7I@4 zEf%Amx5Xr_9oA*q5h&4OT7sdYKsh9l_}XF?m>kjG?2`~-=0Rz#=T+$yC%l$*#gSF+9_$|j62#IvWesIg1oLB1a@SyW$s zR)eTCAXCl5qiWF)`NzE+fsT=?a;juqsM8NFwrX%XfF~MZZ~5CK7LDPA!!UV>u)4N9 zjkJrDCWgvPSTXjJgZ5{Fj@xxOp!3$7rt8L6|MzBr*=n`sq{npMt|48~x`oDQ0fS6& zASTR8v&{igcHc(nQuXu%tRS+Etz<>tzYcaCqc#ShH3&sPXHy;Jg;dC$oSHrDn9pkT&+XA0&F0YoLic z%Dwkp(EUjz_nY*nxLzJ@XDUJ?VerHyV#p7KY?Ex6tf*7?^ zeu?Q#Nv8c3O`5fdHA@j1O`6-E^c7tsPM$p@y0FQW=Xs!b~i&B1JUvIbajq0R!o8eTRfq;_^Uan}CDa@^AIGxdKz&+e02{_(? zf0A)i*nB=6nz1Ru*I}XzSYB_JXsGaxwA}d&*}?Zl-y`_cjbu@ciQ+`FDLp_jKf*pt z|AMHTA@OjhZ#qvF{>0t~gL{vOjZ59m)_|s(Tz0`OhZIHq5J_K|f-2fpsr)FfRwK4| z(b)sr*gVf3MMD?{uW&BCt20nPJF1E1c>gZVEP&c_8^(jSxAxo|=vUt^O!LV`b8rf9 zAUkB1;0|hv6+}JGW`7#K1CVabFNW!b8TmD9Xu;GZo97q;EOs!cdkt8K2 z5Dx`=8skLJVk3nCyZx}vl=N)mPm7i=;cx|ElH+*Dv|98r>( zia!oVbmPMkYo=9go|cP>Dy;N;fG&~>{L5TZ@5Wc2;zjY;FHFo&vi{67>wtzPDL#}X z<`PE7BoR`;LGOJ!A8+hL&nO{xjc(50XSUmnRqw;m&o73CCYFeSB)Vjntck` zn86=Sez9{J86Cgr4&@AEdJpwJNAr|77l>i78Z=2`2mBGY*5!o9Kmc%Z%#kT{I>~wK zb~X$SOF7^uIh-$~n0`As-V7)>gj-~Uh(t&(YX)X@E|s)9{U}()=Kie%;SJ7UAXrYr z5G}R$Zo?fv*1OMNzf^Nh%C5tZGI(_=fO~m|PI{lB@_IvJES0eTXD8?-#ZVNZA9;%+ z&aDfIc{(nTVjn8)IDaKMuG;=WB%$hgs0y*ic7=S9gI*;gWk8*O4O=PVJW^vGJcDNt z_{KM{eW9&W?8roBAldV_iuyJ6U?P|nZ{l<;X4)#1f$E(jVxVqej&-N!y@Wo)BP;RU!DFrB8DhV zx6F~X1T~bp|11Q?$Z75XwYZp8&o!FHqOPPyKe6xCj=H1Uez8_=!mNEbs1gtHjsKMf z-YU1l<9a)__BP@Ub(6Hq{;@lF0uVA^kbc_JYA(xJIX+<}Fy__JV#u>ZconIx4TxzU z(l8BMY?;_+XD%6!8ge)y`OJN8`q4AC6bNgPMq!yS8}_qDev;N4&T}5X$oZPU#0|zz zNJHE_Erd3+ya2xWn>nxiDK&mF9#z@O+6Kk%zM+s8oVoARZE_yh*td`y zj}7aD3cndOMnOum$O5~^a_bUXG#}1s`n5w<_;g+m-tjg0O zCtLlln7C2SB8X-;A4H~kO(ms*0JYLHEbj>~7r6XCp=xkZV4;&^4Ix#5)+I6fL;#5I zi-?ZbP}BW~CM8vcmyg@@4}Ib{>akAqo|AK}_|-d9saFGB<_`(oo+5{!$esjMqMykc z{;`mH7K=ZthP7hT#7N_BApp#leEh>)GFPLP3Z7opsyVf<`bP7L}SCD(!&Zlud zOEv-NOPxOo;V+k#(A%1va@P16v{4U!BEcKU?U$zv9doeTI_ zFdbam#P|-!<7->ebJmL(A`E-Iw7uLZ+ssj!m*`Q&o%Os)4BIW{Nk-FKXvGH}s%A{7 z{H#m!(h4p&7@$8!qMTJX)?phvv2ra)VASY&YF+Na%2cX#b> z_pF@P0%57@i*x5ngjnrW8FNZ_J1S|H*KMduavEfm# zZ$KSy4;Y7oeya=wc|bgT(TDkEucQjW+Dz1j(K7UpQK^0MZowoosS=Ip2bK&qdft_a|L#4{xVB>n2H%mw)sf) z+KZ?v%feK46t6)O;ADNK!)irC_!hO&PqT@1-CDKIvsqEFtgA1pVX$t=J+gj#293I1#CXhr<{t3M}dwdXCJ?yx^YSYok= zrAoGm1IKvyG~vf<#_Zzk!M?tzXmdtCX;*3lTc-Kor5X0p_KHQ}fo(8vZw8)1;SaXa zG$?Tyn5&SB*m*mh78u!XfpvaUI&mbVETa&!KrzcL+qTqnntTD`)nU@7M z4WoqF$F9wd@~}3`hz&`TSf-d#u<_(?1`W9J&9C9rcdPd<4M-{NRBr)yHvHPxQz8R9q~PFMCkXL z9CgAW7@y*e%i;dvgO8VKy}wN8!~FXpu&tB)d5Ll5u-bH+(`Y(GP)mtGo}zk~d~N%; zs7Frz0~u>QMmUx?jf+ez{e}6&g0qE6pET0G;WP49e=Jh>8KHh~ z1GH`;n)%5%X_{R4g>$*|^KnCsqTQ?}f-XL{Xl&|G2OutJuP7~**POiDJ0_2WLpN5k zyFk(FM7^L%>sJc9ygskd06p$}n6VQ%2j)FrW$h5@4aL&yO8^66czQ|xF*&#gChoC- z1)ccGt!LMag+qb|FG7Fa&2^k@wMOE08exBbJ8t~!6#2F<6Gsn&8CuW@sb>Fdd$X`X zZSp=2ULlvrN*_N8(K=+VT=N}K#X$f5YTnl}t|{URj(3&Z zl=T;wYvYK-Nw?c)+P#rjGjdB<1JOksDS;e*&_eh+>!UOw?OY}@uB_Nu8JqjPp>Odv z>zeXz3nc_LJe6s~sqNXe;L6#qtngd#P%?k@beRwx97?R_;zn|h=CdNiR8>K6yM9B0 ztIL;8bR{#97UXk7D=y|u?)dL+f)rpwV)B#PZyidV zyYn@8zaw-f>EE0&1Y$)6$NnNj8?P>T7~pL;{^nk}e4Tn72XREpY8EwCpd<~59=JoF zV255yen@7NCE%gtLh5!TB__(w_kL$%;jo5P56KzsN-t(8du_~8gn*n;G*=^EY}WYW za4cl9_FGXS-2-4F;;^d85{W%7{6*uF`)>)4qoC&3p~;gVfG-k_Jw(x7=qnV6W>xwg zmB{>AS}+T&KY-u1m|5TsPIaI$(;aoc){0Uo_DR3=DyVdBLXuK?-2nfWYJ(yu;$w_c zV=XXmPpnSTW#@Q{YFLUR{eY4&mSd`*_V6Hcdc%=NLlVX*Xw@=wZ75j7Bp}~dRNR2A9NM+D~E$k9b_XyRxONi7h)rVV7&a;vJ*t_|KT|S!X0uRV2 ziMO-tI{WjM7N;Prhm$G`vrv;7rt9*tY7Y$ogetkXTXHu`eFX%-&D*7GqEI@%@-~lt zu;H$=QS97lBbGP}balt(38|6ud*WovLQgWEq@rqP zPb?m$5rzi#hmel%@_{rBwVlX!k0DTl;^O<9^(3VotJ{#+cGfSlfgdxd>(A~v47#N$ zM$xu-YEW=?Im36v8qj2`00$>(r)<2UmOI;JL~N*XRMV%cPH*5X+V+m!_4o_Ta1~I@ zuV;8X@`%V!E4$4hV}s0NviA4M?cFh=F0p^r9K)SECmSE%fnUk`n8NtUwVk7*Gvw~f zE<{uIKwIbA>_lq|JWjWsqbhv^c+^usJNYma5{mxrY;!@n6%1ogjR+0dn77;1XO6ga zrs4!n%zPx&wUC6Wkx_Tnpz8>I|D?!6p|q9nSfDy1P!(udEO3vdgXnNrIB0UDx4d+B z5cb=rY>rDAm1DgzTo!{q8k#zXr)oO++Bg@3%|k%9%@hyq!RDSyU0JddwFIyYk#Z%& z$(-yxufkXxDzUXu64|cNDfld5W+(iq)ZyaJo&cW~+~C4-vWlVd`=kt^#ub}+8GPdj z&x7|RLe}KDh!66nrI*K|X1v3KwV_$@z%~_71Y_^0#R9a=4c!S%0Xl;3%UNljo(b#N z2cI?rZN(oJQ!vdkslQO&bSmYzfTX)Fjm%Y!gj~|m5(^_79bu7+d$@~x zFzY-WAyh;XAsOC%tk*T)%jS>%#m90bTLYlw`Q!4d(|a|It;y4bcJ~+w2{-I;?*u#w z^l))0Sqw-pmyiL8GGJ!77*uRs=$rYV;Y3;FesovqaTXh@?w{ZJlLalkcx76<8o3 zf>@Wi22hjG$$M}O0fa!MQ^4!vRskglNUH#YCIR5hfSzfH-kFJ?8z=vNWOT65FL`#* z;Js&rf3|7LNf-m@reL6)phb@aJ4w3$tjT@#-1KZz++_P>BZwvz776gr>rFVIzjGjI zc~IYCGte;s+=SU4*|}~#l=olM!Q7_cX`#5A+xQ?N+ARpJM&}Yk>+F5Uws^loLO{f|&PyY#V|If%|(U@`K`EfsrJD2H|a{UMf1{ zIzSIw9$K)5dM6fuuYqbs69PPh=!i-Qd=w~HFra`U9m4)8vn2-rC;))K02rJE_!x#1Dg3U- zx4zziBY?t60Uy}#-*5#Z2neIJJiZ#Dim@JR=mY#qs0V2Gfc$m=c1k0UHF3J%C_w)z z)%u`c&6(girJIm|Ms|ofKwv=oN*TU?8W#OaK7Y`@E5?7w?|3{lRlZFJeUD1GsV7AZmXQmcl==v|J;=7uUXfy2d40770gtD;157_b~RsVZQ1_ zvIP}6B0|a0pqsx*(gobM^b5=&LxouPCpp z{PhnQ;Dllq1U?i40{75+j^zb4zzo6!)7lOSs_{cZl%xgWOTh=PTIzv)IvF`pl0gI= zpFuSGkzaeNH6M`!6b@3)I8abQZv%f~{hmh5?+E@7^g_NNQiAL@{5xTG8@}Lw<_K4@ z0tJ~~t7v||{Pg$eLqiS1gA4-zp}}MzHszpNGc=~BI-biCWOXlz)9_#(;yYLe#NNNi z<*lIGROH6I& zx;7$GssMx&lzIWDVhbivWS;RagZ<^|nOD~|&*#@|8Y_^8p@d4wy=t+~FUg^nR!NUW zULE>5M46M2F3X|uWos-ws}k=up;+J)R)w4D$u>Q`@s3r5nr8&K8l5WxvsmX9`}-|^ zz3&j73PMH!dU{YL!uCwzuiOp2rWB!z3pxq1amw0!nQvHZ-vK)EIt%|4JLOlBRgAUoQq>h4$!wBqGxnUUsxXJ+vh019Q6U?B8GA9R8l$;Cq|iR^au0 z+@Z&@rl>Ffi=Odsi!iU}u}dB8V(@mpYyQ!!zr>#puQnj;(@Z4x&o9&#zv(C_d=_-n zwRS7mm^3OTzc*Ke2m^2BGF*%y8lm4Ey&}dgfnVV86lX*(TY1l0E%8NPp}h$U_dgr~Mf{3^xGT%a(x|sgng6xTAwp7n!FAm=4Nk@|O534epA>*j5$Pr6{yU zSHgrZdV9)vhVIqihzFYE^_$MW4wV7^8c>HAJj|5o4wEIe);Uy7p=A|n`9BMZ`2AW- zZF)H=z?Awl&FwoMvOpZ;6xH8AIqq~^%Xuq3A};7H+#1|bV4*m9BQ$)=buqLc?6n|z z1SaT?nGa{yl-W#Gc#DoMd@^!|IO*wqOV}rAJhCmmU&7EIcv-uKs4jR5hV<)X9XI8E zYOdcd%dPD_>GXJy^wwYu*Q4pS_<#|`#I+>WOj+qnlF<+cl2n##O=e4!)hMnOII)1i zM{xF9yON6keV_x<$)oe*fy(lxnY|Tc=lJ4S?ZH_?18kkkbmAS?5s5F9g{Cv*n3m8w zUeFXmOSSs0H4j3te}*wVfKZ()Vvynxj^ z@k9PT9s|W_ypgEnk~|(&F_vAt^AA+v=1=d~xCr^~5j~OkQp3e;a4cR9^*MIN*4UYl zfSu&zkizP;G$m%Ub#UYQN3~0HDDx|v6q5h~2sV=zXx`;kH-Y_iuOQ*p+WiPbh_4M-ALt@r! z+y10E1ZGax^Fleqdpwg_zKATKZ5%|oA4Pxj0~O40cHY@XTtmy%V*-LhWps7fl0i%{7y3%;BugD!VR~6(0vxlw?^C-_Rt&7 zqGqM}hNz(es%M{e^6kwXguAo#2pd~bF7XpeZ1TG*k5TIO@efq6$E6L)>uf-Ml&U+X zv16l{+IIy=%~hg^W`&%?%pv|gJ#oT0ndVYD2+Lasnp;NoB7b+_1WA_Z; zCfd-+wKI*mQ~+$Q4)!Wl{VNbL8*%rbk?JvzR^ZQEtD8%wFlUz*=wST+@ts1T@rCB7j-*1dIOfPZwk8E`cZvSlU1?Xt+%#`$2M23uR zy4>PQLKM%Wq8!#CMZd$-qH)6cW`k&#s?~3^6ne8Xo@+enA|xP+9d0D?x1nsG)UX5I)QZh#j&p1~MgZ@PDc4dvi>r)gHR?zP3eA zE>&RBR~^W+7rxp=5^XEISV48lsT^RXG0BZ=H08-(FzLuAfiv2=p)--y0t;3~661^N zGjwqMOQtgAmTS0`{r9YWht#Slvr$Wqr%EVqiKa&K*Q7avpG60-%mBcb6vo9w%w6)E zbG!bVCQfPcMp@774KvM}m$~oM@93h7gVcn4yH?)O=n;4W>W`FK?MUEQ(<};rkDh57wlIn z4_q~rd>}TY2QvSWxvFRo?b2uv&Mi2-?cj*OdAGe1*`_wYD;4;w>-%{$DIdEhGOl|2S11`8LpfkUZ4!WZ+D_ z@TfLt|65PUllI$Eti$>f_$eM5%UN${Ev<#tw3VDuUI4Bz}n|d-~v~6;9kT_Q( z_RjXQLTxtbJw#U~4R>AU{;Y&cBdI$wZJqWSbw>vA!laU``iFvFm+GJsP}v>+f~{8a zH;wU5B#8bb0rMq#2`>N7eCToqnke&Ig5SN;P5)uS%$~w z9#+i^KEHM<_B91-mfRdc)OM$HQkm0~KOf4}u3*tgN8cerwbuDeZ!!<`UF&LPu~u$T zcE)$kO7COFja1kW^h}eYZ(6vs_!H2-YhSz1&(UnM$gf^&XSj!UjjR2)w)yK~K!{ zH^Q9<(ONmFC^i%FZpy210tB=}(G62RMi=jN_)IwK3&AWRer$?%iT?T_R$@=|P}0-S zg;sZtcWZDhWhmcfjT;b$-lOvP=Ec(%1zK&&)S|?RZuwPe#T=am#;Jm%$F@i$arD(! zx-*?I+~IF3;4IJNk@5z}s(f=&HUXu^qc2FKgI(|7+P_>YCUl}gjJrea=Egj^px7`= zS|Ki%rnN9z)gYW?prV=?&!U=ljR?GLoA0(&_u4nkUtY2ZMtC*1vlT3h+$223 zc;t1H+!}9MNj+Ja86Zk(Ma^U48dd7HdtTF*=o;9BQUK)wldh1^^(YOl<5?#QqYAaD zY;>`^i*L^`_u{l>|5_wbAA37Vh~w1+D27>52JSHPh)2$=zY ze5Ch_XBF5)|KWO`t;%B?f=0ibsc;f4s*;=eV&$vJ+aZWpQD$ny7~|Cr z8zuQC!O-9cUgdKW^J;s@sJT}?NC~GBx_>FAT>{2;&X#GpaO;Vwe!d08BvTzUi|~QW z-;CQWensC?ZO=ln;&C$y19Ewbn8J2Q=kURJ*7Q(KEO4`orkOj*@mFD5AnPqo_O2Ie za-!$URA%=6E8>zcL8-&I%-5(9tmV*NG?wOPxCt+NJfy{60)K0oX|f&H z1^V@OVFrro@GK@BJv%jFCBKFu2wbn1+QCXTnm z@3EGSuzf9`vJSlxW|#~z$vp*hR0hgwoXYIMcGZz=?W}sywulvyUtdS?&Z7(V<5ISMO2FB_19R0_<{f-qRKZ0!vX!(z3T|Sj_Rr*+o zOl`4Ze|>eT_E@T9Pw_jUs=qPuU2dI@5Rmk(|31Z1*ug+jyH8Tt=Q<6b$CD{0Syt2L z(H7I==MFMEf+q+xyMMtpgnZ)Uib#rU3bRF zg}Vhd7>TqOm$7T#wA^K?&JeuEZc~w1@TCEMLr%mIJ=!T?jxa-9AJz`G@^O{(dhB7) zs}5(|@6kKI__RMPvGb!U0|*<(gzd1nS6s5oC{bhcg12#M{qefa*jTNJSHN0e%VEN& zeLsC94H+y@kaGFb8$f9w61#bqtN)E$9rWw)7Pp9ZBeP}x^Y{;2hM^~qw-#A z5)rEZA8{nmH>&*}fmsP)&&x~og?qJi}DL(jy3_#<4t7I zXRhl`q`-`_0={^nkBip?1i#srsLQX67V$5mPCg~vgV+3R;U`nBxFU&_(qCAbk>(wY zb7rNOm-%LGYC+{o#HhA=eM_*Xj&bNc*kxUuV#^)Yfp}*%I$+n^(p*&PV@u`JgHH+X z^hwwTa?6C&&MtG1eFI|d{~Akv!&d*=h?liYcTGCNdZl-@m3uYcs!=GCb9H9HIUTvf zBEJ7K_@`jQc%-IWM3&+-v#Kdfl?z+qtVQDBTYOqZUGuLT-)!vQ z#G8B+LlG07G^Yn(s$x+%P1}qS0BT zyZD*32XmqD2+SV1k+#?J@y|)>(ns3bdJ~s!@AXwwzXW>?u!cL376n?>?U-m@Z>M$c zzT18^j22UHXEshxljTEl`h|sC3%lCKPf{QJDauSY4ISw(@a_p^b>+j3*Y!7KIIKVW zE6YT}x-QjLOd^zNS6uh7^&D1)9fV3mG~bbV(xnw)-qj+@PEeaAPyE9T#D)uU*qMNM z34Q_0l?PisJ6ir07yc>;arCBjVaC3@85YXu=^Yn`xg+y3AshL13>Zx00zWHlOxVRI zLU5HXZnNqZ1%mU%BPPQ%h2v3(bE@KJ1dXpW5d;B5OcQrz_!A@Q7uJzKAl8_D=7~I7<;+soSj9^%MZHf|ul&}qLE+y4}XC1Bp@4*WN)y|0__61x` zu)F0!@j;u9d%AQl(xTz>%`|2U{T1AUCpikzPw^2sRNXcoPI~>;J+64fgvMMK;F?>C zm+dn3R%bs?zf^{1j^v=F#C{d8Y&bWq3pQJh7_t1FndC{~ncq!Bju++_jw5eZ&`!3} zE~t~?neYpqEhg8Y<`2?cPetb}G`G{(j_1_76Fq4#L?@?@Yc)XunsB5+agK_L9MF{` zv59)52<%IK8st(6T;Vn5^;v}cBptn8{DtK~eEZm%>3mO`cb};eU+sb~;}4aQ+OG5g7RIfL8vM}4W8n4d=_q4P`lrOJ+x(BMM1 zZcNtm9)>buDsA4-(j1Y@3cgfuFFR-{PtXe;$OVtETPq2f3&qXSIBGkDw{9>Dp5!qo z18T}G+uQCG7L{g2sCygM2D6hUHnwn;-scob>v9x|M(~qHK@)Ra;SJ*hua;S5=YYpu zul_cZli@3!r~>(CObTnZx!UxVJRbHoSs=W!?k~LiV?{$xM}Bqa zFCxOFIL*CuT?9@w`r-j3<=*S5++IL0K;dl~wi%46`Br_WWyv*PAGc9{4ZM${#Pz9m z5dAxNOLL{BDH$kD=D;CAK0FpjWX@*#F^@$BJ()7L8cPjv<`-ELMB8v*H&%0tRUY6+A{-Fpve7XK!h%;Zs`0rtf3yTO=(?sF(H z!CU-;4m!W#eYLxeGv=j0=^d1(502J9le6Tr&dXnz3Eo-LG5>=lM&ev#WBecue|A>) zRK|!sw#EsV1P`j|s6`g(fNQj3>nr$AQ8}C`+n~Ex80cGt!U=;K@#EuFdU6gbnCpXp zjbifMaU3Jm8Dcvke2`YzUjt_HXVJKODt6lNuAz#9n2E#coUDv7bj~ZClTQcX&pB@! zveuhNQ0I_QtfXbT!4Po?iU)K%*A$6lY1|rR5#pjlAX>$xLVD6>5N;$P33Ss-)tdyJ zakVTCB`~Qp3w|BHWj2pjWn8Q@dfTtE2R;V1c;M$qzP^vvN=5&@13S9dD#ds80?Y-_ z^k(3lw}R-ddu4~nB0eXECVBb|la_6rNZ2WS#tV0e8mLS9^TZXGA~+4UJ_!8dO9vaZ zjRfvqGU0sYSBqnZ`^xtaD${r51N0fLmG<>FenT58SD)IurSx`<1JCpGp7qIv9?yu! zM1LTe8s}1-k8%RMh~g_3ctDar1Pff6VK666&vki}fbd2D3X+D?Z2@H4peMbMX5}p+ z4&MN-T=9I4k8h)>nkg{wm3n*iQYlOoJ)TlKVkCiZIWzshC^Vb11|wFhuzLqJ##w>m zfChXNko3$Dt_*CO`0ymtj0%nDGuu1?@BKCvl~tx*fz4aO0`Av8qcis7ldF~wU3#2r zVDtyDFXutaC!cW-Xa#^L<<8Yrv;__NLV`1A!U-{!}tx4?AUFEdi}H z@lU&e9}6C$L0WxM6^#x4n8o|8Yt!kbxi~8sj*&a*yJHWBFkBF2yq}SNzIQDNn;kC7 zJ!|@kI_Ye~=&a5A+2RbC@cN5-ZUCu1H(AG6#K&_NYGyJTJ?2>PS&%7z4!_?KvD=bM z#o9E77Rk+=X@@=&qk0v;yq{&cr#D%oCXsknasiwLOXLP-`9C`GhQtv%3zHg`bifK_ z_lSWu5$H#M9l9Rojz5;p&;DNQv^7&sMumgSQRQ4{o<=G(pnECLfM1;OPO%J`M7|xh z_Z3f|zywS;H6(&dLPlc!L3)P*A76N@sCjv8@FY~1fTsH{KQMm%cwbpso?pcua+5A~ zE9%e^l}DeM;)bGDjhgdxVd$F_N5PM=by~RfiS#EiFcmWa=FD}}B(uet*oAE-lr-i1 zVpLB9aDKR*)ZLuInY1g8GGmog&7u;6yy6>hQ7bRgv#p{+(tYAdA(zKwT5ZgUuOj(O z)7Al%#;iKQuWv`z4e~@*#BCjA#xu8nUZw0gvwkACCO%U4V)xs7_sK8{LU#euNRZoy z=t(e#QYa@_uw#jL8p56ul!~-tmdF~OAw9lh%%)E1jt{_iXEJX@?f}n~rz(SgF!_XA z5I79^aZwe0voZAo{brcs%U~jN%QJkOzF&Ck<>gX9m!3(M@2ZMxT0W{M2Z7j;85Q4C}Cml^A^x#49y3de3giE~?T z`oK%EQXDM8M-pW6RZsqvyGMSlJIP}=g0qOZnI^3r0BP?v*j*QNw0yLIL)uum2j2z^ z>r6@-!`Z|Xeq&o2BV5P;kQH~%>yJ0T^tebh6hDXJh%XH%%o`c++99~^!B!H;DyQK_ zs)i`_3aF&0t&4mlY`?C89OJ%<0mD@u&%&wU!9mpG&_n>l?&IEn1Z|*)xJLt6C|Of! zGvny>yMGz!Bg^vaeR>2#l{Lq$^ri5?DCeV-X3aLyRKPJ>A`M0t1}7b~jG7qlJUnCN z{Jk2`OseCGP3QldlTH2m`kwj{{ zxH!1}KZcC(|G*(@{C`Psbaq*oe3us_k(Jq47kAisP&lT=SwhLwe-;4AV3!hB$>5+u zR;c;Ay$kPY&zZNMrf&Nwt(nc0>#iH?9YJa~IWTeU&ba_VI;cs6&lXJhQcyRyKu$sMA49@3IQCG!u|iox1-Eeo#ekp+JfJ~vpgWkL zS1>M4pe$TmkRN6j2XrvW^mZXypm7@@a7fBkaCpkI-P1F;y81A_qPG>~UV~{UAZV!D zy3Zp7q!vgXkx98cAXAkzw$*Q{g0?a|!G%6tkTB10btni!Ys^WdKiOMbTiH{K+o4l^ zYtl&x;JXNcnxL$`^akb}wcxw%13bk-3Q1Z~B^WRqKqSa2RFt3s1~ zim4Qc>ZRbTShq>Ixl}b^imqTHKbSOMOa{Q8d^kW6@Q*hR{@yusF8Z<+1s!k4mBIdI?Qn`ne2)d-BfR<}3L zI+NK%af}%37!g}H=xhGro*DJ5i^B7L+xT#yZMk373NZU{?Ecst6d!=hrcmxyk**(z z6r|G7qZ@Ks9lW)sJR}PB+Rnutas}eXpV7)*Mj%8;0RjvG3ZP3cAn!Eoh988Qqcf;) z8R&O9zw_Rejk!K#gSSPnRSY9&zju)bHzrq5P=o1e1N|F+>TjI9KtUkb2rf7Sh~^-{ zxo^}jDY)j(U;zCN);=)fuE#z;RPWu#%gsV2g_kC$;1%zW@%PGCy)~8P7|j{e&)Mq^ zH#9UPVgLsXRPXrM05DMCs~}K!N$`!ogc3{Wr!M%2zs^x!3IY()2*3(3{8$sU^-T^m zurtvI^?GAKji68o4vP6L;v|BAkMK}}c>0rm?%($L!}RH%^n)|@(?W=)&ePGe2wY8{^a5GPw^ON&VwzX?#EyfG&h<^(1PhhQxsb z`9i=oCFEJnJUv~UW1*n_6XF51om&Fl1oRJxW&^~7 zvk3hB4_$Y@hGB5F8}s~;@%9RIIo>1Yk0cPFd$c1d2-Iu$Z9n*c!)Kd!)K<4I?A2A@%ADDyE{sZa6PxkN%=_7sohByjs z@bV7(z2Y&co1G0fe!-{!n7uH3uHb+}cn3_)p`YMRh6dSK1+Q0^4@qrlwhV_R#H-Xi za%zsi#wr?q%`Xh^9I!Por=kgr(mn^8#Mp4Fl4e!c_e=pi?U$97y`A)HmB&A8^I4;_ zy*mQ{Qn%ft1vvvYK@$sdDY;0rj@RKTB=LjiUi4;$OEu7gk9jp$x{?kh12oBdDo}PR zXQ$=#Q@@D`QD?a{Rsz^E;Vo_NvQXzvDmO;J>_oA`N=ge=XkgrR3Whq=4XfZ05UUJc z65J)aRUBYfx%1!y4P{{A6QmpqexFqy8gCvYwO*ARcw~<4OOG;P%d(Is4cnPMUR;yB zg{u7zW9Qf-SlDgb>ayKs+qThV+qP}nwr$(CZQHhQo!sOid6RQK?jP_ZYp*ru7%&?) zJv+|S@aK0eYd^Lrd9dt zea4&YVwKjOk_-SESH}J^+2rE&Jv^Q~BxJ48mM_f?@+mm+jN3Qx&^>P1<$Cm`&hm@s`A3k#jbD zj99bJ0n5$$StSM)V3j#hfeT%FR`+h7V@r^Q# zm21F9=UJ%t8lNG{TQ2WS9Nz{y1LpO&7a%@VaV6K`brt#0?fW66N0Dkn>E5TA9vKul5hBY~G%dK`DojR{Eso@Z2Fohsb@(rc%B{sQv&q zOvegs|DOi>ADoe~!nT=RLy*vB_Jx#Pm9oJeDy_wUqlCTJ#=R}K$}!>8CMiW_G3yCw zgCO$EPE;1K>Mx(T{|Z?4_Mn8x!M@B(;lwVne?fRM5=Q* zhbcC`q@XS#S!WMx+M=#XXBkGdE8H=4}Pt98| zE=G*kFlTOxyT`Ypc^ru#=*(Q&ZR$peFVFQgPdFfpTkuqwIL@y`FypNu3=K{@vL_kD zz61CB5Q^fwk`Q+PE+WPgs3^|>I^W$h}H;6;??jMPa`}oa!&dbbxyjX zK46$962@@s898GLv~#y?>p`>njaJSf^QYTSh=JETIWsRR#}{;a@rD?6-N_B!NFH9e z#hVuN{3=)0XYj3Sx9!ubgjWgX-UBI=YG7G`H+-X9Jt<-=*|)l)8sOE(7<;>6tN~NN z8TrB9i#5}no){~!1%=1iQG@%)rNgh6n)<3ah_4AF-Y1vR(?I63ILS1`W}GGBGZ9H7 z9{wV}FYdWKB@f%B1(C)oNk(H5ffJwTppo(A@;Hpwy7<#5I_nAy0{J+WO#j3@NdY|z zXi01vMme5vhAS!mh*pqC2Y*Qj#oQFw_>;;|xrG>8WyI3;h^}<5e04X*$j$>|ys)u_ zXbUb#BRqjZS@zcrl}`~T^Lo!neJ$BXiaPdJ?c+!-K4-xVPo2k=mY)s?&lljO0AfiT z82xtXk^}I(T6xEQWsDs89;%KtG(50S*>@0oaf`%8lQH5DWbQ5xjFy(!tW#4jST(5` z3IvkKKzTim?vImagtw1Z!L~v{BWNvSwXK3TuGv~jCh^1m;|*_A0{gfyUG^`Nz*~IF z`+>2E%TQUBW+suN^;}vcP(-HaR1VGiA1n}YiBfc?QCRc^UOR7orfrJA;o1supjn0k zGz!*c0U}c6`BBQVl9Uljb<;oIDnUHDb!@58vG(+Zq+^KF(h-<~Vs82pi{JJFe8DE2 zaH165OHC-Z)Qt-yidhgu}}foi|5$wIisLjB~_udq*~$GjuGGt#cY`;0hyU z0jBbKiZE9_;lhoXhnz%aY38r=uh&^MWFqNe7!a;u{!WlO%x@GsYYyNy2{&bc$bA}* z#IcY&qXvi|_B6~(hD(+ZG+>{Ve%xA&B_hT+&@naO+3Ua&H2M3k73G%T#yRQz#HCb; zcODym|DGT`l%6vmSHnEisnP;JLofu622AXNEzQwwWdQXj`m!kX?@%L@TwCm0y2FJRo<$J(hKXgky?F*_ib)(*oStyYC^$ETrpj7yth3wdAJUc~GgiGpu6 z2LvO-r3;?psvJ_>eYBkZ+%%wRaalw8ti=xOjjOJb3SH$vlN?^g!rg12vR(uv1`j^* zTONvfYy%!kt3HPt%y+ZBgd~(ALy`U+H)hHE`Rzm^F+*-DCX(}6H^6~LJurk|KQ76Y zP?#xYfioQAf;>!s3F$zvt@rt7etWlx3Jx~-kBB|3>u!2gZgD!2%NRG7X@ikWQ~%Q8 z_aW|ABD{4IP?~sF>*?-K4rIO2v9i6}6mG1k)6q_p;S_Cl(y zj}L+@f!yQdC}~4Pnk)JsOmL+-IoNyooe*xb?OZM~l-5%#MU4c=mK>qcZV z*7&hI61c9W-wr7D2^Z44a#`>rZg__;5*R2-!#Eu$bh+u)O&@i=51aYI1AhYzrWehi zLnW^@cT!Xi&9rhRYr^U{?GdDNX3u)by)S1{**oMMJoN!eRj8>SMj1pg*8Nq9g$WXe z1o`6R+LO*Rtg0+}>IR%-}K-uG1I7P$R-ntJH&R`MI8euZcqV zs5B7hp_Se+eQzMca8QW@42l#2oCB^cpvlklbQF;_JPk=|v_B-#jJhar?<|<+1Qg-m z0s2#7Wa$L zQFk<)1J5mF$J1LSwbMiZW1e;`T{!MF-5fTF))@_d{)Of2B{WIp-Cn3$_BV5~C$;no zY?}E{28T`9x-_LZb(3M#{ zjCvlQl9eX+x* zsN2yX!itiip&fp-xz17+CXojo?m{q%M`oKEt^o;FR!d!9e&^eJY8HZ#ah&|x18=Y@J1_U zrrT5=zDT10HU*r`OS;f3n+MlUT9W?qVubL?dO};Avu(=VSY-~baMG01w%&KV)Y%Wx z(5PkL+3$*wwTLIRWe4${*mK3*%yO&ATnotOef!x&+|*=49P6!Qb|xN%+1dAjSpgg| zi<(>H!_HiAyl*1)z?}7q4ou@u`yNPj1V^Vh&NN6DzxPQ8ea{waCnp|>nLwc7pua5l zMsAATL;%W+q^g!9>-mACa~yOD;Taf?vk2@)*|O2ONy$8w#Vc|8F%@dShq5>t+TMBj zeCg6o&7Y}aZGvnnX(+4d`|46a~0gCEp;J#cb0<5 zQlJAcN3<*WORfABjCJzi!%mS>aNoPR&b7^%AK!z#c%o{;B4Z#ZB^&sf=)Pt3!yI~U z2nk#fp&vYcBJLHeP9sb0uu6oeq`tFae@0!>2Wr8L_-?a>1rrZdjOtxLm$-<>=uTms zVf>ZClc)kHbzpZ_#M-ORhvb!dWOp!HPt(1Wm>dPTWkel9M|Ag<=1Yk>j&g65=xlQc z*zfZUmNL<2wnFKWuXlTGqa%wT*A#evYy>aeH*-bI$r^x{hG&Gb5Bnbg90 z+i1FY*Ns|V8gFv7g{q_dKceNS`Q4~>(r~LZw-x+tqdL==;Kqx6c><;fz#LMk$`{^ zd0M5|KH%Qc;)x=31Bk~RUh0&c&IWXKVi#gOsSS$5SYxB`F_(LTd9M}^Th=>Y}U<$#L)+o5E2;uu%Fc-YK&5A&mRm?T;52FrR6eF>8Qfk}3CA-?WUN+hKilbwUmY zb{U_TjjR(_91Y6^m2ZEbU4{dMar4PQq&i0i!*Pi@nr!5bmEB3eX{Oa;&=Y{AF~6X_YG{65Pk>u=%L01K~> zeZ({RyFX2%*j&84jF_lglR&$i9OZ< z-W^>e4c1B?>xWgmo>nUW*$xISI!>2xci&D7-8Kw!=Nsv9<5Np~3=5=EQ~D`nsy=ldK0_>a83Jph#Drk#8d%*F{2(mpE^;K`E7WUg+N; zCgutSi=%Ys)_ZT6L_x+gg;{@C2#*vSEfS8(AJSClcT(| z=dh7Cs^_%rr99qL92CA2n%>c0_u4ev?uBoXTD7|lEbQA8xL6J%QSv){7Z>6FUu2U6 zF3=}XdLI1lDXOPOPt2N_P?f>(IOZMu=R6B<`DEZ-DfTkKtN7H!Tb z^WjUo2;z_5dAk~7Dx@!G9V$p$XbGr%*aWrNfgpaMY|0f~F(229+VK<*wQxtwSCTK= zz7r6oxeB{ybRHqg6>K6x*MTLk|9Y&TI26^ec;zxqDY`cgo3~?rbL8kmvU>5~c){{Y zXBkz7%TVE-Yv@#8F>R>OuqfJT@ zDZKYS@HLLZBUmlMNE+LsTLmy4y*7M+jAoTB?-yRESZuBiX(xRFq&~7VEM$>8^B@sG zE4ikj82^CbQ5%AA**)yN{k8ZyJqe_KE@pl3iwiCgK9o-jq7FMoRjNO5!TYl=$ zso@^)55z++N75Xa-tJK6LVSr{Ce)x(>I#B0N@4>{_GN!cC|;h8xZBifpQEvUZdj3l z!Nua@nYYgYcV+dX*q_&+llCS5WYf2|zgJ28LJZN`{w>I+sKGu2#j0n{aHZ&X-lI7- zY0YoRY0tG0xZ+=Fn5WcjH&M36OF#TkrRWT#fdxq=l2%lay(A_1)Cuje@a`N4%PXkK zjs1D?#e+b%Bm{95NQa>6$oDxWs!h-J9i zGCLL~dk>B!l=1^I529w=nR)#3@>*hmfIX{k zq+Zre7-s68sT{t?dc?VL*G^1M>EFoBr0*$`4nlQ z!(my;)x9~x>!Sj2cp}kP%8ka0u8aGPgY;_Ea-8yvF#s*JFMM%S~ghq zyWY3-3;2Ju14zN%y-RN7&cF8>LKw)d(`)`?x;)10=KXt zrV)xG;t2vfg?q5+lftFAwM)%X!@Q50d=vMW2H4wdwUClF*%JtMs~pTWrp)@?=|9Qi z6Hkh&iI!Fd+TN6;9kcbrOg&wqI_|;xt=l&!k}2?JaBh9yM=Ah{2!rm@RX?;Gx0r5- zzAvnYBPrCa=rwB++%DX@SR8L?oowxF7FFS_GBoN3Ya19Fm}6jfq}b#?z+7y{xCPzv z%KW!0tFO})yl~B*1qL9dkG_aJ7=d=h-yG0k<_Se{6-H7t-3?N>W%fQmUe*c*L@T;S zCOtJVi14v(nDQC~tR`M*5ZHs+DO~(tg%lJ7TwVfIPt-o2sj$f*sU`jt=~|$#Q~~(U zj17-&m@r=BQx;k7R2T_{XyMfmy&!h&vAY2(UyBz6hQeQ{P_T!X7;Q8jy+NrVej!cD zqYQazLm8iUE^_hq-XknNQ-X4=XUn`Kn^Q&n6CM}l0-Bv{M!qXswvHPj_!T%dz@!TJ6 zw5VYw0*jo9Qyqf-<5#7m4-<<>oOB^7G*Jt6BNxn)<(M!ETX!tO9|tFpp!d7S^mWcG zv^5xOOp5w54r=-e1BpZfYtk8c!=peq$~8^(`T-}veo$e2u9fPo%btsnN~hwgR-8*N%^;h{ zpOkjJoci}8L6nSo1-qxw6G{9VBQ)e1PwuwzoawKVYDpx_BqvX3f$5mIRd-gVSbs1I zpNV8$CO_Tj-(tb{Dmbb~g-&Ubx5FTR-cES`G6asTN9~}zQbnH<8Ukrhm&z4>x9CxC zO*NGu?uIJ7z;EF+RTTsoz3!(b$0R*Gfjm{GC693Q8gnj4P@D6V8h2{&BfbamMT$Jq z(kmryP3Cv~Iu;-aPL=PtmT;2B&WATSNAya|@_{nVuyGPT(s<^BZ;v8k+_^z&4j6j+ z)%7ZAEy<|V+O$!%Bvb?{(kcxqxeL+)Mkw+-TJ>XnOm3y4e{l`Tem0v);sT6}^!pqa z?%!8UkFe{=5Bw=s9JsrpAH)6j1r62y+Gvku>D}~bA%r6+D%O}|%tJ;;24Q$ve^1<7 z*ejsX+M&@Nf6(0a!iCQlrC$kjC}w_RXx|pcNuhzcyqDb+a2}5GCf~DLU4Lw1Q!0ao zqE<1t_a@8mbzE0;pz~%5R^?L>ldprt0iXpJpPz6742nE~jGmj$DR4T)vigx>c+_~c&uYW_Ctci2`=LV5mN9&;)38iRN)bM!s`$gK%-5SPXfmIi z_62b{gc7C3K;CLD#D(!=89PSg`TY4bFhBNZ0Rf)8jReDm@U5A%=bufiwfPicK!i(% zEPHmdK$09t<`PpZNs0SFo8Ht+Y(GjQFE<8Bf`o`jB%j^DHor@8cAZC6!|asviCI3! zXVps&wHV&WOY4fdQz2X5rDx$1^Fkua-0 z2ywRy9k^*=6merQnrd()o001-%QQx_5nFkq#<5e0R76fV6sRlffg7I?%VP%^ro%b{ zao11r9K~BinyM7K3nULYApxCK+l?xaW{W*dzysSHkwjl5G_3t+_+c)p$vXxzVuZi- zBh-*0EQx8X6Y2JyW%mYw1 z{#Wo{g-P+&+ey_^XP;ZrvI|5wSI7H(Nui;QvF0#?)3@bWd&^9Aam%7 zSooO{F`kIWbkQgH0-^PQuMX7AF;MmN7GW9S=EZDuWmQxe9}4YCaS-!vU0(>gI_nC? zMVY;Cpc0Qw4HYNP^J>`0v+&ez$1!Uo5f%_0@X3_xThh;}_Bv#6-3-_CLDU`QJphN> zZj6wJ%)1R)*2|e{oV54kVE&?QYZ`t5nC22%5wam<%3Pr9yJG65qaTW=&=kIiz7g;*&cN+-Vs?3=nsdpq=AK-y`6DU?fw!{wnDU6@eJ1SfWBn4VLho*b4 zwBHt+E!_Eo`%wwEl{tz829X$t5Up)uv}+`kGfWUT^|^Q2s8q4u&&#MYT;-M>JED;K znmeE9hzk+SsonGf(PqRt=@|sdY$i!7vo|y)T#>$rX_B}hF4+5CE>joXz{4(BgiVx=ZtF~{uc3hOhY9776`xaMP+WC9kiD9AB0Ig1# zS|*}E5+g6chwHihfvUo_L6eR$Rx~i<6ju^pfhYw*o0$`MVvL6CW2AM6c+c5KGXv6m zh#`+jYfV9QB;HXK17;d9R0*zo)FN#z+cJaON{D07&1~~<4*Z>b!3_Ob11z5_FELMO z^~_xe4IiKlV=vk^@Sx^-d8~~xMzudZyW?)@&TH8sUXzK11|q<7@gd_T>PulkS`@aF z6LK1zXm}sx(iwudLtBpzYAUN%7rEt=z4`Cw!B20=we@N`r@rw6fNE8Om{C+M_0*jGS#i9dU@bZDu1MVE|AiiHpE{R+jmmh#&7$q z#I+k_ams5nFeZhR{P}?8x;_K){23GrHPt$>l?gfS^W3Egn6SJ&mKIB)c;PI#!H6Mm zqE}`1v=@}-6p{aIQwHR8D}(&2q}Az*NeWP_nh+F@6%jdi<(6pOJzPm3zBW}VmjErz zL3JEw@zO0c+diOjSsUZjYBoHxAFXzX^(ZBwzUS}Yhxx}TNgOLwkUOf(1#HR31eAy= z5rQG$WArlQQn=zm*3|F7Mg`?X!iF}2XnD_Ij80h?5`QAqeepMPoEs9``<9^(N~I*P zz%q?|Ynxv;mPhAB+!YV=ugB6&cS_2daldjIX=C`uJtu(6%=p-nMO$tw_h3W~`rO*A zK%HSC#b_*EDU0bh7F?NJPQUXgl23Xr8|Ma0w8?FX81#q-QM;5G!>h>-O7te9i9CSY zX#n}X9C@me)7ixN9oMqISgL2=ZL0>Pk$&q)i$0Q#Gqd6X;qRraY=qoyl-~Bf^z8T) z4((a~1Cvcm!BA5@ zgJo#PUS%7z%Ectpax|Fcl9}}-r+B7X6O;y)e6?+?r?66KlJPBlXqs7Ssy_ttMYcx9 zPB#CueS9KJ-bbHBP%@}Ez-TYTQe!{jxjQ%`FJ?>nQ+;9jtwmL>HN%Xu3R}H23e(a3 z&5@!=LsRFf!6GCgQZ*4Ly`eGM#G~x-9F(lT>O&8g$>sw zai}uyCidKsw3Pdvod-jq?}9)TB*2uul!@cpIBI*!Q!0lO&S4F%g#e8Q$5lQ;iuU@6 zJMbwBW#qk%JuQQ|WzSgF{YJr-4naK&X7}@CcOdinu6;QHMJSD0?m@cz9he1MIVFZ{ zMbBAwFyWZXQh z6P@hKgA-)u|M3rFht9JWMFWI=*ZBi!ElUR(K<+P>%0>;0m3w^+3=av7_OfOKcjtLO_F4Akqrp{UqWZ!O2LLWSM{~8GNOK{&6Krv!R@aHuav~2PMh%Y_RH!}|6KBxmf{#z_v zi4NiY4@CgG5pio2VE-CAqzHbP&r=DwLx2F?$o16Ei81ybxJ>JfPB1mJwZVr4IHn7# z_pfVf3A?=b^*69b@D0`wkPkq>XGf23rw6e37vRZ%_2Gx2=H?3U>k9c5#DL`X#fiTa zz>;2&?@O;)b`rOa7V+{ANbcrl-go!U#+^-sDj$F@P(UugvMeWB=4;M58k+gX$gpNN z<|LFZ=%B3(0Kn(dhli10UJ4B0_2HMy>&?ee3M&h}lJfBzD z)^EKwc3EKXK2PB9p0@wemIM zXSF8>glrKC5|n_2;al zwR`SD(P2z3(rNKN!J6&v*m`FJ&N-ov#Q+{oZU^flbl&N2QWZ9t$Hvw++(TiI7%_x1 zY?F}FP^v^38f!B|BLf6Fp`o);DF~QnCxSZh| zY)J#5)vOk!blFDWUw~T!2@lAeI4nh(adJCgCCZ@m_%)&XLRr&V$#9o6MnpVdMf6+- z7f5iY%3_Y73W&v5zj!A5ZY6jE2zV>DmAr|EJWiJrB=AZ#ZuUnN8hO(y7BREM<23WrmnrpTec5hq%Ru9j11WuB{3W3>rK&6L#SRgL{G+n>OiB}fEG_JlPF)MNF3)! zh+DJ3pBY&i4Oz~hr85r_QCT#`e%Wr?e5eE3686HR zXmyXX1aKq*l-;{5dLB?`Di!B+m^=1kqR@L+S7Ljh90=c zZ_e38yl)R*@vLiX+}-j>De^XFPx%hP?`s8<%GF?I{Se2*wf24rVVA z7ESEq%lFZBOV7+Ppqf+hvxFy4KfLXH!>X5I>^#AZHEJ|CDDtG5qZ4{L2* z%7M4gYU!^GlRbEYbb8;hFL7!M%Qkm)5e?fLgGLu&P|MOt=?&{l-gnJ!{WVFOfKS@= zl7}q(zk0);TrgoV>HOX(ViYREB%6|Q%Kzf__aus2TcKS*yK!_y>5O^yDdj3K-XZ06 zVIKDVZdZq|<0~5Nqb{knG^LcI9;eW^=Q-fx!R13s6Gdj^0;R{2W1O1?S#>A^d8pdl z2y<4pSx<;c^L9{Djs+3s))X>GzH2L)qpf%En;msWqvh-oSSDDd&b??2Bsgy_YY_Lp zK{7lm4A^I)f$W^x`pMqVT!`7i;4~dV&y7k$jq3#bTQ2KYCzZ>V`Kfm-*^~Pc6;kl; zAQm7Ef?p91r*PI=|2aN#;aj*?d-|0{5QGbzvcJ*6bi{NLvlS(bshv(+Tab#dZ*vJ# zO4p*F(8t4r1d9-fM47~RqJ9s8x!KbDeVxO;u@t=c$J3`i-wo-1T|;m)8r4|_jJ$YS z-Ek_nnTV*&6lcGy`nZS`{*eiap5XV~qKAv%HxKH~-T2L9<&8TmcPe{-+j#7wOdYak z@O1U;#A?#Y7ucH|1=V{+A=Mb>vdifJ{d;XP)76lbUY*R}TJJEwzl&dKk5lF8pT%T0 zc7ww}iRwDP;@Y50%hpDRT9$IW0R$td|SoYTFBanPL?@UV` z0ixX3NrI3KRg2Zw(`j&=5me(|H$wIabQn@7cwVlY3!%4)*N7#vHRIb9w3(EtPm5Hu zw|gAU<`I;{_oBQ8PR(i+=6fG0d6T?e0UW)RVkJL0s4CPw&se$RqRdj6eNS}V4mv)g* zQ$(Nt^OdVSjF-HJ0?zK=Dk{^z2%4tS^yioDZX154OERyx^jn#87=(ih;C2NUkq*HVWGEUQ3SOigO++UIU0n>% zHB7S$kKq;5YL>tE<>@y#3@9}YY%%Vw$PqE6Oo>AAhB0(h%YtFX-&2fmm&;BO8PN}d z*b3Ht^~3aeudtv6d*%jiV+hNdAx}?fcJ3k6#N6VT@1aUeQo;Z>U-90-hF&JuX4wo0 zV+P?DQ7Tx(Z{Apl5$Gx)N=yHgTnpZVXtCs*%k|q;Q{z>#AxdV@AXSBNkwA6@5ok8- zSR};n&^1^BKc&Knm%Y0om>wf?P$LJ;EVhyehA!SM4rUJm^U#-C(2+%;Lw8)PHJ6pHGcEn zT>8;!Bq#hYP2bNjsPeaq9)3VAjcp@W2WJ6Cv1#?V1T9ZxCY8FRS%hOp)=CdVUAZxD@i2C9nvm)l=QxBkfQ=w?fU>L`3Ej$%p z|Ph~3ODac z5LvGja#}4PcHHGKyHmEk^at@(p^mt$noo54v9Psvu~^4VW`b0-Ke#gD?r$R%nqv#i zRUuNoc1Ey`?ZhK^R`%ogaEs`R@dK=OrzFyo^{o*bF^9VT>ZS7%t6#W&Ic;O7OgCZc z-j$iaqO1Oa!fsUh9Oq5pJJ|;gWW8_UKU#G623o){Ro=C-Gw-!D;DgY+bU8{n&$0w+ zZvlg$9+Hq{S(OPN4m^X$$l|Cn0qKRPcd)%Q8$?Uq=jn))T}BU#q;fzsuiBGYySIAA z)ODieH9=Nm8B8$O;hHbGy2VcfB5yTPgI`!?|Xnwrz^1hG4eagJ< zv*x|kA_wzl)Y^C=L)LB{UfKkh`X^`^(zdKTI_$XFHrX7Xg$ZJ-pQ*JMjUna^1-!l{ z%OD1O`AmM+Cg8Wl3C7OWyGIhibnv!9ndU=X+Aw!oJ;sLHj zWd)+J8^V9yyY$HvA+Z8F*og`ZD_hbMK@tlrDZ8p__3wlQ0(fYVv^Xwas4aE*Y0$HJnD_q%D(Wn*U!k&3 zyg;to6w_C#P!OrxC4_vQ+HcBA-0e7DX@F;M&?Mx!V9hwR7y+ivk);2WQv71wgI8kZ z5c1T@C4~n|ZyVA`m->)OYxjuKa@=L~;%nwexmTm8D>=@&Ao}Y`m+e4JCfS6%18f4o z7{UeP+l)&v0Q{xFhSf6^V_cE^%vh^!5*9?*&ll2cI>2yr;>5uGhU8OQI6Mf>~^ z$lFkWx>B-U=UJ`y9bMN1Oiw>8j>hZQEb@0n4-dyB98(g@FZ4?mOs-E;jxaeBJ3FpZ zE`;->Xb;N`YZ{4Qn9%*>@5IP@Vs>^-+!E}~W)>$j&kC6y9nZEc;qhnm!c-{M0u}`J z%8>JSg-FNoMYYQVN5e4q=yq?HK1^7=U2ik`*RB4ZG}goyZ{d`_2Fz19O*iOCF8*D6 zvqkcu{|07RfCwA*$Om7!IkSce$hcV{@$sloF~y}nxY_MN&~U8RU({qNr} z8-y&y(tirAwiyFl%&R0BUxFUuBw)BAwH|dik^bF}GzHm+&$Ba?XR^6O|NfHlUWa>P zPHz`d@~@E`I*{8)Wwa4RiZt04a(MY2=2?ivwFoB+G2hzin55iK ztC^^driIt6+>|$@XJon*`*_I78X?Ih5dn<07VL$9d9kx>qA>idwU&;>d6iP0*!BGW=FzrTl8q$vzr)sFB742pRJ0uUDoN=1kC@n~NcA830T69~VW#a}9S zd48L=nKqo?l>k%s@r7IHdyzf4V+=BsJ#(0qDEOSRTXVQ^j&(zvPo>_*Bs)Gps8<9x zoZP-1#ZYzUeax^X&nnVu-=pvabp?%_F@mFOv&B~>;Kjfppl4~?L}1Tp_T z$CS^h*Ng)`o4?-2=qLyxT=95H#@g5vN#6&pr%Wi?49`ex0Jd&|Ji2aUFmyMXvW&+ z8Ns{hxHYTSjwnxe28iq;sj3TPWZv=|O5-~5SlsP8C`jbx2^QFCm8EMh2ivEe zj0L|?=Ia8OV27ERheevWBZ;f3nwN=G(78bf<|gbGWjAY0x7-droc(=({%_gtme==KO3P;%bx@Q9>W7DH=m(+B(mu7bmJAs{{s!PtqroHvHVZ68dY&TW6k+rnMkX8k?Dao5H5lbnz z05>&qb8pH%hnnhe9n^RJjwj+r=mnsmi4G z?fhHf6+>8`57+k%;V&Be4x3Zum5EFbM1-SzTHdL@9*I!pP6*Huclwj)erTR)37W-VCb|VY`@onc+ns0V7C9)~tXzUqh?bwfGk`|jTTXM%; z_Ki4o<|n(?j@l_tQ4sDS)d(Tblu1f8K!9y1^V$RVBlwHyhhV5Ue9Xauc+cK}_nD5D z=PFlfpvpe?T~BIR8{h1mQM?r%pzhE(Zo^4j1+A_>R(M%24lfrm0UjS(5@!vGoPBe= z)Fvs(w=wBVFON7S+gX{eIVnWwnyBdynTLAu6>*nn%uUvum$HX6mrfQ9|EOp)DWsoZ#xTz8N^KOv;aYYGQXm;zKb*kzy#;X(o z&k;8286e>EHnyOQWC&VQ5T8R(ZUT5?LxGh~wb}(87dtluij7r=-nh(7WYLR7#bwX; zAblb@j6_|1aeN7iz>l+g+%pJdYg)O6?4Sn=<&GLgmrsArpUf6fyKl%k%hhCh6I_2m z0_pm}rkkS^iq1iKiH3NOgr=u>B>3Ct_kzpZnPISrbrEsF*Lel)B=Dvch5x%Qf_rVb#PJ2oid7>@79z;WG-lEIr@Xh{JVijb2N_4ZF2$rqTi3 z`NfR-Zg!okP-A(R(uy3CdYGy#rY#ybzomj$OH{Hx7(j3l%7s37=EURWu4h0nw=`4joD*bHsV zvZq(mt7JehRs%!U4)QwvbeGi|R!l^AnKqpi*}gFUIY<$r)UeEyO7;}3Sxz2>22wGQ zk24;s<;(h8)q<*bJr1cd;9RBiO`WsSkQ8(&Cy!gCxJ=C$c0Od%WAkijam39eI6?v3paK?a6ZeN>3|yI}y_#+j!CSkY7u>hWPu` zO*WJIAjE{~#)rcd;q2i~zrXgUhgfVQ%qt7#QVIOKs)E!gIhJ*}%mwlzyfJ;A&7M6d zGb%`Uk{7JNzB~v(D7nO0iR6U3@nC+)9~R;{P&(^F*{qH1`Qh(hbNT|@16W_Thz{Z` zlwl~?>Rb#B5K# zC{6@Co;5o(|3l`HdviU8v&#>)3K_LC4P>rQK<~x&I;!n$ie9(mMxPn$QzCCaexpMW znuT>`j8Tyo$zSXu=%9YplzX9d3y={GNnBk=PlQzy_u{|~vW}7BN+(}hcmkPTdJ1bB zp>3^9cr_;)A$XvWDBl@n_rp8y$imz4Cocu+s_cKdIJ5nSi!%c=9n1f{I5W^Ou>Z%C zGXp&<)Bk3r{P(Do$Y&5)&9HTl@O_#-YQBSOl+7*fR+ib;4ngof?p8rt7pUv&YaBpe zf6z8=#*<9L@0apx>T=zhndK4>L80ROX`)|91Z1Lpt&5Sqf$aUEn%j@X>Fy+0ES()#8W3{YAA8tmK2#zKJ1`Milh~pp%GBeY7yxxf4ggGATDXIq zYXCXUT*lGKL7ZIEeRGgTAjb5xRlr5;Nj^T68lRxtzyAw0K+3j&V`1^|@L)Ev zb76LHwiKdc1bBd4tpI937of8{&>Zkr!2l%_JK#T+F(Xj{G^{`_|H#!HEL=TIoPhwa zz!qc%w08k}xY?TnodIBSfV!*#K-m#!|Btc4KL(6||MUjH#?1D=aR2fCD-g*3Z)X!T zGY30I6MHX^y(Pc`WD5i+ODQnBdb%0gI4+%PfJe04`QmRvums0MH2l^fa?# z`76AJmm~0RCEH(Oa0Pxojt-6h3vdxYKad3w{0GU$#l#&5aCLSA`uY5+_%}jgV*{9j z%v=GcKueH4((mYCG0@^43?9BS$P=K)3f?_70P9~r|9dh3ua~)ly{*@8^S|fIA}+2Z zEw97yPsRV!iHSLQ0(_V_SpiJ!T&w`Lzm|*#{NVTRFe)aX|D^GUudKa=1AzCRY{6~% zZ^rKbSpeGq90wiX-?5Y&z*`Fh(EeU>eO4}3Gw?6A|Ie%bx6A*(4gV|3|J#!P--M*x zY;FHm)Bdgh|52ORfo#40V*p-SH&^fhC^~@8!2bW5Y6Jf{T1B8a$j$EmYGqwbz=t4e zZ)y9#HiBHFK%PKz6_Bf$)j!+vk6iPwE3*aJ163ScK!3ef08HS~{2v|ow9IV4uMQXR zO8%_^f-mRal#=#l4(5NI7&{j?z{J_v#0v>LWH90a_^^R*(H!Xc_YwnGnC%^0!7c!B zd42#32WOA`K{&!ut@$7@vs6|q<$l? zwe)Yq0br5+jld)dzY!0BMe#QRQ!4$Y1jkgi16uy(dc0^ufJNgs0vD$F z8-ZE0|A%u*cxc-)N{7?SRO8-v*ZiCrx1Wv*XE?VR=+3kmxYrX z_-KARu>)8venT*cg$3x3AYl9(a&i0x-G7sC{iSzsbN(Y9*u?S=2oCt0pA+0;D=$YY zp#2{fVA&sptl(i={{g|BxA_Bt+wy1f;8xoGhJTI!cVsTGt3CK8{?LQVclezQ*xBJ< zYH%@*zt!Mij^Iz7{lBKl$@U-Vzh}w`&e{?Da&q`R4o+|*9BtiP{)i8jIQR2RF#o!{HAHaKqjHfZ$oV{{g{yc>J+gVDCT3*umkw z{(#`-c>iuCIFdKe`5&r(z0J(roWZkj{rh_Z-u3_DzyEsx0zH9dNGppDX8fVnb)g;i zHKIfwOb3&Kb5sY~sdP*}E6$y6k7)48bk&)`Th6zl$s@gQ*7qc7Z$wr}pMAcyHo$*u zOH^(D<@;n5uQqegjCg?h!N;9FFn!cZ*J!> zbEaNN<>DET{LZ2|ihOjp*<&6Syf-Q|*j>5_C<%1&iJ@;W$7iU0#Ew(s@Roc^iq;30 zJzE8eNOMpbKd&>rVLoQhs0OJ;+Bf&rx{t4PvF+z3143zt2C?=NYfGE4jhxAqajM&m zBC%X+Ic$K$$6Xd;8y&Y=Jr>rV->&k`*1rPgQFW}o1-A6~{AzI87#SU8x(oZXr z?H01K>b`^RgB*W*&Xw!?BgU_?@lvU4dmdxS)&tWZDBb>=gZ4N0xJ$lqA6NY9FRW| z_~^T0uq;v3M^FX?P7YRVp~*8DKw&9O=B7ds1NQ4;Vz%|Jcb3Q_X>5yNm5YAeCiacM zhjKyvZXHO0y_j=tzLFI z#?QT?06MZLix2OE5zLM;A`u|=1QuwphwEZfeyCxoa7gBng);HgV$fi0zf6mw$)Q&> z!>;t#iOWqw$hnq5Q1|)pz{PRbB2ffsP4`WAe_L3TSs+Thj$|nvMUz^x^dOhwN{aRP zp&m}@Tm2g3peitVH2E1BdB)hkNg#`ajkVMlA?;P5{lxB~q4{Asb92P%ax*t{tMVie zp|P>1CPR3Hz*zX2C*>P1ve9@htX^{0^*c`$0Zz6B;%h6+pYu%L9@1{v4Nx|un@TQ7W)#TS1w5-R;Ir;9-Swzfk~Wlnc8y$qu}*|z+e zi~8y(oWVo0NJ7>v;_@p+xd+7@9oCBRSa%=pE&QZK{rf%ulyi>LNIE$Of#4l{OOXrq$jb@8re_(iq(w{1q$M`|-Uu-4fDr zKhAU0r?=A=qYm_=KJ0~&)^VzCBB8PAO`)pb)QNv<_BDFss zzmu^h^yuU{ct22nf0(`-3Z&|<{5ms&$|Y*_T!SH=XOrLsXQxSK85;lP3#i@T|Z$raB|?fONUwHLxF@e3>M)=jBc zS5jf=AC1$$!T0ASZY8o<-1KGHc2cQGvgh%UXo=FPiz%=i3Y6iVb77T*Z~HC#u)J;_)kYV0mt>VdtHRYc?r@h%(!^JeDj7sUM_CO&ne%6lr^A=!%L< z)6xUF&l`Hsb``H}-cwOh0dR*~X6AOgm` zi=fRf7iyTeEx1LU?NZT0&}E$}Sm9SYp8DtZhE^QRBVN!BPXw$|QvL>hwVfb$32% zkUZdp04JRVga}%hbwf1GChQeQdNQ-5nh2khW z#jM9!puWs*>XF1?25>DcJXZn|;#<9y7_Zwv9w1L6Bk|ua=V#z?)Gze#B*4_!l}0k$ z;F7GGSU*n0!F-!zwBDK`-FUZic@juVB8p<$j5Tx4X1xB+jrrP*;e2m}{P9|d|B^Al zd!%883dy0pdMnoxdYCoUB^YCIm;h6oP0DlXeE#_J7QphwE)k}W#%FjcO~y2rfrly&PU4E zK<3Wz7j&P_C)x%{J<`Gv?Q92e?T+;Z1)=9qAcIQYx6^?4+q*RfEN@xG>3`R%*Wm#M&`3wg~$DIoA z67QLAvJh9aX3~FhMXL`;>8BfDHHv?GTb)0~H z9kt7EQHmn(mUTX=JpM$Ql!DZh%s;z+iMpJV59wY&mx-dOYZQXiRTY^;mtEO*r7GBe zP08%mE1~1*r|x>nwVJfgLa8M<(V>}NGwE&8==(wQ-Z@}?D~-k8$UYfbP9YB$8G$xM z1gY*QcWgQxsj^Xt*hgNfack|;&?dulv)BIAANRYlLUn-w!kS5;W*%hgfX`Dnru*)N z!q$4*VLoT#PqtLb04!%a(bsdAWbEF->nnTREol0*cEQrSQJ0%bhYV~}5ubRkMPvjr zadFZ}A3QSzX6*porn3u@LsmR{(eR z0ogl(g+e=|l(moemL4l)@JI;vJO@&UIwD@`2L3-jbMlYRKsi?p08nFM8IRkv{#}x5(Sj}VzDm#usyJnN9MO_oOJ$8f?E4+;BeXg zqU!rrN;sLVFGuL(uCj%d9f$$L3(PAzZ-0m^+vAiwr@S%xd1k*J)Qf=HrTnz#Dyjs_ zq=0Il68Tve)@T#g(CEXOC3Zrie>U!5EPu2yNzL^45_z$Yo0r_c{-&OF((3pYB%!2Z z+pnsQ@nMAJ`2llu-C<2x4~<1vEYbY%>I5_>hOIYz`>rr@wbml1*q-I}A(FJL(xd#7 zZ8&SHPEawWLrFFoG_9A}Z}_tX;+%-=m-pR*Tx}J^*%IIP1Gpv#KO;HCFZDak76l3K zM^1aQiK{bozb#N<>+>f8jzFoiPat!Y%cUr;j)o@N(*Brhq(mTT1CFR3u-G{&amn*Q zYCi)beChhumN!izWKt@(bzA4EIo+Z){k{(LANBn#fy34W%#e+x=p>(=LOhVoL&_q| z>l~EKI-Qek&v5#csXmxtAx;k&l=5y7mZ9hMCN;QSR(Q10l6)=v@VrE~;JHxnn zs989FPu2`VL|ukDMc@^-BjFqd=xz`34l5{2D)_Dbo>pxc$H28or6`$~SH~XTk2wbH zY%{U~&r8^pVACnZm&H#zEEawoTPYde#)^mb$fZkDFe;B|EEHX4;O9x-YimCHJ>51o zx9IdYMjIjr&M#3}PYjXCbX`O$%e*3tOvI2HJv2q~AAhWyyb6flm1}X&L#qoiSf@au zT!Ak`U!xJX5)R@@69`queV@E>qsg%$a?rBXH)R`WNDrxMtG;s*xSH1tXE!<&; zEthbQ%QVLkdPfY}Tapo3j|;Mx3VF6^QDgp=ar5j>6F6kYj7c-0zSk?!KE7h>^+bx# zlZcy-qI0t-USBz2chYFsR4whsWh9*ef8V&mR{RUyl_hE(`DHtLeD@M*oAXmGTcv%t z(Ju)hKSwx*LyIy?UMouC$C3d^1Ca~G2jgYK*;Z-!TYj!`xI&MiZ|yMqvd&Hyq9q&_ zqQP4_7$CQbz}}7hzN^lei?dlw9p^VE#1c2Re6i81<|OcHMbI07L{V1^ly6LBag5k> zyKN?Ag(GcNyHmV+^IzOv5!8?HdF2xbLNWR^c}5aB4TThV z!N}64ymnZ>;ZpcgCfjY+=;v!i(oGrfEwPKGIn^8I(XJEC(D_`U%Qty()IU`?kjeJ- zs?j!J1=vkA1ZnJcF9JpA3sZ4MinF*Le%z2gXt>Hvbk36PHS^2ZG#|8TTVdT&@9W6qQOro8mZNvyNgbIKW~he?enDTz8w&x98%n5pjZ^Z^ zH@=RzlnJ-FkF^gP>OXy=PrzAxRvq0bQ8Kmoz_8ZQwHcc2K#mx_@;0qGMoU@6G}I$~2h_0T?JKA7dv=4~IL;E8^ojh8rK@zqo@plq zphI0|s^<4=f0VnTgoJ4xp)R;=Qn+o%(o*Ww&<8Ve3uzTKfL`(Npi5HW z9V$`kDuTjs2gFRz$T?PA77?!Ww+vMV6&5@Q##Tk>SWzv%_T^iznr8l;PPE9RjVH?Hft+KA~~wW2m$Uy5`~=Zdqh~(zMW{ z^;@AQz7Z{>Ur-}L3&p(jvaEi%bB+4sKFc@=7aW?a-h)3z-1en1EuhC&3P0SaY?X}C zNydf0Ll1t^EXsWJpsTvH#EKZhahm7bHn*lIYOP+!3AciG8bU70>~L{FWoi{kK$3@+ z=84@Suk=-&{s?tg_ILo$z4CVP{SfR|(66x2ppF$$#208$wqV!srB{^WB6jgo9htpf zkRX0huim_QIq^v@Q-8f4m!$IT6|ULYDt_S81G+EVm}{3c+st5w=#leF1Wr}=Ow|j) zxSV@0qdciEB;r-WhpA+(&A7Nsq|~Pj)zAjL^-TfIp7(rjVS-oJgv}UkskUnozbmz` zi>Y(*hTVts)I&y>Ws~6W(g1SLt?T9KyrKQkJ(GQFuAz>BXkvwwMx_C1`mFxQW;)iw?*h6)O7VREXy%wxI0O~gsn@Jfl3e!1O zBvOCr2V_b9m@<;#G#I7Nvr-*6-9Puu9qu2j1|*ifAjO+yI8^O-50J(K_Zi30tn_fj zsZkM|267-kIleD1*T9no7eOv*Lh=3z7yecTb3|gckHa@Q`LH^e{4B+@urhBA=gpdj z?W~f5V9=@H5>a2t8;H+vmCw304o3pCpG%kR$bqGz5)){dz}2SpdNw?51@V%SX{WY8 zjZRM)mN-#J`XxxW9qCFF`&3$`;9X=f_v3GDd8zv54QRxoUuSE{p?-0?C=O^}iY z+wN9J*QwE-ivuHT?0OWv8sv$AQ&G&V0rP;@)@J9=x7iSu&!b*^B-w1#4x1DVH(ehb z*2L>nAth#5R zZ(U&L^3`Hz`M62OhcVQ!lBAhVLD|e}$i2ZeS!sxVF$ZHUNcGSVXZO*c4w|ej*up3g zlq6D(4=oK?inOT**gYOOMumwLi!rD0&nU!yxhoOE7A`7Jm%Ew~a#6rQQpmH(5bMSjqU$5zXZXQz$-Xe0DaV=HEbPW?Qp;C3W_j2hZOgt#qB+)~_)Q-t49GA=C!jA)H8$N~4Pu-kBX(l_b`)^{d9 zd9r&bXg9M#>`1ec&O&wHcwBch?u)w9R_T!vUtVwuEs{|rsu*SwziS=Yx_s>$%34qa(xatI4$9Meu6MMD4%Sv)=Q9pzF) z+yU~rQ7qz!6xK!)%qL{MfNYVcoMc9TI=i*>Oc}dB@QSm>(n5OzygCW-JUH+MnEa4 zsT#VFmwLg@F=tM<>&;kNXV2%pE|xQC^-W(n;oZ7^T&ucZ;y!ab>ZY*6g9 zrUrQ3qiW5#HeDZ{EGW~+i`-bO@CCl1pnlSJNoG-aZd>r5;HMshzsOU#)g`|P@k`5v z95YqiR^T*kg^a^bsOH(YP~ef6OCKIOz_z#>0!foG$0&O;!=jJDhpZOV4U@+M;nq-Yk+m}I z22*4g8NVZJN`1OGt;pN%p-wncoEA+I=6H3~jAy!>F4IkWQ|cuBlOFB+Xdohm6bXWZ zc)Hfs6GYUgD4ed{$NmZ}M~vX5__zAb!B3PJ#9b}0ak?~({x+ydCc$QPz}I8(Zd-iQ z>>tkwceKV}Wbm^`Fr_7DE9FZ>jXVX(7xAK1lf`l2uNN>3KOr9#)~@-iG|p+CiCEMc z-(`JDE=b#&8)SqbWAiaTek>7Q#EVvRie&c~&cuDc)e+uY(;QJZhfK8s@xpwJyPx-s zgWu({TDYBec;lfP${Lm@G-drX@CcD}@@mqh4@8Od9^Y@?ce7tIZ<9LW{3U;p$+)ie zJwn@b?!LlKjG1aclRbx!cQu0XOLSqXx)V+FxF@l-J3fB?8u`yLSjWyFcCt{HADutf zCiqxV^S!Ae~gb`clq@=w$c;&-+|M|c#r}!SPtK39E1NMa?2|~}%r({45TY0u{ z?it;^&pQ>Mg|@&}!7sYnY~8Qfd)zJC zgy>wYT70`e@9$6+vmMPy5&V!ogtlJ~Gn&vZkfh{J*Vdm|dvt*P9wQ=(t78N15dpd;;Y0e$90aI%$Z{vUG4a8tyR z+ahk_+`q=!kG#G7YVZ|?k33KNUgC7py=&@dMk%$RfKZnNdgtE$eeBXIob8za8@t3P zek_dXY@dsU2cMi-dsZI%X)7Dfiz-}3S@|-uo;}b=h*AVS&sYC2F**p zcCD|llV1h^znUzq8ap#+PGG3VTZ-Q`O`@(U7k=7Z!!GUpZvCS*Q9j$=B3YV~%!L2E zwLrxpPW~Dv4nyQin}96@LL+15Qq?i_S~k#;wn6n`D_`}bU*;Syu!zU#m+d1C4CKA} z(a9spix<>*!{c-4H@#oQNZ1r+Oy--3Ig5+w8|Cn5tF7v7!{iaqkbYE(#X{`w%0+D? z+;0!4>aj3GbbRg*Q6$ZskS->cirz}?9S1qe;EnYOf#glZ)clbYQaEetKVPQS3ttVC z-U*^|Y#oi+5k1;4y}|h)r&z$8k-86?>~Go6J~zmND+-%c4ZX_1a*@wa1QKuFDirXG zdTYvH5{WcPVz_tq*-1{_>0NmdRJZcPFDhNX&^~m^XrhaP=sQmxDyh?2jji79*r<$s zTlRrZbRgqs|SM#T#ElQf>g`^ne%0dibpGp;fXCuwro4 zqSX1qt&54qo_7x{C7LX2@eA`mQr$gQMNyaqAjO?a7+)?LR#U&A;{1$aF^RI=Btc^)4;k?pYlbXP+|GApEl!I9;+M%EP48{jF_JhO~t9O~5z zH+(Ak3uYG;ZZ1&i`zL@;+f{}g@#&`3!Pbb}VGJK$N=@A-y!kmAxFOvO5p%%20iT>= z=Co+KlJC5sv0ksuWCzWi2_^ErJFeJwv=Y#B(w?$mKM%UF)4{52ipMI%ub7kIi^w?O z#z6F|9>+Xo(`^TaaEMf(ugd&;)gLZBITiB8cXZX)dHaFq^AII`LdLcgk???Qeb08~ zH))$c=&&h4*#U4X<+SZSok`{G9B1$ zyV9q_Az8YC?_cI?7J!@Vhtdi|8}Ntm6V&2g-44%Hb(N+}T_z9epBiL?NhR!fly!zu zMvbh8_=Svg-T~;aV}xpV&EBwvb|EH2%#+lAuFbnOUhkonKj7VJ`gr@fv2}ao2I{ty z`hW{5|qlFv($jB!T1Juonl>xHhM&ofzTWa_`(ilsQl&HTkXs< zcql&cl?CyJRMEN7LR*VHKj<3TB5W+c`FD!zMpr*;)jb~c8M0W>pZEBRo|Sh^BoBOO zD5u48zbabGW~8%se2cNdyyh!`@0w>*>woTTyS@7y`gIIZj9isf7V*dJjJT^@UHjfQ zaf1va`_IfI%^RotE5c{+9)6o(xSp#@8+v}?PT1+f$n`p}vSTi{eG3gBmPOs{ZUn!vo zzR*v%HekdixCxs=dnDYK-rdx5HFu;;c$Ee*K2=HRpzcJWmhEA~_ZT)oAtO2lA8{43 zHcgrBl?3p6wq?U1I85MHgsRPrAz(=CGVghN3;lP3~~%DoNXoCZ~&dXeu4KMGb# z-yvyq>q|LX0EOO8JcYMR+VDhTIP5_e;Vf3yBNtlEynK+0A{^DVo;`ezsfT^k(Av8u zPeiYp5PU>Ypgdnc^}}@{n29~kTP-B%LWimZhwrSSoEH-xUv+s@hNo>tB$gXViwB_T zG7_FMV)soJwKwWXkHnL3oGd{!&V7O3Z*f)7pJ7@PST3)&2Q1?IZb|Bm_*KxY<4pB4 zSr}KCb9PoiGc0O%Z;O-*kM9TJEa!2x=f!2^6{ZRKq^qwc@9u>AhQ+y9@z%%`X`uq( zi!8)IB_g)dE}Qiv@Yrr;D)Ala!7yg&UvN(hqV}?0Xe=CS5$R<Ktmkhod4taB>aGXg76e=%Zea4t; z^HuAP0bud=Aeqa|6LUtqzAYcKA16WYG1E>TY+7>REt7x-p%HS~a}RD{F=`UFZ+y%3 ztW7*kqeut2ag!CI3+LKg0+Q9KMU+xx8hHmfYfDnE9d3AiUCqFma7TbfzkQ4VU2e zw9wEvA#tlzklcttGRjL(*KHYG_aiGaDrt%VddBVzJIfL-D(f%h(G)-PFz3!^O_J7+ z7J3NT@l>uPlsig7u67C`A+}bO?tr{Hepv2^cD5&da+Ldexkeltc-$C)cG>3UD7nvw z7TRq|kE9#zjlPa_$BS|_{6g|bY|xgikaXVS5=k=kY556MEaVv@Rjm&%X<9$z*XG?{ z<0QlE_`c2rl|f5|WWFlJua3 zHU6YW|99bZ3`?jAC3l&+yD$ib0nUjJDm_whXr;AkK3kP5Re7G- zDhnoYtOUU&a?H=4LKS*5I3f&*dS)a!b_%!vthfWvL$7a#nt{56iet{E$6u$fyh0sE z*7`O0+ngB-?a6NavOnLpSS>6~LOxFA+}cT}e4ob4?<|ywr%(rJ*Lp9@qlhYsZm|ZZ zm&fB3vaJY=nKslk4Ub=IYJ4paJ#y%qRL9V0NKu@in(qRLkGW;ZGTc5207&Ub1an+t zoNGV}~(rwirNx;W;^ku)P)-a8BLOe-&U0a3i;aJL(aD9Wpy86JXJhPZ6h zJ$#u}eP)Ul+!kMV*bAg#Ha0YMj*w$MH*V|cSXc5x@ZZCJYG|uq_0o_~QI}vFL=#z{ z-{v=sgQZqibdi?GhCV(qCos#UX`ewfv$jgnWE1KR>oFavRrPke>9gTWulS1bcs3ZB zkc`uZx2kih*E$^79x9hI_&om&xGeehm86a~JKPB`o%TWU>F7n8_{<6KVV zoh4AoUk#HXRNS1~`A(uFuV;fjmjcREq)V~rT|I%?j^eUmH!1UMq;%*7|Ni~lOV7r- z5v*&~7Q*Z|)=)(YUhl&hix+?dOiCO*Zb7o`DcbDvf;?%?3I5MXbi~v+#$XUivpsG& z+DGB&S;!G(53Ih{EGb z)Ivu2k;4zeoGFwNy;EjYCh)YUBm#7F;&e5%*EJm_2SIdH8sJWryKdk4%M2x9kn=5M zvPOYN_n2L_q;9)aswLYo^hJ@KyQ$12c0JQ*BeU^dvto4NbXV%d^Zj@wS-d4=ZK`AW z&axT<$n|cvzr%$+CznZ3P$FmDY;-b?jaflp$D+Wb8=;ryT^R$heAMjLna_}9Lw@;J6e>h>vQ|`@TjY9dApqv$g%ke-LBz#!IW%!GA){Y0(#3;mDH~Nonj}sUg z1!cv=sW5HJ$Io`SizN3=BAnvdu8KpFPQKPzza53&gc4!#^L32$2SqG)Q@@Dco6>s?~|VTCzS?mBfZ_3Bo?}wAEPJc%w23 zg-l9!*e2{!{(bn~-oyU#)Ba{T`$;}2?>qKWTbmX9D2O|NYCS|5=v_od0Gvg@X+xLx zqT&ESo-#@U?!9;Q=U!N+#mmluW{QeaLA$gs7r^+r1oQ93*x9x+OfNZFFh%BjvuiU? zv9leGZV#eRE``2K5)ed>0x|72Wfg43Y8+^ha}BFYFNxCJF6UN6Y3>hhjr5$J$u$?n z`{ds#Cg#v*iRM5kb)**?i_vGlboXH!xVqHMqvomVllzr5f8oV4F?J|eO>=E|H+;-H za|w#F<6X9K41%~&;qga4H0;)QlA%>DhZ!zlw|_2f{WY#0s3#cgR48X3jXW;k!uOe% zG!b1dad_<^2KMbQ>q5sOE|-F+T4(xGfKsh+p+1kgQB>s|DPx(Wo_B5afKH~b-%jiE zLXC^OM~}G2BRxm=H__Tge@;st%uRLA46+nL34Pgz_twKz{GkU6zXbAL(cN|u$*0|- zf|Z+yFtalQJ&Bkj&PB!d*OZ3FD=$V%YdnAEbq5jjA_Xa1EryYJl6U(|B=d!gZ;g!X zuv@)E4|PqxG6gfa&vv1_%%+a3p=pVkxYx6Phw*2E=%jJOjN?9O{WMln=2uZX4`Dft z2j~6_VJkc#6q%};ERx6VcnBHyT5V$-UFKa!v89VJrh@ggup|JV5}_n;Lp*PFr_&uP zw9)?Mdw=@)dgf=ArdKTExr#MkJxJbF(kg6e9wX3_`g~p`^SJp)vDz99nn^v2#TJ{m zjZs~e1$qFJPi?d^YwlXQ9J<*m@u;o^InNN=SObYv@ogiLDVLsn(MB9RnsstX0YWer zk&^uaPx`@EX1c$}Zu$QR-Pik@gf{D+so`S_16p$by$Q$-roR3vw1_F>91(&9S^y8CQx{0|>8HhxB|7s-D;xI~R<;FMINJlcHyr*_q0SJ}$+sG= zjC*Z%2okd7rEj-sr|0+7`A`wiQMczzhjK$&(-+|b#4pei83-bX7MiBfEE|Y>2sk^5 zNl9-?(Tu7F9Qc2gT_?-ZUFpzN9mn2=gbC$S%dT3yN5s)3sKgw!GSc54)~$&N!E$xS zxxM_ZF_feY$h%F`y3=I46g9z{F(iX7LEqIF7j+9`ZhbB;JemFk8#eb&{w$V`>0QM4=FCxxwasB+s7FM-J*+tzm2&`*`q66SK(>p2lrP?@p{zVti3& z0DeZSh#exXXE^cVq9tqB_tU|;V;aE6puFWD+>F;=yCZ9Jc+k7l#w-3O5Fsw5ZjRc% zCF^iJQ~D_*7Rr3K_(Qnq^dIZor-vLqko`iFu}`PrK;lm_zoHd7Q&NP_fGYBv@IW$z z9gbUkM}k~7b=#{sZM>U9F}kshU4uH5m~MltRbhYbZ%XKj zSvR*56NjqBbt=f|&8KMhMBj6ZfP^;PD6E*aILD{(M8VZs=vPWdtBVW)J-6;zf=PP6 z%Yh3`hx&sg8~U&kwk+H+DGEM))OUi=WK%f9QVaoe?_U*PT_`OeONKkP3giPhj9W3_ zx!Xht&f?zUSiy_efy&`%RwfN;*tyz_SnD;uDD(w8 z{p*mcZ@ztSD#T>4UD!|A054RgmWN>+*r^VdPt1e-D4H)WX-*aAXOD?Q4RsYt#mU-R zW0RT{i59K$UQ*%_h?QI*q0^yj$ENv}>>!5Om^ZQkecN$g*2pJRLtdpN?VqZJZ%!by zA8V~L(T`g34$#W~MfZSl zcOELachOs9#e4T6mEiu(G1jYW6E;Tar90OY+kZ zjt8P2JsC_O{n=Kvzo)nvF`9`Z4C ztjC3+ug*vQQlq6z7S`HF5;GpWFOZ%jji2iskIEMPBXeB1JAr5}7!K%=LMV zy&*H7it7A<@h}N5R!Y!w?($TAm(s?XM{xT3e5pZBh@7Q#lApww*-ReE6M6I+j)c5t zdUmGvM?|6!PC&7XmaVvZO!K<66kd!8*_A>YHsW5haUBj@oow2D$1-V7+&vOuCmdZk zUEUHL3esFypOVhAav)Dd$%-lKadE@&tL`@$g2Yw1ro7qE844T7_=%WBi*PhYo!wXn z4BdX1fi9`(Jm&8P>gLvtnnpVnoDd-K~{7-8&7!5WI-+ zRT0alo%G;BKW~ZqaZ&$#!<2LZcwdpvy8BtKtRH7^yPYbEHqH&9(9?Dr_vw zmx*5^A+p>FlmtHNFF&YE{b;c81{~XLYE6dQp!$gr41;yu zg`zsr;e*dNp(0^vbDWK6DDZQ`_FCm<0XSL+Wil12@^q*BnCx0cY5FiXMm_Mqd^!cj zswsz}d+hWK(*zBQ$Md6>@?APNab#Y%GCUY@Qr?gx!=iQ#*iLvkTqb+r$);pg^E*$u zAL0wE-^*Tf!gHgJosh$51hwnF%-ka|I&Ze-LAn$7&JXYru;1WD=?ZIv!pBuS!rl|8 zCVa@%xH;7bOP27siL}k4=MXwB1yvoJaemluLiyBRIqCR1RbxjZDhla^{N~HfCRJ@G zL<;-GPbIiREmQmf)E1*WP?*PNnB0x|rnXV$vF-yYcO2vW`MC?kxa&!;F*5Yn8~2TZ zOKUgmuR}wyw0%D>FHcJdp;i4srwzSEN`!_Tc>(4+8JfxyFS(u^uLm!CAvYD5HN1US ziocpS3a$^d2_CP|jSpt@21k_9`LjMc7EmUK^d>^{&LJ@5qr9PHA+Gq?3S%1Z$*!Hf zgElEcwvj0J8zN{|E6bgy8I&76E1A7=`Qw0q(I3}mqyb#3q|B&npqW_&Id*T>)y=IiOt&a<+K1tnL*m9<6fRsJpdc` zEZbgvP7T7Li$46^6f4-`@^qi%GIoJnMR3RCgk=9Y44SJ z7DR$j$?7c?`T;@$H-6dxH-1};r~0ff%>am@y4Bagjh~XmM=utQ_*g0q@A!OgQGR?M zTWOqwq?(5lu;4%DzjyAmM~`NDUZGZlp%+X2f{o;TxRfhgeHcD$aKUi!s^dwaloCTD zu(T*gOQ~Ny?A2JE67~S0lji~*vS_s_-KG;wUx&F#oypvIl_VKZ6L$X zU)p4tyT;8)-bq|%LsLAVL_*{=jn?^Y5kt>M9V8su!sRmNG}+2j<*?*B!5}wC04qID zplj*^-cq<3rh!4SvcpAojEI+#Y=k#d(fGzPUWvl{ul;^cu5FCp=omx0qrTGBB;#C? z>+3_icc3or?6M{Hgvuy~YO9mR zRoD?4J5~PTOk$kOhjw29EG6a#4RqQZxa^XSw+>Yo#VCe3HjkSdon(j>9<39Z7k!B> z!-osC!%(j%cYvpp1l+EU%48HZBng(07Pm7HeF{piwjB@^`9e^a*N8m{_cq~s5~1nf z+uXFU7ZO=j8AY@9#d`BwoPk(ijyY?w#QS*_gpiz#S1G=e1M19cD@rx*xW#_WFM)f8 z7<+=Po)k+T3w~tf56@-|`P&wd;BrK^2{;_*p%H~D8H;CUlcRIl26W}es1#ErWnvyl8}&Fx zE6ONbLZNC1`8(ttlU(n*0IMYNO>EmvzB6^I&Z&K|tN#D8`=T$qSM_?=^AI_?{J9sl z7`?Y;Z5iD=u8jB3$$Pp>mN@EI+(u)hn=i$~WQPw9)N>`GS)i<;)L~7$@>Am&nA>`V z6-0Wb0>Ykp1qs$|U`-Z`gnx{z+LzQ14T3Q@Z{ zfELGrIeu)s-GLa0k;QG##S0~{ap#TyI7J8rEjIb`FwD*;O*rX)dtFZ?I?q?&#Zg{e8kBebODh8OVn$ zhCc0+O%W(q|K+S1VW=qmr6Yl~$6$u@E9xaib73m=Wqo8U9 z3XRO~U>)Bv_oL3i**1eYshky+dQ~u?Ay|*T{k!kmjw3Hqt?@m(xa^f!k8C!+#J+1@ zT=F14O|lAwyk zne*rglD{h?*uG^mbpSuAtK*Y|>+je-4(PnQ@IbrFLSDb=D&GOHp1&!pG46c^jv9gc zWUTaDb(SOXw=K`fJn4)keM>Zv9w0o7m_?zQOMnSUNSNAV2aVzyA%`27P)AdE#?z~9 zPd*s^iK1?GnQK1MLa@TX1_R{MZ+5HOBXj#H)wAp5FpZq5NggGcQhv|FZY;d9=vKaJ zxhz4>@rn>^Yp#fDa{ezqZC5RQ%sZfoQx>WWOUU1x*Jo^VPs!Gj~KC2p)ePpj@(MJePxR>xQv-JmbE;V1< zPi#^s3IX}8zfb%*4-YvwrHMr&xe`wPwXDUs6HDFpmMl95Eb|^{)I!MeGp-x%CBK*#G{CClNKLaV{$*?$(%r&9<1X^9)3S97_t40I6Vk8+>}K zVvh-ii!N6WMo8 z;Rb3+fUvJa|D>dU=w<7Dni3fKATeFJaCB#X_iU%E)Z4gd3!AcPZ?R!jZ`izIYd%p@7iEOK6@(Lnl}3|LGniDs@o8@3U7jZsta_iv(5^To!B}R>?;n;zBMk@ zA)#OoC6od$7?8?!s`1`z|F$Y2>Uk~bg*u@s)emS4Y#I-BF{UCo&^6R;ky5w2nAdW za!FwbTk8n#6VheBk)Ht%`awGCGCak~d&iW-zTo^PcS3cWvvN`qjXKw|!23A&(wX-X z@jtG`o8l(vo(t}mIF3dH#yS~)?yuk9IOwTf`e50&;>M>5S`@(tmXe_AL3cxL?w+jx zRTCPut?Ur=!+;S2m`52FO?ytWzH;Qu?Ftgqz7Sob{y_K;)5DkzI!H`v4($#8B`b0D zo<7-vc7ZA9I8EyC9$E0d) z#XU@IwvV1bC)#b9#slGGXij+HlAPn8Ty^AFMe4R+w@Q*pjk*YWdYha@Kb2g@exz1q zpx&*&5gDGbJ(~+rdQh>2A$HB`Yq6W94@d}J|7*+aujj@MRe>YF)1(?(uuO2~0rLXvD4<+$w((+yxXBAYr2;{oz$gRmM}LGALK-GsTY@4Uu_4rg_y^u;?e3 z)=6gTQG9zgMB=U%;}b~=O1a>o!3vBc<^bkMQMLQ9MiAj?j|s^<_|RQ!%CM`@et(6u zq)*!nxVw4N%WQ}O5{>h5%NytUA<8y?(!j8ylb z`$Ue&LoOVJ39tIGF=*Xe#nT~{f=9BpY6U?_7PJ~)Bi0g>rGPniTZ}BSBhj{?^GR*!$$v3Ou79 z3?)(Y;-76UHH_i#lNyrz)X$nZm2;042a8<*Z5XX!*E+#8Y7Mdpx2nLc+SD;rmKzE* zH*Om5H(PrmLLX}bajh+RHoRfCH-2I_64>(Qy$E>VC90VB#AjMhwvsAqw%Ak6M*6!s z-VXx^S;k{n-r)wVK8X9cvxgkE#}7asbqe)?gi=VPIUZRJ#q~vSEvxTqNPbtjFdW^l zB6kB*%Vhu!t-Y7n4`)&awQ~{i7FKn3bL_R}WM7_R!XXf;2bCFYb7H_RQmFOuxGi+i zM1q}UZVWihgDUdr9MTkTcBqZgwH0yZ=Bp^h%F-DZ^%S4kwXp+rIa2q9sH#z{kek^f zrhTd~-Yq=S2ukDxUx6TN#N)?1l5*oD)!&Z75Elc|`Nfnh%z;C`h=jk-a?@^L#D`IR zuyOE?f8Pn*bR`Ib>*CInbAG-p9R?%rJ7fD1^;&LQA9W#1VDDLfpE;yO2GY|vArNo= z=~WKI61MN@dg{xIQXxl2zm(!fbLQ*($FgMHSdgPm+|4mCs4l3`p_)RtPZ`68T59uZ z@TdlnUi&*#`g*{c>HNR|fhFE%Fq3L@beVqW)*g4{;Zh=BaM*Vcpyrpf-GI04xk~aX z%ZG1pGN58#a4|nUSe>z}nnle!uT~qcGCdgRiyb3oDf|V>i@~3pNd@)}TFZ>-A1c+k zi4+}`3=xymT$~bw(rPH5ZVlYbvOwXA9dxqiSUvp8Ya&?5SOxGj??+mPW;= zKgd3Z56Q!sN>7wwJ3uGQ=-cDP%>Ika=X)nTJA7VVPQ$?l=art@u@o&-uQ}lxeg_xRxv(tNS8Cfq>n>i-LAsuIgqJ?|&a{X|tavou`aa3pzU z&D4ukWacq5wq(a#py8~@UahS$fn%i?sEMdTnFT?1Z0cbXhWI{8Y!0I{3o|JPvXu;F zpjbcRZBii#K@=o6k7*7epoy9w)?y8GV#@@N@m~}n$E(E*AhV}L$%$mzjl=Yr=4}>~ z4oAP<4fC3!Kwsz-O0t%OLzq-+nzQ${3L8emOyR-LIiA37aLpW~yR4Y>rHuZ>sXfl`a{QE18B$u!`NXQK~ zUoV-ziTW0b;sBFaau|e4rhBVo& zSitayZ(A`6AZ(nXacn3HLU~!r{?`$jzs1tm+R?VQI^YYGwK=*#dUHqvF9cz-OmS7* z$NT2u;p0%00N+Hh-kXN zq#$dA2&Xab=O!v6&39Y5EN1%Rmz%jlY8A`h>&%Y=hV^N)y9LGg*%yW=Fp_haa71{MtF@bzrbeEdV6aOE7% zf}nfcS$8v%|3-}0Q|uzd?IBLkeSZLVjpdqH`a}fC)?tr!zWQLYpz)@6;it)XxGD5j zHjqb8%E!_o-dcicE5Rt1?Tf_`aB^-G+TB4;t|rimyqpumwAFXgcS&($p9;ROZEr;J z{FOWe4$2p1gRn&T7-20qMsT!0iT{qs3QkdFRZ7+soGc)UZ?g2%8hY9F5Q#H9UGyH- z(HV%&CoO^+}Wm*h1C6L<20YoLoM%Inp(Kr#?H@cG8Y_B1AtS# zYn={WYHr;upf1Tp>|0E{g#HwU_uLatdC}Tkd^<;0NiGD>TE6-{`in+1V*nRm--m&p zyUnE3d%4dt?Ik1hS@9S>{e{Iv8+8HhfMds%&(XswW1*4r$0=jB@kRdpPWtjpjOUD^ zQf3YP)yyiEXYHTp&e$P=(Ig=o#wr4C70Lhw(q+P=4NJUQeQDq(9S0P33;8@JnXy@I z!;x^S!R$xtBrKLJ)XU#^-b*lxHlr{4j0^tU#3a?Rme<0O+4pSn*QTXA7{tEP_bWm@ z0u5qkgEn1r9h_nsUM`R!gPRs_l}hRj`ov*={;V1qcTSRD!CM|IiErT};w@k*Xttwg z4Ld7|w!zJuh#v&^4iBB8?(y7^7zqssp353T8zBkKi@A(@#7xDcvZb3Tc3m_yk)UR$ z^T?R>r2Q1gBEAGLL?j)Vz`$o#p{4}VjJ0ydF4;N0j#rxbPX{R+kE_)HWHPHx$85`* zN$mr~uDR+@;6A6~=&#flo2gg*ICil-E0codDXiTs+@77KZ(>K zB-C$6nl$BRV5_P&WN-5XkyJCR#5aiEM<8rSfxYodH|bCPT(9F=s3Myc3`BFMjw3Ny zXnR#mtuPr?=mEN~1_3k0j(0DE6e;m50rJB&2p>2i4CmN(;rExQX#Zi z4^ch6sYdnr(@Q?MYgc%+p~YywhdPQCeyUo-gJn+md$pM|n%8-PHJgjRxGnL);4i7- zk&@;qARDE9wtx!x^?W_PPckP4LBe|4JVC7UGrU#XNfUTJKF!unoQRcRjuN-4{|Vh@bQDMnd9*nK71 zEKD=$NTqUI*CND}V@Z!fFX2Wt%H6;z{^aDlxmPJsCUDz$lW{{==vh^xX^1~?frlxo+9r2u z9)qN3Md5H^;hlL;ARE{N;hwdBYgPBA=FJ=yAP_o&NwPrH;M|cYA?%j;=z!5QZ znb(*mzShj<8*z%Wy+hHjB^22ipYk3kn}w?>42W#d{xj_ySP0JG@)N9}F9?)`815GK zCmt9{;6dv8#e={@7lx&p6#_zU1Z25=^AnWF2jNhjZW#+gH5{KqN}94?N*k{0p;7HA?u zT~qT&K@$sn%TD}exo?2APktBL7hX9wH#RpuHy=IE(=*0~Q?=ku%^?+?q)MM6ph8xG zku?eN%m8R~6aeV2yR|iWLu#%^rXK>GIOt~}F5*(aki6i~V5L?Lb>#Du(u+udrOyC} z2q}QX$%+KViWr#~9$e-t{4_EdvMjjE5IL|0Ahdx2^3-Rc>E!kxK7fy}+&cMrg4G9c z3<)hQEq(ii2u0m4l)%gk4KfFjkDt%jN*65b7+6n-4JrQiO$U)$MFx9B$v}O2b;SU1 zzC(5t=NWT(0O>NKmJCE$0*ibM76J6)LY@Zc<^}Me^;tlraSiZ&ug2(IDQ^>#qdVFJ z4)!U9j@pG%fr5&I+G9as+nfO&xAGzcO|u2T1^Ntpz>raq-yJ%73j!#DN&KNg`V2L( zIFSdi!W;psgS$$BJsq)t38-Nx010t#1aVvV#lN9LIPj2=OM94JIw+8(Kky)V8<0Tj zS+MBP_Iy5YKEqoB2H0;Im(EFR=!nS5C^+<>`#zw0E-gF^#EyMu?QU+8n?##8*(VV6 znHhZOTN4dgkyBU|d}<4=qWB%_XeAWbIt>yD8UYd{1Vf_?SRw#Cf$;u2(P94r@}JoA z-K^(|cy4EU8No1M1Dp-n9I5+j_roW!D-VFafQEYtR2=O^>4`@MfPxhQ+?AlPL4h}y zt>$H4M7}<+QfWwisGgPlB!Jt$4?BVvKfQ!?Q5<)A&w6Jyl|&^CL=BQ&6i0ziG<2Qs zfX_E^F_6yzV-Wz2v~*x7HZt<-4Lv0Bs)0HHh`21W+6h|pjqcO=@9tf_sC_tjx8Z05 z0nQYkc+=@n2VOYD`~(>e+}%i>12!%Mgnt5IJ~dN-nIphfVmC#u&(_R~Rv_>Ivb}G& zCjiBs{o;4Wa&OJW6*}>Esx{)*kH!uq=&8k{fNmY?xhs5X68v4@mPA@O&lD6aOJIIq zY{1a{sQtUm*e)~pQs44FqM!!IEgVP?@SroBzV6{_de5nHZ0FyX=I*DDG&}ez#=Xrz z=3i}ike1~PO*U!4A;I>DA#V+%>{mJWaRI=tV^`q_W3oAZ5M^mh=d~=yQ z-)8Jb@lt|*;t>OTjq0%YG0}If4xVG-x(fV8FO;sJ3~R=w)o5;jBse}30V zax&mmLm-eH)2ywMhxgv=XK*}a1!#}sI@5pgtDn4vP5vNxB~0Ck&6$UA2CjyM_=#jh zrAQzriCjo;>SUTX$kNEN##&zgHM?Rbsy6wp!HXpDWx5(8pj)6n6(M9@dP3W~?SPaT z)o=}>n4CanX3hVjK#@KYg}*l^gu26X)aaBa$9vftx{I|#WPX)Y+_Z9JbseYcEME15 zprO}zfVJWBM-{tE(G@4gRdeq!Sn2CKLe>?}YBTROh*N&Eu%elRE&QL2N-NoEO^V&( z01@@v$x|=NWtlj6tl5l=B=tGk1xq33$FUCk6EqMH_b2_2K+bRR$G%a9Naw|SyyEi- z&~f~Q6VHq`MKs1tmI96u{&Kc$JE_W=L~%PyNvhAoNO~TY+Dm?%06%9-y(y$*3~CQ% z4NA(T5J9rmu|>rt?kq+*(jzl8a?mc7%1M|C?0>y*O&kUctaN2HeZbxhZv5V zP9G@9X5Uh@Im)dQRh{g;KE)X*zYi$k4-^&xW}N{P936uwln_-lxD^c)$UmR*SDy_V zP?Y(|CXKj{eWjucOdXn&!c@q4Ccvx!rT8ki86TsYkowQ2N~sBGsQUiVw0x_(5%(d za&HXI;iH5@Xv;@VY%(5SdcdqTAMp7 z)BY<7Tw(9N`x)SzgkevEdlAa5#sd|4NH5DU^C+s-!P**Y=*_cg&tRum%-wjG!>4`& zIdc17uD_4;AqL?QD{Pgc{iD8dt{-z}z0Qnv;Xk;?i-$Omo5>v`g%WwQD!8$eUebsF zQE?JK8yLL=6@)aZ{=6(wmt51rQ}8AS`(`5k(O;5Zx8+RT*yrQ_Q!s&wwi;f1A2!^* zGV)wbnS4#Nt(U{)i*5O6G+<;YdG7So>9-`X`53tnSG<|=1GfBDFK9H!>xz{4?rV)) zGhv-GCa0fK{L)=SCDi5Fq?iA+-}q9f{yW`w=RCz-U$@=x7%op zM!PzCUS>R_1xrZ0LKd|#?5DJRg0vc_01d;S-iW_?p6oQ2LN&du`2GC;)IcFx3 z9De>_gtatwhzA+z9iMG=bJ=D$sT?!z!uvG+_Wni{ugy|8|zG{f95LmQrO;8~M6 zzpZm#-n3;=H<&okXcawR2R$wv0;I}YV+cS7?ZIsgHMa|NDv-(g+zu1Alh zs0unKu5Bbs%Kd{l181&+=fdbLe~T|eIdLLU3&0~eEt84F+Y@nkzz^qo0VC;l4<-2A zTl(^Lcke~sF@n(1RjQt>5)~|TA{7(V*@V`Mk4^QCJc0?~h3b!Ec7*L`XaU_Mki(|5 zp4JCaSyxq_rk|GdM&a5J_9h`eFxys#ZWxPKIoct+wTD%!?0|2et$EzUD?d3g(?Lt( zb$;X>uFoX7rPz*Er${rTVlSY}(b!|kbLuP=Sz-C;aT7%U=rmcE;vOxXL1vz5#K**n zmHwv19O^p26cs}&v5KPdA>5`!f8`KRwh)HA!d4$z`-H|?t3cs2a&^DLA=hHV06 zJ|#2^*3P%U(QJUqWY87^N%+Qwjpi;nF&IBkO($&DQqfe?%yFUD2V#sc;$X&--j=Rl ze~U$vx$pXM%)1REU&XqucH~yVWZj*lmBb90}Mss(nAI4re(9~IMUeK?Sn3O>`ScgmJ_9#zt z*7Pog-^D_JoTto66KgJ;^1jroog}FkTugV3LX*bxDM@h2XR`1)%g=wvZ79K9xbomo}w6(QJdd_Rjm_;%5+76_54;E(>NkM%xDG7;9(b z{5;#W2<3AgS#uh=6H^s8@vSrzN%s@E3Xezmqen~5!p(A;(xQ)ANQ)v*=VeX)k-PF|NP-7?-OSDf#RW&!$gjLm?SAf2-fP1mq2l^EC7a#z44BIY~n!dvyT6+)nBw?o0 zF(!Of0tm1bdGVzoA&tTE&sB0kyTT*ITxem5I03-lX#Tn}!J z*8Y}`D%vRBI!2pjsv7SXnf>D=&N>SR=by`}e#L0=E)!jb4j9iHUQC3ZOn&JV4?27T zksx*3jcqJj&_=ZPi{MJ~VSRqJecatm#aPUR8PZ+KqDsmD4hGIhB_$VGsZ~IG66Uau zx`F@Uq5p%FYtWtB?pOG)<*t}`Z7;mriZ!%5Vb;8iVd6-KS11T>h8Mb397;CmyjfiX z?rf$oVn1P|BsI*B@kUFj!1*&+YxQfQTcD!;sWi^YnX4@oC@U;Gc47o@%7dY zfAcy0uLR!KJeCGdCFBu`@S&9Qy8V#z@%|PGeKXS4Fbn#R(^OE%EdxI74ze2~MuXtQ^@K6MnGrh$wE| zhI!LPlHVpf5%;laX4w+dyQfGg8+)_paXa zH~o~tP$KHzn4RdY zao{zH=7<9^)9oFKS*zNEOd0w2qSRu~TGY}EO-ik#j$AqRkHH_W92Aqg@Q@S`7yH;m zK#7}3io~2=6`({E#eYQezteuIdCM?y9u}1m3>_j)+4+u)w$=HG;J!OxJ}d>NS$ktD zCoYi(dB5$LH>0Xa4(3u=47sYC{$cj04<%oSHmov++G#`-b5JQg#XVKfQTjoGMd;2F zJigz3DjxZ-J0hA3sg-ugnH2t9w_y_F!Zk(nHGOI^U*VWSxV6bZrE|k%hb}kE26Yg= zxrHK=jy3rrpIB9jMQ)op%wn@q!T8mpw7%|vkD4JnU{XjZH9A!xWGU2}IfptG=i>Lu z6*E(OQ@{Avf_vO!sT+F=5@d?yrFRA{epkmyfSw0W?$sOxH&c;t78{KpuTGY7I4ENH{)JMju1T4%)Am32<5Boy)j&r3wMy!Ob0?VSo*=5wy5 zA{%~N?SVTz0NP8!tV!#LW`5WI#pUBy5*)rDD~Bw3uGt%1H99NzCz>7~yhHBLN~1wy zu|jlA4PmspyOni@SG6GR1D9iYbla~-P*Ng7UO5koWJ~(1d&Wl54I5os*S53fO3m@O zRbTyucb~9Jf9Ee-vl7eGoQCP-^?eE4GmAomNfTv##>$PSrOVP(zpJ+=RrHnGLwGgN z!P-%b_TI3+MTs8o)J#YN zwgV(IRZ&@Q((hb(F(t?-sa$I=3W;nNL3f2|+@EttYThaxrsTB)b1fw{Xr5*SF!RdK zwtM$8*o3=)uD^4~Bm!ApcKAr}d8?{-IIdT;LI1KzJDN+XQxP9x2~PF~TfN=RIFwyF z4_#OsQS`}aL$Rh7)TA%Jv+=PQ5uPB4w%2j-wAuNGNGmYX?pJ=6e&?%X9(Enb>fd=Tt0uYS$|hQhC>9Xzig!_#iBF5| z5;vxTE;W}v3R{wT{Q>%s`+|~DcKlbTBXb2$0)J-WQFUWIGAvP3C ztd$Gx3F}5nj77*{Mwk<1Jg{RoGqn*?m|zeaCfArJLk(c_MQ$XJWjOx1gPiqd9g>Wq znwNx|4V0mGNGs$lH3At#@M(6>Nji)tJfl1z;{J;8rn)1HSD(Mle0 zS1xO5@Dl^EyQY#T#KLZ42HMH5Kq^au)<8dkdWQ#%61*nXzFD9h3rM)es#5F!GvUmX zw8yR$vyS((kj%-?!f=*VAvE*5X8vYudWw1gj;Cj%U5R45NR4Oyi3W!0JV()6Giu8) z+2mW;BGeR*Yt`*1Y*2Zef>6}pY~T+T2*7zW7JapRQYe1v%Kw!mn4CKP_CzAA8!X@d zG{Lg)sb$3&|1(c=e>>LcQ7pGfkDj|89~OgPoDzoBN4}Xs7n-Reir_|jPH~>o>9%86 z5=`yC%h7P%?xd#GYDQ$iJee% z7}vwEusTPz65pl}!!g{k%B}Nsq;Ao~4kOxa&s^Jx#_g#Kk2l3p)k|HeN>xUqpn4OQ zkDrWxn#0>y`_h?=5iLdO_la5ExO|PWUw5;K(4c~@g~Rl>8W9HSW0RXj6r}x5{$X^d zwiKlxYbH_s{22af5%!m5LA(70^_1)X%E(o+>s z6?E69ZVm4Lq-nWl?V>YH1rH!`L&d{H)naArOx$5YUltOwE8ICj_MWou>hpPNW`rN6 zQ*I%%$2n%2&=DIlKUo~c+0bUftHkP7q?@oIfD7s{#O}o)zzXN$CaDiXnM_#uc=%z;wJksKTIl zI6dkif9QDclC4!VrPhQoQ_4287SIpT+{$ZaZWAMpUk^`RA{2ULv~eV$7I3pk(THns zGWa%fz?|kjf}6irXI_lp2Ex(NvAuTtZy z%;CM+B(}70>uAQfPb0lAq@_zL22GJbkN zooxQpCCSN1=+P#2Y*#m>Dp5GgCA*b7=6rN@lb!Yh);@MV4ur_ToTpjI2lQ3R484Q> z$mXi84U#s8oHQ1SxQ)3ZetWw`O^E|%XlA9hfQ0I8+WK^v-Ar?mYr048-UC*}yy--> zNwS~nbe6i|ESpgzrM#3FuYvQ<<5H#vGSX?9Oz`(-+a*{T9b7r(jc zC3WwS>TRT{Shi%RVUQ_PgPVYOtW0lG;t{uigGgtc94t=OXw9armu_R6BU*R+0p6n* z19~FXR#!gWVV~hK2OoLdRNM#pGfTeT#YM@2yGP{->5MA)NCOh*=mGkBdJx5v4wcb@ zyT({`7+kzPQRfQ%t;O89h>qv$Yh_Csd*CZ7yVTcvZ;2F>R-6gxo`<= z+uhsmIegxtSYk7l0=ui5Q+SR0>4fE)8Qs^3>;q)8R8r!xk=uksvk=|0-x}zY$i`W} z26^SG$AmX=GEJ8St+ujlEP6D?REk=4_FIHt&OboqS_0NV0y=^%b4N5)W2kKZd6ra# zWr&uum=mw3d^yPb6X~`kWY-H<@h90GibjhPA1!2@m07YKQmi<{zKV7xnyVt4wdknG z+;FF?p*A}{T$OL&QJP(_;y5?>{UsNXro~h7fTNN_sBltN>|MyYk$i~dFZRP z6>(2dekJ+ctFkXgu|U)`wmiwxQ9`Guk2_NsqF*cBNqi;+Z9xh`l{*sWazGcAg`x&N zDU6(cgq^+4mpjZ0@*tLt@o%q{(E2~yCspa(ZtD(|+m5+JW7XuR=wnpQ_9x9kI$$5b z;PxH$4K#_1y$mA@5t`bp&<>on;TYroA*16$IqC6XObcIjfToK$WJer+VsS`+k&_y* z`H=R-XbafPRKeUZknpD#^*R}lnPj~L*~q!dCnFG0jTHLI&gWZDEL4G+rsXx^zpjZO<&S|*sw#V#`yQk2Ot(X(pk~`UI5Fjc zn%4Mdx7wz*7Tty~c~9gtFhn)O=mnRSM;GgyvriC+gg=!myOMzo1qnDlv%y4})Ldwb zh=s6@jumueZGI>GNI5L&Q=WOHbMtiqZ?Pf0w|LLrig5HfA03xIq42iu$c92K>l!j= z>vPO5H%+5h`T^c{-E-t2NCcV2Np#*er~-E?w4mrlVl=^W4zxaCggczImAW36VH^vP zA=!yMBhM~YcL6ghL0tTs4}y;|Uc`Urk7l`FS90s9*?XJ*QVTj=|5)~d_m4p7ZZEUX z``L-UK0sO5F+!SDjww$Zn=Iv^HM=2S%H0^m{fm3*hs9fmH(G)vUv#X=Sj6>~4+W#g z8paxuF2~|)U_ZKCB^Ox%YatL)4yg1N`AHGnepP%n1(}kVI+V--&M$ey+3R{`fX@^?CI4Ku@ z1?_4wNX@j{M91xl&-oNjp|2fPkk32{JABc%9b_k&UAkr93ENiU*r-@>o!zne}~=jR?|@Utyd5&Badnse{8&@zboJ}T0?6F4Q^H!yyo zM%k9n$6#m$M0|XWRQmqLB!l1OEL`EM5vy83csGXH3OmIkWK1JzdSjSzr)c;3_*NbD zPmNy#rv5FGiWRXe2bP!bd3Qw5IZ~Uo#|bU$Rt?op0fQBfL$J>Cbe?-n#HaX?331-4 z_|=hd8_7Cz)2tw(#^oD^&5l*aE>-+hNi-&R6+>G?wS;s=^9#!qmn6GhuE22BcT|bK zyncRv9uF*?(kjUd@{Y6H(MjDDrd|C>tNsnTpmblbCtUw;awb=ZnpS8jk7)h(t;Jz9 ztdz{vU1@~13kibclC&xNgNBtq5fZaIm+t$}M;=eF%QOKd${oEx%9Tz`OcaAl?%Z}4 zr{Oi>)wP_g&#n^v9(}ztsGy+xCF98%lo^v!{8p2CDNJ5<<;5PpxRp+)SgMq*7&(fAzr>By!%m7wS5k z3`uF2ZLO7>W>{=^`Kasj3U|(N!XimK)YfBPA+**0pm_}doPyOz{wgO#uyg-M z@PLb(^Z&2@GkCzl%*@L2f0GCQv)(nP<)7Yl4U+ z=B6~U*1wIHT~rdwTcH86A1)Th+rV1yS_Spo2L=P102|F8bC#AaQtN$Hea_5fP*7M@ zQrN`R6~hz&K#(VwFtNQWBqTvZINB={3r`5)>NEjp2rO_?XdS`!?2bIC{?W5R^_MV+ zOpXG8kr05@%bXg>3=O^u85H_$0_}nZIi}?;YzwH!0#IP1U&hW5Be>kTg{-dm@D;z! zQU$JMK=e_NllOgx^9n8CTte2jgo3Iu@L%@NDB@HzWCPZjZJ<{NUwTEDd;c-n9Z?`b zySux&8M3#yjqKfx=`R5e5#jtoaF>Yg51<92;;Rh@fKj2Qckt`zix(OE zJ-o5FnSE+)81)=3XdT3sM8PnyBMY`PJPwMt57qi%V{T!b;Q7$u%nZh_gc57lbW|65hs+{HkXMz%3tHQ?agK%79Xl^fAEH-4F>t1PzXgybl(r2VzKM zrMeg&xr@aKmgac@K?a7*!; z%L^LDAB_jSZYnCwM1e$5NJxPpnMmNs`$u5Vx3D0f-@K7w6o<96Lclg!5j!J5zF?GJ z#zFw>^ZUhTI&d8UvoBy&C4@f#6W;JU{D6{JApU6)=`ZldBGB;-NcMU|4djdkItV-G zC@2J!r32@H0ZS<}$W%MM@Ht!;XLmyZ>Z^;GLcqUjM4u-!6~T7IIWxdY^~XBjbuj6& z?8P0E(6&io-#!jpWF(sp!SVZ2-Itd{Zs9ybgf!m6muk@6UC^L!$(JVWl~_g2@DDUH zpi)pS=1H&Wgh;g!M=xh|X57DVjbrn(C`4~kR8AtIzPJl347)yo07q=VVdwx~jxIp) z3IbqjWPjSLn4F6QNd9Da2ZIR&2(1NNK;HR|R6G=5=^GD*|BN0e zp-Zd}nEN)kr6D^sP(lW{zGI<-0 ziiroLR|Bx7XIB@W4w3J?*F{%g2(YcT&yc8&{rwzuN{4(ipRwzpMIv!C^T1HXHD^yq zFyz;u!*ccF0~Ci0?qqn@97C(kc+%kQQz_qj;MsXC)_%m?d)3e1`F+c($Uh4sc2|6awoCo%J`cnW z7lMvUkv=D|k&ayOVLI+8Ns8g%e`&NwkvEMI;wP6?y;=xx!D;?|czs)pTauBsJq3}3 z;dA(kZfQrm!8EW}J9q4SiC;*uj;PSaB?+9Q$Uz2S|JcC?nQ+!7WyBFv#u$#$1 zuUk^)Q?T*WExfP?ZivsC6t6ANlSZgBuYi}?G_rHtwg2QH;c2YPQPzLE0Jtj>UHwVi zuKCePy4H`~>fbLxBg!XwImi&>b;tJBTmY(D6o;D*s>g-5)}6aBOus*+-0RVlv`-ab z$Q$0%7GsdOsJzvkyW;b+qyo?@+S7YhdT=0U2RaJk8<;5B- zYZ1ohJ!H_;5N1&sK&#>;Aja2c&QaiYA*X)yp1DfYf*8K>*ttJAv*vb=RbCyY%)r4t z>S~)X{uZ#yvhkUxw1gU*&PgJ zJp8G^kEm^y+fI%T+n+ZJr43ySQ(Cn(|I!|oG`nWPf_t4Sj+}L6E$Dg(pI!AfX5Bj> z*L?{?UC`>oV6;&IsnYr)1YYUuf+xhUI-iDqD-!i}u-BPO}yED8ptH9~YO6>AxZ`QF|1xo?NbJU>V5Gm`faH?NLI&JQK z4_^^^FXH6p6tnAhU*L-jI3;w`e{7~Sy~vdr5+cpSoaJ7oP$3I`593Fnx?OyUGs(gl z9oL3&@)`8-6$@*hkq>WAqs<_l!)J4O+X)N*9{o}fI}k2Or~1$x*byZG{cRg-JTjO( zSFfo_%B0wrGCC}#ehiM`qm#1!I?sY$+LbbBIq{a+1eyxop4EX3Ir0lJ$;$3w9RGCs zbzP@0egzfexaQ5-L3g2`%k<<4hC@N+Ze#wriSatN#Gt?3O((jEnxXKHAdw